From b0afc4807d0e6302991d34084e1fcdfc232a5f85 Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Wed, 1 Jun 2016 12:12:21 +0200 Subject: [PATCH 001/990] synthetic commit to import ieee branch from old repo --- drivers/wireless/ieee802154/Kconfig | 6 + drivers/wireless/ieee802154/Make.defs | 4 + drivers/wireless/ieee802154/at86rf23x.c | 1479 +++++++++++++++++ drivers/wireless/ieee802154/at86rf23x.h | 204 +++ drivers/wireless/ieee802154/mrf24j40.c | 229 +-- drivers/wireless/ieee802154/mrf24j40.h | 59 +- include/nuttx/fs/ioctl.h | 7 + include/nuttx/wireless/ieee802154/at86rf23x.h | 100 ++ .../wireless/ieee802154/ieee802154_mac.h | 368 ++++ .../wireless/ieee802154/ieee802154_radio.h | 133 +- include/nuttx/wireless/ieee802154/mrf24j40.h | 2 +- wireless/ieee802154/Kconfig | 18 + wireless/ieee802154/Make.defs | 9 + wireless/ieee802154/ieee802154_device.c | 374 +++++ wireless/ieee802154/mac802154.c | 586 +++++++ 15 files changed, 3362 insertions(+), 216 deletions(-) create mode 100644 drivers/wireless/ieee802154/at86rf23x.c create mode 100644 drivers/wireless/ieee802154/at86rf23x.h create mode 100644 include/nuttx/wireless/ieee802154/at86rf23x.h create mode 100644 include/nuttx/wireless/ieee802154/ieee802154_mac.h create mode 100644 wireless/ieee802154/ieee802154_device.c create mode 100644 wireless/ieee802154/mac802154.c diff --git a/drivers/wireless/ieee802154/Kconfig b/drivers/wireless/ieee802154/Kconfig index 93e802323d..6eba028b2a 100644 --- a/drivers/wireless/ieee802154/Kconfig +++ b/drivers/wireless/ieee802154/Kconfig @@ -11,4 +11,10 @@ config IEEE802154_MRF24J40 ---help--- This selection enables support for the Microchip MRF24J40 device. +config IEEE802154_AT86RF233 + bool "ATMEL RF233 IEEE 802.15.4 transceiver" + default n + ---help--- + This selection enables support for the Atmel RF233 device. + endif # DRIVERS_IEEE802154 diff --git a/drivers/wireless/ieee802154/Make.defs b/drivers/wireless/ieee802154/Make.defs index b0a1406baa..8e0924d67f 100644 --- a/drivers/wireless/ieee802154/Make.defs +++ b/drivers/wireless/ieee802154/Make.defs @@ -45,6 +45,10 @@ ifeq ($(CONFIG_IEEE802154_MRF24J40),y) CSRCS += mrf24j40.c endif +ifeq ($(CONFIG_IEEE802154_AT86RF233),y) + CSRCS += at86rf23x.c +endif + # Include IEEE 802.15.4 build support DEPPATH += --dep-path wireless$(DELIM)ieee802154 diff --git a/drivers/wireless/ieee802154/at86rf23x.c b/drivers/wireless/ieee802154/at86rf23x.c new file mode 100644 index 0000000000..fdd2c3ad64 --- /dev/null +++ b/drivers/wireless/ieee802154/at86rf23x.c @@ -0,0 +1,1479 @@ +/**************************************************************************** + * drivers/wireless/ieee802154/at86rf23x.c + * + * Copyright (C) 2016 Matt Poppe. All rights reserved. + * Author: Matt Poppe + * + * 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 +#include +#include +#include +#include + +#include +#include +#include + +#include + +#include "at86rf23x.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +#ifndef CONFIG_SCHED_HPWORK +#error High priority work queue required in this driver +#endif + +#ifndef CONFIG_IEEE802154_at86rf23x_SPIMODE +# define CONFIG_IEEE802154_at86rf23x_SPIMODE SPIDEV_MODE0 +#endif + +#ifndef CONFIG_IEEE802154_at86rf23x_FREQUENCY +# define CONFIG_IEEE802154_at86rf23x_FREQUENCY 1000000 +#endif + +/* Definitions for the device structure */ + +#define AT86RF23X_RXMODE_NORMAL 0 +#define AT86RF23X_RXMODE_PROMISC 1 +#define AT86RF23X_RXMODE_NOCRC 2 +#define AT86RF23X_RXMODE_AUTOACK 3 + +/* Definitions for PA control on high power modules */ +#define AT86RF23X_PA_AUTO 1 +#define AT86RF23X_PA_ED 2 +#define AT86RF23X_PA_SLEEP 3 + + +/************************************************************************************ + * Private Types + ************************************************************************************/ + +/* + * AT86RF23x device instance + * + * Make sure that struct ieee802154_dev_s remains first. If not it will break the + * code + * + */ +struct at86rf23x_dev_s +{ + struct ieee802154_dev_s ieee; /* Public device instance */ + FAR struct spi_dev_s *spi; /* Saved SPI interface instance */ + struct work_s irqwork; /* Interrupt continuation work queue support */ + FAR const struct at86rf23x_lower_s *lower; /* Low-level MCU-specific support */ + uint16_t panid; /* PAN identifier, FFFF = not set */ + uint16_t saddr; /* short address, FFFF = not set */ + uint8_t eaddr[8]; /* extended address, FFFFFFFFFFFFFFFF = not set */ + uint8_t channel; /* 11 to 26 for the 2.4 GHz band */ + uint8_t devmode; /* device mode: device, coord, pancoord */ + uint8_t paenabled; /* enable usage of PA */ + uint8_t rxmode; /* Reception mode: Main, no CRC, promiscuous */ + int32_t txpower; /* TX power in mBm = dBm/100 */ + struct ieee802154_cca_s cca; /* Clear channel assessement method */ + +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* Internal operations */ +static void at86rf23x_lock(FAR struct spi_dev_s *spi); +static void at86rf23x_unlock(FAR struct spi_dev_s *spi); +static void at86rf23x_setreg(FAR struct spi_dev_s *spi, uint32_t addr, uint8_t val); +static uint8_t at86rf23x_getreg(FAR struct spi_dev_s *spi, uint32_t addr); +static int at86rf23x_writeframe(FAR struct spi_dev_s *spi, uint8_t *frame, uint8_t len); +static uint8_t at86rf23x_readframe(FAR struct spi_dev_s *spi, uint8_t *frame_rx); +static int at86rf23x_setTRXstate(FAR struct at86rf23x_dev_s *dev, uint8_t state, uint8_t force); +static uint8_t at86rf23x_getTRXstate(FAR struct at86rf23x_dev_s *dev); +static int at86rf23x_resetrf(FAR struct at86rf23x_dev_s *dev); +static int at86rf23x_initialize(FAR struct at86rf23x_dev_s *dev); + +static int at86rf23x_regdump(FAR struct at86rf23x_dev_s *dev); +static void at86rf23x_irqwork_rx(FAR struct at86rf23x_dev_s *dev); +static void at86rf23x_irqwork_tx(FAR struct at86rf23x_dev_s *dev); +static void at86rf23x_irqworker(FAR void *arg); +static int at86rf23x_interrupt(int irq, FAR void *context); + +/* Driver operations */ +static int at86rf23x_setchannel (FAR struct ieee802154_dev_s *ieee, uint8_t chan); +static int at86rf23x_getchannel (FAR struct ieee802154_dev_s *ieee, FAR uint8_t *chan); +static int at86rf23x_setpanid (FAR struct ieee802154_dev_s *ieee, uint16_t panid); +static int at86rf23x_getpanid (FAR struct ieee802154_dev_s *ieee, FAR uint16_t *panid); +static int at86rf23x_setsaddr (FAR struct ieee802154_dev_s *ieee, uint16_t saddr); +static int at86rf23x_getsaddr (FAR struct ieee802154_dev_s *ieee, FAR uint16_t *saddr); +static int at86rf23x_seteaddr (FAR struct ieee802154_dev_s *ieee, FAR uint8_t *eaddr); +static int at86rf23x_geteaddr (FAR struct ieee802154_dev_s *ieee, FAR uint8_t *eaddr); +static int at86rf23x_setpromisc (FAR struct ieee802154_dev_s *ieee, bool promisc); +static int at86rf23x_getpromisc (FAR struct ieee802154_dev_s *ieee, FAR bool *promisc); +static int at86rf23x_setdevmode (FAR struct ieee802154_dev_s *ieee, uint8_t mode); +static int at86rf23x_getdevmode (FAR struct ieee802154_dev_s *ieee, FAR uint8_t *mode); +static int at86rf23x_settxpower (FAR struct ieee802154_dev_s *ieee, int32_t txpwr); +static int at86rf23x_gettxpower (FAR struct ieee802154_dev_s *ieee, FAR int32_t *txpwr); +static int at86rf23x_setcca (FAR struct ieee802154_dev_s *ieee, FAR struct ieee802154_cca_s *cca); +static int at86rf23x_getcca (FAR struct ieee802154_dev_s *ieee, FAR struct ieee802154_cca_s *cca); +static int at86rf23x_ioctl (FAR struct ieee802154_dev_s *ieee, int cmd, unsigned long arg); +static int at86rf23x_energydetect(FAR struct ieee802154_dev_s *ieee, FAR uint8_t *energy); +static int at86rf23x_rxenable (FAR struct ieee802154_dev_s *ieee, bool state, FAR struct ieee802154_packet_s *packet); +static int at86rf23x_transmit (FAR struct ieee802154_dev_s *ieee, FAR struct ieee802154_packet_s *packet); + + +/* These are pointers to ALL registered at86rf23x devices. + * This table is used during irqs to find the context + * Only one device is supported for now. + * More devices can be supported in the future by lookup them up + * using the IRQ number. See the ENC28J60 or CC3000 drivers for reference. + */ + +static struct at86rf23x_dev_s g_at86rf23x_devices[1]; + +static const struct ieee802154_devops_s at86rf23x_devops = +{ + .setchannel = at86rf23x_setchannel, + .getchannel = at86rf23x_getchannel, + .setpanid = at86rf23x_setpanid, + .getpanid = at86rf23x_getpanid, + .setsaddr = at86rf23x_setsaddr, + .getsaddr = at86rf23x_getsaddr, + .seteaddr = at86rf23x_seteaddr, + .geteaddr = at86rf23x_geteaddr, + .setpromisc = at86rf23x_setpromisc, + .getpromisc = at86rf23x_getpromisc, + .setdevmode = at86rf23x_setdevmode, + .getdevmode = at86rf23x_getdevmode, + .settxpower = at86rf23x_settxpower, + .gettxpower = at86rf23x_gettxpower, + .setcca = at86rf23x_setcca, + .getcca = at86rf23x_getcca, + .ioctl = at86rf23x_ioctl, + .energydetect = at86rf23x_energydetect, + .rxenable = at86rf23x_rxenable, + .transmit = at86rf23x_transmit +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ +#ifndef CONFIG_SPI_EXCHANGE +#error CONFIG_SPI_EXCHANGE required for this driver +#endif + +/* hardware access routines */ + +/**************************************************************************** + * Name: at86rf23x_lock + * + * Description: + * Acquire exclusive access to the shared SPI bus. + * + ****************************************************************************/ + +static void at86rf23x_lock(FAR struct spi_dev_s *spi) +{ + SPI_LOCK (spi, 1); + SPI_SETBITS (spi, 8); + SPI_SETMODE (spi, CONFIG_IEEE802154_at86rf23x_SPIMODE ); + SPI_SETFREQUENCY(spi, CONFIG_IEEE802154_at86rf23x_FREQUENCY ); + +} + +/**************************************************************************** + * Name: at86rf23x_unlock + * + * Description: + * Release exclusive access to the shared SPI bus. + * + ****************************************************************************/ + +static void at86rf23x_unlock(FAR struct spi_dev_s *spi) +{ + SPI_LOCK(spi,0); +} + +/**************************************************************************** + * Name: at86rf23x_setreg + * + * Description: + * Define the value of an at86rf23x device register + * + ****************************************************************************/ + +static void at86rf23x_setreg(FAR struct spi_dev_s *spi, uint32_t addr, uint8_t val) +{ + uint8_t reg[2]; + + reg[0] = addr; + reg[0] |= RF23X_SPI_REG_WRITE; + + reg[1] = val; + at86rf23x_lock(spi); + SPI_SELECT(spi, SPIDEV_IEEE802154, true); + SPI_SNDBLOCK(spi, reg, 2); + SPI_SELECT(spi, SPIDEV_IEEE802154, false); + at86rf23x_unlock(spi); + + vdbg("0x%02X->r[0x%02X]\n", val, addr); + +} + +/**************************************************************************** + * Name: at86rf23x_getreg + * + * Description: + * Return the value of an at86rf23x device register + * + ****************************************************************************/ +static uint8_t at86rf23x_getreg(FAR struct spi_dev_s *spi, uint32_t addr) +{ + uint8_t reg[2]; + uint8_t val[2]; + + /* Add Read mask to desired register */ + reg[0] = addr | RF23X_SPI_REG_READ; + + at86rf23x_lock (spi); + + SPI_SELECT (spi, SPIDEV_IEEE802154, true); + SPI_EXCHANGE (spi, reg, val, 2); + SPI_SELECT (spi, SPIDEV_IEEE802154, false); + + at86rf23x_unlock(spi); + + vdbg("r[0x%02X]=0x%02X\n",addr,val[1]); + + return val[1]; +} + +/**************************************************************************** + * Name: at86rf23x_setregbits + * + * Description: + * Read the current value of the register. Change only the portion + * of the register we need to change and write the value back to the + * register. + * + ****************************************************************************/ +static void at86rf23x_setregbits(FAR struct spi_dev_s *spi, + uint8_t addr, + uint8_t pos, + uint8_t mask, + uint8_t val) +{ + uint8_t reg; + + reg = at86rf23x_getreg(spi, addr); + reg = (reg & ~(mask << pos)) | (val << pos); + at86rf23x_setreg(spi, addr, reg); +} + +/**************************************************************************** + * Name: at86rf23x_getregbits + * + * Description: + * Return the value of an section of the at86rf23x device register. + * + ****************************************************************************/ +static uint8_t at86rf23x_getregbits(FAR struct spi_dev_s *spi, + uint8_t addr, + uint8_t pos, + uint8_t mask) +{ + uint8_t val; + + val = at86rf23x_getreg(spi, addr); + val = (val >> pos) & mask; + + return val; +} + +/**************************************************************************** + * Name: at86rf23x_writebuffer + * + * Description: + * Write frame to the transmit buffer of the radio. This does not + * initiate the transfer, just write to the buffer. + * + ****************************************************************************/ +static int at86rf23x_writeframe(FAR struct spi_dev_s *spi, uint8_t *frame, uint8_t len) +{ +// report_packet(frame_wr, len); + uint8_t reg = RF23X_SPI_FRAME_WRITE; + + at86rf23x_lock(spi); + + SPI_SELECT(spi, SPIDEV_IEEE802154, true); + + SPI_SNDBLOCK(spi, ®, 1); + SPI_SNDBLOCK(spi, &frame, len); + + SPI_SELECT(spi, SPIDEV_IEEE802154, false); + + at86rf23x_unlock(spi); + + return len; +} + +/**************************************************************************** + * Name: at86rf23x_readframe + * + * Description: + * Read the buffer memory of the radio. This is used when the radio + * indicates a frame has been received. + * + ****************************************************************************/ +static uint8_t at86rf23x_readframe(FAR struct spi_dev_s *spi, uint8_t *frame_rx) +{ + uint8_t len, reg; + + reg = RF23X_SPI_FRAME_READ; + + at86rf23x_lock(spi); + SPI_SELECT(spi, SPIDEV_IEEE802154, true); + + SPI_SNDBLOCK(spi, ®, 1); + SPI_RECVBLOCK(spi, &len, 1); + SPI_RECVBLOCK(spi, frame_rx, len+3); + + SPI_SELECT(spi, SPIDEV_IEEE802154, false); + at86rf23x_unlock(spi); + + return len; +} + + +/**************************************************************************** + * Name: at86rf23x_getTRXstate + * + * Description: + * Return the current status of the TRX state machine. + * + ****************************************************************************/ +static uint8_t at86rf23x_getTRXstate(FAR struct at86rf23x_dev_s *dev) +{ + return at86rf23x_getregbits(dev->spi, RF23X_TRXSTATUS_STATUS); +} + +/**************************************************************************** + * Name: at86rf23x_setTRXstate + * + * Description: + * Set the TRX state machine to the desired state. If the state machine + * cannot move to the desired state an ERROR is returned. If the transistion + * is successful an OK is returned. This is a long running function due to + * waiting for the transistion delay between states. This can be as long as + * 510us. + * + ****************************************************************************/ +static int at86rf23x_setTRXstate(FAR struct at86rf23x_dev_s *dev, uint8_t state, uint8_t force) +{ + /* Get the current state of the transceiver */ + uint8_t status = at86rf23x_getTRXstate(dev); + + int ret = OK; + + /* TODO I don't have every state included verify this will work with SLEEP */ + if((status != TRX_STATUS_TRXOFF) && + (status != TRX_STATUS_RXON) && + (status != TRX_STATUS_PLLON) && + (status != TRX_STATUS_RXAACKON) && + (status != TRX_STATUS_TXARETON) && + (status != TRX_STATUS_PON)) + { + dbg("Invalid State\n"); + return ERROR; + } + + int8_t init_status = status; + + /* Start the state change */ + switch(state) + { + case TRX_CMD_TRXOFF: + if(status == TRX_STATUS_TRXOFF) + { + break; + } + /* verify in a state that will transfer to TRX_OFF if not check if force is required */ + if( (status == TRX_STATUS_RXON) || + (status == TRX_STATUS_PLLON) || + (status == TRX_STATUS_RXAACKON) || + (status == TRX_STATUS_TXARETON)) + { + at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_TRXOFF); + up_udelay(RF23X_TIME_TRANSITION_PLL_ACTIVE); + } + else if(status == TRX_STATUS_PON) + { + at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_TRXOFF); + up_udelay(RF23X_TIME_P_ON_TO_TRXOFF); + } + else if(force) + { + at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_FORCETRXOFF); + up_udelay(RF23X_TIME_FORCE_TRXOFF); + } + + status = at86rf23x_getregbits(dev->spi, RF23X_TRXSTATUS_STATUS); + + if(status != TRX_STATUS_TRXOFF) + { + ret = ERROR; + } + + break; + + case TRX_CMD_RX_ON: + + if(status == TRX_STATUS_RXON) + { + break; + } + + if (status == TRX_STATUS_TRXOFF) + { + at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_RX_ON); + up_udelay(RF23X_TIME_TRXOFF_TO_PLL); + } + + else if((status == TRX_STATUS_RXAACKON) || + (status == TRX_STATUS_RXON) || + (status == TRX_STATUS_PLLON) || + (status == TRX_STATUS_TXARETON)) + { + at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_RX_ON); + up_udelay(RF23X_TIME_TRANSITION_PLL_ACTIVE); + } + + status = at86rf23x_getregbits(dev->spi, RF23X_TRXSTATUS_STATUS); + + if(status != TRX_STATUS_RXON) + { + ret = ERROR; + } + break; + + /* transition to PLL_ON */ + case TRX_CMD_PLL_ON: + + if(status == TRX_STATUS_PLLON) + { + break; + } + + if (status == TRX_STATUS_TRXOFF) + { + at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_PLL_ON); + up_udelay(RF23X_TIME_TRXOFF_TO_PLL); + } + else + { + at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_PLL_ON); + up_udelay(RF23X_TIME_TRANSITION_PLL_ACTIVE); + } + + status = at86rf23x_getregbits(dev->spi, RF23X_TRXSTATUS_STATUS); + + if(status != TRX_STATUS_PLLON) + { + ret = ERROR; + } + break; + + case TRX_CMD_RX_AACK_ON: + + if(status == TRX_STATUS_RXAACKON) + { + break; + } + + if (status == TRX_STATUS_TRXOFF || status == TRX_STATUS_TXARETON) + { + at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_RX_ON); + + (status == TRX_STATUS_TRXOFF) ? up_udelay(RF23X_TIME_TRXOFF_TO_PLL) : + up_udelay(RF23X_TIME_TRANSITION_PLL_ACTIVE); + } + + status = at86rf23x_getTRXstate(dev); + + if ((status == TRX_STATUS_RXON) || (status == TRX_STATUS_PLLON)) + { + at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_RX_AACK_ON); + up_udelay(RF23X_TIME_TRANSITION_PLL_ACTIVE); + } + + status = at86rf23x_getregbits(dev->spi, RF23X_TRXSTATUS_STATUS); + + if(status != TRX_STATUS_RXAACKON) + { + ret = ERROR; + } + + break; + + case TRX_STATUS_TXARETON: + + if(status == TRX_STATUS_TXARETON) + { + break; + } + + if (status == TRX_STATUS_TRXOFF) + { + at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_RX_ON); + up_udelay(RF23X_TIME_TRXOFF_TO_PLL); + } + + if ((status == TRX_STATUS_RXON) || (status == TRX_STATUS_PLLON)) + { + at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_TX_ARET_ON); + up_udelay(RF23X_TIME_TRANSITION_PLL_ACTIVE); + } + else if (status == TRX_STATUS_RXAACKON) + { + at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_RX_ON); + up_udelay(RF23X_TIME_TRANSITION_PLL_ACTIVE); + + at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_TX_ARET_ON); + up_udelay(RF23X_TIME_TRANSITION_PLL_ACTIVE); + } + + status = at86rf23x_getregbits(dev->spi, RF23X_TRXSTATUS_STATUS); + + if(status != TRX_STATUS_TXARETON) + { + ret = ERROR; + } + + break; + + case TRX_STATUS_SLEEP: + at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_FORCETRXOFF); + up_udelay(RF23X_TIME_CMD_FORCE_TRX_OFF); + + dev->lower->slptr(dev->lower, true); + up_udelay(RF23X_TIME_TRXOFF_TO_SLEEP); + + status = at86rf23x_getregbits(dev->spi, RF23X_TRXSTATUS_STATUS); + break; + + default: + dbg("%s \n", EINVAL_STR); + init_status = 0;/* Placed this here to keep compiler happy when not in debug */ + return -EINVAL; + + } + if(ret == ERROR) + { + dbg("State Transistion Error\n"); + } + + vdbg("Radio state change state[0x%02x]->state[0x%02x]\n", init_status, status); + + return ret; +} + +/* Publicized driver routines */ + +/**************************************************************************** + * Name: at86rf23x_setchannel + * + * Description: + * Define the current radio channel the device is operating on. + * In the 2.4 GHz, there are 16 channels, each 2 MHz wide, 5 MHz spacing: + * Chan MHz Chan MHz Chan MHz Chan MHz + * 11 2405 15 2425 19 2445 23 2465 + * 12 2410 16 2430 20 2450 24 2470 + * 13 2415 17 2435 21 2455 25 2475 + * 14 2420 18 2440 22 2460 26 2480 + * + * + ****************************************************************************/ +static int at86rf23x_setchannel(FAR struct ieee802154_dev_s *ieee, uint8_t chan) +{ + FAR struct at86rf23x_dev_s *dev = (FAR struct at86rf23x_dev_s *)ieee; + uint8_t state; + + /* Validate if chan is a valid channel */ + if(chan<11 || chan>26) + { + dbg("Invalid requested chan: %d\n",chan); + return -EINVAL; + } + + /* Validate we are in an acceptable mode to change the channel */ + state = at86rf23x_getTRXstate(dev); + + if((TRX_STATUS_SLEEP == state) || (TRX_STATUS_PON == state)) { + dbg("Radio in invalid mode [%02x] to set the channel\n", state); + return ERROR; + } + /* Set the Channel on the transceiver */ + + at86rf23x_setregbits(dev->spi, RF23X_CCA_BITS_CHANNEL, chan); + + /* Set the channel within local device */ + dev->channel = chan; + + vdbg("CHANNEL Changed to %d\n", chan); + + return OK; +} + +/**************************************************************************** + * Name: at86rf23x_getchannel + * + * Description: + * Define the current radio channel the device is operating on. + * In the 2.4 GHz, there are 16 channels, each 2 MHz wide, 5 MHz spacing: + * Chan MHz Chan MHz Chan MHz Chan MHz + * 11 2405 15 2425 19 2445 23 2465 + * 12 2410 16 2430 20 2450 24 2470 + * 13 2415 17 2435 21 2455 25 2475 + * 14 2420 18 2440 22 2460 26 2480 + * + * This section assumes that the transceiver is not in SLEEP or P_ON state. + * + * + ****************************************************************************/ +static int at86rf23x_getchannel(FAR struct ieee802154_dev_s *ieee, FAR uint8_t *chan) +{ + FAR struct at86rf23x_dev_s *dev = (FAR struct at86rf23x_dev_s *)ieee; + + /* Set the Channel on the transceiver */ + *chan = at86rf23x_getregbits(dev->spi, RF23X_CCA_BITS_CHANNEL); + + /* Set the channel within local device */ + dev->channel = *chan; + + return OK; +} + +/**************************************************************************** + * Name: at86rf23x_setpanid + * + * Description: + * Define the PAN ID for the network. + * + ****************************************************************************/ +static int at86rf23x_setpanid(FAR struct ieee802154_dev_s *ieee, uint16_t panid) +{ + FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; + uint8_t *pan = (uint8_t *)&panid; + + at86rf23x_setreg(dev->spi, RF23X_REG_PANID0, pan[0]); + at86rf23x_setreg(dev->spi, RF23X_REG_PANID1, pan[1]); + + return OK; +} + +/**************************************************************************** + * Name: at86rf23x_getpanid + * + * Description: + * Define the PAN ID for the network. + * + ****************************************************************************/ +static int at86rf23x_getpanid(FAR struct ieee802154_dev_s *ieee, FAR uint16_t *panid) +{ + FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; + uint8_t *pan = (uint8_t *)panid; + /* TODO: Check if we need to pay attention to endianness */ + pan[0] = at86rf23x_getreg(dev->spi, RF23X_REG_PANID0); + pan[1] = at86rf23x_getreg(dev->spi, RF23X_REG_PANID1); + + return OK; +} + +/**************************************************************************** + * Name: at86rf23x_setsaddr + * + * Description: + * Define the Short Address for the device. + * + ****************************************************************************/ +static int at86rf23x_setsaddr(FAR struct ieee802154_dev_s *ieee, uint16_t saddr) +{ + FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; + uint8_t *addr = (uint8_t *)&saddr; + + at86rf23x_setreg(dev->spi, RF23X_REG_SADDR0, addr[0]); + at86rf23x_setreg(dev->spi, RF23X_REG_SADDR1, addr[1]); + + return OK; +} + +/**************************************************************************** + * Name: at86rf23x_getsaddr + * + * Description: + * Get the short address of the device. + * + ****************************************************************************/ +static int at86rf23x_getsaddr(FAR struct ieee802154_dev_s *ieee, FAR uint16_t *saddr) +{ + FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; + uint8_t *addr = (uint8_t *)saddr; + /* TODO: Check if we need to pay attention to endianness */ + addr[0] = at86rf23x_getreg(dev->spi, RF23X_REG_SADDR0); + addr[1] = at86rf23x_getreg(dev->spi, RF23X_REG_SADDR1); + + return OK; +} + +/**************************************************************************** + * Name: at86rf23x_seteaddr + * + * Description: + * Set the IEEE address of the device. + * + ****************************************************************************/ +static int at86rf23x_seteaddr(FAR struct ieee802154_dev_s *ieee, FAR uint8_t *eaddr) +{ + FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; + /* TODO: Check if we need to pay attention to endianness */ + at86rf23x_setreg(dev->spi, RF23X_REG_IEEEADDR0, eaddr[0]); + at86rf23x_setreg(dev->spi, RF23X_REG_IEEEADDR1, eaddr[1]); + at86rf23x_setreg(dev->spi, RF23X_REG_IEEEADDR2, eaddr[2]); + at86rf23x_setreg(dev->spi, RF23X_REG_IEEEADDR3, eaddr[3]); + at86rf23x_setreg(dev->spi, RF23X_REG_IEEEADDR4, eaddr[4]); + at86rf23x_setreg(dev->spi, RF23X_REG_IEEEADDR5, eaddr[5]); + at86rf23x_setreg(dev->spi, RF23X_REG_IEEEADDR6, eaddr[6]); + at86rf23x_setreg(dev->spi, RF23X_REG_IEEEADDR7, eaddr[7]); + + return OK; +} + +/**************************************************************************** + * Name: at86rf23x_geteaddr + * + * Description: + * Get the IEEE address of the device. + * + ****************************************************************************/ +static int at86rf23x_geteaddr(FAR struct ieee802154_dev_s *ieee, FAR uint8_t *eaddr) +{ + FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; + /* TODO: Check if we need to pay attention to endianness */ + eaddr[0] = at86rf23x_getreg(dev->spi, RF23X_REG_IEEEADDR0); + eaddr[1] = at86rf23x_getreg(dev->spi, RF23X_REG_IEEEADDR1); + eaddr[2] = at86rf23x_getreg(dev->spi, RF23X_REG_IEEEADDR2); + eaddr[3] = at86rf23x_getreg(dev->spi, RF23X_REG_IEEEADDR3); + eaddr[4] = at86rf23x_getreg(dev->spi, RF23X_REG_IEEEADDR4); + eaddr[5] = at86rf23x_getreg(dev->spi, RF23X_REG_IEEEADDR5); + eaddr[6] = at86rf23x_getreg(dev->spi, RF23X_REG_IEEEADDR6); + eaddr[7] = at86rf23x_getreg(dev->spi, RF23X_REG_IEEEADDR7); + + return OK; +} + +/**************************************************************************** + * Name: at86rf23x_setpromisc + * + * Description: + * enable/disable promiscuous mode. + * + ****************************************************************************/ +static int at86rf23x_setpromisc(FAR struct ieee802154_dev_s *ieee, bool promisc) +{ + FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; + + /* TODO: Check what mode I should be in to activate promiscuous mode: + * This is way to simple of an implementation. Many other things should be set + * and/or checked before we set the device into promiscuous mode + * */ + at86rf23x_setregbits(dev->spi, RF23X_XAHCTRL1_BITS_PROM_MODE, promisc); + + return OK; +} + +/**************************************************************************** + * Name: at86rf23x_getpromisc + * + * Description: + * Check if the device is in promiscuous mode. + * + ****************************************************************************/ +static int at86rf23x_getpromisc(FAR struct ieee802154_dev_s *ieee, FAR bool *promisc) +{ + FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; + + *promisc = at86rf23x_getregbits(dev->spi, RF23X_XAHCTRL1_BITS_PROM_MODE); + + return OK; +} + +/**************************************************************************** + * Name: at86rf23x_setdevmode + * + * Description: + * Check if the device is in promiscuous mode. + * + ****************************************************************************/ +static int at86rf23x_setdevmode(FAR struct ieee802154_dev_s *ieee, uint8_t mode) +{ + FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; + + /* define dev mode */ + if(mode == IEEE802154_MODE_PANCOORD) + { + at86rf23x_setregbits(dev->spi, RF23X_CSMASEED1_IAMCOORD_BITS, 0x01); + } + else if(mode == IEEE802154_MODE_COORD) + { + /* ????? */ + } + else if(mode == IEEE802154_MODE_DEVICE) + { + at86rf23x_setregbits(dev->spi, RF23X_CSMASEED1_IAMCOORD_BITS, 0x00); + } + else + { + return -EINVAL; + } + + dev->devmode = mode; + + return OK; +} + +/**************************************************************************** + * Name: at86rf23x_getdevmode + * + * Description: + * get the device mode type of the radio. + * + ****************************************************************************/ +static int at86rf23x_getdevmode (FAR struct ieee802154_dev_s *ieee, FAR uint8_t *mode) +{ + FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; + int val; + + val = at86rf23x_getregbits(dev->spi, RF23X_CSMASEED1_IAMCOORD_BITS); + + if(val == 1) + { + mode = IEEE802154_MODE_PANCOORD; + } + else + { + mode = IEEE802154_MODE_DEVICE; + } + + return OK; +} + +/**************************************************************************** + * Name: at86rf23x_settxpower + * + * Description: + * set the tx power attenuation or amplification + * + ****************************************************************************/ +static int at86rf23x_settxpower(FAR struct ieee802154_dev_s *ieee, int32_t txpwr) +{ + FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; + + /* TODO: this needs alot of work to make sure all chips can share this function */ + + /* Right now we only set tx power to 0 */ + at86rf23x_setreg(dev->spi, RF23X_REG_TXPWR, RF23X_TXPWR_0); + + return OK; +} + +/**************************************************************************** + * Name: at86rf23x_gettxpower + * + * Description: + * get the tx power attenuation or amplification. + * + ****************************************************************************/ +static int at86rf23x_gettxpower(FAR struct ieee802154_dev_s *ieee, FAR int32_t *txpwr) +{ + /* TODO: this needs alot of work to make sure all chips can share this function */ + FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; + uint8_t reg; + /* TODO: this needs alot of work to make sure all chips can share this function */ + + /* Right now we only get negative values */ + reg = at86rf23x_getreg(dev->spi, RF23X_REG_TXPWR); + + switch(reg) + { + case RF23X_TXPWR_POS_4: + *txpwr = 0; + break; + case RF23X_TXPWR_POS_3_7: + *txpwr = 0; + break; + case RF23X_TXPWR_POS_3_4: + *txpwr = 0; + break; + case RF23X_TXPWR_POS_3: + *txpwr = 0; + break; + case RF23X_TXPWR_POS_2_5: + *txpwr = 0; + break; + case RF23X_TXPWR_POS_2: + *txpwr = 0; + break; + case RF23X_TXPWR_POS_1: + *txpwr = 0; + break; + case RF23X_TXPWR_0: + *txpwr = 0; + break; + case RF23X_TXPWR_NEG_1: + *txpwr = 1000; + break; + case RF23X_TXPWR_NEG_2: + *txpwr = 2000; + break; + case RF23X_TXPWR_NEG_3: + *txpwr = 3000; + break; + case RF23X_TXPWR_NEG_4: + *txpwr = 4000; + break; + case RF23X_TXPWR_NEG_6: + *txpwr = 6000; + break; + case RF23X_TXPWR_NEG_8: + *txpwr = 8000; + break; + case RF23X_TXPWR_NEG_12: + *txpwr = 12000; + break; + case RF23X_TXPWR_NEG_17: + *txpwr = 17000; + break; + } + + return OK; +} + +/**************************************************************************** + * Name: at86rf23x_setcca + * + * Description: + * Configures if energy detection is used or carrier sense. The base + * measurement is configured here as well + * + * + ****************************************************************************/ +static int at86rf23x_setcca(FAR struct ieee802154_dev_s *ieee, FAR struct ieee802154_cca_s *cca) +{ + FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; + + /* TODO: This doesn't fit the RF233 completely come back to this */ + + if (!cca->use_ed && !cca->use_cs) + { + return -EINVAL; + } + if (cca->use_cs && cca->csth > 0x0f) + { + return -EINVAL; + } + + if (cca->use_ed) + { + at86rf23x_setregbits(dev->spi, RF23X_CCA_BITS_MODE, RF23X_CCA_MODE_ED); + } + if (cca->use_cs) + { + at86rf23x_setregbits(dev->spi, RF23X_CCA_BITS_MODE, RF23X_CCA_MODE_CS); + } + + memcpy(&dev->cca, cca, sizeof(struct ieee802154_cca_s)); + + return OK; +} + +/**************************************************************************** + * Name: at86rf23x_getcca + * + * Description: + * Get CCA for ???: TODO: need to implement + * + ****************************************************************************/ +static int at86rf23x_getcca(FAR struct ieee802154_dev_s *ieee, FAR struct ieee802154_cca_s *cca) +{ + FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; + +#warning at86rf23x_getcca not implemented. + + UNUSED(dev); + UNUSED(cca); + + return ERROR; +} + +/**************************************************************************** + * Name: at86rf23x_ioctl + * + * Description: + * Control operations for the radio. + * + ****************************************************************************/ +static int at86rf23x_ioctl(FAR struct ieee802154_dev_s *ieee, int cmd, unsigned long arg) +{ + FAR struct at86rf23x_dev_s *dev = (FAR struct at86rf23x_dev_s *)ieee; + switch(cmd) + { + case MAC854IORDUMP: return at86rf23x_regdump(dev); + default: return -EINVAL; + } +} +/**************************************************************************** + * Name: at86rf23x_energydetect + * + * Description: + * Perform energy detection scan. TODO: Need to implement. + * + ****************************************************************************/ +static int at86rf23x_energydetect(FAR struct ieee802154_dev_s *ieee, FAR uint8_t *energy) +{ + +#warning at86rf23x_energydetect not implemented. + + /* Not yet implemented */ + + return ERROR; +} + +/**************************************************************************** + * Name: at86rf23x_initialize + * + * Description: + * Initialize the radio. + * + ****************************************************************************/ +int at86rf23x_initialize(FAR struct at86rf23x_dev_s *dev) +{ + uint8_t part; + uint8_t version; + + at86rf23x_resetrf(dev); + + part = at86rf23x_getreg(dev->spi, RF23X_REG_PART); + version = at86rf23x_getreg(dev->spi, RF23X_REG_VERSION); + + dbg("Radio part: 0x%02x version: 0x%02x found\n", part, version); + + return OK; +} + +/**************************************************************************** + * Name: at86rf23x_resetrf + * + * Description: + * Hard Reset of the radio. The reset also brings the radio into the + * TRX_OFF state. + * + ****************************************************************************/ +static int at86rf23x_resetrf(FAR struct at86rf23x_dev_s *dev) +{ + FAR const struct at86rf23x_lower_s *lower = dev->lower; + uint8_t trx_status, retry_cnt = 0; + + /* Reset the radio */ + lower->reset(lower, 0); + lower->slptr(lower, 0); + + up_udelay(RF23X_TIME_RESET); + lower->reset(lower, 1); + + + /* Dummy read of IRQ register */ + at86rf23x_getreg(dev->spi, RF23X_REG_IRQ_STATUS); + + do + { + trx_status = at86rf23x_setTRXstate(dev, TRX_CMD_TRXOFF, true); + + if (retry_cnt == RF23X_MAX_RETRY_RESET_TO_TRX_OFF) + { + dbg("Reset of transceiver failed\n"); + return ERROR; + } + + retry_cnt++; + } while (trx_status != OK); + + return OK; +} + +/**************************************************************************** + * Name: at86rf23x_rxenable + * + * Description: + * puts the radio into RX mode and brings in the buffer to handle + * RX messages. + * + ****************************************************************************/ +static int at86rf23x_rxenable(FAR struct ieee802154_dev_s *ieee, bool state, + FAR struct ieee802154_packet_s *packet) +{ + FAR struct at86rf23x_dev_s *dev = (FAR struct at86rf23x_dev_s *)ieee; + + /* Set the radio to the receive state */ + return at86rf23x_setTRXstate(dev, TRX_CMD_RX_ON, false); + + /* Enable the RX IRQ */ + + /* TODO: + * I am not sure what to do here since the at86rf23x shares the + * irq with the tx finished. Better planning needs to be done on + * my end. + */ + + /* Set buffer to receive next packet */ + ieee->rxbuf = packet; +} + +/**************************************************************************** + * Name: at86rf23x_interrupt + * + * Description: + * Actual interrupt handler ran inside privileged space. + * + ****************************************************************************/ +static int at86rf23x_interrupt(int irq, FAR void *context) +{ + + /* To support multiple devices, + * retrieve the priv structure using the irq number */ + + register FAR struct at86rf23x_dev_s *dev = &g_at86rf23x_devices[0]; + + /* In complex environments, we cannot do SPI transfers from the interrupt + * handler because semaphores are probably used to lock the SPI bus. In + * this case, we will defer processing to the worker thread. This is also + * much kinder in the use of system resources and is, therefore, probably + * a good thing to do in any event. + */ + + DEBUGASSERT(work_available(&dev->irqwork)); + + /* Notice that further GPIO interrupts are disabled until the work is + * actually performed. This is to prevent overrun of the worker thread. + * Interrupts are re-enabled in enc_irqworker() when the work is completed. + */ + dev->lower->irq(dev->lower, NULL, FALSE); + // dev->lower->enable(dev->lower, FALSE); + + return work_queue(HPWORK, &dev->irqwork, at86rf23x_irqworker, (FAR void *)dev, 0); +} + +/**************************************************************************** + * Name: at86rf23x_regdump + * + * Description: + * Dumps all the RF23X radios registers from 00 - 2F there are a few other + * registers that don't get dumped but just fore the ease of code I left + * them out. + * + ****************************************************************************/ +static int at86rf23x_regdump(FAR struct at86rf23x_dev_s *dev) +{ + uint32_t i; + char buf[4+16*3+2+1]; + + int len=0; + printf("RF23X regs:\n"); + + for (i=0;i<0x30;i++) + { + /* First row and every 15 regs */ + if ((i & 0x0f) == 0) + { + len = sprintf(buf, "%02x: ",i&0xFF); + } + + /* print the register value */ + len += sprintf(buf+len, "%02x ", at86rf23x_getreg(dev->spi, i)); + + /* at the end of each 15 regs or end of rf233s regs and actually print dbg message*/ + if ((i&15)==15 || i == 0x2f) + { + sprintf(buf+len, "\n"); + printf("%s",buf); + } + } + + /* TODO: I have a few more regs that are not consecutive. Will print later */ + + return 0; +} + +/**************************************************************************** + * Name: at86rf23x_irqworker + * + * Description: + * Actual thread to handle the irq outside of privaleged mode. + * + ****************************************************************************/ +static void at86rf23x_irqworker(FAR void *arg) +{ + FAR struct at86rf23x_dev_s *dev = (FAR struct at86rf23x_dev_s *)arg; + + uint8_t irq_status = at86rf23x_getreg(dev->spi, RF23X_REG_IRQ_STATUS); + + vdbg("IRQ: 0x%02X\n", irq_status); + + if((irq_status & (1<<3)) != 0) + { + if((irq_status & (1<<2)) != 0) + { + at86rf23x_irqwork_rx(dev); + } + else + { + at86rf23x_irqwork_tx(dev); + } + } + else + { + dbg("Unknown IRQ Status: %d\n", irq_status); + + /* Re enable the IRQ even if we don't know how to handle previous status*/ + dev->lower->irq(dev->lower, NULL, true); + } +} + +/**************************************************************************** + * Name: at86rf23x_irqwork_rx + * + * Description: + * Misc/unofficial device controls. + * + ****************************************************************************/ +static void at86rf23x_irqwork_rx(FAR struct at86rf23x_dev_s *dev) +{ + uint8_t rx_len; + + vdbg("6LOWPAN:Rx IRQ\n"); + + rx_len = at86rf23x_readframe(dev->spi, dev->ieee.rxbuf->data); + + dev->ieee.rxbuf->len = rx_len; + dev->ieee.rxbuf->lqi = 0; + dev->ieee.rxbuf->rssi = 0; + + sem_post(&dev->ieee.rxsem); + /* + * TODO: + * Not to sure yet what I should do here. I will something + * soon. + */ + + /* Re enable the IRQ */ + dev->lower->irq(dev->lower, NULL, true); +} + +/**************************************************************************** + * Name: at86rf23x_irqwork_tx + * + * Description: + * Misc/unofficial device controls. + * + ****************************************************************************/ +static void at86rf23x_irqwork_tx(FAR struct at86rf23x_dev_s *dev) +{ + vdbg("6LOWPAN:Tx IRQ\n"); + + /* + * TODO: + * There needs to be more here but for now just alert the waiting + * thread. Maybe put it back into Rx mode + * + */ + + /* Re enable the IRQ */ + dev->lower->irq(dev->lower, NULL, true); + + sem_post(&dev->ieee.txsem); + + +} + +/**************************************************************************** + * Name: at86rf23x_transmit + * + * Description: + * transmission the packet. Send the packet to the radio and initiate the + * transmit process. Then block the function till we have a successful + * transmission + * + ****************************************************************************/ +static int at86rf23x_transmit(FAR struct ieee802154_dev_s *ieee, FAR struct ieee802154_packet_s *packet) +{ + FAR struct at86rf23x_dev_s *dev = (FAR struct at86rf23x_dev_s *)ieee; + /* + * TODO: + * A plan needs to be made on when we declare the transmission successful. + * 1. If the packet is sent + * 2. If we receive an ACK. + * 3. Where do we control the retry process? + */ + + if(at86rf23x_setTRXstate(dev, TRX_CMD_PLL_ON, false)) + { + at86rf23x_writeframe(dev->spi, packet->data, packet->len); + } + else + { + dbg("Transmit could not put the radio in a Tx state\n"); + return ERROR; + } + + /* put the thread that requested transfer to a waiting state */ + sem_wait(&dev->ieee.txsem); + /*TODO Verify that I want to stay in the PLL state or if I want to roll back to RX_ON */ + return OK; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: at86rf23x_init + * + * Description: + * Return an at86rf23x device for use by other drivers. + * + ****************************************************************************/ + +FAR struct ieee802154_dev_s *at86rf23x_init(FAR struct spi_dev_s *spi, FAR const struct at86rf23x_lower_s *lower) +{ + FAR struct at86rf23x_dev_s *dev; + struct ieee802154_cca_s cca; + + dev = &g_at86rf23x_devices[0]; + /* Attach the interface, lower driver, and devops */ + dev->spi = spi; + dev->lower = lower; + dev->ieee.ops = &at86rf23x_devops; + + /* attach irq */ + if (lower->irq(lower, at86rf23x_interrupt, false) != OK) + { + return NULL; + } + + sem_init(&dev->ieee.rxsem, 0, 0); + sem_init(&dev->ieee.txsem, 0, 0); + + /*Initialize device */ + at86rf23x_initialize(dev); + + /* Configure the desired IRQs of the devices */ + at86rf23x_setreg(dev->spi, RF23X_REG_IRQ_MASK, RF23X_IRQ_MASK_DEFAULT); + + /* Turn the PLL to the on state */ + at86rf23x_setTRXstate(dev, TRX_CMD_PLL_ON, false); + + + /*SEED value of the CSMA backoff algorithm. */ + + +#ifdef RF23X_ANTENNA_DIVERSITY + + /* Use antenna diversity */ + trx_bit_write(SR_ANT_CTRL, ANTENNA_DEFAULT); + trx_bit_write(SR_PDT_THRES, THRES_ANT_DIV_ENABLE); + trx_bit_write(SR_ANT_DIV_EN, ANT_DIV_ENABLE); + trx_bit_write(SR_ANT_EXT_SW_EN, ANT_EXT_SW_ENABLE); + +#endif + +#ifdef RF23X_TIMESTAMP + + /* Enable timestamp init code goes here */ + +#endif + +#ifdef RF23X_RF_FRONTEND_CTRL + + /* Init front end control code goes here */ + +#endif + /* Set the channel of the radio */ + at86rf23x_setchannel(&dev->ieee, 12); + + /* Configure the Pan id */ + // at86rf23x_setpanid (&dev->ieee, IEEE802154_PAN_DEFAULT); + /* Configure the Short Addr */ + // at86rf23x_setsaddr (&dev->ieee, IEEE802154_SADDR_UNSPEC); + /* Configure the IEEE Addr */ +// at86rf23x_seteaddr (&dev->ieee, IEEE802154_EADDR_UNSPEC); + + /* Default device params at86rf23x defaults to energy detect only */ + cca.use_ed = 1; + cca.use_cs = 0; + cca.edth = 0x60; /* CCA mode ED, no carrier sense, recommenced ED threshold -69 dBm */ + at86rf23x_setcca(&dev->ieee, &cca); + + + + /* Put the Device to RX ON Mode */ + // at86rf23x_setTRXstate(dev, TRX_CMD_RX_ON, false ); + + + /* Enable Radio IRQ */ + lower->irq(lower, at86rf23x_interrupt, true); + + return &dev->ieee; +} + diff --git a/drivers/wireless/ieee802154/at86rf23x.h b/drivers/wireless/ieee802154/at86rf23x.h new file mode 100644 index 0000000000..51c96ced3c --- /dev/null +++ b/drivers/wireless/ieee802154/at86rf23x.h @@ -0,0 +1,204 @@ +/* + * at86rf23x.h + * + * Created on: Feb 24, 2016 + * Author: poppe + */ + +#ifndef APPS_EXTERNAL_IEEE_AT86RF23X_H_ +#define APPS_EXTERNAL_IEEE_AT86RF23X_H_ + +#define RF23X_SPI_REG_READ 0x80 +#define RF23X_SPI_REG_WRITE 0xC0 +#define RF23X_SPI_FRAME_WRITE 0x60 +#define RF23X_SPI_FRAME_READ 0x20 +#define RF23X_SPI_SRAM_READ 0x00 +#define RF23X_SPI_SRAM_WRITE 0x40 + +/* us Times Constants for the RF233 */ +#define RF23X_TIME_RESET_BOOT 510 +#define RF23X_TIME_FORCE_TRXOFF 100 +#define RF23X_TIME_P_ON_TO_TRXOFF 510 +#define RF23X_TIME_SLEEP_TO_TRXOFF 1200 +#define RF23X_TIME_RESET 6 +#define RF23X_TIME_ED_MEASUREMENT 140 +#define RF23X_TIME_CCA 140 +#define RF23X_TIME_PLL_LOCK 150 +#define RF23X_TIME_FTN_TUNNING 25 +#define RF23X_TIME_NOCLK_TO_WAKE 6 +#define RF23X_TIME_CMD_FORCE_TRX_OFF 1 +#define RF23X_TIME_TRXOFF_TO_PLL 180 +#define RF23X_TIME_TRANSITION_PLL_ACTIVE 1 +#define RF23X_TIME_TRXOFF_TO_SLEEP 1200 + +#define RF23X_MAX_RETRY_RESET_TO_TRX_OFF 5 + + +#define RF23X_REG_TRXSTATUS 0x01 +#define RF23X_REG_TRXSTATE 0x02 +#define RF23X_REG_TRXCTRL0 0x03 +#define RF23X_REG_TRXCTRL1 0x04 +#define RF23X_REG_TXPWR 0x05 +#define RF23X_REG_RSSI 0x06 +#define RF23X_REG_EDLEVEL 0x07 +#define RF23X_REG_CCA 0x08 +#define RF23X_REG_THRES 0x09 +#define RF23X_REG_RXCTRL 0x0a +#define RF23X_REG_SFD 0x0b +#define RF23X_REG_TRXCTRL2 0x0c +#define RF23X_REG_ANT_DIV 0x0d +#define RF23X_REG_IRQ_MASK 0x0e +#define RF23X_REG_IRQ_STATUS 0x0f +#define RF23X_REG_VREG_CTRL 0x10 +#define RF23X_REG_BATMON 0x11 +#define RF23X_REG_XOSC_CTRL 0x12 +#define RF23X_REG_CCCTRL0 0x13 +#define RF23X_REG_CCCTRL1 0x14 +#define RF23X_REG_RXSYN 0x15 +#define RF23X_REG_TRXRPC 0x16 +#define RF23X_REG_XAHCTRL1 0x17 +#define RF23X_REG_FTNCTRL 0x18 +#define RF23X_REG_XAHCTRL2 0x19 +#define RF23X_REG_PLLCF 0x1a +#define RF23X_REG_PLLDCU 0x1b +#define RF23X_REG_PART 0x1c +#define RF23X_REG_VERSION 0x1d +#define RF23X_REG_MANID0 0x1e +#define RF23X_REG_MANID1 0x1f +#define RF23X_REG_SADDR0 0x20 +#define RF23X_REG_SADDR1 0x21 +#define RF23X_REG_PANID0 0x22 +#define RF23X_REG_PANID1 0x23 +#define RF23X_REG_IEEEADDR0 0x24 +#define RF23X_REG_IEEEADDR1 0x25 +#define RF23X_REG_IEEEADDR2 0x26 +#define RF23X_REG_IEEEADDR3 0x27 +#define RF23X_REG_IEEEADDR4 0x28 +#define RF23X_REG_IEEEADDR5 0x29 +#define RF23X_REG_IEEEADDR6 0x2a +#define RF23X_REG_IEEEADDR7 0x2b +#define RF23X_REG_XAHCTRL0 0x2c +#define RF23X_REG_CSMASEED0 0x2d +#define RF23X_REG_CSMASEED1 0x2e +#define RF23X_REG_CSMABE 0x2f +#define RF23X_REG_TSTCTRLDIGI 0x36 +#define RF23X_REG_TSTAGC 0x3c +#define RF23X_REG_SDM 0x3d +#define RF23X_REG_PHYTXTIME 0x3b +#define RF23X_REG_PHYPMUVALUE 0x3b + + +#define RF23X_TRXSTATUS_POS 0 +#define RF23X_TRXSTATUS_MASK 0x1f +#define RF23X_TRXSTATUS_STATUS RF23X_REG_TRXSTATUS, RF23X_TRXSTATUS_POS, RF23X_TRXSTATUS_MASK + +#define RF23X_TRXCMD_POS 0 +#define RF23X_TRXCMD_MASK 0x1f +#define RF23X_TRXCMD_STATE RF23X_REG_TRXSTATE, RF23X_TRXCMD_POS, RF23X_TRXCMD_MASK + + +#define RF23X_TXPWR_POS_4 0x00 +#define RF23X_TXPWR_POS_3_7 0x01 +#define RF23X_TXPWR_POS_3_4 0x02 +#define RF23X_TXPWR_POS_3 0x03 +#define RF23X_TXPWR_POS_2_5 0x04 +#define RF23X_TXPWR_POS_2 0x05 +#define RF23X_TXPWR_POS_1 0x06 +#define RF23X_TXPWR_0 0x07 +#define RF23X_TXPWR_NEG_1 0x08 +#define RF23X_TXPWR_NEG_2 0x09 +#define RF23X_TXPWR_NEG_3 0x0a +#define RF23X_TXPWR_NEG_4 0x0b +#define RF23X_TXPWR_NEG_6 0x0c +#define RF23X_TXPWR_NEG_8 0x0d +#define RF23X_TXPWR_NEG_12 0x0e +#define RF23X_TXPWR_NEG_17 0x0f + +/**************************************************************************** + * CCA_STATUS + ****************************************************************************/ +#define RF23X_CCA_MODE_CS_OR_ED 0x00 +#define RF23X_CCA_MODE_ED 0x01 +#define RF23X_CCA_MODE_CS 0x02 +#define RF23X_CCA_MODE_CS_AND_ED 0x03 + +#define RF23X_CCA_CHANNEL_POS 0 +#define RF23X_CCA_CHANNEL_MASK 0x1f +#define RF23X_CCA_BITS_CHANNEL RF23X_REG_CCA, RF23X_CCA_CHANNEL_POS, RF23X_CCA_CHANNEL_MASK +#define RF23X_CCA_MODE_POS 5 +#define RF23X_CCA_MODE_MASK 0x03 +#define RF23X_CCA_BITS_MODE RF23X_REG_CCA, RF23X_CCA_MODE_POS, RF23X_CCA_MODE_MASK + + +/**************************************************************************** + * XAH CTRL 1 + ****************************************************************************/ +#define RF23X_XAHCTRL1_PROM_MODE_POS 1 +#define RF23X_XAHCTRL1_PROM_MODE_MASK 0x01 +#define RF23X_XAHCTRL1_BITS_PROM_MODE RF23X_REG_XAHCTRL1, RF23X_XAHCTRL1_PROM_MODE_POS, RF23X_XAHCTRL1_PROM_MODE_MASK + +/**************************************************************************** + * CSMA SEED 0 + ****************************************************************************/ + +/**************************************************************************** + * CSMA SEED 1 + ****************************************************************************/ +#define RF23X_CSMASEED1_IAMCOORD_POS 3 +#define RF23X_CSMASEED1_IAMCOORD_MASK 0x1 +#define RF23X_CSMASEED1_IAMCOORD_BITS RF23X_REG_CSMASEED1, RF23X_CSMASEED1_IAMCOORD_POS, RF23X_CSMASEED1_IAMCOORD_MASK + +#define RF23X_CSMASEED1_AACK_DIS_ACK_POS +#define RF23X_CSMASEED1_AACK_SET_PD_POS +#define RF23X_CSMASEED1_AACK_FVN_MODE_POS +#define RF23X_CSMASEED1_ + + +/**************************************************************************** + * TRX Status + ****************************************************************************/ +#define TRX_STATUS_PON 0x00 +#define TRX_STATUS_BUSYRX 0x01 +#define TRX_STATUS_BUSYTX 0x02 +#define TRX_STATUS_RXON 0x06 +#define TRX_STATUS_TRXOFF 0x08 +#define TRX_STATUS_PLLON 0x09 +#define TRX_STATUS_SLEEP 0x0f +#define TRX_STATUS_DEEPSLEEP 0x10 +#define TRX_STATUS_BUSYRXACK 0x11 +#define TRX_STATUS_BUSYTXARET 0x12 +#define TRX_STATUS_RXAACKON 0x16 +#define TRX_STATUS_TXARETON 0x19 +#define TRX_STATUS_STATEINTRANS 0x1f + +/**************************************************************************** + * TRX Command + ****************************************************************************/ +#define TRX_CMD_NOP 0x00 +#define TRX_CMD_TX 0x02 +#define TRX_CMD_FORCETRXOFF 0x03 +#define TRX_CMD_FORCE_PLLON 0x04 +#define TRX_CMD_RX_ON 0x06 +#define TRX_CMD_TRXOFF 0x08 +#define TRX_CMD_PLL_ON 0x09 +#define TRX_CMD_PREP_DEEPSLEEP 0x10 +#define TRX_CMD_RX_AACK_ON 0x16 +#define TRX_CMD_TX_ARET_ON 0x19 + + +/**************************************************************************** + * IRQ MASK 0x0E + ****************************************************************************/ +#define RF23X_IRQ_MASK_LOCK_PLL (1<<0) +#define RF23X_IRQ_MASK_UNLOCK_PLL (1<<1) +#define RF23X_IRQ_MASK_RX_START (1<<2) +#define RF23X_IRQ_MASK_TRX_END (1<<3) +#define RF23X_IRQ_MASK_CCA_ED_DONE (1<<4) +#define RF23X_IRQ_MASK_AMI (1<<5) +#define RF23X_IRQ_MASK_TRX_UR (1<<6) +#define RF23X_IRQ_MASK_BAT_LOW (1<<7) + +#define RF23X_IRQ_MASK_DEFAULT (RF23X_IRQ_MASK_TRX_END) + + +#endif /* APPS_EXTERNAL_IEEE_AT86RF23X_H_ */ diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c index fa7cfd815d..cc831fd783 100644 --- a/drivers/wireless/ieee802154/mrf24j40.c +++ b/drivers/wireless/ieee802154/mrf24j40.c @@ -91,15 +91,53 @@ #define MRF24J40_PA_ED 2 #define MRF24J40_PA_SLEEP 3 +/* IEEE 802.15.4 frame specifics */ + +/* Security Enabled */ + +#define IEEE802154_SEC_OFF 0x00 +#define IEEE802154_SEC_ON 0x08 + +/* Flags */ + +#define IEEE802154_PEND 0x10 +#define IEEE802154_ACK_REQ 0x20 +#define IEEE802154_INTRA 0x40 + +/* Dest Addressing modes */ + +#define IEEE802154_DADDR_NONE 0x00 +#define IEEE802154_DADDR_SHORT 0x08 +#define IEEE802154_DADDR_EXT 0x0A + +/* Src Addressing modes */ + +#define IEEE802154_SADDR_NONE 0x00 +#define IEEE802154_SADDR_SHORT 0x80 +#define IEEE802154_SADDR_EXT 0xA0 + +/* Frame control field masks, 2 bytes + * Seee IEEE 802.15.4/2003 7.2.1.1 page 112 + */ + +#define IEEE802154_FC1_FTYPE 0x03 /* Frame type, bits 0-2 */ +#define IEEE802154_FC1_SEC 0x08 /* Security Enabled, bit 3 */ +#define IEEE802154_FC1_PEND 0x10 /* Frame pending, bit 4 */ +#define IEEE802154_FC1_ACKREQ 0x20 /* Acknowledge request, bit 5 */ +#define IEEE802154_FC1_INTRA 0x40 /* Intra PAN, bit 6 */ +#define IEEE802154_FC2_DADDR 0x0C /* Dest addressing mode, bits 10-11 */ +#define IEEE802154_FC2_VERSION 0x30 /* Source addressing mode, bits 12-13 */ +#define IEEE802154_FC2_SADDR 0xC0 /* Source addressing mode, bits 14-15 */ + /**************************************************************************** * Private Types ****************************************************************************/ /* A MRF24J40 device instance */ -struct mrf24j40_dev_s +struct mrf24j40_radio_s { - struct ieee802154_dev_s ieee; /* The public device instance */ + struct ieee802154_radio_s ieee; /* The public device instance */ FAR struct spi_dev_s *spi; /* Saved SPI interface instance */ struct work_s irqwork; /* Interrupt continuation work queue support */ FAR const struct mrf24j40_lower_s *lower; /* Low-level MCU-specific support */ @@ -126,39 +164,39 @@ static void mrf24j40_lock (FAR struct spi_dev_s *spi); static void mrf24j40_setreg (FAR struct spi_dev_s *spi, uint32_t addr, uint8_t val); static uint8_t mrf24j40_getreg (FAR struct spi_dev_s *spi, uint32_t addr); -static int mrf24j40_resetrfsm (FAR struct mrf24j40_dev_s *dev); -static int mrf24j40_pacontrol (FAR struct mrf24j40_dev_s *dev, int mode); -static int mrf24j40_initialize(FAR struct mrf24j40_dev_s *dev); +static int mrf24j40_resetrfsm (FAR struct mrf24j40_radio_s *dev); +static int mrf24j40_pacontrol (FAR struct mrf24j40_radio_s *dev, int mode); +static int mrf24j40_initialize(FAR struct mrf24j40_radio_s *dev); -static int mrf24j40_setrxmode (FAR struct mrf24j40_dev_s *dev, int mode); -static int mrf24j40_regdump (FAR struct mrf24j40_dev_s *dev); -static void mrf24j40_irqwork_rx(FAR struct mrf24j40_dev_s *dev); -static void mrf24j40_irqwork_tx(FAR struct mrf24j40_dev_s *dev); +static int mrf24j40_setrxmode (FAR struct mrf24j40_radio_s *dev, int mode); +static int mrf24j40_regdump (FAR struct mrf24j40_radio_s *dev); +static void mrf24j40_irqwork_rx(FAR struct mrf24j40_radio_s *dev); +static void mrf24j40_irqwork_tx(FAR struct mrf24j40_radio_s *dev); static void mrf24j40_irqworker (FAR void *arg); static int mrf24j40_interrupt (int irq, FAR void *context); /* Driver operations */ -static int mrf24j40_setchannel (FAR struct ieee802154_dev_s *ieee, uint8_t chan); -static int mrf24j40_getchannel (FAR struct ieee802154_dev_s *ieee, FAR uint8_t *chan); -static int mrf24j40_setpanid (FAR struct ieee802154_dev_s *ieee, uint16_t panid); -static int mrf24j40_getpanid (FAR struct ieee802154_dev_s *ieee, FAR uint16_t *panid); -static int mrf24j40_setsaddr (FAR struct ieee802154_dev_s *ieee, uint16_t saddr); -static int mrf24j40_getsaddr (FAR struct ieee802154_dev_s *ieee, FAR uint16_t *saddr); -static int mrf24j40_seteaddr (FAR struct ieee802154_dev_s *ieee, FAR uint8_t *eaddr); -static int mrf24j40_geteaddr (FAR struct ieee802154_dev_s *ieee, FAR uint8_t *eaddr); -static int mrf24j40_setpromisc (FAR struct ieee802154_dev_s *ieee, bool promisc); -static int mrf24j40_getpromisc (FAR struct ieee802154_dev_s *ieee, FAR bool *promisc); -static int mrf24j40_setdevmode (FAR struct ieee802154_dev_s *ieee, uint8_t mode); -static int mrf24j40_getdevmode (FAR struct ieee802154_dev_s *ieee, FAR uint8_t *mode); -static int mrf24j40_settxpower (FAR struct ieee802154_dev_s *ieee, int32_t txpwr); -static int mrf24j40_gettxpower (FAR struct ieee802154_dev_s *ieee, FAR int32_t *txpwr); -static int mrf24j40_setcca (FAR struct ieee802154_dev_s *ieee, FAR struct ieee802154_cca_s *cca); -static int mrf24j40_getcca (FAR struct ieee802154_dev_s *ieee, FAR struct ieee802154_cca_s *cca); -static int mrf24j40_ioctl (FAR struct ieee802154_dev_s *ieee, int cmd, unsigned long arg); -static int mrf24j40_energydetect(FAR struct ieee802154_dev_s *ieee, FAR uint8_t *energy); -static int mrf24j40_rxenable (FAR struct ieee802154_dev_s *ieee, bool state, FAR struct ieee802154_packet_s *packet); -static int mrf24j40_transmit (FAR struct ieee802154_dev_s *ieee, FAR struct ieee802154_packet_s *packet); +static int mrf24j40_setchannel (FAR struct ieee802154_radio_s *ieee, uint8_t chan); +static int mrf24j40_getchannel (FAR struct ieee802154_radio_s *ieee, FAR uint8_t *chan); +static int mrf24j40_setpanid (FAR struct ieee802154_radio_s *ieee, uint16_t panid); +static int mrf24j40_getpanid (FAR struct ieee802154_radio_s *ieee, FAR uint16_t *panid); +static int mrf24j40_setsaddr (FAR struct ieee802154_radio_s *ieee, uint16_t saddr); +static int mrf24j40_getsaddr (FAR struct ieee802154_radio_s *ieee, FAR uint16_t *saddr); +static int mrf24j40_seteaddr (FAR struct ieee802154_radio_s *ieee, FAR uint8_t *eaddr); +static int mrf24j40_geteaddr (FAR struct ieee802154_radio_s *ieee, FAR uint8_t *eaddr); +static int mrf24j40_setpromisc (FAR struct ieee802154_radio_s *ieee, bool promisc); +static int mrf24j40_getpromisc (FAR struct ieee802154_radio_s *ieee, FAR bool *promisc); +static int mrf24j40_setdevmode (FAR struct ieee802154_radio_s *ieee, uint8_t mode); +static int mrf24j40_getdevmode (FAR struct ieee802154_radio_s *ieee, FAR uint8_t *mode); +static int mrf24j40_settxpower (FAR struct ieee802154_radio_s *ieee, int32_t txpwr); +static int mrf24j40_gettxpower (FAR struct ieee802154_radio_s *ieee, FAR int32_t *txpwr); +static int mrf24j40_setcca (FAR struct ieee802154_radio_s *ieee, FAR struct ieee802154_cca_s *cca); +static int mrf24j40_getcca (FAR struct ieee802154_radio_s *ieee, FAR struct ieee802154_cca_s *cca); +static int mrf24j40_ioctl (FAR struct ieee802154_radio_s *ieee, int cmd, unsigned long arg); +static int mrf24j40_energydetect(FAR struct ieee802154_radio_s *ieee, FAR uint8_t *energy); +static int mrf24j40_rxenable (FAR struct ieee802154_radio_s *ieee, bool state, FAR struct ieee802154_packet_s *packet); +static int mrf24j40_transmit (FAR struct ieee802154_radio_s *ieee, FAR struct ieee802154_packet_s *packet); /* These are pointers to ALL registered MRF24J40 devices. * This table is used during irqs to find the context @@ -167,9 +205,9 @@ static int mrf24j40_transmit (FAR struct ieee802154_dev_s *ieee, FAR stru * using the IRQ number. See the ENC28J60 or CC3000 drivers for reference. */ -static struct mrf24j40_dev_s g_mrf24j40_devices[1]; +static struct mrf24j40_radio_s g_mrf24j40_devices[1]; -static const struct ieee802154_devops_s mrf24j40_devops = +static const struct ieee802154_radioops_s mrf24j40_devops = { mrf24j40_setchannel, mrf24j40_getchannel, mrf24j40_setpanid , mrf24j40_getpanid, @@ -316,7 +354,7 @@ static uint8_t mrf24j40_getreg(FAR struct spi_dev_s *spi, uint32_t addr) * ****************************************************************************/ -static int mrf24j40_resetrfsm(FAR struct mrf24j40_dev_s *dev) +static int mrf24j40_resetrfsm(FAR struct mrf24j40_radio_s *dev) { uint8_t reg; @@ -341,7 +379,7 @@ static int mrf24j40_resetrfsm(FAR struct mrf24j40_dev_s *dev) * GPIO 3: PA power enable (not required on MB) ****************************************************************************/ -static int mrf24j40_pacontrol(FAR struct mrf24j40_dev_s *dev, int mode) +static int mrf24j40_pacontrol(FAR struct mrf24j40_radio_s *dev, int mode) { if (!dev->paenabled) { @@ -383,7 +421,7 @@ static int mrf24j40_pacontrol(FAR struct mrf24j40_dev_s *dev, int mode) * ****************************************************************************/ -static int mrf24j40_initialize(FAR struct mrf24j40_dev_s *dev) +static int mrf24j40_initialize(FAR struct mrf24j40_radio_s *dev) { /* Software reset */ @@ -415,7 +453,7 @@ static int mrf24j40_initialize(FAR struct mrf24j40_dev_s *dev) * ****************************************************************************/ -static int mrf24j40_setrxmode(FAR struct mrf24j40_dev_s *dev, int mode) +static int mrf24j40_setrxmode(FAR struct mrf24j40_radio_s *dev, int mode) { uint8_t reg; if (mode < MRF24J40_RXMODE_NORMAL || mode > MRF24J40_RXMODE_NOCRC) @@ -463,10 +501,10 @@ static int mrf24j40_setrxmode(FAR struct mrf24j40_dev_s *dev, int mode) * ****************************************************************************/ -static int mrf24j40_setchannel(FAR struct ieee802154_dev_s *ieee, +static int mrf24j40_setchannel(FAR struct ieee802154_radio_s *ieee, uint8_t chan) { - FAR struct mrf24j40_dev_s *dev = (FAR struct mrf24j40_dev_s *)ieee; + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; if (chan<11 || chan>26) { @@ -498,10 +536,10 @@ static int mrf24j40_setchannel(FAR struct ieee802154_dev_s *ieee, * ****************************************************************************/ -static int mrf24j40_getchannel(FAR struct ieee802154_dev_s *ieee, +static int mrf24j40_getchannel(FAR struct ieee802154_radio_s *ieee, FAR uint8_t *chan) { - FAR struct mrf24j40_dev_s *dev = (FAR struct mrf24j40_dev_s *)ieee; + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; *chan = dev->channel; @@ -516,10 +554,10 @@ static int mrf24j40_getchannel(FAR struct ieee802154_dev_s *ieee, * ****************************************************************************/ -static int mrf24j40_setpanid(FAR struct ieee802154_dev_s *ieee, +static int mrf24j40_setpanid(FAR struct ieee802154_radio_s *ieee, uint16_t panid) { - FAR struct mrf24j40_dev_s *dev = (FAR struct mrf24j40_dev_s *)ieee; + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; mrf24j40_setreg(dev->spi, MRF24J40_PANIDH, (uint8_t)(panid>>8)); mrf24j40_setreg(dev->spi, MRF24J40_PANIDL, (uint8_t)(panid&0xFF)); @@ -538,10 +576,10 @@ static int mrf24j40_setpanid(FAR struct ieee802154_dev_s *ieee, * ****************************************************************************/ -static int mrf24j40_getpanid(FAR struct ieee802154_dev_s *ieee, +static int mrf24j40_getpanid(FAR struct ieee802154_radio_s *ieee, FAR uint16_t *panid) { - FAR struct mrf24j40_dev_s *dev = (FAR struct mrf24j40_dev_s *)ieee; + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; *panid = dev->panid; @@ -558,10 +596,10 @@ static int mrf24j40_getpanid(FAR struct ieee802154_dev_s *ieee, * ****************************************************************************/ -static int mrf24j40_setsaddr(FAR struct ieee802154_dev_s *ieee, +static int mrf24j40_setsaddr(FAR struct ieee802154_radio_s *ieee, uint16_t saddr) { - FAR struct mrf24j40_dev_s *dev = (FAR struct mrf24j40_dev_s *)ieee; + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; mrf24j40_setreg(dev->spi, MRF24J40_SADRH, (uint8_t)(saddr>>8)); mrf24j40_setreg(dev->spi, MRF24J40_SADRL, (uint8_t)(saddr&0xFF)); @@ -579,10 +617,10 @@ static int mrf24j40_setsaddr(FAR struct ieee802154_dev_s *ieee, * ****************************************************************************/ -static int mrf24j40_getsaddr(FAR struct ieee802154_dev_s *ieee, +static int mrf24j40_getsaddr(FAR struct ieee802154_radio_s *ieee, FAR uint16_t *saddr) { - FAR struct mrf24j40_dev_s *dev = (FAR struct mrf24j40_dev_s *)ieee; + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; *saddr = dev->saddr; @@ -598,10 +636,10 @@ static int mrf24j40_getsaddr(FAR struct ieee802154_dev_s *ieee, * ****************************************************************************/ -static int mrf24j40_seteaddr(FAR struct ieee802154_dev_s *ieee, +static int mrf24j40_seteaddr(FAR struct ieee802154_radio_s *ieee, FAR uint8_t *eaddr) { - FAR struct mrf24j40_dev_s *dev = (FAR struct mrf24j40_dev_s *)ieee; + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; int i; @@ -622,10 +660,10 @@ static int mrf24j40_seteaddr(FAR struct ieee802154_dev_s *ieee, * ****************************************************************************/ -static int mrf24j40_geteaddr(FAR struct ieee802154_dev_s *ieee, +static int mrf24j40_geteaddr(FAR struct ieee802154_radio_s *ieee, FAR uint8_t *eaddr) { - FAR struct mrf24j40_dev_s *dev = (FAR struct mrf24j40_dev_s *)ieee; + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; memcpy(eaddr, dev->eaddr, 8); @@ -641,10 +679,10 @@ static int mrf24j40_geteaddr(FAR struct ieee802154_dev_s *ieee, * ****************************************************************************/ -static int mrf24j40_setpromisc(FAR struct ieee802154_dev_s *ieee, +static int mrf24j40_setpromisc(FAR struct ieee802154_radio_s *ieee, bool promisc) { - FAR struct mrf24j40_dev_s *dev = (FAR struct mrf24j40_dev_s *)ieee; + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; return mrf24j40_setrxmode(dev, promisc ? MRF24J40_RXMODE_PROMISC : MRF24J40_RXMODE_NORMAL); @@ -658,10 +696,10 @@ static int mrf24j40_setpromisc(FAR struct ieee802154_dev_s *ieee, * ****************************************************************************/ -static int mrf24j40_getpromisc(FAR struct ieee802154_dev_s *ieee, +static int mrf24j40_getpromisc(FAR struct ieee802154_radio_s *ieee, FAR bool *promisc) { - FAR struct mrf24j40_dev_s *dev = (FAR struct mrf24j40_dev_s *)ieee; + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; *promisc = (dev->rxmode == MRF24J40_RXMODE_PROMISC); @@ -676,10 +714,10 @@ static int mrf24j40_getpromisc(FAR struct ieee802154_dev_s *ieee, * ****************************************************************************/ -static int mrf24j40_setdevmode(FAR struct ieee802154_dev_s *ieee, +static int mrf24j40_setdevmode(FAR struct ieee802154_radio_s *ieee, uint8_t mode) { - FAR struct mrf24j40_dev_s *dev = (FAR struct mrf24j40_dev_s *)ieee; + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; int ret = OK; uint8_t reg; @@ -728,10 +766,10 @@ static int mrf24j40_setdevmode(FAR struct ieee802154_dev_s *ieee, * ****************************************************************************/ -static int mrf24j40_getdevmode(FAR struct ieee802154_dev_s *ieee, +static int mrf24j40_getdevmode(FAR struct ieee802154_radio_s *ieee, FAR uint8_t *mode) { - FAR struct mrf24j40_dev_s *dev = (FAR struct mrf24j40_dev_s *)ieee; + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; *mode = dev->devmode; @@ -748,10 +786,10 @@ static int mrf24j40_getdevmode(FAR struct ieee802154_dev_s *ieee, * ****************************************************************************/ -static int mrf24j40_settxpower(FAR struct ieee802154_dev_s *ieee, +static int mrf24j40_settxpower(FAR struct ieee802154_radio_s *ieee, int32_t txpwr) { - FAR struct mrf24j40_dev_s *dev = (FAR struct mrf24j40_dev_s *)ieee; + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; uint8_t reg; int save_txpwr = txpwr; @@ -809,10 +847,10 @@ static int mrf24j40_settxpower(FAR struct ieee802154_dev_s *ieee, * ****************************************************************************/ -static int mrf24j40_gettxpower(FAR struct ieee802154_dev_s *ieee, +static int mrf24j40_gettxpower(FAR struct ieee802154_radio_s *ieee, FAR int32_t *txpwr) { - FAR struct mrf24j40_dev_s *dev = (FAR struct mrf24j40_dev_s *)ieee; + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; *txpwr = dev->txpower; @@ -827,10 +865,10 @@ static int mrf24j40_gettxpower(FAR struct ieee802154_dev_s *ieee, * ****************************************************************************/ -static int mrf24j40_setcca(FAR struct ieee802154_dev_s *ieee, +static int mrf24j40_setcca(FAR struct ieee802154_radio_s *ieee, FAR struct ieee802154_cca_s *cca) { - FAR struct mrf24j40_dev_s *dev = (FAR struct mrf24j40_dev_s *)ieee; + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; uint8_t mode; if (!cca->use_ed && !cca->use_cs) @@ -873,10 +911,10 @@ static int mrf24j40_setcca(FAR struct ieee802154_dev_s *ieee, * ****************************************************************************/ -static int mrf24j40_getcca(FAR struct ieee802154_dev_s *ieee, +static int mrf24j40_getcca(FAR struct ieee802154_radio_s *ieee, FAR struct ieee802154_cca_s *cca) { - FAR struct mrf24j40_dev_s *dev = (FAR struct mrf24j40_dev_s *)ieee; + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; memcpy(cca, &dev->cca, sizeof(struct ieee802154_cca_s)); @@ -891,7 +929,7 @@ static int mrf24j40_getcca(FAR struct ieee802154_dev_s *ieee, * ****************************************************************************/ -static int mrf24j40_regdump(FAR struct mrf24j40_dev_s *dev) +static int mrf24j40_regdump(FAR struct mrf24j40_radio_s *dev) { uint32_t i; char buf[4+16*3+2+1]; @@ -941,10 +979,10 @@ static int mrf24j40_regdump(FAR struct mrf24j40_dev_s *dev) * ****************************************************************************/ -static int mrf24j40_ioctl(FAR struct ieee802154_dev_s *ieee, int cmd, +static int mrf24j40_ioctl(FAR struct ieee802154_radio_s *ieee, int cmd, unsigned long arg) { - FAR struct mrf24j40_dev_s *dev = (FAR struct mrf24j40_dev_s *)ieee; + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; switch(cmd) { @@ -968,10 +1006,10 @@ static int mrf24j40_ioctl(FAR struct ieee802154_dev_s *ieee, int cmd, * ****************************************************************************/ -static int mrf24j40_energydetect(FAR struct ieee802154_dev_s *ieee, +static int mrf24j40_energydetect(FAR struct ieee802154_radio_s *ieee, FAR uint8_t *energy) { - FAR struct mrf24j40_dev_s *dev = (FAR struct mrf24j40_dev_s *)ieee; + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; uint8_t reg; /* Manually enable the LNA*/ @@ -1019,9 +1057,9 @@ static int mrf24j40_energydetect(FAR struct ieee802154_dev_s *ieee, * ****************************************************************************/ -static int mrf24j40_transmit(FAR struct ieee802154_dev_s *ieee, FAR struct ieee802154_packet_s *packet) +static int mrf24j40_transmit(FAR struct ieee802154_radio_s *ieee, FAR struct ieee802154_packet_s *packet) { - FAR struct mrf24j40_dev_s *dev = (FAR struct mrf24j40_dev_s *)ieee; + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; uint32_t addr; uint8_t reg; int ret; @@ -1030,7 +1068,7 @@ static int mrf24j40_transmit(FAR struct ieee802154_dev_s *ieee, FAR struct ieee8 mrf24j40_pacontrol(dev, MRF24J40_PA_AUTO); - addr = 0x80000000; + addr = MRF24J40_TXBUF_BASE; /* Enable tx int */ @@ -1118,22 +1156,19 @@ static int mrf24j40_transmit(FAR struct ieee802154_dev_s *ieee, FAR struct ieee8 * ****************************************************************************/ -static void mrf24j40_irqwork_tx(FAR struct mrf24j40_dev_s *dev) +static void mrf24j40_irqwork_tx(FAR struct mrf24j40_radio_s *dev) { uint8_t txstat; uint8_t reg; txstat = mrf24j40_getreg(dev->spi, MRF24J40_TXSTAT); - /* 1 means it failed, we want 1 to mean it worked. - * tx_ok = !(tmp & ~(1 << TXNSTAT)); - * retries = tmp >> 6; - * channel_busy = (tmp & (1 << CCAFAIL)); - */ + reg = mrf24j40_getreg(dev->spi, MRF24J40_TXSTAT); - //dbg("TXSTAT%02X!\n", txstat); -#warning TODO report errors - UNUSED(txstat); + /* 1 means it failed, we want 1 to mean it worked. */ + dev->ieee.txok = (reg & MRF24J40_TXSTAT_TXNSTAT) != MRF24J40_TXSTAT_TXNSTAT; + dev->ieee.txretries = (reg & MRF24J40_TXSTAT_X_MASK) >> MRF24J40_TXSTAT_X_SHIFT; + dev->ieee.txbusy = (reg & MRF24J40_TXSTAT_CCAFAIL) == MRF24J40_TXSTAT_CCAFAIL; /* Disable tx int */ @@ -1147,17 +1182,17 @@ static void mrf24j40_irqwork_tx(FAR struct mrf24j40_dev_s *dev) } /**************************************************************************** - * Name: mrf24j40_enablerx + * Name: mrf24j40_rxenable * * Description: * Enable reception of a packet. The interrupt will signal the rx semaphore. * ****************************************************************************/ -static int mrf24j40_rxenable(FAR struct ieee802154_dev_s *ieee, bool state, +static int mrf24j40_rxenable(FAR struct ieee802154_radio_s *ieee, bool state, FAR struct ieee802154_packet_s *packet) { - FAR struct mrf24j40_dev_s *dev = (FAR struct mrf24j40_dev_s *)ieee; + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; uint8_t reg; if (state) @@ -1187,7 +1222,7 @@ static int mrf24j40_rxenable(FAR struct ieee802154_dev_s *ieee, bool state, * ****************************************************************************/ -static void mrf24j40_irqwork_rx(FAR struct mrf24j40_dev_s *dev) +static void mrf24j40_irqwork_rx(FAR struct mrf24j40_radio_s *dev) { uint32_t addr; uint32_t index; @@ -1207,7 +1242,7 @@ static void mrf24j40_irqwork_rx(FAR struct mrf24j40_dev_s *dev) /* Read packet */ - addr = 0x80000300; + addr = MRF24J40_RXBUF_BASE; dev->ieee.rxbuf->len = mrf24j40_getreg(dev->spi, addr++); /*dbg("len %3d\n", dev->ieee.rxbuf->len);*/ @@ -1255,7 +1290,7 @@ static void mrf24j40_irqwork_rx(FAR struct mrf24j40_dev_s *dev) static void mrf24j40_irqworker(FAR void *arg) { - FAR struct mrf24j40_dev_s *dev = (FAR struct mrf24j40_dev_s *)arg; + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)arg; uint8_t intstat; DEBUGASSERT(dev); @@ -1310,7 +1345,7 @@ static int mrf24j40_interrupt(int irq, FAR void *context) * retrieve the priv structure using the irq number */ - register FAR struct mrf24j40_dev_s *dev = &g_mrf24j40_devices[0]; + register FAR struct mrf24j40_radio_s *dev = &g_mrf24j40_devices[0]; /* In complex environments, we cannot do SPI transfers from the interrupt * handler because semaphores are probably used to lock the SPI bus. In @@ -1342,14 +1377,14 @@ static int mrf24j40_interrupt(int irq, FAR void *context) * ****************************************************************************/ -FAR struct ieee802154_dev_s *mrf24j40_init(FAR struct spi_dev_s *spi, +FAR struct ieee802154_radio_s *mrf24j40_init(FAR struct spi_dev_s *spi, FAR const struct mrf24j40_lower_s *lower) { - FAR struct mrf24j40_dev_s *dev; + FAR struct mrf24j40_radio_s *dev; struct ieee802154_cca_s cca; #if 0 - dev = kmm_zalloc(sizeof(struct mrf24j40_dev_s)); + dev = kmm_zalloc(sizeof(struct mrf24j40_radio_s)); if (!dev) { @@ -1379,9 +1414,9 @@ FAR struct ieee802154_dev_s *mrf24j40_init(FAR struct spi_dev_s *spi, mrf24j40_initialize(dev); mrf24j40_setchannel(&dev->ieee, 11); - mrf24j40_setpanid (&dev->ieee, IEEE802154_PAN_DEFAULT); - mrf24j40_setsaddr (&dev->ieee, IEEE802154_SADDR_UNSPEC); - mrf24j40_seteaddr (&dev->ieee, IEEE802154_EADDR_UNSPEC); + mrf24j40_setpanid (&dev->ieee, 0xFFFF); + mrf24j40_setsaddr (&dev->ieee, 0xFFFF); + mrf24j40_seteaddr (&dev->ieee, (uint8_t*)"\xFF\xFF\xFF\xFF\xFF\xFF\xFF\xFF"); /* Default device params */ diff --git a/drivers/wireless/ieee802154/mrf24j40.h b/drivers/wireless/ieee802154/mrf24j40.h index de3131e4df..c530e61d63 100644 --- a/drivers/wireless/ieee802154/mrf24j40.h +++ b/drivers/wireless/ieee802154/mrf24j40.h @@ -97,18 +97,22 @@ #define MRF24J40_BBREG6 0x3E #define MRF24J40_CCAEDTH 0x3F -#define MRF24J40_RFCON0 0x80000200 -#define MRF24J40_RFCON1 0x80000201 -#define MRF24J40_RFCON2 0x80000202 -#define MRF24J40_RFCON3 0x80000203 -#define MRF24J40_RFCON5 0x80000205 -#define MRF24J40_RFCON6 0x80000206 -#define MRF24J40_RFCON7 0x80000207 -#define MRF24J40_RFCON8 0x80000208 -#define MRF24J40_SLPCAL0 0x80000209 -#define MRF24J40_SLPCAL1 0x8000020A -#define MRF24J40_SLPCAL2 0x8000020B -#define MRF24J40_RFSTATE 0x8000020F +#define MRF24J40_TXBUF_BASE 0x80000000 +#define MRF24J40_LONGREG_BASE 0x80000200 +#define MRF24J40_RXBUF_BASE 0x80000300 + +#define MRF24J40_RFCON0 (MRF24J40_LONGREG_BASE + 0x00) +#define MRF24J40_RFCON1 (MRF24J40_LONGREG_BASE + 0x01) +#define MRF24J40_RFCON2 (MRF24J40_LONGREG_BASE + 0x02) +#define MRF24J40_RFCON3 (MRF24J40_LONGREG_BASE + 0x03) +#define MRF24J40_RFCON5 (MRF24J40_LONGREG_BASE + 0x05) +#define MRF24J40_RFCON6 (MRF24J40_LONGREG_BASE + 0x06) +#define MRF24J40_RFCON7 (MRF24J40_LONGREG_BASE + 0x07) +#define MRF24J40_RFCON8 (MRF24J40_LONGREG_BASE + 0x08) +#define MRF24J40_SLPCAL0 (MRF24J40_LONGREG_BASE + 0x09) +#define MRF24J40_SLPCAL1 (MRF24J40_LONGREG_BASE + 0x0A) +#define MRF24J40_SLPCAL2 (MRF24J40_LONGREG_BASE + 0x0B) +#define MRF24J40_RFSTATE (MRF24J40_LONGREG_BASE + 0x0F) #define MRF24J40_RSSI 0x80000210 #define MRF24J40_SLPCON0 0x80000211 #define MRF24J40_SLPCON1 0x80000220 @@ -147,18 +151,18 @@ /* INTSTAT bits */ -#define MRF24J40_INTSTAT_SLPIF 0x80 -#define MRF24J40_INTSTAT_WAKEIF 0x40 -#define MRF24J40_INTSTAT_HSYMTMRIF 0x20 -#define MRF24J40_INTSTAT_SECIF 0x10 -#define MRF24J40_INTSTAT_RXIF 0x08 -#define MRF24J40_INTSTAT_TXG2IF 0x04 -#define MRF24J40_INTSTAT_TXG1IF 0x02 -#define MRF24J40_INTSTAT_TXNIF 0x01 +#define MRF24J40_INTSTAT_TXNIF (1 << 0) +#define MRF24J40_INTSTAT_TXG1IF (1 << 1) +#define MRF24J40_INTSTAT_TXG2IF (1 << 2) +#define MRF24J40_INTSTAT_RXIF (1 << 3) +#define MRF24J40_INTSTAT_SECIF (1 << 4) +#define MRF24J40_INTSTAT_HSYMTMRIF (1 << 5) +#define MRF24J40_INTSTAT_WAKEIF (1 << 6) +#define MRF24J40_INTSTAT_SLPIF (1 << 7) /* RXMCR bits */ -#define MRF24J40_RXMCR_PROMI 0x01 /* Enable promisc mode (rx all valid packets) */ +#define MRF24J40_RXMCR_PROMI (1 << 0) /* Enable promisc mode (rx all valid packets) */ #define MRF24J40_RXMCR_ERRPKT 0x02 /* Do not check CRC */ #define MRF24J40_RXMCR_COORD 0x04 /* Enable coordinator mode ??? DIFFERENCE ??? - not used in datasheet! */ #define MRF24J40_RXMCR_PANCOORD 0x08 /* Enable PAN coordinator mode ??? DIFFERENCE ??? */ @@ -166,7 +170,7 @@ /* TXMCR bits */ -#define MRF24J40_TXMCR_CSMABF0 0x01 +#define MRF24J40_TXMCR_CSMABF0 (1 << 0) #define MRF24J40_TXMCR_CSMABF1 0x02 #define MRF24J40_TXMCR_CSMABF2 0x04 #define MRF24J40_TXMCR_MACMINBE0 0x08 @@ -184,7 +188,7 @@ #define MRF24J40_INTCON_RXIE 0x08 #define MRF24J40_INTCON_TXG2IE 0x04 #define MRF24J40_INTCON_TXG1IE 0x02 -#define MRF24J40_INTCON_TXNIE 0x01 +#define MRF24J40_INTCON_TXNIE (1 << 0) /* BBREG1 bits */ @@ -197,10 +201,17 @@ /* TXNCON bits */ -#define MRF24J40_TXNCON_TXNTRIG 0x01 /* Trigger packet tx, automatically cleared */ +#define MRF24J40_TXNCON_TXNTRIG (1 << 0) /* Trigger packet tx, automatically cleared */ #define MRF24J40_TXNCON_TXNSECEN 0x02 /* Enable security */ #define MRF24J40_TXNCON_TXNACKREQ 0x04 /* An ACK is requested for this pkt */ #define MRF24J40_TXNCON_INDIRECT 0x08 /* Activate indirect tx bit (for coordinators) */ #define MRF24J40_TXNCON_FPSTAT 0x10 /* Status of the frame pending big in txed acks */ +/* TXSTAT bits */ + +#define MRF24J40_TXSTAT_TXNSTAT (1 << 0) +#define MRF24J40_TXSTAT_CCAFAIL (1 << 5) +#define MRF24J40_TXSTAT_X_SHIFT 6 +#define MRF24J40_TXSTAT_X_MASK (3 << MRF24J40_TXSTAT_X_SHIFT) + #endif /* __DRIVERS_IEEE802154_MRF24J40_H */ diff --git a/include/nuttx/fs/ioctl.h b/include/nuttx/fs/ioctl.h index e404057d7e..1b0e4f9a00 100644 --- a/include/nuttx/fs/ioctl.h +++ b/include/nuttx/fs/ioctl.h @@ -83,6 +83,7 @@ #define _LOOPBASE (0x1e00) /* Loop device commands */ #define _MODEMBASE (0x1f00) /* Modem ioctl commands */ #define _I2CBASE (0x2000) /* I2C driver commands */ +#define _MAC854BASE (0x2100) /* 802.15.4 device ioctl commands */ /* boardctl commands share the same number space */ @@ -381,6 +382,12 @@ #define _I2CIOCVALID(c) (_IOC_TYPE(c)==_I2CBASE) #define _I2CIOC(nr) _IOC(_I2CBASE,nr) +/* 802.15.4 MAC driver ioctl definitions *******************************************/ +/* (see nuttx/ieee802154/ieee802154_dev.h */ + +#define _MAC854IOCVALID(c) (_IOC_TYPE(c)==_MAC854BASE) +#define _MAC854IOC(nr) _IOC(_MAC854BASE,nr) + /* boardctl() command definitions *******************************************/ #define _BOARDIOCVALID(c) (_IOC_TYPE(c)==_BOARDBASE) diff --git a/include/nuttx/wireless/ieee802154/at86rf23x.h b/include/nuttx/wireless/ieee802154/at86rf23x.h new file mode 100644 index 0000000000..974e2456e2 --- /dev/null +++ b/include/nuttx/wireless/ieee802154/at86rf23x.h @@ -0,0 +1,100 @@ +/**************************************************************************** + * include/nuttx/ieee802154/at86rf23x.h + * + * Copyright (C) 2014-2015 Gregory Nutt. All rights reserved. + * Copyright (C) 2014-2015 Sebastien Lorquet. All rights reserved. + * Author: Sebastien Lorquet + * + * 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_IEEE802154_AT86RF23X_H +#define __INCLUDE_NUTTX_IEEE802154_AT86RF23X_H + +/* The at86rf23x provides interrupts to the MCU via a GPIO pin. The + * following structure provides an MCU-independent mechanixm for controlling + * the at86rf23x GPIO interrupt. + * + * The at86rf23x interrupt is an active low, *level* interrupt. From Datasheet: + * "Note 1: The INTEDGE polarity defaults to: + * 0 = Falling Edge. Ensure that the inter- + * rupt polarity matches the interrupt pin + * polarity of the host microcontroller. + * Note 2: The INT pin will remain high or low, + * depending on INTEDGE polarity setting, + * until INTSTAT register is read." + */ + +struct at86rf23x_lower_s +{ + int (*irq)(FAR const struct at86rf23x_lower_s *lower, xcpt_t handler, int state); + void (*slptr)(FAR const struct at86rf23x_lower_s *lower, int state); + void (*reset)(FAR const struct at86rf23x_lower_s *lower, int state); +}; + +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Function: at86rf23x_init + * + * Description: + * Initialize the IEEE802.15.4 driver. The at86rf23x device is assumed to be + * in the post-reset state upon entry to this function. + * + * Parameters: + * spi - A reference to the platform's SPI driver for the at86rf23x + * lower - The MCU-specific interrupt used to control low-level MCU + * functions (i.e., at86rf23x GPIO interrupts). + * devno - If more than one at86rf23x is supported, then this is the + * zero based number that identifies the at86rf23x; + * + * Returned Value: + * OK on success; Negated errno on failure. + * + * Assumptions: + * + ****************************************************************************/ + +FAR struct ieee802154_dev_s *at86rf23x_init(FAR struct spi_dev_s *spi, FAR const struct at86rf23x_lower_s *lower); + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* __INCLUDE_NUTTX_IEEE802154__AT86RF23X_H */ diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h new file mode 100644 index 0000000000..439825391a --- /dev/null +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -0,0 +1,368 @@ +/**************************************************************************** + * include/nuttx/wireless/ieee802154/ieee802154_mac.h + * + * Copyright (C) 2016 Sebastien Lorquet. All rights reserved. + * Author: Sebastien Lorquet + * + * 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_WIRELESS_IEEE802154_IEEE802154_MAC_H +#define __INCLUDE_NUTTX_WIRELESS_IEEE802154_IEEE802154_MAC_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ +/* None at the moment */ + +/* IEEE 802.15.4 MAC Interface **********************************************/ + +/* Some addresses */ + +#define IEEE802154_PAN_UNSPEC (uint16_t)0xFFFF +#define IEEE802154_SADDR_UNSPEC (uint16_t)0xFFFF +#define IEEE802154_SADDR_BCAST (uint16_t)0xFFFE +#define IEEE802154_EADDR_UNSPEC (uint8_t*)"\xff\xff\xff\xff\xff\xff\xff\xff" + +/* IEEE 802.15.4 MAC status codes */ + +enum +{ + MAC802154_STATUS_OK = 0, + MAC802154_STATUS_BEACON_LOSS = 0xE0, + MAC802154_STATUS_CHANNEL_ACCESS_FAILURE, + MAC802154_STATUS_DENIED, + MAC802154_STATUS_DISABLE_TRX_FAILURE, + MAC802154_STATUS_FAILED_SECURITY_CHECK, + MAC802154_STATUS_FRAME_TOO_LONG, + MAC802154_STATUS_INVALID_GTS, + MAC802154_STATUS_INVALID_HANDLE, + MAC802154_STATUS_INVALID_PARAMETER, + MAC802154_STATUS_NO_ACK, + MAC802154_STATUS_NO_BEACON, + MAC802154_STATUS_NO_DATA, + MAC802154_STATUS_NO_SHORT_ADDRESS, + MAC802154_STATUS_OUT_OF_CAP, + MAC802154_STATUS_PAN_ID_CONFLICT, + MAC802154_STATUS_REALIGNMENT, + MAC802154_STATUS_TRANSACTION_EXPIRED, + MAC802154_STATUS_TRANSACTION_OVERFLOW, + MAC802154_STATUS_TX_ACTIVE, + MAC802154_STATUS_UNAVAILABLE_KEY, + MAC802154_STATUS_UNSUPPORTED_ATTRIBUTE +}; + +/* IEEE 802.15.4 PHY constants */ +#define MAC802154_aMaxPHYPacketSize 127 +#define MAC802154_aTurnaroundTime 12 /*symbol periods*/ + +/* IEEE 802.15.4 MAC constants */ +#define MAC802154_aBaseSlotDuration 60 +#define MAC802154_aNumSuperframeSlots 16 +#define MAC802154_aBaseSuperframeDuration (MAC802154_aBaseSlotDuration * MAC802154_aNumSuperframeSlots) +#define MAC802154_aMaxBE 5 +#define MAC802154_aMaxBeaconOverhead 75 +#define MAC802154_aMaxBeaconPayloadLength (MAC802154_aMaxPHYPacketSize - MAC802154_aMaxBeaconOverhead) +#define MAC802154_aGTSDescPersistenceTime 4 +#define MAC802154_aMaxFrameOverhead 25 +#define MAC802154_aMaxFrameResponseTime 1220 +#define MAC802154_aMaxFrameRetries 3 +#define MAC802154_aMaxLostBeacons 4 +#define MAC802154_aMaxMACFrameSize (MAC802154_aMaxPHYPacketSize - MAC802154_aMaxFrameOverhead) +#define MAC802154_aMaxSIFSFrameSize 18 +#define MAC802154_aMinCAPLength 440 +#define MAC802154_aMinLIFSPeriod 40 +#define MAC802154_aMinSIFSPeriod 12 +#define MAC802154_aResponseWaitTime (32 * MAC802154_aBaseSuperframeDuration) +#define MAC802154_aUnitBackoffPeriod 20 + + +/* IEEE 802.15.4 PHY/MAC PIB attributes IDs */ +enum +{ + MAC802154_phyCurrentChannel = 0x00, + MAC802154_phyChannelsSupported, + MAC802154_phyTransmitPower, + MAC802154_phyCCAMode, + MAC802154_macAckWaitDuration = 0x40, + MAC802154_macAssociationPermit, + MAC802154_macAutoRequest, + MAC802154_macBattLifeExt, + MAC802154_macBattLifeExtPeriods, + MAC802154_macBeaconPayload, + MAC802154_macBeaconPayloadLength, + MAC802154_macBeaconOrder, + MAC802154_macBeaconTxTime, + MAC802154_macBSN, + MAC802154_macCoordExtendedAddress, + MAC802154_macCoordShortAddress, + MAC802154_macDSN, + MAC802154_macGTSPermit, + MAC802154_macMaxCSMABackoffs, + MAC802154_macMinBE, + MAC802154_macPANId, + MAC802154_macPromiscuousMode, + MAC802154_macRxOnWhenIdle, + MAC802154_macShortAddress, + MAC802154_macSuperframeOrder, + MAC802154_macTransactionPersistenceTime, + MAC802154_macACLEntryDescriptorSet = 0x70, + MAC802154_macACLEntryDescriptorSetSize, + MAC802154_macDefaultSecurity, + MAC802154_macDefaultSecurityMaterialLength, + MAC802154_macDefaultSecurityMaterial, + MAC802154_macDefaultSecuritySuite, + MAC802154_macSecurityMode +}; + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* IEEE 802.15.4 Device address + * The addresses in ieee802154 have several formats: + * No address : [none] + * Short address + PAN id : PPPP/SSSS + * Extended address + PAN id : PPPP/LLLLLLLLLLLLLLLL + */ + +struct ieee802154_addr_s +{ + uint8_t ia_len; /* structure length, 0/2/8 */ + uint16_t ia_panid; /* PAN identifier, can be IEEE802154_PAN_UNSPEC */ + union { + uint16_t _ia_saddr; /* short address */ + uint8_t _ia_eaddr[8]; /* extended address */ + } ia_addr; +#define ia_saddr ia_addr._ia_saddr +#define ia_eaddr ia_addr._ia_eaddr +}; +#define IEEE802154_ADDRSTRLEN 22 /* (2*2+1+8*2, PPPP/EEEEEEEEEEEEEEEE) */ + +/* Operations */ + +struct ieee802154_mac_s; + +struct ieee802154_macops_s +{ + /* Requests, confirmed asynchronously via callbacks */ + + CODE int req_data (struct ieee802154_mac_s *mac, /* Transmit a data frame */ + uint8_t handle, + uint8_t *buf, + int len); + + CODE int req_purge (struct ieee802154_mac_s *mac, /* Cancel transmission of a data frame */ + uint8_t handle); + + CODE int req_associate (struct ieee802154_mac_s *mac, /* Start association with coordinator */ + uint16_t panid, + uint8_t *coordeadr); + + CODE int req_disassociate(struct ieee802154_mac_s *mac, /* Start disassociation with coordinator */ + uint8_t *eadr, + uint8_t reason); + + CODE int req_get (struct ieee802154_mac_s *mac, /* Read the PIB */ + int attribute); + + CODE int req_gts (struct ieee802154_mac_s *mac, /* Allocate or deallocate a GTS */ + uint8_t* characteristics); + + CODE int req_reset (struct ieee802154_mac_s *mac, /* MAC layer reset */ + bool setdefaults); + + CODE int req_rxenable (struct ieee802154_mac_s *mac, /* PHY receiver control */ + bool deferrable, + int ontime, + int duration); + + CODE int req_scan (struct ieee802154_mac_s *mac, /* Start a network scan */ + uint8_t type, + uint32_t channels, + int duration); + + CODE int req_set (struct ieee802154_mac_s *mac, /* Change the PIB */ + int attribute, + uint8_t *value, + int valuelen); + + CODE int req_start (struct ieee802154_mac_s *mac, + uint16_t panid, + int channel, + uint8_t bo, + uint8_t fo, + bool coord, + bool batext, + bool realign); + + CODE int req_sync (struct ieee802154_mac_s *mac, + int channel, + bool track); + + CODE int req_poll (struct ieee802154_mac_s *mac, + uint8_t *coordaddr); + + /* Synchronous Responses to Indications received via callbacks */ + + CODE int rsp_associate (struct ieee802154_mac_s *mac, /* Reply to an association request */ + uint8_t eadr, + uint16_t saddr, + int status); + + CODE int rsp_orphan (struct ieee802154_mac_s *mac, /* Orphan device management */ + uint8_t *orphanaddr, + uint16_t saddr, + bool associated); +}; + +/* Notifications */ + +struct ieee802154_maccb_s +{ + /* Asynchronous confirmations to requests */ + + CODE int conf_data (struct ieee802154_mac_s *mac, /* Data frame was received by remote device */ + uint8_t *buf, + int len); + CODE int conf_purge (struct ieee802154_mac_s *mac, /* Data frame was purged */ + uint8_t handle, + int status); + CODE int conf_associate (struct ieee802154_mac_s *mac, /* Association request completed */ + uint16_t saddr, + int status); + CODE int conf_disassociate(struct ieee802154_mac_s *mac, /* Disassociation request completed */ + int status); + CODE int conf_get (struct ieee802154_mac_s *mac, /* PIB data returned */ + int status, + int attribute, + uint8_t *value, + int valuelen); + CODE int conf_gts (struct ieee802154_mac_s *mac, /* GTS management completed */ + uint8_t *characteristics, + int status); + CODE int conf_reset (struct ieee802154_mac_s *mac, /* MAC reset completed */ + int status); + CODE int conf_rxenable (struct ieee802154_mac_s *mac, + int status); + CODE int conf_scan (struct ieee802154_mac_s *mac, + int status, + uint8_t type, + uint32_t unscanned, + int rsltsize, + uint8_t *edlist, + uint8_t *pandescs); + CODE int conf_set (struct ieee802154_mac_s *mac, + int status, int attribute); + CODE int conf_start (struct ieee802154_mac_s *mac, + int status); + CODE int conf_poll (struct ieee802154_mac_s *mac, + int status); + + /* Asynchronous event indications, replied to synchronously with responses */ + + CODE int ind_data (struct ieee802154_mac_s *mac, /* Data frame received */ + uint8_t *buf, + int len); + CODE int ind_associate (struct ieee802154_mac_s *mac, /* Association request received */ + uint16_t clipanid, + uint8_t *clieaddr); + CODE int ind_disassociate (struct ieee802154_mac_s *mac, /* Disassociation request received */ + uint8_t *eadr, + uint8_t reason); + CODE int ind_beaconnotify (struct ieee802154_mac_s *mac, /* Beacon notification */ + uint8_t *bsn, + uint_t *pandesc, + uint8_t *sdu, + int sdulen); + CODE int ind_gts (struct ieee802154_mac_s *mac, /* GTS management request received */ + uint8_t *devaddr, + uint8_t *characteristics); + CODE int ind_orphan (struct ieee802154_mac_s *mac, /* Orphan device detected */ + uint8_t *orphanaddr); + CODE int ind_commstatus (struct ieee802154_mac_s *mac, + uint16_t panid, + uint8_t *src, + uint8_t *dst, + int status); + CODE int ind_syncloss (struct ieee802154_mac_s *mac, + int reason); +}; + +struct ieee802154_radio_s; + +struct ieee802154_mac_s +{ + struct ieee802154_radio_s *radio; + struct ieee802154_macops_s ops; + struct ieee802154_maccb_s cbs; +}; + +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/* + * Instanciate a 802.15.4 MAC from a 802.15.4 radio device. + * To create a 802.15.4 MAC, you need to pass: + * - an instance of a radio driver in radiodev + * - a pointer to a structure that contains MAC callback routines to + * handle confirmations and indications. NULL entries indicate no callback. + * In return you get a mac structure that has pointers to MAC operations and + * responses. + * This API does not create any device accessible to userspace. If you want to + * call these APIs from userspace, you have to wrap your mac in a character + * device via mac802154_device.c . + */ +FAR struct ieee802154_mac_s * mac802154_register(FAR struct ieee802154_radio_s *radiodev, struct ieee802154_maccb_s *callbacks); + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* __INCLUDE_NUTTX_WIRELESS_IEEE802154_MRF24J40_H */ diff --git a/include/nuttx/wireless/ieee802154/ieee802154_radio.h b/include/nuttx/wireless/ieee802154/ieee802154_radio.h index c3439feb89..06276b2870 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_radio.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_radio.h @@ -33,8 +33,8 @@ * ****************************************************************************/ -#ifndef __INCLUDE_NUTTX_WIRELESS_IEEE802154_IEEE802154_H -#define __INCLUDE_NUTTX_WIRELESS_IEEE802154_IEEE802154_H +#ifndef __INCLUDE_NUTTX_WIRELESS_IEEE802154_IEEE802154_RADIO_H +#define __INCLUDE_NUTTX_WIRELESS_IEEE802154_IEEE802154_RADIO_H /**************************************************************************** * Included Files @@ -48,70 +48,13 @@ /**************************************************************************** * Pre-Processor Definitions ****************************************************************************/ -/* Configuration ************************************************************/ -/* None at the moment */ - -/* IEEE 802.15.4 MAC Interface **********************************************/ - -/* Frame control field masks, 2 bytes - * Seee IEEE 802.15.4/2003 7.2.1.1 page 112 - */ - -#define IEEE802154_FC1_FTYPE 0x03 /* Frame type, bits 0-2 */ -#define IEEE802154_FC1_SEC 0x08 /* Security Enabled, bit 3 */ -#define IEEE802154_FC1_PEND 0x10 /* Frame pending, bit 4 */ -#define IEEE802154_FC1_ACKREQ 0x20 /* Acknowledge request, bit 5 */ -#define IEEE802154_FC1_INTRA 0x40 /* Intra PAN, bit 6 */ -#define IEEE802154_FC2_DADDR 0x0C /* Dest addressing mode, bits 10-11 */ -#define IEEE802154_FC2_VERSION 0x30 /* Source addressing mode, bits 12-13 */ -#define IEEE802154_FC2_SADDR 0xC0 /* Source addressing mode, bits 14-15 */ - -/* Frame Type */ - -#define IEEE802154_FRAME_BEACON 0x00 -#define IEEE802154_FRAME_DATA 0x01 -#define IEEE802154_FRAME_ACK 0x02 -#define IEEE802154_FRAME_COMMAND 0x03 - -/* Security Enabled */ - -#define IEEE802154_SEC_OFF 0x00 -#define IEEE802154_SEC_ON 0x08 -/* Flags */ - -#define IEEE802154_PEND 0x10 -#define IEEE802154_ACK_REQ 0x20 -#define IEEE802154_INTRA 0x40 - -/* Dest Addressing modes */ - -#define IEEE802154_DADDR_NONE 0x00 -#define IEEE802154_DADDR_SHORT 0x08 -#define IEEE802154_DADDR_EXT 0x0A - -/* Src Addressing modes */ - -#define IEEE802154_SADDR_NONE 0x00 -#define IEEE802154_SADDR_SHORT 0x80 -#define IEEE802154_SADDR_EXT 0xA0 - -/* Some addresses */ +/* Configuration ************************************************************/ -#define IEEE802154_PAN_DEFAULT (uint16_t)0xFFFF -#define IEEE802154_SADDR_UNSPEC (uint16_t)0xFFFF -#define IEEE802154_SADDR_BCAST (uint16_t)0xFFFE -#define IEEE802154_EADDR_UNSPEC (uint8_t*)"\xff\xff\xff\xff\xff\xff\xff\xff" +/* IEEE 802.15.4 Radio Interface **********************************************/ -#define IEEE802154_CMD_ASSOC_REQ 0x01 -#define IEEE802154_CMD_ASSOC_RSP 0x02 -#define IEEE802154_CMD_DIS_NOT 0x03 -#define IEEE802154_CMD_DATA_REQ 0x04 -#define IEEE802154_CMD_PANID_CONF_NOT 0x05 -#define IEEE802154_CMD_ORPHAN_NOT 0x06 -#define IEEE802154_CMD_BEACON_REQ 0x07 -#define IEEE802154_CMD_COORD_REALIGN 0x08 -#define IEEE802154_CMD_GTS_REQ 0x09 +/* This layer only knows radio frames. There are no 802.15.4 specific bits + * at this layer. */ /* Device modes */ @@ -135,73 +78,75 @@ struct ieee802154_cca_s { uint8_t use_ed : 1; /* CCA using ED */ uint8_t use_cs : 1; /* CCA using carrier sense */ - uint8_t edth; /* Energy detection threshold for CCA */ - uint8_t csth; /* Carrier sense threshold for CCA */ + uint8_t edth; /* Energy detection threshold for CCA */ + uint8_t csth; /* Carrier sense threshold for CCA */ }; -struct ieee802154_dev_s; +struct ieee802154_radio_s; -struct ieee802154_devops_s +struct ieee802154_radioops_s { - CODE int (*setchannel)(FAR struct ieee802154_dev_s *dev, uint8_t channel); - CODE int (*getchannel)(FAR struct ieee802154_dev_s *dev, + CODE int (*setchannel)(FAR struct ieee802154_radio_s *dev, uint8_t channel); + CODE int (*getchannel)(FAR struct ieee802154_radio_s *dev, FAR uint8_t *channel); - CODE int (*setpanid)(FAR struct ieee802154_dev_s *dev, uint16_t panid); - CODE int (*getpanid)(FAR struct ieee802154_dev_s *dev, + CODE int (*setpanid)(FAR struct ieee802154_radio_s *dev, uint16_t panid); + CODE int (*getpanid)(FAR struct ieee802154_radio_s *dev, FAR uint16_t *panid); - CODE int (*setsaddr)(FAR struct ieee802154_dev_s *dev, uint16_t saddr); - CODE int (*getsaddr)(FAR struct ieee802154_dev_s *dev, + CODE int (*setsaddr)(FAR struct ieee802154_radio_s *dev, uint16_t saddr); + CODE int (*getsaddr)(FAR struct ieee802154_radio_s *dev, FAR uint16_t *saddr); - CODE int (*seteaddr)(FAR struct ieee802154_dev_s *dev, + CODE int (*seteaddr)(FAR struct ieee802154_radio_s *dev, FAR uint8_t *laddr); - CODE int (*geteaddr)(FAR struct ieee802154_dev_s *dev, + CODE int (*geteaddr)(FAR struct ieee802154_radio_s *dev, FAR uint8_t *laddr); - CODE int (*setpromisc)(FAR struct ieee802154_dev_s *dev, bool promisc); - CODE int (*getpromisc)(FAR struct ieee802154_dev_s *dev, + CODE int (*setpromisc)(FAR struct ieee802154_radio_s *dev, bool promisc); + CODE int (*getpromisc)(FAR struct ieee802154_radio_s *dev, FAR bool *promisc); - CODE int (*setdevmode)(FAR struct ieee802154_dev_s *dev, uint8_t devmode); - CODE int (*getdevmode)(FAR struct ieee802154_dev_s *dev, + CODE int (*setdevmode)(FAR struct ieee802154_radio_s *dev, uint8_t devmode); + CODE int (*getdevmode)(FAR struct ieee802154_radio_s *dev, FAR uint8_t *devmode); - CODE int (*settxpower)(FAR struct ieee802154_dev_s *dev, + CODE int (*settxpower)(FAR struct ieee802154_radio_s *dev, int32_t txpwr); /* unit = 1 mBm = 1/100 dBm */ - CODE int (*gettxpower)(FAR struct ieee802154_dev_s *dev, + CODE int (*gettxpower)(FAR struct ieee802154_radio_s *dev, FAR int32_t *txpwr); - CODE int (*setcca)(FAR struct ieee802154_dev_s *dev, + CODE int (*setcca)(FAR struct ieee802154_radio_s *dev, FAR struct ieee802154_cca_s *cca); - CODE int (*getcca)(FAR struct ieee802154_dev_s *dev, + CODE int (*getcca)(FAR struct ieee802154_radio_s *dev, FAR struct ieee802154_cca_s *cca); - CODE int (*ioctl)(FAR struct ieee802154_dev_s *ieee, int cmd, + CODE int (*ioctl)(FAR struct ieee802154_radio_s *ieee, int cmd, unsigned long arg); - CODE int (*energydetect)(FAR struct ieee802154_dev_s *dev, + CODE int (*energydetect)(FAR struct ieee802154_radio_s *dev, FAR uint8_t *energy); - CODE int (*rxenable)(FAR struct ieee802154_dev_s *dev, bool state, + CODE int (*rxenable)(FAR struct ieee802154_radio_s *dev, bool state, FAR struct ieee802154_packet_s *packet); - CODE int (*transmit)(FAR struct ieee802154_dev_s *dev, + CODE int (*transmit)(FAR struct ieee802154_radio_s *dev, FAR struct ieee802154_packet_s *packet); /*TODO beacon/sf order*/ }; -struct ieee802154_dev_s +struct ieee802154_radio_s { - FAR const struct ieee802154_devops_s *ops; + FAR const struct ieee802154_radioops_s *ops; /* Packet reception management */ - struct ieee802154_packet_s *rxbuf; - sem_t rxsem; + struct ieee802154_packet_s *rxbuf; /* packet reception buffer, filled by rx interrupt, NULL if rx not enabled */ + sem_t rxsem; /* Semaphore posted after reception of a packet */ /* Packet transmission management */ - - sem_t txsem; + bool txok; /* Last transmission status, filled by tx interrupt */ + bool txbusy; /* Last transmission failed because channel busy */ + uint8_t txretries; /* Last transmission required this much retries */ + sem_t txsem; /* Semaphore posted after transmission of a packet */ }; #ifdef __cplusplus @@ -221,4 +166,4 @@ extern "C" } #endif -#endif /* __INCLUDE_NUTTX_WIRELESS_IEEE802154_MRF24J40_H */ +#endif /* __INCLUDE_NUTTX_WIRELESS_IEEE802154_IEEE802154_RADIO_H */ diff --git a/include/nuttx/wireless/ieee802154/mrf24j40.h b/include/nuttx/wireless/ieee802154/mrf24j40.h index 2c78faee01..167f125b33 100644 --- a/include/nuttx/wireless/ieee802154/mrf24j40.h +++ b/include/nuttx/wireless/ieee802154/mrf24j40.h @@ -100,7 +100,7 @@ extern "C" ****************************************************************************/ struct spi_dev_s; /* Forward reference */ -FAR struct ieee802154_dev_s *mrf24j40_init(FAR struct spi_dev_s *spi, +FAR struct ieee802154_radio_s *mrf24j40_init(FAR struct spi_dev_s *spi, FAR const struct mrf24j40_lower_s *lower); #undef EXTERN diff --git a/wireless/ieee802154/Kconfig b/wireless/ieee802154/Kconfig index 18d5a8753c..60706d45bc 100644 --- a/wireless/ieee802154/Kconfig +++ b/wireless/ieee802154/Kconfig @@ -12,4 +12,22 @@ config IEEE802154 if IEEE802154 +config IEEE802154_MAC + bool "Generic Media Access Control layer for 802.15.4 radios" + default n + depends on IEEE802154 + ---help--- + Enables a Media Access Controller for any IEEE802.15.4 radio + device. This in turn can be used by higher layer entities + such as 6lowpan. It is not required to use 802.15.4 radios, + but is strongly suggested to ensure exchange of valid frames. + +config IEEE802154_DEV + bool "Debug character driver for ieee802.15.4 radio interfaces" + default n + depends on IEEE802154 + ---help--- + Enables a device driver to expose ieee802.15.4 radio controls + to user space as IOCTLs. + endif # IEEE802154 diff --git a/wireless/ieee802154/Make.defs b/wireless/ieee802154/Make.defs index 9e0c66391b..8d7251c148 100644 --- a/wireless/ieee802154/Make.defs +++ b/wireless/ieee802154/Make.defs @@ -36,9 +36,18 @@ ifeq ($(CONFIG_IEEE802154),y) # Include IEEE 802.15.4 support +CSRCS = # Include wireless devices build support +ifeq ($(CONFIG_IEEE802154_MAC),y) +CSRCS += ieee802154/mac802154.c +endif + +ifeq ($(CONFIG_IEEE802154_DEV),y) +CSRCS += ieee802154/ieee802154_device.c +endif + DEPPATH += --dep-path wireless/ieee802154 VPATH += :wireless/ieee802154 CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)$(DELIM)wireless$(DELIM)ieee802154} diff --git a/wireless/ieee802154/ieee802154_device.c b/wireless/ieee802154/ieee802154_device.c new file mode 100644 index 0000000000..75921a88cd --- /dev/null +++ b/wireless/ieee802154/ieee802154_device.c @@ -0,0 +1,374 @@ +/**************************************************************************** + * drivers/ieee802154/ieee802154_device.c + * + * Copyright (C) 2014-2015 Gregory Nutt. All rights reserved. + * Copyright (C) 2014-2015 Sebastien Lorquet. All rights reserved. + * Author: Sebastien Lorquet + * + * 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. + * + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +struct ieee802154_devwrapper_s +{ + FAR struct ieee802154_radio_s *child; + sem_t devsem; /* Device access serialization semaphore */ + int opened; /* this device can only be opened once */ +}; + +/* when rx interrupt is complete, it calls sem_post(&dev->rxsem); */ +/* when tx interrupt is complete, it calls sem_post(&dev->txsem); */ + +static void ieee802154dev_semtake(FAR struct ieee802154_devwrapper_s *dev); +static int ieee802154dev_open (FAR struct file *filep); +static int ieee802154dev_close (FAR struct file *filep); +static ssize_t ieee802154dev_read (FAR struct file *filep, FAR char *buffer, size_t len); +static ssize_t ieee802154dev_write (FAR struct file *filep, FAR const char *buffer, size_t len); +static int ieee802154dev_ioctl (FAR struct file *filep, int cmd, unsigned long arg); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const struct file_operations ieee802154dev_fops = +{ + ieee802154dev_open , /* open */ + ieee802154dev_close, /* close */ + ieee802154dev_read , /* read */ + ieee802154dev_write, /* write */ + 0 , /* seek */ + ieee802154dev_ioctl /* ioctl */ +#ifndef CONFIG_DISABLE_POLL + , 0 /* poll */ +#endif +}; + +/**************************************************************************** + * Name: ieee802154dev_semtake + * + * Description: + * Acquire the semaphore used for access serialization. + * + ****************************************************************************/ + +static void ieee802154dev_semtake(FAR struct ieee802154_devwrapper_s *dev) +{ + /* Take the semaphore (perhaps waiting) */ + + while (sem_wait(&dev->devsem) != 0) + { + /* The only case that an error should occur here is if + * the wait was awakened by a signal. + */ + ASSERT(errno == EINTR); + } +} + +/**************************************************************************** + * Name: ieee802154dev_semgive + * + * Description: + * Release the semaphore used for access serialization. + * + ****************************************************************************/ + +static inline void ieee802154dev_semgive(FAR struct ieee802154_devwrapper_s *dev) +{ + sem_post(&dev->devsem); +} + +/**************************************************************************** + * Name: ieee802154dev_open + * + * Description: + * Open the MRF24J40 device. + * + ****************************************************************************/ + +static int ieee802154dev_open(FAR struct file *filep) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct ieee802154_devwrapper_s *dev = inode->i_private; + + ieee802154dev_semtake(dev); + + if (dev->opened) + { + return -EMFILE; + } + else + { + + /* Enable interrupts (only rx for now)*/ + + //mrf24j40_setreg(dev->spi, MRF24J40_INTCON, ~(MRF24J40_INTCON_RXIE) ); + //dev->lower->enable(dev->lower, TRUE); + + dev->opened = TRUE; + } + + ieee802154dev_semgive(dev); + return OK; +} + +/**************************************************************************** + * Name: ieee802154dev_close + * + * Description: + * Close the MRF24J40 device. + * + ****************************************************************************/ + +static int ieee802154dev_close(FAR struct file *filep) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct ieee802154_devwrapper_s *dev = inode->i_private; + int ret = OK; + + ieee802154dev_semtake(dev); + + if(!dev->opened) + { + ret = -EIO; + } + else + { + /* Disable interrupts */ + + //mrf24j40_setreg(dev->spi, MRF24J40_INTCON, 0xFF ); + //dev->lower->enable(dev->lower, FALSE); + + dev->opened = FALSE; + } + + ieee802154dev_semgive(dev); + return ret; +} + +/**************************************************************************** + * Name: ieee802154dev_read + * + * Description: + * Return the last received packet. + * TODO: Return a packet from the receive queue. The buffer must be a pointer to a + * struct ieee802154_packet_s structure, with a correct length. + * + ****************************************************************************/ + +static ssize_t ieee802154dev_read(FAR struct file *filep, FAR char *buffer, size_t len) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct ieee802154_devwrapper_s *dev = inode->i_private; + int ret = OK; + + FAR struct ieee802154_packet_s *buf = (FAR struct ieee802154_packet_s*)buffer; + + if (lenchild->ops->rxenable(dev->child, 1, buf); +#if 0 + if (ret < 0) + { + goto done; + } +#endif + + /* if no packet is received, this will produce -EAGAIN + * The user is responsible for sleeping until sth arrives + */ +#if 0 + ret = sem_trywait(&dev->child->rxsem); +#else + ret = sem_wait(&dev->child->rxsem); +#endif + if (ret < 0) + { + ret = -errno; + goto done; + } + + /* disable read until we have process the current read */ + dev->child->ops->rxenable(dev->child, 0, NULL); + + ret = buf->len; + +done: + + return ret; +} + +/**************************************************************************** + * Name: ieee802154dev_write + * + * Description: + * Send a packet immediately. + * TODO: Put a packet in the send queue. The packet will be sent as soon as possible. + * The buffer must point to a struct ieee802154_packet_s with the correct length. + * + ****************************************************************************/ + +static ssize_t ieee802154dev_write(FAR struct file *filep, FAR const char *buffer, size_t len) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct ieee802154_devwrapper_s *dev = inode->i_private; + FAR struct ieee802154_packet_s *packet; + int ret = OK; + + /* TODO: Make this an option or have a new method of doing timeout from ioctrl */ + FAR struct timespec timeout; + + timeout.tv_sec = 1; + timeout.tv_nsec = 0; + + /* sanity checks */ + + if (lenlen > 125) /* Max len 125, 2 FCS bytes auto added by mrf*/ + { + ret = -EPERM; + // goto done; + DEBUGASSERT(0); + } + + /* Copy packet to normal device TX fifo. + * Beacons and GTS transmission will be handled via IOCTLs + */ + ret = dev->child->ops->transmit(dev->child, packet); + + if(ret != packet->len) + { + ret = -EPERM; + goto done; + } + + if(sem_timedwait(&dev->child->txsem, &timeout)) + { + dbg("Radio Device timedout on Tx\n"); + } + +done: + + /* okay, tx interrupt received. check transmission status to decide success. */ + + return ret; +} + +/**************************************************************************** + * Name: ieee802154dev_ioctl + * + * Description: + * Control the MRF24J40 device. This is where the real operations happen. + * + ****************************************************************************/ + +static int ieee802154dev_ioctl(FAR struct file *filep, int cmd, unsigned long arg) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct ieee802154_devwrapper_s *dev = inode->i_private; + FAR struct ieee802154_radio_s *child = dev->child; + int ret = OK; + + switch(cmd) + { + case MAC854IOCSCHAN : ret = child->ops->setchannel (child, (uint8_t) arg); break; + case MAC854IOCGCHAN : ret = child->ops->getchannel (child, (FAR uint8_t*) arg); break; + case MAC854IOCSPANID : ret = child->ops->setpanid (child, (uint16_t) arg); break; + case MAC854IOCGPANID : ret = child->ops->getpanid (child, (FAR uint16_t*) arg); break; + case MAC854IOCSSADDR : ret = child->ops->setsaddr (child, (uint16_t) arg); break; + case MAC854IOCGSADDR : ret = child->ops->getsaddr (child, (FAR uint16_t*) arg); break; + case MAC854IOCSEADDR : ret = child->ops->seteaddr (child, (FAR uint8_t*) arg); break; + case MAC854IOCGEADDR : ret = child->ops->geteaddr (child, (FAR uint8_t*) arg); break; + case MAC854IOCSPROMISC: ret = child->ops->setpromisc (child, (bool) arg); break; + case MAC854IOCGPROMISC: ret = child->ops->getpromisc (child, (FAR bool*) arg); break; + case MAC854IOCSDEVMODE: ret = child->ops->setdevmode (child, (uint8_t) arg); break; + case MAC854IOCGDEVMODE: ret = child->ops->getdevmode (child, (FAR uint8_t*) arg); break; + case MAC854IOCSTXP : ret = child->ops->settxpower (child, (int32_t) arg); break; + case MAC854IOCGTXP : ret = child->ops->gettxpower (child, (FAR int32_t*) arg); break; + case MAC854IOCSCCA : ret = child->ops->setcca (child, (FAR struct ieee802154_cca_s*)arg); break; + case MAC854IOCGCCA : ret = child->ops->getcca (child, (FAR struct ieee802154_cca_s*)arg); break; + case MAC854IOCGED : ret = child->ops->energydetect(child, (FAR uint8_t*) arg); break; + default : ret = child->ops->ioctl (child, cmd, arg); + } + + return ret; +} + +/**************************************************************************** + * Name: ieee802154dev_register + * + * Description: + * Register /dev/ieee%d + * + ****************************************************************************/ + +int ieee802154_register(FAR struct ieee802154_radio_s *ieee, unsigned int minor) +{ + char devname[16]; + FAR struct ieee802154_devwrapper_s *dev; + + dev = kmm_zalloc(sizeof(struct ieee802154_devwrapper_s)); + + if (!dev) + { + return -ENOMEM; + } + + dev->child = ieee; + + sem_init(&dev->devsem , 0, 1); /* Allow the device to be opened once before blocking */ + + sprintf(devname, "/dev/ieee%d", minor); + + return register_driver(devname, &ieee802154dev_fops, 0666, dev); +} + diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c new file mode 100644 index 0000000000..ad9e195371 --- /dev/null +++ b/wireless/ieee802154/mac802154.c @@ -0,0 +1,586 @@ +/**************************************************************************** + * wireless/ieee802154/mac802154.c + * + * Copyright (C) 2016 Sebastien Lorquet. All rights reserved. + * Author: Sebastien Lorquet + * + * 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 + +/* Frame Type */ + +#define IEEE802154_FRAME_BEACON 0x00 +#define IEEE802154_FRAME_DATA 0x01 +#define IEEE802154_FRAME_ACK 0x02 +#define IEEE802154_FRAME_COMMAND 0x03 + +/* MAC commands */ + +#define IEEE802154_CMD_ASSOC_REQ 0x01 +#define IEEE802154_CMD_ASSOC_RSP 0x02 +#define IEEE802154_CMD_DIS_NOT 0x03 +#define IEEE802154_CMD_DATA_REQ 0x04 +#define IEEE802154_CMD_PANID_CONF_NOT 0x05 +#define IEEE802154_CMD_ORPHAN_NOT 0x06 +#define IEEE802154_CMD_BEACON_REQ 0x07 +#define IEEE802154_CMD_COORD_REALIGN 0x08 +#define IEEE802154_CMD_GTS_REQ 0x09 + +/* private types */ +/* The privmac structure is an extension of the public ieee802154_mac_s type. + * It contains storage for the IEEE802.15.4 MIB attributes. + */ + +struct ieee802154_privmac_s +{ + struct ieee802154_mac_s pubmac; /* This MUST be the first member */ + + /* MIB attributes, grouped to save memory */ + /* 0x40 */ uint8_t macAckWaitDuration : 1; /* 55 or 120(true) */ + /* 0x41 */ uint8_t macAssociationPermit : 1; + /* 0x42 */ uint8_t macAutoRequest : 1; + /* 0x43 */ uint8_t macBattLifeExt : 1; + /* 0x44 */ uint8_t macBattLifeExtPeriods : 1; /* 6 or 8(true) */ + /* 0x4E */ uint8_t macMaxCSMABackoffs : 3; /* 0-5 */ + + /* 0x47 */ uint8_t macBeaconOrder : 4; + /* 0x54 */ uint8_t macSuperframeOrder : 4; + + /* 0x4F */ uint32_t macMinBE : 2; + /* 0x4D */ uint32_t macGTSPermit : 1; + /* 0x51 */ uint32_t macPromiscuousMode : 1; + /* 0x52 */ uint32_t macRxOnWhenIdle : 1; + uint32_t macPad : 3; + /* 0x48 */ uint32_t macBeaconTxTime : 24; + + /* 0x45 */ uint8_t macBeaconPayload[MAC802154_aMaxBeaconPayloadLength]; + /* 0x46 */ uint8_t macBeaconPayloadLength; + /* 0x49 */ uint8_t macBSN; + /* 0x4A */ uint8_t macCoordExtendedAddress[8]; + /* 0x4B */ uint16_t macCoordShortAddress; + /* 0x4C */ uint8_t macDSN; + /* 0x50 */ uint16_t macPANId; + /* 0x53 */ uint16_t macShortAddress; + /* 0x55 */ uint16_t macTransactionPersistenceTime; +#if 0 + /* Security MIB */ + /* 0x70 */ macACLEntryDescriptorSet + /* 0x71 */ macACLEntryDescriptorSetSize + /* 0x74 */ macDefaultSecurityMaterial + /* 0x72 */ macDefaultSecurity:1 + /* 0x75 */ macDefaultSecuritySuite:3 + /* 0x73 */ macDefaultSecurityMaterialLength:6 + /* 0x76 */ macSecurityMode:2 +#endif +}; + +/* forward declarations */ + +static int mac802154_reqdata (struct ieee802154_mac_s *mac, + uint8_t handle, + uint8_t *buf, + int len); + +static int mac802154_reqpurge (struct ieee802154_mac_s *mac, + uint8_t handle); + +static int mac802154_reqassociate (struct ieee802154_mac_s *mac, + uint16_t panid, + uint8_t *coordeadr); + +static int mac802154_reqdisassociate(struct ieee802154_mac_s *mac, + uint8_t *eadr, + uint8_t reason); + +static int mac802154_reqget (struct ieee802154_mac_s *mac, + int attribute); + +static int mac802154_reqgts (struct ieee802154_mac_s *mac, + uint8_t* characteristics); + +static int mac802154_reqreset (struct ieee802154_mac_s *mac, + bool setdefaults); + +static int mac802154_reqrxenable (struct ieee802154_mac_s *mac, + bool deferrable, + int ontime, + int duration); + +static int mac802154_reqscan (struct ieee802154_mac_s *mac, + uint8_t type, + uint32_t channels, + int duration); + +static int mac802154_reqset (struct ieee802154_mac_s *mac, + int attribute, + uint8_t *value, + int valuelen); + +static int mac802154_reqstart (struct ieee802154_mac_s *mac, + uint16_t panid, + int channel, + uint8_t bo, + uint8_t fo, + bool coord, + bool batext, + bool realign); + +static int mac802154_reqsync (struct ieee802154_mac_s *mac, + int channel, + bool track); + +static int mac802154_reqpoll (struct ieee802154_mac_s *mac, + uint8_t *coordaddr); + +static int mac802154_rspassociate (struct ieee802154_mac_s *mac, + uint8_t eadr, + uint16_t saddr, + int status); + +static int mac802154_rsporphan (struct ieee802154_mac_s *mac, + uint8_t *orphanaddr, + uint16_t saddr, + bool associated); + + +/* data */ +static const struct ieee802154_macops_s mac802154ops = +{ + .req_data = mac802154_reqdata + .req_purge = mac802154_reqpurge + .req_associate = mac802154_reqassociate + .req_disassociate= mac802154_reqdisassociate + .req_get = mac802154_reqget + .req_gts = mac802154_reqgts + .req_reset = mac802154_reqreset + .req_rxenable = mac802154_reqrxenable + .req_scan = mac802154_reqscan + .req_set = mac802154_reqset + .req_start = mac802154_reqstart + .req_sync = mac802154_reqsync + .req_poll = mac802154_reqpoll + .rsp_associate = mac802154_rspassociate + .rsp_orphan = mac802154_rsporphan +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: mac802154_defaultmib + * + * Description: + * Set the MIB to its default values. + * + ****************************************************************************/ + +static int mac802154_defaultmib(FAR struct ieee802154_privmac_s *priv) +{ + priv->macAckWaitDuration = 0; + priv->macAssociationPermit = 0; + priv->macAutoRequest = 1; + priv->macBattLifeExt = 0; + priv->macBattLifeExtPeriods = 0; + priv->macMaxCSMABackoffs = 4; + + priv->macBeaconOrder = 15; + priv->macSuperframeOrder = 15; + + priv->macMinBE = 3; + priv->macGTSPermit = 1; + priv->macPromiscuousMode = 0; + priv->macRxOnWhenIdle = 0; + priv->macBeaconTxTime = 0x000000; + + priv->macBeaconPayloadLength = 0; + priv->macBSN = 0; /*shall be random*/ + priv->macCoordExtendedAddress[8]; + priv->macCoordShortAddress = 0xffff; + priv->macDSN = 0 /*shall be random*/; + priv->macPANId = 0xffff; + priv->macShortAddress = 0xffff; + priv->macTransactionPersistenceTime = 0x01f4; +#if 0 + /* Security MIB */ + priv->macACLEntryDescriptorSetSize = 0; + priv->macDefaultSecurity = 0; + priv->macDefaultSecuritySuite = 0; + priv->macDefaultSecurityMaterialLength = 0x15; + priv->macSecurityMode = 0; +#endif +} + +/**************************************************************************** + * Name: mac802154_applymib + * + * Description: + * Some parts of the MIB must be sent to the radio device. This routine + * calls the radio device routines to store the related parameters in the + * radio driver. It must be called each time a MIB parameter is changed. + * + ****************************************************************************/ + +static int mac802154_applymib(FAR struct ieee802154_privmac_s *priv) +{ + return OK; +} + +/**************************************************************************** + * API Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: mac802154_reqdata + * + * Description: + * The MCPS-DATA.request primitive requests the transfer of a data SPDU + * (i.e., MSDU) from a local SSCS entity to a single peer SSCS entity. + * Confirmation is returned via the + * struct ieee802154_maccb_s->conf_data callback. + * + ****************************************************************************/ + +static int mac802154_reqdata(FAR struct ieee802154_mac_s *mac, + uint8_t handle, + uint8_t *buf, + int len) +{ + FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; + return -ENOTTY; +} + +/**************************************************************************** + * Name: mac802154_reqpurge + * + * Description: + * The MCPS-PURGE.request primitive allows the next higher layer to purge an + * MSDU from the transaction queue. Confirmation is returned via + * the struct ieee802154_maccb_s->conf_purge callback. + * + ****************************************************************************/ + +static int mac802154_reqpurge(FAR struct ieee802154_mac_s *mac, + uint8_t handle) +{ + FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; + return -ENOTTY; +} + +/**************************************************************************** + * Name: mac802154_reqassociate + * + * Description: + * The MLME-ASSOCIATE.request primitive allows a device to request an + * association with a coordinator. Confirmation is returned via the + * struct ieee802154_maccb_s->conf_associate callback. + * + ****************************************************************************/ + +static int mac802154_reqassociate(FAR struct ieee802154_mac_s *mac, + uint16_t panid, + uint8_t *coordeadr) +{ + FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; + return -ENOTTY; +} + +/**************************************************************************** + * Name: mac802154_reqdisassociate + * + * Description: + * The MLME-DISASSOCIATE.request primitive is used by an associated device to + * notify the coordinator of its intent to leave the PAN. It is also used by + * the coordinator to instruct an associated device to leave the PAN. + * Confirmation is returned via the + * struct ieee802154_maccb_s->conf_disassociate callback. + * + ****************************************************************************/ + +static int mac802154_reqdisassociate(FAR struct ieee802154_mac_s *mac, + uint8_t *eadr, + uint8_t reason) +{ + FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; + return -ENOTTY; +} + +/**************************************************************************** + * Name: mac802154_reqget + * + * Description: + * The MLME-GET.request primitive requests information about a given PIB + * attribute. Actual data is returned via the + * struct ieee802154_maccb_s->conf_get callback. + * + ****************************************************************************/ + +static int mac802154_reqget(FAR struct ieee802154_mac_s *mac, + int attribute) +{ + FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; + return -ENOTTY; +} + +/**************************************************************************** + * Name: mac802154_reqgts + * + * Description: + * The MLME-GTS.request primitive allows a device to send a request to the PAN + * coordinator to allocate a new GTS or to deallocate an existing GTS. + * Confirmation is returned via the + * struct ieee802154_maccb_s->conf_gts callback. + * + ****************************************************************************/ + +static int mac802154_reqgts(FAR struct ieee802154_mac_s *mac, + uint8_t* characteristics) +{ + FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; + return -ENOTTY; +} + +/**************************************************************************** + * Name: mac802154_reqreset + * + * Description: + * The MLME-RESET.request primitive allows the next higher layer to request + * that the MLME performs a reset operation. Confirmation is returned via + * the struct ieee802154_maccb_s->conf_reset callback. + * + ****************************************************************************/ + +static int mac802154_reqreset(FAR struct ieee802154_mac_s *mac, + bool setdefaults) +{ + FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; + return -ENOTTY; +} + +/**************************************************************************** + * Name: mac802154_reqrxenable + * + * Description: + * The MLME-RX-ENABLE.request primitive allows the next higher layer to + * request that the receiver is enable for a finite period of time. + * Confirmation is returned via the + * struct ieee802154_maccb_s->conf_rxenable callback. + * + ****************************************************************************/ + +static int mac802154_reqrxenable(FAR struct ieee802154_mac_s *mac, + bool deferrable, + int ontime, + int duration) +{ + FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; + return -ENOTTY; +} + +/**************************************************************************** + * Name: mac802154_reqscan + * + * Description: + * The MLME-SCAN.request primitive is used to initiate a channel scan over a + * given list of channels. A device can use a channel scan to measure the + * energy on the channel, search for the coordinator with which it associated, + * or search for all coordinators transmitting beacon frames within the POS of + * the scanning device. Scan results are returned + * via MULTIPLE calls to the struct ieee802154_maccb_s->conf_scan callback. + * This is a difference with the official 802.15.4 specification, implemented + * here to save memory. + * + ****************************************************************************/ + +static int mac802154_reqscan(FAR struct ieee802154_mac_s *mac, + uint8_t type, + uint32_t channels, + int duration) +{ + FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; + return -ENOTTY; +} + +/**************************************************************************** + * Name: mac802154_reqset + * + * Description: + * The MLME-SET.request primitive attempts to write the given value to the + * indicated MAC PIB attribute. Confirmation is returned via the + * struct ieee802154_maccb_s->conf_set callback. + * + ****************************************************************************/ + +static int mac802154_reqset(FAR struct ieee802154_mac_s *mac, + int attribute, + uint8_t *value, + int valuelen) +{ + FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; + return -ENOTTY; +} + +/**************************************************************************** + * Name: mac802154_reqstart + * + * Description: + * The MLME-START.request primitive makes a request for the device to start + * using a new superframe configuration. Confirmation is returned + * via the struct ieee802154_maccb_s->conf_start callback. + * + ****************************************************************************/ + +static int mac802154_reqstart(FAR struct ieee802154_mac_s *mac, + uint16_t panid, + int channel, + uint8_t bo, + uint8_t fo, + bool coord, + bool batext, + bool realign) +{ + FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; + return -ENOTTY; +} + +/**************************************************************************** + * Name: mac802154_reqsync + * + * Description: + * The MLME-SYNC.request primitive requests to synchronize with the + * coordinator by acquiring and, if specified, tracking its beacons. + * Confirmation is returned via the + * struct ieee802154_maccb_s->int_commstatus callback. TOCHECK. + * + ****************************************************************************/ + +static int mac802154_reqsync(FAR struct ieee802154_mac_s *mac, + int channel, + bool track) +{ + FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; + return -ENOTTY; +} + +/**************************************************************************** + * Name: mac802154_reqpoll + * + * Description: + * The MLME-POLL.request primitive prompts the device to request data from the + * coordinator. Confirmation is returned via the + * struct ieee802154_maccb_s->conf_poll callback, followed by a + * struct ieee802154_maccb_s->ind_data callback. + * + ****************************************************************************/ + +static int mac802154_reqpoll(FAR struct ieee802154_mac_s *mac, + uint8_t *coordaddr) +{ + FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; + return -ENOTTY; +} + +/**************************************************************************** + * Name: mac802154_rspassociate + * + * Description: + * The MLME-ASSOCIATE.response primitive is used to initiate a response to an + * MLME-ASSOCIATE.indication primitive. + * + ****************************************************************************/ + +static int mac802154_rspassociate(FAR struct ieee802154_mac_s *mac, + uint8_t eadr, + uint16_t saddr, + int status) +{ + FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; + return -ENOTTY; +} + +/**************************************************************************** + * Name: mac802154_rsporphan + * + * Description: + * The MLME-ORPHAN.response primitive allows the next higher layer of a + * coordinator to respond to the MLME-ORPHAN.indication primitive. + * + ****************************************************************************/ + +static int mac802154_rsporphan(FAR struct ieee802154_mac_s *mac, + uint8_t *orphanaddr, + uint16_t saddr, + bool associated) +{ + FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; + return -ENOTTY; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: mac802154_register + * + * Description: + * Create a 802.15.4 MAC device from a 802.15.4 compatible radio device. + * + ****************************************************************************/ + +FAR struct ieee802154_mac_s * mac802154_register(FAR struct ieee802154_radio_s *radiodev, unsigned int minor) +{ + FAR struct ieee802154_privmac_s *mac; + + /* allocate object */ + mac = (FAR struct ieee802154_privmac_s *)kmm_zalloc(sizeof(struct ieee802154_privmac_s)); + if(!mac) + { + return NULL; + } + + /* init fields */ + mac->pubmac.radio = radiodev; + mac->pubmac.ops = mac802154ops; + mac802154_defaultmib(mac); + mac802154_applymib(mac); + return &mac->pubmac; +} + -- GitLab From 0ef10e6d0e18bb8edac3d8af6485ad60bfeaf5b1 Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Wed, 1 Jun 2016 13:11:49 +0200 Subject: [PATCH 002/990] fix atmel driver for new 802154 radio api --- drivers/wireless/ieee802154/at86rf23x.c | 96 +++++++++---------- include/nuttx/wireless/ieee802154/at86rf23x.h | 2 +- 2 files changed, 48 insertions(+), 50 deletions(-) diff --git a/drivers/wireless/ieee802154/at86rf23x.c b/drivers/wireless/ieee802154/at86rf23x.c index fdd2c3ad64..8d2e1cb133 100644 --- a/drivers/wireless/ieee802154/at86rf23x.c +++ b/drivers/wireless/ieee802154/at86rf23x.c @@ -58,8 +58,6 @@ #include #include -#include - #include "at86rf23x.h" /************************************************************************************ @@ -98,13 +96,13 @@ /* * AT86RF23x device instance * - * Make sure that struct ieee802154_dev_s remains first. If not it will break the + * Make sure that struct ieee802154_radio_s remains first. If not it will break the * code * */ struct at86rf23x_dev_s { - struct ieee802154_dev_s ieee; /* Public device instance */ + struct ieee802154_radio_s ieee; /* Public device instance */ FAR struct spi_dev_s *spi; /* Saved SPI interface instance */ struct work_s irqwork; /* Interrupt continuation work queue support */ FAR const struct at86rf23x_lower_s *lower; /* Low-level MCU-specific support */ @@ -143,26 +141,26 @@ static void at86rf23x_irqworker(FAR void *arg); static int at86rf23x_interrupt(int irq, FAR void *context); /* Driver operations */ -static int at86rf23x_setchannel (FAR struct ieee802154_dev_s *ieee, uint8_t chan); -static int at86rf23x_getchannel (FAR struct ieee802154_dev_s *ieee, FAR uint8_t *chan); -static int at86rf23x_setpanid (FAR struct ieee802154_dev_s *ieee, uint16_t panid); -static int at86rf23x_getpanid (FAR struct ieee802154_dev_s *ieee, FAR uint16_t *panid); -static int at86rf23x_setsaddr (FAR struct ieee802154_dev_s *ieee, uint16_t saddr); -static int at86rf23x_getsaddr (FAR struct ieee802154_dev_s *ieee, FAR uint16_t *saddr); -static int at86rf23x_seteaddr (FAR struct ieee802154_dev_s *ieee, FAR uint8_t *eaddr); -static int at86rf23x_geteaddr (FAR struct ieee802154_dev_s *ieee, FAR uint8_t *eaddr); -static int at86rf23x_setpromisc (FAR struct ieee802154_dev_s *ieee, bool promisc); -static int at86rf23x_getpromisc (FAR struct ieee802154_dev_s *ieee, FAR bool *promisc); -static int at86rf23x_setdevmode (FAR struct ieee802154_dev_s *ieee, uint8_t mode); -static int at86rf23x_getdevmode (FAR struct ieee802154_dev_s *ieee, FAR uint8_t *mode); -static int at86rf23x_settxpower (FAR struct ieee802154_dev_s *ieee, int32_t txpwr); -static int at86rf23x_gettxpower (FAR struct ieee802154_dev_s *ieee, FAR int32_t *txpwr); -static int at86rf23x_setcca (FAR struct ieee802154_dev_s *ieee, FAR struct ieee802154_cca_s *cca); -static int at86rf23x_getcca (FAR struct ieee802154_dev_s *ieee, FAR struct ieee802154_cca_s *cca); -static int at86rf23x_ioctl (FAR struct ieee802154_dev_s *ieee, int cmd, unsigned long arg); -static int at86rf23x_energydetect(FAR struct ieee802154_dev_s *ieee, FAR uint8_t *energy); -static int at86rf23x_rxenable (FAR struct ieee802154_dev_s *ieee, bool state, FAR struct ieee802154_packet_s *packet); -static int at86rf23x_transmit (FAR struct ieee802154_dev_s *ieee, FAR struct ieee802154_packet_s *packet); +static int at86rf23x_setchannel (FAR struct ieee802154_radio_s *ieee, uint8_t chan); +static int at86rf23x_getchannel (FAR struct ieee802154_radio_s *ieee, FAR uint8_t *chan); +static int at86rf23x_setpanid (FAR struct ieee802154_radio_s *ieee, uint16_t panid); +static int at86rf23x_getpanid (FAR struct ieee802154_radio_s *ieee, FAR uint16_t *panid); +static int at86rf23x_setsaddr (FAR struct ieee802154_radio_s *ieee, uint16_t saddr); +static int at86rf23x_getsaddr (FAR struct ieee802154_radio_s *ieee, FAR uint16_t *saddr); +static int at86rf23x_seteaddr (FAR struct ieee802154_radio_s *ieee, FAR uint8_t *eaddr); +static int at86rf23x_geteaddr (FAR struct ieee802154_radio_s *ieee, FAR uint8_t *eaddr); +static int at86rf23x_setpromisc (FAR struct ieee802154_radio_s *ieee, bool promisc); +static int at86rf23x_getpromisc (FAR struct ieee802154_radio_s *ieee, FAR bool *promisc); +static int at86rf23x_setdevmode (FAR struct ieee802154_radio_s *ieee, uint8_t mode); +static int at86rf23x_getdevmode (FAR struct ieee802154_radio_s *ieee, FAR uint8_t *mode); +static int at86rf23x_settxpower (FAR struct ieee802154_radio_s *ieee, int32_t txpwr); +static int at86rf23x_gettxpower (FAR struct ieee802154_radio_s *ieee, FAR int32_t *txpwr); +static int at86rf23x_setcca (FAR struct ieee802154_radio_s *ieee, FAR struct ieee802154_cca_s *cca); +static int at86rf23x_getcca (FAR struct ieee802154_radio_s *ieee, FAR struct ieee802154_cca_s *cca); +static int at86rf23x_ioctl (FAR struct ieee802154_radio_s *ieee, int cmd, unsigned long arg); +static int at86rf23x_energydetect(FAR struct ieee802154_radio_s *ieee, FAR uint8_t *energy); +static int at86rf23x_rxenable (FAR struct ieee802154_radio_s *ieee, bool state, FAR struct ieee802154_packet_s *packet); +static int at86rf23x_transmit (FAR struct ieee802154_radio_s *ieee, FAR struct ieee802154_packet_s *packet); /* These are pointers to ALL registered at86rf23x devices. @@ -174,7 +172,7 @@ static int at86rf23x_transmit (FAR struct ieee802154_dev_s *ieee, FAR str static struct at86rf23x_dev_s g_at86rf23x_devices[1]; -static const struct ieee802154_devops_s at86rf23x_devops = +static const struct ieee802154_radioops_s at86rf23x_devops = { .setchannel = at86rf23x_setchannel, .getchannel = at86rf23x_getchannel, @@ -636,7 +634,7 @@ static int at86rf23x_setTRXstate(FAR struct at86rf23x_dev_s *dev, uint8_t state, * * ****************************************************************************/ -static int at86rf23x_setchannel(FAR struct ieee802154_dev_s *ieee, uint8_t chan) +static int at86rf23x_setchannel(FAR struct ieee802154_radio_s *ieee, uint8_t chan) { FAR struct at86rf23x_dev_s *dev = (FAR struct at86rf23x_dev_s *)ieee; uint8_t state; @@ -683,7 +681,7 @@ static int at86rf23x_setchannel(FAR struct ieee802154_dev_s *ieee, uint8_t chan) * * ****************************************************************************/ -static int at86rf23x_getchannel(FAR struct ieee802154_dev_s *ieee, FAR uint8_t *chan) +static int at86rf23x_getchannel(FAR struct ieee802154_radio_s *ieee, FAR uint8_t *chan) { FAR struct at86rf23x_dev_s *dev = (FAR struct at86rf23x_dev_s *)ieee; @@ -703,7 +701,7 @@ static int at86rf23x_getchannel(FAR struct ieee802154_dev_s *ieee, FAR uint8_t * * Define the PAN ID for the network. * ****************************************************************************/ -static int at86rf23x_setpanid(FAR struct ieee802154_dev_s *ieee, uint16_t panid) +static int at86rf23x_setpanid(FAR struct ieee802154_radio_s *ieee, uint16_t panid) { FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; uint8_t *pan = (uint8_t *)&panid; @@ -721,7 +719,7 @@ static int at86rf23x_setpanid(FAR struct ieee802154_dev_s *ieee, uint16_t panid) * Define the PAN ID for the network. * ****************************************************************************/ -static int at86rf23x_getpanid(FAR struct ieee802154_dev_s *ieee, FAR uint16_t *panid) +static int at86rf23x_getpanid(FAR struct ieee802154_radio_s *ieee, FAR uint16_t *panid) { FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; uint8_t *pan = (uint8_t *)panid; @@ -739,7 +737,7 @@ static int at86rf23x_getpanid(FAR struct ieee802154_dev_s *ieee, FAR uint16_t *p * Define the Short Address for the device. * ****************************************************************************/ -static int at86rf23x_setsaddr(FAR struct ieee802154_dev_s *ieee, uint16_t saddr) +static int at86rf23x_setsaddr(FAR struct ieee802154_radio_s *ieee, uint16_t saddr) { FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; uint8_t *addr = (uint8_t *)&saddr; @@ -757,7 +755,7 @@ static int at86rf23x_setsaddr(FAR struct ieee802154_dev_s *ieee, uint16_t saddr) * Get the short address of the device. * ****************************************************************************/ -static int at86rf23x_getsaddr(FAR struct ieee802154_dev_s *ieee, FAR uint16_t *saddr) +static int at86rf23x_getsaddr(FAR struct ieee802154_radio_s *ieee, FAR uint16_t *saddr) { FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; uint8_t *addr = (uint8_t *)saddr; @@ -775,7 +773,7 @@ static int at86rf23x_getsaddr(FAR struct ieee802154_dev_s *ieee, FAR uint16_t *s * Set the IEEE address of the device. * ****************************************************************************/ -static int at86rf23x_seteaddr(FAR struct ieee802154_dev_s *ieee, FAR uint8_t *eaddr) +static int at86rf23x_seteaddr(FAR struct ieee802154_radio_s *ieee, FAR uint8_t *eaddr) { FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; /* TODO: Check if we need to pay attention to endianness */ @@ -798,7 +796,7 @@ static int at86rf23x_seteaddr(FAR struct ieee802154_dev_s *ieee, FAR uint8_t *ea * Get the IEEE address of the device. * ****************************************************************************/ -static int at86rf23x_geteaddr(FAR struct ieee802154_dev_s *ieee, FAR uint8_t *eaddr) +static int at86rf23x_geteaddr(FAR struct ieee802154_radio_s *ieee, FAR uint8_t *eaddr) { FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; /* TODO: Check if we need to pay attention to endianness */ @@ -821,7 +819,7 @@ static int at86rf23x_geteaddr(FAR struct ieee802154_dev_s *ieee, FAR uint8_t *ea * enable/disable promiscuous mode. * ****************************************************************************/ -static int at86rf23x_setpromisc(FAR struct ieee802154_dev_s *ieee, bool promisc) +static int at86rf23x_setpromisc(FAR struct ieee802154_radio_s *ieee, bool promisc) { FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; @@ -841,7 +839,7 @@ static int at86rf23x_setpromisc(FAR struct ieee802154_dev_s *ieee, bool promisc) * Check if the device is in promiscuous mode. * ****************************************************************************/ -static int at86rf23x_getpromisc(FAR struct ieee802154_dev_s *ieee, FAR bool *promisc) +static int at86rf23x_getpromisc(FAR struct ieee802154_radio_s *ieee, FAR bool *promisc) { FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; @@ -857,7 +855,7 @@ static int at86rf23x_getpromisc(FAR struct ieee802154_dev_s *ieee, FAR bool *pro * Check if the device is in promiscuous mode. * ****************************************************************************/ -static int at86rf23x_setdevmode(FAR struct ieee802154_dev_s *ieee, uint8_t mode) +static int at86rf23x_setdevmode(FAR struct ieee802154_radio_s *ieee, uint8_t mode) { FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; @@ -891,7 +889,7 @@ static int at86rf23x_setdevmode(FAR struct ieee802154_dev_s *ieee, uint8_t mode) * get the device mode type of the radio. * ****************************************************************************/ -static int at86rf23x_getdevmode (FAR struct ieee802154_dev_s *ieee, FAR uint8_t *mode) +static int at86rf23x_getdevmode (FAR struct ieee802154_radio_s *ieee, FAR uint8_t *mode) { FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; int val; @@ -900,11 +898,11 @@ static int at86rf23x_getdevmode (FAR struct ieee802154_dev_s *ieee, FAR uint8_t if(val == 1) { - mode = IEEE802154_MODE_PANCOORD; + *mode = IEEE802154_MODE_PANCOORD; } else { - mode = IEEE802154_MODE_DEVICE; + *mode = IEEE802154_MODE_DEVICE; } return OK; @@ -917,7 +915,7 @@ static int at86rf23x_getdevmode (FAR struct ieee802154_dev_s *ieee, FAR uint8_t * set the tx power attenuation or amplification * ****************************************************************************/ -static int at86rf23x_settxpower(FAR struct ieee802154_dev_s *ieee, int32_t txpwr) +static int at86rf23x_settxpower(FAR struct ieee802154_radio_s *ieee, int32_t txpwr) { FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; @@ -936,7 +934,7 @@ static int at86rf23x_settxpower(FAR struct ieee802154_dev_s *ieee, int32_t txpwr * get the tx power attenuation or amplification. * ****************************************************************************/ -static int at86rf23x_gettxpower(FAR struct ieee802154_dev_s *ieee, FAR int32_t *txpwr) +static int at86rf23x_gettxpower(FAR struct ieee802154_radio_s *ieee, FAR int32_t *txpwr) { /* TODO: this needs alot of work to make sure all chips can share this function */ FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; @@ -1010,7 +1008,7 @@ static int at86rf23x_gettxpower(FAR struct ieee802154_dev_s *ieee, FAR int32_t * * * ****************************************************************************/ -static int at86rf23x_setcca(FAR struct ieee802154_dev_s *ieee, FAR struct ieee802154_cca_s *cca) +static int at86rf23x_setcca(FAR struct ieee802154_radio_s *ieee, FAR struct ieee802154_cca_s *cca) { FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; @@ -1046,7 +1044,7 @@ static int at86rf23x_setcca(FAR struct ieee802154_dev_s *ieee, FAR struct ieee80 * Get CCA for ???: TODO: need to implement * ****************************************************************************/ -static int at86rf23x_getcca(FAR struct ieee802154_dev_s *ieee, FAR struct ieee802154_cca_s *cca) +static int at86rf23x_getcca(FAR struct ieee802154_radio_s *ieee, FAR struct ieee802154_cca_s *cca) { FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; @@ -1065,12 +1063,12 @@ static int at86rf23x_getcca(FAR struct ieee802154_dev_s *ieee, FAR struct ieee80 * Control operations for the radio. * ****************************************************************************/ -static int at86rf23x_ioctl(FAR struct ieee802154_dev_s *ieee, int cmd, unsigned long arg) +static int at86rf23x_ioctl(FAR struct ieee802154_radio_s *ieee, int cmd, unsigned long arg) { FAR struct at86rf23x_dev_s *dev = (FAR struct at86rf23x_dev_s *)ieee; switch(cmd) { - case MAC854IORDUMP: return at86rf23x_regdump(dev); + case 1000: return at86rf23x_regdump(dev); default: return -EINVAL; } } @@ -1081,7 +1079,7 @@ static int at86rf23x_ioctl(FAR struct ieee802154_dev_s *ieee, int cmd, unsigned * Perform energy detection scan. TODO: Need to implement. * ****************************************************************************/ -static int at86rf23x_energydetect(FAR struct ieee802154_dev_s *ieee, FAR uint8_t *energy) +static int at86rf23x_energydetect(FAR struct ieee802154_radio_s *ieee, FAR uint8_t *energy) { #warning at86rf23x_energydetect not implemented. @@ -1161,7 +1159,7 @@ static int at86rf23x_resetrf(FAR struct at86rf23x_dev_s *dev) * RX messages. * ****************************************************************************/ -static int at86rf23x_rxenable(FAR struct ieee802154_dev_s *ieee, bool state, +static int at86rf23x_rxenable(FAR struct ieee802154_radio_s *ieee, bool state, FAR struct ieee802154_packet_s *packet) { FAR struct at86rf23x_dev_s *dev = (FAR struct at86rf23x_dev_s *)ieee; @@ -1356,7 +1354,7 @@ static void at86rf23x_irqwork_tx(FAR struct at86rf23x_dev_s *dev) * transmission * ****************************************************************************/ -static int at86rf23x_transmit(FAR struct ieee802154_dev_s *ieee, FAR struct ieee802154_packet_s *packet) +static int at86rf23x_transmit(FAR struct ieee802154_radio_s *ieee, FAR struct ieee802154_packet_s *packet) { FAR struct at86rf23x_dev_s *dev = (FAR struct at86rf23x_dev_s *)ieee; /* @@ -1395,7 +1393,7 @@ static int at86rf23x_transmit(FAR struct ieee802154_dev_s *ieee, FAR struct ieee * ****************************************************************************/ -FAR struct ieee802154_dev_s *at86rf23x_init(FAR struct spi_dev_s *spi, FAR const struct at86rf23x_lower_s *lower) +FAR struct ieee802154_radio_s *at86rf23x_init(FAR struct spi_dev_s *spi, FAR const struct at86rf23x_lower_s *lower) { FAR struct at86rf23x_dev_s *dev; struct ieee802154_cca_s cca; diff --git a/include/nuttx/wireless/ieee802154/at86rf23x.h b/include/nuttx/wireless/ieee802154/at86rf23x.h index 974e2456e2..1ef6c909d2 100644 --- a/include/nuttx/wireless/ieee802154/at86rf23x.h +++ b/include/nuttx/wireless/ieee802154/at86rf23x.h @@ -90,7 +90,7 @@ extern "C" { * ****************************************************************************/ -FAR struct ieee802154_dev_s *at86rf23x_init(FAR struct spi_dev_s *spi, FAR const struct at86rf23x_lower_s *lower); +FAR struct ieee802154_radio_s *at86rf23x_init(FAR struct spi_dev_s *spi, FAR const struct at86rf23x_lower_s *lower); #undef EXTERN #ifdef __cplusplus -- GitLab From 5534e0c49311209316016643d37cdf54a0e207ea Mon Sep 17 00:00:00 2001 From: Leif Jakob Date: Fri, 10 Mar 2017 23:21:49 +0100 Subject: [PATCH 003/990] multiple fixes in nrf24l01 driver - signal POLLIN if there is already data in the FIFO - send ETIMEDOUT to userspace after 2 seconds if TX IRQ was not received - handle FIFO overflow - handle invalid pipes/empty FIFO - multiple cosmetics (missing static, duplicate define, missing \n) --- drivers/wireless/nrf24l01.c | 120 ++++++++++++++++++++++-------- include/nuttx/wireless/nrf24l01.h | 2 - 2 files changed, 89 insertions(+), 33 deletions(-) diff --git a/drivers/wireless/nrf24l01.c b/drivers/wireless/nrf24l01.c index 61378b1928..1c597d37ec 100644 --- a/drivers/wireless/nrf24l01.c +++ b/drivers/wireless/nrf24l01.c @@ -93,6 +93,9 @@ /* power-down -> standby transition timing (in us). Note: this value is probably larger than required. */ #define NRF24L01_TPD2STBY_DELAY 4500 +/* max time to wait for TX irq (in ms) */ +#define NRF24L01_MAX_TX_IRQ_WAIT 2000 + #define FIFO_PKTLEN_MASK 0x1F /* 5 ls bits used to store packet length */ #define FIFO_PKTLEN_SHIFT 0 #define FIFO_PIPENO_MASK 0xE0 /* 3 ms bits used to store pipe # */ @@ -134,6 +137,7 @@ struct nrf24l01_dev_s uint8_t last_recvpipeno; sem_t sem_tx; + bool tx_pending; /* is userspace waiting for TX IRQ? - accessor needs to hold lock on SPI bus */ #ifdef CONFIG_WL_NRF24L01_RXSUPPORT uint8_t *rx_fifo; /* Circular RX buffer. [pipe# / pkt_len] [packet data...] */ @@ -193,9 +197,9 @@ static int nrf24l01_unregister(FAR struct nrf24l01_dev_s *dev); #ifdef CONFIG_WL_NRF24L01_RXSUPPORT -void fifoput(struct nrf24l01_dev_s *dev, uint8_t pipeno, +static void fifoput(struct nrf24l01_dev_s *dev, uint8_t pipeno, FAR uint8_t *buffer, uint8_t buflen); -uint8_t fifoget(struct nrf24l01_dev_s *dev, FAR uint8_t *buffer, +static uint8_t fifoget(struct nrf24l01_dev_s *dev, FAR uint8_t *buffer, uint8_t buflen, FAR uint8_t *pipeno); static void nrf24l01_worker(FAR void *arg); @@ -419,7 +423,7 @@ static uint8_t nrf24l01_setregbit(struct nrf24l01_dev_s *dev, uint8_t reg, /* RX fifo mgt */ -void fifoput(struct nrf24l01_dev_s *dev, uint8_t pipeno, uint8_t *buffer, uint8_t buflen) +static void fifoput(struct nrf24l01_dev_s *dev, uint8_t pipeno, uint8_t *buffer, uint8_t buflen) { sem_wait(&dev->sem_fifo); while (dev->fifo_len + buflen + 1 > CONFIG_WL_NRF24L01_RXFIFO_LEN) @@ -447,14 +451,18 @@ void fifoput(struct nrf24l01_dev_s *dev, uint8_t pipeno, uint8_t *buffer, uint8_ sem_post(&dev->sem_fifo); } -uint8_t fifoget(struct nrf24l01_dev_s *dev, uint8_t *buffer, uint8_t buflen, uint8_t *pipeno) +static uint8_t fifoget(struct nrf24l01_dev_s *dev, uint8_t *buffer, uint8_t buflen, uint8_t *pipeno) { uint8_t pktlen; uint8_t i; sem_wait(&dev->sem_fifo); - ASSERT(dev->fifo_len > 0); + if ( dev->fifo_len == 0 ) /* sem_rx contains count of inserted packets in FIFO, but FIFO can overflow - fail smart */ + { + pktlen = 0; + goto no_data; + } pktlen = FIFO_PKTLEN(dev); if (NULL != pipeno) @@ -479,6 +487,7 @@ uint8_t fifoget(struct nrf24l01_dev_s *dev, uint8_t *buffer, uint8_t buflen, uin dev->fifo_len -= (pktlen + 1); + no_data: sem_post(&dev->sem_fifo); return pktlen; } @@ -489,7 +498,7 @@ static int nrf24l01_irqhandler(int irq, FAR void *context, FAR void *arg) { FAR struct nrf24l01_dev_s *dev = (FAR struct nrf24l01_dev_s *)arg; - winfo("*IRQ*"); + winfo("*IRQ*\n"); #ifdef CONFIG_WL_NRF24L01_RXSUPPORT @@ -548,6 +557,8 @@ static void nrf24l01_worker(FAR void *arg) winfo("RX_DR is set!\n"); + bool has_data = false; + /* Read and store all received payloads */ do @@ -563,6 +574,12 @@ static void nrf24l01_worker(FAR void *arg) */ pipeno = (status & NRF24L01_RX_P_NO_MASK) >> NRF24L01_RX_P_NO_SHIFT; + if ( pipeno >= NRF24L01_PIPE_COUNT ) /* 6=invalid 7=fifo empty */ + { + werr("invalid pipe rx: %d\n", (int)pipeno); + nrf24l01_flush_rx(dev); + break; + } pktlen = dev->pipedatalen[pipeno]; if (NRF24L01_DYN_LENGTH == pktlen) @@ -572,11 +589,19 @@ static void nrf24l01_worker(FAR void *arg) nrf24l01_access(dev, MODE_READ, NRF24L01_R_RX_PL_WID, &pktlen, 1); } + if ( pktlen > NRF24L01_MAX_PAYLOAD_LEN ) /* bad length */ + { + werr("invalid length in rx: %d\n", (int)pktlen); + nrf24l01_flush_rx(dev); + break; + } + /* Get payload content */ nrf24l01_access(dev, MODE_READ, NRF24L01_R_RX_PAYLOAD, buf, pktlen); fifoput(dev, pipeno, buf, pktlen); + has_data = true; sem_post(&dev->sem_rx); /* Wake-up any thread waiting in recv */ status = nrf24l01_readreg(dev, NRF24L01_FIFO_STATUS, &fifo_status, 1); @@ -584,32 +609,43 @@ static void nrf24l01_worker(FAR void *arg) winfo("FIFO_STATUS=%02x\n", fifo_status); winfo("STATUS=%02x\n", status); } - while (!(fifo_status | NRF24L01_RX_EMPTY)); - - /* Clear interrupt sources */ - - nrf24l01_writeregbyte(dev, NRF24L01_STATUS, NRF24L01_RX_DR); - - /* Restore CE */ - - nrf24l01_chipenable(dev, ce); + while ( !(fifo_status & NRF24L01_RX_EMPTY) ); /* 1=empty 0=more data */ #ifndef CONFIG_DISABLE_POLL - if (dev->pfd) + if (dev->pfd && has_data) { dev->pfd->revents |= POLLIN; /* Data available for input */ - winfo("Wake up polled fd"); + winfo("Wake up polled fd\n"); sem_post(dev->pfd->sem); } #endif + + /* Clear interrupt sources */ + + nrf24l01_writeregbyte(dev, NRF24L01_STATUS, NRF24L01_RX_DR); + + /* Restore CE */ + + nrf24l01_chipenable(dev, ce); } if (status & (NRF24L01_TX_DS | NRF24L01_MAX_RT)) { - /* The actual work is done in the send function */ + /* confirm send */ + + nrf24l01_chipenable(dev, false); - sem_post(&dev->sem_tx); + if ( dev->tx_pending ) + { + /* The actual work is done in the send function */ + + sem_post(&dev->sem_tx); + } + else + { + werr("invalid length in rx: %d\n", (int)pktlen); + } } if (dev->state == ST_RX) @@ -679,33 +715,40 @@ static int dosend(FAR struct nrf24l01_dev_s *dev, FAR const uint8_t *data, size_ nrf24l01_tostate(dev, ST_STANDBY); + /* flush old - can't harm */ + + nrf24l01_flush_tx(dev); + /* Write payload */ nrf24l01_access(dev, MODE_WRITE, NRF24L01_W_TX_PAYLOAD, (FAR uint8_t *)data, datalen); - /* Enable CE to start transmission */ - - nrf24l01_chipenable(dev, true); + dev->tx_pending = true; /* Free the SPI bus during the IRQ wait */ nrf24l01_unlock(dev->spi); - /* Wait for IRQ (TX_DS or MAX_RT) */ + /* cause rising CE edge to start transmission */ - while (sem_wait(&dev->sem_tx) != 0) - { - /* Note that we really need to wait here, as the interrupt source - * (either TX_DS in case of success, or MAX_RT for failure) needs to be cleared. - */ + nrf24l01_chipenable(dev, true); - DEBUGASSERT(errno == EINTR); - } + /* Wait for IRQ (TX_DS or MAX_RT) - but don't hang on lost IRQ */ + result = sem_tickwait(&dev->sem_tx, clock_systimer(), MSEC2TICK(NRF24L01_MAX_TX_IRQ_WAIT)); /* Re-acquire the SPI bus */ nrf24l01_lock(dev->spi); + dev->tx_pending = false; + + if ( result < 0 ) + { + werr("wait for irq failed\n"); + nrf24l01_flush_tx(dev); + goto out; + } + status = nrf24l01_readreg(dev, NRF24L01_OBSERVE_TX, &obsvalue, 1); if (status & NRF24L01_TX_DS) { @@ -719,7 +762,7 @@ static int dosend(FAR struct nrf24l01_dev_s *dev, FAR const uint8_t *data, size_ } else if (status & NRF24L01_MAX_RT) { - winfo("MAX_RT!\n", dev->lastxmitcount); + winfo("MAX_RT! (lastxmitcount=%d)\n", dev->lastxmitcount); result = -ECOMM; dev->lastxmitcount = NRF24L01_XMIT_MAXRT; @@ -735,10 +778,15 @@ static int dosend(FAR struct nrf24l01_dev_s *dev, FAR const uint8_t *data, size_ result = -EIO; } + out: + /* Clear interrupt sources */ nrf24l01_writeregbyte(dev, NRF24L01_STATUS, NRF24L01_TX_DS | NRF24L01_MAX_RT); + /* Clear fifo */ + nrf24l01_flush_tx(dev); + /* Restore state */ nrf24l01_tostate(dev, prevstate); @@ -1152,6 +1200,16 @@ static int nrf24l01_poll(FAR struct file *filep, FAR struct pollfd *fds, } dev->pfd = fds; + + /* is there is already data in the fifo? then trigger POLLIN now - don't wait for RX */ + sem_wait(&dev->sem_fifo); + if ( dev->fifo_len > 0 ) + { + dev->pfd->revents |= POLLIN; /* Data available for input */ + sem_post(dev->pfd->sem); + } + sem_post(&dev->sem_fifo); + } else /* Tear it down */ { diff --git a/include/nuttx/wireless/nrf24l01.h b/include/nuttx/wireless/nrf24l01.h index af17428d23..76ac27d0df 100644 --- a/include/nuttx/wireless/nrf24l01.h +++ b/include/nuttx/wireless/nrf24l01.h @@ -92,11 +92,9 @@ #ifdef NRF24L01_DEBUG # define werr(format, ...) _err(format, ##__VA_ARGS__) -# define werr(format, ...) _err(format, ##__VA_ARGS__) # define winfo(format, ...) _info(format, ##__VA_ARGS__) #else # define werr(x...) -# define werr(x...) # define winfo(x...) #endif -- GitLab From 34ebdfe51c592fc9127a641f222654852bc42985 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 10 Mar 2017 17:20:15 -0600 Subject: [PATCH 004/990] Update README --- configs/olimex-stm32-p407/README.txt | 39 +++++++++++++++++++++++----- 1 file changed, 32 insertions(+), 7 deletions(-) diff --git a/configs/olimex-stm32-p407/README.txt b/configs/olimex-stm32-p407/README.txt index 8ec5c47938..0302020f0b 100644 --- a/configs/olimex-stm32-p407/README.txt +++ b/configs/olimex-stm32-p407/README.txt @@ -20,25 +20,43 @@ Board Support The following peripherals are available in this configuration. - - LEDs: show the sytem status + - LEDs: Show the sytem status - Buttons: TAMPER-button, WKUP-button, J1-Joystick (consists of RIGHT-, - UP-, LEFT-, DOWN-, and CENTER-button). Built in app - 'buttons' works. + UP-, LEFT-, DOWN-, and CENTER-button). - ADC: ADC1 samples the red trim potentiometer AN_TR Built in app 'adc' works. - USB-FS-OTG: There is a USB-A-connector (host) connected to the full - speed STM32 inputs. + speed STM32 OTG inputs. - USB-HS-OTG: The other connector (device) is connected to the high speed - STM32 inputs. + STM32 OTG inputs. - - CAN: Built in app 'can' works, but apart from that not really tested. + - CAN: Built in app 'can' works, but apart from that not really + tested. - Ethernet: Ping to other station on the network works. + - microSD: Not fully functional. See below. + + - LCD: Nokia 6610. This is similar the Nokia 6100 LCD used on other + Olimex boards. There is a driver for that LCD at + drivers/lcd/nokia6100.c, however, it is not properly + integrated. It uses a 9-bit SPI interface which is difficult + to get working properly. + +- External Support is included for the onboard SRAM. It uses SRAM + SRAM: settings from another board that might need to be tweaked. + Difficult to test because the SRAM conflicts with both + RS232 ports. + +- Other: Buzzer, Camera, Temperature sensor, audio have not been + tested. + + If so, then it requires a 9-bit + microSD Card Interface ====================== @@ -205,6 +223,13 @@ OTGFS Host CONFIG_EXAMPLES_HIDKBD_DEVNAME="/dev/kbda" CONFIG_EXAMPLES_HIDKBD_STACKSIZE=1024 + STATUS: The MSC configurations seems fully functional. The HIDKBD seems rather + flaky. Sometimes the LEDs become very bright (indicating that it is being + swamped with interrupts). Data input is not clean with apps/examples/hidkbd: + There are missing characters and sometimes duplicated characters. This implies + some logic issues, probably in drivers/usbhost/usbhost_hidkbd, with polling and + data filtering. + Configurations ============== @@ -404,7 +429,7 @@ STATUS feature configurations. CCM memory is not included in the heap (CONFIG_STM32_CCMEXCLUDE=y) because - it does no suport DMA, leaving only 128KiB for program usage. + it does not suport DMA, leaving only 128KiB for program usage. 2107-01-23: Added the the knsh configuration and support for the PROTECTED build mode. -- GitLab From 04b2964eaceedbca633cb3dd3a5b39e94d31bdf3 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 10 Mar 2017 17:29:58 -0600 Subject: [PATCH 005/990] drivers/wireless/nrf24l01.c: Review last PR. Also got enthused and did major re-work to file to bring it closer to the NuttX coding style. Fixed a few compile time warnings. --- drivers/wireless/nrf24l01.c | 573 +++++++++++++++++++++++++++--------- 1 file changed, 430 insertions(+), 143 deletions(-) diff --git a/drivers/wireless/nrf24l01.c b/drivers/wireless/nrf24l01.c index 1c597d37ec..a667227e03 100644 --- a/drivers/wireless/nrf24l01.c +++ b/drivers/wireless/nrf24l01.c @@ -73,6 +73,8 @@ * Pre-processor Definitions ****************************************************************************/ +/* Configuration ************************************************************/ + #ifndef CONFIG_WL_NRF24L01_DFLT_ADDR_WIDTH # define CONFIG_WL_NRF24L01_DFLT_ADDR_WIDTH 5 #endif @@ -81,19 +83,32 @@ # define CONFIG_WL_NRF24L01_RXFIFO_LEN 128 #endif +#if defined(CONFIG_WL_NRF24L01_RXSUPPORT) && !defined(CONFIG_SCHED_HPWORK) +# error RX support requires CONFIG_SCHED_HPWORK +#endif + #ifdef CONFIG_WL_NRF24L01_CHECK_PARAMS # define CHECK_ARGS(cond) do { if (!(cond)) return -EINVAL; } while (0) #else # define CHECK_ARGS(cond) #endif -/* Default SPI bus frequency (in Hz) */ -#define NRF24L01_SPIFREQ 9000000 /* Can go up to 10 Mbs according to datasheet */ +/* NRF24L01 Definitions *****************************************************/ + +/* Default SPI bus frequency (in Hz). + * Can go up to 10 Mbs according to datasheet. + */ + +#define NRF24L01_SPIFREQ 9000000 + +/* power-down -> standby transition timing (in us). Note: this value is + * probably larger than required. + */ -/* power-down -> standby transition timing (in us). Note: this value is probably larger than required. */ #define NRF24L01_TPD2STBY_DELAY 4500 -/* max time to wait for TX irq (in ms) */ +/* Max time to wait for TX irq (in ms) */ + #define NRF24L01_MAX_TX_IRQ_WAIT 2000 #define FIFO_PKTLEN_MASK 0x1F /* 5 ls bits used to store packet length */ @@ -124,7 +139,7 @@ struct nrf24l01_dev_s FAR struct spi_dev_s *spi; /* Reference to SPI bus device */ FAR struct nrf24l01_config_s *config; /* Board specific GPIO functions */ - nrf24l01_state_t state; /* Current state of the nRF24L01 */ + nrf24l01_state_t state; /* Current state of the nRF24L01 */ uint8_t en_aa; /* Cache EN_AA register value */ uint8_t en_pipes; /* Cache EN_RXADDR register value */ @@ -137,7 +152,8 @@ struct nrf24l01_dev_s uint8_t last_recvpipeno; sem_t sem_tx; - bool tx_pending; /* is userspace waiting for TX IRQ? - accessor needs to hold lock on SPI bus */ + bool tx_pending; /* Is userspace waiting for TX IRQ? - accessor + * needs to hold lock on SPI bus */ #ifdef CONFIG_WL_NRF24L01_RXSUPPORT uint8_t *rx_fifo; /* Circular RX buffer. [pipe# / pkt_len] [packet data...] */ @@ -160,6 +176,7 @@ struct nrf24l01_dev_s /**************************************************************************** * Private Function Prototypes ****************************************************************************/ + /* Low-level SPI helpers */ static inline void nrf24l01_configspi(FAR struct spi_dev_s *spi); @@ -196,13 +213,15 @@ static int dosend(FAR struct nrf24l01_dev_s *dev, FAR const uint8_t *data, static int nrf24l01_unregister(FAR struct nrf24l01_dev_s *dev); #ifdef CONFIG_WL_NRF24L01_RXSUPPORT - static void fifoput(struct nrf24l01_dev_s *dev, uint8_t pipeno, FAR uint8_t *buffer, uint8_t buflen); static uint8_t fifoget(struct nrf24l01_dev_s *dev, FAR uint8_t *buffer, uint8_t buflen, FAR uint8_t *pipeno); static void nrf24l01_worker(FAR void *arg); +#endif +#ifdef NRF24L01_DEBUG +static void binarycvt(char *deststr, const uint8_t *srcbin, size_t srclen) #endif /* POSIX API */ @@ -215,8 +234,10 @@ static ssize_t nrf24l01_write(FAR struct file *filep, FAR const char *buffer, size_t buflen); static int nrf24l01_ioctl(FAR struct file *filep, int cmd, unsigned long arg); +#ifndef CONFIG_DISABLE_POLL static int nrf24l01_poll(FAR struct file *filep, FAR struct pollfd *fds, bool setup); +#endif /**************************************************************************** * Private Data @@ -229,12 +250,12 @@ static const struct file_operations nrf24l01_fops = nrf24l01_read, /* read */ nrf24l01_write, /* write */ NULL, /* seek */ - nrf24l01_ioctl, /* ioctl */ + nrf24l01_ioctl /* ioctl */ #ifndef CONFIG_DISABLE_POLL - nrf24l01_poll, /* poll */ + , nrf24l01_poll /* poll */ #endif #ifndef CONFIG_DISABLE_PSEUDOFS_OPERATIONS - NULL /* unlink */ + , NULL /* unlink */ #endif }; @@ -242,6 +263,10 @@ static const struct file_operations nrf24l01_fops = * Private Functions ****************************************************************************/ +/**************************************************************************** + * Name: nrf24l01_lock + ****************************************************************************/ + static void nrf24l01_lock(FAR struct spi_dev_s *spi) { /* Lock the SPI bus because there are multiple devices competing for the @@ -315,18 +340,31 @@ static inline void nrf24l01_configspi(FAR struct spi_dev_s *spi) SPI_SELECT(spi, SPIDEV_WIRELESS, false); } +/**************************************************************************** + * Name: nrf24l01_select + ****************************************************************************/ + static inline void nrf24l01_select(struct nrf24l01_dev_s * dev) { SPI_SELECT(dev->spi, SPIDEV_WIRELESS, true); } +/**************************************************************************** + * Name: nrf24l01_deselect + ****************************************************************************/ + static inline void nrf24l01_deselect(struct nrf24l01_dev_s * dev) { SPI_SELECT(dev->spi, SPIDEV_WIRELESS, false); } +/**************************************************************************** + * Name: nrf24l01_access + ****************************************************************************/ + static uint8_t nrf24l01_access(FAR struct nrf24l01_dev_s *dev, - nrf24l01_access_mode_t mode, uint8_t cmd, FAR uint8_t *buf, int length) + nrf24l01_access_mode_t mode, uint8_t cmd, + FAR uint8_t *buf, int length) { uint8_t status; @@ -356,52 +394,92 @@ static uint8_t nrf24l01_access(FAR struct nrf24l01_dev_s *dev, return status; } +/**************************************************************************** + * Name: nrf24l01_flush_rx + ****************************************************************************/ + static inline uint8_t nrf24l01_flush_rx(struct nrf24l01_dev_s *dev) { return nrf24l01_access(dev, MODE_WRITE, NRF24L01_FLUSH_RX, NULL, 0); } +/**************************************************************************** + * Name: nrf24l01_flush_tx + ****************************************************************************/ + static inline uint8_t nrf24l01_flush_tx(struct nrf24l01_dev_s *dev) { return nrf24l01_access(dev, MODE_WRITE, NRF24L01_FLUSH_TX, NULL, 0); } -/* Read register from nrf24l01 */ +/**************************************************************************** + * Name: nrf24l01_readreg + * + * Description: + * Read register from nrf24l01 + * + ****************************************************************************/ -static inline uint8_t nrf24l01_readreg(struct nrf24l01_dev_s *dev, uint8_t reg, - uint8_t *value, int len) +static inline uint8_t nrf24l01_readreg(struct nrf24l01_dev_s *dev, + uint8_t reg, FAR uint8_t *value, + int len) { - return nrf24l01_access(dev, MODE_READ, reg | NRF24L01_R_REGISTER, value, len); + return nrf24l01_access(dev, MODE_READ, reg | NRF24L01_R_REGISTER, + value, len); } -/* Read single byte value from a register of nrf24l01 */ +/**************************************************************************** + * Name: nrf24l01_readregbyte + * + * Description: + * Read single byte value from a register of nrf24l01 + * + ****************************************************************************/ static inline uint8_t nrf24l01_readregbyte(struct nrf24l01_dev_s *dev, - uint8_t reg) + uint8_t reg) { uint8_t val; nrf24l01_readreg(dev, reg, &val, 1); return val; } -/* Write value to a register of nrf24l01 */ +/**************************************************************************** + * Name: nrf24l01_writereg + * + * Description: + * Write value to a register of nrf24l01 + * + ****************************************************************************/ -static inline int nrf24l01_writereg(FAR struct nrf24l01_dev_s *dev, uint8_t reg, - FAR const uint8_t *value, int len) +static inline int nrf24l01_writereg(FAR struct nrf24l01_dev_s *dev, + uint8_t reg, FAR const uint8_t *value, + int len) { - return nrf24l01_access(dev, MODE_WRITE, reg | NRF24L01_W_REGISTER, (FAR uint8_t *)value, len); + return nrf24l01_access(dev, MODE_WRITE, reg | NRF24L01_W_REGISTER, + (FAR uint8_t *)value, len); } -/* Write single byte value to a register of nrf24l01 */ +/**************************************************************************** + * Name: nrf24l01_writeregbyte + * + * Description: + * Write single byte value to a register of nrf24l01 + * + ****************************************************************************/ -static inline void nrf24l01_writeregbyte(struct nrf24l01_dev_s *dev, uint8_t reg, - uint8_t value) +static inline void nrf24l01_writeregbyte(FAR struct nrf24l01_dev_s *dev, + uint8_t reg, uint8_t value) { nrf24l01_writereg(dev, reg, &value, 1); } -static uint8_t nrf24l01_setregbit(struct nrf24l01_dev_s *dev, uint8_t reg, - uint8_t value, bool set) +/**************************************************************************** + * Name: nrf24l01_setregbit + ****************************************************************************/ + +static uint8_t nrf24l01_setregbit(FAR struct nrf24l01_dev_s *dev, + uint8_t reg, uint8_t value, bool set) { uint8_t val; @@ -419,11 +497,17 @@ static uint8_t nrf24l01_setregbit(struct nrf24l01_dev_s *dev, uint8_t reg, return val; } -#ifdef CONFIG_WL_NRF24L01_RXSUPPORT - -/* RX fifo mgt */ +/**************************************************************************** + * Name: fifoput + * + * Description: + * RX fifo mgt + * + ****************************************************************************/ -static void fifoput(struct nrf24l01_dev_s *dev, uint8_t pipeno, uint8_t *buffer, uint8_t buflen) +#ifdef CONFIG_WL_NRF24L01_RXSUPPORT +static void fifoput(FAR struct nrf24l01_dev_s *dev, uint8_t pipeno, + FAR uint8_t *buffer, uint8_t buflen) { sem_wait(&dev->sem_fifo); while (dev->fifo_len + buflen + 1 > CONFIG_WL_NRF24L01_RXFIFO_LEN) @@ -451,14 +535,23 @@ static void fifoput(struct nrf24l01_dev_s *dev, uint8_t pipeno, uint8_t *buffer, sem_post(&dev->sem_fifo); } -static uint8_t fifoget(struct nrf24l01_dev_s *dev, uint8_t *buffer, uint8_t buflen, uint8_t *pipeno) +/**************************************************************************** + * Name: fifoget + ****************************************************************************/ + +static uint8_t fifoget(FAR struct nrf24l01_dev_s *dev, FAR uint8_t *buffer, + uint8_t buflen, uint8_t *pipeno) { uint8_t pktlen; uint8_t i; sem_wait(&dev->sem_fifo); - if ( dev->fifo_len == 0 ) /* sem_rx contains count of inserted packets in FIFO, but FIFO can overflow - fail smart */ + /* sem_rx contains count of inserted packets in FIFO, but FIFO can + * overflow - fail smart. + */ + + if (dev->fifo_len == 0) { pktlen = 0; goto no_data; @@ -491,9 +584,12 @@ static uint8_t fifoget(struct nrf24l01_dev_s *dev, uint8_t *buffer, uint8_t bufl sem_post(&dev->sem_fifo); return pktlen; } - #endif +/**************************************************************************** + * Name: nrf24l01_irqhandler + ****************************************************************************/ + static int nrf24l01_irqhandler(int irq, FAR void *context, FAR void *arg) { FAR struct nrf24l01_dev_s *dev = (FAR struct nrf24l01_dev_s *)arg; @@ -501,12 +597,10 @@ static int nrf24l01_irqhandler(int irq, FAR void *context, FAR void *arg) winfo("*IRQ*\n"); #ifdef CONFIG_WL_NRF24L01_RXSUPPORT - /* If RX is enabled we delegate the actual work to bottom-half handler */ work_queue(HPWORK, &dev->irq_work, nrf24l01_worker, dev, 0); #else - /* Otherwise we simply wake up the send function */ sem_post(&dev->sem_tx); /* Wake up the send function */ @@ -515,7 +609,13 @@ static int nrf24l01_irqhandler(int irq, FAR void *context, FAR void *arg) return OK; } -/* Configure IRQ pin (falling edge) */ +/**************************************************************************** + * Name: nrf24l01_attachirq + * + * Description: + * Configure IRQ pin (falling edge) + * + ****************************************************************************/ static inline int nrf24l01_attachirq(FAR struct nrf24l01_dev_s *dev, xcpt_t isr, FAR void *arg) @@ -523,7 +623,12 @@ static inline int nrf24l01_attachirq(FAR struct nrf24l01_dev_s *dev, xcpt_t isr, return dev->config->irqattach(isr, arg); } -static inline bool nrf24l01_chipenable(FAR struct nrf24l01_dev_s *dev, bool enable) +/**************************************************************************** + * Name: nrf24l01_chipenable + ****************************************************************************/ + +static inline bool nrf24l01_chipenable(FAR struct nrf24l01_dev_s *dev, + bool enable) { if (dev->ce_enabled != enable) { @@ -537,8 +642,11 @@ static inline bool nrf24l01_chipenable(FAR struct nrf24l01_dev_s *dev, bool enab } } -#ifdef CONFIG_WL_NRF24L01_RXSUPPORT +/**************************************************************************** + * Name: nrf24l01_worker + ****************************************************************************/ +#ifdef CONFIG_WL_NRF24L01_RXSUPPORT static void nrf24l01_worker(FAR void *arg) { FAR struct nrf24l01_dev_s *dev = (FAR struct nrf24l01_dev_s *) arg; @@ -551,14 +659,15 @@ static void nrf24l01_worker(FAR void *arg) if (status & NRF24L01_RX_DR) { - /* put CE low */ + /* Put CE low */ bool ce = nrf24l01_chipenable(dev, false); +#ifndef CONFIG_DISABLE_POLL + bool has_data = false; +#endif winfo("RX_DR is set!\n"); - bool has_data = false; - /* Read and store all received payloads */ do @@ -574,7 +683,7 @@ static void nrf24l01_worker(FAR void *arg) */ pipeno = (status & NRF24L01_RX_P_NO_MASK) >> NRF24L01_RX_P_NO_SHIFT; - if ( pipeno >= NRF24L01_PIPE_COUNT ) /* 6=invalid 7=fifo empty */ + if (pipeno >= NRF24L01_PIPE_COUNT) /* 6=invalid 7=fifo empty */ { werr("invalid pipe rx: %d\n", (int)pipeno); nrf24l01_flush_rx(dev); @@ -584,12 +693,14 @@ static void nrf24l01_worker(FAR void *arg) pktlen = dev->pipedatalen[pipeno]; if (NRF24L01_DYN_LENGTH == pktlen) { - /* If dynamic length payload need to use R_RX_PL_WID command to get actual length */ + /* If dynamic length payload need to use R_RX_PL_WID command + * to get actual length. + */ nrf24l01_access(dev, MODE_READ, NRF24L01_R_RX_PL_WID, &pktlen, 1); } - if ( pktlen > NRF24L01_MAX_PAYLOAD_LEN ) /* bad length */ + if (pktlen > NRF24L01_MAX_PAYLOAD_LEN) /* bad length */ { werr("invalid length in rx: %d\n", (int)pktlen); nrf24l01_flush_rx(dev); @@ -601,7 +712,9 @@ static void nrf24l01_worker(FAR void *arg) nrf24l01_access(dev, MODE_READ, NRF24L01_R_RX_PAYLOAD, buf, pktlen); fifoput(dev, pipeno, buf, pktlen); +#ifndef CONFIG_DISABLE_POLL has_data = true; +#endif sem_post(&dev->sem_rx); /* Wake-up any thread waiting in recv */ status = nrf24l01_readreg(dev, NRF24L01_FIFO_STATUS, &fifo_status, 1); @@ -609,7 +722,7 @@ static void nrf24l01_worker(FAR void *arg) winfo("FIFO_STATUS=%02x\n", fifo_status); winfo("STATUS=%02x\n", status); } - while ( !(fifo_status & NRF24L01_RX_EMPTY) ); /* 1=empty 0=more data */ + while ((fifo_status & NRF24L01_RX_EMPTY) == 0); #ifndef CONFIG_DISABLE_POLL if (dev->pfd && has_data) @@ -632,11 +745,11 @@ static void nrf24l01_worker(FAR void *arg) if (status & (NRF24L01_TX_DS | NRF24L01_MAX_RT)) { - /* confirm send */ + /* Confirm send */ nrf24l01_chipenable(dev, false); - if ( dev->tx_pending ) + if (dev->tx_pending) { /* The actual work is done in the send function */ @@ -650,16 +763,21 @@ static void nrf24l01_worker(FAR void *arg) if (dev->state == ST_RX) { - /* re-enable CE (to go back to RX mode state) */ + /* Re-enable CE (to go back to RX mode state) */ nrf24l01_chipenable(dev, true); } + nrf24l01_unlock(dev->spi); } - #endif -static void nrf24l01_tostate(struct nrf24l01_dev_s *dev, nrf24l01_state_t state) +/**************************************************************************** + * Name: nrf24l01_tostate + ****************************************************************************/ + +static void nrf24l01_tostate(struct nrf24l01_dev_s *dev, + nrf24l01_state_t state) { nrf24l01_state_t oldstate = dev->state; @@ -670,7 +788,7 @@ static void nrf24l01_tostate(struct nrf24l01_dev_s *dev, nrf24l01_state_t state) if (oldstate == ST_POWER_DOWN) { - /* Leaving power down (note: new state cannot be power down here) */ + /* Leaving power down (note: new state cannot be power down here) */ nrf24l01_setregbit(dev, NRF24L01_CONFIG, NRF24L01_PWR_UP, true); usleep(NRF24L01_TPD2STBY_DELAY); @@ -703,25 +821,33 @@ static void nrf24l01_tostate(struct nrf24l01_dev_s *dev, nrf24l01_state_t state) dev->state = state; } -static int dosend(FAR struct nrf24l01_dev_s *dev, FAR const uint8_t *data, size_t datalen) +/**************************************************************************** + * Name: dosend + ****************************************************************************/ + +static int dosend(FAR struct nrf24l01_dev_s *dev, FAR const uint8_t *data, + size_t datalen) { uint8_t status; uint8_t obsvalue; int result; - /* Store the current lifecycle state in order to restore it after transmit done */ + /* Store the current lifecycle state in order to restore it after transmit + * done. + */ nrf24l01_state_t prevstate = dev->state; nrf24l01_tostate(dev, ST_STANDBY); - /* flush old - can't harm */ + /* Flush old - can't harm */ nrf24l01_flush_tx(dev); /* Write payload */ - nrf24l01_access(dev, MODE_WRITE, NRF24L01_W_TX_PAYLOAD, (FAR uint8_t *)data, datalen); + nrf24l01_access(dev, MODE_WRITE, NRF24L01_W_TX_PAYLOAD, + (FAR uint8_t *)data, datalen); dev->tx_pending = true; @@ -729,12 +855,14 @@ static int dosend(FAR struct nrf24l01_dev_s *dev, FAR const uint8_t *data, size_ nrf24l01_unlock(dev->spi); - /* cause rising CE edge to start transmission */ + /* Cause rising CE edge to start transmission */ nrf24l01_chipenable(dev, true); /* Wait for IRQ (TX_DS or MAX_RT) - but don't hang on lost IRQ */ - result = sem_tickwait(&dev->sem_tx, clock_systimer(), MSEC2TICK(NRF24L01_MAX_TX_IRQ_WAIT)); + + result = sem_tickwait(&dev->sem_tx, clock_systimer(), + MSEC2TICK(NRF24L01_MAX_TX_IRQ_WAIT)); /* Re-acquire the SPI bus */ @@ -742,17 +870,17 @@ static int dosend(FAR struct nrf24l01_dev_s *dev, FAR const uint8_t *data, size_ dev->tx_pending = false; - if ( result < 0 ) - { - werr("wait for irq failed\n"); - nrf24l01_flush_tx(dev); - goto out; - } + if (result < 0) + { + werr("wait for irq failed\n"); + nrf24l01_flush_tx(dev); + goto out; + } status = nrf24l01_readreg(dev, NRF24L01_OBSERVE_TX, &obsvalue, 1); if (status & NRF24L01_TX_DS) { - /* transmit OK */ + /* Transmit OK */ result = OK; dev->lastxmitcount = (obsvalue & NRF24L01_ARC_CNT_MASK) @@ -766,7 +894,9 @@ static int dosend(FAR struct nrf24l01_dev_s *dev, FAR const uint8_t *data, size_ result = -ECOMM; dev->lastxmitcount = NRF24L01_XMIT_MAXRT; - /* If no ACK packet is received the payload remains in TX fifo. We need to flush it. */ + /* If no ACK packet is received the payload remains in TX fifo. We + * need to flush it. + */ nrf24l01_flush_tx(dev); } @@ -778,13 +908,14 @@ static int dosend(FAR struct nrf24l01_dev_s *dev, FAR const uint8_t *data, size_ result = -EIO; } - out: +out: /* Clear interrupt sources */ nrf24l01_writeregbyte(dev, NRF24L01_STATUS, NRF24L01_TX_DS | NRF24L01_MAX_RT); /* Clear fifo */ + nrf24l01_flush_tx(dev); /* Restore state */ @@ -793,7 +924,31 @@ static int dosend(FAR struct nrf24l01_dev_s *dev, FAR const uint8_t *data, size_ return result; } -/* POSIX API */ +/**************************************************************************** + * Name: binarycvt + ****************************************************************************/ + +#ifdef NRF24L01_DEBUG +static void binarycvt(char *deststr, const uint8_t *srcbin, size_t srclen) +{ + int i = 0; + while (i < srclen) + { + sprintf(deststr + i*2, "%02x", srcbin[i]); + ++i; + } + + *(deststr + i*2) = '\0'; +} +#endif + +/**************************************************************************** + * POSIX API + ****************************************************************************/ + +/**************************************************************************** + * Name: nrf24l01_open + ****************************************************************************/ static int nrf24l01_open(FAR struct file *filep) { @@ -838,6 +993,10 @@ errout: return result; } +/**************************************************************************** + * Name: nrf24l01_close + ****************************************************************************/ + static int nrf24l01_close(FAR struct file *filep) { FAR struct inode *inode; @@ -867,7 +1026,12 @@ static int nrf24l01_close(FAR struct file *filep) return OK; } -static ssize_t nrf24l01_read(FAR struct file *filep, FAR char *buffer, size_t buflen) +/**************************************************************************** + * Name: nrf24l01_read + ****************************************************************************/ + +static ssize_t nrf24l01_read(FAR struct file *filep, FAR char *buffer, + size_t buflen) { #ifndef CONFIG_WL_NRF24L01_RXSUPPORT return -ENOSYS; @@ -896,7 +1060,12 @@ static ssize_t nrf24l01_read(FAR struct file *filep, FAR char *buffer, size_t bu #endif } -static ssize_t nrf24l01_write(FAR struct file *filep, FAR const char *buffer, size_t buflen) +/**************************************************************************** + * Name: nrf24l01_write + ****************************************************************************/ + +static ssize_t nrf24l01_write(FAR struct file *filep, FAR const char *buffer, + size_t buflen) { FAR struct nrf24l01_dev_s *dev; FAR struct inode *inode; @@ -922,6 +1091,10 @@ static ssize_t nrf24l01_write(FAR struct file *filep, FAR const char *buffer, si return result; } +/**************************************************************************** + * Name: nrf24l01_ioctl + ****************************************************************************/ + static int nrf24l01_ioctl(FAR struct file *filep, int cmd, unsigned long arg) { FAR struct inode *inode; @@ -949,7 +1122,8 @@ static int nrf24l01_ioctl(FAR struct file *filep, int cmd, unsigned long arg) switch (cmd) { - case WLIOC_SETRADIOFREQ: /* Set radio frequency. Arg: Pointer to uint32_t frequency value */ + case WLIOC_SETRADIOFREQ: /* Set radio frequency. Arg: Pointer to + * uint32_t frequency value */ { FAR uint32_t *ptr = (FAR uint32_t *)((uintptr_t)arg); DEBUGASSERT(ptr != NULL); @@ -958,7 +1132,8 @@ static int nrf24l01_ioctl(FAR struct file *filep, int cmd, unsigned long arg) } break; - case WLIOC_GETRADIOFREQ: /* Get current radio frequency. arg: Pointer to uint32_t frequency value */ + case WLIOC_GETRADIOFREQ: /* Get current radio frequency. arg: Pointer + * to uint32_t frequency value */ { FAR uint32_t *ptr = (FAR uint32_t *)((uintptr_t)arg); DEBUGASSERT(ptr != NULL); @@ -966,7 +1141,8 @@ static int nrf24l01_ioctl(FAR struct file *filep, int cmd, unsigned long arg) } break; - case NRF24L01IOC_SETTXADDR: /* Set current TX addr. arg: Pointer to uint8_t array defining the address */ + case NRF24L01IOC_SETTXADDR: /* Set current TX addr. arg: Pointer to + * uint8_t array defining the address */ { FAR const uint8_t *addr = (FAR const uint8_t *)(arg); DEBUGASSERT(addr != NULL); @@ -974,7 +1150,8 @@ static int nrf24l01_ioctl(FAR struct file *filep, int cmd, unsigned long arg) } break; - case NRF24L01IOC_GETTXADDR: /* Get current TX addr. arg: Pointer to uint8_t array defining the address */ + case NRF24L01IOC_GETTXADDR: /* Get current TX addr. arg: Pointer to + * uint8_t array defining the address */ { FAR uint8_t *addr = (FAR uint8_t *)(arg); DEBUGASSERT(addr != NULL); @@ -982,7 +1159,8 @@ static int nrf24l01_ioctl(FAR struct file *filep, int cmd, unsigned long arg) } break; - case WLIOC_SETTXPOWER: /* Set current radio frequency. arg: Pointer to int32_t, output power */ + case WLIOC_SETTXPOWER: /* Set current radio frequency. arg: Pointer + * to int32_t, output power */ { FAR int32_t *ptr = (FAR int32_t *)(arg); DEBUGASSERT(ptr != NULL); @@ -990,7 +1168,8 @@ static int nrf24l01_ioctl(FAR struct file *filep, int cmd, unsigned long arg) } break; - case WLIOC_GETTXPOWER: /* Get current radio frequency. arg: Pointer to int32_t, output power */ + case WLIOC_GETTXPOWER: /* Get current radio frequency. arg: Pointer + * to int32_t, output power */ { FAR int32_t *ptr = (FAR int32_t *)(arg); DEBUGASSERT(ptr != NULL); @@ -998,7 +1177,8 @@ static int nrf24l01_ioctl(FAR struct file *filep, int cmd, unsigned long arg) } break; - case NRF24L01IOC_SETRETRCFG: /* Set retransmit params. arg: Pointer to nrf24l01_retrcfg_t */ + case NRF24L01IOC_SETRETRCFG: /* Set retransmit params. arg: Pointer + * to nrf24l01_retrcfg_t */ { FAR nrf24l01_retrcfg_t *ptr = (FAR nrf24l01_retrcfg_t *)(arg); DEBUGASSERT(ptr != NULL); @@ -1006,7 +1186,8 @@ static int nrf24l01_ioctl(FAR struct file *filep, int cmd, unsigned long arg) } break; - case NRF24L01IOC_GETRETRCFG: /* Get retransmit params. arg: Pointer to nrf24l01_retrcfg_t */ + case NRF24L01IOC_GETRETRCFG: /* Get retransmit params. arg: Pointer + * to nrf24l01_retrcfg_t */ result = -ENOSYS; /* TODO */ break; @@ -1146,13 +1327,17 @@ static int nrf24l01_ioctl(FAR struct file *filep, int cmd, unsigned long arg) return result; } -#ifndef CONFIG_DISABLE_POLL +/**************************************************************************** + * Name: nrf24l01_poll + ****************************************************************************/ +#ifndef CONFIG_DISABLE_POLL static int nrf24l01_poll(FAR struct file *filep, FAR struct pollfd *fds, - bool setup) + bool setup) { #ifndef CONFIG_WL_NRF24L01_RXSUPPORT /* Polling is currently implemented for data input only */ + return -ENOSYS; #else @@ -1190,7 +1375,8 @@ static int nrf24l01_poll(FAR struct file *filep, FAR struct pollfd *fds, } /* Check if we can accept this poll. - * For now, only one thread can poll the device at any time (shorter / simpler code) + * For now, only one thread can poll the device at any time + * (shorter / simpler code) */ if (dev->pfd) @@ -1201,17 +1387,20 @@ static int nrf24l01_poll(FAR struct file *filep, FAR struct pollfd *fds, dev->pfd = fds; - /* is there is already data in the fifo? then trigger POLLIN now - don't wait for RX */ + /* Is there is already data in the fifo? then trigger POLLIN now - + * don't wait for RX. + */ + sem_wait(&dev->sem_fifo); - if ( dev->fifo_len > 0 ) - { + if (dev->fifo_len > 0) + { dev->pfd->revents |= POLLIN; /* Data available for input */ sem_post(dev->pfd->sem); - } - sem_post(&dev->sem_fifo); + } + sem_post(&dev->sem_fifo); } - else /* Tear it down */ + else /* Tear it down */ { dev->pfd = NULL; } @@ -1221,9 +1410,12 @@ errout: return result; #endif } - #endif +/**************************************************************************** + * Name: nrf24l01_unregister + ****************************************************************************/ + static int nrf24l01_unregister(FAR struct nrf24l01_dev_s *dev) { CHECK_ARGS(dev); @@ -1246,7 +1438,12 @@ static int nrf24l01_unregister(FAR struct nrf24l01_dev_s *dev) * Public Functions ****************************************************************************/ -int nrf24l01_register(FAR struct spi_dev_s *spi, FAR struct nrf24l01_config_s *cfg) +/**************************************************************************** + * Name: nrf24l01_register + ****************************************************************************/ + +int nrf24l01_register(FAR struct spi_dev_s *spi, + FAR struct nrf24l01_config_s *cfg) { FAR struct nrf24l01_dev_s *dev; int result = OK; @@ -1262,18 +1459,18 @@ int nrf24l01_register(FAR struct spi_dev_s *spi, FAR struct nrf24l01_config_s *c return -ENOMEM; } - dev->spi = spi; - dev->config = cfg; + dev->spi = spi; + dev->config = cfg; - dev->state = ST_UNKNOWN; - dev->en_aa = 0; + dev->state = ST_UNKNOWN; + dev->en_aa = 0; dev->ce_enabled = false; sem_init(&(dev->devsem), 0, 1); - dev->nopens = 0; + dev->nopens = 0; #ifndef CONFIG_DISABLE_POLL - dev->pfd = NULL; + dev->pfd = NULL; #endif sem_init(&dev->sem_tx, 0, 0); @@ -1286,10 +1483,10 @@ int nrf24l01_register(FAR struct spi_dev_s *spi, FAR struct nrf24l01_config_s *c return -ENOMEM; } - dev->rx_fifo = rx_fifo; - dev->nxt_read = 0; - dev->nxt_write = 0; - dev->fifo_len = 0; + dev->rx_fifo = rx_fifo; + dev->nxt_read = 0; + dev->nxt_write = 0; + dev->fifo_len = 0; sem_init(&(dev->sem_fifo), 0, 1); sem_init(&(dev->sem_rx), 0, 0); @@ -1314,7 +1511,13 @@ int nrf24l01_register(FAR struct spi_dev_s *spi, FAR struct nrf24l01_config_s *c return result; } -/* (re)set the device in a default initial state */ +/**************************************************************************** + * Name: nrf24l01_init + * + * Description: + * (Re)set the device in a default initial state + * + ****************************************************************************/ int nrf24l01_init(FAR struct nrf24l01_dev_s *dev) { @@ -1346,7 +1549,9 @@ int nrf24l01_init(FAR struct nrf24l01_dev_s *dev) features = nrf24l01_readregbyte(dev, NRF24L01_FEATURE); if (0 == features) { - /* If FEATURES reg is still unset here, consider there is no actual hardware */ + /* If FEATURES reg is still unset here, consider there is no + * actual hardware. + */ result = -ENODEV; goto out; @@ -1365,7 +1570,8 @@ int nrf24l01_init(FAR struct nrf24l01_dev_s *dev) /* Set addr width to default */ dev->addrlen = CONFIG_WL_NRF24L01_DFLT_ADDR_WIDTH; - nrf24l01_writeregbyte(dev, NRF24L01_SETUP_AW, CONFIG_WL_NRF24L01_DFLT_ADDR_WIDTH - 2); + nrf24l01_writeregbyte(dev, NRF24L01_SETUP_AW, + CONFIG_WL_NRF24L01_DFLT_ADDR_WIDTH - 2); /* Get pipe #0 addr */ @@ -1388,11 +1594,17 @@ out: return result; } -int nrf24l01_setpipeconfig(FAR struct nrf24l01_dev_s *dev, unsigned int pipeno, - FAR const nrf24l01_pipecfg_t *pipecfg) +/**************************************************************************** + * Name: nrf24l01_setpipeconfig + ****************************************************************************/ + +int nrf24l01_setpipeconfig(FAR struct nrf24l01_dev_s *dev, + unsigned int pipeno, + FAR const nrf24l01_pipecfg_t *pipecfg) { bool dynlength; bool en_aa; + int addrlen; CHECK_ARGS(dev && pipecfg && pipeno < NRF24L01_PIPE_COUNT); @@ -1404,10 +1616,13 @@ int nrf24l01_setpipeconfig(FAR struct nrf24l01_dev_s *dev, unsigned int pipeno, nrf24l01_lock(dev->spi); - /* Set addr */ + /* Set addr + * Pipe 0 & 1 are the only ones to have a full length address. + */ - int addrlen = (pipeno <= 1) ? dev->addrlen : 1; /* Pipe 0 & 1 are the only ones to have a full length address */ - nrf24l01_writereg(dev, NRF24L01_RX_ADDR_P0 + pipeno, pipecfg->rx_addr, addrlen); + addrlen = (pipeno <= 1) ? dev->addrlen : 1; + nrf24l01_writereg(dev, NRF24L01_RX_ADDR_P0 + pipeno, pipecfg->rx_addr, + addrlen); /* Auto ack */ @@ -1427,27 +1642,38 @@ int nrf24l01_setpipeconfig(FAR struct nrf24l01_dev_s *dev, unsigned int pipeno, nrf24l01_setregbit(dev, NRF24L01_DYNPD, 1 << pipeno, dynlength); if (!dynlength) { - nrf24l01_writeregbyte(dev, NRF24L01_RX_PW_P0 + pipeno, pipecfg->payload_length); + nrf24l01_writeregbyte(dev, NRF24L01_RX_PW_P0 + pipeno, + pipecfg->payload_length); } + nrf24l01_unlock(dev->spi); dev->pipedatalen[pipeno] = pipecfg->payload_length; return OK; } -int nrf24l01_getpipeconfig(FAR struct nrf24l01_dev_s *dev, unsigned int pipeno, - FAR nrf24l01_pipecfg_t *pipecfg) +/**************************************************************************** + * Name: nrf24l01_getpipeconfig + ****************************************************************************/ + +int nrf24l01_getpipeconfig(FAR struct nrf24l01_dev_s *dev, + unsigned int pipeno, + FAR nrf24l01_pipecfg_t *pipecfg) { bool dynlength; + int addrlen; CHECK_ARGS(dev && pipecfg && pipeno < NRF24L01_PIPE_COUNT); nrf24l01_lock(dev->spi); - /* Get pipe address */ + /* Get pipe address. + * Pipe 0 & 1 are the only ones to have a full length address. + */ - int addrlen = (pipeno <= 1) ? dev->addrlen : 1; /* Pipe 0 & 1 are the only ones to have a full length address */ - nrf24l01_readreg(dev, NRF24L01_RX_ADDR_P0 + pipeno, pipecfg->rx_addr, addrlen); + addrlen = (pipeno <= 1) ? dev->addrlen : 1; + nrf24l01_readreg(dev, NRF24L01_RX_ADDR_P0 + pipeno, pipecfg->rx_addr, + addrlen); /* Auto ack */ @@ -1471,7 +1697,12 @@ int nrf24l01_getpipeconfig(FAR struct nrf24l01_dev_s *dev, unsigned int pipeno, return OK; } -int nrf24l01_enablepipe(FAR struct nrf24l01_dev_s *dev, unsigned int pipeno, bool enable) +/**************************************************************************** + * Name: nrf24l01_enablepipe + ****************************************************************************/ + +int nrf24l01_enablepipe(FAR struct nrf24l01_dev_s *dev, unsigned int pipeno, + bool enable) { CHECK_ARGS(dev && pipeno < NRF24L01_PIPE_COUNT); @@ -1503,7 +1734,12 @@ int nrf24l01_enablepipe(FAR struct nrf24l01_dev_s *dev, unsigned int pipeno, boo return OK; } -int nrf24l01_settxaddr(FAR struct nrf24l01_dev_s *dev, FAR const uint8_t *txaddr) +/**************************************************************************** + * Name: nrf24l01_settxaddr + ****************************************************************************/ + +int nrf24l01_settxaddr(FAR struct nrf24l01_dev_s *dev, + FAR const uint8_t *txaddr) { CHECK_ARGS(dev && txaddr); @@ -1514,6 +1750,10 @@ int nrf24l01_settxaddr(FAR struct nrf24l01_dev_s *dev, FAR const uint8_t *txaddr return OK; } +/**************************************************************************** + * Name: nrf24l01_gettxaddr + ****************************************************************************/ + int nrf24l01_gettxaddr(FAR struct nrf24l01_dev_s *dev, FAR uint8_t *txaddr) { CHECK_ARGS(dev && txaddr); @@ -1525,7 +1765,13 @@ int nrf24l01_gettxaddr(FAR struct nrf24l01_dev_s *dev, FAR uint8_t *txaddr) return OK; } -int nrf24l01_setretransmit(FAR struct nrf24l01_dev_s *dev, nrf24l01_retransmit_delay_t retrdelay, uint8_t retrcount) +/**************************************************************************** + * Name: nrf24l01_setretransmit + ****************************************************************************/ + +int nrf24l01_setretransmit(FAR struct nrf24l01_dev_s *dev, + nrf24l01_retransmit_delay_t retrdelay, + uint8_t retrcount) { uint8_t val; @@ -1540,12 +1786,16 @@ int nrf24l01_setretransmit(FAR struct nrf24l01_dev_s *dev, nrf24l01_retransmit_d return OK; } +/**************************************************************************** + * Name: nrf24l01_settxpower + ****************************************************************************/ + int nrf24l01_settxpower(FAR struct nrf24l01_dev_s *dev, int outpower) { uint8_t value; uint8_t hwpow; - /** RF_PWR value <-> Output power in dBm + /* RF_PWR value <-> Output power in dBm * * '00' – -18dBm * '01' – -12dBm @@ -1587,6 +1837,10 @@ int nrf24l01_settxpower(FAR struct nrf24l01_dev_s *dev, int outpower) return OK; } +/**************************************************************************** + * Name: nrf24l01_gettxpower + ****************************************************************************/ + int nrf24l01_gettxpower(FAR struct nrf24l01_dev_s *dev) { uint8_t value; @@ -1601,7 +1855,12 @@ int nrf24l01_gettxpower(FAR struct nrf24l01_dev_s *dev) return powers[value]; } -int nrf24l01_setdatarate(FAR struct nrf24l01_dev_s *dev, nrf24l01_datarate_t datarate) +/**************************************************************************** + * Name: nrf24l01_setdatarate + ****************************************************************************/ + +int nrf24l01_setdatarate(FAR struct nrf24l01_dev_s *dev, + nrf24l01_datarate_t datarate) { uint8_t value; @@ -1629,6 +1888,10 @@ int nrf24l01_setdatarate(FAR struct nrf24l01_dev_s *dev, nrf24l01_datarate_t dat return OK; } +/**************************************************************************** + * Name: nrf24l01_setradiofreq + ****************************************************************************/ + int nrf24l01_setradiofreq(FAR struct nrf24l01_dev_s *dev, uint32_t freq) { uint8_t value; @@ -1642,6 +1905,10 @@ int nrf24l01_setradiofreq(FAR struct nrf24l01_dev_s *dev, uint32_t freq) return OK; } +/**************************************************************************** + * Name: nrf24l01_getradiofreq + ****************************************************************************/ + uint32_t nrf24l01_getradiofreq(FAR struct nrf24l01_dev_s *dev) { int rffreq; @@ -1655,6 +1922,10 @@ uint32_t nrf24l01_getradiofreq(FAR struct nrf24l01_dev_s *dev) return rffreq + NRF24L01_MIN_FREQ; } +/**************************************************************************** + * Name: nrf24l01_setaddrwidth + ****************************************************************************/ + int nrf24l01_setaddrwidth(FAR struct nrf24l01_dev_s *dev, uint32_t width) { CHECK_ARGS(dev && width <= NRF24L01_MAX_ADDR_LEN && width >= NRF24L01_MIN_ADDR_LEN); @@ -1666,6 +1937,10 @@ int nrf24l01_setaddrwidth(FAR struct nrf24l01_dev_s *dev, uint32_t width) return OK; } +/**************************************************************************** + * Name: nrf24l01_changestate + ****************************************************************************/ + int nrf24l01_changestate(FAR struct nrf24l01_dev_s *dev, nrf24l01_state_t state) { nrf24l01_lock(dev->spi); @@ -1674,7 +1949,12 @@ int nrf24l01_changestate(FAR struct nrf24l01_dev_s *dev, nrf24l01_state_t state) return OK; } -int nrf24l01_send(FAR struct nrf24l01_dev_s *dev, FAR const uint8_t *data, size_t datalen) +/**************************************************************************** + * Name: nrf24l01_send + ****************************************************************************/ + +int nrf24l01_send(FAR struct nrf24l01_dev_s *dev, FAR const uint8_t *data, + size_t datalen) { int result; @@ -1688,8 +1968,12 @@ int nrf24l01_send(FAR struct nrf24l01_dev_s *dev, FAR const uint8_t *data, size_ return result; } +/**************************************************************************** + * Name: nrf24l01_sendto + ****************************************************************************/ + int nrf24l01_sendto(FAR struct nrf24l01_dev_s *dev, FAR const uint8_t *data, - size_t datalen, FAR const uint8_t *destaddr) + size_t datalen, FAR const uint8_t *destaddr) { bool pipeaddrchg = false; int result; @@ -1704,7 +1988,8 @@ int nrf24l01_sendto(FAR struct nrf24l01_dev_s *dev, FAR const uint8_t *data, if ((dev->en_aa & 1) && (memcmp(destaddr, dev->pipe0addr, dev->addrlen))) { winfo("Change pipe #0 addr to dest addr\n"); - nrf24l01_writereg(dev, NRF24L01_RX_ADDR_P0, destaddr, NRF24L01_MAX_ADDR_LEN); + nrf24l01_writereg(dev, NRF24L01_RX_ADDR_P0, destaddr, + NRF24L01_MAX_ADDR_LEN); pipeaddrchg = true; } @@ -1714,7 +1999,8 @@ int nrf24l01_sendto(FAR struct nrf24l01_dev_s *dev, FAR const uint8_t *data, { /* Restore pipe #0 addr */ - nrf24l01_writereg(dev, NRF24L01_RX_ADDR_P0, dev->pipe0addr, NRF24L01_MAX_ADDR_LEN); + nrf24l01_writereg(dev, NRF24L01_RX_ADDR_P0, dev->pipe0addr, + NRF24L01_MAX_ADDR_LEN); winfo("Pipe #0 default addr restored\n"); } @@ -1722,43 +2008,41 @@ int nrf24l01_sendto(FAR struct nrf24l01_dev_s *dev, FAR const uint8_t *data, return result; } +/**************************************************************************** + * Name: nrf24l01_lastxmitcount + ****************************************************************************/ + int nrf24l01_lastxmitcount(FAR struct nrf24l01_dev_s *dev) { return dev->lastxmitcount; } -#ifdef CONFIG_WL_NRF24L01_RXSUPPORT +/**************************************************************************** + * Name: nrf24l01_recv + ****************************************************************************/ +#ifdef CONFIG_WL_NRF24L01_RXSUPPORT ssize_t nrf24l01_recv(struct nrf24l01_dev_s *dev, uint8_t *buffer, - size_t buflen, uint8_t *recvpipe) + size_t buflen, uint8_t *recvpipe) { if (sem_wait(&dev->sem_rx) != 0) { - /* This should only happen if the wait was canceled by an signal */ + /* This should only happen if the wait was canceled by an signal */ - DEBUGASSERT(errno == EINTR); - return -EINTR; + DEBUGASSERT(errno == EINTR); + return -EINTR; } return fifoget(dev, buffer, buflen, recvpipe); } - #endif -#ifdef NRF24L01_DEBUG -static void binarycvt(char *deststr, const uint8_t *srcbin, size_t srclen) -{ - int i = 0; - while (i < srclen) - { - sprintf(deststr + i*2, "%02x", srcbin[i]); - ++i; - } - - *(deststr + i*2) = '\0'; -} +/**************************************************************************** + * Name: nrf24l01_dumpregs + ****************************************************************************/ +#ifdef NRF24L01_DEBUG void nrf24l01_dumpregs(struct nrf24l01_dev_s *dev) { uint8_t addr[NRF24L01_MAX_ADDR_LEN]; @@ -1810,14 +2094,17 @@ void nrf24l01_dumpregs(struct nrf24l01_dev_s *dev) syslog(LOG_INFO, "FEATURE: %02x\n", nrf24l01_readregbyte(dev, NRF24L01_FEATURE)); } +#endif /* NRF24L01_DEBUG */ -#ifdef CONFIG_WL_NRF24L01_RXSUPPORT +/**************************************************************************** + * Name: nrf24l01_dumprxfifo + ****************************************************************************/ + +#if defined(NRF24L01_DEBUG) && defined(CONFIG_WL_NRF24L01_RXSUPPORT) void nrf24l01_dumprxfifo(struct nrf24l01_dev_s *dev) { syslog(LOG_INFO, "bytes count: %d\n", dev->fifo_len); syslog(LOG_INFO, "next read: %d, next write: %d\n", dev->nxt_read, dev-> nxt_write); } -#endif - -#endif +#endif /* NRF24L01_DEBUG && CONFIG_WL_NRF24L01_RXSUPPORT */ -- GitLab From 852b189910f268d9e0962dd5b94b38c7b7707359 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 10 Mar 2017 17:46:19 -0600 Subject: [PATCH 006/990] STM32 F33 ADC: Correct bad definitions of base addresses; Fix naming collision by changing colliding STM32_ADC12_BASE to STM32_ADC12_CMN_BASE --- arch/arm/src/stm32/chip/stm32f33xxx_adc.h | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/arch/arm/src/stm32/chip/stm32f33xxx_adc.h b/arch/arm/src/stm32/chip/stm32f33xxx_adc.h index ddfbd97d1f..7094732e76 100644 --- a/arch/arm/src/stm32/chip/stm32f33xxx_adc.h +++ b/arch/arm/src/stm32/chip/stm32f33xxx_adc.h @@ -49,13 +49,13 @@ * Pre-processor Definitions ****************************************************************************************************/ -#define STM32_ADC1_BASE_OFFSET 0x0000 -#define STM32_ADC2_BASE_OFFSET 0x0100 -#define STM32_ADC12_BASE_OFFSET 0x0300 +#define STM32_ADC1_OFFSET 0x0000 +#define STM32_ADC2_OFFSET 0x0100 +#define STM32_ADC12_CMN_OFFSET 0x0300 -#define STM32_ADC1_BASE (STM32_ADC1_BASE_OFFSET+STM32_ADC12_BASE) /* ADC1 Master ADC */ -#define STM32_ADC2_BASE (STM32_ADC1_BASE_OFFSET+STM32_ADC12_BASE) /* ADC2 Slave ADC */ -#define STM32_ADC12_BASE (STM32_ADC1_BASE_OFFSET+STM32_ADC12_BASE) /* ADC1, ADC2 common */ +#define STM32_ADC1_BASE (STM32_ADC1_OFFSET+STM32_ADC12_BASE) /* ADC1 Master ADC */ +#define STM32_ADC2_BASE (STM32_ADC2_OFFSET+STM32_ADC12_BASE) /* ADC2 Slave ADC */ +#define STM32_ADC12_CMN_BASE (STM32_ADC12_CMN_OFFSET+STM32_ADC12_BASE) /* ADC1, ADC2 common */ /* Register Offsets *********************************************************************************/ -- GitLab From aadf6c6e167cf564a238543a2102a76991196f92 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 10 Mar 2017 17:49:32 -0600 Subject: [PATCH 007/990] STM32 F33: Fix another error in ADC base address usage. --- arch/arm/src/stm32/chip/stm32f33xxx_adc.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/arch/arm/src/stm32/chip/stm32f33xxx_adc.h b/arch/arm/src/stm32/chip/stm32f33xxx_adc.h index 7094732e76..b6609d0828 100644 --- a/arch/arm/src/stm32/chip/stm32f33xxx_adc.h +++ b/arch/arm/src/stm32/chip/stm32f33xxx_adc.h @@ -151,9 +151,9 @@ #define STM32_ADC2_DIFSEL (STM32_ADC2_BASE+STM32_ADC_DIFSEL_OFFSET) #define STM32_ADC2_CALFACT (STM32_ADC2_BASE+STM32_ADC_CALFACT_OFFSET) -#define STM32_ADC12_CSR (STM32_ADC12_BASE+STM32_ADC_CSR_OFFSET) -#define STM32_ADC12_CCR (STM32_ADC12_BASE+STM32_ADC_CCR_OFFSET) -#define STM32_ADC12_CDR (STM32_ADC12_BASE+STM32_ADC_CDR_OFFSET) +#define STM32_ADC12_CSR (STM32_ADC12_CMN_BASE+STM32_ADC_CSR_OFFSET) +#define STM32_ADC12_CCR (STM32_ADC12_CMN_BASE+STM32_ADC_CCR_OFFSET) +#define STM32_ADC12_CDR (STM32_ADC12_CMN_BASE+STM32_ADC_CDR_OFFSET) /* Register Bitfield Definitions ********************************************************************/ /* ADC interrupt and status register (ISR) and ADC interrupt enable register (IER) */ -- GitLab From a1c0117103ebe15c20c07357a255e0208231f203 Mon Sep 17 00:00:00 2001 From: Simon Piriou Date: Sat, 11 Mar 2017 12:22:04 +0100 Subject: [PATCH 008/990] photon: add iwdg timer support --- configs/photon/Kconfig | 40 +++++++ configs/photon/nsh/defconfig | 23 +++- configs/photon/src/Makefile | 4 + configs/photon/src/photon.h | 18 +++ configs/photon/src/photon_wdt.c | 179 +++++++++++++++++++++++++++++ configs/photon/src/stm32_appinit.c | 24 +++- 6 files changed, 283 insertions(+), 5 deletions(-) create mode 100644 configs/photon/src/photon_wdt.c diff --git a/configs/photon/Kconfig b/configs/photon/Kconfig index 9958fb2b4c..408fbc81d4 100644 --- a/configs/photon/Kconfig +++ b/configs/photon/Kconfig @@ -11,4 +11,44 @@ config PHOTON_DFU_BOOTLOADER ---help--- Build image that can be uploaded using stock DFU bootloader. +config PHOTON_WDG + bool + +config PHOTON_IWDG + bool "Photon iwdg kicker support" + depends on STM32_IWDG + depends on WATCHDOG + select PHOTON_WDG + +config PHOTON_IWDG_TIMEOUT + int "Photon iwdg Timeout (ms)" + default 32000 + depends on PHOTON_IWDG + ---help--- + Watchdog timeout value in milliseconds. + +if PHOTON_WDG +config PHOTON_WDG_THREAD + bool "Watchdog Deamon Thread" + +if PHOTON_WDG_THREAD +config PHOTON_WDG_THREAD_NAME + string "Watchdog Thread Name" + default "wdog" + +config PHOTON_WDG_THREAD_INTERVAL + int "Watchdog Thread Interval (ms)" + default 2500 + +config PHOTON_WDG_THREAD_PRIORITY + int "Watchdog Thread Priority" + default 200 + +config PHOTON_WDG_THREAD_STACKSIZE + int "Watchdog Thread Stacksize" + default 1024 + +endif # PHOTON_WDG_THREAD +endif # PHOTON_WDG + endif diff --git a/configs/photon/nsh/defconfig b/configs/photon/nsh/defconfig index f331713db7..9e808a75f3 100644 --- a/configs/photon/nsh/defconfig +++ b/configs/photon/nsh/defconfig @@ -429,7 +429,7 @@ CONFIG_STM32_USART1=y # CONFIG_STM32_UART4 is not set # CONFIG_STM32_UART5 is not set # CONFIG_STM32_USART6 is not set -# CONFIG_STM32_IWDG is not set +CONFIG_STM32_IWDG=y # CONFIG_STM32_WWDG is not set # CONFIG_STM32_NOEXT_VECTORS is not set @@ -574,8 +574,21 @@ CONFIG_ARCH_BOARD="photon" # Board-Specific Options # CONFIG_PHOTON_DFU_BOOTLOADER=y +CONFIG_PHOTON_WDG=y +CONFIG_PHOTON_IWDG=y +CONFIG_PHOTON_IWDG_TIMEOUT=32000 +CONFIG_PHOTON_WDG_THREAD=y +CONFIG_PHOTON_WDG_THREAD_NAME="wdog" +CONFIG_PHOTON_WDG_THREAD_INTERVAL=2500 +CONFIG_PHOTON_WDG_THREAD_PRIORITY=200 +CONFIG_PHOTON_WDG_THREAD_STACKSIZE=1024 # CONFIG_BOARD_CRASHDUMP is not set -# CONFIG_LIB_BOARDCTL is not set +CONFIG_LIB_BOARDCTL=y +# CONFIG_BOARDCTL_RESET is not set +# CONFIG_BOARDCTL_UNIQUEID is not set +# CONFIG_BOARDCTL_TSCTEST is not set +# CONFIG_BOARDCTL_GRAPHICS is not set +# CONFIG_BOARDCTL_IOCTL is not set # # RTOS Features @@ -718,7 +731,8 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y # CONFIG_TIMER is not set # CONFIG_ONESHOT is not set # CONFIG_RTC is not set -# CONFIG_WATCHDOG is not set +CONFIG_WATCHDOG=y +CONFIG_WATCHDOG_DEVPATH="/dev/watchdog0" # CONFIG_ANALOG is not set # CONFIG_AUDIO_DEVICES is not set # CONFIG_VIDEO_DEVICES is not set @@ -1090,6 +1104,7 @@ CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_TELNETD is not set # CONFIG_EXAMPLES_TIFF is not set # CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_USBTERM is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set @@ -1229,7 +1244,7 @@ CONFIG_NSH_FILEIOSIZE=512 # CONFIG_NSH_CONSOLE=y # CONFIG_NSH_ALTCONDEV is not set -# CONFIG_NSH_ARCHINIT is not set +CONFIG_NSH_ARCHINIT=y # CONFIG_NSH_LOGIN is not set # CONFIG_NSH_CONSOLE_LOGIN is not set diff --git a/configs/photon/src/Makefile b/configs/photon/src/Makefile index 3413b18ba6..6fa80bdf05 100644 --- a/configs/photon/src/Makefile +++ b/configs/photon/src/Makefile @@ -41,6 +41,10 @@ ifeq ($(CONFIG_PHOTON_DFU_BOOTLOADER),y) CSRCS += dfu_signature.c endif +ifeq ($(CONFIG_PHOTON_WDG),y) +CSRCS += photon_wdt.c +endif + ifeq ($(CONFIG_NSH_LIBRARY),y) CSRCS += stm32_appinit.c endif diff --git a/configs/photon/src/photon.h b/configs/photon/src/photon.h index b2540c616a..b04068d911 100644 --- a/configs/photon/src/photon.h +++ b/configs/photon/src/photon.h @@ -62,5 +62,23 @@ * Public Functions ****************************************************************************/ +/**************************************************************************** + * Name: photon_watchdog_initialize() + * + * Description: + * Perform architecture-specific initialization of the Watchdog hardware. + * + * Input parameters: + * None + * + * Returned Value: + * Zero on success; a negated errno value on failure. + * + ****************************************************************************/ + +#ifdef CONFIG_PHOTON_WDG +int photon_watchdog_initialize(void); +#endif + #endif /* __ASSEMBLY__ */ #endif /* __CONFIGS_PHOTON_SRC_PHOTON_H */ diff --git a/configs/photon/src/photon_wdt.c b/configs/photon/src/photon_wdt.c new file mode 100644 index 0000000000..beee501404 --- /dev/null +++ b/configs/photon/src/photon_wdt.c @@ -0,0 +1,179 @@ +/************************************************************************************ + * configs/photon/src/photon_wdt.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Simon Piriou + * + * 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 +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* Configuration *******************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/* Watchdog daemon thread */ + +#if defined(CONFIG_PHOTON_WDG_THREAD) + +static int wdog_daemon(int argc, char *argv[]) +{ + int fd; + int ret; + + /* Open watchdog device */ + + fd = open(CONFIG_WATCHDOG_DEVPATH, O_RDONLY); + + if (fd < 0) + { + wderr("ERROR: open %s failed: %d\n", CONFIG_WATCHDOG_DEVPATH, errno); + return ERROR; + } + + /* Start watchdog timer */ + + ret = ioctl(fd, WDIOC_START, 0); + + if (ret < 0) + { + wderr("ERROR: ioctl(WDIOC_START) failed: %d\n", errno); + goto exit_close_dev; + } + + while(1) + { + usleep((CONFIG_PHOTON_WDG_THREAD_INTERVAL)*1000); + + /* Send keep alive ioctl */ + + ret = ioctl(fd, WDIOC_KEEPALIVE, 0); + + if (ret < 0) + { + wderr("ERROR: ioctl(WDIOC_KEEPALIVE) failed: %d\n", errno); + break; + } + } + +exit_close_dev: + + /* Close watchdog device and exit. */ + close(fd); + return ret; +} + +#endif /* CONFIG_PHOTON_WDG_THREAD */ + +/**************************************************************************** + * Name: photon_watchdog_initialize() + * + * Description: + * Perform architecture-specific initialization of the Watchdog hardware. + * This interface must be provided by all configurations using + * apps/examples/watchdog + * + ****************************************************************************/ + +int photon_watchdog_initialize(void) +{ + int fd; + int ret = 0; + + /* Open the watchdog device */ + + fd = open(CONFIG_WATCHDOG_DEVPATH, O_RDONLY); + if (fd < 0) + { + wderr("ERROR: open %s failed: %d\n", CONFIG_WATCHDOG_DEVPATH, errno); + return ERROR; + } + + /* Set the watchdog timeout */ + +#ifdef CONFIG_PHOTON_IWDG + wdinfo("Timeout = %d.\n", CONFIG_PHOTON_IWDG_TIMEOUT); + ret = ioctl(fd, WDIOC_SETTIMEOUT, (unsigned long)CONFIG_PHOTON_IWDG_TIMEOUT); +#else +# error "No watchdog configured" +#endif + + /* Close watchdog as it is not needed here anymore */ + + close(fd); + + if (ret < 0) + { + wderr("ERROR: watchdog configuration failed: %d\n", errno); + return ret; + } + +#if defined(CONFIG_PHOTON_WDG_THREAD) + + /* Spawn wdog deamon thread */ + + int taskid = kernel_thread(CONFIG_PHOTON_WDG_THREAD_NAME, + CONFIG_PHOTON_WDG_THREAD_PRIORITY, + CONFIG_PHOTON_WDG_THREAD_STACKSIZE, + (main_t)wdog_daemon, (FAR char * const *)NULL); + + if (taskid <= 0) + { + wderr("ERROR: cannot spawn wdog_daemon thread\n"); + return ERROR; + } + +#endif /* CONFIG_PHOTON_WDG_THREAD */ + + return OK; +} diff --git a/configs/photon/src/stm32_appinit.c b/configs/photon/src/stm32_appinit.c index 6fc07a0f51..40ac5e3fa7 100644 --- a/configs/photon/src/stm32_appinit.c +++ b/configs/photon/src/stm32_appinit.c @@ -40,8 +40,13 @@ #include #include +#include #include "photon.h" +#include +#include + +#include "stm32_wdg.h" /**************************************************************************** * Pre-processor Definitions @@ -82,5 +87,22 @@ int board_app_initialize(uintptr_t arg) { - return OK; + int ret = OK; + +#ifdef CONFIG_STM32_IWDG + stm32_iwdginitialize("/dev/watchdog0", STM32_LSI_FREQUENCY); +#endif + +#ifdef CONFIG_PHOTON_WDG + + /* Start WDG kicker thread */ + + ret = photon_watchdog_initialize(); + if (ret != OK) + { + serr("Failed to start watchdog thread: %d\n", errno); + return ret; + } +#endif + return ret; } -- GitLab From f542e168473f2c5ae8579fc02ddab8383753b7d4 Mon Sep 17 00:00:00 2001 From: Simon Piriou Date: Sat, 11 Mar 2017 14:14:35 +0100 Subject: [PATCH 009/990] photon: add usb otg hs support and usbnsh app --- configs/photon/src/Makefile | 4 + configs/photon/src/photon.h | 13 + configs/photon/src/stm32_boot.c | 12 + configs/photon/src/stm32_usb.c | 91 +++ configs/photon/usbnsh/Make.defs | 116 +++ configs/photon/usbnsh/defconfig | 1319 +++++++++++++++++++++++++++++++ configs/photon/usbnsh/setenv.sh | 84 ++ 7 files changed, 1639 insertions(+) create mode 100644 configs/photon/src/stm32_usb.c create mode 100644 configs/photon/usbnsh/Make.defs create mode 100644 configs/photon/usbnsh/defconfig create mode 100755 configs/photon/usbnsh/setenv.sh diff --git a/configs/photon/src/Makefile b/configs/photon/src/Makefile index 6fa80bdf05..ae24c7d4c0 100644 --- a/configs/photon/src/Makefile +++ b/configs/photon/src/Makefile @@ -45,6 +45,10 @@ ifeq ($(CONFIG_PHOTON_WDG),y) CSRCS += photon_wdt.c endif +ifeq ($(CONFIG_STM32_OTGHS),y) +CSRCS += stm32_usb.c +endif + ifeq ($(CONFIG_NSH_LIBRARY),y) CSRCS += stm32_appinit.c endif diff --git a/configs/photon/src/photon.h b/configs/photon/src/photon.h index b04068d911..5678dc7c1f 100644 --- a/configs/photon/src/photon.h +++ b/configs/photon/src/photon.h @@ -80,5 +80,18 @@ int photon_watchdog_initialize(void); #endif +/**************************************************************************** + * Name: stm32_usbinitialize + * + * Description: + * Called from stm32_usbinitialize very early in initialization to setup + * USB-related GPIO pins for the Photon board. + * + ****************************************************************************/ + +#ifdef CONFIG_STM32_OTGHS +void weak_function stm32_usbinitialize(void); +#endif + #endif /* __ASSEMBLY__ */ #endif /* __CONFIGS_PHOTON_SRC_PHOTON_H */ diff --git a/configs/photon/src/stm32_boot.c b/configs/photon/src/stm32_boot.c index 3b70208962..c9dfe28729 100644 --- a/configs/photon/src/stm32_boot.c +++ b/configs/photon/src/stm32_boot.c @@ -61,4 +61,16 @@ void stm32_boardinitialize(void) { +#ifdef CONFIG_STM32_OTGHS + /* Initialize USB if the 1) OTG HS controller is in the configuration and 2) + * disabled, and 3) the weak function stm32_usbinitialize() has been brought + * into the build. Presumably either CONFIG_USBDEV or CONFIG_USBHOST is also + * selected. + */ + + if (stm32_usbinitialize) + { + stm32_usbinitialize(); + } +#endif } diff --git a/configs/photon/src/stm32_usb.c b/configs/photon/src/stm32_usb.c new file mode 100644 index 0000000000..5dc24d5ed8 --- /dev/null +++ b/configs/photon/src/stm32_usb.c @@ -0,0 +1,91 @@ +/************************************************************************************ + * configs/photon/src/stm32_usb.c + * + * Copyright (C) 2012-2013, 2015, 2017 Gregory Nutt. 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 "photon.h" +#include + +#include +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/************************************************************************************ + * Private Data + ************************************************************************************/ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_usbinitialize + * + * Description: + * Called from stm32_usbinitialize very early in inialization to setup USB-related + * GPIO pins for the Photon board. + * + ************************************************************************************/ + +void stm32_usbinitialize(void) +{ +} + +/************************************************************************************ + * Name: stm32_usbsuspend + * + * Description: + * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is + * used. This function is called whenever the USB enters or leaves suspend mode. + * This is an opportunity for the board logic to shutdown clocks, power, etc. + * while the USB is suspended. + * + ************************************************************************************/ + +#ifdef CONFIG_USBDEV +void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) +{ + uinfo("resume: %d\n", resume); +} +#endif diff --git a/configs/photon/usbnsh/Make.defs b/configs/photon/usbnsh/Make.defs new file mode 100644 index 0000000000..cb2820a9cb --- /dev/null +++ b/configs/photon/usbnsh/Make.defs @@ -0,0 +1,116 @@ +############################################################################ +# configs/photon/usbnsh/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. +# +############################################################################ + +include ${TOPDIR}/.config +include ${TOPDIR}/tools/Config.mk +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs + +ifeq ($(CONFIG_PHOTON_DFU_BOOTLOADER),y) +LDSCRIPT = photon_dfu.ld +else +LDSCRIPT = ld.script +endif + +ifeq ($(WINTOOL),y) + # Windows-native toolchains + DIRLINK = $(TOPDIR)/tools/copydir.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mkwindeps.sh + ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" + ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" +else + # Linux/Cygwin-native toolchain + MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT) + ARCHINCLUDES = -I. -isystem $(TOPDIR)/include + ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) +endif + +CC = $(CROSSDEV)gcc +CXX = $(CROSSDEV)g++ +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(ARCROSSDEV)ar rcs +NM = $(ARCROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump + +ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} +ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} + +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + ARCHOPTIMIZATION = -g +endif + +ifneq ($(CONFIG_DEBUG_NOOPT),y) + ARCHOPTIMIZATION += $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer +endif + +ARCHCFLAGS = -fno-builtin +ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fcheck-new -fno-rtti +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow -Wundef +ARCHWARNINGSXX = -Wall -Wshadow -Wundef +ARCHDEFINES = +ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 + +CFLAGS = $(ARCHCFLAGS) $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) +CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +NXFLATLDFLAGS1 = -r -d -warn-common +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections +LDNXFLATFLAGS = -e main -s 2048 + +ASMEXT = .S +OBJEXT = .o +LIBEXT = .a +EXEEXT = + +ifneq ($(CROSSDEV),arm-nuttx-elf-) + LDFLAGS += -nostartfiles -nodefaultlibs +endif +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + LDFLAGS += -g +endif + + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -Wundef -g -pipe +HOSTLDFLAGS = diff --git a/configs/photon/usbnsh/defconfig b/configs/photon/usbnsh/defconfig new file mode 100644 index 0000000000..c6326b54df --- /dev/null +++ b/configs/photon/usbnsh/defconfig @@ -0,0 +1,1319 @@ +# +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# + +# +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set +# CONFIG_DEFAULT_SMALL is not set +CONFIG_HOST_LINUX=y +# CONFIG_HOST_OSX is not set +# CONFIG_HOST_WINDOWS is not set +# CONFIG_HOST_OTHER is not set + +# +# Build Configuration +# +CONFIG_APPS_DIR="../apps" +CONFIG_BUILD_FLAT=y +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +CONFIG_INTELHEX_BINARY=y +# CONFIG_MOTOROLA_SREC is not set +CONFIG_RAW_BINARY=y +# CONFIG_UBOOT_UIMAGE is not set + +# +# Customize Header Files +# +# CONFIG_ARCH_STDINT_H is not set +# CONFIG_ARCH_STDBOOL_H is not set +# CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_FLOAT_H is not set +# CONFIG_ARCH_STDARG_H is not set +# CONFIG_ARCH_DEBUG_H is not set + +# +# Debug Options +# +CONFIG_DEBUG_ALERT=y +# CONFIG_DEBUG_FEATURES is not set +CONFIG_ARCH_HAVE_STACKCHECK=y +# CONFIG_STACK_COLORATION is not set +CONFIG_ARCH_HAVE_HEAPCHECK=y +# CONFIG_HEAP_COLORATION is not set +# CONFIG_DEBUG_SYMBOLS is not set +CONFIG_ARCH_HAVE_CUSTOMOPT=y +# CONFIG_DEBUG_NOOPT is not set +# CONFIG_DEBUG_CUSTOMOPT is not set +CONFIG_DEBUG_FULLOPT=y + +# +# System Type +# +CONFIG_ARCH_ARM=y +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_MISOC is not set +# CONFIG_ARCH_RENESAS is not set +# CONFIG_ARCH_RISCV is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_XTENSA is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="arm" + +# +# ARM Options +# +# CONFIG_ARCH_CHIP_A1X is not set +# CONFIG_ARCH_CHIP_C5471 is not set +# CONFIG_ARCH_CHIP_DM320 is not set +# CONFIG_ARCH_CHIP_EFM32 is not set +# CONFIG_ARCH_CHIP_IMX1 is not set +# CONFIG_ARCH_CHIP_IMX6 is not set +# CONFIG_ARCH_CHIP_KINETIS is not set +# CONFIG_ARCH_CHIP_KL is not set +# CONFIG_ARCH_CHIP_LM is not set +# CONFIG_ARCH_CHIP_TIVA is not set +# CONFIG_ARCH_CHIP_LPC11XX is not set +# CONFIG_ARCH_CHIP_LPC17XX is not set +# CONFIG_ARCH_CHIP_LPC214X is not set +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_NUC1XX is not set +# CONFIG_ARCH_CHIP_SAMA5 is not set +# CONFIG_ARCH_CHIP_SAMD is not set +# CONFIG_ARCH_CHIP_SAML is not set +# CONFIG_ARCH_CHIP_SAM34 is not set +# CONFIG_ARCH_CHIP_SAMV7 is not set +CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F7 is not set +# CONFIG_ARCH_CHIP_STM32L4 is not set +# CONFIG_ARCH_CHIP_STR71X is not set +# CONFIG_ARCH_CHIP_TMS570 is not set +# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_ARM7TDMI is not set +# CONFIG_ARCH_ARM926EJS is not set +# CONFIG_ARCH_ARM920T is not set +# CONFIG_ARCH_CORTEXM0 is not set +# CONFIG_ARCH_CORTEXM23 is not set +CONFIG_ARCH_CORTEXM3=y +# CONFIG_ARCH_CORTEXM33 is not set +# CONFIG_ARCH_CORTEXM4 is not set +# CONFIG_ARCH_CORTEXM7 is not set +# CONFIG_ARCH_CORTEXA5 is not set +# CONFIG_ARCH_CORTEXA8 is not set +# CONFIG_ARCH_CORTEXA9 is not set +# CONFIG_ARCH_CORTEXR4 is not set +# CONFIG_ARCH_CORTEXR4F is not set +# CONFIG_ARCH_CORTEXR5 is not set +# CONFIG_ARCH_CORTEX5F is not set +# CONFIG_ARCH_CORTEXR7 is not set +# CONFIG_ARCH_CORTEXR7F is not set +CONFIG_ARCH_FAMILY="armv7-m" +CONFIG_ARCH_CHIP="stm32" +# CONFIG_ARM_TOOLCHAIN_IAR is not set +CONFIG_ARM_TOOLCHAIN_GNU=y +# CONFIG_ARMV7M_USEBASEPRI is not set +CONFIG_ARCH_HAVE_CMNVECTOR=y +# CONFIG_ARMV7M_CMNVECTOR is not set +# CONFIG_ARMV7M_LAZYFPU is not set +# CONFIG_ARCH_HAVE_FPU is not set +# CONFIG_ARCH_HAVE_DPFPU is not set +# CONFIG_ARCH_HAVE_TRUSTZONE is not set +CONFIG_ARM_HAVE_MPU_UNIFIED=y +# CONFIG_ARM_MPU is not set + +# +# ARMV7M Configuration Options +# +# CONFIG_ARMV7M_HAVE_ICACHE is not set +# CONFIG_ARMV7M_HAVE_DCACHE is not set +# CONFIG_ARMV7M_HAVE_ITCM is not set +# CONFIG_ARMV7M_HAVE_DTCM is not set +# CONFIG_ARMV7M_TOOLCHAIN_IARL is not set +# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set +# CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set +# CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL is not set +CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL=y +CONFIG_ARMV7M_HAVE_STACKCHECK=y +# CONFIG_ARMV7M_STACKCHECK is not set +# CONFIG_ARMV7M_ITMSYSLOG is not set +# CONFIG_SERIAL_TERMIOS is not set + +# +# STM32 Configuration Options +# +# CONFIG_ARCH_CHIP_STM32L151C6 is not set +# CONFIG_ARCH_CHIP_STM32L151C8 is not set +# CONFIG_ARCH_CHIP_STM32L151CB is not set +# CONFIG_ARCH_CHIP_STM32L151R6 is not set +# CONFIG_ARCH_CHIP_STM32L151R8 is not set +# CONFIG_ARCH_CHIP_STM32L151RB is not set +# CONFIG_ARCH_CHIP_STM32L151V6 is not set +# CONFIG_ARCH_CHIP_STM32L151V8 is not set +# CONFIG_ARCH_CHIP_STM32L151VB is not set +# CONFIG_ARCH_CHIP_STM32L152C6 is not set +# CONFIG_ARCH_CHIP_STM32L152C8 is not set +# CONFIG_ARCH_CHIP_STM32L152CB is not set +# CONFIG_ARCH_CHIP_STM32L152R6 is not set +# CONFIG_ARCH_CHIP_STM32L152R8 is not set +# CONFIG_ARCH_CHIP_STM32L152RB is not set +# CONFIG_ARCH_CHIP_STM32L152V6 is not set +# CONFIG_ARCH_CHIP_STM32L152V8 is not set +# CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L162ZD is not set +# CONFIG_ARCH_CHIP_STM32L162VE is not set +# CONFIG_ARCH_CHIP_STM32F100C8 is not set +# CONFIG_ARCH_CHIP_STM32F100CB is not set +# CONFIG_ARCH_CHIP_STM32F100R8 is not set +# CONFIG_ARCH_CHIP_STM32F100RB is not set +# CONFIG_ARCH_CHIP_STM32F100RC is not set +# CONFIG_ARCH_CHIP_STM32F100RD is not set +# CONFIG_ARCH_CHIP_STM32F100RE is not set +# CONFIG_ARCH_CHIP_STM32F100V8 is not set +# CONFIG_ARCH_CHIP_STM32F100VB is not set +# CONFIG_ARCH_CHIP_STM32F100VC is not set +# CONFIG_ARCH_CHIP_STM32F100VD is not set +# CONFIG_ARCH_CHIP_STM32F100VE is not set +# CONFIG_ARCH_CHIP_STM32F102CB is not set +# CONFIG_ARCH_CHIP_STM32F103T8 is not set +# CONFIG_ARCH_CHIP_STM32F103TB is not set +# CONFIG_ARCH_CHIP_STM32F103C4 is not set +# CONFIG_ARCH_CHIP_STM32F103C8 is not set +# CONFIG_ARCH_CHIP_STM32F103CB is not set +# CONFIG_ARCH_CHIP_STM32F103R8 is not set +# CONFIG_ARCH_CHIP_STM32F103RB is not set +# CONFIG_ARCH_CHIP_STM32F103RC is not set +# CONFIG_ARCH_CHIP_STM32F103RD is not set +# CONFIG_ARCH_CHIP_STM32F103RE is not set +# CONFIG_ARCH_CHIP_STM32F103RG is not set +# CONFIG_ARCH_CHIP_STM32F103V8 is not set +# CONFIG_ARCH_CHIP_STM32F103VB is not set +# CONFIG_ARCH_CHIP_STM32F103VC is not set +# CONFIG_ARCH_CHIP_STM32F103VE is not set +# CONFIG_ARCH_CHIP_STM32F103ZE is not set +# CONFIG_ARCH_CHIP_STM32F105VB is not set +# CONFIG_ARCH_CHIP_STM32F105RB is not set +# CONFIG_ARCH_CHIP_STM32F107VC is not set +CONFIG_ARCH_CHIP_STM32F205RG=y +# CONFIG_ARCH_CHIP_STM32F207IG is not set +# CONFIG_ARCH_CHIP_STM32F207ZE is not set +# CONFIG_ARCH_CHIP_STM32F302K6 is not set +# CONFIG_ARCH_CHIP_STM32F302K8 is not set +# CONFIG_ARCH_CHIP_STM32F302CB is not set +# CONFIG_ARCH_CHIP_STM32F302CC is not set +# CONFIG_ARCH_CHIP_STM32F302RB is not set +# CONFIG_ARCH_CHIP_STM32F302RC is not set +# CONFIG_ARCH_CHIP_STM32F302VB is not set +# CONFIG_ARCH_CHIP_STM32F302VC is not set +# CONFIG_ARCH_CHIP_STM32F303K6 is not set +# CONFIG_ARCH_CHIP_STM32F303K8 is not set +# CONFIG_ARCH_CHIP_STM32F303C6 is not set +# CONFIG_ARCH_CHIP_STM32F303C8 is not set +# CONFIG_ARCH_CHIP_STM32F303CB is not set +# CONFIG_ARCH_CHIP_STM32F303CC is not set +# CONFIG_ARCH_CHIP_STM32F303RB is not set +# CONFIG_ARCH_CHIP_STM32F303RC is not set +# CONFIG_ARCH_CHIP_STM32F303RD is not set +# CONFIG_ARCH_CHIP_STM32F303RE is not set +# CONFIG_ARCH_CHIP_STM32F303VB is not set +# CONFIG_ARCH_CHIP_STM32F303VC is not set +# CONFIG_ARCH_CHIP_STM32F334K4 is not set +# CONFIG_ARCH_CHIP_STM32F334K6 is not set +# CONFIG_ARCH_CHIP_STM32F334K8 is not set +# CONFIG_ARCH_CHIP_STM32F334C4 is not set +# CONFIG_ARCH_CHIP_STM32F334C6 is not set +# CONFIG_ARCH_CHIP_STM32F334C8 is not set +# CONFIG_ARCH_CHIP_STM32F334R4 is not set +# CONFIG_ARCH_CHIP_STM32F334R6 is not set +# CONFIG_ARCH_CHIP_STM32F334R8 is not set +# CONFIG_ARCH_CHIP_STM32F372C8 is not set +# CONFIG_ARCH_CHIP_STM32F372R8 is not set +# CONFIG_ARCH_CHIP_STM32F372V8 is not set +# CONFIG_ARCH_CHIP_STM32F372CB is not set +# CONFIG_ARCH_CHIP_STM32F372RB is not set +# CONFIG_ARCH_CHIP_STM32F372VB is not set +# CONFIG_ARCH_CHIP_STM32F372CC is not set +# CONFIG_ARCH_CHIP_STM32F372RC is not set +# CONFIG_ARCH_CHIP_STM32F372VC is not set +# CONFIG_ARCH_CHIP_STM32F373C8 is not set +# CONFIG_ARCH_CHIP_STM32F373R8 is not set +# CONFIG_ARCH_CHIP_STM32F373V8 is not set +# CONFIG_ARCH_CHIP_STM32F373CB is not set +# CONFIG_ARCH_CHIP_STM32F373RB is not set +# CONFIG_ARCH_CHIP_STM32F373VB is not set +# CONFIG_ARCH_CHIP_STM32F373CC is not set +# CONFIG_ARCH_CHIP_STM32F373RC is not set +# CONFIG_ARCH_CHIP_STM32F373VC is not set +# CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F411RE is not set +# CONFIG_ARCH_CHIP_STM32F411VE is not set +# CONFIG_ARCH_CHIP_STM32F405RG is not set +# CONFIG_ARCH_CHIP_STM32F405VG is not set +# CONFIG_ARCH_CHIP_STM32F405ZG is not set +# CONFIG_ARCH_CHIP_STM32F407VE is not set +# CONFIG_ARCH_CHIP_STM32F407VG is not set +# CONFIG_ARCH_CHIP_STM32F407ZE is not set +# CONFIG_ARCH_CHIP_STM32F407ZG is not set +# CONFIG_ARCH_CHIP_STM32F407IE is not set +# CONFIG_ARCH_CHIP_STM32F407IG is not set +# CONFIG_ARCH_CHIP_STM32F427V is not set +# CONFIG_ARCH_CHIP_STM32F427Z is not set +# CONFIG_ARCH_CHIP_STM32F427I is not set +# CONFIG_ARCH_CHIP_STM32F429V is not set +# CONFIG_ARCH_CHIP_STM32F429Z is not set +# CONFIG_ARCH_CHIP_STM32F429I is not set +# CONFIG_ARCH_CHIP_STM32F429B is not set +# CONFIG_ARCH_CHIP_STM32F429N is not set +# CONFIG_ARCH_CHIP_STM32F446M is not set +# CONFIG_ARCH_CHIP_STM32F446R is not set +# CONFIG_ARCH_CHIP_STM32F446V is not set +# CONFIG_ARCH_CHIP_STM32F446Z is not set +# CONFIG_ARCH_CHIP_STM32F469A is not set +# CONFIG_ARCH_CHIP_STM32F469I is not set +# CONFIG_ARCH_CHIP_STM32F469B is not set +# CONFIG_ARCH_CHIP_STM32F469N is not set +CONFIG_STM32_FLASH_CONFIG_DEFAULT=y +# CONFIG_STM32_FLASH_CONFIG_4 is not set +# CONFIG_STM32_FLASH_CONFIG_6 is not set +# CONFIG_STM32_FLASH_CONFIG_8 is not set +# CONFIG_STM32_FLASH_CONFIG_B is not set +# CONFIG_STM32_FLASH_CONFIG_C is not set +# CONFIG_STM32_FLASH_CONFIG_D is not set +# CONFIG_STM32_FLASH_CONFIG_E is not set +# CONFIG_STM32_FLASH_CONFIG_F is not set +# CONFIG_STM32_FLASH_CONFIG_G is not set +# CONFIG_STM32_FLASH_CONFIG_I is not set +# CONFIG_STM32_STM32L15XX is not set +# CONFIG_STM32_ENERGYLITE is not set +# CONFIG_STM32_STM32F10XX is not set +# CONFIG_STM32_VALUELINE is not set +# CONFIG_STM32_CONNECTIVITYLINE is not set +# CONFIG_STM32_PERFORMANCELINE is not set +# CONFIG_STM32_USBACCESSLINE is not set +# CONFIG_STM32_HIGHDENSITY is not set +# CONFIG_STM32_MEDIUMDENSITY is not set +# CONFIG_STM32_LOWDENSITY is not set +CONFIG_STM32_STM32F20XX=y +CONFIG_STM32_STM32F205=y +# CONFIG_STM32_STM32F207 is not set +# CONFIG_STM32_STM32F30XX is not set +# CONFIG_STM32_STM32F302 is not set +# CONFIG_STM32_STM32F303 is not set +# CONFIG_STM32_STM32F33XX is not set +# CONFIG_STM32_STM32F37XX is not set +# CONFIG_STM32_STM32F40XX is not set +# CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F411 is not set +# CONFIG_STM32_STM32F405 is not set +# CONFIG_STM32_STM32F407 is not set +# CONFIG_STM32_STM32F427 is not set +# CONFIG_STM32_STM32F429 is not set +# CONFIG_STM32_STM32F446 is not set +# CONFIG_STM32_STM32F469 is not set +CONFIG_STM32_DFU=y + +# +# STM32 Peripheral Support +# +# CONFIG_STM32_HAVE_CCM is not set +# CONFIG_STM32_HAVE_USBDEV is not set +CONFIG_STM32_HAVE_OTGFS=y +# CONFIG_STM32_HAVE_FSMC is not set +# CONFIG_STM32_HAVE_HRTIM1 is not set +# CONFIG_STM32_HAVE_LTDC is not set +CONFIG_STM32_HAVE_USART3=y +CONFIG_STM32_HAVE_UART4=y +CONFIG_STM32_HAVE_UART5=y +CONFIG_STM32_HAVE_USART6=y +# CONFIG_STM32_HAVE_UART7 is not set +# CONFIG_STM32_HAVE_UART8 is not set +CONFIG_STM32_HAVE_TIM1=y +# CONFIG_STM32_HAVE_TIM2 is not set +CONFIG_STM32_HAVE_TIM3=y +CONFIG_STM32_HAVE_TIM4=y +CONFIG_STM32_HAVE_TIM5=y +CONFIG_STM32_HAVE_TIM6=y +CONFIG_STM32_HAVE_TIM7=y +CONFIG_STM32_HAVE_TIM8=y +CONFIG_STM32_HAVE_TIM9=y +CONFIG_STM32_HAVE_TIM10=y +CONFIG_STM32_HAVE_TIM11=y +CONFIG_STM32_HAVE_TIM12=y +CONFIG_STM32_HAVE_TIM13=y +CONFIG_STM32_HAVE_TIM14=y +# CONFIG_STM32_HAVE_TIM15 is not set +# CONFIG_STM32_HAVE_TIM16 is not set +# CONFIG_STM32_HAVE_TIM17 is not set +CONFIG_STM32_HAVE_ADC2=y +CONFIG_STM32_HAVE_ADC3=y +# CONFIG_STM32_HAVE_ADC4 is not set +# CONFIG_STM32_HAVE_ADC1_DMA is not set +# CONFIG_STM32_HAVE_ADC2_DMA is not set +# CONFIG_STM32_HAVE_ADC3_DMA is not set +# CONFIG_STM32_HAVE_ADC4_DMA is not set +# CONFIG_STM32_HAVE_SDADC1 is not set +# CONFIG_STM32_HAVE_SDADC2 is not set +# CONFIG_STM32_HAVE_SDADC3 is not set +# CONFIG_STM32_HAVE_SDADC1_DMA is not set +# CONFIG_STM32_HAVE_SDADC2_DMA is not set +# CONFIG_STM32_HAVE_SDADC3_DMA is not set +CONFIG_STM32_HAVE_CAN1=y +CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP6 is not set +CONFIG_STM32_HAVE_DAC1=y +CONFIG_STM32_HAVE_DAC2=y +CONFIG_STM32_HAVE_RNG=y +# CONFIG_STM32_HAVE_ETHMAC is not set +CONFIG_STM32_HAVE_I2C2=y +CONFIG_STM32_HAVE_I2C3=y +CONFIG_STM32_HAVE_SPI2=y +CONFIG_STM32_HAVE_SPI3=y +# CONFIG_STM32_HAVE_SPI4 is not set +# CONFIG_STM32_HAVE_SPI5 is not set +# CONFIG_STM32_HAVE_SPI6 is not set +# CONFIG_STM32_HAVE_SAIPLL is not set +# CONFIG_STM32_HAVE_I2SPLL is not set +# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_ADC1 is not set +# CONFIG_STM32_ADC2 is not set +# CONFIG_STM32_ADC3 is not set +# CONFIG_STM32_CAN1 is not set +# CONFIG_STM32_CAN2 is not set +# CONFIG_STM32_CRC is not set +# CONFIG_STM32_DMA1 is not set +# CONFIG_STM32_DMA2 is not set +# CONFIG_STM32_DAC1 is not set +# CONFIG_STM32_DAC2 is not set +# CONFIG_STM32_I2C1 is not set +# CONFIG_STM32_I2C2 is not set +# CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OTGFS is not set +CONFIG_STM32_OTGHS=y +# CONFIG_STM32_PWR is not set +# CONFIG_STM32_RNG is not set +# CONFIG_STM32_SDIO is not set +# CONFIG_STM32_SPI1 is not set +# CONFIG_STM32_SPI2 is not set +# CONFIG_STM32_SPI3 is not set +# CONFIG_STM32_TIM1 is not set +# CONFIG_STM32_TIM2 is not set +# CONFIG_STM32_TIM3 is not set +# CONFIG_STM32_TIM4 is not set +# CONFIG_STM32_TIM5 is not set +# CONFIG_STM32_TIM6 is not set +# CONFIG_STM32_TIM7 is not set +# CONFIG_STM32_TIM8 is not set +# CONFIG_STM32_TIM9 is not set +# CONFIG_STM32_TIM10 is not set +# CONFIG_STM32_TIM11 is not set +# CONFIG_STM32_TIM12 is not set +# CONFIG_STM32_TIM13 is not set +# CONFIG_STM32_TIM14 is not set +CONFIG_STM32_USART1=y +# CONFIG_STM32_USART2 is not set +# CONFIG_STM32_USART3 is not set +# CONFIG_STM32_UART4 is not set +# CONFIG_STM32_UART5 is not set +# CONFIG_STM32_USART6 is not set +CONFIG_STM32_IWDG=y +# CONFIG_STM32_WWDG is not set +# CONFIG_STM32_NOEXT_VECTORS is not set + +# +# Alternate Pin Mapping +# +# CONFIG_STM32_JTAG_DISABLE is not set +# CONFIG_STM32_JTAG_FULL_ENABLE is not set +# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set +CONFIG_STM32_JTAG_SW_ENABLE=y +# CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG is not set +# CONFIG_STM32_FORCEPOWER is not set +# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set + +# +# Timer Configuration +# +# CONFIG_STM32_ONESHOT is not set +# CONFIG_STM32_FREERUN is not set +# CONFIG_STM32_TIM1_CAP is not set +# CONFIG_STM32_TIM3_CAP is not set +# CONFIG_STM32_TIM4_CAP is not set +# CONFIG_STM32_TIM5_CAP is not set +# CONFIG_STM32_TIM8_CAP is not set +# CONFIG_STM32_TIM9_CAP is not set +# CONFIG_STM32_TIM10_CAP is not set +# CONFIG_STM32_TIM11_CAP is not set +# CONFIG_STM32_TIM12_CAP is not set +# CONFIG_STM32_TIM13_CAP is not set +# CONFIG_STM32_TIM14_CAP is not set +CONFIG_STM32_USART=y +CONFIG_STM32_SERIALDRIVER=y + +# +# U[S]ART Configuration +# + +# +# U[S]ART Device Configuration +# +CONFIG_STM32_USART1_SERIALDRIVER=y +# CONFIG_STM32_USART1_1WIREDRIVER is not set +# CONFIG_USART1_RS485 is not set + +# +# Serial Driver Configuration +# +# CONFIG_SERIAL_DISABLE_REORDERING is not set +# CONFIG_STM32_FLOWCONTROL_BROKEN is not set +# CONFIG_STM32_USART_BREAKS is not set +# CONFIG_STM32_USART_SINGLEWIRE is not set +# CONFIG_STM32_HAVE_RTC_COUNTER is not set +# CONFIG_STM32_HAVE_RTC_SUBSECONDS is not set + +# +# USB FS Host Configuration +# + +# +# USB HS Host Configuration +# + +# +# USB Host Debug Configuration +# + +# +# USB Device Configuration +# + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_VECNOTIRQ is not set +# CONFIG_ARCH_DMA is not set +CONFIG_ARCH_HAVE_IRQPRIO=y +# CONFIG_ARCH_L2CACHE is not set +# CONFIG_ARCH_HAVE_COHERENT_DCACHE is not set +# CONFIG_ARCH_HAVE_ADDRENV is not set +# CONFIG_ARCH_NEED_ADDRENV_MAPPING is not set +# CONFIG_ARCH_HAVE_MULTICPU is not set +CONFIG_ARCH_HAVE_VFORK=y +# CONFIG_ARCH_HAVE_MMU is not set +CONFIG_ARCH_HAVE_MPU=y +# CONFIG_ARCH_NAND_HWECC is not set +# CONFIG_ARCH_HAVE_EXTCLK is not set +# CONFIG_ARCH_HAVE_POWEROFF is not set +CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_USE_MPU is not set +# CONFIG_ARCH_IRQPRIO is not set +CONFIG_ARCH_STACKDUMP=y +# CONFIG_ENDIAN_BIG is not set +# CONFIG_ARCH_IDLE_CUSTOM is not set +# CONFIG_ARCH_HAVE_RAMFUNCS is not set +CONFIG_ARCH_HAVE_RAMVECTORS=y +# CONFIG_ARCH_RAMVECTORS is not set +# CONFIG_ARCH_MINIMAL_VECTORTABLE is not set + +# +# Board Settings +# +CONFIG_BOARD_LOOPSPERMSEC=16717 +# CONFIG_ARCH_CALIBRATION is not set + +# +# Interrupt options +# +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y +CONFIG_ARCH_INTERRUPTSTACK=0 +CONFIG_ARCH_HAVE_HIPRI_INTERRUPT=y +# CONFIG_ARCH_HIPRI_INTERRUPT is not set + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Boot Memory Configuration +# +CONFIG_RAM_START=0x20000000 +CONFIG_RAM_SIZE=114688 +# CONFIG_ARCH_HAVE_SDRAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_PHOTON=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="photon" + +# +# Common Board Options +# + +# +# Board-Specific Options +# +CONFIG_PHOTON_DFU_BOOTLOADER=y +CONFIG_PHOTON_WDG=y +CONFIG_PHOTON_IWDG=y +CONFIG_PHOTON_IWDG_TIMEOUT=32000 +CONFIG_PHOTON_WDG_THREAD=y +CONFIG_PHOTON_WDG_THREAD_NAME="wdog" +CONFIG_PHOTON_WDG_THREAD_INTERVAL=2500 +CONFIG_PHOTON_WDG_THREAD_PRIORITY=200 +CONFIG_PHOTON_WDG_THREAD_STACKSIZE=1024 +# CONFIG_BOARD_CRASHDUMP is not set +CONFIG_LIB_BOARDCTL=y +# CONFIG_BOARDCTL_RESET is not set +# CONFIG_BOARDCTL_UNIQUEID is not set +CONFIG_BOARDCTL_USBDEVCTRL=y +# CONFIG_BOARDCTL_TSCTEST is not set +# CONFIG_BOARDCTL_GRAPHICS is not set +# CONFIG_BOARDCTL_IOCTL is not set + +# +# RTOS Features +# +CONFIG_DISABLE_OS_API=y +# CONFIG_DISABLE_POSIX_TIMERS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_DISABLE_SIGNALS is not set +# CONFIG_DISABLE_MQUEUE is not set +# CONFIG_DISABLE_ENVIRON is not set + +# +# Clocks and Timers +# +CONFIG_ARCH_HAVE_TICKLESS=y +# CONFIG_SCHED_TICKLESS is not set +CONFIG_USEC_PER_TICK=10000 +# CONFIG_SYSTEM_TIME64 is not set +# CONFIG_CLOCK_MONOTONIC is not set +CONFIG_ARCH_HAVE_TIMEKEEPING=y +# CONFIG_JULIAN_TIME is not set +CONFIG_START_YEAR=2011 +CONFIG_START_MONTH=12 +CONFIG_START_DAY=6 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=16 +CONFIG_WDOG_INTRESERVE=4 +CONFIG_PREALLOC_TIMERS=4 + +# +# Tasks and Scheduling +# +# CONFIG_SPINLOCK is not set +# CONFIG_INIT_NONE is not set +CONFIG_INIT_ENTRYPOINT=y +# CONFIG_INIT_FILEPATH is not set +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_RR_INTERVAL=200 +# CONFIG_SCHED_SPORADIC is not set +CONFIG_TASK_NAME_SIZE=31 +CONFIG_MAX_TASKS=16 +# CONFIG_SCHED_HAVE_PARENT is not set +CONFIG_SCHED_WAITPID=y + +# +# Pthread Options +# +# CONFIG_MUTEX_TYPES is not set +CONFIG_NPTHREAD_KEYS=4 +# CONFIG_PTHREAD_CLEANUP is not set +# CONFIG_CANCELLATION_POINTS is not set + +# +# Performance Monitoring +# +# CONFIG_SCHED_CPULOAD is not set +# CONFIG_SCHED_INSTRUMENTATION is not set + +# +# Files and I/O +# +# CONFIG_DEV_CONSOLE is not set +# CONFIG_FDCLONE_DISABLE is not set +# CONFIG_FDCLONE_STDIO is not set +CONFIG_SDCLONE_DISABLE=y +CONFIG_NFILE_DESCRIPTORS=8 +CONFIG_NFILE_STREAMS=8 +CONFIG_NAME_MAX=32 +# CONFIG_PRIORITY_INHERITANCE is not set + +# +# RTOS hooks +# +# CONFIG_BOARD_INITIALIZE is not set +# CONFIG_SCHED_STARTHOOK is not set +# CONFIG_SCHED_ATEXIT is not set +# CONFIG_SCHED_ONEXIT is not set + +# +# Signal Numbers +# +CONFIG_SIG_SIGUSR1=1 +CONFIG_SIG_SIGUSR2=2 +CONFIG_SIG_SIGALARM=3 +CONFIG_SIG_SIGCONDTIMEDOUT=16 + +# +# POSIX Message Queue Options +# +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_MQ_MAXMSGSIZE=32 +# CONFIG_MODULE is not set + +# +# Work queue support +# +# CONFIG_SCHED_WORKQUEUE is not set +# CONFIG_SCHED_HPWORK is not set +# CONFIG_SCHED_LPWORK is not set + +# +# Stack and heap information +# +CONFIG_IDLETHREAD_STACKSIZE=1024 +CONFIG_USERMAIN_STACKSIZE=2048 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=2048 +# CONFIG_LIB_SYSCALL is not set + +# +# Device Drivers +# +CONFIG_DISABLE_POLL=y +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_DEV_URANDOM is not set +# CONFIG_DEV_LOOP is not set + +# +# Buffering +# +# CONFIG_DRVR_WRITEBUFFER is not set +# CONFIG_DRVR_READAHEAD is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_ARCH_HAVE_PWM_PULSECOUNT is not set +# CONFIG_ARCH_HAVE_PWM_MULTICHAN is not set +# CONFIG_PWM is not set +CONFIG_ARCH_HAVE_I2CRESET=y +# CONFIG_I2C is not set +# CONFIG_ARCH_HAVE_SPI_CRCGENERATION is not set +# CONFIG_ARCH_HAVE_SPI_CS_CONTROL is not set +CONFIG_ARCH_HAVE_SPI_BITORDER=y +# CONFIG_SPI is not set +# CONFIG_I2S is not set + +# +# Timer Driver Support +# +# CONFIG_TIMER is not set +# CONFIG_ONESHOT is not set +# CONFIG_RTC is not set +CONFIG_WATCHDOG=y +CONFIG_WATCHDOG_DEVPATH="/dev/watchdog0" +# CONFIG_ANALOG is not set +# CONFIG_AUDIO_DEVICES is not set +# CONFIG_VIDEO_DEVICES is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set + +# +# IO Expander/GPIO Support +# +# CONFIG_IOEXPANDER is not set +# CONFIG_DEV_GPIO is not set + +# +# LCD Driver Support +# +# CONFIG_LCD is not set +# CONFIG_SLCD is not set + +# +# LED Support +# +# CONFIG_RGBLED is not set +# CONFIG_PCA9635PW is not set +# CONFIG_NCP5623C is not set +# CONFIG_MMCSD is not set +# CONFIG_MODEM is not set +# CONFIG_MTD is not set +# CONFIG_EEPROM is not set +# CONFIG_PIPES is not set +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +CONFIG_SERIAL=y +CONFIG_SERIAL_REMOVABLE=y +# CONFIG_SERIAL_CONSOLE is not set +# CONFIG_16550_UART is not set +# CONFIG_UART_SERIALDRIVER is not set +# CONFIG_UART0_SERIALDRIVER is not set +# CONFIG_UART1_SERIALDRIVER is not set +# CONFIG_UART2_SERIALDRIVER is not set +# CONFIG_UART3_SERIALDRIVER is not set +# CONFIG_UART4_SERIALDRIVER is not set +# CONFIG_UART5_SERIALDRIVER is not set +# CONFIG_UART6_SERIALDRIVER is not set +# CONFIG_UART7_SERIALDRIVER is not set +# CONFIG_UART8_SERIALDRIVER is not set +# CONFIG_SCI0_SERIALDRIVER is not set +# CONFIG_SCI1_SERIALDRIVER is not set +# CONFIG_USART0_SERIALDRIVER is not set +CONFIG_USART1_SERIALDRIVER=y +# CONFIG_USART2_SERIALDRIVER is not set +# CONFIG_USART3_SERIALDRIVER is not set +# CONFIG_USART4_SERIALDRIVER is not set +# CONFIG_USART5_SERIALDRIVER is not set +# CONFIG_USART6_SERIALDRIVER is not set +# CONFIG_USART7_SERIALDRIVER is not set +# CONFIG_USART8_SERIALDRIVER is not set +# CONFIG_OTHER_UART_SERIALDRIVER is not set +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +# CONFIG_SERIAL_IFLOWCONTROL is not set +# CONFIG_SERIAL_OFLOWCONTROL is not set +# CONFIG_SERIAL_DMA is not set +CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y +# CONFIG_USART1_SERIAL_CONSOLE is not set +# CONFIG_OTHER_SERIAL_CONSOLE is not set +CONFIG_NO_SERIAL_CONSOLE=y + +# +# USART1 Configuration +# +CONFIG_USART1_RXBUFSIZE=256 +CONFIG_USART1_TXBUFSIZE=256 +CONFIG_USART1_BAUD=115200 +CONFIG_USART1_BITS=8 +CONFIG_USART1_PARITY=0 +CONFIG_USART1_2STOP=0 +# CONFIG_USART1_IFLOWCONTROL is not set +# CONFIG_USART1_OFLOWCONTROL is not set +# CONFIG_USART1_DMA is not set +# CONFIG_PSEUDOTERM is not set +CONFIG_USBDEV=y + +# +# USB Device Controller Driver Options +# +# CONFIG_USBDEV_ISOCHRONOUS is not set +# CONFIG_USBDEV_DUALSPEED is not set +CONFIG_USBDEV_SELFPOWERED=y +# CONFIG_USBDEV_BUSPOWERED is not set +CONFIG_USBDEV_MAXPOWER=100 +# CONFIG_USBDEV_DMA is not set +# CONFIG_ARCH_USBDEV_STALLQUEUE is not set +# CONFIG_USBDEV_TRACE is not set + +# +# USB Device Class Driver Options +# +# CONFIG_USBDEV_COMPOSITE is not set +# CONFIG_PL2303 is not set +CONFIG_CDCACM=y +CONFIG_CDCACM_CONSOLE=y +CONFIG_CDCACM_EP0MAXPACKET=64 +CONFIG_CDCACM_EPINTIN=1 +CONFIG_CDCACM_EPINTIN_FSSIZE=64 +CONFIG_CDCACM_EPINTIN_HSSIZE=64 +CONFIG_CDCACM_EPBULKOUT=3 +CONFIG_CDCACM_EPBULKOUT_FSSIZE=64 +CONFIG_CDCACM_EPBULKOUT_HSSIZE=512 +CONFIG_CDCACM_EPBULKIN=2 +CONFIG_CDCACM_EPBULKIN_FSSIZE=64 +CONFIG_CDCACM_EPBULKIN_HSSIZE=512 +CONFIG_CDCACM_NRDREQS=4 +CONFIG_CDCACM_NWRREQS=4 +CONFIG_CDCACM_BULKIN_REQLEN=96 +CONFIG_CDCACM_RXBUFSIZE=257 +CONFIG_CDCACM_TXBUFSIZE=193 +CONFIG_CDCACM_VENDORID=0x0525 +CONFIG_CDCACM_PRODUCTID=0xa4a7 +CONFIG_CDCACM_VENDORSTR="NuttX" +CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial" +# CONFIG_USBMSC is not set +# CONFIG_USBHOST is not set +# CONFIG_HAVE_USBTRACE is not set +# CONFIG_DRIVERS_WIRELESS is not set +# CONFIG_DRIVERS_CONTACTLESS is not set + +# +# System Logging +# +# CONFIG_ARCH_SYSLOG is not set +# CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_INTBUFFER is not set +# CONFIG_SYSLOG_TIMESTAMP is not set +# CONFIG_SYSLOG_SERIAL_CONSOLE is not set +CONFIG_SYSLOG_CHAR=y +# CONFIG_SYSLOG_NONE is not set +# CONFIG_SYSLOG_FILE is not set +CONFIG_SYSLOG_CHAR_CRLF=y +CONFIG_SYSLOG_DEVPATH="/dev/ttyS0" +# CONFIG_SYSLOG_CHARDEV is not set + +# +# Networking Support +# +# CONFIG_ARCH_HAVE_NET is not set +# CONFIG_ARCH_HAVE_PHY is not set +# CONFIG_NET is not set + +# +# Crypto API +# +# CONFIG_CRYPTO is not set + +# +# File Systems +# + +# +# File system configuration +# +# CONFIG_DISABLE_MOUNTPOINT is not set +# CONFIG_FS_AUTOMOUNTER is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_PSEUDOFS_SOFTLINKS is not set +CONFIG_FS_READABLE=y +# CONFIG_FS_WRITABLE is not set +# CONFIG_FS_NAMED_SEMAPHORES is not set +CONFIG_FS_MQUEUE_MPATH="/var/mqueue" +# CONFIG_FS_RAMMAP is not set +# CONFIG_FS_FAT is not set +# CONFIG_FS_NXFFS is not set +# CONFIG_FS_ROMFS is not set +# CONFIG_FS_TMPFS is not set +# CONFIG_FS_SMARTFS is not set +# CONFIG_FS_BINFS is not set +CONFIG_FS_PROCFS=y +# CONFIG_FS_PROCFS_REGISTER is not set + +# +# Exclude individual procfs entries +# +# CONFIG_FS_PROCFS_EXCLUDE_PROCESS is not set +# CONFIG_FS_PROCFS_EXCLUDE_UPTIME is not set +# CONFIG_FS_PROCFS_EXCLUDE_MOUNTS is not set +# CONFIG_FS_UNIONFS is not set + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=2 +# CONFIG_ARCH_HAVE_HEAP2 is not set +# CONFIG_GRAN is not set + +# +# Audio Support +# +# CONFIG_AUDIO is not set + +# +# Wireless Support +# + +# +# Binary Loader +# +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_BINFMT_EXEPATH is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +CONFIG_BUILTIN=y +# CONFIG_PIC is not set +# CONFIG_SYMTAB_ORDEREDBYNAME is not set + +# +# Library Routines +# + +# +# Standard C Library Options +# + +# +# Standard C I/O +# +# CONFIG_STDIO_DISABLE_BUFFERING is not set +CONFIG_STDIO_BUFFER_SIZE=64 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +# CONFIG_NOPRINTF_FIELDWIDTH is not set +# CONFIG_LIBC_FLOATINGPOINT is not set +CONFIG_LIBC_LONG_LONG=y +# CONFIG_LIBC_SCANSET is not set +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_MEMCPY_VIK is not set +# CONFIG_LIBM is not set + +# +# Architecture-Specific Support +# +CONFIG_ARCH_LOWPUTC=y +# CONFIG_ARCH_ROMGETC is not set +# CONFIG_LIBC_ARCH_MEMCPY is not set +# CONFIG_LIBC_ARCH_MEMCMP is not set +# CONFIG_LIBC_ARCH_MEMMOVE is not set +# CONFIG_LIBC_ARCH_MEMSET is not set +# CONFIG_LIBC_ARCH_STRCHR is not set +# CONFIG_LIBC_ARCH_STRCMP is not set +# CONFIG_LIBC_ARCH_STRCPY is not set +# CONFIG_LIBC_ARCH_STRNCPY is not set +# CONFIG_LIBC_ARCH_STRLEN is not set +# CONFIG_LIBC_ARCH_STRNLEN is not set +# CONFIG_LIBC_ARCH_ELF is not set +# CONFIG_ARMV7M_MEMCPY is not set + +# +# stdlib Options +# +CONFIG_LIB_RAND_ORDER=1 +CONFIG_LIB_HOMEDIR="/" + +# +# Program Execution Options +# +# CONFIG_LIBC_EXECFUNCS is not set +CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024 +CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=2048 + +# +# errno Decode Support +# +# CONFIG_LIBC_STRERROR is not set +# CONFIG_LIBC_PERROR_STDOUT is not set + +# +# memcpy/memset Options +# +# CONFIG_MEMSET_OPTSPEED is not set +# CONFIG_LIBC_DLLFCN is not set +# CONFIG_LIBC_MODLIB is not set +# CONFIG_LIBC_WCHAR is not set +# CONFIG_LIBC_LOCALE is not set + +# +# Time/Time Zone Support +# +# CONFIG_LIBC_LOCALTIME is not set +# CONFIG_TIME_EXTENDED is not set +CONFIG_ARCH_HAVE_TLS=y + +# +# Thread Local Storage (TLS) +# +# CONFIG_TLS is not set + +# +# Network-Related Options +# +# CONFIG_LIBC_IPv4_ADDRCONV is not set +# CONFIG_LIBC_IPv6_ADDRCONV is not set +# CONFIG_LIBC_NETDB is not set + +# +# NETDB Support +# +# CONFIG_NETDB_HOSTFILE is not set +# CONFIG_LIBC_IOCTL_VARIADIC is not set +CONFIG_LIB_SENDFILE_BUFSIZE=512 + +# +# Non-standard Library Support +# +# CONFIG_LIB_CRC64_FAST is not set +# CONFIG_LIB_KBDCODEC is not set +# CONFIG_LIB_SLCDCODEC is not set +# CONFIG_LIB_HEX2BIN is not set + +# +# Basic CXX Support +# +# CONFIG_C99_BOOL8 is not set +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +# CONFIG_CXX_NEWLONG is not set + +# +# LLVM C++ Library (libcxx) +# +# CONFIG_LIBCXX is not set + +# +# uClibc++ Standard C++ Library +# +# CONFIG_UCLIBCXX is not set + +# +# Application Configuration +# + +# +# NxWidgets/NxWM +# + +# +# Built-In Applications +# +CONFIG_BUILTIN_PROXY_STACKSIZE=1024 + +# +# CAN Utilities +# + +# +# Examples +# +# CONFIG_EXAMPLES_CCTYPE is not set +# CONFIG_EXAMPLES_CHAT is not set +# CONFIG_EXAMPLES_CONFIGDATA is not set +# CONFIG_EXAMPLES_CXXTEST is not set +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HELLOXX is not set +# CONFIG_EXAMPLES_HIDKBD is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_JSON is not set +# CONFIG_EXAMPLES_KEYPADTEST is not set +# CONFIG_EXAMPLES_MEDIA is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MODBUS is not set +# CONFIG_EXAMPLES_MOUNT is not set +CONFIG_EXAMPLES_NSH=y +# CONFIG_EXAMPLES_NSH_CXXINITIALIZE is not set +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NXLINES is not set +# CONFIG_EXAMPLES_NXTERM is not set +# CONFIG_EXAMPLES_NXTEXT is not set +# CONFIG_EXAMPLES_OSTEST is not set +# CONFIG_EXAMPLES_PCA9635 is not set +# CONFIG_EXAMPLES_POSIXSPAWN is not set +# CONFIG_EXAMPLES_PPPD is not set +# CONFIG_EXAMPLES_RFID_READUID is not set +# CONFIG_EXAMPLES_RGBLED is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERIALBLASTER is not set +# CONFIG_EXAMPLES_SERIALRX is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_SLCD is not set +# CONFIG_EXAMPLES_SMART is not set +# CONFIG_EXAMPLES_SMART_TEST is not set +# CONFIG_EXAMPLES_SMP is not set +# CONFIG_EXAMPLES_STAT is not set +# CONFIG_EXAMPLES_TCPECHO is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_USBSERIAL is not set +# CONFIG_EXAMPLES_USBTERM is not set +# CONFIG_EXAMPLES_WATCHDOG is not set +# CONFIG_EXAMPLES_WEBSERVER is not set + +# +# File System Utilities +# +# CONFIG_FSUTILS_INIFILE is not set +# CONFIG_FSUTILS_PASSWD is not set + +# +# GPS Utilities +# +# CONFIG_GPSUTILS_MINMEA_LIB is not set + +# +# Graphics Support +# +# CONFIG_TIFF is not set +# CONFIG_GRAPHICS_TRAVELER is not set + +# +# Interpreters +# +# CONFIG_INTERPRETERS_BAS is not set +# CONFIG_INTERPRETERS_FICL is not set +# CONFIG_INTERPRETERS_MICROPYTHON is not set +# CONFIG_INTERPRETERS_MINIBASIC is not set +# CONFIG_INTERPRETERS_PCODE is not set + +# +# FreeModBus +# +# CONFIG_MODBUS is not set + +# +# Network Utilities +# +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_ESP8266 is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_JSON is not set +# CONFIG_NETUTILS_SMTP is not set + +# +# NSH Library +# +CONFIG_NSH_LIBRARY=y +# CONFIG_NSH_MOTD is not set + +# +# Command Line Configuration +# +CONFIG_NSH_READLINE=y +# CONFIG_NSH_CLE is not set +CONFIG_NSH_LINELEN=64 +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_CMDPARMS is not set +CONFIG_NSH_MAXARGUMENTS=6 +# CONFIG_NSH_ARGCAT is not set +CONFIG_NSH_NESTDEPTH=3 +# CONFIG_NSH_DISABLEBG is not set +CONFIG_NSH_BUILTIN_APPS=y + +# +# Disable Individual commands +# +# CONFIG_NSH_DISABLE_ADDROUTE is not set +# CONFIG_NSH_DISABLE_BASENAME is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_CMP is not set +CONFIG_NSH_DISABLE_DATE=y +# CONFIG_NSH_DISABLE_DD is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_DELROUTE is not set +# CONFIG_NSH_DISABLE_DIRNAME is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_HEXDUMP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +# CONFIG_NSH_DISABLE_IFUPDOWN is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOSETUP is not set +CONFIG_NSH_DISABLE_LOSMART=y +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MB is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKRD is not set +# CONFIG_NSH_DISABLE_MH is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_MW is not set +CONFIG_NSH_DISABLE_PRINTF=y +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PUT is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SH is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNAME is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +# CONFIG_NSH_DISABLE_WGET is not set +# CONFIG_NSH_DISABLE_XD is not set +CONFIG_NSH_MMCSDMINOR=0 + +# +# Configure Command Options +# +# CONFIG_NSH_CMDOPT_DF_H is not set +# CONFIG_NSH_CMDOPT_DD_STATS is not set +CONFIG_NSH_CODECS_BUFSIZE=128 +# CONFIG_NSH_CMDOPT_HEXDUMP is not set +CONFIG_NSH_PROC_MOUNTPOINT="/proc" +CONFIG_NSH_FILEIOSIZE=512 + +# +# Scripting Support +# +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_LOOPS is not set + +# +# Console Configuration +# +CONFIG_NSH_CONSOLE=y +# CONFIG_NSH_USBCONSOLE is not set +# CONFIG_NSH_ALTCONDEV is not set +CONFIG_NSH_ARCHINIT=y +# CONFIG_NSH_LOGIN is not set +# CONFIG_NSH_CONSOLE_LOGIN is not set + +# +# Platform-specific Support +# +# CONFIG_PLATFORM_CONFIGDATA is not set + +# +# System Libraries and NSH Add-Ons +# +# CONFIG_SYSTEM_CDCACM is not set +# CONFIG_SYSTEM_CLE is not set +# CONFIG_SYSTEM_CUTERM is not set +# CONFIG_SYSTEM_FREE is not set +# CONFIG_SYSTEM_HEX2BIN is not set +# CONFIG_SYSTEM_HEXED is not set +# CONFIG_SYSTEM_INSTALL is not set +# CONFIG_SYSTEM_RAMTEST is not set +CONFIG_READLINE_HAVE_EXTMATCH=y +CONFIG_SYSTEM_READLINE=y +CONFIG_READLINE_ECHO=y +# CONFIG_READLINE_TABCOMPLETION is not set +# CONFIG_READLINE_CMD_HISTORY is not set +# CONFIG_SYSTEM_SUDOKU is not set +# CONFIG_SYSTEM_SYSTEM is not set +# CONFIG_SYSTEM_TEE is not set +# CONFIG_SYSTEM_UBLOXMODEM is not set +# CONFIG_SYSTEM_VI is not set +# CONFIG_SYSTEM_ZMODEM is not set diff --git a/configs/photon/usbnsh/setenv.sh b/configs/photon/usbnsh/setenv.sh new file mode 100755 index 0000000000..40ce369964 --- /dev/null +++ b/configs/photon/usbnsh/setenv.sh @@ -0,0 +1,84 @@ +#!/bin/bash +# configs/photon/usbnsh/setenv.sh +# +# 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. +# + +if [ "$_" = "$0" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +fi + +WD=`pwd` +if [ ! -x "setenv.sh" ]; then + echo "This script must be executed from the top-level NuttX build directory" + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then + export PATH_ORIG="${PATH}" +fi + +# This is the Cygwin path to the location where I installed the RIDE +# toolchain under windows. You will also have to edit this if you install +# the RIDE toolchain in any other location +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" + +# This is the Cygwin path to the location where I installed the CodeSourcery +# toolchain under windows. You will also have to edit this if you install +# the CodeSourcery toolchain in any other location +# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" +#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin" + +# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors" +# You can this free toolchain here https://launchpad.net/gcc-arm-embedded +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin" + +# These are the Cygwin paths to the locations where I installed the Atollic +# toolchain under windows. You will also have to edit this if you install +# the Atollic toolchain in any other location. /usr/bin is added before +# the Atollic bin path because there is are binaries named gcc.exe and g++.exe +# at those locations as well. +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" + +# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors" +# You can this free toolchain here https://launchpad.net/gcc-arm-embedded +export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin" + +# This is the Cygwin path to the location where I build the buildroot +# toolchain. +#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" + +# Add the path to the toolchain to the PATH variable +export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" + +echo "PATH : ${PATH}" -- GitLab From 399f3067441941072664bdbfa1bfec8ff35aa449 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 11 Mar 2017 08:57:34 -0600 Subject: [PATCH 010/990] A few cosmetic changes --- drivers/wireless/nrf24l01.c | 19 +++++++++++-------- sched/semaphore/sem_holder.c | 1 - 2 files changed, 11 insertions(+), 9 deletions(-) diff --git a/drivers/wireless/nrf24l01.c b/drivers/wireless/nrf24l01.c index a667227e03..c3ed88d17a 100644 --- a/drivers/wireless/nrf24l01.c +++ b/drivers/wireless/nrf24l01.c @@ -42,7 +42,6 @@ * Todo: * - Add support for payloads in ACK packets (?) * - Add compatibility with nRF24L01 (not +) hardware (?) - * */ /**************************************************************************** @@ -116,11 +115,15 @@ #define FIFO_PIPENO_MASK 0xE0 /* 3 ms bits used to store pipe # */ #define FIFO_PIPENO_SHIFT 4 -#define FIFO_PKTLEN(dev) (((dev->rx_fifo[dev->nxt_read] & FIFO_PKTLEN_MASK) >> FIFO_PKTLEN_SHIFT) + 1) -#define FIFO_PIPENO(dev) (((dev->rx_fifo[dev->nxt_read] & FIFO_PIPENO_MASK) >> FIFO_PIPENO_SHIFT)) -#define FIFO_HEADER(pktlen,pipeno) ((pktlen - 1) | (pipeno << FIFO_PIPENO_SHIFT)) +#define FIFO_PKTLEN(dev) \ + (((dev->rx_fifo[dev->nxt_read] & FIFO_PKTLEN_MASK) >> FIFO_PKTLEN_SHIFT) + 1) +#define FIFO_PIPENO(dev) \ + (((dev->rx_fifo[dev->nxt_read] & FIFO_PIPENO_MASK) >> FIFO_PIPENO_SHIFT)) +#define FIFO_HEADER(pktlen,pipeno) \ + ((pktlen - 1) | (pipeno << FIFO_PIPENO_SHIFT)) -#define DEV_NAME "/dev/nrf24l01" +#define DEV_NAME "/dev/nrf24l01" +#define FL_AA_ENABLED (1 << 0) /**************************************************************************** * Private Data Types @@ -132,8 +135,6 @@ typedef enum MODE_WRITE } nrf24l01_access_mode_t; -#define FL_AA_ENABLED (1 << 0) - struct nrf24l01_dev_s { FAR struct spi_dev_s *spi; /* Reference to SPI bus device */ @@ -800,6 +801,7 @@ static void nrf24l01_tostate(struct nrf24l01_dev_s *dev, { case ST_UNKNOWN: /* Power down the module here... */ + case ST_POWER_DOWN: nrf24l01_chipenable(dev, false); nrf24l01_setregbit(dev, NRF24L01_CONFIG, NRF24L01_PWR_UP, false); @@ -1928,7 +1930,8 @@ uint32_t nrf24l01_getradiofreq(FAR struct nrf24l01_dev_s *dev) int nrf24l01_setaddrwidth(FAR struct nrf24l01_dev_s *dev, uint32_t width) { - CHECK_ARGS(dev && width <= NRF24L01_MAX_ADDR_LEN && width >= NRF24L01_MIN_ADDR_LEN); + CHECK_ARGS(dev && width <= NRF24L01_MAX_ADDR_LEN && + width >= NRF24L01_MIN_ADDR_LEN); nrf24l01_lock(dev->spi); nrf24l01_writeregbyte(dev, NRF24L01_SETUP_AW, width-2); diff --git a/sched/semaphore/sem_holder.c b/sched/semaphore/sem_holder.c index f14f9fe679..b6a5e2c788 100644 --- a/sched/semaphore/sem_holder.c +++ b/sched/semaphore/sem_holder.c @@ -322,7 +322,6 @@ static int sem_boostholderprio(FAR struct semholder_s *pholder, } #if CONFIG_SEM_NNESTPRIO > 0 - /* If the priority of the thread that is waiting for a count is greater * than the base priority of the thread holding a count, then we may need * to adjust the holder's priority now or later to that priority. -- GitLab From c9ecb3c378955e82aec4b8bb6498ddc4ae44b071 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Sat, 11 Mar 2017 15:35:03 +0000 Subject: [PATCH 011/990] As discovered by dcabecinhas. This fix assume the 8 byte alignment options for size stack size or this will overwrite the first word after TOS See https://github.com/PX4/Firmware/issues/6613#issuecomment-285869778 --- arch/arm/src/common/up_initialize.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/arch/arm/src/common/up_initialize.c b/arch/arm/src/common/up_initialize.c index 5182598246..aeee1aaf50 100644 --- a/arch/arm/src/common/up_initialize.c +++ b/arch/arm/src/common/up_initialize.c @@ -106,7 +106,7 @@ static inline void up_color_intstack(void) uint32_t *ptr = (uint32_t *)&g_intstackalloc; ssize_t size; - for (size = (CONFIG_ARCH_INTERRUPTSTACK & ~3); + for (size = (CONFIG_ARCH_INTERRUPTSTACK & ~7); size > 0; size -= sizeof(uint32_t)) { -- GitLab From cdfc158f90968a6eed2bf4dc9cd4fb0ed79cb200 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Sat, 11 Mar 2017 15:40:48 +0000 Subject: [PATCH 012/990] up_initialize.c edited online with Bitbucket --- arch/arm/src/common/up_initialize.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/arch/arm/src/common/up_initialize.c b/arch/arm/src/common/up_initialize.c index aeee1aaf50..267f5e1c59 100644 --- a/arch/arm/src/common/up_initialize.c +++ b/arch/arm/src/common/up_initialize.c @@ -100,7 +100,7 @@ static void up_calibratedelay(void) * ****************************************************************************/ -#if defined(CONFIG_STACK_COLORATION) && CONFIG_ARCH_INTERRUPTSTACK > 3 +#if defined(CONFIG_STACK_COLORATION) && CONFIG_ARCH_INTERRUPTSTACK > 7 static inline void up_color_intstack(void) { uint32_t *ptr = (uint32_t *)&g_intstackalloc; -- GitLab From 70d8f0189d722c8cd7115a6648cdafa5257f99b4 Mon Sep 17 00:00:00 2001 From: Simon Piriou Date: Sat, 11 Mar 2017 18:15:18 +0100 Subject: [PATCH 013/990] stm32f20xxx: add BOARD_DISABLE_USBOTG_HSULPI flag --- arch/arm/src/stm32/stm32f20xxx_rcc.c | 6 ++++++ configs/photon/include/board.h | 4 ++++ 2 files changed, 10 insertions(+) diff --git a/arch/arm/src/stm32/stm32f20xxx_rcc.c b/arch/arm/src/stm32/stm32f20xxx_rcc.c index a45241ed85..ad71714a80 100644 --- a/arch/arm/src/stm32/stm32f20xxx_rcc.c +++ b/arch/arm/src/stm32/stm32f20xxx_rcc.c @@ -195,7 +195,13 @@ static inline void rcc_enableahb1(void) #ifdef CONFIG_STM32_OTGHS /* USB OTG HS */ +#ifndef BOARD_DISABLE_USBOTG_HSULPI + /* Enable clocking for OTG and external PHY */ + regval |= (RCC_AHB1ENR_OTGHSEN | RCC_AHB1ENR_OTGHSULPIEN); +#else + regval |= (RCC_AHB1ENR_OTGHSEN); +#endif #endif putreg32(regval, STM32_RCC_AHB1ENR); /* Enable peripherals */ diff --git a/configs/photon/include/board.h b/configs/photon/include/board.h index ac5faed041..efce673115 100644 --- a/configs/photon/include/board.h +++ b/configs/photon/include/board.h @@ -146,6 +146,10 @@ #define STM32_APB2_TIM10_CLKIN (2*STM32_PCLK2_FREQUENCY) #define STM32_APB2_TIM11_CLKIN (2*STM32_PCLK2_FREQUENCY) +/* USB OTG HS definitions ***********************************************************/ +/* Do not enable external PHY clock or OTG_HS module will not work */ +#define BOARD_DISABLE_USBOTG_HSULPI 1 + /* Alternate function pin selections ************************************************/ /* UART1 */ -- GitLab From ef0fe50ae6803e996bbbb32359cac20d49a8a6f7 Mon Sep 17 00:00:00 2001 From: Simon Piriou Date: Sat, 11 Mar 2017 17:51:45 +0100 Subject: [PATCH 014/990] photon: add LEDs and BUTTONS support --- configs/Kconfig | 3 + configs/photon/include/board.h | 12 ++++ configs/photon/src/Makefile | 8 +++ configs/photon/src/photon.h | 13 ++++ configs/photon/src/photon_buttons.c | 101 ++++++++++++++++++++++++++++ configs/photon/src/photon_leds.c | 86 +++++++++++++++++++++++ configs/photon/src/stm32_appinit.c | 40 +++++++++-- 7 files changed, 258 insertions(+), 5 deletions(-) create mode 100644 configs/photon/src/photon_buttons.c create mode 100644 configs/photon/src/photon_leds.c diff --git a/configs/Kconfig b/configs/Kconfig index e91e262499..d5016d9b7c 100644 --- a/configs/Kconfig +++ b/configs/Kconfig @@ -959,6 +959,9 @@ config ARCH_BOARD_SPARK config ARCH_BOARD_PHOTON bool "Photon wifi board" depends on ARCH_CHIP_STM32F205RG + select ARCH_HAVE_LEDS + select ARCH_HAVE_BUTTONS + select ARCH_HAVE_IRQBUTTONS ---help--- A configuration for the Photon from Particle Devices (https://www.particle.io). This board features the STM32F205RGY6 diff --git a/configs/photon/include/board.h b/configs/photon/include/board.h index efce673115..15ee036088 100644 --- a/configs/photon/include/board.h +++ b/configs/photon/include/board.h @@ -150,6 +150,18 @@ /* Do not enable external PHY clock or OTG_HS module will not work */ #define BOARD_DISABLE_USBOTG_HSULPI 1 +/* LED definitions ******************************************************************/ + +#define BOARD_LED1 0 +#define BOARD_NLEDS 1 +#define BOARD_LED1_BIT (1 << BOARD_LED1) + +/* Button definitions ***************************************************************/ + +#define BOARD_BUTTON1 0 +#define NUM_BUTTONS 1 +#define BOARD_BUTTON1_BIT (1 << BOARD_BUTTON1) + /* Alternate function pin selections ************************************************/ /* UART1 */ diff --git a/configs/photon/src/Makefile b/configs/photon/src/Makefile index ae24c7d4c0..f834e2c7fa 100644 --- a/configs/photon/src/Makefile +++ b/configs/photon/src/Makefile @@ -41,6 +41,14 @@ ifeq ($(CONFIG_PHOTON_DFU_BOOTLOADER),y) CSRCS += dfu_signature.c endif +ifeq ($(CONFIG_BUTTONS),y) +CSRCS += photon_buttons.c +endif + +ifeq ($(CONFIG_USERLED),y) +CSRCS += photon_leds.c +endif + ifeq ($(CONFIG_PHOTON_WDG),y) CSRCS += photon_wdt.c endif diff --git a/configs/photon/src/photon.h b/configs/photon/src/photon.h index 5678dc7c1f..ec160684f6 100644 --- a/configs/photon/src/photon.h +++ b/configs/photon/src/photon.h @@ -48,6 +48,19 @@ * Pre-processor Definitions ****************************************************************************/ +/* LEDs */ + +#define GPIO_LED1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN13) + +/* BUTTONS -- EXTI interrupts are available on Photon board button */ + +#define MIN_IRQBUTTON BOARD_BUTTON1 +#define MAX_IRQBUTTON BOARD_BUTTON1 +#define NUM_IRQBUTTONS 1 + +#define GPIO_BUTTON1 (GPIO_INPUT|GPIO_PULLUP|GPIO_EXTI|GPIO_PORTC|GPIO_PIN7) + /**************************************************************************** * Public Types ****************************************************************************/ diff --git a/configs/photon/src/photon_buttons.c b/configs/photon/src/photon_buttons.c new file mode 100644 index 0000000000..bca373bf75 --- /dev/null +++ b/configs/photon/src/photon_buttons.c @@ -0,0 +1,101 @@ +/**************************************************************************** + * configs/photon/src/photon_buttons.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Simon Piriou + * + * 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 "photon.h" + +#include "stm32_gpio.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_button_initialize + ****************************************************************************/ + +void board_button_initialize(void) +{ + /* Configure Photon button gpio as input */ + + stm32_configgpio(GPIO_BUTTON1); +} + +/**************************************************************************** + * Name: board_buttons + ****************************************************************************/ + +uint8_t board_buttons(void) +{ + /* Check the state of the only button */ + + if (stm32_gpioread(GPIO_BUTTON1)) + { + return BOARD_BUTTON1_BIT; + } + + return 0; +} + +#ifdef CONFIG_ARCH_IRQBUTTONS + +/**************************************************************************** + * Name: board_button_irq + ****************************************************************************/ + +int board_button_irq(int id, xcpt_t irqhandler, FAR void *arg) +{ + if (id != BOARD_BUTTON1) { + /* Invalid button id */ + return ERROR; + } + + /* Configure interrupt on falling edge only */ + + return stm32_gpiosetevent(GPIO_BUTTON1, false, true, false, irqhandler, arg); +} + +#endif /* CONFIG_ARCH_IRQBUTTONS */ diff --git a/configs/photon/src/photon_leds.c b/configs/photon/src/photon_leds.c new file mode 100644 index 0000000000..070d6d6455 --- /dev/null +++ b/configs/photon/src/photon_leds.c @@ -0,0 +1,86 @@ +/**************************************************************************** + * configs/photon/src/photon_leds.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Simon Piriou + * + * 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 "photon.h" + +#include "stm32_gpio.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_userled_initialize + ****************************************************************************/ + +void board_userled_initialize(void) +{ + /* Configure Photon LED gpio as output */ + + stm32_configgpio(GPIO_LED1); +} + +/**************************************************************************** + * Name: board_userled + ****************************************************************************/ + +void board_userled(int led, bool ledon) +{ + if (led == BOARD_LED1) + { + stm32_gpiowrite(GPIO_LED1, ledon); + } +} + +/**************************************************************************** + * Name: board_userled_all + ****************************************************************************/ + +void board_userled_all(uint8_t ledset) +{ + stm32_gpiowrite(GPIO_LED1, !!(ledset & BOARD_LED1_BIT)); +} diff --git a/configs/photon/src/stm32_appinit.c b/configs/photon/src/stm32_appinit.c index 40ac5e3fa7..7952e4ea0f 100644 --- a/configs/photon/src/stm32_appinit.c +++ b/configs/photon/src/stm32_appinit.c @@ -38,15 +38,15 @@ ****************************************************************************/ #include - #include #include -#include "photon.h" -#include -#include +#include +#include "photon.h" #include "stm32_wdg.h" +#include +#include /**************************************************************************** * Pre-processor Definitions @@ -89,6 +89,36 @@ int board_app_initialize(uintptr_t arg) { int ret = OK; +#ifdef CONFIG_USERLED +#ifdef CONFIG_USERLED_LOWER + /* Register the LED driver */ + + ret = userled_lower_initialize("/dev/userleds"); + if (ret != OK) + { + syslog(LOG_ERR, "ERROR: userled_lower_initialize() failed: %d\n", ret); + return ret; + } +#else + board_userled_initialize(); +#endif /* CONFIG_USERLED_LOWER */ +#endif /* CONFIG_USERLED */ + +#ifdef CONFIG_BUTTONS +#ifdef CONFIG_BUTTONS_LOWER + /* Register the BUTTON driver */ + + ret = btn_lower_initialize("/dev/buttons"); + if (ret != OK) + { + syslog(LOG_ERR, "ERROR: btn_lower_initialize() failed: %d\n", ret); + return ret; + } +#else + board_button_initialize(); +#endif /* CONFIG_BUTTONS_LOWER */ +#endif /* CONFIG_BUTTONS */ + #ifdef CONFIG_STM32_IWDG stm32_iwdginitialize("/dev/watchdog0", STM32_LSI_FREQUENCY); #endif @@ -100,7 +130,7 @@ int board_app_initialize(uintptr_t arg) ret = photon_watchdog_initialize(); if (ret != OK) { - serr("Failed to start watchdog thread: %d\n", errno); + syslog(LOG_ERR, "Failed to start watchdog thread: %d\n", ret); return ret; } #endif -- GitLab From e0f7b9582a24ac83c17baf361aac9a18a30f8c0d Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 11 Mar 2017 16:31:11 -0600 Subject: [PATCH 015/990] STM32: Review of last STM32 F2 PR. Progate changes to STM32 F4 and F7 OTGHS. Rename some configs/photon/src files. Naming can be either photon_ or stm32_ but must be consistent. --- arch/arm/src/stm32/stm32_otghsdev.c | 6 ++--- arch/arm/src/stm32/stm32f20xxx_rcc.c | 6 +++-- arch/arm/src/stm32/stm32f40xxx_rcc.c | 9 +++++-- arch/arm/src/stm32f7/stm32f74xx75xx_rcc.c | 9 +++++-- arch/arm/src/stm32f7/stm32f76xx77xx_rcc.c | 9 +++++-- configs/photon/include/board.h | 1 + configs/photon/src/Makefile | 6 ++--- configs/photon/src/stm32_appinit.c | 1 + .../src/{photon_buttons.c => stm32_buttons.c} | 25 +++++++++---------- .../src/{photon_leds.c => stm32_leds.c} | 6 +---- .../photon/src/{photon_wdt.c => stm32_wdt.c} | 2 +- 11 files changed, 47 insertions(+), 33 deletions(-) rename configs/photon/src/{photon_buttons.c => stm32_buttons.c} (89%) rename configs/photon/src/{photon_leds.c => stm32_leds.c} (93%) rename configs/photon/src/{photon_wdt.c => stm32_wdt.c} (99%) diff --git a/arch/arm/src/stm32/stm32_otghsdev.c b/arch/arm/src/stm32/stm32_otghsdev.c index 97474f2f43..c6fc64349e 100644 --- a/arch/arm/src/stm32/stm32_otghsdev.c +++ b/arch/arm/src/stm32/stm32_otghsdev.c @@ -5325,14 +5325,14 @@ static void stm32_hwinitialize(FAR struct stm32_usbdev_s *priv) * some bug / errata in the chip. */ - regval = stm32_getreg(STM32_RCC_AHB1LPENR); + regval = stm32_getreg(STM32_RCC_AHB1LPENR); regval &= ~RCC_AHB1ENR_OTGHSULPIEN; stm32_putreg(regval, STM32_RCC_AHB1LPENR); /* Enable the interrupts in the INTMSK */ - regval = (OTGHS_GINT_RXFLVL | OTGHS_GINT_USBSUSP | OTGHS_GINT_ENUMDNE | - OTGHS_GINT_IEP | OTGHS_GINT_OEP | OTGHS_GINT_USBRST); + regval = (OTGHS_GINT_RXFLVL | OTGHS_GINT_USBSUSP | OTGHS_GINT_ENUMDNE | + OTGHS_GINT_IEP | OTGHS_GINT_OEP | OTGHS_GINT_USBRST); #ifdef CONFIG_USBDEV_ISOCHRONOUS regval |= (OTGHS_GINT_IISOIXFR | OTGHS_GINT_IISOOXFR); diff --git a/arch/arm/src/stm32/stm32f20xxx_rcc.c b/arch/arm/src/stm32/stm32f20xxx_rcc.c index ad71714a80..4a7fd85740 100644 --- a/arch/arm/src/stm32/stm32f20xxx_rcc.c +++ b/arch/arm/src/stm32/stm32f20xxx_rcc.c @@ -196,13 +196,15 @@ static inline void rcc_enableahb1(void) /* USB OTG HS */ #ifndef BOARD_DISABLE_USBOTG_HSULPI - /* Enable clocking for OTG and external PHY */ + /* Enable clocking for USB OTG HS and external PHY */ regval |= (RCC_AHB1ENR_OTGHSEN | RCC_AHB1ENR_OTGHSULPIEN); #else + /* Enable only clocking for USB OTG HS */ + regval |= (RCC_AHB1ENR_OTGHSEN); #endif -#endif +#endif /* CONFIG_STM32_OTGHS */ putreg32(regval, STM32_RCC_AHB1ENR); /* Enable peripherals */ } diff --git a/arch/arm/src/stm32/stm32f40xxx_rcc.c b/arch/arm/src/stm32/stm32f40xxx_rcc.c index adda863cca..e83d4f2573 100644 --- a/arch/arm/src/stm32/stm32f40xxx_rcc.c +++ b/arch/arm/src/stm32/stm32f40xxx_rcc.c @@ -215,10 +215,15 @@ static inline void rcc_enableahb1(void) #endif #ifdef CONFIG_STM32_OTGHS - /* USB OTG HS */ +#if 0 /* ifndef BOARD_DISABLE_USBOTG_HSULPI */ + /* Enable clocking for USB OTG HS and external PHY */ - regval |= RCC_AHB1ENR_OTGHSEN; + regval |= (RCC_AHB1ENR_OTGHSEN | RCC_AHB1ENR_OTGHSULPIEN); +#else + /* Enable only clocking for USB OTG HS */ + regval |= RCC_AHB1ENR_OTGHSEN; +#endif #endif /* CONFIG_STM32_OTGHS */ #ifdef CONFIG_STM32_DMA2D diff --git a/arch/arm/src/stm32f7/stm32f74xx75xx_rcc.c b/arch/arm/src/stm32f7/stm32f74xx75xx_rcc.c index a10c399f88..4ce433efd7 100644 --- a/arch/arm/src/stm32f7/stm32f74xx75xx_rcc.c +++ b/arch/arm/src/stm32f7/stm32f74xx75xx_rcc.c @@ -225,10 +225,15 @@ static inline void rcc_enableahb1(void) #endif #ifdef CONFIG_STM32F7_OTGHS - /* USB OTG HS */ +#if 0 /* ifndef BOARD_DISABLE_USBOTG_HSULPI */ + /* Enable clocking for USB OTG HS and external PHY */ - regval |= RCC_AHB1ENR_OTGHSEN; + regval |= (RCC_AHB1ENR_OTGHSEN | RCC_AHB1ENR_OTGHSULPIEN); +#else + /* Enable only clocking for USB OTG HS */ + regval |= RCC_AHB1ENR_OTGHSEN; +#endif #endif /* CONFIG_STM32F7_OTGHS */ putreg32(regval, STM32_RCC_AHB1ENR); /* Enable peripherals */ diff --git a/arch/arm/src/stm32f7/stm32f76xx77xx_rcc.c b/arch/arm/src/stm32f7/stm32f76xx77xx_rcc.c index b390d422b4..42080ebb16 100644 --- a/arch/arm/src/stm32f7/stm32f76xx77xx_rcc.c +++ b/arch/arm/src/stm32f7/stm32f76xx77xx_rcc.c @@ -221,10 +221,15 @@ static inline void rcc_enableahb1(void) #endif #ifdef CONFIG_STM32F7_OTGHS - /* USB OTG HS */ +#if 0 /* ifndef BOARD_DISABLE_USBOTG_HSULPI */ + /* Enable clocking for USB OTG HS and external PHY */ - regval |= RCC_AHB1ENR_OTGHSEN; + regval |= (RCC_AHB1ENR_OTGHSEN | RCC_AHB1ENR_OTGHSULPIEN); +#else + /* Enable only clocking for USB OTG HS */ + regval |= RCC_AHB1ENR_OTGHSEN; +#endif #endif /* CONFIG_STM32F7_OTGHS */ putreg32(regval, STM32_RCC_AHB1ENR); /* Enable peripherals */ diff --git a/configs/photon/include/board.h b/configs/photon/include/board.h index 15ee036088..08b62d125b 100644 --- a/configs/photon/include/board.h +++ b/configs/photon/include/board.h @@ -148,6 +148,7 @@ /* USB OTG HS definitions ***********************************************************/ /* Do not enable external PHY clock or OTG_HS module will not work */ + #define BOARD_DISABLE_USBOTG_HSULPI 1 /* LED definitions ******************************************************************/ diff --git a/configs/photon/src/Makefile b/configs/photon/src/Makefile index f834e2c7fa..98a11afdc0 100644 --- a/configs/photon/src/Makefile +++ b/configs/photon/src/Makefile @@ -42,15 +42,15 @@ CSRCS += dfu_signature.c endif ifeq ($(CONFIG_BUTTONS),y) -CSRCS += photon_buttons.c +CSRCS += stm32_buttons.c endif ifeq ($(CONFIG_USERLED),y) -CSRCS += photon_leds.c +CSRCS += stm32_leds.c endif ifeq ($(CONFIG_PHOTON_WDG),y) -CSRCS += photon_wdt.c +CSRCS += stm32_wdt.c endif ifeq ($(CONFIG_STM32_OTGHS),y) diff --git a/configs/photon/src/stm32_appinit.c b/configs/photon/src/stm32_appinit.c index 7952e4ea0f..d2fcdf699c 100644 --- a/configs/photon/src/stm32_appinit.c +++ b/configs/photon/src/stm32_appinit.c @@ -134,5 +134,6 @@ int board_app_initialize(uintptr_t arg) return ret; } #endif + return ret; } diff --git a/configs/photon/src/photon_buttons.c b/configs/photon/src/stm32_buttons.c similarity index 89% rename from configs/photon/src/photon_buttons.c rename to configs/photon/src/stm32_buttons.c index bca373bf75..7c695dd5ef 100644 --- a/configs/photon/src/photon_buttons.c +++ b/configs/photon/src/stm32_buttons.c @@ -1,5 +1,5 @@ /**************************************************************************** - * configs/photon/src/photon_buttons.c + * configs/photon/src/stm32_buttons.c * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Simon Piriou @@ -38,17 +38,15 @@ ****************************************************************************/ #include + #include +#include #include #include "photon.h" #include "stm32_gpio.h" -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - /**************************************************************************** * Public Functions ****************************************************************************/ @@ -80,22 +78,23 @@ uint8_t board_buttons(void) return 0; } -#ifdef CONFIG_ARCH_IRQBUTTONS - /**************************************************************************** * Name: board_button_irq ****************************************************************************/ +#ifdef CONFIG_ARCH_IRQBUTTONS int board_button_irq(int id, xcpt_t irqhandler, FAR void *arg) { - if (id != BOARD_BUTTON1) { - /* Invalid button id */ - return ERROR; - } + if (id != BOARD_BUTTON1) + { + /* Invalid button id */ + + return -EINVAL; + } /* Configure interrupt on falling edge only */ - return stm32_gpiosetevent(GPIO_BUTTON1, false, true, false, irqhandler, arg); + return stm32_gpiosetevent(GPIO_BUTTON1, false, true, false, + irqhandler, arg); } - #endif /* CONFIG_ARCH_IRQBUTTONS */ diff --git a/configs/photon/src/photon_leds.c b/configs/photon/src/stm32_leds.c similarity index 93% rename from configs/photon/src/photon_leds.c rename to configs/photon/src/stm32_leds.c index 070d6d6455..076df40ad6 100644 --- a/configs/photon/src/photon_leds.c +++ b/configs/photon/src/stm32_leds.c @@ -1,5 +1,5 @@ /**************************************************************************** - * configs/photon/src/photon_leds.c + * configs/photon/src/stm32_leds.c * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Simon Piriou @@ -45,10 +45,6 @@ #include "stm32_gpio.h" -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - /**************************************************************************** * Public Functions ****************************************************************************/ diff --git a/configs/photon/src/photon_wdt.c b/configs/photon/src/stm32_wdt.c similarity index 99% rename from configs/photon/src/photon_wdt.c rename to configs/photon/src/stm32_wdt.c index beee501404..1df96707c6 100644 --- a/configs/photon/src/photon_wdt.c +++ b/configs/photon/src/stm32_wdt.c @@ -1,5 +1,5 @@ /************************************************************************************ - * configs/photon/src/photon_wdt.c + * configs/photon/src/stm32_wdt.c * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Simon Piriou -- GitLab From 9b11187b2a62604a832d1318ac5f77a570a84474 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 11 Mar 2017 18:00:38 -0600 Subject: [PATCH 016/990] STM32 OTG HS: A little research reveals that only the F2 RCC initialization set the OTGHSULPIEN bit and Photon is the only F2 board configuration that uses OTG . Therefore, we can simplify the conditional logic of the last PR. Negative logic was used (#ifndef BOARD_DISABLE_USBOTG_HSULPI) to prevent bad settings in other configurations. But give these facts, the preferred positive logic now makes more sense (#ifdef BOARD_ENABLE_USBOTG_HSULPI). --- arch/arm/src/stm32/stm32f20xxx_rcc.c | 4 +--- arch/arm/src/stm32/stm32f40xxx_rcc.c | 2 +- arch/arm/src/stm32f7/stm32f74xx75xx_rcc.c | 2 +- arch/arm/src/stm32f7/stm32f76xx77xx_rcc.c | 2 +- configs/photon/include/board.h | 2 +- 5 files changed, 5 insertions(+), 7 deletions(-) diff --git a/arch/arm/src/stm32/stm32f20xxx_rcc.c b/arch/arm/src/stm32/stm32f20xxx_rcc.c index 4a7fd85740..fac0dc911d 100644 --- a/arch/arm/src/stm32/stm32f20xxx_rcc.c +++ b/arch/arm/src/stm32/stm32f20xxx_rcc.c @@ -193,9 +193,7 @@ static inline void rcc_enableahb1(void) #endif #ifdef CONFIG_STM32_OTGHS - /* USB OTG HS */ - -#ifndef BOARD_DISABLE_USBOTG_HSULPI +#ifdef BOARD_ENABLE_USBOTG_HSULPI /* Enable clocking for USB OTG HS and external PHY */ regval |= (RCC_AHB1ENR_OTGHSEN | RCC_AHB1ENR_OTGHSULPIEN); diff --git a/arch/arm/src/stm32/stm32f40xxx_rcc.c b/arch/arm/src/stm32/stm32f40xxx_rcc.c index e83d4f2573..dfed9d8fce 100644 --- a/arch/arm/src/stm32/stm32f40xxx_rcc.c +++ b/arch/arm/src/stm32/stm32f40xxx_rcc.c @@ -215,7 +215,7 @@ static inline void rcc_enableahb1(void) #endif #ifdef CONFIG_STM32_OTGHS -#if 0 /* ifndef BOARD_DISABLE_USBOTG_HSULPI */ +#ifdef BOARD_ENABLE_USBOTG_HSULPI /* Enable clocking for USB OTG HS and external PHY */ regval |= (RCC_AHB1ENR_OTGHSEN | RCC_AHB1ENR_OTGHSULPIEN); diff --git a/arch/arm/src/stm32f7/stm32f74xx75xx_rcc.c b/arch/arm/src/stm32f7/stm32f74xx75xx_rcc.c index 4ce433efd7..7a36d7c7ee 100644 --- a/arch/arm/src/stm32f7/stm32f74xx75xx_rcc.c +++ b/arch/arm/src/stm32f7/stm32f74xx75xx_rcc.c @@ -225,7 +225,7 @@ static inline void rcc_enableahb1(void) #endif #ifdef CONFIG_STM32F7_OTGHS -#if 0 /* ifndef BOARD_DISABLE_USBOTG_HSULPI */ +#ifdef BOARD_ENABLE_USBOTG_HSULPI /* Enable clocking for USB OTG HS and external PHY */ regval |= (RCC_AHB1ENR_OTGHSEN | RCC_AHB1ENR_OTGHSULPIEN); diff --git a/arch/arm/src/stm32f7/stm32f76xx77xx_rcc.c b/arch/arm/src/stm32f7/stm32f76xx77xx_rcc.c index 42080ebb16..5a08806eb3 100644 --- a/arch/arm/src/stm32f7/stm32f76xx77xx_rcc.c +++ b/arch/arm/src/stm32f7/stm32f76xx77xx_rcc.c @@ -221,7 +221,7 @@ static inline void rcc_enableahb1(void) #endif #ifdef CONFIG_STM32F7_OTGHS -#if 0 /* ifndef BOARD_DISABLE_USBOTG_HSULPI */ +#ifdef BOARD_ENABLE_USBOTG_HSULPI /* Enable clocking for USB OTG HS and external PHY */ regval |= (RCC_AHB1ENR_OTGHSEN | RCC_AHB1ENR_OTGHSULPIEN); diff --git a/configs/photon/include/board.h b/configs/photon/include/board.h index 08b62d125b..4db3368d1b 100644 --- a/configs/photon/include/board.h +++ b/configs/photon/include/board.h @@ -149,7 +149,7 @@ /* USB OTG HS definitions ***********************************************************/ /* Do not enable external PHY clock or OTG_HS module will not work */ -#define BOARD_DISABLE_USBOTG_HSULPI 1 +#undef BOARD_ENABLE_USBOTG_HSULPI /* LED definitions ******************************************************************/ -- GitLab From 98a98a0c8b486ca828b4bce8a819d503ead96ba3 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 12 Mar 2017 07:20:10 -0600 Subject: [PATCH 017/990] Minor change for consistency with a previous commit. --- arch/arm/src/stm32/stm32_otghsdev.c | 2 ++ arch/arm/src/stm32f7/stm32_otgdev.c | 2 +- 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/arch/arm/src/stm32/stm32_otghsdev.c b/arch/arm/src/stm32/stm32_otghsdev.c index c6fc64349e..ba02546aac 100644 --- a/arch/arm/src/stm32/stm32_otghsdev.c +++ b/arch/arm/src/stm32/stm32_otghsdev.c @@ -5319,6 +5319,7 @@ static void stm32_hwinitialize(FAR struct stm32_usbdev_s *priv) stm32_putreg(0xbfffffff, STM32_OTGHS_GINTSTS); +#ifndef BOARD_ENABLE_USBOTG_HSULPI /* Disable the ULPI Clock enable in RCC AHB1 Register. This must * be done because if both the ULPI and the FS PHY clock enable bits * are set at the same time, the ARM never awakens from WFI due to @@ -5328,6 +5329,7 @@ static void stm32_hwinitialize(FAR struct stm32_usbdev_s *priv) regval = stm32_getreg(STM32_RCC_AHB1LPENR); regval &= ~RCC_AHB1ENR_OTGHSULPIEN; stm32_putreg(regval, STM32_RCC_AHB1LPENR); +#endif /* Enable the interrupts in the INTMSK */ diff --git a/arch/arm/src/stm32f7/stm32_otgdev.c b/arch/arm/src/stm32f7/stm32_otgdev.c index ff2a6e026e..1ee746da2d 100644 --- a/arch/arm/src/stm32f7/stm32_otgdev.c +++ b/arch/arm/src/stm32f7/stm32_otgdev.c @@ -5446,7 +5446,7 @@ static void stm32_hwinitialize(FAR struct stm32_usbdev_s *priv) regval &= OTG_GINT_RESERVED; stm32_putreg(regval | OTG_GINT_RC_W1, STM32_OTG_GINTSTS); -#if defined(CONFIG_STM32F7_OTGHS) +#if defined(CONFIG_STM32F7_OTGHS) && !defined(BOARD_ENABLE_USBOTG_HSULPI) /* Disable the ULPI Clock enable in RCC AHB1 Register. This must * be done because if both the ULPI and the FS PHY clock enable bits * are set at the same time, the ARM never awakens from WFI due to -- GitLab From d9cdb6c3830200e7c66d7e6ab0fd7afa2871b228 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 12 Mar 2017 08:39:30 -0600 Subject: [PATCH 018/990] STM32; OTG host implementations of stm32_in_transfer() must obey the polling interval for the case of isochronous and itnerrupt endpoints. --- arch/arm/src/stm32/stm32_otgfshost.c | 51 +++++++++++++++++++++--- arch/arm/src/stm32/stm32_otghshost.c | 51 +++++++++++++++++++++--- arch/arm/src/stm32f7/stm32_otghost.c | 51 +++++++++++++++++++++--- arch/arm/src/stm32l4/stm32l4_otgfshost.c | 51 +++++++++++++++++++++--- 4 files changed, 180 insertions(+), 24 deletions(-) diff --git a/arch/arm/src/stm32/stm32_otgfshost.c b/arch/arm/src/stm32/stm32_otgfshost.c index 7451289b27..2163b2eae9 100644 --- a/arch/arm/src/stm32/stm32_otgfshost.c +++ b/arch/arm/src/stm32/stm32_otgfshost.c @@ -212,6 +212,7 @@ struct stm32_chan_s uint8_t eptype; /* See OTGFS_EPTYPE_* definitions */ uint8_t funcaddr; /* Device function address */ uint8_t speed; /* Device speed */ + uint8_t interval; /* Interrupt/isochronous EP polling interval */ uint8_t pid; /* Data PID */ uint8_t npackets; /* Number of packets (for data toggle) */ bool inuse; /* True: This channel is "in use" */ @@ -1210,6 +1211,7 @@ static int stm32_ctrlchan_alloc(FAR struct stm32_usbhost_s *priv, chan->eptype = OTGFS_EPTYPE_CTRL; chan->funcaddr = funcaddr; chan->speed = speed; + chan->interval = 0; chan->maxpacket = STM32_EP0_DEF_PACKET_SIZE; chan->indata1 = false; chan->outdata1 = false; @@ -1234,6 +1236,7 @@ static int stm32_ctrlchan_alloc(FAR struct stm32_usbhost_s *priv, chan->eptype = OTGFS_EPTYPE_CTRL; chan->funcaddr = funcaddr; chan->speed = speed; + chan->interval = 0; chan->maxpacket = STM32_EP0_DEF_PACKET_SIZE; chan->indata1 = false; chan->outdata1 = false; @@ -1363,6 +1366,7 @@ static int stm32_xfrep_alloc(FAR struct stm32_usbhost_s *priv, chan->eptype = epdesc->xfrtype; chan->funcaddr = hport->funcaddr; chan->speed = hport->speed; + chan->interval = epdesc->interval; chan->maxpacket = epdesc->mxpacketsize; chan->indata1 = false; chan->outdata1 = false; @@ -1893,6 +1897,8 @@ static ssize_t stm32_in_transfer(FAR struct stm32_usbhost_s *priv, int chidx, } else { + useconds_t delay; + /* Get the elapsed time. Has the timeout elapsed? * if not then try again. */ @@ -1907,13 +1913,46 @@ static ssize_t stm32_in_transfer(FAR struct stm32_usbhost_s *priv, int chidx, return (ssize_t)ret; } - /* Wait a bit before retrying after a NAK. - * - * REVISIT: This is intended to give the CPU a break from - * the tight polling loop. But are there performance issues? - */ + /* Wait a bit before retrying after a NAK. */ + + if (chan->eptype == OTGFS_HCCHAR_EPTYP_INTR) + { + /* For interrupt (and isochronous) endpoints, the + * polling rate is determined by the bInterval field + * of the endpoint descriptor (in units of frames + * which we treat as milliseconds here). + */ + + if (chan->interval > 0) + { + /* Convert the delay to units of microseconds */ + + delay = (useconds_t)chan->interval * 1000; + } + else + { + /* Out of range! For interrupt endpoints, the valid + * range is 1-255 frames. Assume one frame. + */ + + delay = 1000; + } + } + else + { + /* For Isochronous endpoints, bInterval must be 1. Bulk + * endpoints do not have a polling interval. Rather, + * the should wait until data is received. + * + * REVISIT: For bulk endpoints this 1 msec delay is only + * intended to give the CPU a break from the bulk EP tight + * polling loop. But are there performance issues? + */ + + delay = 1000; + } - usleep(1000); + usleep(delay); } } else diff --git a/arch/arm/src/stm32/stm32_otghshost.c b/arch/arm/src/stm32/stm32_otghshost.c index 85092d89a9..7f16593f63 100644 --- a/arch/arm/src/stm32/stm32_otghshost.c +++ b/arch/arm/src/stm32/stm32_otghshost.c @@ -217,6 +217,7 @@ struct stm32_chan_s uint8_t eptype; /* See OTGHS_EPTYPE_* definitions */ uint8_t funcaddr; /* Device function address */ uint8_t speed; /* Device speed */ + uint8_t interval; /* Interrupt/isochronous EP polling interval */ uint8_t pid; /* Data PID */ uint8_t npackets; /* Number of packets (for data toggle) */ bool inuse; /* True: This channel is "in use" */ @@ -1215,6 +1216,7 @@ static int stm32_ctrlchan_alloc(FAR struct stm32_usbhost_s *priv, chan->eptype = OTGHS_EPTYPE_CTRL; chan->funcaddr = funcaddr; chan->speed = speed; + chan->interval = 0; chan->maxpacket = STM32_EP0_DEF_PACKET_SIZE; chan->indata1 = false; chan->outdata1 = false; @@ -1239,6 +1241,7 @@ static int stm32_ctrlchan_alloc(FAR struct stm32_usbhost_s *priv, chan->eptype = OTGHS_EPTYPE_CTRL; chan->funcaddr = funcaddr; chan->speed = speed; + chan->interval = 0; chan->maxpacket = STM32_EP0_DEF_PACKET_SIZE; chan->indata1 = false; chan->outdata1 = false; @@ -1368,6 +1371,7 @@ static int stm32_xfrep_alloc(FAR struct stm32_usbhost_s *priv, chan->eptype = epdesc->xfrtype; chan->funcaddr = hport->funcaddr; chan->speed = hport->speed; + chan->interval = epdesc->interval; chan->maxpacket = epdesc->mxpacketsize; chan->indata1 = false; chan->outdata1 = false; @@ -1898,6 +1902,8 @@ static ssize_t stm32_in_transfer(FAR struct stm32_usbhost_s *priv, int chidx, } else { + useconds_t delay; + /* Get the elapsed time. Has the timeout elapsed? * if not then try again. */ @@ -1912,13 +1918,46 @@ static ssize_t stm32_in_transfer(FAR struct stm32_usbhost_s *priv, int chidx, return (ssize_t)ret; } - /* Wait a bit before retrying after a NAK. - * - * REVISIT: This is intended to give the CPU a break from - * the tight polling loop. But are there performance issues? - */ + /* Wait a bit before retrying after a NAK. */ + + if (chan->eptype == OTGFS_HCCHAR_EPTYP_INTR) + { + /* For interrupt (and isochronous) endpoints, the + * polling rate is determined by the bInterval field + * of the endpoint descriptor (in units of frames + * which we treat as milliseconds here). + */ + + if (chan->interval > 0) + { + /* Convert the delay to units of microseconds */ + + delay = (useconds_t)chan->interval * 1000; + } + else + { + /* Out of range! For interrupt endpoints, the valid + * range is 1-255 frames. Assume one frame. + */ + + delay = 1000; + } + } + else + { + /* For Isochronous endpoints, bInterval must be 1. Bulk + * endpoints do not have a polling interval. Rather, + * the should wait until data is received. + * + * REVISIT: For bulk endpoints this 1 msec delay is only + * intended to give the CPU a break from the bulk EP tight + * polling loop. But are there performance issues? + */ + + delay = 1000; + } - usleep(1000); + usleep(delay); } } else diff --git a/arch/arm/src/stm32f7/stm32_otghost.c b/arch/arm/src/stm32f7/stm32_otghost.c index a89be679b9..0d2dfd24c8 100644 --- a/arch/arm/src/stm32f7/stm32_otghost.c +++ b/arch/arm/src/stm32f7/stm32_otghost.c @@ -214,6 +214,7 @@ struct stm32_chan_s uint8_t eptype; /* See OTG_EPTYPE_* definitions */ uint8_t funcaddr; /* Device function address */ uint8_t speed; /* Device speed */ + uint8_t interval; /* Interrupt/isochronous EP polling interval */ uint8_t pid; /* Data PID */ uint8_t npackets; /* Number of packets (for data toggle) */ bool inuse; /* True: This channel is "in use" */ @@ -1209,6 +1210,7 @@ static int stm32_ctrlchan_alloc(FAR struct stm32_usbhost_s *priv, chan->eptype = OTG_EPTYPE_CTRL; chan->funcaddr = funcaddr; chan->speed = speed; + chan->interval = 0; chan->maxpacket = STM32_EP0_DEF_PACKET_SIZE; chan->indata1 = false; chan->outdata1 = false; @@ -1233,6 +1235,7 @@ static int stm32_ctrlchan_alloc(FAR struct stm32_usbhost_s *priv, chan->eptype = OTG_EPTYPE_CTRL; chan->funcaddr = funcaddr; chan->speed = speed; + chan->interval = 0; chan->maxpacket = STM32_EP0_DEF_PACKET_SIZE; chan->indata1 = false; chan->outdata1 = false; @@ -1362,6 +1365,7 @@ static int stm32_xfrep_alloc(FAR struct stm32_usbhost_s *priv, chan->eptype = epdesc->xfrtype; chan->funcaddr = hport->funcaddr; chan->speed = hport->speed; + chan->interval = epdesc->interval; chan->maxpacket = epdesc->mxpacketsize; chan->indata1 = false; chan->outdata1 = false; @@ -1892,6 +1896,8 @@ static ssize_t stm32_in_transfer(FAR struct stm32_usbhost_s *priv, int chidx, } else { + useconds_t delay; + /* Get the elapsed time. Has the timeout elapsed? * if not then try again. */ @@ -1906,13 +1912,46 @@ static ssize_t stm32_in_transfer(FAR struct stm32_usbhost_s *priv, int chidx, return (ssize_t)ret; } - /* Wait a bit before retrying after a NAK. - * - * REVISIT: This is intended to give the CPU a break from - * the tight polling loop. But are there performance issues? - */ + /* Wait a bit before retrying after a NAK. */ + + if (chan->eptype == OTGFS_HCCHAR_EPTYP_INTR) + { + /* For interrupt (and isochronous) endpoints, the + * polling rate is determined by the bInterval field + * of the endpoint descriptor (in units of frames + * which we treat as milliseconds here). + */ + + if (chan->interval > 0) + { + /* Convert the delay to units of microseconds */ + + delay = (useconds_t)chan->interval * 1000; + } + else + { + /* Out of range! For interrupt endpoints, the valid + * range is 1-255 frames. Assume one frame. + */ + + delay = 1000; + } + } + else + { + /* For Isochronous endpoints, bInterval must be 1. Bulk + * endpoints do not have a polling interval. Rather, + * the should wait until data is received. + * + * REVISIT: For bulk endpoints this 1 msec delay is only + * intended to give the CPU a break from the bulk EP tight + * polling loop. But are there performance issues? + */ + + delay = 1000; + } - usleep(1000); + usleep(delay); } } else diff --git a/arch/arm/src/stm32l4/stm32l4_otgfshost.c b/arch/arm/src/stm32l4/stm32l4_otgfshost.c index a488825b9c..5b62256f14 100644 --- a/arch/arm/src/stm32l4/stm32l4_otgfshost.c +++ b/arch/arm/src/stm32l4/stm32l4_otgfshost.c @@ -213,6 +213,7 @@ struct stm32l4_chan_s uint8_t eptype; /* See OTGFS_EPTYPE_* definitions */ uint8_t funcaddr; /* Device function address */ uint8_t speed; /* Device speed */ + uint8_t interval; /* Interrupt/isochronous EP polling interval */ uint8_t pid; /* Data PID */ uint8_t npackets; /* Number of packets (for data toggle) */ bool inuse; /* True: This channel is "in use" */ @@ -1212,6 +1213,7 @@ static int stm32l4_ctrlchan_alloc(FAR struct stm32l4_usbhost_s *priv, chan->eptype = OTGFS_EPTYPE_CTRL; chan->funcaddr = funcaddr; chan->speed = speed; + chan->interval = 0; chan->maxpacket = STM32L4_EP0_DEF_PACKET_SIZE; chan->indata1 = false; chan->outdata1 = false; @@ -1236,6 +1238,7 @@ static int stm32l4_ctrlchan_alloc(FAR struct stm32l4_usbhost_s *priv, chan->eptype = OTGFS_EPTYPE_CTRL; chan->funcaddr = funcaddr; chan->speed = speed; + chan->interval = 0; chan->maxpacket = STM32L4_EP0_DEF_PACKET_SIZE; chan->indata1 = false; chan->outdata1 = false; @@ -1365,6 +1368,7 @@ static int stm32l4_xfrep_alloc(FAR struct stm32l4_usbhost_s *priv, chan->eptype = epdesc->xfrtype; chan->funcaddr = hport->funcaddr; chan->speed = hport->speed; + chan->interval = epdesc->interval; chan->maxpacket = epdesc->mxpacketsize; chan->indata1 = false; chan->outdata1 = false; @@ -1897,6 +1901,8 @@ static ssize_t stm32l4_in_transfer(FAR struct stm32l4_usbhost_s *priv, } else { + useconds_t delay; + /* Get the elapsed time. Has the timeout elapsed? * if not then try again. */ @@ -1911,13 +1917,46 @@ static ssize_t stm32l4_in_transfer(FAR struct stm32l4_usbhost_s *priv, return (ssize_t)ret; } - /* Wait a bit before retrying after a NAK. - * - * REVISIT: This is intended to give the CPU a break from - * the tight polling loop. But are there performance issues? - */ + /* Wait a bit before retrying after a NAK. */ + + if (chan->eptype == OTGFS_HCCHAR_EPTYP_INTR) + { + /* For interrupt (and isochronous) endpoints, the + * polling rate is determined by the bInterval field + * of the endpoint descriptor (in units of frames + * which we treat as milliseconds here). + */ + + if (chan->interval > 0) + { + /* Convert the delay to units of microseconds */ + + delay = (useconds_t)chan->interval * 1000; + } + else + { + /* Out of range! For interrupt endpoints, the valid + * range is 1-255 frames. Assume one frame. + */ + + delay = 1000; + } + } + else + { + /* For Isochronous endpoints, bInterval must be 1. Bulk + * endpoints do not have a polling interval. Rather, + * the should wait until data is received. + * + * REVISIT: For bulk endpoints this 1 msec delay is only + * intended to give the CPU a break from the bulk EP tight + * polling loop. But are there performance issues? + */ + + delay = 1000; + } - usleep(1000); + usleep(delay); } } else -- GitLab From e10ce5ce5100373e3e1e40544771b57a2577ae38 Mon Sep 17 00:00:00 2001 From: Simon Piriou Date: Sun, 12 Mar 2017 16:48:09 +0100 Subject: [PATCH 019/990] Photon: add basic support for wlan chip --- configs/photon/Kconfig | 4 + configs/photon/include/board.h | 35 ++- configs/photon/src/Makefile | 4 + configs/photon/src/photon.h | 32 +++ configs/photon/src/stm32_appinit.c | 12 + configs/photon/src/stm32_wlan.c | 129 +++++++++ drivers/wireless/Kconfig | 9 + drivers/wireless/Make.defs | 6 + drivers/wireless/ieee80211/Kconfig | 20 ++ drivers/wireless/ieee80211/Make.defs | 53 ++++ drivers/wireless/ieee80211/bcmf_sdio.c | 271 ++++++++++++++++++ include/nuttx/wireless/ieee80211/bcmf_board.h | 110 +++++++ include/nuttx/wireless/ieee80211/bcmf_sdio.h | 86 ++++++ 13 files changed, 770 insertions(+), 1 deletion(-) create mode 100644 configs/photon/src/stm32_wlan.c create mode 100644 drivers/wireless/ieee80211/Kconfig create mode 100644 drivers/wireless/ieee80211/Make.defs create mode 100644 drivers/wireless/ieee80211/bcmf_sdio.c create mode 100644 include/nuttx/wireless/ieee80211/bcmf_board.h create mode 100644 include/nuttx/wireless/ieee80211/bcmf_sdio.h diff --git a/configs/photon/Kconfig b/configs/photon/Kconfig index 408fbc81d4..f76203d6c0 100644 --- a/configs/photon/Kconfig +++ b/configs/photon/Kconfig @@ -51,4 +51,8 @@ config PHOTON_WDG_THREAD_STACKSIZE endif # PHOTON_WDG_THREAD endif # PHOTON_WDG +config PHOTON_WLAN + bool "Enable WLAN chip support" + depends on IEEE80211_BROADCOM_FULLMAC_SDIO + endif diff --git a/configs/photon/include/board.h b/configs/photon/include/board.h index 4db3368d1b..8c2fc655e3 100644 --- a/configs/photon/include/board.h +++ b/configs/photon/include/board.h @@ -43,7 +43,7 @@ #include #ifndef __ASSEMBLY__ -# include +# include #endif #include "stm32_rcc.h" @@ -171,6 +171,39 @@ # define GPIO_USART1_TX GPIO_USART1_TX_1 #endif +/* SDIO definitions *****************************************************************/ + +/* Note that slower clocking is required when DMA is disabled in order + * to avoid RX overrun/TX underrun errors due to delayed responses + * to service FIFOs in interrupt driven mode. + * + * These values have not been tuned!!! + * + * SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(118+2)=400 KHz + */ + +#define SDIO_INIT_CLKDIV (118 << SDIO_CLKCR_CLKDIV_SHIFT) + +/* DMA ON: SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(1+2)=16 MHz + * DMA OFF: SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(2+2)=12 MHz + */ + +#ifdef CONFIG_SDIO_DMA +# define SDIO_MMCXFR_CLKDIV (1 << SDIO_CLKCR_CLKDIV_SHIFT) +#else +# define SDIO_MMCXFR_CLKDIV (2 << SDIO_CLKCR_CLKDIV_SHIFT) +#endif + +/* DMA ON: SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(1+2)=16 MHz + * DMA OFF: SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(2+2)=12 MHz + */ + +#ifdef CONFIG_SDIO_DMA +# define SDIO_SDXFR_CLKDIV (1 << SDIO_CLKCR_CLKDIV_SHIFT) +#else +# define SDIO_SDXFR_CLKDIV (2 << SDIO_CLKCR_CLKDIV_SHIFT) +#endif + /************************************************************************************ * Public Data ************************************************************************************/ diff --git a/configs/photon/src/Makefile b/configs/photon/src/Makefile index 98a11afdc0..5d9501759c 100644 --- a/configs/photon/src/Makefile +++ b/configs/photon/src/Makefile @@ -53,6 +53,10 @@ ifeq ($(CONFIG_PHOTON_WDG),y) CSRCS += stm32_wdt.c endif +ifeq ($(CONFIG_PHOTON_WLAN),y) +CSRCS += stm32_wlan.c +endif + ifeq ($(CONFIG_STM32_OTGHS),y) CSRCS += stm32_usb.c endif diff --git a/configs/photon/src/photon.h b/configs/photon/src/photon.h index ec160684f6..4e0f312b6c 100644 --- a/configs/photon/src/photon.h +++ b/configs/photon/src/photon.h @@ -61,6 +61,20 @@ #define GPIO_BUTTON1 (GPIO_INPUT|GPIO_PULLUP|GPIO_EXTI|GPIO_PORTC|GPIO_PIN7) +/* WLAN chip */ + +#define SDIO_WLAN0_SLOTNO 0 /* Photon board has only one sdio device */ +#define SDIO_WLAN0_MINOR 0 /* Register "wlan0" device */ + +#define GPIO_WLAN0_RESET (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN1) + +#define GPIO_WLAN0_32K_CLK (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN1) + +#define GPIO_WLAN0_OOB_INT (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|\ + GPIO_PORTB|GPIO_PIN0) + /**************************************************************************** * Public Types ****************************************************************************/ @@ -93,6 +107,24 @@ int photon_watchdog_initialize(void); #endif +/**************************************************************************** + * Name: photon_wlan_initialize + * + * Description: + * Initialize wlan hardware and driver for Photon board. + * + * Input parameters: + * None + * + * Returned Value: + * Zero on success; a negated errno value on failure. + * + ****************************************************************************/ + +#ifdef CONFIG_PHOTON_WLAN +int photon_wlan_initialize(void); +#endif + /**************************************************************************** * Name: stm32_usbinitialize * diff --git a/configs/photon/src/stm32_appinit.c b/configs/photon/src/stm32_appinit.c index d2fcdf699c..dc2899789f 100644 --- a/configs/photon/src/stm32_appinit.c +++ b/configs/photon/src/stm32_appinit.c @@ -135,5 +135,17 @@ int board_app_initialize(uintptr_t arg) } #endif +#ifdef CONFIG_PHOTON_WLAN + + /* Initialize wlan driver and hardware */ + + ret = photon_wlan_initialize(); + if (ret != OK) + { + syslog(LOG_ERR, "Failed to initialize wlan: %d\n", ret); + return ret; + } +#endif + return ret; } diff --git a/configs/photon/src/stm32_wlan.c b/configs/photon/src/stm32_wlan.c new file mode 100644 index 0000000000..a0b19e4e0f --- /dev/null +++ b/configs/photon/src/stm32_wlan.c @@ -0,0 +1,129 @@ +/**************************************************************************** + * configs/photon/src/stm32_wlan.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Simon Piriou + * + * 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 "photon.h" + +#include "stm32_gpio.h" +#include "stm32_sdio.h" + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: bcmf_board_reset + ****************************************************************************/ + +void bcmf_board_reset(int minor, bool reset) +{ + if (minor != SDIO_WLAN0_MINOR) + { + return; + } + + stm32_gpiowrite(GPIO_WLAN0_RESET, !reset); +} + +/**************************************************************************** + * Name: bcmf_board_power + ****************************************************************************/ + +void bcmf_board_power(int minor, bool power) +{ + /* Power signal is not used on Photon board */ +} + +/**************************************************************************** + * Name: bcmf_board_initialize + ****************************************************************************/ + +void bcmf_board_initialize(int minor) +{ + if (minor != SDIO_WLAN0_MINOR) + { + return; + } + + /* Configure reset pin */ + + stm32_configgpio(GPIO_WLAN0_RESET); + + /* Put wlan chip in reset state */ + + bcmf_board_reset(minor, true); +} + +/**************************************************************************** + * Name: photon_wlan_initialize + ****************************************************************************/ + +int photon_wlan_initialize() +{ + int ret; + struct sdio_dev_s *sdio_dev; + + /* Initialize sdio interface */ + _info("Initializing SDIO slot %d\n", SDIO_WLAN0_SLOTNO); + + sdio_dev = sdio_initialize(SDIO_WLAN0_SLOTNO); + + if (!sdio_dev) + { + _err("ERROR: Failed to initialize SDIO with slot %d\n", + SDIO_WLAN0_SLOTNO); + return ERROR; + } + + /* Bind the SDIO interface to the bcmf driver */ + ret = bcmf_sdio_initialize(SDIO_WLAN0_MINOR, sdio_dev); + + if (ret != OK) + { + _err("ERROR: Failed to bind SDIO to bcmf driver\n"); + /* FIXME deinitialize sdio device */ + return ERROR; + } + return OK; +} diff --git a/drivers/wireless/Kconfig b/drivers/wireless/Kconfig index a3537b85cf..a3bab81d21 100644 --- a/drivers/wireless/Kconfig +++ b/drivers/wireless/Kconfig @@ -26,6 +26,15 @@ menuconfig DRIVERS_IEEE802154 source drivers/wireless/ieee802154/Kconfig +menuconfig DRIVERS_IEEE80211 + bool "IEEE 802.11 Device Support" + default n + depends on EXPERIMENTAL + ---help--- + This directory holds implementations of IEEE802.11 device drivers. + +source drivers/wireless/ieee80211/Kconfig + config WL_NRF24L01 bool "nRF24l01+ transceiver support" default n diff --git a/drivers/wireless/Make.defs b/drivers/wireless/Make.defs index 14ffb31208..d6f1df5372 100644 --- a/drivers/wireless/Make.defs +++ b/drivers/wireless/Make.defs @@ -41,6 +41,12 @@ ifeq ($(CONFIG_DRIVERS_IEEE802154),y) include wireless$(DELIM)ieee802154$(DELIM)Make.defs endif +# Include IEEE 802.11 support + +ifeq ($(CONFIG_DRIVERS_IEEE80211),y) +include wireless$(DELIM)ieee80211$(DELIM)Make.defs +endif + # Include wireless drivers ifeq ($(CONFIG_WL_CC1101),y) diff --git a/drivers/wireless/ieee80211/Kconfig b/drivers/wireless/ieee80211/Kconfig new file mode 100644 index 0000000000..ec3952c129 --- /dev/null +++ b/drivers/wireless/ieee80211/Kconfig @@ -0,0 +1,20 @@ +# +# For a description of the syntax of this configuration file, +# see the file kconfig-language.txt in the NuttX tools repository. +# + +if DRIVERS_IEEE80211 + +config IEEE80211_BROADCOM_FULLMAC + bool + +config IEEE80211_BROADCOM_FULLMAC_SDIO + bool "Broadcom FullMAC driver on SDIO bus" + depends on ARCH_HAVE_SDIO + select IEEE80211_BROADCOM_FULLMAC + default n + ---help--- + This selection enables support for broadcom + FullMAC-compliant devices using SDIO bus. + +endif # DRIVERS_IEEE80211 diff --git a/drivers/wireless/ieee80211/Make.defs b/drivers/wireless/ieee80211/Make.defs new file mode 100644 index 0000000000..712ce5d1da --- /dev/null +++ b/drivers/wireless/ieee80211/Make.defs @@ -0,0 +1,53 @@ +############################################################################ +# drivers/wireless/ieee80211/Make.defs +# +# Copyright (C) 2017 Gregory Nutt. 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. +# +############################################################################ + +# Include nothing if IEEE 802.11 is disabled + +ifeq ($(CONFIG_DRIVERS_IEEE80211),y) + +# Include common IEEE 802.11 files into the build + +# Include IEEE 802.11 drivers into the build + +ifeq ($(CONFIG_IEEE80211_BROADCOM_FULLMAC_SDIO),y) + CSRCS += bcmf_sdio.c +endif + +# Include IEEE 802.11 build support + +DEPPATH += --dep-path wireless$(DELIM)ieee80211 +VPATH += :wireless$(DELIM)ieee80211 +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)$(DELIM)drivers$(DELIM)wireless$(DELIM)ieee80211} + +endif # CONFIG_DRIVERS_IEEE80211 diff --git a/drivers/wireless/ieee80211/bcmf_sdio.c b/drivers/wireless/ieee80211/bcmf_sdio.c new file mode 100644 index 0000000000..b1ea523ba2 --- /dev/null +++ b/drivers/wireless/ieee80211/bcmf_sdio.c @@ -0,0 +1,271 @@ +/**************************************************************************** + * drivers/wireless/ieee80211/bcmf_sdio.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Simon Piriou + * + * 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 +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define BCMF_DEVICE_RESET_DELAY_MS 10 +#define BCMF_DEVICE_START_DELAY_MS 10 +#define BCMF_DEVICE_IDLE_DELAY_MS 50 + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/* This structure is contains the unique state of the Broadcom FullMAC driver */ + +struct bcmf_dev_s +{ + FAR struct sdio_dev_s *sdio_dev; /* The SDIO device bound to this instance */ + int minor; /* Device minor number */ +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static int bcmf_sendcmdpoll(FAR struct bcmf_dev_s *priv, + uint32_t cmd, uint32_t arg); + +static int bcmf_probe(FAR struct bcmf_dev_s *priv); +static int bcmf_hwinitialize(FAR struct bcmf_dev_s *priv); +static void bcmf_hwuninitialize(FAR struct bcmf_dev_s *priv); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: bcmf_sendcmdpoll + ****************************************************************************/ + +int bcmf_sendcmdpoll(FAR struct bcmf_dev_s *priv, uint32_t cmd, uint32_t arg) +{ + int ret; + + /* Send the command */ + + ret = SDIO_SENDCMD(priv->sdio_dev, cmd, arg); + if (ret == OK) + { + /* Then poll-wait until the response is available */ + + ret = SDIO_WAITRESPONSE(priv->sdio_dev, cmd); + if (ret != OK) + { + _err("ERROR: Wait for response to cmd: %08x failed: %d\n", + cmd, ret); + } + } + + return ret; +} + +/**************************************************************************** + * Name: bcmf_probe + ****************************************************************************/ + +int bcmf_probe(FAR struct bcmf_dev_s *priv) +{ + int ret; + uint32_t data = 0; + + /* Set device state from reset to idle */ + + bcmf_sendcmdpoll(priv, MMCSD_CMD0, 0); + up_mdelay(BCMF_DEVICE_START_DELAY_MS); + + /* Send IO_SEND_OP_COND command */ + + ret = bcmf_sendcmdpoll(priv, SDIO_CMD5, 0); + + if (ret != OK) + { + goto exit_error; + } + + /* Receive R4 response */ + + ret = SDIO_RECVR4(priv->sdio_dev, SDIO_CMD5, &data); + + if (ret != OK) + { + goto exit_error; + } + + /* Broadcom chips have 2 additional functions and wide voltage range */ + + if ((((data >> 28) & 7) != 2) || + (((data >> 8) & 0xff80) != 0xff80)) + { + goto exit_error; + } + + return OK; + +exit_error: + + _err("ERROR: failed to probe device %d\n", priv->minor); + return ret; +} + +/**************************************************************************** + * Name: bcmf_hwinitialize + ****************************************************************************/ + +int bcmf_hwinitialize(FAR struct bcmf_dev_s *priv) +{ + /* Attach and prepare SDIO interrupts */ + + SDIO_ATTACH(priv->sdio_dev); + + /* Set ID mode clocking (<400KHz) */ + + SDIO_CLOCK(priv->sdio_dev, CLOCK_IDMODE); + + /* Configure hardware */ + + bcmf_board_initialize(priv->minor); + + /* Reset and power device */ + + bcmf_board_reset(priv->minor, true); + bcmf_board_power(priv->minor, true); + up_mdelay(BCMF_DEVICE_RESET_DELAY_MS); + bcmf_board_reset(priv->minor, false); + + /* Wait for device to start */ + + up_mdelay(BCMF_DEVICE_START_DELAY_MS); + + return OK; +} + +/**************************************************************************** + * Name: bcmf_hwuninitialize + ****************************************************************************/ + +void bcmf_hwuninitialize(FAR struct bcmf_dev_s *priv) +{ + /* Shutdown device */ + + bcmf_board_power(priv->minor, false); + bcmf_board_reset(priv->minor, true); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: bcmf_sdio_initialize + ****************************************************************************/ + +int bcmf_sdio_initialize(int minor, FAR struct sdio_dev_s *dev) +{ + FAR struct bcmf_dev_s *priv; + int ret; + + _info("minor: %d\n", minor); + + /* Allocate a bcmf device structure */ + + priv = (FAR struct bcmf_dev_s *)kmm_malloc(sizeof(*priv)); + + if (!priv) + { + return -ENOMEM; + } + + /* Initialize bcmf device structure */ + + memset(priv, 0, sizeof(*priv)); + priv->sdio_dev = dev; + priv->minor = minor; + + /* Initialize device hardware */ + + ret = bcmf_hwinitialize(priv); + + if (ret != OK) + { + goto exit_free_priv; + } + + /* Probe device */ + + ret = bcmf_probe(priv); + + if (ret != OK) + { + goto exit_uninit_hw; + } + + /* TODO Create a wlan device name and register network driver here */ + + return OK; + +exit_uninit_hw: + bcmf_hwuninitialize(priv); + +exit_free_priv: + kmm_free(priv); + return ret; +} diff --git a/include/nuttx/wireless/ieee80211/bcmf_board.h b/include/nuttx/wireless/ieee80211/bcmf_board.h new file mode 100644 index 0000000000..7ae0c21dc2 --- /dev/null +++ b/include/nuttx/wireless/ieee80211/bcmf_board.h @@ -0,0 +1,110 @@ +/**************************************************************************** + * include/nuttx/wireless/ieee80211/bcmf_board.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Simon Piriou + * + * 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_WIRELESS_IEEE80211_BCMF_BOARD_H +#define __INCLUDE_NUTTX_WIRELESS_IEEE80211_BCMF_BOARD_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/************************************************************************************ + * Function: bcmf_board_initialize + * + * Description: + * Board specific function called from Broadcom FullMAC driver + * that must be implemented to configure WLAN chip GPIOs + * + * Parameters: + * minor - zero based minor device number which is unique + * for each wlan device. + ************************************************************************************/ + +void bcmf_board_initialize(int minor); + +/************************************************************************************ + * Function: bcmf_board_power + * + * Description: + * Board specific function called from Broadcom FullMAC driver + * that must be implemented to power WLAN chip + * + * Parameters: + * minor - zero based minor device number which is unique + * for each wlan device. + * power - true to power WLAN chip else false + ************************************************************************************/ + +void bcmf_board_power(int minor, bool power); + +/************************************************************************************ + * Function: bcmf_board_reset + * + * Description: + * Board specific function called from Broadcom FullMAC driver + * that must be implemented to reset WLAN chip + * + * Parameters: + * minor - zero based minor device number which is unique + * for each wlan device. + * reset - true to set WLAN chip in reset state else false + ************************************************************************************/ + +void bcmf_board_reset(int minor, bool reset); + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* __INCLUDE_NUTTX_WIRELESS_IEEE80211_BCMF_BOARD_H */ diff --git a/include/nuttx/wireless/ieee80211/bcmf_sdio.h b/include/nuttx/wireless/ieee80211/bcmf_sdio.h new file mode 100644 index 0000000000..09c5733f3a --- /dev/null +++ b/include/nuttx/wireless/ieee80211/bcmf_sdio.h @@ -0,0 +1,86 @@ +/**************************************************************************** + * include/nuttx/wireless/ieee80211/bcmf_sdio.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Simon Piriou + * + * 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_WIRELESS_IEEE80211_BCMF_SDIO_H +#define __INCLUDE_NUTTX_WIRELESS_IEEE80211_BCMF_SDIO_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Function: bcmf_sdio_initialize + * + * Description: + * Initialize Broadcom FullMAC driver. + * + * Parameters: + * minor - zero based minor device number which is unique + * for each wlan device. + * dev - SDIO device used to communicate with the wlan chip + * + * Returned Value: + * OK on success; Negated errno on failure. + * + * Assumptions: + * + ****************************************************************************/ + +int bcmf_sdio_initialize(int minor, FAR struct sdio_dev_s *dev); + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* __INCLUDE_NUTTX_WIRELESS_IEEE80211_BCMF_SDIO_H */ -- GitLab From 4d33f2671783696ce127f9eca9e3db68cf500657 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 12 Mar 2017 08:45:32 -0600 Subject: [PATCH 020/990] Update some comments --- arch/arm/src/stm32/stm32_otgfshost.c | 7 +++++++ arch/arm/src/stm32/stm32_otghshost.c | 7 +++++++ arch/arm/src/stm32f7/stm32_otghost.c | 7 +++++++ arch/arm/src/stm32l4/stm32l4_otgfshost.c | 7 +++++++ 4 files changed, 28 insertions(+) diff --git a/arch/arm/src/stm32/stm32_otgfshost.c b/arch/arm/src/stm32/stm32_otgfshost.c index 2163b2eae9..c8ce6a2dd8 100644 --- a/arch/arm/src/stm32/stm32_otgfshost.c +++ b/arch/arm/src/stm32/stm32_otgfshost.c @@ -1952,6 +1952,13 @@ static ssize_t stm32_in_transfer(FAR struct stm32_usbhost_s *priv, int chidx, delay = 1000; } + /* Wait for the next polling interval. + * + * REVISIT: This delay could require more resolution than + * is provided by the system timer. In that case, the + * delay could be significantly longer than required. + */ + usleep(delay); } } diff --git a/arch/arm/src/stm32/stm32_otghshost.c b/arch/arm/src/stm32/stm32_otghshost.c index 7f16593f63..090ef4292b 100644 --- a/arch/arm/src/stm32/stm32_otghshost.c +++ b/arch/arm/src/stm32/stm32_otghshost.c @@ -1957,6 +1957,13 @@ static ssize_t stm32_in_transfer(FAR struct stm32_usbhost_s *priv, int chidx, delay = 1000; } + /* Wait for the next polling interval. + * + * REVISIT: This delay could require more resolution than + * is provided by the system timer. In that case, the + * delay could be significantly longer than required. + */ + usleep(delay); } } diff --git a/arch/arm/src/stm32f7/stm32_otghost.c b/arch/arm/src/stm32f7/stm32_otghost.c index 0d2dfd24c8..29de1826ed 100644 --- a/arch/arm/src/stm32f7/stm32_otghost.c +++ b/arch/arm/src/stm32f7/stm32_otghost.c @@ -1951,6 +1951,13 @@ static ssize_t stm32_in_transfer(FAR struct stm32_usbhost_s *priv, int chidx, delay = 1000; } + /* Wait for the next polling interval. + * + * REVISIT: This delay could require more resolution than + * is provided by the system timer. In that case, the + * delay could be significantly longer than required. + */ + usleep(delay); } } diff --git a/arch/arm/src/stm32l4/stm32l4_otgfshost.c b/arch/arm/src/stm32l4/stm32l4_otgfshost.c index 5b62256f14..b24026370d 100644 --- a/arch/arm/src/stm32l4/stm32l4_otgfshost.c +++ b/arch/arm/src/stm32l4/stm32l4_otgfshost.c @@ -1956,6 +1956,13 @@ static ssize_t stm32l4_in_transfer(FAR struct stm32l4_usbhost_s *priv, delay = 1000; } + /* Wait for the next polling interval. + * + * REVISIT: This delay could require more resolution than + * is provided by the system timer. In that case, the + * delay could be significantly longer than required. + */ + usleep(delay); } } -- GitLab From 939ea7461b07aef3749750a753606976a936cbd0 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 12 Mar 2017 12:37:13 -0600 Subject: [PATCH 021/990] Trivial update to TODO --- TODO | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/TODO b/TODO index 8ab2b48b50..56fb52199f 100644 --- a/TODO +++ b/TODO @@ -507,7 +507,7 @@ o Kernel/Protected Build in the nuttx/ directory. However, the user interfaces must be moved into a NuttX library or into apps/. Currently applications calls to the NxTerm user interfaces are - undefined. + undefined in the Kernel/Protected builds. Status: Open Priority: Medium -- GitLab From 430b52c977ca7ebcb4c52aa28f5af7e0b62c8b7a Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 12 Mar 2017 12:50:41 -0600 Subject: [PATCH 022/990] Networking: Add registration support for integrated ieee80211 wireless drivers. Rename CONFIG_IEEE802154 to CONFIG_WIRELESS_IEEE8021514 following the convention of including the location of the configuration variable as a part of its name. --- include/nuttx/net/net.h | 5 +++-- net/netdev/netdev_register.c | 18 ++++++++++++++++-- wireless/ieee802154/Kconfig | 4 ++-- wireless/ieee802154/Make.defs | 4 ++-- 4 files changed, 23 insertions(+), 8 deletions(-) diff --git a/include/nuttx/net/net.h b/include/nuttx/net/net.h index 54f5c83273..8554aab48f 100644 --- a/include/nuttx/net/net.h +++ b/include/nuttx/net/net.h @@ -1,7 +1,7 @@ /**************************************************************************** * include/nuttx/net/net.h * - * Copyright (C) 2007, 2009-2014, 2016 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2009-2014, 2016-2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -75,7 +75,8 @@ enum net_lltype_e NET_LL_LOOPBACK, /* Local loopback */ NET_LL_SLIP, /* Serial Line Internet Protocol (SLIP) */ NET_LL_TUN, /* TUN Virtual Network Device */ - NET_LL_6LOWPAN /* IEEE 802.15.4 6LoWPAN*/ + NET_LL_IEEE80211 /* IEEE 802.11 */ + NET_LL_6LOWPAN /* IEEE 802.15.4 6LoWPAN */ }; /* This defines a bitmap big enough for one bit for each socket option */ diff --git a/net/netdev/netdev_register.c b/net/netdev/netdev_register.c index a2144d2288..dafc17dcc3 100644 --- a/net/netdev/netdev_register.c +++ b/net/netdev/netdev_register.c @@ -1,7 +1,7 @@ /**************************************************************************** * net/netdev/netdev_register.c * - * Copyright (C) 2007-2012, 2014-2015 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2012, 2014-2015, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -63,14 +63,17 @@ #define NETDEV_ETH_FORMAT "eth%d" #define NETDEV_LO_FORMAT "lo" -#define NETDEV_WPAN_FORMAT "wpan%d" #define NETDEV_SLIP_FORMAT "sl%d" #define NETDEV_TUN_FORMAT "tun%d" +#define NETDEV_WLAN_FORMAT "wlan%d" +#define NETDEV_WPAN_FORMAT "wpan%d" #if defined(CONFIG_NET_SLIP) # define NETDEV_DEFAULT_FORMAT NETDEV_SLIP_FORMAT #elif defined(CONFIG_NET_ETHERNET) # define NETDEV_DEFAULT_FORMAT NETDEV_ETH_FORMAT +#elif defined(CONFIG_DRIVERS_IEEE80211) +# define NETDEV_DEFAULT_FORMAT NETDEV_WLAN_FORMAT #elif defined(CONFIG_NET_6LOWPAN) # define NETDEV_DEFAULT_FORMAT NETDEV_WPAN_FORMAT #else /* if defined(CONFIG_NET_LOOPBACK) */ @@ -213,6 +216,17 @@ int netdev_register(FAR struct net_driver_s *dev, enum net_lltype_e lltype) break; #endif +#ifdef CONFIG_DRIVERS_IEEE80211 + case NET_LL_IEEE80211: /* IEEE 802.11 */ + dev->d_llhdrlen = ETH_HDRLEN; + dev->d_mtu = CONFIG_NET_ETH_MTU; +#ifdef CONFIG_NET_TCP + dev->d_recvwndo = CONFIG_NET_ETH_TCP_RECVWNDO; +#endif + devfmt = NETDEV_LPAN_FORMAT; + break; +#endif + #ifdef CONFIG_NET_6LOWPAN case NET_LL_6LOWPAN: /* IEEE 802.15.4 */ dev->d_llhdrlen = 0; /* REVISIT */ diff --git a/wireless/ieee802154/Kconfig b/wireless/ieee802154/Kconfig index 18d5a8753c..1b443ff979 100644 --- a/wireless/ieee802154/Kconfig +++ b/wireless/ieee802154/Kconfig @@ -3,12 +3,12 @@ # see the file kconfig-language.txt in the NuttX tools repository. # -config IEEE802154 +config WIRELESS_IEEE802154 bool "IEEE 802.15.4 Wireless Support" default n depends on EXPERIMENTAL ---help--- - Enables support for the IEEE 802.14.5Wireless library. + Enables support for the IEEE 802.14.5 Wireless library. if IEEE802154 diff --git a/wireless/ieee802154/Make.defs b/wireless/ieee802154/Make.defs index 9e0c66391b..200d948dd7 100644 --- a/wireless/ieee802154/Make.defs +++ b/wireless/ieee802154/Make.defs @@ -33,7 +33,7 @@ # ############################################################################ -ifeq ($(CONFIG_IEEE802154),y) +ifeq ($(CONFIG_WIRELESS_IEEE802154),y) # Include IEEE 802.15.4 support @@ -43,4 +43,4 @@ DEPPATH += --dep-path wireless/ieee802154 VPATH += :wireless/ieee802154 CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)$(DELIM)wireless$(DELIM)ieee802154} -endif # CONFIG_IEEE802154 +endif # CONFIG_WIRELESS_IEEE802154 -- GitLab From b9bb9ea853e3310687544dc8ebcb82326ea16fbf Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 12 Mar 2017 12:59:59 -0600 Subject: [PATCH 023/990] Fix a typo in the last commit. --- include/nuttx/net/net.h | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/include/nuttx/net/net.h b/include/nuttx/net/net.h index 8554aab48f..1c64351fe2 100644 --- a/include/nuttx/net/net.h +++ b/include/nuttx/net/net.h @@ -67,7 +67,10 @@ /**************************************************************************** * Public Types ****************************************************************************/ -/* Data link layer type */ + +/* Data link layer type. This type is used with netdev_register in order to + * identify the type of the network driver. + */ enum net_lltype_e { @@ -75,7 +78,7 @@ enum net_lltype_e NET_LL_LOOPBACK, /* Local loopback */ NET_LL_SLIP, /* Serial Line Internet Protocol (SLIP) */ NET_LL_TUN, /* TUN Virtual Network Device */ - NET_LL_IEEE80211 /* IEEE 802.11 */ + NET_LL_IEEE80211, /* IEEE 802.11 */ NET_LL_6LOWPAN /* IEEE 802.15.4 6LoWPAN */ }; -- GitLab From 2bcb8b7b07ed9c20eab6f6875d720cc2aacdb608 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 13 Mar 2017 07:31:47 -0600 Subject: [PATCH 024/990] If whence is SEEK_END, the file offset shall be set to the size of the file plus offset. Noted by eunb.song@samsung.com --- fs/smartfs/smartfs_smart.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/fs/smartfs/smartfs_smart.c b/fs/smartfs/smartfs_smart.c index 23f36860fe..60a539c10f 100644 --- a/fs/smartfs/smartfs_smart.c +++ b/fs/smartfs/smartfs_smart.c @@ -1044,7 +1044,7 @@ static off_t smartfs_seek_internal(struct smartfs_mountpt_s *fs, break; case SEEK_END: - newpos = sf->entry.datlen - offset; + newpos = sf->entry.datlen + offset; break; } -- GitLab From b808084e57bdb514fc303cf5642bf1ab78bbeb28 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 13 Mar 2017 09:51:31 -0600 Subject: [PATCH 025/990] Move wireless IOCTLs from include/nuttx/net/ioctl to include/nuttx/wireless/wireless.h. Add some linux compatible structures to use with the IOCTL commands. --- configs/dk-tm4c129x/ipv6/defconfig | 2 +- configs/dk-tm4c129x/nsh/defconfig | 2 +- configs/freedom-k64f/netnsh/defconfig | 2 +- configs/freedom-k66f/netnsh/defconfig | 2 +- configs/same70-xplained/netnsh/defconfig | 2 +- configs/samv71-xult/netnsh/defconfig | 2 +- configs/samv71-xult/vnc/defconfig | 2 +- configs/samv71-xult/vnxwm/defconfig | 2 +- configs/stm32f4discovery/netnsh/defconfig | 2 +- configs/tm4c1294-launchpad/ipv6/defconfig | 2 +- configs/tm4c1294-launchpad/nsh/defconfig | 2 +- include/nuttx/net/ioctl.h | 74 +------ include/nuttx/net/netdev.h | 2 +- include/nuttx/wireless/wireless.h | 231 ++++++++++++++++++++-- net/netdev/Kconfig | 15 +- net/netdev/netdev_ioctl.c | 110 +++++++++-- 16 files changed, 347 insertions(+), 107 deletions(-) diff --git a/configs/dk-tm4c129x/ipv6/defconfig b/configs/dk-tm4c129x/ipv6/defconfig index 0b02b897d0..328b1ffd43 100644 --- a/configs/dk-tm4c129x/ipv6/defconfig +++ b/configs/dk-tm4c129x/ipv6/defconfig @@ -700,6 +700,7 @@ CONFIG_NET_ETHERNET=y # # Network Device Operations # +CONFIG_NETDEV_IOCTL=y CONFIG_NETDEV_PHY_IOCTL=y # @@ -998,7 +999,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set # CONFIG_EXAMPLES_NETTEST is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set diff --git a/configs/dk-tm4c129x/nsh/defconfig b/configs/dk-tm4c129x/nsh/defconfig index bce75ec938..1032d72580 100644 --- a/configs/dk-tm4c129x/nsh/defconfig +++ b/configs/dk-tm4c129x/nsh/defconfig @@ -702,6 +702,7 @@ CONFIG_NET_ETHERNET=y # # Network Device Operations # +CONFIG_NETDEV_IOCTL=y CONFIG_NETDEV_PHY_IOCTL=y # @@ -1008,7 +1009,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set # CONFIG_EXAMPLES_NETTEST is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set diff --git a/configs/freedom-k64f/netnsh/defconfig b/configs/freedom-k64f/netnsh/defconfig index 25f75a4e2a..c94d75f438 100644 --- a/configs/freedom-k64f/netnsh/defconfig +++ b/configs/freedom-k64f/netnsh/defconfig @@ -684,6 +684,7 @@ CONFIG_NET_ETHERNET=y # # Network Device Operations # +CONFIG_NETDEV_IOCTL=y CONFIG_NETDEV_PHY_IOCTL=y # @@ -1011,7 +1012,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set # CONFIG_EXAMPLES_NETTEST is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set diff --git a/configs/freedom-k66f/netnsh/defconfig b/configs/freedom-k66f/netnsh/defconfig index 47ed577619..67c13b3089 100644 --- a/configs/freedom-k66f/netnsh/defconfig +++ b/configs/freedom-k66f/netnsh/defconfig @@ -712,6 +712,7 @@ CONFIG_NET_ETHERNET=y # # Network Device Operations # +CONFIG_NETDEV_IOCTL=y CONFIG_NETDEV_PHY_IOCTL=y # @@ -1040,7 +1041,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set # CONFIG_EXAMPLES_NETTEST is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set diff --git a/configs/same70-xplained/netnsh/defconfig b/configs/same70-xplained/netnsh/defconfig index 454ec96568..d472559ad8 100644 --- a/configs/same70-xplained/netnsh/defconfig +++ b/configs/same70-xplained/netnsh/defconfig @@ -793,6 +793,7 @@ CONFIG_NET_ETHERNET=y # # Network Device Operations # +CONFIG_NETDEV_IOCTL=y CONFIG_NETDEV_PHY_IOCTL=y # @@ -1121,7 +1122,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set # CONFIG_EXAMPLES_NETTEST is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set diff --git a/configs/samv71-xult/netnsh/defconfig b/configs/samv71-xult/netnsh/defconfig index 393cbaf43d..a38656d9c1 100644 --- a/configs/samv71-xult/netnsh/defconfig +++ b/configs/samv71-xult/netnsh/defconfig @@ -796,6 +796,7 @@ CONFIG_NET_ETHERNET=y # # Network Device Operations # +CONFIG_NETDEV_IOCTL=y CONFIG_NETDEV_PHY_IOCTL=y # @@ -1125,7 +1126,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set # CONFIG_EXAMPLES_NETTEST is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set diff --git a/configs/samv71-xult/vnc/defconfig b/configs/samv71-xult/vnc/defconfig index 4fe8613005..00e4ca6bca 100644 --- a/configs/samv71-xult/vnc/defconfig +++ b/configs/samv71-xult/vnc/defconfig @@ -797,6 +797,7 @@ CONFIG_NET_ETHERNET=y # # Network Device Operations # +CONFIG_NETDEV_IOCTL=y CONFIG_NETDEV_PHY_IOCTL=y # @@ -1216,7 +1217,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set # CONFIG_EXAMPLES_NETTEST is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set diff --git a/configs/samv71-xult/vnxwm/defconfig b/configs/samv71-xult/vnxwm/defconfig index ef011a531f..2606fbbcab 100644 --- a/configs/samv71-xult/vnxwm/defconfig +++ b/configs/samv71-xult/vnxwm/defconfig @@ -800,6 +800,7 @@ CONFIG_NET_ETHERNET=y # # Network Device Operations # +CONFIG_NETDEV_IOCTL=y CONFIG_NETDEV_PHY_IOCTL=y # @@ -1258,7 +1259,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set # CONFIG_EXAMPLES_NETTEST is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set # CONFIG_EXAMPLES_NSH is not set # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set diff --git a/configs/stm32f4discovery/netnsh/defconfig b/configs/stm32f4discovery/netnsh/defconfig index 80b45e3a8d..f564769ca0 100644 --- a/configs/stm32f4discovery/netnsh/defconfig +++ b/configs/stm32f4discovery/netnsh/defconfig @@ -988,6 +988,7 @@ CONFIG_NET_ETHERNET=y # # Network Device Operations # +CONFIG_NETDEV_IOCTL=y CONFIG_NETDEV_PHY_IOCTL=y # @@ -1329,7 +1330,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set # CONFIG_EXAMPLES_NETTEST is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set diff --git a/configs/tm4c1294-launchpad/ipv6/defconfig b/configs/tm4c1294-launchpad/ipv6/defconfig index 6fa9c16107..df9138c111 100644 --- a/configs/tm4c1294-launchpad/ipv6/defconfig +++ b/configs/tm4c1294-launchpad/ipv6/defconfig @@ -661,6 +661,7 @@ CONFIG_NET_ETHERNET=y # # Network Device Operations # +CONFIG_NETDEV_IOCTL=y CONFIG_NETDEV_PHY_IOCTL=y # @@ -957,7 +958,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set # CONFIG_EXAMPLES_NETTEST is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set diff --git a/configs/tm4c1294-launchpad/nsh/defconfig b/configs/tm4c1294-launchpad/nsh/defconfig index 379b3df359..5690209be4 100644 --- a/configs/tm4c1294-launchpad/nsh/defconfig +++ b/configs/tm4c1294-launchpad/nsh/defconfig @@ -663,6 +663,7 @@ CONFIG_NET_ETHERNET=y # # Network Device Operations # +CONFIG_NETDEV_IOCTL=y CONFIG_NETDEV_PHY_IOCTL=y # @@ -969,7 +970,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set # CONFIG_EXAMPLES_NETTEST is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set diff --git a/include/nuttx/net/ioctl.h b/include/nuttx/net/ioctl.h index a20d5e231b..c618028405 100644 --- a/include/nuttx/net/ioctl.h +++ b/include/nuttx/net/ioctl.h @@ -109,84 +109,22 @@ #define SIOCADDRT _SIOC(0x001f) /* Add an entry to the routing table */ #define SIOCDELRT _SIOC(0x0020) /* Delete an entry from the routing table */ -/* Wireless ioctl commands **************************************************/ -/* Not currently used */ - -#define SIOCSIWCOMMIT _SIOC(0x0021) /* Commit pending changes to driver */ -#define SIOCGIWNAME _SIOC(0x0022) /* Get name of wireless protocol */ - -#define SIOCSIWNWID _SIOC(0x0023) /* Set network ID (pre-802.11) */ -#define SIOCGIWNWID _SIOC(0x0024) /* Get network ID (the cell) */ -#define SIOCSIWFREQ _SIOC(0x0025) /* Set channel/frequency (Hz) */ -#define SIOCGIWFREQ _SIOC(0x0026) /* Get channel/frequency (Hz) */ -#define SIOCSIWMODE _SIOC(0x0027) /* Set operation mode */ -#define SIOCGIWMODE _SIOC(0x0028) /* Get operation mode */ -#define SIOCSIWSENS _SIOC(0x0029) /* Set sensitivity (dBm) */ -#define SIOCGIWSENS _SIOC(0x002a) /* Get sensitivity (dBm) */ - -#define SIOCGIWRANGE _SIOC(0x002b) /* Get range of parameters */ -#define SIOCGIWPRIV _SIOC(0x002c) /* Get private ioctl interface info */ -#define SIOCGIWSTATS _SIOC(0x002d) /* Get wireless stats */ - -#define SIOCSIWSPY _SIOC(0x002e) /* Set spy addresses */ -#define SIOCGIWSPY _SIOC(0x002f) /* Get spy info (quality of link) */ -#define SIOCSIWTHRSPY _SIOC(0x0030) /* Set spy threshold (spy event) */ -#define SIOCGIWTHRSPY _SIOC(0x0031) /* Get spy threshold */ - -#define SIOCSIWAP _SIOC(0x0032) /* Set access point MAC addresses */ -#define SIOCGIWAP _SIOC(0x0033) /* Get access point MAC addresses */ -#define SIOCGIWAPLIST _SIOC(0x0034) /* Deprecated in favor of scanning */ -#define SIOCSIWSCAN _SIOC(0x0035) /* Trigger scanning (list cells) */ -#define SIOCGIWSCAN _SIOC(0x0036) /* Get scanning results */ - -#define SIOCSIWESSID _SIOC(0x0037) /* Set ESSID (network name) */ -#define SIOCGIWESSID _SIOC(0x0038) /* Get ESSID */ -#define SIOCSIWNICKN _SIOC(0x0039) /* Set node name/nickname */ -#define SIOCGIWNICKN _SIOC(0x003a) /* Get node name/nickname */ - -#define SIOCSIWRATE _SIOC(0x003b) /* Set default bit rate (bps) */ -#define SIOCGIWRATE _SIOC(0x003c) /* Get default bit rate (bps) */ -#define SIOCSIWRTS _SIOC(0x003d) /* Set RTS/CTS threshold (bytes) */ -#define SIOCGIWRTS _SIOC(0x003e) /* Get RTS/CTS threshold (bytes) */ -#define SIOCSIWFRAG _SIOC(0x003f) /* Set fragmentation thr (bytes) */ -#define SIOCGIWFRAG _SIOC(0x0040) /* Get fragmentation thr (bytes) */ -#define SIOCSIWTXPOW _SIOC(0x0041) /* Set transmit power (dBm) */ -#define SIOCGIWTXPOW _SIOC(0x0042) /* Get transmit power (dBm) */ -#define SIOCSIWRETRY _SIOC(0x0043) /* Set retry limits and lifetime */ -#define SIOCGIWRETRY _SIOC(0x0044) /* Get retry limits and lifetime */ - -#define SIOCSIWPOWER _SIOC(0x0045) /* Set Power Management settings */ -#define SIOCGIWPOWER _SIOC(0x0046) /* Get Power Management settings */ - -#define SIOCSIWGENIE _SIOC(0x0047) /* Set generic IE */ -#define SIOCGIWGENIE _SIOC(0x0048) /* Get generic IE */ - -#define SIOCSIWMLME _SIOC(0x0049) /* Request MLME operation */ - -#define SIOCSIWAUTH _SIOC(0x004a) /* Set authentication mode params */ -#define SIOCGIWAUTH _SIOC(0x004b) /* Get authentication mode params */ - -#define SIOCSIWENCODEEXT _SIOC(0x004c) /* Set encoding token & mode */ -#define SIOCGIWENCODEEXT _SIOC(0x004d) /* Get encoding token & mode */ - -#define SIOCSIWPMKSA _SIOC(0x004e) /* PMKSA cache operation */ - /* MDIO/MCD *****************************************************************/ -#define SIOCMIINOTIFY _SIOC(0x004f) /* Receive notificaion via signal on +#define SIOCMIINOTIFY _SIOC(0x0021) /* Receive notificaion via signal on * PHY state change */ -#define SIOCGMIIPHY _SIOC(0x0050) /* Get address of MII PHY in use */ -#define SIOCGMIIREG _SIOC(0x0051) /* Get a MII register via MDIO */ -#define SIOCSMIIREG _SIOC(0x0052) /* Set a MII register via MDIO */ +#define SIOCGMIIPHY _SIOC(0x0022) /* Get address of MII PHY in use */ +#define SIOCGMIIREG _SIOC(0x0023) /* Get a MII register via MDIO */ +#define SIOCSMIIREG _SIOC(0x0024) /* Set a MII register via MDIO */ /* Unix domain sockets ******************************************************/ -#define SIOCINQ _SIOC(0x0053) /* Returns the amount of queued unread +#define SIOCINQ _SIOC(0x0025) /* Returns the amount of queued unread * data in the receive */ /* Telnet driver ************************************************************/ -#define SIOCTELNET _SIOC(0x0054) /* Create a Telnet sessions. +#define SIOCTELNET _SIOC(0x0026) /* Create a Telnet sessions. * See include/nuttx/net/telnet.h */ /**************************************************************************** diff --git a/include/nuttx/net/netdev.h b/include/nuttx/net/netdev.h index aceab4d083..6a529fb368 100644 --- a/include/nuttx/net/netdev.h +++ b/include/nuttx/net/netdev.h @@ -330,7 +330,7 @@ struct net_driver_s int (*d_addmac)(FAR struct net_driver_s *dev, FAR const uint8_t *mac); int (*d_rmmac)(FAR struct net_driver_s *dev, FAR const uint8_t *mac); #endif -#ifdef CONFIG_NETDEV_PHY_IOCTL +#ifdef CONFIG_NETDEV_IOCTL int (*d_ioctl)(FAR struct net_driver_s *dev, int cmd, long arg); #endif diff --git a/include/nuttx/wireless/wireless.h b/include/nuttx/wireless/wireless.h index f172669114..cd7de191d1 100644 --- a/include/nuttx/wireless/wireless.h +++ b/include/nuttx/wireless/wireless.h @@ -45,6 +45,11 @@ ************************************************************************************/ #include + +#include +#include + +#include #include #ifdef CONFIG_DRIVERS_WIRELESS @@ -53,18 +58,115 @@ * Pre-processor Definitions ************************************************************************************/ -/* IOCTL Commands *******************************************************************/ -/* Common wireless IOCTL commands */ +/* Network Driver IOCTL Commands ****************************************************/ +/* Wireless identification */ + +#define SIOCSIWCOMMIT _WLIOC(0x0001) /* Commit pending changes to driver */ +#define SIOCGIWNAME _WLIOC(0x0002) /* Get name of wireless protocol */ + +/* Basic Operations */ + +#define SIOCSIWNWID _WLIOC(0x0003) /* Set network ID (pre-802.11) */ +#define SIOCGIWNWID _WLIOC(0x0004) /* Get network ID (the cell) */ +#define SIOCSIWFREQ _WLIOC(0x0005) /* Set channel/frequency (Hz) */ +#define SIOCGIWFREQ _WLIOC(0x0006) /* Get channel/frequency (Hz) */ +#define SIOCSIWMODE _WLIOC(0x0007) /* Set operation mode */ +#define SIOCGIWMODE _WLIOC(0x0008) /* Get operation mode */ +#define SIOCSIWSENS _WLIOC(0x0009) /* Set sensitivity (dBm) */ +#define SIOCGIWSENS _WLIOC(0x000a) /* Get sensitivity (dBm) */ + +/* Informational */ + +#define SIOCGIWRANGE _WLIOC(0x000b) /* Get range of parameters */ +#define SIOCGIWPRIV _WLIOC(0x000c) /* Get private ioctl interface info */ +#define SIOCGIWRANGE _WLIOC(0x000d) /* Get range of parameters */ +#define SIOCGIWPRIV _WLIOC(0x000e) /* Get private ioctl interface info */ +#define SIOCGIWSTATS _WLIOC(0x000f) /* Get wireless stats */ + +/* Spy support (statistics per MAC address - used for Mobile IP support) */ + +#define SIOCSIWSPY _WLIOC(0x0010) /* Set spy addresses */ +#define SIOCGIWSPY _WLIOC(0x0011) /* Get spy info (quality of link) */ +#define SIOCSIWTHRSPY _WLIOC(0x0012) /* Set spy threshold (spy event) */ +#define SIOCGIWTHRSPY _WLIOC(0x0013) /* Get spy threshold */ + +/* Access point manipulation */ + +#define SIOCSIWAP _WLIOC(0x0014) /* Set access point MAC addresses */ +#define SIOCGIWAP _WLIOC(0x0015) /* Get access point MAC addresses */ +#define SIOCGIWAPLIST _WLIOC(0x0016) /* Deprecated in favor of scanning */ +#define SIOCSIWSCAN _WLIOC(0x0017) /* Trigger scanning (list cells) */ +#define SIOCGIWSCAN _WLIOC(0x0018) /* Get scanning results */ + +/* 802.11 specific support */ + +#define SIOCSIWESSID _WLIOC(0x0019) /* Set ESSID (network name) */ +#define SIOCGIWESSID _WLIOC(0x001a) /* Get ESSID */ +#define SIOCSIWNICKN _WLIOC(0x001b) /* Set node name/nickname */ +#define SIOCGIWNICKN _WLIOC(0x001c) /* Get node name/nickname */ + +#define SIOCSIWRATE _WLIOC(0x001d) /* Set default bit rate (bps) */ +#define SIOCGIWRATE _WLIOC(0x001e) /* Get default bit rate (bps) */ +#define SIOCSIWRTS _WLIOC(0x001f) /* Set RTS/CTS threshold (bytes) */ +#define SIOCGIWRTS _WLIOC(0x0010) /* Get RTS/CTS threshold (bytes) */ +#define SIOCSIWFRAG _WLIOC(0x0011) /* Set fragmentation thr (bytes) */ +#define SIOCGIWFRAG _WLIOC(0x0022) /* Get fragmentation thr (bytes) */ +#define SIOCSIWTXPOW _WLIOC(0x0023) /* Set transmit power (dBm) */ +#define SIOCGIWTXPOW _WLIOC(0x0024) /* Get transmit power (dBm) */ +#define SIOCSIWRETRY _WLIOC(0x0025) /* Set retry limits and lifetime */ +#define SIOCGIWRETRY _WLIOC(0x0026) /* Get retry limits and lifetime */ + +/* Encoding */ + +#define SIOCSIWENCODE _WLIOC(0x0027) /* Set encoding token & mode */ +#define SIOCGIWENCODE _WLIOC(0x0028) /* Get encoding token & mode */ + +/* Power saving */ + +#define SIOCSIWPOWER _WLIOC(0x0029) /* Set Power Management settings */ +#define SIOCGIWPOWER _WLIOC(0x002a) /* Get Power Management settings */ + +/* WPA : Generic IEEE 802.11 information element */ + +#define SIOCSIWGENIE _WLIOC(0x002b) /* Set generic IE */ +#define SIOCGIWGENIE _WLIOC(0x002c) /* Get generic IE */ + +/* WPA : IEEE 802.11 MLME requests */ + +#define SIOCSIWMLME _WLIOC(0x002d) /* Request MLME operation */ + +/* WPA : Authentication mode parameters */ + +#define SIOCSIWAUTH _WLIOC(0x002e) /* Set authentication mode params */ +#define SIOCGIWAUTH _WLIOC(0x002f) /* Get authentication mode params */ + +/* WPA : Extended version of encoding configuration */ -#define WLIOC_SETRADIOFREQ _WLIOC(0x0001) /* arg: Pointer to uint32_t, frequency value (in Mhz) */ -#define WLIOC_GETRADIOFREQ _WLIOC(0x0002) /* arg: Pointer to uint32_t, frequency value (in Mhz) */ -#define WLIOC_SETADDR _WLIOC(0x0003) /* arg: Pointer to address value, format of the address is driver specific */ -#define WLIOC_GETADDR _WLIOC(0x0004) /* arg: Pointer to address value, format of the address is driver specific */ -#define WLIOC_SETTXPOWER _WLIOC(0x0005) /* arg: Pointer to int32_t, output power (in dBm) */ -#define WLIOC_GETTXPOWER _WLIOC(0x0006) /* arg: Pointer to int32_t, output power (in dBm) */ +#define SIOCSIWENCODEEXT _WLIOC(0x0030) /* Set encoding token & mode */ +#define SIOCGIWENCODEEXT _WLIOC(0x0031) /* Get encoding token & mode */ -#define WL_FIRST 0x0001 /* First common command */ -#define WL_NCMDS 6 /* Six common commands */ +/* WPA2 : PMKSA cache management */ + +#define SIOCSIWPMKSA _WLIOC(0x0032) /* PMKSA cache operation */ + +#define WL_NNETCMDS 0x0032 + +/* Character Driver IOCTL commands *************************************************/ +/* Non-compatible, NuttX only IOCTL definitions for use with low-level wireless + * drivers that are accessed via a character device. + */ + +#define WLIOC_SETRADIOFREQ _WLIOC(0x0033) /* arg: Pointer to uint32_t, frequency value (in Mhz) */ +#define WLIOC_GETRADIOFREQ _WLIOC(0x0034) /* arg: Pointer to uint32_t, frequency value (in Mhz) */ +#define WLIOC_SETADDR _WLIOC(0x0035) /* arg: Pointer to address value, format of the address is driver specific */ +#define WLIOC_GETADDR _WLIOC(0x0036) /* arg: Pointer to address value, format of the address is driver specific */ +#define WLIOC_SETTXPOWER _WLIOC(0x0037) /* arg: Pointer to int32_t, output power (in dBm) */ +#define WLIOC_GETTXPOWER _WLIOC(0x0038) /* arg: Pointer to int32_t, output power (in dBm) */ + +/* Device-specific IOCTL commands **************************************************/ + +#define WL_FIRST 0x0001 /* First common command */ +#define WL_NCMDS 0x0038 /* Number of common commands */ /* User defined ioctl commands are also supported. These will be forwarded * by the upper-half QE driver to the lower-half QE driver via the ioctl() @@ -75,13 +177,114 @@ /* See include/nuttx/wireless/cc3000.h */ -#define CC3000_FIRST (WL_FIRST + WL_NCMDS) -#define CC3000_NCMDS 7 +#define CC3000_FIRST (WL_FIRST + WL_NCMDS) +#define CC3000_NCMDS 7 /* See include/nuttx/wireless/nrf24l01.h */ -#define NRF24L01_FIRST (CC3000_FIRST + CC3000_NCMDS) -#define NRF24L01_NCMDS 14 +#define NRF24L01_FIRST (CC3000_FIRST + CC3000_NCMDS) +#define NRF24L01_NCMDS 14 + +/************************************************************************************ + * Public Types + ************************************************************************************/ +/* TODO: + * - Add types for statistics (struct iw_statistics and related) + * - Add struct iw_range for use with IOCTL commands that need exchange mode data + * that could not fit in iwreq. + * - Private IOCTL data support (struct iw_priv_arg) + * - Quality + * - WPA support. + * - Wireless events. + * - Various flag definitions. + */ + +/* Generic format for most parameters that fit in a int32_t */ + +struct iw_param +{ + int32_t value; /* The value of the parameter itself */ + uint8_t fixed; /* Hardware should not use auto select */ + uint8_t disabled; /* Disable the feature */ + uint16_t flags; /* Optional flags */ +}; + +/* Large data reference. For all data larger than 16 octets, we need to use a + * pointer to memory allocated in user space. + */ + +struct iw_point +{ + FAR void *pointer; /* Pointer to the data (in user space) */ + uint16_t length; /* number of fields or size in bytes */ + uint16_t flags; /* Optional flags */ +}; + +/* For numbers lower than 10^9, we encode the number in 'm' and set 'e' to 0 + * For number greater than 10^9, we divide it by the lowest power of 10 to + * get 'm' lower than 10^9, with 'm'= f / (10^'e')... + * The power of 10 is in 'e', the result of the division is in 'm'. + */ + +struct iw_freq +{ + int32_t m; /* Mantissa */ + int16_t e; /* Exponent */ + uint8_t i; /* List index (when in range struct) */ + uint8_t flags; /* Flags (fixed/auto) */ +}; + +/* Quality of the link */ + +struct iw_quality +{ + uint8_t qual; /* link quality (%retries, SNR, + * %missed beacons or better...) */ + uint8_t level; /* signal level (dBm) */ + uint8_t noise; /* noise level (dBm) */ + uint8_t updated; /* Flags to know if updated */ +}; + +/* This union defines the data payload of an ioctl, and is used in struct iwreq + * below. + */ + +union iwreq_data +{ + char name[IFNAMSIZ]; /* Network interface name */ + struct iw_point essid; /* Extended network name */ + struct iw_param nwid; /* Network id (or domain - the cell) */ + struct iw_freq freq; /* frequency or channel : + * 0-1000 = channel + * > 1000 = frequency in Hz */ + struct iw_param sens; /* signal level threshold */ + struct iw_param bitrate; /* default bit rate */ + struct iw_param txpower; /* default transmit power */ + struct iw_param rts; /* RTS threshold threshold */ + struct iw_param frag; /* Fragmentation threshold */ + uint32_t mode; /* Operation mode */ + struct iw_param retry; /* Retry limits & lifetime */ + + struct iw_point encoding; /* Encoding stuff : tokens */ + struct iw_param power; /* PM duration/timeout */ + struct iw_quality qual; /* Quality part of statistics */ + + struct sockaddr ap_addr; /* Access point address */ + struct sockaddr addr; /* Destination address (hw/mac) */ + + struct iw_param param; /* Other small parameters */ + struct iw_point data; /* Other large parameters */ + }; + + /* This is the structure used to exchange data in wireless IOCTLs. This structure + * is the same as 'struct ifreq', but defined for use with wireless IOCTLs. + */ + +struct iwreq +{ + char ifrn_name[IFNAMSIZ]; /* Interface name, e.g. "eth0" */ + union iwreq_data u; /* Data payload */ + }; #endif /* CONFIG_DRIVERS_WIRELESS */ #endif /* __INCLUDE_NUTTX_WIRELESS_H */ diff --git a/net/netdev/Kconfig b/net/netdev/Kconfig index fb441f0d26..f63cfd35bc 100644 --- a/net/netdev/Kconfig +++ b/net/netdev/Kconfig @@ -5,10 +5,23 @@ menu "Network Device Operations" +config NETDEV_IOCTL + bool + default n + config NETDEV_PHY_IOCTL bool "Enable PHY ioctl()" default n + select NETDEV_IOCTL + ---help--- + Enable support for ioctl() commands to access PHY registers + +config NETDEV_WIRELESS_IOCTL + bool "Enable Wireless ioctl()" + default n + select NETDEV_IOCTL + depends on DRIVERS_WIRELESS ---help--- - Enable support for ioctl() commands to access PHY registers" + Enable support for wireless device ioctl() commands endmenu # Network Device Operations diff --git a/net/netdev/netdev_ioctl.c b/net/netdev/netdev_ioctl.c index 10d9bf2df6..9f9ee88982 100644 --- a/net/netdev/netdev_ioctl.c +++ b/net/netdev/netdev_ioctl.c @@ -60,8 +60,12 @@ #include #ifdef CONFIG_NET_IGMP -# include "sys/sockio.h" -# include "nuttx/net/igmp.h" +# include +# include +#endif + +#ifdef CONFIG_NETDEV_NETDEV_WIRELESS_IOCTL +# include #endif #include "arp/arp.h" @@ -311,6 +315,80 @@ static void ioctl_setipv6addr(FAR net_ipv6addr_t outaddr, } #endif +/**************************************************************************** + * Name: netdev_wifrdev + * + * Description: + * Verify the struct iwreq and get the Wireless device. + * + * Parameters: + * req - The argument of the ioctl cmd + * + * Return: + * A pointer to the driver structure on success; NULL on failure. + * + ****************************************************************************/ + +#if defined(CONFIG_NETDEV_IOCTL) && defined(CONFIG_NETDEV_NETDEV_WIRELESS_IOCTL) +static FAR struct net_driver_s *netdev_wifrdev(FAR struct iwreq *req) +{ + if (req != NULL) + { + /* Find the network device associated with the device name + * in the request data. + */ + + return netdev_findbyname(req->ifrn_name); + } + + return NULL; +} +#endif + +/**************************************************************************** + * Name: netdev_wifrioctl + * + * Description: + * Perform wireless network device specific operations. + * + * Parameters: + * psock Socket structure + * dev Ethernet driver device structure + * cmd The ioctl command + * req The argument of the ioctl cmd + * + * Return: + * >=0 on success (positive non-zero values are cmd-specific) + * Negated errno returned on failure. + * + ****************************************************************************/ + +#if defined(CONFIG_NETDEV_IOCTL) && defined(CONFIG_NETDEV_NETDEV_WIRELESS_IOCTL) +static int netdev_wifrioctl(FAR struct socket *psock, int cmd, + FAR struct iwreq *req) +{ + FAR struct net_driver_s *dev; + int ret = -ENOTTY; + + /* Verify that this is a valid wireless network IOCTL command */ + + if (_WLIOCVALID(cmd) && (unsigned)_IOC_NR(cmd) <= WL_NNETCMDS) + { + /* Get the wireless device associated with the IOCTL command */ + + dev = netdev_ifrdev(req); + if (dev) + { + /* For now, just forward the IOCTL to the wireless driver */ + + ret = dev->d_ioctl(dev, cmd, ((long)(uintptr_t)req)); + } + } + + return ret; +} +#endif + /**************************************************************************** * Name: netdev_ifrdev * @@ -327,16 +405,16 @@ static void ioctl_setipv6addr(FAR net_ipv6addr_t outaddr, static FAR struct net_driver_s *netdev_ifrdev(FAR struct ifreq *req) { - if (!req) + if (req != NULL) { - return NULL; - } + /* Find the network device associated with the device name + * in the request data. + */ - /* Find the network device associated with the device name - * in the request data. - */ + return netdev_findbyname(req->ifr_name); + } - return netdev_findbyname(req->ifr_name); + return NULL; } /**************************************************************************** @@ -347,7 +425,6 @@ static FAR struct net_driver_s *netdev_ifrdev(FAR struct ifreq *req) * * Parameters: * psock Socket structure - * dev Ethernet driver device structure * cmd The ioctl command * req The argument of the ioctl cmd * @@ -676,7 +753,7 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, } break; -#ifdef CONFIG_NETDEV_PHY_IOCTL +#if defined(CONFIG_NETDEV_IOCTL) && defined(CONFIG_NETDEV_PHY_IOCTL) #ifdef CONFIG_ARCH_PHY_INTERRUPT case SIOCMIINOTIFY: /* Set up for PHY event notifications */ { @@ -1079,10 +1156,19 @@ int psock_ioctl(FAR struct socket *psock, int cmd, unsigned long arg) goto errout; } - /* Execute the command */ + /* Execute the command. First check for a standard network IOCTL command. */ ret = netdev_ifrioctl(psock, cmd, (FAR struct ifreq *)((uintptr_t)arg)); +#if defined(CONFIG_NETDEV_IOCTL) && defined(CONFIG_NETDEV_NETDEV_WIRELESS_IOCTL) + /* Check a wireless network command */ + + if (ret == -ENOTTY) + { + ret = netdev_wifrioctl(psock, cmd, (FAR struct iwreq *)((uintptr_t)arg)); + } +#endif + #ifdef CONFIG_NET_IGMP /* Check for address filtering commands */ -- GitLab From 888cff30dc42bfb4408e634588d32e10eaf599b3 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 13 Mar 2017 10:14:38 -0600 Subject: [PATCH 026/990] Fix some errors in the previous commit --- include/nuttx/wireless/wireless.h | 6 ++++++ net/netdev/netdev_ioctl.c | 12 ++++++------ 2 files changed, 12 insertions(+), 6 deletions(-) diff --git a/include/nuttx/wireless/wireless.h b/include/nuttx/wireless/wireless.h index cd7de191d1..a9aec2373c 100644 --- a/include/nuttx/wireless/wireless.h +++ b/include/nuttx/wireless/wireless.h @@ -185,6 +185,12 @@ #define NRF24L01_FIRST (CC3000_FIRST + CC3000_NCMDS) #define NRF24L01_NCMDS 14 +/* Other Definitions ****************************************************************/ + +/* Maximum size of the ESSID and NICKN strings */ + +#define IW_ESSID_MAX_SIZE 32 + /************************************************************************************ * Public Types ************************************************************************************/ diff --git a/net/netdev/netdev_ioctl.c b/net/netdev/netdev_ioctl.c index 9f9ee88982..41769f653b 100644 --- a/net/netdev/netdev_ioctl.c +++ b/net/netdev/netdev_ioctl.c @@ -64,7 +64,7 @@ # include #endif -#ifdef CONFIG_NETDEV_NETDEV_WIRELESS_IOCTL +#ifdef CONFIG_NETDEV_WIRELESS_IOCTL # include #endif @@ -329,7 +329,7 @@ static void ioctl_setipv6addr(FAR net_ipv6addr_t outaddr, * ****************************************************************************/ -#if defined(CONFIG_NETDEV_IOCTL) && defined(CONFIG_NETDEV_NETDEV_WIRELESS_IOCTL) +#if defined(CONFIG_NETDEV_IOCTL) && defined(CONFIG_NETDEV_WIRELESS_IOCTL) static FAR struct net_driver_s *netdev_wifrdev(FAR struct iwreq *req) { if (req != NULL) @@ -363,7 +363,7 @@ static FAR struct net_driver_s *netdev_wifrdev(FAR struct iwreq *req) * ****************************************************************************/ -#if defined(CONFIG_NETDEV_IOCTL) && defined(CONFIG_NETDEV_NETDEV_WIRELESS_IOCTL) +#if defined(CONFIG_NETDEV_IOCTL) && defined(CONFIG_NETDEV_WIRELESS_IOCTL) static int netdev_wifrioctl(FAR struct socket *psock, int cmd, FAR struct iwreq *req) { @@ -376,10 +376,10 @@ static int netdev_wifrioctl(FAR struct socket *psock, int cmd, { /* Get the wireless device associated with the IOCTL command */ - dev = netdev_ifrdev(req); + dev = netdev_wifrdev(req); if (dev) { - /* For now, just forward the IOCTL to the wireless driver */ + /* Just forward the IOCTL to the wireless driver */ ret = dev->d_ioctl(dev, cmd, ((long)(uintptr_t)req)); } @@ -1160,7 +1160,7 @@ int psock_ioctl(FAR struct socket *psock, int cmd, unsigned long arg) ret = netdev_ifrioctl(psock, cmd, (FAR struct ifreq *)((uintptr_t)arg)); -#if defined(CONFIG_NETDEV_IOCTL) && defined(CONFIG_NETDEV_NETDEV_WIRELESS_IOCTL) +#if defined(CONFIG_NETDEV_IOCTL) && defined(CONFIG_NETDEV_WIRELESS_IOCTL) /* Check a wireless network command */ if (ret == -ENOTTY) -- GitLab From 5f5b20ab74e3e8bd64e44401db4551fa58543899 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 13 Mar 2017 13:15:49 -0600 Subject: [PATCH 027/990] Cosmetic update to some spacing and comments. --- include/nuttx/wireless/wireless.h | 16 ++++++++++------ 1 file changed, 10 insertions(+), 6 deletions(-) diff --git a/include/nuttx/wireless/wireless.h b/include/nuttx/wireless/wireless.h index a9aec2373c..98b2cf7bb1 100644 --- a/include/nuttx/wireless/wireless.h +++ b/include/nuttx/wireless/wireless.h @@ -149,6 +149,7 @@ #define SIOCSIWPMKSA _WLIOC(0x0032) /* PMKSA cache operation */ +#define WL_FIRSTCHAR 0x0033 #define WL_NNETCMDS 0x0032 /* Character Driver IOCTL commands *************************************************/ @@ -185,7 +186,7 @@ #define NRF24L01_FIRST (CC3000_FIRST + CC3000_NCMDS) #define NRF24L01_NCMDS 14 -/* Other Definitions ****************************************************************/ +/* Other Common Wireless Definitions ***********************************************/ /* Maximum size of the ESSID and NICKN strings */ @@ -195,6 +196,7 @@ * Public Types ************************************************************************************/ /* TODO: + * * - Add types for statistics (struct iw_statistics and related) * - Add struct iw_range for use with IOCTL commands that need exchange mode data * that could not fit in iwreq. @@ -203,6 +205,8 @@ * - WPA support. * - Wireless events. * - Various flag definitions. + * + * These future additions will all need to be compatible with BSD/Linux definitions. */ /* Generic format for most parameters that fit in a int32_t */ @@ -280,17 +284,17 @@ union iwreq_data struct iw_param param; /* Other small parameters */ struct iw_point data; /* Other large parameters */ - }; +}; - /* This is the structure used to exchange data in wireless IOCTLs. This structure - * is the same as 'struct ifreq', but defined for use with wireless IOCTLs. - */ +/* This is the structure used to exchange data in wireless IOCTLs. This structure + * is the same as 'struct ifreq', but defined for use with wireless IOCTLs. + */ struct iwreq { char ifrn_name[IFNAMSIZ]; /* Interface name, e.g. "eth0" */ union iwreq_data u; /* Data payload */ - }; +}; #endif /* CONFIG_DRIVERS_WIRELESS */ #endif /* __INCLUDE_NUTTX_WIRELESS_H */ -- GitLab From 4d760c5ea44c5f8d30a1a595800e9fbf4874e705 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Mon, 13 Mar 2017 10:46:26 -1000 Subject: [PATCH 028/990] semaphore:sem_holder add DEBUGASSERT s --- sched/semaphore/sem_holder.c | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/sched/semaphore/sem_holder.c b/sched/semaphore/sem_holder.c index b6a5e2c788..9aeaa28bbb 100644 --- a/sched/semaphore/sem_holder.c +++ b/sched/semaphore/sem_holder.c @@ -125,6 +125,7 @@ static inline FAR struct semholder_s *sem_allocholder(sem_t *sem) pholder = NULL; } + DEBUGASSERT(pholder != NULL) return pholder; } @@ -318,6 +319,7 @@ static int sem_boostholderprio(FAR struct semholder_s *pholder, if (!sched_verifytcb(htcb)) { serr("ERROR: TCB 0x%08x is a stale handle, counts lost\n", htcb); + DEBUGASSERT(!sched_verifytcb(htcb)); sem_freeholder(sem, pholder); } @@ -355,6 +357,7 @@ static int sem_boostholderprio(FAR struct semholder_s *pholder, else { serr("ERROR: CONFIG_SEM_NNESTPRIO exceeded\n"); + DEBUGASSERT(htcb->npend_reprio < CONFIG_SEM_NNESTPRIO); } } @@ -468,6 +471,7 @@ static int sem_restoreholderprio(FAR struct semholder_s *pholder, if (!sched_verifytcb(htcb)) { serr("ERROR: TCB 0x%08x is a stale handle, counts lost\n", htcb); + DEBUGASSERT(!sched_verifytcb(htcb)); sem_freeholder(sem, pholder); } @@ -853,11 +857,13 @@ void sem_destroyholder(FAR sem_t *sem) if (sem->hhead != NULL) { serr("ERROR: Semaphore destroyed with holders\n"); + DEBUGASSERT(sem->hhead != NULL); (void)sem_foreachholder(sem, sem_recoverholders, NULL); } #else if (sem->holder[0].htcb != NULL || sem->holder[0].htcb != NULL) { + DEBUGASSERT(sem->holder[0].htcb != NULL || sem->holder[0].htcb != NULL); serr("ERROR: Semaphore destroyed with holder\n"); } -- GitLab From 3c00651cfef3a0d90bb9e6522463965ad8989e6c Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Mon, 13 Mar 2017 11:56:31 -1000 Subject: [PATCH 029/990] semaphore:sem_holder sem_findholder missing inintalization of pholder sem_findholder would fail and code optimization coverd this up. --- sched/semaphore/sem_holder.c | 1 + 1 file changed, 1 insertion(+) diff --git a/sched/semaphore/sem_holder.c b/sched/semaphore/sem_holder.c index 9aeaa28bbb..cd8b26c662 100644 --- a/sched/semaphore/sem_holder.c +++ b/sched/semaphore/sem_holder.c @@ -154,6 +154,7 @@ static FAR struct semholder_s *sem_findholder(sem_t *sem, } #else int i; + pholder = NULL; /* We have two hard-allocated holder structuse in sem_t */ -- GitLab From d66fd9f965f27eb0446d6aed24b8758674f98b53 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Mon, 13 Mar 2017 12:34:39 -1000 Subject: [PATCH 030/990] semaphore:sem_boostholderprio prevent overrun of pend_reprios The second case rtcb->sched_priority <= htcb->sched_priority did not check if there is sufficient space in the pend_reprios array. --- sched/semaphore/sem_holder.c | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/sched/semaphore/sem_holder.c b/sched/semaphore/sem_holder.c index cd8b26c662..e0d594b132 100644 --- a/sched/semaphore/sem_holder.c +++ b/sched/semaphore/sem_holder.c @@ -379,8 +379,16 @@ static int sem_boostholderprio(FAR struct semholder_s *pholder, * saved priority and not to the base priority. */ - htcb->pend_reprios[htcb->npend_reprio] = rtcb->sched_priority; - htcb->npend_reprio++; + if (htcb->npend_reprio < CONFIG_SEM_NNESTPRIO) + { + htcb->pend_reprios[htcb->npend_reprio] = rtcb->sched_priority; + htcb->npend_reprio++; + } + else + { + serr("ERROR: CONFIG_SEM_NNESTPRIO exceeded\n"); + DEBUGASSERT(htcb->npend_reprio < CONFIG_SEM_NNESTPRIO); + } } } -- GitLab From caf8bac7fb9452f25a3297147e7b414d46e74c6f Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Mon, 13 Mar 2017 22:54:13 +0000 Subject: [PATCH 031/990] missing semi --- sched/semaphore/sem_holder.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sched/semaphore/sem_holder.c b/sched/semaphore/sem_holder.c index e0d594b132..eaf443342d 100644 --- a/sched/semaphore/sem_holder.c +++ b/sched/semaphore/sem_holder.c @@ -125,7 +125,7 @@ static inline FAR struct semholder_s *sem_allocholder(sem_t *sem) pholder = NULL; } - DEBUGASSERT(pholder != NULL) + DEBUGASSERT(pholder != NULL); return pholder; } -- GitLab From aad82bcd9fbe60162c5b320661c0fb086255da9f Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 13 Mar 2017 17:59:36 -0600 Subject: [PATCH 032/990] Cosmetic change --- net/netdev/netdev_ioctl.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/net/netdev/netdev_ioctl.c b/net/netdev/netdev_ioctl.c index 41769f653b..a9a70191fd 100644 --- a/net/netdev/netdev_ioctl.c +++ b/net/netdev/netdev_ioctl.c @@ -1,7 +1,7 @@ /**************************************************************************** * net/netdev/netdev_ioctl.c * - * Copyright (C) 2007-2012, 2015-2016 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2012, 2015-2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -1260,7 +1260,7 @@ void netdev_ifup(FAR struct net_driver_s *dev) { /* Make sure that the device supports the d_ifup() method */ - if (dev->d_ifup) + if (dev->d_ifup != NULL) { /* Is the interface already up? */ @@ -1282,7 +1282,7 @@ void netdev_ifdown(FAR struct net_driver_s *dev) { /* Check sure that the device supports the d_ifdown() method */ - if (dev->d_ifdown) + if (dev->d_ifdown != NULL) { /* Is the interface already down? */ -- GitLab From 1870a35b0bcfc1b5ecb5d9318eb813a19c801179 Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Mon, 13 Mar 2017 18:00:48 -0600 Subject: [PATCH 033/990] Include C++ library to 'make export' --- FlatLibs.mk | 6 ++++++ KernelLibs.mk | 6 ++++++ ProtectedLibs.mk | 6 ++++++ 3 files changed, 18 insertions(+) diff --git a/FlatLibs.mk b/FlatLibs.mk index 69fe6a9fa0..0a05e84c49 100644 --- a/FlatLibs.mk +++ b/FlatLibs.mk @@ -118,6 +118,12 @@ ifeq ($(CONFIG_WIRELESS),y) NUTTXLIBS += lib$(DELIM)libwireless$(LIBEXT) endif +# Add C++ library + +ifeq ($(CONFIG_HAVE_CXX),y) +NUTTXLIBS += lib$(DELIM)libcxx$(LIBEXT) +endif + # Export all libraries EXPORTLIBS = $(NUTTXLIBS) diff --git a/KernelLibs.mk b/KernelLibs.mk index 719430b6c9..b1da6dbd0b 100644 --- a/KernelLibs.mk +++ b/KernelLibs.mk @@ -113,6 +113,12 @@ ifeq ($(CONFIG_WIRELESS),y) NUTTXLIBS += lib$(DELIM)libwireless$(LIBEXT) endif +# Add C++ library + +ifeq ($(CONFIG_HAVE_CXX),y) +NUTTXLIBS += lib$(DELIM)libcxx$(LIBEXT) +endif + # Export only the user libraries EXPORTLIBS = $(USERLIBS) diff --git a/ProtectedLibs.mk b/ProtectedLibs.mk index 4f2e2c6072..5dd45a6fab 100644 --- a/ProtectedLibs.mk +++ b/ProtectedLibs.mk @@ -123,6 +123,12 @@ ifeq ($(CONFIG_WIRELESS),y) NUTTXLIBS += lib$(DELIM)libwireless$(LIBEXT) endif +# Add C++ library + +ifeq ($(CONFIG_HAVE_CXX),y) +NUTTXLIBS += lib$(DELIM)libcxx$(LIBEXT) +endif + # Export only the user libraries EXPORTLIBS = $(USERLIBS) -- GitLab From 86400a252dcbe6e4aef3ecca000b469a0fe96b67 Mon Sep 17 00:00:00 2001 From: David Cabecinhas Date: Tue, 14 Mar 2017 18:22:18 +0800 Subject: [PATCH 034/990] ARM: Fix off-by-one interrupt stack allocation in 8-byte aligned architectures --- arch/arm/src/armv7-m/gnu/up_exception.S | 2 +- arch/arm/src/armv7-m/gnu/up_lazyexception.S | 4 ++-- arch/arm/src/common/up_initialize.c | 2 +- arch/arm/src/kinetis/kinetis_vectors.S | 2 +- arch/arm/src/lpc17xx/lpc17_vectors.S | 4 ++-- arch/arm/src/sam34/sam_vectors.S | 4 ++-- arch/arm/src/stm32/gnu/stm32_vectors.S | 2 +- arch/arm/src/stm32/iar/stm32_vectors.S | 2 +- arch/arm/src/tiva/tiva_vectors.S | 4 ++-- 9 files changed, 13 insertions(+), 13 deletions(-) diff --git a/arch/arm/src/armv7-m/gnu/up_exception.S b/arch/arm/src/armv7-m/gnu/up_exception.S index 0010136b03..4f2927b421 100644 --- a/arch/arm/src/armv7-m/gnu/up_exception.S +++ b/arch/arm/src/armv7-m/gnu/up_exception.S @@ -323,7 +323,7 @@ exception_common: .global g_intstackbase .align 8 g_intstackalloc: - .skip (CONFIG_ARCH_INTERRUPTSTACK & ~7) + .skip ((CONFIG_ARCH_INTERRUPTSTACK + 4) & ~7) g_intstackbase: .size g_intstackalloc, .-g_intstackalloc #endif diff --git a/arch/arm/src/armv7-m/gnu/up_lazyexception.S b/arch/arm/src/armv7-m/gnu/up_lazyexception.S index 08ce8be75c..eb3e27057b 100644 --- a/arch/arm/src/armv7-m/gnu/up_lazyexception.S +++ b/arch/arm/src/armv7-m/gnu/up_lazyexception.S @@ -235,7 +235,7 @@ exception_common: * * Here: * r0 = Address of the register save area - + * NOTE: It is a requirement that up_restorefpu() preserve the value of * r0! */ @@ -355,7 +355,7 @@ exception_common: .global g_intstackbase .align 8 g_intstackalloc: - .skip (CONFIG_ARCH_INTERRUPTSTACK & ~7) + .skip ((CONFIG_ARCH_INTERRUPTSTACK + 4) & ~7) g_intstackbase: .size g_intstackalloc, .-g_intstackalloc #endif diff --git a/arch/arm/src/common/up_initialize.c b/arch/arm/src/common/up_initialize.c index 267f5e1c59..ff11e45170 100644 --- a/arch/arm/src/common/up_initialize.c +++ b/arch/arm/src/common/up_initialize.c @@ -106,7 +106,7 @@ static inline void up_color_intstack(void) uint32_t *ptr = (uint32_t *)&g_intstackalloc; ssize_t size; - for (size = (CONFIG_ARCH_INTERRUPTSTACK & ~7); + for (size = (CONFIG_ARCH_INTERRUPTSTACK & ~3); size > 0; size -= sizeof(uint32_t)) { diff --git a/arch/arm/src/kinetis/kinetis_vectors.S b/arch/arm/src/kinetis/kinetis_vectors.S index 48c74c7059..30940199af 100644 --- a/arch/arm/src/kinetis/kinetis_vectors.S +++ b/arch/arm/src/kinetis/kinetis_vectors.S @@ -484,7 +484,7 @@ exception_common: .global g_intstackbase .align 8 g_intstackalloc: - .skip (CONFIG_ARCH_INTERRUPTSTACK & ~7) + .skip ((CONFIG_ARCH_INTERRUPTSTACK + 4) & ~7) g_intstackbase: .size g_intstackalloc, .-g_intstackalloc #endif diff --git a/arch/arm/src/lpc17xx/lpc17_vectors.S b/arch/arm/src/lpc17xx/lpc17_vectors.S index 6cee7d9731..988147263e 100644 --- a/arch/arm/src/lpc17xx/lpc17_vectors.S +++ b/arch/arm/src/lpc17xx/lpc17_vectors.S @@ -348,7 +348,7 @@ exception_common: * * Here: * r0 = Address of the register save area - + * NOTE: It is a requirement that up_restorefpu() preserve the value of * r0! */ @@ -468,7 +468,7 @@ exception_common: .global g_intstackbase .align 8 g_intstackalloc: - .skip (CONFIG_ARCH_INTERRUPTSTACK & ~7) + .skip ((CONFIG_ARCH_INTERRUPTSTACK + 4) & ~7) g_intstackbase: .size g_intstackalloc, .-g_intstackalloc #endif diff --git a/arch/arm/src/sam34/sam_vectors.S b/arch/arm/src/sam34/sam_vectors.S index 9765f61474..9de7d247a9 100644 --- a/arch/arm/src/sam34/sam_vectors.S +++ b/arch/arm/src/sam34/sam_vectors.S @@ -362,7 +362,7 @@ exception_common: * * Here: * r0 = Address of the register save area - + * NOTE: It is a requirement that up_restorefpu() preserve the value of * r0! */ @@ -482,7 +482,7 @@ exception_common: .global g_intstackbase .align 8 g_intstackalloc: - .skip (CONFIG_ARCH_INTERRUPTSTACK & ~7) + .skip ((CONFIG_ARCH_INTERRUPTSTACK + 4) & ~7) g_intstackbase: .size g_intstackalloc, .-g_intstackalloc #endif diff --git a/arch/arm/src/stm32/gnu/stm32_vectors.S b/arch/arm/src/stm32/gnu/stm32_vectors.S index 31f62c8d11..c961781f33 100644 --- a/arch/arm/src/stm32/gnu/stm32_vectors.S +++ b/arch/arm/src/stm32/gnu/stm32_vectors.S @@ -497,7 +497,7 @@ exception_common: .global g_intstackbase .align 8 g_intstackalloc: - .skip (CONFIG_ARCH_INTERRUPTSTACK & ~7) + .skip ((CONFIG_ARCH_INTERRUPTSTACK + 4) & ~7) g_intstackbase: .size g_intstackalloc, .-g_intstackalloc #endif diff --git a/arch/arm/src/stm32/iar/stm32_vectors.S b/arch/arm/src/stm32/iar/stm32_vectors.S index cf83e7b8bf..f46cb7c57b 100644 --- a/arch/arm/src/stm32/iar/stm32_vectors.S +++ b/arch/arm/src/stm32/iar/stm32_vectors.S @@ -1055,7 +1055,7 @@ l5: .global g_intstackbase .align 8 g_intstackalloc: - .skip (CONFIG_ARCH_INTERRUPTSTACK & ~7) + .skip ((CONFIG_ARCH_INTERRUPTSTACK + 4) & ~7) g_intstackbase: .size g_intstackalloc, .-g_intstackalloc #endif diff --git a/arch/arm/src/tiva/tiva_vectors.S b/arch/arm/src/tiva/tiva_vectors.S index 4f56269ba4..943581c2e1 100644 --- a/arch/arm/src/tiva/tiva_vectors.S +++ b/arch/arm/src/tiva/tiva_vectors.S @@ -339,7 +339,7 @@ exception_common: * * Here: * r0 = Address of the register save area - + * NOTE: It is a requirement that up_restorefpu() preserve the value of * r0! */ @@ -459,7 +459,7 @@ exception_common: .global g_intstackbase .align 8 g_intstackalloc: - .skip (CONFIG_ARCH_INTERRUPTSTACK & ~7) + .skip ((CONFIG_ARCH_INTERRUPTSTACK + 4) & ~7) g_intstackbase: .size g_intstackalloc, .-g_intstackalloc #endif -- GitLab From 33f7bfa351c4edc9e2420afd5d503bb90046d90a Mon Sep 17 00:00:00 2001 From: David Date: Tue, 14 Mar 2017 21:01:44 +0800 Subject: [PATCH 035/990] ARM: Fix off-by-one interrupt stack allocation (revert missed change in up_initialize.c) --- arch/arm/src/common/up_initialize.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/arch/arm/src/common/up_initialize.c b/arch/arm/src/common/up_initialize.c index ff11e45170..5182598246 100644 --- a/arch/arm/src/common/up_initialize.c +++ b/arch/arm/src/common/up_initialize.c @@ -100,7 +100,7 @@ static void up_calibratedelay(void) * ****************************************************************************/ -#if defined(CONFIG_STACK_COLORATION) && CONFIG_ARCH_INTERRUPTSTACK > 7 +#if defined(CONFIG_STACK_COLORATION) && CONFIG_ARCH_INTERRUPTSTACK > 3 static inline void up_color_intstack(void) { uint32_t *ptr = (uint32_t *)&g_intstackalloc; -- GitLab From 4a93b0dc0cc80f9567ac0c470054262aaadf83c6 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 14 Mar 2017 08:44:56 -0600 Subject: [PATCH 036/990] Update comments. --- arch/arm/src/armv7-m/gnu/up_lazyexception.S | 2 +- arch/arm/src/lpc17xx/lpc17_vectors.S | 2 +- arch/arm/src/sam34/sam_vectors.S | 2 +- arch/arm/src/tiva/tiva_vectors.S | 2 +- include/nuttx/wireless/wireless.h | 25 +++++++++++++++------ 5 files changed, 22 insertions(+), 11 deletions(-) diff --git a/arch/arm/src/armv7-m/gnu/up_lazyexception.S b/arch/arm/src/armv7-m/gnu/up_lazyexception.S index eb3e27057b..0a0e088a62 100644 --- a/arch/arm/src/armv7-m/gnu/up_lazyexception.S +++ b/arch/arm/src/armv7-m/gnu/up_lazyexception.S @@ -235,7 +235,7 @@ exception_common: * * Here: * r0 = Address of the register save area - + * * NOTE: It is a requirement that up_restorefpu() preserve the value of * r0! */ diff --git a/arch/arm/src/lpc17xx/lpc17_vectors.S b/arch/arm/src/lpc17xx/lpc17_vectors.S index 988147263e..bf37fc9e81 100644 --- a/arch/arm/src/lpc17xx/lpc17_vectors.S +++ b/arch/arm/src/lpc17xx/lpc17_vectors.S @@ -348,7 +348,7 @@ exception_common: * * Here: * r0 = Address of the register save area - + * * NOTE: It is a requirement that up_restorefpu() preserve the value of * r0! */ diff --git a/arch/arm/src/sam34/sam_vectors.S b/arch/arm/src/sam34/sam_vectors.S index 9de7d247a9..9d2b5e6b31 100644 --- a/arch/arm/src/sam34/sam_vectors.S +++ b/arch/arm/src/sam34/sam_vectors.S @@ -362,7 +362,7 @@ exception_common: * * Here: * r0 = Address of the register save area - + * * NOTE: It is a requirement that up_restorefpu() preserve the value of * r0! */ diff --git a/arch/arm/src/tiva/tiva_vectors.S b/arch/arm/src/tiva/tiva_vectors.S index 943581c2e1..89c9c38e82 100644 --- a/arch/arm/src/tiva/tiva_vectors.S +++ b/arch/arm/src/tiva/tiva_vectors.S @@ -339,7 +339,7 @@ exception_common: * * Here: * r0 = Address of the register save area - + * * NOTE: It is a requirement that up_restorefpu() preserve the value of * r0! */ diff --git a/include/nuttx/wireless/wireless.h b/include/nuttx/wireless/wireless.h index 98b2cf7bb1..6ab0b0b3d1 100644 --- a/include/nuttx/wireless/wireless.h +++ b/include/nuttx/wireless/wireless.h @@ -59,6 +59,10 @@ ************************************************************************************/ /* Network Driver IOCTL Commands ****************************************************/ +/* Use of these IOCTL commands requires a socket descriptor created by the socket() + * interface. + */ + /* Wireless identification */ #define SIOCSIWCOMMIT _WLIOC(0x0001) /* Commit pending changes to driver */ @@ -154,15 +158,22 @@ /* Character Driver IOCTL commands *************************************************/ /* Non-compatible, NuttX only IOCTL definitions for use with low-level wireless - * drivers that are accessed via a character device. + * drivers that are accessed via a character device. Use of these IOCTL commands + * requires a file descriptor created by the open() interface. */ -#define WLIOC_SETRADIOFREQ _WLIOC(0x0033) /* arg: Pointer to uint32_t, frequency value (in Mhz) */ -#define WLIOC_GETRADIOFREQ _WLIOC(0x0034) /* arg: Pointer to uint32_t, frequency value (in Mhz) */ -#define WLIOC_SETADDR _WLIOC(0x0035) /* arg: Pointer to address value, format of the address is driver specific */ -#define WLIOC_GETADDR _WLIOC(0x0036) /* arg: Pointer to address value, format of the address is driver specific */ -#define WLIOC_SETTXPOWER _WLIOC(0x0037) /* arg: Pointer to int32_t, output power (in dBm) */ -#define WLIOC_GETTXPOWER _WLIOC(0x0038) /* arg: Pointer to int32_t, output power (in dBm) */ +#define WLIOC_SETRADIOFREQ _WLIOC(0x0033) /* arg: Pointer to uint32_t, frequency + * value (in Mhz) */ +#define WLIOC_GETRADIOFREQ _WLIOC(0x0034) /* arg: Pointer to uint32_t, frequency + * value (in Mhz) */ +#define WLIOC_SETADDR _WLIOC(0x0035) /* arg: Pointer to address value, format + * of the address is driver specific */ +#define WLIOC_GETADDR _WLIOC(0x0036) /* arg: Pointer to address value, format + * of the address is driver specific */ +#define WLIOC_SETTXPOWER _WLIOC(0x0037) /* arg: Pointer to int32_t, output power + * (in dBm) */ +#define WLIOC_GETTXPOWER _WLIOC(0x0038) /* arg: Pointer to int32_t, output power + * (in dBm) */ /* Device-specific IOCTL commands **************************************************/ -- GitLab From c97581e99bd3d18acb7db502c6d1bc4487da01ce Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 14 Mar 2017 11:16:35 -0600 Subject: [PATCH 037/990] Update some comments --- arch/arm/src/kinetis/chip.h | 2 +- arch/arm/src/kinetis/kinetis_clrpend.c | 1 - 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/arch/arm/src/kinetis/chip.h b/arch/arm/src/kinetis/chip.h index c16f31b14d..262ad55557 100644 --- a/arch/arm/src/kinetis/chip.h +++ b/arch/arm/src/kinetis/chip.h @@ -52,7 +52,7 @@ /* If the common ARMv7-M vector handling logic is used, then it expects the * following definition in this file that provides the number of supported external - * interrupts which, for this architecture, is provided in the arch/stm32f7/chip.h + * interrupts which, for this architecture, is provided in the arch/kinetis/chip.h * header file. */ diff --git a/arch/arm/src/kinetis/kinetis_clrpend.c b/arch/arm/src/kinetis/kinetis_clrpend.c index faf35271d8..aad182df36 100644 --- a/arch/arm/src/kinetis/kinetis_clrpend.c +++ b/arch/arm/src/kinetis/kinetis_clrpend.c @@ -1,6 +1,5 @@ /**************************************************************************** * arch/arm/src/kinetis/kinetis_clrpend.c - * arch/arm/src/chip/kinetis_clrpend.c * * Copyright (C) 2011 Gregory Nutt. All rights reserved. * Author: Gregory Nutt -- GitLab From 240d1e9b3b66b659a4e3ad1d98a0bb67c03b56a6 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 14 Mar 2017 11:39:10 -0600 Subject: [PATCH 038/990] Update some comments --- arch/arm/src/kinetis/kinetis_start.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/arch/arm/src/kinetis/kinetis_start.c b/arch/arm/src/kinetis/kinetis_start.c index 6747ce24e8..f7445c5cde 100644 --- a/arch/arm/src/kinetis/kinetis_start.c +++ b/arch/arm/src/kinetis/kinetis_start.c @@ -1,6 +1,5 @@ /**************************************************************************** * arch/arm/src/kinetis/kinetis_start.c - * arch/arm/src/chip/kinetis_start.c * * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -327,6 +326,7 @@ void __start(void) * can get debug output as soon as possible (This depends on clock * configuration). */ + kinetis_fpuconfig(); kinetis_lowsetup(); #ifdef USE_EARLYSERIALINIT -- GitLab From dc4ac48aad19b791247eef851c3d648cb19a5ada Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 14 Mar 2017 11:56:29 -0600 Subject: [PATCH 039/990] arch/arm/src/xmc4: Initial, partial support for Infineon XMC4xxx --- arch/arm/Kconfig | 16 + arch/arm/src/xmc4/Kconfig | 328 +++++++ arch/arm/src/xmc4/Make.defs | 141 +++ arch/arm/src/xmc4/chip.h | 77 ++ arch/arm/src/xmc4/xmc4_allocateheap.c | 193 +++++ arch/arm/src/xmc4/xmc4_clockconfig.c | 74 ++ arch/arm/src/xmc4/xmc4_clrpend.c | 102 +++ arch/arm/src/xmc4/xmc4_config.h | 198 +++++ arch/arm/src/xmc4/xmc4_dma.c | 0 arch/arm/src/xmc4/xmc4_dma.h | 218 +++++ arch/arm/src/xmc4/xmc4_gpio.c | 0 arch/arm/src/xmc4/xmc4_gpio.h | 0 arch/arm/src/xmc4/xmc4_i2c.c | 0 arch/arm/src/xmc4/xmc4_i2c.h | 87 ++ arch/arm/src/xmc4/xmc4_idle.c | 105 +++ arch/arm/src/xmc4/xmc4_irq.c | 588 +++++++++++++ arch/arm/src/xmc4/xmc4_lowputc.c | 235 +++++ arch/arm/src/xmc4/xmc4_mpuinit.c | 124 +++ arch/arm/src/xmc4/xmc4_mpuinit.h | 78 ++ arch/arm/src/xmc4/xmc4_pwm.c | 0 arch/arm/src/xmc4/xmc4_pwm.h | 100 +++ arch/arm/src/xmc4/xmc4_serial.c | 1146 +++++++++++++++++++++++++ arch/arm/src/xmc4/xmc4_spi.h | 165 ++++ arch/arm/src/xmc4/xmc4_start.c | 355 ++++++++ arch/arm/src/xmc4/xmc4_timerisr.c | 152 ++++ arch/arm/src/xmc4/xmc4_userspace.c | 107 +++ arch/arm/src/xmc4/xmc4_userspace.h | 64 ++ 27 files changed, 4653 insertions(+) create mode 100644 arch/arm/src/xmc4/Kconfig create mode 100644 arch/arm/src/xmc4/Make.defs create mode 100644 arch/arm/src/xmc4/chip.h create mode 100644 arch/arm/src/xmc4/xmc4_allocateheap.c create mode 100644 arch/arm/src/xmc4/xmc4_clockconfig.c create mode 100644 arch/arm/src/xmc4/xmc4_clrpend.c create mode 100644 arch/arm/src/xmc4/xmc4_config.h create mode 100644 arch/arm/src/xmc4/xmc4_dma.c create mode 100644 arch/arm/src/xmc4/xmc4_dma.h create mode 100644 arch/arm/src/xmc4/xmc4_gpio.c create mode 100644 arch/arm/src/xmc4/xmc4_gpio.h create mode 100644 arch/arm/src/xmc4/xmc4_i2c.c create mode 100644 arch/arm/src/xmc4/xmc4_i2c.h create mode 100644 arch/arm/src/xmc4/xmc4_idle.c create mode 100644 arch/arm/src/xmc4/xmc4_irq.c create mode 100644 arch/arm/src/xmc4/xmc4_lowputc.c create mode 100644 arch/arm/src/xmc4/xmc4_mpuinit.c create mode 100644 arch/arm/src/xmc4/xmc4_mpuinit.h create mode 100644 arch/arm/src/xmc4/xmc4_pwm.c create mode 100644 arch/arm/src/xmc4/xmc4_pwm.h create mode 100644 arch/arm/src/xmc4/xmc4_serial.c create mode 100644 arch/arm/src/xmc4/xmc4_spi.h create mode 100644 arch/arm/src/xmc4/xmc4_start.c create mode 100644 arch/arm/src/xmc4/xmc4_timerisr.c create mode 100644 arch/arm/src/xmc4/xmc4_userspace.c create mode 100644 arch/arm/src/xmc4/xmc4_userspace.h diff --git a/arch/arm/Kconfig b/arch/arm/Kconfig index fd44dcff07..21334e7117 100644 --- a/arch/arm/Kconfig +++ b/arch/arm/Kconfig @@ -270,6 +270,19 @@ config ARCH_CHIP_TMS570 ---help--- TI TMS570 family +config ARCH_CHIP_XMC4 + bool "Infineon XMC4xxx" + select ARCH_HAVE_CMNVECTOR + select ARCH_CORTEXM4 + select ARCH_HAVE_MPU + select ARCH_HAVE_RAMFUNCS + select ARCH_HAVE_I2CRESET + select ARM_HAVE_MPU_UNIFIED + select ARMV7M_CMNVECTOR + select ARMV7M_HAVE_STACKCHECK + ---help--- + Infineon XMC4xxx(ARM Cortex-M4) architectures + config ARCH_CHIP_MOXART bool "MoxART" select ARCH_ARM7TDMI @@ -692,6 +705,9 @@ endif if ARCH_CHIP_TMS570 source arch/arm/src/tms570/Kconfig endif +if ARCH_CHIP_XMC4 +source arch/arm/src/xmc4/Kconfig +endif if ARCH_CHIP_MOXART source arch/arm/src/moxart/Kconfig endif diff --git a/arch/arm/src/xmc4/Kconfig b/arch/arm/src/xmc4/Kconfig new file mode 100644 index 0000000000..116d56d14f --- /dev/null +++ b/arch/arm/src/xmc4/Kconfig @@ -0,0 +1,328 @@ +# +# For a description of the syntax of this configuration file, +# see the file kconfig-language.txt in the NuttX tools repository. +# + +comment "XMC4xxx Configuration Options" + +choice + prompt "XMC4xxx Chip Selection" + default ARCH_CHIP_XMC4500 + depends on ARCH_CHIP_XMC4 + +config ARCH_CHIP_XMC4500 + bool "XMC4500" + +endchoice + +# These "hidden" settings determine is a peripheral option is available for +# the selection MCU + + +# When there are multiple instances of a device, these "hidden" settings +# will automatically be selected and will represent the 'OR' of the +# instances selected. + +config XMC4_USIC + bool + default n + +config XMC4_USCI_UART + bool + default n + select MCU_SERIAL + +config XMC4_USCI_LIN + bool + default n + +config XMC4_USCI_SPI + bool + default n + +config XMC4_USCI_I2C + bool + default n + +config XMC4_USCI_I2S + bool + default n + +# Chip families + +menu "ARCH_CHIP_XMC4 Peripheral Support" + +config XMC4_USIC0 + bool "USIC0" + default n + select XMC4_USIC + ---help--- + Support USIC0 + +config XMC4_USIC1 + bool "USIC1" + default n + ---help--- + Support USIC1 + +config XMC4_USIC2 + bool "USIC3" + default n + select XMC4_USIC + ---help--- + Support USIC2 + +config XMC4_USIC3 + bool "USIC3" + default n + select XMC4_USIC + ---help--- + Support USIC3 + +config XMC4_USIC4 + bool "USIC4" + default n + select XMC4_USIC + ---help--- + Support USIC4 + +config XMC4_USIC5 + bool "USIC5" + default n + select XMC4_USIC + ---help--- + Support USIC5 + +endmenu + +menu "XMC4xxx USIC Configuration" + depends on XMC4_USIC + +choice + prompt "USIC0 Configuration" + default XMC4_USIC0_ISUART + depends on XMC4_USIC0 + +config XMC4_USIC0_ISUART + bool "UART" + select UART0_SERIALDRIVER + select XMC4_USCI_UART + ---help--- + Configure USIC0 as a UART + +config XMC4_USIC0_ISLIN + bool "LIN" + select XMC4_USCI_LIN + ---help--- + Configure USIC0 as a LIN UART + +config XMC4_USIC0_ISSPI + bool "SPI" + select XMC4_USCI_SPI + ---help--- + Configure USIC0 For SPI communications + +config XMC4_USIC0_ISI2C + bool "I2C" + select XMC4_USCI_I2C + ---help--- + Configure USIC0 For I2C communications + +config XMC4_USIC0_ISI2S + bool "I2S" + select XMC4_USCI_I2S + ---help--- + Configure USIC0 For I2S audio + +endchoice # USIC0 Configuration + +choice + prompt "USIC1 Configuration" + default XMC4_USIC1_ISUART + depends on XMC4_USIC1 + +config XMC4_USIC1_ISUART + bool "UART" + select UART1_SERIALDRIVER + select XMC4_USCI_UART + ---help--- + Configure USIC1 as a UART + +config XMC4_USIC1_ISLIN + bool "LIN" + select XMC4_USCI_LIN + ---help--- + Configure USIC1 as a LIN UART + +config XMC4_USIC1_ISSPI + bool "SPI" + select XMC4_USCI_SPI + ---help--- + Configure USIC1 For SPI communications + +config XMC4_USIC1_ISI2C + bool "I2C" + select XMC4_USCI_I2C + ---help--- + Configure USIC1 For I2C communications + +config XMC4_USIC1_ISI2S + bool "I2S" + select XMC4_USCI_I2S + ---help--- + Configure USIC1 For I2S audio + +endchoice # USIC1 Configuration + +choice + prompt "USIC2 Configuration" + default XMC4_USIC2_ISUART + depends on XMC4_USIC2 + +config XMC4_USIC2_ISUART + bool "UART" + select UART2_SERIALDRIVER + select XMC4_USCI_UART + ---help--- + Configure USIC2 as a UART + +config XMC4_USIC2_ISLIN + bool "LIN" + select XMC4_USCI_LIN + ---help--- + Configure USIC2 as a LIN UART + +config XMC4_USIC2_ISSPI + bool "SPI" + select XMC4_USCI_SPI + ---help--- + Configure USIC2 For SPI communications + +config XMC4_USIC2_ISI2C + bool "I2C" + select XMC4_USCI_I2C + ---help--- + Configure USIC2 For I2C communications + +config XMC4_USIC2_ISI2S + bool "I2S" + select XMC4_USCI_I2S + ---help--- + Configure USIC2 For I2S audio + +endchoice # USIC2 Configuration + +choice + prompt "USIC3 Configuration" + default XMC4_USIC3_ISUART + depends on XMC4_USIC3 + +config XMC4_USIC3_ISUART + bool "UART" + select UART3_SERIALDRIVER + select XMC4_USCI_UART + ---help--- + Configure USIC3 as a UART + +config XMC4_USIC3_ISLIN + bool "LIN" + select XMC4_USCI_LIN + ---help--- + Configure USIC3 as a LIN UART + +config XMC4_USIC3_ISSPI + bool "SPI" + select XMC4_USCI_SPI + ---help--- + Configure USIC3 For SPI communications + +config XMC4_USIC3_ISI2C + bool "I2C" + select XMC4_USCI_I2C + ---help--- + Configure USIC3 For I2C communications + +config XMC4_USIC3_ISI2S + bool "I2S" + select XMC4_USCI_I2S + ---help--- + Configure USIC3 For I2S audio + +endchoice # USIC3 Configuration + +choice + prompt "USIC4 Configuration" + default XMC4_USIC4_ISUART + depends on XMC4_USIC4 + +config XMC4_USIC4_ISUART + bool "UART" + select UART4_SERIALDRIVER + select XMC4_USCI_UART + ---help--- + Configure USIC4 as a UART + +config XMC4_USIC4_ISLIN + bool "LIN" + select XMC4_USCI_LIN + ---help--- + Configure USIC4 as a LIN UART + +config XMC4_USIC4_ISSPI + bool "SPI" + select XMC4_USCI_SPI + ---help--- + Configure USIC4 For SPI communications + +config XMC4_USIC4_ISI2C + bool "I2C" + select XMC4_USCI_I2C + ---help--- + Configure USIC4 For I2C communications + +config XMC4_USIC4_ISI2S + bool "I2S" + select XMC4_USCI_I2S + ---help--- + Configure USIC4 For I2S audio + +endchoice # USIC4 Configuration + +choice + prompt "USIC5 Configuration" + default XMC4_USIC5_ISUART + depends on XMC4_USIC5 + +config XMC4_USIC5_ISUART + bool "UART" + select UART0_SERIALDRIVER + select XMC4_USCI_UART + ---help--- + Configure USIC5 as a UART + +config XMC4_USIC5_ISLIN + bool "LIN" + select XMC4_USCI_LIN + ---help--- + Configure USIC5 as a LIN UART + +config XMC4_USIC5_ISSPI + bool "SPI" + select XMC4_USCI_SPI + ---help--- + Configure USIC5 For SPI communications + +config XMC4_USIC5_ISI2C + bool "I2C" + select XMC4_USCI_I2C + ---help--- + Configure USIC5 For I2C communications + +config XMC4_USIC5_ISI2S + bool "I2S" + select XMC4_USCI_I2S + ---help--- + Configure USIC5 For I2S audio + +endchoice # USIC5 Configuration +endmenu # XMC4xxx USIC Configuration diff --git a/arch/arm/src/xmc4/Make.defs b/arch/arm/src/xmc4/Make.defs new file mode 100644 index 0000000000..79497388a4 --- /dev/null +++ b/arch/arm/src/xmc4/Make.defs @@ -0,0 +1,141 @@ +############################################################################ +# arch/arm/src/kinetis/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_ARMV7M_CMNVECTOR),y) +HEAD_ASRC = +else +HEAD_ASRC = xmc4_vectors.S +endif + +CMN_UASRCS = +CMN_UCSRCS = + +CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_switchcontext.S +CMN_ASRCS += up_testset.S vfork.S + +CMN_CSRCS = up_assert.c up_blocktask.c up_copyfullstate.c up_createstack.c +CMN_CSRCS += up_mdelay.c up_udelay.c up_exit.c up_initialize.c up_memfault.c +CMN_CSRCS += up_initialstate.c up_interruptcontext.c up_modifyreg8.c +CMN_CSRCS += up_modifyreg16.c up_modifyreg32.c up_releasestack.c +CMN_CSRCS += up_reprioritizertr.c up_schedulesigaction.c up_releasepending.c +CMN_CSRCS += up_sigdeliver.c up_stackframe.c up_unblocktask.c up_usestack.c +CMN_CSRCS += up_doirq.c up_hardfault.c up_svcall.c up_vfork.c +CMN_CSRCS += up_systemreset.c + +ifeq ($(CONFIG_ARMV7M_STACKCHECK),y) +CMN_CSRCS += up_stackcheck.c +endif + +ifeq ($(CONFIG_ARMV7M_CMNVECTOR),y) +ifeq ($(CONFIG_ARMV7M_LAZYFPU),y) +CMN_ASRCS += up_lazyexception.S +else +CMN_ASRCS += up_exception.S +endif +CMN_CSRCS += up_vectors.c +endif + +ifeq ($(CONFIG_ARCH_RAMVECTORS),y) +CMN_CSRCS += up_ramvec_initialize.c up_ramvec_attach.c +endif + +ifeq ($(CONFIG_BUILD_PROTECTED),y) +CMN_CSRCS += up_mpu.c up_task_start.c up_pthread_start.c +ifneq ($(CONFIG_DISABLE_SIGNALS),y) +CMN_CSRCS += up_signal_dispatch.c +CMN_UASRCS += up_signal_handler.S +endif +endif + +ifeq ($(CONFIG_STACK_COLORATION),y) +CMN_CSRCS += up_checkstack.c +endif + +# Use of common/up_etherstub.c is deprecated. The preferred mechanism is to +# use CONFIG_NETDEV_LATEINIT=y to suppress the call to up_netinitialize() in +# up_initialize(). Then this stub would not be needed. + +ifeq ($(CONFIG_NET),y) +ifneq ($(CONFIG_XMC4_ENET),y) +CMN_CSRCS += up_etherstub.c +endif +endif + +ifeq ($(CONFIG_ARCH_FPU),y) +CMN_ASRCS += up_fpu.S +ifneq ($(CONFIG_ARMV7M_CMNVECTOR),y) +CMN_CSRCS += up_copyarmstate.c +else ifeq ($(CONFIG_ARMV7M_LAZYFPU),y) +CMN_CSRCS += up_copyarmstate.c +endif +endif + +ifeq ($(CONFIG_ARMV7M_ITMSYSLOG),y) +CMN_CSRCS += up_itm_syslog.c +endif + +# Required XMC4xxx files + +CHIP_ASRCS = + +CHIP_CSRCS = xmc4_allocateheap.c xmc4_clockconfig.c xmc4_clrpend.c +CHIP_CSRCS += xmc4_idle.c xmc4_irq.c xmc4_lowputc.c xmc4_gpio.c +CHIP_CSRCS += xmc4_serialinit.c xmc4_serial.c xmc4_start.c xmc4_uid.c + +# Configuration-dependent Kinetis files + +ifneq ($(CONFIG_SCHED_TICKLESS),y) +CHIP_CSRCS += xmc4_timerisr.c +endif + +ifeq ($(CONFIG_BUILD_PROTECTED),y) +CHIP_CSRCS += xmc4_userspace.c xmc4_mpuinit.c +endif + +ifeq ($(CONFIG_DEBUG_GPIO_INFO),y) +CHIP_CSRCS += xmc4_pindump.c +endif + +ifeq ($(CONFIG_XMC4_DMA),y) +CHIP_CSRCS += xmc4_dma.c +endif + +ifeq ($(CONFIG_PWM),y) +CHIP_CSRCS += xmc4_pwm.c +endif + +ifeq ($(CONFIG_I2C),y) +CHIP_CSRCS += xmc4_i2c.c +endif diff --git a/arch/arm/src/xmc4/chip.h b/arch/arm/src/xmc4/chip.h new file mode 100644 index 0000000000..ef746cfcc9 --- /dev/null +++ b/arch/arm/src/xmc4/chip.h @@ -0,0 +1,77 @@ +/************************************************************************************ + * arch/arm/src/xmc4/chip.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_XMC4_CHIP_H +#define __ARCH_ARM_SRC_XMC4_CHIP_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/* Include the memory map and the chip definitions file. Other chip hardware files + * should then include this file for the proper setup. + */ + +#include +#include +#include "chip/xmc4_memorymap.h" + +/* If the common ARMv7-M vector handling logic is used, then it expects the + * following definition in this file that provides the number of supported external + * interrupts which, for this architecture, is provided in the arch/xmc4/chip.h + * header file. + */ + +#define ARMV7M_PERIPHERAL_INTERRUPTS NR_INTERRUPTS + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_XMC4_CHIP_H */ diff --git a/arch/arm/src/xmc4/xmc4_allocateheap.c b/arch/arm/src/xmc4/xmc4_allocateheap.c new file mode 100644 index 0000000000..cdbc8ef2d1 --- /dev/null +++ b/arch/arm/src/xmc4/xmc4_allocateheap.c @@ -0,0 +1,193 @@ +/**************************************************************************** + * arch/arm/src/xmc4/xmc4_allocateheap.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include +#include + +#include + +#include "mpu.h" +#include "up_arch.h" +#include "up_internal.h" +#include "xmc4_mpuinit.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_allocate_heap + * + * Description: + * This function will be called to dynamically set aside the heap region. + * + * For the kernel build (CONFIG_BUILD_PROTECTED=y) with both kernel- and + * user-space heaps (CONFIG_MM_KERNEL_HEAP=y), this function provides the + * size of the unprotected, user-space heap. + * + * If a protected kernel-space heap is provided, the kernel heap must be + * allocated (and protected) by an analogous up_allocate_kheap(). + * + * The following memory map is assumed for the flat build: + * + * .data region. Size determined at link time. + * .bss region Size determined at link time. + * IDLE thread stack. Size determined by CONFIG_IDLETHREAD_STACKSIZE. + * Heap. Extends to the end of SRAM. + * + * The following memory map is assumed for the kernel build: + * + * Kernel .data region. Size determined at link time. + * Kernel .bss region Size determined at link time. + * Kernel IDLE thread stack. Size determined by CONFIG_IDLETHREAD_STACKSIZE. + * Padding for alignment + * User .data region. Size determined at link time. + * User .bss region Size determined at link time. + * Kernel heap. Size determined by CONFIG_MM_KERNEL_HEAPSIZE. + * User heap. Extends to the end of SRAM. + * + ****************************************************************************/ + +void up_allocate_heap(FAR void **heap_start, size_t *heap_size) +{ +#if defined(CONFIG_BUILD_PROTECTED) && defined(CONFIG_MM_KERNEL_HEAP) + /* Get the unaligned size and position of the user-space heap. + * This heap begins after the user-space .bss section at an offset + * of CONFIG_MM_KERNEL_HEAPSIZE (subject to alignment). + */ + + uintptr_t ubase = (uintptr_t)USERSPACE->us_bssend + CONFIG_MM_KERNEL_HEAPSIZE; + size_t usize = CONFIG_RAM_END - ubase; + int log2; + + DEBUGASSERT(ubase < (uintptr_t)CONFIG_RAM_END); + + /* Adjust that size to account for MPU alignment requirements. + * NOTE that there is an implicit assumption that the CONFIG_RAM_END + * is aligned to the MPU requirement. + */ + + log2 = (int)mpu_log2regionfloor(usize); + DEBUGASSERT((CONFIG_RAM_END & ((1 << log2) - 1)) == 0); + + usize = (1 << log2); + ubase = CONFIG_RAM_END - usize; + + /* Return the user-space heap settings */ + + board_autoled_on(LED_HEAPALLOCATE); + *heap_start = (FAR void *)ubase; + *heap_size = usize; + + /* Allow user-mode access to the user heap memory */ + + xmc4_mpu_uheap((uintptr_t)ubase, usize); +#else + + /* Return the heap settings */ + + board_autoled_on(LED_HEAPALLOCATE); + *heap_start = (FAR void *)g_idle_topstack; + *heap_size = CONFIG_RAM_END - g_idle_topstack; +#endif +} + +/**************************************************************************** + * Name: up_allocate_kheap + * + * Description: + * For the kernel build (CONFIG_BUILD_PROTECTED=y) with both kernel- and + * user-space heaps (CONFIG_MM_KERNEL_HEAP=y), this function allocates + * (and protects) the kernel-space heap. + * + ****************************************************************************/ + +#if defined(CONFIG_BUILD_PROTECTED) && defined(CONFIG_MM_KERNEL_HEAP) +void up_allocate_kheap(FAR void **heap_start, size_t *heap_size) +{ + /* Get the unaligned size and position of the user-space heap. + * This heap begins after the user-space .bss section at an offset + * of CONFIG_MM_KERNEL_HEAPSIZE (subject to alignment). + */ + + uintptr_t ubase = (uintptr_t)USERSPACE->us_bssend + CONFIG_MM_KERNEL_HEAPSIZE; + size_t usize = CONFIG_RAM_END - ubase; + int log2; + + DEBUGASSERT(ubase < (uintptr_t)CONFIG_RAM_END); + + /* Adjust that size to account for MPU alignment requirements. + * NOTE that there is an implicit assumption that the CONFIG_RAM_END + * is aligned to the MPU requirement. + */ + + log2 = (int)mpu_log2regionfloor(usize); + DEBUGASSERT((CONFIG_RAM_END & ((1 << log2) - 1)) == 0); + + usize = (1 << log2); + ubase = CONFIG_RAM_END - usize; + + /* Return the kernel heap settings (i.e., the part of the heap region + * that was not dedicated to the user heap). + */ + + *heap_start = (FAR void *)USERSPACE->us_bssend; + *heap_size = ubase - (uintptr_t)USERSPACE->us_bssend; +} +#endif diff --git a/arch/arm/src/xmc4/xmc4_clockconfig.c b/arch/arm/src/xmc4/xmc4_clockconfig.c new file mode 100644 index 0000000000..67efe53651 --- /dev/null +++ b/arch/arm/src/xmc4/xmc4_clockconfig.c @@ -0,0 +1,74 @@ +/**************************************************************************** + * arch/arm/src/xmc4/xmc4_clock_config.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Authors: 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include "up_arch.h" + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: xmc4_clock_config + * + * Description: + * Called to initialize the XMC4xxx chip. This does whatever setup is + * needed to put the MCU in a usable state. This includes the + * initialization of clocking using the settings in board.h. + * + ****************************************************************************/ + +void xmc4_clock_config(void) +{ +} diff --git a/arch/arm/src/xmc4/xmc4_clrpend.c b/arch/arm/src/xmc4/xmc4_clrpend.c new file mode 100644 index 0000000000..2eab7d6ffa --- /dev/null +++ b/arch/arm/src/xmc4/xmc4_clrpend.c @@ -0,0 +1,102 @@ +/**************************************************************************** + * arch/arm/src/xmc4/xmc4_clrpend.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include "nvic.h" +#include "up_arch.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: xmc4_clrpend + * + * Description: + * Clear a pending interrupt at the NVIC. This does not seem to be required + * for most interrupts. Don't know why... + * + * I keep it in a separate file so that it will not increase the footprint + * on Kinetis platforms that do not need this function. + * + ****************************************************************************/ + +void xmc4_clrpend(int irq) +{ + /* Check for external interrupt */ + + if (irq >= XMC4_IRQ_FIRST) + { + if (irq < (XMC4_IRQ_FIRST+32)) + { + putreg32(1 << (irq - XMC4_IRQ_FIRST), NVIC_IRQ0_31_CLRPEND); + } + else if (irq < (XMC4_IRQ_FIRST+64)) + { + putreg32(1 << (irq - XMC4_IRQ_FIRST - 32), NVIC_IRQ32_63_CLRPEND); + } + else if (irq < (XMC4_IRQ_FIRST+96)) + { + putreg32(1 << (irq - XMC4_IRQ_FIRST - 64), NVIC_IRQ64_95_CLRPEND); + } + else if (irq < NR_IRQS) + { + putreg32(1 << (irq - XMC4_IRQ_FIRST - 96), NVIC_IRQ96_127_CLRPEND); + } + } +} diff --git a/arch/arm/src/xmc4/xmc4_config.h b/arch/arm/src/xmc4/xmc4_config.h new file mode 100644 index 0000000000..e81932569e --- /dev/null +++ b/arch/arm/src/xmc4/xmc4_config.h @@ -0,0 +1,198 @@ +/************************************************************************************ + * arch/arm/src/xmc4/xmc4_config.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_XMC4_XMC4_CONFIG_H +#define __ARCH_ARM_SRC_XMC4_XMC4_CONFIG_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include + +#include "chip.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Configuration *********************************************************************/ +/* Make sure that no unsupported UARTs are enabled */ + +#ifndef CONFIG_XMC4_USIC0 +# undef CONFIG_XMC4_USIC0_ISUART +#endif +#ifndef CONFIG_XMC4_USIC1 +# undef CONFIG_XMC4_USIC1_ISUART +#endif +#ifndef CONFIG_XMC4_USIC2 +# undef CONFIG_XMC4_USIC2_ISUART +#endif +#ifndef CONFIG_XMC4_USIC3 +# undef CONFIG_XMC4_USIC3_ISUART +#endif +#ifndef CONFIG_XMC4_USIC4 +# undef CONFIG_XMC4_USIC4_ISUART +#endif +#ifndef CONFIG_XMC4_USIC5 +# undef CONFIG_XMC4_USIC5_ISUART +#endif + +/* Are any UARTs enabled? */ + +#undef HAVE_UART_DEVICE +#if defined(CONFIG_XMC4_USIC0_ISUART) || defined(CONFIG_XMC4_USIC1_ISUART) || \ + defined(CONFIG_XMC4_USIC2_ISUART) || defined(CONFIG_XMC4_USIC3_ISUART) || \ + defined(CONFIG_XMC4_USIC3_ISUART) || defined(CONFIG_XMC4_USIC4_ISUART) +# define HAVE_UART_DEVICE 1 +#endif + +/* Is there a serial console? There should be at most one defined. It could be on + * any UARTn, n=0,1,2,3,4,5 + */ + +#undef HAVE_UART_CONSOLE + +#if defined(CONFIG_CONSOLE_SYSLOG) +# undef CONFIG_UART0_SERIAL_CONSOLE +# undef CONFIG_UART1_SERIAL_CONSOLE +# undef CONFIG_UART2_SERIAL_CONSOLE +# undef CONFIG_UART3_SERIAL_CONSOLE +# undef CONFIG_UART4_SERIAL_CONSOLE +# undef CONFIG_UART5_SERIAL_CONSOLE +#else +# if defined(CONFIG_UART0_SERIAL_CONSOLE) && defined(CONFIG_XMC4_USIC0_ISUART) +# undef CONFIG_UART1_SERIAL_CONSOLE +# undef CONFIG_UART2_SERIAL_CONSOLE +# undef CONFIG_UART3_SERIAL_CONSOLE +# undef CONFIG_UART4_SERIAL_CONSOLE +# undef CONFIG_UART5_SERIAL_CONSOLE +# define HAVE_UART_CONSOLE 1 +# elif defined(CONFIG_UART1_SERIAL_CONSOLE) && defined(CONFIG_XMC4_USIC1_ISUART) +# undef CONFIG_UART0_SERIAL_CONSOLE +# undef CONFIG_UART2_SERIAL_CONSOLE +# undef CONFIG_UART3_SERIAL_CONSOLE +# undef CONFIG_UART4_SERIAL_CONSOLE +# undef CONFIG_UART5_SERIAL_CONSOLE +# define HAVE_UART_CONSOLE 1 +# elif defined(CONFIG_UART2_SERIAL_CONSOLE) && defined(CONFIG_XMC4_USIC2_ISUART) +# undef CONFIG_UART0_SERIAL_CONSOLE +# undef CONFIG_UART1_SERIAL_CONSOLE +# undef CONFIG_UART3_SERIAL_CONSOLE +# undef CONFIG_UART4_SERIAL_CONSOLE +# undef CONFIG_UART5_SERIAL_CONSOLE +# define HAVE_UART_CONSOLE 1 +# elif defined(CONFIG_UART3_SERIAL_CONSOLE) && defined(CONFIG_XMC4_USIC3_ISUART) +# undef CONFIG_UART0_SERIAL_CONSOLE +# undef CONFIG_UART1_SERIAL_CONSOLE +# undef CONFIG_UART2_SERIAL_CONSOLE +# undef CONFIG_UART4_SERIAL_CONSOLE +# undef CONFIG_UART5_SERIAL_CONSOLE +# define HAVE_UART_CONSOLE 1 +# elif defined(CONFIG_UART4_SERIAL_CONSOLE) && defined(CONFIG_XMC4_USIC4_ISUART) +# undef CONFIG_UART0_SERIAL_CONSOLE +# undef CONFIG_UART1_SERIAL_CONSOLE +# undef CONFIG_UART2_SERIAL_CONSOLE +# undef CONFIG_UART3_SERIAL_CONSOLE +# undef CONFIG_UART5_SERIAL_CONSOLE +# define HAVE_UART_CONSOLE 1 +# elif defined(CONFIG_UART5_SERIAL_CONSOLE) && defined(CONFIG_XMC4_USIC5_ISUART) +# undef CONFIG_UART0_SERIAL_CONSOLE +# undef CONFIG_UART1_SERIAL_CONSOLE +# undef CONFIG_UART2_SERIAL_CONSOLE +# undef CONFIG_UART3_SERIAL_CONSOLE +# undef CONFIG_UART4_SERIAL_CONSOLE +# define HAVE_UART_CONSOLE 1 +# else +# ifdef CONFIG_DEV_CONSOLE +# warning "No valid CONFIG_[LP]UART[n]_SERIAL_CONSOLE Setting" +# endif +# undef CONFIG_UART0_SERIAL_CONSOLE +# undef CONFIG_UART1_SERIAL_CONSOLE +# undef CONFIG_UART2_SERIAL_CONSOLE +# undef CONFIG_UART3_SERIAL_CONSOLE +# undef CONFIG_UART4_SERIAL_CONSOLE +# undef CONFIG_UART5_SERIAL_CONSOLE +# endif +#endif + +/* Check UART flow control (Not yet supported) */ + +# undef CONFIG_UART0_FLOWCONTROL +# undef CONFIG_UART1_FLOWCONTROL +# undef CONFIG_UART2_FLOWCONTROL +# undef CONFIG_UART3_FLOWCONTROL +# undef CONFIG_UART4_FLOWCONTROL +# undef CONFIG_UART5_FLOWCONTROL + +/* UART Default Interrupt Priorities */ + +#ifndef CONFIG_XMC4_UART0PRIO +# define CONFIG_XMC4_UART0PRIO NVIC_SYSH_PRIORITY_DEFAULT +#endif +#ifndef CONFIG_XMC4_UART1PRIO +# define CONFIG_XMC4_UART1PRIO NVIC_SYSH_PRIORITY_DEFAULT +#endif +#ifndef CONFIG_XMC4_UART2PRIO +# define CONFIG_XMC4_UART2PRIO NVIC_SYSH_PRIORITY_DEFAULT +#endif +#ifndef CONFIG_XMC4_UART3PRIO +# define CONFIG_XMC4_UART3PRIO NVIC_SYSH_PRIORITY_DEFAULT +#endif +#ifndef CONFIG_XMC4_UART4PRIO +# define CONFIG_XMC4_UART4PRIO NVIC_SYSH_PRIORITY_DEFAULT +#endif +#ifndef CONFIG_XMC4_UART5PRIO +# define CONFIG_XMC4_UART5PRIO NVIC_SYSH_PRIORITY_DEFAULT +#endif + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Inline Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_XMC4_XMC4_CONFIG_H */ diff --git a/arch/arm/src/xmc4/xmc4_dma.c b/arch/arm/src/xmc4/xmc4_dma.c new file mode 100644 index 0000000000..e69de29bb2 diff --git a/arch/arm/src/xmc4/xmc4_dma.h b/arch/arm/src/xmc4/xmc4_dma.h new file mode 100644 index 0000000000..8f2edba432 --- /dev/null +++ b/arch/arm/src/xmc4/xmc4_dma.h @@ -0,0 +1,218 @@ +/**************************************************************************** + * arch/arm/src/xmc4/xmc4_dma.h + * + * 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. + * + ****************************************************************************/ + +#ifndef __ARCH_ARM_SRC_XMC4_XMC4_DMA_H +#define __ARCH_ARM_SRC_XMC4_XMC4_DMA_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include "chip/xmc4_dma.h" + +/**************************************************************************** + * Pre-processor Declarations + ****************************************************************************/ + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +typedef FAR void *DMA_HANDLE; +typedef void (*dma_callback_t)(DMA_HANDLE handle, void *arg, int result); + +/* The following is used for sampling DMA registers when CONFIG DEBUG_DMA is selected */ + +#ifdef CONFIG_DEBUG_DMA +struct xmc4_dmaglobalregs_s +{ +#warning "Missing logic" + /* Global Registers */ +}; + +struct xmc4_dmachanregs_s +{ +#warning "Missing logic" + /* Channel Registers */ +}; + +struct xmc4_dmaregs_s +{ + /* Global Registers */ + + struct xmc4_dmaglobalregs_s gbl; + + /* Channel Registers */ + + struct xmc4_dmachanregs_s ch; +}; +#endif + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/**************************************************************************** + * Name: xmc4_dmainitialize + * + * Description: + * Initialize the GPDMA subsystem. + * + * Returned Value: + * None + * + ****************************************************************************/ + +void xmc4_dmainitilaize(void); + +/**************************************************************************** + * Name: xmc4_dmachannel + * + * Description: + * Allocate a DMA channel. This function sets aside a DMA channel and + * gives the caller exclusive access to the DMA channel. + * + * Returned Value: + * One success, this function returns a non-NULL, void* DMA channel + * handle. NULL is returned on any failure. This function can fail only + * if no DMA channel is available. + * + ****************************************************************************/ + +DMA_HANDLE xmc4_dmachannel(void); + +/**************************************************************************** + * Name: xmc4_dmafree + * + * Description: + * Release a DMA channel. NOTE: The 'handle' used in this argument must + * NEVER be used again until xmc4_dmachannel() is called again to re-gain + * a valid handle. + * + * Returned Value: + * None + * + ****************************************************************************/ + +void xmc4_dmafree(DMA_HANDLE handle); + +/**************************************************************************** + * Name: xmc4_dmasetup + * + * Description: + * Configure DMA for one transfer. + * + ****************************************************************************/ + +int xmc4_dmarxsetup(DMA_HANDLE handle, uint32_t control, uint32_t config, + uint32_t srcaddr, uint32_t destaddr, size_t nbytes); + +/**************************************************************************** + * Name: xmc4_dmastart + * + * Description: + * Start the DMA transfer + * + ****************************************************************************/ + +int xmc4_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg); + +/**************************************************************************** + * Name: xmc4_dmastop + * + * Description: + * Cancel the DMA. After xmc4_dmastop() is called, the DMA channel is + * reset and xmc4_dmasetup() must be called before xmc4_dmastart() can be + * called again + * + ****************************************************************************/ + +void xmc4_dmastop(DMA_HANDLE handle); + +/**************************************************************************** + * Name: xmc4_dmasample + * + * Description: + * Sample DMA register contents + * + ****************************************************************************/ + +#ifdef CONFIG_DEBUG_DMA +void xmc4_dmasample(DMA_HANDLE handle, struct xmc4_dmaregs_s *regs); +#else +# define xmc4_dmasample(handle,regs) +#endif + +/**************************************************************************** + * Name: xmc4_dmadump + * + * Description: + * Dump previously sampled DMA register contents + * + ****************************************************************************/ + +#ifdef CONFIG_DEBUG_DMA +void xmc4_dmadump(DMA_HANDLE handle, const struct xmc4_dmaregs_s *regs, + const char *msg); +#else +# define xmc4_dmadump(handle,regs,msg) +#endif + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __ARCH_ARM_SRC_XMC4_XMC4_DMA_H */ diff --git a/arch/arm/src/xmc4/xmc4_gpio.c b/arch/arm/src/xmc4/xmc4_gpio.c new file mode 100644 index 0000000000..e69de29bb2 diff --git a/arch/arm/src/xmc4/xmc4_gpio.h b/arch/arm/src/xmc4/xmc4_gpio.h new file mode 100644 index 0000000000..e69de29bb2 diff --git a/arch/arm/src/xmc4/xmc4_i2c.c b/arch/arm/src/xmc4/xmc4_i2c.c new file mode 100644 index 0000000000..e69de29bb2 diff --git a/arch/arm/src/xmc4/xmc4_i2c.h b/arch/arm/src/xmc4/xmc4_i2c.h new file mode 100644 index 0000000000..f4a167b713 --- /dev/null +++ b/arch/arm/src/xmc4/xmc4_i2c.h @@ -0,0 +1,87 @@ +/**************************************************************************** + * arch/arm/src/xmc4/xmc4_i2c.h + * + * 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. + * + ****************************************************************************/ + +#ifndef __ARCH_ARM_SRC_XMC4_XMC4_I2C_H +#define __ARCH_ARM_SRC_XMC4_XMC4_I2C_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include "chip/xmc4_i2c.h" + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Name: xmc4_i2cbus_initialize + * + * Description: + * Initialize the selected I2C port. And return a unique instance of struct + * struct i2c_master_s. This function may be called to obtain multiple + * instances of the interface, each of which may be set up with a + * different frequency and slave address. + * + * Input Parameter: + * Port number (for hardware that has multiple I2C interfaces) + * + * Returned Value: + * Valid I2C device structure reference on succcess; a NULL on failure + * + ****************************************************************************/ + +FAR struct i2c_master_s *xmc4_i2cbus_initialize(int port); + +/**************************************************************************** + * Name: xmc4_i2cbus_uninitialize + * + * Description: + * De-initialize the selected I2C port, and power down the device. + * + * Input Parameter: + * Device structure as returned by the lpc43_i2cbus_initialize() + * + * Returned Value: + * OK on success, ERROR when internal reference count mismatch or dev + * points to invalid hardware device. + * + ****************************************************************************/ + +int xmc4_i2cbus_uninitialize(FAR struct i2c_master_s *dev); + +#endif /* __ARCH_ARM_SRC_XMC4_XMC4_I2C_H */ diff --git a/arch/arm/src/xmc4/xmc4_idle.c b/arch/arm/src/xmc4/xmc4_idle.c new file mode 100644 index 0000000000..411324311f --- /dev/null +++ b/arch/arm/src/xmc4/xmc4_idle.c @@ -0,0 +1,105 @@ +/**************************************************************************** + * arch/arm/src/xmc4/xmc4_idle.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include + +#include "up_internal.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Does the board support an IDLE LED to indicate that the board is in the + * IDLE state? + */ + +#if defined(CONFIG_ARCH_LEDS) && defined(LED_IDLE) +# define BEGIN_IDLE() board_autoled_on(LED_IDLE) +# define END_IDLE() board_autoled_off(LED_IDLE) +#else +# define BEGIN_IDLE() +# define END_IDLE() +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_idle + * + * Description: + * up_idle() is the logic that will be executed when their is no other + * ready-to-run task. This is processor idle time and will continue until + * some interrupt occurs to cause a context switch from the idle task. + * + * Processing in this state may be processor-specific. e.g., this is where + * power management operations might be performed. + * + ****************************************************************************/ + +void up_idle(void) +{ +#if defined(CONFIG_SUPPRESS_INTERRUPTS) || defined(CONFIG_SUPPRESS_TIMER_INTS) + /* If the system is idle and there are no timer interrupts, then process + * "fake" timer interrupts. Hopefully, something will wake up. + */ + + sched_process_timer(); +#else + + /* Sleep until an interrupt occurs to save power */ + + BEGIN_IDLE(); + asm("WFI"); + END_IDLE(); +#endif +} diff --git a/arch/arm/src/xmc4/xmc4_irq.c b/arch/arm/src/xmc4/xmc4_irq.c new file mode 100644 index 0000000000..17725b8c60 --- /dev/null +++ b/arch/arm/src/xmc4/xmc4_irq.c @@ -0,0 +1,588 @@ +/**************************************************************************** + * arch/arm/src/xmc4/xmc4_irq.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include +#include +#include + +#include "nvic.h" +#include "ram_vectors.h" +#include "up_arch.h" +#include "up_internal.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Get a 32-bit version of the default priority */ + +#define DEFPRIORITY32 \ + (NVIC_SYSH_PRIORITY_DEFAULT << 24 | \ + NVIC_SYSH_PRIORITY_DEFAULT << 16 | \ + NVIC_SYSH_PRIORITY_DEFAULT << 8 | \ + NVIC_SYSH_PRIORITY_DEFAULT) + +/* Given the address of a NVIC ENABLE register, this is the offset to + * the corresponding CLEAR ENABLE register. + */ + +#define NVIC_ENA_OFFSET (0) +#define NVIC_CLRENA_OFFSET (NVIC_IRQ0_31_CLEAR - NVIC_IRQ0_31_ENABLE) + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/* g_current_regs[] holds a references to the current interrupt level + * register storage structure. If is non-NULL only during interrupt + * processing. Access to g_current_regs[] must be through the macro + * CURRENT_REGS for portability. + */ + +volatile uint32_t *g_current_regs[1]; + +/* This is the address of the exception vector table (determined by the + * linker script). + */ + +extern uint32_t _vectors[]; + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: xmc4_dump_nvic + * + * Description: + * Dump some interesting NVIC registers + * + ****************************************************************************/ + +#if defined(CONFIG_DEBUG_IRQ_INFO) +static void xmc4_dump_nvic(const char *msg, int irq) +{ + irqstate_t flags; + + flags = enter_critical_section(); + + irqinfo("NVIC (%s, irq=%d):\n", msg, irq); + irqinfo(" INTCTRL: %08x VECTAB: %08x\n", + getreg32(NVIC_INTCTRL), getreg32(NVIC_VECTAB)); +#if 0 + irqinfo(" SYSH ENABLE MEMFAULT: %08x BUSFAULT: %08x USGFAULT: %08x SYSTICK: %08x\n", + getreg32(NVIC_SYSHCON_MEMFAULTENA), getreg32(NVIC_SYSHCON_BUSFAULTENA), + getreg32(NVIC_SYSHCON_USGFAULTENA), getreg32(NVIC_SYSTICK_CTRL_ENABLE)); +#endif + irqinfo(" IRQ ENABLE: %08x %08x %08x %08x\n", + getreg32(NVIC_IRQ0_31_ENABLE), getreg32(NVIC_IRQ32_63_ENABLE), + getreg32(NVIC_IRQ64_95_ENABLE), getreg32(NVIC_IRQ96_127_ENABLE)); + irqinfo(" SYSH_PRIO: %08x %08x %08x\n", + getreg32(NVIC_SYSH4_7_PRIORITY), getreg32(NVIC_SYSH8_11_PRIORITY), + getreg32(NVIC_SYSH12_15_PRIORITY)); + irqinfo(" IRQ PRIO: %08x %08x %08x %08x\n", + getreg32(NVIC_IRQ0_3_PRIORITY), getreg32(NVIC_IRQ4_7_PRIORITY), + getreg32(NVIC_IRQ8_11_PRIORITY), getreg32(NVIC_IRQ12_15_PRIORITY)); + irqinfo(" %08x %08x %08x %08x\n", + getreg32(NVIC_IRQ16_19_PRIORITY), getreg32(NVIC_IRQ20_23_PRIORITY), + getreg32(NVIC_IRQ24_27_PRIORITY), getreg32(NVIC_IRQ28_31_PRIORITY)); + irqinfo(" %08x %08x %08x %08x\n", + getreg32(NVIC_IRQ32_35_PRIORITY), getreg32(NVIC_IRQ36_39_PRIORITY), + getreg32(NVIC_IRQ40_43_PRIORITY), getreg32(NVIC_IRQ44_47_PRIORITY)); + irqinfo(" %08x %08x %08x %08x\n", + getreg32(NVIC_IRQ48_51_PRIORITY), getreg32(NVIC_IRQ52_55_PRIORITY), + getreg32(NVIC_IRQ56_59_PRIORITY), getreg32(NVIC_IRQ60_63_PRIORITY)); + irqinfo(" %08x %08x %08x %08x\n", + getreg32(NVIC_IRQ64_67_PRIORITY), getreg32(NVIC_IRQ68_71_PRIORITY), + getreg32(NVIC_IRQ72_75_PRIORITY), getreg32(NVIC_IRQ76_79_PRIORITY)); + irqinfo(" %08x %08x %08x %08x\n", + getreg32(NVIC_IRQ80_83_PRIORITY), getreg32(NVIC_IRQ84_87_PRIORITY), + getreg32(NVIC_IRQ88_91_PRIORITY), getreg32(NVIC_IRQ92_95_PRIORITY)); + irqinfo(" %08x %08x %08x %08x\n", + getreg32(NVIC_IRQ96_99_PRIORITY), getreg32(NVIC_IRQ100_103_PRIORITY), + getreg32(NVIC_IRQ104_107_PRIORITY), getreg32(NVIC_IRQ108_111_PRIORITY)); +#if NR_VECTORS > 111 + irqinfo(" %08x %08x\n", + getreg32(NVIC_IRQ112_115_PRIORITY), getreg32(NVIC_IRQ116_119_PRIORITY)); +#endif + + leave_critical_section(flags); +} +#else +# define xmc4_dump_nvic(msg, irq) +#endif + +/**************************************************************************** + * Name: xmc4_nmi, xmc4_busfault, xmc4_usagefault, xmc4_pendsv, + * xmc4_dbgmonitor, xmc4_pendsv, xmc4_reserved + * + * Description: + * Handlers for various execptions. None are handled and all are fatal + * error conditions. The only advantage these provided over the default + * unexpected interrupt handler is that they provide a diagnostic output. + * + ****************************************************************************/ + +#ifdef CONFIG_DEBUG_FEATURES +static int xmc4_nmi(int irq, FAR void *context, FAR void *arg) +{ + (void)up_irq_save(); + _err("PANIC!!! NMI received\n"); + PANIC(); + return 0; +} + +static int xmc4_busfault(int irq, FAR void *context, FAR void *arg) +{ + (void)up_irq_save(); + _err("PANIC!!! Bus fault recived\n"); + PANIC(); + return 0; +} + +static int xmc4_usagefault(int irq, FAR void *context, FAR void *arg) +{ + (void)up_irq_save(); + _err("PANIC!!! Usage fault received\n"); + PANIC(); + return 0; +} + +static int xmc4_pendsv(int irq, FAR void *context, FAR void *arg) +{ + (void)up_irq_save(); + _err("PANIC!!! PendSV received\n"); + PANIC(); + return 0; +} + +static int xmc4_dbgmonitor(int irq, FAR void *context, FAR void *arg) +{ + (void)up_irq_save(); + _err("PANIC!!! Debug Monitor received\n"); + PANIC(); + return 0; +} + +static int xmc4_reserved(int irq, FAR void *context, FAR void *arg) +{ + (void)up_irq_save(); + _err("PANIC!!! Reserved interrupt\n"); + PANIC(); + return 0; +} +#endif + +/**************************************************************************** + * Name: xmc4_prioritize_syscall + * + * Description: + * Set the priority of an exception. This function may be needed + * internally even if support for prioritized interrupts is not enabled. + * + ****************************************************************************/ + +#ifdef CONFIG_ARMV7M_USEBASEPRI +static inline void xmc4_prioritize_syscall(int priority) +{ + uint32_t regval; + + /* SVCALL is system handler 11 */ + + regval = getreg32(NVIC_SYSH8_11_PRIORITY); + regval &= ~NVIC_SYSH_PRIORITY_PR11_MASK; + regval |= (priority << NVIC_SYSH_PRIORITY_PR11_SHIFT); + putreg32(regval, NVIC_SYSH8_11_PRIORITY); +} +#endif + +/**************************************************************************** + * Name: xmc4_irqinfo + * + * Description: + * Given an IRQ number, provide the register and bit setting to enable or + * disable the irq. + * + ****************************************************************************/ + +static int xmc4_irqinfo(int irq, uintptr_t *regaddr, uint32_t *bit, + uintptr_t offset) +{ + DEBUGASSERT(irq >= XMC4_IRQ_NMI && irq < NR_IRQS); + + /* Check for external interrupt */ + + if (irq >= XMC4_IRQ_FIRST) + { + if (irq < (XMC4_IRQ_FIRST+32)) + { + *regaddr = (NVIC_IRQ0_31_ENABLE + offset); + *bit = 1 << (irq - XMC4_IRQ_FIRST); + } + else if (irq < (XMC4_IRQ_FIRST+64)) + { + *regaddr = (NVIC_IRQ32_63_ENABLE + offset); + *bit = 1 << (irq - XMC4_IRQ_FIRST - 32); + } + else if (irq < (XMC4_IRQ_FIRST+96)) + { + *regaddr = (NVIC_IRQ64_95_ENABLE + offset); + *bit = 1 << (irq - XMC4_IRQ_FIRST - 64); + } + else if (irq < NR_IRQS) + { + *regaddr = (NVIC_IRQ96_127_ENABLE + offset); + *bit = 1 << (irq - XMC4_IRQ_FIRST - 96); + } + else + { + return ERROR; /* Invalid irq */ + } + } + + /* Handle processor exceptions. Only a few can be disabled */ + + else + { + *regaddr = NVIC_SYSHCON; + if (irq == XMC4_IRQ_MEMFAULT) + { + *bit = NVIC_SYSHCON_MEMFAULTENA; + } + else if (irq == XMC4_IRQ_BUSFAULT) + { + *bit = NVIC_SYSHCON_BUSFAULTENA; + } + else if (irq == XMC4_IRQ_USAGEFAULT) + { + *bit = NVIC_SYSHCON_USGFAULTENA; + } + else if (irq == XMC4_IRQ_SYSTICK) + { + *regaddr = NVIC_SYSTICK_CTRL; + *bit = NVIC_SYSTICK_CTRL_ENABLE; + } + else + { + return ERROR; /* Invalid or unsupported exception */ + } + } + + return OK; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_irqinitialize + ****************************************************************************/ + +void up_irqinitialize(void) +{ + uintptr_t regaddr; + int nintlines; + int i; + + /* The NVIC ICTR register (bits 0-4) holds the number of of interrupt + * lines that the NVIC supports, defined in groups of 32. That is, + * the total number of interrupt lines is up to (32*(INTLINESNUM+1)). + * + * 0 -> 32 interrupt lines, 1 enable register, 8 priority registers + * 1 -> 64 " " " ", 2 enable registers, 16 priority registers + * 2 -> 96 " " " ", 3 enable regsiters, 24 priority registers + * ... + */ + + nintlines = (getreg32(NVIC_ICTR) & NVIC_ICTR_INTLINESNUM_MASK) + 1; + + /* Disable all interrupts. There are nintlines interrupt enable + * registers. + */ + + for (i = nintlines, regaddr = NVIC_IRQ0_31_ENABLE; + i > 0; + i--, regaddr += 4) + { + putreg32(0, regaddr); + } + + /* Make sure that we are using the correct vector table. The default + * vector address is 0x0000:0000 but if we are executing code that is + * positioned in SRAM or in external FLASH, then we may need to reset + * the interrupt vector so that it refers to the table in SRAM or in + * external FLASH. + */ + + putreg32((uint32_t)_vectors, NVIC_VECTAB); + +#ifdef CONFIG_ARCH_RAMVECTORS + /* If CONFIG_ARCH_RAMVECTORS is defined, then we are using a RAM-based + * vector table that requires special initialization. + */ + + up_ramvec_initialize(); +#endif + + /* Set all interrupts (and exceptions) to the default priority */ + + putreg32(DEFPRIORITY32, NVIC_SYSH4_7_PRIORITY); + putreg32(DEFPRIORITY32, NVIC_SYSH8_11_PRIORITY); + putreg32(DEFPRIORITY32, NVIC_SYSH12_15_PRIORITY); + + /* Now set all of the interrupt lines to the default priority. There are + * nintlines * 8 priority registers. + */ + + for (i = (nintlines << 3), regaddr = NVIC_IRQ0_3_PRIORITY; + i > 0; + i--, regaddr += 4) + { + putreg32(DEFPRIORITY32, regaddr); + } + + /* currents_regs is non-NULL only while processing an interrupt */ + + CURRENT_REGS = NULL; + + /* Attach the SVCall and Hard Fault exception handlers. The SVCall + * exception is used for performing context switches; The Hard Fault + * must also be caught because a SVCall may show up as a Hard Fault + * under certain conditions. + */ + + irq_attach(XMC4_IRQ_SVCALL, up_svcall, NULL); + irq_attach(XMC4_IRQ_HARDFAULT, up_hardfault, NULL); + + /* Set the priority of the SVCall interrupt */ + +#ifdef CONFIG_ARCH_IRQPRIO + /* up_prioritize_irq(XMC4_IRQ_PENDSV, NVIC_SYSH_PRIORITY_MIN); */ +#endif +#ifdef CONFIG_ARMV7M_USEBASEPRI + xmc4_prioritize_syscall(NVIC_SYSH_SVCALL_PRIORITY); +#endif + + /* If the MPU is enabled, then attach and enable the Memory Management + * Fault handler. + */ + +#ifdef CONFIG_ARM_MPU + irq_attach(XMC4_IRQ_MEMFAULT, up_memfault, NULL); + up_enable_irq(XMC4_IRQ_MEMFAULT); +#endif + + /* Attach all other processor exceptions (except reset and sys tick) */ + +#ifdef CONFIG_DEBUG_FEATURES + irq_attach(XMC4_IRQ_NMI, xmc4_nmi, NULL); +#ifndef CONFIG_ARM_MPU + irq_attach(XMC4_IRQ_MEMFAULT, up_memfault, NULL); +#endif + irq_attach(XMC4_IRQ_BUSFAULT, xmc4_busfault, NULL); + irq_attach(XMC4_IRQ_USAGEFAULT, xmc4_usagefault, NULL); + irq_attach(XMC4_IRQ_PENDSV, xmc4_pendsv, NULL); + irq_attach(XMC4_IRQ_DBGMONITOR, xmc4_dbgmonitor, NULL); + irq_attach(XMC4_IRQ_RESERVED, xmc4_reserved, NULL); +#endif + + xmc4_dump_nvic("initial", NR_IRQS); + + /* Initialize logic to support a second level of interrupt decoding for + * configured pin interrupts. + */ + +#ifdef CONFIG_XMC4_GPIOIRQ + xmc4_gpioirq_initialize(); +#endif + + /* And finally, enable interrupts */ + +#ifndef CONFIG_SUPPRESS_INTERRUPTS + up_irq_enable(); +#endif +} + +/**************************************************************************** + * Name: up_disable_irq + * + * Description: + * Disable the IRQ specified by 'irq' + * + ****************************************************************************/ + +void up_disable_irq(int irq) +{ + uintptr_t regaddr; + uint32_t regval; + uint32_t bit; + + if (xmc4_irqinfo(irq, ®addr, &bit, NVIC_CLRENA_OFFSET) == 0) + { + /* Modify the appropriate bit in the register to disable the interrupt. + * For normal interrupts, we need to set the bit in the associated + * Interrupt Clear Enable register. For other exceptions, we need to + * clear the bit in the System Handler Control and State Register. + */ + + if (irq >= XMC4_IRQ_FIRST) + { + putreg32(bit, regaddr); + } + else + { + regval = getreg32(regaddr); + regval &= ~bit; + putreg32(regval, regaddr); + } + } + + xmc4_dump_nvic("disable", irq); +} + +/**************************************************************************** + * Name: up_enable_irq + * + * Description: + * Enable the IRQ specified by 'irq' + * + ****************************************************************************/ + +void up_enable_irq(int irq) +{ + uintptr_t regaddr; + uint32_t regval; + uint32_t bit; + + if (xmc4_irqinfo(irq, ®addr, &bit, NVIC_ENA_OFFSET) == 0) + { + /* Modify the appropriate bit in the register to enable the interrupt. + * For normal interrupts, we need to set the bit in the associated + * Interrupt Set Enable register. For other exceptions, we need to + * set the bit in the System Handler Control and State Register. + */ + + if (irq >= XMC4_IRQ_FIRST) + { + putreg32(bit, regaddr); + } + else + { + regval = getreg32(regaddr); + regval |= bit; + putreg32(regval, regaddr); + } + } + + xmc4_dump_nvic("enable", irq); +} + +/**************************************************************************** + * Name: up_ack_irq + * + * Description: + * Acknowledge the IRQ + * + ****************************************************************************/ + +void up_ack_irq(int irq) +{ +#if 0 /* Does not appear to be necessary in most cases */ + xmc4_clrpend(irq); +#endif +} + +/**************************************************************************** + * Name: up_prioritize_irq + * + * Description: + * Set the priority of an IRQ. + * + * Since this API is not supported on all architectures, it should be + * avoided in common implementations where possible. + * + ****************************************************************************/ + +#ifdef CONFIG_ARCH_IRQPRIO +int up_prioritize_irq(int irq, int priority) +{ + uint32_t regaddr; + uint32_t regval; + int shift; + + DEBUGASSERT(irq >= XMC4_IRQ_MEMFAULT && irq < NR_IRQS && + (unsigned)priority <= NVIC_SYSH_PRIORITY_MIN); + + if (irq < XMC4_IRQ_FIRST) + { + /* NVIC_SYSH_PRIORITY() maps {0..15} to one of three priority + * registers (0-3 are invalid) + */ + + regaddr = NVIC_SYSH_PRIORITY(irq); + irq -= 4; + } + else + { + /* NVIC_IRQ_PRIORITY() maps {0..} to one of many priority registers */ + + irq -= XMC4_IRQ_FIRST; + regaddr = NVIC_IRQ_PRIORITY(irq); + } + + regval = getreg32(regaddr); + shift = ((irq & 3) << 3); + regval &= ~(0xff << shift); + regval |= (priority << shift); + putreg32(regval, regaddr); + + xmc4_dump_nvic("prioritize", irq); + return OK; +} +#endif diff --git a/arch/arm/src/xmc4/xmc4_lowputc.c b/arch/arm/src/xmc4/xmc4_lowputc.c new file mode 100644 index 0000000000..8fe2f4094b --- /dev/null +++ b/arch/arm/src/xmc4/xmc4_lowputc.c @@ -0,0 +1,235 @@ +/**************************************************************************** + * arch/arm/src/xmc4/xmc4_lowputc.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include +#include + +#include "up_internal.h" +#include "up_arch.h" + +#include "xmc4_config.h" +#include "chip/xmc4_uart.h" +#include "chip/xmc4_pinmux.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Select UART parameters for the selected console */ + +#if defined(HAVE_UART_CONSOLE) +# if defined(CONFIG_UART0_SERIAL_CONSOLE) +# define CONSOLE_BASE XMC4_UART0_BASE +# define CONSOLE_FREQ BOARD_CORECLK_FREQ +# define CONSOLE_BAUD CONFIG_UART0_BAUD +# define CONSOLE_BITS CONFIG_UART0_BITS +# define CONSOLE_2STOP CONFIG_UART0_2STOP +# define CONSOLE_PARITY CONFIG_UART0_PARITY +# elif defined(CONFIG_UART1_SERIAL_CONSOLE) +# define CONSOLE_BASE XMC4_UART1_BASE +# define CONSOLE_FREQ BOARD_CORECLK_FREQ +# define CONSOLE_BAUD CONFIG_UART1_BAUD +# define CONSOLE_BITS CONFIG_UART1_BITS +# define CONSOLE_2STOP CONFIG_UART1_2STOP +# define CONSOLE_PARITY CONFIG_UART1_PARITY +# elif defined(CONFIG_UART2_SERIAL_CONSOLE) +# define CONSOLE_BASE XMC4_UART2_BASE +# define CONSOLE_FREQ BOARD_BUS_FREQ +# define CONSOLE_BAUD CONFIG_UART2_BAUD +# define CONSOLE_BITS CONFIG_UART2_BITS +# define CONSOLE_2STOP CONFIG_UART2_2STOP +# define CONSOLE_PARITY CONFIG_UART2_PARITY +# elif defined(CONFIG_UART3_SERIAL_CONSOLE) +# define CONSOLE_BASE XMC4_UART3_BASE +# define CONSOLE_FREQ BOARD_BUS_FREQ +# define CONSOLE_BAUD CONFIG_UART3_BAUD +# define CONSOLE_BITS CONFIG_UART3_BITS +# define CONSOLE_2STOP CONFIG_UART3_2STOP +# define CONSOLE_PARITY CONFIG_UART3_PARITY +# elif defined(CONFIG_UART4_SERIAL_CONSOLE) +# define CONSOLE_BASE XMC4_UART4_BASE +# define CONSOLE_FREQ BOARD_BUS_FREQ +# define CONSOLE_BAUD CONFIG_UART4_BAUD +# define CONSOLE_BITS CONFIG_UART4_BITS +# define CONSOLE_2STOP CONFIG_UART4_2STOP +# define CONSOLE_PARITY CONFIG_UART4_PARITY +# elif defined(CONFIG_UART5_SERIAL_CONSOLE) +# define CONSOLE_BASE XMC4_UART5_BASE +# define CONSOLE_FREQ BOARD_BUS_FREQ +# define CONSOLE_BAUD CONFIG_UART5_BAUD +# define CONSOLE_BITS CONFIG_UART5_BITS +# define CONSOLE_2STOP CONFIG_UART5_2STOP +# define CONSOLE_PARITY CONFIG_UART5_PARITY +# elif defined(HAVE_UART_CONSOLE) +# error "No CONFIG_UARTn_SERIAL_CONSOLE Setting" +# endif +#endif /* HAVE_UART_CONSOLE */ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_lowputc + * + * Description: + * Output one byte on the serial console + * + ****************************************************************************/ + +void up_lowputc(char ch) +{ +#ifdef HAVE_UART_CONSOLE + /* Wait until the transmit data register is "empty" (TDRE). This state + * depends on the TX watermark setting and may not mean that the transmit + * buffer is truly empty. It just means that we can now add another + * character to the transmit buffer without exceeding the watermark. + * + * NOTE: UART0 has an 8-byte deep FIFO; the other UARTs have no FIFOs + * (1-deep). There appears to be no way to know when the FIFO is not + * full (other than reading the FIFO length and comparing the FIFO count). + * Hence, the FIFOs are not used in this implementation and, as a result + * TDRE indeed mean that the single output buffer is available. + * + * Performance on UART0 could be improved by enabling the FIFO and by + * redesigning all of the FIFO status logic. + */ +#warning Missing logic + + /* Then write the character to the UART data register */ + +#warning Missing logic +} + +/**************************************************************************** + * Name: xmc4_lowsetup + * + * Description: + * This performs basic initialization of the UART used for the serial + * console. Its purpose is to get the console output available as soon + * as possible. + * + ****************************************************************************/ + +void xmc4_lowsetup(void) +{ + uint32_t regval; + + /* Enable peripheral clocking for all enabled UARTs. */ +#wanring Missing logic + + /* Configure UART pins for the all enabled UARTs */ + + /* Configure the console (only) now. Other UARTs will be configured + * when the serial driver is opened. + */ + + xmc4_uart_configure(CONSOLE_BASE, CONSOLE_BAUD, CONSOLE_FREQ, \ + CONSOLE_PARITY, CONSOLE_BITS, CONSOLE_2STOP); +#endif /* HAVE_UART_DEVICE */ +} + +/**************************************************************************** + * Name: xmc4_uart_reset + * + * Description: + * Reset a UART. + * + ****************************************************************************/ + +#ifdef HAVE_UART_DEVICE +void xmc4_uart_reset(uintptr_t uart_base) +{ + uint8_t regval; + + /* Just disable the transmitter and receiver */ +#warning Missing logic +} +#endif + +/**************************************************************************** + * Name: xmc4_uart_configure + * + * Description: + * Configure a UART as a RS-232 UART. + * + ****************************************************************************/ + +#ifdef HAVE_UART_DEVICE +void xmc4_uart_configure(uintptr_t uart_base, uint32_t baud, + uint32_t clock, unsigned int parity, + unsigned int nbits, unsigned int stop2) +{ + /* Disable the transmitter and receiver throughout the reconfiguration */ +#warning Missing logic + + /* Configure number of bits, stop bits and parity */ +#warning Missing logic + + /* Check for odd parity */ +#warning Missing logic + + /* Check for even parity */ +#warning Missing logic + + /* Check for 9-bit operation */ +#warning Missing logic + + /* Calculate baud settings (truncating) */ +#warning Missing logic + + /* Configure FIFOs */ +#warning Missing logic + + /* Enable RX and TX FIFOs */ +#warning Missing logic + + /* Now we can (re-)enable the transmitter and receiver */ +#warning Missing logic +} +#endif + diff --git a/arch/arm/src/xmc4/xmc4_mpuinit.c b/arch/arm/src/xmc4/xmc4_mpuinit.c new file mode 100644 index 0000000000..9cd22451be --- /dev/null +++ b/arch/arm/src/xmc4/xmc4_mpuinit.c @@ -0,0 +1,124 @@ +/**************************************************************************** + * arch/arm/src/xmc4/xmc4_mpuinit.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include + +#include "mpu.h" +#include "xmc4_mpuinit.h" + +#if defined(CONFIG_BUILD_PROTECTED) && defined(CONFIG_ARM_MPU) + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#ifndef MAX +# define MAX(a,b) a > b ? a : b +#endif + +#ifndef MIN +# define MIN(a,b) a < b ? a : b +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: xmc4_mpuinitialize + * + * Description: + * Configure the MPU to permit user-space access to only restricted SAM3U + * resources. + * + ****************************************************************************/ + +void xmc4_mpuinitialize(void) +{ + uintptr_t datastart = MIN(USERSPACE->us_datastart, USERSPACE->us_bssstart); + uintptr_t dataend = MAX(USERSPACE->us_dataend, USERSPACE->us_bssend); + + DEBUGASSERT(USERSPACE->us_textend >= USERSPACE->us_textstart && + dataend >= datastart); + + /* Show MPU information */ + + mpu_showtype(); + + /* Configure user flash and SRAM space */ + + mpu_user_flash(USERSPACE->us_textstart, + USERSPACE->us_textend - USERSPACE->us_textstart); + + mpu_user_intsram(datastart, dataend - datastart); + + /* Then enable the MPU */ + + mpu_control(true, false, true); +} + +/**************************************************************************** + * Name: xmc4_mpu_uheap + * + * Description: + * Map the user-heap region. + * + * This logic may need an extension to handle external SDRAM). + * + ****************************************************************************/ + +void xmc4_mpu_uheap(uintptr_t start, size_t size) +{ + mpu_user_intsram(start, size); +} + +#endif /* CONFIG_BUILD_PROTECTED && CONFIG_ARM_MPU */ + diff --git a/arch/arm/src/xmc4/xmc4_mpuinit.h b/arch/arm/src/xmc4/xmc4_mpuinit.h new file mode 100644 index 0000000000..f318424bad --- /dev/null +++ b/arch/arm/src/xmc4/xmc4_mpuinit.h @@ -0,0 +1,78 @@ +/************************************************************************************ + * arch/arm/src/xmc4/xmc4_mpuinit.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_XMC4_XMC4_MPUINIT_H +#define __ARCH_ARM_SRC_XMC4_XMC4_MPUINIT_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/**************************************************************************** + * Name: xmc4_mpuinitialize + * + * Description: + * Configure the MPU to permit user-space access to only unrestricted MCU + * resources. + * + ****************************************************************************/ + +#ifdef CONFIG_BUILD_PROTECTED +void xmc4_mpuinitialize(void); +#else +# define xmc4_mpuinitialize() +#endif + +/**************************************************************************** + * Name: xmc4_mpu_uheap + * + * Description: + * Map the user heap region. + * + ****************************************************************************/ + +#ifdef CONFIG_BUILD_PROTECTED +void xmc4_mpu_uheap(uintptr_t start, size_t size); +#else +# define xmc4_mpu_uheap(start,size) +#endif + +#endif /* __ARCH_ARM_SRC_XMC4_XMC4_MPUINIT_H */ diff --git a/arch/arm/src/xmc4/xmc4_pwm.c b/arch/arm/src/xmc4/xmc4_pwm.c new file mode 100644 index 0000000000..e69de29bb2 diff --git a/arch/arm/src/xmc4/xmc4_pwm.h b/arch/arm/src/xmc4/xmc4_pwm.h new file mode 100644 index 0000000000..4de5b5f56a --- /dev/null +++ b/arch/arm/src/xmc4/xmc4_pwm.h @@ -0,0 +1,100 @@ +/************************************************************************************ + * arch/arm/src/xmc4/xmc4_pwm.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_XMC4_XMC4_PWM_H +#define __ARCH_ARM_SRC_XMC4_XMC4_PWM_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include "chip.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Configuration ********************************************************************/ + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: xmc4_pwm_initialize + * + * Description: + * Initialize one timer for use with the upper_level PWM driver. + * + * Input Parameters: + * timer - A number identifying the timer use. + * + * Returned Value: + * On success, a pointer to the kinetis lower half PWM driver is returned. + * NULL is returned on any failure. + * + ************************************************************************************/ + +FAR struct pwm_lowerhalf_s *xmc4_pwm_initialize(int timer); + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* CONFIG_XMC4_FTMx_PWM */ +#endif /* __ARCH_ARM_SRC_XMC4_XMC4_PWM_H */ diff --git a/arch/arm/src/xmc4/xmc4_serial.c b/arch/arm/src/xmc4/xmc4_serial.c new file mode 100644 index 0000000000..b90f1c19ff --- /dev/null +++ b/arch/arm/src/xmc4/xmc4_serial.c @@ -0,0 +1,1146 @@ +/**************************************************************************** + * arch/arm/src/xmc4/xmc4_serial.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include + +#include "up_arch.h" +#include "up_internal.h" + +#include "xmc4_config.h" +#include "chip.h" +#include "chip/xmc4_uart.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ +/* Some sanity checks *******************************************************/ +/* Is there at least one UART enabled and configured as a RS-232 device? */ + +#ifndef HAVE_UART_DEVICE +# warning "No UARTs enabled" +#endif + +/* If we are not using the serial driver for the console, then we still must + * provide some minimal implementation of up_putc. + */ + +#if defined(HAVE_UART_DEVICE) && defined(USE_SERIALDRIVER) + +/* Which UART with be tty0/console and which tty1-4? The console will always + * be ttyS0. If there is no console then will use the lowest numbered UART. + */ + +/* First pick the console and ttys0. This could be any of UART0-5 */ + +#if defined(CONFIG_UART0_SERIAL_CONSOLE) +# define CONSOLE_DEV g_uart0port /* UART0 is console */ +# define TTYS0_DEV g_uart0port /* UART0 is ttyS0 */ +# define UART0_ASSIGNED 1 +#elif defined(CONFIG_UART1_SERIAL_CONSOLE) +# define CONSOLE_DEV g_uart1port /* UART1 is console */ +# define TTYS0_DEV g_uart1port /* UART1 is ttyS0 */ +# define UART1_ASSIGNED 1 +#elif defined(CONFIG_UART2_SERIAL_CONSOLE) +# define CONSOLE_DEV g_uart2port /* UART2 is console */ +# define TTYS0_DEV g_uart2port /* UART2 is ttyS0 */ +# define UART2_ASSIGNED 1 +#elif defined(CONFIG_UART3_SERIAL_CONSOLE) +# define CONSOLE_DEV g_uart3port /* UART3 is console */ +# define TTYS0_DEV g_uart3port /* UART3 is ttyS0 */ +# define UART3_ASSIGNED 1 +#elif defined(CONFIG_UART4_SERIAL_CONSOLE) +# define CONSOLE_DEV g_uart4port /* UART4 is console */ +# define TTYS0_DEV g_uart4port /* UART4 is ttyS0 */ +# define UART4_ASSIGNED 1 +#elif defined(CONFIG_UART5_SERIAL_CONSOLE) +# define CONSOLE_DEV g_uart5port /* UART5 is console */ +# define TTYS5_DEV g_uart5port /* UART5 is ttyS0 */ +# define UART5_ASSIGNED 1 +#else +# undef CONSOLE_DEV /* No console */ +# if defined(CONFIG_XMC4_USIC0_ISUART) +# define TTYS0_DEV g_uart0port /* UART0 is ttyS0 */ +# define UART0_ASSIGNED 1 +# elif defined(CONFIG_XMC4_USIC1_ISUART) +# define TTYS0_DEV g_uart1port /* UART1 is ttyS0 */ +# define UART1_ASSIGNED 1 +# elif defined(CONFIG_XMC4_USIC2_ISUART) +# define TTYS0_DEV g_uart2port /* UART2 is ttyS0 */ +# define UART2_ASSIGNED 1 +# elif defined(CONFIG_XMC4_USIC3_ISUART) +# define TTYS0_DEV g_uart3port /* UART3 is ttyS0 */ +# define UART3_ASSIGNED 1 +# elif defined(CONFIG_XMC4_USIC4_ISUART) +# define TTYS0_DEV g_uart4port /* UART4 is ttyS0 */ +# define UART4_ASSIGNED 1 +# elif defined(CONFIG_XMC4_USIC5_ISUART) +# define TTYS0_DEV g_uart5port /* UART5 is ttyS0 */ +# define UART5_ASSIGNED 1 +# endif +#endif + +/* Pick ttys1. This could be any of UART0-5 excluding the console UART. */ + +#if defined(CONFIG_XMC4_USIC0_ISUART) && !defined(UART0_ASSIGNED) +# define TTYS1_DEV g_uart0port /* UART0 is ttyS1 */ +# define UART0_ASSIGNED 1 +#elif defined(CONFIG_XMC4_USIC1_ISUART) && !defined(UART1_ASSIGNED) +# define TTYS1_DEV g_uart1port /* UART1 is ttyS1 */ +# define UART1_ASSIGNED 1 +#elif defined(CONFIG_XMC4_USIC2_ISUART) && !defined(UART2_ASSIGNED) +# define TTYS1_DEV g_uart2port /* UART2 is ttyS1 */ +# define UART2_ASSIGNED 1 +#elif defined(CONFIG_XMC4_USIC3_ISUART) && !defined(UART3_ASSIGNED) +# define TTYS1_DEV g_uart3port /* UART3 is ttyS1 */ +# define UART3_ASSIGNED 1 +#elif defined(CONFIG_XMC4_USIC4_ISUART) && !defined(UART4_ASSIGNED) +# define TTYS1_DEV g_uart4port /* UART4 is ttyS1 */ +# define UART4_ASSIGNED 1 +#elif defined(CONFIG_XMC4_USIC5_ISUART) && !defined(UART5_ASSIGNED) +# define TTYS1_DEV g_uart5port /* UART5 is ttyS1 */ +# define UART5_ASSIGNED 1 +#endif + +/* Pick ttys2. This could be one of UART1-5. It can't be UART0 because that + * was either assigned as ttyS0 or ttys1. One of UART 1-5 could also be the + * console. + */ + +#if defined(CONFIG_XMC4_USIC1_ISUART) && !defined(UART1_ASSIGNED) +# define TTYS2_DEV g_uart1port /* UART1 is ttyS2 */ +# define UART1_ASSIGNED 1 +#elif defined(CONFIG_XMC4_USIC2_ISUART) && !defined(UART2_ASSIGNED) +# define TTYS2_DEV g_uart2port /* UART2 is ttyS2 */ +# define UART2_ASSIGNED 1 +#elif defined(CONFIG_XMC4_USIC3_ISUART) && !defined(UART3_ASSIGNED) +# define TTYS2_DEV g_uart3port /* UART3 is ttyS2 */ +# define UART3_ASSIGNED 1 +#elif defined(CONFIG_XMC4_USIC4_ISUART) && !defined(UART4_ASSIGNED) +# define TTYS2_DEV g_uart4port /* UART4 is ttyS2 */ +# define UART4_ASSIGNED 1 +#elif defined(CONFIG_XMC4_USIC5_ISUART) && !defined(UART5_ASSIGNED) +# define TTYS2_DEV g_uart5port /* UART5 is ttyS2 */ +# define UART5_ASSIGNED 1 +#endif + +/* Pick ttys3. This could be one of UART2-5. It can't be UART0-1 because + * those have already been assigned to ttsyS0, 1, or 2. One of + * UART 2-5 could also be the console. + */ + +#if defined(CONFIG_XMC4_USIC2_ISUART) && !defined(UART2_ASSIGNED) +# define TTYS3_DEV g_uart2port /* UART2 is ttyS3 */ +# define UART2_ASSIGNED 1 +#elif defined(CONFIG_XMC4_USIC3_ISUART) && !defined(UART3_ASSIGNED) +# define TTYS3_DEV g_uart3port /* UART3 is ttyS3 */ +# define UART3_ASSIGNED 1 +#elif defined(CONFIG_XMC4_USIC4_ISUART) && !defined(UART4_ASSIGNED) +# define TTYS3_DEV g_uart4port /* UART4 is ttyS3 */ +# define UART4_ASSIGNED 1 +#elif defined(CONFIG_XMC4_USIC5_ISUART) && !defined(UART5_ASSIGNED) +# define TTYS3_DEV g_uart5port /* UART5 is ttyS3 */ +# define UART5_ASSIGNED 1 +#endif + +/* Pick ttys4. This could be one of UART3-5. It can't be UART0-2 because + * those have already been assigned to ttsyS0, 1, 2 or 3. One of + * UART 3-5 could also be the console. + */ + +#if defined(CONFIG_XMC4_USIC3_ISUART) && !defined(UART3_ASSIGNED) +# define TTYS4_DEV g_uart3port /* UART3 is ttyS4 */ +# define UART3_ASSIGNED 1 +#elif defined(CONFIG_XMC4_USIC4_ISUART) && !defined(UART4_ASSIGNED) +# define TTYS4_DEV g_uart4port /* UART4 is ttyS4 */ +# define UART4_ASSIGNED 1 +#elif defined(CONFIG_XMC4_USIC5_ISUART) && !defined(UART5_ASSIGNED) +# define TTYS4_DEV g_uart5port /* UART5 is ttyS4 */ +# define UART5_ASSIGNED 1 +#endif + +/* Pick ttys5. This could be one of UART4-5. It can't be UART0-3 because + * those have already been assigned to ttsyS0, 1, 2, 3 or 4. One of + * UART 4-5 could also be the console. + */ + +#if defined(CONFIG_XMC4_USIC4_ISUART) && !defined(UART4_ASSIGNED) +# define TTYS5_DEV g_uart4port /* UART4 is ttyS5 */ +# define UART4_ASSIGNED 1 +#elif defined(CONFIG_XMC4_USIC5_ISUART) && !defined(UART5_ASSIGNED) +# define TTYS5_DEV g_uart5port /* UART5 is ttyS5 */ +# define UART5_ASSIGNED 1 +#endif + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct xmc4_dev_s +{ + uintptr_t uartbase; /* Base address of UART registers */ + uint32_t baud; /* Configured baud */ + uint32_t clock; /* Clocking frequency of the UART module */ + uint8_t irqs; /* Status IRQ associated with this UART (for enable) */ + uint8_t ie; /* Interrupts enabled */ + uint8_t parity; /* 0=none, 1=odd, 2=even */ + uint8_t bits; /* Number of bits (8 or 9) */ + uint8_t stop2; /* Use 2 stop bits */ +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static int xmc4_setup(struct uart_dev_s *dev); +static void xmc4_shutdown(struct uart_dev_s *dev); +static int xmc4_attach(struct uart_dev_s *dev); +static void xmc4_detach(struct uart_dev_s *dev); +static int xmc4_interrupt(int irq, void *context, FAR void *arg); +static int xmc4_ioctl(struct file *filep, int cmd, unsigned long arg); +static int xmc4_receive(struct uart_dev_s *dev, uint32_t *status); +static void xmc4_rxint(struct uart_dev_s *dev, bool enable); +static bool xmc4_rxavailable(struct uart_dev_s *dev); +static void xmc4_send(struct uart_dev_s *dev, int ch); +static void xmc4_txint(struct uart_dev_s *dev, bool enable); +static bool xmc4_txready(struct uart_dev_s *dev); +static bool xmc4_txempty(struct uart_dev_s *dev); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const struct uart_ops_s g_uart_ops = +{ + .setup = xmc4_setup, + .shutdown = xmc4_shutdown, + .attach = xmc4_attach, + .detach = xmc4_detach, + .ioctl = xmc4_ioctl, + .receive = xmc4_receive, + .rxint = xmc4_rxint, + .rxavailable = xmc4_rxavailable, +#ifdef CONFIG_SERIAL_IFLOWCONTROL + .rxflowcontrol = NULL, +#endif + .send = xmc4_send, + .txint = xmc4_txint, + .txready = xmc4_txready, + .txempty = xmc4_txempty, +}; + +/* I/O buffers */ + +#ifdef CONFIG_XMC4_USIC0_ISUART +static char g_uart0rxbuffer[CONFIG_UART0_RXBUFSIZE]; +static char g_uart0txbuffer[CONFIG_UART0_TXBUFSIZE]; +#endif +#ifdef CONFIG_XMC4_USIC1_ISUART +static char g_uart1rxbuffer[CONFIG_UART1_RXBUFSIZE]; +static char g_uart1txbuffer[CONFIG_UART1_TXBUFSIZE]; +#endif +#ifdef CONFIG_XMC4_USIC2_ISUART +static char g_uart2rxbuffer[CONFIG_UART2_RXBUFSIZE]; +static char g_uart2txbuffer[CONFIG_UART2_TXBUFSIZE]; +#endif +#ifdef CONFIG_XMC4_USIC3_ISUART +static char g_uart3rxbuffer[CONFIG_UART3_RXBUFSIZE]; +static char g_uart3txbuffer[CONFIG_UART3_TXBUFSIZE]; +#endif +#ifdef CONFIG_XMC4_USIC4_ISUART +static char g_uart4rxbuffer[CONFIG_UART4_RXBUFSIZE]; +static char g_uart4txbuffer[CONFIG_UART4_TXBUFSIZE]; +#endif +#ifdef CONFIG_XMC4_USIC5_ISUART +static char g_uart5rxbuffer[CONFIG_UART5_RXBUFSIZE]; +static char g_uart5txbuffer[CONFIG_UART5_TXBUFSIZE]; +#endif + +/* This describes the state of the Kinetis UART0 port. */ + +#ifdef CONFIG_XMC4_USIC0_ISUART +static struct xmc4_dev_s g_uart0priv = +{ + .uartbase = XMC4_UART0_BASE, + .clock = BOARD_CORECLK_FREQ, + .baud = CONFIG_UART0_BAUD, + .irqs = XMC4_IRQ_USIC0, + .parity = CONFIG_UART0_PARITY, + .bits = CONFIG_UART0_BITS, + .stop2 = CONFIG_UART0_2STOP, +}; + +static uart_dev_t g_uart0port = +{ + .recv = + { + .size = CONFIG_UART0_RXBUFSIZE, + .buffer = g_uart0rxbuffer, + }, + .xmit = + { + .size = CONFIG_UART0_TXBUFSIZE, + .buffer = g_uart0txbuffer, + }, + .ops = &g_uart_ops, + .priv = &g_uart0priv, +}; +#endif + +/* This describes the state of the Kinetis UART1 port. */ + +#ifdef CONFIG_XMC4_USIC1_ISUART +static struct xmc4_dev_s g_uart1priv = +{ + .uartbase = XMC4_UART1_BASE, + .clock = BOARD_CORECLK_FREQ, + .baud = CONFIG_UART1_BAUD, + .irqs = XMC4_IRQ_USIC1, + .parity = CONFIG_UART1_PARITY, + .bits = CONFIG_UART1_BITS, + .stop2 = CONFIG_UART1_2STOP, +}; + +static uart_dev_t g_uart1port = +{ + .recv = + { + .size = CONFIG_UART1_RXBUFSIZE, + .buffer = g_uart1rxbuffer, + }, + .xmit = + { + .size = CONFIG_UART1_TXBUFSIZE, + .buffer = g_uart1txbuffer, + }, + .ops = &g_uart_ops, + .priv = &g_uart1priv, +}; +#endif + +/* This describes the state of the Kinetis UART2 port. */ + +#ifdef CONFIG_XMC4_USIC2_ISUART +static struct xmc4_dev_s g_uart2priv = +{ + .uartbase = XMC4_UART2_BASE, + .clock = BOARD_BUS_FREQ, + .baud = CONFIG_UART2_BAUD, + .irqs = XMC4_IRQ_USIC2, + .parity = CONFIG_UART2_PARITY, + .bits = CONFIG_UART2_BITS, + .stop2 = CONFIG_UART2_2STOP, +}; + +static uart_dev_t g_uart2port = +{ + .recv = + { + .size = CONFIG_UART2_RXBUFSIZE, + .buffer = g_uart2rxbuffer, + }, + .xmit = + { + .size = CONFIG_UART2_TXBUFSIZE, + .buffer = g_uart2txbuffer, + }, + .ops = &g_uart_ops, + .priv = &g_uart2priv, +}; +#endif + +/* This describes the state of the Kinetis UART3 port. */ + +#ifdef CONFIG_XMC4_USIC3_ISUART +static struct xmc4_dev_s g_uart3priv = +{ + .uartbase = XMC4_UART3_BASE, + .clock = BOARD_BUS_FREQ, + .baud = CONFIG_UART3_BAUD, + .irqs = XMC4_IRQ_USIC3, + .parity = CONFIG_UART3_PARITY, + .bits = CONFIG_UART3_BITS, + .stop2 = CONFIG_UART3_2STOP, +}; + +static uart_dev_t g_uart3port = +{ + .recv = + { + .size = CONFIG_UART3_RXBUFSIZE, + .buffer = g_uart3rxbuffer, + }, + .xmit = + { + .size = CONFIG_UART3_TXBUFSIZE, + .buffer = g_uart3txbuffer, + }, + .ops = &g_uart_ops, + .priv = &g_uart3priv, +}; +#endif + +/* This describes the state of the Kinetis UART4 port. */ + +#ifdef CONFIG_XMC4_USIC4_ISUART +static struct xmc4_dev_s g_uart4priv = +{ + .uartbase = XMC4_UART4_BASE, + .clock = BOARD_BUS_FREQ, + .baud = CONFIG_UART4_BAUD, + .irqs = XMC4_IRQ_USIC4, + .parity = CONFIG_UART4_PARITY, + .bits = CONFIG_UART4_BITS, + .stop2 = CONFIG_UART4_2STOP, +}; + +static uart_dev_t g_uart4port = +{ + .recv = + { + .size = CONFIG_UART4_RXBUFSIZE, + .buffer = g_uart4rxbuffer, + }, + .xmit = + { + .size = CONFIG_UART4_TXBUFSIZE, + .buffer = g_uart4txbuffer, + }, + .ops = &g_uart_ops, + .priv = &g_uart4priv, +}; +#endif + +/* This describes the state of the Kinetis UART5 port. */ + +#ifdef CONFIG_XMC4_USIC5_ISUART +static struct xmc4_dev_s g_uart5priv = +{ + .uartbase = XMC4_UART5_BASE, + .clock = BOARD_BUS_FREQ, + .baud = CONFIG_UART5_BAUD, + .irqs = XMC4_IRQ_USIC5, + .parity = CONFIG_UART5_PARITY, + .bits = CONFIG_UART5_BITS, + .stop2 = CONFIG_UART5_2STOP, +}; + +static uart_dev_t g_uart5port = +{ + .recv = + { + .size = CONFIG_UART5_RXBUFSIZE, + .buffer = g_uart5rxbuffer, + }, + .xmit = + { + .size = CONFIG_UART5_TXBUFSIZE, + .buffer = g_uart5txbuffer, + }, + .ops = &g_uart_ops, + .priv = &g_uart5priv, +}; +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_serialin + ****************************************************************************/ + +static inline uint8_t up_serialin(struct xmc4_dev_s *priv, int offset) +{ + return getreg8(priv->uartbase + offset); +} + +/**************************************************************************** + * Name: up_serialout + ****************************************************************************/ + +static inline void up_serialout(struct xmc4_dev_s *priv, int offset, uint8_t value) +{ + putreg8(value, priv->uartbase + offset); +} + +/**************************************************************************** + * Name: up_setuartint + ****************************************************************************/ + +static void up_setuartint(struct xmc4_dev_s *priv) +{ + irqstate_t flags; + uint8_t regval; + + /* Re-enable/re-disable interrupts corresponding to the state of bits in ie */ +#warning Missing logic + + leave_critical_section(flags); +} + +/**************************************************************************** + * Name: up_restoreuartint + ****************************************************************************/ + +static void up_restoreuartint(struct xmc4_dev_s *priv, uint8_t ie) +{ + irqstate_t flags; + + /* Re-enable/re-disable interrupts corresponding to the state of bits in ie */ + + flags = enter_critical_section(); +#warning Missing logic + leave_critical_section(flags); +} + +/**************************************************************************** + * Name: up_disableuartint + ****************************************************************************/ + +static void up_disableuartint(struct xmc4_dev_s *priv, uint8_t *ie) +{ + irqstate_t flags; + + flags = enter_critical_section(); + if (ie) + { + *ie = priv->ie; + } + + up_restoreuartint(priv, 0); + leave_critical_section(flags); +} + +/**************************************************************************** + * Name: xmc4_setup + * + * Description: + * Configure the UART baud, bits, parity, etc. This method is called the + * first time that the serial port is opened. + * + ****************************************************************************/ + +static int xmc4_setup(struct uart_dev_s *dev) +{ +#ifndef CONFIG_SUPPRESS_UART_CONFIG + struct xmc4_dev_s *priv = (struct xmc4_dev_s *)dev->priv; + + /* Configure the UART as an RS-232 UART */ + + xmc4_uart_configure(priv->uartbase, priv->baud, priv->clock, + priv->parity, priv->bits, priv->stop2); +#endif + + /* Make sure that all interrupts are disabled */ + + up_restoreuartint(priv, 0); + return OK; +} + +/**************************************************************************** + * Name: xmc4_shutdown + * + * Description: + * Disable the UART. This method is called when the serial + * port is closed + * + ****************************************************************************/ + +static void xmc4_shutdown(struct uart_dev_s *dev) +{ + struct xmc4_dev_s *priv = (struct xmc4_dev_s *)dev->priv; + + /* Disable interrupts */ + + up_restoreuartint(priv, 0); + + /* Reset hardware and disable Rx and Tx */ + + xmc4_uart_reset(priv->uartbase); +} + +/**************************************************************************** + * Name: xmc4_attach + * + * Description: + * Configure the UART to operation in interrupt driven mode. This method is + * called when the serial port is opened. Normally, this is just after the + * the setup() method is called, however, the serial console may operate in + * a non-interrupt driven mode during the boot phase. + * + * RX and TX interrupts are not enabled when by the attach method (unless the + * hardware supports multiple levels of interrupt enabling). The RX and TX + * interrupts are not enabled until the txint() and rxint() methods are called. + * + ****************************************************************************/ + +static int xmc4_attach(struct uart_dev_s *dev) +{ + struct xmc4_dev_s *priv = (struct xmc4_dev_s *)dev->priv; + int ret; + + /* Attach and enable the IRQ(s). The interrupts are (probably) still + * disabled in the C2 register. + */ + + ret = irq_attach(priv->irqs, xmc4_interrupt, dev); + if (ret == OK) + { + up_enable_irq(priv->irqs); + } + + return ret; +} + +/**************************************************************************** + * Name: xmc4_detach + * + * Description: + * Detach UART interrupts. This method is called when the serial port is + * closed normally just before the shutdown method is called. The exception + * is the serial console which is never shutdown. + * + ****************************************************************************/ + +static void xmc4_detach(struct uart_dev_s *dev) +{ + struct xmc4_dev_s *priv = (struct xmc4_dev_s *)dev->priv; + + /* Disable interrupts */ + + up_restoreuartint(priv, 0); + up_disable_irq(priv->irqs); + + /* Detach from the interrupt(s) */ + + irq_detach(priv->irqs); +} + +/**************************************************************************** + * Name: xmc4_interrupt + * + * Description: + * This is the UART status interrupt handler. It will be invoked when an + * interrupt received on the 'irq' It should call uart_transmitchars or + * uart_receivechar to perform the appropriate data transfers. The + * interrupt handling logic must be able to map the 'irq' number into the + * approprite uart_dev_s structure in order to call these functions. + * + ****************************************************************************/ + +static int xmc4_interrupt(int irq, void *context, FAR void *arg) +{ + struct uart_dev_s *dev = (struct uart_dev_s *)arg; + struct xmc4_dev_s *priv; + int passes; + uint8_t s1; + bool handled; + + DEBUGASSERT(dev != NULL && dev->priv != NULL); + priv = (struct xmc4_dev_s *)dev->priv; + + /* Loop until there are no characters to be transferred or, + * until we have been looping for a long time. + */ + + handled = true; + for (passes = 0; passes < 256 && handled; passes++) + { + handled = false; + + /* Read status register 1 */ + + s1 = up_serialin(priv, XMC4_UART_S1_OFFSET); + + /* Handle incoming, receive bytes */ + + /* Check if the receive data register is full (RDRF). NOTE: If + * FIFOS are enabled, this does not mean that the FIFO is full, + * rather, it means that the number of bytes in the RX FIFO has + * exceeded the watermark setting. There may actually be RX data + * available! + * + * The RDRF status indication is cleared when the data is read from + * the RX data register. + */ + +#warning Missing logic + { + /* Process incoming bytes */ + + uart_recvchars(dev); + handled = true; + } + + /* Handle outgoing, transmit bytes */ + + /* Check if the transmit data register is "empty." NOTE: If FIFOS + * are enabled, this does not mean that the FIFO is empty, rather, + * it means that the number of bytes in the TX FIFO is below the + * watermark setting. There could actually be space for additional TX + * data. + * + * The TDRE status indication is cleared when the data is written to + * the TX data register. + */ + +#warning Missing logic + { + /* Process outgoing bytes */ + + uart_xmitchars(dev); + handled = true; + } + } + + return OK; +} + +/**************************************************************************** + * Name: xmc4_ioctl + * + * Description: + * All ioctl calls will be routed through this method + * + ****************************************************************************/ + +static int xmc4_ioctl(struct file *filep, int cmd, unsigned long arg) +{ +#if 0 /* Reserved for future growth */ + struct inode *inode; + struct uart_dev_s *dev; + struct xmc4_dev_s *priv; + int ret = OK; + + DEBUGASSERT(filep, filep->f_inode); + inode = filep->f_inode; + dev = inode->i_private; + + DEBUGASSERT(dev, dev->priv); + priv = (struct xmc4_dev_s *)dev->priv; + + switch (cmd) + { + case xxx: /* Add commands here */ + break; + + default: + ret = -ENOTTY; + break; + } + + return ret; +#else + return -ENOTTY; +#endif +} + +/**************************************************************************** + * Name: xmc4_receive + * + * Description: + * Called (usually) from the interrupt level to receive one + * character from the UART. Error bits associated with the + * receipt are provided in the return 'status'. + * + ****************************************************************************/ + +static int xmc4_receive(struct uart_dev_s *dev, uint32_t *status) +{ + struct xmc4_dev_s *priv = (struct xmc4_dev_s *)dev->priv; + uint8_t s1; + + /* Get error status information: + * + * FE: Framing error. To clear FE, read S1 with FE set and then read + * read UART data register (D). + * NF: Noise flag. To clear NF, read S1 and then read the UART data + * register (D). + * PF: Parity error flag. To clear PF, read S1 and then read the UART + * data register (D). + */ + + s1 = up_serialin(priv, XMC4_UART_S1_OFFSET); + + /* Return status information */ + + if (status) + { + *status = (uint32_t)s1; + } + + /* Then return the actual received byte. Reading S1 then D clears all + * RX errors. + */ + + return (int)up_serialin(priv, XMC4_UART_D_OFFSET); +} + +/**************************************************************************** + * Name: xmc4_rxint + * + * Description: + * Call to enable or disable RX interrupts + * + ****************************************************************************/ + +static void xmc4_rxint(struct uart_dev_s *dev, bool enable) +{ + struct xmc4_dev_s *priv = (struct xmc4_dev_s *)dev->priv; + irqstate_t flags; + + flags = enter_critical_section(); + if (enable) + { + /* Receive an interrupt when their is anything in the Rx data register (or an Rx + * timeout occurs). + */ + +#ifndef CONFIG_SUPPRESS_SERIAL_INTS + priv->ie |= UART_C2_RIE; + up_setuartint(priv); +#endif + } + else + { +#ifdef CONFIG_DEBUG_FEATURES +# warning "Revisit: How are errors enabled?" + priv->ie &= ~UART_C2_RIE; +#else + priv->ie &= ~UART_C2_RIE; +#endif + up_setuartint(priv); + } + + leave_critical_section(flags); +} + +/**************************************************************************** + * Name: xmc4_rxavailable + * + * Description: + * Return true if the receive register is not empty + * + ****************************************************************************/ + +static bool xmc4_rxavailable(struct uart_dev_s *dev) +{ + struct xmc4_dev_s *priv = (struct xmc4_dev_s *)dev->priv; + /* Return true if the receive data register is full (RDRF). NOTE: If + * FIFOS are enabled, this does not mean that the FIFO is full, + * rather, it means that the number of bytes in the RX FIFO has + * exceeded the watermark setting. There may actually be RX data + * available! + */ + + return (up_serialin(priv, XMC4_UART_S1_OFFSET) & UART_S1_RDRF) != 0; +} + +/**************************************************************************** + * Name: xmc4_send + * + * Description: + * This method will send one byte on the UART. + * + ****************************************************************************/ + +static void xmc4_send(struct uart_dev_s *dev, int ch) +{ + struct xmc4_dev_s *priv = (struct xmc4_dev_s *)dev->priv; + up_serialout(priv, XMC4_UART_D_OFFSET, (uint8_t)ch); +} + +/**************************************************************************** + * Name: xmc4_txint + * + * Description: + * Call to enable or disable TX interrupts + * + ****************************************************************************/ + +static void xmc4_txint(struct uart_dev_s *dev, bool enable) +{ + struct xmc4_dev_s *priv = (struct xmc4_dev_s *)dev->priv; + irqstate_t flags; + + flags = enter_critical_section(); + if (enable) + { + /* Enable the TX interrupt */ + +#ifndef CONFIG_SUPPRESS_SERIAL_INTS + priv->ie |= UART_C2_TIE; + up_setuartint(priv); + + /* Fake a TX interrupt here by just calling uart_xmitchars() with + * interrupts disabled (note this may recurse). + */ + + uart_xmitchars(dev); +#endif + } + else + { + /* Disable the TX interrupt */ + + priv->ie &= ~UART_C2_TIE; + up_setuartint(priv); + } + + leave_critical_section(flags); +} + +/**************************************************************************** + * Name: xmc4_txready + * + * Description: + * Return true if the tranmsit data register is empty + * + ****************************************************************************/ + +static bool xmc4_txready(struct uart_dev_s *dev) +{ + struct xmc4_dev_s *priv = (struct xmc4_dev_s *)dev->priv; + + /* Return true if the transmit data register is "empty." NOTE: If + * FIFOS are enabled, this does not mean that the FIFO is empty, + * rather, it means that the number of bytes in the TX FIFO is + * below the watermark setting. There may actually be space for + * additional TX data. + */ + + return (up_serialin(priv, XMC4_UART_S1_OFFSET) & UART_S1_TDRE) != 0; +} + +/**************************************************************************** + * Name: xmc4_txempty + * + * Description: + * Return true if the tranmsit data register is empty + * + ****************************************************************************/ + +static bool xmc4_txempty(struct uart_dev_s *dev) +{ + struct xmc4_dev_s *priv = (struct xmc4_dev_s *)dev->priv; + + /* Return true if the transmit buffer/fifo is "empty." */ + + return (up_serialin(priv, XMC4_UART_SFIFO_OFFSET) & UART_SFIFO_TXEMPT) != 0; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: xmc4_earlyserialinit + * + * Description: + * Performs the low level UART initialization early in debug so that the + * serial console will be available during bootup. This must be called + * before up_serialinit. NOTE: This function depends on GPIO pin + * configuration performed in up_consoleinit() and main clock iniialization + * performed in up_clkinitialize(). + * + ****************************************************************************/ + +#if defined(USE_EARLYSERIALINIT) +void xmc4_earlyserialinit(void) +{ + /* Disable interrupts from all UARTS. The console is enabled in + * pic32mx_consoleinit() + */ + + up_restoreuartint(TTYS0_DEV.priv, 0); +#ifdef TTYS1_DEV + up_restoreuartint(TTYS1_DEV.priv, 0); +#endif +#ifdef TTYS2_DEV + up_restoreuartint(TTYS2_DEV.priv, 0); +#endif +#ifdef TTYS3_DEV + up_restoreuartint(TTYS3_DEV.priv, 0); +#endif +#ifdef TTYS4_DEV + up_restoreuartint(TTYS4_DEV.priv, 0); +#endif +#ifdef TTYS5_DEV + up_restoreuartint(TTYS5_DEV.priv, 0); +#endif + + /* Configuration whichever one is the console */ + +#ifdef HAVE_UART_CONSOLE + CONSOLE_DEV.isconsole = true; + xmc4_setup(&CONSOLE_DEV); +#endif +} +#endif + +/**************************************************************************** + * Name: up_serialinit + * + * Description: + * Register serial console and serial ports. This assumes + * that up_earlyserialinit was called previously. + * + * Input Parameters: + * None + * + * Returns Value: + * None + * + ****************************************************************************/ + +void up_serialinit(void) +{ + char devname[] = "/dev/ttySx"; + + /* Register the console */ + +#ifdef HAVE_UART_CONSOLE + (void)uart_register("/dev/console", &CONSOLE_DEV); +#endif + + /* Register all UARTs */ + + (void)uart_register("/dev/ttyS0", &TTYS0_DEV); +#ifdef TTYS1_DEV + devname[(sizeof(devname)/sizeof(devname[0]))-2] = '0' + first++; + (void)uart_register("/dev/ttyS1", &TTYS1_DEV); +#endif +#ifdef TTYS2_DEV + devname[(sizeof(devname)/sizeof(devname[0]))-2] = '0' + first++; + (void)uart_register("/dev/ttyS2", &TTYS2_DEV); +#endif +#ifdef TTYS3_DEV + devname[(sizeof(devname)/sizeof(devname[0]))-2] = '0' + first++; + (void)uart_register("/dev/ttyS3", &TTYS3_DEV); +#endif +#ifdef TTYS4_DEV + devname[(sizeof(devname)/sizeof(devname[0]))-2] = '0' + first++; + (void)uart_register("/dev/ttyS4", &TTYS4_DEV); +#endif +#ifdef TTYS5_DEV + devname[(sizeof(devname)/sizeof(devname[0]))-2] = '0' + first++; + (void)uart_register("/dev/ttyS5", &TTYS5_DEV); +#endif + return first; +} + +/**************************************************************************** + * Name: up_putc + * + * Description: + * Provide priority, low-level access to support OS debug writes + * + ****************************************************************************/ + +#ifdef HAVE_UART_PUTC +int up_putc(int ch) +{ +#ifdef HAVE_UART_CONSOLE + struct xmc4_dev_s *priv = (struct xmc4_dev_s *)CONSOLE_DEV.priv; + uint8_t ie; + + up_disableuartint(priv, &ie); + + /* Check for LF */ + + if (ch == '\n') + { + /* Add CR */ + + up_lowputc('\r'); + } + + up_lowputc(ch); + up_restoreuartint(priv, ie); +#endif + return ch; +} +#endif + +#else /* USE_SERIALDRIVER */ + +/**************************************************************************** + * Name: up_putc + * + * Description: + * Provide priority, low-level access to support OS debug writes + * + ****************************************************************************/ + +#ifdef HAVE_UART_PUTC +int up_putc(int ch) +{ +#ifdef HAVE_UART_CONSOLE + /* Check for LF */ + + if (ch == '\n') + { + /* Add CR */ + + up_lowputc('\r'); + } + + up_lowputc(ch); +#endif + return ch; +} +#endif + +#endif /* HAVE_UART_DEVICE && USE_SERIALDRIVER */ + diff --git a/arch/arm/src/xmc4/xmc4_spi.h b/arch/arm/src/xmc4/xmc4_spi.h new file mode 100644 index 0000000000..0ac514c5ce --- /dev/null +++ b/arch/arm/src/xmc4/xmc4_spi.h @@ -0,0 +1,165 @@ +/**************************************************************************** + * arch/arm/src/xmc4/xmc4_spi.h + * + * 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. + * + ****************************************************************************/ + +#ifndef __ARCH_ARM_SRC_XMC4_XMC4_SPI_H +#define __ARCH_ARM_SRC_XMC4_XMC4_SPI_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include "chip/xmc4_spi.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +struct spi_dev_s; +enum spi_dev_e; + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/************************************************************************************ + * Name: xmc4_spibus_initialize + * + * Description: + * Initialize the selected SPI bus + * + * Input Parameter: + * bus number (for hardware that has mutiple SPI interfaces) + * + * Returned Value: + * Valid SPI device structure reference on succcess; a NULL on failure + * + ************************************************************************************/ + +FAR struct spi_dev_s *xmc4_spibus_initialize(int bus); + +/************************************************************************************ + * Name: xmc4_spi[n]select, xmc4_spi[n]status, and xmc4_spi[n]cmddata + * + * Description: + * These external functions must be provided by board-specific logic. They are + * implementations of the select, status, and cmddata methods of the SPI interface + * defined by struct spi_ops_s (see include/nuttx/spi/spi.h). All other methods + * including xmc4_spibus_initialize()) are provided by common Kinetis logic. To use + * this common SPI logic on your board: + * + * 1. Provide logic in xmc4_board_initialize() to configure SPI chip select + * pins. + * 2. Provide xmc4_spi[n]select() and xmc4_spi[n]status() functions + * in your board-specific logic. These functions will perform chip selection + * and status operations using GPIOs in the way your board is configured. + * 2. If CONFIG_SPI_CMDDATA is defined in the NuttX configuration, provide + * xmc4_spi[n]cmddata() functions in your board-specific logic. These + * functions will perform cmd/data selection operations using GPIOs in the way + * your board is configured. + * 3. Add a call to xmc4_spibus_initialize() in your low level application + * initialization logic + * 4. The handle returned by xmc4_spibus_initialize() may then be used to bind the + * SPI driver to higher level logic (e.g., calling + * mmcsd_spislotinitialize(), for example, will bind the SPI driver to + * the SPI MMC/SD driver). + * + ************************************************************************************/ + +#ifdef CONFIG_XMC4_SPI0 +void xmc4_spi0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); +uint8_t xmc4_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +#ifdef CONFIG_SPI_CMDDATA +int xmc4_spi0cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +#endif +#endif +#ifdef CONFIG_XMC4_SPI1 +void xmc4_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); +uint8_t xmc4_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +#ifdef CONFIG_SPI_CMDDATA +int xmc4_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +#endif +#endif +#ifdef CONFIG_XMC4_SPI2 +void xmc4_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); +uint8_t xmc4_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +#ifdef CONFIG_SPI_CMDDATA +int xmc4_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +#endif +#endif + +/**************************************************************************** + * Name: ssp_flush + * + * Description: + * Flush and discard any words left in the RX fifo. This can be called + * from spi[n]select after a device is deselected (if you worry about such + * things). + * + * Input Parameters: + * dev - Device-specific state data + * + * Returned Value: + * None + * + ****************************************************************************/ + +#undef EXTERN +#if defined(__cplusplus) +} +#endif +#if defined(CONFIG_XMC4_SPI0) || defined(CONFIG_XMC4_SPI1) || defined(CONFIG_XMC4_SPI2) +struct spi_dev_s; +void spi_flush(FAR struct spi_dev_s *dev); +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __ARCH_ARM_SRC_XMC4_XMC4_SPI_H */ diff --git a/arch/arm/src/xmc4/xmc4_start.c b/arch/arm/src/xmc4/xmc4_start.c new file mode 100644 index 0000000000..e71722e4be --- /dev/null +++ b/arch/arm/src/xmc4/xmc4_start.c @@ -0,0 +1,355 @@ +/**************************************************************************** + * arch/arm/src/xmc4/xmc4_start.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include +#include + +#include "up_arch.h" +#include "up_internal.h" + +#include "xmc4_userspace.h" + +#ifdef CONFIG_ARCH_FPU +# include "nvic.h" +#endif + +/**************************************************************************** + * Private Function prototypes + ****************************************************************************/ + +#ifdef CONFIG_ARCH_FPU +static inline void xmc4_fpu_config(void); +#endif +#ifdef CONFIG_STACK_COLORATION +static void go_os_start(void *pv, unsigned int nbytes) + __attribute__ ((naked, no_instrument_function, noreturn)); +#endif + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ +/* Memory Map ***************************************************************/ +/* + * 0x0000:0000 - Beginning of the internal FLASH. Address of vectors. + * Mapped as boot memory address 0x0000:0000 at reset. + * 0x07ff:ffff - End of flash region (assuming the max of 2MiB of FLASH). + * 0x1fff:0000 - Start of internal SRAM and start of .data (_sdata) + * - End of .data (_edata) and start of .bss (_sbss) + * - End of .bss (_ebss) and bottom of idle stack + * - _ebss + CONFIG_IDLETHREAD_STACKSIZE = end of idle stack, + * start of heap. NOTE that the ARM uses a decrement before + * store stack so that the correct initial value is the end of + * the stack + 4; + * 0x2002:ffff - End of internal SRAM and end of heap (a + */ + +#define IDLE_STACK ((uintptr_t)&_ebss+CONFIG_IDLETHREAD_STACKSIZE-4) +#define HEAP_BASE ((uintptr_t)&_ebss+CONFIG_IDLETHREAD_STACKSIZE) + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/* g_idle_topstack: _sbss is the start of the BSS region as defined by the + * linker script. _ebss lies at the end of the BSS region. The idle task + * stack starts at the end of BSS and is of size CONFIG_IDLETHREAD_STACKSIZE. + * The IDLE thread is the thread that the system boots on and, eventually, + * becomes the IDLE, do nothing task that runs only when there is nothing + * else to run. The heap continues from there until the end of memory. + * g_idle_topstack is a read-only variable the provides this computed + * address. + */ +#if defined(CONFIG_ARMV7M_CMNVECTOR) +const uintptr_t g_idle_topstack = HEAP_BASE; +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + + +#ifdef CONFIG_ARMV7M_STACKCHECK +/* we need to get r10 set before we can allow instrumentation calls */ + +void __start(void) __attribute__ ((no_instrument_function)); +#endif + +/**************************************************************************** + * Name: xmc4_fpu_config + * + * Description: + * Configure the FPU. Relative bit settings: + * + * CPACR: Enables access to CP10 and CP11 + * CONTROL.FPCA: Determines whether the FP extension is active in the + * current context: + * FPCCR.ASPEN: Enables automatic FP state preservation, then the + * processor sets this bit to 1 on successful completion of any FP + * instruction. + * FPCCR.LSPEN: Enables lazy context save of FP state. When this is + * done, the processor reserves space on the stack for the FP state, + * but does not save that state information to the stack. + * + * Software must not change the value of the ASPEN bit or LSPEN bit while either: + * - the CPACR permits access to CP10 and CP11, that give access to the FP + * extension, or + * - the CONTROL.FPCA bit is set to 1 + * + ****************************************************************************/ + +#ifdef CONFIG_ARCH_FPU +#if defined(CONFIG_ARMV7M_CMNVECTOR) && !defined(CONFIG_ARMV7M_LAZYFPU) + +static inline void xmc4_fpu_config(void) +{ + uint32_t regval; + + /* Set CONTROL.FPCA so that we always get the extended context frame + * with the volatile FP registers stacked above the basic context. + */ + + regval = getcontrol(); + regval |= (1 << 2); + setcontrol(regval); + + /* Ensure that FPCCR.LSPEN is disabled, so that we don't have to contend + * with the lazy FP context save behaviour. Clear FPCCR.ASPEN since we + * are going to turn on CONTROL.FPCA for all contexts. + */ + + regval = getreg32(NVIC_FPCCR); + regval &= ~((1 << 31) | (1 << 30)); + putreg32(regval, NVIC_FPCCR); + + /* Enable full access to CP10 and CP11 */ + + regval = getreg32(NVIC_CPACR); + regval |= ((3 << (2*10)) | (3 << (2*11))); + putreg32(regval, NVIC_CPACR); +} + +#else + +static inline void xmc4_fpu_config(void) +{ + uint32_t regval; + + /* Clear CONTROL.FPCA so that we do not get the extended context frame + * with the volatile FP registers stacked in the saved context. + */ + + regval = getcontrol(); + regval &= ~(1 << 2); + setcontrol(regval); + + /* Ensure that FPCCR.LSPEN is disabled, so that we don't have to contend + * with the lazy FP context save behaviour. Clear FPCCR.ASPEN since we + * are going to keep CONTROL.FPCA off for all contexts. + */ + + regval = getreg32(NVIC_FPCCR); + regval &= ~((1 << 31) | (1 << 30)); + putreg32(regval, NVIC_FPCCR); + + /* Enable full access to CP10 and CP11 */ + + regval = getreg32(NVIC_CPACR); + regval |= ((3 << (2*10)) | (3 << (2*11))); + putreg32(regval, NVIC_CPACR); +} + +#endif + +#else +# define xmc4_fpu_config() +#endif + +/**************************************************************************** + * Name: go_os_start + * + * Description: + * Set the IDLE stack to the + * + ****************************************************************************/ + +#ifdef CONFIG_STACK_COLORATION +static void go_os_start(void *pv, unsigned int nbytes) +{ + /* Set the IDLE stack to the stack coloration value then jump to + * os_start(). We take extreme care here because were currently + * executing on this stack. + * + * We want to avoid sneak stack access generated by the compiler. + */ + + __asm__ __volatile__ + ( + "\tmovs r1, r1, lsr #2\n" /* R1 = nwords = nbytes >> 2 */ + "\tbeq 2f\n" /* (should not happen) */ + + "\tbic r0, r0, #3\n" /* R0 = Aligned stackptr */ + "\tmovw r2, #0xbeef\n" /* R2 = STACK_COLOR = 0xdeadbeef */ + "\tmovt r2, #0xdead\n" + + "1:\n" /* Top of the loop */ + "\tsub r1, r1, #1\n" /* R1 nwords-- */ + "\tcmp r1, #0\n" /* Check (nwords == 0) */ + "\tstr r2, [r0], #4\n" /* Save stack color word, increment stackptr */ + "\tbne 1b\n" /* Bottom of the loop */ + + "2:\n" + "\tmov r14, #0\n" /* LR = return address (none) */ + "\tb os_start\n" /* Branch to os_start */ + ); +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: _start + * + * Description: + * This is the reset entry point. + * + ****************************************************************************/ + +void __start(void) +{ + const uint32_t *src; + uint32_t *dest; + +#ifdef CONFIG_ARMV7M_STACKCHECK + /* Set the stack limit before we attempt to call any functions */ + + __asm__ volatile ("sub r10, sp, %0" : : "r" (CONFIG_IDLETHREAD_STACKSIZE - 64) : ); +#endif + + /* Disable the watchdog timer */ + + kinetis_wddisable(); + + /* Clear .bss. We'll do this inline (vs. calling memset) just to be + * certain that there are no issues with the state of global variables. + */ + + for (dest = &_sbss; dest < &_ebss; ) + { + *dest++ = 0; + } + + /* Move the initialized data section from his temporary holding spot in + * FLASH into the correct place in SRAM. The correct place in SRAM is + * give by _sdata and _edata. The temporary location is in FLASH at the + * end of all of the other read-only data (.text, .rodata) at _eronly. + */ + + for (src = &_eronly, dest = &_sdata; dest < &_edata; ) + { + *dest++ = *src++; + } + + /* Copy any necessary code sections from FLASH to RAM. The correct + * destination in SRAM is given by _sramfuncs and _eramfuncs. The + * temporary location is in flash after the data initialization code + * at _framfuncs + */ + +#ifdef CONFIG_ARCH_RAMFUNCS + for (src = &_framfuncs, dest = &_sramfuncs; dest < &_eramfuncs; ) + { + *dest++ = *src++; + } +#endif + + /* Perform clock and Kinetis module initialization (This depends on + * RAM functions having been copied to RAM). + */ + + xmc4_clock_config(); + + /* Configure the uart and perform early serial initialization so that we + * can get debug output as soon as possible (This depends on clock + * configuration). + */ + + xmc4_fpu_config(); + xmc4_lowsetup(); +#ifdef USE_EARLYSERIALINIT + xmc4_earlyserialinit(); +#endif + + /* For the case of the separate user-/kernel-space build, perform whatever + * platform specific initialization of the user memory is required. + * Normally this just means initializing the user space .data and .bss + * segments. + */ + +#ifdef CONFIG_BUILD_PROTECTED + xmc4_userspace(); +#endif + + /* Initialize other on-board resources */ + + xmc4_board_initialize(); + + /* Then start NuttX */ + + os_start(); + + /* Shouldn't get here */ + + for (; ; ); +} diff --git a/arch/arm/src/xmc4/xmc4_timerisr.c b/arch/arm/src/xmc4/xmc4_timerisr.c new file mode 100644 index 0000000000..ba9e98596c --- /dev/null +++ b/arch/arm/src/xmc4/xmc4_timerisr.c @@ -0,0 +1,152 @@ +/**************************************************************************** + * arch/arm/src/xmc4/xmc4_timerisr.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include +#include + +#include "nvic.h" +#include "clock/clock.h" +#include "up_internal.h" +#include "up_arch.h" + +#include "chip.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* The desired timer interrupt frequency is provided by the definition + * CLK_TCK (see include/time.h). CLK_TCK defines the desired number of + * system clock ticks per second. That value is a user configurable setting + * that defaults to 100 (100 ticks per second = 10 MS interval). + * + * The Clock Source: The System Tick Timer's clock source is always the core + * clock + */ + +#define SYSTICK_RELOAD ((BOARD_CORECLK_FREQ / CLK_TCK) - 1) + +/* The size of the reload field is 24 bits. Verify that the reload value + * will fit in the reload register. + */ + +#if SYSTICK_RELOAD > 0x00ffffff +# error SYSTICK_RELOAD exceeds the range of the RELOAD register +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: xmc4_timerisr + * + * Description: + * The timer ISR will perform a variety of services for various portions + * of the systems. + * + ****************************************************************************/ + +static int xmc4_timerisr(int irq, uint32_t *regs, FAR void *arg) +{ + /* Process timer interrupt */ + + sched_process_timer(); + return 0; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: arm_timer_initialize + * + * Description: + * This function is called during start-up to initialize + * the timer interrupt. + * + ****************************************************************************/ + +void arm_timer_initialize(void) +{ + uint32_t regval; + + /* Set the SysTick interrupt to the default priority */ + + regval = getreg32(NVIC_SYSH12_15_PRIORITY); + regval &= ~NVIC_SYSH_PRIORITY_PR15_MASK; + regval |= (NVIC_SYSH_PRIORITY_DEFAULT << NVIC_SYSH_PRIORITY_PR15_SHIFT); + putreg32(regval, NVIC_SYSH12_15_PRIORITY); + + /* Note that is should not be neccesary to set the SYSTICK clock source: + * "The CLKSOURCE bit in SysTick Control and Status register is always set + * to select the core clock." + */ + +#if 0 + regval = getreg32(NVIC_SYSTICK_CTRL); + regval |= NVIC_SYSTICK_CTRL_CLKSOURCE; + putreg32(regval, NVIC_SYSTICK_CTRL); +#endif + + /* Configure SysTick to interrupt at the requested rate */ + + putreg32(SYSTICK_RELOAD, NVIC_SYSTICK_RELOAD); + + /* Attach the timer interrupt vector */ + + (void)irq_attach(XMC4_IRQ_SYSTICK, (xcpt_t)xmc4_timerisr, NULL); + + /* Enable SysTick interrupts */ + + putreg32((NVIC_SYSTICK_CTRL_CLKSOURCE | NVIC_SYSTICK_CTRL_TICKINT | + NVIC_SYSTICK_CTRL_ENABLE), + NVIC_SYSTICK_CTRL); + + /* And enable the timer interrupt */ + + up_enable_irq(XMC4_IRQ_SYSTICK); +} diff --git a/arch/arm/src/xmc4/xmc4_userspace.c b/arch/arm/src/xmc4/xmc4_userspace.c new file mode 100644 index 0000000000..02dc2d2303 --- /dev/null +++ b/arch/arm/src/xmc4/xmc4_userspace.c @@ -0,0 +1,107 @@ +/**************************************************************************** + * arch/arm/src/xmc4/xmc4_userspace.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include + +#include "xmc4_mpuinit.h" +#include "xmc4_userspace.h" + +#ifdef CONFIG_BUILD_PROTECTED + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: xmc4_userspace + * + * Description: + * For the case of the separate user-/kernel-space build, perform whatever + * platform specific initialization of the user memory is required. + * Normally this just means initializing the user space .data and .bss + * segments. + * + ****************************************************************************/ + +void xmc4_userspace(void) +{ + uint8_t *src; + uint8_t *dest; + uint8_t *end; + + /* Clear all of user-space .bss */ + + DEBUGASSERT(USERSPACE->us_bssstart != 0 && USERSPACE->us_bssend != 0 && + USERSPACE->us_bssstart <= USERSPACE->us_bssend); + + dest = (uint8_t *)USERSPACE->us_bssstart; + end = (uint8_t *)USERSPACE->us_bssend; + + while (dest != end) + { + *dest++ = 0; + } + + /* Initialize all of user-space .data */ + + DEBUGASSERT(USERSPACE->us_datasource != 0 && + USERSPACE->us_datastart != 0 && USERSPACE->us_dataend != 0 && + USERSPACE->us_datastart <= USERSPACE->us_dataend); + + src = (uint8_t *)USERSPACE->us_datasource; + dest = (uint8_t *)USERSPACE->us_datastart; + end = (uint8_t *)USERSPACE->us_dataend; + + while (dest != end) + { + *dest++ = *src++; + } + + /* Configure the MPU to permit user-space access to its FLASH and RAM */ + + xmc4_mpuinitialize(); +} + +#endif /* CONFIG_BUILD_PROTECTED */ + diff --git a/arch/arm/src/xmc4/xmc4_userspace.h b/arch/arm/src/xmc4/xmc4_userspace.h new file mode 100644 index 0000000000..661982c8f9 --- /dev/null +++ b/arch/arm/src/xmc4/xmc4_userspace.h @@ -0,0 +1,64 @@ +/************************************************************************************ + * arch/arm/src/xmc4/xmc4_userspace.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_XMC4_XMC4_USERSPACE_H +#define __ARCH_ARM_SRC_XMC4_XMC4_USERSPACE_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/**************************************************************************** + * Name: xmc4_userspace + * + * Description: + * For the case of the separate user-/kernel-space build, perform whatever + * platform specific initialization of the user memory is required. + * Normally this just means initializing the user space .data and .bss + * segments. + * + ****************************************************************************/ + +#ifdef CONFIG_BUILD_PROTECTED +void xmc4_userspace(void); +#endif + +#endif /* __ARCH_ARM_SRC_XMC4_XMC4_USERSPACE_H */ -- GitLab From 2430049e3b5496c91f70ccfaa306c9b0f5878abe Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 14 Mar 2017 13:04:09 -0600 Subject: [PATCH 040/990] arch/arm/include/xmc4: More support for Infineon XMC4xxx arch. Still incomplete. --- arch/arm/include/xmc4/chip.h | 130 ++++++++++++++++ arch/arm/include/xmc4/irq.h | 120 +++++++++++++++ arch/arm/include/xmc4/xmc4500_irq.h | 225 ++++++++++++++++++++++++++++ 3 files changed, 475 insertions(+) create mode 100644 arch/arm/include/xmc4/chip.h create mode 100644 arch/arm/include/xmc4/irq.h create mode 100644 arch/arm/include/xmc4/xmc4500_irq.h diff --git a/arch/arm/include/xmc4/chip.h b/arch/arm/include/xmc4/chip.h new file mode 100644 index 0000000000..7ea5157a73 --- /dev/null +++ b/arch/arm/include/xmc4/chip.h @@ -0,0 +1,130 @@ +/************************************************************************************ + * arch/arm/include/xmc4/chip.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_INCLUDE_XM4_CHIP_H +#define __ARCH_ARM_INCLUDE_XM4_CHIP_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Get customizations for each supported chip */ + +#if defined(CONFIG_ARCH_XMC4500) +# define XM4_NUSIC 3 /* Three USIC modules: USCI0-2 */ + +#else +# error "Unsupported XMC4000 chip" +#endif + +/* NVIC priority levels *************************************************************/ +/* Each priority field holds a priority value, 0-15. The lower the value, the greater + * the priority of the corresponding interrupt. The XMC4500 implements only + * bits[7:2] of this field, bits[1:0] read as zero and ignore writes. + */ + +#define NVIC_SYSH_PRIORITY_MIN 0xfc /* All bits[7:2] set is minimum priority */ +#define NVIC_SYSH_PRIORITY_DEFAULT 0x80 /* Midpoint is the default */ +#define NVIC_SYSH_PRIORITY_MAX 0x00 /* Zero is maximum priority */ +#define NVIC_SYSH_PRIORITY_STEP 0x04 /* Steps between supported priority values */ + +/* If CONFIG_ARMV7M_USEBASEPRI is selected, then interrupts will be disabled + * by setting the BASEPRI register to NVIC_SYSH_DISABLE_PRIORITY so that most + * interrupts will not have execution priority. SVCall must have execution + * priority in all cases. + * + * In the normal cases, interrupts are not nest-able and all interrupts run + * at an execution priority between NVIC_SYSH_PRIORITY_MIN and + * NVIC_SYSH_PRIORITY_MAX (with NVIC_SYSH_PRIORITY_MAX reserved for SVCall). + * + * If, in addition, CONFIG_ARCH_HIPRI_INTERRUPT is defined, then special + * high priority interrupts are supported. These are not "nested" in the + * normal sense of the word. These high priority interrupts can interrupt + * normal processing but execute outside of OS (although they can "get back + * into the game" via a PendSV interrupt). + * + * In the normal course of things, interrupts must occasionally be disabled + * using the up_irq_save() inline function to prevent contention in use of + * resources that may be shared between interrupt level and non-interrupt + * level logic. Now the question arises, if CONFIG_ARCH_HIPRI_INTERRUPT, + * do we disable all interrupts (except SVCall), or do we only disable the + * "normal" interrupts. Since the high priority interrupts cannot interact + * with the OS, you may want to permit the high priority interrupts even if + * interrupts are disabled. The setting CONFIG_ARCH_INT_DISABLEALL can be + * used to select either behavior: + * + * ----------------------------+--------------+---------------------------- + * CONFIG_ARCH_HIPRI_INTERRUPT | NO | YES + * ----------------------------+--------------+--------------+------------- + * CONFIG_ARCH_INT_DISABLEALL | N/A | YES | NO + * ----------------------------+--------------+--------------+------------- + * | | | SVCall + * | SVCall | SVCall | HIGH + * Disable here and below --------> MAXNORMAL ---> HIGH --------> MAXNORMAL + * | | MAXNORMAL | + * ----------------------------+--------------+--------------+------------- + */ + +#if defined(CONFIG_ARCH_HIPRI_INTERRUPT) && defined(CONFIG_ARCH_INT_DISABLEALL) +# define NVIC_SYSH_MAXNORMAL_PRIORITY (NVIC_SYSH_PRIORITY_MAX + 2*NVIC_SYSH_PRIORITY_STEP) +# define NVIC_SYSH_HIGH_PRIORITY (NVIC_SYSH_PRIORITY_MAX + NVIC_SYSH_PRIORITY_STEP) +# define NVIC_SYSH_DISABLE_PRIORITY NVIC_SYSH_HIGH_PRIORITY +# define NVIC_SYSH_SVCALL_PRIORITY NVIC_SYSH_PRIORITY_MAX +#else +# define NVIC_SYSH_MAXNORMAL_PRIORITY (NVIC_SYSH_PRIORITY_MAX + NVIC_SYSH_PRIORITY_STEP) +# define NVIC_SYSH_HIGH_PRIORITY NVIC_SYSH_PRIORITY_MAX +# define NVIC_SYSH_DISABLE_PRIORITY NVIC_SYSH_MAXNORMAL_PRIORITY +# define NVIC_SYSH_SVCALL_PRIORITY NVIC_SYSH_PRIORITY_MAX +#endif + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +#endif /* __ARCH_ARM_INCLUDE_XM4_CHIP_H */ diff --git a/arch/arm/include/xmc4/irq.h b/arch/arm/include/xmc4/irq.h new file mode 100644 index 0000000000..65300dcee3 --- /dev/null +++ b/arch/arm/include/xmc4/irq.h @@ -0,0 +1,120 @@ +/**************************************************************************** + * arch/arm/include/xmc4/irq.h + * + * 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. + * + ****************************************************************************/ + +/* This file should never be included directed but, rather, only indirectly + * through nuttx/irq.h + */ + +#ifndef __ARCH_ARM_INCLUDE_XM4_IRQ_H +#define __ARCH_ARM_INCLUDE_XM4_IRQ_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* IRQ numbers. The IRQ number corresponds vector number and hence map directly to + * bits in the NVIC. This does, however, waste several words of memory in the IRQ + * to handle mapping tables. + */ + +/* Processor Exceptions (vectors 0-15) */ + +#define XM4_IRQ_RESERVED (0) /* Reserved vector (only used with CONFIG_DEBUG_FEATURES) */ + /* Vector 0: Reset stack pointer value */ + /* Vector 1: Reset (not handler as an IRQ) */ +#define XM4_IRQ_NMI (2) /* Vector 2: Non-Maskable Interrupt (NMI) */ +#define XM4_IRQ_HARDFAULT (3) /* Vector 3: Hard fault */ +#define XM4_IRQ_MEMFAULT (4) /* Vector 4: Memory management (MPU) */ +#define XM4_IRQ_BUSFAULT (5) /* Vector 5: Bus fault */ +#define XM4_IRQ_USAGEFAULT (6) /* Vector 6: Usage fault */ + /* Vectors 7-10: Reserved */ +#define XM4_IRQ_SVCALL (11) /* Vector 11: SVC call */ +#define XM4_IRQ_DBGMONITOR (12) /* Vector 12: Debug Monitor */ + /* Vector 13: Reserved */ +#define XM4_IRQ_PENDSV (14) /* Vector 14: Pendable system service request */ +#define XM4_IRQ_SYSTICK (15) /* Vector 15: System tick */ + +/* External interrupts (vectors >= 16). These definitions are chip-specific */ + +#define XM4_IRQ_FIRST (16) /* Vector number of the first external interrupt */ + +#if defined(CONFIG_ARCH_XMC4500) +# include +#else + /* The interrupt vectors for other parts are defined in other documents and may or + * may not be the same as above (the family members are all very similar) This + * error just means that you have to look at the document and determine for yourself + * if the vectors are the same. + */ + +# error "No IRQ numbers for this XMC4xxx part" +#endif + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +#ifndef __ASSEMBLY__ +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +#undef EXTERN +#ifdef __cplusplus +} +#endif +#endif + +#endif /* __ARCH_ARM_INCLUDE_XM4_IRQ_H */ + diff --git a/arch/arm/include/xmc4/xmc4500_irq.h b/arch/arm/include/xmc4/xmc4500_irq.h new file mode 100644 index 0000000000..1005adeb49 --- /dev/null +++ b/arch/arm/include/xmc4/xmc4500_irq.h @@ -0,0 +1,225 @@ +/***************************************************************************** + * arch/arm/include/xmc4/xmc4500_.h + * + * 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. + * + ****************************************************************************/ + +/* This file should never be included directed but, rather, only indirectly + * through nuttx/irq.h + */ + +#ifndef xmc4__ARCH_ARM_INCLUDE_XM4_XM4500_IRQ_H +#define xmc4__ARCH_ARM_INCLUDE_XM4_XM4500_IRQ_H + +/***************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/***************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* IRQ numbers. The IRQ number corresponds vector number and hence map + * directly to bits in the NVIC. This does, however, waste several words of + * memory in the IRQ to handle mapping tables. + * + * Processor Exceptions (vectors 0-15). These common definitions can be found + * in the file nuttx/arch/arm/include/kinets/irq.h which includes this file + * + * External interrupts (vectors >= 16) + * + * Acronyms: + * ADC - Analog to Digital Converter + * CCU - Capture Compare Unit + * DAC - Digital to Analog Converter + * DSD - Delta Sigmoid Demodulator + * ERU - External Request Unit + * FCE - Flexible CRC Engine + * GPDMA - General Purpose DMA + * LEDTS - LED and Touch Sense Control Unit + * PMU - Program Management Unit + * POSIF - Position Interface + * SDMMC - Multi Media Card Interface + * USB - Universal Serial Bus + * USCI - Universal Serial Interface + */ + +#define XM4_IRQ_SCU (XM4_IRQ_FIRST+0) /* 0: System Control */ +#define XM4_IRQ_ERU0_SR0 (XM4_IRQ_FIRST+1) /* 1: ERU0, SR0 */ +#define XM4_IRQ_ERU0_SR1 (XM4_IRQ_FIRST+2) /* 2: ERU0, SR1 */ +#define XM4_IRQ_ERU0_SR2 (XM4_IRQ_FIRST+3) /* 3: ERU0, SR2 */ +#define XM4_IRQ_ERU0_SR3 (XM4_IRQ_FIRST+4) /* 4: ERU0, SR3 */ +#define XM4_IRQ_ERU1_SR0 (XM4_IRQ_FIRST+5) /* 5: ERU1, SR0 */ +#define XM4_IRQ_ERU1_SR1 (XM4_IRQ_FIRST+6) /* 6: ERU1, SR1 */ +#define XM4_IRQ_ERU1_SR2 (XM4_IRQ_FIRST+7) /* 7: ERU1, SR2 */ +#define XM4_IRQ_ERU1_SR3 (XM4_IRQ_FIRST+8) /* 8: ERU1, SR3 */ +#define XM4_IRQ_RESVD009 (XM4_IRQ_FIRST+9) /* 9: Reserved */ +#define XM4_IRQ_RESVD010 (XM4_IRQ_FIRST+10) /* 10: Reserved */ +#define XM4_IRQ_RESVD011 (XM4_IRQ_FIRST+11) /* 11: Reserved */ +#define XM4_IRQ_PMU1_SR0 (XM4_IRQ_FIRST+12) /* 12: PMU, SR0 */ +#define XM4_IRQ_RESVD011 (XM4_IRQ_FIRST+13) /* 13: Reserved */ +#define XM4_IRQ_VADC_COSR0 (XM4_IRQ_FIRST+14) /* 14: ADC Common Block 0 */ +#define XM4_IRQ_VADC_COSR1 (XM4_IRQ_FIRST+15) /* 15: ADC Common Block 1 */ +#define XM4_IRQ_VADC_COSR2 (XM4_IRQ_FIRST+16) /* 16: ADC Common Block 2 */ +#define XM4_IRQ_VADC_COSR3 (XM4_IRQ_FIRST+17) /* 17: ADC Common Block 3 */ +#define XM4_IRQ_VADC_GOSR0 (XM4_IRQ_FIRST+18) /* 18: ADC Group 0, SR0 */ +#define XM4_IRQ_VADC_GOSR1 (XM4_IRQ_FIRST+19) /* 19: ADC Group 0, SR1 */ +#define XM4_IRQ_VADC_GOSR2 (XM4_IRQ_FIRST+20) /* 20: ADC Group 0, SR2 */ +#define XM4_IRQ_VADC_GOSR3 (XM4_IRQ_FIRST+21) /* 21: ADC Group 0, SR3 */ +#define XM4_IRQ_VADC_G1SR0 (XM4_IRQ_FIRST+22) /* 22: ADC Group 1, SR0 */ +#define XM4_IRQ_VADC_G1SR1 (XM4_IRQ_FIRST+23) /* 23: ADC Group 1, SR1 */ +#define XM4_IRQ_VADC_G1SR2 (XM4_IRQ_FIRST+24) /* 24: ADC Group 1, SR2 */ +#define XM4_IRQ_VADC_G1SR3 (XM4_IRQ_FIRST+25) /* 25: ADC Group 1, SR3 */ +#define XM4_IRQ_VADC_G2SR0 (XM4_IRQ_FIRST+26) /* 26: ADC Group 2, SR0 */ +#define XM4_IRQ_VADC_G2SR1 (XM4_IRQ_FIRST+27) /* 27: ADC Group 2, SR1 */ +#define XM4_IRQ_VADC_G2SR2 (XM4_IRQ_FIRST+28) /* 28: ADC Group 2, SR2 */ +#define XM4_IRQ_VADC_G2SR3 (XM4_IRQ_FIRST+29) /* 29: ADC Group 2, SR3 */ +#define XM4_IRQ_VADC_G3SR0 (XM4_IRQ_FIRST+30) /* 30: ADC Group 3, SR0 */ +#define XM4_IRQ_VADC_G3SR1 (XM4_IRQ_FIRST+31) /* 31: ADC Group 3, SR1 */ +#define XM4_IRQ_VADC_G3SR2 (XM4_IRQ_FIRST+32) /* 32: ADC Group 3, SR2 */ +#define XM4_IRQ_VADC_G3SR3 (XM4_IRQ_FIRST+33) /* 33: ADC Group 3, SR3 */ +#define XM4_IRQ_DSD_SRM0 (XM4_IRQ_FIRST+34) /* 34: DSD Main, SRM0 */ +#define XM4_IRQ_DSD_SRM1 (XM4_IRQ_FIRST+35) /* 35: DSD Main, SRM1 */ +#define XM4_IRQ_DSD_SRM2 (XM4_IRQ_FIRST+36) /* 36: DSD Main, SRM2 */ +#define XM4_IRQ_DSD_SRM3 (XM4_IRQ_FIRST+37) /* 37: DSD Main, SRM3 */ +#define XM4_IRQ_DSD_SRA0 (XM4_IRQ_FIRST+38) /* 38: DSD Auxiliary, SRA0 */ +#define XM4_IRQ_DSD_SRA1 (XM4_IRQ_FIRST+39) /* 39: DSD Auxiliary, SRA1 */ +#define XM4_IRQ_DSD_SRA2 (XM4_IRQ_FIRST+40) /* 40: DSD Auxiliary, SRA2 */ +#define XM4_IRQ_DSD_SRA3 (XM4_IRQ_FIRST+41) /* 41: DSD Auxiliary, SRA3 */ +#define XM4_IRQ_DAC_SR0 (XM4_IRQ_FIRST+42) /* 42: DAC, SR0 */ +#define XM4_IRQ_DAC_SR1 (XM4_IRQ_FIRST+43) /* 43: DAC, SR1 */ +#define XM4_IRQ_CCU40_SR0 (XM4_IRQ_FIRST+44) /* 44: CCU4 Module 0, SR0 */ +#define XM4_IRQ_CCU40_SR1 (XM4_IRQ_FIRST+45) /* 45: CCU4 Module 0, SR1 */ +#define XM4_IRQ_CCU40_SR2 (XM4_IRQ_FIRST+46) /* 46: CCU4 Module 0, SR2 */ +#define XM4_IRQ_CCU40_SR3 (XM4_IRQ_FIRST+47) /* 47: CCU4 Module 0, SR3 */ +#define XM4_IRQ_CCU41_SR0 (XM4_IRQ_FIRST+48) /* 48: CCU4 Module 1, SR0 */ +#define XM4_IRQ_CCU41_SR1 (XM4_IRQ_FIRST+49) /* 49: CCU4 Module 1, SR1 */ +#define XM4_IRQ_CCU41_SR2 (XM4_IRQ_FIRST+50) /* 50: CCU4 Module 1, SR2 */ +#define XM4_IRQ_CCU41_SR3 (XM4_IRQ_FIRST+51) /* 51: CCU4 Module 1, SR3 */ +#define XM4_IRQ_CCU42_SR0 (XM4_IRQ_FIRST+52) /* 52: CCU4 Module 2, SR0 */ +#define XM4_IRQ_CCU42_SR1 (XM4_IRQ_FIRST+53) /* 53: CCU4 Module 2, SR1 */ +#define XM4_IRQ_CCU42_SR2 (XM4_IRQ_FIRST+54) /* 54: CCU4 Module 2, SR2 */ +#define XM4_IRQ_CCU42_SR3 (XM4_IRQ_FIRST+55) /* 55: CCU4 Module 2, SR3 */ +#define XM4_IRQ_CCU43_SR0 (XM4_IRQ_FIRST+56) /* 56: CCU4 Module 3, SR0 */ +#define XM4_IRQ_CCU43_SR1 (XM4_IRQ_FIRST+57) /* 57: CCU4 Module 3, SR1 */ +#define XM4_IRQ_CCU43_SR2 (XM4_IRQ_FIRST+58) /* 58: CCU4 Module 3, SR2 */ +#define XM4_IRQ_CCU43_SR3 (XM4_IRQ_FIRST+59) /* 59: CCU4 Module 3, SR3 */ +#define XM4_IRQ_CCU80_SR0 (XM4_IRQ_FIRST+60) /* 60: CCU8 Module 0, SR0 */ +#define XM4_IRQ_CCU80_SR1 (XM4_IRQ_FIRST+61) /* 61: CCU8 Module 0, SR1 */ +#define XM4_IRQ_CCU80_SR2 (XM4_IRQ_FIRST+62) /* 62: CCU8 Module 0, SR2 */ +#define XM4_IRQ_CCU80_SR3 (XM4_IRQ_FIRST+63) /* 63: CCU8 Module 0, SR3 */ +#define XM4_IRQ_CCU81_SR0 (XM4_IRQ_FIRST+64) /* 64: CCU8 Module 1, SR0 */ +#define XM4_IRQ_CCU81_SR1 (XM4_IRQ_FIRST+65) /* 65: CCU8 Module 1, SR1 */ +#define XM4_IRQ_CCU81_SR2 (XM4_IRQ_FIRST+66) /* 66: CCU8 Module 1, SR2 */ +#define XM4_IRQ_CCU81_SR3 (XM4_IRQ_FIRST+67) /* 67: CCU8 Module 1, SR3 */ +#define XM4_IRQ_POSIF0_SR0 (XM4_IRQ_FIRST+68) /* 68: POSIF Module 0, SR0 */ +#define XM4_IRQ_POSIF0_SR1 (XM4_IRQ_FIRST+69) /* 69: POSIF Module 0, SR1 */ +#define XM4_IRQ_POSIF1_SR0 (XM4_IRQ_FIRST+70) /* 70: POSIF Module 1, SR0 */ +#define XM4_IRQ_POSIF1_SR1 (XM4_IRQ_FIRST+71) /* 71: POSIF Module 1, SR1 */ +#define XM4_IRQ_RESVD072 (XM4_IRQ_FIRST+72) /* 72: Reserved */ +#define XM4_IRQ_RESVD073 (XM4_IRQ_FIRST+73) /* 73: Reserved */ +#define XM4_IRQ_RESVD074 (XM4_IRQ_FIRST+74) /* 74: Reserved */ +#define XM4_IRQ_RESVD075 (XM4_IRQ_FIRST+75) /* 75: Reserved */ +#define XM4_IRQ_CAN_SR0 (XM4_IRQ_FIRST+76) /* 76: MultiCAN, SR0 */ +#define XM4_IRQ_CAN_SR1 (XM4_IRQ_FIRST+77) /* 77: MultiCAN, SR1 */ +#define XM4_IRQ_CAN_SR2 (XM4_IRQ_FIRST+78) /* 78: MultiCAN, SR2 */ +#define XM4_IRQ_CAN_SR3 (XM4_IRQ_FIRST+79) /* 79: MultiCAN, SR3 */ +#define XM4_IRQ_CAN_SR4 (XM4_IRQ_FIRST+80) /* 80: MultiCAN, SR4 */ +#define XM4_IRQ_CAN_SR5 (XM4_IRQ_FIRST+81) /* 81: MultiCAN, SR5 */ +#define XM4_IRQ_CAN_SR6 (XM4_IRQ_FIRST+82) /* 82: MultiCAN, SR6 */ +#define XM4_IRQ_CAN_SR7 (XM4_IRQ_FIRST+83) /* 83: MultiCAN, SR7 */ +#define XM4_IRQ_USIC0_SR0 (XM4_IRQ_FIRST+84) /* 84: USIC0 Channel, SR0 */ +#define XM4_IRQ_USIC0_SR1 (XM4_IRQ_FIRST+85) /* 85: USIC0 Channel, SR1 */ +#define XM4_IRQ_USIC0_SR2 (XM4_IRQ_FIRST+86) /* 86: USIC0 Channel, SR2 */ +#define XM4_IRQ_USIC0_SR3 (XM4_IRQ_FIRST+87) /* 87: USIC0 Channel, SR3 */ +#define XM4_IRQ_USIC0_SR4 (XM4_IRQ_FIRST+88) /* 88: USIC0 Channel, SR4 */ +#define XM4_IRQ_USIC0_SR5 (XM4_IRQ_FIRST+89) /* 89: USIC0 Channel, SR5 */ +#define XM4_IRQ_USIC1_SR0 (XM4_IRQ_FIRST+90) /* 90: USIC1 Channel, SR0 */ +#define XM4_IRQ_USIC1_SR1 (XM4_IRQ_FIRST+91) /* 91: USIC1 Channel, SR1 */ +#define XM4_IRQ_USIC1_SR2 (XM4_IRQ_FIRST+92) /* 92: USIC1 Channel, SR2 */ +#define XM4_IRQ_USIC1_SR3 (XM4_IRQ_FIRST+93) /* 93: USIC1 Channel, SR3 */ +#define XM4_IRQ_USIC1_SR4 (XM4_IRQ_FIRST+94) /* 94: USIC1 Channel, SR4 */ +#define XM4_IRQ_USIC1_SR5 (XM4_IRQ_FIRST+95) /* 95: USIC1 Channel, SR5 */ +#define XM4_IRQ_USIC2_SR0 (XM4_IRQ_FIRST+96) /* 96: USIC1 Channel, SR0 */ +#define XM4_IRQ_USIC2_SR1 (XM4_IRQ_FIRST+97) /* 97: USIC1 Channel, SR1 */ +#define XM4_IRQ_USIC2_SR2 (XM4_IRQ_FIRST+98) /* 98: USIC1 Channel, SR2 */ +#define XM4_IRQ_USIC2_SR3 (XM4_IRQ_FIRST+99) /* 99: USIC1 Channel, SR3 */ +#define XM4_IRQ_USIC2_SR4 (XM4_IRQ_FIRST+100) /* 100: USIC1 Channel, SR4 */ +#define XM4_IRQ_USIC2_SR5 (XM4_IRQ_FIRST+101) /* 101: USIC1 Channel, SR5 */ +#define XM4_IRQ_LEDTS0_SR0 (XM4_IRQ_FIRST+102) /* 102: LEDTS0, SR0 */ +#define XM4_IRQ_RESVD103 (XM4_IRQ_FIRST+103) /* 103: Reserved */ +#define XM4_IRQ_FCR_SR0 (XM4_IRQ_FIRST+104) /* 102: FCE, SR0 */ +#define XM4_IRQ_GPCMA0_SR0 (XM4_IRQ_FIRST+105) /* 105: GPDMA0, SR0 */ +#define XM4_IRQ_SDMMC_SR0 (XM4_IRQ_FIRST+106) /* 106: SDMMC, SR0 */ +#define XM4_IRQ_USB0_SR0 (XM4_IRQ_FIRST+107) /* 107: USB, SR0 */ +#define XM4_IRQ_ETH0_SR0 (XM4_IRQ_FIRST+108) /* 108: Ethernet, module 0, SR0 */ +#define XM4_IRQ_RESVD109 (XM4_IRQ_FIRST+109) /* 109: Reserved */ +#define XM4_IRQ_GPCMA1_SR0 (XM4_IRQ_FIRST+110) /* 110: GPDMA1, SR0 */ +#define XM4_IRQ_RESVD111 (XM4_IRQ_FIRST+111) /* 111: Reserved */ + +#define NR_INTERRUPTS 112 /* 112 Non core IRQs*/ +#define NR_VECTORS (XM4_IRQ_FIRST+NR_INTERRUPTS) /* 118 vectors */ + +/* GPIO IRQ interrupts -- To be provided */ + +#define NR_IRQS NR_VECTORS + +/***************************************************************************** + * Public Types + ****************************************************************************/ + +/***************************************************************************** + * Public Data + ****************************************************************************/ + +#ifndef __ASSEMBLY__ +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/***************************************************************************** + * Public Functions + ****************************************************************************/ + +#undef EXTERN +#ifdef __cplusplus +} +#endif +#endif + +#endif /* xmc4__ARCH_ARM_INCLUDE_XM4_XM4500_IRQ_H */ -- GitLab From e1039128a48af86d55633ad6e029cc300e150921 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 14 Mar 2017 13:05:06 -0600 Subject: [PATCH 041/990] Update TODO --- TODO | 18 ++++++++++++++++-- 1 file changed, 16 insertions(+), 2 deletions(-) diff --git a/TODO b/TODO index 56fb52199f..ad47655bf4 100644 --- a/TODO +++ b/TODO @@ -1,4 +1,4 @@ -NuttX TODO List (Last updated March 7, 2017) +NuttX TODO List (Last updated March 14, 2017) ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ This file summarizes known NuttX bugs, limitations, inconsistencies with @@ -19,7 +19,7 @@ nuttx/: (8) Kernel/Protected Build (3) C++ Support (6) Binary loaders (binfmt/) - (13) Network (net/, drivers/net) + (14) Network (net/, drivers/net) (4) USB (drivers/usbdev, drivers/usbhost) (0) Other drivers (drivers/) (12) Libraries (libc/, libm/) @@ -1065,6 +1065,20 @@ o Network (net/, drivers/net) Status: Open Priority: High if you happen to be using Ethernet in this configuration. + Title: REPARTITION DRIVER FUNCTIONALITY + Description: Every network driver performs the first level of packet decoding. + It examines the packet header and calls ipv4_input(), ipv6_input(). + icmp_input(), etc. as appropriate. This is a maintenance problem + because it means that any changes to the network input interfaces + affects all drivers. + + A better, more maintainable solution would use a single net_input() + function that would receive all incoming packets. This function + would then perform that common packet decoding logic that is + currently implemented in every network driver. + Status: Open + Priority: Low. Really just as aesthetic maintainability issue. + o USB (drivers/usbdev, drivers/usbhost) ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -- GitLab From bf9391a1fe24147c07bf6c7a572e20d3d1a7de23 Mon Sep 17 00:00:00 2001 From: Simon Piriou Date: Tue, 14 Mar 2017 21:06:19 +0100 Subject: [PATCH 042/990] photon: porting wlan device --- arch/arm/src/stm32/stm32_sdio.c | 81 +- config_wlan | 1355 +++++++++++++++++++ configs/photon/src/stm32_wlan.c | 20 + drivers/wireless/ieee80211/Make.defs | 1 + drivers/wireless/ieee80211/bcmf_sdio.c | 244 +++- drivers/wireless/ieee80211/mmc_sdio.c | 355 +++++ include/nuttx/sdio.h | 38 + include/nuttx/wireless/ieee80211/mmc_sdio.h | 26 + 8 files changed, 2081 insertions(+), 39 deletions(-) create mode 100644 config_wlan create mode 100644 drivers/wireless/ieee80211/mmc_sdio.c create mode 100644 include/nuttx/wireless/ieee80211/mmc_sdio.h diff --git a/arch/arm/src/stm32/stm32_sdio.c b/arch/arm/src/stm32/stm32_sdio.c index 01d533ba70..7a7cfae725 100644 --- a/arch/arm/src/stm32/stm32_sdio.c +++ b/arch/arm/src/stm32/stm32_sdio.c @@ -300,6 +300,8 @@ # endif #endif +#define STM32_SDIO_USE_DEFAULT_BLOCK_SIZE ((uint8_t)-1) + /**************************************************************************** * Private Types ****************************************************************************/ @@ -333,6 +335,12 @@ struct stm32_dev_s size_t remaining; /* Number of bytes remaining in the transfer */ uint32_t xfrmask; /* Interrupt enables for data transfer */ + /* Fixed transfer block size support */ + +#ifdef CONFIG_SDIO_BLOCKSETUP + uint8_t block_size; +#endif + /* DMA data transfer support */ bool widebus; /* Required for DMA support */ @@ -443,6 +451,10 @@ static int stm32_attach(FAR struct sdio_dev_s *dev); static int stm32_sendcmd(FAR struct sdio_dev_s *dev, uint32_t cmd, uint32_t arg); +#ifdef CONFIG_SDIO_BLOCKSETUP +static void stm32_blocksetup(FAR struct sdio_dev_s *dev, + unsigned int blocklen, unsigned int nblocks); +#endif static int stm32_recvsetup(FAR struct sdio_dev_s *dev, FAR uint8_t *buffer, size_t nbytes); static int stm32_sendsetup(FAR struct sdio_dev_s *dev, @@ -507,7 +519,7 @@ struct stm32_dev_s g_sdiodev = .attach = stm32_attach, .sendcmd = stm32_sendcmd, #ifdef CONFIG_SDIO_BLOCKSETUP - .blocksetup = stm32_blocksetup, /* Not implemented yet */ + .blocksetup = stm32_blocksetup, #endif .recvsetup = stm32_recvsetup, .sendsetup = stm32_sendsetup, @@ -516,8 +528,8 @@ struct stm32_dev_s g_sdiodev = .recvR1 = stm32_recvshortcrc, .recvR2 = stm32_recvlong, .recvR3 = stm32_recvshort, - .recvR4 = stm32_recvnotimpl, - .recvR5 = stm32_recvnotimpl, + .recvR4 = stm32_recvshort, + .recvR5 = stm32_recvshortcrc, .recvR6 = stm32_recvshortcrc, .recvR7 = stm32_recvshort, .waitenable = stm32_waitenable, @@ -1865,6 +1877,34 @@ static int stm32_sendcmd(FAR struct sdio_dev_s *dev, uint32_t cmd, uint32_t arg) return OK; } +/**************************************************************************** + * Name: stm32_blocksetup + * + * Description: + * Configure block size and the number of blocks for next transfer + * + * Input Parameters: + * dev - An instance of the SDIO device interface + * blocklen - The selected block size. + * nblocklen - The number of blocks to transfer + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_SDIO_BLOCKSETUP +static void stm32_blocksetup(FAR struct sdio_dev_s *dev, + unsigned int blocklen, unsigned int nblocks) +{ + struct stm32_dev_s *priv = (struct stm32_dev_s *)dev; + + /* Configure block size for next transfer */ + + priv->block_size = stm32_log2(blocklen); +} +#endif + /**************************************************************************** * Name: stm32_recvsetup * @@ -1911,7 +1951,17 @@ static int stm32_recvsetup(FAR struct sdio_dev_s *dev, FAR uint8_t *buffer, /* Then set up the SDIO data path */ - dblocksize = stm32_log2(nbytes) << SDIO_DCTRL_DBLOCKSIZE_SHIFT; +#ifdef CONFIG_SDIO_BLOCKSETUP + if (priv->block_size != STM32_SDIO_USE_DEFAULT_BLOCKSIZE) + { + dblocksize = priv->block_size << SDIO_DCTRL_DBLOCKSIZE_SHIFT; + } + else +#endif + { + dblocksize = stm32_log2(nbytes) << SDIO_DCTRL_DBLOCKSIZE_SHIFT; + } + stm32_dataconfig(SDIO_DTIMER_DATATIMEOUT, nbytes, dblocksize | SDIO_DCTRL_DTDIR); /* And enable interrupts */ @@ -1965,7 +2015,17 @@ static int stm32_sendsetup(FAR struct sdio_dev_s *dev, FAR const uint8_t *buffer /* Then set up the SDIO data path */ - dblocksize = stm32_log2(nbytes) << SDIO_DCTRL_DBLOCKSIZE_SHIFT; +#ifdef CONFIG_SDIO_BLOCKSETUP + if (priv->block_size != STM32_SDIO_USE_DEFAULT_BLOCKSIZE) + { + dblocksize = priv->block_size << SDIO_DCTRL_DBLOCKSIZE_SHIFT; + } + else +#endif + { + dblocksize = stm32_log2(nbytes) << SDIO_DCTRL_DBLOCKSIZE_SHIFT; + } + stm32_dataconfig(SDIO_DTIMER_DATATIMEOUT, nbytes, dblocksize); /* Enable TX interrupts */ @@ -2061,15 +2121,13 @@ static int stm32_waitresponse(FAR struct sdio_dev_s *dev, uint32_t cmd) case MMCSD_R1_RESPONSE: case MMCSD_R1B_RESPONSE: case MMCSD_R2_RESPONSE: + case MMCSD_R4_RESPONSE: + case MMCSD_R5_RESPONSE: case MMCSD_R6_RESPONSE: events = SDIO_RESPDONE_STA; timeout = SDIO_LONGTIMEOUT; break; - case MMCSD_R4_RESPONSE: - case MMCSD_R5_RESPONSE: - return -ENOSYS; - case MMCSD_R3_RESPONSE: case MMCSD_R7_RESPONSE: events = SDIO_RESPDONE_STA; @@ -2161,6 +2219,7 @@ static int stm32_recvshortcrc(FAR struct sdio_dev_s *dev, uint32_t cmd, uint32_t else if ((cmd & MMCSD_RESPONSE_MASK) != MMCSD_R1_RESPONSE && (cmd & MMCSD_RESPONSE_MASK) != MMCSD_R1B_RESPONSE && + (cmd & MMCSD_RESPONSE_MASK) != MMCSD_R5_RESPONSE && (cmd & MMCSD_RESPONSE_MASK) != MMCSD_R6_RESPONSE) { mcerr("ERROR: Wrong response CMD=%08x\n", cmd); @@ -2201,6 +2260,7 @@ static int stm32_recvshortcrc(FAR struct sdio_dev_s *dev, uint32_t cmd, uint32_t putreg32(SDIO_RESPDONE_ICR | SDIO_CMDDONE_ICR, STM32_SDIO_ICR); *rshort = getreg32(STM32_SDIO_RESP1); + mcinfo("data: %08x %08x\n", *rshort, respcmd); return ret; } @@ -2276,6 +2336,7 @@ static int stm32_recvshort(FAR struct sdio_dev_s *dev, uint32_t cmd, uint32_t *r #ifdef CONFIG_DEBUG_MEMCARD_INFO if ((cmd & MMCSD_RESPONSE_MASK) != MMCSD_R3_RESPONSE && + (cmd & MMCSD_RESPONSE_MASK) != MMCSD_R4_RESPONSE && (cmd & MMCSD_RESPONSE_MASK) != MMCSD_R7_RESPONSE) { mcerr("ERROR: Wrong response CMD=%08x\n", cmd); @@ -2300,7 +2361,9 @@ static int stm32_recvshort(FAR struct sdio_dev_s *dev, uint32_t cmd, uint32_t *r if (rshort) { *rshort = getreg32(STM32_SDIO_RESP1); + mcinfo("data: %08x\n", *rshort); } + return ret; } diff --git a/config_wlan b/config_wlan new file mode 100644 index 0000000000..9e025fe2d9 --- /dev/null +++ b/config_wlan @@ -0,0 +1,1355 @@ +# +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# + +# +# Build Setup +# +CONFIG_EXPERIMENTAL=y +# CONFIG_DEFAULT_SMALL is not set +CONFIG_HOST_LINUX=y +# CONFIG_HOST_OSX is not set +# CONFIG_HOST_WINDOWS is not set +# CONFIG_HOST_OTHER is not set + +# +# Build Configuration +# +CONFIG_APPS_DIR="../apps" +CONFIG_BUILD_FLAT=y +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +CONFIG_INTELHEX_BINARY=y +# CONFIG_MOTOROLA_SREC is not set +CONFIG_RAW_BINARY=y +# CONFIG_UBOOT_UIMAGE is not set + +# +# Customize Header Files +# +# CONFIG_ARCH_STDINT_H is not set +# CONFIG_ARCH_STDBOOL_H is not set +# CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_FLOAT_H is not set +# CONFIG_ARCH_STDARG_H is not set +# CONFIG_ARCH_DEBUG_H is not set + +# +# Debug Options +# +CONFIG_DEBUG_ALERT=y +CONFIG_DEBUG_FEATURES=y + +# +# Debug SYSLOG Output Controls +# +CONFIG_DEBUG_ERROR=y +CONFIG_DEBUG_WARN=y +CONFIG_DEBUG_INFO=y +# CONFIG_DEBUG_ASSERTIONS is not set + +# +# Subsystem Debug Options +# +# CONFIG_DEBUG_BINFMT is not set +# CONFIG_DEBUG_FS is not set +# CONFIG_DEBUG_GRAPHICS is not set +# CONFIG_DEBUG_LIB is not set +# CONFIG_DEBUG_MM is not set +# CONFIG_DEBUG_SCHED is not set + +# +# OS Function Debug Options +# +# CONFIG_DEBUG_IRQ is not set + +# +# Driver Debug Options +# +# CONFIG_DEBUG_LEDS is not set +# CONFIG_DEBUG_GPIO is not set +CONFIG_DEBUG_MEMCARD=y +CONFIG_DEBUG_MEMCARD_ERROR=y +CONFIG_DEBUG_MEMCARD_WARN=y +CONFIG_DEBUG_MEMCARD_INFO=y +# CONFIG_DEBUG_TIMER is not set +# CONFIG_DEBUG_WATCHDOG is not set +CONFIG_ARCH_HAVE_STACKCHECK=y +# CONFIG_STACK_COLORATION is not set +CONFIG_ARCH_HAVE_HEAPCHECK=y +# CONFIG_HEAP_COLORATION is not set +# CONFIG_DEBUG_SYMBOLS is not set +CONFIG_ARCH_HAVE_CUSTOMOPT=y +# CONFIG_DEBUG_NOOPT is not set +# CONFIG_DEBUG_CUSTOMOPT is not set +CONFIG_DEBUG_FULLOPT=y + +# +# System Type +# +CONFIG_ARCH_ARM=y +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_MISOC is not set +# CONFIG_ARCH_RENESAS is not set +# CONFIG_ARCH_RISCV is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_XTENSA is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="arm" + +# +# ARM Options +# +# CONFIG_ARCH_CHIP_A1X is not set +# CONFIG_ARCH_CHIP_C5471 is not set +# CONFIG_ARCH_CHIP_DM320 is not set +# CONFIG_ARCH_CHIP_EFM32 is not set +# CONFIG_ARCH_CHIP_IMX1 is not set +# CONFIG_ARCH_CHIP_IMX6 is not set +# CONFIG_ARCH_CHIP_KINETIS is not set +# CONFIG_ARCH_CHIP_KL is not set +# CONFIG_ARCH_CHIP_LM is not set +# CONFIG_ARCH_CHIP_TIVA is not set +# CONFIG_ARCH_CHIP_LPC11XX is not set +# CONFIG_ARCH_CHIP_LPC17XX is not set +# CONFIG_ARCH_CHIP_LPC214X is not set +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_NUC1XX is not set +# CONFIG_ARCH_CHIP_SAMA5 is not set +# CONFIG_ARCH_CHIP_SAMD is not set +# CONFIG_ARCH_CHIP_SAML is not set +# CONFIG_ARCH_CHIP_SAM34 is not set +# CONFIG_ARCH_CHIP_SAMV7 is not set +CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F7 is not set +# CONFIG_ARCH_CHIP_STM32L4 is not set +# CONFIG_ARCH_CHIP_STR71X is not set +# CONFIG_ARCH_CHIP_TMS570 is not set +# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_ARM7TDMI is not set +# CONFIG_ARCH_ARM926EJS is not set +# CONFIG_ARCH_ARM920T is not set +# CONFIG_ARCH_CORTEXM0 is not set +# CONFIG_ARCH_CORTEXM23 is not set +CONFIG_ARCH_CORTEXM3=y +# CONFIG_ARCH_CORTEXM33 is not set +# CONFIG_ARCH_CORTEXM4 is not set +# CONFIG_ARCH_CORTEXM7 is not set +# CONFIG_ARCH_CORTEXA5 is not set +# CONFIG_ARCH_CORTEXA8 is not set +# CONFIG_ARCH_CORTEXA9 is not set +# CONFIG_ARCH_CORTEXR4 is not set +# CONFIG_ARCH_CORTEXR4F is not set +# CONFIG_ARCH_CORTEXR5 is not set +# CONFIG_ARCH_CORTEX5F is not set +# CONFIG_ARCH_CORTEXR7 is not set +# CONFIG_ARCH_CORTEXR7F is not set +CONFIG_ARCH_FAMILY="armv7-m" +CONFIG_ARCH_CHIP="stm32" +# CONFIG_ARM_TOOLCHAIN_IAR is not set +CONFIG_ARM_TOOLCHAIN_GNU=y +# CONFIG_ARMV7M_USEBASEPRI is not set +CONFIG_ARCH_HAVE_CMNVECTOR=y +# CONFIG_ARMV7M_CMNVECTOR is not set +# CONFIG_ARMV7M_LAZYFPU is not set +# CONFIG_ARCH_HAVE_FPU is not set +# CONFIG_ARCH_HAVE_DPFPU is not set +# CONFIG_ARCH_HAVE_TRUSTZONE is not set +CONFIG_ARM_HAVE_MPU_UNIFIED=y +# CONFIG_ARM_MPU is not set +# CONFIG_DEBUG_HARDFAULT is not set + +# +# ARMV7M Configuration Options +# +# CONFIG_ARMV7M_HAVE_ICACHE is not set +# CONFIG_ARMV7M_HAVE_DCACHE is not set +# CONFIG_ARMV7M_HAVE_ITCM is not set +# CONFIG_ARMV7M_HAVE_DTCM is not set +# CONFIG_ARMV7M_TOOLCHAIN_IARL is not set +# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set +# CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set +# CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL is not set +CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL=y +CONFIG_ARMV7M_HAVE_STACKCHECK=y +# CONFIG_ARMV7M_STACKCHECK is not set +# CONFIG_ARMV7M_ITMSYSLOG is not set +# CONFIG_SERIAL_TERMIOS is not set + +# +# STM32 Configuration Options +# +# CONFIG_ARCH_CHIP_STM32L151C6 is not set +# CONFIG_ARCH_CHIP_STM32L151C8 is not set +# CONFIG_ARCH_CHIP_STM32L151CB is not set +# CONFIG_ARCH_CHIP_STM32L151R6 is not set +# CONFIG_ARCH_CHIP_STM32L151R8 is not set +# CONFIG_ARCH_CHIP_STM32L151RB is not set +# CONFIG_ARCH_CHIP_STM32L151V6 is not set +# CONFIG_ARCH_CHIP_STM32L151V8 is not set +# CONFIG_ARCH_CHIP_STM32L151VB is not set +# CONFIG_ARCH_CHIP_STM32L152C6 is not set +# CONFIG_ARCH_CHIP_STM32L152C8 is not set +# CONFIG_ARCH_CHIP_STM32L152CB is not set +# CONFIG_ARCH_CHIP_STM32L152R6 is not set +# CONFIG_ARCH_CHIP_STM32L152R8 is not set +# CONFIG_ARCH_CHIP_STM32L152RB is not set +# CONFIG_ARCH_CHIP_STM32L152V6 is not set +# CONFIG_ARCH_CHIP_STM32L152V8 is not set +# CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L162ZD is not set +# CONFIG_ARCH_CHIP_STM32L162VE is not set +# CONFIG_ARCH_CHIP_STM32F100C8 is not set +# CONFIG_ARCH_CHIP_STM32F100CB is not set +# CONFIG_ARCH_CHIP_STM32F100R8 is not set +# CONFIG_ARCH_CHIP_STM32F100RB is not set +# CONFIG_ARCH_CHIP_STM32F100RC is not set +# CONFIG_ARCH_CHIP_STM32F100RD is not set +# CONFIG_ARCH_CHIP_STM32F100RE is not set +# CONFIG_ARCH_CHIP_STM32F100V8 is not set +# CONFIG_ARCH_CHIP_STM32F100VB is not set +# CONFIG_ARCH_CHIP_STM32F100VC is not set +# CONFIG_ARCH_CHIP_STM32F100VD is not set +# CONFIG_ARCH_CHIP_STM32F100VE is not set +# CONFIG_ARCH_CHIP_STM32F102CB is not set +# CONFIG_ARCH_CHIP_STM32F103T8 is not set +# CONFIG_ARCH_CHIP_STM32F103TB is not set +# CONFIG_ARCH_CHIP_STM32F103C4 is not set +# CONFIG_ARCH_CHIP_STM32F103C8 is not set +# CONFIG_ARCH_CHIP_STM32F103CB is not set +# CONFIG_ARCH_CHIP_STM32F103R8 is not set +# CONFIG_ARCH_CHIP_STM32F103RB is not set +# CONFIG_ARCH_CHIP_STM32F103RC is not set +# CONFIG_ARCH_CHIP_STM32F103RD is not set +# CONFIG_ARCH_CHIP_STM32F103RE is not set +# CONFIG_ARCH_CHIP_STM32F103RG is not set +# CONFIG_ARCH_CHIP_STM32F103V8 is not set +# CONFIG_ARCH_CHIP_STM32F103VB is not set +# CONFIG_ARCH_CHIP_STM32F103VC is not set +# CONFIG_ARCH_CHIP_STM32F103VE is not set +# CONFIG_ARCH_CHIP_STM32F103ZE is not set +# CONFIG_ARCH_CHIP_STM32F105VB is not set +# CONFIG_ARCH_CHIP_STM32F105RB is not set +# CONFIG_ARCH_CHIP_STM32F107VC is not set +CONFIG_ARCH_CHIP_STM32F205RG=y +# CONFIG_ARCH_CHIP_STM32F207IG is not set +# CONFIG_ARCH_CHIP_STM32F207ZE is not set +# CONFIG_ARCH_CHIP_STM32F302K6 is not set +# CONFIG_ARCH_CHIP_STM32F302K8 is not set +# CONFIG_ARCH_CHIP_STM32F302CB is not set +# CONFIG_ARCH_CHIP_STM32F302CC is not set +# CONFIG_ARCH_CHIP_STM32F302RB is not set +# CONFIG_ARCH_CHIP_STM32F302RC is not set +# CONFIG_ARCH_CHIP_STM32F302VB is not set +# CONFIG_ARCH_CHIP_STM32F302VC is not set +# CONFIG_ARCH_CHIP_STM32F303K6 is not set +# CONFIG_ARCH_CHIP_STM32F303K8 is not set +# CONFIG_ARCH_CHIP_STM32F303C6 is not set +# CONFIG_ARCH_CHIP_STM32F303C8 is not set +# CONFIG_ARCH_CHIP_STM32F303CB is not set +# CONFIG_ARCH_CHIP_STM32F303CC is not set +# CONFIG_ARCH_CHIP_STM32F303RB is not set +# CONFIG_ARCH_CHIP_STM32F303RC is not set +# CONFIG_ARCH_CHIP_STM32F303RD is not set +# CONFIG_ARCH_CHIP_STM32F303RE is not set +# CONFIG_ARCH_CHIP_STM32F303VB is not set +# CONFIG_ARCH_CHIP_STM32F303VC is not set +# CONFIG_ARCH_CHIP_STM32F334K4 is not set +# CONFIG_ARCH_CHIP_STM32F334K6 is not set +# CONFIG_ARCH_CHIP_STM32F334K8 is not set +# CONFIG_ARCH_CHIP_STM32F334C4 is not set +# CONFIG_ARCH_CHIP_STM32F334C6 is not set +# CONFIG_ARCH_CHIP_STM32F334C8 is not set +# CONFIG_ARCH_CHIP_STM32F334R4 is not set +# CONFIG_ARCH_CHIP_STM32F334R6 is not set +# CONFIG_ARCH_CHIP_STM32F334R8 is not set +# CONFIG_ARCH_CHIP_STM32F372C8 is not set +# CONFIG_ARCH_CHIP_STM32F372R8 is not set +# CONFIG_ARCH_CHIP_STM32F372V8 is not set +# CONFIG_ARCH_CHIP_STM32F372CB is not set +# CONFIG_ARCH_CHIP_STM32F372RB is not set +# CONFIG_ARCH_CHIP_STM32F372VB is not set +# CONFIG_ARCH_CHIP_STM32F372CC is not set +# CONFIG_ARCH_CHIP_STM32F372RC is not set +# CONFIG_ARCH_CHIP_STM32F372VC is not set +# CONFIG_ARCH_CHIP_STM32F373C8 is not set +# CONFIG_ARCH_CHIP_STM32F373R8 is not set +# CONFIG_ARCH_CHIP_STM32F373V8 is not set +# CONFIG_ARCH_CHIP_STM32F373CB is not set +# CONFIG_ARCH_CHIP_STM32F373RB is not set +# CONFIG_ARCH_CHIP_STM32F373VB is not set +# CONFIG_ARCH_CHIP_STM32F373CC is not set +# CONFIG_ARCH_CHIP_STM32F373RC is not set +# CONFIG_ARCH_CHIP_STM32F373VC is not set +# CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F411RE is not set +# CONFIG_ARCH_CHIP_STM32F411VE is not set +# CONFIG_ARCH_CHIP_STM32F405RG is not set +# CONFIG_ARCH_CHIP_STM32F405VG is not set +# CONFIG_ARCH_CHIP_STM32F405ZG is not set +# CONFIG_ARCH_CHIP_STM32F407VE is not set +# CONFIG_ARCH_CHIP_STM32F407VG is not set +# CONFIG_ARCH_CHIP_STM32F407ZE is not set +# CONFIG_ARCH_CHIP_STM32F407ZG is not set +# CONFIG_ARCH_CHIP_STM32F407IE is not set +# CONFIG_ARCH_CHIP_STM32F407IG is not set +# CONFIG_ARCH_CHIP_STM32F427V is not set +# CONFIG_ARCH_CHIP_STM32F427Z is not set +# CONFIG_ARCH_CHIP_STM32F427I is not set +# CONFIG_ARCH_CHIP_STM32F429V is not set +# CONFIG_ARCH_CHIP_STM32F429Z is not set +# CONFIG_ARCH_CHIP_STM32F429I is not set +# CONFIG_ARCH_CHIP_STM32F429B is not set +# CONFIG_ARCH_CHIP_STM32F429N is not set +# CONFIG_ARCH_CHIP_STM32F446M is not set +# CONFIG_ARCH_CHIP_STM32F446R is not set +# CONFIG_ARCH_CHIP_STM32F446V is not set +# CONFIG_ARCH_CHIP_STM32F446Z is not set +# CONFIG_ARCH_CHIP_STM32F469A is not set +# CONFIG_ARCH_CHIP_STM32F469I is not set +# CONFIG_ARCH_CHIP_STM32F469B is not set +# CONFIG_ARCH_CHIP_STM32F469N is not set +CONFIG_STM32_FLASH_CONFIG_DEFAULT=y +# CONFIG_STM32_FLASH_CONFIG_4 is not set +# CONFIG_STM32_FLASH_CONFIG_6 is not set +# CONFIG_STM32_FLASH_CONFIG_8 is not set +# CONFIG_STM32_FLASH_CONFIG_B is not set +# CONFIG_STM32_FLASH_CONFIG_C is not set +# CONFIG_STM32_FLASH_CONFIG_D is not set +# CONFIG_STM32_FLASH_CONFIG_E is not set +# CONFIG_STM32_FLASH_CONFIG_F is not set +# CONFIG_STM32_FLASH_CONFIG_G is not set +# CONFIG_STM32_FLASH_CONFIG_I is not set +# CONFIG_STM32_STM32L15XX is not set +# CONFIG_STM32_ENERGYLITE is not set +# CONFIG_STM32_STM32F10XX is not set +# CONFIG_STM32_VALUELINE is not set +# CONFIG_STM32_CONNECTIVITYLINE is not set +# CONFIG_STM32_PERFORMANCELINE is not set +# CONFIG_STM32_USBACCESSLINE is not set +# CONFIG_STM32_HIGHDENSITY is not set +# CONFIG_STM32_MEDIUMDENSITY is not set +# CONFIG_STM32_LOWDENSITY is not set +CONFIG_STM32_STM32F20XX=y +CONFIG_STM32_STM32F205=y +# CONFIG_STM32_STM32F207 is not set +# CONFIG_STM32_STM32F30XX is not set +# CONFIG_STM32_STM32F302 is not set +# CONFIG_STM32_STM32F303 is not set +# CONFIG_STM32_STM32F33XX is not set +# CONFIG_STM32_STM32F37XX is not set +# CONFIG_STM32_STM32F40XX is not set +# CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F411 is not set +# CONFIG_STM32_STM32F405 is not set +# CONFIG_STM32_STM32F407 is not set +# CONFIG_STM32_STM32F427 is not set +# CONFIG_STM32_STM32F429 is not set +# CONFIG_STM32_STM32F446 is not set +# CONFIG_STM32_STM32F469 is not set +CONFIG_STM32_DFU=y + +# +# STM32 Peripheral Support +# +# CONFIG_STM32_HAVE_CCM is not set +# CONFIG_STM32_HAVE_USBDEV is not set +CONFIG_STM32_HAVE_OTGFS=y +# CONFIG_STM32_HAVE_FSMC is not set +# CONFIG_STM32_HAVE_HRTIM1 is not set +# CONFIG_STM32_HAVE_LTDC is not set +CONFIG_STM32_HAVE_USART3=y +CONFIG_STM32_HAVE_UART4=y +CONFIG_STM32_HAVE_UART5=y +CONFIG_STM32_HAVE_USART6=y +# CONFIG_STM32_HAVE_UART7 is not set +# CONFIG_STM32_HAVE_UART8 is not set +CONFIG_STM32_HAVE_TIM1=y +# CONFIG_STM32_HAVE_TIM2 is not set +CONFIG_STM32_HAVE_TIM3=y +CONFIG_STM32_HAVE_TIM4=y +CONFIG_STM32_HAVE_TIM5=y +CONFIG_STM32_HAVE_TIM6=y +CONFIG_STM32_HAVE_TIM7=y +CONFIG_STM32_HAVE_TIM8=y +CONFIG_STM32_HAVE_TIM9=y +CONFIG_STM32_HAVE_TIM10=y +CONFIG_STM32_HAVE_TIM11=y +CONFIG_STM32_HAVE_TIM12=y +CONFIG_STM32_HAVE_TIM13=y +CONFIG_STM32_HAVE_TIM14=y +# CONFIG_STM32_HAVE_TIM15 is not set +# CONFIG_STM32_HAVE_TIM16 is not set +# CONFIG_STM32_HAVE_TIM17 is not set +CONFIG_STM32_HAVE_ADC2=y +CONFIG_STM32_HAVE_ADC3=y +# CONFIG_STM32_HAVE_ADC4 is not set +# CONFIG_STM32_HAVE_ADC1_DMA is not set +# CONFIG_STM32_HAVE_ADC2_DMA is not set +# CONFIG_STM32_HAVE_ADC3_DMA is not set +# CONFIG_STM32_HAVE_ADC4_DMA is not set +# CONFIG_STM32_HAVE_SDADC1 is not set +# CONFIG_STM32_HAVE_SDADC2 is not set +# CONFIG_STM32_HAVE_SDADC3 is not set +# CONFIG_STM32_HAVE_SDADC1_DMA is not set +# CONFIG_STM32_HAVE_SDADC2_DMA is not set +# CONFIG_STM32_HAVE_SDADC3_DMA is not set +CONFIG_STM32_HAVE_CAN1=y +CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP6 is not set +CONFIG_STM32_HAVE_DAC1=y +CONFIG_STM32_HAVE_DAC2=y +CONFIG_STM32_HAVE_RNG=y +# CONFIG_STM32_HAVE_ETHMAC is not set +CONFIG_STM32_HAVE_I2C2=y +CONFIG_STM32_HAVE_I2C3=y +CONFIG_STM32_HAVE_SPI2=y +CONFIG_STM32_HAVE_SPI3=y +# CONFIG_STM32_HAVE_SPI4 is not set +# CONFIG_STM32_HAVE_SPI5 is not set +# CONFIG_STM32_HAVE_SPI6 is not set +# CONFIG_STM32_HAVE_SAIPLL is not set +# CONFIG_STM32_HAVE_I2SPLL is not set +# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_ADC1 is not set +# CONFIG_STM32_ADC2 is not set +# CONFIG_STM32_ADC3 is not set +# CONFIG_STM32_CAN1 is not set +# CONFIG_STM32_CAN2 is not set +# CONFIG_STM32_CRC is not set +# CONFIG_STM32_DMA1 is not set +# CONFIG_STM32_DMA2 is not set +# CONFIG_STM32_DAC1 is not set +# CONFIG_STM32_DAC2 is not set +# CONFIG_STM32_I2C1 is not set +# CONFIG_STM32_I2C2 is not set +# CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OTGFS is not set +# CONFIG_STM32_OTGHS is not set +# CONFIG_STM32_PWR is not set +# CONFIG_STM32_RNG is not set +CONFIG_STM32_SDIO=y +# CONFIG_STM32_SPI1 is not set +# CONFIG_STM32_SPI2 is not set +# CONFIG_STM32_SPI3 is not set +# CONFIG_STM32_TIM1 is not set +# CONFIG_STM32_TIM2 is not set +# CONFIG_STM32_TIM3 is not set +# CONFIG_STM32_TIM4 is not set +# CONFIG_STM32_TIM5 is not set +# CONFIG_STM32_TIM6 is not set +# CONFIG_STM32_TIM7 is not set +# CONFIG_STM32_TIM8 is not set +# CONFIG_STM32_TIM9 is not set +# CONFIG_STM32_TIM10 is not set +# CONFIG_STM32_TIM11 is not set +# CONFIG_STM32_TIM12 is not set +# CONFIG_STM32_TIM13 is not set +# CONFIG_STM32_TIM14 is not set +CONFIG_STM32_USART1=y +# CONFIG_STM32_USART2 is not set +# CONFIG_STM32_USART3 is not set +# CONFIG_STM32_UART4 is not set +# CONFIG_STM32_UART5 is not set +# CONFIG_STM32_USART6 is not set +CONFIG_STM32_IWDG=y +# CONFIG_STM32_WWDG is not set +# CONFIG_STM32_NOEXT_VECTORS is not set + +# +# Alternate Pin Mapping +# +# CONFIG_STM32_JTAG_DISABLE is not set +# CONFIG_STM32_JTAG_FULL_ENABLE is not set +# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set +CONFIG_STM32_JTAG_SW_ENABLE=y +# CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG is not set +# CONFIG_STM32_FORCEPOWER is not set +# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set + +# +# Timer Configuration +# +# CONFIG_STM32_ONESHOT is not set +# CONFIG_STM32_FREERUN is not set +# CONFIG_STM32_TIM1_CAP is not set +# CONFIG_STM32_TIM3_CAP is not set +# CONFIG_STM32_TIM4_CAP is not set +# CONFIG_STM32_TIM5_CAP is not set +# CONFIG_STM32_TIM8_CAP is not set +# CONFIG_STM32_TIM9_CAP is not set +# CONFIG_STM32_TIM10_CAP is not set +# CONFIG_STM32_TIM11_CAP is not set +# CONFIG_STM32_TIM12_CAP is not set +# CONFIG_STM32_TIM13_CAP is not set +# CONFIG_STM32_TIM14_CAP is not set +CONFIG_STM32_USART=y +CONFIG_STM32_SERIALDRIVER=y + +# +# U[S]ART Configuration +# + +# +# U[S]ART Device Configuration +# +CONFIG_STM32_USART1_SERIALDRIVER=y +# CONFIG_STM32_USART1_1WIREDRIVER is not set +# CONFIG_USART1_RS485 is not set + +# +# Serial Driver Configuration +# +# CONFIG_SERIAL_DISABLE_REORDERING is not set +# CONFIG_STM32_FLOWCONTROL_BROKEN is not set +# CONFIG_STM32_USART_BREAKS is not set +# CONFIG_STM32_USART_SINGLEWIRE is not set + +# +# SDIO Configuration +# +CONFIG_STM32_SDIO_DMAPRIO=0x00010000 +# CONFIG_STM32_SDIO_WIDTH_D1_ONLY is not set +# CONFIG_STM32_HAVE_RTC_COUNTER is not set +# CONFIG_STM32_HAVE_RTC_SUBSECONDS is not set + +# +# USB FS Host Configuration +# + +# +# USB HS Host Configuration +# + +# +# USB Host Debug Configuration +# + +# +# USB Device Configuration +# + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_VECNOTIRQ is not set +# CONFIG_ARCH_DMA is not set +CONFIG_ARCH_HAVE_IRQPRIO=y +# CONFIG_ARCH_L2CACHE is not set +# CONFIG_ARCH_HAVE_COHERENT_DCACHE is not set +# CONFIG_ARCH_HAVE_ADDRENV is not set +# CONFIG_ARCH_NEED_ADDRENV_MAPPING is not set +# CONFIG_ARCH_HAVE_MULTICPU is not set +CONFIG_ARCH_HAVE_VFORK=y +# CONFIG_ARCH_HAVE_MMU is not set +CONFIG_ARCH_HAVE_MPU=y +# CONFIG_ARCH_NAND_HWECC is not set +# CONFIG_ARCH_HAVE_EXTCLK is not set +# CONFIG_ARCH_HAVE_POWEROFF is not set +CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_USE_MPU is not set +# CONFIG_ARCH_IRQPRIO is not set +CONFIG_ARCH_STACKDUMP=y +# CONFIG_ENDIAN_BIG is not set +# CONFIG_ARCH_IDLE_CUSTOM is not set +# CONFIG_ARCH_HAVE_RAMFUNCS is not set +CONFIG_ARCH_HAVE_RAMVECTORS=y +# CONFIG_ARCH_RAMVECTORS is not set +# CONFIG_ARCH_MINIMAL_VECTORTABLE is not set + +# +# Board Settings +# +CONFIG_BOARD_LOOPSPERMSEC=16717 +# CONFIG_ARCH_CALIBRATION is not set + +# +# Interrupt options +# +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y +CONFIG_ARCH_INTERRUPTSTACK=0 +CONFIG_ARCH_HAVE_HIPRI_INTERRUPT=y +# CONFIG_ARCH_HIPRI_INTERRUPT is not set + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Boot Memory Configuration +# +CONFIG_RAM_START=0x20000000 +CONFIG_RAM_SIZE=114688 +# CONFIG_ARCH_HAVE_SDRAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_PHOTON=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="photon" + +# +# Common Board Options +# +CONFIG_ARCH_HAVE_LEDS=y +# CONFIG_ARCH_LEDS is not set +CONFIG_ARCH_HAVE_BUTTONS=y +# CONFIG_ARCH_BUTTONS is not set +CONFIG_ARCH_HAVE_IRQBUTTONS=y + +# +# Board-Specific Options +# +CONFIG_PHOTON_DFU_BOOTLOADER=y +CONFIG_PHOTON_WDG=y +CONFIG_PHOTON_IWDG=y +CONFIG_PHOTON_IWDG_TIMEOUT=32000 +CONFIG_PHOTON_WDG_THREAD=y +CONFIG_PHOTON_WDG_THREAD_NAME="wdog" +CONFIG_PHOTON_WDG_THREAD_INTERVAL=2500 +CONFIG_PHOTON_WDG_THREAD_PRIORITY=200 +CONFIG_PHOTON_WDG_THREAD_STACKSIZE=1024 +CONFIG_PHOTON_WLAN=y +# CONFIG_BOARD_CRASHDUMP is not set +CONFIG_LIB_BOARDCTL=y +# CONFIG_BOARDCTL_RESET is not set +# CONFIG_BOARDCTL_UNIQUEID is not set +# CONFIG_BOARDCTL_TSCTEST is not set +# CONFIG_BOARDCTL_GRAPHICS is not set +# CONFIG_BOARDCTL_IOCTL is not set + +# +# RTOS Features +# +CONFIG_DISABLE_OS_API=y +# CONFIG_DISABLE_POSIX_TIMERS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_DISABLE_SIGNALS is not set +# CONFIG_DISABLE_MQUEUE is not set +# CONFIG_DISABLE_ENVIRON is not set + +# +# Clocks and Timers +# +CONFIG_ARCH_HAVE_TICKLESS=y +# CONFIG_SCHED_TICKLESS is not set +CONFIG_USEC_PER_TICK=10000 +# CONFIG_SYSTEM_TIME64 is not set +# CONFIG_CLOCK_MONOTONIC is not set +CONFIG_ARCH_HAVE_TIMEKEEPING=y +# CONFIG_CLOCK_TIMEKEEPING is not set +# CONFIG_JULIAN_TIME is not set +CONFIG_START_YEAR=2011 +CONFIG_START_MONTH=12 +CONFIG_START_DAY=6 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=16 +CONFIG_WDOG_INTRESERVE=4 +CONFIG_PREALLOC_TIMERS=4 + +# +# Tasks and Scheduling +# +# CONFIG_SPINLOCK is not set +# CONFIG_INIT_NONE is not set +CONFIG_INIT_ENTRYPOINT=y +# CONFIG_INIT_FILEPATH is not set +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_RR_INTERVAL=200 +# CONFIG_SCHED_SPORADIC is not set +CONFIG_TASK_NAME_SIZE=31 +CONFIG_MAX_TASKS=16 +# CONFIG_SCHED_HAVE_PARENT is not set +CONFIG_SCHED_WAITPID=y + +# +# Pthread Options +# +# CONFIG_MUTEX_TYPES is not set +CONFIG_NPTHREAD_KEYS=4 +# CONFIG_PTHREAD_CLEANUP is not set +# CONFIG_CANCELLATION_POINTS is not set + +# +# Performance Monitoring +# +# CONFIG_SCHED_CPULOAD is not set +# CONFIG_SCHED_INSTRUMENTATION is not set + +# +# Files and I/O +# +CONFIG_DEV_CONSOLE=y +# CONFIG_FDCLONE_DISABLE is not set +# CONFIG_FDCLONE_STDIO is not set +CONFIG_SDCLONE_DISABLE=y +CONFIG_NFILE_DESCRIPTORS=8 +CONFIG_NFILE_STREAMS=8 +CONFIG_NAME_MAX=32 +# CONFIG_PRIORITY_INHERITANCE is not set + +# +# RTOS hooks +# +# CONFIG_BOARD_INITIALIZE is not set +# CONFIG_SCHED_STARTHOOK is not set +# CONFIG_SCHED_ATEXIT is not set +# CONFIG_SCHED_ONEXIT is not set +# CONFIG_SIG_EVTHREAD is not set + +# +# Signal Numbers +# +CONFIG_SIG_SIGUSR1=1 +CONFIG_SIG_SIGUSR2=2 +CONFIG_SIG_SIGALARM=3 +CONFIG_SIG_SIGCONDTIMEDOUT=16 +CONFIG_SIG_SIGWORK=17 + +# +# POSIX Message Queue Options +# +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_MQ_MAXMSGSIZE=32 +# CONFIG_MODULE is not set + +# +# Work queue support +# +CONFIG_SCHED_WORKQUEUE=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=224 +CONFIG_SCHED_HPWORKPERIOD=50000 +CONFIG_SCHED_HPWORKSTACKSIZE=2048 +# CONFIG_SCHED_LPWORK is not set + +# +# Stack and heap information +# +CONFIG_IDLETHREAD_STACKSIZE=1024 +CONFIG_USERMAIN_STACKSIZE=2048 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=2048 +# CONFIG_LIB_SYSCALL is not set + +# +# Device Drivers +# +CONFIG_DISABLE_POLL=y +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_DEV_URANDOM is not set +# CONFIG_DEV_LOOP is not set + +# +# Buffering +# +# CONFIG_DRVR_WRITEBUFFER is not set +# CONFIG_DRVR_READAHEAD is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_ARCH_HAVE_PWM_PULSECOUNT is not set +# CONFIG_ARCH_HAVE_PWM_MULTICHAN is not set +# CONFIG_PWM is not set +CONFIG_ARCH_HAVE_I2CRESET=y +# CONFIG_I2C is not set +# CONFIG_ARCH_HAVE_SPI_CRCGENERATION is not set +# CONFIG_ARCH_HAVE_SPI_CS_CONTROL is not set +CONFIG_ARCH_HAVE_SPI_BITORDER=y +# CONFIG_SPI is not set +# CONFIG_I2S is not set + +# +# Timer Driver Support +# +# CONFIG_TIMER is not set +# CONFIG_ONESHOT is not set +# CONFIG_RTC is not set +CONFIG_WATCHDOG=y +CONFIG_WATCHDOG_DEVPATH="/dev/watchdog0" +# CONFIG_ANALOG is not set +# CONFIG_AUDIO_DEVICES is not set +# CONFIG_VIDEO_DEVICES is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set + +# +# IO Expander/GPIO Support +# +# CONFIG_IOEXPANDER is not set +# CONFIG_DEV_GPIO is not set + +# +# LCD Driver Support +# +# CONFIG_LCD is not set +# CONFIG_SLCD is not set + +# +# LED Support +# +CONFIG_USERLED=y +# CONFIG_USERLED_LOWER is not set +# CONFIG_RGBLED is not set +# CONFIG_PCA9635PW is not set +# CONFIG_NCP5623C is not set +CONFIG_MMCSD=y +CONFIG_MMCSD_NSLOTS=1 +# CONFIG_MMCSD_READONLY is not set +# CONFIG_MMCSD_MULTIBLOCK_DISABLE is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_HAVECARDDETECT is not set +CONFIG_ARCH_HAVE_SDIO=y +# CONFIG_SDIO_DMA is not set +CONFIG_ARCH_HAVE_SDIOWAIT_WRCOMPLETE=y +# CONFIG_MMCSD_SDIO is not set +CONFIG_SDIO_PREFLIGHT=y +# CONFIG_MODEM is not set +# CONFIG_MTD is not set +# CONFIG_EEPROM is not set +# CONFIG_PIPES is not set +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +CONFIG_SERIAL=y +# CONFIG_DEV_LOWCONSOLE is not set +# CONFIG_SERIAL_REMOVABLE is not set +CONFIG_SERIAL_CONSOLE=y +# CONFIG_16550_UART is not set +# CONFIG_UART_SERIALDRIVER is not set +# CONFIG_UART0_SERIALDRIVER is not set +# CONFIG_UART1_SERIALDRIVER is not set +# CONFIG_UART2_SERIALDRIVER is not set +# CONFIG_UART3_SERIALDRIVER is not set +# CONFIG_UART4_SERIALDRIVER is not set +# CONFIG_UART5_SERIALDRIVER is not set +# CONFIG_UART6_SERIALDRIVER is not set +# CONFIG_UART7_SERIALDRIVER is not set +# CONFIG_UART8_SERIALDRIVER is not set +# CONFIG_SCI0_SERIALDRIVER is not set +# CONFIG_SCI1_SERIALDRIVER is not set +# CONFIG_USART0_SERIALDRIVER is not set +CONFIG_USART1_SERIALDRIVER=y +# CONFIG_USART2_SERIALDRIVER is not set +# CONFIG_USART3_SERIALDRIVER is not set +# CONFIG_USART4_SERIALDRIVER is not set +# CONFIG_USART5_SERIALDRIVER is not set +# CONFIG_USART6_SERIALDRIVER is not set +# CONFIG_USART7_SERIALDRIVER is not set +# CONFIG_USART8_SERIALDRIVER is not set +# CONFIG_OTHER_UART_SERIALDRIVER is not set +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +# CONFIG_SERIAL_IFLOWCONTROL is not set +# CONFIG_SERIAL_OFLOWCONTROL is not set +# CONFIG_SERIAL_DMA is not set +# CONFIG_SERIAL_TIOCSERGSTRUCT is not set +CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y +CONFIG_USART1_SERIAL_CONSOLE=y +# CONFIG_OTHER_SERIAL_CONSOLE is not set +# CONFIG_NO_SERIAL_CONSOLE is not set + +# +# USART1 Configuration +# +CONFIG_USART1_RXBUFSIZE=256 +CONFIG_USART1_TXBUFSIZE=256 +CONFIG_USART1_BAUD=115200 +CONFIG_USART1_BITS=8 +CONFIG_USART1_PARITY=0 +CONFIG_USART1_2STOP=0 +# CONFIG_USART1_IFLOWCONTROL is not set +# CONFIG_USART1_OFLOWCONTROL is not set +# CONFIG_USART1_DMA is not set +# CONFIG_PSEUDOTERM is not set +# CONFIG_USBDEV is not set +# CONFIG_USBHOST is not set +# CONFIG_HAVE_USBTRACE is not set +CONFIG_DRIVERS_WIRELESS=y +# CONFIG_WL_CC1101 is not set +# CONFIG_WL_CC3000 is not set +# CONFIG_DRIVERS_IEEE802154 is not set +CONFIG_DRIVERS_IEEE80211=y +CONFIG_IEEE80211_BROADCOM_FULLMAC=y +CONFIG_IEEE80211_BROADCOM_FULLMAC_SDIO=y +# CONFIG_WL_NRF24L01 is not set +# CONFIG_DRIVERS_CONTACTLESS is not set + +# +# System Logging +# +# CONFIG_ARCH_SYSLOG is not set +# CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_INTBUFFER is not set +# CONFIG_SYSLOG_TIMESTAMP is not set +CONFIG_SYSLOG_SERIAL_CONSOLE=y +# CONFIG_SYSLOG_CHAR is not set +CONFIG_SYSLOG_CONSOLE=y +# CONFIG_SYSLOG_NONE is not set +# CONFIG_SYSLOG_FILE is not set +# CONFIG_SYSLOG_CHARDEV is not set + +# +# Networking Support +# +# CONFIG_ARCH_HAVE_NET is not set +# CONFIG_ARCH_HAVE_PHY is not set +# CONFIG_NET is not set + +# +# Crypto API +# +# CONFIG_CRYPTO is not set + +# +# File Systems +# + +# +# File system configuration +# +# CONFIG_DISABLE_MOUNTPOINT is not set +# CONFIG_FS_AUTOMOUNTER is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_PSEUDOFS_SOFTLINKS is not set +CONFIG_FS_READABLE=y +# CONFIG_FS_WRITABLE is not set +# CONFIG_FS_NAMED_SEMAPHORES is not set +CONFIG_FS_MQUEUE_MPATH="/var/mqueue" +# CONFIG_FS_RAMMAP is not set +# CONFIG_FS_FAT is not set +# CONFIG_FS_NXFFS is not set +# CONFIG_FS_ROMFS is not set +# CONFIG_FS_TMPFS is not set +# CONFIG_FS_SMARTFS is not set +# CONFIG_FS_BINFS is not set +CONFIG_FS_PROCFS=y +# CONFIG_FS_PROCFS_REGISTER is not set + +# +# Exclude individual procfs entries +# +# CONFIG_FS_PROCFS_EXCLUDE_PROCESS is not set +# CONFIG_FS_PROCFS_EXCLUDE_UPTIME is not set +# CONFIG_FS_PROCFS_EXCLUDE_MOUNTS is not set +# CONFIG_FS_UNIONFS is not set + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=2 +# CONFIG_ARCH_HAVE_HEAP2 is not set +# CONFIG_GRAN is not set + +# +# Audio Support +# +# CONFIG_AUDIO is not set + +# +# Wireless Support +# +# CONFIG_WIRELESS is not set + +# +# Binary Loader +# +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_BINFMT_EXEPATH is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +CONFIG_BUILTIN=y +# CONFIG_PIC is not set +# CONFIG_SYMTAB_ORDEREDBYNAME is not set + +# +# Library Routines +# + +# +# Standard C Library Options +# + +# +# Standard C I/O +# +# CONFIG_STDIO_DISABLE_BUFFERING is not set +CONFIG_STDIO_BUFFER_SIZE=64 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +# CONFIG_NOPRINTF_FIELDWIDTH is not set +# CONFIG_LIBC_FLOATINGPOINT is not set +CONFIG_LIBC_LONG_LONG=y +# CONFIG_LIBC_SCANSET is not set +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_MEMCPY_VIK is not set +# CONFIG_LIBM is not set + +# +# Architecture-Specific Support +# +CONFIG_ARCH_LOWPUTC=y +# CONFIG_ARCH_ROMGETC is not set +# CONFIG_LIBC_ARCH_MEMCPY is not set +# CONFIG_LIBC_ARCH_MEMCMP is not set +# CONFIG_LIBC_ARCH_MEMMOVE is not set +# CONFIG_LIBC_ARCH_MEMSET is not set +# CONFIG_LIBC_ARCH_STRCHR is not set +# CONFIG_LIBC_ARCH_STRCMP is not set +# CONFIG_LIBC_ARCH_STRCPY is not set +# CONFIG_LIBC_ARCH_STRNCPY is not set +# CONFIG_LIBC_ARCH_STRLEN is not set +# CONFIG_LIBC_ARCH_STRNLEN is not set +# CONFIG_LIBC_ARCH_ELF is not set +# CONFIG_ARMV7M_MEMCPY is not set + +# +# stdlib Options +# +CONFIG_LIB_RAND_ORDER=1 +CONFIG_LIB_HOMEDIR="/" + +# +# Program Execution Options +# +# CONFIG_LIBC_EXECFUNCS is not set +CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024 +CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=2048 + +# +# errno Decode Support +# +# CONFIG_LIBC_STRERROR is not set +# CONFIG_LIBC_PERROR_STDOUT is not set + +# +# memcpy/memset Options +# +# CONFIG_MEMSET_OPTSPEED is not set +# CONFIG_LIBC_DLLFCN is not set +# CONFIG_LIBC_MODLIB is not set +# CONFIG_LIBC_WCHAR is not set +# CONFIG_LIBC_LOCALE is not set + +# +# Time/Time Zone Support +# +# CONFIG_LIBC_LOCALTIME is not set +# CONFIG_TIME_EXTENDED is not set +CONFIG_ARCH_HAVE_TLS=y + +# +# Thread Local Storage (TLS) +# +# CONFIG_TLS is not set + +# +# Network-Related Options +# +# CONFIG_LIBC_IPv4_ADDRCONV is not set +# CONFIG_LIBC_IPv6_ADDRCONV is not set +# CONFIG_LIBC_NETDB is not set + +# +# NETDB Support +# +# CONFIG_NETDB_HOSTFILE is not set +# CONFIG_LIBC_IOCTL_VARIADIC is not set +CONFIG_LIB_SENDFILE_BUFSIZE=512 + +# +# Non-standard Library Support +# +# CONFIG_LIB_CRC64_FAST is not set +# CONFIG_LIB_KBDCODEC is not set +# CONFIG_LIB_SLCDCODEC is not set +# CONFIG_LIB_HEX2BIN is not set + +# +# Basic CXX Support +# +# CONFIG_C99_BOOL8 is not set +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +# CONFIG_CXX_NEWLONG is not set + +# +# LLVM C++ Library (libcxx) +# +# CONFIG_LIBCXX is not set + +# +# uClibc++ Standard C++ Library +# +# CONFIG_UCLIBCXX is not set + +# +# Application Configuration +# + +# +# NxWidgets/NxWM +# + +# +# Built-In Applications +# +CONFIG_BUILTIN_PROXY_STACKSIZE=1024 + +# +# CAN Utilities +# + +# +# Examples +# +# CONFIG_EXAMPLES_BUTTONS is not set +# CONFIG_EXAMPLES_CCTYPE is not set +# CONFIG_EXAMPLES_CHAT is not set +# CONFIG_EXAMPLES_CONFIGDATA is not set +# CONFIG_EXAMPLES_CXXTEST is not set +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HELLOXX is not set +# CONFIG_EXAMPLES_HIDKBD is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_JSON is not set +# CONFIG_EXAMPLES_KEYPADTEST is not set +# CONFIG_EXAMPLES_LEDS is not set +# CONFIG_EXAMPLES_MEDIA is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MODBUS is not set +# CONFIG_EXAMPLES_MOUNT is not set +# CONFIG_EXAMPLES_NRF24L01TERM is not set +CONFIG_EXAMPLES_NSH=y +# CONFIG_EXAMPLES_NSH_CXXINITIALIZE is not set +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NXLINES is not set +# CONFIG_EXAMPLES_NXTERM is not set +# CONFIG_EXAMPLES_NXTEXT is not set +# CONFIG_EXAMPLES_OSTEST is not set +# CONFIG_EXAMPLES_PCA9635 is not set +# CONFIG_EXAMPLES_POSIXSPAWN is not set +# CONFIG_EXAMPLES_PPPD is not set +# CONFIG_EXAMPLES_RFID_READUID is not set +# CONFIG_EXAMPLES_RGBLED is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERIALBLASTER is not set +# CONFIG_EXAMPLES_SERIALRX is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_SLCD is not set +# CONFIG_EXAMPLES_SMART is not set +# CONFIG_EXAMPLES_SMART_TEST is not set +# CONFIG_EXAMPLES_SMP is not set +# CONFIG_EXAMPLES_STAT is not set +# CONFIG_EXAMPLES_TCPECHO is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_USBSERIAL is not set +# CONFIG_EXAMPLES_USBTERM is not set +# CONFIG_EXAMPLES_WATCHDOG is not set +# CONFIG_EXAMPLES_WEBSERVER is not set + +# +# File System Utilities +# +# CONFIG_FSUTILS_INIFILE is not set +# CONFIG_FSUTILS_PASSWD is not set + +# +# GPS Utilities +# +# CONFIG_GPSUTILS_MINMEA_LIB is not set + +# +# Graphics Support +# +# CONFIG_TIFF is not set +# CONFIG_GRAPHICS_TRAVELER is not set + +# +# Interpreters +# +# CONFIG_INTERPRETERS_BAS is not set +# CONFIG_INTERPRETERS_FICL is not set +# CONFIG_INTERPRETERS_MICROPYTHON is not set +# CONFIG_INTERPRETERS_MINIBASIC is not set +# CONFIG_INTERPRETERS_PCODE is not set + +# +# FreeModBus +# +# CONFIG_MODBUS is not set + +# +# Network Utilities +# +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_ESP8266 is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_JSON is not set +# CONFIG_NETUTILS_SMTP is not set + +# +# NSH Library +# +CONFIG_NSH_LIBRARY=y +# CONFIG_NSH_MOTD is not set + +# +# Command Line Configuration +# +CONFIG_NSH_READLINE=y +# CONFIG_NSH_CLE is not set +CONFIG_NSH_LINELEN=64 +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_CMDPARMS is not set +CONFIG_NSH_MAXARGUMENTS=6 +# CONFIG_NSH_ARGCAT is not set +CONFIG_NSH_NESTDEPTH=3 +# CONFIG_NSH_DISABLEBG is not set +CONFIG_NSH_BUILTIN_APPS=y + +# +# Disable Individual commands +# +# CONFIG_NSH_DISABLE_ADDROUTE is not set +# CONFIG_NSH_DISABLE_BASENAME is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_CMP is not set +CONFIG_NSH_DISABLE_DATE=y +# CONFIG_NSH_DISABLE_DD is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_DELROUTE is not set +# CONFIG_NSH_DISABLE_DIRNAME is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_HEXDUMP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +# CONFIG_NSH_DISABLE_IFUPDOWN is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOSETUP is not set +CONFIG_NSH_DISABLE_LOSMART=y +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MB is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKRD is not set +# CONFIG_NSH_DISABLE_MH is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_MW is not set +CONFIG_NSH_DISABLE_PRINTF=y +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PUT is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SH is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNAME is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +# CONFIG_NSH_DISABLE_WGET is not set +# CONFIG_NSH_DISABLE_XD is not set +CONFIG_NSH_MMCSDMINOR=0 +CONFIG_NSH_MMCSDSLOTNO=0 + +# +# Configure Command Options +# +# CONFIG_NSH_CMDOPT_DF_H is not set +# CONFIG_NSH_CMDOPT_DD_STATS is not set +CONFIG_NSH_CODECS_BUFSIZE=128 +# CONFIG_NSH_CMDOPT_HEXDUMP is not set +CONFIG_NSH_PROC_MOUNTPOINT="/proc" +CONFIG_NSH_FILEIOSIZE=512 + +# +# Scripting Support +# +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_LOOPS is not set + +# +# Console Configuration +# +CONFIG_NSH_CONSOLE=y +# CONFIG_NSH_ALTCONDEV is not set +CONFIG_NSH_ARCHINIT=y +# CONFIG_NSH_LOGIN is not set +# CONFIG_NSH_CONSOLE_LOGIN is not set + +# +# Platform-specific Support +# +# CONFIG_PLATFORM_CONFIGDATA is not set + +# +# System Libraries and NSH Add-Ons +# +# CONFIG_SYSTEM_CLE is not set +# CONFIG_SYSTEM_CUTERM is not set +# CONFIG_SYSTEM_FREE is not set +# CONFIG_SYSTEM_HEX2BIN is not set +# CONFIG_SYSTEM_HEXED is not set +# CONFIG_SYSTEM_INSTALL is not set +# CONFIG_SYSTEM_RAMTEST is not set +CONFIG_READLINE_HAVE_EXTMATCH=y +CONFIG_SYSTEM_READLINE=y +CONFIG_READLINE_ECHO=y +# CONFIG_READLINE_TABCOMPLETION is not set +# CONFIG_READLINE_CMD_HISTORY is not set +# CONFIG_SYSTEM_SUDOKU is not set +# CONFIG_SYSTEM_SYSTEM is not set +# CONFIG_SYSTEM_TEE is not set +# CONFIG_SYSTEM_UBLOXMODEM is not set +# CONFIG_SYSTEM_VI is not set +# CONFIG_SYSTEM_ZMODEM is not set diff --git a/configs/photon/src/stm32_wlan.c b/configs/photon/src/stm32_wlan.c index a0b19e4e0f..fdc6f4ed03 100644 --- a/configs/photon/src/stm32_wlan.c +++ b/configs/photon/src/stm32_wlan.c @@ -95,6 +95,26 @@ void bcmf_board_initialize(int minor) bcmf_board_reset(minor, true); } +/**************************************************************************** + * Name: bcmf_board_setup_oob_irq + ****************************************************************************/ + +void bcmf_board_setup_oob_irq(int minor) +{ + if (minor != SDIO_WLAN0_MINOR) + { + return; + } + + /* Configure reset pin */ + + stm32_configgpio(GPIO_WLAN0_RESET); + + /* Put wlan chip in reset state */ + + bcmf_board_reset(minor, true); +} + /**************************************************************************** * Name: photon_wlan_initialize ****************************************************************************/ diff --git a/drivers/wireless/ieee80211/Make.defs b/drivers/wireless/ieee80211/Make.defs index 712ce5d1da..99c4a4446f 100644 --- a/drivers/wireless/ieee80211/Make.defs +++ b/drivers/wireless/ieee80211/Make.defs @@ -42,6 +42,7 @@ ifeq ($(CONFIG_DRIVERS_IEEE80211),y) ifeq ($(CONFIG_IEEE80211_BROADCOM_FULLMAC_SDIO),y) CSRCS += bcmf_sdio.c + CSRCS += mmc_sdio.c endif # Include IEEE 802.11 build support diff --git a/drivers/wireless/ieee80211/bcmf_sdio.c b/drivers/wireless/ieee80211/bcmf_sdio.c index b1ea523ba2..dfa815863c 100644 --- a/drivers/wireless/ieee80211/bcmf_sdio.c +++ b/drivers/wireless/ieee80211/bcmf_sdio.c @@ -50,6 +50,7 @@ #include #include +#include #include #include @@ -59,7 +60,19 @@ #define BCMF_DEVICE_RESET_DELAY_MS 10 #define BCMF_DEVICE_START_DELAY_MS 10 -#define BCMF_DEVICE_IDLE_DELAY_MS 50 +#define BCMF_CLOCK_SETUP_DELAY_MS 500 + +#define SDIO_FN1_CHIPCLKCSR 0x1000E /* Clock Control Source Register */ +#define SDIO_FN1_PULLUP 0x1000F /* Pull-up Control Register for cmd, D0-2 lines */ + +#define SDIO_FN1_CHIPCLKCSR_FORCE_ALP 0x01 +#define SDIO_FN1_CHIPCLKCSR_FORCE_HT 0x02 +#define SDIO_FN1_CHIPCLKCSR_FORCE_ILP 0x04 +#define SDIO_FN1_CHIPCLKCSR_ALP_AVAIL_REQ 0x08 +#define SDIO_FN1_CHIPCLKCSR_HT_AVAIL_REQ 0x10 +#define SDIO_FN1_CHIPCLKCSR_FORCE_HW_CLKREQ_OFF 0x20 +#define SDIO_FN1_CHIPCLKCSR_ALP_AVAIL 0x40 +#define SDIO_FN1_CHIPCLKCSR_HT_AVAIL 0x80 /**************************************************************************** * Private Types @@ -77,8 +90,17 @@ struct bcmf_dev_s * Private Function Prototypes ****************************************************************************/ -static int bcmf_sendcmdpoll(FAR struct bcmf_dev_s *priv, - uint32_t cmd, uint32_t arg); +static int bcmf_transfer_bytes(FAR struct bcmf_dev_s *priv, bool write, + uint8_t function, uint32_t address, + uint8_t *buf, unsigned int len); + +static int bcmf_read_reg(FAR struct bcmf_dev_s *priv, uint8_t function, + uint32_t address, uint8_t *reg, + unsigned int len); + +static int bcmf_write_reg(FAR struct bcmf_dev_s *priv, uint8_t function, + uint32_t address, uint32_t reg, + unsigned int len); static int bcmf_probe(FAR struct bcmf_dev_s *priv); static int bcmf_hwinitialize(FAR struct bcmf_dev_s *priv); @@ -93,29 +115,50 @@ static void bcmf_hwuninitialize(FAR struct bcmf_dev_s *priv); ****************************************************************************/ /**************************************************************************** - * Name: bcmf_sendcmdpoll + * Name: bcmf_transfer_bytes ****************************************************************************/ -int bcmf_sendcmdpoll(FAR struct bcmf_dev_s *priv, uint32_t cmd, uint32_t arg) +int bcmf_transfer_bytes(FAR struct bcmf_dev_s *priv, bool write, + uint8_t function, uint32_t address, + uint8_t *buf, unsigned int len) { - int ret; - - /* Send the command */ + /* Use rw_io_direct method if len is 1 */ - ret = SDIO_SENDCMD(priv->sdio_dev, cmd, arg); - if (ret == OK) + if (len == 1) { - /* Then poll-wait until the response is available */ + return sdio_io_rw_direct(priv->sdio_dev, write, + function, address, *buf, buf); + } - ret = SDIO_WAITRESPONSE(priv->sdio_dev, cmd); - if (ret != OK) - { - _err("ERROR: Wait for response to cmd: %08x failed: %d\n", - cmd, ret); - } + // return sdio_io_rw_extended(priv->sdio_dev, write, + // function, address, *buf, buf); + return -EINVAL; +} + +/**************************************************************************** + * Name: bcmf_read_reg + ****************************************************************************/ + +int bcmf_read_reg(FAR struct bcmf_dev_s *priv, uint8_t function, + uint32_t address, uint8_t *reg, unsigned int len) +{ + return bcmf_transfer_bytes(priv, false, function, address, reg, len); +} + +/**************************************************************************** + * Name: bcmf_write_reg + ****************************************************************************/ + +int bcmf_write_reg(FAR struct bcmf_dev_s *priv, uint8_t function, + uint32_t address, uint32_t reg, unsigned int len) +{ + if (len > 4) + { + return -EINVAL; } - return ret; + return bcmf_transfer_bytes(priv, true, function, address, + (uint8_t*)®, len); } /**************************************************************************** @@ -125,39 +168,88 @@ int bcmf_sendcmdpoll(FAR struct bcmf_dev_s *priv, uint32_t cmd, uint32_t arg) int bcmf_probe(FAR struct bcmf_dev_s *priv) { int ret; - uint32_t data = 0; + uint8_t value; + int loops; - /* Set device state from reset to idle */ + /* Probe sdio card compatible device */ - bcmf_sendcmdpoll(priv, MMCSD_CMD0, 0); - up_mdelay(BCMF_DEVICE_START_DELAY_MS); - - /* Send IO_SEND_OP_COND command */ + ret = sdio_probe(priv->sdio_dev); + if (ret != OK) + { + goto exit_error; + } - ret = bcmf_sendcmdpoll(priv, SDIO_CMD5, 0); + /* Enable bus FN1 */ + ret = sdio_enable_function(priv->sdio_dev, 1); if (ret != OK) { goto exit_error; } - /* Receive R4 response */ + /* Set FN0 / FN1 / FN2 default block size */ + + ret = sdio_set_blocksize(priv->sdio_dev, 0, 64); + if (ret != OK) + { + goto exit_error; + } - ret = SDIO_RECVR4(priv->sdio_dev, SDIO_CMD5, &data); + ret = sdio_set_blocksize(priv->sdio_dev, 1, 64); + if (ret != OK) + { + goto exit_error; + } + ret = sdio_set_blocksize(priv->sdio_dev, 2, 64); if (ret != OK) { goto exit_error; } - /* Broadcom chips have 2 additional functions and wide voltage range */ + /* Enable device interrupts for FN0, FN1 and FN2 */ - if ((((data >> 28) & 7) != 2) || - (((data >> 8) & 0xff80) != 0xff80)) + ret = sdio_io_rw_direct(priv->sdio_dev, true, 0, SDIO_CCCR_INTEN, + (1 << 0) | (1 << 1) | (1 << 2), NULL); + if (ret != OK) { goto exit_error; } + + /* Default device clock speed is up to 25 Mhz + * We could set EHS bit to operate at a clock rate up to 50 Mhz */ + + SDIO_CLOCK(priv->sdio_dev, CLOCK_SD_TRANSFER_4BIT); + up_mdelay(BCMF_CLOCK_SETUP_DELAY_MS); + + /* Wait for function 1 to be ready */ + + loops = 10; + while (--loops > 0) + { + up_mdelay(1); + + ret = sdio_io_rw_direct(priv->sdio_dev, false, 0, SDIO_CCCR_IORDY, 0, &value); + if (ret != OK) + { + return ret; + } + + if (value & (1 << 1)) + { + /* Function 1 is ready */ + break; + } + } + + if (loops <= 0) + { + return -ETIMEDOUT; + } + + _info("sdio fn1 ready\n"); + return OK; exit_error: @@ -166,6 +258,89 @@ exit_error: return ret; } +/**************************************************************************** + * Name: bcmf_businitialize + ****************************************************************************/ + + int bcmf_businitialize(FAR struct bcmf_dev_s *priv) +{ + int ret; + int loops; + + /* Send Active Low-Power clock request */ + + ret = bcmf_write_reg(priv, 1, SDIO_FN1_CHIPCLKCSR, + SDIO_FN1_CHIPCLKCSR_FORCE_HW_CLKREQ_OFF | + SDIO_FN1_CHIPCLKCSR_ALP_AVAIL_REQ | + SDIO_FN1_CHIPCLKCSR_FORCE_ALP, 1); + + if (ret != OK) + { + return ret;; + } + + loops = 10; + while (--loops > 0) + { + uint8_t value; + + up_mdelay(10); + ret = bcmf_read_reg(priv, 1, SDIO_FN1_CHIPCLKCSR, &value, 1); + + if (ret != OK) + { + return ret; + } + + if (value & SDIO_FN1_CHIPCLKCSR_ALP_AVAIL) + { + /* Active Low-Power clock is ready */ + break; + } + } + + if (loops <= 0) + { + _err("failed to enable ALP\n"); + return -ETIMEDOUT; + } + + /* Clear Active Low-Power clock request */ + + ret = bcmf_write_reg(priv, 1, SDIO_FN1_CHIPCLKCSR, 0, 1); + if (ret != OK) + { + return ret; + } + + /* Disable pull-ups on SDIO cmd, d0-2 lines */ + + ret = bcmf_write_reg(priv, 1, SDIO_FN1_PULLUP, 0, 1); + if (ret != OK) + { + return ret; + } + + /* Enable oob gpio interrupt */ + + // bcmf_board_setup_oob_irq(priv->minor, bcmf_oob_irq, (void*)priv); + + /* Enable F2 interrupt only */ + + /* Upload firmware */ + + /* Enable function 2 */ + + // ret = sdio_enable_function(priv->sdio_dev, 2); + // if (ret != OK) + // { + // goto exit_error; + // } + + + return OK; +} + /**************************************************************************** * Name: bcmf_hwinitialize ****************************************************************************/ @@ -253,6 +428,15 @@ int bcmf_sdio_initialize(int minor, FAR struct sdio_dev_s *dev) ret = bcmf_probe(priv); + if (ret != OK) + { + goto exit_uninit_hw; + } + + /* Initialize device */ + + ret = bcmf_businitialize(priv); + if (ret != OK) { goto exit_uninit_hw; diff --git a/drivers/wireless/ieee80211/mmc_sdio.c b/drivers/wireless/ieee80211/mmc_sdio.c new file mode 100644 index 0000000000..8674ae777c --- /dev/null +++ b/drivers/wireless/ieee80211/mmc_sdio.c @@ -0,0 +1,355 @@ +#include +#include +#include + +#include + +#define SDIO_CMD53_TIMEOUT_MS 100 +#define SDIO_IDLE_DELAY_MS 50 + +struct __attribute__((packed)) sdio_cmd52 { + uint32_t write_data : 8; + uint32_t reserved_8 : 1; + uint32_t register_address : 17; + uint32_t reserved_26 : 1; + uint32_t raw_flag : 1; + uint32_t function_number : 3; + uint32_t rw_flag : 1; +}; + +struct __attribute__((packed)) sdio_cmd53 { + uint32_t byte_block_count : 9; + uint32_t register_address : 17; + uint32_t op_code : 1; + uint32_t block_mode : 1; + uint32_t function_number : 3; + uint32_t rw_flag : 1; +}; + +struct __attribute__((packed)) sdio_resp_R5 { + uint32_t data : 8; + struct { + uint32_t out_of_range : 1; + uint32_t function_number : 1; + uint32_t rfu : 1; + uint32_t error : 1; + uint32_t io_current_state : 2; + uint32_t illegal_command : 1; + uint32_t com_crc_error : 1; + } flags; + uint32_t reserved_16 : 16; +}; + +union sdio_cmd5x { + uint32_t value; + struct sdio_cmd52 cmd52; + struct sdio_cmd53 cmd53; +}; + +int sdio_sendcmdpoll(FAR struct sdio_dev_s *dev, uint32_t cmd, uint32_t arg) +{ + int ret; + + /* Send the command */ + + ret = SDIO_SENDCMD(dev, cmd, arg); + if (ret == OK) + { + /* Then poll-wait until the response is available */ + + ret = SDIO_WAITRESPONSE(dev, cmd); + if (ret != OK) + { + _err("ERROR: Wait for response to cmd: %08x failed: %d\n", + cmd, ret); + } + } + + return ret; +} + +int sdio_io_rw_direct(FAR struct sdio_dev_s *dev, bool write, + uint8_t function, uint32_t address, + uint8_t inb, uint8_t* outb) +{ + union sdio_cmd5x arg; + struct sdio_resp_R5 resp; + int ret; + + /* Setup CMD52 argument */ + + arg.cmd52.write_data = inb; + arg.cmd52.register_address = address & 0x1ffff; + arg.cmd52.raw_flag = (write && outb); + arg.cmd52.function_number = function & 7; + arg.cmd52.rw_flag = write; + + /* Send CMD52 command */ + + sdio_sendcmdpoll(dev, SDIO_ACMD52, arg.value); + ret = SDIO_RECVR5(dev, SDIO_ACMD52, (uint32_t*)&resp); + + if (ret != OK) + { + _err("ERROR: SDIO_RECVR5 failed %d\n", ret); + return ret; + } + + /* Check for errors */ + + if (resp.flags.error) + { + return -EIO; + } + if (resp.flags.function_number || resp.flags.out_of_range) + { + return -EINVAL; + } + + /* Write output byte */ + + if (outb) + { + *outb = resp.data & 0xff; + } + + return OK; +} + +// int sdio_io_rw_extended(FAR struct sdio_dev_s *dev, bool write, +// uint8_t function, uint32_t address, +// bool inc_addr, uint8_t *buf, +// unsigned int blocklen, unsigned int nblocks) +// { +// struct sdio_cmd53 arg; +// struct sdio_resp_R5 resp; +// int ret; +// sdio_eventset_t wkupevent; +// +// /* Setup CMD53 argument */ +// +// arg.byte_block_count = blocklen; +// arg.register_address = address & 0x1ff; +// arg.op_code = inc_addr; +// arg.function_number = function & 7; +// arg.rw_flag = write; +// +// if (nblocks <= 1 && blocklen < 512) +// { +// /* Use byte mode */ +// +// arg.block_mode = 0; +// nblocks = 1; +// } +// else +// { +// /* Use block mode */ +// +// arg.block_mode = 1; +// } +// +// /* Send CMD53 command */ +// +// SDIO_BLOCKSETUP(dev, blocklen, nblocks); +// SDIO_WAITENABLE(dev, +// SDIOWAIT_TRANSFERDONE | SDIOWAIT_TIMEOUT | SDIOWAIT_ERROR); +// +// sdio_sendcmdpoll(dev, SDIO_ACMD53, (uint32_t)arg); +// ret = SDIO_RECVR5(dev, SDIO_ACMD53, (uint32_t*)&resp); +// +// if (write) +// { +// sdio_sendcmdpoll(dev, SDIO_ACMD53, (uint32_t)arg); +// ret = SDIO_RECVR5(dev, SDIO_ACMD53, (uint32_t*)&resp); +// +// SDIO_SENDSETUP(dev, buf, blocklen * nblocks); +// wkupevent = SDIO_EVENTWAIT(dev, SDIO_CMD53_TIMEOUT_MS); +// } +// else +// { +// SDIO_RECVSETUP(dev, buf, blocklen * nblocks); +// SDIO_SENDCMD(dev, SDIO_ACMD53, (uint32_t)arg); +// +// wkupevent = SDIO_EVENTWAIT(dev, SDIO_CMD53_TIMEOUT_MS); +// ret = SDIO_RECVR5(dev, SDIO_ACMD53, (uint32_t*)&resp); +// } +// +// if (ret != OK) +// { +// _err("ERROR: SDIO_RECVR5 failed %d\n", ret); +// return ret; +// } +// +// /* Check for errors */ +// +// if (wkupevent & SDIOWAIT_TIMEOUT) +// { +// return -ETIMEDOUT; +// } +// if (resp.error || (wkupevent & SDIOWAIT_ERROR)) +// { +// return -EIO; +// } +// if (resp.function_number || resp.out_of_range) +// { +// return -EINVAL; +// } +// +// return OK; +// } + +int sdio_set_wide_bus(struct sdio_dev_s *dev) +{ + int ret; + uint8_t value; + + /* Read Bus Interface Control register */ + + ret = sdio_io_rw_direct(dev, false, 0, SDIO_CCCR_BUS_IF, 0, &value); + if (ret != OK) + { + return ret; + } + + /* Set 4 bits bus width setting */ + + value &= ~SDIO_CCCR_BUS_IF_WIDTH_MASK; + value |= SDIO_CCCR_BUS_IF_4_BITS; + + ret = sdio_io_rw_direct(dev, true, 0, SDIO_CCCR_BUS_IF, value, NULL); + if (ret != OK) + { + return ret; + } + + SDIO_WIDEBUS(dev, true); + return OK; +} + +int sdio_probe(FAR struct sdio_dev_s *dev) +{ + int ret; + uint32_t data = 0; + + /* Set device state from reset to idle */ + + sdio_sendcmdpoll(dev, MMCSD_CMD0, 0); + up_mdelay(SDIO_IDLE_DELAY_MS); + + /* Device is SDIO card compatible so we can send CMD5 instead of ACMD41 */ + + sdio_sendcmdpoll(dev, SDIO_CMD5, 0); + + /* Receive R4 response */ + + ret = SDIO_RECVR4(dev, SDIO_CMD5, &data); + if (ret != OK) + { + return ret; + } + + /* Device is in Card Identification Mode, request device RCA */ + + sdio_sendcmdpoll(dev, SD_CMD3, 0); + + ret = SDIO_RECVR6(dev, SD_CMD3, &data); + if (ret != OK) + { + _err("ERROR: RCA request failed: %d\n", ret); + return ret; + } + + _info("rca is %x\n", data >> 16); + + /* Send CMD7 with the argument == RCA in order to select the card + * and put it in Transfer State */ + + sdio_sendcmdpoll(dev, MMCSD_CMD7S, data & 0xffff0000); + + ret = SDIO_RECVR1(dev, MMCSD_CMD7S, &data); + if (ret != OK) + { + _err("ERROR: card selection failed: %d\n", ret); + return ret; + } + + /* Configure 4 bits bus width */ + + ret = sdio_set_wide_bus(dev); + if (ret != OK) + { + return ret; + } + + return OK; +} + +int sdio_set_blocksize(FAR struct sdio_dev_s *dev, uint8_t function, + uint16_t blocksize) +{ + int ret; + + ret = sdio_io_rw_direct(dev, true, 0, + (function << SDIO_FBR_SHIFT) + SDIO_CCCR_FN0_BLKSIZE_0, + blocksize & 0xff, NULL); + if (ret != OK) + { + return ret; + } + + ret = sdio_io_rw_direct(dev, true, 0, + (function << SDIO_FBR_SHIFT) + SDIO_CCCR_FN0_BLKSIZE_1, + (blocksize >> 8), NULL); + + if (ret != OK) + { + return ret; + } + + return OK; +} + +int sdio_enable_function(FAR struct sdio_dev_s *dev, uint8_t function) +{ + int ret; + uint8_t value; + + /* Read current I/O Enable register */ + + ret = sdio_io_rw_direct(dev, false, 0, SDIO_CCCR_IOEN, 0, &value); + if (ret != OK) + { + return ret; + } + + ret = sdio_io_rw_direct(dev, true, 0, SDIO_CCCR_IOEN, value | (1 << function), NULL); + + if (ret != OK) + { + return ret; + } + + /* Wait 10ms for function to be enabled */ + + int loops = 10; + + while (loops-- > 0) + { + up_mdelay(1); + + ret = sdio_io_rw_direct(dev, false, 0, SDIO_CCCR_IOEN, 0, &value); + if (ret != OK) + { + return ret; + } + + if (value & (1 << function)) + { + /* Function enabled */ + + _info("Function %d enabled\n", function); + return OK; + } + } + return -ETIMEDOUT; +} diff --git a/include/nuttx/sdio.h b/include/nuttx/sdio.h index 388c72fd19..035e267710 100644 --- a/include/nuttx/sdio.h +++ b/include/nuttx/sdio.h @@ -328,6 +328,44 @@ #define SDIO_ACMD52 (SDIO_ACMDIDX52|MMCSD_R5_RESPONSE |MMCSD_NODATAXFR) #define SDIO_ACMD53 (SDIO_ACMDIDX53|MMCSD_R5_RESPONSE |MMCSD_NODATAXFR) +/* SDIO Card Common Control Registers definitions + * see https://www.sdcard.org/developers/overview/sdio/ + * sdio_spec/Simplified_SDIO_Card_Spec.pdf */ + +#define SDIO_CCCR_REV 0x00 /* CCCR/SDIO Revision */ +#define SDIO_CCCR_SD_SPEC_REV 0x01 /* SD Specification Revision */ +#define SDIO_CCCR_IOEN 0x02 /* I/O Enable */ +#define SDIO_CCCR_IORDY 0x03 /* I/O Ready */ +#define SDIO_CCCR_INTEN 0x04 /* Int Enable */ +#define SDIO_CCCR_INTPEND 0x05 /* Int Pending */ +#define SDIO_CCCR_IOABORT 0x06 /* I/O Abort */ +#define SDIO_CCCR_BUS_IF 0x07 /* Bus Interface Control */ +#define SDIO_CCCR_CARD_CAP 0x08 /* Card Capabilitiy */ +#define SDIO_CCCR_CCP 0x09 /* Common CIS Pointer */ +#define SDIO_CCCR_BUS_SUSP 0x0C /* Bus Suspend */ +#define SDIO_CCCR_FUNCSEL 0x0D /* Function Select */ +#define SDIO_CCCR_EXEC_FLAGS 0x0E /* Exec Flags */ +#define SDIO_CCCR_RDY_FLAGS 0x0F /* Ready Flags */ +#define SDIO_CCCR_FN0_BLKSIZE_0 0x10 /* FN0 Block Size */ +#define SDIO_CCCR_FN0_BLKSIZE_1 0x11 /* FN0 Block Size */ +#define SDIO_CCCR_POWER 0x12 /* Power Control */ +#define SDIO_CCCR_HIGHSPEED 0x13 /* High-Speed */ +#define SDIO_CCCR_RFU 0x14 /* Reserved for future use */ +#define SDIO_CCCR_VENDOR 0xF0 /* Reserved for Vendors */ + +#define SDIO_CCCR_BUS_IF_WIDTH_MASK 0x03 /* Bus width configuration */ +#define SDIO_CCCR_BUS_IF_1_BIT 0x01 /* 1 bit bus width setting */ +#define SDIO_CCCR_BUS_IF_4_BITS 0x02 /* 4 bits bus width setting */ + +#define SDIO_FBR_SHIFT 8 /* FBR bit shift */ +#define SDIO_FN1_BR_BASE (1 << SDIO_FBR_SHIFT) /* Func 1 registers base */ +#define SDIO_FN2_BR_BASE (2 << SDIO_FBR_SHIFT) /* Func 2 registers base */ +#define SDIO_FN3_BR_BASE (3 << SDIO_FBR_SHIFT) /* Func 3 registers base */ +#define SDIO_FN4_BR_BASE (4 << SDIO_FBR_SHIFT) /* Func 4 registers base */ +#define SDIO_FN5_BR_BASE (5 << SDIO_FBR_SHIFT) /* Func 5 registers base */ +#define SDIO_FN6_BR_BASE (6 << SDIO_FBR_SHIFT) /* Func 6 registers base */ +#define SDIO_FN7_BR_BASE (7 << SDIO_FBR_SHIFT) /* Func 7 registers base */ + /**************************************************************************** * Name: SDIO_LOCK * diff --git a/include/nuttx/wireless/ieee80211/mmc_sdio.h b/include/nuttx/wireless/ieee80211/mmc_sdio.h new file mode 100644 index 0000000000..39e7154f9e --- /dev/null +++ b/include/nuttx/wireless/ieee80211/mmc_sdio.h @@ -0,0 +1,26 @@ +#ifndef caca +#define caca +#include +#include + +int sdio_probe(FAR struct sdio_dev_s *dev); + +int sdio_set_wide_bus(struct sdio_dev_s *dev); + +int sdio_set_blocksize(FAR struct sdio_dev_s *dev, uint8_t function, + uint16_t blocksize); + +int sdio_enable_function(FAR struct sdio_dev_s *dev, uint8_t function); + +int sdio_sendcmdpoll(FAR struct sdio_dev_s *dev, uint32_t cmd, uint32_t arg); + +int sdio_io_rw_direct(FAR struct sdio_dev_s *dev, bool write, + uint8_t function, uint32_t address, + uint8_t inb, uint8_t* outb); + +int sdio_io_rw_extended(FAR struct sdio_dev_s *dev, bool write, + uint8_t function, uint32_t address, + bool inc_addr, uint8_t *buf, + unsigned int blocklen, unsigned int nblocks); + +#endif -- GitLab From a635e7df7a94c0ff187921c16c5aec568e86e6fa Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 14 Mar 2017 16:19:30 -0600 Subject: [PATCH 043/990] XMC4xxx: Add SCU header file. --- arch/arm/src/xmc4/chip/xmc4_scu.h | 453 ++++++++++++++++++++++++++++++ 1 file changed, 453 insertions(+) create mode 100644 arch/arm/src/xmc4/chip/xmc4_scu.h diff --git a/arch/arm/src/xmc4/chip/xmc4_scu.h b/arch/arm/src/xmc4/chip/xmc4_scu.h new file mode 100644 index 0000000000..a3e6d116e7 --- /dev/null +++ b/arch/arm/src/xmc4/chip/xmc4_scu.h @@ -0,0 +1,453 @@ +/************************************************************************************ + * arch/arm/src/xmc4/chip/xmc4_scu.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_XMC4_CHIP_XMC4_SCU_H +#define __ARCH_ARM_SRC_XMC4_CHIP_XMC4_SCU_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include "chip/xmc4_memorymap.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Register Offsets *****************************************************************/ + +#define XMC4_GCU_OFFSET 0x0000 /* Offset address of General Control Unit */ +#define XMC4_PCU_OFFSET 0x0200 /* Offset address of Power Control Unit */ +#define XMC4_HCU_OFFSET 0x0300 /* Offset address of Hibernate Control Unit */ +#define XMC4_RCU_OFFSET 0x0400 /* Offset address of Reset Control Unit */ +#define XMC4_CCU_OFFSET 0x0600 /* Offset address of Clock Control Unit */ + +/* General SCU Registers */ + +#define XMC4_GCU_ID_OFFSET 0x0000 /* Module Identification Register */ +#define XMC4_GCU_IDCHIP_OFFSET 0x0004 /* Chip ID */ +#define XMC4_GCU_IDMANUF_OFFSET 0x0008 /* Manufactory ID */ +#define XMC4_GCU_STCON_OFFSET 0x0010 /* Start-up Control */ +#define XMC4_GCU_GPR0_OFFSET 0x002c /* General Purpose Register 0 */ +#define XMC4_GCU_GPR1_OFFSET 0x0030 /* General Purpose Register 1 */ +#define XMC4_GCU_ETH0CON_OFFSET 0x0040 /* Ethernet 0 Port Control */ +#define XMC4_GCU_CCUCON_OFFSET 0x004c /* CCUx Global Start Control Register */ +#define XMC4_GCU_SRSTAT_OFFSET 0x0074 /* Service Request Status */ +#define XMC4_GCU_SRRAW_OFFSET 0x0078 /* RAW Service Request Status */ +#define XMC4_GCU_SRMSK_OFFSET 0x007c /* Service Request Mask */ +#define XMC4_GCU_SRCLR_OFFSET 0x0080 /* Service Request Clear */ +#define XMC4_GCU_SRSET_OFFSET 0x0084 /* Service Request Set */ +#define XMC4_GCU_NMIREQEN_OFFSET 0x0088 /* Enable Promoting Events to NMI Request */ +#define XMC4_GCU_DTSCON_OFFSET 0x008c /* DTS Control */ +#define XMC4_GCU_DTSSTAT_OFFSET 0x0090 /* DTS Status */ +#define XMC4_GCU_SDMMCDEL_OFFSET 0x009c /* SD-MMC Delay Control Register */ +#define XMC4_GCU_G0ORCEN_OFFSET 0x00a0 /* Out-Of-Range Comparator Enable Register 0 */ +#define XMC4_GCU_G1ORCEN_OFFSET 0x00a4 /* Out-Of-Range Comparator Enable Register 1 */ +#define XMC4_GCU_MIRRSTS_OFFSET 0x00c4 /* Mirror Update Status Register */ +#define XMC4_GCU_RMACR_OFFSET 0x00c8 /* Retention Memory Access Control Register */ +#define XMC4_GCU_RMADATA_OFFSET 0x00cc /* Retention Memory Access Data Register */ +#define XMC4_GCU_PEEN_OFFSET 0x013c /* Parity Error Enable Register */ +#define XMC4_GCU_MCHKCON_OFFSET 0x0140 /* Memory Checking Control Register */ +#define XMC4_GCU_PETE_OFFSET 0x0144 /* Parity Error Trap Enable Register */ +#define XMC4_GCU_PERSTEN_OFFSET 0x0148 /* Reset upon Parity Error Enable Register */ +#define XMC4_GCU_PEFLAG_OFFSET 0x0150 /* Parity Error Control Register */ +#define XMC4_GCU_PMTPR_OFFSET 0x0154 /* Parity Memory Test Pattern Register */ +#define XMC4_GCU_PMTSR_OFFSET 0x0158 /* Parity Memory Test Select Register */ +#define XMC4_GCU_TRAPSTAT_OFFSET 0x0160 /* Trap Status Register */ +#define XMC4_GCU_TRAPRAW_OFFSET 0x0164 /* Trap Raw Status Register */ +#define XMC4_GCU_TRAPDIS_OFFSET 0x0168 /* Trap Mask Register */ +#define XMC4_GCU_TRAPCLR_OFFSET 0x016c /* Trap Clear Register */ +#define XMC4_GCU_TRAPSET_OFFSET 0x0170 /* Trap Set Register */ + +/* PCU Registers */ + +#define XMC4_PCU_PWRSTAT_OFFSET 0x0000 /* Power Status Register */ +#define XMC4_PCU_PWRSET_OFFSET 0x0004 /* Power Set Control Register */ +#define XMC4_PCU_PWRCLR_OFFSET 0x0008 /* Power Clear Control Register */ +#define XMC4_PCU_EVRSTAT_OFFSET 0x0010 /* EVR Status Register */ +#define XMC4_PCU_EVRVADCSTAT_OFFSET 0x0014 /* EVR VADC Status Register */ +#define XMC4_PCU_PWRMON_OFFSET 0x002c /* Power Monitor Value */ + +/* HCU Registers */ + +#define XMC4_HCU_HDSTAT_OFFSET 0x0000 /* Hibernate Domain Status Register */ +#define XMC4_HCU_HDCLR_OFFSET 0x0004 /* Hibernate Domain Status Clear Register */ +#define XMC4_HCU_HDSET_OFFSET 0x0008 /* Hibernate Domain Status Set Register */ +#define XMC4_HCU_HDCR_OFFSET 0x000c /* Hibernate Domain Control Register */ +#define XMC4_HCU_OSCSICTRL_OFFSET 0x0014 /* Internal 32.768 kHz Clock Source Control Register */ +#define XMC4_HCU_OSCULSTAT_OFFSET 0x0018 /* OSC_ULP Status Register */ +#define XMC4_HCU_OSCULCTRL_OFFSET 0x001c /* OSC_ULP Control Register */ + +/* RCU Registers */ + +#define XMC4_RCU_RSTSTAT_OFFSET 0x0000 /* System Reset Status */ +#define XMC4_RCU_RSTSET_OFFSET 0x0004 /* Reset Set Register */ +#define XMC4_RCU_RSTCLR_OFFSET 0x0008 /* Reset Clear Register */ +#define XMC4_RCU_PRSTAT0_OFFSET 0x000c /* Peripheral Reset Status Register 0 */ +#define XMC4_RCU_PRSET0_OFFSET 0x0010 /* Peripheral Reset Set Register 0 */ +#define XMC4_RCU_PRCLR0_OFFSET 0x0014 /* Peripheral Reset Clear Register 0 */ +#define XMC4_RCU_PRSTAT1_OFFSET 0x0018 /* Peripheral Reset Status Register 1 */ +#define XMC4_RCU_PRSET1_OFFSET 0x001c /* Peripheral Reset Set Register 1 */ +#define XMC4_RCU_PRCLR1_OFFSET 0x0020 /* Peripheral Reset Clear Register 1 */ +#define XMC4_RCU_PRSTAT2_OFFSET 0x0024 /* Peripheral Reset Status Register 2 */ +#define XMC4_RCU_PRSET2_OFFSET 0x0028 /* Peripheral Reset Set Register 2 */ +#define XMC4_RCU_PRCLR2_OFFSET 0x002c /* Peripheral Reset Clear Register 2 */ +#define XMC4_RCU_PRSTAT3_OFFSET 0x0030 /* Peripheral Reset Status Register 3 */ +#define XMC4_RCU_PRSET3_OFFSET 0x0034 /* Peripheral Reset Set Register 3 */ +#define XMC4_RCU_PRCLR3_OFFSET 0x0038 /* Peripheral Reset Clear Register 3 */ + +/* CCU Registers */ + +#define XMC4_CCU_CLKSTAT_OFFSET 0x0000 /* Clock Status Register */ +#define XMC4_CCU_CLKSET_OFFSET 0x0004 /* Clock Set Control Register */ +#define XMC4_CCU_CLKCLR_OFFSET 0x0008 /* Clock clear Control Register */ +#define XMC4_CCU_SYSCLKCR_OFFSET 0x000c /* System Clock Control */ +#define XMC4_CCU_CPUCLKCR_OFFSET 0x0010 /* CPU Clock Control */ +#define XMC4_CCU_PBCLKCR_OFFSET 0x0014 /* Peripheral Bus Clock Control */ +#define XMC4_CCU_USBCLKCR_OFFSET 0x0018 /* USB Clock Control */ +#define XMC4_CCU_EBUCLKCR_OFFSET 0x001c /* EBU Clock Control */ +#define XMC4_CCU_CCUCLKCR_OFFSET 0x0020 /* CCU Clock Control */ +#define XMC4_CCU_WDTCLKCR_OFFSET 0x0024 /* WDT Clock Control */ +#define XMC4_CCU_EXTCLKCR_OFFSET 0x0028 /* External clock Control Register */ +#define XMC4_CCU_SLEEPCR_OFFSET 0x0030 /* Sleep Control Register */ +#define XMC4_CCU_DSLEEPCR_OFFSET 0x0034 /* Deep Sleep Control Register */ +#define XMC4_CCU_OSCHPSTAT_OFFSET 0x0100 /* OSC_HP Status Register */ +#define XMC4_CCU_OSCHPCTRL_OFFSET 0x0104 /* OSC_HP Control Register */ +#define XMC4_CCU_CLKCALCONST_OFFSET 0x010c /* Clock Calibration Constant Register */ +#define XMC4_CCU_PLLSTAT_OFFSET 0x0110 /* System PLL Status Register */ +#define XMC4_CCU_PLLCON0_OFFSET 0x0114 /* System PLL Configuration 0 Register */ +#define XMC4_CCU_PLLCON1_OFFSET 0x0118 /* System PLL Configuration 1 Register */ +#define XMC4_CCU_PLLCON2_OFFSET 0x011c /* System PLL Configuration 2 Register */ +#define XMC4_CCU_USBPLLSTAT_OFFSET 0x0120 /* USB PLL Status Register */ +#define XMC4_CCU_USBPLLCON_OFFSET 0x0124 /* USB PLL Control Register */ +#define XMC4_CCU_CLKMXSTAT_OFFSET 0x0138 /* Clock Multiplexing Status Register */ + +/* Register Addresses ***************************************************************/ + +#define XMC4_GCU_BASE (XMC4_SCU_BASE+XMC4_GCU_OFFSET) +#define XMC4_PCU_BASE (XMC4_SCU_BASE+XMC4_PCU_OFFSET) +#define XMC4_HCU_BASE (XMC4_SCU_BASE+XMC4_HCU_OFFSET) +#define XMC4_RCU_BASE (XMC4_SCU_BASE+XMC4_RCU_OFFSET) +#define XMC4_CCU_BASE (XMC4_SCU_BASE+XMC4_CCU_OFFSET) + +/* General SCU Registers */ + +#define XMC4_GCU_ID (XMC4_GCU_BASE+XMC4_GCU_ID_OFFSET) +#define XMC4_GCU_IDCHIP (XMC4_GCU_BASE+XMC4_GCU_IDCHIP_OFFSET) +#define XMC4_GCU_IDMANUF (XMC4_GCU_BASE+XMC4_GCU_IDMANUF_OFFSET) +#define XMC4_GCU_STCON (XMC4_GCU_BASE+XMC4_GCU_STCON_OFFSET) +#define XMC4_GCU_GPR0 (XMC4_GCU_BASE+XMC4_GCU_GPR0_OFFSET) +#define XMC4_GCU_GPR1 (XMC4_GCU_BASE+XMC4_GCU_GPR1_OFFSET) +#define XMC4_GCU_ETH0CON (XMC4_GCU_BASE+XMC4_GCU_ETH0CON_OFFSET) +#define XMC4_GCU_CCUCON (XMC4_GCU_BASE+XMC4_GCU_CCUCON_OFFSET) +#define XMC4_GCU_SRSTAT (XMC4_GCU_BASE+XMC4_GCU_SRSTAT_OFFSET) +#define XMC4_GCU_SRRAW (XMC4_GCU_BASE+XMC4_GCU_SRRAW_OFFSET) +#define XMC4_GCU_SRMSK (XMC4_GCU_BASE+XMC4_GCU_SRMSK_OFFSET) +#define XMC4_GCU_SRCLR (XMC4_GCU_BASE+XMC4_GCU_SRCLR_OFFSET) +#define XMC4_GCU_SRSET (XMC4_GCU_BASE+XMC4_GCU_SRSET_OFFSET) +#define XMC4_GCU_NMIREQEN (XMC4_GCU_BASE+XMC4_GCU_NMIREQEN_OFFSET) +#define XMC4_GCU_DTSCON (XMC4_GCU_BASE+XMC4_GCU_DTSCON_OFFSET) +#define XMC4_GCU_DTSSTAT (XMC4_GCU_BASE+XMC4_GCU_DTSSTAT_OFFSET) +#define XMC4_GCU_SDMMCDEL (XMC4_GCU_BASE+XMC4_GCU_SDMMCDEL_OFFSET) +#define XMC4_GCU_G0ORCEN (XMC4_GCU_BASE+XMC4_GCU_G0ORCEN_OFFSET) +#define XMC4_GCU_G1ORCEN (XMC4_GCU_BASE+XMC4_GCU_G1ORCEN_OFFSET) +#define XMC4_GCU_MIRRSTS (XMC4_GCU_BASE+XMC4_GCU_MIRRSTS_OFFSET) +#define XMC4_GCU_RMACR (XMC4_GCU_BASE+XMC4_GCU_RMACR_OFFSET) +#define XMC4_GCU_RMADATA (XMC4_GCU_BASE+XMC4_GCU_RMADATA_OFFSET) +#define XMC4_GCU_PEEN (XMC4_GCU_BASE+XMC4_GCU_PEEN_OFFSET) +#define XMC4_GCU_MCHKCON (XMC4_GCU_BASE+XMC4_GCU_MCHKCON_OFFSET) +#define XMC4_GCU_PETE (XMC4_GCU_BASE+XMC4_GCU_PETE_OFFSET) +#define XMC4_GCU_PERSTEN (XMC4_GCU_BASE+XMC4_GCU_PERSTEN_OFFSET) +#define XMC4_GCU_PEFLAG (XMC4_GCU_BASE+XMC4_GCU_PEFLAG_OFFSET) +#define XMC4_GCU_PMTPR (XMC4_GCU_BASE+XMC4_GCU_PMTPR_OFFSET) +#define XMC4_GCU_PMTSR (XMC4_GCU_BASE+XMC4_GCU_PMTSR_OFFSET) +#define XMC4_GCU_TRAPSTAT (XMC4_GCU_BASE+XMC4_GCU_TRAPSTAT_OFFSET) +#define XMC4_GCU_TRAPRAW (XMC4_GCU_BASE+XMC4_GCU_TRAPRAW_OFFSET) +#define XMC4_GCU_TRAPDIS (XMC4_GCU_BASE+XMC4_GCU_TRAPDIS_OFFSET) +#define XMC4_GCU_TRAPCLR (XMC4_GCU_BASE+XMC4_GCU_TRAPCLR_OFFSET) +#define XMC4_GCU_TRAPSET (XMC4_GCU_BASE+XMC4_GCU_TRAPSET_OFFSET) + +/* PCU Registers */ + +#define XMC4_PCU_PWRSTAT (XMC4_PCU_BASE+XMC4_PCU_PWRSTAT_OFFSET) +#define XMC4_PCU_PWRSET (XMC4_PCU_BASE+XMC4_PCU_PWRSET_OFFSET) +#define XMC4_PCU_PWRCLR (XMC4_PCU_BASE+XMC4_PCU_PWRCLR_OFFSET) +#define XMC4_PCU_EVRSTAT (XMC4_PCU_BASE+XMC4_PCU_EVRSTAT_OFFSET) +#define XMC4_PCU_EVRVADCSTAT (XMC4_PCU_BASE+XMC4_PCU_EVRVADCSTAT_OFFSET) +#define XMC4_PCU_PWRMON (XMC4_PCU_BASE+XMC4_PCU_PWRMON_OFFSET) + +/* HCU Registers */ + +#define XMC4_HCU_HDSTAT (XMC4_HCU_BASE+XMC4_HCU_HDSTAT_OFFSET) +#define XMC4_HCU_HDCLR (XMC4_HCU_BASE+XMC4_HCU_HDCLR_OFFSET) +#define XMC4_HCU_HDSET (XMC4_HCU_BASE+XMC4_HCU_HDSET_OFFSET) +#define XMC4_HCU_HDCR (XMC4_HCU_BASE+XMC4_HCU_HDCR_OFFSET) +#define XMC4_HCU_OSCSICTRL (XMC4_HCU_BASE+XMC4_HCU_OSCSICTRL_OFFSET) +#define XMC4_HCU_OSCULSTAT (XMC4_HCU_BASE+XMC4_HCU_OSCULSTAT_OFFSET) +#define XMC4_HCU_OSCULCTRL (XMC4_HCU_BASE+XMC4_HCU_OSCULCTRL_OFFSET) + +/* RCU Registers */ + +#define XMC4_RCU_RSTSTAT (XMC4_RCU_BASE+XMC4_RCU_RSTSTAT_OFFSET) +#define XMC4_RCU_RSTSET (XMC4_RCU_BASE+XMC4_RCU_RSTSET_OFFSET) +#define XMC4_RCU_RSTCLR (XMC4_RCU_BASE+XMC4_RCU_RSTCLR_OFFSET) +#define XMC4_RCU_PRSTAT0 (XMC4_RCU_BASE+XMC4_RCU_PRSTAT0_OFFSET) +#define XMC4_RCU_PRSET0 (XMC4_RCU_BASE+XMC4_RCU_PRSET0_OFFSET) +#define XMC4_RCU_PRCLR0 (XMC4_RCU_BASE+XMC4_RCU_PRCLR0_OFFSET) +#define XMC4_RCU_PRSTAT1 (XMC4_RCU_BASE+XMC4_RCU_PRSTAT1_OFFSET) +#define XMC4_RCU_PRSET1 (XMC4_RCU_BASE+XMC4_RCU_PRSET1_OFFSET) +#define XMC4_RCU_PRCLR1 (XMC4_RCU_BASE+XMC4_RCU_PRCLR1_OFFSET) +#define XMC4_RCU_PRSTAT2 (XMC4_RCU_BASE+XMC4_RCU_PRSTAT2_OFFSET) +#define XMC4_RCU_PRSET2 (XMC4_RCU_BASE+XMC4_RCU_PRSET2_OFFSET) +#define XMC4_RCU_PRCLR2 (XMC4_RCU_BASE+XMC4_RCU_PRCLR2_OFFSET) +#define XMC4_RCU_PRSTAT3 (XMC4_RCU_BASE+XMC4_RCU_PRSTAT3_OFFSET) +#define XMC4_RCU_PRSET3 (XMC4_RCU_BASE+XMC4_RCU_PRSET3_OFFSET) +#define XMC4_RCU_PRCLR3 (XMC4_RCU_BASE+XMC4_RCU_PRCLR3_OFFSET) + +/* CCU Registers */ + +#define XMC4_CCU_CLKSTAT (XMC4_CCU_BASE+XMC4_CCU_CLKSTAT_OFFSET) +#define XMC4_CCU_CLKSET (XMC4_CCU_BASE+XMC4_CCU_CLKSET_OFFSET) +#define XMC4_CCU_CLKCLR (XMC4_CCU_BASE+XMC4_CCU_CLKCLR_OFFSET) +#define XMC4_CCU_SYSCLKCR (XMC4_CCU_BASE+XMC4_CCU_SYSCLKCR_OFFSET) +#define XMC4_CCU_CPUCLKCR (XMC4_CCU_BASE+XMC4_CCU_CPUCLKCR_OFFSET) +#define XMC4_CCU_PBCLKCR (XMC4_CCU_BASE+XMC4_CCU_PBCLKCR_OFFSET) +#define XMC4_CCU_USBCLKCR (XMC4_CCU_BASE+XMC4_CCU_USBCLKCR_OFFSET) +#define XMC4_CCU_EBUCLKCR (XMC4_CCU_BASE+XMC4_CCU_EBUCLKCR_OFFSET) +#define XMC4_CCU_CCUCLKCR (XMC4_CCU_BASE+XMC4_CCU_CCUCLKCR_OFFSET) +#define XMC4_CCU_WDTCLKCR (XMC4_CCU_BASE+XMC4_CCU_WDTCLKCR_OFFSET) +#define XMC4_CCU_EXTCLKCR (XMC4_CCU_BASE+XMC4_CCU_EXTCLKCR_OFFSET) +#define XMC4_CCU_SLEEPCR (XMC4_CCU_BASE+XMC4_CCU_SLEEPCR_OFFSET) +#define XMC4_CCU_DSLEEPCR (XMC4_CCU_BASE+XMC4_CCU_DSLEEPCR_OFFSET) +#define XMC4_CCU_OSCHPSTAT (XMC4_CCU_BASE+XMC4_CCU_OSCHPSTAT_OFFSET) +#define XMC4_CCU_OSCHPCTRL (XMC4_CCU_BASE+XMC4_CCU_OSCHPCTRL_OFFSET) +#define XMC4_CCU_CLKCALCONST (XMC4_CCU_BASE+XMC4_CCU_CLKCALCONST_OFFSET) +#define XMC4_CCU_PLLSTAT (XMC4_CCU_BASE+XMC4_CCU_PLLSTAT_OFFSET) +#define XMC4_CCU_PLLCON0 (XMC4_CCU_BASE+XMC4_CCU_PLLCON0_OFFSET) +#define XMC4_CCU_PLLCON1 (XMC4_CCU_BASE+XMC4_CCU_PLLCON1_OFFSET) +#define XMC4_CCU_PLLCON2 (XMC4_CCU_BASE+XMC4_CCU_PLLCON2_OFFSET) +#define XMC4_CCU_USBPLLSTAT (XMC4_CCU_BASE+XMC4_CCU_USBPLLSTAT_OFFSET) +#define XMC4_CCU_USBPLLCON (XMC4_CCU_BASE+XMC4_CCU_USBPLLCON_OFFSET) +#define XMC4_CCU_CLKMXSTAT (XMC4_CCU_BASE+XMC4_CCU_CLKMXSTAT_OFFSET) + +/* Register Bit-Field Definitions ***************************************************/ + +/* General SCU Registers */ + +/* Module Identification Register */ +#define GCU_ID_ +/* Chip ID */ +#define GCU_IDCHIP_ +/* Manufactory ID */ +#define GCU_IDMANUF_ +/* Start-up Control */ +#define GCU_STCON_ +/* General Purpose Register 0 */ +#define GCU_GPR0_ +/* General Purpose Register 1 */ +#define GCU_GPR1_ +/* Ethernet 0 Port Control */ +#define GCU_ETH0CON_ +/* CCUx Global Start Control Register */ +#define GCU_CCUCON_ +/* Service Request Status */ +#define GCU_SRSTAT_ +/* RAW Service Request Status */ +#define GCU_SRRAW_ +/* Service Request Mask */ +#define GCU_SRMSK_ +/* Service Request Clear */ +#define GCU_SRCLR_ +/* Service Request Set */ +#define GCU_SRSET_ +/* Enable Promoting Events to NMI Request */ +#define GCU_NMIREQEN_ +/* DTS Control */ +#define GCU_DTSCON_ +/* DTS Status */ +#define GCU_DTSSTAT_ +/* SD-MMC Delay Control Register */ +#define GCU_SDMMCDEL_ +/* Out-Of-Range Comparator Enable Register 0 */ +#define GCU_G0ORCEN_ +/* Out-Of-Range Comparator Enable Register 1 */ +#define GCU_G1ORCEN_ +/* Mirror Update Status Register */ +#define GCU_MIRRSTS_ +/* Retention Memory Access Control Register */ +#define GCU_RMACR_ +/* Retention Memory Access Data Register */ +#define GCU_RMADATA_ +/* Parity Error Enable Register */ +#define GCU_PEEN_ +/* Memory Checking Control Register */ +#define GCU_MCHKCON_ +/* Parity Error Trap Enable Register */ +#define GCU_PETE_ +/* Reset upon Parity Error Enable Register */ +#define GCU_PERSTEN_ +/* Parity Error Control Register */ +#define GCU_PEFLAG_ +/* Parity Memory Test Pattern Register */ +#define GCU_PMTPR_ +/* Parity Memory Test Select Register */ +#define GCU_PMTSR_ +/* Trap Status Register */ +#define GCU_TRAPSTAT_ +/* Trap Raw Status Register */ +#define GCU_TRAPRAW_ +/* Trap Mask Register */ +#define GCU_TRAPDIS_ +/* Trap Clear Register */ +#define GCU_TRAPCLR_ +/* Trap Set Register */ +#define GCU_TRAPSET_ + +/* PCU Registers */ + +/* Power Status Register */ +#define PCU_PWRSTAT_ +/* Power Set Control Register */ +#define PCU_PWRSET_ +/* Power Clear Control Register */ +#define PCU_PWRCLR_ +/* EVR Status Register */ +#define PCU_EVRSTAT_ +/* EVR VADC Status Register */ +#define PCU_EVRVADCSTAT_ +/* Power Monitor Value */ +#define PCU_PWRMON_ + +/* HCU Registers */ + +/* Hibernate Domain Status Register */ +#define HCU_HDSTAT_ +/* Hibernate Domain Status Clear Register */ +#define HCU_HDCLR_ +/* Hibernate Domain Status Set Register */ +#define HCU_HDSET_ +/* Hibernate Domain Control Register */ +#define HCU_HDCR_ +/* Internal 32.768 kHz Clock Source Control Register */ +#define HCU_OSCSICTRL_ +/* OSC_ULP Status Register */ +#define HCU_OSCULSTAT_ +/* OSC_ULP Control Register */ +#define HCU_OSCULCTRL_ + +/* RCU Registers */ + +/* System Reset Status */ +#define RCU_RSTSTAT_ +/* Reset Set Register */ +#define RCU_RSTSET_ +/* Reset Clear Register */ +#define RCU_RSTCLR_ +/* Peripheral Reset Status Register 0 */ +#define RCU_PRSTAT0_ +/* Peripheral Reset Set Register 0 */ +#define RCU_PRSET0_ +/* Peripheral Reset Clear Register 0 */ +#define RCU_PRCLR0_ +/* Peripheral Reset Status Register 1 */ +#define RCU_PRSTAT1_ +/* Peripheral Reset Set Register 1 */ +#define RCU_PRSET1_ +/* Peripheral Reset Clear Register 1 */ +#define RCU_PRCLR1_ +/* Peripheral Reset Status Register 2 */ +#define RCU_PRSTAT2_ +/* Peripheral Reset Set Register 2 */ +#define RCU_PRSET2_ +/* Peripheral Reset Clear Register 2 */ +#define RCU_PRCLR2_ +/* Peripheral Reset Status Register 3 */ +#define RCU_PRSTAT3_ +/* Peripheral Reset Set Register 3 */ +#define RCU_PRSET3_ +/* Peripheral Reset Clear Register 3 */ +#define RCU_PRCLR3_ + +/* CCU Registers */ + +/* Clock Status Register */ +#define CCU_CLKSTAT_ +/* Clock Set Control Register */ +#define CCU_CLKSET_ +/* Clock clear Control Register */ +#define CCU_CLKCLR_ +/* System Clock Control */ +#define CCU_SYSCLKCR_ +/* CPU Clock Control */ +#define CCU_CPUCLKCR_ +/* Peripheral Bus Clock Control */ +#define CCU_PBCLKCR_ +/* USB Clock Control */ +#define CCU_USBCLKCR_ +/* EBU Clock Control */ +#define CCU_EBUCLKCR_ +/* CCU Clock Control */ +#define CCU_CCUCLKCR_ +/* WDT Clock Control */ +#define CCU_WDTCLKCR_ +/* External clock Control Register */ +#define CCU_EXTCLKCR_ +/* Sleep Control Register */ +#define CCU_SLEEPCR_ +/* Deep Sleep Control Register */ +#define CCU_DSLEEPCR_ +/* OSC_HP Status Register */ +#define CCU_OSCHPSTAT_ +/* OSC_HP Control Register */ +#define CCU_OSCHPCTRL_ +/* Clock Calibration Constant Register */ +#define CCU_CLKCALCONST_ +/* System PLL Status Register */ +#define CCU_PLLSTAT_ +/* System PLL Configuration 0 Register */ +#define CCU_PLLCON0_ +/* System PLL Configuration 1 Register */ +#define CCU_PLLCON1_ +/* System PLL Configuration 2 Register */ +#define CCU_PLLCON2_ +/* USB PLL Status Register */ +#define CCU_USBPLLSTAT_ +/* USB PLL Control Register */ +#define CCU_USBPLLCON_ +/* Clock Multiplexing Status Register */ +#define CCU_CLKMXSTAT_ + +#endif /* __ARCH_ARM_SRC_XMC4_CHIP_XMC4_SCU_H */ -- GitLab From 772b3cf21b66b7649b4b1a8e87d70afc081908e6 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 14 Mar 2017 19:07:19 -0600 Subject: [PATCH 044/990] XMC4xxx: Add Peripheral Memory Map header file. --- arch/arm/src/xmc4/chip/xmc4_memorymap.h | 227 ++++++++ arch/arm/src/xmc4/chip/xmc4_scu.h | 730 ++++++++++++++---------- 2 files changed, 655 insertions(+), 302 deletions(-) create mode 100644 arch/arm/src/xmc4/chip/xmc4_memorymap.h diff --git a/arch/arm/src/xmc4/chip/xmc4_memorymap.h b/arch/arm/src/xmc4/chip/xmc4_memorymap.h new file mode 100644 index 0000000000..8cf50174b9 --- /dev/null +++ b/arch/arm/src/xmc4/chip/xmc4_memorymap.h @@ -0,0 +1,227 @@ +/************************************************************************************ + * arch/arm/src/xmc4/chip/xmc4_memorymap.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Reference: XMC4500 Reference Manual V1.5 2014-07 Microcontrollers. + * + * 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. + * + * May include some logic from sample code provided by Infineon: + * + * Copyright (C) 2011-2015 Infineon Technologies AG. All rights reserved. + * + * Infineon Technologies AG (Infineon) is supplying this software for use with + * Infineon's microcontrollers. This file can be freely distributed within + * development tools that are supporting such microcontrollers. + * + * THIS SOFTWARE IS PROVIDED AS IS. NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * INFINEON SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, + * OR CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_XMC4_CHIP_XMC4_MEMORYMAP_H +#define __ARCH_ARM_SRC_XMC4_CHIP_XMC4_MEMORYMAP_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Peripheral Memory Map ************************************************************/ +/* Acronyms: + * ADC - Analog to Digital Converter + * CCU - Capture Compare Unit + * DAC - Digital to Analog Converter + * DSD - Delta Sigmoid Demodulator + * ERU - External Request Unit + * FCE - Flexible CRC Engine + * GPDMA - General Purpose DMA + * LEDTS - LED and Touch Sense Control Unit + * PMU - Program Management Unit + * POSIF - Position Interface + * SDMMC - Multi Media Card Interface + * USB - Universal Serial Bus + * USCI - Universal Serial Interface + */ + +#define XMC4_PBA0_BASE 0x40000000 +#define XMC4_VADC_BASE 0x40004000 +#define XMC4_VADC_G0_BASE 0x40004400 +#define XMC4_VADC_G1_BASE 0x40004800 +#define XMC4_VADC_G2_BASE 0x40004c00 +#define XMC4_VADC_G3_BASE 0x40005000 +#define XMC4_DSD_BASE 0x40008000 +#define XMC4_DSD_CH0_BASE 0x40008100 +#define XMC4_DSD_CH1_BASE 0x40008200 +#define XMC4_DSD_CH2_BASE 0x40008300 +#define XMC4_DSD_CH3_BASE 0x40008400 +#define XMC4_CCU40_BASE 0x4000c000 +#define XMC4_CCU40_CC40_BASE 0x4000c100 +#define XMC4_CCU40_CC41_BASE 0x4000c200 +#define XMC4_CCU40_CC42_BASE 0x4000c300 +#define XMC4_CCU40_CC43_BASE 0x4000c400 +#define XMC4_CCU41_BASE 0x40010000 +#define XMC4_CCU41_CC40_BASE 0x40010100 +#define XMC4_CCU41_CC41_BASE 0x40010200 +#define XMC4_CCU41_CC42_BASE 0x40010300 +#define XMC4_CCU41_CC43_BASE 0x40010400 +#define XMC4_CCU42_BASE 0x40014000 +#define XMC4_CCU42_CC40_BASE 0x40014100 +#define XMC4_CCU42_CC41_BASE 0x40014200 +#define XMC4_CCU42_CC42_BASE 0x40014300 +#define XMC4_CCU42_CC43_BASE 0x40014400 +#define XMC4_CCU80_BASE 0x40020000 +#define XMC4_CCU80_CC80_BASE 0x40020100 +#define XMC4_CCU80_CC81_BASE 0x40020200 +#define XMC4_CCU80_CC82_BASE 0x40020300 +#define XMC4_CCU80_CC83_BASE 0x40020400 +#define XMC4_CCU81_BASE 0x40024000 +#define XMC4_CCU81_CC80_BASE 0x40024100 +#define XMC4_CCU81_CC81_BASE 0x40024200 +#define XMC4_CCU81_CC82_BASE 0x40024300 +#define XMC4_CCU81_CC83_BASE 0x40024400 +#define XMC4_POSIF0_BASE 0x40028000 +#define XMC4_POSIF1_BASE 0x4002c000 +#define XMC4_USIC0_BASE 0x40030008 +#define XMC4_USIC0_CH0_BASE 0x40030000 +#define XMC4_USIC0_CH1_BASE 0x40030200 +#define XMC4_ERU1_BASE 0x40044000 + +#define XMC4_PBA1_BASE 0x48000000 +#define XMC4_CCU43_BASE 0x48004000 +#define XMC4_CCU43_CC40_BASE 0x48004100 +#define XMC4_CCU43_CC41_BASE 0x48004200 +#define XMC4_CCU43_CC42_BASE 0x48004300 +#define XMC4_CCU43_CC43_BASE 0x48004400 +#define XMC4_LEDTS0_BASE 0x48010000 +#define XMC4_CAN_BASE 0x48014000 +#define XMC4_CAN_NODE0_BASE 0x48014200 +#define XMC4_CAN_NODE1_BASE 0x48014300 +#define XMC4_CAN_NODE2_BASE 0x48014400 +#define XMC4_CAN_NODE3_BASE 0x48014500 +#define XMC4_CAN_NODE4_BASE 0x48014600 +#define XMC4_CAN_NODE5_BASE 0x48014700 +#define XMC4_CAN_MO_BASE 0x48015000 +#define XMC4_DAC_BASE 0x48018000 +#define XMC4_SDMMC_BASE 0x4801c000 +#define XMC4_USIC1_CH0_BASE 0x48020000 +#define XMC4_USIC1_BASE 0x48020008 +#define XMC4_USIC1_CH1_BASE 0x48020200 +#define XMC4_USIC2_CH0_BASE 0x48024000 +#define XMC4_USIC2_BASE 0x48024008 +#define XMC4_USIC2_CH1_BASE 0x48024200 +#define XMC4_PORT0_BASE 0x48028000 +#define XMC4_PORT1_BASE 0x48028100 +#define XMC4_PORT2_BASE 0x48028200 +#define XMC4_PORT3_BASE 0x48028300 +#define XMC4_PORT4_BASE 0x48028400 +#define XMC4_PORT5_BASE 0x48028500 +#define XMC4_PORT6_BASE 0x48028600 +#define XMC4_PORT7_BASE 0x48028700 +#define XMC4_PORT8_BASE 0x48028800 +#define XMC4_PORT9_BASE 0x48028900 +#define XMC4_PORT14_BASE 0x48028e00 +#define XMC4_PORT15_BASE 0x48028f00 + +#define XMC4_SCU_GENERAL_BASE 0x50004000 +#define XMC4_ETH0_CON_BASE 0x50004040 +#define XMC4_SCU_INTERRUPT_BASE 0x50004074 +#define XMC4_SDMMC_CON_BASE 0x500040b4 +#define XMC4_SCU_PARITY_BASE 0x5000413c +#define XMC4_SCU_TRAP_BASE 0x50004160 +#define XMC4_SCU_POWER_BASE 0x50004200 +#define XMC4_SCU_HIBERNATE_BASE 0x50004300 +#define XMC4_SCU_RESET_BASE 0x50004400 +#define XMC4_SCU_CLK_BASE 0x50004600 +#define XMC4_SCU_OSC_BASE 0x50004700 +#define XMC4_SCU_PLL_BASE 0x50004710 +#define XMC4_ERU0_BASE 0x50004800 +#define XMC4_DLR_BASE 0x50004900 +#define XMC4_RTC_BASE 0x50004a00 +#define XMC4_WDT_BASE 0x50008000 +#define XMC4_ETH0_BASE 0x5000c000 +#define XMC4_USB0_BASE 0x50040000 +#define XMC4_USB0_CH0_BASE 0x50040500 +#define XMC4_USB0_CH1_BASE 0x50040520 +#define XMC4_USB0_CH2_BASE 0x50040540 +#define XMC4_USB0_CH3_BASE 0x50040560 +#define XMC4_USB0_CH4_BASE 0x50040580 +#define XMC4_USB0_CH5_BASE 0x500405a0 +#define XMC4_USB0_CH6_BASE 0x500405c0 +#define XMC4_USB0_CH7_BASE 0x500405e0 +#define XMC4_USB0_CH8_BASE 0x50040600 +#define XMC4_USB0_CH9_BASE 0x50040620 +#define XMC4_USB0_CH10_BASE 0x50040640 +#define XMC4_USB0_CH11_BASE 0x50040660 +#define XMC4_USB0_CH12_BASE 0x50040680 +#define XMC4_USB0_CH13_BASE 0x500406a0 +#define XMC4_USB_EP_BASE 0x50040900 +#define XMC4_USB0_EP1_BASE 0x50040920 +#define XMC4_USB0_EP2_BASE 0x50040940 +#define XMC4_USB0_EP3_BASE 0x50040960 +#define XMC4_USB0_EP4_BASE 0x50040980 +#define XMC4_USB0_EP5_BASE 0x500409a0 +#define XMC4_USB0_EP6_BASE 0x500409c0 +#define XMC4_GPDMA0_CH0_BASE 0x50014000 +#define XMC4_GPDMA0_CH1_BASE 0x50014058 +#define XMC4_GPDMA0_CH2_BASE 0x500140b0 +#define XMC4_GPDMA0_CH3_BASE 0x50014108 +#define XMC4_GPDMA0_CH4_BASE 0x50014160 +#define XMC4_GPDMA0_CH5_BASE 0x500141b8 +#define XMC4_GPDMA0_CH6_BASE 0x50014210 +#define XMC4_GPDMA0_CH7_BASE 0x50014268 +#define XMC4_GPDMA0_BASE 0x500142c0 +#define XMC4_GPDMA1_CH0_BASE 0x50018000 +#define XMC4_GPDMA1_CH1_BASE 0x50018058 +#define XMC4_GPDMA1_CH2_BASE 0x500180b0 +#define XMC4_GPDMA1_CH3_BASE 0x50018108 +#define XMC4_GPDMA1_BASE 0x500182c0 +#define XMC4_FCE_BASE 0x50020000 +#define XMC4_FCE_KE0_BASE 0x50020020 +#define XMC4_FCE_KE1_BASE 0x50020040 +#define XMC4_FCE_KE2_BASE 0x50020060 +#define XMC4_FCE_KE3_BASE 0x50020080 + +#define XMC4_PMU0_BASE 0x58000508 +#define XMC4_FLASH0_BASE 0x58001000 +#define XMC4_PREF_BASE 0x58004000 +#define XMC4_EBU_BASE 0x58008000 + +#define XMC4_PPB_BASE 0xe000e000 + +#endif /* __ARCH_ARM_SRC_XMC4_CHIP_XMC4_SCU_H */ diff --git a/arch/arm/src/xmc4/chip/xmc4_scu.h b/arch/arm/src/xmc4/chip/xmc4_scu.h index a3e6d116e7..ab5b771995 100644 --- a/arch/arm/src/xmc4/chip/xmc4_scu.h +++ b/arch/arm/src/xmc4/chip/xmc4_scu.h @@ -4,6 +4,8 @@ * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * + * Reference: XMC4500 Reference Manual V1.5 2014-07 Microcontrollers. + * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: @@ -31,6 +33,20 @@ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * + * May include some logic from sample code provided by Infineon: + * + * Copyright (C) 2011-2015 Infineon Technologies AG. All rights reserved. + * + * Infineon Technologies AG (Infineon) is supplying this software for use with + * Infineon's microcontrollers. This file can be freely distributed within + * development tools that are supporting such microcontrollers. + * + * THIS SOFTWARE IS PROVIDED AS IS. NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * INFINEON SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, + * OR CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * ************************************************************************************/ #ifndef __ARCH_ARM_SRC_XMC4_CHIP_XMC4_SCU_H @@ -48,406 +64,516 @@ ************************************************************************************/ /* Register Offsets *****************************************************************/ - -#define XMC4_GCU_OFFSET 0x0000 /* Offset address of General Control Unit */ -#define XMC4_PCU_OFFSET 0x0200 /* Offset address of Power Control Unit */ -#define XMC4_HCU_OFFSET 0x0300 /* Offset address of Hibernate Control Unit */ -#define XMC4_RCU_OFFSET 0x0400 /* Offset address of Reset Control Unit */ -#define XMC4_CCU_OFFSET 0x0600 /* Offset address of Clock Control Unit */ - /* General SCU Registers */ -#define XMC4_GCU_ID_OFFSET 0x0000 /* Module Identification Register */ -#define XMC4_GCU_IDCHIP_OFFSET 0x0004 /* Chip ID */ -#define XMC4_GCU_IDMANUF_OFFSET 0x0008 /* Manufactory ID */ -#define XMC4_GCU_STCON_OFFSET 0x0010 /* Start-up Control */ -#define XMC4_GCU_GPR0_OFFSET 0x002c /* General Purpose Register 0 */ -#define XMC4_GCU_GPR1_OFFSET 0x0030 /* General Purpose Register 1 */ -#define XMC4_GCU_ETH0CON_OFFSET 0x0040 /* Ethernet 0 Port Control */ -#define XMC4_GCU_CCUCON_OFFSET 0x004c /* CCUx Global Start Control Register */ -#define XMC4_GCU_SRSTAT_OFFSET 0x0074 /* Service Request Status */ -#define XMC4_GCU_SRRAW_OFFSET 0x0078 /* RAW Service Request Status */ -#define XMC4_GCU_SRMSK_OFFSET 0x007c /* Service Request Mask */ -#define XMC4_GCU_SRCLR_OFFSET 0x0080 /* Service Request Clear */ -#define XMC4_GCU_SRSET_OFFSET 0x0084 /* Service Request Set */ -#define XMC4_GCU_NMIREQEN_OFFSET 0x0088 /* Enable Promoting Events to NMI Request */ -#define XMC4_GCU_DTSCON_OFFSET 0x008c /* DTS Control */ -#define XMC4_GCU_DTSSTAT_OFFSET 0x0090 /* DTS Status */ -#define XMC4_GCU_SDMMCDEL_OFFSET 0x009c /* SD-MMC Delay Control Register */ -#define XMC4_GCU_G0ORCEN_OFFSET 0x00a0 /* Out-Of-Range Comparator Enable Register 0 */ -#define XMC4_GCU_G1ORCEN_OFFSET 0x00a4 /* Out-Of-Range Comparator Enable Register 1 */ -#define XMC4_GCU_MIRRSTS_OFFSET 0x00c4 /* Mirror Update Status Register */ -#define XMC4_GCU_RMACR_OFFSET 0x00c8 /* Retention Memory Access Control Register */ -#define XMC4_GCU_RMADATA_OFFSET 0x00cc /* Retention Memory Access Data Register */ -#define XMC4_GCU_PEEN_OFFSET 0x013c /* Parity Error Enable Register */ -#define XMC4_GCU_MCHKCON_OFFSET 0x0140 /* Memory Checking Control Register */ -#define XMC4_GCU_PETE_OFFSET 0x0144 /* Parity Error Trap Enable Register */ -#define XMC4_GCU_PERSTEN_OFFSET 0x0148 /* Reset upon Parity Error Enable Register */ -#define XMC4_GCU_PEFLAG_OFFSET 0x0150 /* Parity Error Control Register */ -#define XMC4_GCU_PMTPR_OFFSET 0x0154 /* Parity Memory Test Pattern Register */ -#define XMC4_GCU_PMTSR_OFFSET 0x0158 /* Parity Memory Test Select Register */ -#define XMC4_GCU_TRAPSTAT_OFFSET 0x0160 /* Trap Status Register */ -#define XMC4_GCU_TRAPRAW_OFFSET 0x0164 /* Trap Raw Status Register */ -#define XMC4_GCU_TRAPDIS_OFFSET 0x0168 /* Trap Mask Register */ -#define XMC4_GCU_TRAPCLR_OFFSET 0x016c /* Trap Clear Register */ -#define XMC4_GCU_TRAPSET_OFFSET 0x0170 /* Trap Set Register */ - -/* PCU Registers */ - -#define XMC4_PCU_PWRSTAT_OFFSET 0x0000 /* Power Status Register */ -#define XMC4_PCU_PWRSET_OFFSET 0x0004 /* Power Set Control Register */ -#define XMC4_PCU_PWRCLR_OFFSET 0x0008 /* Power Clear Control Register */ -#define XMC4_PCU_EVRSTAT_OFFSET 0x0010 /* EVR Status Register */ -#define XMC4_PCU_EVRVADCSTAT_OFFSET 0x0014 /* EVR VADC Status Register */ -#define XMC4_PCU_PWRMON_OFFSET 0x002c /* Power Monitor Value */ - -/* HCU Registers */ - -#define XMC4_HCU_HDSTAT_OFFSET 0x0000 /* Hibernate Domain Status Register */ -#define XMC4_HCU_HDCLR_OFFSET 0x0004 /* Hibernate Domain Status Clear Register */ -#define XMC4_HCU_HDSET_OFFSET 0x0008 /* Hibernate Domain Status Set Register */ -#define XMC4_HCU_HDCR_OFFSET 0x000c /* Hibernate Domain Control Register */ -#define XMC4_HCU_OSCSICTRL_OFFSET 0x0014 /* Internal 32.768 kHz Clock Source Control Register */ -#define XMC4_HCU_OSCULSTAT_OFFSET 0x0018 /* OSC_ULP Status Register */ -#define XMC4_HCU_OSCULCTRL_OFFSET 0x001c /* OSC_ULP Control Register */ - -/* RCU Registers */ - -#define XMC4_RCU_RSTSTAT_OFFSET 0x0000 /* System Reset Status */ -#define XMC4_RCU_RSTSET_OFFSET 0x0004 /* Reset Set Register */ -#define XMC4_RCU_RSTCLR_OFFSET 0x0008 /* Reset Clear Register */ -#define XMC4_RCU_PRSTAT0_OFFSET 0x000c /* Peripheral Reset Status Register 0 */ -#define XMC4_RCU_PRSET0_OFFSET 0x0010 /* Peripheral Reset Set Register 0 */ -#define XMC4_RCU_PRCLR0_OFFSET 0x0014 /* Peripheral Reset Clear Register 0 */ -#define XMC4_RCU_PRSTAT1_OFFSET 0x0018 /* Peripheral Reset Status Register 1 */ -#define XMC4_RCU_PRSET1_OFFSET 0x001c /* Peripheral Reset Set Register 1 */ -#define XMC4_RCU_PRCLR1_OFFSET 0x0020 /* Peripheral Reset Clear Register 1 */ -#define XMC4_RCU_PRSTAT2_OFFSET 0x0024 /* Peripheral Reset Status Register 2 */ -#define XMC4_RCU_PRSET2_OFFSET 0x0028 /* Peripheral Reset Set Register 2 */ -#define XMC4_RCU_PRCLR2_OFFSET 0x002c /* Peripheral Reset Clear Register 2 */ -#define XMC4_RCU_PRSTAT3_OFFSET 0x0030 /* Peripheral Reset Status Register 3 */ -#define XMC4_RCU_PRSET3_OFFSET 0x0034 /* Peripheral Reset Set Register 3 */ -#define XMC4_RCU_PRCLR3_OFFSET 0x0038 /* Peripheral Reset Clear Register 3 */ - -/* CCU Registers */ - -#define XMC4_CCU_CLKSTAT_OFFSET 0x0000 /* Clock Status Register */ -#define XMC4_CCU_CLKSET_OFFSET 0x0004 /* Clock Set Control Register */ -#define XMC4_CCU_CLKCLR_OFFSET 0x0008 /* Clock clear Control Register */ -#define XMC4_CCU_SYSCLKCR_OFFSET 0x000c /* System Clock Control */ -#define XMC4_CCU_CPUCLKCR_OFFSET 0x0010 /* CPU Clock Control */ -#define XMC4_CCU_PBCLKCR_OFFSET 0x0014 /* Peripheral Bus Clock Control */ -#define XMC4_CCU_USBCLKCR_OFFSET 0x0018 /* USB Clock Control */ -#define XMC4_CCU_EBUCLKCR_OFFSET 0x001c /* EBU Clock Control */ -#define XMC4_CCU_CCUCLKCR_OFFSET 0x0020 /* CCU Clock Control */ -#define XMC4_CCU_WDTCLKCR_OFFSET 0x0024 /* WDT Clock Control */ -#define XMC4_CCU_EXTCLKCR_OFFSET 0x0028 /* External clock Control Register */ -#define XMC4_CCU_SLEEPCR_OFFSET 0x0030 /* Sleep Control Register */ -#define XMC4_CCU_DSLEEPCR_OFFSET 0x0034 /* Deep Sleep Control Register */ -#define XMC4_CCU_OSCHPSTAT_OFFSET 0x0100 /* OSC_HP Status Register */ -#define XMC4_CCU_OSCHPCTRL_OFFSET 0x0104 /* OSC_HP Control Register */ -#define XMC4_CCU_CLKCALCONST_OFFSET 0x010c /* Clock Calibration Constant Register */ -#define XMC4_CCU_PLLSTAT_OFFSET 0x0110 /* System PLL Status Register */ -#define XMC4_CCU_PLLCON0_OFFSET 0x0114 /* System PLL Configuration 0 Register */ -#define XMC4_CCU_PLLCON1_OFFSET 0x0118 /* System PLL Configuration 1 Register */ -#define XMC4_CCU_PLLCON2_OFFSET 0x011c /* System PLL Configuration 2 Register */ -#define XMC4_CCU_USBPLLSTAT_OFFSET 0x0120 /* USB PLL Status Register */ -#define XMC4_CCU_USBPLLCON_OFFSET 0x0124 /* USB PLL Control Register */ -#define XMC4_CCU_CLKMXSTAT_OFFSET 0x0138 /* Clock Multiplexing Status Register */ +#define XMC4_SCU_ID_OFFSET 0x0000 /* Module Identification Register */ +#define XMC4_SCU_IDCHIP_OFFSET 0x0004 /* Chip ID */ +#define XMC4_SCU_IDMANUF_OFFSET 0x0008 /* Manufactory ID */ +#define XMC4_SCU_STCON_OFFSET 0x0010 /* Start-up Control */ +#define XMC4_SCU_GPR0_OFFSET 0x002c /* General Purpose Register 0 */ +#define XMC4_SCU_GPR1_OFFSET 0x0030 /* General Purpose Register 1 */ +#define XMC4_SCU_ETH0CON_OFFSET 0x0040 /* Ethernet 0 Port Control */ +#define XMC4_SCU_CCUCON_OFFSET 0x004c /* CCUx Global Start Control Register */ +#define XMC4_SCU_DTSCON_OFFSET 0x008c /* DTS Control */ +#define XMC4_SCU_DTSSTAT_OFFSET 0x0090 /* DTS Status */ +#define XMC4_SCU_SDMMCDEL_OFFSET 0x009c /* SD-MMC Delay Control Register */ +#define XMC4_SCU_G0ORCEN_OFFSET 0x00a0 /* Out-Of-Range Comparator Enable Register 0 */ +#define XMC4_SCU_G1ORCEN_OFFSET 0x00a4 /* Out-Of-Range Comparator Enable Register 1 */ +#define XMC4_SCU_MIRRSTS_OFFSET 0x00c4 /* Mirror Update Status Register */ +#define XMC4_SCU_RMACR_OFFSET 0x00c8 /* Retention Memory Access Control Register */ +#define XMC4_SCU_RMADATA_OFFSET 0x00cc /* Retention Memory Access Data Register */ + +/* Ethernet Control SCU Resters */ + +#define XMC4_SCU_ETHCON_OFFSET 0x0000 /* Ethernet 0 Port Control Register */ + +/* Interrupt Control SCU Registers */ + +#define XMC4_SCU_SRSTAT_OFFSET 0x0000 /* Service Request Status */ +#define XMC4_SCU_SRRAW_OFFSET 0x0004 /* RAW Service Request Status */ +#define XMC4_SCU_SRMSK_OFFSET 0x0008 /* Service Request Mask */ +#define XMC4_SCU_SRCLR_OFFSET 0x000c /* Service Request Clear */ +#define XMC4_SCU_SRSET_OFFSET 0x0010 /* Service Request Set */ +#define XMC4_SCU_NMIREQEN_OFFSET 0x0014 /* Enable Promoting Events to NMI Request */ + +/* SDMMC Control SCU Registers */ + +#define XMC4_SCU_SDMMCCON_OFFSET 0x0000 /* SDMMC Configuration */ + +/* Parity Control Registers */ + +#define XMC4_SCU_PEEN_OFFSET 0x0000 /* Parity Error Enable Register */ +#define XMC4_SCU_MCHKCON_OFFSET 0x0004 /* Memory Checking Control Register */ +#define XMC4_SCU_PETE_OFFSET 0x0008 /* Parity Error Trap Enable Register */ +#define XMC4_SCU_PERSTEN_OFFSET 0x000c /* Reset upon Parity Error Enable Register */ +#define XMC4_SCU_PEFLAG_OFFSET 0x0014 /* Parity Error Control Register */ +#define XMC4_SCU_PMTPR_OFFSET 0x0018 /* Parity Memory Test Pattern Register */ +#define XMC4_SCU_PMTSR_OFFSET 0x001c /* Parity Memory Test Select Register */ + +/* Trap Control Registers */ + +#define XMC4_SCU_TRAPSTAT_OFFSET 0x0000 /* Trap Status Register */ +#define XMC4_SCU_TRAPRAW_OFFSET 0x0004 /* Trap Raw Status Register */ +#define XMC4_SCU_TRAPDIS_OFFSET 0x0008 /* Trap Mask Register */ +#define XMC4_SCU_TRAPCLR_OFFSET 0x000c /* Trap Clear Register */ +#define XMC4_SCU_TRAPSET_OFFSET 0x0010 /* Trap Set Register */ + +/* Power Control SCU Registers */ + +#define XMC4_SCU_PWRSTAT_OFFSET 0x0000 /* Power Status Register */ +#define XMC4_SCU_PWRSET_OFFSET 0x0004 /* Power Set Control Register */ +#define XMC4_SCU_PWRCLR_OFFSET 0x0008 /* Power Clear Control Register */ +#define XMC4_SCU_EVRSTAT_OFFSET 0x0010 /* EVR Status Register */ +#define XMC4_SCU_EVRVADCSTAT_OFFSET 0x0014 /* EVR VADC Status Register */ +#define XMC4_SCU_PWRMON_OFFSET 0x002c /* Power Monitor Value */ + +/* Hibernation SCU Registers */ + +#define XMC4_SCU_HDSTAT_OFFSET 0x0000 /* Hibernate Domain Status Register */ +#define XMC4_SCU_HDCLR_OFFSET 0x0004 /* Hibernate Domain Status Clear Register */ +#define XMC4_SCU_HDSET_OFFSET 0x0008 /* Hibernate Domain Status Set Register */ +#define XMC4_SCU_HDCR_OFFSET 0x000c /* Hibernate Domain Control Register */ +#define XMC4_SCU_OSCSICTRL_OFFSET 0x0014 /* Internal 32.768 kHz Clock Source Control Register */ +#define XMC4_SCU_OSCULSTAT_OFFSET 0x0018 /* OSC_ULP Status Register */ +#define XMC4_SCU_OSCULCTRL_OFFSET 0x001c /* OSC_ULP Control Register */ + +/* Reset SCU Registers */ + +#define XMC4_SCU_RSTSTAT_OFFSET 0x0000 /* System Reset Status */ +#define XMC4_SCU_RSTSET_OFFSET 0x0004 /* Reset Set Register */ +#define XMC4_SCU_RSTCLR_OFFSET 0x0008 /* Reset Clear Register */ +#define XMC4_SCU_PRSTAT0_OFFSET 0x000c /* Peripheral Reset Status Register 0 */ +#define XMC4_SCU_PRSET0_OFFSET 0x0010 /* Peripheral Reset Set Register 0 */ +#define XMC4_SCU_PRCLR0_OFFSET 0x0014 /* Peripheral Reset Clear Register 0 */ +#define XMC4_SCU_PRSTAT1_OFFSET 0x0018 /* Peripheral Reset Status Register 1 */ +#define XMC4_SCU_PRSET1_OFFSET 0x001c /* Peripheral Reset Set Register 1 */ +#define XMC4_SCU_PRCLR1_OFFSET 0x0020 /* Peripheral Reset Clear Register 1 */ +#define XMC4_SCU_PRSTAT2_OFFSET 0x0024 /* Peripheral Reset Status Register 2 */ +#define XMC4_SCU_PRSET2_OFFSET 0x0028 /* Peripheral Reset Set Register 2 */ +#define XMC4_SCU_PRCLR2_OFFSET 0x002c /* Peripheral Reset Clear Register 2 */ +#define XMC4_SCU_PRSTAT3_OFFSET 0x0030 /* Peripheral Reset Status Register 3 */ +#define XMC4_SCU_PRSET3_OFFSET 0x0034 /* Peripheral Reset Set Register 3 */ +#define XMC4_SCU_PRCLR3_OFFSET 0x0038 /* Peripheral Reset Clear Register 3 */ + +/* Clock Control SCU Registers */ + +#define XMC4_SCU_CLKSTAT_OFFSET 0x0000 /* Clock Status Register */ +#define XMC4_SCU_CLKSET_OFFSET 0x0004 /* Clock Set Control Register */ +#define XMC4_SCU_CLKCLR_OFFSET 0x0008 /* Clock clear Control Register */ +#define XMC4_SCU_SYSCLKCR_OFFSET 0x000c /* System Clock Control */ +#define XMC4_SCU_CPUCLKCR_OFFSET 0x0010 /* CPU Clock Control */ +#define XMC4_SCU_PBCLKCR_OFFSET 0x0014 /* Peripheral Bus Clock Control */ +#define XMC4_SCU_USBCLKCR_OFFSET 0x0018 /* USB Clock Control */ +#define XMC4_SCU_EBUCLKCR_OFFSET 0x001c /* EBU Clock Control */ +#define XMC4_SCU_CCUCLKCR_OFFSET 0x0020 /* CCU Clock Control */ +#define XMC4_SCU_WDTCLKCR_OFFSET 0x0024 /* WDT Clock Control */ +#define XMC4_SCU_EXTCLKCR_OFFSET 0x0028 /* External clock Control Register */ +#define XMC4_SCU_SLEEPCR_OFFSET 0x0030 /* Sleep Control Register */ +#define XMC4_SCU_DSLEEPCR_OFFSET 0x0034 /* Deep Sleep Control Register */ +#define XMC4_SCU_CGATSTAT0_OFFSET 0x0040 /* Peripheral 0 Clock Gating Status */ +#define XMC4_SCU_CGATSET0_OFFSET 0x0044 /* Peripheral 0 Clock Gating Set */ +#define XMC4_SCU_CGATCLR0_OFFSET 0x0048 /* Peripheral 0 Clock Gating Clear */ +#define XMC4_SCU_CGATSTAT1_OFFSET 0x004c /* Peripheral 1 Clock Gating Status */ +#define XMC4_SCU_CGATSET1_OFFSET 0x0050 /* Peripheral 1 Clock Gating Set */ +#define XMC4_SCU_CGATCLR1_OFFSET 0x0054 /* Peripheral 1 Clock Gating Clear */ +#define XMC4_SCU_CGATSTAT2_OFFSET 0x0058 /* Peripheral 2 Clock Gating Status */ +#define XMC4_SCU_CGATSET2_OFFSET 0x005c /* Peripheral 2 Clock Gating Set */ +#define XMC4_SCU_CGATCLR2_OFFSET 0x0060 /* Peripheral 2 Clock Gating Clear */ +#define XMC4_SCU_CGATSTAT3_OFFSET 0x0064 /* Peripheral 3 Clock Gating Status */ +#define XMC4_SCU_CGATSET3_OFFSET 0x0068 /* Peripheral 3 Clock Gating Set */ +#define XMC4_SCU_CGATCLR3_OFFSET 0x006c /* Peripheral 3 Clock Gating Clear */ + +/* Oscillator Control SCU Registers */ + +#define XMC4_OCU_OSCHPSTAT_OFFSET 0x0000 /* OSC_HP Status Register */ +#define XMC4_OCU_OSCHPCTRL_OFFSET 0x0004 /* OSC_HP Control Register */ +#define XMC4_OCU_CLKCALCONST_OFFSET 0x000c /* Clock Calibration Constant Register */ + +/* PLL Control SCU Registers */ + +#define XMC4_SCU_PLLSTAT_OFFSET 0x0000 /* System PLL Status Register */ +#define XMC4_SCU_PLLCON0_OFFSET 0x0004 /* System PLL Configuration 0 Register */ +#define XMC4_SCU_PLLCON1_OFFSET 0x0008 /* System PLL Configuration 1 Register */ +#define XMC4_SCU_PLLCON2_OFFSET 0x000c /* System PLL Configuration 2 Register */ +#define XMC4_SCU_USBPLLSTAT_OFFSET 0x0010 /* USB PLL Status Register */ +#define XMC4_SCU_USBPLLCON_OFFSET 0x0014 /* USB PLL Control Register */ +#define XMC4_SCU_CLKMXSTAT_OFFSET 0x0028 /* Clock Multiplexing Status Register */ /* Register Addresses ***************************************************************/ - -#define XMC4_GCU_BASE (XMC4_SCU_BASE+XMC4_GCU_OFFSET) -#define XMC4_PCU_BASE (XMC4_SCU_BASE+XMC4_PCU_OFFSET) -#define XMC4_HCU_BASE (XMC4_SCU_BASE+XMC4_HCU_OFFSET) -#define XMC4_RCU_BASE (XMC4_SCU_BASE+XMC4_RCU_OFFSET) -#define XMC4_CCU_BASE (XMC4_SCU_BASE+XMC4_CCU_OFFSET) - /* General SCU Registers */ -#define XMC4_GCU_ID (XMC4_GCU_BASE+XMC4_GCU_ID_OFFSET) -#define XMC4_GCU_IDCHIP (XMC4_GCU_BASE+XMC4_GCU_IDCHIP_OFFSET) -#define XMC4_GCU_IDMANUF (XMC4_GCU_BASE+XMC4_GCU_IDMANUF_OFFSET) -#define XMC4_GCU_STCON (XMC4_GCU_BASE+XMC4_GCU_STCON_OFFSET) -#define XMC4_GCU_GPR0 (XMC4_GCU_BASE+XMC4_GCU_GPR0_OFFSET) -#define XMC4_GCU_GPR1 (XMC4_GCU_BASE+XMC4_GCU_GPR1_OFFSET) -#define XMC4_GCU_ETH0CON (XMC4_GCU_BASE+XMC4_GCU_ETH0CON_OFFSET) -#define XMC4_GCU_CCUCON (XMC4_GCU_BASE+XMC4_GCU_CCUCON_OFFSET) -#define XMC4_GCU_SRSTAT (XMC4_GCU_BASE+XMC4_GCU_SRSTAT_OFFSET) -#define XMC4_GCU_SRRAW (XMC4_GCU_BASE+XMC4_GCU_SRRAW_OFFSET) -#define XMC4_GCU_SRMSK (XMC4_GCU_BASE+XMC4_GCU_SRMSK_OFFSET) -#define XMC4_GCU_SRCLR (XMC4_GCU_BASE+XMC4_GCU_SRCLR_OFFSET) -#define XMC4_GCU_SRSET (XMC4_GCU_BASE+XMC4_GCU_SRSET_OFFSET) -#define XMC4_GCU_NMIREQEN (XMC4_GCU_BASE+XMC4_GCU_NMIREQEN_OFFSET) -#define XMC4_GCU_DTSCON (XMC4_GCU_BASE+XMC4_GCU_DTSCON_OFFSET) -#define XMC4_GCU_DTSSTAT (XMC4_GCU_BASE+XMC4_GCU_DTSSTAT_OFFSET) -#define XMC4_GCU_SDMMCDEL (XMC4_GCU_BASE+XMC4_GCU_SDMMCDEL_OFFSET) -#define XMC4_GCU_G0ORCEN (XMC4_GCU_BASE+XMC4_GCU_G0ORCEN_OFFSET) -#define XMC4_GCU_G1ORCEN (XMC4_GCU_BASE+XMC4_GCU_G1ORCEN_OFFSET) -#define XMC4_GCU_MIRRSTS (XMC4_GCU_BASE+XMC4_GCU_MIRRSTS_OFFSET) -#define XMC4_GCU_RMACR (XMC4_GCU_BASE+XMC4_GCU_RMACR_OFFSET) -#define XMC4_GCU_RMADATA (XMC4_GCU_BASE+XMC4_GCU_RMADATA_OFFSET) -#define XMC4_GCU_PEEN (XMC4_GCU_BASE+XMC4_GCU_PEEN_OFFSET) -#define XMC4_GCU_MCHKCON (XMC4_GCU_BASE+XMC4_GCU_MCHKCON_OFFSET) -#define XMC4_GCU_PETE (XMC4_GCU_BASE+XMC4_GCU_PETE_OFFSET) -#define XMC4_GCU_PERSTEN (XMC4_GCU_BASE+XMC4_GCU_PERSTEN_OFFSET) -#define XMC4_GCU_PEFLAG (XMC4_GCU_BASE+XMC4_GCU_PEFLAG_OFFSET) -#define XMC4_GCU_PMTPR (XMC4_GCU_BASE+XMC4_GCU_PMTPR_OFFSET) -#define XMC4_GCU_PMTSR (XMC4_GCU_BASE+XMC4_GCU_PMTSR_OFFSET) -#define XMC4_GCU_TRAPSTAT (XMC4_GCU_BASE+XMC4_GCU_TRAPSTAT_OFFSET) -#define XMC4_GCU_TRAPRAW (XMC4_GCU_BASE+XMC4_GCU_TRAPRAW_OFFSET) -#define XMC4_GCU_TRAPDIS (XMC4_GCU_BASE+XMC4_GCU_TRAPDIS_OFFSET) -#define XMC4_GCU_TRAPCLR (XMC4_GCU_BASE+XMC4_GCU_TRAPCLR_OFFSET) -#define XMC4_GCU_TRAPSET (XMC4_GCU_BASE+XMC4_GCU_TRAPSET_OFFSET) - -/* PCU Registers */ - -#define XMC4_PCU_PWRSTAT (XMC4_PCU_BASE+XMC4_PCU_PWRSTAT_OFFSET) -#define XMC4_PCU_PWRSET (XMC4_PCU_BASE+XMC4_PCU_PWRSET_OFFSET) -#define XMC4_PCU_PWRCLR (XMC4_PCU_BASE+XMC4_PCU_PWRCLR_OFFSET) -#define XMC4_PCU_EVRSTAT (XMC4_PCU_BASE+XMC4_PCU_EVRSTAT_OFFSET) -#define XMC4_PCU_EVRVADCSTAT (XMC4_PCU_BASE+XMC4_PCU_EVRVADCSTAT_OFFSET) -#define XMC4_PCU_PWRMON (XMC4_PCU_BASE+XMC4_PCU_PWRMON_OFFSET) - -/* HCU Registers */ - -#define XMC4_HCU_HDSTAT (XMC4_HCU_BASE+XMC4_HCU_HDSTAT_OFFSET) -#define XMC4_HCU_HDCLR (XMC4_HCU_BASE+XMC4_HCU_HDCLR_OFFSET) -#define XMC4_HCU_HDSET (XMC4_HCU_BASE+XMC4_HCU_HDSET_OFFSET) -#define XMC4_HCU_HDCR (XMC4_HCU_BASE+XMC4_HCU_HDCR_OFFSET) -#define XMC4_HCU_OSCSICTRL (XMC4_HCU_BASE+XMC4_HCU_OSCSICTRL_OFFSET) -#define XMC4_HCU_OSCULSTAT (XMC4_HCU_BASE+XMC4_HCU_OSCULSTAT_OFFSET) -#define XMC4_HCU_OSCULCTRL (XMC4_HCU_BASE+XMC4_HCU_OSCULCTRL_OFFSET) - -/* RCU Registers */ - -#define XMC4_RCU_RSTSTAT (XMC4_RCU_BASE+XMC4_RCU_RSTSTAT_OFFSET) -#define XMC4_RCU_RSTSET (XMC4_RCU_BASE+XMC4_RCU_RSTSET_OFFSET) -#define XMC4_RCU_RSTCLR (XMC4_RCU_BASE+XMC4_RCU_RSTCLR_OFFSET) -#define XMC4_RCU_PRSTAT0 (XMC4_RCU_BASE+XMC4_RCU_PRSTAT0_OFFSET) -#define XMC4_RCU_PRSET0 (XMC4_RCU_BASE+XMC4_RCU_PRSET0_OFFSET) -#define XMC4_RCU_PRCLR0 (XMC4_RCU_BASE+XMC4_RCU_PRCLR0_OFFSET) -#define XMC4_RCU_PRSTAT1 (XMC4_RCU_BASE+XMC4_RCU_PRSTAT1_OFFSET) -#define XMC4_RCU_PRSET1 (XMC4_RCU_BASE+XMC4_RCU_PRSET1_OFFSET) -#define XMC4_RCU_PRCLR1 (XMC4_RCU_BASE+XMC4_RCU_PRCLR1_OFFSET) -#define XMC4_RCU_PRSTAT2 (XMC4_RCU_BASE+XMC4_RCU_PRSTAT2_OFFSET) -#define XMC4_RCU_PRSET2 (XMC4_RCU_BASE+XMC4_RCU_PRSET2_OFFSET) -#define XMC4_RCU_PRCLR2 (XMC4_RCU_BASE+XMC4_RCU_PRCLR2_OFFSET) -#define XMC4_RCU_PRSTAT3 (XMC4_RCU_BASE+XMC4_RCU_PRSTAT3_OFFSET) -#define XMC4_RCU_PRSET3 (XMC4_RCU_BASE+XMC4_RCU_PRSET3_OFFSET) -#define XMC4_RCU_PRCLR3 (XMC4_RCU_BASE+XMC4_RCU_PRCLR3_OFFSET) - -/* CCU Registers */ - -#define XMC4_CCU_CLKSTAT (XMC4_CCU_BASE+XMC4_CCU_CLKSTAT_OFFSET) -#define XMC4_CCU_CLKSET (XMC4_CCU_BASE+XMC4_CCU_CLKSET_OFFSET) -#define XMC4_CCU_CLKCLR (XMC4_CCU_BASE+XMC4_CCU_CLKCLR_OFFSET) -#define XMC4_CCU_SYSCLKCR (XMC4_CCU_BASE+XMC4_CCU_SYSCLKCR_OFFSET) -#define XMC4_CCU_CPUCLKCR (XMC4_CCU_BASE+XMC4_CCU_CPUCLKCR_OFFSET) -#define XMC4_CCU_PBCLKCR (XMC4_CCU_BASE+XMC4_CCU_PBCLKCR_OFFSET) -#define XMC4_CCU_USBCLKCR (XMC4_CCU_BASE+XMC4_CCU_USBCLKCR_OFFSET) -#define XMC4_CCU_EBUCLKCR (XMC4_CCU_BASE+XMC4_CCU_EBUCLKCR_OFFSET) -#define XMC4_CCU_CCUCLKCR (XMC4_CCU_BASE+XMC4_CCU_CCUCLKCR_OFFSET) -#define XMC4_CCU_WDTCLKCR (XMC4_CCU_BASE+XMC4_CCU_WDTCLKCR_OFFSET) -#define XMC4_CCU_EXTCLKCR (XMC4_CCU_BASE+XMC4_CCU_EXTCLKCR_OFFSET) -#define XMC4_CCU_SLEEPCR (XMC4_CCU_BASE+XMC4_CCU_SLEEPCR_OFFSET) -#define XMC4_CCU_DSLEEPCR (XMC4_CCU_BASE+XMC4_CCU_DSLEEPCR_OFFSET) -#define XMC4_CCU_OSCHPSTAT (XMC4_CCU_BASE+XMC4_CCU_OSCHPSTAT_OFFSET) -#define XMC4_CCU_OSCHPCTRL (XMC4_CCU_BASE+XMC4_CCU_OSCHPCTRL_OFFSET) -#define XMC4_CCU_CLKCALCONST (XMC4_CCU_BASE+XMC4_CCU_CLKCALCONST_OFFSET) -#define XMC4_CCU_PLLSTAT (XMC4_CCU_BASE+XMC4_CCU_PLLSTAT_OFFSET) -#define XMC4_CCU_PLLCON0 (XMC4_CCU_BASE+XMC4_CCU_PLLCON0_OFFSET) -#define XMC4_CCU_PLLCON1 (XMC4_CCU_BASE+XMC4_CCU_PLLCON1_OFFSET) -#define XMC4_CCU_PLLCON2 (XMC4_CCU_BASE+XMC4_CCU_PLLCON2_OFFSET) -#define XMC4_CCU_USBPLLSTAT (XMC4_CCU_BASE+XMC4_CCU_USBPLLSTAT_OFFSET) -#define XMC4_CCU_USBPLLCON (XMC4_CCU_BASE+XMC4_CCU_USBPLLCON_OFFSET) -#define XMC4_CCU_CLKMXSTAT (XMC4_CCU_BASE+XMC4_CCU_CLKMXSTAT_OFFSET) +#define XMC4_SCU_ID (XMC4_SCU_GENERAL_BASE+XMC4_SCU_ID_OFFSET) +#define XMC4_SCU_IDCHIP (XMC4_SCU_GENERAL_BASE+XMC4_SCU_IDCHIP_OFFSET) +#define XMC4_SCU_IDMANUF (XMC4_SCU_GENERAL_BASE+XMC4_SCU_IDMANUF_OFFSET) +#define XMC4_SCU_STCON (XMC4_SCU_GENERAL_BASE+XMC4_SCU_STCON_OFFSET) +#define XMC4_SCU_GPR0 (XMC4_SCU_GENERAL_BASE+XMC4_SCU_GPR0_OFFSET) +#define XMC4_SCU_GPR1 (XMC4_SCU_GENERAL_BASE+XMC4_SCU_GPR1_OFFSET) +#define XMC4_SCU_ETH0CON (XMC4_SCU_GENERAL_BASE+XMC4_SCU_ETH0CON_OFFSET) +#define XMC4_SCU_CCUCON (XMC4_SCU_GENERAL_BASE+XMC4_SCU_CCUCON_OFFSET) +#define XMC4_SCU_DTSCON (XMC4_SCU_GENERAL_BASE+XMC4_SCU_DTSCON_OFFSET) +#define XMC4_SCU_DTSSTAT (XMC4_SCU_GENERAL_BASE+XMC4_SCU_DTSSTAT_OFFSET) +#define XMC4_SCU_SDMMCDEL (XMC4_SCU_GENERAL_BASE+XMC4_SCU_SDMMCDEL_OFFSET) +#define XMC4_SCU_G0ORCEN (XMC4_SCU_GENERAL_BASE+XMC4_SCU_G0ORCEN_OFFSET) +#define XMC4_SCU_G1ORCEN (XMC4_SCU_GENERAL_BASE+XMC4_SCU_G1ORCEN_OFFSET) +#define XMC4_SCU_MIRRSTS (XMC4_SCU_GENERAL_BASE+XMC4_SCU_MIRRSTS_OFFSET) +#define XMC4_SCU_RMACR (XMC4_SCU_GENERAL_BASE+XMC4_SCU_RMACR_OFFSET) +#define XMC4_SCU_RMADATA (XMC4_SCU_GENERAL_BASE+XMC4_SCU_RMADATA_OFFSET) + +/* Ethernet Control SCU Registers */ + +#define XMC4_SCU_ETHCON (XMC4_ETH0_CON_BASE+XMC4_SCU_ETHCON_OFFSET) + +/* Parity Control Registers */ + +#define XMC4_SCU_PEEN (XMC4_SCU_PARITY_BASE+XMC4_SCU_PEEN_OFFSET) +#define XMC4_SCU_MCHKCON (XMC4_SCU_PARITY_BASE+XMC4_SCU_MCHKCON_OFFSET) +#define XMC4_SCU_PETE (XMC4_SCU_PARITY_BASE+XMC4_SCU_PETE_OFFSET) +#define XMC4_SCU_PERSTEN (XMC4_SCU_PARITY_BASE+XMC4_SCU_PERSTEN_OFFSET) +#define XMC4_SCU_PEFLAG (XMC4_SCU_PARITY_BASE+XMC4_SCU_PEFLAG_OFFSET) +#define XMC4_SCU_PMTPR (XMC4_SCU_PARITY_BASE+XMC4_SCU_PMTPR_OFFSET) +#define XMC4_SCU_PMTSR (XMC4_SCU_PARITY_BASE+XMC4_SCU_PMTSR_OFFSET) + +/* Trap Control Registers */ + +#define XMC4_SCU_TRAPSTAT (XMC4_SCU_TRAP_BASE+XMC4_SCU_TRAPSTAT_OFFSET) +#define XMC4_SCU_TRAPRAW (XMC4_SCU_TRAP_BASE+XMC4_SCU_TRAPRAW_OFFSET) +#define XMC4_SCU_TRAPDIS (XMC4_SCU_TRAP_BASE+XMC4_SCU_TRAPDIS_OFFSET) +#define XMC4_SCU_TRAPCLR (XMC4_SCU_TRAP_BASE+XMC4_SCU_TRAPCLR_OFFSET) +#define XMC4_SCU_TRAPSET (XMC4_SCU_TRAP_BASE+XMC4_SCU_TRAPSET_OFFSET) + +/* Ethernet Control SCU Resters */ + +#define XMC4_SCU_ETHCON_OFFSET 0x0000 /* Ethernet 0 Port Control Register */ +#define XMC4_SCU_ETHCON_OFFSET 0x0000 /* Ethernet 0 Port Control Register */ + +/* Interrupt Control SCU Registers */ + +#define XMC4_SCU_SRSTAT (XMC4_SCU_INTERRUPT_BASE+XMC4_SCU_SRSTAT_OFFSET) +#define XMC4_SCU_SRRAW (XMC4_SCU_INTERRUPT_BASE+XMC4_SCU_SRRAW_OFFSET) +#define XMC4_SCU_SRMSK (XMC4_SCU_INTERRUPT_BASE+XMC4_SCU_SRMSK_OFFSET) +#define XMC4_SCU_SRCLR (XMC4_SCU_INTERRUPT_BASE+XMC4_SCU_SRCLR_OFFSET) +#define XMC4_SCU_SRSET (XMC4_SCU_INTERRUPT_BASE+XMC4_SCU_SRSET_OFFSET) +#define XMC4_SCU_NMIREQEN (XMC4_SCU_INTERRUPT_BASE+XMC4_SCU_NMIREQEN_OFFSET) + +/* SDMMC Control SCU Registers */ + +#define XMC4_SCU_SDMMCCON (XMC4_SDMMC_CON_BASE+XMC4_SCU_SDMMCCON_OFFSET) + +/* Power control SCU Registers */ + +#define XMC4_SCU_PWRSTAT (XMC4_SCU_POWER_BASE+XMC4_SCU_PWRSTAT_OFFSET) +#define XMC4_SCU_PWRSET (XMC4_SCU_POWER_BASE+XMC4_SCU_PWRSET_OFFSET) +#define XMC4_SCU_PWRCLR (XMC4_SCU_POWER_BASE+XMC4_SCU_PWRCLR_OFFSET) +#define XMC4_SCU_EVRSTAT (XMC4_SCU_POWER_BASE+XMC4_SCU_EVRSTAT_OFFSET) +#define XMC4_SCU_EVRVADCSTAT (XMC4_SCU_POWER_BASE+XMC4_SCU_EVRVADCSTAT_OFFSET) +#define XMC4_SCU_PWRMON (XMC4_SCU_POWER_BASE+XMC4_SCU_PWRMON_OFFSET) + +/* Hibernation SCU Registers */ + +#define XMC4_SCU_HDSTAT (XMC4_SCU_HIBERNATE_BASE+XMC4_SCU_HDSTAT_OFFSET) +#define XMC4_SCU_HDCLR (XMC4_SCU_HIBERNATE_BASE+XMC4_SCU_HDCLR_OFFSET) +#define XMC4_SCU_HDSET (XMC4_SCU_HIBERNATE_BASE+XMC4_SCU_HDSET_OFFSET) +#define XMC4_SCU_HDCR (XMC4_SCU_HIBERNATE_BASE+XMC4_SCU_HDCR_OFFSET) +#define XMC4_SCU_OSCSICTRL (XMC4_SCU_HIBERNATE_BASE+XMC4_SCU_OSCSICTRL_OFFSET) +#define XMC4_SCU_OSCULSTAT (XMC4_SCU_HIBERNATE_BASE+XMC4_SCU_OSCULSTAT_OFFSET) +#define XMC4_SCU_OSCULCTRL (XMC4_SCU_HIBERNATE_BASE+XMC4_SCU_OSCULCTRL_OFFSET) + +/* Reset SCU Registers */ + +#define XMC4_SCU_RSTSTAT (XMC4_SCU_RESET_BASE+XMC4_SCU_RSTSTAT_OFFSET) +#define XMC4_SCU_RSTSET (XMC4_SCU_RESET_BASE+XMC4_SCU_RSTSET_OFFSET) +#define XMC4_SCU_RSTCLR (XMC4_SCU_RESET_BASE+XMC4_SCU_RSTCLR_OFFSET) +#define XMC4_SCU_PRSTAT0 (XMC4_SCU_RESET_BASE+XMC4_SCU_PRSTAT0_OFFSET) +#define XMC4_SCU_PRSET0 (XMC4_SCU_RESET_BASE+XMC4_SCU_PRSET0_OFFSET) +#define XMC4_SCU_PRCLR0 (XMC4_SCU_RESET_BASE+XMC4_SCU_PRCLR0_OFFSET) +#define XMC4_SCU_PRSTAT1 (XMC4_SCU_RESET_BASE+XMC4_SCU_PRSTAT1_OFFSET) +#define XMC4_SCU_PRSET1 (XMC4_SCU_RESET_BASE+XMC4_SCU_PRSET1_OFFSET) +#define XMC4_SCU_PRCLR1 (XMC4_SCU_RESET_BASE+XMC4_SCU_PRCLR1_OFFSET) +#define XMC4_SCU_PRSTAT2 (XMC4_SCU_RESET_BASE+XMC4_SCU_PRSTAT2_OFFSET) +#define XMC4_SCU_PRSET2 (XMC4_SCU_RESET_BASE+XMC4_SCU_PRSET2_OFFSET) +#define XMC4_SCU_PRCLR2 (XMC4_SCU_RESET_BASE+XMC4_SCU_PRCLR2_OFFSET) +#define XMC4_SCU_PRSTAT3 (XMC4_SCU_RESET_BASE+XMC4_SCU_PRSTAT3_OFFSET) +#define XMC4_SCU_PRSET3 (XMC4_SCU_RESET_BASE+XMC4_SCU_PRSET3_OFFSET) +#define XMC4_SCU_PRCLR3 (XMC4_SCU_RESET_BASE+XMC4_SCU_PRCLR3_OFFSET) + +/* Clock Control SCU Registers */ + +#define XMC4_SCU_CLKSTAT (XMC4_SCU_CLK_BASE+XMC4_SCU_CLKSTAT_OFFSET) +#define XMC4_SCU_CLKSET (XMC4_SCU_CLK_BASE+XMC4_SCU_CLKSET_OFFSET) +#define XMC4_SCU_CLKCLR (XMC4_SCU_CLK_BASE+XMC4_SCU_CLKCLR_OFFSET) +#define XMC4_SCU_SYSCLKCR (XMC4_SCU_CLK_BASE+XMC4_SCU_SYSCLKCR_OFFSET) +#define XMC4_SCU_CPUCLKCR (XMC4_SCU_CLK_BASE+XMC4_SCU_CPUCLKCR_OFFSET) +#define XMC4_SCU_PBCLKCR (XMC4_SCU_CLK_BASE+XMC4_SCU_PBCLKCR_OFFSET) +#define XMC4_SCU_USBCLKCR (XMC4_SCU_CLK_BASE+XMC4_SCU_USBCLKCR_OFFSET) +#define XMC4_SCU_EBUCLKCR (XMC4_SCU_CLK_BASE+XMC4_SCU_EBUCLKCR_OFFSET) +#define XMC4_SCU_CCUCLKCR (XMC4_SCU_CLK_BASE+XMC4_SCU_CCUCLKCR_OFFSET) +#define XMC4_SCU_WDTCLKCR (XMC4_SCU_CLK_BASE+XMC4_SCU_WDTCLKCR_OFFSET) +#define XMC4_SCU_EXTCLKCR (XMC4_SCU_CLK_BASE+XMC4_SCU_EXTCLKCR_OFFSET) +#define XMC4_SCU_SLEEPCR (XMC4_SCU_CLK_BASE+XMC4_SCU_SLEEPCR_OFFSET) +#define XMC4_SCU_DSLEEPCR (XMC4_SCU_CLK_BASE+XMC4_SCU_DSLEEPCR_OFFSET) +#define XMC4_SCU_CGATSTAT0 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSTAT0_OFFSET) +#define XMC4_SCU_CGATSET0 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSET0_OFFSET) +#define XMC4_SCU_CGATCLR0 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATCLR0_OFFSET) +#define XMC4_SCU_CGATSTAT1 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSTAT1_OFFSET) +#define XMC4_SCU_CGATSET1 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSET1_OFFSET) +#define XMC4_SCU_CGATCLR1 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATCLR1_OFFSET) +#define XMC4_SCU_CGATSTAT2 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSTAT2_OFFSET) +#define XMC4_SCU_CGATSET2 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSET2_OFFSET +#define XMC4_SCU_CGATCLR2 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATCLR2_OFFSET +#define XMC4_SCU_CGATSTAT3 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSTAT3_OFFSET +#define XMC4_SCU_CGATSET3 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSET3_OFFSET +#define XMC4_SCU_CGATCLR3 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATCLR3_OFFSET_ + +/* Oscillator Control SCU Registers */ + +#define XMC4_OSCU_OSCHPSTAT (XMC4_SCU_OSC_BASE+XMC4_OSCU_OSCHPSTAT_OFFSET) +#define XMC4_OSCU_OSCHPCTRL (XMC4_SCU_OSC_BASE+XMC4_OSCU_OSCHPCTRL_OFFSET) +#define XMC4_OSCU_CLKCALCONST (XMC4_SCU_OSC_BASE+XMC4_OSCU_CLKCALCONST_OFFSET) + +/* PLL Control SCU Registers */ + +#define XMC4_SCU_PLLSTAT (XMC4_SCU_PLL_BASE+XMC4_SCU_PLLSTAT_OFFSET) +#define XMC4_SCU_PLLCON0 (XMC4_SCU_PLL_BASE+XMC4_SCU_PLLCON0_OFFSET) +#define XMC4_SCU_PLLCON1 (XMC4_SCU_PLL_BASE+XMC4_SCU_PLLCON1_OFFSET) +#define XMC4_SCU_PLLCON2 (XMC4_SCU_PLL_BASE+XMC4_SCU_PLLCON2_OFFSET) +#define XMC4_SCU_USBPLLSTAT (XMC4_SCU_PLL_BASE+XMC4_SCU_USBPLLSTAT_OFFSET) +#define XMC4_SCU_USBPLLCON (XMC4_SCU_PLL_BASE+XMC4_SCU_USBPLLCON_OFFSET) +#define XMC4_SCU_CLKMXSTAT (XMC4_SCU_PLL_BASE+XMC4_SCU_CLKMXSTAT_OFFSET) /* Register Bit-Field Definitions ***************************************************/ /* General SCU Registers */ /* Module Identification Register */ -#define GCU_ID_ +#define SCU_ID_ /* Chip ID */ -#define GCU_IDCHIP_ +#define SCU_IDCHIP_ /* Manufactory ID */ -#define GCU_IDMANUF_ +#define SCU_IDMANUF_ /* Start-up Control */ -#define GCU_STCON_ +#define SCU_STCON_ /* General Purpose Register 0 */ -#define GCU_GPR0_ +#define SCU_GPR0_ /* General Purpose Register 1 */ -#define GCU_GPR1_ +#define SCU_GPR1_ /* Ethernet 0 Port Control */ -#define GCU_ETH0CON_ +#define SCU_ETH0CON_ /* CCUx Global Start Control Register */ -#define GCU_CCUCON_ +#define SCU_CCUCON_ +/* DTS Control */ +#define SCU_DTSCON_ +/* DTS Status */ +#define SCU_DTSSTAT_ +/* SD-MMC Delay Control Register */ +#define SCU_SDMMCDEL_ +/* Out-Of-Range Comparator Enable Register 0 */ +#define SCU_G0ORCEN_ +/* Out-Of-Range Comparator Enable Register 1 */ +#define SCU_G1ORCEN_ +/* Mirror Update Status Register */ +#define SCU_MIRRSTS_ + +/* Ethernet Control SCU Resters */ + +/* Ethernet 0 Port Control Register */ +#define SCU_ETHCON_ + +/* Interrupt Control SCU Registers */ + /* Service Request Status */ -#define GCU_SRSTAT_ +#define SCU_SRSTAT_ /* RAW Service Request Status */ -#define GCU_SRRAW_ +#define SCU_SRRAW_ /* Service Request Mask */ -#define GCU_SRMSK_ +#define SCU_SRMSK_ /* Service Request Clear */ -#define GCU_SRCLR_ +#define SCU_SRCLR_ /* Service Request Set */ -#define GCU_SRSET_ +#define SCU_SRSET_ /* Enable Promoting Events to NMI Request */ -#define GCU_NMIREQEN_ -/* DTS Control */ -#define GCU_DTSCON_ -/* DTS Status */ -#define GCU_DTSSTAT_ -/* SD-MMC Delay Control Register */ -#define GCU_SDMMCDEL_ -/* Out-Of-Range Comparator Enable Register 0 */ -#define GCU_G0ORCEN_ -/* Out-Of-Range Comparator Enable Register 1 */ -#define GCU_G1ORCEN_ -/* Mirror Update Status Register */ -#define GCU_MIRRSTS_ +#define SCU_NMIREQEN_ /* Retention Memory Access Control Register */ -#define GCU_RMACR_ +#define SCU_RMACR_ /* Retention Memory Access Data Register */ -#define GCU_RMADATA_ +#define SCU_RMADATA_ /* Parity Error Enable Register */ -#define GCU_PEEN_ + +/* SDMMC Control SCU Registers */ + +/* SDMMC Configuration */ +#define SCU_SDMMCCON_ + +/* Parity Control Registers */ + +#define SCU_PEEN_ /* Memory Checking Control Register */ -#define GCU_MCHKCON_ +#define SCU_MCHKCON_ /* Parity Error Trap Enable Register */ -#define GCU_PETE_ +#define SCU_PETE_ /* Reset upon Parity Error Enable Register */ -#define GCU_PERSTEN_ +#define SCU_PERSTEN_ /* Parity Error Control Register */ -#define GCU_PEFLAG_ +#define SCU_PEFLAG_ /* Parity Memory Test Pattern Register */ -#define GCU_PMTPR_ +#define SCU_PMTPR_ /* Parity Memory Test Select Register */ -#define GCU_PMTSR_ +#define SCU_PMTSR_ + +/* Trap Control Registers */ + /* Trap Status Register */ -#define GCU_TRAPSTAT_ +#define SCU_TRAPSTAT_ /* Trap Raw Status Register */ -#define GCU_TRAPRAW_ +#define SCU_TRAPRAW_ /* Trap Mask Register */ -#define GCU_TRAPDIS_ +#define SCU_TRAPDIS_ /* Trap Clear Register */ -#define GCU_TRAPCLR_ +#define SCU_TRAPCLR_ /* Trap Set Register */ -#define GCU_TRAPSET_ +#define SCU_TRAPSET_ -/* PCU Registers */ +/* Power Control SCU Registers */ /* Power Status Register */ -#define PCU_PWRSTAT_ +#define SCU_PWRSTAT_ /* Power Set Control Register */ -#define PCU_PWRSET_ +#define SCU_PWRSET_ /* Power Clear Control Register */ -#define PCU_PWRCLR_ +#define SCU_PWRCLR_ /* EVR Status Register */ -#define PCU_EVRSTAT_ +#define SCU_EVRSTAT_ /* EVR VADC Status Register */ -#define PCU_EVRVADCSTAT_ +#define SCU_EVRVADCSTAT_ /* Power Monitor Value */ -#define PCU_PWRMON_ +#define SCU_PWRMON_ /* HCU Registers */ /* Hibernate Domain Status Register */ -#define HCU_HDSTAT_ +#define SCU_HDSTAT_ /* Hibernate Domain Status Clear Register */ -#define HCU_HDCLR_ +#define SCU_HDCLR_ /* Hibernate Domain Status Set Register */ -#define HCU_HDSET_ +#define SCU_HDSET_ /* Hibernate Domain Control Register */ -#define HCU_HDCR_ +#define SCU_HDCR_ /* Internal 32.768 kHz Clock Source Control Register */ -#define HCU_OSCSICTRL_ +#define SCU_OSCSICTRL_ /* OSC_ULP Status Register */ -#define HCU_OSCULSTAT_ +#define SCU_OSCULSTAT_ /* OSC_ULP Control Register */ -#define HCU_OSCULCTRL_ +#define SCU_OSCULCTRL_ -/* RCU Registers */ +/* Reset SCU Registers */ /* System Reset Status */ -#define RCU_RSTSTAT_ +#define SCU_RSTSTAT_ /* Reset Set Register */ -#define RCU_RSTSET_ +#define SCU_RSTSET_ /* Reset Clear Register */ -#define RCU_RSTCLR_ +#define SCU_RSTCLR_ /* Peripheral Reset Status Register 0 */ -#define RCU_PRSTAT0_ +#define SCU_PRSTAT0_ /* Peripheral Reset Set Register 0 */ -#define RCU_PRSET0_ +#define SCU_PRSET0_ /* Peripheral Reset Clear Register 0 */ -#define RCU_PRCLR0_ +#define SCU_PRCLR0_ /* Peripheral Reset Status Register 1 */ -#define RCU_PRSTAT1_ +#define SCU_PRSTAT1_ /* Peripheral Reset Set Register 1 */ -#define RCU_PRSET1_ +#define SCU_PRSET1_ /* Peripheral Reset Clear Register 1 */ -#define RCU_PRCLR1_ +#define SCU_PRCLR1_ /* Peripheral Reset Status Register 2 */ -#define RCU_PRSTAT2_ +#define SCU_PRSTAT2_ /* Peripheral Reset Set Register 2 */ -#define RCU_PRSET2_ +#define SCU_PRSET2_ /* Peripheral Reset Clear Register 2 */ -#define RCU_PRCLR2_ +#define SCU_PRCLR2_ /* Peripheral Reset Status Register 3 */ -#define RCU_PRSTAT3_ +#define SCU_PRSTAT3_ /* Peripheral Reset Set Register 3 */ -#define RCU_PRSET3_ +#define SCU_PRSET3_ /* Peripheral Reset Clear Register 3 */ -#define RCU_PRCLR3_ +#define SCU_PRCLR3_ -/* CCU Registers */ +/* Clock Control SCU Registers */ /* Clock Status Register */ -#define CCU_CLKSTAT_ +#define SCU_CLKSTAT_ /* Clock Set Control Register */ -#define CCU_CLKSET_ +#define SCU_CLKSET_ /* Clock clear Control Register */ -#define CCU_CLKCLR_ +#define SCU_CLKCLR_ /* System Clock Control */ -#define CCU_SYSCLKCR_ +#define SCU_SYSCLKCR_ /* CPU Clock Control */ -#define CCU_CPUCLKCR_ +#define SCU_CPUCLKCR_ /* Peripheral Bus Clock Control */ -#define CCU_PBCLKCR_ +#define SCU_PBCLKCR_ /* USB Clock Control */ -#define CCU_USBCLKCR_ +#define SCU_USBCLKCR_ /* EBU Clock Control */ -#define CCU_EBUCLKCR_ +#define SCU_EBUCLKCR_ /* CCU Clock Control */ -#define CCU_CCUCLKCR_ +#define SCU_CCUCLKCR_ /* WDT Clock Control */ -#define CCU_WDTCLKCR_ +#define SCU_WDTCLKCR_ /* External clock Control Register */ -#define CCU_EXTCLKCR_ +#define SCU_EXTCLKCR_ /* Sleep Control Register */ -#define CCU_SLEEPCR_ +#define SCU_SLEEPCR_ /* Deep Sleep Control Register */ -#define CCU_DSLEEPCR_ +#define SCU_DSLEEPCR_ +/* Peripheral 0 Clock Gating Status */ +#define SCU_CGATSTAT0_ +/* Peripheral 0 Clock Gating Set */ +#define SCU_CGATSET0_ +/* Peripheral 0 Clock Gating Clear */ +#define SCU_CGATCLR0_ +/* Peripheral 1 Clock Gating Status */ +#define SCU_CGATSTAT1_ +/* Peripheral 1 Clock Gating Set */ +#define SCU_CGATSET1_ +/* Peripheral 1 Clock Gating Clear */ +#define SCU_CGATCLR1_ +/* Peripheral 2 Clock Gating Status */ +#define SCU_CGATSTAT2_ +/* Peripheral 2 Clock Gating Set */ +#define SCU_CGATSET2_ +/* Peripheral 2 Clock Gating Clear */ +#define SCU_CGATCLR2_ +/* Peripheral 3 Clock Gating Status */ +#define SCU_CGATSTAT3_ +/* Peripheral 3 Clock Gating Set */ +#define SCU_CGATSET3_ +/* Peripheral 3 Clock Gating Clear */ +#define SCU_CGATCLR3_ + +/* Oscillator Control SCU Registers */ + /* OSC_HP Status Register */ -#define CCU_OSCHPSTAT_ +#define OSCU_OSCHPSTAT_ /* OSC_HP Control Register */ -#define CCU_OSCHPCTRL_ +#define OSCU_OSCHPCTRL_ /* Clock Calibration Constant Register */ -#define CCU_CLKCALCONST_ +#define OSCU_CLKCALCONST_ + +/* PLL Control SCU Registers */ + /* System PLL Status Register */ -#define CCU_PLLSTAT_ +#define SCU_PLLSTAT_ /* System PLL Configuration 0 Register */ -#define CCU_PLLCON0_ +#define SCU_PLLCON0_ /* System PLL Configuration 1 Register */ -#define CCU_PLLCON1_ +#define SCU_PLLCON1_ /* System PLL Configuration 2 Register */ -#define CCU_PLLCON2_ +#define SCU_PLLCON2_ /* USB PLL Status Register */ -#define CCU_USBPLLSTAT_ +#define SCU_USBPLLSTAT_ /* USB PLL Control Register */ -#define CCU_USBPLLCON_ +#define SCU_USBPLLCON_ /* Clock Multiplexing Status Register */ -#define CCU_CLKMXSTAT_ +#define SCU_CLKMXSTAT_ #endif /* __ARCH_ARM_SRC_XMC4_CHIP_XMC4_SCU_H */ -- GitLab From 77f244ed7b848195b24556f4cfc070fe42a108e8 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 15 Mar 2017 10:22:24 -0600 Subject: [PATCH 045/990] XMC4xx: Add logic to get the CPU frequency. --- arch/arm/src/xmc4/chip/xmc4_scu.h | 52 ++++++++- arch/arm/src/xmc4/xmc4_clockconfig.c | 110 +++++++++++++++++-- arch/arm/src/xmc4/xmc4_clockconfig.h | 79 ++++++++++++++ arch/arm/src/xmc4/xmc4_start.c | 4 +- arch/arm/src/xmc4/xmc4_start.h | 61 +++++++++++ configs/xmc4500-relax/include/board.h | 150 ++++++++++++++++++++++++++ 6 files changed, 442 insertions(+), 14 deletions(-) create mode 100644 arch/arm/src/xmc4/xmc4_clockconfig.h create mode 100644 arch/arm/src/xmc4/xmc4_start.h create mode 100644 configs/xmc4500-relax/include/board.h diff --git a/arch/arm/src/xmc4/chip/xmc4_scu.h b/arch/arm/src/xmc4/chip/xmc4_scu.h index ab5b771995..e9370565ba 100644 --- a/arch/arm/src/xmc4/chip/xmc4_scu.h +++ b/arch/arm/src/xmc4/chip/xmc4_scu.h @@ -505,10 +505,21 @@ #define SCU_CLKSET_ /* Clock clear Control Register */ #define SCU_CLKCLR_ + /* System Clock Control */ -#define SCU_SYSCLKCR_ + +#define SCU_SYSCLKCR_SYSDIV_SHIFT (0) /* Bits 0-7: System Clock Division Value */ +#define SCU_SYSCLKCR_SYSDIV_MASK (0xff << SCU_CLK_SYSCLKCR_SYSDIV_SHIFT) +# define SCU_SYSCLKCR_SYSDIV(n) ((uint32_t)((n)-1) << SCU_CLK_SYSCLKCR_SYSDIV_SHIFT) + +#define SCU_SYSCLKCR_SYSSEL (1 << 16) /* Bit 16: System Clock Selection Value */ +# define SCU_SYSCLKCR_SYSSEL_OFI (0) /* 0=OFI clock */ +# define SCU_SYSCLKCR_SYSSEL_PLL (1 << 16) /* 1=PLL clock */ + /* CPU Clock Control */ -#define SCU_CPUCLKCR_ + +#define SCU_CPUCLKCR_CPUDIV (1 << 0) /* Bit 0: CPU Clock Divider Enable */ + /* Peripheral Bus Clock Control */ #define SCU_PBCLKCR_ /* USB Clock Control */ @@ -562,13 +573,44 @@ /* PLL Control SCU Registers */ /* System PLL Status Register */ -#define SCU_PLLSTAT_ + +#define SCU_PLLSTAT_VCOBYST (1 << 0) /* Bit 0: VCO Bypass Status */ +#define SCU_PLLSTAT_PWDSTAT (1 << 1) /* Bit 1: PLL Power-saving Mode Status */ +#define SCU_PLLSTAT_VCOLOCK (1 << 2) /* Bit 2: PLL LOCK Status */ +#define SCU_PLLSTAT_K1RDY (1 << 4) /* Bit 4: K1 Divider Ready Status */ +#define SCU_PLLSTAT_K2RDY (1 << 5) /* Bit 5: K2 Divider Ready Status */ +#define SCU_PLLSTAT_BY (1 << 6) /* Bit 6: Bypass Mode Status */ +#define SCU_PLLSTAT_PLLLV (1 << 7) /* Bit 7: Oscillator for PLL Valid Low Status */ +#define SCU_PLLSTAT_PLLHV (1 << 8) /* Bit 8: Oscillator for PLL Valid High Status */ +#define SCU_PLLSTAT_PLLSP (1 << 9) /* Bit 9: Oscillator for PLL Valid Spike Status */ + /* System PLL Configuration 0 Register */ #define SCU_PLLCON0_ + /* System PLL Configuration 1 Register */ -#define SCU_PLLCON1_ + +#define SCU_PLLCON1_K1DIV_SHIFT (0) /* Bits 0-6: K1-Divider Value */ +#define SCU_PLLCON1_K1DIV_MASK (0x7f << SCU_PLLCON1_K1DIV_SHIFT) +# define SCU_PLLCON1_K1DIV(n) ((uint32_t)((n)-1) << SCU_PLLCON1_K1DIV_SHIFT) +#define SCU_PLLCON1_NDIV_SHIFT (8) /* Bits 8-14: N-Divider Value */ +#define SCU_PLLCON1_NDIV_MASK (0x7f << SCU_PLLCON1_NDIV_SHIFT) +# define SCU_PLLCON1_NDIV(n) ((uint32_t)((n)-1) << SCU_PLLCON1_NDIV_SHIFT) +#define SCU_PLLCON1_K2DIV_SHIFT (16) /* Bit 16-22: K2-Divider Value */ +#define SCU_PLLCON1_K2DIV_MASK (0x7f << SCU_PLLCON1_K2DIV_SHIFT) +# define SCU_PLLCON1_K2DIV(n) ((uint32_t)((n)-1) << SCU_PLLCON1_K2DIV_SHIFT) +#define SCU_PLLCON1_PDIV_SHIFT (24) /* Bits 24-27: P-Divider Value */ +#define SCU_PLLCON1_PDIV_MASK (0x7f << SCU_PLLCON1_PDIV_SHIFT) +# define SCU_PLLCON1_PDIV(n) ((uint32_t)((n)-1) << SCU_PLLCON1_PDIV_SHIFT) + /* System PLL Configuration 2 Register */ -#define SCU_PLLCON2_ + +#define SCU_PLLCON2_PINSEL (1 << 0) /* Bit 0: P-Divider Input Selection */ +# define SCU_PLLCON2_PINSEL_PLL (0) /* 0=PLL external oscillator selected */ +# define SCU_PLLCON2_PINSEL_OFI (1 << 0) /* 1=Backup clock source selected */ +#define SCU_PLLCON2_K1INSEL (1 << 8) /* Bit 8: K1-Divider Input */ +# define SCU_PLLCON2_K1INSEL_PLL (0) /* 0=PLL external oscillator selected */ +# define SCU_PLLCON2_K1INSEL_OFI (1 << 8) /* 1=Backup clock source selected */ + /* USB PLL Status Register */ #define SCU_USBPLLSTAT_ /* USB PLL Control Register */ diff --git a/arch/arm/src/xmc4/xmc4_clockconfig.c b/arch/arm/src/xmc4/xmc4_clockconfig.c index 67efe53651..d7d5a8bc7d 100644 --- a/arch/arm/src/xmc4/xmc4_clockconfig.c +++ b/arch/arm/src/xmc4/xmc4_clockconfig.c @@ -1,9 +1,11 @@ /**************************************************************************** - * arch/arm/src/xmc4/xmc4_clock_config.c + * arch/arm/src/xmc4/xmc4_clockconfig.c * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Authors: Gregory Nutt * + * Reference: XMC4500 Reference Manual V1.5 2014-07 Microcontrollers. + * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: @@ -31,6 +33,20 @@ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * + * May include some logic from sample code provided by Infineon: + * + * Copyright (C) 2011-2015 Infineon Technologies AG. All rights reserved. + * + * Infineon Technologies AG (Infineon) is supplying this software for use with + * Infineon's microcontrollers. This file can be freely distributed within + * development tools that are supporting such microcontrollers. + * + * THIS SOFTWARE IS PROVIDED AS IS. NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * INFINEON SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, + * OR CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * ****************************************************************************/ /**************************************************************************** @@ -47,10 +63,6 @@ * Pre-processor Definitions ****************************************************************************/ -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - /**************************************************************************** * Private Functions ****************************************************************************/ @@ -60,7 +72,7 @@ ****************************************************************************/ /**************************************************************************** - * Name: xmc4_clock_config + * Name: xmc4_clock_configure * * Description: * Called to initialize the XMC4xxx chip. This does whatever setup is @@ -69,6 +81,90 @@ * ****************************************************************************/ -void xmc4_clock_config(void) +void xmc4_clock_configure(void) +{ +} + +/**************************************************************************** + * Name: xmc4_get_coreclock + * + * Description: + * Return the current core clock frequency (fCPU). + * + ****************************************************************************/ + +uint32_t xmc4_get_coreclock(void) { + uint32_t pdiv; + uint32_t ndiv; + uint32_t kdiv; + uint32_t sysdiv; + uint32_t regval; + uint32_t temp; + + if ((getreg32(XMC4_SCU_SYSCLKCR) & SCU_SYSCLKCR_SYSSEL) != 0) + { + /* fPLL is clock source for fSYS */ + + if ((getreg32(XMC4_SCU_PLLCON2) & SCU_PLLCON2_PINSEL) != 0) + { + /* PLL input clock is the backup clock (fOFI) */ + + temp = OFI_FREQUENCY; + } + else + { + /* PLL input clock is the high performance oscillator (fOSCHP); + * Only board specific logic knows this value. + */ + + temp = BOARD_XTAL_FREQUENCY; + } + + /* Check if PLL is locked */ + + regval = getreg32(XMC4_SCU_PLLSTAT); + if ((regval & SCU_PLLSTAT_VCOLOCK) != 0) + { + /* PLL normal mode */ + + regval = getreg32(XMC4_SCU_PLLCON1); + pdiv = ((regval & SCU_PLLCON1_PDIV_MASK) >> SCU_PLLCON1_PDIV_SHIFT) + 1; + ndiv = ((regval & SCU_PLLCON1_NDIV_MASK) >> SCU_PLLCON1_NDIV_SHIFT) + 1; + kdiv = ((regval & SCU_PLLCON1_K2DIV_MASK) >> SCU_PLLCON1_K2DIV_SHIFT) + 1; + + temp = (temp / (pdiv * kdiv)) * ndiv; + } + else + { + /* PLL prescalar mode */ + + regval = getreg32(XMC4_SCU_PLLCON1); + kdiv = ((regval & SCU_PLLCON1_K1DIV_MASK) >> SCU_PLLCON1_K1DIV_SHIFT) + 1; + + temp = (temp / kdiv); + } + } + else + { + /* fOFI is clock source for fSYS */ + + temp = OFI_FREQUENCY; + } + + /* Divide by SYSDIV to get fSYS */ + + regval = getreg32(XMC4_SCU_SYSCLKCR); + sysdiv = ((regval & SCU_SYSCLKCR_SYSDIV_MASK) >> SCU_SYSCLKCR_SYSDIV_SHIFT) + 1; + temp = temp / sysdiv; + + /* Check if the fSYS clock is divided by two to produce fCPU clock. */ + + regval = getreg32(CPUCLKCR); + if ((regval & SCU_CPUCLKCR_CPUDIV) != 0) + { + temp = temp >> 1; + } + + return temp; } diff --git a/arch/arm/src/xmc4/xmc4_clockconfig.h b/arch/arm/src/xmc4/xmc4_clockconfig.h new file mode 100644 index 0000000000..6e03989cad --- /dev/null +++ b/arch/arm/src/xmc4/xmc4_clockconfig.h @@ -0,0 +1,79 @@ +/************************************************************************************ + * arch/arm/src/xmc4/xmc4_clockconfig.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_XMC4_XMC4_CLOCKCONFIG_H +#define __ARCH_ARM_SRC_XMC4_XMC4_CLOCKCONFIG_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include + +/************************************************************************************ + * Preprocessor Definitions + ************************************************************************************/ + +#define OFI_FREQUENCY 24000000 /* Frequency of internal Backup Clock Source */ +#define OSI_FREQUENCY 32768 /* Frequency of internal Slow Clock Source */ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/**************************************************************************** + * Name: xmc4_clock_configure + * + * Description: + * Called to initialize the XMC4xxx chip. This does whatever setup is + * needed to put the MCU in a usable state. This includes the + * initialization of clocking using the settings in board.h. + * + ****************************************************************************/ + +void xmc4_clock_configure(void); + +/**************************************************************************** + * Name: xmc4_get_coreclock + * + * Description: + * Return the current core clock frequency. + * + ****************************************************************************/ + +uint32_t xmc4_get_coreclock(void); + +#endif /* __ARCH_ARM_SRC_XMC4_XMC4_CLOCKCONFIG_H */ diff --git a/arch/arm/src/xmc4/xmc4_start.c b/arch/arm/src/xmc4/xmc4_start.c index e71722e4be..77e792847e 100644 --- a/arch/arm/src/xmc4/xmc4_start.c +++ b/arch/arm/src/xmc4/xmc4_start.c @@ -279,7 +279,7 @@ void __start(void) /* Disable the watchdog timer */ - kinetis_wddisable(); + xmc4_wddisable(); /* Clear .bss. We'll do this inline (vs. calling memset) just to be * certain that there are no issues with the state of global variables. @@ -318,7 +318,7 @@ void __start(void) * RAM functions having been copied to RAM). */ - xmc4_clock_config(); + xmc4_clock_configure(); /* Configure the uart and perform early serial initialization so that we * can get debug output as soon as possible (This depends on clock diff --git a/arch/arm/src/xmc4/xmc4_start.h b/arch/arm/src/xmc4/xmc4_start.h new file mode 100644 index 0000000000..2be470640b --- /dev/null +++ b/arch/arm/src/xmc4/xmc4_start.h @@ -0,0 +1,61 @@ +/************************************************************************************ + * arch/arm/src/xmc4/xmc4_start.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_XMC4_XMC4_CLOCKCONFIG_H +#define __ARCH_ARM_SRC_XMC4_XMC4_CLOCKCONFIG_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: xmc4_board_initialize + * + * Description: + * All XMC4xxx architectures must provide the following entry point. This entry + * point is called early in the initialization -- after all memory has been + * configured and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +void xmc4_board_initialize(void); + +#endif /* __ARCH_ARM_SRC_XMC4_XMC4_CLOCKCONFIG_H */ diff --git a/configs/xmc4500-relax/include/board.h b/configs/xmc4500-relax/include/board.h new file mode 100644 index 0000000000..a448469bca --- /dev/null +++ b/configs/xmc4500-relax/include/board.h @@ -0,0 +1,150 @@ +/************************************************************************************ + * configs/xmc4500-relax/include/board.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __CONFIG_XMC4500_RELAX_INCLUDE_BOARD_H +#define __CONFIG_XMC4500_RELAX_INCLUDE_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#ifndef __ASSEMBLY__ +# include +# include +#endif + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ +/* Default clock initialization + * fPLL = 288MHz => fSYS = 288MHz => fCPU = 144MHz + * => fPB = 144MHz + * => fCCU = 144MHz + * => fETH = 72MHz + * => fUSB = 48MHz + * => fEBU = 72MHz + * + * fUSBPLL Disabled, only enabled if SCU_CLK_USBCLKCR_USBSEL_USBPLL is selected + * + * fOFI = 24MHz => fWDT = 24MHz + */ + +/* On-board crystals + * + * NOTE: Only the XMC4500 Relax Kit-V1 provides the 32.768KHz RTC crystal. It + * is not available on XMC4500 Relax Lite Kit-V1. + */ + +#define BOARD_XTAL_FREQUENCY 12000000 /* 12MHz XTAL */ +#undef BOARD_RTC_XTAL_FRQUENCY /* 32.768KHz RTC XTAL not available */ + +/* Select the external crystal as the PLL clock source */ + +#define BOARD_PLL_CLOCKSRC_XTAL 1 /* PLL Clock source == extnernal crystal */ +#undef BOARD_PLL_CLOCKSRC_OFI /* PLL Clock source != internal fast oscillator */ + +/* PLL Configuration: + * + * fPLL = (fPLLSRC / (pdiv * k2div) * ndiv + * + * fPLL = (12000000 / (2 * 1)) * 48 + * = 288MHz + */ + +#define BOARD_PLL_PDIV 2 +#define BOARD_PLL_NDIV 48 +#define BOARD_PLL_K2DIV 1 +#define BOARD_PLL_FREQUENCY 288000000 + +/* System frequency is divided down from PLL output */ + +#define BOARD_SYSDIV 1 /* PLL Output divider to get fSYS */ +#define BOARD_SYS_FREQUENCY 288000000 + +/* CPU frequency may be divided down from system frequency */ + +#define BOARD_CPUDIV_ENABLE 1 /* Enable PLL dive by 2 for fCPU */ +#define BOARD_CPU_FREQUENCY 144000000 + +/* Standby clock source selection + * + * BOARD_STDBY_CLOCKSRC_OSI - Internal slow oscillator (32768Hz) + * BOARD_STDBY_CLOCKSRC_OSCULP - External 32.768KHz crystal + */ + +#define BOARD_STDBY_CLOCKSRC_OSI 1 +#undef BOARD_STDBY_CLOCKSRC_OSCULP + +/* USB PLL settings. + * + * fUSBPLL = 48MHz and fUSBPLLVCO = 384 MHz + * + * Note: Implicit divider of 2 and fUSBPLLVCO >= 260 MHz and + * fUSBPLLVCO <= 520 MHz + */ + +#define BOARD_USB_PDIV 2 +#define BOARD_USB_NDIV 64 + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __CONFIG_XMC4500_RELAX_INCLUDE_BOARD_H */ -- GitLab From 55fb9645a7212aaa1661d8c03c84c8951a8644c4 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Wed, 15 Mar 2017 07:42:55 -1000 Subject: [PATCH 046/990] Guard from pend_reprios overlow --- sched/wqueue/kwork_inherit.c | 17 +++++++++++++++-- 1 file changed, 15 insertions(+), 2 deletions(-) diff --git a/sched/wqueue/kwork_inherit.c b/sched/wqueue/kwork_inherit.c index b6d98c7b40..a960480bd0 100644 --- a/sched/wqueue/kwork_inherit.c +++ b/sched/wqueue/kwork_inherit.c @@ -110,6 +110,11 @@ static void lpwork_boostworker(pid_t wpid, uint8_t reqprio) wtcb->pend_reprios[wtcb->npend_reprio] = wtcb->sched_priority; wtcb->npend_reprio++; } + else + { + serr("ERROR: CONFIG_SEM_NNESTPRIO exceeded\n"); + DEBUGASSERT(wtcb->npend_reprio < CONFIG_SEM_NNESTPRIO); + } } /* Raise the priority of the worker. This cannot cause a context @@ -129,8 +134,16 @@ static void lpwork_boostworker(pid_t wpid, uint8_t reqprio) * saved priority and not to the base priority. */ - wtcb->pend_reprios[wtcb->npend_reprio] = reqprio; - wtcb->npend_reprio++; + if (wtcb->npend_reprio < CONFIG_SEM_NNESTPRIO) + { + wtcb->pend_reprios[wtcb->npend_reprio] = reqprio; + wtcb->npend_reprio++; + } + else + { + serr("ERROR: CONFIG_SEM_NNESTPRIO exceeded\n"); + DEBUGASSERT(wtcb->npend_reprio < CONFIG_SEM_NNESTPRIO); + } } } #else -- GitLab From 519f14fbb5bd981966148623b430144d4ba135c2 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 15 Mar 2017 11:43:58 -0600 Subject: [PATCH 047/990] XMC4xxx: A few more SCU register bit definitions. --- arch/arm/src/xmc4/chip/xmc4_scu.h | 78 +++++++++++++++++++++++-------- 1 file changed, 58 insertions(+), 20 deletions(-) diff --git a/arch/arm/src/xmc4/chip/xmc4_scu.h b/arch/arm/src/xmc4/chip/xmc4_scu.h index e9370565ba..87b11f3753 100644 --- a/arch/arm/src/xmc4/chip/xmc4_scu.h +++ b/arch/arm/src/xmc4/chip/xmc4_scu.h @@ -421,25 +421,30 @@ /* Trap Control Registers */ -/* Trap Status Register */ -#define SCU_TRAPSTAT_ -/* Trap Raw Status Register */ -#define SCU_TRAPRAW_ -/* Trap Mask Register */ -#define SCU_TRAPDIS_ -/* Trap Clear Register */ -#define SCU_TRAPCLR_ -/* Trap Set Register */ -#define SCU_TRAPSET_ +/* Trap Status Register, Trap Raw Status Register, Trap Mask Register, Trap Clear + * Register, and Trap Set Register + */ + +#define SCU_TRAP_SOSCWDGT (1 << 0) /* Bit 0: OSC_HP Oscillator Watchdog Trap */ +#define SCU_TRAP_SVCOLCKT (1 << 2) /* Bit 2: System VCO Lock Trap */ +#define SCU_TRAP_UVCOLCKT (1 << 3) /* Bit 3: USB VCO Lock Trap */ +#define SCU_TRAP_PET (1 << 4) /* Bit 4: Parity Error Trap */ +#define SCU_TRAP_BRWNT (1 << 5) /* Bit 5: Brown Out Trap */ +#define SCU_TRAP_ULPWDGT (1 << 6) /* Bit 6: OSC_ULP Oscillator Watchdog Trap */ +#define SCU_TRAP_BWERR0T (1 << 7) /* Bit 7: Peripheral Bridge 0 Trap */ +#define SCU_TRAP_BWERR1T (1 << 8) /* Bit 8: Peripheral Bridge 1 Trap */ /* Power Control SCU Registers */ -/* Power Status Register */ -#define SCU_PWRSTAT_ -/* Power Set Control Register */ -#define SCU_PWRSET_ -/* Power Clear Control Register */ -#define SCU_PWRCLR_ +/* Power Status Register, Power Set Control Register, and Power Clear + * Control Register + */ + +#define SCU_PWR_HIBEN (1 << 0) /* Bit 0: Hibernate Domain Enable State */ +#define SCU_PWR_USBPHYPDQ (1 << 16) /* Bit 16: USB PHY Transceiver State */ +#define SCU_PWR_USBOTGEN (1 << 17) /* Bit 17: USB On-The-Go Comparators State */ +#define SCU_PWR_USBPUWQ (1 << 18) /* Bit 18: USB Weak Pull-Up at PADN State */ + /* EVR Status Register */ #define SCU_EVRSTAT_ /* EVR VADC Status Register */ @@ -467,11 +472,34 @@ /* Reset SCU Registers */ /* System Reset Status */ -#define SCU_RSTSTAT_ + +#define SCU_RSTSTAT_RSTSTAT_SHIFT (0) /* Bits 0-7: Reset Status Information */ +#define SCU_RSTSTAT_RSTSTAT_MASK (0xff << SCU_RSTSTAT_RSTSTAT_SHIFT) +# define SCU_RSTSTAT_RSTSTAT_PORST (1 << SCU_RSTSTAT_RSTSTAT_SHIFT) /* PORST reset */ +# define SCU_RSTSTAT_RSTSTAT_SWD (2 << SCU_RSTSTAT_RSTSTAT_SHIFT) /* SWD reset */ +# define SCU_RSTSTAT_RSTSTAT_PV (4 << SCU_RSTSTAT_RSTSTAT_SHIFT) /* PV reset */ +# define SCU_RSTSTAT_RSTSTAT_CPUSYS (8 << SCU_RSTSTAT_RSTSTAT_SHIFT) /* CPU system reset */ +# define SCU_RSTSTAT_RSTSTAT_CPULOCK (16 << SCU_RSTSTAT_RSTSTAT_SHIFT) /* CPU lockup reset */ +# define SCU_RSTSTAT_RSTSTAT_WDT (32 << SCU_RSTSTAT_RSTSTAT_SHIFT) /* WDT reset */ +# define SCU_RSTSTAT_RSTSTAT_PERR (128 << SCU_RSTSTAT_RSTSTAT_SHIFT) /* Parity Error reset */ + +#define SCU_RSTSTAT_HIBWK (1 << 8) /* Bit 8: Hibernate Wake-up Status */ +#define SCU_RSTSTAT_HIBRS (1 << 9) /* Bit 9: Hibernate Reset Status */ +#define SCU_RSTSTAT_LCKEN (1 << 10) /* Bit 10: Enable Lockup Status */ + /* Reset Set Register */ -#define SCU_RSTSET_ + +#define SCU_RSTSET_HIBWK (1 << 8) /* Bit 8: Hibernate Wake-up Reset Status */ +#define SCU_RSTSET_HIBRS (1 << 9) /* Bit 9: Hibernate Reset Reset Status */ +#define SCU_RSTSET_LCKEN (1 << 10) /* Bit 10: Enable Lockup Reset Status */ + /* Reset Clear Register */ -#define SCU_RSTCLR_ + +#define SCU_RSTCLR_RSCLR (1 << 0) /* Bit 0: Clear Reset Status */ +#define SCU_RSTCLR_HIBWK (1 << 8) /* Bit 8: Clear Hibernate Wake-up Reset Status */ +#define SCU_RSTCLR_HIBRS (1 << 9) /* Bit 9: Clear Hibernate Reset */ +#define SCU_RSTCLR_LCKEN (1 << 10) /* Bit 10: Clear Hibernate Reset */ + /* Peripheral Reset Status Register 0 */ #define SCU_PRSTAT0_ /* Peripheral Reset Set Register 0 */ @@ -585,7 +613,17 @@ #define SCU_PLLSTAT_PLLSP (1 << 9) /* Bit 9: Oscillator for PLL Valid Spike Status */ /* System PLL Configuration 0 Register */ -#define SCU_PLLCON0_ + +#define SCU_PLLCON0_VCOBYP (1 << 0) /* Bit 0: VCO Bypass */ +#define SCU_PLLCON0_VCOPWD (1 << 1) /* Bit 1: VCO Power Saving Mode */ +#define SCU_PLLCON0_VCOTR (1 << 2) /* Bit 2: VCO Trim Control */ +#define SCU_PLLCON0_FINDIS (1 << 4) /* Bit 4: Disconnect Oscillator from VCO */ +#define SCU_PLLCON0_OSCDISCDIS (1 << 6) /* Bit 6: Oscillator Disconnect Disable */ +#define SCU_PLLCON0_PLLPWD (1 << 16) /* Bit 16: PLL Power Saving Mode */ +#define SCU_PLLCON0_OSCRES (1 << 17) /* Bit 17: Oscillator Watchdog Reset */ +#define SCU_PLLCON0_RESLD (1 << 18) /* Bit 18: Restart VCO Lock Detection */ +#define SCU_PLLCON0_AOTREN (1 << 19) /* Bit 19: Automatic Oscillator Calibration Enable */ +#define SCU_PLLCON0_FOTR (1 << 20) /* Bit 20: Factory Oscillator Calibration */ /* System PLL Configuration 1 Register */ -- GitLab From a122dddb5891f2ce781608d572b49c25b482912e Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 15 Mar 2017 13:24:51 -0600 Subject: [PATCH 048/990] Bring closer to NuttX coding standard. --- wireless/ieee802154/mac802154.c | 230 ++++++++++++++------------------ 1 file changed, 98 insertions(+), 132 deletions(-) diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index ad9e195371..3de16fb374 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -44,6 +44,10 @@ #include +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + /* Frame Type */ #define IEEE802154_FRAME_BEACON 0x00 @@ -63,7 +67,10 @@ #define IEEE802154_CMD_COORD_REALIGN 0x08 #define IEEE802154_CMD_GTS_REQ 0x09 -/* private types */ +/**************************************************************************** + * Private Types + ****************************************************************************/ + /* The privmac structure is an extension of the public ieee802154_mac_s type. * It contains storage for the IEEE802.15.4 MIB attributes. */ @@ -111,76 +118,47 @@ struct ieee802154_privmac_s #endif }; -/* forward declarations */ - -static int mac802154_reqdata (struct ieee802154_mac_s *mac, - uint8_t handle, - uint8_t *buf, - int len); - -static int mac802154_reqpurge (struct ieee802154_mac_s *mac, - uint8_t handle); - -static int mac802154_reqassociate (struct ieee802154_mac_s *mac, - uint16_t panid, - uint8_t *coordeadr); - -static int mac802154_reqdisassociate(struct ieee802154_mac_s *mac, - uint8_t *eadr, - uint8_t reason); - -static int mac802154_reqget (struct ieee802154_mac_s *mac, - int attribute); - -static int mac802154_reqgts (struct ieee802154_mac_s *mac, - uint8_t* characteristics); - -static int mac802154_reqreset (struct ieee802154_mac_s *mac, - bool setdefaults); - -static int mac802154_reqrxenable (struct ieee802154_mac_s *mac, - bool deferrable, - int ontime, - int duration); - -static int mac802154_reqscan (struct ieee802154_mac_s *mac, - uint8_t type, - uint32_t channels, - int duration); - -static int mac802154_reqset (struct ieee802154_mac_s *mac, - int attribute, - uint8_t *value, - int valuelen); - -static int mac802154_reqstart (struct ieee802154_mac_s *mac, - uint16_t panid, - int channel, - uint8_t bo, - uint8_t fo, - bool coord, - bool batext, - bool realign); - -static int mac802154_reqsync (struct ieee802154_mac_s *mac, - int channel, - bool track); - -static int mac802154_reqpoll (struct ieee802154_mac_s *mac, - uint8_t *coordaddr); +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ -static int mac802154_rspassociate (struct ieee802154_mac_s *mac, - uint8_t eadr, - uint16_t saddr, - int status); +static int mac802154_reqdata(FAR struct ieee802154_mac_s *mac, + uint8_t handle, FAR uint8_t *buf, int len); +static int mac802154_reqpurge(FAR struct ieee802154_mac_s *mac, + uint8_t handle); +static int mac802154_reqassociate(FAR struct ieee802154_mac_s *mac, + uint16_t panid, FAR uint8_t *coordeadr); +static int mac802154_reqdisassociate(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *eadr, uint8_t reason); +static int mac802154_reqget(FAR struct ieee802154_mac_s *mac, + int attribute); +static int mac802154_reqgts(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *characteristics); +static int mac802154_reqreset(FAR struct ieee802154_mac_s *mac, + bool setdefaults); +static int mac802154_reqrxenable(FAR struct ieee802154_mac_s *mac, + bool deferrable, int ontime, int duration); +static int mac802154_reqscan(FAR struct ieee802154_mac_s *mac, + uint8_t type, uint32_t channels, int duration); +static int mac802154_reqset(FAR struct ieee802154_mac_s *mac, + int attribute, FAR uint8_t *value, int valuelen); +static int mac802154_reqstart(FAR struct ieee802154_mac_s *mac, + uint16_t panid, int channel, uint8_t bo, uint8_t fo, + bool coord, bool batext, bool realign); +static int mac802154_reqsync(FAR struct ieee802154_mac_s *mac, + int channel, bool track); +static int mac802154_reqpoll(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *coordaddr); +static int mac802154_rspassociate(FAR struct ieee802154_mac_s *mac, + uint8_t eadr, uint16_t saddr, int status); +static int mac802154_rsporphan(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *orphanaddr, uint16_t saddr, bool associated); -static int mac802154_rsporphan (struct ieee802154_mac_s *mac, - uint8_t *orphanaddr, - uint16_t saddr, - bool associated); +/**************************************************************************** + * Private Data + ****************************************************************************/ -/* data */ static const struct ieee802154_macops_s mac802154ops = { .req_data = mac802154_reqdata @@ -221,30 +199,31 @@ static int mac802154_defaultmib(FAR struct ieee802154_privmac_s *priv) priv->macBattLifeExtPeriods = 0; priv->macMaxCSMABackoffs = 4; - priv->macBeaconOrder = 15; - priv->macSuperframeOrder = 15; + priv->macBeaconOrder = 15; + priv->macSuperframeOrder = 15; - priv->macMinBE = 3; - priv->macGTSPermit = 1; - priv->macPromiscuousMode = 0; - priv->macRxOnWhenIdle = 0; - priv->macBeaconTxTime = 0x000000; + priv->macMinBE = 3; + priv->macGTSPermit = 1; + priv->macPromiscuousMode = 0; + priv->macRxOnWhenIdle = 0; + priv->macBeaconTxTime = 0x000000; priv->macBeaconPayloadLength = 0; - priv->macBSN = 0; /*shall be random*/ + priv->macBSN = 0; /* Shall be random */ priv->macCoordExtendedAddress[8]; - priv->macCoordShortAddress = 0xffff; - priv->macDSN = 0 /*shall be random*/; - priv->macPANId = 0xffff; - priv->macShortAddress = 0xffff; + priv->macCoordShortAddress = 0xffff; + priv->macDSN = 0; /* Shall be random */ + priv->macPANId = 0xffff; + priv->macShortAddress = 0xffff; priv->macTransactionPersistenceTime = 0x01f4; #if 0 /* Security MIB */ - priv->macACLEntryDescriptorSetSize = 0; - priv->macDefaultSecurity = 0; - priv->macDefaultSecuritySuite = 0; + + priv->macACLEntryDescriptorSetSize = 0; + priv->macDefaultSecurity = 0; + priv->macDefaultSecuritySuite = 0; priv->macDefaultSecurityMaterialLength = 0x15; - priv->macSecurityMode = 0; + priv->macSecurityMode = 0; #endif } @@ -279,11 +258,9 @@ static int mac802154_applymib(FAR struct ieee802154_privmac_s *priv) ****************************************************************************/ static int mac802154_reqdata(FAR struct ieee802154_mac_s *mac, - uint8_t handle, - uint8_t *buf, - int len) + uint8_t handle, FAR uint8_t *buf, int len) { - FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; + FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } @@ -298,9 +275,9 @@ static int mac802154_reqdata(FAR struct ieee802154_mac_s *mac, ****************************************************************************/ static int mac802154_reqpurge(FAR struct ieee802154_mac_s *mac, - uint8_t handle) + uint8_t handle) { - FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; + FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } @@ -318,7 +295,7 @@ static int mac802154_reqassociate(FAR struct ieee802154_mac_s *mac, uint16_t panid, uint8_t *coordeadr) { - FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; + FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } @@ -335,10 +312,9 @@ static int mac802154_reqassociate(FAR struct ieee802154_mac_s *mac, ****************************************************************************/ static int mac802154_reqdisassociate(FAR struct ieee802154_mac_s *mac, - uint8_t *eadr, - uint8_t reason) + FAR uint8_t *eadr, uint8_t reason) { - FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; + FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } @@ -355,7 +331,7 @@ static int mac802154_reqdisassociate(FAR struct ieee802154_mac_s *mac, static int mac802154_reqget(FAR struct ieee802154_mac_s *mac, int attribute) { - FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; + FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } @@ -371,9 +347,9 @@ static int mac802154_reqget(FAR struct ieee802154_mac_s *mac, ****************************************************************************/ static int mac802154_reqgts(FAR struct ieee802154_mac_s *mac, - uint8_t* characteristics) + FAR uint8_t *characteristics) { - FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; + FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } @@ -406,11 +382,9 @@ static int mac802154_reqreset(FAR struct ieee802154_mac_s *mac, ****************************************************************************/ static int mac802154_reqrxenable(FAR struct ieee802154_mac_s *mac, - bool deferrable, - int ontime, - int duration) + bool deferrable, int ontime, int duration) { - FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; + FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } @@ -430,11 +404,9 @@ static int mac802154_reqrxenable(FAR struct ieee802154_mac_s *mac, ****************************************************************************/ static int mac802154_reqscan(FAR struct ieee802154_mac_s *mac, - uint8_t type, - uint32_t channels, - int duration) + uint8_t type, uint32_t channels, int duration) { - FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; + FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } @@ -449,11 +421,9 @@ static int mac802154_reqscan(FAR struct ieee802154_mac_s *mac, ****************************************************************************/ static int mac802154_reqset(FAR struct ieee802154_mac_s *mac, - int attribute, - uint8_t *value, - int valuelen) + int attribute, FAR uint8_t *value, int valuelen) { - FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; + FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } @@ -468,15 +438,11 @@ static int mac802154_reqset(FAR struct ieee802154_mac_s *mac, ****************************************************************************/ static int mac802154_reqstart(FAR struct ieee802154_mac_s *mac, - uint16_t panid, - int channel, - uint8_t bo, - uint8_t fo, - bool coord, - bool batext, + uint16_t panid, int channel, uint8_t bo, + uint8_t fo, bool coord, bool batext, bool realign) { - FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; + FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } @@ -492,10 +458,9 @@ static int mac802154_reqstart(FAR struct ieee802154_mac_s *mac, ****************************************************************************/ static int mac802154_reqsync(FAR struct ieee802154_mac_s *mac, - int channel, - bool track) + int channel, bool track) { - FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; + FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } @@ -511,9 +476,9 @@ static int mac802154_reqsync(FAR struct ieee802154_mac_s *mac, ****************************************************************************/ static int mac802154_reqpoll(FAR struct ieee802154_mac_s *mac, - uint8_t *coordaddr) + FAR uint8_t *coordaddr) { - FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; + FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } @@ -527,11 +492,9 @@ static int mac802154_reqpoll(FAR struct ieee802154_mac_s *mac, ****************************************************************************/ static int mac802154_rspassociate(FAR struct ieee802154_mac_s *mac, - uint8_t eadr, - uint16_t saddr, - int status) + uint8_t eadr, uint16_t saddr, int status) { - FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; + FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } @@ -545,11 +508,10 @@ static int mac802154_rspassociate(FAR struct ieee802154_mac_s *mac, ****************************************************************************/ static int mac802154_rsporphan(FAR struct ieee802154_mac_s *mac, - uint8_t *orphanaddr, - uint16_t saddr, + FAR uint8_t *orphanaddr, uint16_t saddr, bool associated) { - FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; + FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } @@ -565,22 +527,26 @@ static int mac802154_rsporphan(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -FAR struct ieee802154_mac_s * mac802154_register(FAR struct ieee802154_radio_s *radiodev, unsigned int minor) +FAR struct ieee802154_mac_s * + mac802154_register(FAR struct ieee802154_radio_s *radiodev, + unsigned int minor) { FAR struct ieee802154_privmac_s *mac; - /* allocate object */ - mac = (FAR struct ieee802154_privmac_s *)kmm_zalloc(sizeof(struct ieee802154_privmac_s)); + /* Allocate object */ + + mac = (FAR struct ieee802154_privmac_s *) + kmm_zalloc(sizeof(struct ieee802154_privmac_s)); if(!mac) { return NULL; } - /* init fields */ + /* Initialize fields */ + mac->pubmac.radio = radiodev; mac->pubmac.ops = mac802154ops; mac802154_defaultmib(mac); mac802154_applymib(mac); return &mac->pubmac; } - -- GitLab From 7a814ce1dc3b41efb069986ea8071389a0e2e505 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 15 Mar 2017 13:44:03 -0600 Subject: [PATCH 049/990] Bring closer to NuttX coding standard. --- wireless/ieee802154/ieee802154_device.c | 279 +++++++++++++++++------- 1 file changed, 200 insertions(+), 79 deletions(-) diff --git a/wireless/ieee802154/ieee802154_device.c b/wireless/ieee802154/ieee802154_device.c index 75921a88cd..f1413b31cf 100644 --- a/wireless/ieee802154/ieee802154_device.c +++ b/wireless/ieee802154/ieee802154_device.c @@ -34,9 +34,14 @@ * ****************************************************************************/ +/**************************************************************************** + * Included Files + ****************************************************************************/ + #include #include +#include #include #include #include @@ -47,22 +52,30 @@ #include #include +/**************************************************************************** + * Private Types + ****************************************************************************/ + struct ieee802154_devwrapper_s { - FAR struct ieee802154_radio_s *child; - sem_t devsem; /* Device access serialization semaphore */ - int opened; /* this device can only be opened once */ + FAR struct ieee802154_radio_s *child; + sem_t devsem; /* Device access serialization semaphore */ + bool opened; /* This device can only be opened once */ }; -/* when rx interrupt is complete, it calls sem_post(&dev->rxsem); */ -/* when tx interrupt is complete, it calls sem_post(&dev->txsem); */ +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ -static void ieee802154dev_semtake(FAR struct ieee802154_devwrapper_s *dev); -static int ieee802154dev_open (FAR struct file *filep); -static int ieee802154dev_close (FAR struct file *filep); -static ssize_t ieee802154dev_read (FAR struct file *filep, FAR char *buffer, size_t len); -static ssize_t ieee802154dev_write (FAR struct file *filep, FAR const char *buffer, size_t len); -static int ieee802154dev_ioctl (FAR struct file *filep, int cmd, unsigned long arg); +static void ieee802154dev_semtake(FAR struct ieee802154_devwrapper_s *dev); +static int ieee802154dev_open(FAR struct file *filep); +static int ieee802154dev_close(FAR struct file *filep); +static ssize_t ieee802154dev_read(FAR struct file *filep, FAR char *buffer, + size_t len); +static ssize_t ieee802154dev_write(FAR struct file *filep, + FAR const char *buffer, size_t len); +static int ieee802154dev_ioctl(FAR struct file *filep, int cmd, + unsigned long arg); /**************************************************************************** * Private Data @@ -74,13 +87,20 @@ static const struct file_operations ieee802154dev_fops = ieee802154dev_close, /* close */ ieee802154dev_read , /* read */ ieee802154dev_write, /* write */ - 0 , /* seek */ + NULL, /* seek */ ieee802154dev_ioctl /* ioctl */ #ifndef CONFIG_DISABLE_POLL - , 0 /* poll */ + , NULL /* poll */ +#endif +#ifndef CONFIG_DISABLE_PSEUDOFS_OPERATIONS + , NULL /* unlink */ #endif }; +/**************************************************************************** + * Private Functions + ****************************************************************************/ + /**************************************************************************** * Name: ieee802154dev_semtake * @@ -98,7 +118,8 @@ static void ieee802154dev_semtake(FAR struct ieee802154_devwrapper_s *dev) /* The only case that an error should occur here is if * the wait was awakened by a signal. */ - ASSERT(errno == EINTR); + + DEBUGASSERT(errno == EINTR); } } @@ -125,24 +146,32 @@ static inline void ieee802154dev_semgive(FAR struct ieee802154_devwrapper_s *dev static int ieee802154dev_open(FAR struct file *filep) { - FAR struct inode *inode = filep->f_inode; - FAR struct ieee802154_devwrapper_s *dev = inode->i_private; + FAR struct inode *inode; + FAR struct ieee802154_devwrapper_s *dev; + + DEBUGASSERT(filep != NULL && filep->f_inode != NULL); + inode = filep->f_inode; + dev = inode->i_private; + DEBUGASSERT(dev != NULL); + + /* Get exclusive access to the driver data structures */ ieee802154dev_semtake(dev); if (dev->opened) { + /* Already opened */ + return -EMFILE; } else { - /* Enable interrupts (only rx for now)*/ //mrf24j40_setreg(dev->spi, MRF24J40_INTCON, ~(MRF24J40_INTCON_RXIE) ); //dev->lower->enable(dev->lower, TRUE); - dev->opened = TRUE; + dev->opened = true; } ieee802154dev_semgive(dev); @@ -159,15 +188,24 @@ static int ieee802154dev_open(FAR struct file *filep) static int ieee802154dev_close(FAR struct file *filep) { - FAR struct inode *inode = filep->f_inode; - FAR struct ieee802154_devwrapper_s *dev = inode->i_private; + FAR struct inode *inode; + FAR struct ieee802154_devwrapper_s *dev; int ret = OK; + DEBUGASSERT(filep != NULL && filep->f_inode != NULL); + inode = filep->f_inode; + dev = inode->i_private; + DEBUGASSERT(dev != NULL); + + /* Get exclusive access to the driver data structures */ + ieee802154dev_semtake(dev); - if(!dev->opened) + if (!dev->opened) { - ret = -EIO; + /* Driver has not been opened */ + + ret = -EIO; } else { @@ -176,7 +214,7 @@ static int ieee802154dev_close(FAR struct file *filep) //mrf24j40_setreg(dev->spi, MRF24J40_INTCON, 0xFF ); //dev->lower->enable(dev->lower, FALSE); - dev->opened = FALSE; + dev->opened = false; } ieee802154dev_semgive(dev); @@ -195,13 +233,20 @@ static int ieee802154dev_close(FAR struct file *filep) static ssize_t ieee802154dev_read(FAR struct file *filep, FAR char *buffer, size_t len) { - FAR struct inode *inode = filep->f_inode; - FAR struct ieee802154_devwrapper_s *dev = inode->i_private; + FAR struct inode *inode; + FAR struct ieee802154_devwrapper_s *dev; + FAR struct ieee802154_packet_s *buf; int ret = OK; - FAR struct ieee802154_packet_s *buf = (FAR struct ieee802154_packet_s*)buffer; + DEBUGASSERT(filep != NULL && filep->f_inode != NULL); + inode = filep->f_inode; + dev = inode->i_private; + DEBUGASSERT(dev != NULL && buffer != NULL); + buf = (FAR struct ieee802154_packet_s*)buffer; + + /* Get exclusive access to the driver data structures */ - if (lenchild->rxsem); #else @@ -229,13 +275,12 @@ static ssize_t ieee802154dev_read(FAR struct file *filep, FAR char *buffer, size goto done; } - /* disable read until we have process the current read */ - dev->child->ops->rxenable(dev->child, 0, NULL); + /* Disable read until we have process the current read */ + dev->child->ops->rxenable(dev->child, 0, NULL); ret = buf->len; done: - return ret; } @@ -244,61 +289,76 @@ done: * * Description: * Send a packet immediately. - * TODO: Put a packet in the send queue. The packet will be sent as soon as possible. - * The buffer must point to a struct ieee802154_packet_s with the correct length. + * TODO: Put a packet in the send queue. The packet will be sent as soon + * as possible. The buffer must point to a struct ieee802154_packet_s + * with the correct length. * ****************************************************************************/ -static ssize_t ieee802154dev_write(FAR struct file *filep, FAR const char *buffer, size_t len) +static ssize_t ieee802154dev_write(FAR struct file *filep, + FAR const char *buffer, size_t len) { - FAR struct inode *inode = filep->f_inode; - FAR struct ieee802154_devwrapper_s *dev = inode->i_private; - FAR struct ieee802154_packet_s *packet; - int ret = OK; - - /* TODO: Make this an option or have a new method of doing timeout from ioctrl */ + FAR struct inode *inode; + FAR struct ieee802154_devwrapper_s *dev; + FAR struct ieee802154_packet_s *packet; FAR struct timespec timeout; + int ret = OK; + + DEBUGASSERT(filep != NULL && filep->f_inode != NULL); + inode = filep->f_inode; + dev = inode->i_private; + DEBUGASSERT(dev != NULL); + + /* Get exclusive access to the driver data structures */ + + /* TODO: Make this an option or have a new method of doing timeout from + * ioctrl. + */ timeout.tv_sec = 1; timeout.tv_nsec = 0; - /* sanity checks */ + /* Sanity checks */ - if (lenlen > 125) /* Max len 125, 2 FCS bytes auto added by mrf*/ + if (packet->len > 125) /* Max len 125, 2 FCS bytes auto added by mrf */ { ret = -EPERM; - // goto done; + //goto done; DEBUGASSERT(0); } /* Copy packet to normal device TX fifo. * Beacons and GTS transmission will be handled via IOCTLs */ - ret = dev->child->ops->transmit(dev->child, packet); - if(ret != packet->len) + ret = dev->child->ops->transmit(dev->child, packet); + if (ret != packet->len) { ret = -EPERM; goto done; } - if(sem_timedwait(&dev->child->txsem, &timeout)) + if (sem_timedwait(&dev->child->txsem, &timeout)) { dbg("Radio Device timedout on Tx\n"); } done: - /* okay, tx interrupt received. check transmission status to decide success. */ + /* Okay, tx interrupt received. check transmission status to decide success. */ return ret; } @@ -311,33 +371,95 @@ done: * ****************************************************************************/ -static int ieee802154dev_ioctl(FAR struct file *filep, int cmd, unsigned long arg) +static int ieee802154dev_ioctl(FAR struct file *filep, int cmd, + unsigned long arg) { - FAR struct inode *inode = filep->f_inode; - FAR struct ieee802154_devwrapper_s *dev = inode->i_private; - FAR struct ieee802154_radio_s *child = dev->child; + FAR struct inode *inode; + FAR struct ieee802154_devwrapper_s *dev; + FAR struct ieee802154_radio_s *child; int ret = OK; - switch(cmd) + DEBUGASSERT(filep != NULL && filep->f_inode != NULL); + inode = filep->f_inode; + dev = inode->i_private; + DEBUGASSERT(dev != NULL && dev->child != NULL; + child = dev->child; + + /* Get exclusive access to the driver data structures */ + + switch (cmd) { - case MAC854IOCSCHAN : ret = child->ops->setchannel (child, (uint8_t) arg); break; - case MAC854IOCGCHAN : ret = child->ops->getchannel (child, (FAR uint8_t*) arg); break; - case MAC854IOCSPANID : ret = child->ops->setpanid (child, (uint16_t) arg); break; - case MAC854IOCGPANID : ret = child->ops->getpanid (child, (FAR uint16_t*) arg); break; - case MAC854IOCSSADDR : ret = child->ops->setsaddr (child, (uint16_t) arg); break; - case MAC854IOCGSADDR : ret = child->ops->getsaddr (child, (FAR uint16_t*) arg); break; - case MAC854IOCSEADDR : ret = child->ops->seteaddr (child, (FAR uint8_t*) arg); break; - case MAC854IOCGEADDR : ret = child->ops->geteaddr (child, (FAR uint8_t*) arg); break; - case MAC854IOCSPROMISC: ret = child->ops->setpromisc (child, (bool) arg); break; - case MAC854IOCGPROMISC: ret = child->ops->getpromisc (child, (FAR bool*) arg); break; - case MAC854IOCSDEVMODE: ret = child->ops->setdevmode (child, (uint8_t) arg); break; - case MAC854IOCGDEVMODE: ret = child->ops->getdevmode (child, (FAR uint8_t*) arg); break; - case MAC854IOCSTXP : ret = child->ops->settxpower (child, (int32_t) arg); break; - case MAC854IOCGTXP : ret = child->ops->gettxpower (child, (FAR int32_t*) arg); break; - case MAC854IOCSCCA : ret = child->ops->setcca (child, (FAR struct ieee802154_cca_s*)arg); break; - case MAC854IOCGCCA : ret = child->ops->getcca (child, (FAR struct ieee802154_cca_s*)arg); break; - case MAC854IOCGED : ret = child->ops->energydetect(child, (FAR uint8_t*) arg); break; - default : ret = child->ops->ioctl (child, cmd, arg); + case MAC854IOCSCHAN: + ret = child->ops->setchannel(child, (uint8_t)arg); + break; + + case MAC854IOCGCHAN: + ret = child->ops->getchannel(child, (FAR uint8_t*)arg); + break; + + case MAC854IOCSPANID: + ret = child->ops->setpanid(child, (uint16_t)arg); + break; + + case MAC854IOCGPANID: + ret = child->ops->getpanid(child, (FAR uint16_t*)arg); + break; + + case MAC854IOCSSADDR: + ret = child->ops->setsaddr(child, (uint16_t)arg); + break; + + case MAC854IOCGSADDR: + ret = child->ops->getsaddr(child, (FAR uint16_t*)arg); + break; + + case MAC854IOCSEADDR: + ret = child->ops->seteaddr(child, (FAR uint8_t*)arg); + break; + + case MAC854IOCGEADDR: + ret = child->ops->geteaddr(child, (FAR uint8_t*)arg); + break; + + case MAC854IOCSPROMISC: + ret = child->ops->setpromisc(child, (bool)arg); + break; + + case MAC854IOCGPROMISC: + ret = child->ops->getpromisc(child, (FAR bool*)arg); + break; + + case MAC854IOCSDEVMODE: + ret = child->ops->setdevmode(child, (uint8_t)arg); + break; + + case MAC854IOCGDEVMODE: + ret = child->ops->getdevmode(child, (FAR uint8_t*)arg); + break; + + case MAC854IOCSTXP: + ret = child->ops->settxpower(child, (int32_t)arg); + break; + + case MAC854IOCGTXP: + ret = child->ops->gettxpower(child, (FAR int32_t*)arg); + break; + + case MAC854IOCSCCA: + ret = child->ops->setcca(child, (FAR struct ieee802154_cca_s*)arg); + break; + + case MAC854IOCGCCA: + ret = child->ops->getcca(child, (FAR struct ieee802154_cca_s*)arg); + break; + + case MAC854IOCGED: + ret = child->ops->energydetect(child, (FAR uint8_t*)arg); + break; + + default: + ret = child->ops->ioctl(child, cmd,arg); + break; } return ret; @@ -351,24 +473,23 @@ static int ieee802154dev_ioctl(FAR struct file *filep, int cmd, unsigned long ar * ****************************************************************************/ -int ieee802154_register(FAR struct ieee802154_radio_s *ieee, unsigned int minor) +int ieee802154_register(FAR struct ieee802154_radio_s *ieee, + unsigned int minor) { - char devname[16]; FAR struct ieee802154_devwrapper_s *dev; + char devname[16]; dev = kmm_zalloc(sizeof(struct ieee802154_devwrapper_s)); - - if (!dev) + if (dev == NULL) { return -ENOMEM; } dev->child = ieee; - sem_init(&dev->devsem , 0, 1); /* Allow the device to be opened once before blocking */ + sem_init(&dev->devsem, 0, 1); /* Allow the device to be opened once before blocking */ sprintf(devname, "/dev/ieee%d", minor); return register_driver(devname, &ieee802154dev_fops, 0666, dev); } - -- GitLab From fc6405d51995f32789aaa062a2badb6eae36fa46 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 15 Mar 2017 14:16:19 -0600 Subject: [PATCH 050/990] Bring closer to NuttX coding standard. --- drivers/wireless/ieee802154/at86rf23x.c | 1055 +++++++++++++---------- wireless/ieee802154/ieee802154_device.c | 2 +- 2 files changed, 590 insertions(+), 467 deletions(-) diff --git a/drivers/wireless/ieee802154/at86rf23x.c b/drivers/wireless/ieee802154/at86rf23x.c index 8d2e1cb133..653a92b313 100644 --- a/drivers/wireless/ieee802154/at86rf23x.c +++ b/drivers/wireless/ieee802154/at86rf23x.c @@ -65,7 +65,11 @@ ************************************************************************************/ #ifndef CONFIG_SCHED_HPWORK -#error High priority work queue required in this driver +# error High priority work queue required in this driver +#endif + +#ifndef CONFIG_SPI_EXCHANGE +# error CONFIG_SPI_EXCHANGE required for this driver #endif #ifndef CONFIG_IEEE802154_at86rf23x_SPIMODE @@ -84,38 +88,36 @@ #define AT86RF23X_RXMODE_AUTOACK 3 /* Definitions for PA control on high power modules */ + #define AT86RF23X_PA_AUTO 1 #define AT86RF23X_PA_ED 2 #define AT86RF23X_PA_SLEEP 3 - /************************************************************************************ * Private Types ************************************************************************************/ -/* - * AT86RF23x device instance +/* AT86RF23x device instance * * Make sure that struct ieee802154_radio_s remains first. If not it will break the * code - * */ + struct at86rf23x_dev_s { - struct ieee802154_radio_s ieee; /* Public device instance */ - FAR struct spi_dev_s *spi; /* Saved SPI interface instance */ - struct work_s irqwork; /* Interrupt continuation work queue support */ - FAR const struct at86rf23x_lower_s *lower; /* Low-level MCU-specific support */ - uint16_t panid; /* PAN identifier, FFFF = not set */ - uint16_t saddr; /* short address, FFFF = not set */ - uint8_t eaddr[8]; /* extended address, FFFFFFFFFFFFFFFF = not set */ - uint8_t channel; /* 11 to 26 for the 2.4 GHz band */ - uint8_t devmode; /* device mode: device, coord, pancoord */ - uint8_t paenabled; /* enable usage of PA */ - uint8_t rxmode; /* Reception mode: Main, no CRC, promiscuous */ - int32_t txpower; /* TX power in mBm = dBm/100 */ - struct ieee802154_cca_s cca; /* Clear channel assessement method */ - + struct ieee802154_radio_s ieee; /* Public device instance */ + FAR struct spi_dev_s *spi; /* Saved SPI interface instance */ + struct work_s irqwork; /* Interrupt continuation work queue support */ + FAR const struct at86rf23x_lower_s *lower; /* Low-level MCU-specific support */ + uint16_t panid; /* PAN identifier, FFFF = not set */ + uint16_t saddr; /* Short address, FFFF = not set */ + uint8_t eaddr[8]; /* Extended address, FFFFFFFFFFFFFFFF = not set */ + uint8_t channel; /* 11 to 26 for the 2.4 GHz band */ + uint8_t devmode; /* Device mode: device, coord, pancoord */ + uint8_t paenabled; /* Enable usage of PA */ + uint8_t rxmode; /* Reception mode: Main, no CRC, promiscuous */ + int32_t txpower; /* TX power in mBm = dBm/100 */ + struct ieee802154_cca_s cca; /* Clear channel assessement method */ }; /**************************************************************************** @@ -123,45 +125,74 @@ struct at86rf23x_dev_s ****************************************************************************/ /* Internal operations */ + static void at86rf23x_lock(FAR struct spi_dev_s *spi); static void at86rf23x_unlock(FAR struct spi_dev_s *spi); -static void at86rf23x_setreg(FAR struct spi_dev_s *spi, uint32_t addr, uint8_t val); +static void at86rf23x_setreg(FAR struct spi_dev_s *spi, uint32_t addr, + uint8_t val); static uint8_t at86rf23x_getreg(FAR struct spi_dev_s *spi, uint32_t addr); -static int at86rf23x_writeframe(FAR struct spi_dev_s *spi, uint8_t *frame, uint8_t len); -static uint8_t at86rf23x_readframe(FAR struct spi_dev_s *spi, uint8_t *frame_rx); -static int at86rf23x_setTRXstate(FAR struct at86rf23x_dev_s *dev, uint8_t state, uint8_t force); +static int at86rf23x_writeframe(FAR struct spi_dev_s *spi, FAR uint8_t *frame, + uint8_t len); +static uint8_t at86rf23x_readframe(FAR struct spi_dev_s *spi, + FAR uint8_t *frame_rx); +static int at86rf23x_setTRXstate(FAR struct at86rf23x_dev_s *dev, + uint8_t state, uint8_t force); static uint8_t at86rf23x_getTRXstate(FAR struct at86rf23x_dev_s *dev); static int at86rf23x_resetrf(FAR struct at86rf23x_dev_s *dev); static int at86rf23x_initialize(FAR struct at86rf23x_dev_s *dev); -static int at86rf23x_regdump(FAR struct at86rf23x_dev_s *dev); -static void at86rf23x_irqwork_rx(FAR struct at86rf23x_dev_s *dev); -static void at86rf23x_irqwork_tx(FAR struct at86rf23x_dev_s *dev); -static void at86rf23x_irqworker(FAR void *arg); -static int at86rf23x_interrupt(int irq, FAR void *context); +static int at86rf23x_regdump(FAR struct at86rf23x_dev_s *dev); +static void at86rf23x_irqwork_rx(FAR struct at86rf23x_dev_s *dev); +static void at86rf23x_irqwork_tx(FAR struct at86rf23x_dev_s *dev); +static void at86rf23x_irqworker(FAR void *arg); +static int at86rf23x_interrupt(int irq, FAR void *context); /* Driver operations */ -static int at86rf23x_setchannel (FAR struct ieee802154_radio_s *ieee, uint8_t chan); -static int at86rf23x_getchannel (FAR struct ieee802154_radio_s *ieee, FAR uint8_t *chan); -static int at86rf23x_setpanid (FAR struct ieee802154_radio_s *ieee, uint16_t panid); -static int at86rf23x_getpanid (FAR struct ieee802154_radio_s *ieee, FAR uint16_t *panid); -static int at86rf23x_setsaddr (FAR struct ieee802154_radio_s *ieee, uint16_t saddr); -static int at86rf23x_getsaddr (FAR struct ieee802154_radio_s *ieee, FAR uint16_t *saddr); -static int at86rf23x_seteaddr (FAR struct ieee802154_radio_s *ieee, FAR uint8_t *eaddr); -static int at86rf23x_geteaddr (FAR struct ieee802154_radio_s *ieee, FAR uint8_t *eaddr); -static int at86rf23x_setpromisc (FAR struct ieee802154_radio_s *ieee, bool promisc); -static int at86rf23x_getpromisc (FAR struct ieee802154_radio_s *ieee, FAR bool *promisc); -static int at86rf23x_setdevmode (FAR struct ieee802154_radio_s *ieee, uint8_t mode); -static int at86rf23x_getdevmode (FAR struct ieee802154_radio_s *ieee, FAR uint8_t *mode); -static int at86rf23x_settxpower (FAR struct ieee802154_radio_s *ieee, int32_t txpwr); -static int at86rf23x_gettxpower (FAR struct ieee802154_radio_s *ieee, FAR int32_t *txpwr); -static int at86rf23x_setcca (FAR struct ieee802154_radio_s *ieee, FAR struct ieee802154_cca_s *cca); -static int at86rf23x_getcca (FAR struct ieee802154_radio_s *ieee, FAR struct ieee802154_cca_s *cca); -static int at86rf23x_ioctl (FAR struct ieee802154_radio_s *ieee, int cmd, unsigned long arg); -static int at86rf23x_energydetect(FAR struct ieee802154_radio_s *ieee, FAR uint8_t *energy); -static int at86rf23x_rxenable (FAR struct ieee802154_radio_s *ieee, bool state, FAR struct ieee802154_packet_s *packet); -static int at86rf23x_transmit (FAR struct ieee802154_radio_s *ieee, FAR struct ieee802154_packet_s *packet); +static int at86rf23x_setchannel(FAR struct ieee802154_radio_s *ieee, + uint8_t chan); +static int at86rf23x_getchannel(FAR struct ieee802154_radio_s *ieee, + FAR uint8_t *chan); +static int at86rf23x_setpanid(FAR struct ieee802154_radio_s *ieee, + uint16_t panid); +static int at86rf23x_getpanid(FAR struct ieee802154_radio_s *ieee, + FAR uint16_t *panid); +static int at86rf23x_setsaddr(FAR struct ieee802154_radio_s *ieee, + uint16_t saddr); +static int at86rf23x_getsaddr(FAR struct ieee802154_radio_s *ieee, + FAR uint16_t *saddr); +static int at86rf23x_seteaddr(FAR struct ieee802154_radio_s *ieee, + FAR uint8_t *eaddr); +static int at86rf23x_geteaddr(FAR struct ieee802154_radio_s *ieee, + FAR uint8_t *eaddr); +static int at86rf23x_setpromisc(FAR struct ieee802154_radio_s *ieee, + bool promisc); +static int at86rf23x_getpromisc(FAR struct ieee802154_radio_s *ieee, + FAR bool *promisc); +static int at86rf23x_setdevmode(FAR struct ieee802154_radio_s *ieee, + uint8_t mode); +static int at86rf23x_getdevmode(FAR struct ieee802154_radio_s *ieee, + FAR uint8_t *mode); +static int at86rf23x_settxpower(FAR struct ieee802154_radio_s *ieee, + int32_t txpwr); +static int at86rf23x_gettxpower(FAR struct ieee802154_radio_s *ieee, + FAR int32_t *txpwr); +static int at86rf23x_setcca(FAR struct ieee802154_radio_s *ieee, + FAR struct ieee802154_cca_s *cca); +static int at86rf23x_getcca(FAR struct ieee802154_radio_s *ieee, + FAR struct ieee802154_cca_s *cca); +static int at86rf23x_ioctl(FAR struct ieee802154_radio_s *ieee, int cmd, + unsigned long arg); +static int at86rf23x_energydetect(FAR struct ieee802154_radio_s *ieee, + FAR uint8_t *energy); +static int at86rf23x_rxenable(FAR struct ieee802154_radio_s *ieee, + bool state, FAR struct ieee802154_packet_s *packet); +static int at86rf23x_transmit(FAR struct ieee802154_radio_s *ieee, + FAR struct ieee802154_packet_s *packet); + +/**************************************************************************** + * Private Data + ****************************************************************************/ /* These are pointers to ALL registered at86rf23x devices. * This table is used during irqs to find the context @@ -174,37 +205,32 @@ static struct at86rf23x_dev_s g_at86rf23x_devices[1]; static const struct ieee802154_radioops_s at86rf23x_devops = { - .setchannel = at86rf23x_setchannel, - .getchannel = at86rf23x_getchannel, - .setpanid = at86rf23x_setpanid, - .getpanid = at86rf23x_getpanid, - .setsaddr = at86rf23x_setsaddr, - .getsaddr = at86rf23x_getsaddr, - .seteaddr = at86rf23x_seteaddr, - .geteaddr = at86rf23x_geteaddr, - .setpromisc = at86rf23x_setpromisc, - .getpromisc = at86rf23x_getpromisc, - .setdevmode = at86rf23x_setdevmode, - .getdevmode = at86rf23x_getdevmode, - .settxpower = at86rf23x_settxpower, - .gettxpower = at86rf23x_gettxpower, - .setcca = at86rf23x_setcca, - .getcca = at86rf23x_getcca, - .ioctl = at86rf23x_ioctl, + .setchannel = at86rf23x_setchannel, + .getchannel = at86rf23x_getchannel, + .setpanid = at86rf23x_setpanid, + .getpanid = at86rf23x_getpanid, + .setsaddr = at86rf23x_setsaddr, + .getsaddr = at86rf23x_getsaddr, + .seteaddr = at86rf23x_seteaddr, + .geteaddr = at86rf23x_geteaddr, + .setpromisc = at86rf23x_setpromisc, + .getpromisc = at86rf23x_getpromisc, + .setdevmode = at86rf23x_setdevmode, + .getdevmode = at86rf23x_getdevmode, + .settxpower = at86rf23x_settxpower, + .gettxpower = at86rf23x_gettxpower, + .setcca = at86rf23x_setcca, + .getcca = at86rf23x_getcca, + .ioctl = at86rf23x_ioctl, .energydetect = at86rf23x_energydetect, - .rxenable = at86rf23x_rxenable, - .transmit = at86rf23x_transmit + .rxenable = at86rf23x_rxenable, + .transmit = at86rf23x_transmit }; /**************************************************************************** * Private Functions ****************************************************************************/ -#ifndef CONFIG_SPI_EXCHANGE -#error CONFIG_SPI_EXCHANGE required for this driver -#endif - -/* hardware access routines */ - + /**************************************************************************** * Name: at86rf23x_lock * @@ -215,11 +241,10 @@ static const struct ieee802154_radioops_s at86rf23x_devops = static void at86rf23x_lock(FAR struct spi_dev_s *spi) { - SPI_LOCK (spi, 1); - SPI_SETBITS (spi, 8); - SPI_SETMODE (spi, CONFIG_IEEE802154_at86rf23x_SPIMODE ); - SPI_SETFREQUENCY(spi, CONFIG_IEEE802154_at86rf23x_FREQUENCY ); - + SPI_LOCK(spi, 1); + SPI_SETBITS(spi, 8); + SPI_SETMODE(spi, CONFIG_IEEE802154_at86rf23x_SPIMODE); + SPI_SETFREQUENCY(spi, CONFIG_IEEE802154_at86rf23x_FREQUENCY); } /**************************************************************************** @@ -232,7 +257,7 @@ static void at86rf23x_lock(FAR struct spi_dev_s *spi) static void at86rf23x_unlock(FAR struct spi_dev_s *spi) { - SPI_LOCK(spi,0); + SPI_LOCK(spi, 0); } /**************************************************************************** @@ -243,7 +268,8 @@ static void at86rf23x_unlock(FAR struct spi_dev_s *spi) * ****************************************************************************/ -static void at86rf23x_setreg(FAR struct spi_dev_s *spi, uint32_t addr, uint8_t val) +static void at86rf23x_setreg(FAR struct spi_dev_s *spi, uint32_t addr, + uint8_t val) { uint8_t reg[2]; @@ -258,7 +284,6 @@ static void at86rf23x_setreg(FAR struct spi_dev_s *spi, uint32_t addr, uint8_t v at86rf23x_unlock(spi); vdbg("0x%02X->r[0x%02X]\n", val, addr); - } /**************************************************************************** @@ -268,25 +293,27 @@ static void at86rf23x_setreg(FAR struct spi_dev_s *spi, uint32_t addr, uint8_t v * Return the value of an at86rf23x device register * ****************************************************************************/ + static uint8_t at86rf23x_getreg(FAR struct spi_dev_s *spi, uint32_t addr) { - uint8_t reg[2]; - uint8_t val[2]; + uint8_t reg[2]; + uint8_t val[2]; - /* Add Read mask to desired register */ - reg[0] = addr | RF23X_SPI_REG_READ; + /* Add Read mask to desired register */ - at86rf23x_lock (spi); + reg[0] = addr | RF23X_SPI_REG_READ; - SPI_SELECT (spi, SPIDEV_IEEE802154, true); - SPI_EXCHANGE (spi, reg, val, 2); - SPI_SELECT (spi, SPIDEV_IEEE802154, false); + at86rf23x_lock (spi); - at86rf23x_unlock(spi); + SPI_SELECT(spi, SPIDEV_IEEE802154, true); + SPI_EXCHANGE(spi, reg, val, 2); + SPI_SELECT(spi, SPIDEV_IEEE802154, false); - vdbg("r[0x%02X]=0x%02X\n",addr,val[1]); + at86rf23x_unlock(spi); - return val[1]; + vdbg("r[0x%02X]=0x%02X\n",addr,val[1]); + + return val[1]; } /**************************************************************************** @@ -298,17 +325,15 @@ static uint8_t at86rf23x_getreg(FAR struct spi_dev_s *spi, uint32_t addr) * register. * ****************************************************************************/ -static void at86rf23x_setregbits(FAR struct spi_dev_s *spi, - uint8_t addr, - uint8_t pos, - uint8_t mask, - uint8_t val) + +static void at86rf23x_setregbits(FAR struct spi_dev_s *spi, uint8_t addr, + uint8_t pos, uint8_t mask, uint8_t val) { - uint8_t reg; + uint8_t reg; - reg = at86rf23x_getreg(spi, addr); - reg = (reg & ~(mask << pos)) | (val << pos); - at86rf23x_setreg(spi, addr, reg); + reg = at86rf23x_getreg(spi, addr); + reg = (reg & ~(mask << pos)) | (val << pos); + at86rf23x_setreg(spi, addr, reg); } /**************************************************************************** @@ -318,17 +343,16 @@ static void at86rf23x_setregbits(FAR struct spi_dev_s *spi, * Return the value of an section of the at86rf23x device register. * ****************************************************************************/ -static uint8_t at86rf23x_getregbits(FAR struct spi_dev_s *spi, - uint8_t addr, - uint8_t pos, - uint8_t mask) + +static uint8_t at86rf23x_getregbits(FAR struct spi_dev_s *spi, uint8_t addr, + uint8_t pos, uint8_t mask) { - uint8_t val; + uint8_t val; - val = at86rf23x_getreg(spi, addr); - val = (val >> pos) & mask; + val = at86rf23x_getreg(spi, addr); + val = (val >> pos) & mask; - return val; + return val; } /**************************************************************************** @@ -339,23 +363,25 @@ static uint8_t at86rf23x_getregbits(FAR struct spi_dev_s *spi, * initiate the transfer, just write to the buffer. * ****************************************************************************/ -static int at86rf23x_writeframe(FAR struct spi_dev_s *spi, uint8_t *frame, uint8_t len) + +static int at86rf23x_writeframe(FAR struct spi_dev_s *spi, FAR uint8_t *frame, + uint8_t len) { -// report_packet(frame_wr, len); - uint8_t reg = RF23X_SPI_FRAME_WRITE; +//report_packet(frame_wr, len); + uint8_t reg = RF23X_SPI_FRAME_WRITE; - at86rf23x_lock(spi); + at86rf23x_lock(spi); - SPI_SELECT(spi, SPIDEV_IEEE802154, true); + SPI_SELECT(spi, SPIDEV_IEEE802154, true); - SPI_SNDBLOCK(spi, ®, 1); - SPI_SNDBLOCK(spi, &frame, len); + SPI_SNDBLOCK(spi, ®, 1); + SPI_SNDBLOCK(spi, &frame, len); - SPI_SELECT(spi, SPIDEV_IEEE802154, false); + SPI_SELECT(spi, SPIDEV_IEEE802154, false); - at86rf23x_unlock(spi); + at86rf23x_unlock(spi); - return len; + return len; } /**************************************************************************** @@ -366,26 +392,27 @@ static int at86rf23x_writeframe(FAR struct spi_dev_s *spi, uint8_t *frame, uint8 * indicates a frame has been received. * ****************************************************************************/ -static uint8_t at86rf23x_readframe(FAR struct spi_dev_s *spi, uint8_t *frame_rx) + +static uint8_t at86rf23x_readframe(FAR struct spi_dev_s *spi, + FAR uint8_t *frame_rx) { - uint8_t len, reg; + uint8_t len, reg; - reg = RF23X_SPI_FRAME_READ; + reg = RF23X_SPI_FRAME_READ; - at86rf23x_lock(spi); - SPI_SELECT(spi, SPIDEV_IEEE802154, true); + at86rf23x_lock(spi); + SPI_SELECT(spi, SPIDEV_IEEE802154, true); - SPI_SNDBLOCK(spi, ®, 1); - SPI_RECVBLOCK(spi, &len, 1); - SPI_RECVBLOCK(spi, frame_rx, len+3); + SPI_SNDBLOCK(spi, ®, 1); + SPI_RECVBLOCK(spi, &len, 1); + SPI_RECVBLOCK(spi, frame_rx, len+3); - SPI_SELECT(spi, SPIDEV_IEEE802154, false); - at86rf23x_unlock(spi); + SPI_SELECT(spi, SPIDEV_IEEE802154, false); + at86rf23x_unlock(spi); - return len; + return len; } - /**************************************************************************** * Name: at86rf23x_getTRXstate * @@ -393,9 +420,10 @@ static uint8_t at86rf23x_readframe(FAR struct spi_dev_s *spi, uint8_t *frame_rx) * Return the current status of the TRX state machine. * ****************************************************************************/ + static uint8_t at86rf23x_getTRXstate(FAR struct at86rf23x_dev_s *dev) { - return at86rf23x_getregbits(dev->spi, RF23X_TRXSTATUS_STATUS); + return at86rf23x_getregbits(dev->spi, RF23X_TRXSTATUS_STATUS); } /**************************************************************************** @@ -409,15 +437,19 @@ static uint8_t at86rf23x_getTRXstate(FAR struct at86rf23x_dev_s *dev) * 510us. * ****************************************************************************/ -static int at86rf23x_setTRXstate(FAR struct at86rf23x_dev_s *dev, uint8_t state, uint8_t force) + +static int at86rf23x_setTRXstate(FAR struct at86rf23x_dev_s *dev, + uint8_t state, uint8_t force) { /* Get the current state of the transceiver */ + uint8_t status = at86rf23x_getTRXstate(dev); int ret = OK; /* TODO I don't have every state included verify this will work with SLEEP */ - if((status != TRX_STATUS_TRXOFF) && + + if ((status != TRX_STATUS_TRXOFF) && (status != TRX_STATUS_RXON) && (status != TRX_STATUS_PLLON) && (status != TRX_STATUS_RXAACKON) && @@ -431,164 +463,161 @@ static int at86rf23x_setTRXstate(FAR struct at86rf23x_dev_s *dev, uint8_t state, int8_t init_status = status; /* Start the state change */ + switch(state) { case TRX_CMD_TRXOFF: - if(status == TRX_STATUS_TRXOFF) - { - break; - } - /* verify in a state that will transfer to TRX_OFF if not check if force is required */ - if( (status == TRX_STATUS_RXON) || - (status == TRX_STATUS_PLLON) || - (status == TRX_STATUS_RXAACKON) || - (status == TRX_STATUS_TXARETON)) - { - at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_TRXOFF); - up_udelay(RF23X_TIME_TRANSITION_PLL_ACTIVE); - } - else if(status == TRX_STATUS_PON) - { - at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_TRXOFF); - up_udelay(RF23X_TIME_P_ON_TO_TRXOFF); - } - else if(force) - { - at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_FORCETRXOFF); - up_udelay(RF23X_TIME_FORCE_TRXOFF); - } + if (status == TRX_STATUS_TRXOFF) + { + break; + } + + /* verify in a state that will transfer to TRX_OFF if not check if + * force is required. + */ + + if ((status == TRX_STATUS_RXON) || + (status == TRX_STATUS_PLLON) || + (status == TRX_STATUS_RXAACKON) || + (status == TRX_STATUS_TXARETON)) + { + at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_TRXOFF); + up_udelay(RF23X_TIME_TRANSITION_PLL_ACTIVE); + } + else if (status == TRX_STATUS_PON) + { + at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_TRXOFF); + up_udelay(RF23X_TIME_P_ON_TO_TRXOFF); + } + else if (force) + { + at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_FORCETRXOFF); + up_udelay(RF23X_TIME_FORCE_TRXOFF); + } status = at86rf23x_getregbits(dev->spi, RF23X_TRXSTATUS_STATUS); + if (status != TRX_STATUS_TRXOFF) + { + ret = ERROR; + } - if(status != TRX_STATUS_TRXOFF) - { - ret = ERROR; - } - - break; + break; case TRX_CMD_RX_ON: + if (status == TRX_STATUS_RXON) + { + break; + } - if(status == TRX_STATUS_RXON) - { - break; - } - - if (status == TRX_STATUS_TRXOFF) - { - at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_RX_ON); - up_udelay(RF23X_TIME_TRXOFF_TO_PLL); - } - - else if((status == TRX_STATUS_RXAACKON) || - (status == TRX_STATUS_RXON) || - (status == TRX_STATUS_PLLON) || - (status == TRX_STATUS_TXARETON)) - { - at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_RX_ON); - up_udelay(RF23X_TIME_TRANSITION_PLL_ACTIVE); - } - - status = at86rf23x_getregbits(dev->spi, RF23X_TRXSTATUS_STATUS); - - if(status != TRX_STATUS_RXON) - { - ret = ERROR; - } - break; - - /* transition to PLL_ON */ - case TRX_CMD_PLL_ON: + if (status == TRX_STATUS_TRXOFF) + { + at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_RX_ON); + up_udelay(RF23X_TIME_TRXOFF_TO_PLL); + } + else if ((status == TRX_STATUS_RXAACKON) || + (status == TRX_STATUS_RXON) || + (status == TRX_STATUS_PLLON) || + (status == TRX_STATUS_TXARETON)) + { + at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_RX_ON); + up_udelay(RF23X_TIME_TRANSITION_PLL_ACTIVE); + } + + status = at86rf23x_getregbits(dev->spi, RF23X_TRXSTATUS_STATUS); + if (status != TRX_STATUS_RXON) + { + ret = ERROR; + } + + break; - if(status == TRX_STATUS_PLLON) - { - break; - } + /* Transition to PLL_ON */ + + case TRX_CMD_PLL_ON: + if (status == TRX_STATUS_PLLON) + { + break; + } if (status == TRX_STATUS_TRXOFF) - { - at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_PLL_ON); - up_udelay(RF23X_TIME_TRXOFF_TO_PLL); - } + { + at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_PLL_ON); + up_udelay(RF23X_TIME_TRXOFF_TO_PLL); + } else - { - at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_PLL_ON); - up_udelay(RF23X_TIME_TRANSITION_PLL_ACTIVE); - } + { + at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_PLL_ON); + up_udelay(RF23X_TIME_TRANSITION_PLL_ACTIVE); + } status = at86rf23x_getregbits(dev->spi, RF23X_TRXSTATUS_STATUS); + if (status != TRX_STATUS_PLLON) + { + ret = ERROR; + } - if(status != TRX_STATUS_PLLON) - { - ret = ERROR; - } break; case TRX_CMD_RX_AACK_ON: - - if(status == TRX_STATUS_RXAACKON) - { - break; - } + if (status == TRX_STATUS_RXAACKON) + { + break; + } if (status == TRX_STATUS_TRXOFF || status == TRX_STATUS_TXARETON) - { - at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_RX_ON); + { + at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_RX_ON); - (status == TRX_STATUS_TRXOFF) ? up_udelay(RF23X_TIME_TRXOFF_TO_PLL) : - up_udelay(RF23X_TIME_TRANSITION_PLL_ACTIVE); - } + (status == TRX_STATUS_TRXOFF) ? up_udelay(RF23X_TIME_TRXOFF_TO_PLL) : + up_udelay(RF23X_TIME_TRANSITION_PLL_ACTIVE); + } status = at86rf23x_getTRXstate(dev); - if ((status == TRX_STATUS_RXON) || (status == TRX_STATUS_PLLON)) - { - at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_RX_AACK_ON); - up_udelay(RF23X_TIME_TRANSITION_PLL_ACTIVE); - } + { + at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_RX_AACK_ON); + up_udelay(RF23X_TIME_TRANSITION_PLL_ACTIVE); + } status = at86rf23x_getregbits(dev->spi, RF23X_TRXSTATUS_STATUS); - - if(status != TRX_STATUS_RXAACKON) - { - ret = ERROR; - } + if (status != TRX_STATUS_RXAACKON) + { + ret = ERROR; + } break; case TRX_STATUS_TXARETON: - - if(status == TRX_STATUS_TXARETON) - { - break; - } + if (status == TRX_STATUS_TXARETON) + { + break; + } if (status == TRX_STATUS_TRXOFF) - { - at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_RX_ON); - up_udelay(RF23X_TIME_TRXOFF_TO_PLL); - } + { + at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_RX_ON); + up_udelay(RF23X_TIME_TRXOFF_TO_PLL); + } if ((status == TRX_STATUS_RXON) || (status == TRX_STATUS_PLLON)) - { - at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_TX_ARET_ON); - up_udelay(RF23X_TIME_TRANSITION_PLL_ACTIVE); - } + { + at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_TX_ARET_ON); + up_udelay(RF23X_TIME_TRANSITION_PLL_ACTIVE); + } else if (status == TRX_STATUS_RXAACKON) - { - at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_RX_ON); - up_udelay(RF23X_TIME_TRANSITION_PLL_ACTIVE); + { + at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_RX_ON); + up_udelay(RF23X_TIME_TRANSITION_PLL_ACTIVE); - at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_TX_ARET_ON); - up_udelay(RF23X_TIME_TRANSITION_PLL_ACTIVE); - } + at86rf23x_setregbits(dev->spi, RF23X_TRXCMD_STATE, TRX_CMD_TX_ARET_ON); + up_udelay(RF23X_TIME_TRANSITION_PLL_ACTIVE); + } status = at86rf23x_getregbits(dev->spi, RF23X_TRXSTATUS_STATUS); - - if(status != TRX_STATUS_TXARETON) - { - ret = ERROR; - } + if (status != TRX_STATUS_TXARETON) + { + ret = ERROR; + } break; @@ -606,20 +635,17 @@ static int at86rf23x_setTRXstate(FAR struct at86rf23x_dev_s *dev, uint8_t state, dbg("%s \n", EINVAL_STR); init_status = 0;/* Placed this here to keep compiler happy when not in debug */ return -EINVAL; - } - if(ret == ERROR) + + if (ret == ERROR) { dbg("State Transistion Error\n"); } vdbg("Radio state change state[0x%02x]->state[0x%02x]\n", init_status, status); - return ret; } -/* Publicized driver routines */ - /**************************************************************************** * Name: at86rf23x_setchannel * @@ -634,34 +660,40 @@ static int at86rf23x_setTRXstate(FAR struct at86rf23x_dev_s *dev, uint8_t state, * * ****************************************************************************/ -static int at86rf23x_setchannel(FAR struct ieee802154_radio_s *ieee, uint8_t chan) + +static int at86rf23x_setchannel(FAR struct ieee802154_radio_s *ieee, + uint8_t chan) { FAR struct at86rf23x_dev_s *dev = (FAR struct at86rf23x_dev_s *)ieee; uint8_t state; /* Validate if chan is a valid channel */ - if(chan<11 || chan>26) + + if (chan < 11 || chan > 26) { dbg("Invalid requested chan: %d\n",chan); return -EINVAL; } /* Validate we are in an acceptable mode to change the channel */ - state = at86rf23x_getTRXstate(dev); - if((TRX_STATUS_SLEEP == state) || (TRX_STATUS_PON == state)) { - dbg("Radio in invalid mode [%02x] to set the channel\n", state); - return ERROR; - } + state = at86rf23x_getTRXstate(dev); + + if ((TRX_STATUS_SLEEP == state) || (TRX_STATUS_PON == state)) + { + dbg("Radio in invalid mode [%02x] to set the channel\n", state); + return ERROR; + } + /* Set the Channel on the transceiver */ at86rf23x_setregbits(dev->spi, RF23X_CCA_BITS_CHANNEL, chan); /* Set the channel within local device */ + dev->channel = chan; vdbg("CHANNEL Changed to %d\n", chan); - return OK; } @@ -681,16 +713,19 @@ static int at86rf23x_setchannel(FAR struct ieee802154_radio_s *ieee, uint8_t cha * * ****************************************************************************/ -static int at86rf23x_getchannel(FAR struct ieee802154_radio_s *ieee, FAR uint8_t *chan) + +static int at86rf23x_getchannel(FAR struct ieee802154_radio_s *ieee, + FAR uint8_t *chan) { FAR struct at86rf23x_dev_s *dev = (FAR struct at86rf23x_dev_s *)ieee; /* Set the Channel on the transceiver */ + *chan = at86rf23x_getregbits(dev->spi, RF23X_CCA_BITS_CHANNEL); /* Set the channel within local device */ - dev->channel = *chan; + dev->channel = *chan; return OK; } @@ -701,7 +736,9 @@ static int at86rf23x_getchannel(FAR struct ieee802154_radio_s *ieee, FAR uint8_t * Define the PAN ID for the network. * ****************************************************************************/ -static int at86rf23x_setpanid(FAR struct ieee802154_radio_s *ieee, uint16_t panid) + +static int at86rf23x_setpanid(FAR struct ieee802154_radio_s *ieee, + uint16_t panid) { FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; uint8_t *pan = (uint8_t *)&panid; @@ -719,14 +756,17 @@ static int at86rf23x_setpanid(FAR struct ieee802154_radio_s *ieee, uint16_t pani * Define the PAN ID for the network. * ****************************************************************************/ -static int at86rf23x_getpanid(FAR struct ieee802154_radio_s *ieee, FAR uint16_t *panid) + +static int at86rf23x_getpanid(FAR struct ieee802154_radio_s *ieee, + FAR uint16_t *panid) { FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; uint8_t *pan = (uint8_t *)panid; + /* TODO: Check if we need to pay attention to endianness */ + pan[0] = at86rf23x_getreg(dev->spi, RF23X_REG_PANID0); pan[1] = at86rf23x_getreg(dev->spi, RF23X_REG_PANID1); - return OK; } @@ -737,7 +777,9 @@ static int at86rf23x_getpanid(FAR struct ieee802154_radio_s *ieee, FAR uint16_t * Define the Short Address for the device. * ****************************************************************************/ -static int at86rf23x_setsaddr(FAR struct ieee802154_radio_s *ieee, uint16_t saddr) + +static int at86rf23x_setsaddr(FAR struct ieee802154_radio_s *ieee, + uint16_t saddr) { FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; uint8_t *addr = (uint8_t *)&saddr; @@ -755,11 +797,15 @@ static int at86rf23x_setsaddr(FAR struct ieee802154_radio_s *ieee, uint16_t sadd * Get the short address of the device. * ****************************************************************************/ -static int at86rf23x_getsaddr(FAR struct ieee802154_radio_s *ieee, FAR uint16_t *saddr) + +static int at86rf23x_getsaddr(FAR struct ieee802154_radio_s *ieee, + FAR uint16_t *saddr) { FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; uint8_t *addr = (uint8_t *)saddr; + /* TODO: Check if we need to pay attention to endianness */ + addr[0] = at86rf23x_getreg(dev->spi, RF23X_REG_SADDR0); addr[1] = at86rf23x_getreg(dev->spi, RF23X_REG_SADDR1); @@ -773,10 +819,14 @@ static int at86rf23x_getsaddr(FAR struct ieee802154_radio_s *ieee, FAR uint16_t * Set the IEEE address of the device. * ****************************************************************************/ -static int at86rf23x_seteaddr(FAR struct ieee802154_radio_s *ieee, FAR uint8_t *eaddr) + +static int at86rf23x_seteaddr(FAR struct ieee802154_radio_s *ieee, + FAR uint8_t *eaddr) { FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; + /* TODO: Check if we need to pay attention to endianness */ + at86rf23x_setreg(dev->spi, RF23X_REG_IEEEADDR0, eaddr[0]); at86rf23x_setreg(dev->spi, RF23X_REG_IEEEADDR1, eaddr[1]); at86rf23x_setreg(dev->spi, RF23X_REG_IEEEADDR2, eaddr[2]); @@ -796,10 +846,14 @@ static int at86rf23x_seteaddr(FAR struct ieee802154_radio_s *ieee, FAR uint8_t * * Get the IEEE address of the device. * ****************************************************************************/ -static int at86rf23x_geteaddr(FAR struct ieee802154_radio_s *ieee, FAR uint8_t *eaddr) + +static int at86rf23x_geteaddr(FAR struct ieee802154_radio_s *ieee, + FAR uint8_t *eaddr) { FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; + /* TODO: Check if we need to pay attention to endianness */ + eaddr[0] = at86rf23x_getreg(dev->spi, RF23X_REG_IEEEADDR0); eaddr[1] = at86rf23x_getreg(dev->spi, RF23X_REG_IEEEADDR1); eaddr[2] = at86rf23x_getreg(dev->spi, RF23X_REG_IEEEADDR2); @@ -819,16 +873,18 @@ static int at86rf23x_geteaddr(FAR struct ieee802154_radio_s *ieee, FAR uint8_t * * enable/disable promiscuous mode. * ****************************************************************************/ -static int at86rf23x_setpromisc(FAR struct ieee802154_radio_s *ieee, bool promisc) + +static int at86rf23x_setpromisc(FAR struct ieee802154_radio_s *ieee, + bool promisc) { FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; /* TODO: Check what mode I should be in to activate promiscuous mode: * This is way to simple of an implementation. Many other things should be set * and/or checked before we set the device into promiscuous mode - * */ - at86rf23x_setregbits(dev->spi, RF23X_XAHCTRL1_BITS_PROM_MODE, promisc); + */ + at86rf23x_setregbits(dev->spi, RF23X_XAHCTRL1_BITS_PROM_MODE, promisc); return OK; } @@ -839,12 +895,13 @@ static int at86rf23x_setpromisc(FAR struct ieee802154_radio_s *ieee, bool promis * Check if the device is in promiscuous mode. * ****************************************************************************/ -static int at86rf23x_getpromisc(FAR struct ieee802154_radio_s *ieee, FAR bool *promisc) + +static int at86rf23x_getpromisc(FAR struct ieee802154_radio_s *ieee, + FAR bool *promisc) { FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; *promisc = at86rf23x_getregbits(dev->spi, RF23X_XAHCTRL1_BITS_PROM_MODE); - return OK; } @@ -855,31 +912,33 @@ static int at86rf23x_getpromisc(FAR struct ieee802154_radio_s *ieee, FAR bool *p * Check if the device is in promiscuous mode. * ****************************************************************************/ -static int at86rf23x_setdevmode(FAR struct ieee802154_radio_s *ieee, uint8_t mode) + +static int at86rf23x_setdevmode(FAR struct ieee802154_radio_s *ieee, + uint8_t mode) { FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; - /* define dev mode */ - if(mode == IEEE802154_MODE_PANCOORD) - { - at86rf23x_setregbits(dev->spi, RF23X_CSMASEED1_IAMCOORD_BITS, 0x01); - } - else if(mode == IEEE802154_MODE_COORD) - { - /* ????? */ - } - else if(mode == IEEE802154_MODE_DEVICE) - { - at86rf23x_setregbits(dev->spi, RF23X_CSMASEED1_IAMCOORD_BITS, 0x00); - } - else - { - return -EINVAL; - } + /* Define dev mode */ - dev->devmode = mode; + if (mode == IEEE802154_MODE_PANCOORD) + { + at86rf23x_setregbits(dev->spi, RF23X_CSMASEED1_IAMCOORD_BITS, 0x01); + } + else if (mode == IEEE802154_MODE_COORD) + { + /* ????? */ + } + else if (mode == IEEE802154_MODE_DEVICE) + { + at86rf23x_setregbits(dev->spi, RF23X_CSMASEED1_IAMCOORD_BITS, 0x00); + } + else + { + return -EINVAL; + } - return OK; + dev->devmode = mode; + return OK; } /**************************************************************************** @@ -889,14 +948,15 @@ static int at86rf23x_setdevmode(FAR struct ieee802154_radio_s *ieee, uint8_t mod * get the device mode type of the radio. * ****************************************************************************/ -static int at86rf23x_getdevmode (FAR struct ieee802154_radio_s *ieee, FAR uint8_t *mode) + +static int at86rf23x_getdevmode(FAR struct ieee802154_radio_s *ieee, + FAR uint8_t *mode) { FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; int val; val = at86rf23x_getregbits(dev->spi, RF23X_CSMASEED1_IAMCOORD_BITS); - - if(val == 1) + if (val == 1) { *mode = IEEE802154_MODE_PANCOORD; } @@ -915,15 +975,17 @@ static int at86rf23x_getdevmode (FAR struct ieee802154_radio_s *ieee, FAR uint8 * set the tx power attenuation or amplification * ****************************************************************************/ -static int at86rf23x_settxpower(FAR struct ieee802154_radio_s *ieee, int32_t txpwr) + +static int at86rf23x_settxpower(FAR struct ieee802154_radio_s *ieee, + int32_t txpwr) { FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; /* TODO: this needs alot of work to make sure all chips can share this function */ /* Right now we only set tx power to 0 */ - at86rf23x_setreg(dev->spi, RF23X_REG_TXPWR, RF23X_TXPWR_0); + at86rf23x_setreg(dev->spi, RF23X_REG_TXPWR, RF23X_TXPWR_0); return OK; } @@ -934,67 +996,86 @@ static int at86rf23x_settxpower(FAR struct ieee802154_radio_s *ieee, int32_t txp * get the tx power attenuation or amplification. * ****************************************************************************/ -static int at86rf23x_gettxpower(FAR struct ieee802154_radio_s *ieee, FAR int32_t *txpwr) + +static int at86rf23x_gettxpower(FAR struct ieee802154_radio_s *ieee, + FAR int32_t *txpwr) { - /* TODO: this needs alot of work to make sure all chips can share this function */ FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; uint8_t reg; - /* TODO: this needs alot of work to make sure all chips can share this function */ + + /* TODO: this needs alot of work to make sure all chips can share this + * function. + */ /* Right now we only get negative values */ + reg = at86rf23x_getreg(dev->spi, RF23X_REG_TXPWR); + switch (reg) + { + case RF23X_TXPWR_POS_4: + *txpwr = 0; + break; + + case RF23X_TXPWR_POS_3_7: + *txpwr = 0; + break; + + case RF23X_TXPWR_POS_3_4: + *txpwr = 0; + break; + + case RF23X_TXPWR_POS_3: + *txpwr = 0; + break; + + case RF23X_TXPWR_POS_2_5: + *txpwr = 0; + break; + + case RF23X_TXPWR_POS_2: + *txpwr = 0; + break; + + case RF23X_TXPWR_POS_1: + *txpwr = 0; + break; + + case RF23X_TXPWR_0: + *txpwr = 0; + break; + + case RF23X_TXPWR_NEG_1: + *txpwr = 1000; + break; + + case RF23X_TXPWR_NEG_2: + *txpwr = 2000; + break; - switch(reg) - { - case RF23X_TXPWR_POS_4: - *txpwr = 0; - break; - case RF23X_TXPWR_POS_3_7: - *txpwr = 0; - break; - case RF23X_TXPWR_POS_3_4: - *txpwr = 0; - break; - case RF23X_TXPWR_POS_3: - *txpwr = 0; - break; - case RF23X_TXPWR_POS_2_5: - *txpwr = 0; - break; - case RF23X_TXPWR_POS_2: - *txpwr = 0; - break; - case RF23X_TXPWR_POS_1: - *txpwr = 0; - break; - case RF23X_TXPWR_0: - *txpwr = 0; - break; - case RF23X_TXPWR_NEG_1: - *txpwr = 1000; - break; - case RF23X_TXPWR_NEG_2: - *txpwr = 2000; - break; - case RF23X_TXPWR_NEG_3: - *txpwr = 3000; - break; - case RF23X_TXPWR_NEG_4: - *txpwr = 4000; - break; - case RF23X_TXPWR_NEG_6: - *txpwr = 6000; - break; - case RF23X_TXPWR_NEG_8: - *txpwr = 8000; - break; - case RF23X_TXPWR_NEG_12: - *txpwr = 12000; - break; - case RF23X_TXPWR_NEG_17: - *txpwr = 17000; - break; - } + case RF23X_TXPWR_NEG_3: + *txpwr = 3000; + break; + + case RF23X_TXPWR_NEG_4: + *txpwr = 4000; + break; + + case RF23X_TXPWR_NEG_6: + *txpwr = 6000; + break; + + case RF23X_TXPWR_NEG_8: + *txpwr = 8000; + break; + + case RF23X_TXPWR_NEG_12: + *txpwr = 12000; + break; + + case RF23X_TXPWR_NEG_17: + *txpwr = 17000; + break; + } return OK; } @@ -1008,7 +1089,9 @@ static int at86rf23x_gettxpower(FAR struct ieee802154_radio_s *ieee, FAR int32_t * * ****************************************************************************/ -static int at86rf23x_setcca(FAR struct ieee802154_radio_s *ieee, FAR struct ieee802154_cca_s *cca) + +static int at86rf23x_setcca(FAR struct ieee802154_radio_s *ieee, + FAR struct ieee802154_cca_s *cca) { FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; @@ -1018,6 +1101,7 @@ static int at86rf23x_setcca(FAR struct ieee802154_radio_s *ieee, FAR struct ieee { return -EINVAL; } + if (cca->use_cs && cca->csth > 0x0f) { return -EINVAL; @@ -1025,15 +1109,15 @@ static int at86rf23x_setcca(FAR struct ieee802154_radio_s *ieee, FAR struct ieee if (cca->use_ed) { - at86rf23x_setregbits(dev->spi, RF23X_CCA_BITS_MODE, RF23X_CCA_MODE_ED); + at86rf23x_setregbits(dev->spi, RF23X_CCA_BITS_MODE, RF23X_CCA_MODE_ED); } + if (cca->use_cs) { - at86rf23x_setregbits(dev->spi, RF23X_CCA_BITS_MODE, RF23X_CCA_MODE_CS); + at86rf23x_setregbits(dev->spi, RF23X_CCA_BITS_MODE, RF23X_CCA_MODE_CS); } memcpy(&dev->cca, cca, sizeof(struct ieee802154_cca_s)); - return OK; } @@ -1044,7 +1128,9 @@ static int at86rf23x_setcca(FAR struct ieee802154_radio_s *ieee, FAR struct ieee * Get CCA for ???: TODO: need to implement * ****************************************************************************/ -static int at86rf23x_getcca(FAR struct ieee802154_radio_s *ieee, FAR struct ieee802154_cca_s *cca) + +static int at86rf23x_getcca(FAR struct ieee802154_radio_s *ieee, + FAR struct ieee802154_cca_s *cca) { FAR struct at86rf23x_dev_s *dev = (struct at86rf23x_dev_s *)ieee; @@ -1063,15 +1149,22 @@ static int at86rf23x_getcca(FAR struct ieee802154_radio_s *ieee, FAR struct ieee * Control operations for the radio. * ****************************************************************************/ -static int at86rf23x_ioctl(FAR struct ieee802154_radio_s *ieee, int cmd, unsigned long arg) + +static int at86rf23x_ioctl(FAR struct ieee802154_radio_s *ieee, int cmd, + unsigned long arg) { FAR struct at86rf23x_dev_s *dev = (FAR struct at86rf23x_dev_s *)ieee; - switch(cmd) + + switch (cmd) { - case 1000: return at86rf23x_regdump(dev); - default: return -EINVAL; + case 1000: + return at86rf23x_regdump(dev); + + default: + return -ENOTTY; } } + /**************************************************************************** * Name: at86rf23x_energydetect * @@ -1079,9 +1172,9 @@ static int at86rf23x_ioctl(FAR struct ieee802154_radio_s *ieee, int cmd, unsigne * Perform energy detection scan. TODO: Need to implement. * ****************************************************************************/ -static int at86rf23x_energydetect(FAR struct ieee802154_radio_s *ieee, FAR uint8_t *energy) +static int at86rf23x_energydetect(FAR struct ieee802154_radio_s *ieee, + FAR uint8_t *energy) { - #warning at86rf23x_energydetect not implemented. /* Not yet implemented */ @@ -1096,19 +1189,19 @@ static int at86rf23x_energydetect(FAR struct ieee802154_radio_s *ieee, FAR uint8 * Initialize the radio. * ****************************************************************************/ + int at86rf23x_initialize(FAR struct at86rf23x_dev_s *dev) { - uint8_t part; - uint8_t version; + uint8_t part; + uint8_t version; - at86rf23x_resetrf(dev); + at86rf23x_resetrf(dev); - part = at86rf23x_getreg(dev->spi, RF23X_REG_PART); - version = at86rf23x_getreg(dev->spi, RF23X_REG_VERSION); + part = at86rf23x_getreg(dev->spi, RF23X_REG_PART); + version = at86rf23x_getreg(dev->spi, RF23X_REG_VERSION); - dbg("Radio part: 0x%02x version: 0x%02x found\n", part, version); - - return OK; + dbg("Radio part: 0x%02x version: 0x%02x found\n", part, version); + return OK; } /**************************************************************************** @@ -1119,34 +1212,37 @@ int at86rf23x_initialize(FAR struct at86rf23x_dev_s *dev) * TRX_OFF state. * ****************************************************************************/ + static int at86rf23x_resetrf(FAR struct at86rf23x_dev_s *dev) { FAR const struct at86rf23x_lower_s *lower = dev->lower; uint8_t trx_status, retry_cnt = 0; /* Reset the radio */ + lower->reset(lower, 0); lower->slptr(lower, 0); up_udelay(RF23X_TIME_RESET); lower->reset(lower, 1); - /* Dummy read of IRQ register */ + at86rf23x_getreg(dev->spi, RF23X_REG_IRQ_STATUS); do - { - trx_status = at86rf23x_setTRXstate(dev, TRX_CMD_TRXOFF, true); - - if (retry_cnt == RF23X_MAX_RETRY_RESET_TO_TRX_OFF) { - dbg("Reset of transceiver failed\n"); - return ERROR; - } + trx_status = at86rf23x_setTRXstate(dev, TRX_CMD_TRXOFF, true); - retry_cnt++; - } while (trx_status != OK); + if (retry_cnt == RF23X_MAX_RETRY_RESET_TO_TRX_OFF) + { + dbg("Reset of transceiver failed\n"); + return ERROR; + } + + retry_cnt++; + } + while (trx_status != OK); return OK; } @@ -1159,12 +1255,14 @@ static int at86rf23x_resetrf(FAR struct at86rf23x_dev_s *dev) * RX messages. * ****************************************************************************/ + static int at86rf23x_rxenable(FAR struct ieee802154_radio_s *ieee, bool state, - FAR struct ieee802154_packet_s *packet) + FAR struct ieee802154_packet_s *packet) { FAR struct at86rf23x_dev_s *dev = (FAR struct at86rf23x_dev_s *)ieee; /* Set the radio to the receive state */ + return at86rf23x_setTRXstate(dev, TRX_CMD_RX_ON, false); /* Enable the RX IRQ */ @@ -1176,6 +1274,7 @@ static int at86rf23x_rxenable(FAR struct ieee802154_radio_s *ieee, bool state, */ /* Set buffer to receive next packet */ + ieee->rxbuf = packet; } @@ -1186,11 +1285,12 @@ static int at86rf23x_rxenable(FAR struct ieee802154_radio_s *ieee, bool state, * Actual interrupt handler ran inside privileged space. * ****************************************************************************/ + static int at86rf23x_interrupt(int irq, FAR void *context) { - - /* To support multiple devices, - * retrieve the priv structure using the irq number */ + /* To support multiple devices, retrieve the priv structure using the irq + * number. + */ register FAR struct at86rf23x_dev_s *dev = &g_at86rf23x_devices[0]; @@ -1207,10 +1307,12 @@ static int at86rf23x_interrupt(int irq, FAR void *context) * actually performed. This is to prevent overrun of the worker thread. * Interrupts are re-enabled in enc_irqworker() when the work is completed. */ + dev->lower->irq(dev->lower, NULL, FALSE); - // dev->lower->enable(dev->lower, FALSE); + //dev->lower->enable(dev->lower, FALSE); - return work_queue(HPWORK, &dev->irqwork, at86rf23x_irqworker, (FAR void *)dev, 0); + return work_queue(HPWORK, &dev->irqwork, at86rf23x_irqworker, + (FAR void *)dev, 0); } /**************************************************************************** @@ -1222,31 +1324,35 @@ static int at86rf23x_interrupt(int irq, FAR void *context) * them out. * ****************************************************************************/ + static int at86rf23x_regdump(FAR struct at86rf23x_dev_s *dev) { uint32_t i; char buf[4+16*3+2+1]; - int len=0; + printf("RF23X regs:\n"); for (i=0;i<0x30;i++) { - /* First row and every 15 regs */ + /* First row and every 15 regs */ + if ((i & 0x0f) == 0) - { - len = sprintf(buf, "%02x: ",i&0xFF); - } + { + len = sprintf(buf, "%02x: ",i&0xFF); + } + + /* Print the register value */ - /* print the register value */ len += sprintf(buf+len, "%02x ", at86rf23x_getreg(dev->spi, i)); - /* at the end of each 15 regs or end of rf233s regs and actually print dbg message*/ + /* At the end of each 15 regs or end of rf233s regs and actually print dbg message*/ + if ((i&15)==15 || i == 0x2f) - { - sprintf(buf+len, "\n"); - printf("%s",buf); - } + { + sprintf(buf+len, "\n"); + printf("%s",buf); + } } /* TODO: I have a few more regs that are not consecutive. Will print later */ @@ -1261,30 +1367,33 @@ static int at86rf23x_regdump(FAR struct at86rf23x_dev_s *dev) * Actual thread to handle the irq outside of privaleged mode. * ****************************************************************************/ + static void at86rf23x_irqworker(FAR void *arg) { FAR struct at86rf23x_dev_s *dev = (FAR struct at86rf23x_dev_s *)arg; - uint8_t irq_status = at86rf23x_getreg(dev->spi, RF23X_REG_IRQ_STATUS); vdbg("IRQ: 0x%02X\n", irq_status); - if((irq_status & (1<<3)) != 0) + if ((irq_status & (1<<3)) != 0) { - if((irq_status & (1<<2)) != 0) - { - at86rf23x_irqwork_rx(dev); - } + if ((irq_status & (1<<2)) != 0) + { + at86rf23x_irqwork_rx(dev); + } else - { - at86rf23x_irqwork_tx(dev); - } + { + at86rf23x_irqwork_tx(dev); + } } else { dbg("Unknown IRQ Status: %d\n", irq_status); - /* Re enable the IRQ even if we don't know how to handle previous status*/ + /* Re enable the IRQ even if we don't know how to handle previous + * status. + */ + dev->lower->irq(dev->lower, NULL, true); } } @@ -1296,6 +1405,7 @@ static void at86rf23x_irqworker(FAR void *arg) * Misc/unofficial device controls. * ****************************************************************************/ + static void at86rf23x_irqwork_rx(FAR struct at86rf23x_dev_s *dev) { uint8_t rx_len; @@ -1309,13 +1419,14 @@ static void at86rf23x_irqwork_rx(FAR struct at86rf23x_dev_s *dev) dev->ieee.rxbuf->rssi = 0; sem_post(&dev->ieee.rxsem); - /* - * TODO: - * Not to sure yet what I should do here. I will something - * soon. + + /* TODO: + * Not to sure yet what I should do here. I will something + * soon. */ /* Re enable the IRQ */ + dev->lower->irq(dev->lower, NULL, true); } @@ -1326,23 +1437,21 @@ static void at86rf23x_irqwork_rx(FAR struct at86rf23x_dev_s *dev) * Misc/unofficial device controls. * ****************************************************************************/ + static void at86rf23x_irqwork_tx(FAR struct at86rf23x_dev_s *dev) { vdbg("6LOWPAN:Tx IRQ\n"); - /* - * TODO: - * There needs to be more here but for now just alert the waiting - * thread. Maybe put it back into Rx mode - * + /* TODO: + * There needs to be more here but for now just alert the waiting + * thread. Maybe put it back into Rx mode */ /* Re enable the IRQ */ + dev->lower->irq(dev->lower, NULL, true); sem_post(&dev->ieee.txsem); - - } /**************************************************************************** @@ -1354,30 +1463,37 @@ static void at86rf23x_irqwork_tx(FAR struct at86rf23x_dev_s *dev) * transmission * ****************************************************************************/ -static int at86rf23x_transmit(FAR struct ieee802154_radio_s *ieee, FAR struct ieee802154_packet_s *packet) + +static int at86rf23x_transmit(FAR struct ieee802154_radio_s *ieee, + FAR struct ieee802154_packet_s *packet) { FAR struct at86rf23x_dev_s *dev = (FAR struct at86rf23x_dev_s *)ieee; - /* - * TODO: - * A plan needs to be made on when we declare the transmission successful. - * 1. If the packet is sent - * 2. If we receive an ACK. - * 3. Where do we control the retry process? + + /* TODO: + * A plan needs to be made on when we declare the transmission successful. + * 1. If the packet is sent + * 2. If we receive an ACK. + * 3. Where do we control the retry process? */ - if(at86rf23x_setTRXstate(dev, TRX_CMD_PLL_ON, false)) - { + if (at86rf23x_setTRXstate(dev, TRX_CMD_PLL_ON, false)) + { at86rf23x_writeframe(dev->spi, packet->data, packet->len); - } + } else - { + { dbg("Transmit could not put the radio in a Tx state\n"); return ERROR; - } + } + + /* Put the thread that requested transfer to a waiting state */ - /* put the thread that requested transfer to a waiting state */ sem_wait(&dev->ieee.txsem); - /*TODO Verify that I want to stay in the PLL state or if I want to roll back to RX_ON */ + + /* TODO Verify that I want to stay in the PLL state or if I want to roll + * back to RX_ON. + */ + return OK; } @@ -1393,18 +1509,22 @@ static int at86rf23x_transmit(FAR struct ieee802154_radio_s *ieee, FAR struct ie * ****************************************************************************/ -FAR struct ieee802154_radio_s *at86rf23x_init(FAR struct spi_dev_s *spi, FAR const struct at86rf23x_lower_s *lower) +FAR struct ieee802154_radio_s *at86rf23x_init(FAR struct spi_dev_s *spi, + FAR const struct at86rf23x_lower_s *lower) { FAR struct at86rf23x_dev_s *dev; struct ieee802154_cca_s cca; dev = &g_at86rf23x_devices[0]; + /* Attach the interface, lower driver, and devops */ + dev->spi = spi; dev->lower = lower; dev->ieee.ops = &at86rf23x_devops; - /* attach irq */ + /* Attach irq */ + if (lower->irq(lower, at86rf23x_interrupt, false) != OK) { return NULL; @@ -1413,65 +1533,68 @@ FAR struct ieee802154_radio_s *at86rf23x_init(FAR struct spi_dev_s *spi, FAR con sem_init(&dev->ieee.rxsem, 0, 0); sem_init(&dev->ieee.txsem, 0, 0); - /*Initialize device */ + /* Initialize device */ + at86rf23x_initialize(dev); /* Configure the desired IRQs of the devices */ + at86rf23x_setreg(dev->spi, RF23X_REG_IRQ_MASK, RF23X_IRQ_MASK_DEFAULT); /* Turn the PLL to the on state */ - at86rf23x_setTRXstate(dev, TRX_CMD_PLL_ON, false); + at86rf23x_setTRXstate(dev, TRX_CMD_PLL_ON, false); - /*SEED value of the CSMA backoff algorithm. */ - + /* SEED value of the CSMA backoff algorithm. */ #ifdef RF23X_ANTENNA_DIVERSITY + /* Use antenna diversity */ - /* Use antenna diversity */ - trx_bit_write(SR_ANT_CTRL, ANTENNA_DEFAULT); - trx_bit_write(SR_PDT_THRES, THRES_ANT_DIV_ENABLE); - trx_bit_write(SR_ANT_DIV_EN, ANT_DIV_ENABLE); - trx_bit_write(SR_ANT_EXT_SW_EN, ANT_EXT_SW_ENABLE); - + trx_bit_write(SR_ANT_CTRL, ANTENNA_DEFAULT); + trx_bit_write(SR_PDT_THRES, THRES_ANT_DIV_ENABLE); + trx_bit_write(SR_ANT_DIV_EN, ANT_DIV_ENABLE); + trx_bit_write(SR_ANT_EXT_SW_EN, ANT_EXT_SW_ENABLE); #endif #ifdef RF23X_TIMESTAMP - - /* Enable timestamp init code goes here */ + /* Enable timestamp init code goes here */ #endif #ifdef RF23X_RF_FRONTEND_CTRL - - /* Init front end control code goes here */ + /* Init front end control code goes here */ #endif + /* Set the channel of the radio */ + at86rf23x_setchannel(&dev->ieee, 12); /* Configure the Pan id */ - // at86rf23x_setpanid (&dev->ieee, IEEE802154_PAN_DEFAULT); + + //at86rf23x_setpanid (&dev->ieee, IEEE802154_PAN_DEFAULT); + /* Configure the Short Addr */ - // at86rf23x_setsaddr (&dev->ieee, IEEE802154_SADDR_UNSPEC); + + //at86rf23x_setsaddr (&dev->ieee, IEEE802154_SADDR_UNSPEC); + /* Configure the IEEE Addr */ -// at86rf23x_seteaddr (&dev->ieee, IEEE802154_EADDR_UNSPEC); + + //at86rf23x_seteaddr (&dev->ieee, IEEE802154_EADDR_UNSPEC); /* Default device params at86rf23x defaults to energy detect only */ + cca.use_ed = 1; cca.use_cs = 0; - cca.edth = 0x60; /* CCA mode ED, no carrier sense, recommenced ED threshold -69 dBm */ + cca.edth = 0x60; /* CCA mode ED, no carrier sense, recommenced ED + * threshold -69 dBm */ at86rf23x_setcca(&dev->ieee, &cca); - - /* Put the Device to RX ON Mode */ - // at86rf23x_setTRXstate(dev, TRX_CMD_RX_ON, false ); - + //at86rf23x_setTRXstate(dev, TRX_CMD_RX_ON, false); /* Enable Radio IRQ */ - lower->irq(lower, at86rf23x_interrupt, true); + lower->irq(lower, at86rf23x_interrupt, true); return &dev->ieee; } - diff --git a/wireless/ieee802154/ieee802154_device.c b/wireless/ieee802154/ieee802154_device.c index f1413b31cf..792b37ed8d 100644 --- a/wireless/ieee802154/ieee802154_device.c +++ b/wireless/ieee802154/ieee802154_device.c @@ -353,7 +353,7 @@ static ssize_t ieee802154dev_write(FAR struct file *filep, if (sem_timedwait(&dev->child->txsem, &timeout)) { - dbg("Radio Device timedout on Tx\n"); + _err("Radio Device timedout on Tx\n"); } done: -- GitLab From 5a6c95fddf4ff283dc656c20b96a30d737b7ffd2 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Wed, 15 Mar 2017 16:18:38 -0400 Subject: [PATCH 051/990] wireless/ieee802154: Renamed file ieee802154_device to radio802154_device --- wireless/ieee802154/{ieee802154_device.c => radio802154_device.c} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename wireless/ieee802154/{ieee802154_device.c => radio802154_device.c} (100%) diff --git a/wireless/ieee802154/ieee802154_device.c b/wireless/ieee802154/radio802154_device.c similarity index 100% rename from wireless/ieee802154/ieee802154_device.c rename to wireless/ieee802154/radio802154_device.c -- GitLab From 57a1360c847734ce54a87b3f43dc79bc36896f47 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 15 Mar 2017 14:30:24 -0600 Subject: [PATCH 052/990] Add option to enable wireless debug output. --- Kconfig | 32 +++++++++++++++++++ drivers/wireless/nrf24l01.c | 52 +++++++++++++++---------------- include/debug.h | 44 ++++++++++++++++++++++++++ include/nuttx/wireless/nrf24l01.h | 17 +--------- 4 files changed, 103 insertions(+), 42 deletions(-) diff --git a/Kconfig b/Kconfig index 4d7949d4e3..bbff98b262 100644 --- a/Kconfig +++ b/Kconfig @@ -732,6 +732,38 @@ config DEBUG_NET_INFO endif # DEBUG_NET +config DEBUG_WIRELESS + bool "Wireless Debug Features" + default n + depends on WIRELESS | DRIVERS_WIRELESS + ---help--- + Enable DEBUG_WIRELESS debug features. + +if DEBUG_WIRELESS + +config DEBUG_WIRELESS_ERROR + bool "Wireless Error Output" + default n + depends on DEBUG_ERROR + ---help--- + Enable wireless error output to SYSLOG. + +config DEBUG_WIRELESS_WARN + bool "Wireless Warnings Output" + default n + depends on DEBUG_WARN + ---help--- + Enable wireless warning output to SYSLOG. + +config DEBUG_WIRELESS_INFO + bool "Wireless Informational Output" + default n + depends on DEBUG_INFO + ---help--- + Enable wireless informational output to SYSLOG. + +endif # DEBUG_WIRELESS + config DEBUG_SCHED bool "Scheduler Debug Features" default n diff --git a/drivers/wireless/nrf24l01.c b/drivers/wireless/nrf24l01.c index c3ed88d17a..ae0d29b483 100644 --- a/drivers/wireless/nrf24l01.c +++ b/drivers/wireless/nrf24l01.c @@ -221,7 +221,7 @@ static uint8_t fifoget(struct nrf24l01_dev_s *dev, FAR uint8_t *buffer, static void nrf24l01_worker(FAR void *arg); #endif -#ifdef NRF24L01_DEBUG +#ifdef CONFIG_DEBUG_WIRELESS static void binarycvt(char *deststr, const uint8_t *srcbin, size_t srclen) #endif @@ -595,7 +595,7 @@ static int nrf24l01_irqhandler(int irq, FAR void *context, FAR void *arg) { FAR struct nrf24l01_dev_s *dev = (FAR struct nrf24l01_dev_s *)arg; - winfo("*IRQ*\n"); + wlinfo("*IRQ*\n"); #ifdef CONFIG_WL_NRF24L01_RXSUPPORT /* If RX is enabled we delegate the actual work to bottom-half handler */ @@ -667,7 +667,7 @@ static void nrf24l01_worker(FAR void *arg) bool has_data = false; #endif - winfo("RX_DR is set!\n"); + wlinfo("RX_DR is set!\n"); /* Read and store all received payloads */ @@ -686,7 +686,7 @@ static void nrf24l01_worker(FAR void *arg) pipeno = (status & NRF24L01_RX_P_NO_MASK) >> NRF24L01_RX_P_NO_SHIFT; if (pipeno >= NRF24L01_PIPE_COUNT) /* 6=invalid 7=fifo empty */ { - werr("invalid pipe rx: %d\n", (int)pipeno); + wlerr("invalid pipe rx: %d\n", (int)pipeno); nrf24l01_flush_rx(dev); break; } @@ -703,7 +703,7 @@ static void nrf24l01_worker(FAR void *arg) if (pktlen > NRF24L01_MAX_PAYLOAD_LEN) /* bad length */ { - werr("invalid length in rx: %d\n", (int)pktlen); + wlerr("invalid length in rx: %d\n", (int)pktlen); nrf24l01_flush_rx(dev); break; } @@ -720,8 +720,8 @@ static void nrf24l01_worker(FAR void *arg) status = nrf24l01_readreg(dev, NRF24L01_FIFO_STATUS, &fifo_status, 1); - winfo("FIFO_STATUS=%02x\n", fifo_status); - winfo("STATUS=%02x\n", status); + wlinfo("FIFO_STATUS=%02x\n", fifo_status); + wlinfo("STATUS=%02x\n", status); } while ((fifo_status & NRF24L01_RX_EMPTY) == 0); @@ -730,7 +730,7 @@ static void nrf24l01_worker(FAR void *arg) { dev->pfd->revents |= POLLIN; /* Data available for input */ - winfo("Wake up polled fd\n"); + wlinfo("Wake up polled fd\n"); sem_post(dev->pfd->sem); } #endif @@ -758,7 +758,7 @@ static void nrf24l01_worker(FAR void *arg) } else { - werr("invalid length in rx: %d\n", (int)pktlen); + wlerr("invalid length in rx: %d\n", (int)pktlen); } } @@ -874,7 +874,7 @@ static int dosend(FAR struct nrf24l01_dev_s *dev, FAR const uint8_t *data, if (result < 0) { - werr("wait for irq failed\n"); + wlerr("wait for irq failed\n"); nrf24l01_flush_tx(dev); goto out; } @@ -888,11 +888,11 @@ static int dosend(FAR struct nrf24l01_dev_s *dev, FAR const uint8_t *data, dev->lastxmitcount = (obsvalue & NRF24L01_ARC_CNT_MASK) >> NRF24L01_ARC_CNT_SHIFT; - winfo("Transmission OK (lastxmitcount=%d)\n", dev->lastxmitcount); + wlinfo("Transmission OK (lastxmitcount=%d)\n", dev->lastxmitcount); } else if (status & NRF24L01_MAX_RT) { - winfo("MAX_RT! (lastxmitcount=%d)\n", dev->lastxmitcount); + wlinfo("MAX_RT! (lastxmitcount=%d)\n", dev->lastxmitcount); result = -ECOMM; dev->lastxmitcount = NRF24L01_XMIT_MAXRT; @@ -906,7 +906,7 @@ static int dosend(FAR struct nrf24l01_dev_s *dev, FAR const uint8_t *data, { /* Unexpected... */ - werr("ERROR: No TX_DS nor MAX_RT bit set in STATUS reg!\n"); + wlerr("ERROR: No TX_DS nor MAX_RT bit set in STATUS reg!\n"); result = -EIO; } @@ -930,7 +930,7 @@ out: * Name: binarycvt ****************************************************************************/ -#ifdef NRF24L01_DEBUG +#ifdef CONFIG_DEBUG_WIRELESS static void binarycvt(char *deststr, const uint8_t *srcbin, size_t srclen) { int i = 0; @@ -958,7 +958,7 @@ static int nrf24l01_open(FAR struct file *filep) FAR struct nrf24l01_dev_s *dev; int result; - winfo("Opening nRF24L01 dev\n"); + wlinfo("Opening nRF24L01 dev\n"); DEBUGASSERT(filep); inode = filep->f_inode; @@ -1004,7 +1004,7 @@ static int nrf24l01_close(FAR struct file *filep) FAR struct inode *inode; FAR struct nrf24l01_dev_s *dev; - winfo("Closing nRF24L01 dev\n"); + wlinfo("Closing nRF24L01 dev\n"); DEBUGASSERT(filep); inode = filep->f_inode; @@ -1103,7 +1103,7 @@ static int nrf24l01_ioctl(FAR struct file *filep, int cmd, unsigned long arg) FAR struct nrf24l01_dev_s *dev; int result = OK; - winfo("cmd: %d arg: %ld\n", cmd, arg); + wlinfo("cmd: %d arg: %ld\n", cmd, arg); DEBUGASSERT(filep); inode = filep->f_inode; @@ -1347,7 +1347,7 @@ static int nrf24l01_poll(FAR struct file *filep, FAR struct pollfd *fds, FAR struct nrf24l01_dev_s *dev; int result = OK; - winfo("setup: %d\n", (int)setup); + wlinfo("setup: %d\n", (int)setup); DEBUGASSERT(filep && fds); inode = filep->f_inode; @@ -1501,12 +1501,12 @@ int nrf24l01_register(FAR struct spi_dev_s *spi, /* Register the device as an input device */ - winfo("Registering " DEV_NAME "\n"); + wlinfo("Registering " DEV_NAME "\n"); result = register_driver(DEV_NAME, &nrf24l01_fops, 0666, dev); if (result < 0) { - werr("ERROR: register_driver() failed: %d\n", result); + wlerr("ERROR: register_driver() failed: %d\n", result); nrf24l01_unregister(dev); } @@ -1990,7 +1990,7 @@ int nrf24l01_sendto(FAR struct nrf24l01_dev_s *dev, FAR const uint8_t *data, if ((dev->en_aa & 1) && (memcmp(destaddr, dev->pipe0addr, dev->addrlen))) { - winfo("Change pipe #0 addr to dest addr\n"); + wlinfo("Change pipe #0 addr to dest addr\n"); nrf24l01_writereg(dev, NRF24L01_RX_ADDR_P0, destaddr, NRF24L01_MAX_ADDR_LEN); pipeaddrchg = true; @@ -2004,7 +2004,7 @@ int nrf24l01_sendto(FAR struct nrf24l01_dev_s *dev, FAR const uint8_t *data, nrf24l01_writereg(dev, NRF24L01_RX_ADDR_P0, dev->pipe0addr, NRF24L01_MAX_ADDR_LEN); - winfo("Pipe #0 default addr restored\n"); + wlinfo("Pipe #0 default addr restored\n"); } nrf24l01_unlock(dev->spi); @@ -2045,7 +2045,7 @@ ssize_t nrf24l01_recv(struct nrf24l01_dev_s *dev, uint8_t *buffer, * Name: nrf24l01_dumpregs ****************************************************************************/ -#ifdef NRF24L01_DEBUG +#ifdef CONFIG_DEBUG_WIRELESS void nrf24l01_dumpregs(struct nrf24l01_dev_s *dev) { uint8_t addr[NRF24L01_MAX_ADDR_LEN]; @@ -2097,17 +2097,17 @@ void nrf24l01_dumpregs(struct nrf24l01_dev_s *dev) syslog(LOG_INFO, "FEATURE: %02x\n", nrf24l01_readregbyte(dev, NRF24L01_FEATURE)); } -#endif /* NRF24L01_DEBUG */ +#endif /* CONFIG_DEBUG_WIRELESS */ /**************************************************************************** * Name: nrf24l01_dumprxfifo ****************************************************************************/ -#if defined(NRF24L01_DEBUG) && defined(CONFIG_WL_NRF24L01_RXSUPPORT) +#if defined(CONFIG_DEBUG_WIRELESS) && defined(CONFIG_WL_NRF24L01_RXSUPPORT) void nrf24l01_dumprxfifo(struct nrf24l01_dev_s *dev) { syslog(LOG_INFO, "bytes count: %d\n", dev->fifo_len); syslog(LOG_INFO, "next read: %d, next write: %d\n", dev->nxt_read, dev-> nxt_write); } -#endif /* NRF24L01_DEBUG && CONFIG_WL_NRF24L01_RXSUPPORT */ +#endif /* CONFIG_DEBUG_WIRELESS && CONFIG_WL_NRF24L01_RXSUPPORT */ diff --git a/include/debug.h b/include/debug.h index 0bde25605b..64352dad34 100644 --- a/include/debug.h +++ b/include/debug.h @@ -233,6 +233,24 @@ # define ninfo(x...) #endif +#ifdef CONFIG_DEBUG_WIRELESS_ERROR +# define wlerr(format, ...) _err(format, ##__VA_ARGS__) +#else +# define wlerr(x...) +#endif + +#ifdef CONFIG_DEBUG_WIRELESS_WARN +# define wlwarn(format, ...) _warn(format, ##__VA_ARGS__) +#else +# define wlwarn(x...) +#endif + +#ifdef CONFIG_DEBUG_WIRELESS_INFO +# define wlinfo(format, ...) _info(format, ##__VA_ARGS__) +#else +# define wlinfo(x...) +#endif + #ifdef CONFIG_DEBUG_FS_ERROR # define ferr(format, ...) _err(format, ##__VA_ARGS__) #else @@ -777,6 +795,24 @@ # define ninfo (void) #endif +#ifdef CONFIG_DEBUG_WIRELESS_ERROR +# define wlerr _err +#else +# define wlerr (void) +#endif + +#ifdef CONFIG_DEBUG_WIRELESS_WARN +# define wlwarn _warn +#else +# define wlwarn (void) +#endif + +#ifdef CONFIG_DEBUG_WIRELESS_INFO +# define wlinfo _info +#else +# define wlinfo (void) +#endif + #ifdef CONFIG_DEBUG_FS_ERROR # define ferr _err #else @@ -1267,6 +1303,14 @@ # define ninfodumpbuffer(m,b,n) #endif +#ifdef CONFIG_DEBUG_WIRELESS +# define wlerrdumpbuffer(m,b,n) errdumpbuffer(m,b,n) +# define wlinfodumpbuffer(m,b,n) infodumpbuffer(m,b,n) +#else +# define wlerrdumpbuffer(m,b,n) +# define wlinfodumpbuffer(m,b,n) +#endif + #ifdef CONFIG_DEBUG_FS # define ferrdumpbuffer(m,b,n) errdumpbuffer(m,b,n) # define finfodumpbuffer(m,b,n) infodumpbuffer(m,b,n) diff --git a/include/nuttx/wireless/nrf24l01.h b/include/nuttx/wireless/nrf24l01.h index 76ac27d0df..610b3c3682 100644 --- a/include/nuttx/wireless/nrf24l01.h +++ b/include/nuttx/wireless/nrf24l01.h @@ -64,8 +64,6 @@ #define NRF24L01_DYN_LENGTH 33 /* Specific length value to use to enable dynamic packet length */ #define NRF24L01_XMIT_MAXRT 255 /* Specific value returned by Number of available pipes */ -/* #define NRF24L01_DEBUG 1 */ - /* IOCTL commands */ #define NRF24L01IOC_SETRETRCFG _WLIOC(NRF24L01_FIRST+0) /* arg: Pointer to nrf24l01_retrcfg_t structure */ @@ -88,16 +86,6 @@ #define NRF24L01IOC_SETTXADDR WLIOC_SETADDR #define NRF24L01IOC_GETTXADDR WLIOC_GETADDR -/* NRF24L01 debug */ - -#ifdef NRF24L01_DEBUG -# define werr(format, ...) _err(format, ##__VA_ARGS__) -# define winfo(format, ...) _info(format, ##__VA_ARGS__) -#else -# define werr(x...) -# define winfo(x...) -#endif - /**************************************************************************** * Public Data Types ****************************************************************************/ @@ -505,12 +493,9 @@ ssize_t nrf24l01_recv(struct nrf24l01_dev_s *dev, uint8_t *buffer, #endif -#ifdef NRF24L01_DEBUG - +#ifdef CONFIG_DEBUG_WIRELESS void nrf24l01_dumpregs(FAR struct nrf24l01_dev_s *dev); - void nrf24l01_dumprxfifo(FAR struct nrf24l01_dev_s *dev); - #endif #undef EXTERN -- GitLab From a4313bd07b7e7c577ece7ae8f72ba799d4323cb6 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Wed, 15 Mar 2017 16:32:23 -0400 Subject: [PATCH 053/990] wireless/ieee802.15.4: Refactors ieee802154_dev character driver to be radio802154_device --- wireless/ieee802154/radio802154_device.c | 108 ++++++++++++----------- 1 file changed, 57 insertions(+), 51 deletions(-) diff --git a/wireless/ieee802154/radio802154_device.c b/wireless/ieee802154/radio802154_device.c index 792b37ed8d..a170cec7b6 100644 --- a/wireless/ieee802154/radio802154_device.c +++ b/wireless/ieee802154/radio802154_device.c @@ -1,9 +1,10 @@ /**************************************************************************** - * drivers/ieee802154/ieee802154_device.c + * drivers/ieee802154/radio802154_device.c * * Copyright (C) 2014-2015 Gregory Nutt. All rights reserved. * Copyright (C) 2014-2015 Sebastien Lorquet. All rights reserved. * Author: Sebastien Lorquet + * Author: Anthony Merlino * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -56,7 +57,7 @@ * Private Types ****************************************************************************/ -struct ieee802154_devwrapper_s +struct radio802154_devwrapper_s { FAR struct ieee802154_radio_s *child; sem_t devsem; /* Device access serialization semaphore */ @@ -67,28 +68,28 @@ struct ieee802154_devwrapper_s * Private Function Prototypes ****************************************************************************/ -static void ieee802154dev_semtake(FAR struct ieee802154_devwrapper_s *dev); -static int ieee802154dev_open(FAR struct file *filep); -static int ieee802154dev_close(FAR struct file *filep); -static ssize_t ieee802154dev_read(FAR struct file *filep, FAR char *buffer, +static void radio802154dev_semtake(FAR struct radio802154_devwrapper_s *dev); +static int radio802154dev_open(FAR struct file *filep); +static int radio802154dev_close(FAR struct file *filep); +static ssize_t radio802154dev_read(FAR struct file *filep, FAR char *buffer, size_t len); -static ssize_t ieee802154dev_write(FAR struct file *filep, +static ssize_t radio802154dev_write(FAR struct file *filep, FAR const char *buffer, size_t len); -static int ieee802154dev_ioctl(FAR struct file *filep, int cmd, +static int radio802154dev_ioctl(FAR struct file *filep, int cmd, unsigned long arg); /**************************************************************************** * Private Data ****************************************************************************/ -static const struct file_operations ieee802154dev_fops = +static const struct file_operations radio802154dev_fops = { - ieee802154dev_open , /* open */ - ieee802154dev_close, /* close */ - ieee802154dev_read , /* read */ - ieee802154dev_write, /* write */ + radio802154dev_open , /* open */ + radio802154dev_close, /* close */ + radio802154dev_read , /* read */ + radio802154dev_write, /* write */ NULL, /* seek */ - ieee802154dev_ioctl /* ioctl */ + radio802154dev_ioctl /* ioctl */ #ifndef CONFIG_DISABLE_POLL , NULL /* poll */ #endif @@ -102,14 +103,14 @@ static const struct file_operations ieee802154dev_fops = ****************************************************************************/ /**************************************************************************** - * Name: ieee802154dev_semtake + * Name: radio802154dev_semtake * * Description: * Acquire the semaphore used for access serialization. * ****************************************************************************/ -static void ieee802154dev_semtake(FAR struct ieee802154_devwrapper_s *dev) +static void radio802154dev_semtake(FAR struct radio802154_devwrapper_s *dev) { /* Take the semaphore (perhaps waiting) */ @@ -124,30 +125,30 @@ static void ieee802154dev_semtake(FAR struct ieee802154_devwrapper_s *dev) } /**************************************************************************** - * Name: ieee802154dev_semgive + * Name: radio802154dev_semgive * * Description: * Release the semaphore used for access serialization. * ****************************************************************************/ -static inline void ieee802154dev_semgive(FAR struct ieee802154_devwrapper_s *dev) +static inline void radio802154dev_semgive(FAR struct radio802154_devwrapper_s *dev) { sem_post(&dev->devsem); } /**************************************************************************** - * Name: ieee802154dev_open + * Name: radio802154dev_open * * Description: - * Open the MRF24J40 device. + * Open the 802.15.4 radio character device. * ****************************************************************************/ -static int ieee802154dev_open(FAR struct file *filep) +static int radio802154dev_open(FAR struct file *filep) { FAR struct inode *inode; - FAR struct ieee802154_devwrapper_s *dev; + FAR struct radio802154_devwrapper_s *dev; DEBUGASSERT(filep != NULL && filep->f_inode != NULL); inode = filep->f_inode; @@ -156,7 +157,7 @@ static int ieee802154dev_open(FAR struct file *filep) /* Get exclusive access to the driver data structures */ - ieee802154dev_semtake(dev); + radio802154dev_semtake(dev); if (dev->opened) { @@ -174,22 +175,22 @@ static int ieee802154dev_open(FAR struct file *filep) dev->opened = true; } - ieee802154dev_semgive(dev); + radio802154dev_semgive(dev); return OK; } /**************************************************************************** - * Name: ieee802154dev_close + * Name: radio802154dev_close * * Description: - * Close the MRF24J40 device. + * Close the 802.15.4 radio character device. * ****************************************************************************/ -static int ieee802154dev_close(FAR struct file *filep) +static int radio802154dev_close(FAR struct file *filep) { FAR struct inode *inode; - FAR struct ieee802154_devwrapper_s *dev; + FAR struct radio802154_devwrapper_s *dev; int ret = OK; DEBUGASSERT(filep != NULL && filep->f_inode != NULL); @@ -199,7 +200,7 @@ static int ieee802154dev_close(FAR struct file *filep) /* Get exclusive access to the driver data structures */ - ieee802154dev_semtake(dev); + radio802154dev_semtake(dev); if (!dev->opened) { @@ -217,12 +218,12 @@ static int ieee802154dev_close(FAR struct file *filep) dev->opened = false; } - ieee802154dev_semgive(dev); + radio802154dev_semgive(dev); return ret; } /**************************************************************************** - * Name: ieee802154dev_read + * Name: radio802154dev_read * * Description: * Return the last received packet. @@ -231,10 +232,10 @@ static int ieee802154dev_close(FAR struct file *filep) * ****************************************************************************/ -static ssize_t ieee802154dev_read(FAR struct file *filep, FAR char *buffer, size_t len) +static ssize_t radio802154dev_read(FAR struct file *filep, FAR char *buffer, size_t len) { FAR struct inode *inode; - FAR struct ieee802154_devwrapper_s *dev; + FAR struct radio802154_devwrapper_s *dev; FAR struct ieee802154_packet_s *buf; int ret = OK; @@ -285,21 +286,21 @@ done: } /**************************************************************************** - * Name: ieee802154dev_write + * Name: radio802154dev_write * * Description: * Send a packet immediately. * TODO: Put a packet in the send queue. The packet will be sent as soon - * as possible. The buffer must point to a struct ieee802154_packet_s + * as possible. The buffer must point to a struct radio802154_packet_s * with the correct length. * ****************************************************************************/ -static ssize_t ieee802154dev_write(FAR struct file *filep, +static ssize_t radio802154dev_write(FAR struct file *filep, FAR const char *buffer, size_t len) { FAR struct inode *inode; - FAR struct ieee802154_devwrapper_s *dev; + FAR struct radio802154_devwrapper_s *dev; FAR struct ieee802154_packet_s *packet; FAR struct timespec timeout; int ret = OK; @@ -364,18 +365,18 @@ done: } /**************************************************************************** - * Name: ieee802154dev_ioctl + * Name: radio802154dev_ioctl * * Description: * Control the MRF24J40 device. This is where the real operations happen. * ****************************************************************************/ -static int ieee802154dev_ioctl(FAR struct file *filep, int cmd, +static int radio802154dev_ioctl(FAR struct file *filep, int cmd, unsigned long arg) { FAR struct inode *inode; - FAR struct ieee802154_devwrapper_s *dev; + FAR struct radio802154_devwrapper_s *dev; FAR struct ieee802154_radio_s *child; int ret = OK; @@ -466,30 +467,35 @@ static int ieee802154dev_ioctl(FAR struct file *filep, int cmd, } /**************************************************************************** - * Name: ieee802154dev_register + * Name: radio802154dev_register * * Description: - * Register /dev/ieee%d + * Register a character driver to access the IEEE 802.15.4 radio from + * user-space + * + * Input Parameters: + * radio - Pointer to the radio struct to be registerd. + * devname - The name of the IEEE 802.15.4 radio to be registered. + * + * Returned Values: + * Zero (OK) is returned on success. Otherwise a negated errno value is + * returned to indicate the nature of the failure. * ****************************************************************************/ -int ieee802154_register(FAR struct ieee802154_radio_s *ieee, - unsigned int minor) +int radio802154dev_register(FAR struct ieee802154_radio_s *radio, FAR char *devname) { - FAR struct ieee802154_devwrapper_s *dev; - char devname[16]; + FAR struct radio802154_devwrapper_s *dev; - dev = kmm_zalloc(sizeof(struct ieee802154_devwrapper_s)); + dev = kmm_zalloc(sizeof(struct radio802154_devwrapper_s)); if (dev == NULL) { return -ENOMEM; } - dev->child = ieee; + dev->child = radio; sem_init(&dev->devsem, 0, 1); /* Allow the device to be opened once before blocking */ - sprintf(devname, "/dev/ieee%d", minor); - - return register_driver(devname, &ieee802154dev_fops, 0666, dev); + return register_driver(devname, &radio802154dev_fops, 0666, dev); } -- GitLab From f985b525871d2d0f71a562fab2aeaf016163fa5e Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 15 Mar 2017 14:37:17 -0600 Subject: [PATCH 054/990] Integrate use of new wireless debug macros. Replace ad hoc debug macros. Convert obsolete dbg() macros to current info(), warn(), err() macros. --- drivers/wireless/ieee802154/at86rf23x.c | 38 +++++++++++++------------ drivers/wireless/ieee802154/mrf24j40.c | 36 +++++++++++------------ wireless/ieee802154/ieee802154_device.c | 2 +- 3 files changed, 39 insertions(+), 37 deletions(-) diff --git a/drivers/wireless/ieee802154/at86rf23x.c b/drivers/wireless/ieee802154/at86rf23x.c index 653a92b313..e0920c3f47 100644 --- a/drivers/wireless/ieee802154/at86rf23x.c +++ b/drivers/wireless/ieee802154/at86rf23x.c @@ -283,7 +283,7 @@ static void at86rf23x_setreg(FAR struct spi_dev_s *spi, uint32_t addr, SPI_SELECT(spi, SPIDEV_IEEE802154, false); at86rf23x_unlock(spi); - vdbg("0x%02X->r[0x%02X]\n", val, addr); + wlinfo("0x%02X->r[0x%02X]\n", val, addr); } /**************************************************************************** @@ -311,7 +311,7 @@ static uint8_t at86rf23x_getreg(FAR struct spi_dev_s *spi, uint32_t addr) at86rf23x_unlock(spi); - vdbg("r[0x%02X]=0x%02X\n",addr,val[1]); + wlinfo("r[0x%02X]=0x%02X\n",addr,val[1]); return val[1]; } @@ -456,7 +456,7 @@ static int at86rf23x_setTRXstate(FAR struct at86rf23x_dev_s *dev, (status != TRX_STATUS_TXARETON) && (status != TRX_STATUS_PON)) { - dbg("Invalid State\n"); + wlerr("ERROR: Invalid State\n"); return ERROR; } @@ -632,17 +632,17 @@ static int at86rf23x_setTRXstate(FAR struct at86rf23x_dev_s *dev, break; default: - dbg("%s \n", EINVAL_STR); + wlerr("ERRPR: %s \n", EINVAL_STR); init_status = 0;/* Placed this here to keep compiler happy when not in debug */ return -EINVAL; } if (ret == ERROR) { - dbg("State Transistion Error\n"); + wlerr("ERROR: State Transistion Error\n"); } - vdbg("Radio state change state[0x%02x]->state[0x%02x]\n", init_status, status); + wlinfo("Radio state change state[0x%02x]->state[0x%02x]\n", init_status, status); return ret; } @@ -671,7 +671,7 @@ static int at86rf23x_setchannel(FAR struct ieee802154_radio_s *ieee, if (chan < 11 || chan > 26) { - dbg("Invalid requested chan: %d\n",chan); + wlerr("ERROR: Invalid requested chan: %d\n",chan); return -EINVAL; } @@ -681,7 +681,7 @@ static int at86rf23x_setchannel(FAR struct ieee802154_radio_s *ieee, if ((TRX_STATUS_SLEEP == state) || (TRX_STATUS_PON == state)) { - dbg("Radio in invalid mode [%02x] to set the channel\n", state); + wlerr("ERROR: Radio in invalid mode [%02x] to set the channel\n", state); return ERROR; } @@ -693,7 +693,7 @@ static int at86rf23x_setchannel(FAR struct ieee802154_radio_s *ieee, dev->channel = chan; - vdbg("CHANNEL Changed to %d\n", chan); + wlinfo("CHANNEL Changed to %d\n", chan); return OK; } @@ -1200,7 +1200,7 @@ int at86rf23x_initialize(FAR struct at86rf23x_dev_s *dev) part = at86rf23x_getreg(dev->spi, RF23X_REG_PART); version = at86rf23x_getreg(dev->spi, RF23X_REG_VERSION); - dbg("Radio part: 0x%02x version: 0x%02x found\n", part, version); + wlinfo("Radio part: 0x%02x version: 0x%02x found\n", part, version); return OK; } @@ -1236,7 +1236,7 @@ static int at86rf23x_resetrf(FAR struct at86rf23x_dev_s *dev) if (retry_cnt == RF23X_MAX_RETRY_RESET_TO_TRX_OFF) { - dbg("Reset of transceiver failed\n"); + wlerr("ERROR: Reset of transceiver failed\n"); return ERROR; } @@ -1346,9 +1346,11 @@ static int at86rf23x_regdump(FAR struct at86rf23x_dev_s *dev) len += sprintf(buf+len, "%02x ", at86rf23x_getreg(dev->spi, i)); - /* At the end of each 15 regs or end of rf233s regs and actually print dbg message*/ + /* At the end of each 15 regs or end of rf233s regs and actually print + * debug message. + */ - if ((i&15)==15 || i == 0x2f) + if ((i&15) == 15 || i == 0x2f) { sprintf(buf+len, "\n"); printf("%s",buf); @@ -1373,7 +1375,7 @@ static void at86rf23x_irqworker(FAR void *arg) FAR struct at86rf23x_dev_s *dev = (FAR struct at86rf23x_dev_s *)arg; uint8_t irq_status = at86rf23x_getreg(dev->spi, RF23X_REG_IRQ_STATUS); - vdbg("IRQ: 0x%02X\n", irq_status); + wlinfo("IRQ: 0x%02X\n", irq_status); if ((irq_status & (1<<3)) != 0) { @@ -1388,7 +1390,7 @@ static void at86rf23x_irqworker(FAR void *arg) } else { - dbg("Unknown IRQ Status: %d\n", irq_status); + wlerr("ERROR: Unknown IRQ Status: %d\n", irq_status); /* Re enable the IRQ even if we don't know how to handle previous * status. @@ -1410,7 +1412,7 @@ static void at86rf23x_irqwork_rx(FAR struct at86rf23x_dev_s *dev) { uint8_t rx_len; - vdbg("6LOWPAN:Rx IRQ\n"); + wlinfo("6LOWPAN:Rx IRQ\n"); rx_len = at86rf23x_readframe(dev->spi, dev->ieee.rxbuf->data); @@ -1440,7 +1442,7 @@ static void at86rf23x_irqwork_rx(FAR struct at86rf23x_dev_s *dev) static void at86rf23x_irqwork_tx(FAR struct at86rf23x_dev_s *dev) { - vdbg("6LOWPAN:Tx IRQ\n"); + wlinfo("6LOWPAN:Tx IRQ\n"); /* TODO: * There needs to be more here but for now just alert the waiting @@ -1482,7 +1484,7 @@ static int at86rf23x_transmit(FAR struct ieee802154_radio_s *ieee, } else { - dbg("Transmit could not put the radio in a Tx state\n"); + wlerr("ERROR: Transmit could not put the radio in a Tx state\n"); return ERROR; } diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c index 3c8e9ec8d7..f9cd98cb2d 100644 --- a/drivers/wireless/ieee802154/mrf24j40.c +++ b/drivers/wireless/ieee802154/mrf24j40.c @@ -342,7 +342,7 @@ static uint8_t mrf24j40_getreg(FAR struct spi_dev_s *spi, uint32_t addr) SPI_SELECT (spi, SPIDEV_IEEE802154, false); mrf24j40_unlock(spi); - /*winfo("r[%04X]=%02X\n", addr, rx[len-1]);*/ + /*wlinfo("r[%04X]=%02X\n", addr, rx[len-1]);*/ return rx[len-1]; } @@ -482,7 +482,7 @@ static int mrf24j40_setrxmode(FAR struct mrf24j40_radio_s *dev, int mode) mrf24j40_setreg(dev->spi, MRF24J40_RXMCR, reg); dev->rxmode = mode; - winfo("%u\n", (unsigned)mode); + wlinfo("%u\n", (unsigned)mode); return OK; } @@ -508,7 +508,7 @@ static int mrf24j40_setchannel(FAR struct ieee802154_radio_s *ieee, FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; if (chan<11 || chan>26) { - werr("ERROR: Invalid chan: %d\n",chan); + wlerr("ERROR: Invalid chan: %d\n",chan); return -EINVAL; } @@ -523,7 +523,7 @@ static int mrf24j40_setchannel(FAR struct ieee802154_radio_s *ieee, mrf24j40_resetrfsm(dev); dev->channel = chan; - //winfo("%u\n", (unsigned)chan); + //wlinfo("%u\n", (unsigned)chan); return OK; } @@ -563,7 +563,7 @@ static int mrf24j40_setpanid(FAR struct ieee802154_radio_s *ieee, mrf24j40_setreg(dev->spi, MRF24J40_PANIDL, (uint8_t)(panid&0xFF)); dev->panid = panid; - winfo("%04X\n", (unsigned)panid); + wlinfo("%04X\n", (unsigned)panid); return OK; } @@ -605,7 +605,7 @@ static int mrf24j40_setsaddr(FAR struct ieee802154_radio_s *ieee, mrf24j40_setreg(dev->spi, MRF24J40_SADRL, (uint8_t)(saddr&0xFF)); dev->saddr = saddr; - winfo("%04X\n", (unsigned)saddr); + wlinfo("%04X\n", (unsigned)saddr); return OK; } @@ -817,7 +817,7 @@ static int mrf24j40_settxpower(FAR struct ieee802154_radio_s *ieee, return -EINVAL; } - winfo("remaining attenuation: %d mBm\n",txpwr); + wlinfo("remaining attenuation: %d mBm\n",txpwr); switch(txpwr/100) { @@ -935,7 +935,7 @@ static int mrf24j40_regdump(FAR struct mrf24j40_radio_s *dev) char buf[4+16*3+2+1]; int len=0; - winfo("Short regs:\n"); + wlinfo("Short regs:\n"); for (i = 0; i < 0x40; i++) { @@ -948,11 +948,11 @@ static int mrf24j40_regdump(FAR struct mrf24j40_radio_s *dev) if ((i & 15) == 15) { sprintf(buf+len, "\n"); - winfo("%s", buf); + wlinfo("%s", buf); } } - winfo("Long regs:\n"); + wlinfo("Long regs:\n"); for (i=0x80000200;i<0x80000250;i++) { if ((i&15)==0) @@ -964,7 +964,7 @@ static int mrf24j40_regdump(FAR struct mrf24j40_radio_s *dev) if ((i & 15) == 15) { sprintf(buf+len, "\n"); - winfo("%s", buf); + wlinfo("%s", buf); } } @@ -990,7 +990,7 @@ static int mrf24j40_ioctl(FAR struct ieee802154_radio_s *ieee, int cmd, return mrf24j40_regdump(dev); case 1001: dev->paenabled = (uint8_t)arg; - winfo("PA %sabled\n", arg ? "en" : "dis"); + wlinfo("PA %sabled\n", arg ? "en" : "dis"); return OK; default: @@ -1081,7 +1081,7 @@ static int mrf24j40_transmit(FAR struct ieee802154_radio_s *ieee, FAR struct iee fc1 = packet->data[0]; fc2 = packet->data[1]; - // winfo("fc1 %02X fc2 %02X\n", fc1,fc2); + // wlinfo("fc1 %02X fc2 %02X\n", fc1,fc2); if ((fc2 & IEEE802154_FC2_DADDR) == IEEE802154_DADDR_SHORT) { @@ -1111,7 +1111,7 @@ static int mrf24j40_transmit(FAR struct ieee802154_radio_s *ieee, FAR struct iee hlen += 8; /* Ext saddr */ } -// winfo("hlen %d\n",hlen); +// wlinfo("hlen %d\n",hlen); /* Header len, 0, TODO for security modes */ @@ -1170,7 +1170,7 @@ static void mrf24j40_irqwork_tx(FAR struct mrf24j40_radio_s *dev) dev->ieee.txretries = (reg & MRF24J40_TXSTAT_X_MASK) >> MRF24J40_TXSTAT_X_SHIFT; dev->ieee.txbusy = (reg & MRF24J40_TXSTAT_CCAFAIL) == MRF24J40_TXSTAT_CCAFAIL; - //winfo("TXSTAT%02X!\n", txstat); + //wlinfo("TXSTAT%02X!\n", txstat); #warning TODO report errors UNUSED(txstat); @@ -1232,7 +1232,7 @@ static void mrf24j40_irqwork_rx(FAR struct mrf24j40_radio_s *dev) uint32_t index; uint8_t reg; - /*winfo("!\n");*/ + /*wlinfo("!\n");*/ /* Disable rx int */ @@ -1248,7 +1248,7 @@ static void mrf24j40_irqwork_rx(FAR struct mrf24j40_radio_s *dev) addr = MRF24J40_RXBUF_BASE; dev->ieee.rxbuf->len = mrf24j40_getreg(dev->spi, addr++); - /*winfo("len %3d\n", dev->ieee.rxbuf->len);*/ + /*wlinfo("len %3d\n", dev->ieee.rxbuf->len);*/ for (index = 0; index < dev->ieee.rxbuf->len; index++) { @@ -1303,7 +1303,7 @@ static void mrf24j40_irqworker(FAR void *arg) /* Read and store INTSTAT - this clears the register. */ intstat = mrf24j40_getreg(dev->spi, MRF24J40_INTSTAT); -// winfo("INT%02X\n", intstat); +// wlinfo("INT%02X\n", intstat); /* Do work according to the pending interrupts */ diff --git a/wireless/ieee802154/ieee802154_device.c b/wireless/ieee802154/ieee802154_device.c index 792b37ed8d..aa77a7e105 100644 --- a/wireless/ieee802154/ieee802154_device.c +++ b/wireless/ieee802154/ieee802154_device.c @@ -353,7 +353,7 @@ static ssize_t ieee802154dev_write(FAR struct file *filep, if (sem_timedwait(&dev->child->txsem, &timeout)) { - _err("Radio Device timedout on Tx\n"); + wlerr("Radio Device timedout on Tx\n"); } done: -- GitLab From 25e4e3c3146579fc550cf43584ac132bbedb0c5b Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 15 Mar 2017 14:57:13 -0600 Subject: [PATCH 055/990] Bring closer to NuttX coding standard. --- drivers/wireless/ieee802154/Kconfig | 8 +- drivers/wireless/ieee802154/at86rf23x.c | 1 + drivers/wireless/ieee802154/at86rf23x.h | 401 ++++++++++++------------ drivers/wireless/ieee802154/mrf24j40.c | 186 ++++++----- drivers/wireless/ieee802154/mrf24j40.h | 6 +- 5 files changed, 333 insertions(+), 269 deletions(-) diff --git a/drivers/wireless/ieee802154/Kconfig b/drivers/wireless/ieee802154/Kconfig index 6eba028b2a..d0d8c550ec 100644 --- a/drivers/wireless/ieee802154/Kconfig +++ b/drivers/wireless/ieee802154/Kconfig @@ -12,9 +12,9 @@ config IEEE802154_MRF24J40 This selection enables support for the Microchip MRF24J40 device. config IEEE802154_AT86RF233 - bool "ATMEL RF233 IEEE 802.15.4 transceiver" - default n - ---help--- - This selection enables support for the Atmel RF233 device. + bool "ATMEL RF233 IEEE 802.15.4 transceiver" + default n + ---help--- + This selection enables support for the Atmel RF233 device. endif # DRIVERS_IEEE802154 diff --git a/drivers/wireless/ieee802154/at86rf23x.c b/drivers/wireless/ieee802154/at86rf23x.c index e0920c3f47..3bcf203373 100644 --- a/drivers/wireless/ieee802154/at86rf23x.c +++ b/drivers/wireless/ieee802154/at86rf23x.c @@ -32,6 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. * ****************************************************************************/ + /**************************************************************************** * Included Files ****************************************************************************/ diff --git a/drivers/wireless/ieee802154/at86rf23x.h b/drivers/wireless/ieee802154/at86rf23x.h index 51c96ced3c..4d64fed0c8 100644 --- a/drivers/wireless/ieee802154/at86rf23x.h +++ b/drivers/wireless/ieee802154/at86rf23x.h @@ -1,204 +1,221 @@ -/* - * at86rf23x.h - * - * Created on: Feb 24, 2016 - * Author: poppe - */ - -#ifndef APPS_EXTERNAL_IEEE_AT86RF23X_H_ -#define APPS_EXTERNAL_IEEE_AT86RF23X_H_ - -#define RF23X_SPI_REG_READ 0x80 -#define RF23X_SPI_REG_WRITE 0xC0 -#define RF23X_SPI_FRAME_WRITE 0x60 -#define RF23X_SPI_FRAME_READ 0x20 -#define RF23X_SPI_SRAM_READ 0x00 -#define RF23X_SPI_SRAM_WRITE 0x40 - -/* us Times Constants for the RF233 */ -#define RF23X_TIME_RESET_BOOT 510 -#define RF23X_TIME_FORCE_TRXOFF 100 -#define RF23X_TIME_P_ON_TO_TRXOFF 510 -#define RF23X_TIME_SLEEP_TO_TRXOFF 1200 -#define RF23X_TIME_RESET 6 -#define RF23X_TIME_ED_MEASUREMENT 140 -#define RF23X_TIME_CCA 140 -#define RF23X_TIME_PLL_LOCK 150 -#define RF23X_TIME_FTN_TUNNING 25 -#define RF23X_TIME_NOCLK_TO_WAKE 6 -#define RF23X_TIME_CMD_FORCE_TRX_OFF 1 -#define RF23X_TIME_TRXOFF_TO_PLL 180 -#define RF23X_TIME_TRANSITION_PLL_ACTIVE 1 -#define RF23X_TIME_TRXOFF_TO_SLEEP 1200 - -#define RF23X_MAX_RETRY_RESET_TO_TRX_OFF 5 - - -#define RF23X_REG_TRXSTATUS 0x01 -#define RF23X_REG_TRXSTATE 0x02 -#define RF23X_REG_TRXCTRL0 0x03 -#define RF23X_REG_TRXCTRL1 0x04 -#define RF23X_REG_TXPWR 0x05 -#define RF23X_REG_RSSI 0x06 -#define RF23X_REG_EDLEVEL 0x07 -#define RF23X_REG_CCA 0x08 -#define RF23X_REG_THRES 0x09 -#define RF23X_REG_RXCTRL 0x0a -#define RF23X_REG_SFD 0x0b -#define RF23X_REG_TRXCTRL2 0x0c -#define RF23X_REG_ANT_DIV 0x0d -#define RF23X_REG_IRQ_MASK 0x0e -#define RF23X_REG_IRQ_STATUS 0x0f -#define RF23X_REG_VREG_CTRL 0x10 -#define RF23X_REG_BATMON 0x11 -#define RF23X_REG_XOSC_CTRL 0x12 -#define RF23X_REG_CCCTRL0 0x13 -#define RF23X_REG_CCCTRL1 0x14 -#define RF23X_REG_RXSYN 0x15 -#define RF23X_REG_TRXRPC 0x16 -#define RF23X_REG_XAHCTRL1 0x17 -#define RF23X_REG_FTNCTRL 0x18 -#define RF23X_REG_XAHCTRL2 0x19 -#define RF23X_REG_PLLCF 0x1a -#define RF23X_REG_PLLDCU 0x1b -#define RF23X_REG_PART 0x1c -#define RF23X_REG_VERSION 0x1d -#define RF23X_REG_MANID0 0x1e -#define RF23X_REG_MANID1 0x1f -#define RF23X_REG_SADDR0 0x20 -#define RF23X_REG_SADDR1 0x21 -#define RF23X_REG_PANID0 0x22 -#define RF23X_REG_PANID1 0x23 -#define RF23X_REG_IEEEADDR0 0x24 -#define RF23X_REG_IEEEADDR1 0x25 -#define RF23X_REG_IEEEADDR2 0x26 -#define RF23X_REG_IEEEADDR3 0x27 -#define RF23X_REG_IEEEADDR4 0x28 -#define RF23X_REG_IEEEADDR5 0x29 -#define RF23X_REG_IEEEADDR6 0x2a -#define RF23X_REG_IEEEADDR7 0x2b -#define RF23X_REG_XAHCTRL0 0x2c -#define RF23X_REG_CSMASEED0 0x2d -#define RF23X_REG_CSMASEED1 0x2e -#define RF23X_REG_CSMABE 0x2f -#define RF23X_REG_TSTCTRLDIGI 0x36 -#define RF23X_REG_TSTAGC 0x3c -#define RF23X_REG_SDM 0x3d -#define RF23X_REG_PHYTXTIME 0x3b -#define RF23X_REG_PHYPMUVALUE 0x3b - - -#define RF23X_TRXSTATUS_POS 0 -#define RF23X_TRXSTATUS_MASK 0x1f -#define RF23X_TRXSTATUS_STATUS RF23X_REG_TRXSTATUS, RF23X_TRXSTATUS_POS, RF23X_TRXSTATUS_MASK - -#define RF23X_TRXCMD_POS 0 -#define RF23X_TRXCMD_MASK 0x1f -#define RF23X_TRXCMD_STATE RF23X_REG_TRXSTATE, RF23X_TRXCMD_POS, RF23X_TRXCMD_MASK - - -#define RF23X_TXPWR_POS_4 0x00 -#define RF23X_TXPWR_POS_3_7 0x01 -#define RF23X_TXPWR_POS_3_4 0x02 -#define RF23X_TXPWR_POS_3 0x03 -#define RF23X_TXPWR_POS_2_5 0x04 -#define RF23X_TXPWR_POS_2 0x05 -#define RF23X_TXPWR_POS_1 0x06 -#define RF23X_TXPWR_0 0x07 -#define RF23X_TXPWR_NEG_1 0x08 -#define RF23X_TXPWR_NEG_2 0x09 -#define RF23X_TXPWR_NEG_3 0x0a -#define RF23X_TXPWR_NEG_4 0x0b -#define RF23X_TXPWR_NEG_6 0x0c -#define RF23X_TXPWR_NEG_8 0x0d -#define RF23X_TXPWR_NEG_12 0x0e -#define RF23X_TXPWR_NEG_17 0x0f - /**************************************************************************** - * CCA_STATUS + * drivers/wireless/ieee802154/at86rf23x.c + * + * Copyright (C) 2016 Matt Poppe. All rights reserved. + * Author: Matt Poppe + * + * 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. + * ****************************************************************************/ -#define RF23X_CCA_MODE_CS_OR_ED 0x00 -#define RF23X_CCA_MODE_ED 0x01 -#define RF23X_CCA_MODE_CS 0x02 -#define RF23X_CCA_MODE_CS_AND_ED 0x03 -#define RF23X_CCA_CHANNEL_POS 0 -#define RF23X_CCA_CHANNEL_MASK 0x1f -#define RF23X_CCA_BITS_CHANNEL RF23X_REG_CCA, RF23X_CCA_CHANNEL_POS, RF23X_CCA_CHANNEL_MASK -#define RF23X_CCA_MODE_POS 5 -#define RF23X_CCA_MODE_MASK 0x03 -#define RF23X_CCA_BITS_MODE RF23X_REG_CCA, RF23X_CCA_MODE_POS, RF23X_CCA_MODE_MASK - - -/**************************************************************************** - * XAH CTRL 1 - ****************************************************************************/ -#define RF23X_XAHCTRL1_PROM_MODE_POS 1 -#define RF23X_XAHCTRL1_PROM_MODE_MASK 0x01 -#define RF23X_XAHCTRL1_BITS_PROM_MODE RF23X_REG_XAHCTRL1, RF23X_XAHCTRL1_PROM_MODE_POS, RF23X_XAHCTRL1_PROM_MODE_MASK +#ifndef __DRIVERS_WIRELESS_IEEE802154_AT86RF23X_H +#define __DRIVERS_WIRELESS_IEEE802154_AT86RF23X_H /**************************************************************************** - * CSMA SEED 0 + * Pre-processor Definitions ****************************************************************************/ -/**************************************************************************** - * CSMA SEED 1 - ****************************************************************************/ -#define RF23X_CSMASEED1_IAMCOORD_POS 3 -#define RF23X_CSMASEED1_IAMCOORD_MASK 0x1 -#define RF23X_CSMASEED1_IAMCOORD_BITS RF23X_REG_CSMASEED1, RF23X_CSMASEED1_IAMCOORD_POS, RF23X_CSMASEED1_IAMCOORD_MASK +#define RF23X_SPI_REG_READ 0x80 +#define RF23X_SPI_REG_WRITE 0xc0 +#define RF23X_SPI_FRAME_WRITE 0x60 +#define RF23X_SPI_FRAME_READ 0x20 +#define RF23X_SPI_SRAM_READ 0x00 +#define RF23X_SPI_SRAM_WRITE 0x40 + +/* US Times Constants for the RF233 */ + +#define RF23X_TIME_RESET_BOOT 510 +#define RF23X_TIME_FORCE_TRXOFF 100 +#define RF23X_TIME_P_ON_TO_TRXOFF 510 +#define RF23X_TIME_SLEEP_TO_TRXOFF 1200 +#define RF23X_TIME_RESET 6 +#define RF23X_TIME_ED_MEASUREMENT 140 +#define RF23X_TIME_CCA 140 +#define RF23X_TIME_PLL_LOCK 150 +#define RF23X_TIME_FTN_TUNNING 25 +#define RF23X_TIME_NOCLK_TO_WAKE 6 +#define RF23X_TIME_CMD_FORCE_TRX_OFF 1 +#define RF23X_TIME_TRXOFF_TO_PLL 180 +#define RF23X_TIME_TRANSITION_PLL_ACTIVE 1 +#define RF23X_TIME_TRXOFF_TO_SLEEP 1200 + +#define RF23X_MAX_RETRY_RESET_TO_TRX_OFF 5 + +#define RF23X_REG_TRXSTATUS 0x01 +#define RF23X_REG_TRXSTATE 0x02 +#define RF23X_REG_TRXCTRL0 0x03 +#define RF23X_REG_TRXCTRL1 0x04 +#define RF23X_REG_TXPWR 0x05 +#define RF23X_REG_RSSI 0x06 +#define RF23X_REG_EDLEVEL 0x07 +#define RF23X_REG_CCA 0x08 +#define RF23X_REG_THRES 0x09 +#define RF23X_REG_RXCTRL 0x0a +#define RF23X_REG_SFD 0x0b +#define RF23X_REG_TRXCTRL2 0x0c +#define RF23X_REG_ANT_DIV 0x0d +#define RF23X_REG_IRQ_MASK 0x0e +#define RF23X_REG_IRQ_STATUS 0x0f +#define RF23X_REG_VREG_CTRL 0x10 +#define RF23X_REG_BATMON 0x11 +#define RF23X_REG_XOSC_CTRL 0x12 +#define RF23X_REG_CCCTRL0 0x13 +#define RF23X_REG_CCCTRL1 0x14 +#define RF23X_REG_RXSYN 0x15 +#define RF23X_REG_TRXRPC 0x16 +#define RF23X_REG_XAHCTRL1 0x17 +#define RF23X_REG_FTNCTRL 0x18 +#define RF23X_REG_XAHCTRL2 0x19 +#define RF23X_REG_PLLCF 0x1a +#define RF23X_REG_PLLDCU 0x1b +#define RF23X_REG_PART 0x1c +#define RF23X_REG_VERSION 0x1d +#define RF23X_REG_MANID0 0x1e +#define RF23X_REG_MANID1 0x1f +#define RF23X_REG_SADDR0 0x20 +#define RF23X_REG_SADDR1 0x21 +#define RF23X_REG_PANID0 0x22 +#define RF23X_REG_PANID1 0x23 +#define RF23X_REG_IEEEADDR0 0x24 +#define RF23X_REG_IEEEADDR1 0x25 +#define RF23X_REG_IEEEADDR2 0x26 +#define RF23X_REG_IEEEADDR3 0x27 +#define RF23X_REG_IEEEADDR4 0x28 +#define RF23X_REG_IEEEADDR5 0x29 +#define RF23X_REG_IEEEADDR6 0x2a +#define RF23X_REG_IEEEADDR7 0x2b +#define RF23X_REG_XAHCTRL0 0x2c +#define RF23X_REG_CSMASEED0 0x2d +#define RF23X_REG_CSMASEED1 0x2e +#define RF23X_REG_CSMABE 0x2f +#define RF23X_REG_TSTCTRLDIGI 0x36 +#define RF23X_REG_TSTAGC 0x3c +#define RF23X_REG_SDM 0x3d +#define RF23X_REG_PHYTXTIME 0x3b +#define RF23X_REG_PHYPMUVALUE 0x3b + +#define RF23X_TRXSTATUS_POS 0 +#define RF23X_TRXSTATUS_MASK 0x1f +#define RF23X_TRXSTATUS_STATUS RF23X_REG_TRXSTATUS, RF23X_TRXSTATUS_POS, RF23X_TRXSTATUS_MASK + +#define RF23X_TRXCMD_POS 0 +#define RF23X_TRXCMD_MASK 0x1f +#define RF23X_TRXCMD_STATE RF23X_REG_TRXSTATE, RF23X_TRXCMD_POS, RF23X_TRXCMD_MASK + +#define RF23X_TXPWR_POS_4 0x00 +#define RF23X_TXPWR_POS_3_7 0x01 +#define RF23X_TXPWR_POS_3_4 0x02 +#define RF23X_TXPWR_POS_3 0x03 +#define RF23X_TXPWR_POS_2_5 0x04 +#define RF23X_TXPWR_POS_2 0x05 +#define RF23X_TXPWR_POS_1 0x06 +#define RF23X_TXPWR_0 0x07 +#define RF23X_TXPWR_NEG_1 0x08 +#define RF23X_TXPWR_NEG_2 0x09 +#define RF23X_TXPWR_NEG_3 0x0a +#define RF23X_TXPWR_NEG_4 0x0b +#define RF23X_TXPWR_NEG_6 0x0c +#define RF23X_TXPWR_NEG_8 0x0d +#define RF23X_TXPWR_NEG_12 0x0e +#define RF23X_TXPWR_NEG_17 0x0f + +/* CCA_STATUS */ + +#define RF23X_CCA_MODE_CS_OR_ED 0x00 +#define RF23X_CCA_MODE_ED 0x01 +#define RF23X_CCA_MODE_CS 0x02 +#define RF23X_CCA_MODE_CS_AND_ED 0x03 + +#define RF23X_CCA_CHANNEL_POS 0 +#define RF23X_CCA_CHANNEL_MASK 0x1f +#define RF23X_CCA_BITS_CHANNEL RF23X_REG_CCA, RF23X_CCA_CHANNEL_POS, RF23X_CCA_CHANNEL_MASK +#define RF23X_CCA_MODE_POS 5 +#define RF23X_CCA_MODE_MASK 0x03 +#define RF23X_CCA_BITS_MODE RF23X_REG_CCA, RF23X_CCA_MODE_POS, RF23X_CCA_MODE_MASK + +/* XAH CTRL 1 */ + +#define RF23X_XAHCTRL1_PROM_MODE_POS 1 +#define RF23X_XAHCTRL1_PROM_MODE_MASK 0x01 +#define RF23X_XAHCTRL1_BITS_PROM_MODE RF23X_REG_XAHCTRL1, RF23X_XAHCTRL1_PROM_MODE_POS, RF23X_XAHCTRL1_PROM_MODE_MASK + +/* CSMA SEED 0 */ + +/* CSMA SEED 1 */ + +#define RF23X_CSMASEED1_IAMCOORD_POS 3 +#define RF23X_CSMASEED1_IAMCOORD_MASK 0x1 +#define RF23X_CSMASEED1_IAMCOORD_BITS RF23X_REG_CSMASEED1, RF23X_CSMASEED1_IAMCOORD_POS, RF23X_CSMASEED1_IAMCOORD_MASK #define RF23X_CSMASEED1_AACK_DIS_ACK_POS #define RF23X_CSMASEED1_AACK_SET_PD_POS #define RF23X_CSMASEED1_AACK_FVN_MODE_POS -#define RF23X_CSMASEED1_ - - -/**************************************************************************** - * TRX Status - ****************************************************************************/ -#define TRX_STATUS_PON 0x00 -#define TRX_STATUS_BUSYRX 0x01 -#define TRX_STATUS_BUSYTX 0x02 -#define TRX_STATUS_RXON 0x06 -#define TRX_STATUS_TRXOFF 0x08 -#define TRX_STATUS_PLLON 0x09 -#define TRX_STATUS_SLEEP 0x0f -#define TRX_STATUS_DEEPSLEEP 0x10 -#define TRX_STATUS_BUSYRXACK 0x11 -#define TRX_STATUS_BUSYTXARET 0x12 -#define TRX_STATUS_RXAACKON 0x16 -#define TRX_STATUS_TXARETON 0x19 -#define TRX_STATUS_STATEINTRANS 0x1f - -/**************************************************************************** - * TRX Command - ****************************************************************************/ -#define TRX_CMD_NOP 0x00 -#define TRX_CMD_TX 0x02 -#define TRX_CMD_FORCETRXOFF 0x03 -#define TRX_CMD_FORCE_PLLON 0x04 -#define TRX_CMD_RX_ON 0x06 -#define TRX_CMD_TRXOFF 0x08 -#define TRX_CMD_PLL_ON 0x09 -#define TRX_CMD_PREP_DEEPSLEEP 0x10 -#define TRX_CMD_RX_AACK_ON 0x16 -#define TRX_CMD_TX_ARET_ON 0x19 - - -/**************************************************************************** - * IRQ MASK 0x0E - ****************************************************************************/ -#define RF23X_IRQ_MASK_LOCK_PLL (1<<0) -#define RF23X_IRQ_MASK_UNLOCK_PLL (1<<1) -#define RF23X_IRQ_MASK_RX_START (1<<2) -#define RF23X_IRQ_MASK_TRX_END (1<<3) -#define RF23X_IRQ_MASK_CCA_ED_DONE (1<<4) -#define RF23X_IRQ_MASK_AMI (1<<5) -#define RF23X_IRQ_MASK_TRX_UR (1<<6) -#define RF23X_IRQ_MASK_BAT_LOW (1<<7) - -#define RF23X_IRQ_MASK_DEFAULT (RF23X_IRQ_MASK_TRX_END) - -#endif /* APPS_EXTERNAL_IEEE_AT86RF23X_H_ */ +/* TRX Status */ + +#define TRX_STATUS_PON 0x00 +#define TRX_STATUS_BUSYRX 0x01 +#define TRX_STATUS_BUSYTX 0x02 +#define TRX_STATUS_RXON 0x06 +#define TRX_STATUS_TRXOFF 0x08 +#define TRX_STATUS_PLLON 0x09 +#define TRX_STATUS_SLEEP 0x0f +#define TRX_STATUS_DEEPSLEEP 0x10 +#define TRX_STATUS_BUSYRXACK 0x11 +#define TRX_STATUS_BUSYTXARET 0x12 +#define TRX_STATUS_RXAACKON 0x16 +#define TRX_STATUS_TXARETON 0x19 +#define TRX_STATUS_STATEINTRANS 0x1f + +/* TRX Command */ + +#define TRX_CMD_NOP 0x00 +#define TRX_CMD_TX 0x02 +#define TRX_CMD_FORCETRXOFF 0x03 +#define TRX_CMD_FORCE_PLLON 0x04 +#define TRX_CMD_RX_ON 0x06 +#define TRX_CMD_TRXOFF 0x08 +#define TRX_CMD_PLL_ON 0x09 +#define TRX_CMD_PREP_DEEPSLEEP 0x10 +#define TRX_CMD_RX_AACK_ON 0x16 +#define TRX_CMD_TX_ARET_ON 0x19 + +/* IRQ MASK 0x0e */ + +#define RF23X_IRQ_MASK_LOCK_PLL (1 << 0) +#define RF23X_IRQ_MASK_UNLOCK_PLL (1 << 1) +#define RF23X_IRQ_MASK_RX_START (1 << 2) +#define RF23X_IRQ_MASK_TRX_END (1 << 3) +#define RF23X_IRQ_MASK_CCA_ED_DONE (1 << 4) +#define RF23X_IRQ_MASK_AMI (1 << 5) +#define RF23X_IRQ_MASK_TRX_UR (1 << 6) +#define RF23X_IRQ_MASK_BAT_LOW (1 << 7) + +#define RF23X_IRQ_MASK_DEFAULT (RF23X_IRQ_MASK_TRX_END) + +#endif /* __DRIVERS_WIRELESS_IEEE802154_AT86RF23X_H */ diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c index f9cd98cb2d..4cb4ed9934 100644 --- a/drivers/wireless/ieee802154/mrf24j40.c +++ b/drivers/wireless/ieee802154/mrf24j40.c @@ -65,7 +65,7 @@ ****************************************************************************/ #ifndef CONFIG_SCHED_HPWORK -#error High priority work queue required in this driver +# error High priority work queue required in this driver #endif #ifndef CONFIG_IEEE802154_MRF24J40_SPIMODE @@ -160,44 +160,69 @@ struct mrf24j40_radio_s /* Internal operations */ -static void mrf24j40_lock (FAR struct spi_dev_s *spi); +static void mrf24j40_lock(FAR struct spi_dev_s *spi); -static void mrf24j40_setreg (FAR struct spi_dev_s *spi, uint32_t addr, uint8_t val); -static uint8_t mrf24j40_getreg (FAR struct spi_dev_s *spi, uint32_t addr); +static void mrf24j40_setreg(FAR struct spi_dev_s *spi, uint32_t addr, + uint8_t val); +static uint8_t mrf24j40_getreg(FAR struct spi_dev_s *spi, uint32_t addr); -static int mrf24j40_resetrfsm (FAR struct mrf24j40_radio_s *dev); -static int mrf24j40_pacontrol (FAR struct mrf24j40_radio_s *dev, int mode); -static int mrf24j40_initialize(FAR struct mrf24j40_radio_s *dev); +static int mrf24j40_resetrfsm(FAR struct mrf24j40_radio_s *dev); +static int mrf24j40_pacontrol(FAR struct mrf24j40_radio_s *dev, int mode); +static int mrf24j40_initialize(FAR struct mrf24j40_radio_s *dev); -static int mrf24j40_setrxmode (FAR struct mrf24j40_radio_s *dev, int mode); -static int mrf24j40_regdump (FAR struct mrf24j40_radio_s *dev); -static void mrf24j40_irqwork_rx(FAR struct mrf24j40_radio_s *dev); -static void mrf24j40_irqwork_tx(FAR struct mrf24j40_radio_s *dev); -static void mrf24j40_irqworker (FAR void *arg); -static int mrf24j40_interrupt (int irq, FAR void *context); +static int mrf24j40_setrxmode(FAR struct mrf24j40_radio_s *dev, int mode); +static int mrf24j40_regdump(FAR struct mrf24j40_radio_s *dev); +static void mrf24j40_irqwork_rx(FAR struct mrf24j40_radio_s *dev); +static void mrf24j40_irqwork_tx(FAR struct mrf24j40_radio_s *dev); +static void mrf24j40_irqworker(FAR void *arg); +static int mrf24j40_interrupt(int irq, FAR void *context); /* Driver operations */ -static int mrf24j40_setchannel (FAR struct ieee802154_radio_s *ieee, uint8_t chan); -static int mrf24j40_getchannel (FAR struct ieee802154_radio_s *ieee, FAR uint8_t *chan); -static int mrf24j40_setpanid (FAR struct ieee802154_radio_s *ieee, uint16_t panid); -static int mrf24j40_getpanid (FAR struct ieee802154_radio_s *ieee, FAR uint16_t *panid); -static int mrf24j40_setsaddr (FAR struct ieee802154_radio_s *ieee, uint16_t saddr); -static int mrf24j40_getsaddr (FAR struct ieee802154_radio_s *ieee, FAR uint16_t *saddr); -static int mrf24j40_seteaddr (FAR struct ieee802154_radio_s *ieee, FAR uint8_t *eaddr); -static int mrf24j40_geteaddr (FAR struct ieee802154_radio_s *ieee, FAR uint8_t *eaddr); -static int mrf24j40_setpromisc (FAR struct ieee802154_radio_s *ieee, bool promisc); -static int mrf24j40_getpromisc (FAR struct ieee802154_radio_s *ieee, FAR bool *promisc); -static int mrf24j40_setdevmode (FAR struct ieee802154_radio_s *ieee, uint8_t mode); -static int mrf24j40_getdevmode (FAR struct ieee802154_radio_s *ieee, FAR uint8_t *mode); -static int mrf24j40_settxpower (FAR struct ieee802154_radio_s *ieee, int32_t txpwr); -static int mrf24j40_gettxpower (FAR struct ieee802154_radio_s *ieee, FAR int32_t *txpwr); -static int mrf24j40_setcca (FAR struct ieee802154_radio_s *ieee, FAR struct ieee802154_cca_s *cca); -static int mrf24j40_getcca (FAR struct ieee802154_radio_s *ieee, FAR struct ieee802154_cca_s *cca); -static int mrf24j40_ioctl (FAR struct ieee802154_radio_s *ieee, int cmd, unsigned long arg); -static int mrf24j40_energydetect(FAR struct ieee802154_radio_s *ieee, FAR uint8_t *energy); -static int mrf24j40_rxenable (FAR struct ieee802154_radio_s *ieee, bool state, FAR struct ieee802154_packet_s *packet); -static int mrf24j40_transmit (FAR struct ieee802154_radio_s *ieee, FAR struct ieee802154_packet_s *packet); +static int mrf24j40_setchannel(FAR struct ieee802154_radio_s *ieee, + uint8_t chan); +static int mrf24j40_getchannel(FAR struct ieee802154_radio_s *ieee, + FAR uint8_t *chan); +static int mrf24j40_setpanid(FAR struct ieee802154_radio_s *ieee, + uint16_t panid); +static int mrf24j40_getpanid(FAR struct ieee802154_radio_s *ieee, + FAR uint16_t *panid); +static int mrf24j40_setsaddr(FAR struct ieee802154_radio_s *ieee, + uint16_t saddr); +static int mrf24j40_getsaddr(FAR struct ieee802154_radio_s *ieee, + FAR uint16_t *saddr); +static int mrf24j40_seteaddr(FAR struct ieee802154_radio_s *ieee, + FAR uint8_t *eaddr); +static int mrf24j40_geteaddr(FAR struct ieee802154_radio_s *ieee, + FAR uint8_t *eaddr); +static int mrf24j40_setpromisc(FAR struct ieee802154_radio_s *ieee, + bool promisc); +static int mrf24j40_getpromisc(FAR struct ieee802154_radio_s *ieee, + FAR bool *promisc); +static int mrf24j40_setdevmode(FAR struct ieee802154_radio_s *ieee, + uint8_t mode); +static int mrf24j40_getdevmode(FAR struct ieee802154_radio_s *ieee, + FAR uint8_t *mode); +static int mrf24j40_settxpower(FAR struct ieee802154_radio_s *ieee, + int32_t txpwr); +static int mrf24j40_gettxpower(FAR struct ieee802154_radio_s *ieee, + FAR int32_t *txpwr); +static int mrf24j40_setcca(FAR struct ieee802154_radio_s *ieee, + FAR struct ieee802154_cca_s *cca); +static int mrf24j40_getcca(FAR struct ieee802154_radio_s *ieee, + FAR struct ieee802154_cca_s *cca); +static int mrf24j40_ioctl(FAR struct ieee802154_radio_s *ieee, int cmd, + unsigned long arg); +static int mrf24j40_energydetect(FAR struct ieee802154_radio_s *ieee, + FAR uint8_t *energy); +static int mrf24j40_rxenable(FAR struct ieee802154_radio_s *ieee, + bool state, FAR struct ieee802154_packet_s *packet); +static int mrf24j40_transmit(FAR struct ieee802154_radio_s *ieee, + FAR struct ieee802154_packet_s *packet); + +/**************************************************************************** + * Private Data + ****************************************************************************/ /* These are pointers to ALL registered MRF24J40 devices. * This table is used during irqs to find the context @@ -228,8 +253,6 @@ static const struct ieee802154_radioops_s mrf24j40_devops = * Private Functions ****************************************************************************/ -/* Hardware access routines */ - /**************************************************************************** * Name: mrf24j40_lock * @@ -240,9 +263,9 @@ static const struct ieee802154_radioops_s mrf24j40_devops = static void mrf24j40_lock(FAR struct spi_dev_s *spi) { - SPI_LOCK (spi, 1); - SPI_SETBITS (spi, 8); - SPI_SETMODE (spi, CONFIG_IEEE802154_MRF24J40_SPIMODE); + SPI_LOCK(spi, 1); + SPI_SETBITS(spi, 8); + SPI_SETMODE(spi, CONFIG_IEEE802154_MRF24J40_SPIMODE); SPI_SETFREQUENCY(spi, CONFIG_IEEE802154_MRF24J40_FREQUENCY); } @@ -267,7 +290,8 @@ static inline void mrf24j40_unlock(FAR struct spi_dev_s *spi) * ****************************************************************************/ -static void mrf24j40_setreg(FAR struct spi_dev_s *spi, uint32_t addr, uint8_t val) +static void mrf24j40_setreg(FAR struct spi_dev_s *spi, uint32_t addr, + uint8_t val) { uint8_t buf[3]; int len; @@ -342,8 +366,8 @@ static uint8_t mrf24j40_getreg(FAR struct spi_dev_s *spi, uint32_t addr) SPI_SELECT (spi, SPIDEV_IEEE802154, false); mrf24j40_unlock(spi); - /*wlinfo("r[%04X]=%02X\n", addr, rx[len-1]);*/ - return rx[len-1]; + /* wlinfo("r[%04X]=%02X\n", addr, rx[len - 1]); */ + return rx[len - 1]; } /**************************************************************************** @@ -457,12 +481,13 @@ static int mrf24j40_initialize(FAR struct mrf24j40_radio_s *dev) static int mrf24j40_setrxmode(FAR struct mrf24j40_radio_s *dev, int mode) { uint8_t reg; + if (mode < MRF24J40_RXMODE_NORMAL || mode > MRF24J40_RXMODE_NOCRC) { return -EINVAL; } - reg = mrf24j40_getreg(dev->spi, MRF24J40_RXMCR); + reg = mrf24j40_getreg(dev->spi, MRF24J40_RXMCR); reg &= ~0x03; reg |= mode; @@ -471,11 +496,13 @@ static int mrf24j40_setrxmode(FAR struct mrf24j40_radio_s *dev, int mode) if (mode != MRF24J40_RXMODE_NORMAL) { /* Promisc and error modes: Disable auto ACK */ + reg |= MRF24J40_RXMCR_NOACKRSP; } else { /* Normal mode : enable auto-ACK */ + reg &= ~MRF24J40_RXMCR_NOACKRSP; } @@ -486,8 +513,6 @@ static int mrf24j40_setrxmode(FAR struct mrf24j40_radio_s *dev, int mode) return OK; } -/* Publicized driver routines */ - /**************************************************************************** * Name: mrf24j40_setchannel * @@ -506,7 +531,8 @@ static int mrf24j40_setchannel(FAR struct ieee802154_radio_s *ieee, uint8_t chan) { FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; - if (chan<11 || chan>26) + + if (chan < 11 || chan > 26) { wlerr("ERROR: Invalid chan: %d\n",chan); return -EINVAL; @@ -640,10 +666,9 @@ static int mrf24j40_seteaddr(FAR struct ieee802154_radio_s *ieee, FAR uint8_t *eaddr) { FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; - int i; - for (i=0; i<8; i++) + for (i = 0; i < 8; i++) { mrf24j40_setreg(dev->spi, MRF24J40_EADR0 + i, eaddr[i]); dev->eaddr[i] = eaddr[i]; @@ -824,14 +849,36 @@ static int mrf24j40_settxpower(FAR struct ieee802154_radio_s *ieee, case -9: case -8: case -7: - case -6: reg |= 0x07; break; - case -5: reg |= 0x06; break; - case -4: reg |= 0x05; break; - case -3: reg |= 0x04; break; - case -2: reg |= 0x03; break; - case -1: reg |= 0x02; break; - case 0: reg |= 0x00; break; /* value 0x01 is 0.5 db, not used */ - default: return -EINVAL; + case -6: + reg |= 0x07; + break; + + case -5: + reg |= 0x06; + break; + + case -4: + reg |= 0x05; + break; + + case -3: + reg |= 0x04; + break; + + case -2: + reg |= 0x03; + break; + + case -1: + reg |= 0x02; + break; + + case 0: + reg |= 0x00; /* value 0x01 is 0.5 db, not used */ + break; + + default: + return -EINVAL; } mrf24j40_setreg(dev->spi, MRF24J40_RFCON3, reg); @@ -899,7 +946,6 @@ static int mrf24j40_setcca(FAR struct ieee802154_radio_s *ieee, mrf24j40_setreg(dev->spi, MRF24J40_BBREG2, mode); memcpy(&dev->cca, cca, sizeof(struct ieee802154_cca_s)); - return OK; } @@ -933,7 +979,7 @@ static int mrf24j40_regdump(FAR struct mrf24j40_radio_s *dev) { uint32_t i; char buf[4+16*3+2+1]; - int len=0; + int len = 0; wlinfo("Short regs:\n"); @@ -953,9 +999,9 @@ static int mrf24j40_regdump(FAR struct mrf24j40_radio_s *dev) } wlinfo("Long regs:\n"); - for (i=0x80000200;i<0x80000250;i++) + for (i = 0x80000200; i < 0x80000250; i++) { - if ((i&15)==0) + if ((i & 15) == 0) { len=sprintf(buf, "%02x: ",i&0xFF); } @@ -1043,7 +1089,6 @@ static int mrf24j40_energydetect(FAR struct ieee802154_radio_s *ieee, /* Back to automatic control */ mrf24j40_pacontrol(dev, MRF24J40_PA_AUTO); - return OK; } @@ -1057,13 +1102,14 @@ static int mrf24j40_energydetect(FAR struct ieee802154_radio_s *ieee, * ****************************************************************************/ -static int mrf24j40_transmit(FAR struct ieee802154_radio_s *ieee, FAR struct ieee802154_packet_s *packet) +static int mrf24j40_transmit(FAR struct ieee802154_radio_s *ieee, + FAR struct ieee802154_packet_s *packet) { FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; uint32_t addr; uint8_t reg; int ret; - int hlen = 3; /* include frame control and seq number */ + int hlen = 3; /* Include frame control and seq number */ uint8_t fc1, fc2; mrf24j40_pacontrol(dev, MRF24J40_PA_AUTO); @@ -1081,7 +1127,7 @@ static int mrf24j40_transmit(FAR struct ieee802154_radio_s *ieee, FAR struct iee fc1 = packet->data[0]; fc2 = packet->data[1]; - // wlinfo("fc1 %02X fc2 %02X\n", fc1,fc2); + //wlinfo("fc1 %02X fc2 %02X\n", fc1,fc2); if ((fc2 & IEEE802154_FC2_DADDR) == IEEE802154_DADDR_SHORT) { @@ -1111,7 +1157,7 @@ static int mrf24j40_transmit(FAR struct ieee802154_radio_s *ieee, FAR struct iee hlen += 8; /* Ext saddr */ } -// wlinfo("hlen %d\n",hlen); + //wlinfo("hlen %d\n",hlen); /* Header len, 0, TODO for security modes */ @@ -1166,6 +1212,7 @@ static void mrf24j40_irqwork_tx(FAR struct mrf24j40_radio_s *dev) reg = mrf24j40_getreg(dev->spi, MRF24J40_TXSTAT); /* 1 means it failed, we want 1 to mean it worked. */ + dev->ieee.txok = (reg & MRF24J40_TXSTAT_TXNSTAT) != MRF24J40_TXSTAT_TXNSTAT; dev->ieee.txretries = (reg & MRF24J40_TXSTAT_X_MASK) >> MRF24J40_TXSTAT_X_SHIFT; dev->ieee.txbusy = (reg & MRF24J40_TXSTAT_CCAFAIL) == MRF24J40_TXSTAT_CCAFAIL; @@ -1232,7 +1279,7 @@ static void mrf24j40_irqwork_rx(FAR struct mrf24j40_radio_s *dev) uint32_t index; uint8_t reg; - /*wlinfo("!\n");*/ + /* wlinfo("!\n"); */ /* Disable rx int */ @@ -1248,7 +1295,7 @@ static void mrf24j40_irqwork_rx(FAR struct mrf24j40_radio_s *dev) addr = MRF24J40_RXBUF_BASE; dev->ieee.rxbuf->len = mrf24j40_getreg(dev->spi, addr++); - /*wlinfo("len %3d\n", dev->ieee.rxbuf->len);*/ + /* wlinfo("len %3d\n", dev->ieee.rxbuf->len); */ for (index = 0; index < dev->ieee.rxbuf->len; index++) { @@ -1303,7 +1350,7 @@ static void mrf24j40_irqworker(FAR void *arg) /* Read and store INTSTAT - this clears the register. */ intstat = mrf24j40_getreg(dev->spi, MRF24J40_INTSTAT); -// wlinfo("INT%02X\n", intstat); + //wlinfo("INT%02X\n", intstat); /* Do work according to the pending interrupts */ @@ -1382,15 +1429,14 @@ static int mrf24j40_interrupt(int irq, FAR void *context) ****************************************************************************/ FAR struct ieee802154_radio_s *mrf24j40_init(FAR struct spi_dev_s *spi, - FAR const struct mrf24j40_lower_s *lower) + FAR const struct mrf24j40_lower_s *lower) { FAR struct mrf24j40_radio_s *dev; struct ieee802154_cca_s cca; #if 0 dev = kmm_zalloc(sizeof(struct mrf24j40_radio_s)); - - if (!dev) + if (dev == NULL) { return NULL; } diff --git a/drivers/wireless/ieee802154/mrf24j40.h b/drivers/wireless/ieee802154/mrf24j40.h index c530e61d63..62b2bee888 100644 --- a/drivers/wireless/ieee802154/mrf24j40.h +++ b/drivers/wireless/ieee802154/mrf24j40.h @@ -33,8 +33,8 @@ * ****************************************************************************/ -#ifndef __DRIVERS_IEEE802154_MRF24J40_H -#define __DRIVERS_IEEE802154_MRF24J40_H +#ifndef __DRIVERS_WIRELESS_IEEE802154_MRF24J40_H +#define __DRIVERS_WIRELESS_IEEE802154_MRF24J40_H /* MRF24J40 Registers *******************************************************/ @@ -214,4 +214,4 @@ #define MRF24J40_TXSTAT_X_SHIFT 6 #define MRF24J40_TXSTAT_X_MASK (3 << MRF24J40_TXSTAT_X_SHIFT) -#endif /* __DRIVERS_IEEE802154_MRF24J40_H */ +#endif /* __DRIVERS_WIRELESS_IEEE802154_MRF24J40_H */ -- GitLab From f449b45b5d19db6ab81d707b727f2456e8f39107 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 15 Mar 2017 14:59:58 -0600 Subject: [PATCH 056/990] Trivial spacing fix --- wireless/ieee802154/radio802154_device.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/wireless/ieee802154/radio802154_device.c b/wireless/ieee802154/radio802154_device.c index e925b1cf5e..feb4410465 100644 --- a/wireless/ieee802154/radio802154_device.c +++ b/wireless/ieee802154/radio802154_device.c @@ -88,7 +88,7 @@ static const struct file_operations radio802154dev_fops = radio802154dev_close, /* close */ radio802154dev_read , /* read */ radio802154dev_write, /* write */ - NULL, /* seek */ + NULL, /* seek */ radio802154dev_ioctl /* ioctl */ #ifndef CONFIG_DISABLE_POLL , NULL /* poll */ -- GitLab From 255673b9d097bdfa417a2c51c1eaaec019fcb78f Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 15 Mar 2017 15:16:16 -0600 Subject: [PATCH 057/990] Fix a typo introduced in Kconfig with last commit --- Kconfig | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Kconfig b/Kconfig index bbff98b262..1116ba6ccc 100644 --- a/Kconfig +++ b/Kconfig @@ -735,7 +735,7 @@ endif # DEBUG_NET config DEBUG_WIRELESS bool "Wireless Debug Features" default n - depends on WIRELESS | DRIVERS_WIRELESS + depends on WIRELESS || DRIVERS_WIRELESS ---help--- Enable DEBUG_WIRELESS debug features. -- GitLab From e897949e6d5e7e5bc001b1e2d6567550c60f00be Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 15 Mar 2017 15:47:26 -0600 Subject: [PATCH 058/990] Trivial correction of a typo in a comment. --- Kconfig | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Kconfig b/Kconfig index 1116ba6ccc..5496d5920a 100644 --- a/Kconfig +++ b/Kconfig @@ -737,7 +737,7 @@ config DEBUG_WIRELESS default n depends on WIRELESS || DRIVERS_WIRELESS ---help--- - Enable DEBUG_WIRELESS debug features. + Enable wireless debug features. if DEBUG_WIRELESS -- GitLab From fbd7e2ae34a9b4567e415b3e3cb72378baf19629 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 15 Mar 2017 16:08:56 -0600 Subject: [PATCH 059/990] Bring closer to NuttX coding standard. --- include/nuttx/wireless/ieee802154/at86rf23x.h | 6 +- .../wireless/ieee802154/ieee802154_mac.h | 322 ++++++++++-------- 2 files changed, 182 insertions(+), 146 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/at86rf23x.h b/include/nuttx/wireless/ieee802154/at86rf23x.h index 1ef6c909d2..b33e58020f 100644 --- a/include/nuttx/wireless/ieee802154/at86rf23x.h +++ b/include/nuttx/wireless/ieee802154/at86rf23x.h @@ -60,7 +60,8 @@ struct at86rf23x_lower_s #ifdef __cplusplus #define EXTERN extern "C" -extern "C" { +extern "C" +{ #else #define EXTERN extern #endif @@ -90,7 +91,8 @@ extern "C" { * ****************************************************************************/ -FAR struct ieee802154_radio_s *at86rf23x_init(FAR struct spi_dev_s *spi, FAR const struct at86rf23x_lower_s *lower); +FAR struct ieee802154_radio_s *at86rf23x_init(FAR struct spi_dev_s *spi, + FAR const struct at86rf23x_lower_s *lower); #undef EXTERN #ifdef __cplusplus diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index 439825391a..0cddb694bf 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -60,6 +60,36 @@ #define IEEE802154_SADDR_BCAST (uint16_t)0xFFFE #define IEEE802154_EADDR_UNSPEC (uint8_t*)"\xff\xff\xff\xff\xff\xff\xff\xff" +/* IEEE 802.15.4 PHY constants */ + +#define MAC802154_aMaxPHYPacketSize 127 +#define MAC802154_aTurnaroundTime 12 /*symbol periods*/ + +/* IEEE 802.15.4 MAC constants */ + +#define MAC802154_aBaseSlotDuration 60 +#define MAC802154_aNumSuperframeSlots 16 +#define MAC802154_aBaseSuperframeDuration (MAC802154_aBaseSlotDuration * MAC802154_aNumSuperframeSlots) +#define MAC802154_aMaxBE 5 +#define MAC802154_aMaxBeaconOverhead 75 +#define MAC802154_aMaxBeaconPayloadLength (MAC802154_aMaxPHYPacketSize - MAC802154_aMaxBeaconOverhead) +#define MAC802154_aGTSDescPersistenceTime 4 +#define MAC802154_aMaxFrameOverhead 25 +#define MAC802154_aMaxFrameResponseTime 1220 +#define MAC802154_aMaxFrameRetries 3 +#define MAC802154_aMaxLostBeacons 4 +#define MAC802154_aMaxMACFrameSize (MAC802154_aMaxPHYPacketSize - MAC802154_aMaxFrameOverhead) +#define MAC802154_aMaxSIFSFrameSize 18 +#define MAC802154_aMinCAPLength 440 +#define MAC802154_aMinLIFSPeriod 40 +#define MAC802154_aMinSIFSPeriod 12 +#define MAC802154_aResponseWaitTime (32 * MAC802154_aBaseSuperframeDuration) +#define MAC802154_aUnitBackoffPeriod 20 + +/**************************************************************************** + * Public Types + ****************************************************************************/ + /* IEEE 802.15.4 MAC status codes */ enum @@ -88,32 +118,8 @@ enum MAC802154_STATUS_UNSUPPORTED_ATTRIBUTE }; -/* IEEE 802.15.4 PHY constants */ -#define MAC802154_aMaxPHYPacketSize 127 -#define MAC802154_aTurnaroundTime 12 /*symbol periods*/ - -/* IEEE 802.15.4 MAC constants */ -#define MAC802154_aBaseSlotDuration 60 -#define MAC802154_aNumSuperframeSlots 16 -#define MAC802154_aBaseSuperframeDuration (MAC802154_aBaseSlotDuration * MAC802154_aNumSuperframeSlots) -#define MAC802154_aMaxBE 5 -#define MAC802154_aMaxBeaconOverhead 75 -#define MAC802154_aMaxBeaconPayloadLength (MAC802154_aMaxPHYPacketSize - MAC802154_aMaxBeaconOverhead) -#define MAC802154_aGTSDescPersistenceTime 4 -#define MAC802154_aMaxFrameOverhead 25 -#define MAC802154_aMaxFrameResponseTime 1220 -#define MAC802154_aMaxFrameRetries 3 -#define MAC802154_aMaxLostBeacons 4 -#define MAC802154_aMaxMACFrameSize (MAC802154_aMaxPHYPacketSize - MAC802154_aMaxFrameOverhead) -#define MAC802154_aMaxSIFSFrameSize 18 -#define MAC802154_aMinCAPLength 440 -#define MAC802154_aMinLIFSPeriod 40 -#define MAC802154_aMinSIFSPeriod 12 -#define MAC802154_aResponseWaitTime (32 * MAC802154_aBaseSuperframeDuration) -#define MAC802154_aUnitBackoffPeriod 20 - - /* IEEE 802.15.4 PHY/MAC PIB attributes IDs */ + enum { MAC802154_phyCurrentChannel = 0x00, @@ -166,90 +172,95 @@ struct ieee802154_addr_s { uint8_t ia_len; /* structure length, 0/2/8 */ uint16_t ia_panid; /* PAN identifier, can be IEEE802154_PAN_UNSPEC */ - union { + union + { uint16_t _ia_saddr; /* short address */ uint8_t _ia_eaddr[8]; /* extended address */ } ia_addr; + #define ia_saddr ia_addr._ia_saddr #define ia_eaddr ia_addr._ia_eaddr }; + #define IEEE802154_ADDRSTRLEN 22 /* (2*2+1+8*2, PPPP/EEEEEEEEEEEEEEEE) */ /* Operations */ -struct ieee802154_mac_s; +struct ieee802154_mac_s; /* Forward reference */ struct ieee802154_macops_s { /* Requests, confirmed asynchronously via callbacks */ - CODE int req_data (struct ieee802154_mac_s *mac, /* Transmit a data frame */ - uint8_t handle, - uint8_t *buf, - int len); + /* Transmit a data frame */ - CODE int req_purge (struct ieee802154_mac_s *mac, /* Cancel transmission of a data frame */ - uint8_t handle); + CODE int (*req_data)(FAR struct ieee802154_mac_s *mac, uint8_t handle, + FAR uint8_t *buf, int len); - CODE int req_associate (struct ieee802154_mac_s *mac, /* Start association with coordinator */ - uint16_t panid, + /* Cancel transmission of a data frame */ + + CODE int (*req_purge)(FAR struct ieee802154_mac_s *mac, uint8_t handle); + + /* Start association with coordinator */ + + CODE int (*req_associate)(FAR struct ieee802154_mac_s *mac, uint16_t panid, uint8_t *coordeadr); - CODE int req_disassociate(struct ieee802154_mac_s *mac, /* Start disassociation with coordinator */ - uint8_t *eadr, - uint8_t reason); + /* Start disassociation with coordinator */ + + CODE int (*req_disassociate)(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *eadr, uint8_t reason); + + /* Read the PIB */ + + CODE int (*req_get)(FAR struct ieee802154_mac_s *mac, int attribute); - CODE int req_get (struct ieee802154_mac_s *mac, /* Read the PIB */ - int attribute); + /* Allocate or deallocate a GTS */ - CODE int req_gts (struct ieee802154_mac_s *mac, /* Allocate or deallocate a GTS */ - uint8_t* characteristics); + CODE int (*req_gts)(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *characteristics); - CODE int req_reset (struct ieee802154_mac_s *mac, /* MAC layer reset */ - bool setdefaults); + /* MAC layer reset */ - CODE int req_rxenable (struct ieee802154_mac_s *mac, /* PHY receiver control */ - bool deferrable, - int ontime, - int duration); + CODE int (*req_reset)(FAR struct ieee802154_mac_s *mac, bool setdefaults); - CODE int req_scan (struct ieee802154_mac_s *mac, /* Start a network scan */ - uint8_t type, - uint32_t channels, - int duration); + /* PHY receiver control */ - CODE int req_set (struct ieee802154_mac_s *mac, /* Change the PIB */ - int attribute, - uint8_t *value, - int valuelen); + CODE int (*req_rxenable)(FAR struct ieee802154_mac_s *mac, bool deferrable, + int ontime, int duration); - CODE int req_start (struct ieee802154_mac_s *mac, - uint16_t panid, - int channel, - uint8_t bo, - uint8_t fo, - bool coord, - bool batext, - bool realign); + /* Start a network scan */ - CODE int req_sync (struct ieee802154_mac_s *mac, - int channel, - bool track); + CODE int (*req_scan)(FAR struct ieee802154_mac_s *mac, uint8_t type, + uint32_t channels, int duration); - CODE int req_poll (struct ieee802154_mac_s *mac, - uint8_t *coordaddr); + /* Change the PIB */ + + CODE int (*req_set)(FAR struct ieee802154_mac_s *mac, int attribute, + FAR uint8_t *value, int valuelen); + + CODE int (*req_start)(FAR struct ieee802154_mac_s *mac, uint16_t panid, + int channel, uint8_t bo, uint8_t fo, bool coord, + bool batext, bool realign); + + CODE int (*req_sync)(FAR struct ieee802154_mac_s *mac, int channel, + bool track); + + CODE int (*req_poll)(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *coordaddr); /* Synchronous Responses to Indications received via callbacks */ - CODE int rsp_associate (struct ieee802154_mac_s *mac, /* Reply to an association request */ - uint8_t eadr, - uint16_t saddr, - int status); + /* Reply to an association request */ - CODE int rsp_orphan (struct ieee802154_mac_s *mac, /* Orphan device management */ - uint8_t *orphanaddr, - uint16_t saddr, - bool associated); + CODE int (*rsp_associate)(FAR struct ieee802154_mac_s *mac, uint8_t eadr, + uint16_t saddr, int status); + + /* Orphan device management */ + + CODE int (*rsp_orphan)(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *orphanaddr, uint16_t saddr, + bool associated); }; /* Notifications */ @@ -258,74 +269,95 @@ struct ieee802154_maccb_s { /* Asynchronous confirmations to requests */ - CODE int conf_data (struct ieee802154_mac_s *mac, /* Data frame was received by remote device */ - uint8_t *buf, - int len); - CODE int conf_purge (struct ieee802154_mac_s *mac, /* Data frame was purged */ - uint8_t handle, - int status); - CODE int conf_associate (struct ieee802154_mac_s *mac, /* Association request completed */ - uint16_t saddr, - int status); - CODE int conf_disassociate(struct ieee802154_mac_s *mac, /* Disassociation request completed */ - int status); - CODE int conf_get (struct ieee802154_mac_s *mac, /* PIB data returned */ - int status, - int attribute, - uint8_t *value, - int valuelen); - CODE int conf_gts (struct ieee802154_mac_s *mac, /* GTS management completed */ - uint8_t *characteristics, - int status); - CODE int conf_reset (struct ieee802154_mac_s *mac, /* MAC reset completed */ - int status); - CODE int conf_rxenable (struct ieee802154_mac_s *mac, - int status); - CODE int conf_scan (struct ieee802154_mac_s *mac, - int status, - uint8_t type, - uint32_t unscanned, - int rsltsize, - uint8_t *edlist, - uint8_t *pandescs); - CODE int conf_set (struct ieee802154_mac_s *mac, - int status, int attribute); - CODE int conf_start (struct ieee802154_mac_s *mac, - int status); - CODE int conf_poll (struct ieee802154_mac_s *mac, - int status); + /* Data frame was received by remote device */ + + CODE int (*conf_data)(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *buf, int len); + + /* Data frame was purged */ + + CODE int (*conf_purge)(FAR struct ieee802154_mac_s *mac, uint8_t handle, + int status); + + /* Association request completed */ + + CODE int (*conf_associate)(FAR struct ieee802154_mac_s *mac, + uint16_t saddr, int status); + + /* Disassociation request completed */ + + CODE int (*conf_disassociate)(FAR struct ieee802154_mac_s *mac, + int status); + + /* PIB data returned */ + + CODE int (*conf_get)(FAR struct ieee802154_mac_s *mac, int status, + int attribute, FAR uint8_t *value, + int valuelen); + + /* GTS management completed */ + + CODE int (*conf_gts)(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *characteristics, int status); + + /* MAC reset completed */ + + CODE int (*conf_reset)(FAR struct ieee802154_mac_s *mac, int status); + + CODE int (*conf_rxenable)(FAR struct ieee802154_mac_s *mac, int status); + + CODE int (*conf_scan)(FAR struct ieee802154_mac_s *mac, int status, + uint8_t type, uint32_t unscanned, int rsltsize, + FAR uint8_t *edlist, FAR uint8_t *pandescs); + + CODE int (*conf_set)(FAR struct ieee802154_mac_s *mac, int status, + int attribute); + + CODE int (*conf_start)(FAR struct ieee802154_mac_s *mac, int status); + + CODE int (*conf_poll)(FAR struct ieee802154_mac_s *mac, int status); /* Asynchronous event indications, replied to synchronously with responses */ - CODE int ind_data (struct ieee802154_mac_s *mac, /* Data frame received */ - uint8_t *buf, - int len); - CODE int ind_associate (struct ieee802154_mac_s *mac, /* Association request received */ - uint16_t clipanid, - uint8_t *clieaddr); - CODE int ind_disassociate (struct ieee802154_mac_s *mac, /* Disassociation request received */ - uint8_t *eadr, - uint8_t reason); - CODE int ind_beaconnotify (struct ieee802154_mac_s *mac, /* Beacon notification */ - uint8_t *bsn, - uint_t *pandesc, - uint8_t *sdu, - int sdulen); - CODE int ind_gts (struct ieee802154_mac_s *mac, /* GTS management request received */ - uint8_t *devaddr, - uint8_t *characteristics); - CODE int ind_orphan (struct ieee802154_mac_s *mac, /* Orphan device detected */ - uint8_t *orphanaddr); - CODE int ind_commstatus (struct ieee802154_mac_s *mac, - uint16_t panid, - uint8_t *src, - uint8_t *dst, - int status); - CODE int ind_syncloss (struct ieee802154_mac_s *mac, - int reason); + /* Data frame received */ + + CODE int (*ind_data)(FAR struct ieee802154_mac_s *mac, FAR uint8_t *buf, + int len); + + /* Association request received */ + + CODE int (*ind_associate)(FAR struct ieee802154_mac_s *mac, + uint16_t clipanid, FAR uint8_t *clieaddr); + + /* Disassociation request received */ + + CODE int (*ind_disassociate)(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *eadr, uint8_t reason); + + /* Beacon notification */ + + CODE int (*ind_beaconnotify)(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *bsn, FAR uint_t *pandesc, + FAR uint8_t *sdu, int sdulen); + + /* GTS management request received */ + + CODE int (*ind_gts)(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *devaddr, FAR uint8_t *characteristics); + + /* Orphan device detected */ + + CODE int (*ind_orphan)(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *orphanaddr); + + CODE int (*ind_commstatus)(FAR struct ieee802154_mac_s *mac, + uint16_t panid, FAR uint8_t *src, + FAR uint8_t *dst, int status); + + CODE int (*ind_syncloss)(FAR struct ieee802154_mac_s *mac, int reason); }; -struct ieee802154_radio_s; +struct ieee802154_radio_s; /* Forware reference */ struct ieee802154_mac_s { @@ -346,8 +378,7 @@ extern "C" * Public Function Prototypes ****************************************************************************/ -/* - * Instanciate a 802.15.4 MAC from a 802.15.4 radio device. +/* Instanciate a 802.15.4 MAC from a 802.15.4 radio device. * To create a 802.15.4 MAC, you need to pass: * - an instance of a radio driver in radiodev * - a pointer to a structure that contains MAC callback routines to @@ -356,9 +387,12 @@ extern "C" * responses. * This API does not create any device accessible to userspace. If you want to * call these APIs from userspace, you have to wrap your mac in a character - * device via mac802154_device.c . + * device via mac802154_device.c . */ -FAR struct ieee802154_mac_s * mac802154_register(FAR struct ieee802154_radio_s *radiodev, struct ieee802154_maccb_s *callbacks); + +FAR struct ieee802154_mac_s * + mac802154_register(FAR struct ieee802154_radio_s *radiodev, + FAR struct ieee802154_maccb_s *callbacks); #undef EXTERN #ifdef __cplusplus -- GitLab From 89a907a5827aec756925b06001f8ecc2992b146e Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 15 Mar 2017 16:11:36 -0600 Subject: [PATCH 060/990] Bring closer to NuttX coding standard. --- .../wireless/ieee802154/ieee802154_radio.h | 25 +++++++++++++------ include/nuttx/wireless/ieee802154/mrf24j40.h | 5 ++-- 2 files changed, 20 insertions(+), 10 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_radio.h b/include/nuttx/wireless/ieee802154/ieee802154_radio.h index 06276b2870..7adbbfd7ae 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_radio.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_radio.h @@ -86,7 +86,8 @@ struct ieee802154_radio_s; struct ieee802154_radioops_s { - CODE int (*setchannel)(FAR struct ieee802154_radio_s *dev, uint8_t channel); + CODE int (*setchannel)(FAR struct ieee802154_radio_s *dev, + uint8_t channel); CODE int (*getchannel)(FAR struct ieee802154_radio_s *dev, FAR uint8_t *channel); @@ -107,7 +108,8 @@ struct ieee802154_radioops_s CODE int (*getpromisc)(FAR struct ieee802154_radio_s *dev, FAR bool *promisc); - CODE int (*setdevmode)(FAR struct ieee802154_radio_s *dev, uint8_t devmode); + CODE int (*setdevmode)(FAR struct ieee802154_radio_s *dev, + uint8_t devmode); CODE int (*getdevmode)(FAR struct ieee802154_radio_s *dev, FAR uint8_t *devmode); @@ -139,14 +141,21 @@ struct ieee802154_radio_s /* Packet reception management */ - struct ieee802154_packet_s *rxbuf; /* packet reception buffer, filled by rx interrupt, NULL if rx not enabled */ - sem_t rxsem; /* Semaphore posted after reception of a packet */ + struct ieee802154_packet_s *rxbuf; /* packet reception buffer, filled by + * rx interrupt, NULL if rx not enabled */ + sem_t rxsem; /* Semaphore posted after reception of + * a packet */ /* Packet transmission management */ - bool txok; /* Last transmission status, filled by tx interrupt */ - bool txbusy; /* Last transmission failed because channel busy */ - uint8_t txretries; /* Last transmission required this much retries */ - sem_t txsem; /* Semaphore posted after transmission of a packet */ + + bool txok; /* Last transmission status, filled by + * tx interrupt */ + bool txbusy; /* Last transmission failed because + * channel busy */ + uint8_t txretries; /* Last transmission required this much + * retries */ + sem_t txsem; /* Semaphore posted after transmission + * of a packet */ }; #ifdef __cplusplus diff --git a/include/nuttx/wireless/ieee802154/mrf24j40.h b/include/nuttx/wireless/ieee802154/mrf24j40.h index 167f125b33..1871769c82 100644 --- a/include/nuttx/wireless/ieee802154/mrf24j40.h +++ b/include/nuttx/wireless/ieee802154/mrf24j40.h @@ -100,8 +100,9 @@ extern "C" ****************************************************************************/ struct spi_dev_s; /* Forward reference */ -FAR struct ieee802154_radio_s *mrf24j40_init(FAR struct spi_dev_s *spi, - FAR const struct mrf24j40_lower_s *lower); +FAR struct ieee802154_radio_s * + mrf24j40_init(FAR struct spi_dev_s *spi, + FAR const struct mrf24j40_lower_s *lower); #undef EXTERN #ifdef __cplusplus -- GitLab From a492a05e34fe1f6bdbb701135d02ee41a2b4c101 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Wed, 15 Mar 2017 18:14:56 -0400 Subject: [PATCH 061/990] fs/ioctl.h: Changes _MAC854 to _MAC802154 and creates _RADIO802154 --- include/nuttx/fs/ioctl.h | 15 +++++++++++---- 1 file changed, 11 insertions(+), 4 deletions(-) diff --git a/include/nuttx/fs/ioctl.h b/include/nuttx/fs/ioctl.h index 18f20b3d43..35265fad08 100644 --- a/include/nuttx/fs/ioctl.h +++ b/include/nuttx/fs/ioctl.h @@ -86,7 +86,8 @@ #define _SPIBASE (0x2100) /* SPI driver commands */ #define _GPIOBASE (0x2200) /* GPIO driver commands */ #define _CLIOCBASE (0x1200) /* Contactless modules ioctl commands */ -#define _MAC854BASE (0x2300) /* 802.15.4 device ioctl commands */ +#define _MAC802154BASE (0x2300) /* 802.15.4 MAC ioctl commands */ +#define _RADIO802154BASE(0x2400) /* 802.15.4 Radio ioctl commands */ /* boardctl() commands share the same number space */ @@ -403,10 +404,16 @@ #define _CLIOC(nr) _IOC(_CLIOCBASE,nr) /* 802.15.4 MAC driver ioctl definitions *******************************************/ -/* (see nuttx/ieee802154/ieee802154_dev.h */ +/* (see nuttx/include/wireless/ieee802154/ieee802154_mac.h */ -#define _MAC854IOCVALID(c) (_IOC_TYPE(c)==_MAC854BASE) -#define _MAC854IOC(nr) _IOC(_MAC854BASE,nr) +#define _MAC802154IOCVALID(c) (_IOC_TYPE(c)==_MAC802154BASE) +#define _MAC802154IOC(nr) _IOC(_MAC802154BASE,nr) + +/* 802.15.4 Radio driver ioctl definitions *******************************************/ +/* (see nuttx/ieee802154/wireless/ieee802154_radio.h */ + +#define _RADIO802154IOCVALID(c) (_IOC_TYPE(c)==_RADIO802154BASE) +#define _RADIO802154IOC(nr) _IOC(_RADIO802154BASE,nr) /* boardctl() command definitions *******************************************/ -- GitLab From f9c22461c45234ef628c902fdc50b93b05a0db77 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 15 Mar 2017 16:38:09 -0600 Subject: [PATCH 062/990] include/nuttx/fs/ioctl.h: Fix IOCTL numbering --- include/nuttx/fs/ioctl.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/nuttx/fs/ioctl.h b/include/nuttx/fs/ioctl.h index c5d25cd212..5582ccd0fe 100644 --- a/include/nuttx/fs/ioctl.h +++ b/include/nuttx/fs/ioctl.h @@ -85,7 +85,7 @@ #define _I2CBASE (0x2000) /* I2C driver commands */ #define _SPIBASE (0x2100) /* SPI driver commands */ #define _GPIOBASE (0x2200) /* GPIO driver commands */ -#define _CLIOCBASE (0x1200) /* Contactless modules ioctl commands */ +#define _CLIOCBASE (0x2300) /* Contactless modules ioctl commands */ /* boardctl() commands share the same number space */ -- GitLab From 059e398185c3861406a9e4350ff719f1fb226e53 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 15 Mar 2017 18:50:48 -0600 Subject: [PATCH 063/990] XMC4xxx: A few more SCU register bit definitions. --- arch/arm/src/xmc4/chip/xmc4_scu.h | 132 ++++++++++++++++++++++++++---- 1 file changed, 117 insertions(+), 15 deletions(-) diff --git a/arch/arm/src/xmc4/chip/xmc4_scu.h b/arch/arm/src/xmc4/chip/xmc4_scu.h index 87b11f3753..8f6f89cc4a 100644 --- a/arch/arm/src/xmc4/chip/xmc4_scu.h +++ b/arch/arm/src/xmc4/chip/xmc4_scu.h @@ -326,9 +326,9 @@ /* Oscillator Control SCU Registers */ -#define XMC4_OSCU_OSCHPSTAT (XMC4_SCU_OSC_BASE+XMC4_OSCU_OSCHPSTAT_OFFSET) -#define XMC4_OSCU_OSCHPCTRL (XMC4_SCU_OSC_BASE+XMC4_OSCU_OSCHPCTRL_OFFSET) -#define XMC4_OSCU_CLKCALCONST (XMC4_SCU_OSC_BASE+XMC4_OSCU_CLKCALCONST_OFFSET) +#define XMC4_SCU_OSCHPSTAT (XMC4_SCU_OSC_BASE+XMC4_SCU_OSCHPSTAT_OFFSET) +#define XMC4_SCU_OSCHPCTRL (XMC4_SCU_OSC_BASE+XMC4_SCU_OSCHPCTRL_OFFSET) +#define XMC4_SCU_CLKCALCONST (XMC4_SCU_OSC_BASE+XMC4_SCU_CLKCALCONST_OFFSET) /* PLL Control SCU Registers */ @@ -370,8 +370,23 @@ #define SCU_G0ORCEN_ /* Out-Of-Range Comparator Enable Register 1 */ #define SCU_G1ORCEN_ + /* Mirror Update Status Register */ -#define SCU_MIRRSTS_ + +#define SCU_MIRRSTS_HDCLR (1 << 1) /* Bit 1: HDCLR Mirror Register Write Status */ +#define SCU_MIRRSTS_HDSET (1 << 2) /* Bit 2: HDSET Mirror Register Write Status */ +#define SCU_MIRRSTS_HDCR (1 << 3) /* Bit 3: HDCR Mirror Register Write Status */ +#define SCU_MIRRSTS_OSCSICTRL (1 << 5) /* Bit 5: OSCSICTRL Mirror Register Write Status */ +#define SCU_MIRRSTS_OSCULSTAT (1 << 6) /* Bit 6: OSCULSTAT Mirror Register Write Status */ +#define SCU_MIRRSTS_OSCULCTRL (1 << 7) /* Bit 7: OSCULCTRL Mirror Register Write Status */ +#define SCU_MIRRSTS_RTC_CTR (1 << 8) /* Bit 8: RTC CTR Mirror Register Write Status */ +#define SCU_MIRRSTS_RTC_ATIM0 (1 << 9) /* Bit 9: RTC ATIM0 Mirror Register Write Status */ +#define SCU_MIRRSTS_RTC_ATIM1 (1 << 10) /* Bit 10: RTC ATIM1 Mirror Register Write Status */ +#define SCU_MIRRSTS_RTC_TIM0 (1 << 11) /* Bit 11: RTC TIM0 Mirror Register Write Status */ +#define SCU_MIRRSTS_RTC_TIM1 (1 << 12) /* Bit 12: RTC TIM1 Mirror Register Write Status */ +#define SCU_MIRRSTS_RMX (1 << 13) /* Bit 13: Retention Memory Access Register Update Status */ +#define SCU_MIRRSTS_RTC_MSKSR (1 << 14) /* Bit 14: RTC MSKSSR Mirror Register Write Status */ +#define SCU_MIRRSTS_RTC_CLRSR (1 << 15) /* Bit 15: RTC CLRSR Mirror Register Write Status */ /* Ethernet Control SCU Resters */ @@ -452,22 +467,93 @@ /* Power Monitor Value */ #define SCU_PWRMON_ -/* HCU Registers */ - +/* Hibernation SCU Registers */ /* Hibernate Domain Status Register */ -#define SCU_HDSTAT_ + +#define SCU_HDSTAT_EPEV (1 << 0) /* Bit 0: Wake-up Pin Event Positive Edge Status */ +#define SCU_HDSTAT_ENEV (1 << 1) /* Bit 1: Wake-up Pin Event Negative Edge Status */ +#define SCU_HDSTAT_RTCEV (1 << 2) /* Bit 2: RTC Event Status */ +#define SCU_HDSTAT_ULPWDG (1 << 3) /* Bit 3: ULP WDG Alarm Status */ +#define SCU_HDSTAT_HIBNOUT (1 << 4) /* Bit 3: Hibernate Control Status */ + /* Hibernate Domain Status Clear Register */ -#define SCU_HDCLR_ + +#define SCU_HDCLR_EPEV (1 << 0) /* Bit 0: Wake-up Pin Event Positive Edge Clear */ +#define SCU_HDCLR_ENEV (1 << 1) /* Bit 1: Wake-up Pin Event Negative Edge Clear */ +#define SCU_HDCLR_RTCEV (1 << 2) /* Bit 2: RTC Event Clear */ +#define SCU_HDCLR_ULPWDG (1 << 3) /* Bit 3: ULP WDG Alarm Clear */ + /* Hibernate Domain Status Set Register */ -#define SCU_HDSET_ + +#define SCU_HDSET_EPEV (1 << 0) /* Bit 0: Wake-up Pin Event Positive Edge Set */ +#define SCU_HDSET_ENEV (1 << 1) /* Bit 1: Wake-up Pin Event Negative Edge Set */ +#define SCU_HDSET_RTCEV (1 << 2) /* Bit 2: RTC Event Set */ +#define SCU_HDSET_ULPWDG (1 << 3) /* Bit 3: ULP WDG Alarm Set */ + /* Hibernate Domain Control Register */ -#define SCU_HDCR_ + +#define SCU_HDCR_WKPEP (1 << 0) /* Bit 0: Wake-Up on Pin Event Positive Edge Enable */ +#define SCU_HDCR_WKPEN (1 << 1) /* Bit 1: Wake-up on Pin Event Negative Edge Enable */ +#define SCU_HDCR_RTCE (1 << 2) /* Bit 2: Wake-up on RTC Event Enable */ +#define SCU_HDCR_ULPWDGEN (1 << 3) /* Bit 3: ULP WDG Alarm Enable */ +#define SCU_HDCR_HIB (1 << 4) /* Bit 4: Hibernate Request Value Set */ +#define SCU_HDCR_RCS (1 << 6) /* Bit 6: fRTC Clock Selection */ +# define SCU_HDCR_RCS_OSI (0) /* 0=fOSI */ +# define SCU_HDCR_RCS_ULP (1 << 6) /* 1=fULP */ +#define SCU_HDCR_STDBYSEL (1 << 7) /* Bit 7: fSTDBY Clock Selection */ +# define SCU_HDCR_STDBYSEL_OSI (0) /* 0=fOSI */ +# define SCU_HDCR_STDBYSEL_ULP (1 << 7) /* 1=fULP */ +#define SCU_HDCR_WKUPSEL (1 << 8) /* Bit 8: Wake-Up from Hibernate Trigger Input Select */ +# define SCU_HDCR_WKUPSEL_HIBIO1 (0) /* 0=HIB_IO_1 pin selected */ +# define SCU_HDCR_WKUPSEL_HIBIO0 (1 << 8) /* 1=HIB_IO_0 pin selected */ +#define SCU_HDCR_GPI0SEL (1 << 10) /* Bit 10: General Purpose Input 0 Selection */ +# define SCU_HDCR_GPIOSEL_HIBIO1 (0) /* 0=HIB_IO_1 pin selected */ +# define SCU_HDCR_GPIOSEL_HIBIO0 (1 << 10) /* 1=HIB_IO_0 pin selected */ +#define SCU_HDCR_HIBIO0POL (1 << 12) /* Bit 12: HIBIO0 Polarity Set */ +# define SCU_HDCR_HIBIO0POL_DIR (0) /* 0=Direct */ +# define SCU_HDCR_HIBIO0POL_INV (1 << 12) /* 1=Inverted */ +#define SCU_HDCR_HIBIO1POL (1 << 13) /* Bit 13: HIBIO1 Polarity Set */ +# define SCU_HDCR_HIBIO1POL_DIR (0) /* 0=Direct */ +# define SCU_HDCR_HIBIO1POL_INV (1 << 13) /* 1=Inverted */ +#define SCU_HDCR_HIBIO0SEL_SHIFT (16) /* Bits 16-19: HIB_IO_0 Pin I/O Control */ +#define SCU_HDCR_HIBIO0SEL_MASK (15 << SCU_HDCR_HIBIO0SEL_SHIFT) +# define SCU_HDCR_HIBIO0SEL_DIR (0 << SCU_HDCR_HIBIO0SEL_SHIFT) /* Direct input */ +# define SCU_HDCR_HIBIO0SEL_DIRPD (1 << SCU_HDCR_HIBIO0SEL_SHIFT) /* Direct input, Input pull-down */ +# define SCU_HDCR_HIBIO0SEL_DIRPU (2 << SCU_HDCR_HIBIO0SEL_SHIFT) /* Direct input, Input pull-up */ +# define SCU_HDCR_HIBIO0SEL_PP (8 << SCU_HDCR_HIBIO0SEL_SHIFT) /* Push-pull HIB Control output */ +# define SCU_HDCR_HIBIO0SEL_PPWDT (9 << SCU_HDCR_HIBIO0SEL_SHIFT) /* Push-pull WDT service output */ +# define SCU_HDCR_HIBIO0SEL_PPGPIO (10 << SCU_HDCR_HIBIO0SEL_SHIFT) /* Push-pull GPIO output */ +# define SCU_HDCR_HIBIO0SEL_OD (12 << SCU_HDCR_HIBIO0SEL_SHIFT) /* Open-drain HIB Control output */ +# define SCU_HDCR_HIBIO0SEL_ODWDT (13 << SCU_HDCR_HIBIO0SEL_SHIFT) /* Open-drain WDT service output */ +# define SCU_HDCR_HIBIO0SEL_ODGPIO (14 << SCU_HDCR_HIBIO0SEL_SHIFT) /* Open-drain GPIO output */ +#define SCU_HDCR_HIBIO1SEL_SHIFT (20) /* Bits 20-23: HIB_IO_1 Pin I/O Control */ +#define SCU_HDCR_HIBIO1SEL_MASK (15 << SCU_HDCR_HIBIO1SEL_SHIFT) +# define SCU_HDCR_HIBIO1SEL_DIR (0 << SCU_HDCR_HIBIO1SEL_SHIFT) /* Direct input */ +# define SCU_HDCR_HIBIO1SEL_DIRPD (1 << SCU_HDCR_HIBIO1SEL_SHIFT) /* Direct input, Input pull-down */ +# define SCU_HDCR_HIBIO1SEL_DIRPU (2 << SCU_HDCR_HIBIO1SEL_SHIFT) /* Direct input, Input pull-up */ +# define SCU_HDCR_HIBIO1SEL_PP (8 << SCU_HDCR_HIBIO1SEL_SHIFT) /* Push-pull HIB Control output */ +# define SCU_HDCR_HIBIO1SEL_PPWDT (9 << SCU_HDCR_HIBIO1SEL_SHIFT) /* Push-pull WDT service output */ +# define SCU_HDCR_HIBIO1SEL_PPGPIO (10 << SCU_HDCR_HIBIO1SEL_SHIFT) /* Push-pull GPIO output */ +# define SCU_HDCR_HIBIO1SEL_OD (12 << SCU_HDCR_HIBIO1SEL_SHIFT) /* Open-drain HIB Control output */ +# define SCU_HDCR_HIBIO1SEL_ODWDT (13 << SCU_HDCR_HIBIO1SEL_SHIFT) /* Open-drain WDT service output */ +# define SCU_HDCR_HIBIO1SEL_ODGPIO (14 << SCU_HDCR_HIBIO1SEL_SHIFT) /* Open-drain GPIO output */ + /* Internal 32.768 kHz Clock Source Control Register */ #define SCU_OSCSICTRL_ + /* OSC_ULP Status Register */ -#define SCU_OSCULSTAT_ + +#define SCU_OSCULSTAT_X1D (1 << 0) /* Bit 0: XTAL1 Data Value */ + /* OSC_ULP Control Register */ -#define SCU_OSCULCTRL_ + +#define SCU_OSCULCTRL_X1DEN (1 << 0) /* Bit 0: XTAL1 Data General Purpose Input Enable */ +#define SCU_OSCULCTRL_MODE_SHIFT (4) /* Bits 4-5: Oscillator Mode */ +#define SCU_OSCULCTRL_MODE_MASK (3 << SCU_OSCULCTRL_MODE_SHIFT) +# define SCU_OSCULCTRL_MODE_OPER (0 << SCU_OSCULCTRL_MODE_SHIFT) /* OSC enabled in operation */ +# define SCU_OSCULCTRL_MODE_BYPASS (1 << SCU_OSCULCTRL_MODE_SHIFT) /* OSC enabled in bypass */ +# define SCU_OSCULCTRL_MODE_PDN (2 << SCU_OSCULCTRL_MODE_SHIFT) /* OSC power down */ +# define SCU_OSCULCTRL_MODE_PDNGPI (3 << SCU_OSCULCTRL_MODE_SHIFT) /* OSC power down, GPI possible */ /* Reset SCU Registers */ @@ -592,11 +678,27 @@ /* Oscillator Control SCU Registers */ /* OSC_HP Status Register */ -#define OSCU_OSCHPSTAT_ +#define SCU_OSCHPSTAT_ + /* OSC_HP Control Register */ -#define OSCU_OSCHPCTRL_ + +#define SCU_OSCHPCTRL_X1DEN (1 << 0) /* Bit 0: XTAL1 Data Enable */ +#define SCU_OSCHPCTRL_SHBY (1 << 1) /* Bit 1: Shaper Bypass */ +#define SCU_OSCHPCTRL_GAINSEL_SHIFT (2) /* Bits 2-3: */ +#define SCU_OSCHPCTRL_GAINSEL_MASK (3 << SCU_OSCHPCTRL_GAINSEL_SHIFT) +# define SCU_OSCHPCTRL_GAINSEL(n) ((uint32_t)(n) << SCU_OSCHPCTRL_GAINSEL_SHIFT) +#define SCU_OSCHPCTRL_MODE_SHIFT (4) +#define SCU_OSCHPCTRL_MODE_MASK (3 << SCU_OSCHPCTRL_MODE_SHIFT) +# define SCU_OSCHPCTRL_MODE_XTAL (0 << SCU_OSCHPCTRL_MODE_SHIFT) /* External Crystal Mode */ +# define SCU_OSCHPCTRL_MODE_DIS (1 << SCU_OSCHPCTRL_MODE_SHIFT) /* OSC is disabled */ +# define SCU_OSCHPCTRL_MODE_EXTIN (2 << SCU_OSCHPCTRL_MODE_SHIFT) /* External Input Clock Mode */ +# define SCU_OSCHPCTRL_MODE_DISPSM (3 << SCU_OSCHPCTRL_MODE_SHIFT) /* OSC is disabled, Power-Saving Mode */ +#define SCU_OSCHPCTRL_OSCVAL_SHIFT (16) +#define SCU_OSCHPCTRL_OSCVAL_MASK (15 << SCU_OSCHPCTRL_OSCVAL_SHIFT) +# define SCU_OSCHPCTRL_OSCVAL(n) ((uint32_t)((n)-1) << SCU_OSCHPCTRL_OSCVAL_SHIFT) + /* Clock Calibration Constant Register */ -#define OSCU_CLKCALCONST_ +#define SCU_CLKCALCONST_ /* PLL Control SCU Registers */ -- GitLab From 3cc2a4f7c9bb495da6c59f373f8d0e7672e4ee13 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Wed, 15 Mar 2017 14:02:55 -1000 Subject: [PATCH 064/990] sem_holder: Fixes improper restoration of base_priority in the case of CONFIG_SEM_PREALLOCHOLDERS=0 The call to sem_restorebaseprio_task context switches in the sem_foreachholder(sem, sem_restoreholderprioB, stcb); call prior to releasing the holder. So the running task is left as a holder as is the started task. Leaving both slots filled Thus failing to perforem the boost/or restoration on the correct tcb. This PR fixes this by releasing the running task slot prior to reprioritization that can lead to the context switch. To faclitate this, the interface to sem_restorebaseprio needed to take the tcb from the holder prior to the holder being freed. In the failure case where sched_verifytcb fails it added the overhead of looking up the holder. There is also the adfitinal thunking on the foreach to get from holer to holder->tcb. An alternate approach could be to leve the interface the same and allocate a holder on the stack of sem_restoreholderprioB copy the sem's holder to it, free it as is done in this pr and and then pass that address sem_restoreholderprio as the holder. It could then get the holder's tcb but we would keep the same sem_findholder in sched_verifytcb. --- sched/semaphore/sem_holder.c | 71 +++++++++++++++++++++++++++--------- 1 file changed, 53 insertions(+), 18 deletions(-) diff --git a/sched/semaphore/sem_holder.c b/sched/semaphore/sem_holder.c index eaf443342d..bca4b4429b 100644 --- a/sched/semaphore/sem_holder.c +++ b/sched/semaphore/sem_holder.c @@ -235,6 +235,24 @@ static inline void sem_freeholder(sem_t *sem, FAR struct semholder_s *pholder) #endif } +/**************************************************************************** + * Name: sem_findandfreeholder + ****************************************************************************/ + +static inline void sem_findandfreeholder(sem_t *sem, FAR struct tcb_s *htcb) +{ + FAR struct semholder_s *pholder = sem_findholder(sem, htcb); + + /* When no more counts are held, remove the holder from the list. The + * count was decremented in sem_releaseholder. + */ + + if (pholder != NULL && pholder->counts <= 0) + { + sem_freeholder(sem, pholder); + } +} + /**************************************************************************** * Name: sem_foreachholder ****************************************************************************/ @@ -460,10 +478,10 @@ static int sem_dumpholder(FAR struct semholder_s *pholder, FAR sem_t *sem, * Name: sem_restoreholderprio ****************************************************************************/ -static int sem_restoreholderprio(FAR struct semholder_s *pholder, +static int sem_restoreholderprio(FAR struct tcb_s *htcb, FAR sem_t *sem, FAR void *arg) { - FAR struct tcb_s *htcb = (FAR struct tcb_s *)pholder->htcb; + FAR struct semholder_s *pholder = 0; #if CONFIG_SEM_NNESTPRIO > 0 FAR struct tcb_s *stcb = (FAR struct tcb_s *)arg; int rpriority; @@ -481,7 +499,11 @@ static int sem_restoreholderprio(FAR struct semholder_s *pholder, { serr("ERROR: TCB 0x%08x is a stale handle, counts lost\n", htcb); DEBUGASSERT(!sched_verifytcb(htcb)); - sem_freeholder(sem, pholder); + pholder = sem_findholder(sem, htcb); + if (pholder != NULL) + { + sem_freeholder(sem, pholder); + } } /* Was the priority of the holder thread boosted? If so, then drop its @@ -600,6 +622,20 @@ static int sem_restoreholderprio(FAR struct semholder_s *pholder, return 0; } +/**************************************************************************** + * Name: sem_restoreholderprioall + * + * Description: + * Reprioritize all holders + * + ****************************************************************************/ + +static int sem_restoreholderprioall(FAR struct semholder_s *pholder, + FAR sem_t *sem, FAR void *arg) +{ + return sem_restoreholderprio(pholder->htcb, sem, arg); +} + /**************************************************************************** * Name: sem_restoreholderprioA * @@ -614,7 +650,7 @@ static int sem_restoreholderprioA(FAR struct semholder_s *pholder, FAR struct tcb_s *rtcb = this_task(); if (pholder->htcb != rtcb) { - return sem_restoreholderprio(pholder, sem, arg); + return sem_restoreholderprio(pholder->htcb, sem, arg); } return 0; @@ -632,9 +668,18 @@ static int sem_restoreholderprioB(FAR struct semholder_s *pholder, FAR sem_t *sem, FAR void *arg) { FAR struct tcb_s *rtcb = this_task(); + if (pholder->htcb == rtcb) { - (void)sem_restoreholderprio(pholder, sem, arg); + + /* The running task has given up a count on the semaphore + * Release the holder if all counts have been given up. + * before reprioritizing causes a context switch. + */ + + sem_findandfreeholder(sem, rtcb); + + (void)sem_restoreholderprio(rtcb, sem, arg); return 1; } @@ -687,7 +732,7 @@ static inline void sem_restorebaseprio_irq(FAR struct tcb_s *stcb, { /* Drop the priority of all holder threads */ - (void)sem_foreachholder(sem, sem_restoreholderprio, stcb); + (void)sem_foreachholder(sem, sem_restoreholderprioall, stcb); } /* If there are no tasks waiting for available counts, then all holders @@ -781,18 +826,8 @@ static inline void sem_restorebaseprio_task(FAR struct tcb_s *stcb, * counts, then we need to remove it from the list of holders. */ - pholder = sem_findholder(sem, rtcb); - if (pholder != NULL) - { - /* When no more counts are held, remove the holder from the list. The - * count was decremented in sem_releaseholder. - */ + sem_findandfreeholder(sem, rtcb); - if (pholder->counts <= 0) - { - sem_freeholder(sem, pholder); - } - } } /**************************************************************************** @@ -1097,7 +1132,7 @@ void sem_canceled(FAR struct tcb_s *stcb, FAR sem_t *sem) /* Adjust the priority of every holder as necessary */ - (void)sem_foreachholder(sem, sem_restoreholderprio, stcb); + (void)sem_foreachholder(sem, sem_restoreholderprioall, stcb); } #endif -- GitLab From 08e92abb0ba744927ed0b32294859b0f47726f82 Mon Sep 17 00:00:00 2001 From: David Cabecinhas Date: Thu, 16 Mar 2017 19:13:39 +0800 Subject: [PATCH 065/990] ARM: Remove redundant interrupt stack coloring --- arch/arm/src/a1x/a1x_irq.c | 10 ---------- arch/arm/src/efm32/efm32_irq.c | 10 ---------- arch/arm/src/imx6/imx_irq.c | 10 ---------- arch/arm/src/sam34/sam_irq.c | 10 ---------- arch/arm/src/sama5/sam_irq.c | 10 ---------- arch/arm/src/samv7/sam_irq.c | 10 ---------- arch/arm/src/stm32/stm32_irq.c | 10 ---------- arch/arm/src/stm32f7/stm32_irq.c | 10 ---------- arch/arm/src/stm32l4/stm32l4_irq.c | 10 ---------- arch/arm/src/tms570/tms570_irq.c | 8 -------- 10 files changed, 98 deletions(-) diff --git a/arch/arm/src/a1x/a1x_irq.c b/arch/arm/src/a1x/a1x_irq.c index ecabb5ff4d..21c074d83c 100644 --- a/arch/arm/src/a1x/a1x_irq.c +++ b/arch/arm/src/a1x/a1x_irq.c @@ -159,16 +159,6 @@ void up_irqinitialize(void) (void)getreg32(A1X_INTC_IRQ_PEND(i)); /* Reading status clears pending interrupts */ } - /* Colorize the interrupt stack for debug purposes */ - -#if defined(CONFIG_STACK_COLORATION) && CONFIG_ARCH_INTERRUPTSTACK > 3 - { - size_t intstack_size = (CONFIG_ARCH_INTERRUPTSTACK & ~3); - up_stack_color((FAR void *)((uintptr_t)&g_intstackbase - intstack_size), - intstack_size); - } -#endif - /* Set the interrupt base address to zero. We do not use the vectored * interrupts. */ diff --git a/arch/arm/src/efm32/efm32_irq.c b/arch/arm/src/efm32/efm32_irq.c index 859860d072..254d196f12 100644 --- a/arch/arm/src/efm32/efm32_irq.c +++ b/arch/arm/src/efm32/efm32_irq.c @@ -319,16 +319,6 @@ void up_irqinitialize(void) putreg32(0xffffffff, NVIC_IRQ_CLEAR(i)); } -#if defined(CONFIG_STACK_COLORATION) && CONFIG_ARCH_INTERRUPTSTACK > 3 - /* Colorize the interrupt stack for debug purposes */ - - { - size_t intstack_size = (CONFIG_ARCH_INTERRUPTSTACK & ~3); - up_stack_color((FAR void *)((uintptr_t)&g_intstackbase - intstack_size), - intstack_size); - } -#endif - /* Make sure that we are using the correct vector table. The default * vector address is 0x0000:0000 but if we are executing code that is * positioned in SRAM or in external FLASH, then we may need to reset diff --git a/arch/arm/src/imx6/imx_irq.c b/arch/arm/src/imx6/imx_irq.c index b15a9a4e6d..d5248ef40f 100644 --- a/arch/arm/src/imx6/imx_irq.c +++ b/arch/arm/src/imx6/imx_irq.c @@ -93,16 +93,6 @@ void up_irqinitialize(void) * access to the GIC. */ - /* Colorize the interrupt stack for debug purposes */ - -#if defined(CONFIG_STACK_COLORATION) && CONFIG_ARCH_INTERRUPTSTACK > 3 - { - size_t intstack_size = (CONFIG_ARCH_INTERRUPTSTACK & ~3); - up_stack_color((FAR void *)((uintptr_t)&g_intstackbase - intstack_size), - intstack_size); - } -#endif - /* Initialize the Generic Interrupt Controller (GIC) for CPU0 */ arm_gic0_initialize(); /* Initialization unique to CPU0 */ diff --git a/arch/arm/src/sam34/sam_irq.c b/arch/arm/src/sam34/sam_irq.c index eb6b174705..24d08cff92 100644 --- a/arch/arm/src/sam34/sam_irq.c +++ b/arch/arm/src/sam34/sam_irq.c @@ -385,16 +385,6 @@ void up_irqinitialize(void) putreg32(0, regaddr); } - /* Colorize the interrupt stack for debug purposes */ - -#if defined(CONFIG_STACK_COLORATION) && CONFIG_ARCH_INTERRUPTSTACK > 3 - { - size_t intstack_size = (CONFIG_ARCH_INTERRUPTSTACK & ~3); - up_stack_color((FAR void *)((uintptr_t)&g_intstackbase - intstack_size), - intstack_size); - } -#endif - /* Make sure that we are using the correct vector table. The default * vector address is 0x0000:0000 but if we are executing code that is * positioned in SRAM or in external FLASH, then we may need to reset diff --git a/arch/arm/src/sama5/sam_irq.c b/arch/arm/src/sama5/sam_irq.c index c8cf1f5cd5..fd4dfd8c5c 100644 --- a/arch/arm/src/sama5/sam_irq.c +++ b/arch/arm/src/sama5/sam_irq.c @@ -431,16 +431,6 @@ void up_irqinitialize(void) * access to the AIC. */ - /* Colorize the interrupt stack for debug purposes */ - -#if defined(CONFIG_STACK_COLORATION) && CONFIG_ARCH_INTERRUPTSTACK > 3 - { - size_t intstack_size = (CONFIG_ARCH_INTERRUPTSTACK & ~3); - up_stack_color((FAR void *)((uintptr_t)&g_intstackbase - intstack_size), - intstack_size); - } -#endif - /* Redirect all interrupts to the AIC if so configured */ sam_aic_redirection(); diff --git a/arch/arm/src/samv7/sam_irq.c b/arch/arm/src/samv7/sam_irq.c index f2e4489329..15910d24d6 100644 --- a/arch/arm/src/samv7/sam_irq.c +++ b/arch/arm/src/samv7/sam_irq.c @@ -381,16 +381,6 @@ void up_irqinitialize(void) putreg32(0, regaddr); } - /* Colorize the interrupt stack for debug purposes */ - -#if defined(CONFIG_STACK_COLORATION) && CONFIG_ARCH_INTERRUPTSTACK > 3 - { - size_t intstack_size = (CONFIG_ARCH_INTERRUPTSTACK & ~3); - up_stack_color((FAR void *)((uintptr_t)&g_intstackbase - intstack_size), - intstack_size); - } -#endif - /* Make sure that we are using the correct vector table. The default * vector address is 0x0000:0000 but if we are executing code that is * positioned in SRAM or in external FLASH, then we may need to reset diff --git a/arch/arm/src/stm32/stm32_irq.c b/arch/arm/src/stm32/stm32_irq.c index 051c982979..2a51836a52 100644 --- a/arch/arm/src/stm32/stm32_irq.c +++ b/arch/arm/src/stm32/stm32_irq.c @@ -310,16 +310,6 @@ void up_irqinitialize(void) putreg32(0xffffffff, NVIC_IRQ_CLEAR(i)); } - /* Colorize the interrupt stack for debug purposes */ - -#if defined(CONFIG_STACK_COLORATION) && CONFIG_ARCH_INTERRUPTSTACK > 3 - { - size_t intstack_size = (CONFIG_ARCH_INTERRUPTSTACK & ~3); - up_stack_color((FAR void *)((uintptr_t)&g_intstackbase - intstack_size), - intstack_size); - } -#endif - /* The standard location for the vector table is at the beginning of FLASH * at address 0x0800:0000. If we are using the STMicro DFU bootloader, then * the vector table will be offset to a different location in FLASH and we diff --git a/arch/arm/src/stm32f7/stm32_irq.c b/arch/arm/src/stm32f7/stm32_irq.c index b240750103..fc6a207854 100644 --- a/arch/arm/src/stm32f7/stm32_irq.c +++ b/arch/arm/src/stm32f7/stm32_irq.c @@ -415,16 +415,6 @@ void up_irqinitialize(void) putreg32(0, regaddr); } - /* Colorize the interrupt stack for debug purposes */ - -#if defined(CONFIG_STACK_COLORATION) && CONFIG_ARCH_INTERRUPTSTACK > 3 - { - size_t intstack_size = (CONFIG_ARCH_INTERRUPTSTACK & ~3); - up_stack_color((FAR void *)((uintptr_t)&g_intstackbase - intstack_size), - intstack_size); - } -#endif - /* Make sure that we are using the correct vector table. The default * vector address is 0x0000:0000 but if we are executing code that is * positioned in SRAM or in external FLASH, then we may need to reset diff --git a/arch/arm/src/stm32l4/stm32l4_irq.c b/arch/arm/src/stm32l4/stm32l4_irq.c index 7a0ed88bd3..4b401d8830 100644 --- a/arch/arm/src/stm32l4/stm32l4_irq.c +++ b/arch/arm/src/stm32l4/stm32l4_irq.c @@ -304,16 +304,6 @@ void up_irqinitialize(void) putreg32(0xffffffff, NVIC_IRQ_CLEAR(i)); } - /* Colorize the interrupt stack for debug purposes */ - -#if defined(CONFIG_STACK_COLORATION) && CONFIG_ARCH_INTERRUPTSTACK > 3 - { - size_t intstack_size = (CONFIG_ARCH_INTERRUPTSTACK & ~3); - up_stack_color((FAR void *)((uintptr_t)&g_intstackbase - intstack_size), - intstack_size); - } -#endif - /* The standard location for the vector table is at the beginning of FLASH * at address 0x0800:0000. If we are using the STMicro DFU bootloader, then * the vector table will be offset to a different location in FLASH and we diff --git a/arch/arm/src/tms570/tms570_irq.c b/arch/arm/src/tms570/tms570_irq.c index 9903261199..11d606d637 100644 --- a/arch/arm/src/tms570/tms570_irq.c +++ b/arch/arm/src/tms570/tms570_irq.c @@ -115,14 +115,6 @@ void up_irqinitialize(void) FAR uintptr_t *vimram; int i; - /* Colorize the interrupt stack for debug purposes */ - -#if defined(CONFIG_STACK_COLORATION) && CONFIG_ARCH_INTERRUPTSTACK > 3 - size_t intstack_size = (CONFIG_ARCH_INTERRUPTSTACK & ~3); - up_stack_color((FAR void *)((uintptr_t)&g_intstackbase - intstack_size), - intstack_size); -#endif - /* Initialize VIM RAM vectors. These vectors are not used in the current * interrupt handler logic. */ -- GitLab From 4b65817e99cbdf04fefad883eca0e7c8a9add63c Mon Sep 17 00:00:00 2001 From: David Cabecinhas Date: Thu, 16 Mar 2017 19:58:50 +0800 Subject: [PATCH 066/990] ARM: Set EABI stack alignment for all ARM architectures (remove OABI code) --- arch/arm/src/common/up_createstack.c | 23 ++++++----------------- arch/arm/src/common/up_stackframe.c | 17 +++-------------- arch/arm/src/common/up_usestack.c | 23 ++++++----------------- arch/arm/src/common/up_vfork.c | 17 +++-------------- 4 files changed, 18 insertions(+), 62 deletions(-) diff --git a/arch/arm/src/common/up_createstack.c b/arch/arm/src/common/up_createstack.c index 70d83a83a5..4503e15532 100644 --- a/arch/arm/src/common/up_createstack.c +++ b/arch/arm/src/common/up_createstack.c @@ -66,22 +66,11 @@ # define HAVE_KERNEL_HEAP 1 #endif -/* ARM requires at least a 4-byte stack alignment. For use with EABI and - * floating point, the stack must be aligned to 8-byte addresses. +/* For use with EABI and floating point, the stack must be aligned to 8-byte + * addresses. */ -#ifndef CONFIG_STACK_ALIGNMENT - -/* The symbol __ARM_EABI__ is defined by GCC if EABI is being used. If you - * are not using GCC, make sure that CONFIG_STACK_ALIGNMENT is set correctly! - */ - -# ifdef __ARM_EABI__ -# define CONFIG_STACK_ALIGNMENT 8 -# else -# define CONFIG_STACK_ALIGNMENT 4 -# endif -#endif +#define CONFIG_STACK_ALIGNMENT 8 /* Stack alignment macros */ @@ -233,9 +222,9 @@ int up_create_stack(FAR struct tcb_s *tcb, size_t stack_size, uint8_t ttype) top_of_stack = (uint32_t)tcb->stack_alloc_ptr + stack_size - 4; - /* The ARM stack must be aligned; 4 byte alignment for OABI and - * 8-byte alignment for EABI. If necessary top_of_stack must be - * rounded down to the next boundary + /* The ARM stack must be aligned to 8-byte alignment for EABI. + * If necessary top_of_stack must be rounded down to the next + * boundary */ top_of_stack = STACK_ALIGN_DOWN(top_of_stack); diff --git a/arch/arm/src/common/up_stackframe.c b/arch/arm/src/common/up_stackframe.c index b5712b2a29..dace2e9239 100644 --- a/arch/arm/src/common/up_stackframe.c +++ b/arch/arm/src/common/up_stackframe.c @@ -53,22 +53,11 @@ * Pre-processor Macros ****************************************************************************/ -/* ARM requires at least a 4-byte stack alignment. For use with EABI and - * floating point, the stack must be aligned to 8-byte addresses. +/* For use with EABI and floating point, the stack must be aligned to 8-byte + * addresses. */ -#ifndef CONFIG_STACK_ALIGNMENT - -/* The symbol __ARM_EABI__ is defined by GCC if EABI is being used. If you - * are not using GCC, make sure that CONFIG_STACK_ALIGNMENT is set correctly! - */ - -# ifdef __ARM_EABI__ -# define CONFIG_STACK_ALIGNMENT 8 -# else -# define CONFIG_STACK_ALIGNMENT 4 -# endif -#endif +#define CONFIG_STACK_ALIGNMENT 8 /* Stack alignment macros */ diff --git a/arch/arm/src/common/up_usestack.c b/arch/arm/src/common/up_usestack.c index 887387976a..f8072a66d4 100644 --- a/arch/arm/src/common/up_usestack.c +++ b/arch/arm/src/common/up_usestack.c @@ -56,22 +56,11 @@ * Pre-processor Macros ****************************************************************************/ -/* ARM requires at least a 4-byte stack alignment. For use with EABI and - * floating point, the stack must be aligned to 8-byte addresses. +/* For use with EABI and floating point, the stack must be aligned to 8-byte + * addresses. */ -#ifndef CONFIG_STACK_ALIGNMENT - -/* The symbol __ARM_EABI__ is defined by GCC if EABI is being used. If you - * are not using GCC, make sure that CONFIG_STACK_ALIGNMENT is set correctly! - */ - -# ifdef __ARM_EABI__ -# define CONFIG_STACK_ALIGNMENT 8 -# else -# define CONFIG_STACK_ALIGNMENT 4 -# endif -#endif +#define CONFIG_STACK_ALIGNMENT 8 /* Stack alignment macros */ @@ -143,9 +132,9 @@ int up_use_stack(struct tcb_s *tcb, void *stack, size_t stack_size) top_of_stack = (uint32_t)tcb->stack_alloc_ptr + stack_size - 4; - /* The ARM stack must be aligned; 4 byte alignment for OABI and 8-byte - * alignment for EABI. If necessary top_of_stack must be rounded down - * to the next boundary + /* The ARM stack must be aligned to 8-byte alignment for EABI. + * If necessary top_of_stack must be rounded down to the next + * boundary */ top_of_stack = STACK_ALIGN_DOWN(top_of_stack); diff --git a/arch/arm/src/common/up_vfork.c b/arch/arm/src/common/up_vfork.c index e655ab15b4..5a69e310e3 100644 --- a/arch/arm/src/common/up_vfork.c +++ b/arch/arm/src/common/up_vfork.c @@ -56,22 +56,11 @@ * Pre-processor Definitions ****************************************************************************/ -/* ARM requires at least a 4-byte stack alignment. For use with EABI and - * floating point, the stack must be aligned to 8-byte addresses. +/* For use with EABI and floating point, the stack must be aligned to 8-byte + * addresses. */ -#ifndef CONFIG_STACK_ALIGNMENT - -/* The symbol __ARM_EABI__ is defined by GCC if EABI is being used. If you - * are not using GCC, make sure that CONFIG_STACK_ALIGNMENT is set correctly! - */ - -# ifdef __ARM_EABI__ -# define CONFIG_STACK_ALIGNMENT 8 -# else -# define CONFIG_STACK_ALIGNMENT 4 -# endif -#endif +#define CONFIG_STACK_ALIGNMENT 8 /**************************************************************************** * Public Functions -- GitLab From 1280c915648cf1f74969130b8dccc896effd2547 Mon Sep 17 00:00:00 2001 From: no1wudi <757509347@qq.com> Date: Thu, 16 Mar 2017 23:04:52 +0800 Subject: [PATCH 067/990] fixed descritpions of NUC100/120 --- arch/arm/Kconfig | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/arch/arm/Kconfig b/arch/arm/Kconfig index fd44dcff07..9be59af000 100644 --- a/arch/arm/Kconfig +++ b/arch/arm/Kconfig @@ -156,7 +156,7 @@ config ARCH_CHIP_NUC1XX select ARCH_CORTEXM0 select ARCH_HAVE_CMNVECTOR ---help--- - NPX LPC43XX architectures (ARM Cortex-M4). + Nuvoton NUC100/120 architectures (ARM Cortex-M0). config ARCH_CHIP_SAMA5 bool "Atmel SAMA5" -- GitLab From 66d001d0e1ebb8f19deb393666e596715256ac6a Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 16 Mar 2017 09:48:57 -0600 Subject: [PATCH 068/990] XMC4xxx: Initial clock configuration logic. --- arch/arm/src/xmc4/chip/xmc4_flash.h | 203 +++++++++++ arch/arm/src/xmc4/chip/xmc4_memorymap.h | 454 ++++++++++++------------ arch/arm/src/xmc4/chip/xmc4_scu.h | 48 ++- arch/arm/src/xmc4/xmc4_clockconfig.c | 445 +++++++++++++++++++++++ arch/arm/src/xmc4/xmc4_start.c | 46 +++ configs/xmc4500-relax/include/board.h | 8 + 6 files changed, 969 insertions(+), 235 deletions(-) create mode 100644 arch/arm/src/xmc4/chip/xmc4_flash.h diff --git a/arch/arm/src/xmc4/chip/xmc4_flash.h b/arch/arm/src/xmc4/chip/xmc4_flash.h new file mode 100644 index 0000000000..e68e7078e9 --- /dev/null +++ b/arch/arm/src/xmc4/chip/xmc4_flash.h @@ -0,0 +1,203 @@ +/************************************************************************************ + * arch/arm/src/xmc4/chip/xmc4_flash.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Reference: XMC4500 Reference Manual V1.5 2014-07 Microcontrollers. + * + * 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. + * + * May include some logic from sample code provided by Infineon: + * + * Copyright (C) 2011-2015 Infineon Technologies AG. All rights reserved. + * + * Infineon Technologies AG (Infineon) is supplying this software for use with + * Infineon's microcontrollers. This file can be freely distributed within + * development tools that are supporting such microcontrollers. + * + * THIS SOFTWARE IS PROVIDED AS IS. NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * INFINEON SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, + * OR CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_XMC4_CHIP_XMC4_FLASH_H +#define __ARCH_ARM_SRC_XMC4_CHIP_XMC4_FLASH_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Register Offsets *****************************************************************/ + +/* PMU Registers -- See ID register */ +/* Prefetch Registers -- See PCON register */ + +/* FLASH Registers */ + +#define XMC4_FLASH_ID_OFFSET 0x1008 /* Flash Module Identification Register */ +#define XMC4_FLASH_FSR_OFFSET 0x1010 /* Flash Status Register */ +#define XMC4_FLASH_FCON_OFFSET 0x1014 /* Flash Configuration Register */ +#define XMC4_FLASH_MARP_OFFSET 0x1018 /* Flash Margin Control Register PFLASH */ +#define XMC4_FLASH_PROCON0_OFFSET 0x1020 /* Flash Protection Configuration User 0 */ +#define XMC4_FLASH_PROCON1_OFFSET 0x1024 /* Flash Protection Configuration User 1 */ +#define XMC4_FLASH_PROCON2_OFFSET 0x1028 /* Flash Protection Configuration User 2 */ + +/* Register Addresses ****************************************************************/ + +/* FLASH Registers */ + +#define XMC4_FLASH_ID (XMC4_FLASH0_BASE+XMC4_FLASH_ID_OFFSET) +#define XMC4_FLASH_FSR (XMC4_FLASH0_BASE+XMC4_FLASH_FSR_OFFSET) +#define XMC4_FLASH_FCON (XMC4_FLASH0_BASE+XMC4_FLASH_FCON_OFFSET) +#define XMC4_FLASH_MARP (XMC4_FLASH0_BASE+XMC4_FLASH_MARP_OFFSET) +#define XMC4_FLASH_PROCON0 (XMC4_FLASH0_BASE+XMC4_FLASH_PROCON0_OFFSET) +#define XMC4_FLASH_PROCON1 (XMC4_FLASH0_BASE+XMC4_FLASH_PROCON1_OFFSET) +#define XMC4_FLASH_PROCON2 (XMC4_FLASH0_BASE+XMC4_FLASH_PROCON2_OFFSET) + +/* Register Bit-Field Definitions **************************************************/ + +/* FLASH Registers */ + +/* Flash Module Identification Register */ + +#define FLASH_ID_MOD_REV_SHIFT (0) /* Bits 0-7: Module Revision Number */ +#define FLASH_ID_MOD_REV_MASK (0xff << FLASH_ID_MOD_REV_SHIFT) +#define FLASH_ID_MOD_TYPE_SHIFT (8) /* Bits 8-15: Module Type */ +#define FLASH_ID_MOD_TYPE_MASK (0xff << FLASH_ID_MOD_REV_SHIFT) +#define FLASH_ID_MOD_NUMBER_SHIFT (16) /* Bits 16-31: Module Number Value */ +#define FLASH_ID_MOD_NUMBER_MASK (0xffff << FLASH_ID_MOD_NUMBER_SHIFT) + +/* Flash Status Register */ + +#define FLASH_FSR_PBUSY (1 << 0) /* Bit 0: Program Flash Busy */ +#define FLASH_FSR_FABUSY (1 << 1) /* Bit 1: Flash Array Busy */ +#define FLASH_FSR_PROG (1 << 4) /* Bit 4: Programming State */ +#define FLASH_FSR_ERASE (1 << 5) /* Bit 5: Erase State */ +#define FLASH_FSR_PFPAGE (1 << 6) /* Bit 6: Program Flash in Page Mode */ +#define FLASH_FSR_PFOPER (1 << 8) /* Bit 8: Program Flash Operation Error */ +#define FLASH_FSR_SQER (1 << 10) /* Bit 10: Command Sequence Error */ +#define FLASH_FSR_PROER (1 << 11) /* Bit 11: Protection Error */ +#define FLASH_FSR_PFSBER (1 << 12) /* Bit 12: PFLASH Single-Bit Error and Correction */ +#define FLASH_FSR_PFDBER (1 << 14) /* Bit 14: PFLASH Double-Bit Error */ +#define FLASH_FSR_PROIN (1 << 16) /* Bit 16: Protection Installed */ +#define FLASH_FSR_RPROIN (1 << 18) /* Bit 18: Read Protection Installed */ +#define FLASH_FSR_RPRODIS (1 << 19) /* Bit 19: Read Protection Disable State */ +#define FLASH_FSR_WPROIN0 (1 << 21) /* Bit 21: Sector Write Protection Installed for User 0 */ +#define FLASH_FSR_WPROIN1 (1 << 22) /* Bit 22: Sector Write Protection Installed for User 1 */ +#define FLASH_FSR_WPROIN2 (1 << 23) /* Bit 23: Sector Write Protection Installed for User 2 */ +#define FLASH_FSR_WPRODIS0 (1 << 25) /* Bit 25: Sector Write Protection Disabled for User 0 */ +#define FLASH_FSR_WPRODIS1 (1 << 26) /* Bit 26: Sector Write Protection Disabled for User 1 */ +#define FLASH_FSR_SLM (1 << 28) /* Bit 28: Flash Sleep Mode */ +#define FLASH_FSR_VER (1 << 31) /* Bit 31: Verify Error */ + +/* Flash Configuration Register */ + +#define FLASH_FCON_WSPFLASH_SHIFT (0) /* Bits 0-3: Wait States for read access to PFLASH */ +#define FLASH_FCON_WSPFLASH_MASK (15 << FLASH_FCON_WSPFLASH_SHIFT) +# define FLASH_FCON_WSPFLASH(n) ((uint32_t)((n)-1) << FLASH_FCON_WSPFLASH_SHIFT) +#define FLASH_FCON_WSECPF (1 << 4) /* Bit 4: Wait State for Error Correction of PFLASH */ +#define FLASH_FCON_IDLE (1 << 13) /* Bit 13: Dynamic Flash Idle */ +#define FLASH_FCON_ESLDIS (1 << 14) /* Bit 14: External Sleep Request Disable */ +#define FLASH_FCON_SLEEP (1 << 15) /* Bit 15: Flash SLEEP */ +#define FLASH_FCON_RPA (1 << 16) /* Bit 16: Read Protection Activated */ +#define FLASH_FCON_DCF (1 << 17) /* Bit 17: Disable Code Fetch from Flash Memory */ +#define FLASH_FCON_DDF (1 << 18) /* Bit 18: Disable Any Data Fetch from Flash */ +#define FLASH_FCON_VOPERM (1 << 24) /* Bit 24: Verify and Operation Error Interrupt Mask */ +#define FLASH_FCON_SQERM (1 << 25) /* Bit 25: Command Sequence Error Interrupt Mask */ +#define FLASH_FCON_PROERM (1 << 26) /* Bit 26: Protection Error Interrupt Mask */ +#define FLASH_FCON_PFSBERM (1 << 27) /* Bit 27: PFLASH Single-Bit Error Interrupt Mask */ +#define FLASH_FCON_PFDBERM (1 << 29) /* Bit 29: PFLASH Double-Bit Error Interrupt Mask */ +#define FLASH_FCON_EOBM (1 << 31) /* Bit 31: End of Busy Interrupt Mask */ + +/* Flash Margin Control Register PFLASH */ + +#define FLASH_MARP_MARGIN_SHIFT (0) /* Bits 0-3: PFLASH Margin Selection */ +#define FLASH_MARP_MARGIN_MASK (15 << FLASH_MARP_MARGIN_SHIFT) +#define FLASH_MARP_TRAPDIS (1 << 15) /* Bit 15: PFLASH Double-Bit Error Trap Disable */ + +/* Flash Protection Configuration User 0 */ + +#define FLASH_PROCON0_S0L (1 << 0) /* Bit 0: Sector 0 Locked for Write Protection by User 0 */ +#define FLASH_PROCON0_S1L (1 << 1) /* Bit 1: Sector 1 Locked for Write Protection by User 0 */ +#define FLASH_PROCON0_S2L (1 << 2) /* Bit 2: Sector 2 Locked for Write Protection by User 0 */ +#define FLASH_PROCON0_S3L (1 << 3) /* Bit 3: Sector 3 Locked for Write Protection by User 0 */ +#define FLASH_PROCON0_S4L (1 << 4) /* Bit 4: Sector 4 Locked for Write Protection by User 0 */ +#define FLASH_PROCON0_S5L (1 << 5) /* Bit 5: Sector 5 Locked for Write Protection by User 0 */ +#define FLASH_PROCON0_S6L (1 << 6) /* Bit 6: Sector 6 Locked for Write Protection by User 0 */ +#define FLASH_PROCON0_S7L (1 << 7) /* Bit 7: Sector 7 Locked for Write Protection by User 0 */ +#define FLASH_PROCON0_S8L (1 << 8) /* Bit 8: Sector 8 Locked for Write Protection by User 0 */ +#define FLASH_PROCON0_S9L (1 << 9) /* Bit 9: Sector 9 Locked for Write Protection by User 0 */ +#define FLASH_PROCON0_S10_S11L (1 << 10) /* Bit 10: Sectors 10 and 11 Locked for Write Protection by User 0 */ +#define FLASH_PROCON0_S12_S13L (1 << 11) /* Bit 11: Sectors 12 and 13 Locked for Write Protection by User 0 */ +#define FLASH_PROCON0_S14_S15L (1 << 12) /* Bit 12: Sectors 14 and 15 Locked for Write Protection by User 0 */ +#define FLASH_PROCON0_RPRO (1 << 15) /* Bit 15: Read Protection Configuration */ + +/* Flash Protection Configuration User 1 */ + +#define FLASH_PROCON1_S0L (1 << 0) /* Bit 0: Sector 0 Locked for Write Protection by User 1 */ +#define FLASH_PROCON1_S1L (1 << 1) /* Bit 1: Sector 1 Locked for Write Protection by User 1 */ +#define FLASH_PROCON1_S2L (1 << 2) /* Bit 2: Sector 2 Locked for Write Protection by User 1 */ +#define FLASH_PROCON1_S3L (1 << 3) /* Bit 3: Sector 3 Locked for Write Protection by User 1 */ +#define FLASH_PROCON1_S4L (1 << 4) /* Bit 4: Sector 4 Locked for Write Protection by User 1 */ +#define FLASH_PROCON1_S5L (1 << 5) /* Bit 5: Sector 5 Locked for Write Protection by User 1 */ +#define FLASH_PROCON1_S6L (1 << 6) /* Bit 6: Sector 6 Locked for Write Protection by User 1 */ +#define FLASH_PROCON1_S7L (1 << 7) /* Bit 7: Sector 7 Locked for Write Protection by User 1 */ +#define FLASH_PROCON1_S8L (1 << 8) /* Bit 8: Sector 8 Locked for Write Protection by User 1 */ +#define FLASH_PROCON1_S9L (1 << 9) /* Bit 9: Sector 9 Locked for Write Protection by User 1 */ +#define FLASH_PROCON1_S10_S11L (1 << 10) /* Bit 10: Sectors 10 and 11 Locked for Write Protection by User 1 */ +#define FLASH_PROCON1_S12_S13L (1 << 11) /* Bit 11: Sectors 12 and 13 Locked for Write Protection by User 1 */ +#define FLASH_PROCON1_S14_S15L (1 << 12) /* Bit 12: Sectors 14 and 15 Locked for Write Protection by User 1 */ +#define FLASH_PROCON1_PSR (1 << 16) /* Bit 16: */ + +/* Flash Protection Configuration User 2 */ + +#define FLASH_PROCON2_S0ROM (1 << 0) /* Bit 0: Sector 0 Locked Forever by User 2 */ +#define FLASH_PROCON2_S1ROM (1 << 1) /* Bit 1: Sector 1 Locked Forever by User 2 */ +#define FLASH_PROCON2_S2ROM (1 << 2) /* Bit 2: Sector 2 Locked Forever by User 2 */ +#define FLASH_PROCON2_S3ROM (1 << 3) /* Bit 3: Sector 3 Locked Forever by User 2 */ +#define FLASH_PROCON2_S4ROM (1 << 4) /* Bit 4: Sector 4 Locked Forever by User 2 */ +#define FLASH_PROCON2_S5ROM (1 << 5) /* Bit 5: Sector 5 Locked Forever by User 2 */ +#define FLASH_PROCON2_S6ROM (1 << 6) /* Bit 6: Sector 6 Locked Forever by User 2 */ +#define FLASH_PROCON2_S7ROM (1 << 7) /* Bit 7: Sector 7 Locked Forever by User 2 */ +#define FLASH_PROCON2_S8ROM (1 << 8) /* Bit 8: Sector 8 Locked Forever by User 2 */ +#define FLASH_PROCON2_S9ROM (1 << 9) /* Bit 9: Sector 9 Locked Forever by User 2 */ +#define FLASH_PROCON2_S10_S11ROM (1 << 10) /* Bit 10: Sectors 10 and 11 Locked Forever by User 2 */ +#define FLASH_PROCON2_S12_S13ROM (1 << 11) /* Bit 11: Sectors 12 and 13 Locked Forever by User 2 */ +#define FLASH_PROCON2_S14_S15ROM (1 << 12) /* Bit 12: Sectors 14 and 15 Locked Forever by User 2 */ + +#endif /* __ARCH_ARM_SRC_XMC4_CHIP_XMC4_SCU_H */ diff --git a/arch/arm/src/xmc4/chip/xmc4_memorymap.h b/arch/arm/src/xmc4/chip/xmc4_memorymap.h index 8cf50174b9..19dd637ab5 100644 --- a/arch/arm/src/xmc4/chip/xmc4_memorymap.h +++ b/arch/arm/src/xmc4/chip/xmc4_memorymap.h @@ -1,227 +1,227 @@ -/************************************************************************************ - * arch/arm/src/xmc4/chip/xmc4_memorymap.h - * - * Copyright (C) 2017 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Reference: XMC4500 Reference Manual V1.5 2014-07 Microcontrollers. - * - * 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. - * - * May include some logic from sample code provided by Infineon: - * - * Copyright (C) 2011-2015 Infineon Technologies AG. All rights reserved. - * - * Infineon Technologies AG (Infineon) is supplying this software for use with - * Infineon's microcontrollers. This file can be freely distributed within - * development tools that are supporting such microcontrollers. - * - * THIS SOFTWARE IS PROVIDED AS IS. NO WARRANTIES, WHETHER EXPRESS, IMPLIED - * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. - * INFINEON SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, - * OR CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. - * - ************************************************************************************/ - -#ifndef __ARCH_ARM_SRC_XMC4_CHIP_XMC4_MEMORYMAP_H -#define __ARCH_ARM_SRC_XMC4_CHIP_XMC4_MEMORYMAP_H - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include - -/************************************************************************************ - * Pre-processor Definitions - ************************************************************************************/ - -/* Peripheral Memory Map ************************************************************/ -/* Acronyms: - * ADC - Analog to Digital Converter - * CCU - Capture Compare Unit - * DAC - Digital to Analog Converter - * DSD - Delta Sigmoid Demodulator - * ERU - External Request Unit - * FCE - Flexible CRC Engine - * GPDMA - General Purpose DMA - * LEDTS - LED and Touch Sense Control Unit - * PMU - Program Management Unit - * POSIF - Position Interface - * SDMMC - Multi Media Card Interface - * USB - Universal Serial Bus - * USCI - Universal Serial Interface - */ - -#define XMC4_PBA0_BASE 0x40000000 -#define XMC4_VADC_BASE 0x40004000 -#define XMC4_VADC_G0_BASE 0x40004400 -#define XMC4_VADC_G1_BASE 0x40004800 -#define XMC4_VADC_G2_BASE 0x40004c00 -#define XMC4_VADC_G3_BASE 0x40005000 -#define XMC4_DSD_BASE 0x40008000 -#define XMC4_DSD_CH0_BASE 0x40008100 -#define XMC4_DSD_CH1_BASE 0x40008200 -#define XMC4_DSD_CH2_BASE 0x40008300 -#define XMC4_DSD_CH3_BASE 0x40008400 -#define XMC4_CCU40_BASE 0x4000c000 -#define XMC4_CCU40_CC40_BASE 0x4000c100 -#define XMC4_CCU40_CC41_BASE 0x4000c200 -#define XMC4_CCU40_CC42_BASE 0x4000c300 -#define XMC4_CCU40_CC43_BASE 0x4000c400 -#define XMC4_CCU41_BASE 0x40010000 -#define XMC4_CCU41_CC40_BASE 0x40010100 -#define XMC4_CCU41_CC41_BASE 0x40010200 -#define XMC4_CCU41_CC42_BASE 0x40010300 -#define XMC4_CCU41_CC43_BASE 0x40010400 -#define XMC4_CCU42_BASE 0x40014000 -#define XMC4_CCU42_CC40_BASE 0x40014100 -#define XMC4_CCU42_CC41_BASE 0x40014200 -#define XMC4_CCU42_CC42_BASE 0x40014300 -#define XMC4_CCU42_CC43_BASE 0x40014400 -#define XMC4_CCU80_BASE 0x40020000 -#define XMC4_CCU80_CC80_BASE 0x40020100 -#define XMC4_CCU80_CC81_BASE 0x40020200 -#define XMC4_CCU80_CC82_BASE 0x40020300 -#define XMC4_CCU80_CC83_BASE 0x40020400 -#define XMC4_CCU81_BASE 0x40024000 -#define XMC4_CCU81_CC80_BASE 0x40024100 -#define XMC4_CCU81_CC81_BASE 0x40024200 -#define XMC4_CCU81_CC82_BASE 0x40024300 -#define XMC4_CCU81_CC83_BASE 0x40024400 -#define XMC4_POSIF0_BASE 0x40028000 -#define XMC4_POSIF1_BASE 0x4002c000 -#define XMC4_USIC0_BASE 0x40030008 -#define XMC4_USIC0_CH0_BASE 0x40030000 -#define XMC4_USIC0_CH1_BASE 0x40030200 -#define XMC4_ERU1_BASE 0x40044000 - -#define XMC4_PBA1_BASE 0x48000000 -#define XMC4_CCU43_BASE 0x48004000 -#define XMC4_CCU43_CC40_BASE 0x48004100 -#define XMC4_CCU43_CC41_BASE 0x48004200 -#define XMC4_CCU43_CC42_BASE 0x48004300 -#define XMC4_CCU43_CC43_BASE 0x48004400 -#define XMC4_LEDTS0_BASE 0x48010000 -#define XMC4_CAN_BASE 0x48014000 -#define XMC4_CAN_NODE0_BASE 0x48014200 -#define XMC4_CAN_NODE1_BASE 0x48014300 -#define XMC4_CAN_NODE2_BASE 0x48014400 -#define XMC4_CAN_NODE3_BASE 0x48014500 -#define XMC4_CAN_NODE4_BASE 0x48014600 -#define XMC4_CAN_NODE5_BASE 0x48014700 -#define XMC4_CAN_MO_BASE 0x48015000 -#define XMC4_DAC_BASE 0x48018000 -#define XMC4_SDMMC_BASE 0x4801c000 -#define XMC4_USIC1_CH0_BASE 0x48020000 -#define XMC4_USIC1_BASE 0x48020008 -#define XMC4_USIC1_CH1_BASE 0x48020200 -#define XMC4_USIC2_CH0_BASE 0x48024000 -#define XMC4_USIC2_BASE 0x48024008 -#define XMC4_USIC2_CH1_BASE 0x48024200 -#define XMC4_PORT0_BASE 0x48028000 -#define XMC4_PORT1_BASE 0x48028100 -#define XMC4_PORT2_BASE 0x48028200 -#define XMC4_PORT3_BASE 0x48028300 -#define XMC4_PORT4_BASE 0x48028400 -#define XMC4_PORT5_BASE 0x48028500 -#define XMC4_PORT6_BASE 0x48028600 -#define XMC4_PORT7_BASE 0x48028700 -#define XMC4_PORT8_BASE 0x48028800 -#define XMC4_PORT9_BASE 0x48028900 -#define XMC4_PORT14_BASE 0x48028e00 -#define XMC4_PORT15_BASE 0x48028f00 - -#define XMC4_SCU_GENERAL_BASE 0x50004000 -#define XMC4_ETH0_CON_BASE 0x50004040 -#define XMC4_SCU_INTERRUPT_BASE 0x50004074 -#define XMC4_SDMMC_CON_BASE 0x500040b4 -#define XMC4_SCU_PARITY_BASE 0x5000413c -#define XMC4_SCU_TRAP_BASE 0x50004160 -#define XMC4_SCU_POWER_BASE 0x50004200 -#define XMC4_SCU_HIBERNATE_BASE 0x50004300 -#define XMC4_SCU_RESET_BASE 0x50004400 -#define XMC4_SCU_CLK_BASE 0x50004600 -#define XMC4_SCU_OSC_BASE 0x50004700 -#define XMC4_SCU_PLL_BASE 0x50004710 -#define XMC4_ERU0_BASE 0x50004800 -#define XMC4_DLR_BASE 0x50004900 -#define XMC4_RTC_BASE 0x50004a00 -#define XMC4_WDT_BASE 0x50008000 -#define XMC4_ETH0_BASE 0x5000c000 -#define XMC4_USB0_BASE 0x50040000 -#define XMC4_USB0_CH0_BASE 0x50040500 -#define XMC4_USB0_CH1_BASE 0x50040520 -#define XMC4_USB0_CH2_BASE 0x50040540 -#define XMC4_USB0_CH3_BASE 0x50040560 -#define XMC4_USB0_CH4_BASE 0x50040580 -#define XMC4_USB0_CH5_BASE 0x500405a0 -#define XMC4_USB0_CH6_BASE 0x500405c0 -#define XMC4_USB0_CH7_BASE 0x500405e0 -#define XMC4_USB0_CH8_BASE 0x50040600 -#define XMC4_USB0_CH9_BASE 0x50040620 -#define XMC4_USB0_CH10_BASE 0x50040640 -#define XMC4_USB0_CH11_BASE 0x50040660 -#define XMC4_USB0_CH12_BASE 0x50040680 -#define XMC4_USB0_CH13_BASE 0x500406a0 -#define XMC4_USB_EP_BASE 0x50040900 -#define XMC4_USB0_EP1_BASE 0x50040920 -#define XMC4_USB0_EP2_BASE 0x50040940 -#define XMC4_USB0_EP3_BASE 0x50040960 -#define XMC4_USB0_EP4_BASE 0x50040980 -#define XMC4_USB0_EP5_BASE 0x500409a0 -#define XMC4_USB0_EP6_BASE 0x500409c0 -#define XMC4_GPDMA0_CH0_BASE 0x50014000 -#define XMC4_GPDMA0_CH1_BASE 0x50014058 -#define XMC4_GPDMA0_CH2_BASE 0x500140b0 -#define XMC4_GPDMA0_CH3_BASE 0x50014108 -#define XMC4_GPDMA0_CH4_BASE 0x50014160 -#define XMC4_GPDMA0_CH5_BASE 0x500141b8 -#define XMC4_GPDMA0_CH6_BASE 0x50014210 -#define XMC4_GPDMA0_CH7_BASE 0x50014268 -#define XMC4_GPDMA0_BASE 0x500142c0 -#define XMC4_GPDMA1_CH0_BASE 0x50018000 -#define XMC4_GPDMA1_CH1_BASE 0x50018058 -#define XMC4_GPDMA1_CH2_BASE 0x500180b0 -#define XMC4_GPDMA1_CH3_BASE 0x50018108 -#define XMC4_GPDMA1_BASE 0x500182c0 -#define XMC4_FCE_BASE 0x50020000 -#define XMC4_FCE_KE0_BASE 0x50020020 -#define XMC4_FCE_KE1_BASE 0x50020040 -#define XMC4_FCE_KE2_BASE 0x50020060 -#define XMC4_FCE_KE3_BASE 0x50020080 - -#define XMC4_PMU0_BASE 0x58000508 -#define XMC4_FLASH0_BASE 0x58001000 -#define XMC4_PREF_BASE 0x58004000 -#define XMC4_EBU_BASE 0x58008000 - -#define XMC4_PPB_BASE 0xe000e000 - -#endif /* __ARCH_ARM_SRC_XMC4_CHIP_XMC4_SCU_H */ +/************************************************************************************ + * arch/arm/src/xmc4/chip/xmc4_memorymap.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Reference: XMC4500 Reference Manual V1.5 2014-07 Microcontrollers. + * + * 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. + * + * May include some logic from sample code provided by Infineon: + * + * Copyright (C) 2011-2015 Infineon Technologies AG. All rights reserved. + * + * Infineon Technologies AG (Infineon) is supplying this software for use with + * Infineon's microcontrollers. This file can be freely distributed within + * development tools that are supporting such microcontrollers. + * + * THIS SOFTWARE IS PROVIDED AS IS. NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * INFINEON SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, + * OR CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_XMC4_CHIP_XMC4_MEMORYMAP_H +#define __ARCH_ARM_SRC_XMC4_CHIP_XMC4_MEMORYMAP_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Peripheral Memory Map ************************************************************/ +/* Acronyms: + * ADC - Analog to Digital Converter + * CCU - Capture Compare Unit + * DAC - Digital to Analog Converter + * DSD - Delta Sigmoid Demodulator + * ERU - External Request Unit + * FCE - Flexible CRC Engine + * GPDMA - General Purpose DMA + * LEDTS - LED and Touch Sense Control Unit + * PMU - Program Management Unit + * POSIF - Position Interface + * SDMMC - Multi Media Card Interface + * USB - Universal Serial Bus + * USCI - Universal Serial Interface + */ + +#define XMC4_PBA0_BASE 0x40000000 +#define XMC4_VADC_BASE 0x40004000 +#define XMC4_VADC_G0_BASE 0x40004400 +#define XMC4_VADC_G1_BASE 0x40004800 +#define XMC4_VADC_G2_BASE 0x40004c00 +#define XMC4_VADC_G3_BASE 0x40005000 +#define XMC4_DSD_BASE 0x40008000 +#define XMC4_DSD_CH0_BASE 0x40008100 +#define XMC4_DSD_CH1_BASE 0x40008200 +#define XMC4_DSD_CH2_BASE 0x40008300 +#define XMC4_DSD_CH3_BASE 0x40008400 +#define XMC4_CCU40_BASE 0x4000c000 +#define XMC4_CCU40_CC40_BASE 0x4000c100 +#define XMC4_CCU40_CC41_BASE 0x4000c200 +#define XMC4_CCU40_CC42_BASE 0x4000c300 +#define XMC4_CCU40_CC43_BASE 0x4000c400 +#define XMC4_CCU41_BASE 0x40010000 +#define XMC4_CCU41_CC40_BASE 0x40010100 +#define XMC4_CCU41_CC41_BASE 0x40010200 +#define XMC4_CCU41_CC42_BASE 0x40010300 +#define XMC4_CCU41_CC43_BASE 0x40010400 +#define XMC4_CCU42_BASE 0x40014000 +#define XMC4_CCU42_CC40_BASE 0x40014100 +#define XMC4_CCU42_CC41_BASE 0x40014200 +#define XMC4_CCU42_CC42_BASE 0x40014300 +#define XMC4_CCU42_CC43_BASE 0x40014400 +#define XMC4_CCU80_BASE 0x40020000 +#define XMC4_CCU80_CC80_BASE 0x40020100 +#define XMC4_CCU80_CC81_BASE 0x40020200 +#define XMC4_CCU80_CC82_BASE 0x40020300 +#define XMC4_CCU80_CC83_BASE 0x40020400 +#define XMC4_CCU81_BASE 0x40024000 +#define XMC4_CCU81_CC80_BASE 0x40024100 +#define XMC4_CCU81_CC81_BASE 0x40024200 +#define XMC4_CCU81_CC82_BASE 0x40024300 +#define XMC4_CCU81_CC83_BASE 0x40024400 +#define XMC4_POSIF0_BASE 0x40028000 +#define XMC4_POSIF1_BASE 0x4002c000 +#define XMC4_USIC0_BASE 0x40030008 +#define XMC4_USIC0_CH0_BASE 0x40030000 +#define XMC4_USIC0_CH1_BASE 0x40030200 +#define XMC4_ERU1_BASE 0x40044000 + +#define XMC4_PBA1_BASE 0x48000000 +#define XMC4_CCU43_BASE 0x48004000 +#define XMC4_CCU43_CC40_BASE 0x48004100 +#define XMC4_CCU43_CC41_BASE 0x48004200 +#define XMC4_CCU43_CC42_BASE 0x48004300 +#define XMC4_CCU43_CC43_BASE 0x48004400 +#define XMC4_LEDTS0_BASE 0x48010000 +#define XMC4_CAN_BASE 0x48014000 +#define XMC4_CAN_NODE0_BASE 0x48014200 +#define XMC4_CAN_NODE1_BASE 0x48014300 +#define XMC4_CAN_NODE2_BASE 0x48014400 +#define XMC4_CAN_NODE3_BASE 0x48014500 +#define XMC4_CAN_NODE4_BASE 0x48014600 +#define XMC4_CAN_NODE5_BASE 0x48014700 +#define XMC4_CAN_MO_BASE 0x48015000 +#define XMC4_DAC_BASE 0x48018000 +#define XMC4_SDMMC_BASE 0x4801c000 +#define XMC4_USIC1_CH0_BASE 0x48020000 +#define XMC4_USIC1_BASE 0x48020008 +#define XMC4_USIC1_CH1_BASE 0x48020200 +#define XMC4_USIC2_CH0_BASE 0x48024000 +#define XMC4_USIC2_BASE 0x48024008 +#define XMC4_USIC2_CH1_BASE 0x48024200 +#define XMC4_PORT0_BASE 0x48028000 +#define XMC4_PORT1_BASE 0x48028100 +#define XMC4_PORT2_BASE 0x48028200 +#define XMC4_PORT3_BASE 0x48028300 +#define XMC4_PORT4_BASE 0x48028400 +#define XMC4_PORT5_BASE 0x48028500 +#define XMC4_PORT6_BASE 0x48028600 +#define XMC4_PORT7_BASE 0x48028700 +#define XMC4_PORT8_BASE 0x48028800 +#define XMC4_PORT9_BASE 0x48028900 +#define XMC4_PORT14_BASE 0x48028e00 +#define XMC4_PORT15_BASE 0x48028f00 + +#define XMC4_SCU_GENERAL_BASE 0x50004000 +#define XMC4_ETH0_CON_BASE 0x50004040 +#define XMC4_SCU_INTERRUPT_BASE 0x50004074 +#define XMC4_SDMMC_CON_BASE 0x500040b4 +#define XMC4_SCU_PARITY_BASE 0x5000413c +#define XMC4_SCU_TRAP_BASE 0x50004160 +#define XMC4_SCU_POWER_BASE 0x50004200 +#define XMC4_SCU_HIBERNATE_BASE 0x50004300 +#define XMC4_SCU_RESET_BASE 0x50004400 +#define XMC4_SCU_CLK_BASE 0x50004600 +#define XMC4_SCU_OSC_BASE 0x50004700 +#define XMC4_SCU_PLL_BASE 0x50004710 +#define XMC4_ERU0_BASE 0x50004800 +#define XMC4_DLR_BASE 0x50004900 +#define XMC4_RTC_BASE 0x50004a00 +#define XMC4_WDT_BASE 0x50008000 +#define XMC4_ETH0_BASE 0x5000c000 +#define XMC4_USB0_BASE 0x50040000 +#define XMC4_USB0_CH0_BASE 0x50040500 +#define XMC4_USB0_CH1_BASE 0x50040520 +#define XMC4_USB0_CH2_BASE 0x50040540 +#define XMC4_USB0_CH3_BASE 0x50040560 +#define XMC4_USB0_CH4_BASE 0x50040580 +#define XMC4_USB0_CH5_BASE 0x500405a0 +#define XMC4_USB0_CH6_BASE 0x500405c0 +#define XMC4_USB0_CH7_BASE 0x500405e0 +#define XMC4_USB0_CH8_BASE 0x50040600 +#define XMC4_USB0_CH9_BASE 0x50040620 +#define XMC4_USB0_CH10_BASE 0x50040640 +#define XMC4_USB0_CH11_BASE 0x50040660 +#define XMC4_USB0_CH12_BASE 0x50040680 +#define XMC4_USB0_CH13_BASE 0x500406a0 +#define XMC4_USB_EP_BASE 0x50040900 +#define XMC4_USB0_EP1_BASE 0x50040920 +#define XMC4_USB0_EP2_BASE 0x50040940 +#define XMC4_USB0_EP3_BASE 0x50040960 +#define XMC4_USB0_EP4_BASE 0x50040980 +#define XMC4_USB0_EP5_BASE 0x500409a0 +#define XMC4_USB0_EP6_BASE 0x500409c0 +#define XMC4_GPDMA0_CH0_BASE 0x50014000 +#define XMC4_GPDMA0_CH1_BASE 0x50014058 +#define XMC4_GPDMA0_CH2_BASE 0x500140b0 +#define XMC4_GPDMA0_CH3_BASE 0x50014108 +#define XMC4_GPDMA0_CH4_BASE 0x50014160 +#define XMC4_GPDMA0_CH5_BASE 0x500141b8 +#define XMC4_GPDMA0_CH6_BASE 0x50014210 +#define XMC4_GPDMA0_CH7_BASE 0x50014268 +#define XMC4_GPDMA0_BASE 0x500142c0 +#define XMC4_GPDMA1_CH0_BASE 0x50018000 +#define XMC4_GPDMA1_CH1_BASE 0x50018058 +#define XMC4_GPDMA1_CH2_BASE 0x500180b0 +#define XMC4_GPDMA1_CH3_BASE 0x50018108 +#define XMC4_GPDMA1_BASE 0x500182c0 +#define XMC4_FCE_BASE 0x50020000 +#define XMC4_FCE_KE0_BASE 0x50020020 +#define XMC4_FCE_KE1_BASE 0x50020040 +#define XMC4_FCE_KE2_BASE 0x50020060 +#define XMC4_FCE_KE3_BASE 0x50020080 + +#define XMC4_PMU0_BASE 0x58000500 +#define XMC4_FLASH0_BASE 0x58001000 +#define XMC4_PREF_BASE 0x58004000 +#define XMC4_EBU_BASE 0x58008000 + +#define XMC4_PPB_BASE 0xe000e000 + +#endif /* __ARCH_ARM_SRC_XMC4_CHIP_XMC4_SCU_H */ diff --git a/arch/arm/src/xmc4/chip/xmc4_scu.h b/arch/arm/src/xmc4/chip/xmc4_scu.h index 8f6f89cc4a..e08a64a48c 100644 --- a/arch/arm/src/xmc4/chip/xmc4_scu.h +++ b/arch/arm/src/xmc4/chip/xmc4_scu.h @@ -626,18 +626,26 @@ #define SCU_SYSCLKCR_SYSDIV_MASK (0xff << SCU_CLK_SYSCLKCR_SYSDIV_SHIFT) # define SCU_SYSCLKCR_SYSDIV(n) ((uint32_t)((n)-1) << SCU_CLK_SYSCLKCR_SYSDIV_SHIFT) -#define SCU_SYSCLKCR_SYSSEL (1 << 16) /* Bit 16: System Clock Selection Value */ -# define SCU_SYSCLKCR_SYSSEL_OFI (0) /* 0=OFI clock */ -# define SCU_SYSCLKCR_SYSSEL_PLL (1 << 16) /* 1=PLL clock */ +#define SCU_SYSCLKCR_SYSSEL (1 << 16) /* Bit 16: System Clock Selection Value */ +# define SCU_SYSCLKCR_SYSSEL_OFI (0) /* 0=OFI clock */ +# define SCU_SYSCLKCR_SYSSEL_PLL (1 << 16) /* 1=PLL clock */ /* CPU Clock Control */ -#define SCU_CPUCLKCR_CPUDIV (1 << 0) /* Bit 0: CPU Clock Divider Enable */ +#define SCU_CPUCLKCR_CPUDIV (1 << 0) /* Bit 0: CPU Clock Divider Enable */ /* Peripheral Bus Clock Control */ #define SCU_PBCLKCR_ + /* USB Clock Control */ -#define SCU_USBCLKCR_ + +#define SCU_USBCLKCR_USBDIV_SHIFT (0) /* Bits 0-2: USB Clock Divider Value */ +#define SCU_USBCLKCR_USBDIV_MASK (7 << SCU_CLK_USBCLKCR_USBDIV_SHIFT) +# define SCU_SYSCLKCR_USBDIV(n) ((uint32_t)((n)-1) << SCU_CLK_USBCLKCR_USBDIV_SHIFT) +#define SCU_USBCLKCR_USBSEL (1 << 16) /* Bit 16: USB Clock Selection Value */ +# define SCU_USBCLKCR_USBSEL_USBPLL (0) /* 0=USB PLL Clock */ +# define SCU_USBCLKCR_USBSEL_PLL (1 << 16) /* 1= PLL Clock */ + /* EBU Clock Control */ #define SCU_EBUCLKCR_ /* CCU Clock Control */ @@ -752,10 +760,34 @@ # define SCU_PLLCON2_K1INSEL_OFI (1 << 8) /* 1=Backup clock source selected */ /* USB PLL Status Register */ -#define SCU_USBPLLSTAT_ + +#define SCU_USBPLLSTAT_VCOBYST (1 << 0) /* Bit 0: VCO Bypass Status */ +#define SCU_USBPLLSTAT_PWDSTAT (1 << 1) /* Bit 1: PLL Power-saving Mode Status */ +#define SCU_USBPLLSTAT_VCOLOCK (1 << 2) /* Bit 2: PLL VCO Lock Status */ +#define SCU_USBPLLSTAT_BY (1 << 6) /* Bit 6: Bypass Mode Status */ +#define SCU_USBPLLSTAT_VCOLOCKED (1 << 7) /* Bit 7: PLL LOCK Status */ + /* USB PLL Control Register */ -#define SCU_USBPLLCON_ + +#define SCU_USBPLLCON_VCOBYP (1 << 0) /* Bit 0: VCO Bypass */ +#define SCU_USBPLLCON_VCOPWD (1 << 1) /* Bit 1: VCO Power Saving Mode */ +#define SCU_USBPLLCON_VCOTR (1 << 2) /* Bit 2: VCO Trim Control */ +#define SCU_USBPLLCON_FINDIS (1 << 4) /* Bit 4: Disconnect Oscillator from VCO */ +#define SCU_USBPLLCON_OSCDISCDIS (1 << 6) /* Bit 6: Oscillator Disconnect Disable */ +#define SCU_USBPLLCON_NDIV_SHIFT (8) /* Bits 8-14: N-Divider Val */ +#define SCU_USBPLLCON_NDIV_MASK (0x7f << SCU_USBPLLCON_NDIV_SHIFT) +# define SCU_USBPLLCON_NDIV(n) ((uint32_t)((n)-1) << SCU_USBPLLCON_NDIV_SHIFT) +#define SCU_USBPLLCON_PLLPWD (1 << 16) /* Bit 16: PLL Power Saving Mode */ +#define SCU_USBPLLCON_RESLD (1 << 18) /* Bit 18: Restart VCO Lock Detection */ +#define SCU_USBPLLCON_PDIV_SHIFT (24) /* Bits 24-27: P-Divider Value */ +#define SCU_USBPLLCON_PDIV_MASK (15 << SCU_USBPLLCON_PDIV_SHIFT) +# define SCU_USBPLLCON_PDIV(n) ((uint32_t)((n)-1) << SCU_USBPLLCON_PDIV_SHIFT) + /* Clock Multiplexing Status Register */ -#define SCU_CLKMXSTAT_ + +#define SCU_CLKMXSTAT_SYSCLKMUX_SHIFT (0) /* Bits 0-1: System Clock Multiplexing Status */ +#define SCU_CLKMXSTAT_SYSCLKMUX_MASK (3 << SCU_CLKMXSTAT_SYSCLKMUX_SHIFT) +# define SCU_CLKMXSTAT_SYSCLKMUX_OFI (1 << SCU_CLKMXSTAT_SYSCLKMUX_SHIFT) +# define SCU_CLKMXSTAT_SYSCLKMUX_PLL (2 << SCU_CLKMXSTAT_SYSCLKMUX_SHIFT) #endif /* __ARCH_ARM_SRC_XMC4_CHIP_XMC4_SCU_H */ diff --git a/arch/arm/src/xmc4/xmc4_clockconfig.c b/arch/arm/src/xmc4/xmc4_clockconfig.c index d7d5a8bc7d..6667ceca86 100644 --- a/arch/arm/src/xmc4/xmc4_clockconfig.c +++ b/arch/arm/src/xmc4/xmc4_clockconfig.c @@ -56,6 +56,7 @@ #include #include "up_arch.h" +#include "chip/xmc4_scu.h" #include @@ -63,10 +64,77 @@ * Pre-processor Definitions ****************************************************************************/ +/* Oscilator reference frequency */ + +#define FOSCREF (2500000U) + +/* Loop delays at different CPU frequencies */ + +#define DELAY_CNT_50US_50MHZ (2500) +#define DELAY_CNT_150US_50MHZ (7500) +#define DELAY_CNT_50US_48MHZ (2400) +#define DELAY_CNT_50US_72MHZ (3600) +#define DELAY_CNT_50US_96MHZ (4800) +#define DELAY_CNT_50US_120MHZ (6000) +#define DELAY_CNT_50US_144MHZ (7200) + +/* PLL settings */ + +#define SCU_PLLSTAT_OSC_USABLE \ + (SCU_PLLSTAT_PLLHV | SCU_PLLSTAT_PLLLV | SCU_PLLSTAT_PLLSP) + +#ifndef BOARD_PLL_CLOCKSRC_XTAL +# define VCO ((BOARD_XTAL_FREQUENCY / BOARD_PLL_PDIV) * BOARD_PLL_NDIV) +#else /* BOARD_PLL_CLOCKSRC_XTAL */ + +# define BOARD_PLL_PDIV 2 +# define BOARD_PLL_NDIV 24 +# define BOARD_PLL_K2DIV 1 + +# define VCO ((OFI_FREQUENCY / BOARD_PLL_PDIV) * BOARD_PLL_NDIV) + +#endif /* !BOARD_PLL_CLOCKSRC_XTAL */ + +#define PLL_K2DIV_24MHZ (VCO / OFI_FREQUENCY) +#define PLL_K2DIV_48MHZ (VCO / 48000000) +#define PLL_K2DIV_72MHZ (VCO / 72000000) +#define PLL_K2DIV_96MHZ (VCO / 96000000) +#define PLL_K2DIV_120MHZ (VCO / 120000000) + +#define CLKSET_VALUE (0x00000000) +#define SYSCLKCR_VALUE (0x00010001) +#define CPUCLKCR_VALUE (0x00000000) +#define PBCLKCR_VALUE (0x00000000) +#define CCUCLKCR_VALUE (0x00000000) +#define WDTCLKCR_VALUE (0x00000000) +#define EBUCLKCR_VALUE (0x00000003) +#define USBCLKCR_VALUE (0x00010000) +#define EXTCLKCR_VALUE (0x01200003) + +#if ((USBCLKCR_VALUE & SCU_USBCLKCR_USBSEL) == SCU_USBCLKCR_USBSEL_USBPLL) +# define USB_DIV 3 +#else +# define USB_DIV 5 +#endif + /**************************************************************************** * Private Functions ****************************************************************************/ +/**************************************************************************** + * Name: delay + ****************************************************************************/ + +static void delay(uint32_t cycles) +{ + volatile uint32_t i; + + for (i = 0; i < cycles ;++i) + { + __asm__ __volatile__ ("nop"); + } +} + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -83,6 +151,383 @@ void xmc4_clock_configure(void) { + uint32_t regval; + uint32_t bitset; + + /* Disable and clear OSC_HP Oscillator Watchdog, System VCO Lock, USB VCO + * Lock, and OSC_ULP Oscillator Watchdog traps. + */ + + bitset = SCU_TRAP_SOSCWDGT | SCU_TRAP_SVCOLCKT | SCU_TRAP_UVCOLCKT | + SCU_TRAP_ULPWDGT; + + regval = getreg32(XMC4_SCU_TRAPDIS); + regval |= bitset; + putreg32(regval, XMC4_SCU_TRAPDIS); + putreg32(bitset, XMC4_SCU_TRAPCLR); + +#ifdef BOARD_FOFI_CALIBRATION + /* Enable factory calibration */ + + regval = getreg32(XMC4_SCU_PLLCON0); + regval |= SCU_PLLCON0_FOTR; + putreg(regval, XMC4_SCU_PLLCON0); +#else + /* Automatic calibration uses the fSTDBY */ + + /* Enable HIB domain */ + /* Power up HIB domain if and only if it is currently powered down */ + + regval = getreg32(XMC4_SCU_PWRSTAT); + if ((regval & SCU_PWR_HIBEN) == 0) + { + regval = getreg32(XMC4_SCU_PWRSET); + regval |= SCU_PWR_HIBEN; + putreg32(regval, XMC4_SCU_PWRSTAT); + + /* Wait until HIB domain is enabled */ + + while((getreg32(XMC4_SCU_PWRSTAT) & SCU_PWR_HIBEN) == 0) + { + } + } + + /* Remove the reset only if HIB domain were in a state of reset */ + + regval = getreg32(XMC4_SCU_RSTSTAT); + if ((regval & SCU_RSTSTAT_HIBRS) ! = 0) + { + regval = getreg32(XMC4_SCU_RSTSTAT); + SCU_RESET->RSTCLR |= SCU_RESET_RSTCLR_HIBRS_Msk; + delay(DELAY_CNT_150US_50MHZ); + } + +#ifdef BOARD_STDBY_CLOCKSRC_OSCULP + /* Enable OSC_ULP */ + + regval = getreg32(XMC4_SCU_OSCULCTRL); + if ((regval & SCU_OSCULCTRL_MODE_MASK) != 0) + { + /* Check SCU_MIRRSTS to ensure that no transfer over serial interface + * is pending. + */ + + while ((getreg32(XMC4_SCU_MIRRSTS) & SCU_MIRRSTS_OSCULCTRL) != 0) + { + } + + /* Enable OSC_ULP */ + + regval &= ~SCU_OSCULCTRL_MODE_MASK; + putreg32(regval, XMC4_SCU_OSCULCTRL); + + /* Check if the clock is OK using OSCULP Oscillator Watchdog */ + + while ((getreg32(XMC4_SCU_MIRRSTS) & SCU_MIRRSTS_HDCR) != 0) + { + } + + regval = getreg32(XMC4_SCU_HDCR); + regval |= SCU_HDCR_ULPWDGEN; + putreg32(regval, XMC4_SCU_HDCR) + + /* Wait till clock is stable */ + + do + { + /* Check SCU_MIRRSTS to ensure that no transfer over serial interface + * is pending. + */ + + while ((getreg32(XMC4_SCU_MIRRSTS) & SCU_MIRRSTS_HDCLR) != 0) + { + } + + putreg32(SCU_HDCLR_ULPWDG, XMC4_SCU_HDCLR) + delay(DELAY_CNT_50US_50MHZ); + } + while ((getreg32(XMC4_SCU_HDSTAT) & SCU_HDSTAT_ULPWDG) != 0); + } + + /* Now OSC_ULP is running and can be used */ + + while ((getreg32(XMC4_SCU_MIRRSTS) & SCU_MIRRSTS_HDCR) != 0) + { + } + + /* Select OSC_ULP as the clock source for RTC and STDBY */ + + regval = getreg32(XMC4_SCU_HDCR); + regval |= (SCU_HDCR_RCS_ULP | SCU_HDCR_STDBYSEL_ULP); + putreg32(regval, XMC4_SCU_HDCR) + + regval = getreg32(XMC4_SCU_TRAPDIS); + regval &= ~SCU_TRAP_ULPWDGT; + putreg32(regval, XMC4_SCU_TRAPDIS); + +#endif /* BOARD_STDBY_CLOCKSRC_OSCULP */ + + /* Enable automatic calibration of internal fast oscillator */ + + regval = getreg32(XMC4_SCU_PLLCON0); + regval |= SCU_PLLCON0_AOTREN; + putreg(regval, XMC4_SCU_PLLCON0); + +#endif /* BOARD_FOFI_CALIBRATION */ + + delay(DELAY_CNT_50US_50MHZ); + +#if BOARD_ENABLE_PLL + + /* Enable PLL */ + + regval = getreg32(XMC4_SCU_PLLCON0); + regval &= ~(SCU_PLLCON0_VCOPWD | SCU_PLLCON0_PLLPWD); + putreg(regval, XMC4_SCU_PLLCON0); + +#ifdef BOARD_PLL_CLOCKSRC_XTAL + /* Enable OSC_HP */ + + if ((getreg32(XMC4_SCU_OSCHPCTRL) & SCU_OSCHPCTRL_MODE_MASK) != 0U) + { + regval = getreg32(XMC4_SCU_OSCHPCTRL); + regval &= ~(SCU_OSCHPCTRL_MODE_MASK | SCU_OSCHPCTRL_OSCVAL_MASK); + regval |= ((OSCHP_GetFrequency() / FOSCREF) - 1) << SCU_OSCHPCTRL_OSCVAL_SHIFT; + putreg32(regval, XMC4_SCU_OSCHPCTRL); + + /* Select OSC_HP clock as PLL input */ + + regval = getreg32(XMC4_SCU_PLLCON2); + regval &= ~SCU_PLLCON2_PINSEL; + putreg32(regval, XMC4_SCU_PLLCON2); + + /* Restart OSC Watchdog */ + + regval = getreg32(XMC4_SCU_PLLCON0); + regval &= ~SCU_PLLCON0_OSCRES; + putreg(regval, XMC4_SCU_PLLCON0); + + /* Wait till OSC_HP output frequency is usable */ + + while ((getreg32(XMC4_SCU_PLLSTAT) & SCU_PLLSTAT_OSC_USABLE) != SCU_PLLSTAT_OSC_USABLE) + { + } + + regval = getreg32(SCU_TRAP_SOSCWDGT); + regval &= ~bitset; + putreg32(regval, SCU_TRAP_SOSCWDGT); + } +#else /* BOARD_PLL_CLOCKSRC_XTAL */ + + /* Select backup clock as PLL input */ + + regval = getreg32(XMC4_SCU_PLLCON2); + regval |= SCU_PLLCON2_PINSEL; + putreg32(regval, XMC4_SCU_PLLCON2); +#endif + + /* Go to bypass the Main PLL */ + + regval = getreg32(XMC4_SCU_PLLCON0); + regval |= SCU_PLLCON0_VCOBYP; + putreg(regval, XMC4_SCU_PLLCON0); + + /* Disconnect Oscillator from PLL */ + + regval |= SCU_PLLCON0_FINDIS; + putreg(regval, XMC4_SCU_PLLCON0); + + /* Setup divider settings for main PLL */ + + regval = (SCU_PLLCON1_NDIV(BOARD_PLL_NDIV) | + SCU_PLLCON1_K2DIV(PLL_K2DIV_24MHZ) | + SCU_PLLCON1_PDIV(BOARD_PLL_PDIV); + putreg32(regval, XMC4_SCU_PLLCON1); + + /* Set OSCDISCDIS */ + + regval = getreg32(XMC4_SCU_PLLCON0); + regval |= SCU_PLLCON0_OSCDISCDIS; + putreg(regval, XMC4_SCU_PLLCON0); + + /* Connect Oscillator to PLL */ + + regval = getreg32(XMC4_SCU_PLLCON0); + regval &= ~SCU_PLLCON0_FINDIS; + putreg(regval, XMC4_SCU_PLLCON0); + + /* Restart PLL Lock detection */ + + regval |= SCU_PLLCON0_RESLD; + putreg(regval, XMC4_SCU_PLLCON0); + + /* wait for PLL Lock at 24MHz*/ + + while ((getreg32(XMC4_SCU_PLLSTAT) & SCU_PLLSTAT_VCOLOCK) == 0) + { + } + + /* Disable bypass- put PLL clock back */ + + regval = getreg32(XMC4_SCU_PLLCON0); + regval &= ~SCU_PLLCON0_VCOBYP; + putreg(regval, XMC4_SCU_PLLCON0); + + /* Wait for normal mode */ + + while ((getreg32(XMC4_SCU_PLLSTAT) & SCU_PLLSTAT_VCOBYST) != 0) + { + } + + regval = getreg32(XMC4_SCU_TRAPDIS); + regval &= ~SCU_TRAP_UVCOLCKT; + putreg32(regval, XMC4_SCU_TRAPDIS); +#endif /* BOARD_ENABLE_PLL */ + + /* Before scaling to final frequency we need to setup the clock dividers */ + + putreg32(SYSCLKCR_VALUE, XMC4_SCU_SYSCLKCR); + putreg32(PBCLKCR_VALUE, XMC4_SCU_PBCLKCR); + putreg32(CPUCLKCR_VALUE, XMC4_SCU_CPUCLKCR); + putreg32(CCUCLKCR_VALUE, XMC4_SCU_CCUCLKCR); + putreg32(WDTCLKCR_VALUE, XMC4_SCU_WDTCLKCR); + putreg32(EBUCLKCR_VALUE, XMC4_SCU_EBUCLKCR); + putreg32(USBCLKCR_VALUE | USB_DIV, XMC4_SCU_USBCLKCR); + putreg32(EXTCLKCR_VALUE, EXTCLKCR); + +#if BOARD_ENABLE_PLL + /* PLL frequency stepping...*/ + /* Reset OSCDISCDIS */ + + regval = getreg32(XMC4_SCU_PLLCON0); + regval &= ~SCU_PLLCON0_OSCDISCDIS; + putreg(regval, XMC4_SCU_PLLCON0); + + regval = (SCU_PLLCON1_NDIV(BOARD_PLL_NDIV) | + SCU_PLLCON1_K2DIV(PLL_K2DIV_48MHZ) | + SCU_PLLCON1_PDIV(BOARD_PLL_PDIV)); + putreg32(regval, XMC4_SCU_PLLCON1); + + delay(DELAY_CNT_50US_48MHZ); + + regval = (SCU_PLLCON1_NDIV(BOARD_PLL_NDIV) | + SCU_PLLCON1_K2DIV(PLL_K2DIV_72MHZ) | + SCU_PLLCON1_PDIV(BOARD_PLL_PDIV)); + putreg32(regval, XMC4_SCU_PLLCON1); + + delay(DELAY_CNT_50US_72MHZ); + + regval = (SCU_PLLCON1_NDIV(BOARD_PLL_NDIV) | + SCU_PLLCON1_K2DIV(PLL_K2DIV_96MHZ) | + SCU_PLLCON1_PDIV(BOARD_PLL_PDIV)); + putreg32(regval, XMC4_SCU_PLLCON1); + + delay(DELAY_CNT_50US_96MHZ); + + regval = (SCU_PLLCON1_NDIV(BOARD_PLL_NDIV) | + SCU_PLLCON1_K2DIV(PLL_K2DIV_120MHZ) | + SCU_PLLCON1_PDIV(BOARD_PLL_PDIV)); + putreg32(regval, XMC4_SCU_PLLCON1); + + delay(DELAY_CNT_50US_120MHZ); + + regval = (SCU_PLLCON1_NDIV(BOARD_PLL_NDIV) | + SCU_PLLCON1_K2DIV(BOARD_PLL_K2DIV) | + SCU_PLLCON1_PDIV(BOARD_PLL_PDIV)); + putreg32(regval, XMC4_SCU_PLLCON1); + + delay(DELAY_CNT_50US_144MHZ); + +#endif /* BOARD_ENABLE_PLL */ + +#if BOARD_ENABLE_USBPLL + /* Enable USB PLL first */ + + regval = getreg32(XMC4_SCU_USBPLLCON); + regval &= ~(SCU_USBPLLCON_VCOPWD | SCU_USBPLLCON_PLLPWD); + getreg32(regval, XMC4_SCU_USBPLLCON); + + /* USB PLL uses as clock input the OSC_HP */ + /* check and if not already running enable OSC_HP */ + + if ((getreg32(XMC4_SCU_OSCHPCTRL) & SCU_OSCHPCTRL_MODE_MASK) != 0U) + { + /* Check if Main PLL is switched on for OSC WDG */ + + regval = getreg32(XMC4_SCU_PLLCON0); + if ((regval & (SCU_PLLCON0_VCOPWD | SCU_PLLCON0_PLLPWD)) != 0) + { + /* Enable PLL first */ + + regval = getreg32(XMC4_SCU_PLLCON0); + regval &= ~(SCU_PLLCON0_VCOPWD | SCU_PLLCON0_PLLPWD); + putreg(regval, XMC4_SCU_PLLCON0); + } + + regval = getreg32(XMC4_SCU_OSCHPCTRL); + regval &= ~(SCU_OSCHPCTRL_MODE_MASK | SCU_OSCHPCTRL_OSCVAL_MASK); + regval |= ((OSCHP_GetFrequency() / FOSCREF) - 1) << SCU_OSCHPCTRL_OSCVAL_SHIFT; + putreg32(regval, XMC4_SCU_OSCHPCTRL); + + /* Restart OSC Watchdog */ + + regval = getreg32(XMC4_SCU_PLLCON0); + regval &= ~SCU_PLLCON0_OSCRES; + putreg(regval, XMC4_SCU_PLLCON0); + + /* Wait till OSC_HP output frequency is usable */ + + while ((getreg32(XMC4_SCU_PLLSTAT) & SCU_PLLSTAT_OSC_USABLE) != SCU_PLLSTAT_OSC_USABLE) + { + } + } + + /* Setup USB PLL */ + /* Go to bypass the USB PLL */ + + regval = getreg32(XMC4_SCU_USBPLLCON); + regval |= SCU_USBPLLCON_VCOBYP; + putreg32(regval, XMC4_SCU_USBPLLCON); + + /* Disconnect Oscillator from USB PLL */ + + regval |= SCU_USBPLLCON_FINDIS; + putreg32(regval, XMC4_SCU_USBPLLCON); + + /* Setup Divider settings for USB PLL */ + + regval = (SCU_USBPLLCON_NDIV(BOARD_USB_NDIV) | SCU_USBPLLCON_PDIV(BOARD_USB_PDIV)); + putreg32(regval, XMC4_SCU_USBPLLCON); + + /* Set OSCDISCDIS */ + + regval |= SCU_USBPLLCON_OSCDISCDIS; + putreg32(regval, XMC4_SCU_USBPLLCON); + + /* Connect Oscillator to USB PLL */ + + regval &= ~SCU_USBPLLCON_FINDIS; + putreg32(regval, XMC4_SCU_USBPLLCON); + + /* Restart PLL Lock detection */ + + regval |= SCU_USBPLLCON_RESLD; + putreg32(regval, XMC4_SCU_USBPLLCON); + + /* Wait for PLL Lock */ + + while ((getreg32(XMC4_SCU_USBPLLSTAT) & SCU_USBPLLSTAT_VCOLOCK) == 0) + { + } + + regval = getreg32(XMC4_SCU_TRAPDIS); + regval &= ~SCU_TRAP_UVCOLCKT; + putreg32(regval, XMC4_SCU_TRAPDIS); +#endif + + /* Enable selected clocks */ + + putreg32(CLKSET_VALUE, XMC4_SCU_CLKSET) } /**************************************************************************** diff --git a/arch/arm/src/xmc4/xmc4_start.c b/arch/arm/src/xmc4/xmc4_start.c index 77e792847e..e712f97dd3 100644 --- a/arch/arm/src/xmc4/xmc4_start.c +++ b/arch/arm/src/xmc4/xmc4_start.c @@ -48,6 +48,7 @@ #include "up_arch.h" #include "up_internal.h" +#include "chip/xmc4_flash.h" #include "xmc4_userspace.h" @@ -62,6 +63,8 @@ #ifdef CONFIG_ARCH_FPU static inline void xmc4_fpu_config(void); #endif +static inline void xmc4_unaligned(void); +static inline void xmc4_flash_waitstates(void); #ifdef CONFIG_STACK_COLORATION static void go_os_start(void *pv, unsigned int nbytes) __attribute__ ((naked, no_instrument_function, noreturn)); @@ -214,6 +217,41 @@ static inline void xmc4_fpu_config(void) # define xmc4_fpu_config() #endif +/**************************************************************************** + * Name: xmc4_unaligned + * + * Description: + * Enable unaligned memory access by setting SCB_CCR.UNALIGN_TRP = 0 + * + ****************************************************************************/ + +static inline void xmc4_unaligned(void) +{ + uint32_t regval; + + regval = getreg32(NVIC_CFGCON); + regval &= ~NVIC_CFGCON_UNALIGNTRP; + putreg32(regval, NVIC_CFGCON); +} + +/**************************************************************************** + * Name: xmc4_flash_waitstates + * + * Description: + * Enable unaligned memory access by setting SCB_CCR.UNALIGN_TRP = 0 + * + ****************************************************************************/ + +static inline void xmc4_flash_waitstates(void) +{ + uint32_t regval; + + regval = getreg32(XMC4_FLASH_FCON); + regval &= ~FLASH_FCON_WSPFLASH_MASK; + regval |= FLASH_FCON_WSPFLASH(BOARD_FLASH_WS); + putreg32(regval, XMC4_FLASH_FCON); +} + /**************************************************************************** * Name: go_os_start * @@ -281,6 +319,10 @@ void __start(void) xmc4_wddisable(); + /* Enable unaligned memory access */ + + xmc4_unaligned(); + /* Clear .bss. We'll do this inline (vs. calling memset) just to be * certain that there are no issues with the state of global variables. */ @@ -314,6 +356,10 @@ void __start(void) } #endif + /* Set FLASH wait states prior to the configuration of clocking */ + + xmc4_flash_waitstates(); + /* Perform clock and Kinetis module initialization (This depends on * RAM functions having been copied to RAM). */ diff --git a/configs/xmc4500-relax/include/board.h b/configs/xmc4500-relax/include/board.h index a448469bca..f3616a21e2 100644 --- a/configs/xmc4500-relax/include/board.h +++ b/configs/xmc4500-relax/include/board.h @@ -65,6 +65,8 @@ * fOFI = 24MHz => fWDT = 24MHz */ +#undef BOARD_FOFI_CALIBRATION /* Enable factory calibration */ + /* On-board crystals * * NOTE: Only the XMC4500 Relax Kit-V1 provides the 32.768KHz RTC crystal. It @@ -87,6 +89,7 @@ * = 288MHz */ +#define BOARD_ENABLE_PLL 1 #define BOARD_PLL_PDIV 2 #define BOARD_PLL_NDIV 48 #define BOARD_PLL_K2DIV 1 @@ -119,9 +122,14 @@ * fUSBPLLVCO <= 520 MHz */ +#undef BOARD_ENABLE_USBPLL #define BOARD_USB_PDIV 2 #define BOARD_USB_NDIV 64 +/* FLASH wait states */ + +#define BOARD_FLASH_WS 5 + /************************************************************************************ * Public Data ************************************************************************************/ -- GitLab From fe610e7a1d793919f14aaa7f01b69659c51220ec Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 16 Mar 2017 10:52:01 -0600 Subject: [PATCH 069/990] XMC4500 Relax: Add basic board support infrastructure of Infineon XMC4500 Relax Lite v1 --- arch/arm/Kconfig | 25 +- arch/arm/src/xmc4/Kconfig | 2 +- configs/Kconfig | 13 + configs/README.txt | 3 + configs/xmc4500-relax/Kconfig | 4 + configs/xmc4500-relax/nsh/Make.defs | 128 +++ configs/xmc4500-relax/nsh/defconfig | 1038 +++++++++++++++++++++ configs/xmc4500-relax/nsh/setenv.sh | 77 ++ configs/xmc4500-relax/src/Makefile | 55 ++ configs/xmc4500-relax/src/xmc4500-relax.h | 78 ++ configs/xmc4500-relax/src/xmc4_appinit.c | 80 ++ configs/xmc4500-relax/src/xmc4_autoleds.c | 80 ++ configs/xmc4500-relax/src/xmc4_boot.c | 91 ++ configs/xmc4500-relax/src/xmc4_bringup.c | 65 ++ configs/xmc4500-relax/src/xmc4_buttons.c | 78 ++ configs/xmc4500-relax/src/xmc4_userleds.c | 75 ++ 16 files changed, 1879 insertions(+), 13 deletions(-) create mode 100644 configs/xmc4500-relax/Kconfig create mode 100644 configs/xmc4500-relax/nsh/Make.defs create mode 100644 configs/xmc4500-relax/nsh/defconfig create mode 100644 configs/xmc4500-relax/nsh/setenv.sh create mode 100644 configs/xmc4500-relax/src/Makefile create mode 100644 configs/xmc4500-relax/src/xmc4500-relax.h create mode 100644 configs/xmc4500-relax/src/xmc4_appinit.c create mode 100644 configs/xmc4500-relax/src/xmc4_autoleds.c create mode 100644 configs/xmc4500-relax/src/xmc4_boot.c create mode 100644 configs/xmc4500-relax/src/xmc4_bringup.c create mode 100644 configs/xmc4500-relax/src/xmc4_buttons.c create mode 100644 configs/xmc4500-relax/src/xmc4_userleds.c diff --git a/arch/arm/Kconfig b/arch/arm/Kconfig index 21334e7117..ce6fc7f2af 100644 --- a/arch/arm/Kconfig +++ b/arch/arm/Kconfig @@ -151,6 +151,14 @@ config ARCH_CHIP_LPC43XX ---help--- NPX LPC43XX architectures (ARM Cortex-M4). +config ARCH_CHIP_MOXART + bool "MoxART" + select ARCH_ARM7TDMI + select ARCH_HAVE_RESET + select ARCH_HAVE_SERIAL_TERMIOS + ---help--- + MoxART family + config ARCH_CHIP_NUC1XX bool "Nuvoton NUC100/120" select ARCH_CORTEXM0 @@ -283,14 +291,6 @@ config ARCH_CHIP_XMC4 ---help--- Infineon XMC4xxx(ARM Cortex-M4) architectures -config ARCH_CHIP_MOXART - bool "MoxART" - select ARCH_ARM7TDMI - select ARCH_HAVE_RESET - select ARCH_HAVE_SERIAL_TERMIOS - ---help--- - MoxART family - endchoice config ARCH_ARM7TDMI @@ -434,6 +434,7 @@ config ARCH_CHIP default "lpc2378" if ARCH_CHIP_LPC2378 default "lpc31xx" if ARCH_CHIP_LPC31XX default "lpc43xx" if ARCH_CHIP_LPC43XX + default "moxart" if ARCH_CHIP_MOXART default "nuc1xx" if ARCH_CHIP_NUC1XX default "sama5" if ARCH_CHIP_SAMA5 default "samdl" if ARCH_CHIP_SAMD || ARCH_CHIP_SAML @@ -444,7 +445,7 @@ config ARCH_CHIP default "stm32l4" if ARCH_CHIP_STM32L4 default "str71x" if ARCH_CHIP_STR71X default "tms570" if ARCH_CHIP_TMS570 - default "moxart" if ARCH_CHIP_MOXART + default "xmc4" if ARCH_CHIP_XMC4 config ARM_TOOLCHAIN_IAR bool @@ -675,6 +676,9 @@ endif if ARCH_CHIP_LPC43XX source arch/arm/src/lpc43xx/Kconfig endif +if ARCH_CHIP_MOXART +source arch/arm/src/moxart/Kconfig +endif if ARCH_CHIP_NUC1XX source arch/arm/src/nuc1xx/Kconfig endif @@ -708,8 +712,5 @@ endif if ARCH_CHIP_XMC4 source arch/arm/src/xmc4/Kconfig endif -if ARCH_CHIP_MOXART -source arch/arm/src/moxart/Kconfig -endif endif # ARCH_ARM diff --git a/arch/arm/src/xmc4/Kconfig b/arch/arm/src/xmc4/Kconfig index 116d56d14f..096a65fb85 100644 --- a/arch/arm/src/xmc4/Kconfig +++ b/arch/arm/src/xmc4/Kconfig @@ -50,7 +50,7 @@ config XMC4_USCI_I2S # Chip families -menu "ARCH_CHIP_XMC4 Peripheral Support" +menu "XMC4xxx Peripheral Support" config XMC4_USIC0 bool "USIC0" diff --git a/configs/Kconfig b/configs/Kconfig index d5016d9b7c..d4bb9fe5bd 100644 --- a/configs/Kconfig +++ b/configs/Kconfig @@ -1270,6 +1270,15 @@ config ARCH_BOARD_VIEWTOOL_STM32F107 board may be fitted with either: (1) STM32F107VCT6 or (2) STM32F103VCT6. See http://www.viewtool.com/ for further information. +config ARCH_BOARD_XMC4500RELAX + bool "Infineon XMC4500 Relax" + depends on ARCH_CHIP_XMC4500 + select ARCH_HAVE_LEDS + select ARCH_HAVE_BUTTONS + select ARCH_HAVE_IRQBUTTONS + ---help--- + Infineon XMC4000 Relax Lite v1 + config ARCH_BOARD_XTRS bool "XTRS TRS80 Model 3 emulation" depends on ARCH_CHIP_Z80 @@ -1531,6 +1540,7 @@ config ARCH_BOARD default "ubw32" if ARCH_BOARD_UBW32 default "us7032evb1" if ARCH_BOARD_US7032EVB1 default "viewtool-stm32f107" if ARCH_BOARD_VIEWTOOL_STM32F107 + default "xmc4500-relax" if ARCH_BOARD_XMC4500RELAX default "xtrs" if ARCH_BOARD_XTRS default "z16f2800100zcog" if ARCH_BOARD_Z16F2800100ZCOG default "z80sim" if ARCH_BOARD_Z80SIM @@ -1936,6 +1946,9 @@ endif if ARCH_BOARD_VIEWTOOL_STM32F107 source "configs/viewtool-stm32f107/Kconfig" endif +if ARCH_BOARD_XMC4500RELAX +source "configs/xmc4500-relax/Kconfig" +endif if ARCH_BOARD_XTRS source "configs/xtrs/Kconfig" endif diff --git a/configs/README.txt b/configs/README.txt index b883163e71..316108f877 100644 --- a/configs/README.txt +++ b/configs/README.txt @@ -763,6 +763,9 @@ configs/viewtool-stm32f107 board may be fitted with either: (1) STM32F107VCT6 or (2) STM32F103VCT6. See http://www.viewtool.com/ for further information. +config/xmc4500-relax + Infineon XMC4000 Relax Lite v1 + configs/xtrs TRS80 Model 3. This port uses a vintage computer based on the Z80. An emulator for this computer is available to run TRS80 programs on a diff --git a/configs/xmc4500-relax/Kconfig b/configs/xmc4500-relax/Kconfig new file mode 100644 index 0000000000..f72f3c094c --- /dev/null +++ b/configs/xmc4500-relax/Kconfig @@ -0,0 +1,4 @@ +# +# For a description of the syntax of this configuration file, +# see the file kconfig-language.txt in the NuttX tools repository. +# diff --git a/configs/xmc4500-relax/nsh/Make.defs b/configs/xmc4500-relax/nsh/Make.defs new file mode 100644 index 0000000000..2d795a8ee1 --- /dev/null +++ b/configs/xmc4500-relax/nsh/Make.defs @@ -0,0 +1,128 @@ +############################################################################ +# configs/xmc4500-relax/nsh/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. +# +############################################################################ + +include ${TOPDIR}/.config +include ${TOPDIR}/tools/Config.mk +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs + +ifeq ($(CONFIG_ARMV7M_DTCM),y) + LDSCRIPT = flash-dtcm.ld +else + LDSCRIPT = flash-sram.ld +endif + +ifeq ($(WINTOOL),y) + # Windows-native toolchains + DIRLINK = $(TOPDIR)/tools/copydir.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mkwindeps.sh + ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" + ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" +else + # Linux/Cygwin-native toolchain + MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT) + ARCHINCLUDES = -I. -isystem $(TOPDIR)/include + ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) +endif + +CC = $(CROSSDEV)gcc +CXX = $(CROSSDEV)g++ +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(CROSSDEV)ar rcs +NM = $(CROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump + +ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} +ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} + +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + ARCHOPTIMIZATION = -g +endif + +ifneq ($(CONFIG_DEBUG_NOOPT),y) + ARCHOPTIMIZATION += $(MAXOPTIMIZATION) +endif + +ARCHCFLAGS = -fno-builtin +ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fcheck-new -fno-rtti +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow -Wundef -fno-strict-aliasing +ARCHWARNINGSXX = -Wall -Wshadow -Wundef +ARCHDEFINES = +ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 + +CFLAGS = $(ARCHCFLAGS) $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) +CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +NXFLATLDFLAGS1 = -r -d -warn-common +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections +LDNXFLATFLAGS = -e main -s 2048 + +# Loadable module definitions + +CMODULEFLAGS = $(CFLAGS) -mlong-calls # --target1-abs + +LDMODULEFLAGS = -r -e module_initialize +ifeq ($(WINTOOL),y) + LDMODULEFLAGS += -T "${shell cygpath -w $(TOPDIR)/libc/modlib/gnu-elf.ld}" +else + LDMODULEFLAGS += -T $(TOPDIR)/libc/modlib/gnu-elf.ld +endif + +ASMEXT = .S +OBJEXT = .o +LIBEXT = .a +EXEEXT = + +ifneq ($(CROSSDEV),arm-nuttx-elf-) + LDFLAGS += -nostartfiles -nodefaultlibs +endif +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + LDFLAGS += -g +endif + + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -Wundef -g -pipe +HOSTLDFLAGS = + diff --git a/configs/xmc4500-relax/nsh/defconfig b/configs/xmc4500-relax/nsh/defconfig new file mode 100644 index 0000000000..54bd16a392 --- /dev/null +++ b/configs/xmc4500-relax/nsh/defconfig @@ -0,0 +1,1038 @@ +# +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# + +# +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set +# CONFIG_DEFAULT_SMALL is not set +# CONFIG_HOST_LINUX is not set +# CONFIG_HOST_OSX is not set +CONFIG_HOST_WINDOWS=y +# CONFIG_HOST_OTHER is not set +CONFIG_TOOLCHAIN_WINDOWS=y +# CONFIG_WINDOWS_NATIVE is not set +CONFIG_WINDOWS_CYGWIN=y +# CONFIG_WINDOWS_UBUNTU is not set +# CONFIG_WINDOWS_MSYS is not set +# CONFIG_WINDOWS_OTHER is not set + +# +# Build Configuration +# +# CONFIG_APPS_DIR="../apps" +CONFIG_BUILD_FLAT=y +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +# CONFIG_INTELHEX_BINARY is not set +# CONFIG_MOTOROLA_SREC is not set +CONFIG_RAW_BINARY=y +# CONFIG_UBOOT_UIMAGE is not set + +# +# Customize Header Files +# +# CONFIG_ARCH_STDINT_H is not set +# CONFIG_ARCH_STDBOOL_H is not set +# CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_FLOAT_H is not set +# CONFIG_ARCH_STDARG_H is not set +# CONFIG_ARCH_DEBUG_H is not set + +# +# Debug Options +# +CONFIG_DEBUG_ALERT=y +# CONFIG_DEBUG_FEATURES is not set +CONFIG_ARCH_HAVE_STACKCHECK=y +# CONFIG_STACK_COLORATION is not set +# CONFIG_ARCH_HAVE_HEAPCHECK is not set +# CONFIG_DEBUG_SYMBOLS is not set +CONFIG_ARCH_HAVE_CUSTOMOPT=y +# CONFIG_DEBUG_NOOPT is not set +# CONFIG_DEBUG_CUSTOMOPT is not set +CONFIG_DEBUG_FULLOPT=y + +# +# System Type +# +CONFIG_ARCH_ARM=y +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_MISOC is not set +# CONFIG_ARCH_RENESAS is not set +# CONFIG_ARCH_RISCV is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_XTENSA is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="arm" + +# +# ARM Options +# +# CONFIG_ARCH_CHIP_A1X is not set +# CONFIG_ARCH_CHIP_C5471 is not set +# CONFIG_ARCH_CHIP_DM320 is not set +# CONFIG_ARCH_CHIP_EFM32 is not set +# CONFIG_ARCH_CHIP_IMX1 is not set +# CONFIG_ARCH_CHIP_IMX6 is not set +# CONFIG_ARCH_CHIP_KINETIS is not set +# CONFIG_ARCH_CHIP_KL is not set +# CONFIG_ARCH_CHIP_LM is not set +# CONFIG_ARCH_CHIP_TIVA is not set +# CONFIG_ARCH_CHIP_LPC11XX is not set +# CONFIG_ARCH_CHIP_LPC17XX is not set +# CONFIG_ARCH_CHIP_LPC214X is not set +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_NUC1XX is not set +# CONFIG_ARCH_CHIP_SAMA5 is not set +# CONFIG_ARCH_CHIP_SAMD is not set +# CONFIG_ARCH_CHIP_SAML is not set +# CONFIG_ARCH_CHIP_SAM34 is not set +# CONFIG_ARCH_CHIP_SAMV7 is not set +# CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F7 is not set +# CONFIG_ARCH_CHIP_STM32L4 is not set +# CONFIG_ARCH_CHIP_STR71X is not set +# CONFIG_ARCH_CHIP_TMS570 is not set +CONFIG_ARCH_CHIP_XMC4=y +# CONFIG_ARCH_ARM7TDMI is not set +# CONFIG_ARCH_ARM926EJS is not set +# CONFIG_ARCH_ARM920T is not set +# CONFIG_ARCH_CORTEXM0 is not set +# CONFIG_ARCH_CORTEXM23 is not set +# CONFIG_ARCH_CORTEXM3 is not set +# CONFIG_ARCH_CORTEXM33 is not set +CONFIG_ARCH_CORTEXM4=y +# CONFIG_ARCH_CORTEXM7 is not set +# CONFIG_ARCH_CORTEXA5 is not set +# CONFIG_ARCH_CORTEXA8 is not set +# CONFIG_ARCH_CORTEXA9 is not set +# CONFIG_ARCH_CORTEXR4 is not set +# CONFIG_ARCH_CORTEXR4F is not set +# CONFIG_ARCH_CORTEXR5 is not set +# CONFIG_ARCH_CORTEX5F is not set +# CONFIG_ARCH_CORTEXR7 is not set +# CONFIG_ARCH_CORTEXR7F is not set +CONFIG_ARCH_FAMILY="armv7-m" +CONFIG_ARCH_CHIP="xmc4" +# CONFIG_ARM_TOOLCHAIN_IAR is not set +CONFIG_ARM_TOOLCHAIN_GNU=y +# CONFIG_ARMV7M_USEBASEPRI is not set +CONFIG_ARCH_HAVE_CMNVECTOR=y +CONFIG_ARMV7M_CMNVECTOR=y +CONFIG_ARMV7M_LAZYFPU=y +# CONFIG_ARCH_HAVE_FPU is not set +# CONFIG_ARCH_HAVE_DPFPU is not set +# CONFIG_ARCH_HAVE_TRUSTZONE is not set +CONFIG_ARM_HAVE_MPU_UNIFIED=y +# CONFIG_ARM_MPU is not set + +# +# ARMV7M Configuration Options +# +# CONFIG_ARMV7M_HAVE_ICACHE is not set +# CONFIG_ARMV7M_HAVE_DCACHE is not set +# CONFIG_ARMV7M_HAVE_ITCM is not set +# CONFIG_ARMV7M_HAVE_DTCM is not set +# CONFIG_ARMV7M_TOOLCHAIN_IARW is not set +# CONFIG_ARMV7M_TOOLCHAIN_ATOLLIC is not set +# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set +# CONFIG_ARMV7M_TOOLCHAIN_CODEREDW is not set +# CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYW is not set +# CONFIG_ARMV7M_TOOLCHAIN_DEVKITARM is not set +# CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL is not set +CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIW=y +# CONFIG_ARMV7M_TOOLCHAIN_RAISONANCE is not set +CONFIG_ARMV7M_HAVE_STACKCHECK=y +# CONFIG_ARMV7M_STACKCHECK is not set +# CONFIG_ARMV7M_ITMSYSLOG is not set + +# +# XMC4xxx Configuration Options +# +CONFIG_ARCH_CHIP_XMC4500=y +CONFIG_XMC4_USIC=y +CONFIG_XMC4_USCI_UART=y +# CONFIG_XMC4_USCI_LIN is not set +# CONFIG_XMC4_USCI_SPI is not set +# CONFIG_XMC4_USCI_I2C is not set +# CONFIG_XMC4_USCI_I2S is not set + +# +# XMC4xxx Peripheral Support +# +CONFIG_XMC4_USIC0=y +# CONFIG_XMC4_USIC1 is not set +# CONFIG_XMC4_USIC2 is not set +# CONFIG_XMC4_USIC3 is not set +# CONFIG_XMC4_USIC4 is not set +# CONFIG_XMC4_USIC5 is not set + +# +# XMC4xxx USIC Configuration +# +CONFIG_XMC4_USIC0_ISUART=y +# CONFIG_XMC4_USIC0_ISLIN is not set +# CONFIG_XMC4_USIC0_ISSPI is not set +# CONFIG_XMC4_USIC0_ISI2C is not set +# CONFIG_XMC4_USIC0_ISI2S is not set + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_VECNOTIRQ is not set +# CONFIG_ARCH_DMA is not set +CONFIG_ARCH_HAVE_IRQPRIO=y +# CONFIG_ARCH_L2CACHE is not set +# CONFIG_ARCH_HAVE_COHERENT_DCACHE is not set +# CONFIG_ARCH_HAVE_ADDRENV is not set +# CONFIG_ARCH_NEED_ADDRENV_MAPPING is not set +# CONFIG_ARCH_HAVE_MULTICPU is not set +CONFIG_ARCH_HAVE_VFORK=y +# CONFIG_ARCH_HAVE_MMU is not set +CONFIG_ARCH_HAVE_MPU=y +# CONFIG_ARCH_NAND_HWECC is not set +# CONFIG_ARCH_HAVE_EXTCLK is not set +# CONFIG_ARCH_HAVE_POWEROFF is not set +CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_USE_MPU is not set +# CONFIG_ARCH_IRQPRIO is not set +CONFIG_ARCH_STACKDUMP=y +# CONFIG_ENDIAN_BIG is not set +# CONFIG_ARCH_IDLE_CUSTOM is not set +CONFIG_ARCH_HAVE_RAMFUNCS=y +# CONFIG_ARCH_RAMFUNCS is not set +CONFIG_ARCH_HAVE_RAMVECTORS=y +# CONFIG_ARCH_RAMVECTORS is not set +# CONFIG_ARCH_MINIMAL_VECTORTABLE is not set + +# +# Board Settings +# +CONFIG_BOARD_LOOPSPERMSEC=8000 +# CONFIG_ARCH_CALIBRATION is not set + +# +# Interrupt options +# +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y +CONFIG_ARCH_INTERRUPTSTACK=2048 +CONFIG_ARCH_HAVE_HIPRI_INTERRUPT=y +# CONFIG_ARCH_HIPRI_INTERRUPT is not set + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Boot Memory Configuration +# +CONFIG_RAM_START=0x20400000 +CONFIG_RAM_SIZE=393216 +# CONFIG_ARCH_HAVE_SDRAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_XMC4500RELAX=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="xmc4500-relax" + +# +# Common Board Options +# +CONFIG_ARCH_HAVE_LEDS=y +CONFIG_ARCH_LEDS=y +CONFIG_ARCH_HAVE_BUTTONS=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_HAVE_IRQBUTTONS=y +CONFIG_ARCH_IRQBUTTONS=y + +# +# Board-Specific Options +# +# CONFIG_BOARD_CRASHDUMP is not set +CONFIG_LIB_BOARDCTL=y +# CONFIG_BOARDCTL_RESET is not set +# CONFIG_BOARDCTL_UNIQUEID is not set +# CONFIG_BOARDCTL_TSCTEST is not set +# CONFIG_BOARDCTL_GRAPHICS is not set +# CONFIG_BOARDCTL_IOCTL is not set + +# +# RTOS Features +# +CONFIG_DISABLE_OS_API=y +# CONFIG_DISABLE_POSIX_TIMERS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_DISABLE_SIGNALS is not set +# CONFIG_DISABLE_MQUEUE is not set +# CONFIG_DISABLE_ENVIRON is not set + +# +# Clocks and Timers +# +CONFIG_USEC_PER_TICK=10000 +# CONFIG_SYSTEM_TIME64 is not set +# CONFIG_CLOCK_MONOTONIC is not set +# CONFIG_ARCH_HAVE_TIMEKEEPING is not set +# CONFIG_JULIAN_TIME is not set +CONFIG_START_YEAR=2014 +CONFIG_START_MONTH=3 +CONFIG_START_DAY=10 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=32 +CONFIG_WDOG_INTRESERVE=4 +CONFIG_PREALLOC_TIMERS=4 + +# +# Tasks and Scheduling +# +# CONFIG_SPINLOCK is not set +# CONFIG_INIT_NONE is not set +CONFIG_INIT_ENTRYPOINT=y +# CONFIG_INIT_FILEPATH is not set +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_RR_INTERVAL=200 +# CONFIG_SCHED_SPORADIC is not set +CONFIG_TASK_NAME_SIZE=31 +CONFIG_MAX_TASKS=16 +# CONFIG_SCHED_HAVE_PARENT is not set +CONFIG_SCHED_WAITPID=y + +# +# Pthread Options +# +# CONFIG_MUTEX_TYPES is not set +CONFIG_NPTHREAD_KEYS=4 +# CONFIG_PTHREAD_CLEANUP is not set +# CONFIG_CANCELLATION_POINTS is not set + +# +# Performance Monitoring +# +# CONFIG_SCHED_CPULOAD is not set +# CONFIG_SCHED_INSTRUMENTATION is not set + +# +# Files and I/O +# +CONFIG_DEV_CONSOLE=y +# CONFIG_FDCLONE_DISABLE is not set +# CONFIG_FDCLONE_STDIO is not set +CONFIG_SDCLONE_DISABLE=y +CONFIG_NFILE_DESCRIPTORS=8 +CONFIG_NFILE_STREAMS=8 +CONFIG_NAME_MAX=32 +# CONFIG_PRIORITY_INHERITANCE is not set + +# +# RTOS hooks +# +# CONFIG_BOARD_INITIALIZE is not set +# CONFIG_SCHED_STARTHOOK is not set +# CONFIG_SCHED_ATEXIT is not set +# CONFIG_SCHED_ONEXIT is not set +# CONFIG_SIG_EVTHREAD is not set + +# +# Signal Numbers +# +CONFIG_SIG_SIGUSR1=1 +CONFIG_SIG_SIGUSR2=2 +CONFIG_SIG_SIGALARM=3 +CONFIG_SIG_SIGCONDTIMEDOUT=16 +CONFIG_SIG_SIGWORK=17 + +# +# POSIX Message Queue Options +# +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_MQ_MAXMSGSIZE=32 +# CONFIG_MODULE is not set + +# +# Work queue support +# +CONFIG_SCHED_WORKQUEUE=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=224 +CONFIG_SCHED_HPWORKPERIOD=50000 +CONFIG_SCHED_HPWORKSTACKSIZE=2048 +# CONFIG_SCHED_LPWORK is not set + +# +# Stack and heap information +# +CONFIG_IDLETHREAD_STACKSIZE=1024 +CONFIG_USERMAIN_STACKSIZE=2048 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=2048 +# CONFIG_LIB_SYSCALL is not set + +# +# Device Drivers +# +CONFIG_DISABLE_POLL=y +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_DEV_URANDOM is not set +# CONFIG_DEV_LOOP is not set + +# +# Buffering +# +# CONFIG_DRVR_WRITEBUFFER is not set +# CONFIG_DRVR_READAHEAD is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_ARCH_HAVE_PWM_PULSECOUNT is not set +# CONFIG_ARCH_HAVE_PWM_MULTICHAN is not set +# CONFIG_PWM is not set +CONFIG_ARCH_HAVE_I2CRESET=y +CONFIG_I2C=y +# CONFIG_I2C_SLAVE is not set +# CONFIG_I2C_POLLED is not set +CONFIG_I2C_RESET=y +# CONFIG_I2C_TRACE is not set +CONFIG_I2C_DRIVER=y +# CONFIG_ARCH_HAVE_SPI_CRCGENERATION is not set +# CONFIG_ARCH_HAVE_SPI_CS_CONTROL is not set +# CONFIG_ARCH_HAVE_SPI_BITORDER is not set +CONFIG_SPI=y +# CONFIG_SPI_SLAVE is not set +CONFIG_SPI_EXCHANGE=y +# CONFIG_SPI_CMDDATA is not set +# CONFIG_SPI_CALLBACK is not set +# CONFIG_SPI_HWFEATURES is not set +# CONFIG_SPI_CS_DELAY_CONTROL is not set +# CONFIG_SPI_DRIVER is not set +# CONFIG_SPI_BITBANG is not set +# CONFIG_I2S is not set + +# +# Timer Driver Support +# +# CONFIG_TIMER is not set +# CONFIG_ONESHOT is not set +# CONFIG_RTC is not set +# CONFIG_WATCHDOG is not set +# CONFIG_TIMERS_CS2100CP is not set +# CONFIG_ANALOG is not set +# CONFIG_AUDIO_DEVICES is not set +# CONFIG_VIDEO_DEVICES is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set + +# +# IO Expander/GPIO Support +# +# CONFIG_IOEXPANDER is not set +# CONFIG_DEV_GPIO is not set + +# +# LCD Driver Support +# +# CONFIG_LCD is not set +# CONFIG_SLCD is not set + +# +# LED Support +# +# CONFIG_USERLED is not set +# CONFIG_RGBLED is not set +# CONFIG_PCA9635PW is not set +# CONFIG_NCP5623C is not set +CONFIG_MMCSD=y +CONFIG_MMCSD_NSLOTS=1 +# CONFIG_MMCSD_READONLY is not set +CONFIG_MMCSD_MULTIBLOCK_DISABLE=y +# CONFIG_MMCSD_MMCSUPPORT is not set +CONFIG_MMCSD_HAVECARDDETECT=y +# CONFIG_MMCSD_SPI is not set +# CONFIG_ARCH_HAVE_SDIO is not set +# CONFIG_SDIO_DMA is not set +# CONFIG_ARCH_HAVE_SDIOWAIT_WRCOMPLETE is not set +# CONFIG_MODEM is not set +CONFIG_MTD=y + +# +# MTD Configuration +# +# CONFIG_MTD_PARTITION is not set +# CONFIG_MTD_SECT512 is not set +# CONFIG_MTD_BYTE_WRITE is not set +# CONFIG_MTD_PROGMEM is not set +CONFIG_MTD_CONFIG=y +# CONFIG_MTD_CONFIG_RAM_CONSOLIDATE is not set +CONFIG_MTD_CONFIG_ERASEDVALUE=0xff + +# +# MTD Device Drivers +# +# CONFIG_MTD_NAND is not set +# CONFIG_RAMMTD is not set +# CONFIG_FILEMTD is not set +CONFIG_MTD_AT24XX=y +# CONFIG_AT24XX_MULTI is not set +CONFIG_AT24XX_SIZE=2 +CONFIG_AT24XX_ADDR=0x57 +CONFIG_AT24XX_EXTENDED=y +CONFIG_AT24XX_EXTSIZE=160 +CONFIG_AT24XX_FREQUENCY=100000 +CONFIG_MTD_AT25=y +CONFIG_AT25_SPIMODE=0 +CONFIG_AT25_SPIFREQUENCY=20000000 +# CONFIG_MTD_AT45DB is not set +# CONFIG_MTD_IS25XP is not set +# CONFIG_MTD_M25P is not set +# CONFIG_MTD_MX25L is not set +# CONFIG_MTD_S25FL1 is not set +# CONFIG_MTD_N25QXXX is not set +# CONFIG_MTD_SMART is not set +# CONFIG_MTD_RAMTRON is not set +# CONFIG_MTD_SST25 is not set +# CONFIG_MTD_SST25XX is not set +# CONFIG_MTD_SST26 is not set +# CONFIG_MTD_SST39FV is not set +# CONFIG_MTD_W25 is not set +# CONFIG_EEPROM is not set +# CONFIG_PIPES is not set +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +CONFIG_SERIAL=y +# CONFIG_DEV_LOWCONSOLE is not set +# CONFIG_SERIAL_REMOVABLE is not set +CONFIG_SERIAL_CONSOLE=y +# CONFIG_16550_UART is not set +# CONFIG_UART_SERIALDRIVER is not set +CONFIG_UART0_SERIALDRIVER=y +# CONFIG_UART1_SERIALDRIVER is not set +# CONFIG_UART2_SERIALDRIVER is not set +# CONFIG_UART3_SERIALDRIVER is not set +# CONFIG_UART4_SERIALDRIVER is not set +# CONFIG_UART5_SERIALDRIVER is not set +# CONFIG_UART6_SERIALDRIVER is not set +# CONFIG_UART7_SERIALDRIVER is not set +# CONFIG_UART8_SERIALDRIVER is not set +# CONFIG_SCI0_SERIALDRIVER is not set +# CONFIG_SCI1_SERIALDRIVER is not set +# CONFIG_USART0_SERIALDRIVER is not set +# CONFIG_USART1_SERIALDRIVER is not set +# CONFIG_USART2_SERIALDRIVER is not set +# CONFIG_USART3_SERIALDRIVER is not set +# CONFIG_USART4_SERIALDRIVER is not set +# CONFIG_USART5_SERIALDRIVER is not set +# CONFIG_USART6_SERIALDRIVER is not set +# CONFIG_USART7_SERIALDRIVER is not set +# CONFIG_USART8_SERIALDRIVER is not set +# CONFIG_OTHER_UART_SERIALDRIVER is not set +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +# CONFIG_SERIAL_IFLOWCONTROL is not set +# CONFIG_SERIAL_OFLOWCONTROL is not set +# CONFIG_SERIAL_DMA is not set +# CONFIG_ARCH_HAVE_SERIAL_TERMIOS is not set +CONFIG_UART0_SERIAL_CONSOLE=y +# CONFIG_OTHER_SERIAL_CONSOLE is not set +# CONFIG_NO_SERIAL_CONSOLE is not set + +# +# UART0 Configuration +# +CONFIG_UART0_RXBUFSIZE=256 +CONFIG_UART0_TXBUFSIZE=256 +CONFIG_UART0_BAUD=115200 +CONFIG_UART0_BITS=8 +CONFIG_UART0_PARITY=0 +CONFIG_UART0_2STOP=0 +# CONFIG_UART0_IFLOWCONTROL is not set +# CONFIG_UART0_OFLOWCONTROL is not set +# CONFIG_UART0_DMA is not set +# CONFIG_PSEUDOTERM is not set +# CONFIG_USBDEV is not set +# CONFIG_USBHOST is not set +# CONFIG_HAVE_USBTRACE is not set +# CONFIG_DRIVERS_WIRELESS is not set +# CONFIG_DRIVERS_CONTACTLESS is not set + +# +# System Logging +# +# CONFIG_ARCH_SYSLOG is not set +# CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_INTBUFFER is not set +# CONFIG_SYSLOG_TIMESTAMP is not set +CONFIG_SYSLOG_SERIAL_CONSOLE=y +# CONFIG_SYSLOG_CHAR is not set +CONFIG_SYSLOG_CONSOLE=y +# CONFIG_SYSLOG_NONE is not set +# CONFIG_SYSLOG_FILE is not set +# CONFIG_SYSLOG_CHARDEV is not set + +# +# Networking Support +# +# CONFIG_ARCH_HAVE_NET is not set +# CONFIG_ARCH_HAVE_PHY is not set +# CONFIG_NET is not set + +# +# Crypto API +# +# CONFIG_CRYPTO is not set + +# +# File Systems +# + +# +# File system configuration +# +# CONFIG_DISABLE_MOUNTPOINT is not set +# CONFIG_FS_AUTOMOUNTER is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_PSEUDOFS_SOFTLINKS is not set +CONFIG_FS_READABLE=y +CONFIG_FS_WRITABLE=y +# CONFIG_FS_NAMED_SEMAPHORES is not set +CONFIG_FS_MQUEUE_MPATH="/var/mqueue" +# CONFIG_FS_RAMMAP is not set +CONFIG_FS_FAT=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_MAXFNAME=32 +# CONFIG_FS_FATTIME is not set +# CONFIG_FAT_FORCE_INDIRECT is not set +# CONFIG_FAT_DMAMEMORY is not set +# CONFIG_FAT_DIRECT_RETRY is not set +# CONFIG_FS_NXFFS is not set +# CONFIG_FS_ROMFS is not set +# CONFIG_FS_TMPFS is not set +# CONFIG_FS_SMARTFS is not set +# CONFIG_FS_BINFS is not set +CONFIG_FS_PROCFS=y +# CONFIG_FS_PROCFS_REGISTER is not set + +# +# Exclude individual procfs entries +# +# CONFIG_FS_PROCFS_EXCLUDE_PROCESS is not set +# CONFIG_FS_PROCFS_EXCLUDE_UPTIME is not set +# CONFIG_FS_PROCFS_EXCLUDE_MOUNTS is not set +# CONFIG_FS_PROCFS_EXCLUDE_MTD is not set +# CONFIG_FS_UNIONFS is not set + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=1 +# CONFIG_ARCH_HAVE_HEAP2 is not set +# CONFIG_GRAN is not set + +# +# Audio Support +# +# CONFIG_AUDIO is not set + +# +# Wireless Support +# + +# +# Binary Loader +# +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_BINFMT_EXEPATH is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +CONFIG_BUILTIN=y +# CONFIG_PIC is not set +# CONFIG_SYMTAB_ORDEREDBYNAME is not set + +# +# Library Routines +# + +# +# Standard C Library Options +# + +# +# Standard C I/O +# +# CONFIG_STDIO_DISABLE_BUFFERING is not set +CONFIG_STDIO_BUFFER_SIZE=64 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +# CONFIG_NOPRINTF_FIELDWIDTH is not set +# CONFIG_LIBC_FLOATINGPOINT is not set +CONFIG_LIBC_LONG_LONG=y +# CONFIG_LIBC_SCANSET is not set +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_MEMCPY_VIK is not set +# CONFIG_LIBM is not set + +# +# Architecture-Specific Support +# +CONFIG_ARCH_LOWPUTC=y +# CONFIG_ARCH_ROMGETC is not set +# CONFIG_LIBC_ARCH_MEMCPY is not set +# CONFIG_LIBC_ARCH_MEMCMP is not set +# CONFIG_LIBC_ARCH_MEMMOVE is not set +# CONFIG_LIBC_ARCH_MEMSET is not set +# CONFIG_LIBC_ARCH_STRCHR is not set +# CONFIG_LIBC_ARCH_STRCMP is not set +# CONFIG_LIBC_ARCH_STRCPY is not set +# CONFIG_LIBC_ARCH_STRNCPY is not set +# CONFIG_LIBC_ARCH_STRLEN is not set +# CONFIG_LIBC_ARCH_STRNLEN is not set +# CONFIG_LIBC_ARCH_ELF is not set +# CONFIG_ARMV7M_MEMCPY is not set + +# +# stdlib Options +# +CONFIG_LIB_RAND_ORDER=1 +CONFIG_LIB_HOMEDIR="/" +CONFIG_LIBC_TMPDIR="/tmp" +CONFIG_LIBC_MAX_TMPFILE=32 + +# +# Program Execution Options +# +# CONFIG_LIBC_EXECFUNCS is not set +CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024 +CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=2048 + +# +# errno Decode Support +# +# CONFIG_LIBC_STRERROR is not set +# CONFIG_LIBC_PERROR_STDOUT is not set + +# +# memcpy/memset Options +# +# CONFIG_MEMSET_OPTSPEED is not set +# CONFIG_LIBC_DLLFCN is not set +# CONFIG_LIBC_MODLIB is not set +# CONFIG_LIBC_WCHAR is not set +# CONFIG_LIBC_LOCALE is not set + +# +# Time/Time Zone Support +# +# CONFIG_LIBC_LOCALTIME is not set +# CONFIG_TIME_EXTENDED is not set +CONFIG_ARCH_HAVE_TLS=y + +# +# Thread Local Storage (TLS) +# +# CONFIG_TLS is not set + +# +# Network-Related Options +# +# CONFIG_LIBC_IPv4_ADDRCONV is not set +# CONFIG_LIBC_IPv6_ADDRCONV is not set +# CONFIG_LIBC_NETDB is not set + +# +# NETDB Support +# +# CONFIG_NETDB_HOSTFILE is not set +# CONFIG_LIBC_IOCTL_VARIADIC is not set +CONFIG_LIB_SENDFILE_BUFSIZE=512 + +# +# Non-standard Library Support +# +# CONFIG_LIB_CRC64_FAST is not set +# CONFIG_LIB_KBDCODEC is not set +# CONFIG_LIB_SLCDCODEC is not set +# CONFIG_LIB_HEX2BIN is not set + +# +# Basic CXX Support +# +# CONFIG_C99_BOOL8 is not set +# CONFIG_HAVE_CXX is not set + +# +# Application Configuration +# + +# +# Built-In Applications +# +CONFIG_BUILTIN_PROXY_STACKSIZE=1024 + +# +# CAN Utilities +# + +# +# Examples +# +# CONFIG_EXAMPLES_BUTTONS is not set +# CONFIG_EXAMPLES_CCTYPE is not set +# CONFIG_EXAMPLES_CHAT is not set +# CONFIG_EXAMPLES_CONFIGDATA is not set +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FSTEST is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HIDKBD is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_JSON is not set +# CONFIG_EXAMPLES_KEYPADTEST is not set +# CONFIG_EXAMPLES_MEDIA is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MODBUS is not set +# CONFIG_EXAMPLES_MOUNT is not set +CONFIG_EXAMPLES_NSH=y +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NXLINES is not set +# CONFIG_EXAMPLES_NXTERM is not set +# CONFIG_EXAMPLES_NXTEXT is not set +# CONFIG_EXAMPLES_OSTEST is not set +# CONFIG_EXAMPLES_PCA9635 is not set +# CONFIG_EXAMPLES_POSIXSPAWN is not set +# CONFIG_EXAMPLES_PPPD is not set +# CONFIG_EXAMPLES_RFID_READUID is not set +# CONFIG_EXAMPLES_RGBLED is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERIALBLASTER is not set +# CONFIG_EXAMPLES_SERIALRX is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_SLCD is not set +# CONFIG_EXAMPLES_SMART is not set +# CONFIG_EXAMPLES_SMART_TEST is not set +# CONFIG_EXAMPLES_SMP is not set +# CONFIG_EXAMPLES_STAT is not set +# CONFIG_EXAMPLES_TCPECHO is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_USBSERIAL is not set +# CONFIG_EXAMPLES_WATCHDOG is not set +# CONFIG_EXAMPLES_WEBSERVER is not set + +# +# File System Utilities +# +# CONFIG_FSUTILS_FLASH_ERASEALL is not set +# CONFIG_FSUTILS_INIFILE is not set +# CONFIG_FSUTILS_PASSWD is not set + +# +# GPS Utilities +# +# CONFIG_GPSUTILS_MINMEA_LIB is not set + +# +# Graphics Support +# +# CONFIG_TIFF is not set +# CONFIG_GRAPHICS_TRAVELER is not set + +# +# Interpreters +# +# CONFIG_INTERPRETERS_BAS is not set +# CONFIG_INTERPRETERS_FICL is not set +# CONFIG_INTERPRETERS_MICROPYTHON is not set +# CONFIG_INTERPRETERS_MINIBASIC is not set +# CONFIG_INTERPRETERS_PCODE is not set + +# +# FreeModBus +# +# CONFIG_MODBUS is not set + +# +# Network Utilities +# +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_ESP8266 is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_JSON is not set +# CONFIG_NETUTILS_SMTP is not set + +# +# NSH Library +# +CONFIG_NSH_LIBRARY=y +# CONFIG_NSH_MOTD is not set + +# +# Command Line Configuration +# +CONFIG_NSH_READLINE=y +# CONFIG_NSH_CLE is not set +CONFIG_NSH_LINELEN=64 +# CONFIG_NSH_DISABLE_SEMICOLON is not set +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_MAXARGUMENTS=6 +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_NESTDEPTH=3 +# CONFIG_NSH_DISABLEBG is not set +CONFIG_NSH_BUILTIN_APPS=y + +# +# Disable Individual commands +# +# CONFIG_NSH_DISABLE_ADDROUTE is not set +# CONFIG_NSH_DISABLE_BASENAME is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_CMP is not set +CONFIG_NSH_DISABLE_DATE=y +# CONFIG_NSH_DISABLE_DD is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_DELROUTE is not set +# CONFIG_NSH_DISABLE_DIRNAME is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_HEXDUMP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +# CONFIG_NSH_DISABLE_IFUPDOWN is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOSETUP is not set +CONFIG_NSH_DISABLE_LOSMART=y +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MB is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MKRD is not set +# CONFIG_NSH_DISABLE_MH is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_MW is not set +CONFIG_NSH_DISABLE_PRINTF=y +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PUT is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SH is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNAME is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +# CONFIG_NSH_DISABLE_WGET is not set +# CONFIG_NSH_DISABLE_XD is not set +CONFIG_NSH_MMCSDMINOR=0 +CONFIG_NSH_MMCSDSLOTNO=0 + +# +# Configure Command Options +# +# CONFIG_NSH_CMDOPT_DF_H is not set +# CONFIG_NSH_CMDOPT_DD_STATS is not set +CONFIG_NSH_CODECS_BUFSIZE=128 +CONFIG_NSH_CMDOPT_HEXDUMP=y +CONFIG_NSH_PROC_MOUNTPOINT="/proc" +CONFIG_NSH_FILEIOSIZE=512 + +# +# Scripting Support +# +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_LOOPS is not set + +# +# Console Configuration +# +CONFIG_NSH_CONSOLE=y +# CONFIG_NSH_ALTCONDEV is not set +CONFIG_NSH_ARCHINIT=y +# CONFIG_NSH_LOGIN is not set +# CONFIG_NSH_CONSOLE_LOGIN is not set + +# +# NxWidgets/NxWM +# + +# +# Platform-specific Support +# +# CONFIG_PLATFORM_CONFIGDATA is not set + +# +# System Libraries and NSH Add-Ons +# +# CONFIG_SYSTEM_CLE is not set +# CONFIG_SYSTEM_CUTERM is not set +# CONFIG_SYSTEM_FLASH_ERASEALL is not set +# CONFIG_SYSTEM_FREE is not set +# CONFIG_SYSTEM_HEX2BIN is not set +# CONFIG_SYSTEM_HEXED is not set +CONFIG_SYSTEM_I2CTOOL=y +CONFIG_I2CTOOL_MINBUS=0 +CONFIG_I2CTOOL_MAXBUS=0 +CONFIG_I2CTOOL_MINADDR=0x03 +CONFIG_I2CTOOL_MAXADDR=0x77 +CONFIG_I2CTOOL_MAXREGADDR=0xff +CONFIG_I2CTOOL_DEFFREQ=400000 +# CONFIG_SYSTEM_INSTALL is not set +CONFIG_SYSTEM_RAMTEST=y +CONFIG_READLINE_HAVE_EXTMATCH=y +CONFIG_SYSTEM_READLINE=y +CONFIG_READLINE_ECHO=y +# CONFIG_READLINE_TABCOMPLETION is not set +# CONFIG_READLINE_CMD_HISTORY is not set +# CONFIG_SYSTEM_SUDOKU is not set +# CONFIG_SYSTEM_SYSTEM is not set +# CONFIG_SYSTEM_TEE is not set +# CONFIG_SYSTEM_UBLOXMODEM is not set +# CONFIG_SYSTEM_VI is not set +# CONFIG_SYSTEM_ZMODEM is not set diff --git a/configs/xmc4500-relax/nsh/setenv.sh b/configs/xmc4500-relax/nsh/setenv.sh new file mode 100644 index 0000000000..2116ba35be --- /dev/null +++ b/configs/xmc4500-relax/nsh/setenv.sh @@ -0,0 +1,77 @@ +#!/bin/bash +# configs/xmc4500-relax/nsh/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. +# + +if [ "$_" = "$0" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +fi + +WD=`pwd` +if [ ! -x "setenv.sh" ]; then + echo "This script must be executed from the top-level NuttX build directory" + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then + export PATH_ORIG="${PATH}" +fi + +# This is the Cygwin path to the location where I installed the Atmel GCC +# toolchain under Windows. You will also have to edit this if you install +# this toolchain in any other location +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin" + +# This is the Cygwin path to the location where I installed the CodeSourcery +# toolchain under windows. You will also have to edit this if you install +# the CodeSourcery toolchain in any other location +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin" +# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin" + +# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors" +# You can this free toolchain here https://launchpad.net/gcc-arm-embedded +export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin" + +# This is the path to the location where I installed the devkitARM toolchain +# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/ +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin" + +# This is the Cygwin path to the location where I build the buildroot +# toolchain. +# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" + +# Add the path to the toolchain to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" + +echo "PATH : ${PATH}" diff --git a/configs/xmc4500-relax/src/Makefile b/configs/xmc4500-relax/src/Makefile new file mode 100644 index 0000000000..d609e49ac8 --- /dev/null +++ b/configs/xmc4500-relax/src/Makefile @@ -0,0 +1,55 @@ +############################################################################ +# configs/xmc4500-relax/src/Makefile +# +# 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. +# +############################################################################ + +-include $(TOPDIR)/Make.defs + +ASRCS = +CSRCS = xmc4_boot.c xmc4_bringup.c + +ifeq ($(CONFIG_BUTTONS),y) +CSRCS += xmc4_buttons.c +endif + +ifeq ($(CONFIG_USERLED),y) +CSRCS += xmc4_autoleds.c +else +CSRCS += xmc4_userleds.c +endif + +ifeq ($(CONFIG_LIB_BOARDCTL),y) +CSRCS += xmc4_appinit.c +endif + +include $(TOPDIR)/configs/Board.mk diff --git a/configs/xmc4500-relax/src/xmc4500-relax.h b/configs/xmc4500-relax/src/xmc4500-relax.h new file mode 100644 index 0000000000..6a004c8244 --- /dev/null +++ b/configs/xmc4500-relax/src/xmc4500-relax.h @@ -0,0 +1,78 @@ +/**************************************************************************** + * configs/xmc4500-relax/src/xmc4500-relax.h + * + * 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. + * + ****************************************************************************/ + +#ifndef __CONFIGS_XMC4500_RELAX_SRC_XMC4500_RELAX_H +#define __CONFIGS_XMC4500_RELAX_SRC_XMC4500_RELAX_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* LEDs */ + +/* BUTTONS */ + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/**************************************************************************** + * Public data + ****************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: xmc4_bringup + * + * Description: + * Bring up board features + * + ****************************************************************************/ + +int xmc4_bringup(void); + +#endif /* __ASSEMBLY__ */ +#endif /* __CONFIGS_XMC4500_RELAX_SRC_XMC4500_RELAX_H */ diff --git a/configs/xmc4500-relax/src/xmc4_appinit.c b/configs/xmc4500-relax/src/xmc4_appinit.c new file mode 100644 index 0000000000..8e1fa87efe --- /dev/null +++ b/configs/xmc4500-relax/src/xmc4_appinit.c @@ -0,0 +1,80 @@ +/**************************************************************************** + * config/xmc4500-relax/src/xmc4_appinit.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; the meaning of the argument is a contract + * between the board-specific initalization logic and the the + * matching application logic. The value cold be such things as a + * mode enumeration value, a set of DIP switch switch settings, a + * pointer to configuration data read from a file or serial FLASH, + * or whatever you would like to do with it. Every implementation + * should accept zero/NULL as a default configuration. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ + +int board_app_initialize(uintptr_t arg) +{ +#ifndef CONFIG_BOARD_INITIALIZE + /* Perform board initialization */ + + return xmc4_bringup(); +#else + return OK; +#endif /* CONFIG_BOARD_INITIALIZE */ +} diff --git a/configs/xmc4500-relax/src/xmc4_autoleds.c b/configs/xmc4500-relax/src/xmc4_autoleds.c new file mode 100644 index 0000000000..7fd88f7866 --- /dev/null +++ b/configs/xmc4500-relax/src/xmc4_autoleds.c @@ -0,0 +1,80 @@ +/**************************************************************************** + * configs/xmc4500-relax/include/xmc4_autoleds.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include "xmc4500-relax.h" + +#ifdef CONFIG_ARCH_LEDS + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_autoled_initialize + ****************************************************************************/ + +void board_autoled_initialize(void) +{ +#warning Missing logic +} + +/**************************************************************************** + * Name: board_autoled_on + ****************************************************************************/ + +void board_autoled_on(int led) +{ +#warning Missing logic +} + +/**************************************************************************** + * Name: board_autoled_off + ****************************************************************************/ + +void board_autoled_off(int led) +{ +#warning Missing logic +} + +#endif /* CONFIG_ARCH_LEDS */ diff --git a/configs/xmc4500-relax/src/xmc4_boot.c b/configs/xmc4500-relax/src/xmc4_boot.c new file mode 100644 index 0000000000..994cdf86c6 --- /dev/null +++ b/configs/xmc4500-relax/src/xmc4_boot.c @@ -0,0 +1,91 @@ +/************************************************************************************ + * configs/xmc4500-relax/src/xmc4_boot.c + * + * 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. + * + ************************************************************************************/ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include + +#include "xmc4500-relax.h" + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: xmc4_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +void xmc4_boardinitialize(void) +{ +#ifdef CONFIG_ARCH_LEDS + /* Configure on-board LEDs if LED support has been selected. */ + + board_autoled_initialize(); +#endif +} + +/**************************************************************************** + * Name: board_initialize + * + * Description: + * If CONFIG_BOARD_INITIALIZE is selected, then an additional + * initialization call will be performed in the boot-up sequence to a + * function called board_initialize(). board_initialize() will be + * called immediately after up_intitialize() is called and just before the + * initial application is started. This additional initialization phase + * may be used, for example, to initialize board-specific device drivers. + * + ****************************************************************************/ + +#ifdef CONFIG_BOARD_INITIALIZE +void board_initialize(void) +{ + /* Perform board initialization */ + + (void)xmc4_bringup(); +} +#endif /* CONFIG_BOARD_INITIALIZE */ + diff --git a/configs/xmc4500-relax/src/xmc4_bringup.c b/configs/xmc4500-relax/src/xmc4_bringup.c new file mode 100644 index 0000000000..ae7b5a593e --- /dev/null +++ b/configs/xmc4500-relax/src/xmc4_bringup.c @@ -0,0 +1,65 @@ +/**************************************************************************** + * config/samv71-xult/src/xmc4_bringup.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: xmc4_bringup + * + * Description: + * Bring up board features + * + ****************************************************************************/ + +int xmc4_bringup(void) +{ + return OK; +} diff --git a/configs/xmc4500-relax/src/xmc4_buttons.c b/configs/xmc4500-relax/src/xmc4_buttons.c new file mode 100644 index 0000000000..24f9e05a20 --- /dev/null +++ b/configs/xmc4500-relax/src/xmc4_buttons.c @@ -0,0 +1,78 @@ +/**************************************************************************** + * configs/xmc4500-relax/src/xmc4_buttons.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include "xmc4500-relax.h" + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_button_initialize + ****************************************************************************/ + +void board_button_initialize(void) +{ +#warning Missing logic +} + +/**************************************************************************** + * Name: board_buttons + ****************************************************************************/ + +uint8_t board_buttons(void) +{ +#warning Missing logic + return 0; +} + +/**************************************************************************** + * Name: board_button_irq + ****************************************************************************/ + +#ifdef CONFIG_ARCH_IRQBUTTONS +int board_button_irq(int id, xcpt_t irqhandler, FAR void *arg) +{ +#warning Missing logic + return -ENOSYS; +} +#endif /* CONFIG_ARCH_IRQBUTTONS */ diff --git a/configs/xmc4500-relax/src/xmc4_userleds.c b/configs/xmc4500-relax/src/xmc4_userleds.c new file mode 100644 index 0000000000..8bb69336f7 --- /dev/null +++ b/configs/xmc4500-relax/src/xmc4_userleds.c @@ -0,0 +1,75 @@ +/**************************************************************************** + * configs/xmc4500-relax/src/xmc4_userleds.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include "xmc4500-relax.h" + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_userled_initialize + ****************************************************************************/ + +void board_userled_initialize(void) +{ +#warning Missing logic +} + +/**************************************************************************** + * Name: board_userled + ****************************************************************************/ + +void board_userled(int led, bool ledon) +{ +#warning Missing logic +} + +/**************************************************************************** + * Name: board_userled_all + ****************************************************************************/ + +void board_userled_all(uint8_t ledset) +{ +#warning Missing logic +} -- GitLab From 5693f26a5ed42d2120fa2adb222c38696965dc36 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 16 Mar 2017 11:30:02 -0600 Subject: [PATCH 070/990] XMC4xx: Fix several early compilation problems. --- arch/arm/include/xmc4/chip.h | 4 +- arch/arm/include/xmc4/irq.h | 38 ++-- arch/arm/include/xmc4/xmc4500_irq.h | 238 +++++++++++----------- arch/arm/src/xmc4/chip/xmc4_scu.h | 14 +- arch/arm/src/xmc4/xmc4_clockconfig.c | 50 ++--- arch/arm/src/xmc4/xmc4_irq.c | 1 + configs/xmc4500-relax/include/board.h | 62 ++++++ configs/xmc4500-relax/src/xmc4500-relax.h | 16 +- 8 files changed, 249 insertions(+), 174 deletions(-) diff --git a/arch/arm/include/xmc4/chip.h b/arch/arm/include/xmc4/chip.h index 7ea5157a73..019c107823 100644 --- a/arch/arm/include/xmc4/chip.h +++ b/arch/arm/include/xmc4/chip.h @@ -48,11 +48,11 @@ /* Get customizations for each supported chip */ -#if defined(CONFIG_ARCH_XMC4500) +#if defined(CONFIG_ARCH_CHIP_XMC4500) # define XM4_NUSIC 3 /* Three USIC modules: USCI0-2 */ #else -# error "Unsupported XMC4000 chip" +# error "Unsupported XMC4xxx chip" #endif /* NVIC priority levels *************************************************************/ diff --git a/arch/arm/include/xmc4/irq.h b/arch/arm/include/xmc4/irq.h index 65300dcee3..10fc176a43 100644 --- a/arch/arm/include/xmc4/irq.h +++ b/arch/arm/include/xmc4/irq.h @@ -37,8 +37,8 @@ * through nuttx/irq.h */ -#ifndef __ARCH_ARM_INCLUDE_XM4_IRQ_H -#define __ARCH_ARM_INCLUDE_XM4_IRQ_H +#ifndef __ARCH_ARM_INCLUDE_XMC4_IRQ_H +#define __ARCH_ARM_INCLUDE_XMC4_IRQ_H /************************************************************************************ * Included Files @@ -58,26 +58,26 @@ /* Processor Exceptions (vectors 0-15) */ -#define XM4_IRQ_RESERVED (0) /* Reserved vector (only used with CONFIG_DEBUG_FEATURES) */ - /* Vector 0: Reset stack pointer value */ - /* Vector 1: Reset (not handler as an IRQ) */ -#define XM4_IRQ_NMI (2) /* Vector 2: Non-Maskable Interrupt (NMI) */ -#define XM4_IRQ_HARDFAULT (3) /* Vector 3: Hard fault */ -#define XM4_IRQ_MEMFAULT (4) /* Vector 4: Memory management (MPU) */ -#define XM4_IRQ_BUSFAULT (5) /* Vector 5: Bus fault */ -#define XM4_IRQ_USAGEFAULT (6) /* Vector 6: Usage fault */ - /* Vectors 7-10: Reserved */ -#define XM4_IRQ_SVCALL (11) /* Vector 11: SVC call */ -#define XM4_IRQ_DBGMONITOR (12) /* Vector 12: Debug Monitor */ - /* Vector 13: Reserved */ -#define XM4_IRQ_PENDSV (14) /* Vector 14: Pendable system service request */ -#define XM4_IRQ_SYSTICK (15) /* Vector 15: System tick */ +#define XMC4_IRQ_RESERVED (0) /* Reserved vector (only used with CONFIG_DEBUG_FEATURES) */ + /* Vector 0: Reset stack pointer value */ + /* Vector 1: Reset (not handler as an IRQ) */ +#define XMC4_IRQ_NMI (2) /* Vector 2: Non-Maskable Interrupt (NMI) */ +#define XMC4_IRQ_HARDFAULT (3) /* Vector 3: Hard fault */ +#define XMC4_IRQ_MEMFAULT (4) /* Vector 4: Memory management (MPU) */ +#define XMC4_IRQ_BUSFAULT (5) /* Vector 5: Bus fault */ +#define XMC4_IRQ_USAGEFAULT (6) /* Vector 6: Usage fault */ + /* Vectors 7-10: Reserved */ +#define XMC4_IRQ_SVCALL (11) /* Vector 11: SVC call */ +#define XMC4_IRQ_DBGMONITOR (12) /* Vector 12: Debug Monitor */ + /* Vector 13: Reserved */ +#define XMC4_IRQ_PENDSV (14) /* Vector 14: Pendable system service request */ +#define XMC4_IRQ_SYSTICK (15) /* Vector 15: System tick */ /* External interrupts (vectors >= 16). These definitions are chip-specific */ -#define XM4_IRQ_FIRST (16) /* Vector number of the first external interrupt */ +#define XMC4_IRQ_FIRST (16) /* Vector number of the first external interrupt */ -#if defined(CONFIG_ARCH_XMC4500) +#if defined(CONFIG_ARCH_CHIP_XMC4500) # include #else /* The interrupt vectors for other parts are defined in other documents and may or @@ -116,5 +116,5 @@ extern "C" #endif #endif -#endif /* __ARCH_ARM_INCLUDE_XM4_IRQ_H */ +#endif /* __ARCH_ARM_INCLUDE_XMC4_IRQ_H */ diff --git a/arch/arm/include/xmc4/xmc4500_irq.h b/arch/arm/include/xmc4/xmc4500_irq.h index 1005adeb49..dfd21d6c21 100644 --- a/arch/arm/include/xmc4/xmc4500_irq.h +++ b/arch/arm/include/xmc4/xmc4500_irq.h @@ -37,8 +37,8 @@ * through nuttx/irq.h */ -#ifndef xmc4__ARCH_ARM_INCLUDE_XM4_XM4500_IRQ_H -#define xmc4__ARCH_ARM_INCLUDE_XM4_XM4500_IRQ_H +#ifndef xmc4__ARCH_ARM_INCLUDE_XMC4_XM4500_IRQ_H +#define xmc4__ARCH_ARM_INCLUDE_XMC4_XM4500_IRQ_H /***************************************************************************** * Included Files @@ -75,125 +75,125 @@ * USCI - Universal Serial Interface */ -#define XM4_IRQ_SCU (XM4_IRQ_FIRST+0) /* 0: System Control */ -#define XM4_IRQ_ERU0_SR0 (XM4_IRQ_FIRST+1) /* 1: ERU0, SR0 */ -#define XM4_IRQ_ERU0_SR1 (XM4_IRQ_FIRST+2) /* 2: ERU0, SR1 */ -#define XM4_IRQ_ERU0_SR2 (XM4_IRQ_FIRST+3) /* 3: ERU0, SR2 */ -#define XM4_IRQ_ERU0_SR3 (XM4_IRQ_FIRST+4) /* 4: ERU0, SR3 */ -#define XM4_IRQ_ERU1_SR0 (XM4_IRQ_FIRST+5) /* 5: ERU1, SR0 */ -#define XM4_IRQ_ERU1_SR1 (XM4_IRQ_FIRST+6) /* 6: ERU1, SR1 */ -#define XM4_IRQ_ERU1_SR2 (XM4_IRQ_FIRST+7) /* 7: ERU1, SR2 */ -#define XM4_IRQ_ERU1_SR3 (XM4_IRQ_FIRST+8) /* 8: ERU1, SR3 */ -#define XM4_IRQ_RESVD009 (XM4_IRQ_FIRST+9) /* 9: Reserved */ -#define XM4_IRQ_RESVD010 (XM4_IRQ_FIRST+10) /* 10: Reserved */ -#define XM4_IRQ_RESVD011 (XM4_IRQ_FIRST+11) /* 11: Reserved */ -#define XM4_IRQ_PMU1_SR0 (XM4_IRQ_FIRST+12) /* 12: PMU, SR0 */ -#define XM4_IRQ_RESVD011 (XM4_IRQ_FIRST+13) /* 13: Reserved */ -#define XM4_IRQ_VADC_COSR0 (XM4_IRQ_FIRST+14) /* 14: ADC Common Block 0 */ -#define XM4_IRQ_VADC_COSR1 (XM4_IRQ_FIRST+15) /* 15: ADC Common Block 1 */ -#define XM4_IRQ_VADC_COSR2 (XM4_IRQ_FIRST+16) /* 16: ADC Common Block 2 */ -#define XM4_IRQ_VADC_COSR3 (XM4_IRQ_FIRST+17) /* 17: ADC Common Block 3 */ -#define XM4_IRQ_VADC_GOSR0 (XM4_IRQ_FIRST+18) /* 18: ADC Group 0, SR0 */ -#define XM4_IRQ_VADC_GOSR1 (XM4_IRQ_FIRST+19) /* 19: ADC Group 0, SR1 */ -#define XM4_IRQ_VADC_GOSR2 (XM4_IRQ_FIRST+20) /* 20: ADC Group 0, SR2 */ -#define XM4_IRQ_VADC_GOSR3 (XM4_IRQ_FIRST+21) /* 21: ADC Group 0, SR3 */ -#define XM4_IRQ_VADC_G1SR0 (XM4_IRQ_FIRST+22) /* 22: ADC Group 1, SR0 */ -#define XM4_IRQ_VADC_G1SR1 (XM4_IRQ_FIRST+23) /* 23: ADC Group 1, SR1 */ -#define XM4_IRQ_VADC_G1SR2 (XM4_IRQ_FIRST+24) /* 24: ADC Group 1, SR2 */ -#define XM4_IRQ_VADC_G1SR3 (XM4_IRQ_FIRST+25) /* 25: ADC Group 1, SR3 */ -#define XM4_IRQ_VADC_G2SR0 (XM4_IRQ_FIRST+26) /* 26: ADC Group 2, SR0 */ -#define XM4_IRQ_VADC_G2SR1 (XM4_IRQ_FIRST+27) /* 27: ADC Group 2, SR1 */ -#define XM4_IRQ_VADC_G2SR2 (XM4_IRQ_FIRST+28) /* 28: ADC Group 2, SR2 */ -#define XM4_IRQ_VADC_G2SR3 (XM4_IRQ_FIRST+29) /* 29: ADC Group 2, SR3 */ -#define XM4_IRQ_VADC_G3SR0 (XM4_IRQ_FIRST+30) /* 30: ADC Group 3, SR0 */ -#define XM4_IRQ_VADC_G3SR1 (XM4_IRQ_FIRST+31) /* 31: ADC Group 3, SR1 */ -#define XM4_IRQ_VADC_G3SR2 (XM4_IRQ_FIRST+32) /* 32: ADC Group 3, SR2 */ -#define XM4_IRQ_VADC_G3SR3 (XM4_IRQ_FIRST+33) /* 33: ADC Group 3, SR3 */ -#define XM4_IRQ_DSD_SRM0 (XM4_IRQ_FIRST+34) /* 34: DSD Main, SRM0 */ -#define XM4_IRQ_DSD_SRM1 (XM4_IRQ_FIRST+35) /* 35: DSD Main, SRM1 */ -#define XM4_IRQ_DSD_SRM2 (XM4_IRQ_FIRST+36) /* 36: DSD Main, SRM2 */ -#define XM4_IRQ_DSD_SRM3 (XM4_IRQ_FIRST+37) /* 37: DSD Main, SRM3 */ -#define XM4_IRQ_DSD_SRA0 (XM4_IRQ_FIRST+38) /* 38: DSD Auxiliary, SRA0 */ -#define XM4_IRQ_DSD_SRA1 (XM4_IRQ_FIRST+39) /* 39: DSD Auxiliary, SRA1 */ -#define XM4_IRQ_DSD_SRA2 (XM4_IRQ_FIRST+40) /* 40: DSD Auxiliary, SRA2 */ -#define XM4_IRQ_DSD_SRA3 (XM4_IRQ_FIRST+41) /* 41: DSD Auxiliary, SRA3 */ -#define XM4_IRQ_DAC_SR0 (XM4_IRQ_FIRST+42) /* 42: DAC, SR0 */ -#define XM4_IRQ_DAC_SR1 (XM4_IRQ_FIRST+43) /* 43: DAC, SR1 */ -#define XM4_IRQ_CCU40_SR0 (XM4_IRQ_FIRST+44) /* 44: CCU4 Module 0, SR0 */ -#define XM4_IRQ_CCU40_SR1 (XM4_IRQ_FIRST+45) /* 45: CCU4 Module 0, SR1 */ -#define XM4_IRQ_CCU40_SR2 (XM4_IRQ_FIRST+46) /* 46: CCU4 Module 0, SR2 */ -#define XM4_IRQ_CCU40_SR3 (XM4_IRQ_FIRST+47) /* 47: CCU4 Module 0, SR3 */ -#define XM4_IRQ_CCU41_SR0 (XM4_IRQ_FIRST+48) /* 48: CCU4 Module 1, SR0 */ -#define XM4_IRQ_CCU41_SR1 (XM4_IRQ_FIRST+49) /* 49: CCU4 Module 1, SR1 */ -#define XM4_IRQ_CCU41_SR2 (XM4_IRQ_FIRST+50) /* 50: CCU4 Module 1, SR2 */ -#define XM4_IRQ_CCU41_SR3 (XM4_IRQ_FIRST+51) /* 51: CCU4 Module 1, SR3 */ -#define XM4_IRQ_CCU42_SR0 (XM4_IRQ_FIRST+52) /* 52: CCU4 Module 2, SR0 */ -#define XM4_IRQ_CCU42_SR1 (XM4_IRQ_FIRST+53) /* 53: CCU4 Module 2, SR1 */ -#define XM4_IRQ_CCU42_SR2 (XM4_IRQ_FIRST+54) /* 54: CCU4 Module 2, SR2 */ -#define XM4_IRQ_CCU42_SR3 (XM4_IRQ_FIRST+55) /* 55: CCU4 Module 2, SR3 */ -#define XM4_IRQ_CCU43_SR0 (XM4_IRQ_FIRST+56) /* 56: CCU4 Module 3, SR0 */ -#define XM4_IRQ_CCU43_SR1 (XM4_IRQ_FIRST+57) /* 57: CCU4 Module 3, SR1 */ -#define XM4_IRQ_CCU43_SR2 (XM4_IRQ_FIRST+58) /* 58: CCU4 Module 3, SR2 */ -#define XM4_IRQ_CCU43_SR3 (XM4_IRQ_FIRST+59) /* 59: CCU4 Module 3, SR3 */ -#define XM4_IRQ_CCU80_SR0 (XM4_IRQ_FIRST+60) /* 60: CCU8 Module 0, SR0 */ -#define XM4_IRQ_CCU80_SR1 (XM4_IRQ_FIRST+61) /* 61: CCU8 Module 0, SR1 */ -#define XM4_IRQ_CCU80_SR2 (XM4_IRQ_FIRST+62) /* 62: CCU8 Module 0, SR2 */ -#define XM4_IRQ_CCU80_SR3 (XM4_IRQ_FIRST+63) /* 63: CCU8 Module 0, SR3 */ -#define XM4_IRQ_CCU81_SR0 (XM4_IRQ_FIRST+64) /* 64: CCU8 Module 1, SR0 */ -#define XM4_IRQ_CCU81_SR1 (XM4_IRQ_FIRST+65) /* 65: CCU8 Module 1, SR1 */ -#define XM4_IRQ_CCU81_SR2 (XM4_IRQ_FIRST+66) /* 66: CCU8 Module 1, SR2 */ -#define XM4_IRQ_CCU81_SR3 (XM4_IRQ_FIRST+67) /* 67: CCU8 Module 1, SR3 */ -#define XM4_IRQ_POSIF0_SR0 (XM4_IRQ_FIRST+68) /* 68: POSIF Module 0, SR0 */ -#define XM4_IRQ_POSIF0_SR1 (XM4_IRQ_FIRST+69) /* 69: POSIF Module 0, SR1 */ -#define XM4_IRQ_POSIF1_SR0 (XM4_IRQ_FIRST+70) /* 70: POSIF Module 1, SR0 */ -#define XM4_IRQ_POSIF1_SR1 (XM4_IRQ_FIRST+71) /* 71: POSIF Module 1, SR1 */ -#define XM4_IRQ_RESVD072 (XM4_IRQ_FIRST+72) /* 72: Reserved */ -#define XM4_IRQ_RESVD073 (XM4_IRQ_FIRST+73) /* 73: Reserved */ -#define XM4_IRQ_RESVD074 (XM4_IRQ_FIRST+74) /* 74: Reserved */ -#define XM4_IRQ_RESVD075 (XM4_IRQ_FIRST+75) /* 75: Reserved */ -#define XM4_IRQ_CAN_SR0 (XM4_IRQ_FIRST+76) /* 76: MultiCAN, SR0 */ -#define XM4_IRQ_CAN_SR1 (XM4_IRQ_FIRST+77) /* 77: MultiCAN, SR1 */ -#define XM4_IRQ_CAN_SR2 (XM4_IRQ_FIRST+78) /* 78: MultiCAN, SR2 */ -#define XM4_IRQ_CAN_SR3 (XM4_IRQ_FIRST+79) /* 79: MultiCAN, SR3 */ -#define XM4_IRQ_CAN_SR4 (XM4_IRQ_FIRST+80) /* 80: MultiCAN, SR4 */ -#define XM4_IRQ_CAN_SR5 (XM4_IRQ_FIRST+81) /* 81: MultiCAN, SR5 */ -#define XM4_IRQ_CAN_SR6 (XM4_IRQ_FIRST+82) /* 82: MultiCAN, SR6 */ -#define XM4_IRQ_CAN_SR7 (XM4_IRQ_FIRST+83) /* 83: MultiCAN, SR7 */ -#define XM4_IRQ_USIC0_SR0 (XM4_IRQ_FIRST+84) /* 84: USIC0 Channel, SR0 */ -#define XM4_IRQ_USIC0_SR1 (XM4_IRQ_FIRST+85) /* 85: USIC0 Channel, SR1 */ -#define XM4_IRQ_USIC0_SR2 (XM4_IRQ_FIRST+86) /* 86: USIC0 Channel, SR2 */ -#define XM4_IRQ_USIC0_SR3 (XM4_IRQ_FIRST+87) /* 87: USIC0 Channel, SR3 */ -#define XM4_IRQ_USIC0_SR4 (XM4_IRQ_FIRST+88) /* 88: USIC0 Channel, SR4 */ -#define XM4_IRQ_USIC0_SR5 (XM4_IRQ_FIRST+89) /* 89: USIC0 Channel, SR5 */ -#define XM4_IRQ_USIC1_SR0 (XM4_IRQ_FIRST+90) /* 90: USIC1 Channel, SR0 */ -#define XM4_IRQ_USIC1_SR1 (XM4_IRQ_FIRST+91) /* 91: USIC1 Channel, SR1 */ -#define XM4_IRQ_USIC1_SR2 (XM4_IRQ_FIRST+92) /* 92: USIC1 Channel, SR2 */ -#define XM4_IRQ_USIC1_SR3 (XM4_IRQ_FIRST+93) /* 93: USIC1 Channel, SR3 */ -#define XM4_IRQ_USIC1_SR4 (XM4_IRQ_FIRST+94) /* 94: USIC1 Channel, SR4 */ -#define XM4_IRQ_USIC1_SR5 (XM4_IRQ_FIRST+95) /* 95: USIC1 Channel, SR5 */ -#define XM4_IRQ_USIC2_SR0 (XM4_IRQ_FIRST+96) /* 96: USIC1 Channel, SR0 */ -#define XM4_IRQ_USIC2_SR1 (XM4_IRQ_FIRST+97) /* 97: USIC1 Channel, SR1 */ -#define XM4_IRQ_USIC2_SR2 (XM4_IRQ_FIRST+98) /* 98: USIC1 Channel, SR2 */ -#define XM4_IRQ_USIC2_SR3 (XM4_IRQ_FIRST+99) /* 99: USIC1 Channel, SR3 */ -#define XM4_IRQ_USIC2_SR4 (XM4_IRQ_FIRST+100) /* 100: USIC1 Channel, SR4 */ -#define XM4_IRQ_USIC2_SR5 (XM4_IRQ_FIRST+101) /* 101: USIC1 Channel, SR5 */ -#define XM4_IRQ_LEDTS0_SR0 (XM4_IRQ_FIRST+102) /* 102: LEDTS0, SR0 */ -#define XM4_IRQ_RESVD103 (XM4_IRQ_FIRST+103) /* 103: Reserved */ -#define XM4_IRQ_FCR_SR0 (XM4_IRQ_FIRST+104) /* 102: FCE, SR0 */ -#define XM4_IRQ_GPCMA0_SR0 (XM4_IRQ_FIRST+105) /* 105: GPDMA0, SR0 */ -#define XM4_IRQ_SDMMC_SR0 (XM4_IRQ_FIRST+106) /* 106: SDMMC, SR0 */ -#define XM4_IRQ_USB0_SR0 (XM4_IRQ_FIRST+107) /* 107: USB, SR0 */ -#define XM4_IRQ_ETH0_SR0 (XM4_IRQ_FIRST+108) /* 108: Ethernet, module 0, SR0 */ -#define XM4_IRQ_RESVD109 (XM4_IRQ_FIRST+109) /* 109: Reserved */ -#define XM4_IRQ_GPCMA1_SR0 (XM4_IRQ_FIRST+110) /* 110: GPDMA1, SR0 */ -#define XM4_IRQ_RESVD111 (XM4_IRQ_FIRST+111) /* 111: Reserved */ - -#define NR_INTERRUPTS 112 /* 112 Non core IRQs*/ -#define NR_VECTORS (XM4_IRQ_FIRST+NR_INTERRUPTS) /* 118 vectors */ +#define XMC4_IRQ_SCU (XMC4_IRQ_FIRST+0) /* 0: System Control */ +#define XMC4_IRQ_ERU0_SR0 (XMC4_IRQ_FIRST+1) /* 1: ERU0, SR0 */ +#define XMC4_IRQ_ERU0_SR1 (XMC4_IRQ_FIRST+2) /* 2: ERU0, SR1 */ +#define XMC4_IRQ_ERU0_SR2 (XMC4_IRQ_FIRST+3) /* 3: ERU0, SR2 */ +#define XMC4_IRQ_ERU0_SR3 (XMC4_IRQ_FIRST+4) /* 4: ERU0, SR3 */ +#define XMC4_IRQ_ERU1_SR0 (XMC4_IRQ_FIRST+5) /* 5: ERU1, SR0 */ +#define XMC4_IRQ_ERU1_SR1 (XMC4_IRQ_FIRST+6) /* 6: ERU1, SR1 */ +#define XMC4_IRQ_ERU1_SR2 (XMC4_IRQ_FIRST+7) /* 7: ERU1, SR2 */ +#define XMC4_IRQ_ERU1_SR3 (XMC4_IRQ_FIRST+8) /* 8: ERU1, SR3 */ +#define XMC4_IRQ_RESVD009 (XMC4_IRQ_FIRST+9) /* 9: Reserved */ +#define XMC4_IRQ_RESVD010 (XMC4_IRQ_FIRST+10) /* 10: Reserved */ +#define XMC4_IRQ_RESVD011 (XMC4_IRQ_FIRST+11) /* 11: Reserved */ +#define XMC4_IRQ_PMU1_SR0 (XMC4_IRQ_FIRST+12) /* 12: PMU, SR0 */ +#define XMC4_IRQ_RESVD011 (XMC4_IRQ_FIRST+13) /* 13: Reserved */ +#define XMC4_IRQ_VADC_COSR0 (XMC4_IRQ_FIRST+14) /* 14: ADC Common Block 0 */ +#define XMC4_IRQ_VADC_COSR1 (XMC4_IRQ_FIRST+15) /* 15: ADC Common Block 1 */ +#define XMC4_IRQ_VADC_COSR2 (XMC4_IRQ_FIRST+16) /* 16: ADC Common Block 2 */ +#define XMC4_IRQ_VADC_COSR3 (XMC4_IRQ_FIRST+17) /* 17: ADC Common Block 3 */ +#define XMC4_IRQ_VADC_GOSR0 (XMC4_IRQ_FIRST+18) /* 18: ADC Group 0, SR0 */ +#define XMC4_IRQ_VADC_GOSR1 (XMC4_IRQ_FIRST+19) /* 19: ADC Group 0, SR1 */ +#define XMC4_IRQ_VADC_GOSR2 (XMC4_IRQ_FIRST+20) /* 20: ADC Group 0, SR2 */ +#define XMC4_IRQ_VADC_GOSR3 (XMC4_IRQ_FIRST+21) /* 21: ADC Group 0, SR3 */ +#define XMC4_IRQ_VADC_G1SR0 (XMC4_IRQ_FIRST+22) /* 22: ADC Group 1, SR0 */ +#define XMC4_IRQ_VADC_G1SR1 (XMC4_IRQ_FIRST+23) /* 23: ADC Group 1, SR1 */ +#define XMC4_IRQ_VADC_G1SR2 (XMC4_IRQ_FIRST+24) /* 24: ADC Group 1, SR2 */ +#define XMC4_IRQ_VADC_G1SR3 (XMC4_IRQ_FIRST+25) /* 25: ADC Group 1, SR3 */ +#define XMC4_IRQ_VADC_G2SR0 (XMC4_IRQ_FIRST+26) /* 26: ADC Group 2, SR0 */ +#define XMC4_IRQ_VADC_G2SR1 (XMC4_IRQ_FIRST+27) /* 27: ADC Group 2, SR1 */ +#define XMC4_IRQ_VADC_G2SR2 (XMC4_IRQ_FIRST+28) /* 28: ADC Group 2, SR2 */ +#define XMC4_IRQ_VADC_G2SR3 (XMC4_IRQ_FIRST+29) /* 29: ADC Group 2, SR3 */ +#define XMC4_IRQ_VADC_G3SR0 (XMC4_IRQ_FIRST+30) /* 30: ADC Group 3, SR0 */ +#define XMC4_IRQ_VADC_G3SR1 (XMC4_IRQ_FIRST+31) /* 31: ADC Group 3, SR1 */ +#define XMC4_IRQ_VADC_G3SR2 (XMC4_IRQ_FIRST+32) /* 32: ADC Group 3, SR2 */ +#define XMC4_IRQ_VADC_G3SR3 (XMC4_IRQ_FIRST+33) /* 33: ADC Group 3, SR3 */ +#define XMC4_IRQ_DSD_SRM0 (XMC4_IRQ_FIRST+34) /* 34: DSD Main, SRM0 */ +#define XMC4_IRQ_DSD_SRM1 (XMC4_IRQ_FIRST+35) /* 35: DSD Main, SRM1 */ +#define XMC4_IRQ_DSD_SRM2 (XMC4_IRQ_FIRST+36) /* 36: DSD Main, SRM2 */ +#define XMC4_IRQ_DSD_SRM3 (XMC4_IRQ_FIRST+37) /* 37: DSD Main, SRM3 */ +#define XMC4_IRQ_DSD_SRA0 (XMC4_IRQ_FIRST+38) /* 38: DSD Auxiliary, SRA0 */ +#define XMC4_IRQ_DSD_SRA1 (XMC4_IRQ_FIRST+39) /* 39: DSD Auxiliary, SRA1 */ +#define XMC4_IRQ_DSD_SRA2 (XMC4_IRQ_FIRST+40) /* 40: DSD Auxiliary, SRA2 */ +#define XMC4_IRQ_DSD_SRA3 (XMC4_IRQ_FIRST+41) /* 41: DSD Auxiliary, SRA3 */ +#define XMC4_IRQ_DAC_SR0 (XMC4_IRQ_FIRST+42) /* 42: DAC, SR0 */ +#define XMC4_IRQ_DAC_SR1 (XMC4_IRQ_FIRST+43) /* 43: DAC, SR1 */ +#define XMC4_IRQ_CCU40_SR0 (XMC4_IRQ_FIRST+44) /* 44: CCU4 Module 0, SR0 */ +#define XMC4_IRQ_CCU40_SR1 (XMC4_IRQ_FIRST+45) /* 45: CCU4 Module 0, SR1 */ +#define XMC4_IRQ_CCU40_SR2 (XMC4_IRQ_FIRST+46) /* 46: CCU4 Module 0, SR2 */ +#define XMC4_IRQ_CCU40_SR3 (XMC4_IRQ_FIRST+47) /* 47: CCU4 Module 0, SR3 */ +#define XMC4_IRQ_CCU41_SR0 (XMC4_IRQ_FIRST+48) /* 48: CCU4 Module 1, SR0 */ +#define XMC4_IRQ_CCU41_SR1 (XMC4_IRQ_FIRST+49) /* 49: CCU4 Module 1, SR1 */ +#define XMC4_IRQ_CCU41_SR2 (XMC4_IRQ_FIRST+50) /* 50: CCU4 Module 1, SR2 */ +#define XMC4_IRQ_CCU41_SR3 (XMC4_IRQ_FIRST+51) /* 51: CCU4 Module 1, SR3 */ +#define XMC4_IRQ_CCU42_SR0 (XMC4_IRQ_FIRST+52) /* 52: CCU4 Module 2, SR0 */ +#define XMC4_IRQ_CCU42_SR1 (XMC4_IRQ_FIRST+53) /* 53: CCU4 Module 2, SR1 */ +#define XMC4_IRQ_CCU42_SR2 (XMC4_IRQ_FIRST+54) /* 54: CCU4 Module 2, SR2 */ +#define XMC4_IRQ_CCU42_SR3 (XMC4_IRQ_FIRST+55) /* 55: CCU4 Module 2, SR3 */ +#define XMC4_IRQ_CCU43_SR0 (XMC4_IRQ_FIRST+56) /* 56: CCU4 Module 3, SR0 */ +#define XMC4_IRQ_CCU43_SR1 (XMC4_IRQ_FIRST+57) /* 57: CCU4 Module 3, SR1 */ +#define XMC4_IRQ_CCU43_SR2 (XMC4_IRQ_FIRST+58) /* 58: CCU4 Module 3, SR2 */ +#define XMC4_IRQ_CCU43_SR3 (XMC4_IRQ_FIRST+59) /* 59: CCU4 Module 3, SR3 */ +#define XMC4_IRQ_CCU80_SR0 (XMC4_IRQ_FIRST+60) /* 60: CCU8 Module 0, SR0 */ +#define XMC4_IRQ_CCU80_SR1 (XMC4_IRQ_FIRST+61) /* 61: CCU8 Module 0, SR1 */ +#define XMC4_IRQ_CCU80_SR2 (XMC4_IRQ_FIRST+62) /* 62: CCU8 Module 0, SR2 */ +#define XMC4_IRQ_CCU80_SR3 (XMC4_IRQ_FIRST+63) /* 63: CCU8 Module 0, SR3 */ +#define XMC4_IRQ_CCU81_SR0 (XMC4_IRQ_FIRST+64) /* 64: CCU8 Module 1, SR0 */ +#define XMC4_IRQ_CCU81_SR1 (XMC4_IRQ_FIRST+65) /* 65: CCU8 Module 1, SR1 */ +#define XMC4_IRQ_CCU81_SR2 (XMC4_IRQ_FIRST+66) /* 66: CCU8 Module 1, SR2 */ +#define XMC4_IRQ_CCU81_SR3 (XMC4_IRQ_FIRST+67) /* 67: CCU8 Module 1, SR3 */ +#define XMC4_IRQ_POSIF0_SR0 (XMC4_IRQ_FIRST+68) /* 68: POSIF Module 0, SR0 */ +#define XMC4_IRQ_POSIF0_SR1 (XMC4_IRQ_FIRST+69) /* 69: POSIF Module 0, SR1 */ +#define XMC4_IRQ_POSIF1_SR0 (XMC4_IRQ_FIRST+70) /* 70: POSIF Module 1, SR0 */ +#define XMC4_IRQ_POSIF1_SR1 (XMC4_IRQ_FIRST+71) /* 71: POSIF Module 1, SR1 */ +#define XMC4_IRQ_RESVD072 (XMC4_IRQ_FIRST+72) /* 72: Reserved */ +#define XMC4_IRQ_RESVD073 (XMC4_IRQ_FIRST+73) /* 73: Reserved */ +#define XMC4_IRQ_RESVD074 (XMC4_IRQ_FIRST+74) /* 74: Reserved */ +#define XMC4_IRQ_RESVD075 (XMC4_IRQ_FIRST+75) /* 75: Reserved */ +#define XMC4_IRQ_CAN_SR0 (XMC4_IRQ_FIRST+76) /* 76: MultiCAN, SR0 */ +#define XMC4_IRQ_CAN_SR1 (XMC4_IRQ_FIRST+77) /* 77: MultiCAN, SR1 */ +#define XMC4_IRQ_CAN_SR2 (XMC4_IRQ_FIRST+78) /* 78: MultiCAN, SR2 */ +#define XMC4_IRQ_CAN_SR3 (XMC4_IRQ_FIRST+79) /* 79: MultiCAN, SR3 */ +#define XMC4_IRQ_CAN_SR4 (XMC4_IRQ_FIRST+80) /* 80: MultiCAN, SR4 */ +#define XMC4_IRQ_CAN_SR5 (XMC4_IRQ_FIRST+81) /* 81: MultiCAN, SR5 */ +#define XMC4_IRQ_CAN_SR6 (XMC4_IRQ_FIRST+82) /* 82: MultiCAN, SR6 */ +#define XMC4_IRQ_CAN_SR7 (XMC4_IRQ_FIRST+83) /* 83: MultiCAN, SR7 */ +#define XMC4_IRQ_USIC0_SR0 (XMC4_IRQ_FIRST+84) /* 84: USIC0 Channel, SR0 */ +#define XMC4_IRQ_USIC0_SR1 (XMC4_IRQ_FIRST+85) /* 85: USIC0 Channel, SR1 */ +#define XMC4_IRQ_USIC0_SR2 (XMC4_IRQ_FIRST+86) /* 86: USIC0 Channel, SR2 */ +#define XMC4_IRQ_USIC0_SR3 (XMC4_IRQ_FIRST+87) /* 87: USIC0 Channel, SR3 */ +#define XMC4_IRQ_USIC0_SR4 (XMC4_IRQ_FIRST+88) /* 88: USIC0 Channel, SR4 */ +#define XMC4_IRQ_USIC0_SR5 (XMC4_IRQ_FIRST+89) /* 89: USIC0 Channel, SR5 */ +#define XMC4_IRQ_USIC1_SR0 (XMC4_IRQ_FIRST+90) /* 90: USIC1 Channel, SR0 */ +#define XMC4_IRQ_USIC1_SR1 (XMC4_IRQ_FIRST+91) /* 91: USIC1 Channel, SR1 */ +#define XMC4_IRQ_USIC1_SR2 (XMC4_IRQ_FIRST+92) /* 92: USIC1 Channel, SR2 */ +#define XMC4_IRQ_USIC1_SR3 (XMC4_IRQ_FIRST+93) /* 93: USIC1 Channel, SR3 */ +#define XMC4_IRQ_USIC1_SR4 (XMC4_IRQ_FIRST+94) /* 94: USIC1 Channel, SR4 */ +#define XMC4_IRQ_USIC1_SR5 (XMC4_IRQ_FIRST+95) /* 95: USIC1 Channel, SR5 */ +#define XMC4_IRQ_USIC2_SR0 (XMC4_IRQ_FIRST+96) /* 96: USIC1 Channel, SR0 */ +#define XMC4_IRQ_USIC2_SR1 (XMC4_IRQ_FIRST+97) /* 97: USIC1 Channel, SR1 */ +#define XMC4_IRQ_USIC2_SR2 (XMC4_IRQ_FIRST+98) /* 98: USIC1 Channel, SR2 */ +#define XMC4_IRQ_USIC2_SR3 (XMC4_IRQ_FIRST+99) /* 99: USIC1 Channel, SR3 */ +#define XMC4_IRQ_USIC2_SR4 (XMC4_IRQ_FIRST+100) /* 100: USIC1 Channel, SR4 */ +#define XMC4_IRQ_USIC2_SR5 (XMC4_IRQ_FIRST+101) /* 101: USIC1 Channel, SR5 */ +#define XMC4_IRQ_LEDTS0_SR0 (XMC4_IRQ_FIRST+102) /* 102: LEDTS0, SR0 */ +#define XMC4_IRQ_RESVD103 (XMC4_IRQ_FIRST+103) /* 103: Reserved */ +#define XMC4_IRQ_FCR_SR0 (XMC4_IRQ_FIRST+104) /* 102: FCE, SR0 */ +#define XMC4_IRQ_GPCMA0_SR0 (XMC4_IRQ_FIRST+105) /* 105: GPDMA0, SR0 */ +#define XMC4_IRQ_SDMMC_SR0 (XMC4_IRQ_FIRST+106) /* 106: SDMMC, SR0 */ +#define XMC4_IRQ_USB0_SR0 (XMC4_IRQ_FIRST+107) /* 107: USB, SR0 */ +#define XMC4_IRQ_ETH0_SR0 (XMC4_IRQ_FIRST+108) /* 108: Ethernet, module 0, SR0 */ +#define XMC4_IRQ_RESVD109 (XMC4_IRQ_FIRST+109) /* 109: Reserved */ +#define XMC4_IRQ_GPCMA1_SR0 (XMC4_IRQ_FIRST+110) /* 110: GPDMA1, SR0 */ +#define XMC4_IRQ_RESVD111 (XMC4_IRQ_FIRST+111) /* 111: Reserved */ + +#define NR_INTERRUPTS 112 /* 112 Non core IRQs*/ +#define NR_VECTORS (XMC4_IRQ_FIRST+NR_INTERRUPTS) /* 118 vectors */ /* GPIO IRQ interrupts -- To be provided */ -#define NR_IRQS NR_VECTORS +#define NR_IRQS NR_VECTORS /***************************************************************************** * Public Types @@ -222,4 +222,4 @@ extern "C" #endif #endif -#endif /* xmc4__ARCH_ARM_INCLUDE_XM4_XM4500_IRQ_H */ +#endif /* xmc4__ARCH_ARM_INCLUDE_XMC4_XM4500_IRQ_H */ diff --git a/arch/arm/src/xmc4/chip/xmc4_scu.h b/arch/arm/src/xmc4/chip/xmc4_scu.h index e08a64a48c..7e706f501b 100644 --- a/arch/arm/src/xmc4/chip/xmc4_scu.h +++ b/arch/arm/src/xmc4/chip/xmc4_scu.h @@ -185,9 +185,9 @@ /* Oscillator Control SCU Registers */ -#define XMC4_OCU_OSCHPSTAT_OFFSET 0x0000 /* OSC_HP Status Register */ -#define XMC4_OCU_OSCHPCTRL_OFFSET 0x0004 /* OSC_HP Control Register */ -#define XMC4_OCU_CLKCALCONST_OFFSET 0x000c /* Clock Calibration Constant Register */ +#define XMC4_SCU_OSCHPSTAT_OFFSET 0x0000 /* OSC_HP Status Register */ +#define XMC4_SCU_OSCHPCTRL_OFFSET 0x0004 /* OSC_HP Control Register */ +#define XMC4_SCU_CLKCALCONST_OFFSET 0x000c /* Clock Calibration Constant Register */ /* PLL Control SCU Registers */ @@ -623,8 +623,8 @@ /* System Clock Control */ #define SCU_SYSCLKCR_SYSDIV_SHIFT (0) /* Bits 0-7: System Clock Division Value */ -#define SCU_SYSCLKCR_SYSDIV_MASK (0xff << SCU_CLK_SYSCLKCR_SYSDIV_SHIFT) -# define SCU_SYSCLKCR_SYSDIV(n) ((uint32_t)((n)-1) << SCU_CLK_SYSCLKCR_SYSDIV_SHIFT) +#define SCU_SYSCLKCR_SYSDIV_MASK (0xff << SCU_SYSCLKCR_SYSDIV_SHIFT) +# define SCU_SYSCLKCR_SYSDIV(n) ((uint32_t)((n)-1) << SCU_SYSCLKCR_SYSDIV_SHIFT) #define SCU_SYSCLKCR_SYSSEL (1 << 16) /* Bit 16: System Clock Selection Value */ # define SCU_SYSCLKCR_SYSSEL_OFI (0) /* 0=OFI clock */ @@ -640,8 +640,8 @@ /* USB Clock Control */ #define SCU_USBCLKCR_USBDIV_SHIFT (0) /* Bits 0-2: USB Clock Divider Value */ -#define SCU_USBCLKCR_USBDIV_MASK (7 << SCU_CLK_USBCLKCR_USBDIV_SHIFT) -# define SCU_SYSCLKCR_USBDIV(n) ((uint32_t)((n)-1) << SCU_CLK_USBCLKCR_USBDIV_SHIFT) +#define SCU_USBCLKCR_USBDIV_MASK (7 << SCU_USBCLKCR_USBDIV_SHIFT) +# define SCU_SYSCLKCR_USBDIV(n) ((uint32_t)((n)-1) << SCU_USBCLKCR_USBDIV_SHIFT) #define SCU_USBCLKCR_USBSEL (1 << 16) /* Bit 16: USB Clock Selection Value */ # define SCU_USBCLKCR_USBSEL_USBPLL (0) /* 0=USB PLL Clock */ # define SCU_USBCLKCR_USBSEL_PLL (1 << 16) /* 1= PLL Clock */ diff --git a/arch/arm/src/xmc4/xmc4_clockconfig.c b/arch/arm/src/xmc4/xmc4_clockconfig.c index 6667ceca86..26608a85b8 100644 --- a/arch/arm/src/xmc4/xmc4_clockconfig.c +++ b/arch/arm/src/xmc4/xmc4_clockconfig.c @@ -57,6 +57,7 @@ #include "up_arch.h" #include "chip/xmc4_scu.h" +#include "xmc4_clockconfig.h" #include @@ -83,7 +84,7 @@ #define SCU_PLLSTAT_OSC_USABLE \ (SCU_PLLSTAT_PLLHV | SCU_PLLSTAT_PLLLV | SCU_PLLSTAT_PLLSP) -#ifndef BOARD_PLL_CLOCKSRC_XTAL +#ifdef BOARD_PLL_CLOCKSRC_XTAL # define VCO ((BOARD_XTAL_FREQUENCY / BOARD_PLL_PDIV) * BOARD_PLL_NDIV) #else /* BOARD_PLL_CLOCKSRC_XTAL */ @@ -171,7 +172,7 @@ void xmc4_clock_configure(void) regval = getreg32(XMC4_SCU_PLLCON0); regval |= SCU_PLLCON0_FOTR; - putreg(regval, XMC4_SCU_PLLCON0); + putreg32(regval, XMC4_SCU_PLLCON0); #else /* Automatic calibration uses the fSTDBY */ @@ -195,10 +196,9 @@ void xmc4_clock_configure(void) /* Remove the reset only if HIB domain were in a state of reset */ regval = getreg32(XMC4_SCU_RSTSTAT); - if ((regval & SCU_RSTSTAT_HIBRS) ! = 0) + if ((regval & SCU_RSTSTAT_HIBRS) != 0) { - regval = getreg32(XMC4_SCU_RSTSTAT); - SCU_RESET->RSTCLR |= SCU_RESET_RSTCLR_HIBRS_Msk; + regval = putreg32(SCU_RSTCLR_HIBRS, XMC4_SCU_RSTCLR); delay(DELAY_CNT_150US_50MHZ); } @@ -271,19 +271,19 @@ void xmc4_clock_configure(void) regval = getreg32(XMC4_SCU_PLLCON0); regval |= SCU_PLLCON0_AOTREN; - putreg(regval, XMC4_SCU_PLLCON0); + putreg32(regval, XMC4_SCU_PLLCON0); #endif /* BOARD_FOFI_CALIBRATION */ delay(DELAY_CNT_50US_50MHZ); -#if BOARD_ENABLE_PLL +#ifdef BOARD_ENABLE_PLL /* Enable PLL */ regval = getreg32(XMC4_SCU_PLLCON0); regval &= ~(SCU_PLLCON0_VCOPWD | SCU_PLLCON0_PLLPWD); - putreg(regval, XMC4_SCU_PLLCON0); + putreg32(regval, XMC4_SCU_PLLCON0); #ifdef BOARD_PLL_CLOCKSRC_XTAL /* Enable OSC_HP */ @@ -292,7 +292,7 @@ void xmc4_clock_configure(void) { regval = getreg32(XMC4_SCU_OSCHPCTRL); regval &= ~(SCU_OSCHPCTRL_MODE_MASK | SCU_OSCHPCTRL_OSCVAL_MASK); - regval |= ((OSCHP_GetFrequency() / FOSCREF) - 1) << SCU_OSCHPCTRL_OSCVAL_SHIFT; + regval |= ((BOARD_XTAL_FREQUENCY / FOSCREF) - 1) << SCU_OSCHPCTRL_OSCVAL_SHIFT; putreg32(regval, XMC4_SCU_OSCHPCTRL); /* Select OSC_HP clock as PLL input */ @@ -305,7 +305,7 @@ void xmc4_clock_configure(void) regval = getreg32(XMC4_SCU_PLLCON0); regval &= ~SCU_PLLCON0_OSCRES; - putreg(regval, XMC4_SCU_PLLCON0); + putreg32(regval, XMC4_SCU_PLLCON0); /* Wait till OSC_HP output frequency is usable */ @@ -330,36 +330,36 @@ void xmc4_clock_configure(void) regval = getreg32(XMC4_SCU_PLLCON0); regval |= SCU_PLLCON0_VCOBYP; - putreg(regval, XMC4_SCU_PLLCON0); + putreg32(regval, XMC4_SCU_PLLCON0); /* Disconnect Oscillator from PLL */ regval |= SCU_PLLCON0_FINDIS; - putreg(regval, XMC4_SCU_PLLCON0); + putreg32(regval, XMC4_SCU_PLLCON0); /* Setup divider settings for main PLL */ regval = (SCU_PLLCON1_NDIV(BOARD_PLL_NDIV) | SCU_PLLCON1_K2DIV(PLL_K2DIV_24MHZ) | - SCU_PLLCON1_PDIV(BOARD_PLL_PDIV); + SCU_PLLCON1_PDIV(BOARD_PLL_PDIV)); putreg32(regval, XMC4_SCU_PLLCON1); /* Set OSCDISCDIS */ regval = getreg32(XMC4_SCU_PLLCON0); regval |= SCU_PLLCON0_OSCDISCDIS; - putreg(regval, XMC4_SCU_PLLCON0); + putreg32(regval, XMC4_SCU_PLLCON0); /* Connect Oscillator to PLL */ regval = getreg32(XMC4_SCU_PLLCON0); regval &= ~SCU_PLLCON0_FINDIS; - putreg(regval, XMC4_SCU_PLLCON0); + putreg32(regval, XMC4_SCU_PLLCON0); /* Restart PLL Lock detection */ regval |= SCU_PLLCON0_RESLD; - putreg(regval, XMC4_SCU_PLLCON0); + putreg32(regval, XMC4_SCU_PLLCON0); /* wait for PLL Lock at 24MHz*/ @@ -371,7 +371,7 @@ void xmc4_clock_configure(void) regval = getreg32(XMC4_SCU_PLLCON0); regval &= ~SCU_PLLCON0_VCOBYP; - putreg(regval, XMC4_SCU_PLLCON0); + putreg32(regval, XMC4_SCU_PLLCON0); /* Wait for normal mode */ @@ -393,7 +393,7 @@ void xmc4_clock_configure(void) putreg32(WDTCLKCR_VALUE, XMC4_SCU_WDTCLKCR); putreg32(EBUCLKCR_VALUE, XMC4_SCU_EBUCLKCR); putreg32(USBCLKCR_VALUE | USB_DIV, XMC4_SCU_USBCLKCR); - putreg32(EXTCLKCR_VALUE, EXTCLKCR); + putreg32(EXTCLKCR_VALUE, XMC4_SCU_EXTCLKCR); #if BOARD_ENABLE_PLL /* PLL frequency stepping...*/ @@ -401,7 +401,7 @@ void xmc4_clock_configure(void) regval = getreg32(XMC4_SCU_PLLCON0); regval &= ~SCU_PLLCON0_OSCDISCDIS; - putreg(regval, XMC4_SCU_PLLCON0); + putreg32(regval, XMC4_SCU_PLLCON0); regval = (SCU_PLLCON1_NDIV(BOARD_PLL_NDIV) | SCU_PLLCON1_K2DIV(PLL_K2DIV_48MHZ) | @@ -440,7 +440,7 @@ void xmc4_clock_configure(void) #endif /* BOARD_ENABLE_PLL */ -#if BOARD_ENABLE_USBPLL +#ifdef BOARD_ENABLE_USBPLL /* Enable USB PLL first */ regval = getreg32(XMC4_SCU_USBPLLCON); @@ -461,19 +461,19 @@ void xmc4_clock_configure(void) regval = getreg32(XMC4_SCU_PLLCON0); regval &= ~(SCU_PLLCON0_VCOPWD | SCU_PLLCON0_PLLPWD); - putreg(regval, XMC4_SCU_PLLCON0); + putreg32(regval, XMC4_SCU_PLLCON0); } regval = getreg32(XMC4_SCU_OSCHPCTRL); regval &= ~(SCU_OSCHPCTRL_MODE_MASK | SCU_OSCHPCTRL_OSCVAL_MASK); - regval |= ((OSCHP_GetFrequency() / FOSCREF) - 1) << SCU_OSCHPCTRL_OSCVAL_SHIFT; + regval |= ((BOARD_XTAL_FREQUENCY / FOSCREF) - 1) << SCU_OSCHPCTRL_OSCVAL_SHIFT; putreg32(regval, XMC4_SCU_OSCHPCTRL); /* Restart OSC Watchdog */ regval = getreg32(XMC4_SCU_PLLCON0); regval &= ~SCU_PLLCON0_OSCRES; - putreg(regval, XMC4_SCU_PLLCON0); + putreg32(regval, XMC4_SCU_PLLCON0); /* Wait till OSC_HP output frequency is usable */ @@ -527,7 +527,7 @@ void xmc4_clock_configure(void) /* Enable selected clocks */ - putreg32(CLKSET_VALUE, XMC4_SCU_CLKSET) + putreg32(CLKSET_VALUE, XMC4_SCU_CLKSET); } /**************************************************************************** @@ -605,7 +605,7 @@ uint32_t xmc4_get_coreclock(void) /* Check if the fSYS clock is divided by two to produce fCPU clock. */ - regval = getreg32(CPUCLKCR); + regval = getreg32(XMC4_SCU_CPUCLKCR); if ((regval & SCU_CPUCLKCR_CPUDIV) != 0) { temp = temp >> 1; diff --git a/arch/arm/src/xmc4/xmc4_irq.c b/arch/arm/src/xmc4/xmc4_irq.c index 17725b8c60..c31482b638 100644 --- a/arch/arm/src/xmc4/xmc4_irq.c +++ b/arch/arm/src/xmc4/xmc4_irq.c @@ -45,6 +45,7 @@ #include #include #include +#include #include "nvic.h" #include "ram_vectors.h" diff --git a/configs/xmc4500-relax/include/board.h b/configs/xmc4500-relax/include/board.h index f3616a21e2..dbc2440902 100644 --- a/configs/xmc4500-relax/include/board.h +++ b/configs/xmc4500-relax/include/board.h @@ -130,6 +130,68 @@ #define BOARD_FLASH_WS 5 +/* LED definitions ******************************************************************/ +/* The XMC4500 Relax Lite v1 board has two LEDs: + * + * LED1 P1.1 High output illuminates + * LED2 P1.0 High output illuminates + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any + * way. The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +#define BOARD_LED0 0 +#define BOARD_LED1 1 +#define BOARD_NLEDS 2 + +/* LED bits for use with board_userled_all() */ + +#define BOARD_LED0_BIT (1 << BOARD_LED0) +#define BOARD_LED1_BIT (1 << BOARD_LED1) + +/* These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is + * defined. In that case, the usage by the board port is defined in + * include/board.h and src/sam_autoleds.c. The LEDs are used to encode + * OS-related events as follows: + * + * SYMBOL Meaning LED state + * LED2 LED1 + * --------------------- -------------------------- ------ ------ */ + +#define LED_STARTED 0 /* NuttX has been started OFF OFF */ +#define LED_HEAPALLOCATE 0 /* Heap has been allocated OFF OFF */ +#define LED_IRQSENABLED 0 /* Interrupts enabled OFF OFF */ +#define LED_STACKCREATED 1 /* Idle stack created ON OFF */ +#define LED_INIRQ 2 /* In an interrupt No change */ +#define LED_SIGNAL 2 /* In a signal handler No change */ +#define LED_ASSERTION 2 /* An assertion failed No change */ +#define LED_PANIC 3 /* The system has crashed N/C Blinking */ +#undef LED_IDLE /* MCU is is sleep mode Not used */ + +/* Thus if LED0 is statically on, NuttX has successfully booted and is, + * apparently, running normally. If LED1 is flashing at approximately + * 2Hz, then a fatal error has been detected and the system has halted. + * + * NOTE: That LED0 is not used after completion of booting and may + * be used by other board-specific logic. + */ + +/* Button definitions ***************************************************************/ +/* The XMC4500 Relax Lite v1 board has two buttons: + * + * BUTTON1 P1.14 Low input sensed when button pressed + * BUTTON2 P1.15 Low input sensed when button pressed + */ + +#define BUTTON_0 0 +#define BUTTON_1 1 +#define NUM_BUTTONS 2 + +#define BUTTON_0_BIT (1 << BUTTON_0) +#define BUTTON_1_BIT (1 << BUTTON_1) + /************************************************************************************ * Public Data ************************************************************************************/ diff --git a/configs/xmc4500-relax/src/xmc4500-relax.h b/configs/xmc4500-relax/src/xmc4500-relax.h index 6a004c8244..7934462b70 100644 --- a/configs/xmc4500-relax/src/xmc4500-relax.h +++ b/configs/xmc4500-relax/src/xmc4500-relax.h @@ -46,9 +46,21 @@ * Pre-processor Definitions ****************************************************************************/ -/* LEDs */ +/* LEDs + * + * The XMC4500 Relax Lite v1 board has two LEDs: + * + * LED1 P1.1 High output illuminates + * LED2 P1.0 High output illuminates + */ -/* BUTTONS */ +/* BUTTONS + * + * The XMC4500 Relax Lite v1 board has two buttons: + * + * BUTTON1 P1.14 Low input sensed when button pressed + * BUTTON2 P1.15 Low input sensed when button pressed + */ /**************************************************************************** * Public Types -- GitLab From c3ccfab720bb0d0e922c2243e9c183d9e3b76dc9 Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Thu, 16 Mar 2017 11:40:03 -0600 Subject: [PATCH 071/990] Fix mksyscall host binary name --- syscall/Makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/syscall/Makefile b/syscall/Makefile index 14c0c4dea5..94fa8cdfdb 100644 --- a/syscall/Makefile +++ b/syscall/Makefile @@ -39,7 +39,7 @@ DELIM ?= $(strip /) include proxies$(DELIM)Make.defs include stubs$(DELIM)Make.defs -MKSYSCALL = "$(TOPDIR)$(DELIM)tools$(DELIM)mksyscall$(EXEEXT)" +MKSYSCALL = "$(TOPDIR)$(DELIM)tools$(DELIM)mksyscall$(HOSTEXEEXT)" CSVFILE = "$(TOPDIR)$(DELIM)syscall$(DELIM)syscall.csv" STUB_SRCS += syscall_funclookup.c syscall_stublookup.c syscall_nparms.c -- GitLab From e67baffc15109ec38969113524961417a772f830 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 16 Mar 2017 13:04:01 -0600 Subject: [PATCH 072/990] XMC4xxx: Add partial USIC header file. --- arch/arm/src/xmc4/chip/xmc4_memorymap.h | 9 +- arch/arm/src/xmc4/chip/xmc4_usic.h | 475 ++++++++++++++++++++++++ 2 files changed, 481 insertions(+), 3 deletions(-) create mode 100644 arch/arm/src/xmc4/chip/xmc4_usic.h diff --git a/arch/arm/src/xmc4/chip/xmc4_memorymap.h b/arch/arm/src/xmc4/chip/xmc4_memorymap.h index 19dd637ab5..c6d15f234f 100644 --- a/arch/arm/src/xmc4/chip/xmc4_memorymap.h +++ b/arch/arm/src/xmc4/chip/xmc4_memorymap.h @@ -117,9 +117,10 @@ #define XMC4_CCU81_CC83_BASE 0x40024400 #define XMC4_POSIF0_BASE 0x40028000 #define XMC4_POSIF1_BASE 0x4002c000 -#define XMC4_USIC0_BASE 0x40030008 +#define XMC4_USIC0_BASE 0x40030000 #define XMC4_USIC0_CH0_BASE 0x40030000 #define XMC4_USIC0_CH1_BASE 0x40030200 +#define XMC4_USIC0_RAM_BASE 0x40030400 #define XMC4_ERU1_BASE 0x40044000 #define XMC4_PBA1_BASE 0x48000000 @@ -139,12 +140,14 @@ #define XMC4_CAN_MO_BASE 0x48015000 #define XMC4_DAC_BASE 0x48018000 #define XMC4_SDMMC_BASE 0x4801c000 +#define XMC4_USIC1_BASE 0x48020000 #define XMC4_USIC1_CH0_BASE 0x48020000 -#define XMC4_USIC1_BASE 0x48020008 #define XMC4_USIC1_CH1_BASE 0x48020200 +#define XMC4_USIC1_RAM_BASE 0x48020400 +#define XMC4_USIC2_BASE 0x48024000 #define XMC4_USIC2_CH0_BASE 0x48024000 -#define XMC4_USIC2_BASE 0x48024008 #define XMC4_USIC2_CH1_BASE 0x48024200 +#define XMC4_USIC2_CH1_BASE 0x48024400 #define XMC4_PORT0_BASE 0x48028000 #define XMC4_PORT1_BASE 0x48028100 #define XMC4_PORT2_BASE 0x48028200 diff --git a/arch/arm/src/xmc4/chip/xmc4_usic.h b/arch/arm/src/xmc4/chip/xmc4_usic.h new file mode 100644 index 0000000000..089a14811f --- /dev/null +++ b/arch/arm/src/xmc4/chip/xmc4_usic.h @@ -0,0 +1,475 @@ +/************************************************************************************ + * arch/arm/src/xmc4/chip/xmc4_usic.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Reference: XMC4500 Reference Manual V1.5 2014-07 Microcontrollers. + * + * 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. + * + * May include some logic from sample code provided by Infineon: + * + * Copyright (C) 2011-2015 Infineon Technologies AG. All rights reserved. + * + * Infineon Technologies AG (Infineon) is supplying this software for use with + * Infineon's microcontrollers. This file can be freely distributed within + * development tools that are supporting such microcontrollers. + * + * THIS SOFTWARE IS PROVIDED AS IS. NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * INFINEON SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, + * OR CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_XMC4_CHIP_XMC4_USIC_H +#define __ARCH_ARM_SRC_XMC4_CHIP_XMC4_USIC_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Register Offsets *****************************************************************/ + +/* PMU Registers -- See ID register */ +/* Prefetch Registers -- See PCON register */ + +/* Kernal Registers */ + +#define XMC4_USIC_ID_OFFSET 0x0008 /* Kernel State Configuration Register */ + +/* USIC Channel Registers */ + +#define XMC4_USIC_CCFG_OFFSET 0x0004 /* Channel Configuration Register */ +#define XMC4_USIC_KSCFG_OFFSET 0x000c /* Kernel State Configuration Register */ +#define XMC4_USIC_FDR_OFFSET 0x0010 /* Fractional Divider Register */ +#define XMC4_USIC_BRG_OFFSET 0x0014 /* Baud Rate Generator Register */ +#define XMC4_USIC_INPR_OFFSET 0x0018 /* Interrupt Node Pointer Register */ +#define XMC4_USIC_DX0CR_OFFSET 0x001c /* Input Control Register 0 */ +#define XMC4_USIC_DX1CR_OFFSET 0x0020 /* Input Control Register 1 */ +#define XMC4_USIC_DX2CR_OFFSET 0x0024 /* Input Control Register 2 */ +#define XMC4_USIC_DX3CR_OFFSET 0x0028 /* Input Control Register 3 */ +#define XMC4_USIC_DX4CR_OFFSET 0x002c /* Input Control Register 4 */ +#define XMC4_USIC_DX5CR_OFFSET 0x0030 /* Input Control Register 5 */ +#define XMC4_USIC_SCTR_OFFSET 0x0034 /* Shift Control Register */ +#define XMC4_USIC_TCSR_OFFSET 0x0038 /* Transmit Control/Status Register */ +#define XMC4_USIC_PCR_OFFSET 0x003c /* Protocol Control Register */ +#define XMC4_USIC_CCR_OFFSET 0x0040 /* Channel Control Register */ +#define XMC4_USIC_CMTR_OFFSET 0x0044 /* Capture Mode Timer Register */ +#define XMC4_USIC_PSR_OFFSET 0x0048 /* Protocol Status Register */ +#define XMC4_USIC_PSCR_OFFSET 0x004c /* Protocol Status Clear Register */ +#define XMC4_USIC_RBUFSR_OFFSET 0x0050 /* Receiver Buffer Status Register */ +#define XMC4_USIC_RBUF_OFFSET 0x0054 /* Receiver Buffer Register */ +#define XMC4_USIC_RBUFD_OFFSET 0x0058 /* Receiver Buffer Register for Debugger */ +#define XMC4_USIC_RBUF0_OFFSET 0x005c /* Receiver Buffer Register 0 */ +#define XMC4_USIC_RBUF1_OFFSET 0x0060 /* Receiver Buffer Register 1 */ +#define XMC4_USIC_RBUF01SR_OFFSET 0x0064 /* Receiver Buffer 01 Status Register */ +#define XMC4_USIC_FMR_OFFSET 0x0068 /* Flag Modification Register */ +#define XMC4_USIC_TBUF_OFFSET 0x0080 /* Transmit Buffer (32 x 4-bytes) */ + +/* USIC FIFO Registers */ + +#define XMC4_USIC_BYP_OFFSET 0x0100 /* Bypass Data Register */ +#define XMC4_USIC_BYPCR_OFFSET 0x0104 /* Bypass Control Register */ +#define XMC4_USIC_TBCTR_OFFSET 0x0108 /* Transmitter Buffer Control Register */ +#define XMC4_USIC_RBCTR_OFFSET 0x010c /* Receiver Buffer Control Register */ +#define XMC4_USIC_TRBPTR_OFFSET 0x0110 /* Transmit/Receive Buffer Pointer Register */ +#define XMC4_USIC_TRBSR_OFFSET 0x0114 /* Transmit/Receive Buffer Status Register */ +#define XMC4_USIC_TRBSCR_OFFSET 0x0118 /* Transmit/Receive Buffer Status Clear Register */ +#define XMC4_USIC_OUTR_OFFSET 0x011c /* Receiver Buffer Output Register */ +#define XMC4_USIC_OUTDR_OFFSET 0x0120 /* Receiver Buffer Output Register L for Debugger */ +#define XMC4_USIC_IN_OFFSET 0x0180 /* Transmit FIFO Buffer (32 x 4-bytes) */ + +/* Register Addresses ****************************************************************/ + +/* USIC0 Registers */ +/* Kernal Registers */ + +#define XMC4_USIC0_ID (XMC4_USIC0_BASE+XMC4_USIC_ID_OFFSET) + +/* USIC0 Channel 0 Registers */ + +#define XMC4_USIC00_CCFG (XMC4_USIC0_CH0_BASE+XMC4_USIC_CCFG_OFFSET) +#define XMC4_USIC00_KSCFG (XMC4_USIC0_CH0_BASE+XMC4_USIC_KSCFG_OFFSET) +#define XMC4_USIC00_FDR (XMC4_USIC0_CH0_BASE+XMC4_USIC_FDR_OFFSET) +#define XMC4_USIC00_BRG (XMC4_USIC0_CH0_BASE+XMC4_USIC_BRG_OFFSET) +#define XMC4_USIC00_INPR (XMC4_USIC0_CH0_BASE+XMC4_USIC_INPR_OFFSET) +#define XMC4_USIC00_DX0CR (XMC4_USIC0_CH0_BASE+XMC4_USIC_DX0CR_OFFSET) +#define XMC4_USIC00_DX1CR (XMC4_USIC0_CH0_BASE+XMC4_USIC_DX1CR_OFFSET) +#define XMC4_USIC00_DX2CR (XMC4_USIC0_CH0_BASE+XMC4_USIC_DX2CR_OFFSET) +#define XMC4_USIC00_DX3CR (XMC4_USIC0_CH0_BASE+XMC4_USIC_DX3CR_OFFSET) +#define XMC4_USIC00_DX4CR (XMC4_USIC0_CH0_BASE+XMC4_USIC_DX4CR_OFFSET) +#define XMC4_USIC00_DX5CR (XMC4_USIC0_CH0_BASE+XMC4_USIC_DX5CR_OFFSET) +#define XMC4_USIC00_SCTR (XMC4_USIC0_CH0_BASE+XMC4_USIC_SCTR_OFFSET) +#define XMC4_USIC00_TCSR (XMC4_USIC0_CH0_BASE+XMC4_USIC_TCSR_OFFSET) +#define XMC4_USIC00_PCR (XMC4_USIC0_CH0_BASE+XMC4_USIC_PCR_OFFSET) +#define XMC4_USIC00_CCR (XMC4_USIC0_CH0_BASE+XMC4_USIC_CCR_OFFSET) +#define XMC4_USIC00_CMTR (XMC4_USIC0_CH0_BASE+XMC4_USIC_CMTR_OFFSET) +#define XMC4_USIC00_PSR (XMC4_USIC0_CH0_BASE+XMC4_USIC_PSR_OFFSET) +#define XMC4_USIC00_PSCR (XMC4_USIC0_CH0_BASE+XMC4_USIC_PSCR_OFFSET) +#define XMC4_USIC00_RBUFSR (XMC4_USIC0_CH0_BASE+XMC4_USIC_RBUFSR_OFFSET) +#define XMC4_USIC00_RBUF (XMC4_USIC0_CH0_BASE+XMC4_USIC_RBUF_OFFSET) +#define XMC4_USIC00_RBUFD (XMC4_USIC0_CH0_BASE+XMC4_USIC_RBUFD_OFFSET) +#define XMC4_USIC00_RBUF0 (XMC4_USIC0_CH0_BASE+XMC4_USIC_RBUF0_OFFSET) +#define XMC4_USIC00_RBUF1 (XMC4_USIC0_CH0_BASE+XMC4_USIC_RBUF1_OFFSET) +#define XMC4_USIC00_RBUF01SR (XMC4_USIC0_CH0_BASE+XMC4_USIC_RBUF01SR_OFFSET) +#define XMC4_USIC00_FMR (XMC4_USIC0_CH0_BASE+XMC4_USIC_FMR_OFFSET) +#define XMC4_USIC00_TBUF (XMC4_USIC0_CH0_BASE+XMC4_USIC_TBUF_OFFSET) + +/* USIC0 Channel 0 FIFO Registers */ + +#define XMC4_USIC00_BYP (XMC4_USIC0_CH0_BASE+XMC4_USIC_BYP_OFFSET) +#define XMC4_USIC00_BYPCR (XMC4_USIC0_CH0_BASE+XMC4_USIC_BYPCR_OFFSET) +#define XMC4_USIC00_TBCTR (XMC4_USIC0_CH0_BASE+XMC4_USIC_TBCTR_OFFSET) +#define XMC4_USIC00_RBCTR (XMC4_USIC0_CH0_BASE+XMC4_USIC_RBCTR_OFFSET) +#define XMC4_USIC00_TRBPTR (XMC4_USIC0_CH0_BASE+XMC4_USIC_TRBPTR_OFFSET) +#define XMC4_USIC00_TRBSR (XMC4_USIC0_CH0_BASE+XMC4_USIC_TRBSR_OFFSET) +#define XMC4_USIC00_TRBSCR (XMC4_USIC0_CH0_BASE+XMC4_USIC_TRBSCR_OFFSET) +#define XMC4_USIC00_OUTR (XMC4_USIC0_CH0_BASE+XMC4_USIC_OUTR_OFFSET) +#define XMC4_USIC00_OUTDR (XMC4_USIC0_CH0_BASE+XMC4_USIC_OUTDR_OFFSET) +#define XMC4_USIC00_IN (XMC4_USIC0_CH0_BASE+XMC4_USIC_IN_OFFSET) + +/* USIC0 Channel 1 Registers */ + +#define XMC4_USIC01_CCFG (XMC4_USIC0_CH1_BASE+XMC4_USIC_CCFG_OFFSET) +#define XMC4_USIC01_KSCFG (XMC4_USIC0_CH1_BASE+XMC4_USIC_KSCFG_OFFSET) +#define XMC4_USIC01_FDR (XMC4_USIC0_CH1_BASE+XMC4_USIC_FDR_OFFSET) +#define XMC4_USIC01_BRG (XMC4_USIC0_CH1_BASE+XMC4_USIC_BRG_OFFSET) +#define XMC4_USIC01_INPR (XMC4_USIC0_CH1_BASE+XMC4_USIC_INPR_OFFSET) +#define XMC4_USIC01_DX0CR (XMC4_USIC0_CH1_BASE+XMC4_USIC_DX0CR_OFFSET) +#define XMC4_USIC01_DX1CR (XMC4_USIC0_CH1_BASE+XMC4_USIC_DX1CR_OFFSET) +#define XMC4_USIC01_DX2CR (XMC4_USIC0_CH1_BASE+XMC4_USIC_DX2CR_OFFSET) +#define XMC4_USIC01_DX3CR (XMC4_USIC0_CH1_BASE+XMC4_USIC_DX3CR_OFFSET) +#define XMC4_USIC01_DX4CR (XMC4_USIC0_CH1_BASE+XMC4_USIC_DX4CR_OFFSET) +#define XMC4_USIC01_DX5CR (XMC4_USIC0_CH1_BASE+XMC4_USIC_DX5CR_OFFSET) +#define XMC4_USIC01_SCTR (XMC4_USIC0_CH1_BASE+XMC4_USIC_SCTR_OFFSET) +#define XMC4_USIC01_TCSR (XMC4_USIC0_CH1_BASE+XMC4_USIC_TCSR_OFFSET) +#define XMC4_USIC01_PCR (XMC4_USIC0_CH1_BASE+XMC4_USIC_PCR_OFFSET) +#define XMC4_USIC01_CCR (XMC4_USIC0_CH1_BASE+XMC4_USIC_CCR_OFFSET) +#define XMC4_USIC01_CMTR (XMC4_USIC0_CH1_BASE+XMC4_USIC_CMTR_OFFSET) +#define XMC4_USIC01_PSR (XMC4_USIC0_CH1_BASE+XMC4_USIC_PSR_OFFSET) +#define XMC4_USIC01_PSCR (XMC4_USIC0_CH1_BASE+XMC4_USIC_PSCR_OFFSET) +#define XMC4_USIC01_RBUFSR (XMC4_USIC0_CH1_BASE+XMC4_USIC_RBUFSR_OFFSET) +#define XMC4_USIC01_RBUF (XMC4_USIC0_CH1_BASE+XMC4_USIC_RBUF_OFFSET) +#define XMC4_USIC01_RBUFD (XMC4_USIC0_CH1_BASE+XMC4_USIC_RBUFD_OFFSET) +#define XMC4_USIC01_RBUF0 (XMC4_USIC0_CH1_BASE+XMC4_USIC_RBUF0_OFFSET) +#define XMC4_USIC01_RBUF1 (XMC4_USIC0_CH1_BASE+XMC4_USIC_RBUF1_OFFSET) +#define XMC4_USIC01_RBUF01SR (XMC4_USIC0_CH1_BASE+XMC4_USIC_RBUF01SR_OFFSET) +#define XMC4_USIC01_FMR (XMC4_USIC0_CH1_BASE+XMC4_USIC_FMR_OFFSET) +#define XMC4_USIC01_TBUF (XMC4_USIC0_CH1_BASE+XMC4_USIC_TBUF_OFFSET) + +/* USIC0 Channel 1 FIFO Registers */ + +#define XMC4_USIC01_BYP (XMC4_USIC0_CH1_BASE+XMC4_USIC_BYP_OFFSET) +#define XMC4_USIC01_BYPCR (XMC4_USIC0_CH1_BASE+XMC4_USIC_BYPCR_OFFSET) +#define XMC4_USIC01_TBCTR (XMC4_USIC0_CH1_BASE+XMC4_USIC_TBCTR_OFFSET) +#define XMC4_USIC01_RBCTR (XMC4_USIC0_CH1_BASE+XMC4_USIC_RBCTR_OFFSET) +#define XMC4_USIC01_TRBPTR (XMC4_USIC0_CH1_BASE+XMC4_USIC_TRBPTR_OFFSET) +#define XMC4_USIC01_TRBSR (XMC4_USIC0_CH1_BASE+XMC4_USIC_TRBSR_OFFSET) +#define XMC4_USIC01_TRBSCR (XMC4_USIC0_CH1_BASE+XMC4_USIC_TRBSCR_OFFSET) +#define XMC4_USIC01_OUTR (XMC4_USIC0_CH1_BASE+XMC4_USIC_OUTR_OFFSET) +#define XMC4_USIC01_OUTDR (XMC4_USIC0_CH1_BASE+XMC4_USIC_OUTDR_OFFSET) +#define XMC4_USIC01_IN (XMC4_USIC0_CH1_BASE+XMC4_USIC_IN_OFFSET) + +/* USIC1 Registers */ +/* Kernal Registers */ + +#define XMC4_USIC1_ID (XMC4_USIC1_BASE+XMC4_USIC_ID_OFFSET) + +/* USIC1 Channel 0 Registers */ + +#define XMC4_USIC10_CCFG (XMC4_USIC1_CH0_BASE+XMC4_USIC_CCFG_OFFSET) +#define XMC4_USIC10_KSCFG (XMC4_USIC1_CH0_BASE+XMC4_USIC_KSCFG_OFFSET) +#define XMC4_USIC10_FDR (XMC4_USIC1_CH0_BASE+XMC4_USIC_FDR_OFFSET) +#define XMC4_USIC10_BRG (XMC4_USIC1_CH0_BASE+XMC4_USIC_BRG_OFFSET) +#define XMC4_USIC10_INPR (XMC4_USIC1_CH0_BASE+XMC4_USIC_INPR_OFFSET) +#define XMC4_USIC10_DX0CR (XMC4_USIC1_CH0_BASE+XMC4_USIC_DX0CR_OFFSET) +#define XMC4_USIC10_DX1CR (XMC4_USIC1_CH0_BASE+XMC4_USIC_DX1CR_OFFSET) +#define XMC4_USIC10_DX2CR (XMC4_USIC1_CH0_BASE+XMC4_USIC_DX2CR_OFFSET) +#define XMC4_USIC10_DX3CR (XMC4_USIC1_CH0_BASE+XMC4_USIC_DX3CR_OFFSET) +#define XMC4_USIC10_DX4CR (XMC4_USIC1_CH0_BASE+XMC4_USIC_DX4CR_OFFSET) +#define XMC4_USIC10_DX5CR (XMC4_USIC1_CH0_BASE+XMC4_USIC_DX5CR_OFFSET) +#define XMC4_USIC10_SCTR (XMC4_USIC1_CH0_BASE+XMC4_USIC_SCTR_OFFSET) +#define XMC4_USIC10_TCSR (XMC4_USIC1_CH0_BASE+XMC4_USIC_TCSR_OFFSET) +#define XMC4_USIC10_PCR (XMC4_USIC1_CH0_BASE+XMC4_USIC_PCR_OFFSET) +#define XMC4_USIC10_CCR (XMC4_USIC1_CH0_BASE+XMC4_USIC_CCR_OFFSET) +#define XMC4_USIC10_CMTR (XMC4_USIC1_CH0_BASE+XMC4_USIC_CMTR_OFFSET) +#define XMC4_USIC10_PSR (XMC4_USIC1_CH0_BASE+XMC4_USIC_PSR_OFFSET) +#define XMC4_USIC10_PSCR (XMC4_USIC1_CH0_BASE+XMC4_USIC_PSCR_OFFSET) +#define XMC4_USIC10_RBUFSR (XMC4_USIC1_CH0_BASE+XMC4_USIC_RBUFSR_OFFSET) +#define XMC4_USIC10_RBUF (XMC4_USIC1_CH0_BASE+XMC4_USIC_RBUF_OFFSET) +#define XMC4_USIC10_RBUFD (XMC4_USIC1_CH0_BASE+XMC4_USIC_RBUFD_OFFSET) +#define XMC4_USIC10_RBUF0 (XMC4_USIC1_CH0_BASE+XMC4_USIC_RBUF0_OFFSET) +#define XMC4_USIC10_RBUF1 (XMC4_USIC1_CH0_BASE+XMC4_USIC_RBUF1_OFFSET) +#define XMC4_USIC10_RBUF01SR (XMC4_USIC1_CH0_BASE+XMC4_USIC_RBUF01SR_OFFSET) +#define XMC4_USIC10_FMR (XMC4_USIC1_CH0_BASE+XMC4_USIC_FMR_OFFSET) +#define XMC4_USIC10_TBUF (XMC4_USIC1_CH0_BASE+XMC4_USIC_TBUF_OFFSET) + +/* USIC1 Channel 0 FIFO Registers */ + +#define XMC4_USIC10_BYP (XMC4_USIC1_CH0_BASE+XMC4_USIC_BYP_OFFSET) +#define XMC4_USIC10_BYPCR (XMC4_USIC1_CH0_BASE+XMC4_USIC_BYPCR_OFFSET) +#define XMC4_USIC10_TBCTR (XMC4_USIC1_CH0_BASE+XMC4_USIC_TBCTR_OFFSET) +#define XMC4_USIC10_RBCTR (XMC4_USIC1_CH0_BASE+XMC4_USIC_RBCTR_OFFSET) +#define XMC4_USIC10_TRBPTR (XMC4_USIC1_CH0_BASE+XMC4_USIC_TRBPTR_OFFSET) +#define XMC4_USIC10_TRBSR (XMC4_USIC1_CH0_BASE+XMC4_USIC_TRBSR_OFFSET) +#define XMC4_USIC10_TRBSCR (XMC4_USIC1_CH0_BASE+XMC4_USIC_TRBSCR_OFFSET) +#define XMC4_USIC10_OUTR (XMC4_USIC1_CH0_BASE+XMC4_USIC_OUTR_OFFSET) +#define XMC4_USIC10_OUTDR (XMC4_USIC1_CH0_BASE+XMC4_USIC_OUTDR_OFFSET) +#define XMC4_USIC10_IN (XMC4_USIC1_CH0_BASE+XMC4_USIC_IN_OFFSET) + +/* USIC1 Channel 1 Registers */ + +#define XMC4_USCI11_CCFG (XMC4_USIC1_CH1_BASE+XMC4_USIC_CCFG_OFFSET) +#define XMC4_USCI11_KSCFG (XMC4_USIC1_CH1_BASE+XMC4_USIC_KSCFG_OFFSET) +#define XMC4_USCI11_FDR (XMC4_USIC1_CH1_BASE+XMC4_USIC_FDR_OFFSET) +#define XMC4_USCI11_BRG (XMC4_USIC1_CH1_BASE+XMC4_USIC_BRG_OFFSET) +#define XMC4_USCI11_INPR (XMC4_USIC1_CH1_BASE+XMC4_USIC_INPR_OFFSET) +#define XMC4_USCI11_DX0CR (XMC4_USIC1_CH1_BASE+XMC4_USIC_DX0CR_OFFSET) +#define XMC4_USCI11_DX1CR (XMC4_USIC1_CH1_BASE+XMC4_USIC_DX1CR_OFFSET) +#define XMC4_USCI11_DX2CR (XMC4_USIC1_CH1_BASE+XMC4_USIC_DX2CR_OFFSET) +#define XMC4_USCI11_DX3CR (XMC4_USIC1_CH1_BASE+XMC4_USIC_DX3CR_OFFSET) +#define XMC4_USCI11_DX4CR (XMC4_USIC1_CH1_BASE+XMC4_USIC_DX4CR_OFFSET) +#define XMC4_USCI11_DX5CR (XMC4_USIC1_CH1_BASE+XMC4_USIC_DX5CR_OFFSET) +#define XMC4_USCI11_SCTR (XMC4_USIC1_CH1_BASE+XMC4_USIC_SCTR_OFFSET) +#define XMC4_USCI11_TCSR (XMC4_USIC1_CH1_BASE+XMC4_USIC_TCSR_OFFSET) +#define XMC4_USCI11_PCR (XMC4_USIC1_CH1_BASE+XMC4_USIC_PCR_OFFSET) +#define XMC4_USCI11_CCR (XMC4_USIC1_CH1_BASE+XMC4_USIC_CCR_OFFSET) +#define XMC4_USCI11_CMTR (XMC4_USIC1_CH1_BASE+XMC4_USIC_CMTR_OFFSET) +#define XMC4_USCI11_PSR (XMC4_USIC1_CH1_BASE+XMC4_USIC_PSR_OFFSET) +#define XMC4_USCI11_PSCR (XMC4_USIC1_CH1_BASE+XMC4_USIC_PSCR_OFFSET) +#define XMC4_USCI11_RBUFSR (XMC4_USIC1_CH1_BASE+XMC4_USIC_RBUFSR_OFFSET) +#define XMC4_USCI11_RBUF (XMC4_USIC1_CH1_BASE+XMC4_USIC_RBUF_OFFSET) +#define XMC4_USCI11_RBUFD (XMC4_USIC1_CH1_BASE+XMC4_USIC_RBUFD_OFFSET) +#define XMC4_USCI11_RBUF0 (XMC4_USIC1_CH1_BASE+XMC4_USIC_RBUF0_OFFSET) +#define XMC4_USCI11_RBUF1 (XMC4_USIC1_CH1_BASE+XMC4_USIC_RBUF1_OFFSET) +#define XMC4_USCI11_RBUF01SR (XMC4_USIC1_CH1_BASE+XMC4_USIC_RBUF01SR_OFFSET) +#define XMC4_USCI11_FMR (XMC4_USIC1_CH1_BASE+XMC4_USIC_FMR_OFFSET) +#define XMC4_USCI11_TBUF (XMC4_USIC1_CH1_BASE+XMC4_USIC_TBUF_OFFSET) + +/* USIC1 Channel 1 FIFO Registers */ + +#define XMC4_USCI11_BYP (XMC4_USIC1_CH1_BASE+XMC4_USIC_BYP_OFFSET) +#define XMC4_USCI11_BYPCR (XMC4_USIC1_CH1_BASE+XMC4_USIC_BYPCR_OFFSET) +#define XMC4_USCI11_TBCTR (XMC4_USIC1_CH1_BASE+XMC4_USIC_TBCTR_OFFSET) +#define XMC4_USCI11_RBCTR (XMC4_USIC1_CH1_BASE+XMC4_USIC_RBCTR_OFFSET) +#define XMC4_USCI11_TRBPTR (XMC4_USIC1_CH1_BASE+XMC4_USIC_TRBPTR_OFFSET) +#define XMC4_USCI11_TRBSR (XMC4_USIC1_CH1_BASE+XMC4_USIC_TRBSR_OFFSET) +#define XMC4_USCI11_TRBSCR (XMC4_USIC1_CH1_BASE+XMC4_USIC_TRBSCR_OFFSET) +#define XMC4_USCI11_OUTR (XMC4_USIC1_CH1_BASE+XMC4_USIC_OUTR_OFFSET) +#define XMC4_USCI11_OUTDR (XMC4_USIC1_CH1_BASE+XMC4_USIC_OUTDR_OFFSET) +#define XMC4_USCI11_IN (XMC4_USIC1_CH1_BASE+XMC4_USIC_IN_OFFSET) + +/* USCI2 Registers */ +/* Kernal Registers */ + +#define XMC4_USCI2_ID (XMC4_USCI2_BASE+XMC4_USIC_ID_OFFSET) + +/* USCI2 Channel 0 Registers */ + +#define XMC4_USCI20_CCFG (XMC4_USCI2_CH0_BASE+XMC4_USIC_CCFG_OFFSET) +#define XMC4_USCI20_KSCFG (XMC4_USCI2_CH0_BASE+XMC4_USIC_KSCFG_OFFSET) +#define XMC4_USCI20_FDR (XMC4_USCI2_CH0_BASE+XMC4_USIC_FDR_OFFSET) +#define XMC4_USCI20_BRG (XMC4_USCI2_CH0_BASE+XMC4_USIC_BRG_OFFSET) +#define XMC4_USCI20_INPR (XMC4_USCI2_CH0_BASE+XMC4_USIC_INPR_OFFSET) +#define XMC4_USCI20_DX0CR (XMC4_USCI2_CH0_BASE+XMC4_USIC_DX0CR_OFFSET) +#define XMC4_USCI20_DX1CR (XMC4_USCI2_CH0_BASE+XMC4_USIC_DX1CR_OFFSET) +#define XMC4_USCI20_DX2CR (XMC4_USCI2_CH0_BASE+XMC4_USIC_DX2CR_OFFSET) +#define XMC4_USCI20_DX3CR (XMC4_USCI2_CH0_BASE+XMC4_USIC_DX3CR_OFFSET) +#define XMC4_USCI20_DX4CR (XMC4_USCI2_CH0_BASE+XMC4_USIC_DX4CR_OFFSET) +#define XMC4_USCI20_DX5CR (XMC4_USCI2_CH0_BASE+XMC4_USIC_DX5CR_OFFSET) +#define XMC4_USCI20_SCTR (XMC4_USCI2_CH0_BASE+XMC4_USIC_SCTR_OFFSET) +#define XMC4_USCI20_TCSR (XMC4_USCI2_CH0_BASE+XMC4_USIC_TCSR_OFFSET) +#define XMC4_USCI20_PCR (XMC4_USCI2_CH0_BASE+XMC4_USIC_PCR_OFFSET) +#define XMC4_USCI20_CCR (XMC4_USCI2_CH0_BASE+XMC4_USIC_CCR_OFFSET) +#define XMC4_USCI20_CMTR (XMC4_USCI2_CH0_BASE+XMC4_USIC_CMTR_OFFSET) +#define XMC4_USCI20_PSR (XMC4_USCI2_CH0_BASE+XMC4_USIC_PSR_OFFSET) +#define XMC4_USCI20_PSCR (XMC4_USCI2_CH0_BASE+XMC4_USIC_PSCR_OFFSET) +#define XMC4_USCI20_RBUFSR (XMC4_USCI2_CH0_BASE+XMC4_USIC_RBUFSR_OFFSET) +#define XMC4_USCI20_RBUF (XMC4_USCI2_CH0_BASE+XMC4_USIC_RBUF_OFFSET) +#define XMC4_USCI20_RBUFD (XMC4_USCI2_CH0_BASE+XMC4_USIC_RBUFD_OFFSET) +#define XMC4_USCI20_RBUF0 (XMC4_USCI2_CH0_BASE+XMC4_USIC_RBUF0_OFFSET) +#define XMC4_USCI20_RBUF1 (XMC4_USCI2_CH0_BASE+XMC4_USIC_RBUF1_OFFSET) +#define XMC4_USCI20_RBUF01SR (XMC4_USCI2_CH0_BASE+XMC4_USIC_RBUF01SR_OFFSET) +#define XMC4_USCI20_FMR (XMC4_USCI2_CH0_BASE+XMC4_USIC_FMR_OFFSET) +#define XMC4_USCI20_TBUF (XMC4_USCI2_CH0_BASE+XMC4_USIC_TBUF_OFFSET) + +/* USCI2 Channel 0 FIFO Registers */ + +#define XMC4_USCI20_BYP (XMC4_USCI2_CH0_BASE+XMC4_USIC_BYP_OFFSET) +#define XMC4_USCI20_BYPCR (XMC4_USCI2_CH0_BASE+XMC4_USIC_BYPCR_OFFSET) +#define XMC4_USCI20_TBCTR (XMC4_USCI2_CH0_BASE+XMC4_USIC_TBCTR_OFFSET) +#define XMC4_USCI20_RBCTR (XMC4_USCI2_CH0_BASE+XMC4_USIC_RBCTR_OFFSET) +#define XMC4_USCI20_TRBPTR (XMC4_USCI2_CH0_BASE+XMC4_USIC_TRBPTR_OFFSET) +#define XMC4_USCI20_TRBSR (XMC4_USCI2_CH0_BASE+XMC4_USIC_TRBSR_OFFSET) +#define XMC4_USCI20_TRBSCR (XMC4_USCI2_CH0_BASE+XMC4_USIC_TRBSCR_OFFSET) +#define XMC4_USCI20_OUTR (XMC4_USCI2_CH0_BASE+XMC4_USIC_OUTR_OFFSET) +#define XMC4_USCI20_OUTDR (XMC4_USCI2_CH0_BASE+XMC4_USIC_OUTDR_OFFSET) +#define XMC4_USCI20_IN (XMC4_USCI2_CH0_BASE+XMC4_USIC_IN_OFFSET) + +/* USCI2 Channel 1 Registers */ + +#define XMC4_USCI21_CCFG (XMC4_USCI2_CH1_BASE+XMC4_USIC_CCFG_OFFSET) +#define XMC4_USCI21_KSCFG (XMC4_USCI2_CH1_BASE+XMC4_USIC_KSCFG_OFFSET) +#define XMC4_USCI21_FDR (XMC4_USCI2_CH1_BASE+XMC4_USIC_FDR_OFFSET) +#define XMC4_USCI21_BRG (XMC4_USCI2_CH1_BASE+XMC4_USIC_BRG_OFFSET) +#define XMC4_USCI21_INPR (XMC4_USCI2_CH1_BASE+XMC4_USIC_INPR_OFFSET) +#define XMC4_USCI21_DX0CR (XMC4_USCI2_CH1_BASE+XMC4_USIC_DX0CR_OFFSET) +#define XMC4_USCI21_DX1CR (XMC4_USCI2_CH1_BASE+XMC4_USIC_DX1CR_OFFSET) +#define XMC4_USCI21_DX2CR (XMC4_USCI2_CH1_BASE+XMC4_USIC_DX2CR_OFFSET) +#define XMC4_USCI21_DX3CR (XMC4_USCI2_CH1_BASE+XMC4_USIC_DX3CR_OFFSET) +#define XMC4_USCI21_DX4CR (XMC4_USCI2_CH1_BASE+XMC4_USIC_DX4CR_OFFSET) +#define XMC4_USCI21_DX5CR (XMC4_USCI2_CH1_BASE+XMC4_USIC_DX5CR_OFFSET) +#define XMC4_USCI21_SCTR (XMC4_USCI2_CH1_BASE+XMC4_USIC_SCTR_OFFSET) +#define XMC4_USCI21_TCSR (XMC4_USCI2_CH1_BASE+XMC4_USIC_TCSR_OFFSET) +#define XMC4_USCI21_PCR (XMC4_USCI2_CH1_BASE+XMC4_USIC_PCR_OFFSET) +#define XMC4_USCI21_CCR (XMC4_USCI2_CH1_BASE+XMC4_USIC_CCR_OFFSET) +#define XMC4_USCI21_CMTR (XMC4_USCI2_CH1_BASE+XMC4_USIC_CMTR_OFFSET) +#define XMC4_USCI21_PSR (XMC4_USCI2_CH1_BASE+XMC4_USIC_PSR_OFFSET) +#define XMC4_USCI21_PSCR (XMC4_USCI2_CH1_BASE+XMC4_USIC_PSCR_OFFSET) +#define XMC4_USCI21_RBUFSR (XMC4_USCI2_CH1_BASE+XMC4_USIC_RBUFSR_OFFSET) +#define XMC4_USCI21_RBUF (XMC4_USCI2_CH1_BASE+XMC4_USIC_RBUF_OFFSET) +#define XMC4_USCI21_RBUFD (XMC4_USCI2_CH1_BASE+XMC4_USIC_RBUFD_OFFSET) +#define XMC4_USCI21_RBUF0 (XMC4_USCI2_CH1_BASE+XMC4_USIC_RBUF0_OFFSET) +#define XMC4_USCI21_RBUF1 (XMC4_USCI2_CH1_BASE+XMC4_USIC_RBUF1_OFFSET) +#define XMC4_USCI21_RBUF01SR (XMC4_USCI2_CH1_BASE+XMC4_USIC_RBUF01SR_OFFSET) +#define XMC4_USCI21_FMR (XMC4_USCI2_CH1_BASE+XMC4_USIC_FMR_OFFSET) +#define XMC4_USCI21_TBUF (XMC4_USCI2_CH1_BASE+XMC4_USIC_TBUF_OFFSET) + +/* USCI2 Channel 1 FIFO Registers */ + +#define XMC4_USCI21_BYP (XMC4_USCI2_CH1_BASE+XMC4_USIC_BYP_OFFSET) +#define XMC4_USCI21_BYPCR (XMC4_USCI2_CH1_BASE+XMC4_USIC_BYPCR_OFFSET) +#define XMC4_USCI21_TBCTR (XMC4_USCI2_CH1_BASE+XMC4_USIC_TBCTR_OFFSET) +#define XMC4_USCI21_RBCTR (XMC4_USCI2_CH1_BASE+XMC4_USIC_RBCTR_OFFSET) +#define XMC4_USCI21_TRBPTR (XMC4_USCI2_CH1_BASE+XMC4_USIC_TRBPTR_OFFSET) +#define XMC4_USCI21_TRBSR (XMC4_USCI2_CH1_BASE+XMC4_USIC_TRBSR_OFFSET) +#define XMC4_USCI21_TRBSCR (XMC4_USCI2_CH1_BASE+XMC4_USIC_TRBSCR_OFFSET) +#define XMC4_USCI21_OUTR (XMC4_USCI2_CH1_BASE+XMC4_USIC_OUTR_OFFSET) +#define XMC4_USCI21_OUTDR (XMC4_USCI2_CH1_BASE+XMC4_USIC_OUTDR_OFFSET) +#define XMC4_USCI21_IN (XMC4_USCI2_CH1_BASE+XMC4_USIC_IN_OFFSET) + +/* Register Bit-Field Definitions **************************************************/ + +/* Kernal Registers */ +/* Kernel State Configuration Register */ + +#define USIC_ID_MOD_REV_SHIFT (0) /* Bits 0-7: Module Revision Number */ +#define USIC_ID_MOD_REV_MASK (0xff << USIC_ID_MOD_REV_SHIFT) +#define USIC_ID_MOD_TYPE_SHIFT (8) /* Bits 8-15: Module Type */ +#define USIC_ID_MOD_TYPE_MASK (0xff << USIC_ID_MOD_REV_SHIFT) +#define USIC_ID_MOD_NUMBER_SHIFT (16) /* Bits 16-31: Module Number Value */ +#define USIC_ID_MOD_NUMBER_MASK (0xffff << USIC_ID_MOD_NUMBER_SHIFT) + +/* USIC Channel Registers */ + +/* Channel Configuration Register */ +#define USIC_CCFG_ +/* Kernel State Configuration Register */ +#define USIC_KSCFG_ +/* Fractional Divider Register */ +#define USIC_FDR_ +/* Baud Rate Generator Register */ +#define USIC_BRG_ +/* Interrupt Node Pointer Register */ +#define USIC_INPR_ +/* Input Control Register 0 */ +#define USIC_DX0CR_ +/* Input Control Register 1 */ +#define USIC_DX1CR_ +/* Input Control Register 2 */ +#define USIC_DX2CR_ +/* Input Control Register 3 */ +#define USIC_DX3CR_ +/* Input Control Register 4 */ +#define USIC_DX4CR_ +/* Input Control Register 5 */ +#define USIC_DX5CR_ +/* Shift Control Register */ +#define USIC_SCTR_ +/* Transmit Control/Status Register */ +#define USIC_TCSR_ +/* Protocol Control Register */ +#define USIC_PCR_ +/* Channel Control Register */ +#define USIC_CCR_ +/* Capture Mode Timer Register */ +#define USIC_CMTR_ +/* Protocol Status Register */ +#define USIC_PSR_ +/* Protocol Status Clear Register */ +#define USIC_PSCR_ +/* Receiver Buffer Status Register */ +#define USIC_RBUFSR_ +/* Receiver Buffer Register */ +#define USIC_RBUF_ +/* Receiver Buffer Register for Debugger */ +#define USIC_RBUFD_ +/* Receiver Buffer Register 0 */ +#define USIC_RBUF0_ +/* Receiver Buffer Register 1 */ +#define USIC_RBUF1_ +/* Receiver Buffer 01 Status Register */ +#define USIC_RBUF01SR_ +/* Flag Modification Register */ +#define USIC_FMR_ +/* Transmit Buffer (32 x 4-bytes) */ +#define USIC_TBUF_ + +/* USIC FIFO Registers */ + +/* Bypass Data Register */ +#define USIC_BYP_ +/* Bypass Control Register */ +#define USIC_BYPCR_ +/* Transmitter Buffer Control Register */ +#define USIC_TBCTR_ +/* Receiver Buffer Control Register */ +#define USIC_RBCTR_ +/* Transmit/Receive Buffer Pointer Register */ +#define USIC_TRBPTR_ +/* Transmit/Receive Buffer Status Register */ +#define USIC_TRBSR_ +/* Transmit/Receive Buffer Status Clear Register */ +#define USIC_TRBSCR_ +/* Receiver Buffer Output Register */ +#define USIC_OUTR_ +/* Receiver Buffer Output Register L for Debugger */ +#define USIC_OUTDR_ +/* Transmit FIFO Buffer (32 x 4-bytes) */ +#define USIC_IN_ + +#endif /* __ARCH_ARM_SRC_XMC4_CHIP_XMC4_SCU_H */ -- GitLab From e30e47683bb23c45e0b029303bef28eabf895611 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 16 Mar 2017 13:24:32 -0600 Subject: [PATCH 073/990] XMC4xxx: Add partial PORTS header file. --- arch/arm/src/xmc4/chip/xmc4_ports.h | 279 ++++++++++++++++++++++++++++ 1 file changed, 279 insertions(+) create mode 100644 arch/arm/src/xmc4/chip/xmc4_ports.h diff --git a/arch/arm/src/xmc4/chip/xmc4_ports.h b/arch/arm/src/xmc4/chip/xmc4_ports.h new file mode 100644 index 0000000000..9bfa067eca --- /dev/null +++ b/arch/arm/src/xmc4/chip/xmc4_ports.h @@ -0,0 +1,279 @@ +/************************************************************************************ + * arch/arm/src/xmc4/chip/xmc4_ports.h + * + * Copyright (C /*2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Reference: XMC4500 Reference Manual V1.5 2014-07 Microcontrollers. + * + * 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. + * + * May include some logic from sample code provided by Infineon: + * + * Copyright (C /*2011-2015 Infineon Technologies AG. All rights reserved. + * + * Infineon Technologies AG (Infineon /*is supplying this software for use with + * Infineon's microcontrollers. This file can be freely distributed within + * development tools that are supporting such microcontrollers. + * + * THIS SOFTWARE IS PROVIDED AS IS. NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * INFINEON SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, + * OR CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_XMC4_CHIP_XMC4_PORTS_H +#define __ARCH_ARM_SRC_XMC4_CHIP_XMC4_PORTS_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Register Offsets *****************************************************************/ + +/* PORTS Registers */ + +#define XMC4_PORTS_OUT_OFFSET 0x0000 /* Port Output Register */ +#define XMC4_PORTS_OMR_OFFSET 0x0004 /* Port Output Modification Register */ +#define XMC4_PORTS_IOCR0_OFFSET 0x0010 /* Port Input/Output Control Register 0 */ +#define XMC4_PORTS_IOCR4_OFFSET 0x0014 /* Port Input/Output Control Register 4 */ +#define XMC4_PORTS_IOCR8_OFFSET 0x0018 /* Port Input/Output Control Register 8 */ +#define XMC4_PORTS_IOCR12_OFFSET 0x001c /* Port Input/Output Control Register 12 */ +#define XMC4_PORTS_IN_OFFSET 0x0024 /* Port Input Register */ +#define XMC4_PORTS_PDR0_OFFSET 0x0040 /* Port Pad Driver Mode 0 Register */ +#define XMC4_PORTS_PDR1_OFFSET 0x0044 /* Port Pad Driver Mode 1 Register */ +#define XMC4_PORTS_PDISC_OFFSET 0x0060 /* Port Pin Function Decision Control Register */ +#define XMC4_PORTS_PPS_OFFSET 0x0070 /* Port Pin Power Save Register */ +#define XMC4_PORTS_HWSEL_OFFSET 0x0074 /* Port Pin Hardware Select Register */ + +/* Register Addresses ****************************************************************/ +#define 0x48028000 +#define XMC4_PORT1_BASE 0x48028100 +#define XMC4_PORT2_BASE 0x48028200 +#define XMC4_PORT3_BASE 0x48028300 +#define XMC4_PORT4_BASE 0x48028400 +#define XMC4_PORT5_BASE 0x48028500 +#define XMC4_PORT6_BASE 0x48028600 +#define XMC4_PORT7_BASE 0x48028700 +#define XMC4_PORT8_BASE 0x48028800 +#define XMC4_PORT9_BASE 0x48028900 +#define XMC4_PORT14_BASE 0x48028e00 +#define XMC4_PORT15_BASE 0x48028f00 + +#define XMC4_PORT0_OUT (XMC4_PORT0_BASE+XMC4_PORTS_OUT_OFFSET) +#define XMC4_PORT0_OMR (XMC4_PORT0_BASE+XMC4_PORTS_OMR_OFFSET) +#define XMC4_PORT0_IOCR0 (XMC4_PORT0_BASE+XMC4_PORTS_IOCR0_OFFSET) +#define XMC4_PORT0_IOCR4 (XMC4_PORT0_BASE+XMC4_PORTS_IOCR4_OFFSET) +#define XMC4_PORT0_IOCR8 (XMC4_PORT0_BASE+XMC4_PORTS_IOCR8_OFFSET) +#define XMC4_PORT0_IOCR12 (XMC4_PORT0_BASE+XMC4_PORTS_IOCR12_OFFSET) +#define XMC4_PORT0_IN (XMC4_PORT0_BASE+XMC4_PORTS_IN_OFFSET) +#define XMC4_PORT0_PDR0 (XMC4_PORT0_BASE+XMC4_PORTS_PDR0_OFFSET) +#define XMC4_PORT0_PDR1 (XMC4_PORT0_BASE+XMC4_PORTS_PDR1_OFFSET) +#define XMC4_PORT0_PDISC (XMC4_PORT0_BASE+XMC4_PORTS_PDISC_OFFSET) +#define XMC4_PORT0_PPS (XMC4_PORT0_BASE+XMC4_PORTS_PPS_OFFSET) +#define XMC4_PORT0_HWSEL (XMC4_PORT0_BASE+XMC4_PORTS_HWSEL_OFFSET) + +#define XMC4_PORT1_OUT (XMC4_PORT1_BASE+XMC4_PORTS_OUT_OFFSET) +#define XMC4_PORT1_OMR (XMC4_PORT1_BASE+XMC4_PORTS_OMR_OFFSET) +#define XMC4_PORT1_IOCR0 (XMC4_PORT1_BASE+XMC4_PORTS_IOCR0_OFFSET) +#define XMC4_PORT1_IOCR4 (XMC4_PORT1_BASE+XMC4_PORTS_IOCR4_OFFSET) +#define XMC4_PORT1_IOCR8 (XMC4_PORT1_BASE+XMC4_PORTS_IOCR8_OFFSET) +#define XMC4_PORT1_IOCR12 (XMC4_PORT1_BASE+XMC4_PORTS_IOCR12_OFFSET) +#define XMC4_PORT1_IN (XMC4_PORT1_BASE+XMC4_PORTS_IN_OFFSET) +#define XMC4_PORT1_PDR0 (XMC4_PORT1_BASE+XMC4_PORTS_PDR0_OFFSET) +#define XMC4_PORT1_PDR1 (XMC4_PORT1_BASE+XMC4_PORTS_PDR1_OFFSET) +#define XMC4_PORT1_PDISC (XMC4_PORT1_BASE+XMC4_PORTS_PDISC_OFFSET) +#define XMC4_PORT1_PPS (XMC4_PORT1_BASE+XMC4_PORTS_PPS_OFFSET) +#define XMC4_PORT1_HWSEL (XMC4_PORT1_BASE+XMC4_PORTS_HWSEL_OFFSET) + +#define XMC4_PORT2_OUT (XMC4_PORT2_BASE+XMC4_PORTS_OUT_OFFSET) +#define XMC4_PORT2_OMR (XMC4_PORT2_BASE+XMC4_PORTS_OMR_OFFSET) +#define XMC4_PORT2_IOCR0 (XMC4_PORT2_BASE+XMC4_PORTS_IOCR0_OFFSET) +#define XMC4_PORT2_IOCR4 (XMC4_PORT2_BASE+XMC4_PORTS_IOCR4_OFFSET) +#define XMC4_PORT2_IOCR8 (XMC4_PORT2_BASE+XMC4_PORTS_IOCR8_OFFSET) +#define XMC4_PORT2_IOCR12 (XMC4_PORT2_BASE+XMC4_PORTS_IOCR12_OFFSET) +#define XMC4_PORT2_IN (XMC4_PORT2_BASE+XMC4_PORTS_IN_OFFSET) +#define XMC4_PORT2_PDR0 (XMC4_PORT2_BASE+XMC4_PORTS_PDR0_OFFSET) +#define XMC4_PORT2_PDR1 (XMC4_PORT2_BASE+XMC4_PORTS_PDR1_OFFSET) +#define XMC4_PORT2_PDISC (XMC4_PORT2_BASE+XMC4_PORTS_PDISC_OFFSET) +#define XMC4_PORT2_PPS (XMC4_PORT2_BASE+XMC4_PORTS_PPS_OFFSET) +#define XMC4_PORT2_HWSEL (XMC4_PORT2_BASE+XMC4_PORTS_HWSEL_OFFSET) + +#define XMC4_PORT3_OUT (XMC4_PORT3_BASE+XMC4_PORTS_OUT_OFFSET) +#define XMC4_PORT3_OMR (XMC4_PORT3_BASE+XMC4_PORTS_OMR_OFFSET) +#define XMC4_PORT3_IOCR0 (XMC4_PORT3_BASE+XMC4_PORTS_IOCR0_OFFSET) +#define XMC4_PORT3_IOCR4 (XMC4_PORT3_BASE+XMC4_PORTS_IOCR4_OFFSET) +#define XMC4_PORT3_IOCR8 (XMC4_PORT3_BASE+XMC4_PORTS_IOCR8_OFFSET) +#define XMC4_PORT3_IOCR12 (XMC4_PORT3_BASE+XMC4_PORTS_IOCR12_OFFSET) +#define XMC4_PORT3_IN (XMC4_PORT3_BASE+XMC4_PORTS_IN_OFFSET) +#define XMC4_PORT3_PDR0 (XMC4_PORT3_BASE+XMC4_PORTS_PDR0_OFFSET) +#define XMC4_PORT3_PDR1 (XMC4_PORT3_BASE+XMC4_PORTS_PDR1_OFFSET) +#define XMC4_PORT3_PDISC (XMC4_PORT3_BASE+XMC4_PORTS_PDISC_OFFSET) +#define XMC4_PORT3_PPS (XMC4_PORT3_BASE+XMC4_PORTS_PPS_OFFSET) +#define XMC4_PORT3_HWSEL (XMC4_PORT3_BASE+XMC4_PORTS_HWSEL_OFFSET) + +#define XMC4_PORT4_OUT (XMC4_PORT4_BASE+XMC4_PORTS_OUT_OFFSET) +#define XMC4_PORT4_OMR (XMC4_PORT4_BASE+XMC4_PORTS_OMR_OFFSET) +#define XMC4_PORT4_IOCR0 (XMC4_PORT4_BASE+XMC4_PORTS_IOCR0_OFFSET) +#define XMC4_PORT4_IOCR4 (XMC4_PORT4_BASE+XMC4_PORTS_IOCR4_OFFSET) +#define XMC4_PORT4_IOCR8 (XMC4_PORT4_BASE+XMC4_PORTS_IOCR8_OFFSET) +#define XMC4_PORT4_IOCR12 (XMC4_PORT4_BASE+XMC4_PORTS_IOCR12_OFFSET) +#define XMC4_PORT4_IN (XMC4_PORT4_BASE+XMC4_PORTS_IN_OFFSET) +#define XMC4_PORT4_PDR0 (XMC4_PORT4_BASE+XMC4_PORTS_PDR0_OFFSET) +#define XMC4_PORT4_PDR1 (XMC4_PORT4_BASE+XMC4_PORTS_PDR1_OFFSET) +#define XMC4_PORT4_PDISC (XMC4_PORT4_BASE+XMC4_PORTS_PDISC_OFFSET) +#define XMC4_PORT4_PPS (XMC4_PORT4_BASE+XMC4_PORTS_PPS_OFFSET) +#define XMC4_PORT4_HWSEL (XMC4_PORT4_BASE+XMC4_PORTS_HWSEL_OFFSET) + +#define XMC4_PORT5_OUT (XMC4_PORT5_BASE+XMC4_PORTS_OUT_OFFSET) +#define XMC4_PORT5_OMR (XMC4_PORT5_BASE+XMC4_PORTS_OMR_OFFSET) +#define XMC4_PORT5_IOCR0 (XMC4_PORT5_BASE+XMC4_PORTS_IOCR0_OFFSET) +#define XMC4_PORT5_IOCR4 (XMC4_PORT5_BASE+XMC4_PORTS_IOCR4_OFFSET) +#define XMC4_PORT5_IOCR8 (XMC4_PORT5_BASE+XMC4_PORTS_IOCR8_OFFSET) +#define XMC4_PORT5_IOCR12 (XMC4_PORT5_BASE+XMC4_PORTS_IOCR12_OFFSET) +#define XMC4_PORT5_IN (XMC4_PORT5_BASE+XMC4_PORTS_IN_OFFSET) +#define XMC4_PORT5_PDR0 (XMC4_PORT5_BASE+XMC4_PORTS_PDR0_OFFSET) +#define XMC4_PORT5_PDR1 (XMC4_PORT5_BASE+XMC4_PORTS_PDR1_OFFSET) +#define XMC4_PORT5_PDISC (XMC4_PORT5_BASE+XMC4_PORTS_PDISC_OFFSET) +#define XMC4_PORT5_PPS (XMC4_PORT5_BASE+XMC4_PORTS_PPS_OFFSET) +#define XMC4_PORT5_HWSEL (XMC4_PORT5_BASE+XMC4_PORTS_HWSEL_OFFSET) + +#define XMC4_PORT6_OUT (XMC4_PORT6_BASE+XMC4_PORTS_OUT_OFFSET) +#define XMC4_PORT6_OMR (XMC4_PORT6_BASE+XMC4_PORTS_OMR_OFFSET) +#define XMC4_PORT6_IOCR0 (XMC4_PORT6_BASE+XMC4_PORTS_IOCR0_OFFSET) +#define XMC4_PORT6_IOCR4 (XMC4_PORT6_BASE+XMC4_PORTS_IOCR4_OFFSET) +#define XMC4_PORT6_IOCR8 (XMC4_PORT6_BASE+XMC4_PORTS_IOCR8_OFFSET) +#define XMC4_PORT6_IOCR12 (XMC4_PORT6_BASE+XMC4_PORTS_IOCR12_OFFSET) +#define XMC4_PORT6_IN (XMC4_PORT6_BASE+XMC4_PORTS_IN_OFFSET) +#define XMC4_PORT6_PDR0 (XMC4_PORT6_BASE+XMC4_PORTS_PDR0_OFFSET) +#define XMC4_PORT6_PDR1 (XMC4_PORT6_BASE+XMC4_PORTS_PDR1_OFFSET) +#define XMC4_PORT6_PDISC (XMC4_PORT6_BASE+XMC4_PORTS_PDISC_OFFSET) +#define XMC4_PORT6_PPS (XMC4_PORT6_BASE+XMC4_PORTS_PPS_OFFSET) +#define XMC4_PORT6_HWSEL (XMC4_PORT6_BASE+XMC4_PORTS_HWSEL_OFFSET) + +#define XMC4_PORT7_OUT (XMC4_PORT7_BASE+XMC4_PORTS_OUT_OFFSET) +#define XMC4_PORT7_OMR (XMC4_PORT7_BASE+XMC4_PORTS_OMR_OFFSET) +#define XMC4_PORT7_IOCR0 (XMC4_PORT7_BASE+XMC4_PORTS_IOCR0_OFFSET) +#define XMC4_PORT7_IOCR4 (XMC4_PORT7_BASE+XMC4_PORTS_IOCR4_OFFSET) +#define XMC4_PORT7_IOCR8 (XMC4_PORT7_BASE+XMC4_PORTS_IOCR8_OFFSET) +#define XMC4_PORT7_IOCR12 (XMC4_PORT7_BASE+XMC4_PORTS_IOCR12_OFFSET) +#define XMC4_PORT7_IN (XMC4_PORT7_BASE+XMC4_PORTS_IN_OFFSET) +#define XMC4_PORT7_PDR0 (XMC4_PORT7_BASE+XMC4_PORTS_PDR0_OFFSET) +#define XMC4_PORT7_PDR1 (XMC4_PORT7_BASE+XMC4_PORTS_PDR1_OFFSET) +#define XMC4_PORT7_PDISC (XMC4_PORT7_BASE+XMC4_PORTS_PDISC_OFFSET) +#define XMC4_PORT7_PPS (XMC4_PORT7_BASE+XMC4_PORTS_PPS_OFFSET) +#define XMC4_PORT7_HWSEL (XMC4_PORT7_BASE+XMC4_PORTS_HWSEL_OFFSET) + +#define XMC4_PORT8_OUT (XMC4_PORT8_BASE+XMC4_PORTS_OUT_OFFSET) +#define XMC4_PORT8_OMR (XMC4_PORT8_BASE+XMC4_PORTS_OMR_OFFSET) +#define XMC4_PORT8_IOCR0 (XMC4_PORT8_BASE+XMC4_PORTS_IOCR0_OFFSET) +#define XMC4_PORT8_IOCR4 (XMC4_PORT8_BASE+XMC4_PORTS_IOCR4_OFFSET) +#define XMC4_PORT8_IOCR8 (XMC4_PORT8_BASE+XMC4_PORTS_IOCR8_OFFSET) +#define XMC4_PORT8_IOCR12 (XMC4_PORT8_BASE+XMC4_PORTS_IOCR12_OFFSET) +#define XMC4_PORT8_IN (XMC4_PORT8_BASE+XMC4_PORTS_IN_OFFSET) +#define XMC4_PORT8_PDR0 (XMC4_PORT8_BASE+XMC4_PORTS_PDR0_OFFSET) +#define XMC4_PORT8_PDR1 (XMC4_PORT8_BASE+XMC4_PORTS_PDR1_OFFSET) +#define XMC4_PORT8_PDISC (XMC4_PORT8_BASE+XMC4_PORTS_PDISC_OFFSET) +#define XMC4_PORT8_PPS (XMC4_PORT8_BASE+XMC4_PORTS_PPS_OFFSET) +#define XMC4_PORT8_HWSEL (XMC4_PORT8_BASE+XMC4_PORTS_HWSEL_OFFSET) + +#define XMC4_PORT9_OUT (XMC4_PORT9_BASE+XMC4_PORTS_OUT_OFFSET) +#define XMC4_PORT9_OMR (XMC4_PORT9_BASE+XMC4_PORTS_OMR_OFFSET) +#define XMC4_PORT9_IOCR0 (XMC4_PORT9_BASE+XMC4_PORTS_IOCR0_OFFSET) +#define XMC4_PORT9_IOCR4 (XMC4_PORT9_BASE+XMC4_PORTS_IOCR4_OFFSET) +#define XMC4_PORT9_IOCR8 (XMC4_PORT9_BASE+XMC4_PORTS_IOCR8_OFFSET) +#define XMC4_PORT9_IOCR12 (XMC4_PORT9_BASE+XMC4_PORTS_IOCR12_OFFSET) +#define XMC4_PORT9_IN (XMC4_PORT9_BASE+XMC4_PORTS_IN_OFFSET) +#define XMC4_PORT9_PDR0 (XMC4_PORT9_BASE+XMC4_PORTS_PDR0_OFFSET) +#define XMC4_PORT9_PDR1 (XMC4_PORT9_BASE+XMC4_PORTS_PDR1_OFFSET) +#define XMC4_PORT9_PDISC (XMC4_PORT9_BASE+XMC4_PORTS_PDISC_OFFSET) +#define XMC4_PORT9_PPS (XMC4_PORT9_BASE+XMC4_PORTS_PPS_OFFSET) +#define XMC4_PORT9_HWSEL (XMC4_PORT9_BASE+XMC4_PORTS_HWSEL_OFFSET) + +#define XMC4_PORT14_OUT (XMC4_PORT14_BASE+XMC4_PORTS_OUT_OFFSET) +#define XMC4_PORT14_OMR (XMC4_PORT14_BASE+XMC4_PORTS_OMR_OFFSET) +#define XMC4_PORT14_IOCR0 (XMC4_PORT14_BASE+XMC4_PORTS_IOCR0_OFFSET) +#define XMC4_PORT14_IOCR4 (XMC4_PORT14_BASE+XMC4_PORTS_IOCR4_OFFSET) +#define XMC4_PORT14_IOCR8 (XMC4_PORT14_BASE+XMC4_PORTS_IOCR8_OFFSET) +#define XMC4_PORT14_IOCR12 (XMC4_PORT14_BASE+XMC4_PORTS_IOCR12_OFFSET) +#define XMC4_PORT14_IN (XMC4_PORT14_BASE+XMC4_PORTS_IN_OFFSET) +#define XMC4_PORT14_PDR0 (XMC4_PORT14_BASE+XMC4_PORTS_PDR0_OFFSET) +#define XMC4_PORT14_PDR1 (XMC4_PORT14_BASE+XMC4_PORTS_PDR1_OFFSET) +#define XMC4_PORT14_PDISC (XMC4_PORT14_BASE+XMC4_PORTS_PDISC_OFFSET) +#define XMC4_PORT14_PPS (XMC4_PORT14_BASE+XMC4_PORTS_PPS_OFFSET) +#define XMC4_PORT14_HWSEL (XMC4_PORT14_BASE+XMC4_PORTS_HWSEL_OFFSET) + +#define XMC4_PORT15_OUT (XMC4_PORT15_BASE+XMC4_PORTS_OUT_OFFSET) +#define XMC4_PORT15_OMR (XMC4_PORT15_BASE+XMC4_PORTS_OMR_OFFSET) +#define XMC4_PORT15_IOCR0 (XMC4_PORT15_BASE+XMC4_PORTS_IOCR0_OFFSET) +#define XMC4_PORT15_IOCR4 (XMC4_PORT15_BASE+XMC4_PORTS_IOCR4_OFFSET) +#define XMC4_PORT15_IOCR8 (XMC4_PORT15_BASE+XMC4_PORTS_IOCR8_OFFSET) +#define XMC4_PORT15_IOCR12 (XMC4_PORT15_BASE+XMC4_PORTS_IOCR12_OFFSET) +#define XMC4_PORT15_IN (XMC4_PORT15_BASE+XMC4_PORTS_IN_OFFSET) +#define XMC4_PORT15_PDR0 (XMC4_PORT15_BASE+XMC4_PORTS_PDR0_OFFSET) +#define XMC4_PORT15_PDR1 (XMC4_PORT15_BASE+XMC4_PORTS_PDR1_OFFSET) +#define XMC4_PORT15_PDISC (XMC4_PORT15_BASE+XMC4_PORTS_PDISC_OFFSET) +#define XMC4_PORT15_PPS (XMC4_PORT15_BASE+XMC4_PORTS_PPS_OFFSET) +#define XMC4_PORT15_HWSEL (XMC4_PORT15_BASE+XMC4_PORTS_HWSEL_OFFSET) + +/* Register Bit-Field Definitions **************************************************/ + +/* Port Output Register */ +#define PORTS_OUT_ +/* Port Output Modification Register */ +#define PORTS_OMR_ +/* Port Input/Output Control Register 0 */ +#define PORTS_IOCR0_ +/* Port Input/Output Control Register 4 */ +#define PORTS_IOCR4_ +/* Port Input/Output Control Register 8 */ +#define PORTS_IOCR8_ +/* Port Input/Output Control Register 12 */ +#define PORTS_IOCR12_ +/* Port Input Register */ +#define PORTS_IN_ +/* Port Pad Driver Mode 0 Register */ +#define PORTS_PDR0_ +/* Port Pad Driver Mode 1 Register */ +#define PORTS_PDR1_ +/* Port Pin Function Decision Control Register */ +#define PORTS_PDISC_ +/* Port Pin Power Save Register */ +#define PORTS_PPS_ +/* Port Pin Hardware Select Register */ +#define PORTS_HWSEL_ + +#endif /* __ARCH_ARM_SRC_XMC4_CHIP_XMC4_SCU_H */ -- GitLab From 6b167122c0e82f55f95b1037c1f63eb3fdc99c32 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 16 Mar 2017 14:26:22 -0600 Subject: [PATCH 074/990] XMC4xxx: Move clock utility functions from xmc4_clocconfig.c to new xmc4_clockutils.c --- arch/arm/src/xmc4/Make.defs | 6 +- arch/arm/src/xmc4/chip/xmc4_memorymap.h | 2 +- arch/arm/src/xmc4/xmc4_clockconfig.c | 84 ------------- arch/arm/src/xmc4/xmc4_clockutils.c | 150 ++++++++++++++++++++++++ 4 files changed, 154 insertions(+), 88 deletions(-) create mode 100644 arch/arm/src/xmc4/xmc4_clockutils.c diff --git a/arch/arm/src/xmc4/Make.defs b/arch/arm/src/xmc4/Make.defs index 79497388a4..63998a7133 100644 --- a/arch/arm/src/xmc4/Make.defs +++ b/arch/arm/src/xmc4/Make.defs @@ -110,9 +110,9 @@ endif CHIP_ASRCS = -CHIP_CSRCS = xmc4_allocateheap.c xmc4_clockconfig.c xmc4_clrpend.c -CHIP_CSRCS += xmc4_idle.c xmc4_irq.c xmc4_lowputc.c xmc4_gpio.c -CHIP_CSRCS += xmc4_serialinit.c xmc4_serial.c xmc4_start.c xmc4_uid.c +CHIP_CSRCS = xmc4_allocateheap.c xmc4_clockconfig.c xmc4_clockutils.c +CHIP_CSRCS += xmc4_clrpend.c xmc4_idle.c xmc4_irq.c xmc4_lowputc.c +CHIP_CSRCS += xmc4_gpio.c xmc4_serial.c xmc4_start.c # Configuration-dependent Kinetis files diff --git a/arch/arm/src/xmc4/chip/xmc4_memorymap.h b/arch/arm/src/xmc4/chip/xmc4_memorymap.h index c6d15f234f..c2b847d4e0 100644 --- a/arch/arm/src/xmc4/chip/xmc4_memorymap.h +++ b/arch/arm/src/xmc4/chip/xmc4_memorymap.h @@ -147,7 +147,7 @@ #define XMC4_USIC2_BASE 0x48024000 #define XMC4_USIC2_CH0_BASE 0x48024000 #define XMC4_USIC2_CH1_BASE 0x48024200 -#define XMC4_USIC2_CH1_BASE 0x48024400 +#define XMC4_USIC2_RAM_BASE 0x48024400 #define XMC4_PORT0_BASE 0x48028000 #define XMC4_PORT1_BASE 0x48028100 #define XMC4_PORT2_BASE 0x48028200 diff --git a/arch/arm/src/xmc4/xmc4_clockconfig.c b/arch/arm/src/xmc4/xmc4_clockconfig.c index 26608a85b8..d663ea9f82 100644 --- a/arch/arm/src/xmc4/xmc4_clockconfig.c +++ b/arch/arm/src/xmc4/xmc4_clockconfig.c @@ -529,87 +529,3 @@ void xmc4_clock_configure(void) putreg32(CLKSET_VALUE, XMC4_SCU_CLKSET); } - -/**************************************************************************** - * Name: xmc4_get_coreclock - * - * Description: - * Return the current core clock frequency (fCPU). - * - ****************************************************************************/ - -uint32_t xmc4_get_coreclock(void) -{ - uint32_t pdiv; - uint32_t ndiv; - uint32_t kdiv; - uint32_t sysdiv; - uint32_t regval; - uint32_t temp; - - if ((getreg32(XMC4_SCU_SYSCLKCR) & SCU_SYSCLKCR_SYSSEL) != 0) - { - /* fPLL is clock source for fSYS */ - - if ((getreg32(XMC4_SCU_PLLCON2) & SCU_PLLCON2_PINSEL) != 0) - { - /* PLL input clock is the backup clock (fOFI) */ - - temp = OFI_FREQUENCY; - } - else - { - /* PLL input clock is the high performance oscillator (fOSCHP); - * Only board specific logic knows this value. - */ - - temp = BOARD_XTAL_FREQUENCY; - } - - /* Check if PLL is locked */ - - regval = getreg32(XMC4_SCU_PLLSTAT); - if ((regval & SCU_PLLSTAT_VCOLOCK) != 0) - { - /* PLL normal mode */ - - regval = getreg32(XMC4_SCU_PLLCON1); - pdiv = ((regval & SCU_PLLCON1_PDIV_MASK) >> SCU_PLLCON1_PDIV_SHIFT) + 1; - ndiv = ((regval & SCU_PLLCON1_NDIV_MASK) >> SCU_PLLCON1_NDIV_SHIFT) + 1; - kdiv = ((regval & SCU_PLLCON1_K2DIV_MASK) >> SCU_PLLCON1_K2DIV_SHIFT) + 1; - - temp = (temp / (pdiv * kdiv)) * ndiv; - } - else - { - /* PLL prescalar mode */ - - regval = getreg32(XMC4_SCU_PLLCON1); - kdiv = ((regval & SCU_PLLCON1_K1DIV_MASK) >> SCU_PLLCON1_K1DIV_SHIFT) + 1; - - temp = (temp / kdiv); - } - } - else - { - /* fOFI is clock source for fSYS */ - - temp = OFI_FREQUENCY; - } - - /* Divide by SYSDIV to get fSYS */ - - regval = getreg32(XMC4_SCU_SYSCLKCR); - sysdiv = ((regval & SCU_SYSCLKCR_SYSDIV_MASK) >> SCU_SYSCLKCR_SYSDIV_SHIFT) + 1; - temp = temp / sysdiv; - - /* Check if the fSYS clock is divided by two to produce fCPU clock. */ - - regval = getreg32(XMC4_SCU_CPUCLKCR); - if ((regval & SCU_CPUCLKCR_CPUDIV) != 0) - { - temp = temp >> 1; - } - - return temp; -} diff --git a/arch/arm/src/xmc4/xmc4_clockutils.c b/arch/arm/src/xmc4/xmc4_clockutils.c new file mode 100644 index 0000000000..cf9649099e --- /dev/null +++ b/arch/arm/src/xmc4/xmc4_clockutils.c @@ -0,0 +1,150 @@ +/**************************************************************************** + * arch/arm/src/xmc4/xmc4_clockutils.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * + * Reference: XMC4500 Reference Manual V1.5 2014-07 Microcontrollers. + * + * 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. + * + * May include some logic from sample code provided by Infineon: + * + * Copyright (C) 2011-2015 Infineon Technologies AG. All rights reserved. + * + * Infineon Technologies AG (Infineon) is supplying this software for use with + * Infineon's microcontrollers. This file can be freely distributed within + * development tools that are supporting such microcontrollers. + * + * THIS SOFTWARE IS PROVIDED AS IS. NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * INFINEON SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, + * OR CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include "up_arch.h" +#include "chip/xmc4_scu.h" +#include "xmc4_clockconfig.h" + +#include + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: xmc4_get_coreclock + * + * Description: + * Return the current core clock frequency (fCPU). + * + ****************************************************************************/ + +uint32_t xmc4_get_coreclock(void) +{ + uint32_t pdiv; + uint32_t ndiv; + uint32_t kdiv; + uint32_t sysdiv; + uint32_t regval; + uint32_t temp; + + if ((getreg32(XMC4_SCU_SYSCLKCR) & SCU_SYSCLKCR_SYSSEL) != 0) + { + /* fPLL is clock source for fSYS */ + + if ((getreg32(XMC4_SCU_PLLCON2) & SCU_PLLCON2_PINSEL) != 0) + { + /* PLL input clock is the backup clock (fOFI) */ + + temp = OFI_FREQUENCY; + } + else + { + /* PLL input clock is the high performance oscillator (fOSCHP); + * Only board specific logic knows this value. + */ + + temp = BOARD_XTAL_FREQUENCY; + } + + /* Check if PLL is locked */ + + regval = getreg32(XMC4_SCU_PLLSTAT); + if ((regval & SCU_PLLSTAT_VCOLOCK) != 0) + { + /* PLL normal mode */ + + regval = getreg32(XMC4_SCU_PLLCON1); + pdiv = ((regval & SCU_PLLCON1_PDIV_MASK) >> SCU_PLLCON1_PDIV_SHIFT) + 1; + ndiv = ((regval & SCU_PLLCON1_NDIV_MASK) >> SCU_PLLCON1_NDIV_SHIFT) + 1; + kdiv = ((regval & SCU_PLLCON1_K2DIV_MASK) >> SCU_PLLCON1_K2DIV_SHIFT) + 1; + + temp = (temp / (pdiv * kdiv)) * ndiv; + } + else + { + /* PLL prescalar mode */ + + regval = getreg32(XMC4_SCU_PLLCON1); + kdiv = ((regval & SCU_PLLCON1_K1DIV_MASK) >> SCU_PLLCON1_K1DIV_SHIFT) + 1; + + temp = (temp / kdiv); + } + } + else + { + /* fOFI is clock source for fSYS */ + + temp = OFI_FREQUENCY; + } + + /* Divide by SYSDIV to get fSYS */ + + regval = getreg32(XMC4_SCU_SYSCLKCR); + sysdiv = ((regval & SCU_SYSCLKCR_SYSDIV_MASK) >> SCU_SYSCLKCR_SYSDIV_SHIFT) + 1; + temp = temp / sysdiv; + + /* Check if the fSYS clock is divided by two to produce fCPU clock. */ + + regval = getreg32(XMC4_SCU_CPUCLKCR); + if ((regval & SCU_CPUCLKCR_CPUDIV) != 0) + { + temp = temp >> 1; + } + + return temp; +} -- GitLab From 7601a27cee348f70bebcac95e8e8372fe0651bbf Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Thu, 16 Mar 2017 14:16:18 -1000 Subject: [PATCH 075/990] sem_holder:The logic for the list version is unchanged --- sched/semaphore/sem_holder.c | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/sched/semaphore/sem_holder.c b/sched/semaphore/sem_holder.c index bca4b4429b..bc5c186e6b 100644 --- a/sched/semaphore/sem_holder.c +++ b/sched/semaphore/sem_holder.c @@ -672,13 +672,17 @@ static int sem_restoreholderprioB(FAR struct semholder_s *pholder, if (pholder->htcb == rtcb) { - /* The running task has given up a count on the semaphore - * Release the holder if all counts have been given up. - * before reprioritizing causes a context switch. + /* The running task has given up a count on the semaphore */ + +#if CONFIG_SEM_PREALLOCHOLDERS == 0 + /* In the case where there are only 2 holders. This step + * is necessary to insure we have space. Release the holder + * if all counts have been given up. before reprioritizing + * causes a context switch. */ sem_findandfreeholder(sem, rtcb); - +#endif (void)sem_restoreholderprio(rtcb, sem, arg); return 1; } -- GitLab From f672478e7ea1a0248c1a1068d43eba486bed954a Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 17 Mar 2017 08:12:21 -0600 Subject: [PATCH 076/990] XMC4xxx: Completes the PORT register definition header file. --- arch/arm/src/xmc4/chip/xmc4_ports.h | 592 +++++++++++++++++++--------- 1 file changed, 395 insertions(+), 197 deletions(-) diff --git a/arch/arm/src/xmc4/chip/xmc4_ports.h b/arch/arm/src/xmc4/chip/xmc4_ports.h index 9bfa067eca..1d6cfa6b42 100644 --- a/arch/arm/src/xmc4/chip/xmc4_ports.h +++ b/arch/arm/src/xmc4/chip/xmc4_ports.h @@ -66,214 +66,412 @@ /* PORTS Registers */ -#define XMC4_PORTS_OUT_OFFSET 0x0000 /* Port Output Register */ -#define XMC4_PORTS_OMR_OFFSET 0x0004 /* Port Output Modification Register */ -#define XMC4_PORTS_IOCR0_OFFSET 0x0010 /* Port Input/Output Control Register 0 */ -#define XMC4_PORTS_IOCR4_OFFSET 0x0014 /* Port Input/Output Control Register 4 */ -#define XMC4_PORTS_IOCR8_OFFSET 0x0018 /* Port Input/Output Control Register 8 */ -#define XMC4_PORTS_IOCR12_OFFSET 0x001c /* Port Input/Output Control Register 12 */ -#define XMC4_PORTS_IN_OFFSET 0x0024 /* Port Input Register */ -#define XMC4_PORTS_PDR0_OFFSET 0x0040 /* Port Pad Driver Mode 0 Register */ -#define XMC4_PORTS_PDR1_OFFSET 0x0044 /* Port Pad Driver Mode 1 Register */ -#define XMC4_PORTS_PDISC_OFFSET 0x0060 /* Port Pin Function Decision Control Register */ -#define XMC4_PORTS_PPS_OFFSET 0x0070 /* Port Pin Power Save Register */ -#define XMC4_PORTS_HWSEL_OFFSET 0x0074 /* Port Pin Hardware Select Register */ +#define XMC4_PORT_OUT_OFFSET 0x0000 /* Port Output Register */ +#define XMC4_PORT_OMR_OFFSET 0x0004 /* Port Output Modification Register */ +#define XMC4_PORT_IOCR0_OFFSET 0x0010 /* Port Input/Output Control Register 0 */ +#define XMC4_PORT_IOCR4_OFFSET 0x0014 /* Port Input/Output Control Register 4 */ +#define XMC4_PORT_IOCR8_OFFSET 0x0018 /* Port Input/Output Control Register 8 */ +#define XMC4_PORT_IOCR12_OFFSET 0x001c /* Port Input/Output Control Register 12 */ +#define XMC4_PORT_IN_OFFSET 0x0024 /* Port Input Register */ +#define XMC4_PORT_PDR0_OFFSET 0x0040 /* Port Pad Driver Mode 0 Register */ +#define XMC4_PORT_PDR1_OFFSET 0x0044 /* Port Pad Driver Mode 1 Register */ +#define XMC4_PORT_PDISC_OFFSET 0x0060 /* Port Pin Function Decision Control Register */ +#define XMC4_PORT_PPS_OFFSET 0x0070 /* Port Pin Power Save Register */ +#define XMC4_PORT_HWSEL_OFFSET 0x0074 /* Port Pin Hardware Select Register */ /* Register Addresses ****************************************************************/ -#define 0x48028000 -#define XMC4_PORT1_BASE 0x48028100 -#define XMC4_PORT2_BASE 0x48028200 -#define XMC4_PORT3_BASE 0x48028300 -#define XMC4_PORT4_BASE 0x48028400 -#define XMC4_PORT5_BASE 0x48028500 -#define XMC4_PORT6_BASE 0x48028600 -#define XMC4_PORT7_BASE 0x48028700 -#define XMC4_PORT8_BASE 0x48028800 -#define XMC4_PORT9_BASE 0x48028900 -#define XMC4_PORT14_BASE 0x48028e00 -#define XMC4_PORT15_BASE 0x48028f00 - -#define XMC4_PORT0_OUT (XMC4_PORT0_BASE+XMC4_PORTS_OUT_OFFSET) -#define XMC4_PORT0_OMR (XMC4_PORT0_BASE+XMC4_PORTS_OMR_OFFSET) -#define XMC4_PORT0_IOCR0 (XMC4_PORT0_BASE+XMC4_PORTS_IOCR0_OFFSET) -#define XMC4_PORT0_IOCR4 (XMC4_PORT0_BASE+XMC4_PORTS_IOCR4_OFFSET) -#define XMC4_PORT0_IOCR8 (XMC4_PORT0_BASE+XMC4_PORTS_IOCR8_OFFSET) -#define XMC4_PORT0_IOCR12 (XMC4_PORT0_BASE+XMC4_PORTS_IOCR12_OFFSET) -#define XMC4_PORT0_IN (XMC4_PORT0_BASE+XMC4_PORTS_IN_OFFSET) -#define XMC4_PORT0_PDR0 (XMC4_PORT0_BASE+XMC4_PORTS_PDR0_OFFSET) -#define XMC4_PORT0_PDR1 (XMC4_PORT0_BASE+XMC4_PORTS_PDR1_OFFSET) -#define XMC4_PORT0_PDISC (XMC4_PORT0_BASE+XMC4_PORTS_PDISC_OFFSET) -#define XMC4_PORT0_PPS (XMC4_PORT0_BASE+XMC4_PORTS_PPS_OFFSET) -#define XMC4_PORT0_HWSEL (XMC4_PORT0_BASE+XMC4_PORTS_HWSEL_OFFSET) - -#define XMC4_PORT1_OUT (XMC4_PORT1_BASE+XMC4_PORTS_OUT_OFFSET) -#define XMC4_PORT1_OMR (XMC4_PORT1_BASE+XMC4_PORTS_OMR_OFFSET) -#define XMC4_PORT1_IOCR0 (XMC4_PORT1_BASE+XMC4_PORTS_IOCR0_OFFSET) -#define XMC4_PORT1_IOCR4 (XMC4_PORT1_BASE+XMC4_PORTS_IOCR4_OFFSET) -#define XMC4_PORT1_IOCR8 (XMC4_PORT1_BASE+XMC4_PORTS_IOCR8_OFFSET) -#define XMC4_PORT1_IOCR12 (XMC4_PORT1_BASE+XMC4_PORTS_IOCR12_OFFSET) -#define XMC4_PORT1_IN (XMC4_PORT1_BASE+XMC4_PORTS_IN_OFFSET) -#define XMC4_PORT1_PDR0 (XMC4_PORT1_BASE+XMC4_PORTS_PDR0_OFFSET) -#define XMC4_PORT1_PDR1 (XMC4_PORT1_BASE+XMC4_PORTS_PDR1_OFFSET) -#define XMC4_PORT1_PDISC (XMC4_PORT1_BASE+XMC4_PORTS_PDISC_OFFSET) -#define XMC4_PORT1_PPS (XMC4_PORT1_BASE+XMC4_PORTS_PPS_OFFSET) -#define XMC4_PORT1_HWSEL (XMC4_PORT1_BASE+XMC4_PORTS_HWSEL_OFFSET) - -#define XMC4_PORT2_OUT (XMC4_PORT2_BASE+XMC4_PORTS_OUT_OFFSET) -#define XMC4_PORT2_OMR (XMC4_PORT2_BASE+XMC4_PORTS_OMR_OFFSET) -#define XMC4_PORT2_IOCR0 (XMC4_PORT2_BASE+XMC4_PORTS_IOCR0_OFFSET) -#define XMC4_PORT2_IOCR4 (XMC4_PORT2_BASE+XMC4_PORTS_IOCR4_OFFSET) -#define XMC4_PORT2_IOCR8 (XMC4_PORT2_BASE+XMC4_PORTS_IOCR8_OFFSET) -#define XMC4_PORT2_IOCR12 (XMC4_PORT2_BASE+XMC4_PORTS_IOCR12_OFFSET) -#define XMC4_PORT2_IN (XMC4_PORT2_BASE+XMC4_PORTS_IN_OFFSET) -#define XMC4_PORT2_PDR0 (XMC4_PORT2_BASE+XMC4_PORTS_PDR0_OFFSET) -#define XMC4_PORT2_PDR1 (XMC4_PORT2_BASE+XMC4_PORTS_PDR1_OFFSET) -#define XMC4_PORT2_PDISC (XMC4_PORT2_BASE+XMC4_PORTS_PDISC_OFFSET) -#define XMC4_PORT2_PPS (XMC4_PORT2_BASE+XMC4_PORTS_PPS_OFFSET) -#define XMC4_PORT2_HWSEL (XMC4_PORT2_BASE+XMC4_PORTS_HWSEL_OFFSET) - -#define XMC4_PORT3_OUT (XMC4_PORT3_BASE+XMC4_PORTS_OUT_OFFSET) -#define XMC4_PORT3_OMR (XMC4_PORT3_BASE+XMC4_PORTS_OMR_OFFSET) -#define XMC4_PORT3_IOCR0 (XMC4_PORT3_BASE+XMC4_PORTS_IOCR0_OFFSET) -#define XMC4_PORT3_IOCR4 (XMC4_PORT3_BASE+XMC4_PORTS_IOCR4_OFFSET) -#define XMC4_PORT3_IOCR8 (XMC4_PORT3_BASE+XMC4_PORTS_IOCR8_OFFSET) -#define XMC4_PORT3_IOCR12 (XMC4_PORT3_BASE+XMC4_PORTS_IOCR12_OFFSET) -#define XMC4_PORT3_IN (XMC4_PORT3_BASE+XMC4_PORTS_IN_OFFSET) -#define XMC4_PORT3_PDR0 (XMC4_PORT3_BASE+XMC4_PORTS_PDR0_OFFSET) -#define XMC4_PORT3_PDR1 (XMC4_PORT3_BASE+XMC4_PORTS_PDR1_OFFSET) -#define XMC4_PORT3_PDISC (XMC4_PORT3_BASE+XMC4_PORTS_PDISC_OFFSET) -#define XMC4_PORT3_PPS (XMC4_PORT3_BASE+XMC4_PORTS_PPS_OFFSET) -#define XMC4_PORT3_HWSEL (XMC4_PORT3_BASE+XMC4_PORTS_HWSEL_OFFSET) - -#define XMC4_PORT4_OUT (XMC4_PORT4_BASE+XMC4_PORTS_OUT_OFFSET) -#define XMC4_PORT4_OMR (XMC4_PORT4_BASE+XMC4_PORTS_OMR_OFFSET) -#define XMC4_PORT4_IOCR0 (XMC4_PORT4_BASE+XMC4_PORTS_IOCR0_OFFSET) -#define XMC4_PORT4_IOCR4 (XMC4_PORT4_BASE+XMC4_PORTS_IOCR4_OFFSET) -#define XMC4_PORT4_IOCR8 (XMC4_PORT4_BASE+XMC4_PORTS_IOCR8_OFFSET) -#define XMC4_PORT4_IOCR12 (XMC4_PORT4_BASE+XMC4_PORTS_IOCR12_OFFSET) -#define XMC4_PORT4_IN (XMC4_PORT4_BASE+XMC4_PORTS_IN_OFFSET) -#define XMC4_PORT4_PDR0 (XMC4_PORT4_BASE+XMC4_PORTS_PDR0_OFFSET) -#define XMC4_PORT4_PDR1 (XMC4_PORT4_BASE+XMC4_PORTS_PDR1_OFFSET) -#define XMC4_PORT4_PDISC (XMC4_PORT4_BASE+XMC4_PORTS_PDISC_OFFSET) -#define XMC4_PORT4_PPS (XMC4_PORT4_BASE+XMC4_PORTS_PPS_OFFSET) -#define XMC4_PORT4_HWSEL (XMC4_PORT4_BASE+XMC4_PORTS_HWSEL_OFFSET) - -#define XMC4_PORT5_OUT (XMC4_PORT5_BASE+XMC4_PORTS_OUT_OFFSET) -#define XMC4_PORT5_OMR (XMC4_PORT5_BASE+XMC4_PORTS_OMR_OFFSET) -#define XMC4_PORT5_IOCR0 (XMC4_PORT5_BASE+XMC4_PORTS_IOCR0_OFFSET) -#define XMC4_PORT5_IOCR4 (XMC4_PORT5_BASE+XMC4_PORTS_IOCR4_OFFSET) -#define XMC4_PORT5_IOCR8 (XMC4_PORT5_BASE+XMC4_PORTS_IOCR8_OFFSET) -#define XMC4_PORT5_IOCR12 (XMC4_PORT5_BASE+XMC4_PORTS_IOCR12_OFFSET) -#define XMC4_PORT5_IN (XMC4_PORT5_BASE+XMC4_PORTS_IN_OFFSET) -#define XMC4_PORT5_PDR0 (XMC4_PORT5_BASE+XMC4_PORTS_PDR0_OFFSET) -#define XMC4_PORT5_PDR1 (XMC4_PORT5_BASE+XMC4_PORTS_PDR1_OFFSET) -#define XMC4_PORT5_PDISC (XMC4_PORT5_BASE+XMC4_PORTS_PDISC_OFFSET) -#define XMC4_PORT5_PPS (XMC4_PORT5_BASE+XMC4_PORTS_PPS_OFFSET) -#define XMC4_PORT5_HWSEL (XMC4_PORT5_BASE+XMC4_PORTS_HWSEL_OFFSET) - -#define XMC4_PORT6_OUT (XMC4_PORT6_BASE+XMC4_PORTS_OUT_OFFSET) -#define XMC4_PORT6_OMR (XMC4_PORT6_BASE+XMC4_PORTS_OMR_OFFSET) -#define XMC4_PORT6_IOCR0 (XMC4_PORT6_BASE+XMC4_PORTS_IOCR0_OFFSET) -#define XMC4_PORT6_IOCR4 (XMC4_PORT6_BASE+XMC4_PORTS_IOCR4_OFFSET) -#define XMC4_PORT6_IOCR8 (XMC4_PORT6_BASE+XMC4_PORTS_IOCR8_OFFSET) -#define XMC4_PORT6_IOCR12 (XMC4_PORT6_BASE+XMC4_PORTS_IOCR12_OFFSET) -#define XMC4_PORT6_IN (XMC4_PORT6_BASE+XMC4_PORTS_IN_OFFSET) -#define XMC4_PORT6_PDR0 (XMC4_PORT6_BASE+XMC4_PORTS_PDR0_OFFSET) -#define XMC4_PORT6_PDR1 (XMC4_PORT6_BASE+XMC4_PORTS_PDR1_OFFSET) -#define XMC4_PORT6_PDISC (XMC4_PORT6_BASE+XMC4_PORTS_PDISC_OFFSET) -#define XMC4_PORT6_PPS (XMC4_PORT6_BASE+XMC4_PORTS_PPS_OFFSET) -#define XMC4_PORT6_HWSEL (XMC4_PORT6_BASE+XMC4_PORTS_HWSEL_OFFSET) - -#define XMC4_PORT7_OUT (XMC4_PORT7_BASE+XMC4_PORTS_OUT_OFFSET) -#define XMC4_PORT7_OMR (XMC4_PORT7_BASE+XMC4_PORTS_OMR_OFFSET) -#define XMC4_PORT7_IOCR0 (XMC4_PORT7_BASE+XMC4_PORTS_IOCR0_OFFSET) -#define XMC4_PORT7_IOCR4 (XMC4_PORT7_BASE+XMC4_PORTS_IOCR4_OFFSET) -#define XMC4_PORT7_IOCR8 (XMC4_PORT7_BASE+XMC4_PORTS_IOCR8_OFFSET) -#define XMC4_PORT7_IOCR12 (XMC4_PORT7_BASE+XMC4_PORTS_IOCR12_OFFSET) -#define XMC4_PORT7_IN (XMC4_PORT7_BASE+XMC4_PORTS_IN_OFFSET) -#define XMC4_PORT7_PDR0 (XMC4_PORT7_BASE+XMC4_PORTS_PDR0_OFFSET) -#define XMC4_PORT7_PDR1 (XMC4_PORT7_BASE+XMC4_PORTS_PDR1_OFFSET) -#define XMC4_PORT7_PDISC (XMC4_PORT7_BASE+XMC4_PORTS_PDISC_OFFSET) -#define XMC4_PORT7_PPS (XMC4_PORT7_BASE+XMC4_PORTS_PPS_OFFSET) -#define XMC4_PORT7_HWSEL (XMC4_PORT7_BASE+XMC4_PORTS_HWSEL_OFFSET) - -#define XMC4_PORT8_OUT (XMC4_PORT8_BASE+XMC4_PORTS_OUT_OFFSET) -#define XMC4_PORT8_OMR (XMC4_PORT8_BASE+XMC4_PORTS_OMR_OFFSET) -#define XMC4_PORT8_IOCR0 (XMC4_PORT8_BASE+XMC4_PORTS_IOCR0_OFFSET) -#define XMC4_PORT8_IOCR4 (XMC4_PORT8_BASE+XMC4_PORTS_IOCR4_OFFSET) -#define XMC4_PORT8_IOCR8 (XMC4_PORT8_BASE+XMC4_PORTS_IOCR8_OFFSET) -#define XMC4_PORT8_IOCR12 (XMC4_PORT8_BASE+XMC4_PORTS_IOCR12_OFFSET) -#define XMC4_PORT8_IN (XMC4_PORT8_BASE+XMC4_PORTS_IN_OFFSET) -#define XMC4_PORT8_PDR0 (XMC4_PORT8_BASE+XMC4_PORTS_PDR0_OFFSET) -#define XMC4_PORT8_PDR1 (XMC4_PORT8_BASE+XMC4_PORTS_PDR1_OFFSET) -#define XMC4_PORT8_PDISC (XMC4_PORT8_BASE+XMC4_PORTS_PDISC_OFFSET) -#define XMC4_PORT8_PPS (XMC4_PORT8_BASE+XMC4_PORTS_PPS_OFFSET) -#define XMC4_PORT8_HWSEL (XMC4_PORT8_BASE+XMC4_PORTS_HWSEL_OFFSET) - -#define XMC4_PORT9_OUT (XMC4_PORT9_BASE+XMC4_PORTS_OUT_OFFSET) -#define XMC4_PORT9_OMR (XMC4_PORT9_BASE+XMC4_PORTS_OMR_OFFSET) -#define XMC4_PORT9_IOCR0 (XMC4_PORT9_BASE+XMC4_PORTS_IOCR0_OFFSET) -#define XMC4_PORT9_IOCR4 (XMC4_PORT9_BASE+XMC4_PORTS_IOCR4_OFFSET) -#define XMC4_PORT9_IOCR8 (XMC4_PORT9_BASE+XMC4_PORTS_IOCR8_OFFSET) -#define XMC4_PORT9_IOCR12 (XMC4_PORT9_BASE+XMC4_PORTS_IOCR12_OFFSET) -#define XMC4_PORT9_IN (XMC4_PORT9_BASE+XMC4_PORTS_IN_OFFSET) -#define XMC4_PORT9_PDR0 (XMC4_PORT9_BASE+XMC4_PORTS_PDR0_OFFSET) -#define XMC4_PORT9_PDR1 (XMC4_PORT9_BASE+XMC4_PORTS_PDR1_OFFSET) -#define XMC4_PORT9_PDISC (XMC4_PORT9_BASE+XMC4_PORTS_PDISC_OFFSET) -#define XMC4_PORT9_PPS (XMC4_PORT9_BASE+XMC4_PORTS_PPS_OFFSET) -#define XMC4_PORT9_HWSEL (XMC4_PORT9_BASE+XMC4_PORTS_HWSEL_OFFSET) - -#define XMC4_PORT14_OUT (XMC4_PORT14_BASE+XMC4_PORTS_OUT_OFFSET) -#define XMC4_PORT14_OMR (XMC4_PORT14_BASE+XMC4_PORTS_OMR_OFFSET) -#define XMC4_PORT14_IOCR0 (XMC4_PORT14_BASE+XMC4_PORTS_IOCR0_OFFSET) -#define XMC4_PORT14_IOCR4 (XMC4_PORT14_BASE+XMC4_PORTS_IOCR4_OFFSET) -#define XMC4_PORT14_IOCR8 (XMC4_PORT14_BASE+XMC4_PORTS_IOCR8_OFFSET) -#define XMC4_PORT14_IOCR12 (XMC4_PORT14_BASE+XMC4_PORTS_IOCR12_OFFSET) -#define XMC4_PORT14_IN (XMC4_PORT14_BASE+XMC4_PORTS_IN_OFFSET) -#define XMC4_PORT14_PDR0 (XMC4_PORT14_BASE+XMC4_PORTS_PDR0_OFFSET) -#define XMC4_PORT14_PDR1 (XMC4_PORT14_BASE+XMC4_PORTS_PDR1_OFFSET) -#define XMC4_PORT14_PDISC (XMC4_PORT14_BASE+XMC4_PORTS_PDISC_OFFSET) -#define XMC4_PORT14_PPS (XMC4_PORT14_BASE+XMC4_PORTS_PPS_OFFSET) -#define XMC4_PORT14_HWSEL (XMC4_PORT14_BASE+XMC4_PORTS_HWSEL_OFFSET) - -#define XMC4_PORT15_OUT (XMC4_PORT15_BASE+XMC4_PORTS_OUT_OFFSET) -#define XMC4_PORT15_OMR (XMC4_PORT15_BASE+XMC4_PORTS_OMR_OFFSET) -#define XMC4_PORT15_IOCR0 (XMC4_PORT15_BASE+XMC4_PORTS_IOCR0_OFFSET) -#define XMC4_PORT15_IOCR4 (XMC4_PORT15_BASE+XMC4_PORTS_IOCR4_OFFSET) -#define XMC4_PORT15_IOCR8 (XMC4_PORT15_BASE+XMC4_PORTS_IOCR8_OFFSET) -#define XMC4_PORT15_IOCR12 (XMC4_PORT15_BASE+XMC4_PORTS_IOCR12_OFFSET) -#define XMC4_PORT15_IN (XMC4_PORT15_BASE+XMC4_PORTS_IN_OFFSET) -#define XMC4_PORT15_PDR0 (XMC4_PORT15_BASE+XMC4_PORTS_PDR0_OFFSET) -#define XMC4_PORT15_PDR1 (XMC4_PORT15_BASE+XMC4_PORTS_PDR1_OFFSET) -#define XMC4_PORT15_PDISC (XMC4_PORT15_BASE+XMC4_PORTS_PDISC_OFFSET) -#define XMC4_PORT15_PPS (XMC4_PORT15_BASE+XMC4_PORTS_PPS_OFFSET) -#define XMC4_PORT15_HWSEL (XMC4_PORT15_BASE+XMC4_PORTS_HWSEL_OFFSET) + +#define XMC4_PORT0_OUT (XMC4_PORT0_BASE+XMC4_PORT_OUT_OFFSET) +#define XMC4_PORT0_OMR (XMC4_PORT0_BASE+XMC4_PORT_OMR_OFFSET) +#define XMC4_PORT0_IOCR0 (XMC4_PORT0_BASE+XMC4_PORT_IOCR0_OFFSET) +#define XMC4_PORT0_IOCR4 (XMC4_PORT0_BASE+XMC4_PORT_IOCR4_OFFSET) +#define XMC4_PORT0_IOCR8 (XMC4_PORT0_BASE+XMC4_PORT_IOCR8_OFFSET) +#define XMC4_PORT0_IOCR12 (XMC4_PORT0_BASE+XMC4_PORT_IOCR12_OFFSET) +#define XMC4_PORT0_IN (XMC4_PORT0_BASE+XMC4_PORT_IN_OFFSET) +#define XMC4_PORT0_PDR0 (XMC4_PORT0_BASE+XMC4_PORT_PDR0_OFFSET) +#define XMC4_PORT0_PDR1 (XMC4_PORT0_BASE+XMC4_PORT_PDR1_OFFSET) +#define XMC4_PORT0_PDISC (XMC4_PORT0_BASE+XMC4_PORT_PDISC_OFFSET) +#define XMC4_PORT0_PPS (XMC4_PORT0_BASE+XMC4_PORT_PPS_OFFSET) +#define XMC4_PORT0_HWSEL (XMC4_PORT0_BASE+XMC4_PORT_HWSEL_OFFSET) + +#define XMC4_PORT1_OUT (XMC4_PORT1_BASE+XMC4_PORT_OUT_OFFSET) +#define XMC4_PORT1_OMR (XMC4_PORT1_BASE+XMC4_PORT_OMR_OFFSET) +#define XMC4_PORT1_IOCR0 (XMC4_PORT1_BASE+XMC4_PORT_IOCR0_OFFSET) +#define XMC4_PORT1_IOCR4 (XMC4_PORT1_BASE+XMC4_PORT_IOCR4_OFFSET) +#define XMC4_PORT1_IOCR8 (XMC4_PORT1_BASE+XMC4_PORT_IOCR8_OFFSET) +#define XMC4_PORT1_IOCR12 (XMC4_PORT1_BASE+XMC4_PORT_IOCR12_OFFSET) +#define XMC4_PORT1_IN (XMC4_PORT1_BASE+XMC4_PORT_IN_OFFSET) +#define XMC4_PORT1_PDR0 (XMC4_PORT1_BASE+XMC4_PORT_PDR0_OFFSET) +#define XMC4_PORT1_PDR1 (XMC4_PORT1_BASE+XMC4_PORT_PDR1_OFFSET) +#define XMC4_PORT1_PDISC (XMC4_PORT1_BASE+XMC4_PORT_PDISC_OFFSET) +#define XMC4_PORT1_PPS (XMC4_PORT1_BASE+XMC4_PORT_PPS_OFFSET) +#define XMC4_PORT1_HWSEL (XMC4_PORT1_BASE+XMC4_PORT_HWSEL_OFFSET) + +#define XMC4_PORT2_OUT (XMC4_PORT2_BASE+XMC4_PORT_OUT_OFFSET) +#define XMC4_PORT2_OMR (XMC4_PORT2_BASE+XMC4_PORT_OMR_OFFSET) +#define XMC4_PORT2_IOCR0 (XMC4_PORT2_BASE+XMC4_PORT_IOCR0_OFFSET) +#define XMC4_PORT2_IOCR4 (XMC4_PORT2_BASE+XMC4_PORT_IOCR4_OFFSET) +#define XMC4_PORT2_IOCR8 (XMC4_PORT2_BASE+XMC4_PORT_IOCR8_OFFSET) +#define XMC4_PORT2_IOCR12 (XMC4_PORT2_BASE+XMC4_PORT_IOCR12_OFFSET) +#define XMC4_PORT2_IN (XMC4_PORT2_BASE+XMC4_PORT_IN_OFFSET) +#define XMC4_PORT2_PDR0 (XMC4_PORT2_BASE+XMC4_PORT_PDR0_OFFSET) +#define XMC4_PORT2_PDR1 (XMC4_PORT2_BASE+XMC4_PORT_PDR1_OFFSET) +#define XMC4_PORT2_PDISC (XMC4_PORT2_BASE+XMC4_PORT_PDISC_OFFSET) +#define XMC4_PORT2_PPS (XMC4_PORT2_BASE+XMC4_PORT_PPS_OFFSET) +#define XMC4_PORT2_HWSEL (XMC4_PORT2_BASE+XMC4_PORT_HWSEL_OFFSET) + +#define XMC4_PORT3_OUT (XMC4_PORT3_BASE+XMC4_PORT_OUT_OFFSET) +#define XMC4_PORT3_OMR (XMC4_PORT3_BASE+XMC4_PORT_OMR_OFFSET) +#define XMC4_PORT3_IOCR0 (XMC4_PORT3_BASE+XMC4_PORT_IOCR0_OFFSET) +#define XMC4_PORT3_IOCR4 (XMC4_PORT3_BASE+XMC4_PORT_IOCR4_OFFSET) +#define XMC4_PORT3_IOCR8 (XMC4_PORT3_BASE+XMC4_PORT_IOCR8_OFFSET) +#define XMC4_PORT3_IOCR12 (XMC4_PORT3_BASE+XMC4_PORT_IOCR12_OFFSET) +#define XMC4_PORT3_IN (XMC4_PORT3_BASE+XMC4_PORT_IN_OFFSET) +#define XMC4_PORT3_PDR0 (XMC4_PORT3_BASE+XMC4_PORT_PDR0_OFFSET) +#define XMC4_PORT3_PDR1 (XMC4_PORT3_BASE+XMC4_PORT_PDR1_OFFSET) +#define XMC4_PORT3_PDISC (XMC4_PORT3_BASE+XMC4_PORT_PDISC_OFFSET) +#define XMC4_PORT3_PPS (XMC4_PORT3_BASE+XMC4_PORT_PPS_OFFSET) +#define XMC4_PORT3_HWSEL (XMC4_PORT3_BASE+XMC4_PORT_HWSEL_OFFSET) + +#define XMC4_PORT4_OUT (XMC4_PORT4_BASE+XMC4_PORT_OUT_OFFSET) +#define XMC4_PORT4_OMR (XMC4_PORT4_BASE+XMC4_PORT_OMR_OFFSET) +#define XMC4_PORT4_IOCR0 (XMC4_PORT4_BASE+XMC4_PORT_IOCR0_OFFSET) +#define XMC4_PORT4_IOCR4 (XMC4_PORT4_BASE+XMC4_PORT_IOCR4_OFFSET) +#define XMC4_PORT4_IOCR8 (XMC4_PORT4_BASE+XMC4_PORT_IOCR8_OFFSET) +#define XMC4_PORT4_IOCR12 (XMC4_PORT4_BASE+XMC4_PORT_IOCR12_OFFSET) +#define XMC4_PORT4_IN (XMC4_PORT4_BASE+XMC4_PORT_IN_OFFSET) +#define XMC4_PORT4_PDR0 (XMC4_PORT4_BASE+XMC4_PORT_PDR0_OFFSET) +#define XMC4_PORT4_PDR1 (XMC4_PORT4_BASE+XMC4_PORT_PDR1_OFFSET) +#define XMC4_PORT4_PDISC (XMC4_PORT4_BASE+XMC4_PORT_PDISC_OFFSET) +#define XMC4_PORT4_PPS (XMC4_PORT4_BASE+XMC4_PORT_PPS_OFFSET) +#define XMC4_PORT4_HWSEL (XMC4_PORT4_BASE+XMC4_PORT_HWSEL_OFFSET) + +#define XMC4_PORT5_OUT (XMC4_PORT5_BASE+XMC4_PORT_OUT_OFFSET) +#define XMC4_PORT5_OMR (XMC4_PORT5_BASE+XMC4_PORT_OMR_OFFSET) +#define XMC4_PORT5_IOCR0 (XMC4_PORT5_BASE+XMC4_PORT_IOCR0_OFFSET) +#define XMC4_PORT5_IOCR4 (XMC4_PORT5_BASE+XMC4_PORT_IOCR4_OFFSET) +#define XMC4_PORT5_IOCR8 (XMC4_PORT5_BASE+XMC4_PORT_IOCR8_OFFSET) +#define XMC4_PORT5_IOCR12 (XMC4_PORT5_BASE+XMC4_PORT_IOCR12_OFFSET) +#define XMC4_PORT5_IN (XMC4_PORT5_BASE+XMC4_PORT_IN_OFFSET) +#define XMC4_PORT5_PDR0 (XMC4_PORT5_BASE+XMC4_PORT_PDR0_OFFSET) +#define XMC4_PORT5_PDR1 (XMC4_PORT5_BASE+XMC4_PORT_PDR1_OFFSET) +#define XMC4_PORT5_PDISC (XMC4_PORT5_BASE+XMC4_PORT_PDISC_OFFSET) +#define XMC4_PORT5_PPS (XMC4_PORT5_BASE+XMC4_PORT_PPS_OFFSET) +#define XMC4_PORT5_HWSEL (XMC4_PORT5_BASE+XMC4_PORT_HWSEL_OFFSET) + +#define XMC4_PORT6_OUT (XMC4_PORT6_BASE+XMC4_PORT_OUT_OFFSET) +#define XMC4_PORT6_OMR (XMC4_PORT6_BASE+XMC4_PORT_OMR_OFFSET) +#define XMC4_PORT6_IOCR0 (XMC4_PORT6_BASE+XMC4_PORT_IOCR0_OFFSET) +#define XMC4_PORT6_IOCR4 (XMC4_PORT6_BASE+XMC4_PORT_IOCR4_OFFSET) +#define XMC4_PORT6_IOCR8 (XMC4_PORT6_BASE+XMC4_PORT_IOCR8_OFFSET) +#define XMC4_PORT6_IOCR12 (XMC4_PORT6_BASE+XMC4_PORT_IOCR12_OFFSET) +#define XMC4_PORT6_IN (XMC4_PORT6_BASE+XMC4_PORT_IN_OFFSET) +#define XMC4_PORT6_PDR0 (XMC4_PORT6_BASE+XMC4_PORT_PDR0_OFFSET) +#define XMC4_PORT6_PDR1 (XMC4_PORT6_BASE+XMC4_PORT_PDR1_OFFSET) +#define XMC4_PORT6_PDISC (XMC4_PORT6_BASE+XMC4_PORT_PDISC_OFFSET) +#define XMC4_PORT6_PPS (XMC4_PORT6_BASE+XMC4_PORT_PPS_OFFSET) +#define XMC4_PORT6_HWSEL (XMC4_PORT6_BASE+XMC4_PORT_HWSEL_OFFSET) + +#define XMC4_PORT7_OUT (XMC4_PORT7_BASE+XMC4_PORT_OUT_OFFSET) +#define XMC4_PORT7_OMR (XMC4_PORT7_BASE+XMC4_PORT_OMR_OFFSET) +#define XMC4_PORT7_IOCR0 (XMC4_PORT7_BASE+XMC4_PORT_IOCR0_OFFSET) +#define XMC4_PORT7_IOCR4 (XMC4_PORT7_BASE+XMC4_PORT_IOCR4_OFFSET) +#define XMC4_PORT7_IOCR8 (XMC4_PORT7_BASE+XMC4_PORT_IOCR8_OFFSET) +#define XMC4_PORT7_IOCR12 (XMC4_PORT7_BASE+XMC4_PORT_IOCR12_OFFSET) +#define XMC4_PORT7_IN (XMC4_PORT7_BASE+XMC4_PORT_IN_OFFSET) +#define XMC4_PORT7_PDR0 (XMC4_PORT7_BASE+XMC4_PORT_PDR0_OFFSET) +#define XMC4_PORT7_PDR1 (XMC4_PORT7_BASE+XMC4_PORT_PDR1_OFFSET) +#define XMC4_PORT7_PDISC (XMC4_PORT7_BASE+XMC4_PORT_PDISC_OFFSET) +#define XMC4_PORT7_PPS (XMC4_PORT7_BASE+XMC4_PORT_PPS_OFFSET) +#define XMC4_PORT7_HWSEL (XMC4_PORT7_BASE+XMC4_PORT_HWSEL_OFFSET) + +#define XMC4_PORT8_OUT (XMC4_PORT8_BASE+XMC4_PORT_OUT_OFFSET) +#define XMC4_PORT8_OMR (XMC4_PORT8_BASE+XMC4_PORT_OMR_OFFSET) +#define XMC4_PORT8_IOCR0 (XMC4_PORT8_BASE+XMC4_PORT_IOCR0_OFFSET) +#define XMC4_PORT8_IOCR4 (XMC4_PORT8_BASE+XMC4_PORT_IOCR4_OFFSET) +#define XMC4_PORT8_IOCR8 (XMC4_PORT8_BASE+XMC4_PORT_IOCR8_OFFSET) +#define XMC4_PORT8_IOCR12 (XMC4_PORT8_BASE+XMC4_PORT_IOCR12_OFFSET) +#define XMC4_PORT8_IN (XMC4_PORT8_BASE+XMC4_PORT_IN_OFFSET) +#define XMC4_PORT8_PDR0 (XMC4_PORT8_BASE+XMC4_PORT_PDR0_OFFSET) +#define XMC4_PORT8_PDR1 (XMC4_PORT8_BASE+XMC4_PORT_PDR1_OFFSET) +#define XMC4_PORT8_PDISC (XMC4_PORT8_BASE+XMC4_PORT_PDISC_OFFSET) +#define XMC4_PORT8_PPS (XMC4_PORT8_BASE+XMC4_PORT_PPS_OFFSET) +#define XMC4_PORT8_HWSEL (XMC4_PORT8_BASE+XMC4_PORT_HWSEL_OFFSET) + +#define XMC4_PORT9_OUT (XMC4_PORT9_BASE+XMC4_PORT_OUT_OFFSET) +#define XMC4_PORT9_OMR (XMC4_PORT9_BASE+XMC4_PORT_OMR_OFFSET) +#define XMC4_PORT9_IOCR0 (XMC4_PORT9_BASE+XMC4_PORT_IOCR0_OFFSET) +#define XMC4_PORT9_IOCR4 (XMC4_PORT9_BASE+XMC4_PORT_IOCR4_OFFSET) +#define XMC4_PORT9_IOCR8 (XMC4_PORT9_BASE+XMC4_PORT_IOCR8_OFFSET) +#define XMC4_PORT9_IOCR12 (XMC4_PORT9_BASE+XMC4_PORT_IOCR12_OFFSET) +#define XMC4_PORT9_IN (XMC4_PORT9_BASE+XMC4_PORT_IN_OFFSET) +#define XMC4_PORT9_PDR0 (XMC4_PORT9_BASE+XMC4_PORT_PDR0_OFFSET) +#define XMC4_PORT9_PDR1 (XMC4_PORT9_BASE+XMC4_PORT_PDR1_OFFSET) +#define XMC4_PORT9_PDISC (XMC4_PORT9_BASE+XMC4_PORT_PDISC_OFFSET) +#define XMC4_PORT9_PPS (XMC4_PORT9_BASE+XMC4_PORT_PPS_OFFSET) +#define XMC4_PORT9_HWSEL (XMC4_PORT9_BASE+XMC4_PORT_HWSEL_OFFSET) + +#define XMC4_PORT14_OUT (XMC4_PORT14_BASE+XMC4_PORT_OUT_OFFSET) +#define XMC4_PORT14_OMR (XMC4_PORT14_BASE+XMC4_PORT_OMR_OFFSET) +#define XMC4_PORT14_IOCR0 (XMC4_PORT14_BASE+XMC4_PORT_IOCR0_OFFSET) +#define XMC4_PORT14_IOCR4 (XMC4_PORT14_BASE+XMC4_PORT_IOCR4_OFFSET) +#define XMC4_PORT14_IOCR8 (XMC4_PORT14_BASE+XMC4_PORT_IOCR8_OFFSET) +#define XMC4_PORT14_IOCR12 (XMC4_PORT14_BASE+XMC4_PORT_IOCR12_OFFSET) +#define XMC4_PORT14_IN (XMC4_PORT14_BASE+XMC4_PORT_IN_OFFSET) +#define XMC4_PORT14_PDR0 (XMC4_PORT14_BASE+XMC4_PORT_PDR0_OFFSET) +#define XMC4_PORT14_PDR1 (XMC4_PORT14_BASE+XMC4_PORT_PDR1_OFFSET) +#define XMC4_PORT14_PDISC (XMC4_PORT14_BASE+XMC4_PORT_PDISC_OFFSET) +#define XMC4_PORT14_PPS (XMC4_PORT14_BASE+XMC4_PORT_PPS_OFFSET) +#define XMC4_PORT14_HWSEL (XMC4_PORT14_BASE+XMC4_PORT_HWSEL_OFFSET) + +#define XMC4_PORT15_OUT (XMC4_PORT15_BASE+XMC4_PORT_OUT_OFFSET) +#define XMC4_PORT15_OMR (XMC4_PORT15_BASE+XMC4_PORT_OMR_OFFSET) +#define XMC4_PORT15_IOCR0 (XMC4_PORT15_BASE+XMC4_PORT_IOCR0_OFFSET) +#define XMC4_PORT15_IOCR4 (XMC4_PORT15_BASE+XMC4_PORT_IOCR4_OFFSET) +#define XMC4_PORT15_IOCR8 (XMC4_PORT15_BASE+XMC4_PORT_IOCR8_OFFSET) +#define XMC4_PORT15_IOCR12 (XMC4_PORT15_BASE+XMC4_PORT_IOCR12_OFFSET) +#define XMC4_PORT15_IN (XMC4_PORT15_BASE+XMC4_PORT_IN_OFFSET) +#define XMC4_PORT15_PDR0 (XMC4_PORT15_BASE+XMC4_PORT_PDR0_OFFSET) +#define XMC4_PORT15_PDR1 (XMC4_PORT15_BASE+XMC4_PORT_PDR1_OFFSET) +#define XMC4_PORT15_PDISC (XMC4_PORT15_BASE+XMC4_PORT_PDISC_OFFSET) +#define XMC4_PORT15_PPS (XMC4_PORT15_BASE+XMC4_PORT_PPS_OFFSET) +#define XMC4_PORT15_HWSEL (XMC4_PORT15_BASE+XMC4_PORT_HWSEL_OFFSET) /* Register Bit-Field Definitions **************************************************/ -/* Port Output Register */ -#define PORTS_OUT_ -/* Port Output Modification Register */ -#define PORTS_OMR_ +/* Port Output Register, Port Output Modification Register, Port Input Register, + * Port Pin Function Decision Control Register, Port Pin Power Save Register. + */ + +#define PORT_PIN(n) (1 << (n)) + +/* Basic port input/output field values */ +/* Director Input */ + +#define IOCR_NOPULL 0 /* No internal pull device active */ +#define IOCR_PULLDOWN 1 /* Internal pull-down device active */ +#define IOCR_PULLUP 2 /* Internal pull-down device active */ +#define IOCR_CONT 3 /* No internal pull device active; Pn_OUTx continuously + * samples the input value */ + +/* Any of the above may be OR'ed with */ +/* Inverted Input */ + +#define IOCR_INVERT 4 /* Inverted input */ + /* Port Input/Output Control Register 0 */ -#define PORTS_IOCR0_ + +#define PORT_IOCR0_PC_SHIFT(p) (((p) << 3) + 3) +#define PORT_IOCR0_PC_MASK(p) (31 << PORT_IOCR0_PC_SHIFT(p)) +# define PORT_IOCR0_PC(p,n) ((uint32_t)(n) << PORT_IOCR0_PC_SHIFT(p)) +#define PORT_IOCR0_PC0_SHIFT (3) /* Bit 3-7: Port Control for Port n Pin 0 */ +#define PORT_IOCR0_PC0_MASK (31 << PORT_IOCR0_PC0_SHIFT) +# define PORT_IOCR0_PC0(n) ((uint32_t)(n) << PORT_IOCR0_PC0_SHIFT) +#define PORT_IOCR0_PC1_SHIFT (11) /* Bit 11-15: Port Control for Port n Pin 1 */ +#define PORT_IOCR0_PC1_MASK (31 << PORT_IOCR0_PC1_SHIFT) +# define PORT_IOCR0_PC1(n) ((uint32_t)(n) << PORT_IOCR0_PC1_SHIFT) +#define PORT_IOCR0_PC2_SHIFT (19) /* Bit 19-23: Port Control for Port n Pin 2 */ +#define PORT_IOCR0_PC2_MASK (31 << PORT_IOCR0_PC2_SHIFT) +# define PORT_IOCR0_PC2(n) ((uint32_t)(n) << PORT_IOCR0_PC2_SHIFT) +#define PORT_IOCR0_PC3_SHIFT (27) /* Bit 27-31: Port Control for Port 0 Pin 3 */ +#define PORT_IOCR0_PC3_MASK (31 << PORT_IOCR0_PC3_SHIFT) +# define PORT_IOCR0_PC3(n) ((uint32_t)(n) << PORT_IOCR0_PC3_SHIFT) + /* Port Input/Output Control Register 4 */ -#define PORTS_IOCR4_ + +#define PORT_IOCR4_PC_SHIFT(p) ((((p) - 4) << 3) + 3) +#define PORT_IOCR4_PC_MASK(p) (31 << PORT_IOCR4_PC_SHIFT(p)) +# define PORT_IOCR4_PC(p,n) ((uint32_t)(n) << PORT_IOCR4_PC_SHIFT(p)) +#define PORT_IOCR4_PC4_SHIFT (3) /* Bit 3-7: Port Control for Port n Pin 4 */ +#define PORT_IOCR4_PC4_MASK (31 << PORT_IOCR4_PC4_SHIFT) +# define PORT_IOCR4_PC4(n) ((uint32_t)(n) << PORT_IOCR4_PC4_SHIFT) +#define PORT_IOCR4_PC5_SHIFT (11) /* Bit 11-15: Port Control for Port n Pin 5 */ +#define PORT_IOCR4_PC5_MASK (31 << PORT_IOCR4_PC5_SHIFT) +# define PORT_IOCR4_PC5(n) ((uint32_t)(n) << PORT_IOCR4_PC5_SHIFT) +#define PORT_IOCR4_PC6_SHIFT (19) /* Bit 19-23: Port Control for Port n Pin 6 */ +#define PORT_IOCR4_PC6_MASK (31 << PORT_IOCR4_PC6_SHIFT) +# define PORT_IOCR4_PC6(n) ((uint32_t)(n) << PORT_IOCR4_PC6_SHIFT) +#define PORT_IOCR4_PC7_SHIFT (27) /* Bit 27-31: Port Control for Port 0 Pin 7 */ +#define PORT_IOCR4_PC7_MASK (31 << PORT_IOCR4_PC7_SHIFT) +# define PORT_IOCR4_PC7(n) ((uint32_t)(n) << PORT_IOCR4_PC7_SHIFT) + /* Port Input/Output Control Register 8 */ -#define PORTS_IOCR8_ + +#define PORT_IOCR8_PC_SHIFT(p) ((((p) - 8) << 3) + 3) +#define PORT_IOCR8_PC_MASK(p) (31 << PORT_IOCR8_PC_SHIFT(p)) +# define PORT_IOCR8_PC(p,n) ((uint32_t)(n) << PORT_IOCR8_PC_SHIFT(p)) +#define PORT_IOCR8_PC8_SHIFT (3) /* Bit 3-7: Port Control for Port n Pin 8 */ +#define PORT_IOCR8_PC8_MASK (31 << PORT_IOCR8_PC8_SHIFT) +# define PORT_IOCR8_PC8(n) ((uint32_t)(n) << PORT_IOCR8_PC8_SHIFT) +#define PORT_IOCR8_PC9_SHIFT (11) /* Bit 11-15: Port Control for Port n Pin 9 */ +#define PORT_IOCR8_PC9_MASK (31 << PORT_IOCR8_PC9_SHIFT) +# define PORT_IOCR8_PC9(n) ((uint32_t)(n) << PORT_IOCR8_PC9_SHIFT) +#define PORT_IOCR8_PC10_SHIFT (19) /* Bit 19-23: Port Control for Port n Pin 10 */ +#define PORT_IOCR8_PC10_MASK (31 << PORT_IOCR8_PC10_SHIFT) +# define PORT_IOCR8_PC10(n) ((uint32_t)(n) << PORT_IOCR8_PC10_SHIFT) +#define PORT_IOCR8_PC11_SHIFT (27) /* Bit 17-31: Port Control for Port 0 Pin 11 */ +#define PORT_IOCR8_PC11_MASK (31 << PORT_IOCR8_PC11_SHIFT) +# define PORT_IOCR8_PC11(n) ((uint32_t)(n) << PORT_IOCR8_PC11_SHIFT) + /* Port Input/Output Control Register 12 */ -#define PORTS_IOCR12_ -/* Port Input Register */ -#define PORTS_IN_ + +#define PORT_IOCR12_PC_SHIFT(p) ((((p) - 12) << 3) + 3) +#define PORT_IOCR12_PC_MASK(p) (31 << PORT_IOCR12_PC_SHIFT(p)) +# define PORT_IOCR12_PC(p,n) ((uint32_t)(n) << PORT_IOCR12_PC_SHIFT(p)) +#define PORT_IOCR12_PC12_SHIFT (3) /* Bit 3-7: Port Control for Port n Pin 12 */ +#define PORT_IOCR12_PC12_MASK (31 << PORT_IOCR12_PC12_SHIFT) +# define PORT_IOCR12_PC12(n) ((uint32_t)(n) << PORT_IOCR12_PC12_SHIFT) +#define PORT_IOCR12_PC13_SHIFT (11) /* Bit 3-7: Port Control for Port n Pin 13 */ +#define PORT_IOCR12_PC13_MASK (31 << PORT_IOCR12_PC13_SHIFT) +# define PORT_IOCR12_PC13(n) ((uint32_t)(n) << PORT_IOCR12_PC13_SHIFT) +#define PORT_IOCR12_PC14_SHIFT (19) /* Bit 3-7: Port Control for Port n Pin 14 */ +#define PORT_IOCR12_PC14_MASK (31 << PORT_IOCR12_PC14_SHIFT) +# define PORT_IOCR12_PC14(n) ((uint32_t)(n) << PORT_IOCR12_PC14_SHIFT) +#define PORT_IOCR12_PC15_SHIFT (27) /* Bit 3-7: Port Control for Port 0 Pin 15 */ +#define PORT_IOCR12_PC15_MASK (31 << PORT_IOCR12_PC15_SHIFT) +# define PORT_IOCR12_PC15(n) ((uint32_t)(n) << PORT_IOCR12_PC15_SHIFT) + +/* Pad driver field values */ +/* Pad class A1: */ + +#define PDR_PADA1_MEDIUM 0 /* Medium driver */ +#define PDR_PADA1_WEAK 1 /* Weak driver */ + +/* Pad class A1+: */ + +#define PDR_PADA1P_STRONGSOFT 0 /* Strong driver soft edge */ +#define PDR_PADA1P_STRONGSLOW 1 /* Strong driver slow edge */ +#define PDR_PADA1P_MEDIUM 4 /* Medium driver */ +#define PDR_PADA1P_WEAK 5 /* Weak driver */ + +/* Pad class A2: */ + +#define PDR_PADA2_STRONGSHARP 0 /* Strong driver sharp edge */ +#define PDR_PADA2_STRONGMEDIUM 1 /* Strong driver medium edge */ +#define PDR_PADA2_STRONGSOFT 2 /* Strong driver soft edge */ +#define PDR_PADA2_MEDIUM 4 /* Medium driver */ +#define PDR_PADA2_WEAK 7 /* Weak driver */ + /* Port Pad Driver Mode 0 Register */ -#define PORTS_PDR0_ + +#define PORT_PDR0_PD_SHIFT(p) ((p) << 2) +#define PORT_PDR0_PD_MASK(p) (7 << PORT_PDR0_PD_SHIFT(p)) +# define PORT_PDR0_PD(p,n) ((uint32_t)(n) << PORT_PDR0_PD_SHIFT(p)) +#define PORT_PDR0_PD0_SHIFT (0) /* Bit 0-2: Pad Driver Mode for Port n Pin 0 */ +#define PORT_PDR0_PD0_MASK (7 << PORT_PDR0_PD0_SHIFT) +# define PORT_PDR0_PD0(n) ((uint32_t)(n) << PORT_PDR0_PD0_SHIFT) +#define PORT_PDR0_PD1_SHIFT (4) /* Bit 4-6: Pad Driver Mode for Port n Pin 1 */ +#define PORT_PDR0_PD1_MASK (7 << PORT_PDR0_PD1_SHIFT) +# define PORT_PDR0_PD1(n) ((uint32_t)(n) << PORT_PDR0_PD1_SHIFT) +#define PORT_PDR0_PD2_SHIFT (8) /* Bit 8-10: Pad Driver Mode for Port n Pin 2 */ +#define PORT_PDR0_PD2_MASK (7 << PORT_PDR0_PD2_SHIFT) +# define PORT_PDR0_PD2(n) ((uint32_t)(n) << PORT_PDR0_PD2_SHIFT) +#define PORT_PDR0_PD3_SHIFT (12) /* Bit 12-14: Pad Driver Mode for Port 0 Pin 3 */ +#define PORT_PDR0_PD3_MASK (7 << PORT_PDR0_PD3_SHIFT) +# define PORT_PDR0_PD3(n) ((uint32_t)(n) << PORT_PDR0_PD3_SHIFT) +#define PORT_PDR0_PD4_SHIFT (16) /* Bit 16-18: Pad Driver Mode for Port 0 Pin 4 */ +#define PORT_PDR0_PD4_MASK (7 << PORT_PDR0_PD4_SHIFT) +# define PORT_PDR0_PD4(n) ((uint32_t)(n) << PORT_PDR0_PD4_SHIFT) +#define PORT_PDR0_PD5_SHIFT (20) /* Bit 20-22: Pad Driver Mode for Port 0 Pin 5 */ +#define PORT_PDR0_PD5_MASK (7 << PORT_PDR0_PD5_SHIFT) +# define PORT_PDR0_PD5(n) ((uint32_t)(n) << PORT_PDR0_PD5_SHIFT) +#define PORT_PDR0_PD6_SHIFT (24) /* Bit 24-26: Pad Driver Mode for Port 0 Pin 6 */ +#define PORT_PDR0_PD6_MASK (7 << PORT_PDR0_PD6_SHIFT) +# define PORT_PDR0_PD6(n) ((uint32_t)(n) << PORT_PDR0_PD6_SHIFT) +#define PORT_PDR0_PD7_SHIFT (28) /* Bit 28-30: Pad Driver Mode for Port 0 Pin 7 */ +#define PORT_PDR0_PD7_MASK (7 << PORT_PDR0_PD7_SHIFT) +# define PORT_PDR0_PD7(n) ((uint32_t)(n) << PORT_PDR0_PD7_SHIFT) + /* Port Pad Driver Mode 1 Register */ -#define PORTS_PDR1_ -/* Port Pin Function Decision Control Register */ -#define PORTS_PDISC_ -/* Port Pin Power Save Register */ -#define PORTS_PPS_ + +#define PORT_PDR1_PD_SHIFT(p) (((p) - 8) << 2) +#define PORT_PDR1_PD_MASK(p) (7 << PORT_PDR1_PD_SHIFT(p)) +# define PORT_PDR1_PD(p,n) ((uint32_t)(n) << PORT_PDR1_PD_SHIFT(p)) +#define PORT_PDR1_PD8_SHIFT (0) /* Bit 0-2: Pad Driver Mode for Port n Pin 8 */ +#define PORT_PDR1_PD8_MASK (7 << PORT_PDR1_PD8_SHIFT) +# define PORT_PDR1_PD8(n) ((uint32_t)(n) << PORT_PDR1_PD8_SHIFT) +#define PORT_PDR1_PD9_SHIFT (4) /* Bit 4-6: Pad Driver Mode for Port n Pin 9 */ +#define PORT_PDR1_PD9_MASK (7 << PORT_PDR1_PD9_SHIFT) +# define PORT_PDR1_PD9(n) ((uint32_t)(n) << PORT_PDR1_PD9_SHIFT) +#define PORT_PDR1_PD10_SHIFT (8) /* Bit 8-10: Pad Driver Mode for Port n Pin 10 */ +#define PORT_PDR1_PD10_MASK (7 << PORT_PDR1_PD10_SHIFT) +# define PORT_PDR1_PD10(n) ((uint32_t)(n) << PORT_PDR1_PD10_SHIFT) +#define PORT_PDR1_PD11_SHIFT (12) /* Bit 12-14: Pad Driver Mode for Port 0 Pin 11 */ +#define PORT_PDR1_PD11_MASK (7 << PORT_PDR1_PD11_SHIFT) +# define PORT_PDR1_PD11(n) ((uint32_t)(n) << PORT_PDR1_PD11_SHIFT) +#define PORT_PDR1_PD12_SHIFT (16) /* Bit 16-18: Pad Driver Mode for Port 0 Pin 12 */ +#define PORT_PDR1_PD12_MASK (7 << PORT_PDR1_PD12_SHIFT) +# define PORT_PDR1_PD12(n) ((uint32_t)(n) << PORT_PDR1_PD12_SHIFT) +#define PORT_PDR1_PD13_SHIFT (20) /* Bit 20-22: Pad Driver Mode for Port 0 Pin 13 */ +#define PORT_PDR1_PD13_MASK (7 << PORT_PDR1_PD13_SHIFT) +# define PORT_PDR1_PD13(n) ((uint32_t)(n) << PORT_PDR1_PD13_SHIFT) +#define PORT_PDR1_PD14_SHIFT (24) /* Bit 24-26: Pad Driver Mode for Port 0 Pin 14 */ +#define PORT_PDR1_PD14_MASK (7 << PORT_PDR1_PD14_SHIFT) +# define PORT_PDR1_PD14(n) ((uint32_t)(n) << PORT_PDR1_PD14_SHIFT) +#define PORT_PDR1_PD15_SHIFT (28) /* Bit 28-30: Pad Driver Mode for Port 0 Pin 15 */ +#define PORT_PDR1_PD15_MASK (7 << PORT_PDR1_PD15_SHIFT) +# define PORT_PDR1_PD15(n) ((uint32_t)(n) << PORT_PDR1_PD15_SHIFT) + +/* Hardware select field values */ + +#define HWSEL_SOFTWARE 0 /* Software control only */ +#define HWSEL_OVERRIDE0 1 /* HWI0/HWO0 control path can override the + * software configuration */ +#define HWSEL_OVERRIDE1 2 /* HWI1/HWO1 control path can override the + * software configuration */ + /* Port Pin Hardware Select Register */ -#define PORTS_HWSEL_ + +#define PORT_HWSEL_HW_SHIFT(p) ((p) << 1) +#define PORT_HWSEL_HW_MASK(p) (3 << PORT_HWSEL_HW_SHIFT(p)) +# define PORT_HWSEL_HW(p,n) ((uint32_t)(n) << PORT_HWSEL_HW_SHIFT(p)) +#define PORT_HWSEL_HW0_SHIFT (0) /* Bit 0-1: Port n Pin 0 Hardware Select */ +#define PORT_HWSEL_HW0_MASK (3 << PORT_HWSEL_HW0_SHIFT) +# define PORT_HWSEL_HW0(n) ((uint32_t)(n) << PORT_HWSEL_HW0_SHIFT) +#define PORT_HWSEL_HW1_SHIFT (2) /* Bit 2-3: Port n Pin 1 Hardware Select */ +#define PORT_HWSEL_HW1_MASK (3 << PORT_HWSEL_HW1_SHIFT) +# define PORT_HWSEL_HW1(n) ((uint32_t)(n) << PORT_HWSEL_HW1_SHIFT) +#define PORT_HWSEL_HW2_SHIFT (4) /* Bit 4-5: Port n Pin 2 Hardware Select */ +#define PORT_HWSEL_HW2_MASK (3 << PORT_HWSEL_HW2_SHIFT) +# define PORT_HWSEL_HW2(n) ((uint32_t)(n) << PORT_HWSEL_HW2_SHIFT) +#define PORT_HWSEL_HW3_SHIFT (6) /* Bit 6-7: Port 0 Pin 3 Hardware Select */ +#define PORT_HWSEL_HW3_MASK (3 << PORT_HWSEL_HW3_SHIFT) +# define PORT_HWSEL_HW3(n) ((uint32_t)(n) << PORT_HWSEL_HW3_SHIFT) +#define PORT_HWSEL_HW4_SHIFT (8) /* Bit 8-9: Port 0 Pin 4 Hardware Select */ +#define PORT_HWSEL_HW4_MASK (3 << PORT_HWSEL_HW4_SHIFT) +# define PORT_HWSEL_HW4(n) ((uint32_t)(n) << PORT_HWSEL_HW4_SHIFT) +#define PORT_HWSEL_HW5_SHIFT (10) /* Bit 10-11: Port 0 Pin 5 Hardware Select */ +#define PORT_HWSEL_HW5_MASK (3 << PORT_HWSEL_HW5_SHIFT) +# define PORT_HWSEL_HW5(n) ((uint32_t)(n) << PORT_HWSEL_HW5_SHIFT) +#define PORT_HWSEL_HW6_SHIFT (12) /* Bit 12-13: Port 0 Pin 6 Hardware Select */ +#define PORT_HWSEL_HW6_MASK (3 << PORT_HWSEL_HW6_SHIFT) +# define PORT_HWSEL_HW6(n) 14uint32_t)(n) << PORT_HWSEL_HW6_SHIFT) +#define PORT_HWSEL_HW7_SHIFT (14) /* Bit 14-15: Port 0 Pin 7 Hardware Select */ +#define PORT_HWSEL_HW7_MASK (3 << PORT_HWSEL_HW7_SHIFT) +# define PORT_HWSEL_HW7(n) ((uint32_t)(n) << PORT_HWSEL_HW7_SHIFT) +#define PORT_HWSEL_HW8_SHIFT (16) /* Bit 16-17: Port n Pin 8 Hardware Select */ +#define PORT_HWSEL_HW8_MASK (3 << PORT_HWSEL_HW8_SHIFT) +# define PORT_HWSEL_HW8(n) ((uint32_t)(n) << PORT_HWSEL_HW8_SHIFT) +#define PORT_HWSEL_HW9_SHIFT (18) /* Bit 18-19: Port n Pin 9 Hardware Select */ +#define PORT_HWSEL_HW9_MASK (3 << PORT_HWSEL_HW9_SHIFT) +# define PORT_HWSEL_HW9(n) ((uint32_t)(n) << PORT_HWSEL_HW9_SHIFT) +#define PORT_HWSEL_HW10_SHIFT (20) /* Bit 20-21: Port n Pin 10 Hardware Select */ +#define PORT_HWSEL_HW10_MASK (3 << PORT_HWSEL_HW10_SHIFT) +# define PORT_HWSEL_HW10(n) ((uint32_t)(n) << PORT_HWSEL_HW10_SHIFT) +#define PORT_HWSEL_HW11_SHIFT (22) /* Bit 22-23: Port 0 Pin 11 Hardware Select */ +#define PORT_HWSEL_HW11_MASK (3 << PORT_HWSEL_HW11_SHIFT) +# define PORT_HWSEL_HW11(n) ((uint32_t)(n) << PORT_HWSEL_HW11_SHIFT) +#define PORT_HWSEL_HW12_SHIFT (24) /* Bit 24-25: Port 0 Pin 12 Hardware Select */ +#define PORT_HWSEL_HW12_MASK (3 << PORT_HWSEL_HW12_SHIFT) +# define PORT_HWSEL_HW12(n) ((uint32_t)(n) << PORT_HWSEL_HW12_SHIFT) +#define PORT_HWSEL_HW13_SHIFT (26) /* Bit 26-27: Port 0 Pin 13 Hardware Select */ +#define PORT_HWSEL_HW13_MASK (3 << PORT_HWSEL_HW13_SHIFT) +# define PORT_HWSEL_HW13(n) ((uint32_t)(n) << PORT_HWSEL_HW13_SHIFT) +#define PORT_HWSEL_HW14_SHIFT (28) /* Bit 28-29: Port 0 Pin 14 Hardware Select */ +#define PORT_HWSEL_HW14_MASK (3 << PORT_HWSEL_HW14_SHIFT) +# define PORT_HWSEL_HW14(n) 14uint32_t)(n) << PORT_HWSEL_HW14_SHIFT) +#define PORT_HWSEL_HW15_SHIFT (30) /* Bit 30-31: Port 0 Pin 15 Hardware Select */ +#define PORT_HWSEL_HW15_MASK (3 << PORT_HWSEL_HW15_SHIFT) +# define PORT_HWSEL_HW15(n) ((uint32_t)(n) << PORT_HWSEL_HW15_SHIFT) #endif /* __ARCH_ARM_SRC_XMC4_CHIP_XMC4_SCU_H */ -- GitLab From 8f91c73304e5236a90f760373f23637aad378f8a Mon Sep 17 00:00:00 2001 From: Pascal Speck Date: Fri, 17 Mar 2017 15:13:03 +0100 Subject: [PATCH 077/990] - fixed wrong assert on udp dgram send --- net/udp/udp_psock_send.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/net/udp/udp_psock_send.c b/net/udp/udp_psock_send.c index e3e2eb0c88..c701fe064d 100644 --- a/net/udp/udp_psock_send.c +++ b/net/udp/udp_psock_send.c @@ -78,7 +78,7 @@ ssize_t psock_udp_send(FAR struct socket *psock, FAR const void *buf, socklen_t tolen; DEBUGASSERT(psock != NULL && psock->s_crefs > 0); - DEBUGASSERT(psock->s_type != SOCK_DGRAM); + DEBUGASSERT(psock->s_type == SOCK_DGRAM); conn = (FAR struct udp_conn_s *)psock->s_conn; DEBUGASSERT(conn); -- GitLab From 042b33414abe8950d7dd7223490846681b46957c Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 17 Mar 2017 08:28:40 -0600 Subject: [PATCH 078/990] XMC4xxx: Missing OMR field in PORT register definition header file. --- arch/arm/src/xmc4/chip/xmc4_ports.h | 28 ++++++++++++++++++++-------- 1 file changed, 20 insertions(+), 8 deletions(-) diff --git a/arch/arm/src/xmc4/chip/xmc4_ports.h b/arch/arm/src/xmc4/chip/xmc4_ports.h index 1d6cfa6b42..1465c41a64 100644 --- a/arch/arm/src/xmc4/chip/xmc4_ports.h +++ b/arch/arm/src/xmc4/chip/xmc4_ports.h @@ -239,25 +239,37 @@ /* Register Bit-Field Definitions **************************************************/ -/* Port Output Register, Port Output Modification Register, Port Input Register, - * Port Pin Function Decision Control Register, Port Pin Power Save Register. +/* Port Output Register, , Port Input Register, Port Pin Function Decision Control + * Register, Port Pin Power Save Register. */ #define PORT_PIN(n) (1 << (n)) +/* Port Output Modification Register: + * + * PRx PSx Function + * 0 0 Bit Pn_OUT.Px is not changed. + * 0 1 Bit Pn_OUT.Px is set. + * 1 0 Bit Pn_OUT.Px is reset. + * 1 1 Bit Pn_OUT.Px is toggled. + */ + +#define OMR_PS(n) (1 << (n)) +#define OMR_PR(n) (1 << ((n) + 16)) + /* Basic port input/output field values */ /* Director Input */ -#define IOCR_NOPULL 0 /* No internal pull device active */ -#define IOCR_PULLDOWN 1 /* Internal pull-down device active */ -#define IOCR_PULLUP 2 /* Internal pull-down device active */ -#define IOCR_CONT 3 /* No internal pull device active; Pn_OUTx continuously - * samples the input value */ +#define IOCR_NOPULL 0 /* No internal pull device active */ +#define IOCR_PULLDOWN 1 /* Internal pull-down device active */ +#define IOCR_PULLUP 2 /* Internal pull-down device active */ +#define IOCR_CONT 3 /* No internal pull device active; Pn_OUTx + * continuously samples the input value */ /* Any of the above may be OR'ed with */ /* Inverted Input */ -#define IOCR_INVERT 4 /* Inverted input */ +#define IOCR_INVERT 4 /* Inverted input */ /* Port Input/Output Control Register 0 */ -- GitLab From d2d54b4ae70f0a85bdad8cb35dc521f524541564 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 17 Mar 2017 11:18:24 -0600 Subject: [PATCH 079/990] XMC4xxx: Add framework and definitions for GPIO support --- arch/arm/src/xmc4/chip/xmc4_ports.h | 37 +++-- arch/arm/src/xmc4/xmc4_gpio.c | 98 ++++++++++++ arch/arm/src/xmc4/xmc4_gpio.h | 222 ++++++++++++++++++++++++++++ arch/arm/src/xmc4/xmc4_lowputc.c | 2 +- arch/arm/src/xmc4/xmc4_serial.c | 2 +- arch/arm/src/xmc4/xmc4_start.c | 2 + 6 files changed, 349 insertions(+), 14 deletions(-) diff --git a/arch/arm/src/xmc4/chip/xmc4_ports.h b/arch/arm/src/xmc4/chip/xmc4_ports.h index 1465c41a64..3478d9dedb 100644 --- a/arch/arm/src/xmc4/chip/xmc4_ports.h +++ b/arch/arm/src/xmc4/chip/xmc4_ports.h @@ -1,7 +1,7 @@ /************************************************************************************ * arch/arm/src/xmc4/chip/xmc4_ports.h * - * Copyright (C /*2017 Gregory Nutt. All rights reserved. + * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Reference: XMC4500 Reference Manual V1.5 2014-07 Microcontrollers. @@ -27,17 +27,17 @@ * 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 + * 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 + * 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. * * May include some logic from sample code provided by Infineon: * - * Copyright (C /*2011-2015 Infineon Technologies AG. All rights reserved. + * Copyright (C) 2011-2015 Infineon Technologies AG. All rights reserved. * - * Infineon Technologies AG (Infineon /*is supplying this software for use with + * Infineon Technologies AG (Infineon) is supplying this software for use with * Infineon's microcontrollers. This file can be freely distributed within * development tools that are supporting such microcontrollers. * @@ -258,18 +258,31 @@ #define OMR_PR(n) (1 << ((n) + 16)) /* Basic port input/output field values */ -/* Director Input */ +/* Direct Input */ -#define IOCR_NOPULL 0 /* No internal pull device active */ -#define IOCR_PULLDOWN 1 /* Internal pull-down device active */ -#define IOCR_PULLUP 2 /* Internal pull-down device active */ -#define IOCR_CONT 3 /* No internal pull device active; Pn_OUTx +#define IOCR_INPUT_NOPULL 0 /* No internal pull device active */ +#define IOCR_INPUT_PULLDOWN 1 /* Internal pull-down device active */ +#define IOCR_INPUT_PULLUP 2 /* Internal pull-down device active */ +#define IOCR_INPUT_CONT 3 /* No internal pull device active; Pn_OUTx * continuously samples the input value */ -/* Any of the above may be OR'ed with */ +/* Any of the above input configurations may be OR'ed with */ /* Inverted Input */ -#define IOCR_INVERT 4 /* Inverted input */ +#define IOCR_INPUT_INVERT 4 /* Inverted input modifier */ + +/* Push-pull Output (direct input) */ + +#define IOCR_OUTPUT 16 /* General-purpose output */ +#define IOCR_OUTPUT_ALT1 17 /* Alternate output function 1 */ +#define IOCR_OUTPUT_ALT2 18 /* Alternate output function 2 */ +#define IOCR_OUTPUT_ALT3 19 /* Alternate output function 3 */ +#define IOCR_OUTPUT_ALT4 20 /* Alternate output function 4 */ + +/* Any of the above may be OR'ed with */ +/* Open drain output */ + +#define IOCR_OUTPUT_OPENDRAIN 8 /* Output drain output modifier */ /* Port Input/Output Control Register 0 */ diff --git a/arch/arm/src/xmc4/xmc4_gpio.c b/arch/arm/src/xmc4/xmc4_gpio.c index e69de29bb2..4080a0be99 100644 --- a/arch/arm/src/xmc4/xmc4_gpio.c +++ b/arch/arm/src/xmc4/xmc4_gpio.c @@ -0,0 +1,98 @@ +/**************************************************************************** + * arch/arm/src/xmc4/xmc4_gpio.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include + +#include + +#include "up_arch.h" +#include "up_internal.h" + +#include "chip/xmc4_ports.h" +#include "xmc4_gpio.h" + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: xmc4_gpio_config + * + * Description: + * Configure a PIN based on bit-encoded description of the pin, + * 'pincconfig'. + * + ****************************************************************************/ + +int xmc4_gpio_config(gpioconfig_t pinconfig) +{ +#warning Missing logic + return -EINVAL; +} + +/**************************************************************************** + * Name: xmc4_gpio_write + * + * Description: + * Write one or zero to the PORT pin selected by 'pinconfig' + * + ****************************************************************************/ + +void xmc4_gpio_write(gpioconfig_t pinconfig, bool value) +{ +#warning Missing logic +} + +/**************************************************************************** + * Name: xmc4_gpio_read + * + * Description: + * Read one or zero from the PORT pin selected by 'pinconfig' + * + ****************************************************************************/ + +bool xmc4_gpio_read(gpioconfig_t pinconfig) +{ +#warning Missing logic + return false; +} diff --git a/arch/arm/src/xmc4/xmc4_gpio.h b/arch/arm/src/xmc4/xmc4_gpio.h index e69de29bb2..44ab0bde53 100644 --- a/arch/arm/src/xmc4/xmc4_gpio.h +++ b/arch/arm/src/xmc4/xmc4_gpio.h @@ -0,0 +1,222 @@ +/**************************************************************************** + * arch/arm/src/xmc4/xmc4_gpio.h + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include "chip/xmc4_ports.h" + +/**************************************************************************** + * Preprocessor Definitions + ****************************************************************************/ + +/* 32-bit GIO encoding: + * + * .... TTTT TMDD DCC. .... .... PPPP BBBB + */ + + +/* This identifies the GPIO pint type: + * + * .... TTTT T... .... .... .... .... .... + */ + +#define GPIO_PINTYPE_SHIFT (23) /* Bits 23-27: Pin type */ +#define GPIO_PINTYPE_MASK (31 << GPIO_PINTYPE_SHIFT) + +/* See chip/xmc4_ports.h for the IOCR definitions */ +/* Direct input */ + +# define GPIO_INPUT_NOPULL (IOCR_INPUT_NOPULL << GPIO_PINTYPE_SHIFT) +# define GPIO_INPUT_PULLDOWN (IOCR_INPUT_PULLDOWN << GPIO_PINTYPE_SHIFT) +# define GPIO_INPUT_PULLUP (IOCR_INPUT_PULLUP << GPIO_PINTYPE_SHIFT) +# define GPIO_INPUT_CONT (IOCR_INPUT_CONT << GPIO_PINTYPE_SHIFT) + +/* Push-pull Output (direct input) */ + +# define GPIO_OUTPUT (IOCR_OUTPUT << GPIO_PINTYPE_SHIFT) +# define GPIO_OUTPUT_ALT1 (IOCR_OUTPUT_ALT1 << GPIO_PINTYPE_SHIFT) +# define GPIO_OUTPUT_ALT2 (IOCR_OUTPUT_ALT2 << GPIO_PINTYPE_SHIFT) +# define GPIO_OUTPUT_ALT3 (IOCR_OUTPUT_ALT3 << GPIO_PINTYPE_SHIFT) +# define GPIO_OUTPUT_ALT4 (IOCR_OUTPUT_ALT4 << GPIO_PINTYPE_SHIFT) + +# define _GPIO_OUTPUT_BIT (16 << GPIO_PINTYPE_SHIFT) +# define GPIO_ISINPUT(p) (((p) & _GPIO_OUTPUT_BIT) != 0) +# define GPIO_ISOUTPUT(p) (((p) & _GPIO_OUTPUT_BIT) == 0) + +/* Pin type modifier: + * + * .... .... .M.. .... .... .... .... .... + */ + +#define GPIO_INPUT_INVERT (1 << 22) /* Inverted input modifier */ +#define GPIOS_OUTPUT_OPENDRAIN (1 << 22) /* Output drain output modifier */ + +/* Pad driver strength: + * + * .... .... ..DD D... .... .... .... .... + */ + +#define GPIO_PADTYPE_SHIFT (19) /* Bits 19-21: Pad driver strength */ +#define GPIO_PADTYPE_MASK (7 << GPIO_PADTYPE_SHIFT) + +/* See chip/xmc4_ports.h for the PDR definitions */ +/* Pad class A1: */ + +# define GPIO_PADA1_MEDIUM (PDR_PADA1_MEDIUM << GPIO_PADTYPE_SHIFT) +# define GPIO_PADA1_WEAK (PDR_PADA1_WEAK << GPIO_PADTYPE_SHIFT) + +/* Pad class A1+: */ + +# define GPIO_PADA1P_STRONGSOFT (PDR_PADA1P_STRONGSOFT << GPIO_PADTYPE_SHIFT) +# define GPIO_PADA1P_STRONGSLOW (PDR_PADA1P_STRONGSLOW << GPIO_PADTYPE_SHIFT) +# define GPIO_PADA1P_MEDIUM (PDR_PADA1P_MEDIUM << GPIO_PADTYPE_SHIFT) +# define GPIO_PADA1P_WEAK (PDR_PADA1P_WEAK << GPIO_PADTYPE_SHIFT) + +/* Pad class A2: */ + +# define GPIO_PADA2_STRONGSHARP (PDR_PADA2_STRONGSHARP << GPIO_PADTYPE_SHIFT) +# define GPIO_PADA2_STRONGMEDIUM (PDR_PADA2_STRONGMEDIUM << GPIO_PADTYPE_SHIFT) +# define GPIO_PADA2_STRONGSOFT (PDR_PADA2_STRONGSOFT << GPIO_PADTYPE_SHIFT) +# define GPIO_PADA2_MEDIUM (PDR_PADA2_MEDIUM << GPIO_PADTYPE_SHIFT) +# define GPIO_PADA2_WEAK (PDR_PADA2_WEAK << GPIO_PADTYPE_SHIFT) + +/* Pin control: + * + * .... .... .... .CC. .... .... .... .... + */ + +#define GPIO_PINCTRL_SHIFT (17) /* Bits 17-18: Pad driver strength */ +#define GPIO_PINCTRL_MASK (3 << GPIO_PINCTRL_SHIFT) + +/* See chip/xmc4_ports.h for the PDR definitions */ + +# define GPIO_PINCTRL_SOFTWARE (HWSEL_SOFTWARE << GPIO_PINCTRL_SHIFT) +# define GPIO_PINCTRL_OVERRIDE0 (HWSEL_OVERRIDE0 << GPIO_PINCTRL_SHIFT) +# define GPIO_PINCTRL_OVERRIDE1 (HWSEL_OVERRIDE1 << GPIO_PINCTRL_SHIFT) + +/* This identifies the GPIO port: + * + * .... ... .... .... .... .... PPPP .... + */ + +#define GPIO_PORT_SHIFT (4) /* Bit 4-7: Port number */ +#define GPIO_PORT_MASK (7 << GPIO_PORT_SHIFT) +# define GPIO_PORT0 (0 << GPIO_PORT_SHIFT) +# define GPIO_PORT1 (1 << GPIO_PORT_SHIFT) +# define GPIO_PORT2 (2 << GPIO_PORT_SHIFT) +# define GPIO_PORT3 (3 << GPIO_PORT_SHIFT) +# define GPIO_PORT4 (4 << GPIO_PORT_SHIFT) +# define GPIO_PORT5 (5 << GPIO_PORT_SHIFT) +# define GPIO_PORT6 (6 << GPIO_PORT_SHIFT) +# define GPIO_PORT7 (7 << GPIO_PORT_SHIFT) +# define GPIO_PORT8 (8 << GPIO_PORT_SHIFT) +# define GPIO_PORT9 (9 << GPIO_PORT_SHIFT) +# define GPIO_PORT14 (14 << GPIO_PORT_SHIFT) +# define GPIO_PORT15 (15 << GPIO_PORT_SHIFT) + +/* This identifies the bit in the port: + * + * ... ..... .... .... .... .... .... BBBB + */ + +#define GPIO_PIN_SHIFT (0) /* Bits 0-3: GPIO pin: 0-15 */ +#define GPIO_PIN_MASK (31 << GPIO_PIN_SHIFT) +#define GPIO_PIN0 (0 << GPIO_PIN_SHIFT) +#define GPIO_PIN1 (1 << GPIO_PIN_SHIFT) +#define GPIO_PIN2 (2 << GPIO_PIN_SHIFT) +#define GPIO_PIN3 (3 << GPIO_PIN_SHIFT) +#define GPIO_PIN4 (4 << GPIO_PIN_SHIFT) +#define GPIO_PIN5 (5 << GPIO_PIN_SHIFT) +#define GPIO_PIN6 (6 << GPIO_PIN_SHIFT) +#define GPIO_PIN7 (7 << GPIO_PIN_SHIFT) +#define GPIO_PIN8 (8 << GPIO_PIN_SHIFT) +#define GPIO_PIN9 (9 << GPIO_PIN_SHIFT) +#define GPIO_PIN10 (10 << GPIO_PIN_SHIFT) +#define GPIO_PIN11 (11 << GPIO_PIN_SHIFT) +#define GPIO_PIN12 (12 << GPIO_PIN_SHIFT) +#define GPIO_PIN13 (13 << GPIO_PIN_SHIFT) +#define GPIO_PIN14 (14 << GPIO_PIN_SHIFT) +#define GPIO_PIN15 (15 << GPIO_PIN_SHIFT) + + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* This is a type large enought to hold all pin configuration bits. */ + +typedef uint32_t gpioconfig_t; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: xmc4_gpio_config + * + * Description: + * Configure a PIN based on bit-encoded description of the pin, + * 'pincconfig'. + * + ****************************************************************************/ + +int xmc4_gpio_config(gpioconfig_t pinconfig); + +/**************************************************************************** + * Name: xmc4_gpio_write + * + * Description: + * Write one or zero to the PORT pin selected by 'pinconfig' + * + ****************************************************************************/ + +void xmc4_gpio_write(gpioconfig_t pinconfig, bool value); + +/**************************************************************************** + * Name: xmc4_gpio_read + * + * Description: + * Read one or zero from the PORT pin selected by 'pinconfig' + * + ****************************************************************************/ + +bool xmc4_gpio_read(gpioconfig_t pinconfig); diff --git a/arch/arm/src/xmc4/xmc4_lowputc.c b/arch/arm/src/xmc4/xmc4_lowputc.c index 8fe2f4094b..ec44caba54 100644 --- a/arch/arm/src/xmc4/xmc4_lowputc.c +++ b/arch/arm/src/xmc4/xmc4_lowputc.c @@ -48,7 +48,7 @@ #include "up_arch.h" #include "xmc4_config.h" -#include "chip/xmc4_uart.h" +#include "chip/xmc4_usic.h" #include "chip/xmc4_pinmux.h" /**************************************************************************** diff --git a/arch/arm/src/xmc4/xmc4_serial.c b/arch/arm/src/xmc4/xmc4_serial.c index b90f1c19ff..509cca5615 100644 --- a/arch/arm/src/xmc4/xmc4_serial.c +++ b/arch/arm/src/xmc4/xmc4_serial.c @@ -59,7 +59,7 @@ #include "xmc4_config.h" #include "chip.h" -#include "chip/xmc4_uart.h" +#include "chip/xmc4_usic.h" /**************************************************************************** * Pre-processor Definitions diff --git a/arch/arm/src/xmc4/xmc4_start.c b/arch/arm/src/xmc4/xmc4_start.c index e712f97dd3..7bf76f1fae 100644 --- a/arch/arm/src/xmc4/xmc4_start.c +++ b/arch/arm/src/xmc4/xmc4_start.c @@ -46,11 +46,13 @@ #include #include +#include "nvic.h" #include "up_arch.h" #include "up_internal.h" #include "chip/xmc4_flash.h" #include "xmc4_userspace.h" +#include "xmc4_start.h" #ifdef CONFIG_ARCH_FPU # include "nvic.h" -- GitLab From 41758d8e4c274df26b4bc0373c322c6090899aa1 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 17 Mar 2017 11:22:42 -0600 Subject: [PATCH 080/990] XMC4xxx: minor update to GPIO definitions. --- arch/arm/src/xmc4/xmc4_gpio.h | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/arch/arm/src/xmc4/xmc4_gpio.h b/arch/arm/src/xmc4/xmc4_gpio.h index 44ab0bde53..716d821192 100644 --- a/arch/arm/src/xmc4/xmc4_gpio.h +++ b/arch/arm/src/xmc4/xmc4_gpio.h @@ -87,8 +87,10 @@ * .... .... .M.. .... .... .... .... .... */ -#define GPIO_INPUT_INVERT (1 << 22) /* Inverted input modifier */ -#define GPIOS_OUTPUT_OPENDRAIN (1 << 22) /* Output drain output modifier */ +#define GPIO_INPUT_INVERT (1 << 22) /* Inverted direct input modifier */ + +#define GPIOS_OUTPUT_PUSHPULL (0) /* Push-ull output is the default */ +#define GPIOS_OUTPUT_OPENDRAIN (1 << 22) /* Output drain output modifier */ /* Pad driver strength: * -- GitLab From 8bfb735351850e374a435a5fb116e8fbe3b5fc37 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 17 Mar 2017 13:02:07 -0600 Subject: [PATCH 081/990] XMC4xxx: Finishes implementation of GPIO support. --- arch/arm/src/xmc4/chip/xmc4_memorymap.h | 1 + arch/arm/src/xmc4/chip/xmc4_ports.h | 8 + arch/arm/src/xmc4/xmc4_gpio.c | 399 +++++++++++++++++++++++- arch/arm/src/xmc4/xmc4_gpio.h | 75 +++-- 4 files changed, 450 insertions(+), 33 deletions(-) diff --git a/arch/arm/src/xmc4/chip/xmc4_memorymap.h b/arch/arm/src/xmc4/chip/xmc4_memorymap.h index c2b847d4e0..ea41ac30b1 100644 --- a/arch/arm/src/xmc4/chip/xmc4_memorymap.h +++ b/arch/arm/src/xmc4/chip/xmc4_memorymap.h @@ -148,6 +148,7 @@ #define XMC4_USIC2_CH0_BASE 0x48024000 #define XMC4_USIC2_CH1_BASE 0x48024200 #define XMC4_USIC2_RAM_BASE 0x48024400 +#define XMC4_PORT_BASE(n) (0x48028000 + ((n) << 8)) #define XMC4_PORT0_BASE 0x48028000 #define XMC4_PORT1_BASE 0x48028100 #define XMC4_PORT2_BASE 0x48028200 diff --git a/arch/arm/src/xmc4/chip/xmc4_ports.h b/arch/arm/src/xmc4/chip/xmc4_ports.h index 3478d9dedb..588965c9f0 100644 --- a/arch/arm/src/xmc4/chip/xmc4_ports.h +++ b/arch/arm/src/xmc4/chip/xmc4_ports.h @@ -58,6 +58,8 @@ #include +#include "chip/xmc4_memorymap.h" + /************************************************************************************ * Pre-processor Definitions ************************************************************************************/ @@ -68,13 +70,19 @@ #define XMC4_PORT_OUT_OFFSET 0x0000 /* Port Output Register */ #define XMC4_PORT_OMR_OFFSET 0x0004 /* Port Output Modification Register */ + +#define XMC4_PORT_IOCR_OFFSET(n) (0x0010 + ((n) & 3)) #define XMC4_PORT_IOCR0_OFFSET 0x0010 /* Port Input/Output Control Register 0 */ #define XMC4_PORT_IOCR4_OFFSET 0x0014 /* Port Input/Output Control Register 4 */ #define XMC4_PORT_IOCR8_OFFSET 0x0018 /* Port Input/Output Control Register 8 */ #define XMC4_PORT_IOCR12_OFFSET 0x001c /* Port Input/Output Control Register 12 */ + #define XMC4_PORT_IN_OFFSET 0x0024 /* Port Input Register */ + +#define XMC4_PORT_PDR_OFFSET(n) (0x0010 + (((n) >> 1) & 3)) #define XMC4_PORT_PDR0_OFFSET 0x0040 /* Port Pad Driver Mode 0 Register */ #define XMC4_PORT_PDR1_OFFSET 0x0044 /* Port Pad Driver Mode 1 Register */ + #define XMC4_PORT_PDISC_OFFSET 0x0060 /* Port Pin Function Decision Control Register */ #define XMC4_PORT_PPS_OFFSET 0x0070 /* Port Pin Power Save Register */ #define XMC4_PORT_HWSEL_OFFSET 0x0074 /* Port Pin Hardware Select Register */ diff --git a/arch/arm/src/xmc4/xmc4_gpio.c b/arch/arm/src/xmc4/xmc4_gpio.c index 4080a0be99..2bc8f10828 100644 --- a/arch/arm/src/xmc4/xmc4_gpio.c +++ b/arch/arm/src/xmc4/xmc4_gpio.c @@ -44,6 +44,7 @@ #include #include +#include #include "up_arch.h" #include "up_internal.h" @@ -51,6 +52,301 @@ #include "chip/xmc4_ports.h" #include "xmc4_gpio.h" +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: xmc4_gpio_getreg + * + * Description: + * Return the pin number for this pin configuration + * + ****************************************************************************/ + +static inline uint32_t xmc4_gpio_getreg(uintptr_t portbase, + unsigned int offset) +{ + return getreg32(portbase + offset); +} + +/**************************************************************************** + * Name: xmc4_gpio_putreg + * + * Description: + * Return the pin number for this pin configuration + * + ****************************************************************************/ + +static inline void xmc4_gpio_putreg(uintptr_t portbase, unsigned int offset, + uint32_t regval) +{ + putreg32(regval, portbase + offset); +} + +/**************************************************************************** + * Name: xmc4_gpio_port + * + * Description: + * Return the port number for this pin configuration + * + ****************************************************************************/ + +static inline int xmc4_gpio_port(gpioconfig_t pinconfig) +{ + return ((pinconfig & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT); +} + +/**************************************************************************** + * Name: xmc4_gpio_portbase + * + * Description: + * Return the base address of the port register for this pin configuration. + * + ****************************************************************************/ + +static uintptr_t xmc4_gpio_portbase(gpioconfig_t pinconfig) +{ + return XMC4_PORT_BASE(xmc4_gpio_port(pinconfig)); +} + +/**************************************************************************** + * Name: xmc4_gpio_pin + * + * Description: + * Return the pin number for this pin configuration + * + ****************************************************************************/ + +static unsigned int xmc4_gpio_pin(gpioconfig_t pinconfig) +{ + return ((pinconfig & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT); +} + +/**************************************************************************** + * Name: xmc4_gpio_pintype + * + * Description: + * Return the pintype for this pin configuration + * + ****************************************************************************/ + +static inline unsigned int xmc4_gpio_pintype(gpioconfig_t pinconfig) +{ + return ((pinconfig & GPIO_PINTYPE_MASK) >> GPIO_PINTYPE_SHIFT); +} + +/**************************************************************************** + * Name: xmc4_gpio_pinctrl + * + * Description: + * Return the pintype for this pin configuration + * + ****************************************************************************/ + +static inline unsigned int xmc4_gpio_pinctrl(gpioconfig_t pinconfig) +{ + return ((pinconfig & GPIO_PINCTRL_MASK) >> GPIO_PINCTRL_SHIFT); +} + +/**************************************************************************** + * Name: xmc4_gpio_padtype + * + * Description: + * Return the padtype for this pin configuration + * + ****************************************************************************/ + +static inline unsigned int xmc4_gpio_padtype(gpioconfig_t pinconfig) +{ + return ((pinconfig & GPIO_PADTYPE_MASK) >> GPIO_PADTYPE_SHIFT); +} + +/**************************************************************************** + * Name: xmc4_gpio_iocr + * + * Description: + * Update the IOCR register + * + ****************************************************************************/ + +static void xmc4_gpio_iocr(uintptr_t portbase, unsigned int pin, + unsigned int value) +{ + uint32_t regval; + uint32_t mask; + unsigned int offset; + unsigned int shift; + + /* Read the IOCR register */ + + offset = XMC4_PORT_IOCR_OFFSET(pin); + regval = xmc4_gpio_getreg(portbase, offset); + + /* Set the new value for this field */ + + pin &= 3; + shift = PORT_IOCR0_PC_SHIFT(pin); + mask = PORT_IOCR0_PC_MASK(pin); + + regval &= ~mask; + regval |= (uint32_t)value << shift; + + xmc4_gpio_putreg(portbase, offset, regval); +} + +/**************************************************************************** + * Name: xmc4_gpio_hwsel + * + * Description: + * Update the HWSEL register + * + ****************************************************************************/ + +static inline void xmc4_gpio_hwsel(uintptr_t portbase, unsigned int pin, + unsigned int value) +{ + uint32_t regval; + uint32_t mask; + unsigned int shift; + + /* Read the HWSEL register */ + + regval = xmc4_gpio_getreg(portbase, XMC4_PORT_HWSEL_OFFSET); + + /* Set the new value for this field */ + + shift = PORT_HWSEL_HW_SHIFT(pin); + mask = PORT_HWSEL_HW_MASK(pin); + + regval &= ~mask; + regval |= (uint32_t)value << shift; + + xmc4_gpio_putreg(portbase, XMC4_PORT_HWSEL_OFFSET, regval); +} + +/**************************************************************************** + * Name: xmc4_gpio_pdisc + * + * Description: + * Update the PDISC register + * + ****************************************************************************/ + +static inline void xmc4_gpio_pdisc(uintptr_t portbase, unsigned int pin, + bool value) +{ + uint32_t regval; + uint32_t mask; + + /* Read the PDISC register */ + + regval = xmc4_gpio_getreg(portbase, XMC4_PORT_PDISC_OFFSET); + + /* Set/clear the enable/disable (or analg) value for this field */ + + mask = PORT_PIN(pin); + if (value) + { + regval |= mask; + } + else + { + regval &= ~mask; + } + + xmc4_gpio_putreg(portbase, XMC4_PORT_PDISC_OFFSET, regval); +} + +/**************************************************************************** + * Name: xmc4_gpio_pps + * + * Description: + * Update the PPS register + * + ****************************************************************************/ + +static inline void xmc4_gpio_pps(uintptr_t portbase, unsigned int pin, + bool value) +{ + uint32_t regval; + uint32_t mask; + + /* Read the PPS register */ + + regval = xmc4_gpio_getreg(portbase, XMC4_PORT_PPS_OFFSET); + + /* Set/clear the enable/disable (or analg) value for this field */ + + mask = PORT_PIN(pin); + if (value) + { + regval |= mask; + } + else + { + regval &= ~mask; + } + + xmc4_gpio_putreg(portbase, XMC4_PORT_PPS_OFFSET, regval); +} + +/**************************************************************************** + * Name: xmc4_gpio_pdr + * + * Description: + * Update the IOCR register + * + ****************************************************************************/ + +static void xmc4_gpio_pdr(uintptr_t portbase, unsigned int pin, + unsigned int value) +{ + uint32_t regval; + uint32_t mask; + unsigned int offset; + unsigned int shift; + + /* Read the PDRregister */ + + offset = XMC4_PORT_PDR_OFFSET(pin); + regval = xmc4_gpio_getreg(portbase, offset); + + /* Set the new value for this field */ + + pin &= 7; + shift = PORT_PDR0_PD_SHIFT(pin); + mask = PORT_PDR0_PD_MASK(pin); + + regval &= ~mask; + regval |= (uint32_t)value << shift; + + xmc4_gpio_putreg(portbase, offset, regval); +} + +/**************************************************************************** + * Name: xmc4_gpio_inverted + * + * Description: + * Check if the input is inverted + * + ****************************************************************************/ + +static inline bool xmc4_gpio_inverted(gpioconfig_t pinconfig) +{ + return ((pinconfig & GPIO_INPUT_INVERT) != 0); +} + +/**************************************************************************** + * Name: xmc4_gpio_opendrain + * + * Description: + * Check if the output is opendram + * + ****************************************************************************/ + +#define xmc4_gpio_opendrain(p) xmc4_gpio_inverted(p) + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -66,8 +362,71 @@ int xmc4_gpio_config(gpioconfig_t pinconfig) { -#warning Missing logic - return -EINVAL; + uintptr_t portbase = xmc4_gpio_portbase(pinconfig); + unsigned int pin = xmc4_gpio_pin(pinconfig); + unsigned int value; + irqstate_t flags; + + flags = enter_critical_section(); + if (GPIO_ISINPUT(pinconfig)) + { + /* Get input pin type (IOCR) */ + + value = xmc4_gpio_pintype(pinconfig); + + /* Check if the input is inverted */ + + if (xmc4_gpio_inverted(pinconfig)) + { + value |= IOCR_INPUT_INVERT; + } + } + else + { + /* Force input while we configure */ + + xmc4_gpio_iocr(portbase, pin, IOCR_INPUT_NOPULL); + + /* Set output value before enabling output */ + + xmc4_gpio_write(pinconfig, ((pinconfig & GPIO_OUTPUT_SET) != 0)); + + /* Get output pin type (IOCR) */ + + value = xmc4_gpio_pintype(pinconfig); + + /* Get if the output is opendrain */ + + if (xmc4_gpio_opendrain(pinconfig)) + { + value |= IOCR_OUTPUT_OPENDRAIN; + } + } + + /* Update the IOCR register to instantiate the pin type */ + + xmc4_gpio_iocr(portbase, pin, value); + + /* Select pin control (HWSEL) */ + + value = xmc4_gpio_pinctrl(pinconfig); + xmc4_gpio_hwsel(portbase, pin, value); + + /* Select drive strength */ + + value = xmc4_gpio_padtype(pinconfig); + xmc4_gpio_pdr(portbase, pin, value); + + /* Enable/enable pad or Analog only (PDISC) */ + + xmc4_gpio_pdisc(portbase, pin, ((pinconfig & GPIO_PAD_DISABLE) != 0)); + + /* Make sure pin is not in power save mode (PDR) */ + + xmc4_gpio_pdisc(portbase, pin, false); + + leave_critical_section(flags); + return OK; } /**************************************************************************** @@ -80,7 +439,28 @@ int xmc4_gpio_config(gpioconfig_t pinconfig) void xmc4_gpio_write(gpioconfig_t pinconfig, bool value) { -#warning Missing logic + uintptr_t portbase = xmc4_gpio_portbase(pinconfig); + unsigned int pin = xmc4_gpio_pin(pinconfig); + uint32_t regval; + uint32_t mask; + + /* Read the OUT register */ + + regval = xmc4_gpio_getreg(portbase, XMC4_PORT_OUT_OFFSET); + + /* Set/clear output value for this pin */ + + mask = PORT_PIN(pin); + if (value) + { + regval |= mask; + } + else + { + regval &= ~mask; + } + + xmc4_gpio_putreg(portbase, XMC4_PORT_OUT_OFFSET, regval); } /**************************************************************************** @@ -93,6 +473,15 @@ void xmc4_gpio_write(gpioconfig_t pinconfig, bool value) bool xmc4_gpio_read(gpioconfig_t pinconfig) { -#warning Missing logic - return false; + uintptr_t portbase = xmc4_gpio_portbase(pinconfig); + unsigned int pin = xmc4_gpio_pin(pinconfig); + uint32_t regval; + + /* Read the OUT register */ + + regval = xmc4_gpio_getreg(portbase, XMC4_PORT_IN_OFFSET); + + /* Return in the input state for this pin */ + + return ((regval & PORT_PIN(pin)) != 0); } diff --git a/arch/arm/src/xmc4/xmc4_gpio.h b/arch/arm/src/xmc4/xmc4_gpio.h index 716d821192..62b11bf048 100644 --- a/arch/arm/src/xmc4/xmc4_gpio.h +++ b/arch/arm/src/xmc4/xmc4_gpio.h @@ -50,16 +50,16 @@ /* 32-bit GIO encoding: * - * .... TTTT TMDD DCC. .... .... PPPP BBBB + * TTTT TMPD DDCC V.... .... .... PPPP BBBB */ /* This identifies the GPIO pint type: * - * .... TTTT T... .... .... .... .... .... + * TTTT T... .... .... .... .... .... .... */ -#define GPIO_PINTYPE_SHIFT (23) /* Bits 23-27: Pin type */ +#define GPIO_PINTYPE_SHIFT (27) /* Bits 27-31: Pin type */ #define GPIO_PINTYPE_MASK (31 << GPIO_PINTYPE_SHIFT) /* See chip/xmc4_ports.h for the IOCR definitions */ @@ -84,60 +84,79 @@ /* Pin type modifier: * - * .... .... .M.. .... .... .... .... .... + * .... .M.. .... .... .... .... .... .... */ -#define GPIO_INPUT_INVERT (1 << 22) /* Inverted direct input modifier */ +#define GPIO_INPUT_INVERT (1 << 26) /* Bit 26: Inverted direct input modifier */ -#define GPIOS_OUTPUT_PUSHPULL (0) /* Push-ull output is the default */ -#define GPIOS_OUTPUT_OPENDRAIN (1 << 22) /* Output drain output modifier */ +#define GPIO_OUTPUT_OPENDRAIN (1 << 26) /* Bit 26: Output drain output modifier */ +#define GPIO_OUTPUT_PUSHPULL (0) /* Push-pull output is the default */ + +/* Disable PAD: + * + * .... ..P. .... ..... .... .... .... .... + * + * For P0-P6, the PDISC register is ready only. + * For P14-P15, the bit setting also selects Analog+Digital or Analog only + */ + +#define GPIO_PAD_DISABLE (1 << 25) /* Bit 25: Disable Pad (P7-P9) */ +#define GPIO_PAD_ANALOG (1 << 25) /* Bit 25: Analog only (P14-P15) */ /* Pad driver strength: * - * .... .... ..DD D... .... .... .... .... + * .... ...D DD.. ..... .... ......... .... */ -#define GPIO_PADTYPE_SHIFT (19) /* Bits 19-21: Pad driver strength */ -#define GPIO_PADTYPE_MASK (7 << GPIO_PADTYPE_SHIFT) +#define GPIO_PADTYPE_SHIFT (22) /* Bits 22-24: Pad driver strength */ +#define GPIO_PADTYPE_MASK (7 << GPIO_PADTYPE_SHIFT) /* See chip/xmc4_ports.h for the PDR definitions */ /* Pad class A1: */ -# define GPIO_PADA1_MEDIUM (PDR_PADA1_MEDIUM << GPIO_PADTYPE_SHIFT) -# define GPIO_PADA1_WEAK (PDR_PADA1_WEAK << GPIO_PADTYPE_SHIFT) +# define GPIO_PADA1_MEDIUM (PDR_PADA1_MEDIUM << GPIO_PADTYPE_SHIFT) +# define GPIO_PADA1_WEAK (PDR_PADA1_WEAK << GPIO_PADTYPE_SHIFT) /* Pad class A1+: */ -# define GPIO_PADA1P_STRONGSOFT (PDR_PADA1P_STRONGSOFT << GPIO_PADTYPE_SHIFT) -# define GPIO_PADA1P_STRONGSLOW (PDR_PADA1P_STRONGSLOW << GPIO_PADTYPE_SHIFT) -# define GPIO_PADA1P_MEDIUM (PDR_PADA1P_MEDIUM << GPIO_PADTYPE_SHIFT) -# define GPIO_PADA1P_WEAK (PDR_PADA1P_WEAK << GPIO_PADTYPE_SHIFT) +# define GPIO_PADA1P_STRONGSOFT (PDR_PADA1P_STRONGSOFT << GPIO_PADTYPE_SHIFT) +# define GPIO_PADA1P_STRONGSLOW (PDR_PADA1P_STRONGSLOW << GPIO_PADTYPE_SHIFT) +# define GPIO_PADA1P_MEDIUM (PDR_PADA1P_MEDIUM << GPIO_PADTYPE_SHIFT) +# define GPIO_PADA1P_WEAK (PDR_PADA1P_WEAK << GPIO_PADTYPE_SHIFT) /* Pad class A2: */ -# define GPIO_PADA2_STRONGSHARP (PDR_PADA2_STRONGSHARP << GPIO_PADTYPE_SHIFT) -# define GPIO_PADA2_STRONGMEDIUM (PDR_PADA2_STRONGMEDIUM << GPIO_PADTYPE_SHIFT) -# define GPIO_PADA2_STRONGSOFT (PDR_PADA2_STRONGSOFT << GPIO_PADTYPE_SHIFT) -# define GPIO_PADA2_MEDIUM (PDR_PADA2_MEDIUM << GPIO_PADTYPE_SHIFT) -# define GPIO_PADA2_WEAK (PDR_PADA2_WEAK << GPIO_PADTYPE_SHIFT) +# define GPIO_PADA2_STRONGSHARP (PDR_PADA2_STRONGSHARP << GPIO_PADTYPE_SHIFT) +# define GPIO_PADA2_STRONGMEDIUM (PDR_PADA2_STRONGMEDIUM << GPIO_PADTYPE_SHIFT) +# define GPIO_PADA2_STRONGSOFT (PDR_PADA2_STRONGSOFT << GPIO_PADTYPE_SHIFT) +# define GPIO_PADA2_MEDIUM (PDR_PADA2_MEDIUM << GPIO_PADTYPE_SHIFT) +# define GPIO_PADA2_WEAK (PDR_PADA2_WEAK << GPIO_PADTYPE_SHIFT) /* Pin control: * - * .... .... .... .CC. .... .... .... .... + * .... .... ..CC ..... .... .... .... .... */ -#define GPIO_PINCTRL_SHIFT (17) /* Bits 17-18: Pad driver strength */ -#define GPIO_PINCTRL_MASK (3 << GPIO_PINCTRL_SHIFT) +#define GPIO_PINCTRL_SHIFT (20) /* Bits 20-21: Pad driver strength */ +#define GPIO_PINCTRL_MASK (3 << GPIO_PINCTRL_SHIFT) /* See chip/xmc4_ports.h for the PDR definitions */ -# define GPIO_PINCTRL_SOFTWARE (HWSEL_SOFTWARE << GPIO_PINCTRL_SHIFT) -# define GPIO_PINCTRL_OVERRIDE0 (HWSEL_OVERRIDE0 << GPIO_PINCTRL_SHIFT) -# define GPIO_PINCTRL_OVERRIDE1 (HWSEL_OVERRIDE1 << GPIO_PINCTRL_SHIFT) +# define GPIO_PINCTRL_SOFTWARE (HWSEL_SOFTWARE << GPIO_PINCTRL_SHIFT) +# define GPIO_PINCTRL_OVERRIDE0 (HWSEL_OVERRIDE0 << GPIO_PINCTRL_SHIFT) +# define GPIO_PINCTRL_OVERRIDE1 (HWSEL_OVERRIDE1 << GPIO_PINCTRL_SHIFT) + +/* If the pin is an GPIO output, then this identifies the initial output value: + * + * .... .... .... V.... .... .... PPPP BBBB + */ + +#define GPIO_OUTPUT_SET (1 << 19) /* Bit 19: Initial value of output */ +#define GPIO_OUTPUT_CLEAR (0) /* This identifies the GPIO port: * - * .... ... .... .... .... .... PPPP .... + * .... .... .... .... .... .... PPPP .... */ #define GPIO_PORT_SHIFT (4) /* Bit 4-7: Port number */ -- GitLab From 5ae9564b7d2eab24ff753f7fdd0c5902180d137a Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 17 Mar 2017 16:26:11 -0600 Subject: [PATCH 082/990] XMC4xxx: GPIO write should use OMR, not OUTPUT register. --- arch/arm/src/xmc4/xmc4_gpio.c | 35 +++++++++++++++++++++++------------ 1 file changed, 23 insertions(+), 12 deletions(-) diff --git a/arch/arm/src/xmc4/xmc4_gpio.c b/arch/arm/src/xmc4/xmc4_gpio.c index 2bc8f10828..e26967f06f 100644 --- a/arch/arm/src/xmc4/xmc4_gpio.c +++ b/arch/arm/src/xmc4/xmc4_gpio.c @@ -442,25 +442,34 @@ void xmc4_gpio_write(gpioconfig_t pinconfig, bool value) uintptr_t portbase = xmc4_gpio_portbase(pinconfig); unsigned int pin = xmc4_gpio_pin(pinconfig); uint32_t regval; - uint32_t mask; - - /* Read the OUT register */ - - regval = xmc4_gpio_getreg(portbase, XMC4_PORT_OUT_OFFSET); - /* Set/clear output value for this pin */ + /* Setup OMR value for this pin: + * + * PRx PSx Function + * 0 0 Bit Pn_OUT.Px is not changed. + * 0 1 Bit Pn_OUT.Px is set. + * 1 0 Bit Pn_OUT.Px is reset. + * 1 1 Bit Pn_OUT.Px is toggled. + */ - mask = PORT_PIN(pin); if (value) { - regval |= mask; + /* PRx==0; PSx==1 -> Set output */ + + regval = OMR_PS(pin); } else { - regval &= ~mask; + /* PRx==1; PSx==0 -> Reset output */ + + regval = OMR_PR(pin); } - xmc4_gpio_putreg(portbase, XMC4_PORT_OUT_OFFSET, regval); + /* Set/clear the OUTPUT. This is an atomoc operation so no critical + * section is needed. + */ + + xmc4_gpio_putreg(portbase, XMC4_PORT_OMR_OFFSET, regval); } /**************************************************************************** @@ -477,11 +486,13 @@ bool xmc4_gpio_read(gpioconfig_t pinconfig) unsigned int pin = xmc4_gpio_pin(pinconfig); uint32_t regval; - /* Read the OUT register */ + /* Read the OUT register. This is an atomoc operation so no critical + * section is needed. + */ regval = xmc4_gpio_getreg(portbase, XMC4_PORT_IN_OFFSET); - /* Return in the input state for this pin */ + /* Return in the input state for this pin at the time is was read */ return ((regval & PORT_PIN(pin)) != 0); } -- GitLab From 7bde01df98890f1b774c27f224a03ebd54995255 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 17 Mar 2017 16:40:29 -0600 Subject: [PATCH 083/990] XMC4C: Clean up some naming, fix some comments, add empty PINMUX header file. --- arch/arm/src/xmc4/chip/xmc4_flash.h | 2 +- arch/arm/src/xmc4/chip/xmc4_memorymap.h | 2 +- arch/arm/src/xmc4/chip/xmc4_pinmux.h | 52 +++++++++++++++++++++++++ arch/arm/src/xmc4/chip/xmc4_ports.h | 12 +++--- arch/arm/src/xmc4/chip/xmc4_usic.h | 2 +- arch/arm/src/xmc4/xmc4_gpio.h | 6 +-- 6 files changed, 64 insertions(+), 12 deletions(-) create mode 100644 arch/arm/src/xmc4/chip/xmc4_pinmux.h diff --git a/arch/arm/src/xmc4/chip/xmc4_flash.h b/arch/arm/src/xmc4/chip/xmc4_flash.h index e68e7078e9..37afed16a2 100644 --- a/arch/arm/src/xmc4/chip/xmc4_flash.h +++ b/arch/arm/src/xmc4/chip/xmc4_flash.h @@ -200,4 +200,4 @@ #define FLASH_PROCON2_S12_S13ROM (1 << 11) /* Bit 11: Sectors 12 and 13 Locked Forever by User 2 */ #define FLASH_PROCON2_S14_S15ROM (1 << 12) /* Bit 12: Sectors 14 and 15 Locked Forever by User 2 */ -#endif /* __ARCH_ARM_SRC_XMC4_CHIP_XMC4_SCU_H */ +#endif /* __ARCH_ARM_SRC_XMC4_CHIP_XMC4_FLASH_H */ diff --git a/arch/arm/src/xmc4/chip/xmc4_memorymap.h b/arch/arm/src/xmc4/chip/xmc4_memorymap.h index ea41ac30b1..fb8dcbf183 100644 --- a/arch/arm/src/xmc4/chip/xmc4_memorymap.h +++ b/arch/arm/src/xmc4/chip/xmc4_memorymap.h @@ -228,4 +228,4 @@ #define XMC4_PPB_BASE 0xe000e000 -#endif /* __ARCH_ARM_SRC_XMC4_CHIP_XMC4_SCU_H */ +#endif /* __ARCH_ARM_SRC_XMC4_CHIP_XMC4_MEMORYMAP_H */ diff --git a/arch/arm/src/xmc4/chip/xmc4_pinmux.h b/arch/arm/src/xmc4/chip/xmc4_pinmux.h new file mode 100644 index 0000000000..44d43074a8 --- /dev/null +++ b/arch/arm/src/xmc4/chip/xmc4_pinmux.h @@ -0,0 +1,52 @@ +/************************************************************************************ + * arch/arm/src/xmc4/chip/xmc4_pinmux.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Reference: XMC4500 Reference Manual V1.5 2014-07 Microcontrollers. + * + * 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 __ARCH_ARM_SRC_XMC4_CHIP_XMC4_PINMUX_H +#define __ARCH_ARM_SRC_XMC4_CHIP_XMC4_PINMUX_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + + +#endif /* __ARCH_ARM_SRC_XMC4_CHIP_XMC4_PINMXU_H */ diff --git a/arch/arm/src/xmc4/chip/xmc4_ports.h b/arch/arm/src/xmc4/chip/xmc4_ports.h index 588965c9f0..bdd90c2902 100644 --- a/arch/arm/src/xmc4/chip/xmc4_ports.h +++ b/arch/arm/src/xmc4/chip/xmc4_ports.h @@ -447,11 +447,11 @@ /* Hardware select field values */ -#define HWSEL_SOFTWARE 0 /* Software control only */ -#define HWSEL_OVERRIDE0 1 /* HWI0/HWO0 control path can override the - * software configuration */ -#define HWSEL_OVERRIDE1 2 /* HWI1/HWO1 control path can override the - * software configuration */ +#define HWSEL_SW 0 /* Software control only */ +#define HWSEL_HW0 1 /* HWI0/HWO0 control path can override + * the software configuration */ +#define HWSEL_HW1 2 /* HWI1/HWO1 control path can override + * the software configuration */ /* Port Pin Hardware Select Register */ @@ -507,4 +507,4 @@ #define PORT_HWSEL_HW15_MASK (3 << PORT_HWSEL_HW15_SHIFT) # define PORT_HWSEL_HW15(n) ((uint32_t)(n) << PORT_HWSEL_HW15_SHIFT) -#endif /* __ARCH_ARM_SRC_XMC4_CHIP_XMC4_SCU_H */ +#endif /* __ARCH_ARM_SRC_XMC4_CHIP_XMC4_PORTS_H */ diff --git a/arch/arm/src/xmc4/chip/xmc4_usic.h b/arch/arm/src/xmc4/chip/xmc4_usic.h index 089a14811f..1b3c4d2bdc 100644 --- a/arch/arm/src/xmc4/chip/xmc4_usic.h +++ b/arch/arm/src/xmc4/chip/xmc4_usic.h @@ -472,4 +472,4 @@ /* Transmit FIFO Buffer (32 x 4-bytes) */ #define USIC_IN_ -#endif /* __ARCH_ARM_SRC_XMC4_CHIP_XMC4_SCU_H */ +#endif /* __ARCH_ARM_SRC_XMC4_CHIP_XMC4_USIC_H */ diff --git a/arch/arm/src/xmc4/xmc4_gpio.h b/arch/arm/src/xmc4/xmc4_gpio.h index 62b11bf048..c1bf09b87b 100644 --- a/arch/arm/src/xmc4/xmc4_gpio.h +++ b/arch/arm/src/xmc4/xmc4_gpio.h @@ -142,9 +142,9 @@ /* See chip/xmc4_ports.h for the PDR definitions */ -# define GPIO_PINCTRL_SOFTWARE (HWSEL_SOFTWARE << GPIO_PINCTRL_SHIFT) -# define GPIO_PINCTRL_OVERRIDE0 (HWSEL_OVERRIDE0 << GPIO_PINCTRL_SHIFT) -# define GPIO_PINCTRL_OVERRIDE1 (HWSEL_OVERRIDE1 << GPIO_PINCTRL_SHIFT) +# define GPIO_PINCTRL_SOFTWARE (HWSEL_SW << GPIO_PINCTRL_SHIFT) +# define GPIO_PINCTRL_HW0 (HWSEL_HW0 << GPIO_PINCTRL_SHIFT) +# define GPIO_PINCTRL_HW1 (HWSEL_HW1 << GPIO_PINCTRL_SHIFT) /* If the pin is an GPIO output, then this identifies the initial output value: * -- GitLab From c6d5d3bdedd77e7430b58214fa871cb5e9c1b4e8 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 17 Mar 2017 16:44:26 -0600 Subject: [PATCH 084/990] XMC4xxx: All register definition files need to include memorymap.h --- arch/arm/src/xmc4/chip/xmc4_flash.h | 2 ++ arch/arm/src/xmc4/chip/xmc4_usic.h | 2 ++ arch/arm/src/xmc4/xmc4_gpio.h | 6 +++--- 3 files changed, 7 insertions(+), 3 deletions(-) diff --git a/arch/arm/src/xmc4/chip/xmc4_flash.h b/arch/arm/src/xmc4/chip/xmc4_flash.h index 37afed16a2..0432e465b0 100644 --- a/arch/arm/src/xmc4/chip/xmc4_flash.h +++ b/arch/arm/src/xmc4/chip/xmc4_flash.h @@ -58,6 +58,8 @@ #include +#include "chip/xmc4_memorymap.h" + /************************************************************************************ * Pre-processor Definitions ************************************************************************************/ diff --git a/arch/arm/src/xmc4/chip/xmc4_usic.h b/arch/arm/src/xmc4/chip/xmc4_usic.h index 1b3c4d2bdc..8b91e88583 100644 --- a/arch/arm/src/xmc4/chip/xmc4_usic.h +++ b/arch/arm/src/xmc4/chip/xmc4_usic.h @@ -58,6 +58,8 @@ #include +#include "chip/xmc4_memorymap.h" + /************************************************************************************ * Pre-processor Definitions ************************************************************************************/ diff --git a/arch/arm/src/xmc4/xmc4_gpio.h b/arch/arm/src/xmc4/xmc4_gpio.h index c1bf09b87b..49b80ba196 100644 --- a/arch/arm/src/xmc4/xmc4_gpio.h +++ b/arch/arm/src/xmc4/xmc4_gpio.h @@ -142,9 +142,9 @@ /* See chip/xmc4_ports.h for the PDR definitions */ -# define GPIO_PINCTRL_SOFTWARE (HWSEL_SW << GPIO_PINCTRL_SHIFT) -# define GPIO_PINCTRL_HW0 (HWSEL_HW0 << GPIO_PINCTRL_SHIFT) -# define GPIO_PINCTRL_HW1 (HWSEL_HW1 << GPIO_PINCTRL_SHIFT) +# define GPIO_PINCTRL_SOFTWARE (HWSEL_SW << GPIO_PINCTRL_SHIFT) +# define GPIO_PINCTRL_HW0 (HWSEL_HW0 << GPIO_PINCTRL_SHIFT) +# define GPIO_PINCTRL_HW1 (HWSEL_HW1 << GPIO_PINCTRL_SHIFT) /* If the pin is an GPIO output, then this identifies the initial output value: * -- GitLab From ac0d957f26a8214835df6cfcd0bfcd89d6ce863e Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Fri, 17 Mar 2017 17:32:44 -0600 Subject: [PATCH 085/990] libc: printf: fix precision for string formatting. Fixes use of format precision to truncate input string. --- libc/stdio/lib_libvsprintf.c | 19 ++++++++++--------- 1 file changed, 10 insertions(+), 9 deletions(-) diff --git a/libc/stdio/lib_libvsprintf.c b/libc/stdio/lib_libvsprintf.c index 894f040453..1a3501c704 100644 --- a/libc/stdio/lib_libvsprintf.c +++ b/libc/stdio/lib_libvsprintf.c @@ -1171,9 +1171,7 @@ int lib_vsprintf(FAR struct lib_outstream_s *obj, FAR const IPTR char *src, FAR char *ptmp; #ifndef CONFIG_NOPRINTF_FIELDWIDTH int width; -#ifdef CONFIG_LIBC_FLOATINGPOINT int trunc; -#endif uint8_t fmt; #endif uint8_t flags; @@ -1215,9 +1213,7 @@ int lib_vsprintf(FAR struct lib_outstream_s *obj, FAR const IPTR char *src, #ifndef CONFIG_NOPRINTF_FIELDWIDTH fmt = FMT_RJUST; width = 0; -#ifdef CONFIG_LIBC_FLOATINGPOINT trunc = 0; -#endif #endif /* Process each format qualifier. */ @@ -1265,10 +1261,8 @@ int lib_vsprintf(FAR struct lib_outstream_s *obj, FAR const IPTR char *src, int value = va_arg(ap, int); if (IS_HASDOT(flags)) { -#ifdef CONFIG_LIBC_FLOATINGPOINT trunc = value; SET_HASASTERISKTRUNC(flags); -#endif } else { @@ -1307,9 +1301,7 @@ int lib_vsprintf(FAR struct lib_outstream_s *obj, FAR const IPTR char *src, if (IS_HASDOT(flags)) { -#ifdef CONFIG_LIBC_FLOATINGPOINT trunc = n; -#endif } else { @@ -1361,6 +1353,7 @@ int lib_vsprintf(FAR struct lib_outstream_s *obj, FAR const IPTR char *src, { #ifndef CONFIG_NOPRINTF_FIELDWIDTH int swidth; + int left; #endif /* Get the string to output */ @@ -1375,13 +1368,21 @@ int lib_vsprintf(FAR struct lib_outstream_s *obj, FAR const IPTR char *src, */ #ifndef CONFIG_NOPRINTF_FIELDWIDTH - swidth = strlen(ptmp); + swidth = (IS_HASDOT(flags) && trunc >= 0) + ? strnlen(ptmp, trunc) : strlen(ptmp); prejustify(obj, fmt, 0, width, swidth); + left = swidth; #endif /* Concatenate the string into the output */ while (*ptmp) { +#ifndef CONFIG_NOPRINTF_FIELDWIDTH + if (left-- <= 0) + { + break; + } +#endif obj->put(obj, *ptmp); ptmp++; } -- GitLab From acec5e3199e13e2d772e3340b2f73a0bf424c5d9 Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Fri, 17 Mar 2017 17:34:56 -0600 Subject: [PATCH 086/990] vsnprintf(): If size is zero, then vsnprintf() should return the size of the required buffer without writing anything. This is same fix that was done for snprintf in 2014 by commit 59846a8fe928abb389e3776ebdbb52022da45be3. --- libc/stdio/lib_vsnprintf.c | 35 ++++++++++++++++++++++++++++------- 1 file changed, 28 insertions(+), 7 deletions(-) diff --git a/libc/stdio/lib_vsnprintf.c b/libc/stdio/lib_vsnprintf.c index d25fc0d2d5..40f7dffc50 100644 --- a/libc/stdio/lib_vsnprintf.c +++ b/libc/stdio/lib_vsnprintf.c @@ -55,17 +55,38 @@ int vsnprintf(FAR char *buf, size_t size, FAR const IPTR char *format, va_list ap) { - struct lib_memoutstream_s memoutstream; - int n; + union + { + struct lib_outstream_s nulloutstream; + struct lib_memoutstream_s memoutstream; + } u; - /* Initialize a memory stream to write to the buffer */ + FAR struct lib_outstream_s *stream; + int n; - lib_memoutstream((FAR struct lib_memoutstream_s *)&memoutstream, - buf, size); + /* "If the value of [size] is zero on a call to vsnprintf(), nothing shall + * be written, the number of bytes that would have been written had [size] + * been sufficiently large excluding the terminating null shall be returned, + * and [buf] may be a null pointer." -- opengroup.org + */ + + if (size > 0) + { + /* Initialize a memory stream to write to the buffer */ + + lib_memoutstream(&u.memoutstream, buf, size); + stream = &u.memoutstream.public; + } + else + { + /* Use a null stream to get the size of the buffer */ + + lib_nulloutstream(&u.nulloutstream); + stream = &u.nulloutstream; + } /* Then let lib_vsprintf do the real work */ - n = lib_vsprintf((FAR struct lib_outstream_s *)&memoutstream.public, - format, ap); + n = lib_vsprintf(stream, format, ap); return n; } -- GitLab From 0a95536b850ce4a8513989ab9c6b088e84a122a3 Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Fri, 17 Mar 2017 20:35:49 -0700 Subject: [PATCH 087/990] Adds driver support for the XBox One controller. Currently only the latest version (XBox One X) controller works. The older XBox One controllers do not enumerate correctly. --- configs/stm32f4discovery/src/stm32_usb.c | 13 +- drivers/usbhost/Kconfig | 32 + drivers/usbhost/Make.defs | 4 + drivers/usbhost/usbhost_xboxcontroller.c | 2195 ++++++++++++++++++++++ include/nuttx/input/xbox-controller.h | 88 + include/nuttx/usb/usbhost.h | 21 + 6 files changed, 2352 insertions(+), 1 deletion(-) create mode 100644 drivers/usbhost/usbhost_xboxcontroller.c create mode 100644 include/nuttx/input/xbox-controller.h diff --git a/configs/stm32f4discovery/src/stm32_usb.c b/configs/stm32f4discovery/src/stm32_usb.c index c929c1bfe2..f0d2e16170 100644 --- a/configs/stm32f4discovery/src/stm32_usb.c +++ b/configs/stm32f4discovery/src/stm32_usb.c @@ -167,7 +167,8 @@ int stm32_usbhost_initialize(void) { int pid; #if defined(CONFIG_USBHOST_HUB) || defined(CONFIG_USBHOST_MSC) || \ - defined(CONFIG_USBHOST_HIDKBD) || defined(CONFIG_USBHOST_HIDMOUSE) + defined(CONFIG_USBHOST_HIDKBD) || defined(CONFIG_USBHOST_HIDMOUSE) || \ + defined(CONFIG_USBHOST_XBOXCONTROLLER) int ret; #endif @@ -227,6 +228,16 @@ int stm32_usbhost_initialize(void) } #endif +#ifdef CONFIG_USBHOST_XBOXCONTROLLER + /* Initialize the HID mouse class */ + + ret = usbhost_xboxcontroller_init(); + if (ret != OK) + { + uerr("ERROR: Failed to register the XBox Controller class\n"); + } +#endif + /* Then get an instance of the USB host interface */ uinfo("Initialize USB host\n"); diff --git a/drivers/usbhost/Kconfig b/drivers/usbhost/Kconfig index 334e393f51..5e49aa7b86 100644 --- a/drivers/usbhost/Kconfig +++ b/drivers/usbhost/Kconfig @@ -521,6 +521,38 @@ config RTL8187_PID endif # USBHOST_RTL8187 +config USBHOST_XBOXCONTROLLER + bool "Xbox Controller Support" + default n + depends on !INT_DISABLE + select INPUT + ---help--- + Enable support for the Xbox Controller driver. + +if USBHOST_XBOXCONTROLLER + +config XBOXCONTROLLER_DEFPRIO + int "Polling Thread Priority" + default 50 + ---help--- + Priority of the polling thread. Default: 50. + +config XBOXCONTROLLER_STACKSIZE + int "Polling thread stack size" + default 1024 + ---help--- + Stack size for polling thread. Default: 1024 + +config XBOXCONTROLLER_NPOLLWAITERS + int "Max Number of Waiters for Poll Event" + default 2 + depends on !DISABLE_POLL + ---help--- + If the poll() method is enabled, this defines the maximum number + of threads that can be waiting for mouse events. Default: 2. + +endif # USBHOST_XBOXCONTROLLER + config USBHOST_TRACE bool "Enable USB HCD tracing for debug" default n diff --git a/drivers/usbhost/Make.defs b/drivers/usbhost/Make.defs index fd28be8766..105156aee3 100644 --- a/drivers/usbhost/Make.defs +++ b/drivers/usbhost/Make.defs @@ -66,6 +66,10 @@ ifeq ($(CONFIG_USBHOST_HIDMOUSE),y) CSRCS += usbhost_hidmouse.c endif +ifeq ($(CONFIG_USBHOST_XBOXCONTROLLER),y) +CSRCS += usbhost_xboxcontroller.c +endif + # HCD debug/trace logic ifeq ($(CONFIG_USBHOST_TRACE),y) diff --git a/drivers/usbhost/usbhost_xboxcontroller.c b/drivers/usbhost/usbhost_xboxcontroller.c new file mode 100644 index 0000000000..fd12efee97 --- /dev/null +++ b/drivers/usbhost/usbhost_xboxcontroller.c @@ -0,0 +1,2195 @@ +/**************************************************************************** + * drivers/usbhost/usbhost_xboxcontroller.c + * + * Copyright (C) 2016 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +#ifndef CONFIG_SCHED_WORKQUEUE +# warning "Worker thread support is required (CONFIG_SCHED_WORKQUEUE)" +#endif + +#ifndef CONFIG_XBOXCONTROLLER_DEFPRIO +# define CONFIG_XBOXCONTROLLER_DEFPRIO 50 +#endif + +#ifndef CONFIG_XBOXCONTROLLER_STACKSIZE +# define CONFIG_XBOXCONTROLLER_STACKSIZE 1024 +#endif + +#ifndef CONFIG_XBOXCONTROLLER_NPOLLWAITERS +# define CONFIG_XBOXCONTROLLER_NPOLLWAITERS 2 +#endif + +/* Driver support ***********************************************************/ +/* This format is used to construct the /dev/xbox[n] device driver path. It + * defined here so that it will be used consistently in all places. + */ + +#define DEV_FORMAT "/dev/xbox%c" +#define DEV_NAMELEN 11 + +/* Used in usbhost_cfgdesc() */ + +#define USBHOST_IFFOUND 0x01 +#define USBHOST_EPINFOUND 0x02 /* Required interrupt IN EP descriptor found */ +#define USBHOST_EPOUTFOUND 0x04 /* Required interrupt OUT EP descriptor found */ +#define USBHOST_ALLFOUND 0x07 + +#define USBHOST_MAX_CREFS 0x7fff + +/* Received message types */ + +#define USBHOST_WAITING_CONNECTION 0x02 +#define USBHOST_GUIDE_BUTTON_STATUS 0x07 +#define USBHOST_BUTTON_DATA 0x20 + +/* Button definitions */ + +#define XBOX_BUTTON_GUIDE_INDEX 4 +#define XBOX_BUTTON_SYNC_INDEX 4 +#define XBOX_BUTTON_SYNC_MASK (1 << 0) +#define XBOX_BUTTON_START_INDEX 4 +#define XBOX_BUTTON_START_MASK (1 << 2) +#define XBOX_BUTTON_BACK_INDEX 4 +#define XBOX_BUTTON_BACK_MASK (1 << 3) +#define XBOX_BUTTON_A_INDEX 4 +#define XBOX_BUTTON_A_MASK (1 << 4) +#define XBOX_BUTTON_B_INDEX 4 +#define XBOX_BUTTON_B_MASK (1 << 5) +#define XBOX_BUTTON_X_INDEX 4 +#define XBOX_BUTTON_X_MASK (1 << 6) +#define XBOX_BUTTON_Y_INDEX 4 +#define XBOX_BUTTON_Y_MASK (1 << 7) +#define XBOX_BUTTON_DPAD_UP_INDEX 5 +#define XBOX_BUTTON_DPAD_UP_MASK (1 << 0) +#define XBOX_BUTTON_DPAD_DOWN_INDEX 5 +#define XBOX_BUTTON_DPAD_DOWN_MASK (1 << 1) +#define XBOX_BUTTON_DPAD_LEFT_INDEX 5 +#define XBOX_BUTTON_DPAD_LEFT_MASK (1 << 2) +#define XBOX_BUTTON_DPAD_RIGHT_INDEX 5 +#define XBOX_BUTTON_DPAD_RIGHT_MASK (1 << 3) +#define XBOX_BUTTON_BUMPER_LEFT_INDEX 5 +#define XBOX_BUTTON_BUMPER_LEFT_MASK (1 << 4) +#define XBOX_BUTTON_BUMPER_RIGHT_INDEX 5 +#define XBOX_BUTTON_BUMPER_RIGHT_MASK (1 << 5) +#define XBOX_BUTTON_STICK_LEFT_INDEX 5 +#define XBOX_BUTTON_STICK_LEFT_MASK (1 << 6) +#define XBOX_BUTTON_STICK_RIGHT_INDEX 5 +#define XBOX_BUTTON_STICK_RIGHT_MASK (1 << 7) +#define XBOX_BUTTON_TRIGGER_LEFT 3 +#define XBOX_BUTTON_TRIGGER_RIGHT 4 +#define XBOX_BUTTON_STICK_LEFT_X 5 +#define XBOX_BUTTON_STICK_LEFT_Y 6 +#define XBOX_BUTTON_STICK_RIGHT_X 7 +#define XBOX_BUTTON_STICK_RIGHT_Y 8 +#define XBOX_BUTTON_SET(buffer, index, mask) ((((buffer)[(index)] & (mask)) != 0) ? true : false); + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/* This structure contains the internal, private state of the USB host class + * driver. + */ + +struct usbhost_state_s +{ + /* This is the externally visible portion of the state */ + + struct usbhost_class_s usbclass; + + /* The remainder of the fields are provide to the class driver */ + + char devchar; /* Character identifying the /dev/xbox[n] device */ + volatile bool disconnected; /* TRUE: Device has been disconnected */ + volatile bool polling; /* TRUE: Poll thread is running */ + volatile bool open; /* TRUE: The controller device is open */ + volatile bool valid; /* TRUE: New sample data is available */ + volatile bool initialized; /* TRUE: The initialization packet has been sent */ + uint8_t ifno; /* Interface number */ + uint8_t nwaiters; /* Number of threads waiting for controller data */ + sem_t waitsem; /* Used to wait for controller data */ + int16_t crefs; /* Reference count on the driver instance */ + sem_t exclsem; /* Used to maintain mutual exclusive access */ + struct work_s work; /* For interacting with the worker thread */ + FAR uint8_t *tbuffer; /* The allocated transfer buffer */ + FAR uint8_t obuffer[20]; /* The fixed output transfer buffer */ + size_t tbuflen; /* Size of the allocated transfer buffer */ + usbhost_ep_t epin; /* IN endpoint */ + usbhost_ep_t epout; /* OUT endpoint */ + pid_t pollpid; /* PID of the poll task */ + size_t out_seq_num; /* The sequence number for outgoing packets */ + struct xbox_controller_buttonstate_s rpt; /* The latest report out of the controller. */ +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* Semaphores */ + +static void usbhost_takesem(sem_t *sem); +#define usbhost_givesem(s) sem_post(s); + +/* Memory allocation services */ + +static inline FAR struct usbhost_state_s *usbhost_allocclass(void); +static inline void usbhost_freeclass(FAR struct usbhost_state_s *usbclass); + +/* Device name management */ + +static int usbhost_allocdevno(FAR struct usbhost_state_s *priv); +static void usbhost_freedevno(FAR struct usbhost_state_s *priv); +static inline void usbhost_mkdevname(FAR struct usbhost_state_s *priv, + FAR char *devname); + +/* Worker thread actions */ + +static void usbhost_destroy(FAR void *arg); +static void usbhost_notify(FAR struct usbhost_state_s *priv); +static int usbhost_xboxcontroller_poll(int argc, char *argv[]); + +/* Helpers for usbhost_connect() */ + +static inline int usbhost_cfgdesc(FAR struct usbhost_state_s *priv, + FAR const uint8_t *configdesc, + int desclen); +static inline int usbhost_devinit(FAR struct usbhost_state_s *priv); + +/* (Little Endian) Data helpers */ + +static inline uint16_t usbhost_getle16(const uint8_t *val); +static inline void usbhost_putle16(uint8_t *dest, uint16_t val); +static inline uint32_t usbhost_getle32(const uint8_t *val); +#if 0 /* Not used */ +static void usbhost_putle32(uint8_t *dest, uint32_t val); +#endif + +/* Transfer descriptor memory management */ + +static inline int usbhost_talloc(FAR struct usbhost_state_s *priv); +static inline int usbhost_tfree(FAR struct usbhost_state_s *priv); + +/* struct usbhost_registry_s methods */ + +static struct usbhost_class_s *usbhost_create(FAR struct usbhost_hubport_s *hport, + FAR const struct usbhost_id_s *id); + +/* struct usbhost_class_s methods */ + +static int usbhost_connect(FAR struct usbhost_class_s *usbclass, + FAR const uint8_t *configdesc, int desclen); +static int usbhost_disconnected(FAR struct usbhost_class_s *usbclass); + +/* Driver methods. We export the controller as a standard character driver */ + +static int usbhost_open(FAR struct file *filep); +static int usbhost_close(FAR struct file *filep); +static ssize_t usbhost_read(FAR struct file *filep, + FAR char *buffer, size_t len); +static ssize_t usbhost_write(FAR struct file *filep, + FAR const char *buffer, size_t len); +static int usbhost_ioctl(FAR struct file* filep, int cmd, unsigned long arg); +#ifndef CONFIG_DISABLE_POLL +static int usbhost_poll(FAR struct file *filep, FAR struct pollfd *fds, + bool setup); +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* This structure provides the registry entry ID information that will be + * used to associate the USB class driver to a connected USB device. + */ + +static const const struct usbhost_id_s g_xboxcontroller_id[] = +{ + /* XBox One classic controller */ + { + USB_CLASS_VENDOR_SPEC, /* base -- Must be one of the USB_CLASS_* definitions in usb.h */ + 0x0047, /* subclass -- depends on the device */ + 0x00d0, /* proto -- depends on the device */ + 0x045E, /* vid */ + 0x02DD /* pid */ + }, + /* XBox One S controller */ + { + USB_CLASS_VENDOR_SPEC, /* base -- Must be one of the USB_CLASS_* definitions in usb.h */ + 0x0047, /* subclass -- depends on the device */ + 0x00d0, /* proto -- depends on the device */ + 0x045E, /* vid */ + 0x02EA /* pid */ + } +}; + +/* This is the USB host storage class's registry entry */ + +static struct usbhost_registry_s g_xboxcontroller = +{ + NULL, /* flink */ + usbhost_create, /* create */ + 2, /* nids */ + g_xboxcontroller_id /* id[] */ +}; + +/* The configuration information for the block file device. */ + +static const struct file_operations g_xboxcontroller_fops = +{ + usbhost_open, /* open */ + usbhost_close, /* close */ + usbhost_read, /* read */ + usbhost_write, /* write */ + 0, /* seek */ + usbhost_ioctl /* ioctl */ +#ifndef CONFIG_DISABLE_POLL + , usbhost_poll /* poll */ +#endif +}; + +/* This is a bitmap that is used to allocate device names /dev/xboxa-z. */ + +static uint32_t g_devinuse; + +/* The following are used to managed the class creation operation */ + +static sem_t g_exclsem; /* For mutually exclusive thread creation */ +static sem_t g_syncsem; /* Thread data passing interlock */ +static struct usbhost_state_s *g_priv; /* Data passed to thread */ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: usbhost_takesem + * + * Description: + * This is just a wrapper to handle the annoying behavior of semaphore + * waits that return due to the receipt of a signal. + * + ****************************************************************************/ + +static void usbhost_takesem(sem_t *sem) +{ + /* Take the semaphore (perhaps waiting) */ + + while (sem_wait(sem) != 0) + { + /* The only case that an error should occur here is if the wait was + * awakened by a signal. + */ + + ASSERT(errno == EINTR); + } +} + +/**************************************************************************** + * Name: usbhost_allocclass + * + * Description: + * This is really part of the logic that implements the create() method + * of struct usbhost_registry_s. This function allocates memory for one + * new class instance. + * + * Input Parameters: + * None + * + * Returned Values: + * On success, this function will return a non-NULL instance of struct + * usbhost_class_s. NULL is returned on failure; this function will + * will fail only if there are insufficient resources to create another + * USB host class instance. + * + ****************************************************************************/ + +static inline FAR struct usbhost_state_s *usbhost_allocclass(void) +{ + FAR struct usbhost_state_s *priv; + + DEBUGASSERT(!up_interrupt_context()); + priv = (FAR struct usbhost_state_s *)kmm_malloc(sizeof(struct usbhost_state_s)); + uinfo("Allocated: %p\n", priv); + return priv; +} + +/**************************************************************************** + * Name: usbhost_freeclass + * + * Description: + * Free a class instance previously allocated by usbhost_allocclass(). + * + * Input Parameters: + * usbclass - A reference to the class instance to be freed. + * + * Returned Values: + * None + * + ****************************************************************************/ + +static inline void usbhost_freeclass(FAR struct usbhost_state_s *usbclass) +{ + DEBUGASSERT(usbclass != NULL); + + /* Free the class instance (perhaps calling sched_kmm_free() in case we are + * executing from an interrupt handler. + */ + + uinfo("Freeing: %p\n", usbclass); + kmm_free(usbclass); +} + +/**************************************************************************** + * Name: Device name management + * + * Description: + * Some tiny functions to coordinate management of device names. + * + ****************************************************************************/ + +static int usbhost_allocdevno(FAR struct usbhost_state_s *priv) +{ + irqstate_t flags; + int devno; + + flags = enter_critical_section(); + for (devno = 0; devno < 26; devno++) + { + uint32_t bitno = 1 << devno; + if ((g_devinuse & bitno) == 0) + { + g_devinuse |= bitno; + priv->devchar = 'a' + devno; + leave_critical_section(flags); + return OK; + } + } + + leave_critical_section(flags); + return -EMFILE; +} + +static void usbhost_freedevno(FAR struct usbhost_state_s *priv) +{ + int devno = 'a' - priv->devchar; + + if (devno >= 0 && devno < 26) + { + irqstate_t flags = enter_critical_section(); + g_devinuse &= ~(1 << devno); + leave_critical_section(flags); + } +} + +static inline void usbhost_mkdevname(FAR struct usbhost_state_s *priv, + FAR char *devname) +{ + (void)snprintf(devname, DEV_NAMELEN, DEV_FORMAT, priv->devchar); +} + +/**************************************************************************** + * Name: usbhost_destroy + * + * Description: + * The USB device has been disconnected and the reference count on the USB + * host class instance has gone to 1.. Time to destroy the USB host class + * instance. + * + * Input Parameters: + * arg - A reference to the class instance to be destroyed. + * + * Returned Values: + * None + * + ****************************************************************************/ + +static void usbhost_destroy(FAR void *arg) +{ + FAR struct usbhost_state_s *priv = (FAR struct usbhost_state_s *)arg; + FAR struct usbhost_hubport_s *hport; + char devname[DEV_NAMELEN]; + + DEBUGASSERT(priv != NULL && priv->usbclass.hport != NULL); + uinfo("crefs: %d\n", priv->crefs); + + hport = priv->usbclass.hport; + + DEBUGASSERT(hport->drvr); + + uinfo("crefs: %d\n", priv->crefs); + + /* Unregister the driver */ + + uinfo("Unregister driver\n"); + usbhost_mkdevname(priv, devname); + (void)unregister_driver(devname); + + /* Release the device name used by this connection */ + + usbhost_freedevno(priv); + + /* Free the interrupt endpoints */ + + if (priv->epin) + { + DRVR_EPFREE(hport->drvr, priv->epin); + } + + /* Free any transfer buffers */ + + usbhost_tfree(priv); + + /* Destroy the semaphores */ + + sem_destroy(&priv->exclsem); + sem_destroy(&priv->waitsem); + + /* Disconnect the USB host device */ + + DRVR_DISCONNECT(hport->drvr, hport); + + /* Free the function address assigned to this device */ + + usbhost_devaddr_destroy(hport, hport->funcaddr); + hport->funcaddr = 0; + + /* And free the class instance. */ + + usbhost_freeclass(priv); +} + +/**************************************************************************** + * Name: usbhost_notify + * + * Description: + * Wake any threads waiting for controller data + * + * Input Paramters: + * priv - A reference to the controller state structure. + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void usbhost_notify(FAR struct usbhost_state_s *priv) +{ +#ifndef CONFIG_DISABLE_POLL + int i; +#endif + + /* If there are threads waiting for read data, then signal one of them + * that the read data is available. + */ + + if (priv->nwaiters > 0) + { + sem_post(&priv->waitsem); + } + + /* If there are threads waiting on poll() for controller 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. + */ + +#ifndef CONFIG_DISABLE_POLL + for (i = 0; i < CONFIG_XBOXCONTROLLER_NPOLLWAITERS; i++) + { + struct pollfd *fds = priv->fds[i]; + if (fds) + { + fds->revents |= POLLIN; + iinfo("Report events: %02x\n", fds->revents); + sem_post(fds->sem); + } + } +#endif +} + +/**************************************************************************** + * Name: usbhost_xboxcontroller_poll + * + * Description: + * Periodically check for new controller data. + * + * Input Parameters: + * arg - A reference to the class instance to be destroyed. + * + * Returned Values: + * None + * + ****************************************************************************/ + +static int usbhost_xboxcontroller_poll(int argc, char *argv[]) +{ + FAR struct usbhost_state_s *priv; + FAR struct usbhost_hubport_s *hport; + irqstate_t flags; +#if defined(CONFIG_DEBUG_USB) && defined(CONFIG_DEBUG_INFO) + unsigned int npolls = 0; +#endif + unsigned int nerrors = 0; + ssize_t nbytes; + int ret = OK; + + /* Synchronize with the start-up logic. Get the private instance, re-start + * the start-up logic, and wait a bit to make sure that all of the class + * creation logic has a chance to run to completion. + * + * NOTE: that the reference count is *not* incremented here. When the driver + * structure was created, it was created with a reference count of one. This + * thread is responsible for that count. The count will be decrement when + * this thread exits. + */ + + priv = g_priv; + DEBUGASSERT(priv != NULL && priv->usbclass.hport != NULL); + hport = priv->usbclass.hport; + + priv->polling = true; + usbhost_givesem(&g_syncsem); + sleep(1); + + /* Loop here until the device is disconnected */ + + uinfo("Entering poll loop\n"); + + while (!priv->disconnected) + { + /* Read the next ccontroller report. We will stall here until the + * controller sends data. + */ + + nbytes = DRVR_TRANSFER(hport->drvr, priv->epin, + priv->tbuffer, priv->tbuflen); + + /* Check for errors -- Bail if an excessive number of consecutive + * errors are encountered. + */ + + if (nbytes < 0) + { + /* If DRVR_TRANSFER() returns EAGAIN, that simply means that + * the devices was not ready and has NAK'ed the transfer. That + * should not be treated as an error (unless it persists for a + * long time). + */ + + if (nbytes != -EAGAIN) + { + + uerr("ERROR: DRVR_TRANSFER returned: %d/%u\n", + (int)nbytes, nerrors); + + if (++nerrors > 200) + { + uerr(" Too many errors... aborting: %d\n", nerrors); + ret = (int)nbytes; + break; + } + } + } + + /* The report was received correctly. */ + + else + { + + /* Success, reset the error counter */ + + nerrors = 0; + + /* The type of message is in the first byte */ + switch (priv->tbuffer[0]) + { + + case USBHOST_WAITING_CONNECTION: + + /* Send the initialization message when we received the + * the first waiting connection message. + */ + + if (!priv->initialized) { + + /* Get exclusive access to the controller state data */ + + usbhost_takesem(&priv->exclsem); + + priv->tbuffer[0] = 0x05; + priv->tbuffer[1] = 0x20; + priv->tbuffer[2] = priv->out_seq_num++; + priv->tbuffer[3] = 0x01; + priv->tbuffer[4] = 0x00; + nbytes = DRVR_TRANSFER(hport->drvr, priv->epout, + priv->tbuffer, 5); + priv->initialized = true; + + /* Release our lock on the state structure */ + + usbhost_givesem(&priv->exclsem); + } + + break; + + case USBHOST_GUIDE_BUTTON_STATUS: + + /* Get exclusive access to the controller state data */ + + usbhost_takesem(&priv->exclsem); + + /* Read the data out of the controller report. */ + + priv->rpt.guide = (priv->tbuffer[XBOX_BUTTON_GUIDE_INDEX] != 0) ? true : false; + + priv->valid = true; + + /* The One X controller requires an ACK of the guide button status message. */ + + if (priv->tbuffer[1] == 0x30) + { + + static const uint8_t guide_button_report_ack[] = { + 0x01, 0x20, 0x00, 0x09, 0x00, 0x07, 0x20, 0x02, + 0x00, 0x00, 0x00, 0x00, 0x00 + }; + + /* Remember the input packet sequence number. */ + + uint8_t seq_num = priv->tbuffer[2]; + + /* Copy the ACK packet into the transfer buffer. */ + + memcpy(priv->tbuffer, guide_button_report_ack, sizeof(guide_button_report_ack)); + + /* Ensure the sequence number is the same as the input packet. */ + + priv->tbuffer[2] = seq_num; + + /* Perform the transfer. */ + + nbytes = DRVR_TRANSFER(hport->drvr, priv->epout, + priv->tbuffer, sizeof(guide_button_report_ack)); + } + + /* Notify any waiters that new controller data is available */ + + usbhost_notify(priv); + + /* Release our lock on the state structure */ + + usbhost_givesem(&priv->exclsem); + + break; + + case USBHOST_BUTTON_DATA: + + /* Ignore the controller data if no task has opened the driver. */ + + if (priv->open) + { + /* Get exclusive access to the controller state data */ + + usbhost_takesem(&priv->exclsem); + + /* Read the data out of the controller report. */ + + priv->rpt.sync = XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_SYNC_INDEX, XBOX_BUTTON_SYNC_MASK); + priv->rpt.start = XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_START_INDEX, XBOX_BUTTON_START_MASK); + priv->rpt.back = XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_BACK_INDEX, XBOX_BUTTON_BACK_MASK); + priv->rpt.a = XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_A_INDEX, XBOX_BUTTON_A_MASK); + priv->rpt.b = XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_B_INDEX, XBOX_BUTTON_B_MASK); + priv->rpt.x = XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_X_INDEX, XBOX_BUTTON_X_MASK); + priv->rpt.y = XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_Y_INDEX, XBOX_BUTTON_Y_MASK); + priv->rpt.dpad_up = XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_DPAD_UP_INDEX, XBOX_BUTTON_DPAD_UP_MASK); + priv->rpt.dpad_down = XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_DPAD_DOWN_INDEX, XBOX_BUTTON_DPAD_DOWN_MASK); + priv->rpt.dpad_left = XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_DPAD_LEFT_INDEX, XBOX_BUTTON_DPAD_LEFT_MASK); + priv->rpt.dpad_right = XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_DPAD_RIGHT_INDEX, XBOX_BUTTON_DPAD_RIGHT_MASK); + priv->rpt.bumper_left = XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_BUMPER_LEFT_INDEX, XBOX_BUTTON_BUMPER_LEFT_MASK); + priv->rpt.bumper_right = XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_BUMPER_RIGHT_INDEX, XBOX_BUTTON_BUMPER_RIGHT_MASK); + priv->rpt.stick_click_left = XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_STICK_LEFT_INDEX, XBOX_BUTTON_STICK_LEFT_MASK); + priv->rpt.stick_click_right = XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_STICK_RIGHT_INDEX, XBOX_BUTTON_STICK_RIGHT_MASK); + priv->rpt.trigger_left = ((int16_t*)(priv->tbuffer))[XBOX_BUTTON_TRIGGER_LEFT]; + priv->rpt.trigger_right = ((int16_t*)(priv->tbuffer))[XBOX_BUTTON_TRIGGER_RIGHT]; + priv->rpt.stick_left_x = ((int16_t*)(priv->tbuffer))[XBOX_BUTTON_STICK_LEFT_X]; + priv->rpt.stick_left_y = ((int16_t*)(priv->tbuffer))[XBOX_BUTTON_STICK_LEFT_Y]; + priv->rpt.stick_right_x = ((int16_t*)(priv->tbuffer))[XBOX_BUTTON_STICK_RIGHT_X]; + priv->rpt.stick_right_y = ((int16_t*)(priv->tbuffer))[XBOX_BUTTON_STICK_RIGHT_Y]; + + priv->valid = true; + + /* Notify any waiters that new controller data is available */ + + usbhost_notify(priv); + + /* Release our lock on the state structure */ + + usbhost_givesem(&priv->exclsem); + } + + break; + + default: + + uinfo("Received messge type: %x\n", priv->tbuffer[0]); + + } + + } + + /* If USB debug is on, then provide some periodic indication that + * polling is still happening. + */ + +#if defined(CONFIG_DEBUG_USB) && defined(CONFIG_DEBUG_INFO) + npolls++; + if ((npolls & 31) == 0) + { + uinfo("Still polling: %d\n", npolls); + } +#endif + } + + /* We get here when the driver is removed.. or when too many errors have + * been encountered. + * + * Make sure that we have exclusive access to the private data structure. + * There may now be other tasks with the character driver open and actively + * trying to interact with the class driver. + */ + + usbhost_takesem(&priv->exclsem); + + /* Indicate that we are no longer running and decrement the reference + * count held by this thread. If there are no other users of the class, + * we can destroy it now. Otherwise, we have to wait until the all + * of the file descriptors are closed. + */ + + uinfo("Controller removed, polling halted\n"); + + flags = enter_critical_section(); + priv->polling = false; + + /* Decrement the reference count held by this thread. */ + + DEBUGASSERT(priv->crefs > 0); + priv->crefs--; + + /* There are two possibilities: + * 1) The reference count is greater than zero. This means that there + * are still open references to the controller driver. In this case + * we need to wait until usbhost_close() is called and all of the + * open driver references are decremented. Then usbhost_destroy() can + * be called from usbhost_close(). + * 2) The reference count is now zero. This means that there are no + * further open references and we can call usbhost_destroy() now. + */ + + if (priv->crefs < 1) + { + /* Unregister the driver and destroy the instance (while we hold + * the semaphore!) + */ + + usbhost_destroy(priv); + } + else + { + /* No, we will destroy the driver instance when it is final open + * reference is closed + */ + + usbhost_givesem(&priv->exclsem); + } + + leave_critical_section(flags); + return ret; +} + +/**************************************************************************** + * Name: usbhost_sample + * + * Description: + * Check if new controller data is available + * + * Input Parameters: + * priv - controller state instance + * sample - The location to return the sample data + * + ****************************************************************************/ + +static int usbhost_sample(FAR struct usbhost_state_s *priv, + FAR struct xbox_controller_buttonstate_s *sample) +{ + irqstate_t flags; + int ret = -EAGAIN; + + /* Interrupts me be disabled when this is called to (1) prevent posting + * of semaphores from interrupt handlers, and (2) to prevent sampled data + * from changing until it has been reported. + */ + + flags = enter_critical_section(); + + /* Is there new mouse data available? */ + + if (priv->valid) + { + /* Return a copy of the sampled data. */ + + memcpy(sample, &priv->rpt, sizeof(struct xbox_controller_buttonstate_s)); + + /* The sample has been reported and is no longer valid */ + + priv->valid = false; + ret = OK; + } + + leave_critical_section(flags); + return ret; +} + +/**************************************************************************** + * Name: usbhost_waitsample + * + * Description: + * Wait for the next valid controller sample + * + * Input Parameters: + * priv - controller state instance + * sample - The location to return the sample data + * + ****************************************************************************/ + +static int usbhost_waitsample(FAR struct usbhost_state_s *priv, + FAR struct xbox_controller_buttonstate_s *sample) +{ + irqstate_t flags; + int ret; + + /* Interrupts me be disabled when this is called to (1) prevent posting + * of semaphores from interrupt handlers, and (2) to prevent sampled data + * from changing until it has been reported. + * + * In addition, we will also disable pre-emption to prevent other threads + * from getting control while we muck with the semaphores. + */ + + sched_lock(); + flags = enter_critical_section(); + + /* Now release the semaphore that manages mutually exclusive access to + * the device structure. This may cause other tasks to become ready to + * run, but they cannot run yet because pre-emption is disabled. + */ + + sem_post(&priv->exclsem); + + /* Try to get the a sample... if we cannot, then wait on the semaphore + * that is posted when new sample data is available. + */ + + while (usbhost_sample(priv, sample) < 0) + { + /* Wait for a change in the HIDMOUSE state */ + + iinfo("Waiting..\n"); + priv->nwaiters++; + ret = sem_wait(&priv->waitsem); + priv->nwaiters--; + + if (ret < 0) + { + /* If we are awakened by a signal, then we need to return + * the failure now. + */ + + ierr("ERROR: sem_wait: %d\n", errno); + DEBUGASSERT(errno == EINTR); + ret = -EINTR; + goto errout; + } + + /* Did the controller become disconnected while we were waiting */ + + if (priv->disconnected) + { + ret = -ENODEV; + goto errout; + } + } + + iinfo("Sampled\n"); + + /* Re-acquire the semaphore that manages mutually exclusive access to + * the device structure. We may have to wait here. But we have our sample. + * Interrupts and pre-emption will be re-enabled while we wait. + */ + + ret = sem_wait(&priv->exclsem); + +errout: + /* Then re-enable interrupts. We might get interrupt here and there + * could be a new sample. But no new threads will run because we still + * have pre-emption disabled. + */ + + leave_critical_section(flags); + + /* Restore pre-emption. We might get suspended here but that is okay + * because we already have our sample. Note: this means that if there + * were two threads reading from the HIDMOUSE for some reason, the data + * might be read out of order. + */ + + sched_unlock(); + return ret; +} + +/**************************************************************************** + * Name: usbhost_cfgdesc + * + * Description: + * This function implements the connect() method of struct + * usbhost_class_s. This method is a callback into the class + * implementation. It is used to provide the device's configuration + * descriptor to the class so that the class may initialize properly + * + * Input Parameters: + * priv - The USB host class instance. + * configdesc - A pointer to a uint8_t buffer container the configuration + * descriptor. + * desclen - The length in bytes of the configuration descriptor. + * + * Returned Values: + * On success, zero (OK) is returned. On a failure, a negated errno value is + * returned indicating the nature of the failure + * + * Assumptions: + * This function will *not* be called from an interrupt handler. + * + ****************************************************************************/ + +static inline int usbhost_cfgdesc(FAR struct usbhost_state_s *priv, + FAR const uint8_t *configdesc, int desclen) +{ + FAR struct usbhost_hubport_s *hport; + FAR struct usb_cfgdesc_s *cfgdesc; + FAR struct usb_desc_s *desc; + FAR struct usbhost_epdesc_s epindesc; + FAR struct usbhost_epdesc_s epoutdesc; + int remaining; + uint8_t found = 0; + bool done = false; + int ret; + + DEBUGASSERT(priv != NULL && priv->usbclass.hport && + configdesc != NULL && desclen >= sizeof(struct usb_cfgdesc_s)); + hport = priv->usbclass.hport; + + /* Keep the compiler from complaining about uninitialized variables */ + + memset(&epindesc, 0, sizeof(struct usbhost_epdesc_s)); + memset(&epoutdesc, 0, sizeof(struct usbhost_epdesc_s)); + + /* Verify that we were passed a configuration descriptor */ + + cfgdesc = (FAR struct usb_cfgdesc_s *)configdesc; + if (cfgdesc->type != USB_DESC_TYPE_CONFIG) + { + return -EINVAL; + } + + /* Get the total length of the configuration descriptor (little endian). + * It might be a good check to get the number of interfaces here too. + */ + + remaining = (int)usbhost_getle16(cfgdesc->totallen); + + /* Skip to the next entry descriptor */ + + configdesc += cfgdesc->len; + remaining -= cfgdesc->len; + + /* Loop where there are more dscriptors to examine */ + + while (remaining >= sizeof(struct usb_desc_s) && !done) + { + /* What is the next descriptor? */ + + desc = (FAR struct usb_desc_s *)configdesc; + switch (desc->type) + { + /* Interface descriptor. We really should get the number of endpoints + * from this descriptor too. + */ + + case USB_DESC_TYPE_INTERFACE: + { + uinfo("Interface descriptor\n"); + DEBUGASSERT(remaining >= USB_SIZEOF_IFDESC); + + /* Did we already find what we needed from a preceding interface? */ + + if ((found & USBHOST_ALLFOUND) == USBHOST_ALLFOUND) + { + /* Yes.. then break out of the loop and use the preceding + * interface. + */ + + done = true; + } + else + { + /* Otherwise, discard any endpoints previously found */ + + found = USBHOST_IFFOUND; + } + } + break; + + /* Endpoint descriptor. Here, we expect two bulk endpoints, an IN + * and an OUT. + */ + + case USB_DESC_TYPE_ENDPOINT: + { + FAR struct usb_epdesc_s *epdesc = (FAR struct usb_epdesc_s *)configdesc; + + uinfo("Endpoint descriptor\n"); + DEBUGASSERT(remaining >= USB_SIZEOF_EPDESC); + + /* Check for a interrupt endpoint. */ + + if ((epdesc->attr & USB_EP_ATTR_XFERTYPE_MASK) == USB_EP_ATTR_XFER_INT) + { + /* Yes.. it is a interrupt endpoint. IN or OUT? */ + + if (USB_ISEPOUT(epdesc->addr)) + { + /* It is an OUT interrupt endpoint. There should be only one + * interrupt OUT endpoint. + */ + + if ((found & USBHOST_EPOUTFOUND) != 0) + { + /* Oops.. more than one endpoint. We don't know + * what to do with this. + */ + + return -EINVAL; + } + found |= USBHOST_EPOUTFOUND; + + /* Save the bulk OUT endpoint information */ + + epoutdesc.hport = hport; + epoutdesc.addr = epdesc->addr & USB_EP_ADDR_NUMBER_MASK; + epoutdesc.in = false; + epoutdesc.xfrtype = USB_EP_ATTR_XFER_INT; + epoutdesc.interval = epdesc->interval; + epoutdesc.mxpacketsize = usbhost_getle16(epdesc->mxpacketsize); + uerr("Interrupt OUT EP addr:%d mxpacketsize:%d\n", + epoutdesc.addr, epoutdesc.mxpacketsize); + } + else + { + /* It is an IN interrupt endpoint. There should be only one + * interrupt IN endpoint. + */ + + if ((found & USBHOST_EPINFOUND) != 0) + { + /* Oops.. more than one endpoint. We don't know + * what to do with this. + */ + + return -EINVAL; + } + + found |= USBHOST_EPINFOUND; + + /* Save the bulk IN endpoint information */ + + epindesc.hport = hport; + epindesc.addr = epdesc->addr & USB_EP_ADDR_NUMBER_MASK; + epindesc.in = true; + epindesc.xfrtype = USB_EP_ATTR_XFER_INT; + epindesc.interval = epdesc->interval; + epindesc.mxpacketsize = usbhost_getle16(epdesc->mxpacketsize); + uerr("Interrupt IN EP addr:%d mxpacketsize:%d\n", + epindesc.addr, epindesc.mxpacketsize); + } + } + } + break; + + /* Other descriptors are just ignored for now */ + + default: + break; + } + + /* If we found everything we need with this interface, then break out + * of the loop early. + */ + + if (found == USBHOST_ALLFOUND) + { + done=true; + } + + /* Increment the address of the next descriptor */ + + configdesc += desc->len; + remaining -= desc->len; + } + + /* Sanity checking... did we find all of things that we need? */ + + if (found != USBHOST_ALLFOUND) + { + uerr("ERROR: Found IF:%s BIN:%s EPOUT:%s\n", + (found & USBHOST_IFFOUND) != 0 ? "YES" : "NO", + (found & USBHOST_EPINFOUND) != 0 ? "YES" : "NO", + (found & USBHOST_EPOUTFOUND) != 0 ? "YES" : "NO"); + return -EINVAL; + } + + /* We are good... Allocate the endpoints */ + + ret = DRVR_EPALLOC(hport->drvr, &epoutdesc, &priv->epout); + if (ret < 0) + { + uerr("ERROR: Failed to allocate Interrupt OUT endpoint\n"); + return ret; + } + + ret = DRVR_EPALLOC(hport->drvr, &epindesc, &priv->epin); + if (ret < 0) + { + uerr("ERROR: Failed to allocate Interrupt IN endpoint\n"); + (void)DRVR_EPFREE(hport->drvr, priv->epout); + return ret; + } + + uinfo("Endpoints allocated\n"); + return OK; +} + +/**************************************************************************** + * Name: usbhost_devinit + * + * Description: + * The USB device has been successfully connected. This completes the + * initialization operations. It is first called after the + * configuration descriptor has been received. + * + * This function is called from the connect() method. This function always + * executes on the thread of the caller of connect(). + * + * Input Parameters: + * priv - A reference to the class instance. + * + * Returned Values: + * None + * + ****************************************************************************/ + +static inline int usbhost_devinit(FAR struct usbhost_state_s *priv) +{ + char devname[DEV_NAMELEN]; + int ret = OK; + + /* Set aside a transfer buffer for exclusive use by the class driver */ + + ret = usbhost_talloc(priv); + if (ret < 0) + { + uerr("ERROR: Failed to allocate transfer buffer\n"); + return ret; + } + + /* Increment the reference count. This will prevent usbhost_destroy() from + * being called asynchronously if the device is removed. + */ + + priv->crefs++; + DEBUGASSERT(priv->crefs == 2); + + /* Start a worker task to poll the USB device. It would be nice to used the + * the NuttX worker thread to do this, but this task needs to wait for events + * and activities on the worker thread should not involve significant waiting. + * Having a dedicated thread is more efficient in this sense, but requires more + * memory resources, primarily for the dedicated stack (CONFIG_XBOXCONTROLLER_STACKSIZE). + */ + + /* The inputs to a task started by kernel_thread() are very awkward for this + * purpose. They are really designed for command line tasks (argc/argv). So + * the following is kludge pass binary data when the controller poll task + * is started. + * + * First, make sure we have exclusive access to g_priv (what is the likelihood + * of this being used? About zero, but we protect it anyway). + */ + + usbhost_takesem(&g_exclsem); + g_priv = priv; + + uinfo("Starting thread\n"); + priv->pollpid = kernel_thread("xbox", CONFIG_XBOXCONTROLLER_DEFPRIO, + CONFIG_XBOXCONTROLLER_STACKSIZE, + (main_t)usbhost_xboxcontroller_poll, (FAR char * const *)NULL); + if (priv->pollpid == ERROR) + { + /* Failed to started the poll thread... probably due to memory resources */ + + usbhost_givesem(&g_exclsem); + ret = -ENOMEM; + goto errout; + } + + /* Now wait for the poll task to get properly initialized */ + + usbhost_takesem(&g_syncsem); + usbhost_givesem(&g_exclsem); + + /* Configure the device */ + + /* Register the driver */ + + uinfo("Register block driver\n"); + usbhost_mkdevname(priv, devname); + ret = register_driver(devname, &g_xboxcontroller_fops, 0666, priv); + + /* Check if we successfully initialized. We now have to be concerned + * about asynchronous modification of crefs because the block + * driver has been registerd. + */ + +errout: + usbhost_takesem(&priv->exclsem); + priv->crefs--; + usbhost_givesem(&priv->exclsem); + return ret; +} + +/**************************************************************************** + * Name: usbhost_getle16 + * + * Description: + * Get a (possibly unaligned) 16-bit little endian value. + * + * Input Parameters: + * val - A pointer to the first byte of the little endian value. + * + * Returned Values: + * A uint16_t representing the whole 16-bit integer value + * + ****************************************************************************/ + +static inline uint16_t usbhost_getle16(const uint8_t *val) +{ + return (uint16_t)val[1] << 8 | (uint16_t)val[0]; +} + +/**************************************************************************** + * Name: usbhost_putle16 + * + * Description: + * Put a (possibly unaligned) 16-bit little endian value. + * + * Input Parameters: + * dest - A pointer to the first byte to save the little endian value. + * val - The 16-bit value to be saved. + * + * Returned Values: + * None + * + ****************************************************************************/ + +static void usbhost_putle16(uint8_t *dest, uint16_t val) +{ + dest[0] = val & 0xff; /* Little endian means LS byte first in byte stream */ + dest[1] = val >> 8; +} + +/**************************************************************************** + * Name: usbhost_getle32 + * + * Description: + * Get a (possibly unaligned) 32-bit little endian value. + * + * Input Parameters: + * dest - A pointer to the first byte to save the big endian value. + * val - The 32-bit value to be saved. + * + * Returned Values: + * None + * + ****************************************************************************/ + +static inline uint32_t usbhost_getle32(const uint8_t *val) +{ + /* Little endian means LS halfword first in byte stream */ + + return (uint32_t)usbhost_getle16(&val[2]) << 16 | (uint32_t)usbhost_getle16(val); +} + +/**************************************************************************** + * Name: usbhost_putle32 + * + * Description: + * Put a (possibly unaligned) 32-bit little endian value. + * + * Input Parameters: + * dest - A pointer to the first byte to save the little endian value. + * val - The 32-bit value to be saved. + * + * Returned Values: + * None + * + ****************************************************************************/ + +#if 0 /* Not used */ +static void usbhost_putle32(uint8_t *dest, uint32_t val) +{ + /* Little endian means LS halfword first in byte stream */ + + usbhost_putle16(dest, (uint16_t)(val & 0xffff)); + usbhost_putle16(dest+2, (uint16_t)(val >> 16)); +} +#endif + +/**************************************************************************** + * Name: usbhost_talloc + * + * Description: + * Allocate transfer buffer memory. + * + * Input Parameters: + * priv - A reference to the class instance. + * + * Returned Values: + * On sucess, zero (OK) is returned. On failure, an negated errno value + * is returned to indicate the nature of the failure. + * + ****************************************************************************/ + +static inline int usbhost_talloc(FAR struct usbhost_state_s *priv) +{ + FAR struct usbhost_hubport_s *hport; + + DEBUGASSERT(priv != NULL && priv->usbclass.hport != NULL && + priv->tbuffer == NULL); + hport = priv->usbclass.hport; + + return DRVR_ALLOC(hport->drvr, &priv->tbuffer, &priv->tbuflen); +} + +/**************************************************************************** + * Name: usbhost_tfree + * + * Description: + * Free transfer buffer memory. + * + * Input Parameters: + * priv - A reference to the class instance. + * + * Returned Values: + * On sucess, zero (OK) is returned. On failure, an negated errno value + * is returned to indicate the nature of the failure. + * + ****************************************************************************/ + +static inline int usbhost_tfree(FAR struct usbhost_state_s *priv) +{ + FAR struct usbhost_hubport_s *hport; + int result = OK; + + DEBUGASSERT(priv != NULL && priv->usbclass.hport != NULL); + + if (priv->tbuffer) + { + hport = priv->usbclass.hport; + result = DRVR_FREE(hport->drvr, priv->tbuffer); + priv->tbuffer = NULL; + priv->tbuflen = 0; + } + + return result; +} + +/**************************************************************************** + * struct usbhost_registry_s methods + ****************************************************************************/ + +/**************************************************************************** + * Name: usbhost_create + * + * Description: + * This function implements the create() method of struct usbhost_registry_s. + * The create() method is a callback into the class implementation. It is + * used to (1) create a new instance of the USB host class state and to (2) + * bind a USB host driver "session" to the class instance. Use of this + * create() method will support environments where there may be multiple + * USB ports and multiple USB devices simultaneously connected. + * + * Input Parameters: + * hport - The hub hat manages the new class instance. + * id - In the case where the device supports multiple base classes, + * subclasses, or protocols, this specifies which to configure for. + * + * Returned Values: + * On success, this function will return a non-NULL instance of struct + * usbhost_class_s that can be used by the USB host driver to communicate + * with the USB host class. NULL is returned on failure; this function + * will fail only if the hport input parameter is NULL or if there are + * insufficient resources to create another USB host class instance. + * + ****************************************************************************/ + +static FAR struct usbhost_class_s *usbhost_create(FAR struct usbhost_hubport_s *hport, + FAR const struct usbhost_id_s *id) +{ + FAR struct usbhost_state_s *priv; + + /* Allocate a USB host class instance */ + + priv = usbhost_allocclass(); + if (priv) + { + /* Initialize the allocated storage class instance */ + + memset(priv, 0, sizeof(struct usbhost_state_s)); + + /* Assign a device number to this class instance */ + + if (usbhost_allocdevno(priv) == OK) + { + /* Initialize class method function pointers */ + + priv->usbclass.hport = hport; + priv->usbclass.connect = usbhost_connect; + priv->usbclass.disconnected = usbhost_disconnected; + + /* The initial reference count is 1... One reference is held by the driver */ + + priv->crefs = 1; + + /* Initialize semaphores (this works okay in the interrupt context) */ + + sem_init(&priv->exclsem, 0, 1); + sem_init(&priv->waitsem, 0, 0); + + /* The waitsem semaphore is used for signaling and, hence, should + * not have priority inheritance enabled. + */ + + sem_setprotocol(&priv->waitsem, SEM_PRIO_NONE); + + /* Return the instance of the USB class driver */ + + return &priv->usbclass; + } + } + + /* An error occurred. Free the allocation and return NULL on all failures */ + + if (priv) + { + usbhost_freeclass(priv); + } + return NULL; +} + +/**************************************************************************** + * struct usbhost_class_s methods + ****************************************************************************/ +/**************************************************************************** + * Name: usbhost_connect + * + * Description: + * This function implements the connect() method of struct + * usbhost_class_s. This method is a callback into the class + * implementation. It is used to provide the device's configuration + * descriptor to the class so that the class may initialize properly + * + * Input Parameters: + * usbclass - The USB host class entry previously obtained from a call to + * create(). + * configdesc - A pointer to a uint8_t buffer container the configuration + * descriptor. + * desclen - The length in bytes of the configuration descriptor. + * + * Returned Values: + * On success, zero (OK) is returned. On a failure, a negated errno value is + * returned indicating the nature of the failure + * + * NOTE that the class instance remains valid upon return with a failure. It is + * the responsibility of the higher level enumeration logic to call + * CLASS_DISCONNECTED to free up the class driver resources. + * + * Assumptions: + * - This function will *not* be called from an interrupt handler. + * - If this function returns an error, the USB host controller driver + * must call to DISCONNECTED method to recover from the error + * + ****************************************************************************/ + +static int usbhost_connect(FAR struct usbhost_class_s *usbclass, + FAR const uint8_t *configdesc, int desclen) +{ + FAR struct usbhost_state_s *priv = (FAR struct usbhost_state_s *)usbclass; + int ret; + + DEBUGASSERT(priv != NULL && + configdesc != NULL && + desclen >= sizeof(struct usb_cfgdesc_s)); + + /* Parse the configuration descriptor to get the endpoints */ + + ret = usbhost_cfgdesc(priv, configdesc, desclen); + if (ret < 0) + { + uerr("ERROR: usbhost_cfgdesc() failed: %d\n", ret); + } + else + { + /* Now configure the device and register the NuttX driver */ + + ret = usbhost_devinit(priv); + if (ret < 0) + { + uerr("ERROR: usbhost_devinit() failed: %d\n", ret); + } + } + + return ret; +} + +/**************************************************************************** + * Name: usbhost_disconnected + * + * Description: + * This function implements the disconnected() method of struct + * usbhost_class_s. This method is a callback into the class + * implementation. It is used to inform the class that the USB device has + * been disconnected. + * + * Input Parameters: + * usbclass - The USB host class entry previously obtained from a call to + * create(). + * + * Returned Values: + * On success, zero (OK) is returned. On a failure, a negated errno value + * is returned indicating the nature of the failure + * + * Assumptions: + * This function may be called from an interrupt handler. + * + ****************************************************************************/ + +static int usbhost_disconnected(struct usbhost_class_s *usbclass) +{ + FAR struct usbhost_state_s *priv = (FAR struct usbhost_state_s *)usbclass; + int i; + + DEBUGASSERT(priv != NULL); + + /* Set an indication to any users of the device that the device is no + * longer available. + */ + + priv->disconnected = true; + uinfo("Disconnected\n"); + + /* Are there a thread(s) waiting for controller data that will never come? */ + + for (i = 0; i < priv->nwaiters; i++) + { + /* Yes.. wake them up */ + + usbhost_givesem(&priv->waitsem); + } + + /* Possibilities: + * + * - Failure occurred before the controller poll task was started successfully. + * In this case, the disconnection will have to be handled on the worker + * task. + * - Failure occurred after the controller poll task was started successfully. In + * this case, the disconnection can be performed on the mouse poll thread. + */ + + if (priv->polling) + { + /* The polling task is still alive. Signal the mouse polling task. + * When that task wakes up, it will decrement the reference count and, + * perhaps, destroy the class instance. Then it will exit. + */ + + (void)kill(priv->pollpid, SIGALRM); + } + else + { + /* In the case where the failure occurs before the polling task was + * started. Now what? We are probably executing from an interrupt + * handler here. We will use the worker thread. This is kind of + * wasteful and begs for a re-design. + */ + + DEBUGASSERT(priv->work.worker == NULL); + (void)work_queue(HPWORK, &priv->work, usbhost_destroy, priv, 0); + } + + return OK; +} + +/**************************************************************************** + * Character driver methods + ****************************************************************************/ +/**************************************************************************** + * Name: usbhost_open + * + * Description: + * Standard character driver open method. + * + ****************************************************************************/ + +static int usbhost_open(FAR struct file *filep) +{ + FAR struct inode *inode; + FAR struct usbhost_state_s *priv; + irqstate_t flags; + int ret; + + uinfo("Entry\n"); + DEBUGASSERT(filep && filep->f_inode); + inode = filep->f_inode; + priv = inode->i_private; + + /* Make sure that we have exclusive access to the private data structure */ + + DEBUGASSERT(priv && priv->crefs > 0 && priv->crefs < USBHOST_MAX_CREFS); + usbhost_takesem(&priv->exclsem); + + /* Check if the controller device is still connected. We need to disable + * interrupts momentarily to assure that there are no asynchronous disconnect + * events. + */ + + flags = enter_critical_section(); + if (priv->disconnected) + { + /* No... the driver is no longer bound to the class. That means that + * the USB storage device is no longer connected. Refuse any further + * attempts to open the driver. + */ + + ret = -ENODEV; + } + else + { + /* Was the driver previously open? We need to perform special + * initialization on the first time that the driver is opened. + */ + + if (!priv->open) + { + /* Set the thresholding values so that the first button press + * will be reported. + */ + +#ifdef NEVER + priv->xlast = INVALID_POSITION_B16; + priv->ylast = INVALID_POSITION_B16; +#ifdef CONFIG_MOUSE_WHEEL + priv->wlast = INVALID_POSITION_B16; +#endif + /* Set the reported position to the center of the range */ + + priv->xaccum = (HIDMOUSE_XMAX_B16 >> 1); + priv->yaccum = (HIDMOUSE_YMAX_B16 >> 1); +#endif + } + + /* Otherwise, just increment the reference count on the driver */ + + priv->crefs++; + priv->open = true; + ret = OK; + } + + leave_critical_section(flags); + + usbhost_givesem(&priv->exclsem); + return ret; +} + +/**************************************************************************** + * Name: usbhost_close + * + * Description: + * Standard character driver close method. + * + ****************************************************************************/ + +static int usbhost_close(FAR struct file *filep) +{ + FAR struct inode *inode; + FAR struct usbhost_state_s *priv; + irqstate_t flags; + + uinfo("Entry\n"); + DEBUGASSERT(filep && filep->f_inode); + inode = filep->f_inode; + priv = inode->i_private; + + /* Decrement the reference count on the driver */ + + DEBUGASSERT(priv->crefs >= 1); + usbhost_takesem(&priv->exclsem); + + /* We need to disable interrupts momentarily to assure that there are no + * asynchronous poll or disconnect events. + */ + + flags = enter_critical_section(); + priv->crefs--; + + /* Check if the USB controller device is still connected. If the device is + * no longer connected, then unregister the driver and free the driver + * class instance. + */ + + if (priv->disconnected) + { + /* If the reference count is one or less then there are two + * possibilities: + * + * 1) It might be zero meaning that the polling thread has already + * exited and decremented its count. + * 2) If might be one meaning either that (a) the polling thread is still + * running and still holds a count, or (b) the polling thread has exited, + * but there is still an outstanding open reference. + */ + + if (priv->crefs == 0 || (priv->crefs == 1 && priv->polling)) + { + /* Yes.. In either case, then the driver is no longer open */ + + priv->open = false; + + /* Check if the USB keyboard device is still connected. */ + + if (priv->crefs == 0) + { + /* The polling thread is no longer running */ + + DEBUGASSERT(!priv->polling); + + /* If the device is no longer connected, unregister the driver + * and free the driver class instance. + */ + + usbhost_destroy(priv); + + /* Skip giving the semaphore... it is no longer valid */ + + leave_critical_section(flags); + return OK; + } + else /* if (priv->crefs == 1) */ + { + /* The polling thread is still running. Signal it so that it + * will wake up and call usbhost_destroy(). The particular + * signal that we use does not matter in this case. + */ + + (void)kill(priv->pollpid, SIGALRM); + } + } + } + + usbhost_givesem(&priv->exclsem); + leave_critical_section(flags); + return OK; +} + +/**************************************************************************** + * Name: usbhost_read + * + * Description: + * Standard character driver read method. + * + ****************************************************************************/ + +static ssize_t usbhost_read(FAR struct file *filep, FAR char *buffer, size_t len) +{ + FAR struct inode *inode; + FAR struct usbhost_state_s *priv; + FAR struct xbox_controller_buttonstate_s sample; + int ret; + + DEBUGASSERT(filep && filep->f_inode && buffer); + inode = filep->f_inode; + priv = inode->i_private; + + /* Make sure that we have exclusive access to the private data structure */ + + DEBUGASSERT(priv && priv->crefs > 0 && priv->crefs < USBHOST_MAX_CREFS); + usbhost_takesem(&priv->exclsem); + + /* Check if the controller is still connected. We need to disable interrupts + * momentarily to assure that there are no asynchronous disconnect events. + */ + + if (priv->disconnected) + { + /* No... the driver is no longer bound to the class. That means that + * the USB controller is no longer connected. Refuse any further attempts + * to access the driver. + */ + + ret = -ENODEV; + goto errout; + } + + /* Try to read sample data. */ + + ret = usbhost_sample(priv, &sample); + if (ret < 0) + { + /* Sample data is not available now. We would ave to wait to get + * receive sample data. If the user has specified the O_NONBLOCK + * option, then just return an error. + */ + + if (filep->f_oflags & O_NONBLOCK) + { + /* Yes.. then return a failure */ + + ret = -EAGAIN; + goto errout; + } + + /* Wait for sample data */ + + ret = usbhost_waitsample(priv, &sample); + ret = 0; + if (ret < 0) + { + /* We might have been awakened by a signal */ + + ierr("ERROR: usbhost_waitsample: %d\n", ret); + goto errout; + } + } + + /* We now have sampled controller data that we can report to the caller. */ + + memcpy(buffer, &sample, sizeof(struct xbox_controller_buttonstate_s)); + + ret = sizeof(struct xbox_controller_buttonstate_s); + +errout: + usbhost_givesem(&priv->exclsem); + iinfo("Returning: %d\n", ret); + return (ssize_t)ret; +} + +/**************************************************************************** + * Name: usbhost_write + * + * Description: + * Standard character driver write method. + * + ****************************************************************************/ + +static ssize_t usbhost_write(FAR struct file *filep, FAR const char *buffer, + size_t len) +{ + + /* Not implemented. */ + + return -ENOSYS; +} + +/**************************************************************************** + * Name: usbhost_ioctl + * + * Description: + * Standard character driver ioctl method. + * + ****************************************************************************/ + +static int usbhost_ioctl(FAR struct file* filep, int cmd, unsigned long arg) +{ + FAR struct inode *inode; + FAR struct usbhost_state_s *priv; + int ret = 0; + int nbytes; + FAR struct usbhost_hubport_s *hport; + static uint8_t rumble_cmd[] = { + 0x09, 0x00, 0x00, 0x09, 0x00, 0x0f, 0x00, + 0x00, 0x00, 0x00, 0xff, 0x00, 0xff + }; + + uinfo("Entered\n"); + DEBUGASSERT(filep && filep->f_inode && buffer); + inode = filep->f_inode; + priv = inode->i_private; + hport = priv->usbclass.hport; + + /* Check if the controller is still connected. We need to disable interrupts + * momentarily to assure that there are no asynchronous disconnect events. + */ + + if (priv->disconnected) + { + /* No... the driver is no longer bound to the class. That means that + * the USB controller is no longer connected. Refuse any further attempts + * to access the driver. + */ + + ret = -ENODEV; + goto errout; + } + + /* Determine which IOCTL command to execute. */ + switch (cmd) + { + + case XBOX_CONTROLLER_IOCTL_RUMBLE: + + /* The least significant byte is the weak actuator strength. + * The second byte is the strong actuator strength. + */ + + memcpy(priv->obuffer, rumble_cmd, sizeof(rumble_cmd)); + priv->obuffer[2] = priv->out_seq_num++; + priv->obuffer[8] = (arg >> 1) & 0xff; // Strong (left actuator) + priv->obuffer[9] = arg & 0xff; // Weak (right actuator) + + /* Perform the transfer. */ + + nbytes = DRVR_TRANSFER(hport->drvr, priv->epout, + priv->obuffer, sizeof(rumble_cmd)); + + /* Did we encounter an error? */ + + if (nbytes < 0) + { + ret = nbytes; + } + + break; + + default: + + ret = -EINVAL; + goto errout; + } + +errout: + iinfo("Returning: %d\n", ret); + return ret; +} + +/**************************************************************************** + * Name: usbhost_poll + * + * Description: + * Standard character driver poll method. + * + ****************************************************************************/ + +#ifndef CONFIG_DISABLE_POLL +static int usbhost_poll(FAR struct file *filep, FAR struct pollfd *fds, + bool setup) +{ + FAR struct inode *inode; + FAR struct usbhost_state_s *priv; + int ret = OK; + int i; + + DEBUGASSERT(filep && filep->f_inode && fds); + inode = filep->f_inode; + priv = inode->i_private; + + /* Make sure that we have exclusive access to the private data structure */ + + DEBUGASSERT(priv); + usbhost_takesem(&priv->exclsem); + + /* Check if the controller is still connected. We need to disable interrupts + * momentarily to assure that there are no asynchronous disconnect events. + */ + + if (priv->disconnected) + { + /* No... the driver is no longer bound to the class. That means that + * the USB controller is no longer connected. Refuse any further attempts + * to access the driver. + */ + + ret = -ENODEV; + } + else if (setup) + { + /* This is a request to set up the poll. Find an available slot for + * the poll structure reference + */ + + for (i = 0; i < CONFIG_XBOXCONTROLLER_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_XBOXCONTROLLER_NPOLLWAITERS) + { + fds->priv = NULL; + ret = -EBUSY; + goto errout; + } + + /* Should we immediately notify on any of the requested events? Notify + * the POLLIN event if there is buffered controller data. + */ + + if (priv->valid) + { + usbhost_pollnotify(priv); + } + } + else + { + /* This is a request to tear down the poll. */ + + struct pollfd **slot = (struct pollfd **)fds->priv; + DEBUGASSERT(slot); + + /* Remove all memory of the poll setup */ + + *slot = NULL; + fds->priv = NULL; + } + +errout: + sem_post(&priv->exclsem); + return ret; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: usbhost_xboxcontroller_init + * + * Description: + * Initialize the USB class driver. This function should be called + * be platform-specific code in order to initialize and register support + * for the USB host class device. + * + * Input Parameters: + * None + * + * Returned Values: + * On success this function will return zero (OK); A negated errno value + * will be returned on failure. + * + ****************************************************************************/ + +int usbhost_xboxcontroller_init(void) +{ + + /* Perform any one-time initialization of the class implementation */ + + sem_init(&g_exclsem, 0, 1); + sem_init(&g_syncsem, 0, 0); + + /* The g_syncsem semaphore is used for signaling and, hence, should not + * have priority inheritance enabled. + */ + + sem_setprotocol(&g_syncsem, SEM_PRIO_NONE); + + /* Advertise our availability to support (certain) devices */ + + return usbhost_registerclass(&g_xboxcontroller); +} diff --git a/include/nuttx/input/xbox-controller.h b/include/nuttx/input/xbox-controller.h new file mode 100644 index 0000000000..b4e0262740 --- /dev/null +++ b/include/nuttx/input/xbox-controller.h @@ -0,0 +1,88 @@ +/************************************************************************************ + * include/nuttx/input/xbox-controller.h + * + * Copyright (C) 2016 Brian Webb. + * Author: Brian Webb + * + * 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_INPUT_XBOX_CONTROLLER_H +#define __INCLUDE_NUTTX_INPUT_XBOX_CONTROLLER_H + +#ifdef __cplusplus +extern "C" +{ +#endif + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* This type defines the button data report from the controller. */ + +struct xbox_controller_buttonstate_s +{ + bool guide : 1; + bool sync : 1; + bool start : 1; + bool back : 1; + bool a : 1; + bool b : 1; + bool x : 1; + bool y : 1; + bool dpad_up : 1; + bool dpad_down : 1; + bool dpad_left : 1; + bool dpad_right : 1; + bool bumper_left : 1; + bool bumper_right : 1; + bool stick_click_left : 1; + bool stick_click_right : 1; + int16_t stick_left_x; + int16_t stick_left_y; + int16_t stick_right_x; + int16_t stick_right_y; + int16_t trigger_left; + int16_t trigger_right; +}; + +/* The supported IOCTL commands. */ + +enum +{ + XBOX_CONTROLLER_IOCTL_RUMBLE +} xbox_controller_iotcl_cmds; + +#ifdef __cplusplus +} +#endif + +#endif /* __INCLUDE_NUTTX_INPUT_XBOX_CONTROLLER_H */ + diff --git a/include/nuttx/usb/usbhost.h b/include/nuttx/usb/usbhost.h index 587917701c..6b6b495954 100644 --- a/include/nuttx/usb/usbhost.h +++ b/include/nuttx/usb/usbhost.h @@ -1084,6 +1084,27 @@ int usbhost_kbdinit(void); int usbhost_mouse_init(void); #endif +#ifdef CONFIG_USBHOST_XBOXCONTROLLER +/**************************************************************************** + * Name: usbhost_xboxcontroller_init + * + * Description: + * Initialize the USB XBox controller driver. This function + * should be called be platform-specific code in order to initialize and + * register support for the USB XBox controller. + * + * Input Parameters: + * None + * + * Returned Values: + * On success this function will return zero (OK); A negated errno value + * will be returned on failure. + * + ****************************************************************************/ + +int usbhost_xboxcontroller_init(void); +#endif + /**************************************************************************** * Name: usbhost_wlaninit * -- GitLab From 175f8960cfc20a00c8882be8bb04807d47adaee0 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 18 Mar 2017 06:47:34 -0600 Subject: [PATCH 088/990] Cosmetic changes from review of last PR --- drivers/usbhost/usbhost_xboxcontroller.c | 351 +++++++++++++---------- 1 file changed, 192 insertions(+), 159 deletions(-) diff --git a/drivers/usbhost/usbhost_xboxcontroller.c b/drivers/usbhost/usbhost_xboxcontroller.c index fd12efee97..6fcf49d6a8 100644 --- a/drivers/usbhost/usbhost_xboxcontroller.c +++ b/drivers/usbhost/usbhost_xboxcontroller.c @@ -2,7 +2,8 @@ * drivers/usbhost/usbhost_xboxcontroller.c * * Copyright (C) 2016 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Authors: Gregory Nutt + * Brian Webb * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -143,7 +144,8 @@ #define XBOX_BUTTON_STICK_LEFT_Y 6 #define XBOX_BUTTON_STICK_RIGHT_X 7 #define XBOX_BUTTON_STICK_RIGHT_Y 8 -#define XBOX_BUTTON_SET(buffer, index, mask) ((((buffer)[(index)] & (mask)) != 0) ? true : false); +#define XBOX_BUTTON_SET(buffer, index, mask) \ + ((((buffer)[(index)] & (mask)) != 0) ? true : false); /**************************************************************************** * Private Types @@ -291,7 +293,7 @@ static struct usbhost_registry_s g_xboxcontroller = NULL, /* flink */ usbhost_create, /* create */ 2, /* nids */ - g_xboxcontroller_id /* id[] */ + g_xboxcontroller_id /* id[] */ }; /* The configuration information for the block file device. */ @@ -342,7 +344,7 @@ static void usbhost_takesem(sem_t *sem) * awakened by a signal. */ - ASSERT(errno == EINTR); + DEBUGASSERT(errno == EINTR); } } @@ -558,7 +560,7 @@ static void usbhost_notify(FAR struct usbhost_state_s *priv) #ifndef CONFIG_DISABLE_POLL for (i = 0; i < CONFIG_XBOXCONTROLLER_NPOLLWAITERS; i++) { - struct pollfd *fds = priv->fds[i]; + FAR struct pollfd *fds = priv->fds[i]; if (fds) { fds->revents |= POLLIN; @@ -640,16 +642,15 @@ static int usbhost_xboxcontroller_poll(int argc, char *argv[]) if (nbytes != -EAGAIN) { - - uerr("ERROR: DRVR_TRANSFER returned: %d/%u\n", - (int)nbytes, nerrors); - + uerr("ERROR: DRVR_TRANSFER returned: %d/%u\n", + (int)nbytes, nerrors); + if (++nerrors > 200) { uerr(" Too many errors... aborting: %d\n", nerrors); ret = (int)nbytes; break; - } + } } } @@ -657,146 +658,176 @@ static int usbhost_xboxcontroller_poll(int argc, char *argv[]) else { - /* Success, reset the error counter */ - nerrors = 0; - - /* The type of message is in the first byte */ - switch (priv->tbuffer[0]) - { + nerrors = 0; + + /* The type of message is in the first byte */ + + switch (priv->tbuffer[0]) + { + case USBHOST_WAITING_CONNECTION: + /* Send the initialization message when we received the + * the first waiting connection message. + */ + + if (!priv->initialized) + { + /* Get exclusive access to the controller state data */ + + usbhost_takesem(&priv->exclsem); + + priv->tbuffer[0] = 0x05; + priv->tbuffer[1] = 0x20; + priv->tbuffer[2] = priv->out_seq_num++; + priv->tbuffer[3] = 0x01; + priv->tbuffer[4] = 0x00; + nbytes = DRVR_TRANSFER(hport->drvr, priv->epout, + priv->tbuffer, 5); + priv->initialized = true; + + /* Release our lock on the state structure */ + + usbhost_givesem(&priv->exclsem); + } + + break; + + case USBHOST_GUIDE_BUTTON_STATUS: + /* Get exclusive access to the controller state data */ + + usbhost_takesem(&priv->exclsem); + + /* Read the data out of the controller report. */ + + priv->rpt.guide = (priv->tbuffer[XBOX_BUTTON_GUIDE_INDEX] != 0) ? true : false; + priv->valid = true; + + /* The One X controller requires an ACK of the guide button status + * message. + */ + + if (priv->tbuffer[1] == 0x30) + { + static const uint8_t guide_button_report_ack[] = + { + 0x01, 0x20, 0x00, 0x09, 0x00, 0x07, 0x20, 0x02, + 0x00, 0x00, 0x00, 0x00, 0x00 + }; + + /* Remember the input packet sequence number. */ + + uint8_t seq_num = priv->tbuffer[2]; + + /* Copy the ACK packet into the transfer buffer. */ + + memcpy(priv->tbuffer, guide_button_report_ack, + sizeof(guide_button_report_ack)); - case USBHOST_WAITING_CONNECTION: - - /* Send the initialization message when we received the - * the first waiting connection message. - */ - - if (!priv->initialized) { - - /* Get exclusive access to the controller state data */ - - usbhost_takesem(&priv->exclsem); - - priv->tbuffer[0] = 0x05; - priv->tbuffer[1] = 0x20; - priv->tbuffer[2] = priv->out_seq_num++; - priv->tbuffer[3] = 0x01; - priv->tbuffer[4] = 0x00; - nbytes = DRVR_TRANSFER(hport->drvr, priv->epout, - priv->tbuffer, 5); - priv->initialized = true; - - /* Release our lock on the state structure */ - - usbhost_givesem(&priv->exclsem); - } - - break; - - case USBHOST_GUIDE_BUTTON_STATUS: - - /* Get exclusive access to the controller state data */ - - usbhost_takesem(&priv->exclsem); - - /* Read the data out of the controller report. */ - - priv->rpt.guide = (priv->tbuffer[XBOX_BUTTON_GUIDE_INDEX] != 0) ? true : false; - - priv->valid = true; - - /* The One X controller requires an ACK of the guide button status message. */ - - if (priv->tbuffer[1] == 0x30) - { - - static const uint8_t guide_button_report_ack[] = { - 0x01, 0x20, 0x00, 0x09, 0x00, 0x07, 0x20, 0x02, - 0x00, 0x00, 0x00, 0x00, 0x00 - }; - - /* Remember the input packet sequence number. */ - - uint8_t seq_num = priv->tbuffer[2]; - - /* Copy the ACK packet into the transfer buffer. */ - - memcpy(priv->tbuffer, guide_button_report_ack, sizeof(guide_button_report_ack)); - - /* Ensure the sequence number is the same as the input packet. */ - - priv->tbuffer[2] = seq_num; - - /* Perform the transfer. */ - - nbytes = DRVR_TRANSFER(hport->drvr, priv->epout, - priv->tbuffer, sizeof(guide_button_report_ack)); - } - - /* Notify any waiters that new controller data is available */ - - usbhost_notify(priv); - - /* Release our lock on the state structure */ - - usbhost_givesem(&priv->exclsem); - - break; - - case USBHOST_BUTTON_DATA: - - /* Ignore the controller data if no task has opened the driver. */ - - if (priv->open) - { - /* Get exclusive access to the controller state data */ - - usbhost_takesem(&priv->exclsem); - - /* Read the data out of the controller report. */ - - priv->rpt.sync = XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_SYNC_INDEX, XBOX_BUTTON_SYNC_MASK); - priv->rpt.start = XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_START_INDEX, XBOX_BUTTON_START_MASK); - priv->rpt.back = XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_BACK_INDEX, XBOX_BUTTON_BACK_MASK); - priv->rpt.a = XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_A_INDEX, XBOX_BUTTON_A_MASK); - priv->rpt.b = XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_B_INDEX, XBOX_BUTTON_B_MASK); - priv->rpt.x = XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_X_INDEX, XBOX_BUTTON_X_MASK); - priv->rpt.y = XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_Y_INDEX, XBOX_BUTTON_Y_MASK); - priv->rpt.dpad_up = XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_DPAD_UP_INDEX, XBOX_BUTTON_DPAD_UP_MASK); - priv->rpt.dpad_down = XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_DPAD_DOWN_INDEX, XBOX_BUTTON_DPAD_DOWN_MASK); - priv->rpt.dpad_left = XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_DPAD_LEFT_INDEX, XBOX_BUTTON_DPAD_LEFT_MASK); - priv->rpt.dpad_right = XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_DPAD_RIGHT_INDEX, XBOX_BUTTON_DPAD_RIGHT_MASK); - priv->rpt.bumper_left = XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_BUMPER_LEFT_INDEX, XBOX_BUTTON_BUMPER_LEFT_MASK); - priv->rpt.bumper_right = XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_BUMPER_RIGHT_INDEX, XBOX_BUTTON_BUMPER_RIGHT_MASK); - priv->rpt.stick_click_left = XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_STICK_LEFT_INDEX, XBOX_BUTTON_STICK_LEFT_MASK); - priv->rpt.stick_click_right = XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_STICK_RIGHT_INDEX, XBOX_BUTTON_STICK_RIGHT_MASK); - priv->rpt.trigger_left = ((int16_t*)(priv->tbuffer))[XBOX_BUTTON_TRIGGER_LEFT]; - priv->rpt.trigger_right = ((int16_t*)(priv->tbuffer))[XBOX_BUTTON_TRIGGER_RIGHT]; - priv->rpt.stick_left_x = ((int16_t*)(priv->tbuffer))[XBOX_BUTTON_STICK_LEFT_X]; - priv->rpt.stick_left_y = ((int16_t*)(priv->tbuffer))[XBOX_BUTTON_STICK_LEFT_Y]; - priv->rpt.stick_right_x = ((int16_t*)(priv->tbuffer))[XBOX_BUTTON_STICK_RIGHT_X]; - priv->rpt.stick_right_y = ((int16_t*)(priv->tbuffer))[XBOX_BUTTON_STICK_RIGHT_Y]; - - priv->valid = true; - - /* Notify any waiters that new controller data is available */ - - usbhost_notify(priv); - - /* Release our lock on the state structure */ - - usbhost_givesem(&priv->exclsem); - } + /* Ensure the sequence number is the same as the input packet. */ - break; + priv->tbuffer[2] = seq_num; - default: - - uinfo("Received messge type: %x\n", priv->tbuffer[0]); - - } - + /* Perform the transfer. */ + + nbytes = DRVR_TRANSFER(hport->drvr, priv->epout, priv->tbuffer, + sizeof(guide_button_report_ack)); + } + + /* Notify any waiters that new controller data is available */ + + usbhost_notify(priv); + + /* Release our lock on the state structure */ + + usbhost_givesem(&priv->exclsem); + + break; + + case USBHOST_BUTTON_DATA: + /* Ignore the controller data if no task has opened the driver. */ + + if (priv->open) + { + /* Get exclusive access to the controller state data */ + + usbhost_takesem(&priv->exclsem); + + /* Read the data out of the controller report. */ + + priv->rpt.sync = + XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_SYNC_INDEX, + XBOX_BUTTON_SYNC_MASK); + priv->rpt.start = + XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_START_INDEX, + XBOX_BUTTON_START_MASK); + priv->rpt.back = + XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_BACK_INDEX, + XBOX_BUTTON_BACK_MASK); + priv->rpt.a = + XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_A_INDEX, + XBOX_BUTTON_A_MASK); + priv->rpt.b = + XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_B_INDEX, + XBOX_BUTTON_B_MASK); + priv->rpt.x = + XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_X_INDEX, + XBOX_BUTTON_X_MASK); + priv->rpt.y = + XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_Y_INDEX, + XBOX_BUTTON_Y_MASK); + priv->rpt.dpad_up = + XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_DPAD_UP_INDEX, + XBOX_BUTTON_DPAD_UP_MASK); + priv->rpt.dpad_down = + XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_DPAD_DOWN_INDEX, + XBOX_BUTTON_DPAD_DOWN_MASK); + priv->rpt.dpad_left = + XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_DPAD_LEFT_INDEX, + XBOX_BUTTON_DPAD_LEFT_MASK); + priv->rpt.dpad_right = + XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_DPAD_RIGHT_INDEX, + XBOX_BUTTON_DPAD_RIGHT_MASK); + priv->rpt.bumper_left = + XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_BUMPER_LEFT_INDEX, + XBOX_BUTTON_BUMPER_LEFT_MASK); + priv->rpt.bumper_right = + XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_BUMPER_RIGHT_INDEX, XBOX_BUTTON_BUMPER_RIGHT_MASK); + priv->rpt.stick_click_left = + XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_STICK_LEFT_INDEX, + XBOX_BUTTON_STICK_LEFT_MASK); + priv->rpt.stick_click_right = + XBOX_BUTTON_SET(priv->tbuffer, XBOX_BUTTON_STICK_RIGHT_INDEX, + XBOX_BUTTON_STICK_RIGHT_MASK); + priv->rpt.trigger_left = + ((int16_t*)(priv->tbuffer))[XBOX_BUTTON_TRIGGER_LEFT]; + priv->rpt.trigger_right = + ((int16_t*)(priv->tbuffer))[XBOX_BUTTON_TRIGGER_RIGHT]; + priv->rpt.stick_left_x = + ((int16_t*)(priv->tbuffer))[XBOX_BUTTON_STICK_LEFT_X]; + priv->rpt.stick_left_y = + ((int16_t*)(priv->tbuffer))[XBOX_BUTTON_STICK_LEFT_Y]; + priv->rpt.stick_right_x = + ((int16_t*)(priv->tbuffer))[XBOX_BUTTON_STICK_RIGHT_X]; + priv->rpt.stick_right_y = + ((int16_t*)(priv->tbuffer))[XBOX_BUTTON_STICK_RIGHT_Y]; + + priv->valid = true; + + /* Notify any waiters that new controller data is available */ + + usbhost_notify(priv); + + /* Release our lock on the state structure */ + + usbhost_givesem(&priv->exclsem); + } + + break; + + default: + uinfo("Received messge type: %x\n", priv->tbuffer[0]); + } } /* If USB debug is on, then provide some periodic indication that @@ -925,7 +956,7 @@ static int usbhost_sample(FAR struct usbhost_state_s *priv, ****************************************************************************/ static int usbhost_waitsample(FAR struct usbhost_state_s *priv, - FAR struct xbox_controller_buttonstate_s *sample) + FAR struct xbox_controller_buttonstate_s *sample) { irqstate_t flags; int ret; @@ -1142,6 +1173,7 @@ static inline int usbhost_cfgdesc(FAR struct usbhost_state_s *priv, return -EINVAL; } + found |= USBHOST_EPOUTFOUND; /* Save the bulk OUT endpoint information */ @@ -1199,7 +1231,7 @@ static inline int usbhost_cfgdesc(FAR struct usbhost_state_s *priv, if (found == USBHOST_ALLFOUND) { - done=true; + done = true; } /* Increment the address of the next descriptor */ @@ -1563,6 +1595,7 @@ static FAR struct usbhost_class_s *usbhost_create(FAR struct usbhost_hubport_s * { usbhost_freeclass(priv); } + return NULL; } @@ -1785,7 +1818,6 @@ static int usbhost_open(FAR struct file *filep) } leave_critical_section(flags); - usbhost_givesem(&priv->exclsem); return ret; } @@ -1838,7 +1870,7 @@ static int usbhost_close(FAR struct file *filep) * but there is still an outstanding open reference. */ - if (priv->crefs == 0 || (priv->crefs == 1 && priv->polling)) + if (priv->crefs == 0 || (priv->crefs == 1 && priv->polling)) { /* Yes.. In either case, then the driver is no longer open */ @@ -1973,9 +2005,8 @@ errout: static ssize_t usbhost_write(FAR struct file *filep, FAR const char *buffer, size_t len) { - /* Not implemented. */ - + return -ENOSYS; } @@ -1994,7 +2025,8 @@ static int usbhost_ioctl(FAR struct file* filep, int cmd, unsigned long arg) int ret = 0; int nbytes; FAR struct usbhost_hubport_s *hport; - static uint8_t rumble_cmd[] = { + static uint8_t rumble_cmd[] = + { 0x09, 0x00, 0x00, 0x09, 0x00, 0x0f, 0x00, 0x00, 0x00, 0x00, 0xff, 0x00, 0xff }; @@ -2021,6 +2053,7 @@ static int usbhost_ioctl(FAR struct file* filep, int cmd, unsigned long arg) } /* Determine which IOCTL command to execute. */ + switch (cmd) { @@ -2034,18 +2067,18 @@ static int usbhost_ioctl(FAR struct file* filep, int cmd, unsigned long arg) priv->obuffer[2] = priv->out_seq_num++; priv->obuffer[8] = (arg >> 1) & 0xff; // Strong (left actuator) priv->obuffer[9] = arg & 0xff; // Weak (right actuator) - + /* Perform the transfer. */ - + nbytes = DRVR_TRANSFER(hport->drvr, priv->epout, - priv->obuffer, sizeof(rumble_cmd)); + priv->obuffer, sizeof(rumble_cmd)); /* Did we encounter an error? */ if (nbytes < 0) - { - ret = nbytes; - } + { + ret = nbytes; + } break; @@ -2054,7 +2087,7 @@ static int usbhost_ioctl(FAR struct file* filep, int cmd, unsigned long arg) ret = -EINVAL; goto errout; } - + errout: iinfo("Returning: %d\n", ret); return ret; -- GitLab From 49e4e62aabad09c9d7a1a0b5398fcda993514b13 Mon Sep 17 00:00:00 2001 From: raiden00pl Date: Sat, 18 Mar 2017 16:31:06 +0100 Subject: [PATCH 089/990] STM32F33: Move DMA logic to a separate files --- arch/arm/src/stm32/chip/stm32f33xxx_dma.h | 366 ++++++++++++ arch/arm/src/stm32/stm32_dma.c | 5 +- arch/arm/src/stm32/stm32_dma.h | 5 +- arch/arm/src/stm32/stm32f10xxx_dma.c | 3 +- arch/arm/src/stm32/stm32f33xxx_dma.c | 696 ++++++++++++++++++++++ 5 files changed, 1070 insertions(+), 5 deletions(-) create mode 100644 arch/arm/src/stm32/chip/stm32f33xxx_dma.h create mode 100644 arch/arm/src/stm32/stm32f33xxx_dma.c diff --git a/arch/arm/src/stm32/chip/stm32f33xxx_dma.h b/arch/arm/src/stm32/chip/stm32f33xxx_dma.h new file mode 100644 index 0000000000..c30bcb0472 --- /dev/null +++ b/arch/arm/src/stm32/chip/stm32f33xxx_dma.h @@ -0,0 +1,366 @@ +/************************************************************************************ + * arch/arm/src/stm32/chip/stm32f33xxx_dma.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * Mateusz Szafoni + * + * 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 __ARCH_ARM_SRC_STM32_CHIP_STM32F33XXX_DMA_H +#define __ARCH_ARM_SRC_STM32_CHIP_STM32F33XXX_DMA_H + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* 12 Channels Total: 7 DMA1 Channels(1-7) and 5 DMA2 channels (1-5) */ + +#define DMA1 0 +#define DMA2 1 +#define DMA3 2 +#define DMA4 3 +#define DMA5 4 +#define DMA6 5 +#define DMA7 6 + +/* Register Offsets *****************************************************************/ + +#define STM32_DMA_ISR_OFFSET 0x0000 /* DMA interrupt status register */ +#define STM32_DMA_IFCR_OFFSET 0x0004 /* DMA interrupt flag clear register */ + +#define STM32_DMACHAN_OFFSET(n) (0x0014*(n)) +#define STM32_DMACHAN1_OFFSET 0x0000 +#define STM32_DMACHAN2_OFFSET 0x0014 +#define STM32_DMACHAN3_OFFSET 0x0028 +#define STM32_DMACHAN4_OFFSET 0x003c +#define STM32_DMACHAN5_OFFSET 0x0050 +#define STM32_DMACHAN6_OFFSET 0x0064 +#define STM32_DMACHAN7_OFFSET 0x0078 + +#define STM32_DMACHAN_CCR_OFFSET 0x0008 /* DMA channel configuration register */ +#define STM32_DMACHAN_CNDTR_OFFSET 0x000c /* DMA channel number of data register */ +#define STM32_DMACHAN_CPAR_OFFSET 0x0010 /* DMA channel peripheral address register */ +#define STM32_DMACHAN_CMAR_OFFSET 0x0014 /* DMA channel 1 memory address register */ + +#define STM32_DMA_CCR_OFFSET(n) (STM32_DMACHAN_CCR_OFFSET+STM32_DMACHAN_OFFSET(n)) +#define STM32_DMA_CNDTR_OFFSET(n) (STM32_DMACHAN_CNDTR_OFFSET+STM32_DMACHAN_OFFSET(n)) +#define STM32_DMA_CPAR_OFFSET(n) (STM32_DMACHAN_CPAR_OFFSET+STM32_DMACHAN_OFFSET(n)) +#define STM32_DMA_CMAR_OFFSET(n) (STM32_DMACHAN_CMAR_OFFSET+STM32_DMACHAN_OFFSET(n)) + +#define STM32_DMA_CCR1_OFFSET 0x0008 /* DMA channel 1 configuration register */ +#define STM32_DMA_CCR2_OFFSET 0x001c /* DMA channel 2 configuration register */ +#define STM32_DMA_CCR3_OFFSET 0x0030 /* DMA channel 3 configuration register */ +#define STM32_DMA_CCR4_OFFSET 0x0044 /* DMA channel 4 configuration register */ +#define STM32_DMA_CCR5_OFFSET 0x0058 /* DMA channel 5 configuration register */ +#define STM32_DMA_CCR6_OFFSET 0x006c /* DMA channel 6 configuration register */ +#define STM32_DMA_CCR7_OFFSET 0x0080 /* DMA channel 7 configuration register */ + +#define STM32_DMA_CNDTR1_OFFSET 0x000c /* DMA channel 1 number of data register */ +#define STM32_DMA_CNDTR2_OFFSET 0x0020 /* DMA channel 2 number of data register */ +#define STM32_DMA_CNDTR3_OFFSET 0x0034 /* DMA channel 3 number of data register */ +#define STM32_DMA_CNDTR4_OFFSET 0x0048 /* DMA channel 4 number of data register */ +#define STM32_DMA_CNDTR5_OFFSET 0x005c /* DMA channel 5 number of data register */ +#define STM32_DMA_CNDTR6_OFFSET 0x0070 /* DMA channel 6 number of data register */ +#define STM32_DMA_CNDTR7_OFFSET 0x0084 /* DMA channel 7 number of data register */ + +#define STM32_DMA_CPAR1_OFFSET 0x0010 /* DMA channel 1 peripheral address register */ +#define STM32_DMA_CPAR2_OFFSET 0x0024 /* DMA channel 2 peripheral address register */ +#define STM32_DMA_CPAR3_OFFSET 0x0038 /* DMA channel 3 peripheral address register */ +#define STM32_DMA_CPAR4_OFFSET 0x004c /* DMA channel 4 peripheral address register */ +#define STM32_DMA_CPAR5_OFFSET 0x0060 /* DMA channel 5 peripheral address register */ +#define STM32_DMA_CPAR6_OFFSET 0x0074 /* DMA channel 6 peripheral address register */ +#define STM32_DMA_CPAR7_OFFSET 0x0088 /* DMA channel 7 peripheral address register */ + +#define STM32_DMA_CMAR1_OFFSET 0x0014 /* DMA channel 1 memory address register */ +#define STM32_DMA_CMAR2_OFFSET 0x0028 /* DMA channel 2 memory address register */ +#define STM32_DMA_CMAR3_OFFSET 0x003c /* DMA channel 3 memory address register */ +#define STM32_DMA_CMAR4_OFFSET 0x0050 /* DMA channel 4 memory address register */ +#define STM32_DMA_CMAR5_OFFSET 0x0064 /* DMA channel 5 memory address register */ +#define STM32_DMA_CMAR6_OFFSET 0x0078 /* DMA channel 6 memory address register */ +#define STM32_DMA_CMAR7_OFFSET 0x008c /* DMA channel 7 memory address register */ + +/* Register Addresses ***************************************************************/ + +#define STM32_DMA1_ISRC (STM32_DMA1_BASE+STM32_DMA_ISR_OFFSET) +#define STM32_DMA1_IFCR (STM32_DMA1_BASE+STM32_DMA_IFCR_OFFSET) + +#define STM32_DMA1_CCR(n) (STM32_DMA1_BASE+STM32_DMA_CCR_OFFSET(n)) +#define STM32_DMA1_CCR1 (STM32_DMA1_BASE+STM32_DMA_CCR1_OFFSET) +#define STM32_DMA1_CCR2 (STM32_DMA1_BASE+STM32_DMA_CCR2_OFFSET) +#define STM32_DMA1_CCR3 (STM32_DMA1_BASE+STM32_DMA_CCR3_OFFSET) +#define STM32_DMA1_CCR4 (STM32_DMA1_BASE+STM32_DMA_CCR4_OFFSET) +#define STM32_DMA1_CCR5 (STM32_DMA1_BASE+STM32_DMA_CCR5_OFFSET) +#define STM32_DMA1_CCR6 (STM32_DMA1_BASE+STM32_DMA_CCR6_OFFSET) +#define STM32_DMA1_CCR7 (STM32_DMA1_BASE+STM32_DMA_CCR7_OFFSET) + +#define STM32_DMA1_CNDTR(n) (STM32_DMA1_BASE+STM32_DMA_CNDTR_OFFSET(n)) +#define STM32_DMA1_CNDTR1 (STM32_DMA1_BASE+STM32_DMA_CNDTR1_OFFSET) +#define STM32_DMA1_CNDTR2 (STM32_DMA1_BASE+STM32_DMA_CNDTR2_OFFSET) +#define STM32_DMA1_CNDTR3 (STM32_DMA1_BASE+STM32_DMA_CNDTR3_OFFSET) +#define STM32_DMA1_CNDTR4 (STM32_DMA1_BASE+STM32_DMA_CNDTR4_OFFSET) +#define STM32_DMA1_CNDTR5 (STM32_DMA1_BASE+STM32_DMA_CNDTR5_OFFSET) +#define STM32_DMA1_CNDTR6 (STM32_DMA1_BASE+STM32_DMA_CNDTR6_OFFSET) +#define STM32_DMA1_CNDTR7 (STM32_DMA1_BASE+STM32_DMA_CNDTR7_OFFSET) + +#define STM32_DMA1_CPAR(n) (STM32_DMA1_BASE+STM32_DMA_CPAR_OFFSET(n)) +#define STM32_DMA1_CPAR1 (STM32_DMA1_BASE+STM32_DMA_CPAR1_OFFSET) +#define STM32_DMA1_CPAR2 (STM32_DMA1_BASE+STM32_DMA_CPAR2_OFFSET) +#define STM32_DMA1_CPAR3 (STM32_DMA1_BASE+STM32_DMA_CPAR3_OFFSET) +#define STM32_DMA1_CPAR4 (STM32_DMA1_BASE+STM32_DMA_CPAR4_OFFSET) +#define STM32_DMA1_CPAR5 (STM32_DMA1_BASE+STM32_DMA_CPAR5_OFFSET) +#define STM32_DMA1_CPAR6 (STM32_DMA1_BASE+STM32_DMA_CPAR6_OFFSET) +#define STM32_DMA1_CPAR7 (STM32_DMA1_BASE+STM32_DMA_CPAR7_OFFSET) + +#define STM32_DMA1_CMAR(n) (STM32_DMA1_BASE+STM32_DMA_CMAR_OFFSET(n)) +#define STM32_DMA1_CMAR1 (STM32_DMA1_BASE+STM32_DMA_CMAR1_OFFSET) +#define STM32_DMA1_CMAR2 (STM32_DMA1_BASE+STM32_DMA_CMAR2_OFFSET) +#define STM32_DMA1_CMAR3 (STM32_DMA1_BASE+STM32_DMA_CMAR3_OFFSET) +#define STM32_DMA1_CMAR4 (STM32_DMA1_BASE+STM32_DMA_CMAR4_OFFSET) +#define STM32_DMA1_CMAR5 (STM32_DMA1_BASE+STM32_DMA_CMAR5_OFFSET) +#define STM32_DMA1_CMAR6 (STM32_DMA1_BASE+STM32_DMA_CMAR6_OFFSET) +#define STM32_DMA1_CMAR7 (STM32_DMA1_BASE+STM32_DMA_CMAR7_OFFSET) + +#define STM32_DMA2_ISRC (STM32_DMA2_BASE+STM32_DMA_ISR_OFFSET) +#define STM32_DMA2_IFCR (STM32_DMA2_BASE+STM32_DMA_IFCR_OFFSET) + +#define STM32_DMA2_CCR(n) (STM32_DMA2_BASE+STM32_DMA_CCR_OFFSET(n)) +#define STM32_DMA2_CCR1 (STM32_DMA2_BASE+STM32_DMA_CCR1_OFFSET) +#define STM32_DMA2_CCR2 (STM32_DMA2_BASE+STM32_DMA_CCR2_OFFSET) +#define STM32_DMA2_CCR3 (STM32_DMA2_BASE+STM32_DMA_CCR3_OFFSET) +#define STM32_DMA2_CCR4 (STM32_DMA2_BASE+STM32_DMA_CCR4_OFFSET) +#define STM32_DMA2_CCR5 (STM32_DMA2_BASE+STM32_DMA_CCR5_OFFSET) + +#define STM32_DMA2_CNDTR(n) (STM32_DMA2_BASE+STM32_DMA_CNDTR_OFFSET(n)) +#define STM32_DMA2_CNDTR1 (STM32_DMA2_BASE+STM32_DMA_CNDTR1_OFFSET) +#define STM32_DMA2_CNDTR2 (STM32_DMA2_BASE+STM32_DMA_CNDTR2_OFFSET) +#define STM32_DMA2_CNDTR3 (STM32_DMA2_BASE+STM32_DMA_CNDTR3_OFFSET) +#define STM32_DMA2_CNDTR4 (STM32_DMA2_BASE+STM32_DMA_CNDTR4_OFFSET) +#define STM32_DMA2_CNDTR5 (STM32_DMA2_BASE+STM32_DMA_CNDTR5_OFFSET) + +#define STM32_DMA2_CPAR(n) (STM32_DMA2_BASE+STM32_DMA_CPAR_OFFSET(n)) +#define STM32_DMA2_CPAR1 (STM32_DMA2_BASE+STM32_DMA_CPAR1_OFFSET) +#define STM32_DMA2_CPAR2 (STM32_DMA2_BASE+STM32_DMA_CPAR2_OFFSET) +#define STM32_DMA2_CPAR3 (STM32_DMA2_BASE+STM32_DMA_CPAR3_OFFSET) +#define STM32_DMA2_CPAR4 (STM32_DMA2_BASE+STM32_DMA_CPAR4_OFFSET) +#define STM32_DMA2_CPAR5 (STM32_DMA2_BASE+STM32_DMA_CPAR5_OFFSET) + +#define STM32_DMA2_CMAR(n) (STM32_DMA2_BASE+STM32_DMA_CMAR_OFFSET(n)) +#define STM32_DMA2_CMAR1 (STM32_DMA2_BASE+STM32_DMA_CMAR1_OFFSET) +#define STM32_DMA2_CMAR2 (STM32_DMA2_BASE+STM32_DMA_CMAR2_OFFSET) +#define STM32_DMA2_CMAR3 (STM32_DMA2_BASE+STM32_DMA_CMAR3_OFFSET) +#define STM32_DMA2_CMAR4 (STM32_DMA2_BASE+STM32_DMA_CMAR4_OFFSET) +#define STM32_DMA2_CMAR5 (STM32_DMA2_BASE+STM32_DMA_CMAR5_OFFSET) + +/* Register Bitfield Definitions ****************************************************/ + +#define DMA_CHAN_SHIFT(n) ((n) << 2) +#define DMA_CHAN_MASK 0x0f +#define DMA_CHAN_GIF_BIT (1 << 0) /* Bit 0: Channel Global interrupt flag */ +#define DMA_CHAN_TCIF_BIT (1 << 1) /* Bit 1: Channel Transfer Complete flag */ +#define DMA_CHAN_HTIF_BIT (1 << 2) /* Bit 2: Channel Half Transfer flag */ +#define DMA_CHAN_TEIF_BIT (1 << 3) /* Bit 3: Channel Transfer Error flag */ + +/* DMA interrupt status register */ + +#define DMA_ISR_CHAN_SHIFT(n) DMA_CHAN_SHIFT(n) +#define DMA_ISR_CHAN_MASK(n) (DMA_CHAN_MASK << DMA_ISR_CHAN_SHIFT(n)) +#define DMA_ISR_CHAN1_SHIFT (0) /* Bits 3-0: DMA Channel 1 interrupt status */ +#define DMA_ISR_CHAN1_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN1_SHIFT) +#define DMA_ISR_CHAN2_SHIFT (4) /* Bits 7-4: DMA Channel 2 interrupt status */ +#define DMA_ISR_CHAN2_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN2_SHIFT) +#define DMA_ISR_CHAN3_SHIFT (8) /* Bits 11-8: DMA Channel 3 interrupt status */ +#define DMA_ISR_CHAN3_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN3_SHIFT) +#define DMA_ISR_CHAN4_SHIFT (12) /* Bits 15-12: DMA Channel 4 interrupt status */ +#define DMA_ISR_CHAN4_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN4_SHIFT) +#define DMA_ISR_CHAN5_SHIFT (16) /* Bits 19-16: DMA Channel 5 interrupt status */ +#define DMA_ISR_CHAN5_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN5_SHIFT) +#define DMA_ISR_CHAN6_SHIFT (20) /* Bits 23-20: DMA Channel 6 interrupt status */ +#define DMA_ISR_CHAN6_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN6_SHIFT) +#define DMA_ISR_CHAN7_SHIFT (24) /* Bits 27-24: DMA Channel 7 interrupt status */ +#define DMA_ISR_CHAN7_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN7_SHIFT) + +#define DMA_ISR_GIF(n) (DMA_CHAN_GIF_BIT << DMA_ISR_CHAN_SHIFT(n)) +#define DMA_ISR_TCIF(n) (DMA_CHAN_TCIF_BIT << DMA_ISR_CHAN_SHIFT(n)) +#define DMA_ISR_HTIF(n) (DMA_CHAN_HTIF_BIT << DMA_ISR_CHAN_SHIFT(n)) +#define DMA_ISR_TEIF(n) (DMA_CHAN_TEIF_BIT << DMA_ISR_CHAN_SHIFT(n)) + +/* DMA interrupt flag clear register */ + +#define DMA_IFCR_CHAN_SHIFT(n) DMA_CHAN_SHIFT(n) +#define DMA_IFCR_CHAN_MASK(n) (DMA_CHAN_MASK << DMA_IFCR_CHAN_SHIFT(n)) +#define DMA_IFCR_CHAN1_SHIFT (0) /* Bits 3-0: DMA Channel 1 interrupt flag clear */ +#define DMA_IFCR_CHAN1_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN1_SHIFT) +#define DMA_IFCR_CHAN2_SHIFT (4) /* Bits 7-4: DMA Channel 2 interrupt flag clear */ +#define DMA_IFCR_CHAN2_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN2_SHIFT) +#define DMA_IFCR_CHAN3_SHIFT (8) /* Bits 11-8: DMA Channel 3 interrupt flag clear */ +#define DMA_IFCR_CHAN3_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN3_SHIFT) +#define DMA_IFCR_CHAN4_SHIFT (12) /* Bits 15-12: DMA Channel 4 interrupt flag clear */ +#define DMA_IFCR_CHAN4_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN4_SHIFT) +#define DMA_IFCR_CHAN5_SHIFT (16) /* Bits 19-16: DMA Channel 5 interrupt flag clear */ +#define DMA_IFCR_CHAN5_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN5_SHIFT) +#define DMA_IFCR_CHAN6_SHIFT (20) /* Bits 23-20: DMA Channel 6 interrupt flag clear */ +#define DMA_IFCR_CHAN6_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN6_SHIFT) +#define DMA_IFCR_CHAN7_SHIFT (24) /* Bits 27-24: DMA Channel 7 interrupt flag clear */ +#define DMA_IFCR_CHAN7_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN7_SHIFT) +#define DMA_IFCR_ALLCHANNELS (0x0fffffff) + +#define DMA_IFCR_CGIF(n) (DMA_CHAN_GIF_BIT << DMA_IFCR_CHAN_SHIFT(n)) +#define DMA_IFCR_CTCIF(n) (DMA_CHAN_TCIF_BIT << DMA_IFCR_CHAN_SHIFT(n)) +#define DMA_IFCR_CHTIF(n) (DMA_CHAN_HTIF_BIT << DMA_IFCR_CHAN_SHIFT(n)) +#define DMA_IFCR_CTEIF(n) (DMA_CHAN_TEIF_BIT << DMA_IFCR_CHAN_SHIFT(n)) + +/* DMA channel configuration register */ + +#define DMA_CCR_EN (1 << 0) /* Bit 0: Channel enable */ +#define DMA_CCR_TCIE (1 << 1) /* Bit 1: Transfer complete interrupt enable */ +#define DMA_CCR_HTIE (1 << 2) /* Bit 2: Half Transfer interrupt enable */ +#define DMA_CCR_TEIE (1 << 3) /* Bit 3: Transfer error interrupt enable */ +#define DMA_CCR_DIR (1 << 4) /* Bit 4: Data transfer direction */ +#define DMA_CCR_CIRC (1 << 5) /* Bit 5: Circular mode */ +#define DMA_CCR_PINC (1 << 6) /* Bit 6: Peripheral increment mode */ +#define DMA_CCR_MINC (1 << 7) /* Bit 7: Memory increment mode */ +#define DMA_CCR_PSIZE_SHIFT (8) /* Bits 8-9: Peripheral size */ +#define DMA_CCR_PSIZE_MASK (3 << DMA_CCR_PSIZE_SHIFT) +# define DMA_CCR_PSIZE_8BITS (0 << DMA_CCR_PSIZE_SHIFT) /* 00: 8-bits */ +# define DMA_CCR_PSIZE_16BITS (1 << DMA_CCR_PSIZE_SHIFT) /* 01: 16-bits */ +# define DMA_CCR_PSIZE_32BITS (2 << DMA_CCR_PSIZE_SHIFT) /* 10: 32-bits */ +#define DMA_CCR_MSIZE_SHIFT (10) /* Bits 10-11: Memory size */ +#define DMA_CCR_MSIZE_MASK (3 << DMA_CCR_MSIZE_SHIFT) +# define DMA_CCR_MSIZE_8BITS (0 << DMA_CCR_MSIZE_SHIFT) /* 00: 8-bits */ +# define DMA_CCR_MSIZE_16BITS (1 << DMA_CCR_MSIZE_SHIFT) /* 01: 16-bits */ +# define DMA_CCR_MSIZE_32BITS (2 << DMA_CCR_MSIZE_SHIFT) /* 10: 32-bits */ +#define DMA_CCR_PL_SHIFT (12) /* Bits 12-13: Channel Priority level */ +#define DMA_CCR_PL_MASK (3 << DMA_CCR_PL_SHIFT) +# define DMA_CCR_PRILO (0 << DMA_CCR_PL_SHIFT) /* 00: Low */ +# define DMA_CCR_PRIMED (1 << DMA_CCR_PL_SHIFT) /* 01: Medium */ +# define DMA_CCR_PRIHI (2 << DMA_CCR_PL_SHIFT) /* 10: High */ +# define DMA_CCR_PRIVERYHI (3 << DMA_CCR_PL_SHIFT) /* 11: Very high */ +#define DMA_CCR_MEM2MEM (1 << 14) /* Bit 14: Memory to memory mode */ + +#define DMA_CCR_ALLINTS (DMA_CCR_TEIE|DMA_CCR_HTIE|DMA_CCR_TCIE) + +/* DMA channel number of data register */ + +#define DMA_CNDTR_NDT_SHIFT (0) /* Bits 15-0: Number of data to Transfer */ +#define DMA_CNDTR_NDT_MASK (0xffff << DMA_CNDTR_NDT_SHIFT) + +/* DMA Channel mapping. Each DMA channel has a mapping to several possible + * sources/sinks of data. The requests from peripherals assigned to a channel + * are simply OR'ed together before entering the DMA block. This means that only + * one request on a given channel can be enabled at once. + * + * Alternative DMA channel selections are provided with a numeric suffix like _1, + * _2, etc. Drivers, however, will use the pin selection without the numeric suffix. + * Additional definitions are required in the board.h file. + */ + +#define STM32_DMA1_CHAN1 (0) +#define STM32_DMA1_CHAN2 (1) +#define STM32_DMA1_CHAN3 (2) +#define STM32_DMA1_CHAN4 (3) +#define STM32_DMA1_CHAN5 (4) +#define STM32_DMA1_CHAN6 (5) +#define STM32_DMA1_CHAN7 (6) + +#define STM32_DMA2_CHAN1 (7) +#define STM32_DMA2_CHAN2 (8) +#define STM32_DMA2_CHAN3 (9) +#define STM32_DMA2_CHAN4 (10) +#define STM32_DMA2_CHAN5 (11) + +#define DMACHAN_ADC1 STM32_DMA1_CHAN1 +#define DMACHAN_TIM2_CH3 STM32_DMA1_CHAN1 +#define DMACHAN_TIM17_CH1_1 STM32_DMA1_CHAN1 +#define DMACHAN_TIM17_UP_1 STM32_DMA1_CHAN1 + +#define DMACHAN_ADC2_1 STM32_DMA1_CHAN2 +#define DMACHAN_SPI1_RX_1 STM32_DMA1_CHAN2 +#define DMACHAN_USART3_TX STM32_DMA1_CHAN2 +#define DMACHAN_I2C1_TX_3 STM32_DMA1_CHAN4 +#define DMACHAN_TIM1_CH1 STM32_DMA1_CHAN2 +#define DMACHAN_TIM2_UP STM32_DMA1_CHAN2 +#define DMACHAN_TIM3_CH3 STM32_DMA1_CHAN2 +#define DMACHAN_HRTIM1_M STM32_DMA1_CHAN2 + +#define DMACHAN_SPI1_TX_1 STM32_DMA1_CHAN3 +#define DMACHAN_USART3_RX STM32_DMA1_CHAN3 +#define DMACHAN_I2C1_RX_2 STM32_DMA1_CHAN3 +#define DMACHAN_TIM3_CH4 STM32_DMA1_CHAN3 +#define DMACHAN_TIM3_UP STM32_DMA1_CHAN3 +#define DMACHAN_TIM6_UP STM32_DMA1_CHAN3 +#define DMACHAN_DAC1_CH1 STM32_DMA1_CHAN3 +#define DMACHAN_DAC16_CH1_1 STM32_DMA1_CHAN3 +#define DMACHAN_DAC16_UP_1 STM32_DMA1_CHAN3 +#define DMACHAN_HRTIM1_A STM32_DMA1_CHAN3 + +#define DMACHAN_ADC2_2 STM32_DMA1_CHAN4 +#define DMACHAN_SPI1_RX_2 STM32_DMA1_CHAN4 +#define DMACHAN_USART1_TX STM32_DMA1_CHAN4 +#define DMACHAN_I2C1_TX_3 STM32_DMA1_CHAN4 +#define DMACHAN_TIM1_CH4 STM32_DMA1_CHAN4 +#define DMACHAN_TIM1_TRIG STM32_DMA1_CHAN4 +#define DMACHAN_TIM1_COM STM32_DMA1_CHAN4 +#define DMACHAN_TIM7_UP STM32_DMA1_CHAN4 +#define DMACHAN_DAC2_CH2 STM32_DMA1_CHAN4 +#define DMACHAN_HRTIM1_B STM32_DMA1_CHAN4 + +#define DMACHAN_SPI1_TX_2 STM32_DMA1_CHAN5 +#define DMACHAN_USART1_RX STM32_DMA1_CHAN5 +#define DMACHAN_I2C1_RX_3 STM32_DMA1_CHAN5 +#define DMACHAN_TIM1_UP STM32_DMA1_CHAN5 +#define DMACHAN_TIM2_CH1 STM32_DMA1_CHAN5 +#define DMACHAN_DAC2_CH1 STM32_DMA1_CHAN5 +#define DMACHAN_TIM15_CH1 STM32_DMA1_CHAN5 +#define DMACHAN_TIM15_UP STM32_DMA1_CHAN5 +#define DMACHAN_TIM15_TRIG STM32_DMA1_CHAN5 +#define DMACHAN_TIM15_COM STM32_DMA1_CHAN5 +#define DMACHAN_HRTIM1_C STM32_DMA1_CHAN5 + +#define DMACHAN_SPI1_RX_3 STM32_DMA1_CHAN6 +#define DMACHAN_USART2_RX STM32_DMA1_CHAN6 +#define DMACHAN_I2C1_TX_1 STM32_DMA1_CHAN6 +#define DMACHAN_TIM1_CH3 STM32_DMA1_CHAN6 +#define DMACHAN_TIM3_CH1 STM32_DMA1_CHAN6 +#define DMACHAN_TIM3_TRIG STM32_DMA1_CHAN6 +#define DMACHAN_TIM16_CH1_2 STM32_DMA1_CHAN6 +#define DMACHAN_TIM16_UP_2 STM32_DMA1_CHAN6 +#define DMACHAN_HRTIM1_D STM32_DMA1_CHAN6 + +#define DMACHAN_SPI1_TX_3 STM32_DMA1_CHAN7 +#define DMACHAN_USART2_TX STM32_DMA1_CHAN7 +#define DMACHAN_I2C1_RX_1 STM32_DMA1_CHAN7 +#define DMACHAN_TIM2_CH2 STM32_DMA1_CHAN7 +#define DMACHAN_TIM2_CH4 STM32_DMA1_CHAN7 +#define DMACHAN_TIM17_CH1_2 STM32_DMA1_CHAN7 +#define DMACHAN_TIM17_UP_2 STM32_DMA1_CHAN7 +#define DMACHAN_HRTIM1_E STM32_DMA1_CHAN7 + +#endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32F33XXX_DMA_H */ diff --git a/arch/arm/src/stm32/stm32_dma.c b/arch/arm/src/stm32/stm32_dma.c index 0de9cdcc3b..9118c586d4 100644 --- a/arch/arm/src/stm32/stm32_dma.c +++ b/arch/arm/src/stm32/stm32_dma.c @@ -56,9 +56,10 @@ */ #if defined(CONFIG_STM32_STM32L15XX) || defined(CONFIG_STM32_STM32F10XX) || \ - defined(CONFIG_STM32_STM32F30XX) || defined(CONFIG_STM32_STM32F33XX) || \ - defined(CONFIG_STM32_STM32F37XX) + defined(CONFIG_STM32_STM32F30XX) || defined(CONFIG_STM32_STM32F37XX) # include "stm32f10xxx_dma.c" +#elif defined(CONFIG_STM32_STM32F33XX) +# include "stm32f33xxx_dma.c" #elif defined(CONFIG_STM32_STM32F20XX) # include "stm32f20xxx_dma.c" #elif defined(CONFIG_STM32_STM32F40XX) diff --git a/arch/arm/src/stm32/stm32_dma.h b/arch/arm/src/stm32/stm32_dma.h index 36c21f3ca6..c29f7f0d8c 100644 --- a/arch/arm/src/stm32/stm32_dma.h +++ b/arch/arm/src/stm32/stm32_dma.h @@ -48,9 +48,10 @@ /* Include the correct DMA register definitions for this STM32 family */ #if defined(CONFIG_STM32_STM32L15XX) || defined(CONFIG_STM32_STM32F10XX) || \ - defined(CONFIG_STM32_STM32F30XX) || defined(CONFIG_STM32_STM32F33XX) || \ - defined(CONFIG_STM32_STM32F37XX) + defined(CONFIG_STM32_STM32F30XX) || defined(CONFIG_STM32_STM32F37XX) # include "chip/stm32f10xxx_dma.h" +#elif defined(CONFIG_STM32_STM32F33XX) +# include "chip/stm32f33xxx_dma.h" #elif defined(CONFIG_STM32_STM32F20XX) # include "chip/stm32f20xxx_dma.h" #elif defined(CONFIG_STM32_STM32F40XX) diff --git a/arch/arm/src/stm32/stm32f10xxx_dma.c b/arch/arm/src/stm32/stm32f10xxx_dma.c index 1e6751ee56..65136a450f 100644 --- a/arch/arm/src/stm32/stm32f10xxx_dma.c +++ b/arch/arm/src/stm32/stm32f10xxx_dma.c @@ -57,7 +57,8 @@ #if defined(CONFIG_STM32_STM32F10XX) || defined(CONFIG_STM32_STM32F30XX) || \ - defined(CONFIG_STM32_STM32F37XX) || defined(CONFIG_STM32_STM32L15XX) + defined(CONFIG_STM32_STM32F33XX) || defined(CONFIG_STM32_STM32F37XX) || \ + defined(CONFIG_STM32_STM32L15XX) /**************************************************************************** * Pre-processor Definitions diff --git a/arch/arm/src/stm32/stm32f33xxx_dma.c b/arch/arm/src/stm32/stm32f33xxx_dma.c new file mode 100644 index 0000000000..af8601a0fb --- /dev/null +++ b/arch/arm/src/stm32/stm32f33xxx_dma.c @@ -0,0 +1,696 @@ +/**************************************************************************** + * arch/arm/src/stm32/stm32f33xxx_dma.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * Mateusz Szafoni + * + * 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 "up_arch.h" +#include "up_internal.h" +#include "sched/sched.h" +#include "chip.h" +#include "stm32_dma.h" +#include "stm32.h" + +#if defined(CONFIG_STM32_DMA1) && defined(CONFIG_STM32_STM32F33XX) + +#ifndef CONFIG_ARCH_DMA +# warning "STM32 DMA enabled but CONFIG_ARCH_DMA disabled" +#endif + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define DMA1_NCHANNELS 7 +#define DMA_NCHANNELS DMA1_NCHANNELS + +#ifndef CONFIG_DMA_PRI +# define CONFIG_DMA_PRI NVIC_SYSH_PRIORITY_DEFAULT +#endif + +/* Convert the DMA channel base address to the DMA register block address */ + +#define DMA_BASE(ch) (ch & 0xfffffc00) + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/* This structure descibes one DMA channel */ + +struct stm32_dma_s +{ + uint8_t chan; /* DMA channel number (0-6) */ + uint8_t irq; /* DMA channel IRQ number */ + sem_t sem; /* Used to wait for DMA channel to become available */ + uint32_t base; /* DMA register channel base address */ + dma_callback_t callback; /* Callback invoked when the DMA completes */ + void *arg; /* Argument passed to callback function */ +}; + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* This array describes the state of each DMA */ + +static struct stm32_dma_s g_dma[DMA_NCHANNELS] = +{ + { + .chan = 0, + .irq = STM32_IRQ_DMA1CH1, + .base = STM32_DMA1_BASE + STM32_DMACHAN_OFFSET(0), + }, + { + .chan = 1, + .irq = STM32_IRQ_DMA1CH2, + .base = STM32_DMA1_BASE + STM32_DMACHAN_OFFSET(1), + }, + { + .chan = 2, + .irq = STM32_IRQ_DMA1CH3, + .base = STM32_DMA1_BASE + STM32_DMACHAN_OFFSET(2), + }, + { + .chan = 3, + .irq = STM32_IRQ_DMA1CH4, + .base = STM32_DMA1_BASE + STM32_DMACHAN_OFFSET(3), + }, + { + .chan = 4, + .irq = STM32_IRQ_DMA1CH5, + .base = STM32_DMA1_BASE + STM32_DMACHAN_OFFSET(4), + }, + { + .chan = 5, + .irq = STM32_IRQ_DMA1CH6, + .base = STM32_DMA1_BASE + STM32_DMACHAN_OFFSET(5), + }, + { + .chan = 6, + .irq = STM32_IRQ_DMA1CH7, + .base = STM32_DMA1_BASE + STM32_DMACHAN_OFFSET(6), + }, +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * DMA register access functions + ****************************************************************************/ + +/* Get non-channel register from DMA1 or DMA2 */ + +static inline uint32_t dmabase_getreg(struct stm32_dma_s *dmach, uint32_t offset) +{ + return getreg32(DMA_BASE(dmach->base) + offset); +} + +/* Write to non-channel register in DMA1 or DMA2 */ + +static inline void dmabase_putreg(struct stm32_dma_s *dmach, uint32_t offset, uint32_t value) +{ + putreg32(value, DMA_BASE(dmach->base) + offset); +} + +/* Get channel register from DMA1 or DMA2 */ + +static inline uint32_t dmachan_getreg(struct stm32_dma_s *dmach, uint32_t offset) +{ + return getreg32(dmach->base + offset); +} + +/* Write to channel register in DMA1 or DMA2 */ + +static inline void dmachan_putreg(struct stm32_dma_s *dmach, uint32_t offset, uint32_t value) +{ + putreg32(value, dmach->base + offset); +} + +/************************************************************************************ + * Name: stm32_dmatake() and stm32_dmagive() + * + * Description: + * Used to get exclusive access to a DMA channel. + * + ************************************************************************************/ + +static void stm32_dmatake(FAR struct stm32_dma_s *dmach) +{ + /* Take the semaphore (perhaps waiting) */ + + while (sem_wait(&dmach->sem) != 0) + { + /* The only case that an error should occur here is if the wait was awakened + * by a signal. + */ + + ASSERT(errno == EINTR); + } +} + +static inline void stm32_dmagive(FAR struct stm32_dma_s *dmach) +{ + (void)sem_post(&dmach->sem); +} + +/************************************************************************************ + * Name: stm32_dmachandisable + * + * Description: + * Disable the DMA channel + * + ************************************************************************************/ + +static void stm32_dmachandisable(struct stm32_dma_s *dmach) +{ + uint32_t regval; + + /* Disable all interrupts at the DMA controller */ + + regval = dmachan_getreg(dmach, STM32_DMACHAN_CCR_OFFSET); + regval &= ~DMA_CCR_ALLINTS; + + /* Disable the DMA channel */ + + regval &= ~DMA_CCR_EN; + dmachan_putreg(dmach, STM32_DMACHAN_CCR_OFFSET, regval); + + /* Clear pending channel interrupts */ + + dmabase_putreg(dmach, STM32_DMA_IFCR_OFFSET, DMA_ISR_CHAN_MASK(dmach->chan)); +} + +/************************************************************************************ + * Name: stm32_dmainterrupt + * + * Description: + * DMA interrupt handler + * + ************************************************************************************/ + +static int stm32_dmainterrupt(int irq, void *context, FAR void *arg) +{ + struct stm32_dma_s *dmach; + uint32_t isr; + int chndx = 0; + + /* Get the channel structure from the interrupt number */ + + if (irq >= STM32_IRQ_DMA1CH1 && irq <= STM32_IRQ_DMA1CH7) + { + chndx = irq - STM32_IRQ_DMA1CH1; + } + else + { + PANIC(); + } + dmach = &g_dma[chndx]; + + /* Get the interrupt status (for this channel only) */ + + isr = dmabase_getreg(dmach, STM32_DMA_ISR_OFFSET) & DMA_ISR_CHAN_MASK(dmach->chan); + + /* Clear the interrupts we are handling */ + + dmabase_putreg(dmach, STM32_DMA_IFCR_OFFSET, isr); + + /* Invoke the callback */ + + if (dmach->callback) + { + dmach->callback(dmach, isr >> DMA_ISR_CHAN_SHIFT(dmach->chan), dmach->arg); + } + return OK; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_dmainitialize + * + * Description: + * Initialize the DMA subsystem + * + * Returned Value: + * None + * + ****************************************************************************/ + +void weak_function up_dmainitialize(void) +{ + struct stm32_dma_s *dmach; + int chndx; + + /* Initialize each DMA channel */ + + for (chndx = 0; chndx < DMA_NCHANNELS; chndx++) + { + dmach = &g_dma[chndx]; + sem_init(&dmach->sem, 0, 1); + + /* Attach DMA interrupt vectors */ + + (void)irq_attach(dmach->irq, stm32_dmainterrupt, NULL); + + /* Disable the DMA channel */ + + stm32_dmachandisable(dmach); + + /* Enable the IRQ at the NVIC (still disabled at the DMA controller) */ + + up_enable_irq(dmach->irq); + +#ifdef CONFIG_ARCH_IRQPRIO + /* Set the interrupt priority */ + + up_prioritize_irq(dmach->irq, CONFIG_DMA_PRI); +#endif + } +} + +/**************************************************************************** + * Name: stm32_dmachannel + * + * Description: + * Allocate a DMA channel. This function gives the caller mutually + * exclusive access to the DMA channel specified by the 'chndx' argument. + * DMA channels are shared on the STM32: Devices sharing the same DMA + * channel cannot do DMA concurrently! See the DMACHAN_* definitions in + * stm32_dma.h. + * + * If the DMA channel is not available, then stm32_dmachannel() will wait + * until the holder of the channel relinquishes the channel by calling + * stm32_dmafree(). WARNING: If you have two devices sharing a DMA + * channel and the code never releases the channel, the stm32_dmachannel + * call for the other will hang forever in this function! Don't let your + * design do that! + * + * Hmm.. I suppose this interface could be extended to make a non-blocking + * version. Feel free to do that if that is what you need. + * + * Input parameter: + * chndx - Identifies the stream/channel resource. For the STM32 F1, this + * is simply the channel number as provided by the DMACHAN_* definitions + * in chip/stm32f10xxx_dma.h. + * + * Returned Value: + * Provided that 'chndx' is valid, this function ALWAYS returns a non-NULL, + * void* DMA channel handle. (If 'chndx' is invalid, the function will + * assert if debug is enabled or do something ignorant otherwise). + * + * Assumptions: + * - The caller does not hold he DMA channel. + * - The caller can wait for the DMA channel to be freed if it is no + * available. + * + ****************************************************************************/ + +DMA_HANDLE stm32_dmachannel(unsigned int chndx) +{ + struct stm32_dma_s *dmach = &g_dma[chndx]; + + DEBUGASSERT(chndx < DMA_NCHANNELS); + + /* Get exclusive access to the DMA channel -- OR wait until the channel + * is available if it is currently being used by another driver + */ + + stm32_dmatake(dmach); + + /* The caller now has exclusive use of the DMA channel */ + + return (DMA_HANDLE)dmach; +} + +/**************************************************************************** + * Name: stm32_dmafree + * + * Description: + * Release a DMA channel. If another thread is waiting for this DMA channel + * in a call to stm32_dmachannel, then this function will re-assign the + * DMA channel to that thread and wake it up. NOTE: The 'handle' used + * in this argument must NEVER be used again until stm32_dmachannel() is + * called again to re-gain access to the channel. + * + * Returned Value: + * None + * + * Assumptions: + * - The caller holds the DMA channel. + * - There is no DMA in progress + * + ****************************************************************************/ + +void stm32_dmafree(DMA_HANDLE handle) +{ + struct stm32_dma_s *dmach = (struct stm32_dma_s *)handle; + + DEBUGASSERT(handle != NULL); + + /* Release the channel */ + + stm32_dmagive(dmach); +} + +/**************************************************************************** + * Name: stm32_dmasetup + * + * Description: + * Configure DMA before using + * + ****************************************************************************/ + +void stm32_dmasetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr, + size_t ntransfers, uint32_t ccr) +{ + struct stm32_dma_s *dmach = (struct stm32_dma_s *)handle; + uint32_t regval; + + /* Then DMA_CNDTRx register can only be modified if the DMA channel is + * disabled. + */ + + regval = dmachan_getreg(dmach, STM32_DMACHAN_CCR_OFFSET); + regval &= ~(DMA_CCR_EN); + dmachan_putreg(dmach, STM32_DMACHAN_CCR_OFFSET, regval); + + /* Set the peripheral register address in the DMA_CPARx register. The data + * will be moved from/to this address to/from the memory after the + * peripheral event. + */ + + dmachan_putreg(dmach, STM32_DMACHAN_CPAR_OFFSET, paddr); + + /* Set the memory address in the DMA_CMARx register. The data will be + * written to or read from this memory after the peripheral event. + */ + + dmachan_putreg(dmach, STM32_DMACHAN_CMAR_OFFSET, maddr); + + /* Configure the total number of data to be transferred in the DMA_CNDTRx + * register. After each peripheral event, this value will be decremented. + */ + + dmachan_putreg(dmach, STM32_DMACHAN_CNDTR_OFFSET, ntransfers); + + /* Configure the channel priority using the PL[1:0] bits in the DMA_CCRx + * register. Configure data transfer direction, circular mode, peripheral & memory + * incremented mode, peripheral & memory data size, and interrupt after + * half and/or full transfer in the DMA_CCRx register. + */ + + regval = dmachan_getreg(dmach, STM32_DMACHAN_CCR_OFFSET); + regval &= ~(DMA_CCR_MEM2MEM | DMA_CCR_PL_MASK | DMA_CCR_MSIZE_MASK | + DMA_CCR_PSIZE_MASK | DMA_CCR_MINC | DMA_CCR_PINC | DMA_CCR_CIRC | + DMA_CCR_DIR); + ccr &= (DMA_CCR_MEM2MEM | DMA_CCR_PL_MASK | DMA_CCR_MSIZE_MASK | + DMA_CCR_PSIZE_MASK | DMA_CCR_MINC | DMA_CCR_PINC | DMA_CCR_CIRC | + DMA_CCR_DIR); + regval |= ccr; + dmachan_putreg(dmach, STM32_DMACHAN_CCR_OFFSET, regval); +} + +/**************************************************************************** + * Name: stm32_dmastart + * + * Description: + * Start the DMA transfer + * + * Assumptions: + * - DMA handle allocated by stm32_dmachannel() + * - No DMA in progress + * + ****************************************************************************/ + +void stm32_dmastart(DMA_HANDLE handle, dma_callback_t callback, + void *arg, bool half) +{ + struct stm32_dma_s *dmach = (struct stm32_dma_s *)handle; + uint32_t ccr; + + DEBUGASSERT(handle != NULL); + + /* Save the callback info. This will be invoked whent the DMA commpletes */ + + dmach->callback = callback; + dmach->arg = arg; + + /* Activate the channel by setting the ENABLE bit in the DMA_CCRx register. + * As soon as the channel is enabled, it can serve any DMA request from the + * peripheral connected on the channel. + */ + + ccr = dmachan_getreg(dmach, STM32_DMACHAN_CCR_OFFSET); + ccr |= DMA_CCR_EN; + + /* In normal mode, interrupt at either half or full completion. In circular mode, + * always interrupt on buffer wrap, and optionally interrupt at the halfway point. + */ + + if ((ccr & DMA_CCR_CIRC) == 0) + { + /* Once half of the bytes are transferred, the half-transfer flag (HTIF) is + * set and an interrupt is generated if the Half-Transfer Interrupt Enable + * bit (HTIE) is set. At the end of the transfer, the Transfer Complete Flag + * (TCIF) is set and an interrupt is generated if the Transfer Complete + * Interrupt Enable bit (TCIE) is set. + */ + + ccr |= (half ? (DMA_CCR_HTIE | DMA_CCR_TEIE) : (DMA_CCR_TCIE | DMA_CCR_TEIE)); + } + else + { + /* In nonstop mode, when the transfer completes it immediately resets + * and starts again. The transfer-complete interrupt is thus always + * enabled, and the half-complete interrupt can be used in circular + * mode to determine when the buffer is half-full, or in double-buffered + * mode to determine when one of the two buffers is full. + */ + + ccr |= (half ? DMA_CCR_HTIE : 0) | DMA_CCR_TCIE | DMA_CCR_TEIE; + } + + dmachan_putreg(dmach, STM32_DMACHAN_CCR_OFFSET, ccr); +} + +/**************************************************************************** + * Name: stm32_dmastop + * + * Description: + * Cancel the DMA. After stm32_dmastop() is called, the DMA channel is + * reset and stm32_dmasetup() must be called before stm32_dmastart() can be + * called again + * + * Assumptions: + * - DMA handle allocated by stm32_dmachannel() + * + ****************************************************************************/ + +void stm32_dmastop(DMA_HANDLE handle) +{ + struct stm32_dma_s *dmach = (struct stm32_dma_s *)handle; + stm32_dmachandisable(dmach); +} + +/**************************************************************************** + * Name: stm32_dmaresidual + * + * Description: + * Returns the number of bytes remaining to be transferred + * + * Assumptions: + * - DMA handle allocated by stm32_dmachannel() + * + ****************************************************************************/ + +size_t stm32_dmaresidual(DMA_HANDLE handle) +{ + struct stm32_dma_s *dmach = (struct stm32_dma_s *)handle; + + return dmachan_getreg(dmach, STM32_DMACHAN_CNDTR_OFFSET); +} + +/**************************************************************************** + * Name: stm32_dmacapable + * + * Description: + * Check if the DMA controller can transfer data to/from given memory + * address. This depends on the internal connections in the ARM bus matrix + * of the processor. Note that this only applies to memory addresses, it + * will return false for any peripheral address. + * + * Returned value: + * True, if transfer is possible. + * + ****************************************************************************/ + +#ifdef CONFIG_STM32_DMACAPABLE +bool stm32_dmacapable(uint32_t maddr, uint32_t count, uint32_t ccr) +{ + uint32_t transfer_size; + uint32_t mend; + + /* Verify that the address conforms to the memory transfer size. + * Transfers to/from memory performed by the DMA controller are + * required to be aligned to their size. + * + * See ST RM0090 rev4, section 9.3.11 + * + * Compute mend inline to avoid a possible non-constant integer + * multiply. + */ + + switch (ccr & DMA_CCR_MSIZE_MASK) + { + case DMA_CCR_MSIZE_8BITS: + transfer_size = 1; + mend = maddr + count - 1; + break; + + case DMA_CCR_MSIZE_16BITS: + transfer_size = 2; + mend = maddr + (count << 1) - 1; + break; + + case DMA_CCR_MSIZE_32BITS: + transfer_size = 4; + mend = maddr + (count << 2) - 1; + break; + + default: + return false; + } + + if ((maddr & (transfer_size - 1)) != 0) + { + return false; + } + + /* Verify that the transfer is to a memory region that supports DMA. */ + + if ((maddr & STM32_REGION_MASK) != (mend & STM32_REGION_MASK)) + { + return false; + } + + switch (maddr & STM32_REGION_MASK) + { + case STM32_SRAM_BASE: + case STM32_CODE_BASE: + /* All RAM and flash is supported */ + + return true; + + default: + /* Everything else is unsupported by DMA */ + + return false; + } +} +#endif + +/**************************************************************************** + * Name: stm32_dmasample + * + * Description: + * Sample DMA register contents + * + * Assumptions: + * - DMA handle allocated by stm32_dmachannel() + * + ****************************************************************************/ + +#ifdef CONFIG_DEBUG_DMA_INFO +void stm32_dmasample(DMA_HANDLE handle, struct stm32_dmaregs_s *regs) +{ + struct stm32_dma_s *dmach = (struct stm32_dma_s *)handle; + irqstate_t flags; + + flags = enter_critical_section(); + regs->isr = dmabase_getreg(dmach, STM32_DMA_ISR_OFFSET); + regs->ccr = dmachan_getreg(dmach, STM32_DMACHAN_CCR_OFFSET); + regs->cndtr = dmachan_getreg(dmach, STM32_DMACHAN_CNDTR_OFFSET); + regs->cpar = dmachan_getreg(dmach, STM32_DMACHAN_CPAR_OFFSET); + regs->cmar = dmachan_getreg(dmach, STM32_DMACHAN_CMAR_OFFSET); + leave_critical_section(flags); +} +#endif + +/**************************************************************************** + * Name: stm32_dmadump + * + * Description: + * Dump previously sampled DMA register contents + * + * Assumptions: + * - DMA handle allocated by stm32_dmachannel() + * + ****************************************************************************/ + +#ifdef CONFIG_DEBUG_DMA_INFO +void stm32_dmadump(DMA_HANDLE handle, const struct stm32_dmaregs_s *regs, + const char *msg) +{ + struct stm32_dma_s *dmach = (struct stm32_dma_s *)handle; + uint32_t dmabase = DMA_BASE(dmach->base); + + dmainfo("DMA Registers: %s\n", msg); + dmainfo(" ISRC[%08x]: %08x\n", dmabase + STM32_DMA_ISR_OFFSET, regs->isr); + dmainfo(" CCR[%08x]: %08x\n", dmach->base + STM32_DMACHAN_CCR_OFFSET, regs->ccr); + dmainfo(" CNDTR[%08x]: %08x\n", dmach->base + STM32_DMACHAN_CNDTR_OFFSET, regs->cndtr); + dmainfo(" CPAR[%08x]: %08x\n", dmach->base + STM32_DMACHAN_CPAR_OFFSET, regs->cpar); + dmainfo(" CMAR[%08x]: %08x\n", dmach->base + STM32_DMACHAN_CMAR_OFFSET, regs->cmar); +} +#endif + +#endif /* CONFIG_STM32_DMA1 && CONFIG_STM32_STM32F33XX */ -- GitLab From fd42900dcc64ad2cf4d45fd4f4d7cfb98b6eccfb Mon Sep 17 00:00:00 2001 From: raiden00pl Date: Sat, 18 Mar 2017 16:34:24 +0100 Subject: [PATCH 090/990] STM32F33: Add ADC support --- arch/arm/src/stm32/stm32_adc.c | 69 ++++++++++++++++++++++------------ 1 file changed, 44 insertions(+), 25 deletions(-) diff --git a/arch/arm/src/stm32/stm32_adc.c b/arch/arm/src/stm32/stm32_adc.c index ef91b77b40..66ae2ce8b0 100644 --- a/arch/arm/src/stm32/stm32_adc.c +++ b/arch/arm/src/stm32/stm32_adc.c @@ -6,6 +6,7 @@ * Authors: Gregory Nutt * Diego Sanchez * Paul Alexander Patience + * Mateusz Szafoni * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -77,11 +78,12 @@ #if defined(CONFIG_STM32_ADC1) || defined(CONFIG_STM32_ADC2) || \ defined(CONFIG_STM32_ADC3) || defined(CONFIG_STM32_ADC4) -/* This implementation is for the STM32 F1, F2, F4 and STM32L15XX only */ +/* This implementation is for the STM32 F1, F2, F3, F4 and STM32L15XX only */ #if defined(CONFIG_STM32_STM32F10XX) || defined(CONFIG_STM32_STM32F20XX) || \ - defined(CONFIG_STM32_STM32F30XX) || defined(CONFIG_STM32_STM32F37XX) || \ - defined(CONFIG_STM32_STM32F40XX) || defined(CONFIG_STM32_STM32L15XX) + defined(CONFIG_STM32_STM32F30XX) || defined(CONFIG_STM32_STM32F33XX) || \ + defined(CONFIG_STM32_STM32F37XX) || defined(CONFIG_STM32_STM32F40XX) || \ + defined(CONFIG_STM32_STM32L15XX) /* At the moment there is no proper implementation for timers external * trigger in STM32L15XX May be added latter @@ -91,6 +93,14 @@ # warning "There is no proper implementation for TIMER TRIGGERS at the moment" #endif +/* At the moment there is no proper implementation for HRTIMER external + * trigger in STM32F33XX + */ + +#if defined(ADC_HAVE_HRTIMER) && defined(CONFIG_STM32_STM32F33XX) +# warning "There is no proper implementation for HRTIMER TRIGGERS at the moment" +#endif + /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ @@ -108,6 +118,10 @@ # define RCC_RSTR_ADC2RST RCC_AHBRSTR_ADC12RST # define RCC_RSTR_ADC3RST RCC_AHBRSTR_ADC34RST # define RCC_RSTR_ADC4RST RCC_AHBRSTR_ADC34RST +#elif defined(CONFIG_STM32_STM32F33XX) +# define STM32_RCC_RSTR STM32_RCC_AHBRSTR +# define RCC_RSTR_ADC1RST RCC_AHBRSTR_ADC12RST +# define RCC_RSTR_ADC2RST RCC_AHBRSTR_ADC12RST #elif defined(CONFIG_STM32_STM32F37XX) # define STM32_RCC_RSTR STM32_RCC_APB2RSTR # define RCC_RSTR_ADC1RST RCC_APB2RSTR_ADCRST @@ -124,7 +138,7 @@ /* ADC interrupts ***********************************************************/ -#ifdef CONFIG_STM32_STM32F30XX +#if defined(CONFIG_STM32_STM32F30XX) || defined(CONFIG_STM32_STM32F33XX) # define STM32_ADC_DMAREG_OFFSET STM32_ADC_CFGR_OFFSET # define ADC_DMAREG_DMA ADC_CFGR_DMAEN # define STM32_ADC_EXTREG_OFFSET STM32_ADC_CFGR_OFFSET @@ -226,7 +240,7 @@ (ADC_SMPR_DEFAULT << ADC_SMPR2_SMP7_SHIFT) | \ (ADC_SMPR_DEFAULT << ADC_SMPR2_SMP8_SHIFT) | \ (ADC_SMPR_DEFAULT << ADC_SMPR2_SMP9_SHIFT)) -#elif defined(CONFIG_STM32_STM32F30XX) +#elif defined(CONFIG_STM32_STM32F30XX) || defined(CONFIG_STM32_STM32F33XX) # if defined(ADC_HAVE_DMA) || (ADC_MAX_SAMPLES == 1) # define ADC_SMPR_DEFAULT ADC_SMPR_61p5 # else /* Slow down sampling frequency */ @@ -338,8 +352,8 @@ struct stm32_dev_s /* ADC Register access */ #if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F30XX) || \ - defined(CONFIG_STM32_STM32F37XX) ||defined(CONFIG_STM32_STM32F40XX) || \ - defined(CONFIG_STM32_STM32L15XX) + defined(CONFIG_STM32_STM32F33XX) || defined(CONFIG_STM32_STM32F37XX) || \ + defined(CONFIG_STM32_STM32F40XX) || defined(CONFIG_STM32_STM32L15XX) static void stm32_modifyreg32(unsigned int addr, uint32_t clrbits, uint32_t setbits); #endif @@ -606,8 +620,8 @@ static struct adc_dev_s g_adcdev4 = ****************************************************************************/ #if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F30XX) || \ - defined(CONFIG_STM32_STM32F37XX) ||defined(CONFIG_STM32_STM32F40XX) || \ - defined(CONFIG_STM32_STM32L15XX) + defined(CONFIG_STM32_STM32F33XX) || defined(CONFIG_STM32_STM32F37XX) || \ + defined(CONFIG_STM32_STM32F40XX) || defined(CONFIG_STM32_STM32L15XX) static void stm32_modifyreg32(unsigned int addr, uint32_t clrbits, uint32_t setbits) { @@ -1242,7 +1256,7 @@ static void adc_startconv(FAR struct stm32_dev_s *priv, bool enable) adc_enable(priv, true); } -#elif defined(CONFIG_STM32_STM32F30XX) +#elif defined(CONFIG_STM32_STM32F30XX) || defined(CONFIG_STM32_STM32F33XX) static void adc_startconv(FAR struct stm32_dev_s *priv, bool enable) { uint32_t regval; @@ -1520,7 +1534,7 @@ static void adc_select_ch_bank(FAR struct stm32_dev_s *priv, * ****************************************************************************/ -#ifdef CONFIG_STM32_STM32F30XX +#if defined(CONFIG_STM32_STM32F30XX) || defined(CONFIG_STM32_STM32F33XX) static void adc_enable(FAR struct stm32_dev_s *priv, bool enable) { uint32_t regval; @@ -1699,8 +1713,8 @@ static void adc_dmaconvcallback(DMA_HANDLE handle, uint8_t isr, FAR void *arg) * Name: adc_bind * * Description: - * Bind the upper-half driver callbacks to the lower-half implementation. This - * must be called early in order to receive ADC event notifications. + * Bind the upper-half driver callbacks to the lower-half implementation. + * This must be called early in order to receive ADC event notifications. * ****************************************************************************/ @@ -1718,8 +1732,8 @@ static int adc_bind(FAR struct adc_dev_s *dev, * Name: adc_reset * * Description: - * Reset the ADC device. Called early to initialize the hardware. This - * is called, before adc_setup() and on error conditions. + * Reset the ADC device. Called early to initialize the hardware. + * This is called, before adc_setup() and on error conditions. * * Input Parameters: * @@ -1751,7 +1765,7 @@ static void adc_reset(FAR struct adc_dev_s *dev) #endif -#ifdef CONFIG_STM32_STM32F30XX +#if defined(CONFIG_STM32_STM32F30XX) || defined(CONFIG_STM32_STM32F33XX) /* Turn off the ADC so we can write the RCC bits */ @@ -1767,7 +1781,7 @@ static void adc_reset(FAR struct adc_dev_s *dev) adc_rccreset(priv, false); -#ifdef CONFIG_STM32_STM32F30XX +#if defined(CONFIG_STM32_STM32F30XX) || defined(CONFIG_STM32_STM32F33XX) /* Set voltage regular enable to intermediate state */ @@ -1822,7 +1836,7 @@ static void adc_reset(FAR struct adc_dev_s *dev) adc_putreg(priv, STM32_ADC_SMPR2_OFFSET, ADC_SMPR2_DEFAULT); #endif -#ifdef CONFIG_STM32_STM32F30XX +#if defined(CONFIG_STM32_STM32F30XX) || defined(CONFIG_STM32_STM32F33XX) /* Enable the analog watchdog */ @@ -1870,7 +1884,7 @@ static void adc_reset(FAR struct adc_dev_s *dev) adc_modifyreg(priv, STM32_ADC_IER_OFFSET, clrbits, setbits); -#else /* ifdef CONFIG_STM32_STM32F30XX */ +#else /* CONFIG_STM32_STM32F30XX || CONFIG_STM32_STM33XX */ /* Enable the analog watchdog */ @@ -1968,7 +1982,7 @@ static void adc_reset(FAR struct adc_dev_s *dev) /* ADC CCR configuration */ -#if defined(CONFIG_STM32_STM32F30XX) +#if defined(CONFIG_STM32_STM32F30XX) || defined(CONFIG_STM32_STM32F33XX) clrbits = ADC_CCR_DUAL_MASK | ADC_CCR_DELAY_MASK | ADC_CCR_DMACFG | ADC_CCR_MDMA_MASK | ADC_CCR_CKMODE_MASK | ADC_CCR_VREFEN | ADC_CCR_TSEN | ADC_CCR_VBATEN; @@ -1979,10 +1993,12 @@ static void adc_reset(FAR struct adc_dev_s *dev) { stm32_modifyreg32(STM32_ADC12_CCR, clrbits, setbits); } +#ifndef CONFIG_STM32_STM32F33XX else { stm32_modifyreg32(STM32_ADC34_CCR, clrbits, setbits); } +#endif #elif defined(CONFIG_STM32_STM32F20XX) || \ defined(CONFIG_STM32_STM32F40XX) || \ defined(CONFIG_STM32_STM32L15XX) @@ -2050,7 +2066,7 @@ static void adc_reset(FAR struct adc_dev_s *dev) leave_critical_section(flags); -#ifdef CONFIG_STM32_STM32F30XX +#if defined(CONFIG_STM32_STM32F30XX) || defined(CONFIG_STM32_STM32F33XX) ainfo("ISR: 0x%08x CR: 0x%08x CFGR: 0x%08x\n", adc_getreg(priv, STM32_ADC_ISR_OFFSET), adc_getreg(priv, STM32_ADC_CR_OFFSET), @@ -2067,7 +2083,7 @@ static void adc_reset(FAR struct adc_dev_s *dev) adc_getreg(priv, STM32_ADC_SQR2_OFFSET), adc_getreg(priv, STM32_ADC_SQR3_OFFSET)); -#if defined(CONFIG_STM32_STM32F30XX) +#if defined(CONFIG_STM32_STM32F30XX) || defined(CONFIG_STM32_STM32F33XX) ainfo("SQR4: 0x%08x\n", adc_getreg(priv, STM32_ADC_SQR4_OFFSET)); #elif defined(CONFIG_STM32_STM32L15XX) ainfo("SQR4: 0x%08x SQR5: 0x%08x\n", @@ -2075,15 +2091,17 @@ static void adc_reset(FAR struct adc_dev_s *dev) adc_getreg(priv, STM32_ADC_SQR5_OFFSET)); #endif -#if defined(CONFIG_STM32_STM32F30XX) +#if defined(CONFIG_STM32_STM32F30XX) || defined(CONFIG_STM32_STM32F33XX) if (priv->base == STM32_ADC1_BASE || priv->base == STM32_ADC2_BASE) { ainfo("CCR: 0x%08x\n", getreg32(STM32_ADC12_CCR)); } +#ifndef CONFIG_STM32_STM32F33XX else { ainfo("CCR: 0x%08x\n", getreg32(STM32_ADC34_CCR)); } +#endif #elif defined(CONFIG_STM32_STM32F20XX) || \ defined(CONFIG_STM32_STM32F40XX) || \ defined(CONFIG_STM32_STM32L15XX) @@ -3085,8 +3103,9 @@ struct adc_dev_s *stm32_adcinitialize(int intf, FAR const uint8_t *chanlist, } #endif /* CONFIG_STM32_STM32F10XX || CONFIG_STM32_STM32F20XX || - * CONFIG_STM32_STM32F30XX || CONFIG_STM32_STM32F47XX || - * CONFIG_STM32_STM32F40XX || CONFIG_STM32_STM32L15XX + * CONFIG_STM32_STM32F30XX || CONFIG_STM32_STM32F33XX || + * CONFIG_STM32_STM32F47XX || CONFIG_STM32_STM32F40XX || + * CONFIG_STM32_STM32L15XX */ #endif /* CONFIG_STM32_ADC1 || CONFIG_STM32_ADC2 || * CONFIG_STM32_ADC3 || CONFIG_STM32_ADC4 -- GitLab From 8491cd65bca944709fd3b6fc85e0927cb579c917 Mon Sep 17 00:00:00 2001 From: raiden00pl Date: Sat, 18 Mar 2017 16:39:40 +0100 Subject: [PATCH 091/990] configs/nucleo_f334r8: add ADC example --- configs/nucleo-f334r8/adc/Make.defs | 113 ++ configs/nucleo-f334r8/adc/defconfig | 1239 +++++++++++++++++++++ configs/nucleo-f334r8/adc/setenv.sh | 77 ++ configs/nucleo-f334r8/include/board.h | 4 +- configs/nucleo-f334r8/src/stm32_adc.c | 253 +++++ configs/nucleo-f334r8/src/stm32_appinit.c | 22 +- configs/nucleo-f334r8/src/stm32_boot.c | 3 +- 7 files changed, 1707 insertions(+), 4 deletions(-) create mode 100644 configs/nucleo-f334r8/adc/Make.defs create mode 100644 configs/nucleo-f334r8/adc/defconfig create mode 100644 configs/nucleo-f334r8/adc/setenv.sh diff --git a/configs/nucleo-f334r8/adc/Make.defs b/configs/nucleo-f334r8/adc/Make.defs new file mode 100644 index 0000000000..192071b180 --- /dev/null +++ b/configs/nucleo-f334r8/adc/Make.defs @@ -0,0 +1,113 @@ +############################################################################ +# configs/nucleo-f334r8/adc/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. +# +############################################################################ + +include ${TOPDIR}/.config +include ${TOPDIR}/tools/Config.mk +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs + +LDSCRIPT = ld.script + +ifeq ($(WINTOOL),y) + # Windows-native toolchains + DIRLINK = $(TOPDIR)/tools/copydir.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mkwindeps.sh + ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" + ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" +else + # Linux/Cygwin-native toolchain + MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT) + ARCHINCLUDES = -I. -isystem $(TOPDIR)/include + ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) +endif + +CC = $(CROSSDEV)gcc +CXX = $(CROSSDEV)g++ +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(ARCROSSDEV)ar rcs +NM = $(ARCROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump + +ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} +ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} + +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + ARCHOPTIMIZATION = -g +endif + +ifneq ($(CONFIG_DEBUG_NOOPT),y) + ARCHOPTIMIZATION += $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer +endif + +ARCHCFLAGS = -fno-builtin +ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fcheck-new -fno-rtti +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow -Wundef +ARCHWARNINGSXX = -Wall -Wshadow -Wundef +ARCHDEFINES = +ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 + +CFLAGS = $(ARCHCFLAGS) $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) +CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +NXFLATLDFLAGS1 = -r -d -warn-common +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections +LDNXFLATFLAGS = -e main -s 2048 + +ASMEXT = .S +OBJEXT = .o +LIBEXT = .a +EXEEXT = + +ifneq ($(CROSSDEV),arm-nuttx-elf-) + LDFLAGS += -nostartfiles -nodefaultlibs +endif +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + LDFLAGS += -g +endif + + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -Wundef -g -pipe +HOSTLDFLAGS = + diff --git a/configs/nucleo-f334r8/adc/defconfig b/configs/nucleo-f334r8/adc/defconfig new file mode 100644 index 0000000000..9a8481f516 --- /dev/null +++ b/configs/nucleo-f334r8/adc/defconfig @@ -0,0 +1,1239 @@ +# +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# + +# +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set +# CONFIG_DEFAULT_SMALL is not set +CONFIG_HOST_LINUX=y +# CONFIG_HOST_OSX is not set +# CONFIG_HOST_WINDOWS is not set +# CONFIG_HOST_OTHER is not set + +# +# Build Configuration +# +# CONFIG_APPS_DIR="../apps" +CONFIG_BUILD_FLAT=y +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +CONFIG_INTELHEX_BINARY=y +# CONFIG_MOTOROLA_SREC is not set +CONFIG_RAW_BINARY=y +# CONFIG_UBOOT_UIMAGE is not set + +# +# Customize Header Files +# +# CONFIG_ARCH_STDINT_H is not set +# CONFIG_ARCH_STDBOOL_H is not set +# CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_FLOAT_H is not set +# CONFIG_ARCH_STDARG_H is not set +# CONFIG_ARCH_DEBUG_H is not set + +# +# Debug Options +# +CONFIG_DEBUG_ALERT=y +CONFIG_DEBUG_FEATURES=y + +# +# Debug SYSLOG Output Controls +# +CONFIG_DEBUG_ERROR=y +CONFIG_DEBUG_INFO=y +CONFIG_DEBUG_ERROR=y +CONFIG_DEBUG_ASSERTIONS=y + +# +# Subsystem Debug Options +# +# CONFIG_DEBUG_BINFMT is not set +# CONFIG_DEBUG_FS is not set +# CONFIG_DEBUG_GRAPHICS is not set +# CONFIG_DEBUG_LIB is not set +# CONFIG_DEBUG_MM is not set +# CONFIG_DEBUG_SCHED is not set + +# +# OS Function Debug Options +# +# CONFIG_DEBUG_IRQ is not set + +# +# Driver Debug Options +# +# CONFIG_DEBUG_LEDS is not set +# CONFIG_DEBUG_GPIO is not set +# CONFIG_DEBUG_TIMER is not set +CONFIG_ARCH_HAVE_STACKCHECK=y +# CONFIG_STACK_COLORATION is not set +CONFIG_ARCH_HAVE_HEAPCHECK=y +# CONFIG_HEAP_COLORATION is not set +CONFIG_DEBUG_SYMBOLS=y +CONFIG_ARCH_HAVE_CUSTOMOPT=y +# CONFIG_DEBUG_NOOPT is not set +# CONFIG_DEBUG_CUSTOMOPT is not set +CONFIG_DEBUG_FULLOPT=y + +# +# System Type +# +CONFIG_ARCH_ARM=y +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_MISOC is not set +# CONFIG_ARCH_RENESAS is not set +# CONFIG_ARCH_RISCV is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_XTENSA is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="arm" + +# +# ARM Options +# +# CONFIG_ARCH_CHIP_A1X is not set +# CONFIG_ARCH_CHIP_C5471 is not set +# CONFIG_ARCH_CHIP_DM320 is not set +# CONFIG_ARCH_CHIP_EFM32 is not set +# CONFIG_ARCH_CHIP_IMX1 is not set +# CONFIG_ARCH_CHIP_IMX6 is not set +# CONFIG_ARCH_CHIP_KINETIS is not set +# CONFIG_ARCH_CHIP_KL is not set +# CONFIG_ARCH_CHIP_LM is not set +# CONFIG_ARCH_CHIP_TIVA is not set +# CONFIG_ARCH_CHIP_LPC11XX is not set +# CONFIG_ARCH_CHIP_LPC17XX is not set +# CONFIG_ARCH_CHIP_LPC214X is not set +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_NUC1XX is not set +# CONFIG_ARCH_CHIP_SAMA5 is not set +# CONFIG_ARCH_CHIP_SAMD is not set +# CONFIG_ARCH_CHIP_SAML is not set +# CONFIG_ARCH_CHIP_SAM34 is not set +# CONFIG_ARCH_CHIP_SAMV7 is not set +CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F7 is not set +# CONFIG_ARCH_CHIP_STM32L4 is not set +# CONFIG_ARCH_CHIP_STR71X is not set +# CONFIG_ARCH_CHIP_TMS570 is not set +# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_ARM7TDMI is not set +# CONFIG_ARCH_ARM926EJS is not set +# CONFIG_ARCH_ARM920T is not set +# CONFIG_ARCH_CORTEXM0 is not set +# CONFIG_ARCH_CORTEXM23 is not set +# CONFIG_ARCH_CORTEXM3 is not set +# CONFIG_ARCH_CORTEXM33 is not set +CONFIG_ARCH_CORTEXM4=y +# CONFIG_ARCH_CORTEXM7 is not set +# CONFIG_ARCH_CORTEXA5 is not set +# CONFIG_ARCH_CORTEXA8 is not set +# CONFIG_ARCH_CORTEXA9 is not set +# CONFIG_ARCH_CORTEXR4 is not set +# CONFIG_ARCH_CORTEXR4F is not set +# CONFIG_ARCH_CORTEXR5 is not set +# CONFIG_ARCH_CORTEX5F is not set +# CONFIG_ARCH_CORTEXR7 is not set +# CONFIG_ARCH_CORTEXR7F is not set +CONFIG_ARCH_FAMILY="armv7-m" +CONFIG_ARCH_CHIP="stm32" +# CONFIG_ARM_TOOLCHAIN_IAR is not set +CONFIG_ARM_TOOLCHAIN_GNU=y +# CONFIG_ARMV7M_USEBASEPRI is not set +CONFIG_ARCH_HAVE_CMNVECTOR=y +# CONFIG_ARMV7M_CMNVECTOR is not set +# CONFIG_ARMV7M_LAZYFPU is not set +CONFIG_ARCH_HAVE_FPU=y +# CONFIG_ARCH_HAVE_DPFPU is not set +# CONFIG_ARCH_FPU is not set +# CONFIG_ARCH_HAVE_TRUSTZONE is not set +CONFIG_ARM_HAVE_MPU_UNIFIED=y +# CONFIG_ARM_MPU is not set +# CONFIG_DEBUG_HARDFAULT is not set + +# +# ARMV7M Configuration Options +# +# CONFIG_ARMV7M_HAVE_ICACHE is not set +# CONFIG_ARMV7M_HAVE_DCACHE is not set +# CONFIG_ARMV7M_HAVE_ITCM is not set +# CONFIG_ARMV7M_HAVE_DTCM is not set +# CONFIG_ARMV7M_TOOLCHAIN_IARL is not set +CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y +# CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set +# CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL is not set +# CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL is not set +# CONFIG_ARMV7M_OABI_TOOLCHAIN is not set +CONFIG_ARMV7M_HAVE_STACKCHECK=y +# CONFIG_ARMV7M_STACKCHECK is not set +# CONFIG_ARMV7M_ITMSYSLOG is not set +# CONFIG_SERIAL_TERMIOS is not set + +# +# STM32 Configuration Options +# +# CONFIG_ARCH_CHIP_STM32L151C6 is not set +# CONFIG_ARCH_CHIP_STM32L151C8 is not set +# CONFIG_ARCH_CHIP_STM32L151CB is not set +# CONFIG_ARCH_CHIP_STM32L151R6 is not set +# CONFIG_ARCH_CHIP_STM32L151R8 is not set +# CONFIG_ARCH_CHIP_STM32L151RB is not set +# CONFIG_ARCH_CHIP_STM32L151V6 is not set +# CONFIG_ARCH_CHIP_STM32L151V8 is not set +# CONFIG_ARCH_CHIP_STM32L151VB is not set +# CONFIG_ARCH_CHIP_STM32L152C6 is not set +# CONFIG_ARCH_CHIP_STM32L152C8 is not set +# CONFIG_ARCH_CHIP_STM32L152CB is not set +# CONFIG_ARCH_CHIP_STM32L152R6 is not set +# CONFIG_ARCH_CHIP_STM32L152R8 is not set +# CONFIG_ARCH_CHIP_STM32L152RB is not set +# CONFIG_ARCH_CHIP_STM32L152V6 is not set +# CONFIG_ARCH_CHIP_STM32L152V8 is not set +# CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L162ZD is not set +# CONFIG_ARCH_CHIP_STM32L162VE is not set +# CONFIG_ARCH_CHIP_STM32F100C8 is not set +# CONFIG_ARCH_CHIP_STM32F100CB is not set +# CONFIG_ARCH_CHIP_STM32F100R8 is not set +# CONFIG_ARCH_CHIP_STM32F100RB is not set +# CONFIG_ARCH_CHIP_STM32F100RC is not set +# CONFIG_ARCH_CHIP_STM32F100RD is not set +# CONFIG_ARCH_CHIP_STM32F100RE is not set +# CONFIG_ARCH_CHIP_STM32F100V8 is not set +# CONFIG_ARCH_CHIP_STM32F100VB is not set +# CONFIG_ARCH_CHIP_STM32F100VC is not set +# CONFIG_ARCH_CHIP_STM32F100VD is not set +# CONFIG_ARCH_CHIP_STM32F100VE is not set +# CONFIG_ARCH_CHIP_STM32F102CB is not set +# CONFIG_ARCH_CHIP_STM32F103T8 is not set +# CONFIG_ARCH_CHIP_STM32F103TB is not set +# CONFIG_ARCH_CHIP_STM32F103C4 is not set +# CONFIG_ARCH_CHIP_STM32F103C8 is not set +# CONFIG_ARCH_CHIP_STM32F103CB is not set +# CONFIG_ARCH_CHIP_STM32F103R8 is not set +# CONFIG_ARCH_CHIP_STM32F103RB is not set +# CONFIG_ARCH_CHIP_STM32F103RC is not set +# CONFIG_ARCH_CHIP_STM32F103RD is not set +# CONFIG_ARCH_CHIP_STM32F103RE is not set +# CONFIG_ARCH_CHIP_STM32F103RG is not set +# CONFIG_ARCH_CHIP_STM32F103V8 is not set +# CONFIG_ARCH_CHIP_STM32F103VB is not set +# CONFIG_ARCH_CHIP_STM32F103VC is not set +# CONFIG_ARCH_CHIP_STM32F103VE is not set +# CONFIG_ARCH_CHIP_STM32F103ZE is not set +# CONFIG_ARCH_CHIP_STM32F105VB is not set +# CONFIG_ARCH_CHIP_STM32F105RB is not set +# CONFIG_ARCH_CHIP_STM32F107VC is not set +# CONFIG_ARCH_CHIP_STM32F205RG is not set +# CONFIG_ARCH_CHIP_STM32F207IG is not set +# CONFIG_ARCH_CHIP_STM32F207ZE is not set +# CONFIG_ARCH_CHIP_STM32F302K6 is not set +# CONFIG_ARCH_CHIP_STM32F302K8 is not set +# CONFIG_ARCH_CHIP_STM32F302CB is not set +# CONFIG_ARCH_CHIP_STM32F302CC is not set +# CONFIG_ARCH_CHIP_STM32F302RB is not set +# CONFIG_ARCH_CHIP_STM32F302RC is not set +# CONFIG_ARCH_CHIP_STM32F302VB is not set +# CONFIG_ARCH_CHIP_STM32F302VC is not set +# CONFIG_ARCH_CHIP_STM32F303K6 is not set +# CONFIG_ARCH_CHIP_STM32F303K8 is not set +# CONFIG_ARCH_CHIP_STM32F303C6 is not set +# CONFIG_ARCH_CHIP_STM32F303C8 is not set +# CONFIG_ARCH_CHIP_STM32F303CB is not set +# CONFIG_ARCH_CHIP_STM32F303CC is not set +# CONFIG_ARCH_CHIP_STM32F303RB is not set +# CONFIG_ARCH_CHIP_STM32F303RC is not set +# CONFIG_ARCH_CHIP_STM32F303RD is not set +# CONFIG_ARCH_CHIP_STM32F303RE is not set +# CONFIG_ARCH_CHIP_STM32F303VB is not set +# CONFIG_ARCH_CHIP_STM32F303VC is not set +# CONFIG_ARCH_CHIP_STM32F334K4 is not set +# CONFIG_ARCH_CHIP_STM32F334K6 is not set +# CONFIG_ARCH_CHIP_STM32F334K8 is not set +# CONFIG_ARCH_CHIP_STM32F334C4 is not set +# CONFIG_ARCH_CHIP_STM32F334C6 is not set +# CONFIG_ARCH_CHIP_STM32F334C8 is not set +# CONFIG_ARCH_CHIP_STM32F334R4 is not set +# CONFIG_ARCH_CHIP_STM32F334R6 is not set +CONFIG_ARCH_CHIP_STM32F334R8=y +# CONFIG_ARCH_CHIP_STM32F372C8 is not set +# CONFIG_ARCH_CHIP_STM32F372R8 is not set +# CONFIG_ARCH_CHIP_STM32F372V8 is not set +# CONFIG_ARCH_CHIP_STM32F372CB is not set +# CONFIG_ARCH_CHIP_STM32F372RB is not set +# CONFIG_ARCH_CHIP_STM32F372VB is not set +# CONFIG_ARCH_CHIP_STM32F372CC is not set +# CONFIG_ARCH_CHIP_STM32F372RC is not set +# CONFIG_ARCH_CHIP_STM32F372VC is not set +# CONFIG_ARCH_CHIP_STM32F373C8 is not set +# CONFIG_ARCH_CHIP_STM32F373R8 is not set +# CONFIG_ARCH_CHIP_STM32F373V8 is not set +# CONFIG_ARCH_CHIP_STM32F373CB is not set +# CONFIG_ARCH_CHIP_STM32F373RB is not set +# CONFIG_ARCH_CHIP_STM32F373VB is not set +# CONFIG_ARCH_CHIP_STM32F373CC is not set +# CONFIG_ARCH_CHIP_STM32F373RC is not set +# CONFIG_ARCH_CHIP_STM32F373VC is not set +# CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F411RE is not set +# CONFIG_ARCH_CHIP_STM32F411VE is not set +# CONFIG_ARCH_CHIP_STM32F405RG is not set +# CONFIG_ARCH_CHIP_STM32F405VG is not set +# CONFIG_ARCH_CHIP_STM32F405ZG is not set +# CONFIG_ARCH_CHIP_STM32F407VE is not set +# CONFIG_ARCH_CHIP_STM32F407VG is not set +# CONFIG_ARCH_CHIP_STM32F407ZE is not set +# CONFIG_ARCH_CHIP_STM32F407ZG is not set +# CONFIG_ARCH_CHIP_STM32F407IE is not set +# CONFIG_ARCH_CHIP_STM32F407IG is not set +# CONFIG_ARCH_CHIP_STM32F427V is not set +# CONFIG_ARCH_CHIP_STM32F427Z is not set +# CONFIG_ARCH_CHIP_STM32F427I is not set +# CONFIG_ARCH_CHIP_STM32F429V is not set +# CONFIG_ARCH_CHIP_STM32F429Z is not set +# CONFIG_ARCH_CHIP_STM32F429I is not set +# CONFIG_ARCH_CHIP_STM32F429B is not set +# CONFIG_ARCH_CHIP_STM32F429N is not set +# CONFIG_ARCH_CHIP_STM32F446M is not set +# CONFIG_ARCH_CHIP_STM32F446R is not set +# CONFIG_ARCH_CHIP_STM32F446V is not set +# CONFIG_ARCH_CHIP_STM32F446Z is not set +# CONFIG_ARCH_CHIP_STM32F469A is not set +# CONFIG_ARCH_CHIP_STM32F469I is not set +# CONFIG_ARCH_CHIP_STM32F469B is not set +# CONFIG_ARCH_CHIP_STM32F469N is not set +CONFIG_STM32_FLASH_CONFIG_DEFAULT=y +# CONFIG_STM32_FLASH_CONFIG_4 is not set +# CONFIG_STM32_FLASH_CONFIG_6 is not set +# CONFIG_STM32_FLASH_CONFIG_8 is not set +# CONFIG_STM32_FLASH_CONFIG_B is not set +# CONFIG_STM32_FLASH_CONFIG_C is not set +# CONFIG_STM32_FLASH_CONFIG_D is not set +# CONFIG_STM32_FLASH_CONFIG_E is not set +# CONFIG_STM32_FLASH_CONFIG_F is not set +# CONFIG_STM32_FLASH_CONFIG_G is not set +# CONFIG_STM32_FLASH_CONFIG_I is not set +# CONFIG_STM32_STM32L15XX is not set +# CONFIG_STM32_ENERGYLITE is not set +# CONFIG_STM32_STM32F10XX is not set +# CONFIG_STM32_VALUELINE is not set +# CONFIG_STM32_CONNECTIVITYLINE is not set +# CONFIG_STM32_PERFORMANCELINE is not set +# CONFIG_STM32_USBACCESSLINE is not set +# CONFIG_STM32_HIGHDENSITY is not set +# CONFIG_STM32_MEDIUMDENSITY is not set +# CONFIG_STM32_LOWDENSITY is not set +# CONFIG_STM32_STM32F20XX is not set +# CONFIG_STM32_STM32F205 is not set +# CONFIG_STM32_STM32F207 is not set +# CONFIG_STM32_STM32F30XX is not set +# CONFIG_STM32_STM32F302 is not set +# CONFIG_STM32_STM32F303 is not set +CONFIG_STM32_STM32F33XX=y +# CONFIG_STM32_STM32F37XX is not set +# CONFIG_STM32_STM32F40XX is not set +# CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F411 is not set +# CONFIG_STM32_STM32F405 is not set +# CONFIG_STM32_STM32F407 is not set +# CONFIG_STM32_STM32F427 is not set +# CONFIG_STM32_STM32F429 is not set +# CONFIG_STM32_STM32F446 is not set +# CONFIG_STM32_STM32F469 is not set +# CONFIG_STM32_DFU is not set + +# +# STM32 Peripheral Support +# +CONFIG_STM32_HAVE_CCM=y +# CONFIG_STM32_HAVE_USBDEV is not set +# CONFIG_STM32_HAVE_OTGFS is not set +# CONFIG_STM32_HAVE_FSMC is not set +CONFIG_STM32_HAVE_HRTIM1=y +# CONFIG_STM32_HAVE_LTDC is not set +CONFIG_STM32_HAVE_USART3=y +# CONFIG_STM32_HAVE_UART4 is not set +# CONFIG_STM32_HAVE_UART5 is not set +# CONFIG_STM32_HAVE_USART6 is not set +# CONFIG_STM32_HAVE_UART7 is not set +# CONFIG_STM32_HAVE_UART8 is not set +CONFIG_STM32_HAVE_TIM1=y +# CONFIG_STM32_HAVE_TIM2 is not set +# CONFIG_STM32_HAVE_TIM3 is not set +# CONFIG_STM32_HAVE_TIM4 is not set +# CONFIG_STM32_HAVE_TIM5 is not set +# CONFIG_STM32_HAVE_TIM6 is not set +# CONFIG_STM32_HAVE_TIM7 is not set +# CONFIG_STM32_HAVE_TIM8 is not set +# CONFIG_STM32_HAVE_TIM9 is not set +# CONFIG_STM32_HAVE_TIM10 is not set +# CONFIG_STM32_HAVE_TIM11 is not set +# CONFIG_STM32_HAVE_TIM12 is not set +# CONFIG_STM32_HAVE_TIM13 is not set +# CONFIG_STM32_HAVE_TIM14 is not set +CONFIG_STM32_HAVE_TIM15=y +CONFIG_STM32_HAVE_TIM16=y +CONFIG_STM32_HAVE_TIM17=y +CONFIG_STM32_HAVE_ADC2=y +# CONFIG_STM32_HAVE_ADC3 is not set +# CONFIG_STM32_HAVE_ADC4 is not set +CONFIG_STM32_HAVE_ADC1_DMA=y +# CONFIG_STM32_HAVE_ADC2_DMA is not set +# CONFIG_STM32_HAVE_ADC3_DMA is not set +# CONFIG_STM32_HAVE_ADC4_DMA is not set +# CONFIG_STM32_HAVE_SDADC1 is not set +# CONFIG_STM32_HAVE_SDADC2 is not set +# CONFIG_STM32_HAVE_SDADC3 is not set +# CONFIG_STM32_HAVE_SDADC1_DMA is not set +# CONFIG_STM32_HAVE_SDADC2_DMA is not set +# CONFIG_STM32_HAVE_SDADC3_DMA is not set +CONFIG_STM32_HAVE_CAN1=y +# CONFIG_STM32_HAVE_CAN2 is not set +CONFIG_STM32_HAVE_COMP2=y +CONFIG_STM32_HAVE_COMP4=y +CONFIG_STM32_HAVE_COMP6=y +CONFIG_STM32_HAVE_DAC1=y +CONFIG_STM32_HAVE_DAC2=y +# CONFIG_STM32_HAVE_RNG is not set +# CONFIG_STM32_HAVE_ETHMAC is not set +# CONFIG_STM32_HAVE_I2C2 is not set +# CONFIG_STM32_HAVE_I2C3 is not set +# CONFIG_STM32_HAVE_SPI2 is not set +# CONFIG_STM32_HAVE_SPI3 is not set +# CONFIG_STM32_HAVE_SPI4 is not set +# CONFIG_STM32_HAVE_SPI5 is not set +# CONFIG_STM32_HAVE_SPI6 is not set +# CONFIG_STM32_HAVE_SAIPLL is not set +# CONFIG_STM32_HAVE_I2SPLL is not set +CONFIG_STM32_HAVE_OPAMP=y +CONFIG_STM32_ADC1=y +# CONFIG_STM32_ADC2 is not set +# CONFIG_STM32_COMP2 is not set +# CONFIG_STM32_COMP4 is not set +# CONFIG_STM32_COMP6 is not set +# CONFIG_STM32_CAN1 is not set +# CONFIG_STM32_CRC is not set +CONFIG_STM32_DMA1=y +# CONFIG_STM32_DMA2 is not set +# CONFIG_STM32_DAC1 is not set +# CONFIG_STM32_DAC2 is not set +# CONFIG_STM32_HRTIM1 is not set +# CONFIG_STM32_I2C1 is not set +# CONFIG_STM32_OPAMP is not set +CONFIG_STM32_PWR=y +# CONFIG_STM32_SDIO is not set +# CONFIG_STM32_SPI1 is not set +# CONFIG_STM32_TIM1 is not set +# CONFIG_STM32_TIM2 is not set +# CONFIG_STM32_TIM15 is not set +# CONFIG_STM32_TIM16 is not set +# CONFIG_STM32_TIM17 is not set +CONFIG_STM32_USART1=y +# CONFIG_STM32_USART2 is not set +# CONFIG_STM32_USART3 is not set +# CONFIG_STM32_IWDG is not set +# CONFIG_STM32_WWDG is not set +CONFIG_STM32_ADC=y +# CONFIG_STM32_NOEXT_VECTORS is not set + +# +# Alternate Pin Mapping +# +# CONFIG_STM32_JTAG_DISABLE is not set +# CONFIG_STM32_JTAG_FULL_ENABLE is not set +# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set +CONFIG_STM32_JTAG_SW_ENABLE=y +# CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG is not set +# CONFIG_STM32_FORCEPOWER is not set +# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set +CONFIG_STM32_CCMEXCLUDE=y + +# +# Timer Configuration +# +# CONFIG_STM32_ONESHOT is not set +# CONFIG_STM32_FREERUN is not set +# CONFIG_STM32_TIM1_CAP is not set +CONFIG_STM32_USART=y +CONFIG_STM32_SERIALDRIVER=y + +# +# ADC Configuration +# +CONFIG_STM32_ADC1_DMA=y +# CONFIG_STM32_HAVE_RTC_COUNTER is not set +# CONFIG_STM32_HAVE_RTC_SUBSECONDS is not set + +# +# U[S]ART Configuration +# + +# +# U[S]ART Device Configuration +# +CONFIG_STM32_USART1_SERIALDRIVER=y +# CONFIG_STM32_USART1_1WIREDRIVER is not set +# CONFIG_USART1_RS485 is not set + +# +# Serial Driver Configuration +# +# CONFIG_SERIAL_DISABLE_REORDERING is not set +# CONFIG_STM32_FLOWCONTROL_BROKEN is not set +# CONFIG_STM32_USART_BREAKS is not set +# CONFIG_STM32_USART_SINGLEWIRE is not set +# CONFIG_STM32_HAVE_RTC_COUNTER is not set +# CONFIG_STM32_HAVE_RTC_SUBSECONDS is not set + +# +# USB FS Host Configuration +# + +# +# USB HS Host Configuration +# + +# +# USB Host Debug Configuration +# + +# +# USB Device Configuration +# + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_VECNOTIRQ is not set +CONFIG_ARCH_DMA=y +CONFIG_ARCH_HAVE_IRQPRIO=y +# CONFIG_ARCH_L2CACHE is not set +# CONFIG_ARCH_HAVE_COHERENT_DCACHE is not set +# CONFIG_ARCH_HAVE_ADDRENV is not set +# CONFIG_ARCH_NEED_ADDRENV_MAPPING is not set +# CONFIG_ARCH_HAVE_MULTICPU is not set +CONFIG_ARCH_HAVE_VFORK=y +# CONFIG_ARCH_HAVE_MMU is not set +CONFIG_ARCH_HAVE_MPU=y +# CONFIG_ARCH_NAND_HWECC is not set +# CONFIG_ARCH_HAVE_EXTCLK is not set +# CONFIG_ARCH_HAVE_POWEROFF is not set +CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_USE_MPU is not set +# CONFIG_ARCH_IRQPRIO is not set +CONFIG_ARCH_STACKDUMP=y +# CONFIG_ENDIAN_BIG is not set +# CONFIG_ARCH_IDLE_CUSTOM is not set +# CONFIG_ARCH_HAVE_RAMFUNCS is not set +CONFIG_ARCH_HAVE_RAMVECTORS=y +# CONFIG_ARCH_RAMVECTORS is not set +# CONFIG_ARCH_MINIMAL_VECTORTABLE is not set + +# +# Board Settings +# +CONFIG_BOARD_LOOPSPERMSEC=16717 +# CONFIG_ARCH_CALIBRATION is not set + +# +# Interrupt options +# +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y +CONFIG_ARCH_INTERRUPTSTACK=0 +CONFIG_ARCH_HAVE_HIPRI_INTERRUPT=y +# CONFIG_ARCH_HIPRI_INTERRUPT is not set + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Boot Memory Configuration +# +CONFIG_RAM_START=0x20000000 +CONFIG_RAM_SIZE=12288 +# CONFIG_ARCH_HAVE_SDRAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_NUCLEO_F334R8=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="nucleo-f334r8" + +# +# Common Board Options +# +CONFIG_ARCH_HAVE_LEDS=y +CONFIG_ARCH_LEDS=y +CONFIG_ARCH_HAVE_BUTTONS=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_HAVE_IRQBUTTONS=y +# CONFIG_ARCH_IRQBUTTONS is not set + +# +# Board-Specific Options +# +# CONFIG_BOARD_CRASHDUMP is not set +CONFIG_LIB_BOARDCTL=y +# CONFIG_BOARDCTL_RESET is not set +# CONFIG_BOARDCTL_UNIQUEID is not set +# CONFIG_BOARDCTL_TSCTEST is not set +# CONFIG_BOARDCTL_GRAPHICS is not set +# CONFIG_BOARDCTL_IOCTL is not set + +# +# RTOS Features +# +CONFIG_DISABLE_OS_API=y +CONFIG_DISABLE_POSIX_TIMERS=y +CONFIG_DISABLE_PTHREAD=y +CONFIG_DISABLE_SIGNALS=y +CONFIG_DISABLE_MQUEUE=y +CONFIG_DISABLE_ENVIRON=y + +# +# Clocks and Timers +# +CONFIG_ARCH_HAVE_TICKLESS=y +# CONFIG_SCHED_TICKLESS is not set +CONFIG_USEC_PER_TICK=10000 +# CONFIG_SYSTEM_TIME64 is not set +# CONFIG_CLOCK_MONOTONIC is not set +CONFIG_ARCH_HAVE_TIMEKEEPING=y +# CONFIG_JULIAN_TIME is not set +CONFIG_START_YEAR=2011 +CONFIG_START_MONTH=12 +CONFIG_START_DAY=6 +CONFIG_MAX_WDOGPARMS=1 +CONFIG_PREALLOC_WDOGS=1 +CONFIG_WDOG_INTRESERVE=0 +CONFIG_PREALLOC_TIMERS=2 + +# +# Tasks and Scheduling +# +# CONFIG_SPINLOCK is not set +# CONFIG_INIT_NONE is not set +CONFIG_INIT_ENTRYPOINT=y +# CONFIG_INIT_FILEPATH is not set +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_RR_INTERVAL=200 +# CONFIG_SCHED_SPORADIC is not set +CONFIG_TASK_NAME_SIZE=0 +CONFIG_MAX_TASKS=4 +# CONFIG_SCHED_HAVE_PARENT is not set +CONFIG_SCHED_WAITPID=y +# CONFIG_CANCELLATION_POINTS is not set + +# +# Performance Monitoring +# +# CONFIG_SCHED_CPULOAD is not set +# CONFIG_SCHED_INSTRUMENTATION is not set + +# +# Files and I/O +# +CONFIG_DEV_CONSOLE=y +# CONFIG_FDCLONE_DISABLE is not set +CONFIG_FDCLONE_STDIO=y +CONFIG_SDCLONE_DISABLE=y +CONFIG_NFILE_DESCRIPTORS=8 +CONFIG_NFILE_STREAMS=8 +CONFIG_NAME_MAX=16 +# CONFIG_PRIORITY_INHERITANCE is not set + +# +# RTOS hooks +# +# CONFIG_BOARD_INITIALIZE is not set +# CONFIG_SCHED_STARTHOOK is not set +# CONFIG_SCHED_ATEXIT is not set +# CONFIG_SCHED_ONEXIT is not set +# CONFIG_MODULE is not set + +# +# Work queue support +# + +# +# Stack and heap information +# +CONFIG_IDLETHREAD_STACKSIZE=1024 +CONFIG_USERMAIN_STACKSIZE=1024 +CONFIG_PTHREAD_STACK_MIN=1024 +CONFIG_PTHREAD_STACK_DEFAULT=1024 +# CONFIG_LIB_SYSCALL is not set + +# +# Device Drivers +# +CONFIG_DISABLE_POLL=y +# CONFIG_DEV_NULL is not set +# CONFIG_DEV_ZERO is not set +# CONFIG_DEV_URANDOM is not set +# CONFIG_DEV_LOOP is not set + +# +# Buffering +# +# CONFIG_DRVR_WRITEBUFFER is not set +# CONFIG_DRVR_READAHEAD is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_ARCH_HAVE_PWM_PULSECOUNT is not set +# CONFIG_ARCH_HAVE_PWM_MULTICHAN is not set +# CONFIG_PWM is not set +CONFIG_ARCH_HAVE_I2CRESET=y +# CONFIG_I2C is not set +# CONFIG_ARCH_HAVE_SPI_CRCGENERATION is not set +# CONFIG_ARCH_HAVE_SPI_CS_CONTROL is not set +CONFIG_ARCH_HAVE_SPI_BITORDER=y +# CONFIG_SPI is not set +# CONFIG_I2S is not set + +# +# Timer Driver Support +# +# CONFIG_TIMER is not set +# CONFIG_ONESHOT is not set +# CONFIG_RTC is not set +# CONFIG_WATCHDOG is not set +CONFIG_ANALOG=y +CONFIG_ADC=y +CONFIG_ADC_FIFOSIZE=8 +# CONFIG_AUDIO_DEVICES is not set +# CONFIG_VIDEO_DEVICES is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set + +# +# IO Expander/GPIO Support +# +# CONFIG_IOEXPANDER is not set +# CONFIG_DEV_GPIO is not set + +# +# LCD Driver Support +# +# CONFIG_LCD is not set +# CONFIG_SLCD is not set + +# +# LED Support +# +# CONFIG_USERLED is not set +# CONFIG_RGBLED is not set +# CONFIG_PCA9635PW is not set +# CONFIG_NCP5623C is not set +# CONFIG_MMCSD is not set +# CONFIG_MODEM is not set +# CONFIG_MTD is not set +# CONFIG_EEPROM is not set +# CONFIG_PIPES is not set +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +CONFIG_SERIAL=y +# CONFIG_DEV_LOWCONSOLE is not set +# CONFIG_SERIAL_REMOVABLE is not set +CONFIG_SERIAL_CONSOLE=y +# CONFIG_16550_UART is not set +# CONFIG_UART_SERIALDRIVER is not set +# CONFIG_UART0_SERIALDRIVER is not set +# CONFIG_UART1_SERIALDRIVER is not set +# CONFIG_UART2_SERIALDRIVER is not set +# CONFIG_UART3_SERIALDRIVER is not set +# CONFIG_UART4_SERIALDRIVER is not set +# CONFIG_UART5_SERIALDRIVER is not set +# CONFIG_UART6_SERIALDRIVER is not set +# CONFIG_UART7_SERIALDRIVER is not set +# CONFIG_UART8_SERIALDRIVER is not set +# CONFIG_SCI0_SERIALDRIVER is not set +# CONFIG_SCI1_SERIALDRIVER is not set +# CONFIG_USART0_SERIALDRIVER is not set +CONFIG_USART1_SERIALDRIVER=y +# CONFIG_USART2_SERIALDRIVER is not set +# CONFIG_USART3_SERIALDRIVER is not set +# CONFIG_USART4_SERIALDRIVER is not set +# CONFIG_USART5_SERIALDRIVER is not set +# CONFIG_USART6_SERIALDRIVER is not set +# CONFIG_USART7_SERIALDRIVER is not set +# CONFIG_USART8_SERIALDRIVER is not set +# CONFIG_OTHER_UART_SERIALDRIVER is not set +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +# CONFIG_SERIAL_IFLOWCONTROL is not set +# CONFIG_SERIAL_OFLOWCONTROL is not set +# CONFIG_SERIAL_DMA is not set +# CONFIG_SERIAL_TIOCSERGSTRUCT is not set +CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y +CONFIG_USART1_SERIAL_CONSOLE=y +# CONFIG_OTHER_SERIAL_CONSOLE is not set +# CONFIG_NO_SERIAL_CONSOLE is not set + +# +# USART1 Configuration +# +CONFIG_USART1_RXBUFSIZE=256 +CONFIG_USART1_TXBUFSIZE=256 +CONFIG_USART1_BAUD=115200 +CONFIG_USART1_BITS=8 +CONFIG_USART1_PARITY=0 +CONFIG_USART1_2STOP=0 +# CONFIG_USART1_IFLOWCONTROL is not set +# CONFIG_USART1_OFLOWCONTROL is not set +# CONFIG_USART1_DMA is not set +# CONFIG_PSEUDOTERM is not set +# CONFIG_USBDEV is not set +# CONFIG_USBHOST is not set +# CONFIG_HAVE_USBTRACE is not set +# CONFIG_DRIVERS_WIRELESS is not set +# CONFIG_DRIVERS_CONTACTLESS is not set + +# +# System Logging +# +# CONFIG_ARCH_SYSLOG is not set +# CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_INTBUFFER is not set +# CONFIG_SYSLOG_TIMESTAMP is not set +CONFIG_SYSLOG_SERIAL_CONSOLE=y +# CONFIG_SYSLOG_CHAR is not set +# CONFIG_SYSLOG_CONSOLE is not set +# CONFIG_SYSLOG_NONE is not set +# CONFIG_SYSLOG_FILE is not set +# CONFIG_CONSOLE_SYSLOG is not set +# CONFIG_SYSLOG_CHARDEV is not set + +# +# Networking Support +# +# CONFIG_ARCH_HAVE_NET is not set +# CONFIG_ARCH_HAVE_PHY is not set +# CONFIG_NET is not set + +# +# Crypto API +# +# CONFIG_CRYPTO is not set + +# +# File Systems +# + +# +# File system configuration +# +# CONFIG_DISABLE_MOUNTPOINT is not set +# CONFIG_FS_AUTOMOUNTER is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_PSEUDOFS_SOFTLINKS is not set +# CONFIG_FS_READABLE is not set +# CONFIG_FS_WRITABLE is not set +# CONFIG_FS_NAMED_SEMAPHORES is not set +# CONFIG_FS_RAMMAP is not set +# CONFIG_FS_FAT is not set +# CONFIG_FS_NXFFS is not set +# CONFIG_FS_ROMFS is not set +# CONFIG_FS_TMPFS is not set +# CONFIG_FS_SMARTFS is not set +# CONFIG_FS_BINFS is not set +# CONFIG_FS_PROCFS is not set +# CONFIG_FS_UNIONFS is not set + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=1 +# CONFIG_ARCH_HAVE_HEAP2 is not set +# CONFIG_GRAN is not set + +# +# Audio Support +# +# CONFIG_AUDIO is not set + +# +# Wireless Support +# + +# +# Binary Loader +# +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +CONFIG_BUILTIN=y +# CONFIG_PIC is not set +# CONFIG_SYMTAB_ORDEREDBYNAME is not set + +# +# Library Routines +# + +# +# Standard C Library Options +# + +# +# Standard C I/O +# +# CONFIG_STDIO_DISABLE_BUFFERING is not set +CONFIG_STDIO_BUFFER_SIZE=64 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +# CONFIG_NOPRINTF_FIELDWIDTH is not set +# CONFIG_LIBC_FLOATINGPOINT is not set +# CONFIG_LIBC_LONG_LONG is not set +# CONFIG_LIBC_SCANSET is not set +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_MEMCPY_VIK is not set +# CONFIG_LIBM is not set + +# +# Architecture-Specific Support +# +CONFIG_ARCH_LOWPUTC=y +# CONFIG_ARCH_ROMGETC is not set +# CONFIG_LIBC_ARCH_MEMCPY is not set +# CONFIG_LIBC_ARCH_MEMCMP is not set +# CONFIG_LIBC_ARCH_MEMMOVE is not set +# CONFIG_LIBC_ARCH_MEMSET is not set +# CONFIG_LIBC_ARCH_STRCHR is not set +# CONFIG_LIBC_ARCH_STRCMP is not set +# CONFIG_LIBC_ARCH_STRCPY is not set +# CONFIG_LIBC_ARCH_STRNCPY is not set +# CONFIG_LIBC_ARCH_STRLEN is not set +# CONFIG_LIBC_ARCH_STRNLEN is not set +# CONFIG_LIBC_ARCH_ELF is not set +# CONFIG_ARMV7M_MEMCPY is not set + +# +# stdlib Options +# +CONFIG_LIB_RAND_ORDER=1 + +# +# Program Execution Options +# +# CONFIG_LIBC_EXECFUNCS is not set +CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=512 +CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=512 + +# +# errno Decode Support +# +# CONFIG_LIBC_STRERROR is not set +# CONFIG_LIBC_PERROR_STDOUT is not set + +# +# memcpy/memset Options +# +# CONFIG_MEMSET_OPTSPEED is not set +# CONFIG_LIBC_DLLFCN is not set +# CONFIG_LIBC_MODLIB is not set +# CONFIG_LIBC_WCHAR is not set +# CONFIG_LIBC_LOCALE is not set + +# +# Time/Time Zone Support +# +# CONFIG_TIME_EXTENDED is not set +CONFIG_ARCH_HAVE_TLS=y + +# +# Thread Local Storage (TLS) +# +# CONFIG_TLS is not set + +# +# Network-Related Options +# +# CONFIG_LIBC_IPv4_ADDRCONV is not set +# CONFIG_LIBC_IPv6_ADDRCONV is not set +# CONFIG_LIBC_NETDB is not set + +# +# NETDB Support +# +# CONFIG_LIBC_IOCTL_VARIADIC is not set +CONFIG_LIB_SENDFILE_BUFSIZE=512 + +# +# Non-standard Library Support +# +# CONFIG_LIB_CRC64_FAST is not set +# CONFIG_LIB_KBDCODEC is not set +# CONFIG_LIB_SLCDCODEC is not set +# CONFIG_LIB_HEX2BIN is not set + +# +# Basic CXX Support +# +# CONFIG_C99_BOOL8 is not set +# CONFIG_HAVE_CXX is not set + +# +# Application Configuration +# + +# +# Built-In Applications +# +CONFIG_BUILTIN_PROXY_STACKSIZE=512 + +# +# CAN Utilities +# + +# +# Examples +# +CONFIG_EXAMPLES_ADC=y +CONFIG_EXAMPLES_ADC_DEVPATH="/dev/adc0" +CONFIG_EXAMPLES_ADC_NSAMPLES=0 +CONFIG_EXAMPLES_ADC_GROUPSIZE=4 +CONFIG_EXAMPLES_ADC_SWTRIG=y +# CONFIG_EXAMPLES_BUTTONS is not set +# CONFIG_EXAMPLES_CCTYPE is not set +# CONFIG_EXAMPLES_CHAT is not set +# CONFIG_EXAMPLES_CONFIGDATA is not set +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HIDKBD is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_JSON is not set +# CONFIG_EXAMPLES_KEYPADTEST is not set +# CONFIG_EXAMPLES_MEDIA is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MODBUS is not set +# CONFIG_EXAMPLES_MOUNT is not set +# CONFIG_EXAMPLES_NRF24L01TERM is not set +CONFIG_EXAMPLES_NSH=y +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NXLINES is not set +# CONFIG_EXAMPLES_NXTERM is not set +# CONFIG_EXAMPLES_NXTEXT is not set +# CONFIG_EXAMPLES_PCA9635 is not set +# CONFIG_EXAMPLES_POSIXSPAWN is not set +# CONFIG_EXAMPLES_PPPD is not set +# CONFIG_EXAMPLES_RFID_READUID is not set +# CONFIG_EXAMPLES_RGBLED is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERIALBLASTER is not set +# CONFIG_EXAMPLES_SERIALRX is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_SLCD is not set +# CONFIG_EXAMPLES_SMART is not set +# CONFIG_EXAMPLES_SMART_TEST is not set +# CONFIG_EXAMPLES_SMP is not set +# CONFIG_EXAMPLES_STAT is not set +# CONFIG_EXAMPLES_TCPECHO is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_WATCHDOG is not set +# CONFIG_EXAMPLES_WEBSERVER is not set + +# +# File System Utilities +# +# CONFIG_FSUTILS_INIFILE is not set + +# +# GPS Utilities +# +# CONFIG_GPSUTILS_MINMEA_LIB is not set + +# +# Graphics Support +# +# CONFIG_TIFF is not set +# CONFIG_GRAPHICS_TRAVELER is not set + +# +# Interpreters +# +# CONFIG_INTERPRETERS_FICL is not set +# CONFIG_INTERPRETERS_MICROPYTHON is not set +# CONFIG_INTERPRETERS_MINIBASIC is not set +# CONFIG_INTERPRETERS_PCODE is not set + +# +# FreeModBus +# +# CONFIG_MODBUS is not set + +# +# Network Utilities +# +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_ESP8266 is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_JSON is not set +# CONFIG_NETUTILS_SMTP is not set + +# +# NSH Library +# +CONFIG_NSH_LIBRARY=y +CONFIG_NSH_ARCHINIT=y + +# +# Command Line Configuration +# +CONFIG_NSH_READLINE=y +# CONFIG_NSH_CLE is not set +CONFIG_NSH_LINELEN=64 +# CONFIG_NSH_DISABLE_SEMICOLON is not set +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_MAXARGUMENTS=6 +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_NESTDEPTH=3 +# CONFIG_NSH_DISABLEBG is not set +CONFIG_NSH_BUILTIN_APPS=y + +# +# Disable Individual commands +# +CONFIG_NSH_DISABLE_ADDROUTE=y +CONFIG_NSH_DISABLE_BASENAME=y +CONFIG_NSH_DISABLE_CAT=y +CONFIG_NSH_DISABLE_CD=y +CONFIG_NSH_DISABLE_CP=y +CONFIG_NSH_DISABLE_CMP=y +CONFIG_NSH_DISABLE_DATE=y +CONFIG_NSH_DISABLE_DD=y +CONFIG_NSH_DISABLE_DF=y +CONFIG_NSH_DISABLE_DELROUTE=y +CONFIG_NSH_DISABLE_DIRNAME=y +# CONFIG_NSH_DISABLE_ECHO is not set +CONFIG_NSH_DISABLE_EXEC=y +CONFIG_NSH_DISABLE_EXIT=y +# CONFIG_NSH_DISABLE_FREE is not set +CONFIG_NSH_DISABLE_GET=y +# CONFIG_NSH_DISABLE_HELP is not set +CONFIG_NSH_DISABLE_HEXDUMP=y +CONFIG_NSH_DISABLE_IFCONFIG=y +CONFIG_NSH_DISABLE_IFUPDOWN=y +CONFIG_NSH_DISABLE_KILL=y +CONFIG_NSH_DISABLE_LOSETUP=y +CONFIG_NSH_DISABLE_LOSMART=y +CONFIG_NSH_DISABLE_LS=y +CONFIG_NSH_DISABLE_MB=y +CONFIG_NSH_DISABLE_MKDIR=y +CONFIG_NSH_DISABLE_MKRD=y +CONFIG_NSH_DISABLE_MH=y +CONFIG_NSH_DISABLE_MOUNT=y +CONFIG_NSH_DISABLE_MV=y +CONFIG_NSH_DISABLE_MW=y +# CONFIG_NSH_DISABLE_PRINTF is not set +CONFIG_NSH_DISABLE_PS=y +CONFIG_NSH_DISABLE_PUT=y +CONFIG_NSH_DISABLE_PWD=y +CONFIG_NSH_DISABLE_RM=y +CONFIG_NSH_DISABLE_RMDIR=y +CONFIG_NSH_DISABLE_SET=y +CONFIG_NSH_DISABLE_SH=y +CONFIG_NSH_DISABLE_SLEEP=y +CONFIG_NSH_DISABLE_TIME=y +CONFIG_NSH_DISABLE_TEST=y +CONFIG_NSH_DISABLE_UMOUNT=y +CONFIG_NSH_DISABLE_UNAME=y +CONFIG_NSH_DISABLE_UNSET=y +CONFIG_NSH_DISABLE_USLEEP=y +CONFIG_NSH_DISABLE_WGET=y +CONFIG_NSH_DISABLE_XD=y +CONFIG_NSH_MMCSDMINOR=0 + +# +# Configure Command Options +# +CONFIG_NSH_CODECS_BUFSIZE=128 +CONFIG_NSH_FILEIOSIZE=256 + +# +# Scripting Support +# +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_LOOPS is not set + +# +# Console Configuration +# +CONFIG_NSH_CONSOLE=y +# CONFIG_NSH_ALTCONDEV is not set +# CONFIG_NSH_ARCHINIT is not set +# CONFIG_NSH_LOGIN is not set +# CONFIG_NSH_CONSOLE_LOGIN is not set + +# +# NxWidgets/NxWM +# + +# +# Platform-specific Support +# +# CONFIG_PLATFORM_CONFIGDATA is not set + +# +# System Libraries and NSH Add-Ons +# +# CONFIG_SYSTEM_CLE is not set +# CONFIG_SYSTEM_CUTERM is not set +# CONFIG_SYSTEM_FREE is not set +# CONFIG_SYSTEM_HEX2BIN is not set +# CONFIG_SYSTEM_HEXED is not set +# CONFIG_SYSTEM_INSTALL is not set +# CONFIG_SYSTEM_RAMTEST is not set +CONFIG_READLINE_HAVE_EXTMATCH=y +CONFIG_SYSTEM_READLINE=y +CONFIG_READLINE_ECHO=y +# CONFIG_READLINE_TABCOMPLETION is not set +# CONFIG_READLINE_CMD_HISTORY is not set +# CONFIG_SYSTEM_SUDOKU is not set +# CONFIG_SYSTEM_SYSTEM is not set +# CONFIG_SYSTEM_TEE is not set +# CONFIG_SYSTEM_UBLOXMODEM is not set +# CONFIG_SYSTEM_VI is not set +# CONFIG_SYSTEM_ZMODEM is not set \ No newline at end of file diff --git a/configs/nucleo-f334r8/adc/setenv.sh b/configs/nucleo-f334r8/adc/setenv.sh new file mode 100644 index 0000000000..a9a8fc14a4 --- /dev/null +++ b/configs/nucleo-f334r8/adc/setenv.sh @@ -0,0 +1,77 @@ +#!/bin/bash +# configs/nucleo-f224r8/adc/setenv.sh +# +# 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. +# + +if [ "$_" = "$0" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +fi + +WD=`pwd` +if [ ! -x "setenv.sh" ]; then + echo "This script must be executed from the top-level NuttX build directory" + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then + export PATH_ORIG="${PATH}" +fi + +# This is the Cygwin path to the location where I installed the Atmel GCC +# toolchain under Windows. You will also have to edit this if you install +# this toolchain in any other location +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin" + +# This is the Cygwin path to the location where I installed the CodeSourcery +# toolchain under windows. You will also have to edit this if you install +# the CodeSourcery toolchain in any other location +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin" +# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin" + +# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors" +# You can this free toolchain here https://launchpad.net/gcc-arm-embedded +export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin" + +# This is the path to the location where I installed the devkitARM toolchain +# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/ +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin" + +# This is the Cygwin path to the location where I build the buildroot +# toolchain. +# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" + +# Add the path to the toolchain to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" + +echo "PATH : ${PATH}" diff --git a/configs/nucleo-f334r8/include/board.h b/configs/nucleo-f334r8/include/board.h index 0ebacd0b0c..8d5ce807dc 100644 --- a/configs/nucleo-f334r8/include/board.h +++ b/configs/nucleo-f334r8/include/board.h @@ -243,8 +243,8 @@ /* DMA channels *************************************************************/ /* ADC */ -#define ADC1_DMA_CHAN DMACHAN_ADC1 -#define ADC2_DMA_CHAN DMACHAN_ADC2_ +#define ADC1_DMA_CHAN DMACHAN_ADC1 /* DMA1_CH1 */ +#define ADC2_DMA_CHAN DMACHAN_ADC2_1 /* DMA1_CH2 */ /**************************************************************************** * Public Data diff --git a/configs/nucleo-f334r8/src/stm32_adc.c b/configs/nucleo-f334r8/src/stm32_adc.c index e69de29bb2..f46970cef9 100644 --- a/configs/nucleo-f334r8/src/stm32_adc.c +++ b/configs/nucleo-f334r8/src/stm32_adc.c @@ -0,0 +1,253 @@ +/**************************************************************************** + * configs/nucleo-f334r8/src/stm32_adc.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Mateusz Szafoni + * + * 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 "stm32.h" + +#if defined(CONFIG_ADC) && (defined(CONFIG_STM32_ADC1) || defined(CONFIG_STM32_ADC2)) + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +/* 1 or 2 ADC devices (DEV1, DEV2) */ + +#if defined(CONFIG_STM32_ADC1) +# define DEV1_PORT 1 +#endif + +#if defined(CONFIG_STM32_ADC2) +# if defined(DEV1_PORT) +# define DEV2_PORT 2 +# else +# define DEV1_PORT 2 +# endif +#endif + +/* The number of ADC channels in the conversion list */ +/* TODO DMA */ + +#define ADC1_NCHANNELS 3 +#define ADC2_NCHANNELS 3 + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* DEV 1 */ + +#if DEV1_PORT == 1 + +#define DEV1_NCHANNELS ADC1_NCHANNELS + +/* Identifying number of each ADC channel (even if NCHANNELS is less ) */ + +static const uint8_t g_chanlist1[3] = +{ + 1, + 2, + 11 +}; + +/* Configurations of pins used by each ADC channel */ + +static const uint32_t g_pinlist1[3] = +{ + GPIO_ADC1_IN1, /* PA0/A0 */ + GPIO_ADC1_IN2, /* PA1/A1 */ + GPIO_ADC1_IN11, /* PB0/A3 */ +}; + +#elif DEV1_PORT == 2 + +#define DEV1_NCHANNELS ADC2_NCHANNELS + +/* Identifying number of each ADC channel */ + +static const uint8_t g_chanlist1[3] = +{ + 1, + 6, + 7 +}; + +/* Configurations of pins used by each ADC channel */ + +static const uint32_t g_pinlist1[3] = +{ + GPIO_ADC2_IN1, /* PA4/A2 */ + GPIO_ADC2_IN7, /* PC1/A4 */ + GPIO_ADC2_IN6, /* PC0/A5 */ +}; + +#endif /* DEV1_PORT == 1 */ + +#ifdef DEV2_PORT + +/* DEV 2 */ + +#if DEV2_PORT == 2 + +#define DEV2_NCHANNELS ADC2_NCHANNELS + +/* Identifying number of each ADC channel */ + +static const uint8_t g_chanlist2[1] = +{ + 1, + 6, + 7 +}; + +/* Configurations of pins used by each ADC channel */ + +static const uint32_t g_pinlist2[3] = +{ + GPIO_ADC2_IN1, /* PA4/A2 */ + GPIO_ADC2_IN7, /* PC1/A4 */ + GPIO_ADC2_IN6, /* PC0/A5 */ +}; + +#endif /* DEV2_PORT == 2 */ +#endif /* DEV2_PORT */ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/************************************************************************************ + * Name: stm32_adc_setup + * + * Description: + * Initialize ADC and register the ADC driver. + * + ************************************************************************************/ + +int stm32_adc_setup(void) +{ + static bool initialized = false; + FAR struct adc_dev_s *adc; + int ret; + int i; + + /* Check if we have already initialized */ + + if (!initialized) + { + /* DEV1 */ + /* Configure the pins as analog inputs for the selected channels */ + + for (i = 0; i < DEV1_NCHANNELS; i++) + { + stm32_configgpio(g_pinlist1[i]); + } + + /* Call stm32_adcinitialize() to get an instance of the ADC interface */ + + adc = stm32_adcinitialize(DEV1_PORT, g_chanlist1, DEV1_NCHANNELS); + if (adc == NULL) + { + aerr("ERROR: Failed to get ADC interface 1\n"); + return -ENODEV; + } + + /* Register the ADC driver at "/dev/adc0" */ + + ret = adc_register("/dev/adc0", adc); + if (ret < 0) + { + aerr("ERROR: adc_register /dev/adc0 failed: %d\n", ret); + return ret; + } + +#ifdef DEV2_PORT + + /* DEV2 */ + /* Configure the pins as analog inputs for the selected channels */ + + for (i = 0; i < DEV2_NCHANNELS; i++) + { + stm32_configgpio(g_pinlist2[i]); + } + + /* Call stm32_adcinitialize() to get an instance of the ADC interface */ + + adc = stm32_adcinitialize(DEV2_PORT, g_chanlist2, DEV2_NCHANNELS); + if (adc == NULL) + { + aerr("ERROR: Failed to get ADC interface 2\n"); + return -ENODEV; + } + + /* Register the ADC driver at "/dev/adc1" */ + + ret = adc_register("/dev/adc1", adc); + if (ret < 0) + { + aerr("ERROR: adc_register /dev/adc1 failed: %d\n", ret); + return ret; + } +#endif + + initialized = true; + + } + + return OK; +} + +#endif /* CONFIG_ADC && (CONFIG_STM32_ADC1 || CONFIG_STM32_ADC2) */ diff --git a/configs/nucleo-f334r8/src/stm32_appinit.c b/configs/nucleo-f334r8/src/stm32_appinit.c index 8e7e7535d4..3579835c63 100644 --- a/configs/nucleo-f334r8/src/stm32_appinit.c +++ b/configs/nucleo-f334r8/src/stm32_appinit.c @@ -45,7 +45,7 @@ #include #include -#include "nucleo-f303re.h" +#include "nucleo-f334r8.h" /**************************************************************************** * Pre-processor Definitions @@ -107,6 +107,26 @@ int board_app_initialize(uintptr_t arg) } #endif +#ifdef CONFIG_ADC + /* Initialize ADC and register the ADC driver. */ + + ret = stm32_adc_setup(); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: stm32_adc_setup failed: %d\n", ret); + } +#endif + +#ifdef CONFIG_DAC + /* Initialize DAC and register the DAC driver. */ + + ret = stm32_dac_setup(); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: stm32_dac_setup failed: %d\n", ret); + } +#endif + UNUSED(ret); return OK; } diff --git a/configs/nucleo-f334r8/src/stm32_boot.c b/configs/nucleo-f334r8/src/stm32_boot.c index 370a198410..278589e295 100644 --- a/configs/nucleo-f334r8/src/stm32_boot.c +++ b/configs/nucleo-f334r8/src/stm32_boot.c @@ -78,9 +78,10 @@ void stm32_boardinitialize(void) { +#ifdef CONFIG_ARCH_LEDS /* Configure on-board LEDs if LED support has been selected. */ -#ifdef CONFIG_ARCH_LEDS board_autoled_initialize(); #endif + } -- GitLab From a10735b50d781f5006ed0dd9ac464bb8582dee73 Mon Sep 17 00:00:00 2001 From: Heesub Shin Date: Sat, 18 Mar 2017 22:27:06 +0900 Subject: [PATCH 092/990] mtd/progmem: fix incorrect target address calculation progmem_read/write() is incorrectly calculating the target address, expecting the offset argument is given in a block number. This is completely wrong and as a result invalid flash region is accessed. Byte-oriented read/write interfaces of mtd device accept the target address in a byte offset, not a block number. Signed-off-by: Heesub Shin --- drivers/mtd/mtd_progmem.c | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/drivers/mtd/mtd_progmem.c b/drivers/mtd/mtd_progmem.c index 3d76402fd8..9785a4c360 100644 --- a/drivers/mtd/mtd_progmem.c +++ b/drivers/mtd/mtd_progmem.c @@ -245,14 +245,18 @@ static ssize_t progmem_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, static ssize_t progmem_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes, FAR uint8_t *buffer) { + FAR struct progmem_dev_s *priv = (FAR struct progmem_dev_s *)dev; FAR const uint8_t *src; + off_t startblock; /* Read the specified bytes into the provided user buffer and return * status (The positive, number of bytes actually read or a negated * errno) */ - src = (FAR const uint8_t *)up_progmem_getaddress(offset); + startblock = offset >> priv->blkshift; + src = (FAR const uint8_t *)up_progmem_getaddress(startblock) + + (offset & ((1 << priv->blkshift) - 1)); memcpy(buffer, src, nbytes); return nbytes; } @@ -271,13 +275,16 @@ static ssize_t progmem_write(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes, FAR const uint8_t *buffer) { FAR struct progmem_dev_s *priv = (FAR struct progmem_dev_s *)dev; + off_t startblock; ssize_t result; /* Write the specified blocks from the provided user buffer and return status * (The positive, number of blocks actually written or a negated errno) */ - result = up_progmem_write(up_progmem_getaddress(offset), buffer, nbytes); + startblock = offset >> priv->blkshift; + result = up_progmem_write(up_progmem_getaddress(startblock) + + (offset & ((1 << priv->blkshift) - 1)), buffer, nbytes); return result < 0 ? result : nbytes; } #endif -- GitLab From 9769c67d4da19d1a52e910cc7fba21887442095c Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 18 Mar 2017 11:25:14 -0600 Subject: [PATCH 093/990] XMC4xxx: Add pin multiplexing header file. --- arch/arm/src/xmc4/chip/xmc4_pinmux.h | 752 +++++++++++++++++++++++++++ arch/arm/src/xmc4/xmc4_gpio.h | 2 +- 2 files changed, 753 insertions(+), 1 deletion(-) diff --git a/arch/arm/src/xmc4/chip/xmc4_pinmux.h b/arch/arm/src/xmc4/chip/xmc4_pinmux.h index 44d43074a8..b4ba4b0e24 100644 --- a/arch/arm/src/xmc4/chip/xmc4_pinmux.h +++ b/arch/arm/src/xmc4/chip/xmc4_pinmux.h @@ -47,6 +47,758 @@ /************************************************************************************ * Pre-processor Definitions ************************************************************************************/ +/* Alternate Pin Functions. All members of the XMC4xxx family share the same + * pin multiplexing (although they may differ in the pins physically available). + * + * Alternative pin selections are provided with a numeric suffix like _1, _2, etc. + * Drivers, however, will use the pin selection without the numeric suffix. + * Additional definitions are required in the board.h file. For example, if + * CAN_N2TXD connects vis P1.9 on some board, then the following definition should + * appear in the board.h header file for that board: + * + * #define GPIO_CAN_N2TXD GPIO_CAN_N2TXD_1 + * + * The driver will then automatically configre PA11 as the CAN1 RX pin. + */ + +/* WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!! + * Additional effort is required to select specific GPIO options such as frequency, + * open-drain/push-pull, and pull-up/down! Just the basics are defined for most + * pins in this file. + */ + +#define GPIO_CAN_N0RXDA (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN5) +#define GPIO_CAN_N0RXDB (GPIO_INPUT | GPIO_PORT14 | GPIO_PIN3) +#define GPIO_CAN_N0RXDC (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN12) +#define GPIO_CAN_N0TXD_1 (GPIO_OUTPUT_ALT2 | GPIO_PORT0 | GPIO_PIN0) +#define GPIO_CAN_N0TXD_2 (GPIO_OUTPUT_ALT2 | GPIO_PORT1 | GPIO_PIN4) +#define GPIO_CAN_N0TXD_3 (GPIO_OUTPUT_ALT2 | GPIO_PORT3 | GPIO_PIN10) +#define GPIO_CAN_N0TXD_4 (GPIO_OUTPUT_ALT2 | GPIO_PORT3 | GPIO_PIN2) +#define GPIO_CAN_N1RXDA (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN6) +#define GPIO_CAN_N1RXDB (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN11) +#define GPIO_CAN_N1RXDC (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN13) +#define GPIO_CAN_N1RXDD (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN4) +#define GPIO_CAN_N1TXD_1 (GPIO_OUTPUT_ALT1 | GPIO_PORT1 | GPIO_PIN5) +#define GPIO_CAN_N1TXD_2 (GPIO_OUTPUT_ALT2 | GPIO_PORT1 | GPIO_PIN12) +#define GPIO_CAN_N1TXD_3 (GPIO_OUTPUT_ALT2 | GPIO_PORT2 | GPIO_PIN7) +#define GPIO_CAN_N1TXD_4 (GPIO_OUTPUT_ALT2 | GPIO_PORT3 | GPIO_PIN9) +#define GPIO_CAN_N2RXDA (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN8) +#define GPIO_CAN_N2RXDB (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN8) +#define GPIO_CAN_N2RXDC (GPIO_INPUT | GPIO_PORT4 | GPIO_PIN6) +#define GPIO_CAN_N2TXD_1 (GPIO_OUTPUT_ALT2 | GPIO_PORT1 | GPIO_PIN9) +#define GPIO_CAN_N2TXD_2 (GPIO_OUTPUT_ALT2 | GPIO_PORT3 | GPIO_PIN7) +#define GPIO_CAN_N2TXD_3 (GPIO_OUTPUT_ALT2 | GPIO_PORT4 | GPIO_PIN7) + +#define GPIO_CCU40_IN0A (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN3) +#define GPIO_CCU40_IN0B (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN8) +#define GPIO_CCU40_IN0C (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN1) +#define GPIO_CCU40_IN1A (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN2) +#define GPIO_CCU40_IN1B (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN8) +#define GPIO_CCU40_IN1C (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN0) +#define GPIO_CCU40_IN2A (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN1) +#define GPIO_CCU40_IN2B (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN8) +#define GPIO_CCU40_IN2C (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN7) +#define GPIO_CCU40_IN3A (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN0) +#define GPIO_CCU40_IN3B (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN8) +#define GPIO_CCU40_IN3C (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN6) +#define GPIO_CCU40_OUT0_1 (GPIO_OUTPUT_ALT3 | GPIO_PORT0 | GPIO_PIN15) +#define GPIO_CCU40_OUT0_2 (GPIO_OUTPUT_ALT3 | GPIO_PORT1 | GPIO_PIN3) +#define GPIO_CCU40_OUT1_1 (GPIO_OUTPUT_ALT3 | GPIO_PORT0 | GPIO_PIN14) +#define GPIO_CCU40_OUT1_2 (GPIO_OUTPUT_ALT3 | GPIO_PORT1 | GPIO_PIN2) +#define GPIO_CCU40_OUT2_1 (GPIO_OUTPUT_ALT3 | GPIO_PORT0 | GPIO_PIN13) +#define GPIO_CCU40_OUT2_2 (GPIO_OUTPUT_ALT3 | GPIO_PORT1 | GPIO_PIN1) +#define GPIO_CCU40_OUT3_1 (GPIO_OUTPUT_ALT3 | GPIO_PORT0 | GPIO_PIN12) +#define GPIO_CCU40_OUT3_2 (GPIO_OUTPUT_ALT3 | GPIO_PORT1 | GPIO_PIN0) +#define GPIO_CCU41_IN0A (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN5) +#define GPIO_CCU41_IN0B (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN9) +#define GPIO_CCU41_IN0C (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN4) +#define GPIO_CCU41_IN1A (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN4) +#define GPIO_CCU41_IN1B (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN9) +#define GPIO_CCU41_IN1C (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN5) +#define GPIO_CCU41_IN2A (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN3) +#define GPIO_CCU41_IN2B (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN9) +#define GPIO_CCU41_IN2C (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN10) +#define GPIO_CCU41_IN3A (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN2) +#define GPIO_CCU41_IN3B (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN9) +#define GPIO_CCU41_IN3C (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN11) +#define GPIO_CCU41_OUT0_1 (GPIO_OUTPUT_ALT3 | GPIO_PORT2 | GPIO_PIN5) +#define GPIO_CCU41_OUT0_2 (GPIO_OUTPUT_ALT3 | GPIO_PORT3 | GPIO_PIN10) +#define GPIO_CCU41_OUT1_1 (GPIO_OUTPUT_ALT3 | GPIO_PORT2 | GPIO_PIN4) +#define GPIO_CCU41_OUT1_2 (GPIO_OUTPUT_ALT3 | GPIO_PORT3 | GPIO_PIN9) +#define GPIO_CCU41_OUT2_1 (GPIO_OUTPUT_ALT3 | GPIO_PORT2 | GPIO_PIN3) +#define GPIO_CCU41_OUT2_2 (GPIO_OUTPUT_ALT3 | GPIO_PORT3 | GPIO_PIN8) +#define GPIO_CCU41_OUT3_1 (GPIO_OUTPUT_ALT3 | GPIO_PORT2 | GPIO_PIN2) +#define GPIO_CCU41_OUT3_2 (GPIO_OUTPUT_ALT3 | GPIO_PORT3 | GPIO_PIN7) +#define GPIO_CCU42_IN0A (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN6) +#define GPIO_CCU42_IN0B (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN15) +#define GPIO_CCU42_IN0C (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN15) +#define GPIO_CCU42_IN1A (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN5) +#define GPIO_CCU42_IN1B (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN15) +#define GPIO_CCU42_IN1C (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN14) +#define GPIO_CCU42_IN2A (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN4) +#define GPIO_CCU42_IN2B (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN15) +#define GPIO_CCU42_IN2C (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN15) +#define GPIO_CCU42_IN3A (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN3) +#define GPIO_CCU42_IN3B (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN15) +#define GPIO_CCU42_IN3C (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN14) +#define GPIO_CCU42_OUT0_1 (GPIO_OUTPUT_ALT3 | GPIO_PORT3 | GPIO_PIN0) +#define GPIO_CCU42_OUT0_2 (GPIO_OUTPUT_ALT3 | GPIO_PORT3 | GPIO_PIN6) +#define GPIO_CCU42_OUT1_1 (GPIO_OUTPUT_ALT3 | GPIO_PORT3 | GPIO_PIN13) +#define GPIO_CCU42_OUT1_2 (GPIO_OUTPUT_ALT3 | GPIO_PORT3 | GPIO_PIN5) +#define GPIO_CCU42_OUT2_1 (GPIO_OUTPUT_ALT3 | GPIO_PORT3 | GPIO_PIN12) +#define GPIO_CCU42_OUT2_2 (GPIO_OUTPUT_ALT3 | GPIO_PORT3 | GPIO_PIN4) +#define GPIO_CCU42_OUT3_1 (GPIO_OUTPUT_ALT3 | GPIO_PORT3 | GPIO_PIN11) +#define GPIO_CCU42_OUT3_2 (GPIO_OUTPUT_ALT3 | GPIO_PORT3 | GPIO_PIN3) +#define GPIO_CCU43_IN0A (GPIO_INPUT | GPIO_PORT4 | GPIO_PIN6) +#define GPIO_CCU43_IN0B (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN14) +#define GPIO_CCU43_IN0C (GPIO_INPUT | GPIO_PORT4 | GPIO_PIN7) +#define GPIO_CCU43_IN1A (GPIO_INPUT | GPIO_PORT4 | GPIO_PIN5) +#define GPIO_CCU43_IN1B (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN14) +#define GPIO_CCU43_IN1C (GPIO_INPUT | GPIO_PORT4 | GPIO_PIN2) +#define GPIO_CCU43_IN2A (GPIO_INPUT | GPIO_PORT4 | GPIO_PIN4) +#define GPIO_CCU43_IN2B (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN14) +#define GPIO_CCU43_IN2C (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN13) +#define GPIO_CCU43_IN3A (GPIO_INPUT | GPIO_PORT4 | GPIO_PIN3) +#define GPIO_CCU43_IN3B (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN14) +#define GPIO_CCU43_IN3C (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN12) +#define GPIO_CCU43_OUT0_1 (GPIO_OUTPUT_ALT3 | GPIO_PORT4 | GPIO_PIN6) +#define GPIO_CCU43_OUT0_2 (GPIO_OUTPUT_ALT3 | GPIO_PORT6 | GPIO_PIN5) +#define GPIO_CCU43_OUT1_1 (GPIO_OUTPUT_ALT3 | GPIO_PORT4 | GPIO_PIN5) +#define GPIO_CCU43_OUT1_2 (GPIO_OUTPUT_ALT3 | GPIO_PORT6 | GPIO_PIN4) +#define GPIO_CCU43_OUT2_1 (GPIO_OUTPUT_ALT3 | GPIO_PORT4 | GPIO_PIN4) +#define GPIO_CCU43_OUT2_2 (GPIO_OUTPUT_ALT3 | GPIO_PORT6 | GPIO_PIN3) +#define GPIO_CCU43_OUT3_1 (GPIO_OUTPUT_ALT3 | GPIO_PORT4 | GPIO_PIN3) +#define GPIO_CCU43_OUT3_2 (GPIO_OUTPUT_ALT3 | GPIO_PORT6 | GPIO_PIN2) +#define GPIO_CCU80_IN0A (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN7) +#define GPIO_CCU80_IN0B (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN4) +#define GPIO_CCU80_IN0C (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN2) +#define GPIO_CCU80_IN1A (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN7) +#define GPIO_CCU80_IN1B (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN8) +#define GPIO_CCU80_IN1C (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN1) +#define GPIO_CCU80_IN2A (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN7) +#define GPIO_CCU80_IN2B (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN6) +#define GPIO_CCU80_IN2C (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN0) +#define GPIO_CCU80_IN3A (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN7) +#define GPIO_CCU80_IN3B (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN3) +#define GPIO_CCU80_IN3C (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN13) +#define GPIO_CCU80_OUT00_1 (GPIO_OUTPUT_ALT3 | GPIO_PORT0 | GPIO_PIN5) +#define GPIO_CCU80_OUT00_2 (GPIO_OUTPUT_ALT3 | GPIO_PORT5 | GPIO_PIN11) +#define GPIO_CCU80_OUT01_1 (GPIO_OUTPUT_ALT3 | GPIO_PORT0 | GPIO_PIN2) +#define GPIO_CCU80_OUT01_2 (GPIO_OUTPUT_ALT3 | GPIO_PORT5 | GPIO_PIN8) +#define GPIO_CCU80_OUT02 1 (GPIO_OUTPUT_ALT3 | GPIO_PORT0 | GPIO_PIN10) +#define GPIO_CCU80_OUT03 2 (GPIO_OUTPUT_ALT3 | GPIO_PORT2 | GPIO_PIN7) +#define GPIO_CCU80_OUT10_1 (GPIO_OUTPUT_ALT3 | GPIO_PORT0 | GPIO_PIN4) +#define GPIO_CCU80_OUT10_2 (GPIO_OUTPUT_ALT3 | GPIO_PORT5 | GPIO_PIN10) +#define GPIO_CCU80_OUT11_1 (GPIO_OUTPUT_ALT3 | GPIO_PORT0 | GPIO_PIN1) +#define GPIO_CCU80_OUT11_2 (GPIO_OUTPUT_ALT3 | GPIO_PORT2 | GPIO_PIN15) +#define GPIO_CCU80_OUT12 (GPIO_OUTPUT_ALT3 | GPIO_PORT0 | GPIO_PIN9) +#define GPIO_CCU80_OUT13 (GPIO_OUTPUT_ALT3 | GPIO_PORT2 | GPIO_PIN6) +#define GPIO_CCU80_OUT20_1 (GPIO_OUTPUT_ALT3 | GPIO_PORT0 | GPIO_PIN3) +#define GPIO_CCU80_OUT20_2 (GPIO_OUTPUT_ALT3 | GPIO_PORT5 | GPIO_PIN9) +#define GPIO_CCU80_OUT21_1 (GPIO_OUTPUT_ALT3 | GPIO_PORT0 | GPIO_PIN0) +#define GPIO_CCU80_OUT21_2 (GPIO_OUTPUT_ALT3 | GPIO_PORT2 | GPIO_PIN14) +#define GPIO_CCU80_OUT22_1 (GPIO_OUTPUT_ALT3 | GPIO_PORT2 | GPIO_PIN11) +#define GPIO_CCU80_OUT22_2 (GPIO_OUTPUT_ALT3 | GPIO_PORT2 | GPIO_PIN9) +#define GPIO_CCU80_OUT23 (GPIO_OUTPUT_ALT3 | GPIO_PORT1 | GPIO_PIN5) +#define GPIO_CCU80_OUT30 (GPIO_OUTPUT_ALT3 | GPIO_PORT0 | GPIO_PIN6) +#define GPIO_CCU80_OUT31 (GPIO_OUTPUT_ALT3 | GPIO_PORT0 | GPIO_PIN11) +#define GPIO_CCU80_OUT32 (GPIO_OUTPUT_ALT3 | GPIO_PORT2 | GPIO_PIN8) +#define GPIO_CCU80_OUT33 (GPIO_OUTPUT_ALT3 | GPIO_PORT1 | GPIO_PIN4) +#define GPIO_CCU81_IN0A (GPIO_INPUT | GPIO_PORT5 | GPIO_PIN0) +#define GPIO_CCU81_IN0B (GPIO_INPUT | GPIO_PORT5 | GPIO_PIN1) +#define GPIO_CCU81_IN0C (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN0) +#define GPIO_CCU81_IN1A (GPIO_INPUT | GPIO_PORT5 | GPIO_PIN0) +#define GPIO_CCU81_IN1B (GPIO_INPUT | GPIO_PORT5 | GPIO_PIN2) +#define GPIO_CCU81_IN1C (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN13) +#define GPIO_CCU81_IN2A (GPIO_INPUT | GPIO_PORT5 | GPIO_PIN0) +#define GPIO_CCU81_IN2B (GPIO_INPUT | GPIO_PORT5 | GPIO_PIN3) +#define GPIO_CCU81_IN2C (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN12) +#define GPIO_CCU81_IN3A (GPIO_INPUT | GPIO_PORT5 | GPIO_PIN0) +#define GPIO_CCU81_IN3B (GPIO_INPUT | GPIO_PORT5 | GPIO_PIN4) +#define GPIO_CCU81_IN3C (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN11) +#define GPIO_CCU81_OUT00 (GPIO_OUTPUT_ALT3 | GPIO_PORT1 | GPIO_PIN15) +#define GPIO_CCU81_OUT01_1 (GPIO_OUTPUT_ALT2 | GPIO_PORT2 | GPIO_PIN2) +#define GPIO_CCU81_OUT01_2 (GPIO_OUTPUT_ALT3 | GPIO_PORT1 | GPIO_PIN12) +#define GPIO_CCU81_OUT02 (GPIO_OUTPUT_ALT3 | GPIO_PORT5 | GPIO_PIN7) +#define GPIO_CCU81_OUT03 (GPIO_OUTPUT_ALT3 | GPIO_PORT5 | GPIO_PIN6) +#define GPIO_CCU81_OUT10_1 (GPIO_OUTPUT_ALT3 | GPIO_PORT1 | GPIO_PIN14) +#define GPIO_CCU81_OUT10_2 (GPIO_OUTPUT_ALT4 | GPIO_PORT1 | GPIO_PIN5) +#define GPIO_CCU81_OUT11_1 (GPIO_OUTPUT_ALT2 | GPIO_PORT2 | GPIO_PIN1) +#define GPIO_CCU81_OUT11_2 (GPIO_OUTPUT_ALT3 | GPIO_PORT1 | GPIO_PIN11) +#define GPIO_CCU81_OUT12 (GPIO_OUTPUT_ALT3 | GPIO_PORT5 | GPIO_PIN5) +#define GPIO_CCU81_OUT13 (GPIO_OUTPUT_ALT3 | GPIO_PORT5 | GPIO_PIN4) +#define GPIO_CCU81_OUT20_1 (GPIO_OUTPUT_ALT3 | GPIO_PORT1 | GPIO_PIN13) +#define GPIO_CCU81_OUT20_2 (GPIO_OUTPUT_ALT4 | GPIO_PORT1 | GPIO_PIN4) +#define GPIO_CCU81_OUT21_1 (GPIO_OUTPUT_ALT2 | GPIO_PORT2 | GPIO_PIN0) +#define GPIO_CCU81_OUT21_2 (GPIO_OUTPUT_ALT3 | GPIO_PORT1 | GPIO_PIN10) +#define GPIO_CCU81_OUT22 (GPIO_OUTPUT_ALT3 | GPIO_PORT5 | GPIO_PIN3) +#define GPIO_CCU81_OUT23 (GPIO_OUTPUT_ALT3 | GPIO_PORT5 | GPIO_PIN2) +#define GPIO_CCU81_OUT30 (GPIO_OUTPUT_ALT3 | GPIO_PORT6 | GPIO_PIN1) +#define GPIO_CCU81_OUT31 (GPIO_OUTPUT_ALT3 | GPIO_PORT6 | GPIO_PIN0) +#define GPIO_CCU81_OUT32 (GPIO_OUTPUT_ALT3 | GPIO_PORT5 | GPIO_PIN1) +#define GPIO_CCU81_OUT33_1 (GPIO_OUTPUT_ALT3 | GPIO_PORT2 | GPIO_PIN12) +#define GPIO_CCU81_OUT33_2 (GPIO_OUTPUT_ALT3 | GPIO_PORT5 | GPIO_PIN0) + +#define GPIO_DAC_OUT0 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT14 | GPIO_PIN8) +#define GPIO_DAC_OUT1 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT14 | GPIO_PIN9) + +#define GPIO_DAC_TRIGGER4 (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN9) +#define GPIO_DAC_TRIGGER5 (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN8) +#define GPIO_DB_ETMTRACECLK_1 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT2 | GPIO_PIN14) +#define GPIO_DB_ETMTRACECLK_2 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT6 | GPIO_PIN0) +#define GPIO_DB_ETMTRACEDATA0_1 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT2 | GPIO_PIN13) +#define GPIO_DB_ETMTRACEDATA0_2 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT6 | GPIO_PIN6) +#define GPIO_DB_ETMTRACEDATA1_1 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT2 | GPIO_PIN12) +#define GPIO_DB_ETMTRACEDATA1_2 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT6 | GPIO_PIN5) +#define GPIO_DB_ETMTRACEDATA2_1 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT2 | GPIO_PIN11) +#define GPIO_DB_ETMTRACEDATA2_2 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT6 | GPIO_PIN2) +#define GPIO_DB_ETMTRACEDATA3_1 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT2 | GPIO_PIN10) +#define GPIO_DB_ETMTRACEDATA3_2 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT6 | GPIO_PIN1) +#define GPIO_DB_TDI (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT0 | GPIO_PIN7) +#define GPIO_DB_TDO (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT2 | GPIO_PIN1) + +#define GPIO_DB_TRST (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT0 | GPIO_PIN8) +#define GPIO_DSD_CGPWMN_1 (GPIO_OUTPUT_ALT1 | GPIO_PORT1 | GPIO_PIN0) +#define GPIO_DSD_CGPWMN_2 (GPIO_OUTPUT_ALT2 | GPIO_PORT5 | GPIO_PIN0) +#define GPIO_DSD_CGPWMN_3 (GPIO_OUTPUT_ALT3 | GPIO_PORT2 | GPIO_PIN0) +#define GPIO_DSD_CGPWMP_1 (GPIO_OUTPUT_ALT1 | GPIO_PORT1 | GPIO_PIN1) +#define GPIO_DSD_CGPWMP_2 (GPIO_OUTPUT_ALT2 | GPIO_PORT5 | GPIO_PIN1) +#define GPIO_DSD_CGPWMP_3 (GPIO_OUTPUT_ALT3 | GPIO_PORT2 | GPIO_PIN1) +#define GPIO_DSD_DIN0A (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN8) +#define GPIO_DSD_DIN0B (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN7) +#define GPIO_DSD_DIN1A (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN7) +#define GPIO_DSD_DIN1B (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN6) +#define GPIO_DSD_DIN2A (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN6) +#define GPIO_DSD_DIN2B (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN5) +#define GPIO_DSD_DIN3A (GPIO_INPUT | GPIO_PORT6 | GPIO_PIN5) +#define GPIO_DSD_DIN3B (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN3) +#define GPIO_DSD_MCLK0 (GPIO_OUTPUT_ALT3 | GPIO_PORT4 | GPIO_PIN1) +#define GPIO_DSD_MCLK0A (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN9) +#define GPIO_DSD_MCLK0B (GPIO_INPUT | GPIO_PORT4 | GPIO_PIN1) +#define GPIO_DSD_MCLK1_1 (GPIO_OUTPUT_ALT3 | GPIO_PORT1 | GPIO_PIN8) +#define GPIO_DSD_MCLK1_2 (GPIO_OUTPUT_ALT3 | GPIO_PORT4 | GPIO_PIN0) +#define GPIO_DSD_MCLK1A (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN8) +#define GPIO_DSD_MCLK1B (GPIO_INPUT | GPIO_PORT4 | GPIO_PIN0) +#define GPIO_DSD_MCLK2_1 (GPIO_OUTPUT_ALT2 | GPIO_PORT1 | GPIO_PIN15) +#define GPIO_DSD_MCLK2_2 (GPIO_OUTPUT_ALT3 | GPIO_PORT1 | GPIO_PIN7) +#define GPIO_DSD_MCLK2A (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN7) +#define GPIO_DSD_MCLK2B (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN15) +#define GPIO_DSD_MCLK3_1 (GPIO_OUTPUT_ALT3 | GPIO_PORT6 | GPIO_PIN6) +#define GPIO_DSD_MCLK3_2 (GPIO_OUTPUT_ALT4 | GPIO_PORT3 | GPIO_PIN4) +#define GPIO_DSD_MCLK3A (GPIO_INPUT | GPIO_PORT6 | GPIO_PIN6) +#define GPIO_DSD_MCLK3B (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN4) + +#define GPIO_EBU_A16 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT6 | GPIO_PIN0) +#define GPIO_EBU_A17 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT6 | GPIO_PIN1) +#define GPIO_EBU_A18 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT6 | GPIO_PIN2) +#define GPIO_EBU_A19 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT6 | GPIO_PIN4) +#define GPIO_EBU_A20 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT5 | GPIO_PIN3) +#define GPIO_EBU_A21 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT5 | GPIO_PIN4) +#define GPIO_EBU_A22 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT5 | GPIO_PIN5) +#define GPIO_EBU_A23 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT5 | GPIO_PIN6) +#define GPIO_EBU_AD0 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT0 | GPIO_PIN2) +#define GPIO_EBU_AD1 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT0 | GPIO_PIN3) +#define GPIO_EBU_AD2 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT0 | GPIO_PIN4) +#define GPIO_EBU_AD3 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT0 | GPIO_PIN5) +#define GPIO_EBU_AD4 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT3 | GPIO_PIN5) +#define GPIO_EBU_AD5 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT3 | GPIO_PIN6) +#define GPIO_EBU_AD6 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT0 | GPIO_PIN7) +#define GPIO_EBU_AD7 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT0 | GPIO_PIN8) +#define GPIO_EBU_AD8 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT4 | GPIO_PIN0) +#define GPIO_EBU_AD9 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT4 | GPIO_PIN1) +#define GPIO_EBU_AD10 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT1 | GPIO_PIN6) +#define GPIO_EBU_AD11 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT1 | GPIO_PIN7) +#define GPIO_EBU_AD12 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT1 | GPIO_PIN8) +#define GPIO_EBU_AD13 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT1 | GPIO_PIN9) +#define GPIO_EBU_AD14 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT1 | GPIO_PIN2) +#define GPIO_EBU_AD15 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT1 | GPIO_PIN3) +#define GPIO_EBU_AD16 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT1 | GPIO_PIN12) +#define GPIO_EBU_AD17 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT1 | GPIO_PIN13) +#define GPIO_EBU_AD18 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT1 | GPIO_PIN14) +#define GPIO_EBU_AD19 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT1 | GPIO_PIN15) +#define GPIO_EBU_AD20 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT2 | GPIO_PIN0) +#define GPIO_EBU_AD21 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT2 | GPIO_PIN1) +#define GPIO_EBU_AD22 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT2 | GPIO_PIN2) +#define GPIO_EBU_AD23 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT2 | GPIO_PIN3) +#define GPIO_EBU_AD24 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT2 | GPIO_PIN4) +#define GPIO_EBU_AD25 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT2 | GPIO_PIN5) +#define GPIO_EBU_AD26 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT2 | GPIO_PIN8) +#define GPIO_EBU_AD27 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT2 | GPIO_PIN9) +#define GPIO_EBU_AD28 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT2 | GPIO_PIN10) +#define GPIO_EBU_AD29 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT2 | GPIO_PIN11) +#define GPIO_EBU_AD30 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT2 | GPIO_PIN12) +#define GPIO_EBU_AD31 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT2 | GPIO_PIN13) +#define GPIO_EBU_ADV (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT0 | GPIO_PIN6) +#define GPIO_EBU_BC0 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT2 | GPIO_PIN14) +#define GPIO_EBU_BC1 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT2 | GPIO_PIN15) +#define GPIO_EBU_BC2 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT6 | GPIO_PIN5) +#define GPIO_EBU_BC3 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT6 | GPIO_PIN6) +#define GPIO_EBU_BFCLKI (GPIO_INPUT | GPIO_PORT5 | GPIO_PIN6) +#define GPIO_EBU_BFCLKO_1 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT5 | GPIO_PIN6) +#define GPIO_EBU_BFCLKO_2 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT5 | GPIO_PIN9) +#define GPIO_EBU_BREQ (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT0 | GPIO_PIN11) +#define GPIO_EBU_CAS (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT5 | GPIO_PIN5) +#define GPIO_EBU_CKE (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT5 | GPIO_PIN3) +#define GPIO_EBU_CS0 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT3 | GPIO_PIN2) +#define GPIO_EBU_CS1 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT0 | GPIO_PIN9) +#define GPIO_EBU_CS2 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT5 | GPIO_PIN8) +#define GPIO_EBU_CS3 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT5 | GPIO_PIN9) +#define GPIO_EBU_D0 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT0 | GPIO_PIN2) +#define GPIO_EBU_D1 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT0 | GPIO_PIN3) +#define GPIO_EBU_D2 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT0 | GPIO_PIN4) +#define GPIO_EBU_D3 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT0 | GPIO_PIN5) +#define GPIO_EBU_D4 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT3 | GPIO_PIN5) +#define GPIO_EBU_D5 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT3 | GPIO_PIN6) +#define GPIO_EBU_D6 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT0 | GPIO_PIN7) +#define GPIO_EBU_D7 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT0 | GPIO_PIN8) +#define GPIO_EBU_D8 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT4 | GPIO_PIN0) +#define GPIO_EBU_D9 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT4 | GPIO_PIN1) +#define GPIO_EBU_D10 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT1 | GPIO_PIN6) +#define GPIO_EBU_D11 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT1 | GPIO_PIN7) +#define GPIO_EBU_D12 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT1 | GPIO_PIN8) +#define GPIO_EBU_D13 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT1 | GPIO_PIN9) +#define GPIO_EBU_D14 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT1 | GPIO_PIN2) +#define GPIO_EBU_D15 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT1 | GPIO_PIN3) +#define GPIO_EBU_D16 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT1 | GPIO_PIN12) +#define GPIO_EBU_D17 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT1 | GPIO_PIN13) +#define GPIO_EBU_D18 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT1 | GPIO_PIN14) +#define GPIO_EBU_D19 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT1 | GPIO_PIN15) +#define GPIO_EBU_D20 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT2 | GPIO_PIN0) +#define GPIO_EBU_D21 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT2 | GPIO_PIN1) +#define GPIO_EBU_D22 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT2 | GPIO_PIN2) +#define GPIO_EBU_D23 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT2 | GPIO_PIN3) +#define GPIO_EBU_D24 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT2 | GPIO_PIN4) +#define GPIO_EBU_D25 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT2 | GPIO_PIN5) +#define GPIO_EBU_D26 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT2 | GPIO_PIN8) +#define GPIO_EBU_D27 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT2 | GPIO_PIN9) +#define GPIO_EBU_D28 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT2 | GPIO_PIN10) +#define GPIO_EBU_D29 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT2 | GPIO_PIN11) +#define GPIO_EBU_D30 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT2 | GPIO_PIN12) +#define GPIO_EBU_D31 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT2 | GPIO_PIN13) +#define GPIO_EBU_HLDA_1 (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT0 | GPIO_PIN12) +#define GPIO_EBU_HLDA_2 (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT0 | GPIO_PIN12) +#define GPIO_EBU_HOLD (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT3 | GPIO_PIN4) +#define GPIO_EBU_RAS (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT5 | GPIO_PIN4) +#define GPIO_EBU_RD (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT3 | GPIO_PIN0) +#define GPIO_EBU_RDWR (GPIO_OUTPUT | GPIO_PINCTRL_HW1 | GPIO_PORT3 | GPIO_PIN1) +#define GPIO_EBU_SDCLKI (GPIO_INPUT | GPIO_PORT6 | GPIO_PIN4) +#define GPIO_EBU_SDCLKO_1 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT5 | GPIO_PIN8) +#define GPIO_EBU_SDCLKO_2 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT6 | GPIO_PIN4) +#define GPIO_EBU_WAIT (GPIO_INPUT | GPIO_PINCTRL_HW1 | GPIO_PORT3 | GPIO_PIN3) +#define GPIO_ERU0_0A0 (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN1) +#define GPIO_ERU0_0A1 (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN2) +#define GPIO_ERU0_0A2 (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN5) +#define GPIO_ERU0_0B0 (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN0) +#define GPIO_ERU0_0B1 (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN1) +#define GPIO_ERU0_0B2 (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN4) +#define GPIO_ERU0_0B3 (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN0) +#define GPIO_ERU0_1A0 (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN10) +#define GPIO_ERU0_1A2 (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN3) +#define GPIO_ERU0_1B0 (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN9) +#define GPIO_ERU0_1B2 (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN2) +#define GPIO_ERU0_1B3 (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN6) +#define GPIO_ERU0_2A0 (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN5) +#define GPIO_ERU0_2A1 (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN8) +#define GPIO_ERU0_2A2 (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN13) +#define GPIO_ERU0_2B0 (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN4) +#define GPIO_ERU0_2B1 (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN7) +#define GPIO_ERU0_2B2 (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN12) +#define GPIO_ERU0_2B3 (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN4) +#define GPIO_ERU0_3A0 (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN1) +#define GPIO_ERU0_3A1 (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN6) +#define GPIO_ERU0_3A2 (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN11) +#define GPIO_ERU0_3B0 (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN0) +#define GPIO_ERU0_3B1 (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN5) +#define GPIO_ERU0_3B2 (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN6) +#define GPIO_ERU0_3B3 (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN2) +#define GPIO_ERU1_0A0 (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN5) +#define GPIO_ERU1_0B0 (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN1) +#define GPIO_ERU1_1A0 (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN15) +#define GPIO_ERU1_1B0 (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN7) +#define GPIO_ERU1_2A0 (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN3) +#define GPIO_ERU1_2B0 (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN2) +#define GPIO_ERU1_3A0 (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN5) +#define GPIO_ERU1_3B0 (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN3) +#define GPIO_ERU1_PDOUT0 (GPIO_OUTPUT_ALT4 | GPIO_PORT1 | GPIO_PIN3) +#define GPIO_ERU1_PDOUT1 (GPIO_OUTPUT_ALT4 | GPIO_PORT1 | GPIO_PIN2) +#define GPIO_ERU1_PDOUT2 (GPIO_OUTPUT_ALT4 | GPIO_PORT1 | GPIO_PIN1) +#define GPIO_ERU1_PDOUT3 (GPIO_OUTPUT_ALT4 | GPIO_PORT1 | GPIO_PIN0) + +#define GPIO_ETH0_CLKRMIIA (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN1) +#define GPIO_ETH0_CLKRMIIB (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN0) +#define GPIO_ETH0_CLKRMIIC (GPIO_INPUT | GPIO_PORT15 | GPIO_PIN8) +#define GPIO_ETH0_CLKRMIID (GPIO_INPUT | GPIO_PORT6 | GPIO_PIN5) +#define GPIO_ETH0_CLKRXA (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN1) +#define GPIO_ETH0_CLKRXB (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN0) +#define GPIO_ETH0_CLKRXC (GPIO_INPUT | GPIO_PORT15 | GPIO_PIN8) +#define GPIO_ETH0_CLKRXD (GPIO_INPUT | GPIO_PORT6 | GPIO_PIN5) +#define GPIO_ETH0_CLKTXA (GPIO_INPUT | GPIO_PORT5 | GPIO_PIN10) +#define GPIO_ETH0_CLKTXB (GPIO_INPUT | GPIO_PORT6 | GPIO_PIN6) +#define GPIO_ETH0_COLA (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN15) +#define GPIO_ETH0_COLD (GPIO_INPUT | GPIO_PORT5 | GPIO_PIN5) +#define GPIO_ETH0_CRSA (GPIO_INPUT | GPIO_PORT5 | GPIO_PIN11) +#define GPIO_ETH0_CRSD (GPIO_INPUT | GPIO_PORT5 | GPIO_PIN4) +#define GPIO_ETH0_CRSDVA_1 (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN5) +#define GPIO_ETH0_CRSDVA_2 (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN5) +#define GPIO_ETH0_CRSDVB (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN1) +#define GPIO_ETH0_CRSDVC (GPIO_INPUT | GPIO_PORT15 | GPIO_PIN9) +#define GPIO_ETH0_CRSDVD (GPIO_INPUT | GPIO_PORT5 | GPIO_PIN2) +#define GPIO_ETH0_MDC_1 (GPIO_OUTPUT_ALT1 | GPIO_PORT0 | GPIO_PIN10) +#define GPIO_ETH0_MDC_2 (GPIO_OUTPUT_ALT1 | GPIO_PORT1 | GPIO_PIN10) +#define GPIO_ETH0_MDC_3 (GPIO_OUTPUT_ALT1 | GPIO_PORT2 | GPIO_PIN7) +#define GPIO_ETH0_MDIA (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT0 | GPIO_PIN9) +#define GPIO_ETH0_MDIB (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT2 | GPIO_PIN0) +#define GPIO_ETH0_MDIC (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT1 | GPIO_PIN11) +#define GPIO_ETH0_MDO_1 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT0 | GPIO_PIN9) +#define GPIO_ETH0_MDO_2 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT1 | GPIO_PIN11) +#define GPIO_ETH0_MDO_3 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT2 | GPIO_PIN0) +#define GPIO_ETH0_RXD0A (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN2) +#define GPIO_ETH0_RXD0B (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN2) +#define GPIO_ETH0_RXD0C (GPIO_INPUT | GPIO_PORT14 | GPIO_PIN8) +#define GPIO_ETH0_RXD0D (GPIO_INPUT | GPIO_PORT5 | GPIO_PIN0) +#define GPIO_ETH0_RXD1A (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN3) +#define GPIO_ETH0_RXD1B (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN3) +#define GPIO_ETH0_RXD1C (GPIO_INPUT | GPIO_PORT14 | GPIO_PIN9) +#define GPIO_ETH0_RXD1D (GPIO_INPUT | GPIO_PORT5 | GPIO_PIN1) +#define GPIO_ETH0_RXD2A (GPIO_INPUT | GPIO_PORT5 | GPIO_PIN8) +#define GPIO_ETH0_RXD2B (GPIO_INPUT | GPIO_PORT6 | GPIO_PIN4) +#define GPIO_ETH0_RXD3A (GPIO_INPUT | GPIO_PORT5 | GPIO_PIN9) +#define GPIO_ETH0_RXD3B (GPIO_INPUT | GPIO_PORT6 | GPIO_PIN3) +#define GPIO_ETH0_RXDVB (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN1) +#define GPIO_ETH0_RXDVC (GPIO_INPUT | GPIO_PORT15 | GPIO_PIN9) +#define GPIO_ETH0_RXDVD (GPIO_INPUT | GPIO_PORT5 | GPIO_PIN2) +#define GPIO_ETH0_RXERA (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN4) +#define GPIO_ETH0_RXERB (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN11) +#define GPIO_ETH0_RXERD (GPIO_INPUT | GPIO_PORT5 | GPIO_PIN3) +#define GPIO_ETH0_TXD0_1 (GPIO_OUTPUT_ALT1 | GPIO_PORT0 | GPIO_PIN5) +#define GPIO_ETH0_TXD0_2 (GPIO_OUTPUT_ALT1 | GPIO_PORT1 | GPIO_PIN13) +#define GPIO_ETH0_TXD0_3 (GPIO_OUTPUT_ALT1 | GPIO_PORT2 | GPIO_PIN8) +#define GPIO_ETH0_TXD0_4 (GPIO_OUTPUT_ALT4 | GPIO_PORT2 | GPIO_PIN12) +#define GPIO_ETH0_TXD1_1 (GPIO_OUTPUT_ALT1 | GPIO_PORT0 | GPIO_PIN6) +#define GPIO_ETH0_TXD1_2 (GPIO_OUTPUT_ALT1 | GPIO_PORT1 | GPIO_PIN14) +#define GPIO_ETH0_TXD1_3 (GPIO_OUTPUT_ALT1 | GPIO_PORT2 | GPIO_PIN9) +#define GPIO_ETH0_TXD1_4 (GPIO_OUTPUT_ALT4 | GPIO_PORT2 | GPIO_PIN13) +#define GPIO_ETH0_TXD2_1 (GPIO_OUTPUT_ALT1 | GPIO_PORT2 | GPIO_PIN12) +#define GPIO_ETH0_TXD2_2 (GPIO_OUTPUT_ALT1 | GPIO_PORT6 | GPIO_PIN0) +#define GPIO_ETH0_TXD3_1 (GPIO_OUTPUT_ALT1 | GPIO_PORT2 | GPIO_PIN13) +#define GPIO_ETH0_TXD3_2 (GPIO_OUTPUT_ALT1 | GPIO_PORT6 | GPIO_PIN1) +#define GPIO_ETH0_TXEN_1 (GPIO_OUTPUT_ALT1 | GPIO_PORT0 | GPIO_PIN4) +#define GPIO_ETH0_TXEN_2 (GPIO_OUTPUT_ALT1 | GPIO_PORT1 | GPIO_PIN12) +#define GPIO_ETH0_TXEN_3 (GPIO_OUTPUT_ALT1 | GPIO_PORT2 | GPIO_PIN5) +#define GPIO_ETH0_TXEN_4 (GPIO_OUTPUT_ALT4 | GPIO_PORT5 | GPIO_PIN9) +#define GPIO_ETH0_TXER_1 (GPIO_OUTPUT_ALT1 | GPIO_PORT2 | GPIO_PIN11) +#define GPIO_ETH0_TXER_2 (GPIO_OUTPUT_ALT1 | GPIO_PORT6 | GPIO_PIN2) + +#define GPIO_G0ORC6 (GPIO_INPUT | GPIO_PORT14 | GPIO_PIN6) +#define GPIO_G0ORC7 (GPIO_INPUT | GPIO_PORT14 | GPIO_PIN7) +#define GPIO_G1ORC6 (GPIO_INPUT | GPIO_PORT14 | GPIO_PIN14) +#define GPIO_G1ORC7 (GPIO_INPUT | GPIO_PORT14 | GPIO_PIN15) + +#define GPIO_LEDTS0_COL0_1 (GPIO_OUTPUT_ALT4 | GPIO_PORT0 | GPIO_PIN9) +#define GPIO_LEDTS0_COL0_2 (GPIO_OUTPUT_ALT4 | GPIO_PORT2 | GPIO_PIN1) +#define GPIO_LEDTS0_COL1_1 (GPIO_OUTPUT_ALT4 | GPIO_PORT0 | GPIO_PIN10) +#define GPIO_LEDTS0_COL1_2 (GPIO_OUTPUT_ALT4 | GPIO_PORT2 | GPIO_PIN0) +#define GPIO_LEDTS0_COL2_1 (GPIO_OUTPUT_ALT4 | GPIO_PORT0 | GPIO_PIN0) +#define GPIO_LEDTS0_COL2_2 (GPIO_OUTPUT_ALT4 | GPIO_PORT2 | GPIO_PIN7) +#define GPIO_LEDTS0_COL3_1 (GPIO_OUTPUT_ALT4 | GPIO_PORT0 | GPIO_PIN1) +#define GPIO_LEDTS0_COL3_2 (GPIO_OUTPUT_ALT4 | GPIO_PORT2 | GPIO_PIN6) +#define GPIO_LEDTS0_COLA_1 (GPIO_OUTPUT_ALT4 | GPIO_PORT3 | GPIO_PIN2) +#define GPIO_LEDTS0_COLA_2 (GPIO_OUTPUT_ALT4 | GPIO_PORT5 | GPIO_PIN7) +#define GPIO_LEDTS0_EXTENDED0 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT2 | GPIO_PIN2) +#define GPIO_LEDTS0_EXTENDED1 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT2 | GPIO_PIN3) +#define GPIO_LEDTS0_EXTENDED2 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT2 | GPIO_PIN4) +#define GPIO_LEDTS0_EXTENDED3 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT2 | GPIO_PIN5) +#define GPIO_LEDTS0_EXTENDED4 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT2 | GPIO_PIN8) +#define GPIO_LEDTS0_EXTENDED5 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT2 | GPIO_PIN9) +#define GPIO_LEDTS0_EXTENDED6 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT2 | GPIO_PIN15) +#define GPIO_LEDTS0_EXTENDED7 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT5 | GPIO_PIN10) +#define GPIO_LEDTS0_LINE0_1 (GPIO_OUTPUT_ALT4 | GPIO_PORT2 | GPIO_PIN2) +#define GPIO_LEDTS0_LINE0_2 (GPIO_OUTPUT_ALT4 | GPIO_PORT3 | GPIO_PIN7) +#define GPIO_LEDTS0_LINE1_1 (GPIO_OUTPUT_ALT4 | GPIO_PORT2 | GPIO_PIN3) +#define GPIO_LEDTS0_LINE1_2 (GPIO_OUTPUT_ALT4 | GPIO_PORT3 | GPIO_PIN8) +#define GPIO_LEDTS0_LINE2_1 (GPIO_OUTPUT_ALT4 | GPIO_PORT2 | GPIO_PIN4) +#define GPIO_LEDTS0_LINE2_2 (GPIO_OUTPUT_ALT4 | GPIO_PORT3 | GPIO_PIN9) +#define GPIO_LEDTS0_LINE3_1 (GPIO_OUTPUT_ALT4 | GPIO_PORT2 | GPIO_PIN5) +#define GPIO_LEDTS0_LINE3_2 (GPIO_OUTPUT_ALT4 | GPIO_PORT3 | GPIO_PIN10) +#define GPIO_LEDTS0_LINE4_1 (GPIO_OUTPUT_ALT4 | GPIO_PORT2 | GPIO_PIN8) +#define GPIO_LEDTS0_LINE4_2 (GPIO_OUTPUT_ALT4 | GPIO_PORT3 | GPIO_PIN11) +#define GPIO_LEDTS0_LINE5_1 (GPIO_OUTPUT_ALT4 | GPIO_PORT2 | GPIO_PIN9) +#define GPIO_LEDTS0_LINE5_2 (GPIO_OUTPUT_ALT4 | GPIO_PORT3 | GPIO_PIN12) +#define GPIO_LEDTS0_LINE6_1 (GPIO_OUTPUT_ALT4 | GPIO_PORT2 | GPIO_PIN15) +#define GPIO_LEDTS0_LINE6_2 (GPIO_OUTPUT_ALT4 | GPIO_PORT3 | GPIO_PIN13) +#define GPIO_LEDTS0_LINE7 (GPIO_OUTPUT_ALT4 | GPIO_PORT5 | GPIO_PIN10) +#define GPIO_LEDTS0_TSIN0A (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT2 | GPIO_PIN2) +#define GPIO_LEDTS0_TSIN1A (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT2 | GPIO_PIN3) +#define GPIO_LEDTS0_TSIN2A (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT2 | GPIO_PIN4) +#define GPIO_LEDTS0_TSIN3A (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT2 | GPIO_PIN5) +#define GPIO_LEDTS0_TSIN4A (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT2 | GPIO_PIN8) +#define GPIO_LEDTS0_TSIN5A (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT2 | GPIO_PIN9) +#define GPIO_LEDTS0_TSIN6A (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT2 | GPIO_PIN15) +#define GPIO_LEDTS0_TSIN7A (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT5 | GPIO_PIN10) + +#define GPIO_POSIF0_IN0A (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN3) +#define GPIO_POSIF0_IN0B (GPIO_INPUT | GPIO_PORT14 | GPIO_PIN7) +#define GPIO_POSIF0_IN1A (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN2) +#define GPIO_POSIF0_IN1B (GPIO_INPUT | GPIO_PORT14 | GPIO_PIN6) +#define GPIO_POSIF0_IN2A (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN1) +#define GPIO_POSIF0_IN2B (GPIO_INPUT | GPIO_PORT14 | GPIO_PIN5) +#define GPIO_POSIF1_IN0A (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN5) +#define GPIO_POSIF1_IN0B (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN10) +#define GPIO_POSIF1_IN1A (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN4) +#define GPIO_POSIF1_IN1B (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN9) +#define GPIO_POSIF1_IN2A (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN3) +#define GPIO_POSIF1_IN2B (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN8) + +#define GPIO_SCU_EXTCLK_1 (GPIO_OUTPUT_ALT1 | GPIO_PORT0 | GPIO_PIN8) +#define GPIO_SCU_EXTCLK_2 (GPIO_OUTPUT_ALT1 | GPIO_PORT1 | GPIO_PIN15) + +#define GPIO_SDMMC_BUSPOWER (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT3 | GPIO_PIN4) +#define GPIO_SDMMC_CLKIN (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT3 | GPIO_PIN6) +#define GPIO_SDMMC_CLKOUT (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT3 | GPIO_PIN6) +#define GPIO_SDMMC_CMDIN (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT3 | GPIO_PIN5) +#define GPIO_SDMMC_CMDOUT (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT3 | GPIO_PIN5) +#define GPIO_SDMMC_DATA0IN (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT4 | GPIO_PIN0) +#define GPIO_SDMMC_DATA0OUT (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT4 | GPIO_PIN0) +#define GPIO_SDMMC_DATA1IN (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT1 | GPIO_PIN6) +#define GPIO_SDMMC_DATA1OUT (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT1 | GPIO_PIN6) +#define GPIO_SDMMC_DATA2IN (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT1 | GPIO_PIN7) +#define GPIO_SDMMC_DATA2OUT (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT1 | GPIO_PIN7) +#define GPIO_SDMMC_DATA3IN (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT4 | GPIO_PIN1) +#define GPIO_SDMMC_DATA3OUT (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT4 | GPIO_PIN1) +#define GPIO_SDMMC_DATA4IN (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT1 | GPIO_PIN8) +#define GPIO_SDMMC_DATA4OUT (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT1 | GPIO_PIN8) +#define GPIO_SDMMC_DATA5IN (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT1 | GPIO_PIN9) +#define GPIO_SDMMC_DATA5OUT (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT1 | GPIO_PIN9) +#define GPIO_SDMMC_DATA6IN (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT1 | GPIO_PIN12) +#define GPIO_SDMMC_DATA6OUT (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT1 | GPIO_PIN12) +#define GPIO_SDMMC_DATA7IN (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT1 | GPIO_PIN13) +#define GPIO_SDMMC_DATA7OUT (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT1 | GPIO_PIN13) +#define GPIO_SDMMC_LED (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT3 | GPIO_PIN3) +#define GPIO_SDMMC_RST (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT0 | GPIO_PIN11) +#define GPIO_SDMMC_SDCD (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT1 | GPIO_PIN10) +#define GPIO_SDMMC_SDWC (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT1 | GPIO_PIN1) +#define GPIO_TRACESWO (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT2 | GPIO_PIN1) + +#define GPIO_U0C0_DOUT0_1 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT1 | GPIO_PIN5) +#define GPIO_U0C0_DOUT0_2 (GPIO_OUTPUT_ALT1 | GPIO_PORT5 | GPIO_PIN1) +#define GPIO_U0C0_DOUT0_3 (GPIO_OUTPUT_ALT2 | GPIO_PORT1 | GPIO_PIN5) +#define GPIO_U0C0_DOUT0_4 (GPIO_OUTPUT_ALT2 | GPIO_PORT1 | GPIO_PIN7) +#define GPIO_U0C0_DOUT1_1 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT1 | GPIO_PIN4) +#define GPIO_U0C0_DOUT2_2 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT1 | GPIO_PIN3) +#define GPIO_U0C0_DOUT3_3 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT1 | GPIO_PIN2) +#define GPIO_U0C0_DX0A (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN5) +#define GPIO_U0C0_DX0B (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN4) +#define GPIO_U0C0_DX0C (GPIO_INPUT | GPIO_PORT4 | GPIO_PIN7) +#define GPIO_U0C0_DX0D (GPIO_INPUT | GPIO_PORT5 | GPIO_PIN0) +#define GPIO_U0C0_DX1A (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN1) +#define GPIO_U0C0_DX1B (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN8) +#define GPIO_U0C0_DX2A (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN0) +#define GPIO_U0C0_DX2B (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN7) +#define GPIO_U0C0_HWIN0 (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT1 | GPIO_PIN5) +#define GPIO_U0C0_HWIN1 (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT1 | GPIO_PIN4) +#define GPIO_U0C0_HWIN2 (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT1 | GPIO_PIN3) +#define GPIO_U0C0_HWIN3 (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT1 | GPIO_PIN2) +#define GPIO_U0C0_MCLKOUT (GPIO_OUTPUT_ALT2 | GPIO_PORT1 | GPIO_PIN3) +#define GPIO_U0C0_SCLKOUT_1 (GPIO_OUTPUT_ALT2 | GPIO_PORT0 | GPIO_PIN8) +#define GPIO_U0C0_SCLKOUT_2 (GPIO_OUTPUT_ALT2 | GPIO_PORT1 | GPIO_PIN1) +#define GPIO_U0C0_SCLKOUT_3 (GPIO_OUTPUT_ALT2 | GPIO_PORT1 | GPIO_PIN10) +#define GPIO_U0C0_SCLKOUT_4 (GPIO_OUTPUT_ALT2 | GPIO_PORT1 | GPIO_PIN6) +#define GPIO_U0C0_SELO0_1 (GPIO_OUTPUT_ALT2 | GPIO_PORT0 | GPIO_PIN7) +#define GPIO_U0C0_SELO0_2 (GPIO_OUTPUT_ALT2 | GPIO_PORT1 | GPIO_PIN0) +#define GPIO_U0C0_SELO0_3 (GPIO_OUTPUT_ALT2 | GPIO_PORT1 | GPIO_PIN11) +#define GPIO_U0C0_SELO1 (GPIO_OUTPUT_ALT2 | GPIO_PORT1 | GPIO_PIN8) +#define GPIO_U0C0_SELO2 (GPIO_OUTPUT_ALT2 | GPIO_PORT4 | GPIO_PIN6) +#define GPIO_U0C0_SELO3 (GPIO_OUTPUT_ALT2 | GPIO_PORT4 | GPIO_PIN5) +#define GPIO_U0C0_SELO4 (GPIO_OUTPUT_ALT2 | GPIO_PORT4 | GPIO_PIN4) +#define GPIO_U0C0_SELO5 (GPIO_OUTPUT_ALT2 | GPIO_PORT4 | GPIO_PIN3) +#define GPIO_U0C1_DOUT0_1 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT3 | GPIO_PIN13) +#define GPIO_U0C1_DOUT0_2 (GPIO_OUTPUT_ALT2 | GPIO_PORT2 | GPIO_PIN5) +#define GPIO_U0C1_DOUT0_3 (GPIO_OUTPUT_ALT2 | GPIO_PORT3 | GPIO_PIN13) +#define GPIO_U0C1_DOUT0_4 (GPIO_OUTPUT_ALT2 | GPIO_PORT6 | GPIO_PIN4) +#define GPIO_U0C1_DOUT0_5 (GPIO_OUTPUT_ALT4 | GPIO_PORT3 | GPIO_PIN5) +#define GPIO_U0C1_DOUT1 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT3 | GPIO_PIN12) +#define GPIO_U0C1_DOUT2 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT3 | GPIO_PIN11) +#define GPIO_U0C1_DOUT3 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT3 | GPIO_PIN10) +#define GPIO_U0C1_DX0A (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN2) +#define GPIO_U0C1_DX0B (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN5) +#define GPIO_U0C1_DX0C (GPIO_INPUT | GPIO_PORT6 | GPIO_PIN3) +#define GPIO_U0C1_DX0D (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN13) +#define GPIO_U0C1_DX0E (GPIO_INPUT | GPIO_PORT4 | GPIO_PIN0) +#define GPIO_U0C1_DX1A (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN4) +#define GPIO_U0C1_DX1B (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN0) +#define GPIO_U0C1_DX1C (GPIO_INPUT | GPIO_PORT6 | GPIO_PIN2) +#define GPIO_U0C1_DX2A (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN3) +#define GPIO_U0C1_DX2B (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN1) +#define GPIO_U0C1_DX2C (GPIO_INPUT | GPIO_PORT6 | GPIO_PIN1) +#define GPIO_U0C1_HWIN0 (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT3 | GPIO_PIN13) +#define GPIO_U0C1_HWIN1 (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT3 | GPIO_PIN12) +#define GPIO_U0C1_HWIN2 (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT3 | GPIO_PIN11) +#define GPIO_U0C1_HWIN3 (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT3 | GPIO_PIN10) +#define GPIO_U0C1_MCLKOUT (GPIO_OUTPUT_ALT2 | GPIO_PORT6 | GPIO_PIN5) +#define GPIO_U0C1_SCLKOUT_1 (GPIO_OUTPUT_ALT2 | GPIO_PORT2 | GPIO_PIN4) +#define GPIO_U0C1_SCLKOUT_2 (GPIO_OUTPUT_ALT2 | GPIO_PORT3 | GPIO_PIN0) +#define GPIO_U0C1_SCLKOUT_3 (GPIO_OUTPUT_ALT2 | GPIO_PORT6 | GPIO_PIN2) +#define GPIO_U0C1_SCLKOUT_4 (GPIO_OUTPUT_ALT4 | GPIO_PORT3 | GPIO_PIN6) +#define GPIO_U0C1_SELO0_1 (GPIO_OUTPUT_ALT2 | GPIO_PORT2 | GPIO_PIN3) +#define GPIO_U0C1_SELO0_2 (GPIO_OUTPUT_ALT2 | GPIO_PORT3 | GPIO_PIN1) +#define GPIO_U0C1_SELO0_3 (GPIO_OUTPUT_ALT2 | GPIO_PORT6 | GPIO_PIN1) +#define GPIO_U0C1_SELO0_4 (GPIO_OUTPUT_ALT4 | GPIO_PORT4 | GPIO_PIN1) +#define GPIO_U0C1_SELO1_1 (GPIO_OUTPUT_ALT2 | GPIO_PORT3 | GPIO_PIN12) +#define GPIO_U0C1_SELO1_2 (GPIO_OUTPUT_ALT2 | GPIO_PORT6 | GPIO_PIN0) +#define GPIO_U0C1_SELO2_1 (GPIO_OUTPUT_ALT2 | GPIO_PORT1 | GPIO_PIN14) +#define GPIO_U0C1_SELO2_2 (GPIO_OUTPUT_ALT2 | GPIO_PORT3 | GPIO_PIN11) +#define GPIO_U0C1_SELO3_1 (GPIO_OUTPUT_ALT2 | GPIO_PORT1 | GPIO_PIN13) +#define GPIO_U0C1_SELO3_2 (GPIO_OUTPUT_ALT2 | GPIO_PORT3 | GPIO_PIN8) +#define GPIO_U1C0_DOUT0_1 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT0 | GPIO_PIN5) +#define GPIO_U1C0_DOUT0_2 (GPIO_OUTPUT_ALT2 | GPIO_PORT0 | GPIO_PIN5) +#define GPIO_U1C0_DOUT0_3 (GPIO_OUTPUT_ALT2 | GPIO_PORT2 | GPIO_PIN14) +#define GPIO_U1C0_DOUT1 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT0 | GPIO_PIN4) +#define GPIO_U1C0_DOUT2 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT0 | GPIO_PIN3) +#define GPIO_U1C0_DOUT3 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT0 | GPIO_PIN2) +#define GPIO_U1C0_DX0A (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN4) +#define GPIO_U1C0_DX0B (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN5) +#define GPIO_U1C0_DX0C (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN15) +#define GPIO_U1C0_DX0D (GPIO_INPUT | GPIO_PORT2 | GPIO_PIN14) +#define GPIO_U1C0_DX1A (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN11) +#define GPIO_U1C0_DX1B (GPIO_INPUT | GPIO_PORT5 | GPIO_PIN8) +#define GPIO_U1C0_DX2A (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN6) +#define GPIO_U1C0_DX2B (GPIO_INPUT | GPIO_PORT5 | GPIO_PIN9) +#define GPIO_U1C0_HWIN0 (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT0 | GPIO_PIN5) +#define GPIO_U1C0_HWIN1 (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT0 | GPIO_PIN4) +#define GPIO_U1C0_HWIN2 (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT0 | GPIO_PIN3) +#define GPIO_U1C0_HWIN3 (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT0 | GPIO_PIN2) +#define GPIO_U1C0_MCLKOUT (GPIO_OUTPUT_ALT2 | GPIO_PORT5 | GPIO_PIN10) +#define GPIO_U1C0_SCLKOUT_1 (GPIO_OUTPUT_ALT2 | GPIO_PORT0 | GPIO_PIN11) +#define GPIO_U1C0_SCLKOUT_2 (GPIO_OUTPUT_ALT2 | GPIO_PORT5 | GPIO_PIN8) +#define GPIO_U1C0_SELO0_1 (GPIO_OUTPUT_ALT2 | GPIO_PORT0 | GPIO_PIN6) +#define GPIO_U1C0_SELO0_2 (GPIO_OUTPUT_ALT2 | GPIO_PORT5 | GPIO_PIN9) +#define GPIO_U1C0_SELO1_1 (GPIO_OUTPUT_ALT2 | GPIO_PORT0 | GPIO_PIN14) +#define GPIO_U1C0_SELO1_2 (GPIO_OUTPUT_ALT2 | GPIO_PORT5 | GPIO_PIN11) +#define GPIO_U1C0_SELO2 (GPIO_OUTPUT_ALT2 | GPIO_PORT0 | GPIO_PIN15) +#define GPIO_U1C0_SELO3 (GPIO_OUTPUT_ALT2 | GPIO_PORT3 | GPIO_PIN14) +#define GPIO_U1C1_DOUT0_1 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT3 | GPIO_PIN15) +#define GPIO_U1C1_DOUT0_2 (GPIO_OUTPUT_ALT2 | GPIO_PORT0 | GPIO_PIN1) +#define GPIO_U1C1_DOUT0_3 (GPIO_OUTPUT_ALT2 | GPIO_PORT3 | GPIO_PIN15) +#define GPIO_U1C1_DOUT0_4 (GPIO_OUTPUT_ALT2 | GPIO_PORT4 | GPIO_PIN2) +#define GPIO_U1C1_DOUT1 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT3 | GPIO_PIN14) +#define GPIO_U1C1_DOUT2 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT0 | GPIO_PIN15) +#define GPIO_U1C1_DOUT3 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT0 | GPIO_PIN14) +#define GPIO_U1C1_DX0A (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN15) +#define GPIO_U1C1_DX0B (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN14) +#define GPIO_U1C1_DX0C (GPIO_INPUT | GPIO_PORT4 | GPIO_PIN2) +#define GPIO_U1C1_DX0D (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN0) +#define GPIO_U1C1_DX1A (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN10) +#define GPIO_U1C1_DX1B (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN13) +#define GPIO_U1C1_DX1C (GPIO_INPUT | GPIO_PORT4 | GPIO_PIN0) +#define GPIO_U1C1_DX2A (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN9) +#define GPIO_U1C1_DX2B (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN12) +#define GPIO_U1C1_HWIN0 (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT3 | GPIO_PIN15) +#define GPIO_U1C1_HWIN1 (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT3 | GPIO_PIN14) +#define GPIO_U1C1_HWIN2 (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT0 | GPIO_PIN15) +#define GPIO_U1C1_HWIN3 (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT0 | GPIO_PIN14) +#define GPIO_U1C1_SCLKOUT_1 (GPIO_OUTPUT_ALT2 | GPIO_PORT0 | GPIO_PIN10) +#define GPIO_U1C1_SCLKOUT_2 (GPIO_OUTPUT_ALT2 | GPIO_PORT0 | GPIO_PIN13) +#define GPIO_U1C1_SELO0_1 (GPIO_OUTPUT_ALT2 | GPIO_PORT0 | GPIO_PIN12) +#define GPIO_U1C1_SELO0_2 (GPIO_OUTPUT_ALT2 | GPIO_PORT0 | GPIO_PIN9) +#define GPIO_U1C1_SELO1_1 (GPIO_OUTPUT_ALT2 | GPIO_PORT0 | GPIO_PIN2) +#define GPIO_U1C1_SELO1_2 (GPIO_OUTPUT_ALT2 | GPIO_PORT3 | GPIO_PIN3) +#define GPIO_U1C1_SELO2 (GPIO_OUTPUT_ALT2 | GPIO_PORT3 | GPIO_PIN4) +#define GPIO_U1C1_SELO3 (GPIO_OUTPUT_ALT2 | GPIO_PORT3 | GPIO_PIN5) +#define GPIO_U1C1_SELO4 (GPIO_OUTPUT_ALT2 | GPIO_PORT3 | GPIO_PIN6) +#define GPIO_U2C0_DOUT0_1 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT5 | GPIO_PIN0) +#define GPIO_U2C0_DOUT0_2 (GPIO_OUTPUT_ALT1 | GPIO_PORT3 | GPIO_PIN8) +#define GPIO_U2C0_DOUT0_3 (GPIO_OUTPUT_ALT1 | GPIO_PORT5 | GPIO_PIN0) +#define GPIO_U2C0_DOUT1 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT5 | GPIO_PIN1) +#define GPIO_U2C0_DOUT2 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT5 | GPIO_PIN7) +#define GPIO_U2C0_DOUT3 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT2 | GPIO_PIN6) +#define GPIO_U2C0_DX0A (GPIO_INPUT | GPIO_PORT5 | GPIO_PIN1) +#define GPIO_U2C0_DX0B (GPIO_INPUT | GPIO_PORT5 | GPIO_PIN0) +#define GPIO_U2C0_DX0C (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN7) +#define GPIO_U2C0_DX1A (GPIO_INPUT | GPIO_PORT5 | GPIO_PIN2) +#define GPIO_U2C0_DX2A (GPIO_INPUT | GPIO_PORT5 | GPIO_PIN3) +#define GPIO_U2C0_HWIN0 (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT5 | GPIO_PIN0) +#define GPIO_U2C0_HWIN1 (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT5 | GPIO_PIN1) +#define GPIO_U2C0_HWIN2 (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT5 | GPIO_PIN7) +#define GPIO_U2C0_HWIN3 (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT2 | GPIO_PIN6) +#define GPIO_U2C0_SCLKOUT_1 (GPIO_OUTPUT_ALT1 | GPIO_PORT3 | GPIO_PIN9) +#define GPIO_U2C0_SCLKOUT_2 (GPIO_OUTPUT_ALT1 | GPIO_PORT5 | GPIO_PIN2) +#define GPIO_U2C0_SELO0_1 (GPIO_OUTPUT_ALT1 | GPIO_PORT3 | GPIO_PIN10) +#define GPIO_U2C0_SELO0_2 (GPIO_OUTPUT_ALT1 | GPIO_PORT5 | GPIO_PIN3) +#define GPIO_U2C0_SELO1 (GPIO_OUTPUT_ALT1 | GPIO_PORT5 | GPIO_PIN4) +#define GPIO_U2C0_SELO2 (GPIO_OUTPUT_ALT1 | GPIO_PORT5 | GPIO_PIN5) +#define GPIO_U2C0_SELO3 (GPIO_OUTPUT_ALT1 | GPIO_PORT5 | GPIO_PIN6) +#define GPIO_U2C0_SELO4 (GPIO_OUTPUT_ALT1 | GPIO_PORT2 | GPIO_PIN6) +#define GPIO_U2C1_DOUT0_1 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT4 | GPIO_PIN7) +#define GPIO_U2C1_DOUT0_2 (GPIO_OUTPUT_ALT1 | GPIO_PORT3 | GPIO_PIN11) +#define GPIO_U2C1_DOUT0_3 (GPIO_OUTPUT_ALT1 | GPIO_PORT3 | GPIO_PIN5) +#define GPIO_U2C1_DOUT1 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT4 | GPIO_PIN6) +#define GPIO_U2C1_DOUT2 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT4 | GPIO_PIN5) +#define GPIO_U2C1_DOUT3 (GPIO_OUTPUT | GPIO_PINCTRL_HW0 | GPIO_PORT4 | GPIO_PIN4) +#define GPIO_U2C1_DX0A (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN5) +#define GPIO_U2C1_DX0B (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN4) +#define GPIO_U2C1_DX0C (GPIO_INPUT | GPIO_PORT4 | GPIO_PIN0) +#define GPIO_U2C1_DX0D (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN12) +#define GPIO_U2C1_DX1A (GPIO_INPUT | GPIO_PORT4 | GPIO_PIN2) +#define GPIO_U2C1_DX1B (GPIO_INPUT | GPIO_PORT3 | GPIO_PIN6) +#define GPIO_U2C1_DX2A (GPIO_INPUT | GPIO_PORT4 | GPIO_PIN1) +#define GPIO_U2C1_DX2B (GPIO_INPUT | GPIO_PORT4 | GPIO_PIN1) +#define GPIO_U2C1_HWIN0 (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT4 | GPIO_PIN7) +#define GPIO_U2C1_HWIN1 (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT4 | GPIO_PIN6) +#define GPIO_U2C1_HWIN2 (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT4 | GPIO_PIN5) +#define GPIO_U2C1_HWIN3 (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT4 | GPIO_PIN4) +#define GPIO_U2C1_MCLKOUT (GPIO_OUTPUT_ALT1 | GPIO_PORT3 | GPIO_PIN4) +#define GPIO_U2C1_SCLKOUT_1 (GPIO_OUTPUT_ALT1 | GPIO_PORT3 | GPIO_PIN13) +#define GPIO_U2C1_SCLKOUT_1 (GPIO_OUTPUT_ALT1 | GPIO_PORT3 | GPIO_PIN6) +#define GPIO_U2C1_SCLKOUT_1 (GPIO_OUTPUT_ALT4 | GPIO_PORT4 | GPIO_PIN2) +#define GPIO_U2C1_SELO0_1 (GPIO_OUTPUT_ALT1 | GPIO_PORT3 | GPIO_PIN0) +#define GPIO_U2C1_SELO0_2 (GPIO_OUTPUT_ALT1 | GPIO_PORT4 | GPIO_PIN1) +#define GPIO_U2C1_SELO1 (GPIO_OUTPUT_ALT1 | GPIO_PORT4 | GPIO_PIN2) +#define GPIO_U2C1_SELO2 (GPIO_OUTPUT_ALT1 | GPIO_PORT4 | GPIO_PIN3) + +#define GPIO_USB_DRIVEVBUS_1 (GPIO_OUTPUT_ALT1 | GPIO_PORT0 | GPIO_PIN1) +#define GPIO_USB_DRIVEVBUS_2 (GPIO_OUTPUT_ALT1 | GPIO_PORT3 | GPIO_PIN2) +#define GPIO_USB_ID (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN9) + +#define GPIO_VADC_EMUX00 (GPIO_OUTPUT_ALT1 | GPIO_PORT2 | GPIO_PIN2) +#define GPIO_VADC_EMUX01 (GPIO_OUTPUT_ALT1 | GPIO_PORT2 | GPIO_PIN3) +#define GPIO_VADC_EMUX02 (GPIO_OUTPUT_ALT1 | GPIO_PORT2 | GPIO_PIN4) +#define GPIO_VADC_EMUX10 (GPIO_OUTPUT_ALT1 | GPIO_PORT2 | GPIO_PIN10) +#define GPIO_VADC_EMUX11 (GPIO_OUTPUT_ALT1 | GPIO_PORT2 | GPIO_PIN14) +#define GPIO_VADC_EMUX12 (GPIO_OUTPUT_ALT1 | GPIO_PORT2 | GPIO_PIN15) +#define GPIO_VADC_G0CH0 (GPIO_INPUT | GPIO_PORT14 | GPIO_PIN0) +#define GPIO_VADC_G0CH1 (GPIO_INPUT | GPIO_PORT14 | GPIO_PIN1) +#define GPIO_VADC_G0CH2 (GPIO_INPUT | GPIO_PORT14 | GPIO_PIN2) +#define GPIO_VADC_G0CH3 (GPIO_INPUT | GPIO_PORT14 | GPIO_PIN3) +#define GPIO_VADC_G0CH4 (GPIO_INPUT | GPIO_PORT14 | GPIO_PIN4) +#define GPIO_VADC_G0CH5 (GPIO_INPUT | GPIO_PORT14 | GPIO_PIN5) +#define GPIO_VADC_G0CH6 (GPIO_INPUT | GPIO_PORT14 | GPIO_PIN6) +#define GPIO_VADC_G0CH7 (GPIO_INPUT | GPIO_PORT14 | GPIO_PIN7) +#define GPIO_VADC_G1CH0 (GPIO_INPUT | GPIO_PORT14 | GPIO_PIN8) +#define GPIO_VADC_G1CH1 (GPIO_INPUT | GPIO_PORT14 | GPIO_PIN9) +#define GPIO_VADC_G1CH2 (GPIO_INPUT | GPIO_PORT14 | GPIO_PIN2) +#define GPIO_VADC_G1CH3 (GPIO_INPUT | GPIO_PORT14 | GPIO_PIN3) +#define GPIO_VADC_G1CH4 (GPIO_INPUT | GPIO_PORT14 | GPIO_PIN12) +#define GPIO_VADC_G1CH5 (GPIO_INPUT | GPIO_PORT14 | GPIO_PIN13) +#define GPIO_VADC_G1CH6 (GPIO_INPUT | GPIO_PORT14 | GPIO_PIN14) +#define GPIO_VADC_G1CH7 (GPIO_INPUT | GPIO_PORT14 | GPIO_PIN15) +#define GPIO_VADC_G2CH0 (GPIO_INPUT | GPIO_PORT14 | GPIO_PIN4) +#define GPIO_VADC_G2CH1 (GPIO_INPUT | GPIO_PORT14 | GPIO_PIN5) +#define GPIO_VADC_G2CH2 (GPIO_INPUT | GPIO_PORT15 | GPIO_PIN2) +#define GPIO_VADC_G2CH3 (GPIO_INPUT | GPIO_PORT15 | GPIO_PIN3) +#define GPIO_VADC_G2CH4 (GPIO_INPUT | GPIO_PORT15 | GPIO_PIN4) +#define GPIO_VADC_G2CH5 (GPIO_INPUT | GPIO_PORT15 | GPIO_PIN5) +#define GPIO_VADC_G2CH6 (GPIO_INPUT | GPIO_PORT15 | GPIO_PIN6) +#define GPIO_VADC_G2CH7 (GPIO_INPUT | GPIO_PORT15 | GPIO_PIN7) +#define GPIO_VADC_G3CH0 (GPIO_INPUT | GPIO_PORT15 | GPIO_PIN8) +#define GPIO_VADC_G3CH1 (GPIO_INPUT | GPIO_PORT15 | GPIO_PIN9) +#define GPIO_VADC_G3CH2 (GPIO_INPUT | GPIO_PORT14 | GPIO_PIN8) +#define GPIO_VADC_G3CH3 (GPIO_INPUT | GPIO_PORT14 | GPIO_PIN9) +#define GPIO_VADC_G3CH4 (GPIO_INPUT | GPIO_PORT15 | GPIO_PIN12) +#define GPIO_VADC_G3CH5 (GPIO_INPUT | GPIO_PORT15 | GPIO_PIN13) +#define GPIO_VADC_G3CH6 (GPIO_INPUT | GPIO_PORT15 | GPIO_PIN14) +#define GPIO_VADC_G3CH7 (GPIO_INPUT | GPIO_PORT15 | GPIO_PIN15) +#define GPIO_WWDT_SERVICEOUT_1 (GPIO_OUTPUT_ALT1 | GPIO_PORT0 | GPIO_PIN7) +#define GPIO_WWDT_SERVICEOUT_2 (GPIO_OUTPUT_ALT1 | GPIO_PORT1 | GPIO_PIN4) #endif /* __ARCH_ARM_SRC_XMC4_CHIP_XMC4_PINMXU_H */ diff --git a/arch/arm/src/xmc4/xmc4_gpio.h b/arch/arm/src/xmc4/xmc4_gpio.h index 49b80ba196..4595fe6a79 100644 --- a/arch/arm/src/xmc4/xmc4_gpio.h +++ b/arch/arm/src/xmc4/xmc4_gpio.h @@ -65,7 +65,7 @@ /* See chip/xmc4_ports.h for the IOCR definitions */ /* Direct input */ -# define GPIO_INPUT_NOPULL (IOCR_INPUT_NOPULL << GPIO_PINTYPE_SHIFT) +# define GPIO_INPUT (IOCR_INPUT_NOPULL << GPIO_PINTYPE_SHIFT) # define GPIO_INPUT_PULLDOWN (IOCR_INPUT_PULLDOWN << GPIO_PINTYPE_SHIFT) # define GPIO_INPUT_PULLUP (IOCR_INPUT_PULLUP << GPIO_PINTYPE_SHIFT) # define GPIO_INPUT_CONT (IOCR_INPUT_CONT << GPIO_PINTYPE_SHIFT) -- GitLab From cfa75de85a92470926b40d73e9b3f0db3b2b0e0f Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 18 Mar 2017 13:07:59 -0600 Subject: [PATCH 094/990] XMC4xxx: A few more SCU register definitions. --- arch/arm/src/xmc4/chip/xmc4_scu.h | 167 ++++++++++++++++++++++++++---- 1 file changed, 148 insertions(+), 19 deletions(-) diff --git a/arch/arm/src/xmc4/chip/xmc4_scu.h b/arch/arm/src/xmc4/chip/xmc4_scu.h index 7e706f501b..26862d8cba 100644 --- a/arch/arm/src/xmc4/chip/xmc4_scu.h +++ b/arch/arm/src/xmc4/chip/xmc4_scu.h @@ -344,32 +344,161 @@ /* General SCU Registers */ -/* Module Identification Register */ -#define SCU_ID_ -/* Chip ID */ -#define SCU_IDCHIP_ +/* Module Identification Register (32-bit Chip ID) */ + +#define SCU_ID_MOD_REV_SHIFT (0) /* Bits 0-7: Module Revision Number */ +#define SCU_ID_MOD_REV_MASK (0xff << SCU_ID_MOD_REV_SHIFT) +#define SCU_ID_MOD_TYPE_SHIFT (8) /* Bits 8-15: Module Type */ +#define SCU_ID_MOD_TYPE_MASK (0xff << SCU_ID_MOD_REV_SHIFT) +#define SCU_ID_MOD_NUMBER_SHIFT (16) /* Bits 16-31: Module Number Value */ +#define SCU_ID_MOD_NUMBER_MASK (0xffff << SCU_ID_MOD_NUMBER_SHIFT) + +/* Chip ID (32-bit Chip ID) */ + /* Manufactory ID */ -#define SCU_IDMANUF_ + +#define SCU_IDMANUF_DEPT_SHIFT (0) /* Bits 0-4: Department Identification Number */ +#define SCU_IDMANUF_DEPT_MASK (31 << SCU_IDMANUF_MOD_DEPT_SHIFT) +#define SCU_IDMANUF_MANUF_SHIFT (5) /* Bits 5-15: Manufacturer Identification Number */ +#define SCU_IDMANUF_MANUF_MASK (0x7ff << SCU_IDMANUF_MOD_MANUF_SHIFT) + /* Start-up Control */ -#define SCU_STCON_ -/* General Purpose Register 0 */ -#define SCU_GPR0_ -/* General Purpose Register 1 */ -#define SCU_GPR1_ + +#define SCU_STCON_HWCON_SHIFT (0) /* Bits 0-1: HW Configuration */ +#define SCU_STCON_HWCON_MASK (3 << SCU_STCON_HWCON_SHIFT) +# define SCU_STCON_HWCON_JTAG (0 << SCU_STCON_HWCON_SHIFT) /* Normal mode, JTAG */ +# define SCU_STCON_HWCON_ACBSL (1 << SCU_STCON_HWCON_SHIFT) /* ASC BSL enabled */ +# define SCU_STCON_HWCON_BMI (2 << SCU_STCON_HWCON_SHIFT) /* BMI customized boot enabled */ +# define SCU_STCON_HWCON_CANBSL (3 << SCU_STCON_HWCON_SHIFT) /* CAN BSL enabled */ +#define SCU_STCON_SWCON_SHIFT (8) /* Bits 8-11: SW Configuration */ +#define SCU_STCON_SWCON_MASK (15 << SCU_STCON_SWCON_SHIFT) +# define SCU_STCON_SWCON_ ROM (0 << SCU_STCON_SWCON_SHIFT) /* Normal boot from Boot ROM */ +# define SCU_STCON_SWCON_ASCBSL (1 << SCU_STCON_SWCON_SHIFT) /* ASC BSL enabled */ +# define SCU_STCON_SWCON_BMI (2 << SCU_STCON_SWCON_SHIFT) /* BMI customized boot enabled */ +# define SCU_STCON_SWCON_CANBSL (3 << SCU_STCON_SWCON_SHIFT) /* CAN BSL enabled */ +# define SCU_STCON_SWCON_SRAM (4 << SCU_STCON_SWCON_SHIFT) /* Boot from Code SRAM */ +# define SCU_STCON_SWCON_FLASH0 (8 << SCU_STCON_SWCON_SHIFT) /* Boot from alternate Flash Address 0 */ +# define SCU_STCON_SWCON_FLASH1 (12 << SCU_STCON_SWCON_SHIFT) /* Boot from alternate Flash Address 1 */ +# define SCU_STCON_SWCON_ABM (15 << SCU_STCON_SWCON_SHIFT) /* Enable fallback Alternate Boot Mode (ABM) */ + +/* General Purpose Register 0 and General Purpose Register 1 (32-bit data) */ + /* Ethernet 0 Port Control */ -#define SCU_ETH0CON_ + +#define SCU_ETH0CON_RXD0_SHIFT (0) /* Bits 0-1: MAC Receive Input 0 */ +#define SCU_ETH0CON_RXD0_MASK (3 << SCU_ETH0CON_RXD0_SHIFT) +# define SCU_ETH0CON_RXD0A (0 << SCU_ETH0CON_RXD0_SHIFT) /* Data input RXD0A is selected */ +# define SCU_ETH0CON_RXD0B (1 << SCU_ETH0CON_RXD0_SHIFT) /* Data input RXD0B is selected */ +# define SCU_ETH0CON_RXD0C (2 << SCU_ETH0CON_RXD0_SHIFT) /* Data input RXD0C is selected */ +# define SCU_ETH0CON_RXD0D (3 << SCU_ETH0CON_RXD0_SHIFT) /* Data input RXD0D is selected */ +#define SCU_ETH0CON_RXD1_SHIFT (2) /* Bits 2-3: MAC Receive Input 1 */ +#define SCU_ETH0CON_RXD1_MASK (3 << SCU_ETH0CON_RXD1_SHIFT) +# define SCU_ETH0CON_RXD1A (0 << SCU_ETH0CON_RXD1_SHIFT) /* Data input RXD1A is selected */ +# define SCU_ETH0CON_RXD1B (1 << SCU_ETH0CON_RXD1_SHIFT) /* Data input RXD1B is selected */ +# define SCU_ETH0CON_RXD1C (2 << SCU_ETH0CON_RXD1_SHIFT) /* Data input RXD1C is selected */ +# define SCU_ETH0CON_RXD1D (3 << SCU_ETH0CON_RXD1_SHIFT) /* Data input RXD1D is selected */ +#define SCU_ETH0CON_RXD2_SHIFT (4) /* Bits 4-5: MAC Receive Input 2 */ +#define SCU_ETH0CON_RXD2_MASK (3 << SCU_ETH0CON_RXD2_SHIFT) +# define SCU_ETH0CON_RXD2A (0 << SCU_ETH0CON_RXD2_SHIFT) /* Data input RXD2A is selected */ +# define SCU_ETH0CON_RXD2B (1 << SCU_ETH0CON_RXD2_SHIFT) /* Data input RXD2B is selected */ +# define SCU_ETH0CON_RXD2C (2 << SCU_ETH0CON_RXD2_SHIFT) /* Data input RXD2C is selected */ +# define SCU_ETH0CON_RXD2D (3 << SCU_ETH0CON_RXD2_SHIFT) /* Data input RXD2D is selected */ +#define SCU_ETH0CON_RXD3_SHIFT (6) /* Bits 6-7: MAC Receive Input 3 */ +#define SCU_ETH0CON_RXD3_MASK (3 << SCU_ETH0CON_RXD3_SHIFT) +# define SCU_ETH0CON_RXD3A (0 << SCU_ETH0CON_RXD3_SHIFT) /* Data input RXD3A is selected */ +# define SCU_ETH0CON_RXD3B (1 << SCU_ETH0CON_RXD3_SHIFT) /* Data input RXD3B is selected */ +# define SCU_ETH0CON_RXD3C (2 << SCU_ETH0CON_RXD3_SHIFT) /* Data input RXD3C is selected */ +# define SCU_ETH0CON_RXD3D (3 << SCU_ETH0CON_RXD3_SHIFT) /* Data input RXD3D is selected */ +#define SCU_ETH0CON_CLKRMII_SHIFT (8) /* Bits 8-9: RMII clock input */ +#define SCU_ETH0CON_CLKRMII_MASK (3 << SCU_ETH0CON_CLKRMII_SHIFT) +# define SCU_ETH0CON_CLKRMIIA (0 << SCU_ETH0CON_CLKRMII_SHIFT) /* Data input RMIIA is selected */ +# define SCU_ETH0CON_CLKRMIIB (1 << SCU_ETH0CON_CLKRMII_SHIFT) /* Data input RMIIB is selected */ +# define SCU_ETH0CON_CLKRMIIC (2 << SCU_ETH0CON_CLKRMII_SHIFT) /* Data input RMIIC is selected */ +# define SCU_ETH0CON_CLKRMIID (3 << SCU_ETH0CON_CLKRMII_SHIFT) /* Data input RMIID is selected */ +#define SCU_ETH0CON_CRSDV_SHIFT (10) /* Bits 10-11: CRS_DV input */ +#define SCU_ETH0CON_CRSDV_MASK (3 << SCU_ETH0CON_CRSDV_SHIFT) +# define SCU_ETH0CON_CRSDVA (0 << SCU_ETH0CON_CRSDV_SHIFT) /* Data input CRS_DVA is selected */ +# define SCU_ETH0CON_CRSDVB (1 << SCU_ETH0CON_CRSDV_SHIFT) /* Data input CRS_DVB is selected */ +# define SCU_ETH0CON_CRSDVC (2 << SCU_ETH0CON_CRSDV_SHIFT) /* Data input CRS_DVC is selected */ +# define SCU_ETH0CON_CRSDVD (3 << SCU_ETH0CON_CRSDV_SHIFT) /* Data input CRS_DVD is selected */ +#define SCU_ETH0CON_CRS_SHIFT (12) /* Bits 12-13: CRS input */ +#define SCU_ETH0CON_CRS_MASK (3 << SCU_ETH0CON_CRS_SHIFT) +# define SCU_ETH0CON_CRSA (0 << SCU_ETH0CON_CRS_SHIFT) /* Data input CRSA is selected */ +# define SCU_ETH0CON_CRSB (1 << SCU_ETH0CON_CRS_SHIFT) /* Data input CRSB is selected */ +# define SCU_ETH0CON_CRSC (2 << SCU_ETH0CON_CRS_SHIFT) /* Data input CRSC is selected */ +# define SCU_ETH0CON_CRSD (3 << SCU_ETH0CON_CRS_SHIFT) /* Data input CRSD is selected */ +#define SCU_ETH0CON_RXER_SHIFT (14) /* Bits 14-15: RXER Input */ +#define SCU_ETH0CON_RXER_MASK (3 << SCU_ETH0CON_RXER_SHIFT) +# define SCU_ETH0CON_RXERA (0 << SCU_ETH0CON_RXER_SHIFT) /* Data input RXERA is selected */ +# define SCU_ETH0CON_RXERB (1 << SCU_ETH0CON_RXER_SHIFT) /* Data input RXERB is selected */ +# define SCU_ETH0CON_RXERC (2 << SCU_ETH0CON_RXER_SHIFT) /* Data input RXERC is selected */ +# define SCU_ETH0CON_RXERD (3 << SCU_ETH0CON_RXER_SHIFT) /* Data input RXERD is selected */ +#define SCU_ETH0CON_COL_SHIFT (16) /* Bits 16-17: COL input */ +#define SCU_ETH0CON_COL_MASK (3 << SCU_ETH0CON_COL_SHIFT) +# define SCU_ETH0CON_COLA (0 << SCU_ETH0CON_COL_SHIFT) /* Data input COLA is selected */ +# define SCU_ETH0CON_COLB (1 << SCU_ETH0CON_COL_SHIFT) /* Data input COLB is selected */ +# define SCU_ETH0CON_COLC (2 << SCU_ETH0CON_COL_SHIFT) /* Data input COLC is selected */ +# define SCU_ETH0CON_COLD (3 << SCU_ETH0CON_COL_SHIFT) /* Data input COLD is selected */ +#define SCU_ETH0CON_CLKTX_SHIFT (18) /* Bits 18-19: CLK_TX input */ +#define SCU_ETH0CON_CLKTX_MASK (3 << SCU_ETH0CON_CLKTX_SHIFT) +# define SCU_ETH0CON_CLKTXA (0 << SCU_ETH0CON_CLKTX_SHIFT) /* Data input CLK_TXA is selected */ +# define SCU_ETH0CON_CLKTXB (1 << SCU_ETH0CON_CLKTX_SHIFT) /* Data input CLK_TXB is selected */ +# define SCU_ETH0CON_CLKTXC (2 << SCU_ETH0CON_CLKTX_SHIFT) /* Data input CLK_TXC is selected */ +# define SCU_ETH0CON_CLKTXD (3 << SCU_ETH0CON_CLKTX_SHIFT) /* Data input CLK_TXD is selected */ +#define SCU_ETH0CON_MDIO_SHIFT (22) /* Bits 22-23: MDIO Input Select */ +#define SCU_ETH0CON_MDIO_MASK (3 << SCU_ETH0CON_MDIO_SHIFT) +# define SCU_ETH0CON_MDIOA (0 << SCU_ETH0CON_MDIO_SHIFT) /* Data input MDIOA is selected */ +# define SCU_ETH0CON_MDIOB (1 << SCU_ETH0CON_MDIO_SHIFT) /* Data input MDIOB is selected */ +# define SCU_ETH0CON_MDIOC (2 << SCU_ETH0CON_MDIO_SHIFT) /* Data input MDIOC is selected */ +# define SCU_ETH0CON_MDIOD (3 << SCU_ETH0CON_MDIO_SHIFT) /* Data input MDIOD is selected */ +#define SCU_ETH0CON_INFSEL (1 << 26) /* Bit 26: Ethernet MAC Interface Selection */ +# define SCU_ETH0CON_INFSEL_MII (0) /* 0=MII */ +# define SCU_ETH0CON_INFSEL_RMII (1 << 26) /* 1=RMII */ + /* CCUx Global Start Control Register */ -#define SCU_CCUCON_ + +#define SCU_CCUCON_GSC40 (1 << 0) /* Bit 0: Global Start Control CCU40 */ +#define SCU_CCUCON_GSC41 (1 << 1) /* Bit 1: Global Start Control CCU41 */ +#define SCU_CCUCON_GSC42 (1 << 2) /* Bit 2: Global Start Control CCU42 */ +#define SCU_CCUCON_GSC43 (1 << 3) /* Bit 3: Global Start Control CCU43 */ +#define SCU_CCUCON_GSC80 (1 << 8) /* Bit 8: Global Start Control CCU80 */ +#define SCU_CCUCON_GSC81 (1 << 9) /* Bit 9: Global Start Control CCU81 */ + /* DTS Control */ -#define SCU_DTSCON_ + +#define SCU_DTSCON_PWD (1 << 0) /* Bit 0: Sensor Power Down */ +#define SCU_DTSCON_START (1 << 1) /* Bit 1: Sensor Measurement Start */ +#define SCU_DTSCON_OFFSET_SHIFT (4) /* Bits 4-10: Offset Calibration Value */ +#define SCU_DTSCON_OFFSET_MASK (0x7f << SCU_DTSCON_OFFSET_SHIFT) +# define SCU_DTSCON_OFFSET(n) ((uint32_t)(n) << SCU_DTSCON_OFFSET_SHIFT) +#define SCU_DTSCON_GAIN_SHIFT (11) /* Bits 11-16: Gain Calibration Value */ +#define SCU_DTSCON_GAIN_MASK (0x3f << SCU_DTSCON_GAIN_SHIFT) +# define SCU_DTSCON_GAIN(n) ((uint32_t)(n) << SCU_DTSCON_GAIN_SHIFT) +#define SCU_DTSCON_REFTRIM_SHIFT (17) /* Bits 17-19: Reference Trim Calibration Value */ +#define SCU_DTSCON_REFTRIM_MASK (7 << SCU_DTSCON_REFTRIM_SHIFT) +# define SCU_DTSCON_REFTRIM(n) ((uint32_t)(n) << SCU_DTSCON_REFTRIM_SHIFT) +#define SCU_DTSCON_BGTRIM_SHIFT (20) /* Bits 20-23: Bandgap Trim Calibration Value */ +#define SCU_DTSCON_BGTRIM_MASK (15 << SCU_DTSCON_BGTRIM_SHIFT) +# define SCU_DTSCON_BGTRIM(n) ((uint32_t)(n) << SCU_DTSCON_BGTRIM_SHIFT) + /* DTS Status */ -#define SCU_DTSSTAT_ + +#define SCU_DTSSTAT_RESULT_SHIFT (0) /* Bits 0-9: Result of the DTS Measurement */ +#define SCU_DTSSTAT_RESULT_MASK (0x3ff << SCU_DTSSTAT_RESULT_SHIFT) +#define SCU_DTSSTAT_RDY (1 << 14) /* Bit 14: Sensor Ready Status */ +#define SCU_DTSSTAT_BUSY (1 << 15) /* Bit 15: Sensor Busy Status */ + /* SD-MMC Delay Control Register */ -#define SCU_SDMMCDEL_ -/* Out-Of-Range Comparator Enable Register 0 */ -#define SCU_G0ORCEN_ -/* Out-Of-Range Comparator Enable Register 1 */ -#define SCU_G1ORCEN_ + +#define SCU_SDMMCDEL_TAPEN (1 << 0) /* Bit 0: Enable delay on the CMD/DAT out lines */ +#define SCU_SDMMCDEL_TAPDEL_SHIFT (4) /* Bitx 4-7: Number of Delay Elements Select */ +#define SCU_SDMMCDEL_TAPDEL_MASK (15 << SCU_SDMMCDEL_TAPDEL_SHIFT) +# define SCU_SDMMCDEL_TAPDEL(n) ((uint32_t)((n)-1) << SCU_SDMMCDEL_TAPDEL_SHIFT) + +/* Out-Of-Range Comparator Enable Register 0 and Out-Of-Range Comparator Enable Register 1 */ + +#define SCU_GORCEN_ENORC6 (1 << 6) /* Bit 6: Enable Out of Range Comparator, Channel 6 */ +#define SCU_GORCEN_ENORC7 (1 << 7) /* Bit 7: Enable Out of Range Comparator, Channel 7 */ /* Mirror Update Status Register */ -- GitLab From 7706810fc021b91678af2326a63872a06b29ae60 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 18 Mar 2017 14:08:35 -0600 Subject: [PATCH 095/990] XMC4xxx: A few more SCU register definitions. --- arch/arm/src/xmc4/chip/xmc4_scu.h | 133 +++++++++++++++++++++--------- 1 file changed, 94 insertions(+), 39 deletions(-) diff --git a/arch/arm/src/xmc4/chip/xmc4_scu.h b/arch/arm/src/xmc4/chip/xmc4_scu.h index 26862d8cba..7e8b10bc7b 100644 --- a/arch/arm/src/xmc4/chip/xmc4_scu.h +++ b/arch/arm/src/xmc4/chip/xmc4_scu.h @@ -537,10 +537,13 @@ /* Enable Promoting Events to NMI Request */ #define SCU_NMIREQEN_ /* Retention Memory Access Control Register */ -#define SCU_RMACR_ -/* Retention Memory Access Data Register */ -#define SCU_RMADATA_ -/* Parity Error Enable Register */ + +#define SCU_RMACR_RDWR (1 << 0) /* Bit 0: Hibernate Retention Memory Register Update Control */ +#define SCU_RMACR_ADDR_SHIFT (16) /* Bits 16-19: Hibernate Retention Memory Register Address Select */ +#define SCU_RMACR_ADDR_MASK (15 << SCU_RMACR_ADDR_SHIFT) +# define SCU_RMACR_ADDR(n) ((uint32_t)(n) << SCU_RMACR_ADDR_SHIFT) + +/* Retention Memory Access Data Register (32-bit data) */ /* SDMMC Control SCU Registers */ @@ -715,39 +718,62 @@ #define SCU_RSTCLR_HIBRS (1 << 9) /* Bit 9: Clear Hibernate Reset */ #define SCU_RSTCLR_LCKEN (1 << 10) /* Bit 10: Clear Hibernate Reset */ -/* Peripheral Reset Status Register 0 */ -#define SCU_PRSTAT0_ -/* Peripheral Reset Set Register 0 */ -#define SCU_PRSET0_ -/* Peripheral Reset Clear Register 0 */ -#define SCU_PRCLR0_ -/* Peripheral Reset Status Register 1 */ -#define SCU_PRSTAT1_ -/* Peripheral Reset Set Register 1 */ -#define SCU_PRSET1_ -/* Peripheral Reset Clear Register 1 */ -#define SCU_PRCLR1_ -/* Peripheral Reset Status Register 2 */ -#define SCU_PRSTAT2_ -/* Peripheral Reset Set Register 2 */ -#define SCU_PRSET2_ -/* Peripheral Reset Clear Register 2 */ -#define SCU_PRCLR2_ -/* Peripheral Reset Status Register 3 */ -#define SCU_PRSTAT3_ -/* Peripheral Reset Set Register 3 */ -#define SCU_PRSET3_ -/* Peripheral Reset Clear Register 3 */ -#define SCU_PRCLR3_ +/* Peripheral Reset Status Register 0, Peripheral Reset Set Register 0, Peripheral + * Reset Clear Register 0 + */ + +#define SCU_PR0_VADCRS (1 << 0) /* Bit 0: VADC Reset */ +#define SCU_PR0_DSDRS (1 << 1) /* Bit 1: DSD Reset */ +#define SCU_PR0_CCU40RS (1 << 2) /* Bit 2: CCU40 Reset */ +#define SCU_PR0_CCU41RS (1 << 3) /* Bit 3: CCU41 Reset */ +#define SCU_PR0_CCU42RS (1 << 4) /* Bit 4: CCU42 Reset */ +#define SCU_PR0_CCU80RS (1 << 7) /* Bit 7: CCU80 Reset */ +#define SCU_PR0_CCU81RS (1 << 8) /* Bit 8: CCU81 Reset */ +#define SCU_PR0_POSIF0RS (1 << 9) /* Bit 9: POSIF0 Reset */ +#define SCU_PR0_POSIF1RS (1 << 10) /* Bit 10: POSIF1 Reset */ +#define SCU_PR0_USIC0RS (1 << 11) /* Bit 11: USIC0 Reset */ +#define SCU_PR0_ERU1RS (1 << 16) /* Bit 16: ERU1 Reset */ + +/* Peripheral Reset Status Register 1, Peripheral Reset Set Register 1, Peripheral + * Reset Clear Register 1 + */ + +#define SCU_PR1_CCU43RS (1 << 0) /* Bit 0: CCU43 Reset */ +#define SCU_PR1_LEDTSCU0RS (1 << 3) /* Bit 3: LEDTS Reset */ +#define SCU_PR1_MCAN0RS (1 << 4) /* Bit 4: MultiCAN Reset */ +#define SCU_PR1_DACRS (1 << 5) /* Bit 5: DAC Reset */ +#define SCU_PR1_MMCIRS (1 << 6) /* Bit 6: MMC Interface Reset */ +#define SCU_PR1_USIC1RS (1 << 7) /* Bit 7: USIC1 Reset */ +#define SCU_PR1_USIC2RS (1 << 8) /* Bit 8: USIC2 Reset */ +#define SCU_PR1_PPORTSRS (1 << 9) /* Bit 9: PORTS Reset */ + +/* Peripheral Reset Status Register 1, Peripheral Reset Set Register 1, Peripheral + * Reset Clear Register 1 + */ + +#define SCU_PR2_WDTRS (1 << 1) /* Bit 1: WDT Reset */ +#define SCU_PR2_ETH0RS (1 << 2) /* Bit 2: ETH0 Reset */ +#define SCU_PR2_DMA0RS (1 << 4) /* Bit 4: DMA0 Reset */ +#define SCU_PR2_DMA1RS (1 << 5) /* Bit 5: DMA1 Reset */ +#define SCU_PR2_FCERS (1 << 6) /* Bit 6: FCE Reset */ +#define SCU_PR2_USBRS (1 << 7) /* Bit 7: USB Reset */ + +/* Peripheral Reset Status Register 3, Peripheral Reset Set Register 3, Peripheral + * Reset Clear Register 3 + */ + +#define SCU_PR3_EBURS (1 << 2) /* Bit 2: EBU Reset */ /* Clock Control SCU Registers */ -/* Clock Status Register */ -#define SCU_CLKSTAT_ -/* Clock Set Control Register */ -#define SCU_CLKSET_ -/* Clock clear Control Register */ -#define SCU_CLKCLR_ +/* Clock Status Register, Clock Set Control Register, Clock clear Control Register */ + +#define SCU_CLK_USBC (1 << 0) /* Bit 0: USB Clock */ +#define SCU_CLK_MMCC (1 << 1) /* Bit 1: MMC Clock */ +#define SCU_CLK_ETH0C (1 << 2) /* Bit 2: Ethernet Clock */ +#define SCU_CLK_EBUC (1 << 3) /* Bit 3: EBU Clock */ +#define SCU_CLK_CCUC (1 << 4) /* Bit 4: CCU Clock */ +#define SCU_CLK_WDTC (1 << 5) /* Bit 5: WDT Clock */ /* System Clock Control */ @@ -764,7 +790,10 @@ #define SCU_CPUCLKCR_CPUDIV (1 << 0) /* Bit 0: CPU Clock Divider Enable */ /* Peripheral Bus Clock Control */ -#define SCU_PBCLKCR_ + +#define SCU_PBCLKCR_PBDIV_Pos (1 << 0) /* Bit 0: PB Clock Divider Enable */ +# define SCU_PBCLKCR_PBDIV_FCPU (0) /* 0=fCPU */ +# define SCU_PBCLKCR_PBDIV_DIV2 ((1 << 0) /* 1=fCPU/2 */ /* USB Clock Control */ @@ -776,13 +805,39 @@ # define SCU_USBCLKCR_USBSEL_PLL (1 << 16) /* 1= PLL Clock */ /* EBU Clock Control */ -#define SCU_EBUCLKCR_ + +#define SCU_EBUCLKCR_EBUDIV_SHIFT (0) /* Bitx 0-5: EBU Clock Divider Value */ +#define SCU_EBUCLKCR_EBUDIV_MASK (0x3f << SCU_EBUCLKCR_EBUDIV_SHIFT) +# define SCU_EBUCLKCR_EBUDIV(n) ((uint32_t)((n)-1) << SCU_EBUCLKCR_EBUDIV_SHIFT) + /* CCU Clock Control */ -#define SCU_CCUCLKCR_ + +#define SCU_CCUCLKCR_CCUDIV_Pos (1 << 0) /* Bit 0: CCU Clock Divider Enable */ +# define SCU_CCUCLKCR_CCUDIV_FSYS (0) /* 0= SYS */ +# define SCU_CCUCLKCR_CCUDIV_DIV2 (1 << 0) /* 1=fSYS/2 */ + /* WDT Clock Control */ -#define SCU_WDTCLKCR_ + +#define SCU_WDTCLKCR_WDTDIV_SHIFT (0) /* Bits 0-7: WDT Clock Divider Value */ +#define SCU_WDTCLKCR_WDTDIV_MASK (0xff << SCU_WDTCLKCR_WDTDIV_SHIFT) +# define SCU_WDTCLKCR_WDTDIV(n) ((uint32_t)((n)-1) << SCU_WDTCLKCR_WDTDIV_SHIFT) +#define SCU_WDTCLKCR_WDTSEL_SHIFT (16) /* Bits 16-17: WDT Clock Selection Value */ +#define SCU_WDTCLKCR_WDTSEL_MASK (3 << SCU_WDTCLKCR_WDTSEL_SHIFT) +# define SCU_WDTCLKCR_WDTSEL_FOFI (0 << SCU_WDTCLKCR_WDTSEL_SHIFT) /* fOFI clock */ +# define SCU_WDTCLKCR_WDTSEL_FSTDY (1 << SCU_WDTCLKCR_WDTSEL_SHIFT) /* fSTDBY clock */ +# define SCU_WDTCLKCR_WDTSEL_FPLL (2 << SCU_WDTCLKCR_WDTSEL_SHIFT) /* fPLL clock */ + /* External clock Control Register */ -#define SCU_EXTCLKCR_ + +#define SCU_EXTCLKCR_ECKSEL_SHIFT (0) /* Bits 0-1: External Clock Selection Value */ +#define SCU_EXTCLKCR_ECKSEL_MASK (3 << SCU_EXTCLKCR_ECKSEL_SHIFT) +# define SCU_EXTCLKCR_ECKSEL_FSYS (0 << SCU_EXTCLKCR_ECKSEL_SHIFT) /* fSYS clock */ +# define SCU_EXTCLKCR_ECKSEL_FUSB (2 << SCU_EXTCLKCR_ECKSEL_SHIFT) /* fUSB clock divided by ECKDIV */ +# define SCU_EXTCLKCR_ECKSEL_FPLL (3 << SCU_EXTCLKCR_ECKSEL_SHIFT) /* fPLL clock divided by ECKDIV */ +#define SCU_EXTCLKCR_ECKDIV_SHIFT (16) /* Bits 16-24: External Clock Divider Value */ +#define SCU_EXTCLKCR_ECKDIV_MASK (0x1ff << SCU_EXTCLKCR_ECKDIV_SHIFT) +# define SCU_EXTCLKCR_ECKDIV(n) ((uint32_t)((n)-1) << SCU_EXTCLKCR_ECKDIV_SHIFT) + /* Sleep Control Register */ #define SCU_SLEEPCR_ /* Deep Sleep Control Register */ -- GitLab From 301e70b0731175caa03d2f22dda3fa1b6619de5e Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 18 Mar 2017 15:19:02 -0600 Subject: [PATCH 096/990] XMC4xxx: A few more SCU register definitions. --- arch/arm/src/xmc4/chip/xmc4_scu.h | 237 ++++++++++++++++++++++-------- 1 file changed, 178 insertions(+), 59 deletions(-) diff --git a/arch/arm/src/xmc4/chip/xmc4_scu.h b/arch/arm/src/xmc4/chip/xmc4_scu.h index 7e8b10bc7b..b48eebd824 100644 --- a/arch/arm/src/xmc4/chip/xmc4_scu.h +++ b/arch/arm/src/xmc4/chip/xmc4_scu.h @@ -538,10 +538,10 @@ #define SCU_NMIREQEN_ /* Retention Memory Access Control Register */ -#define SCU_RMACR_RDWR (1 << 0) /* Bit 0: Hibernate Retention Memory Register Update Control */ -#define SCU_RMACR_ADDR_SHIFT (16) /* Bits 16-19: Hibernate Retention Memory Register Address Select */ -#define SCU_RMACR_ADDR_MASK (15 << SCU_RMACR_ADDR_SHIFT) -# define SCU_RMACR_ADDR(n) ((uint32_t)(n) << SCU_RMACR_ADDR_SHIFT) +#define SCU_RMACR_RDWR (1 << 0) /* Bit 0: Hibernate Retention Memory Register Update Control */ +#define SCU_RMACR_ADDR_SHIFT (16) /* Bits 16-19: Hibernate Retention Memory Register Address Select */ +#define SCU_RMACR_ADDR_MASK (15 << SCU_RMACR_ADDR_SHIFT) +# define SCU_RMACR_ADDR(n) ((uint32_t)(n) << SCU_RMACR_ADDR_SHIFT) /* Retention Memory Access Data Register (32-bit data) */ @@ -552,19 +552,98 @@ /* Parity Control Registers */ -#define SCU_PEEN_ +/* Parity Error Enable Register */ + +#define SCU_PEEN_PEENPS (1 << 0) /* Bit 0: Parity Error Enable for PSRAM */ +#define SCU_PEEN_PEENDS1 (1 << 1) /* Bit 1: Parity Error Enable for DSRAM1 */ +#define SCU_PEEN_PEENDS2 (1 << 2) /* Bit 2: Parity Error Enable for DSRAM2 */ +#define SCU_PEEN_PEENU0 (1 << 8) /* Bit 8: Parity Error Enable for USIC0 Memory */ +#define SCU_PEEN_PEENU1 (1 << 9) /* Bit 9: Parity Error Enable for USIC1 Memory */ +#define SCU_PEEN_PEENU2 (1 << 10) /* Bit 10: Parity Error Enable for USIC2 Memory */ +#define SCU_PEEN_PEENMC (1 << 12) /* Bit 12: Parity Error Enable for MultiCAN Memory */ +#define SCU_PEEN_PEENPPRF (1 << 13) /* Bit 13: Parity Error Enable for PMU Prefetch Memory */ +#define SCU_PEEN_PEENUSB (1 << 16) /* Bit 16: Parity Error Enable for USB Memory */ +#define SCU_PEEN_PEENETH0TX (1 << 17) /* Bit 17: Parity Error Enable for ETH TX Memory */ +#define SCU_PEEN_PEENETH0RX (1 << 18) /* Bit 18: Parity Error Enable for ETH RX Memory */ +#define SCU_PEEN_PEENSD0 (1 << 19) /* Bit 19: Parity Error Enable for SDMMC Memory 0 */ +#define SCU_PEEN_PEENSD1 (1 << 20) /* Bit 20: Parity Error Enable for SDMMC Memory 1 */ + /* Memory Checking Control Register */ -#define SCU_MCHKCON_ + +#define SCU_MCHKCON_SELPS (1 << 0) /* Bit 0: Select Memory Check for PSRAM */ +#define SCU_MCHKCON_SELDS1 (1 << 1) /* Bit 1: Select Memory Check for DSRAM1 */ +#define SCU_MCHKCON_SELDS2 (1 << 2) /* Bit 2: Select Memory Check for DSRAM2 */ +#define SCU_MCHKCON_USIC0DRA (1 << 8) /* Bit 8: Select Memory Check for USIC0 */ +#define SCU_MCHKCON_USIC1DRA (1 << 9) /* Bit 9: Select Memory Check for USIC1 */ +#define SCU_MCHKCON_USIC2DRA (1 << 10) /* Bit 10: Select Memory Check for USIC2 */ +#define SCU_MCHKCON_MCANDRA (1 << 12) /* Bit 12: Select Memory Check for MultiCAN */ +#define SCU_MCHKCON_PPRFDRA (1 << 13) /* Bit 13: Select Memory Check for PMU */ +#define SCU_MCHKCON_SELUSB (1 << 16) /* Bit 16: Select Memory Check for USB SRAM */ +#define SCU_MCHKCON_SELETH0TX (1 << 17) /* Bit 17: Select Memory Check for ETH0 TX SRAM */ +#define SCU_MCHKCON_SELETH0RX (1 << 18) /* Bit 18: Select Memory Check for ETH0 RX SRAM */ +#define SCU_MCHKCON_SELSD0 (1 << 19) /* Bit 19: Select Memory Check for SDMMC SRAM 0 */ +#define SCU_MCHKCON_SELSD1 (1 << 20) /* Bit 20: Select Memory Check for SDMMC SRAM 1 */ + /* Parity Error Trap Enable Register */ -#define SCU_PETE_ + +#define SCU_PETE_PETEPS (1 << 0) /* Bit 0: Parity Error Trap Enable for PSRAM */ +#define SCU_PETE_PETEDS1 (1 << 1) /* Bit 1: Parity Error Trap Enable for DSRAM1 */ +#define SCU_PETE_PETEDS2 (1 << 2) /* Bit 2: Parity Error Trap Enable for DSRAM2 */ +#define SCU_PETE_PETEU0 (1 << 8) /* Bit 8: Parity Error Trap Enable for USIC0 Memory */ +#define SCU_PETE_PETEU1 (1 << 9) /* Bit 9: Parity Error Trap Enable for USIC1 Memory */ +#define SCU_PETE_PETEU2 (1 << 10) /* Bit 10: Parity Error Trap Enable for USIC2 Memory */ +#define SCU_PETE_PETEMC (1 << 12) /* Bit 12: Parity Error Trap Enable for MultiCAN Memory */ +#define SCU_PETE_PETEPPRF (1 << 13) /* Bit 13: Parity Error Trap Enable for PMU Prefetch Memory */ +#define SCU_PETE_PETEUSB (1 << 16) /* Bit 16: Parity Error Trap Enable for USB Memory */ +#define SCU_PETE_PETEETH0TX (1 << 17) /* Bit 17: Parity Error Trap Enable for ETH0 TX Memory */ +#define SCU_PETE_PETEETH0RX (1 << 18) /* Bit 18: Parity Error Trap Enable for ETH0 RX Memory */ +#define SCU_PETE_PETESD0 (1 << 19) /* Bit 19: Parity Error Trap Enable for SDMMC SRAM 0 Memory */ +#define SCU_PETE_PETESD1 (1 << 20) /* Bit 20: Parity Error Trap Enable for SDMMC SRAM 1 Memory */ + /* Reset upon Parity Error Enable Register */ -#define SCU_PERSTEN_ + +#define SCU_PERSTEN_RSEN (1 << 0) /* Bit 0: System Reset Enable upon Parity Error Trap */ + /* Parity Error Control Register */ -#define SCU_PEFLAG_ + +#define SCU_PEFLAG_PEFPS (1 << 0) /* Bit 0: Parity Error Flag for PSRAM */ +#define SCU_PEFLAG_PEFDS1 (1 << 1) /* Bit 1: Parity Error Flag for DSRAM1 */ +#define SCU_PEFLAG_PEFDS2 (1 << 2) /* Bit 2: Parity Error Flag for DSRAM2 */ +#define SCU_PEFLAG_PEFU0 (1 << 8) /* Bit 8: Parity Error Flag for USIC0 Memory */ +#define SCU_PEFLAG_PEFU1 (1 << 9) /* Bit 9: Parity Error Flag for USIC1 Memory */ +#define SCU_PEFLAG_PEFU2 (1 << 10) /* Bit 10: Parity Error Flag for USIC2 Memory */ +#define SCU_PEFLAG_PEFMC (1 << 12) /* Bit 12: Parity Error Flag for MultiCAN Memory */ +#define SCU_PEFLAG_PEFPPRF (1 << 13) /* Bit 13: Parity Error Flag for PMU Prefetch Memory */ +#define SCU_PEFLAG_PEUSB (1 << 16) /* Bit 16: Parity Error Flag for USB Memory */ +#define SCU_PEFLAG_PEETH0TX (1 << 17) /* Bit 17: Parity Error Flag for ETH TX Memory */ +#define SCU_PEFLAG_PEETH0RX (1 << 18) /* Bit 18: Parity Error Flag for ETH RX Memory */ +#define SCU_PEFLAG_PESD0 (1 << 19) /* Bit 19: Parity Error Flag for SDMMC Memory 0 */ +#define SCU_PEFLAG_PESD1 (1 << 20) /* Bit 20: Parity Error Flag for SDMMC Memory 1 */ + /* Parity Memory Test Pattern Register */ -#define SCU_PMTPR_ + +#define SCU_PMTPR_PWR_SHIFT (0) /* Bits 0-7: Parity Read Values for Memory Test */ +#define SCU_PMTPR_PWR_MASK (0xff << SCU_PMTPR_PWR_SHIFT) +# define SCU_PMTPR_PWR(n) ((uint32_t)(n) << SCU_PMTPR_PWR_SHIFT) +#define SCU_PMTPR_PRD_SHIFT (8) /* Bits 8-15: Parity Write Values for Memory Test */ +#define SCU_PMTPR_PRD_MASK (0xff << SCU_PMTPR_PRD_SHIFT) +# define SCU_PMTPR_PRD(n) ((uint32_t)(n) << SCU_PMTPR_PRD_SHIFT) + /* Parity Memory Test Select Register */ -#define SCU_PMTSR_ + +#define SCU_PMTSR_MTENPS (1 << 0) /* Bit 0: Test Enable Control for PSRAM */ +#define SCU_PMTSR_MTENDS1 (1 << 1) /* Bit 1: Test Enable Control for DSRAM1 */ +#define SCU_PMTSR_MTENDS2 (1 << 2) /* Bit 2: Test Enable Control for DSRAM2 */ +#define SCU_PMTSR_MTEU0 (1 << 8) /* Bit 8: Test Enable Control for USIC0 Memory */ +#define SCU_PMTSR_MTEU1 (1 << 9) /* Bit 9: Test Enable Control for USIC1 Memory */ +#define SCU_PMTSR_MTEU2 (1 << 10) /* Bit 10: Test Enable Control for USIC2 Memory */ +#define SCU_PMTSR_MTEMC (1 << 12) /* Bit 12: Test Enable Control for MultiCAN Memory */ +#define SCU_PMTSR_MTEPPRF (1 << 13) /* Bit 13: Test Enable Control for PMU Prefetch Memory */ +#define SCU_PMTSR_MTUSB (1 << 16) /* Bit 16: Test Enable Control for USB Memory */ +#define SCU_PMTSR_MTETH0TX (1 << 17) /* Bit 17: Test Enable Control for ETH TX Memory */ +#define SCU_PMTSR_MTETH0RX (1 << 18) /* Bit 18: Test Enable Control for ETH RX Memory */ +#define SCU_PMTSR_MTSD0 (1 << 19) /* Bit 19: Test Enable Control for SDMMC Memory 0 */ +#define SCU_PMTSR_MTSD1 (1 << 20) /* Bit 20: Test Enable Control for SDMMC Memory 1 */ /* Trap Control Registers */ @@ -791,7 +870,7 @@ /* Peripheral Bus Clock Control */ -#define SCU_PBCLKCR_PBDIV_Pos (1 << 0) /* Bit 0: PB Clock Divider Enable */ +#define SCU_PBCLKCR_PBDIV (1 << 0) /* Bit 0: PB Clock Divider Enable */ # define SCU_PBCLKCR_PBDIV_FCPU (0) /* 0=fCPU */ # define SCU_PBCLKCR_PBDIV_DIV2 ((1 << 0) /* 1=fCPU/2 */ @@ -812,65 +891,102 @@ /* CCU Clock Control */ -#define SCU_CCUCLKCR_CCUDIV_Pos (1 << 0) /* Bit 0: CCU Clock Divider Enable */ -# define SCU_CCUCLKCR_CCUDIV_FSYS (0) /* 0= SYS */ -# define SCU_CCUCLKCR_CCUDIV_DIV2 (1 << 0) /* 1=fSYS/2 */ +#define SCU_CCUCLKCR_CCUDIV (1 << 0) /* Bit 0: CCU Clock Divider Enable */ +# define SCU_CCUCLKCR_CCUDIV_FSYS (0) /* 0= SYS */ +# define SCU_CCUCLKCR_CCUDIV_DIV2 (1 << 0) /* 1=fSYS/2 */ /* WDT Clock Control */ -#define SCU_WDTCLKCR_WDTDIV_SHIFT (0) /* Bits 0-7: WDT Clock Divider Value */ -#define SCU_WDTCLKCR_WDTDIV_MASK (0xff << SCU_WDTCLKCR_WDTDIV_SHIFT) -# define SCU_WDTCLKCR_WDTDIV(n) ((uint32_t)((n)-1) << SCU_WDTCLKCR_WDTDIV_SHIFT) -#define SCU_WDTCLKCR_WDTSEL_SHIFT (16) /* Bits 16-17: WDT Clock Selection Value */ -#define SCU_WDTCLKCR_WDTSEL_MASK (3 << SCU_WDTCLKCR_WDTSEL_SHIFT) -# define SCU_WDTCLKCR_WDTSEL_FOFI (0 << SCU_WDTCLKCR_WDTSEL_SHIFT) /* fOFI clock */ -# define SCU_WDTCLKCR_WDTSEL_FSTDY (1 << SCU_WDTCLKCR_WDTSEL_SHIFT) /* fSTDBY clock */ -# define SCU_WDTCLKCR_WDTSEL_FPLL (2 << SCU_WDTCLKCR_WDTSEL_SHIFT) /* fPLL clock */ +#define SCU_WDTCLKCR_WDTDIV_SHIFT (0) /* Bits 0-7: WDT Clock Divider Value */ +#define SCU_WDTCLKCR_WDTDIV_MASK (0xff << SCU_WDTCLKCR_WDTDIV_SHIFT) +# define SCU_WDTCLKCR_WDTDIV(n) ((uint32_t)((n)-1) << SCU_WDTCLKCR_WDTDIV_SHIFT) +#define SCU_WDTCLKCR_WDTSEL_SHIFT (16) /* Bits 16-17: WDT Clock Selection Value */ +#define SCU_WDTCLKCR_WDTSEL_MASK (3 << SCU_WDTCLKCR_WDTSEL_SHIFT) +# define SCU_WDTCLKCR_WDTSEL_FOFI (0 << SCU_WDTCLKCR_WDTSEL_SHIFT) /* fOFI clock */ +# define SCU_WDTCLKCR_WDTSEL_FSTDY (1 << SCU_WDTCLKCR_WDTSEL_SHIFT) /* fSTDBY clock */ +# define SCU_WDTCLKCR_WDTSEL_FPLL (2 << SCU_WDTCLKCR_WDTSEL_SHIFT) /* fPLL clock */ /* External clock Control Register */ -#define SCU_EXTCLKCR_ECKSEL_SHIFT (0) /* Bits 0-1: External Clock Selection Value */ -#define SCU_EXTCLKCR_ECKSEL_MASK (3 << SCU_EXTCLKCR_ECKSEL_SHIFT) -# define SCU_EXTCLKCR_ECKSEL_FSYS (0 << SCU_EXTCLKCR_ECKSEL_SHIFT) /* fSYS clock */ -# define SCU_EXTCLKCR_ECKSEL_FUSB (2 << SCU_EXTCLKCR_ECKSEL_SHIFT) /* fUSB clock divided by ECKDIV */ -# define SCU_EXTCLKCR_ECKSEL_FPLL (3 << SCU_EXTCLKCR_ECKSEL_SHIFT) /* fPLL clock divided by ECKDIV */ -#define SCU_EXTCLKCR_ECKDIV_SHIFT (16) /* Bits 16-24: External Clock Divider Value */ -#define SCU_EXTCLKCR_ECKDIV_MASK (0x1ff << SCU_EXTCLKCR_ECKDIV_SHIFT) -# define SCU_EXTCLKCR_ECKDIV(n) ((uint32_t)((n)-1) << SCU_EXTCLKCR_ECKDIV_SHIFT) +#define SCU_EXTCLKCR_ECKSEL_SHIFT (0) /* Bits 0-1: External Clock Selection Value */ +#define SCU_EXTCLKCR_ECKSEL_MASK (3 << SCU_EXTCLKCR_ECKSEL_SHIFT) +# define SCU_EXTCLKCR_ECKSEL_FSYS (0 << SCU_EXTCLKCR_ECKSEL_SHIFT) /* fSYS clock */ +# define SCU_EXTCLKCR_ECKSEL_FUSB (2 << SCU_EXTCLKCR_ECKSEL_SHIFT) /* fUSB clock divided by ECKDIV */ +# define SCU_EXTCLKCR_ECKSEL_FPLL (3 << SCU_EXTCLKCR_ECKSEL_SHIFT) /* fPLL clock divided by ECKDIV */ +#define SCU_EXTCLKCR_ECKDIV_SHIFT (16) /* Bits 16-24: External Clock Divider Value */ +#define SCU_EXTCLKCR_ECKDIV_MASK (0x1ff << SCU_EXTCLKCR_ECKDIV_SHIFT) +# define SCU_EXTCLKCR_ECKDIV(n) ((uint32_t)((n)-1) << SCU_EXTCLKCR_ECKDIV_SHIFT) /* Sleep Control Register */ -#define SCU_SLEEPCR_ + +#define SCU_SLEEPCR_SYSSEL (1 << 0) /* Bit 0: System Clock Selection Value */ +# define SCU_SLEEPCR_SYSSEL_OFI (0) /* 0=fOFI */ +# define SCU_SLEEPCR_SYSSEL_ PLL (1 << 0) /* 1=fPLL */ +#define SCU_SLEEPCR_USBCR (1 << 16) /* Bit 6: USB Clock Control in Sleep Mode */ +#define SCU_SLEEPCR_MMCCR (1 << 17) /* Bit 17: MMC Clock Control in Sleep Mode */ +#define SCU_SLEEPCR_ETH0CR (1 << 18) /* Bit 18: Ethernet Clock Control in Sleep Mode */ +#define SCU_SLEEPCR_EBUCR (1 << 19) /* Bit 19: EBU Clock Control in Sleep Mode */ +#define SCU_SLEEPCR_CCUCR (1 << 20) /* Bit 20: CCU Clock Control in Sleep Mode */ +#define SCU_SLEEPCR_WDTCR (1 << 21) /* Bit 21: WDT Clock Control in Sleep Mode */ + /* Deep Sleep Control Register */ -#define SCU_DSLEEPCR_ -/* Peripheral 0 Clock Gating Status */ -#define SCU_CGATSTAT0_ -/* Peripheral 0 Clock Gating Set */ -#define SCU_CGATSET0_ -/* Peripheral 0 Clock Gating Clear */ -#define SCU_CGATCLR0_ -/* Peripheral 1 Clock Gating Status */ -#define SCU_CGATSTAT1_ -/* Peripheral 1 Clock Gating Set */ -#define SCU_CGATSET1_ -/* Peripheral 1 Clock Gating Clear */ -#define SCU_CGATCLR1_ -/* Peripheral 2 Clock Gating Status */ -#define SCU_CGATSTAT2_ -/* Peripheral 2 Clock Gating Set */ -#define SCU_CGATSET2_ -/* Peripheral 2 Clock Gating Clear */ -#define SCU_CGATCLR2_ -/* Peripheral 3 Clock Gating Status */ -#define SCU_CGATSTAT3_ -/* Peripheral 3 Clock Gating Set */ -#define SCU_CGATSET3_ -/* Peripheral 3 Clock Gating Clear */ -#define SCU_CGATCLR3_ + +#define SCU_DSLEEPCR_SYSSEL (1 << 0) /* Bit 0: System Clock Selection Value */ +# define SCU_DSLEEPCR_SYSSEL_FOFI (0) /* 0=fOFI */ +# define SCU_DSLEEPCR_SYSSEL_FPLL (1 << 0) /* 1=fPLL */ +#define SCU_DSLEEPCR_FPDN (1 << 11) /* Bit 11: Flash Power Down */ +#define SCU_DSLEEPCR_PLLPDN (1 << 12) /* Bit 12: PLL Power Down */ +#define SCU_DSLEEPCR_VCOPDN (1 << 13) /* Bit 13: PLL Power Down */ +#define SCU_DSLEEPCR_USBCR (1 << 16) /* Bit 16: USB Clock Control in Deep Sleep Mode */ +#define SCU_DSLEEPCR_MMCCR (1 << 17) /* Bit 17: MMC Clock Control in Deep Sleep Mode */ +#define SCU_DSLEEPCR_ETH0CR (1 << 18) /* Bit 18: Ethernet Clock Control in Deep Sleep Mode */ +#define SCU_DSLEEPCR_EBUCR (1 << 19) /* Bit 19: EBU Clock Control in Deep Sleep Mode */ +#define SCU_DSLEEPCR_CCUCR (1 << 20) /* Bit 20: CCU Clock Control in Deep Sleep Mod */ +#define SCU_DSLEEPCR_WDTCR (1 << 21) /* Bit 21: WDT Clock Control in Deep Sleep Mode */ + +/* Peripheral 0 Clock Gating Status, Peripheral 0 Clock Gating Set, Peripheral 0 Clock Gating Clear */ + +#define SCU_CGAT0_VADC (1 << 0) /* Bit 0: */ +#define SCU_CGAT0_DSD (1 << 1) /* Bit 1: */ +#define SCU_CGAT0_CCU40 (1 << 2) /* Bit 2: */ +#define SCU_CGAT0_CCU41 (1 << 3) /* Bit 3: */ +#define SCU_CGAT0_CCU42 (1 << 4) /* Bit 4: */ +#define SCU_CGAT0_CCU80 (1 << 7) /* Bit 7: */ +#define SCU_CGAT0_CCU81 (1 << 8) /* Bit 8: */ +#define SCU_CGAT0_POSIF0 (1 << 9) /* Bit 9: */ +#define SCU_CGAT0_POSIF1 (1 << 10) /* Bit 10: */ +#define SCU_CGAT0_USIC0 (1 << 11) /* Bit 11: */ +#define SCU_CGAT0_ERU1_ (1 << 16) /* Bit 16: */ + +/* Peripheral 1 Clock Gating Status, Peripheral 1 Clock Gating Set, Peripheral 1 Clock Gating Clear */ + +#define SCU_CGATSTAT1_CCU43 (1 << 0) /* Bit 0: */ +#define SCU_CGATSTAT1_LEDTSCU0 (1 << 3) /* Bit 3: */ +#define SCU_CGATSTAT1_MCAN0 (1 << 4) /* Bit 4: */ +#define SCU_CGATSTAT1_DAC (1 << 5) /* Bit 5: */ +#define SCU_CGATSTAT1_MMCI (1 << 6) /* Bit 6: */ +#define SCU_CGATSTAT1_USIC1 (1 << 7) /* Bit 7: */ +#define SCU_CGATSTAT1_USIC2 (1 << 8) /* Bit 8: */ +#define SCU_CGATSTAT1_PPORTS (1 << 9) /* Bit 9: */ + +/* Peripheral 2 Clock Gating Status, Peripheral 2 Clock Gating Set, Peripheral 2 Clock Gating Clear */ + +#define SCU_CGATSTAT2_WDT (1 << 1) /* Bit 1: */ +#define SCU_CGATSTAT2_ETH0 (1 << 2) /* Bit 2: */ +#define SCU_CGATSTAT2_DMA0 (1 << 4) /* Bit 4: */ +#define SCU_CGATSTAT2_DMA1 (1 << 5) /* Bit 5: */ +#define SCU_CGATSTAT2_FCE (1 << 6) /* Bit 6: */ +#define SCU_CGATSTAT2_USB (1 << 7) /* Bit 7: */ + +/* Peripheral 3 Clock Gating Status, Peripheral 3 Clock Gating Set, Peripheral 3 Clock Gating Clear */ + +#define SCU_CGATSTAT3_EBU (1 << 2) /* Bit 2: */ /* Oscillator Control SCU Registers */ /* OSC_HP Status Register */ -#define SCU_OSCHPSTAT_ + +#define SCU_OSCHPSTAT_X1D (1 << 0) /* Bit 0: XTAL1 Data Value */ /* OSC_HP Control Register */ @@ -890,7 +1006,10 @@ # define SCU_OSCHPCTRL_OSCVAL(n) ((uint32_t)((n)-1) << SCU_OSCHPCTRL_OSCVAL_SHIFT) /* Clock Calibration Constant Register */ -#define SCU_CLKCALCONST_ + +#define SCU_CLKCALCONST_CALIBCONST_SHIFT (0) /* Bits 0-3: Clock Calibration Constant Value */ +#define SCU_CLKCALCONST_CALIBCONST_MASK (15 << SCU_CLKCALCONST_CALIBCONST_SHIFT) +# define SCU_CLKCALCONST_CALIBCONST(n) ((uint32_t)(n) << SCU_CLKCALCONST_CALIBCONST_SHIFT) /* PLL Control SCU Registers */ -- GitLab From e82a3b3ca7f84b159c7daeb72d46e25e186aedbe Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 18 Mar 2017 16:13:59 -0600 Subject: [PATCH 097/990] XMC4xxx: Completes most SCU register definitions. --- arch/arm/src/xmc4/chip/xmc4_scu.h | 75 ++++++++++++++++++++++--------- 1 file changed, 55 insertions(+), 20 deletions(-) diff --git a/arch/arm/src/xmc4/chip/xmc4_scu.h b/arch/arm/src/xmc4/chip/xmc4_scu.h index b48eebd824..fee8e55b8f 100644 --- a/arch/arm/src/xmc4/chip/xmc4_scu.h +++ b/arch/arm/src/xmc4/chip/xmc4_scu.h @@ -318,11 +318,11 @@ #define XMC4_SCU_CGATSET1 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSET1_OFFSET) #define XMC4_SCU_CGATCLR1 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATCLR1_OFFSET) #define XMC4_SCU_CGATSTAT2 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSTAT2_OFFSET) -#define XMC4_SCU_CGATSET2 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSET2_OFFSET -#define XMC4_SCU_CGATCLR2 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATCLR2_OFFSET -#define XMC4_SCU_CGATSTAT3 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSTAT3_OFFSET -#define XMC4_SCU_CGATSET3 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSET3_OFFSET -#define XMC4_SCU_CGATCLR3 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATCLR3_OFFSET_ +#define XMC4_SCU_CGATSET2 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSET2_OFFSET) +#define XMC4_SCU_CGATCLR2 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATCLR2_OFFSET) +#define XMC4_SCU_CGATSTAT3 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSTAT3_OFFSET) +#define XMC4_SCU_CGATSET3 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSET3_OFFSET) +#define XMC4_SCU_CGATCLR3 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATCLR3_OFFSET) /* Oscillator Control SCU Registers */ @@ -524,18 +524,38 @@ /* Interrupt Control SCU Registers */ -/* Service Request Status */ -#define SCU_SRSTAT_ -/* RAW Service Request Status */ -#define SCU_SRRAW_ -/* Service Request Mask */ -#define SCU_SRMSK_ -/* Service Request Clear */ -#define SCU_SRCLR_ -/* Service Request Set */ -#define SCU_SRSET_ +/* Service Request Status, RAW Service Request Status, Service Request Mask, Service + * Request Clear, Service Request Set + */ + +#define SCU_INT_PRWARN (1 << 0) /* Bit 0: WDT pre-warning Interrupt */ +#define SCU_INT_PI (1 << 1) /* Bit 1: RTC Periodic Interrupt */ +#define SCU_INT_AI (1 << 2) /* Bit 2: Alarm Interrupt */ +#define SCU_INT_DLROVR (1 << 3) /* Bit 3: DLR Request Overrun Interrupt */ +#define SCU_INT_HDSTAT (1 << 16) /* Bit 16: HDSTAT Mirror Register Update */ +#define SCU_INT_HDCLR (1 << 17) /* Bit 17: HDCLR Mirror Register Update */ +#define SCU_INT_HDSET (1 << 18) /* Bit 18: HDSET Mirror Register Update */ +#define SCU_INT_HDCR (1 << 19) /* Bit 19: HDCR Mirror Register Update */ +#define SCU_INT_OSCSICTRL (1 << 21) /* Bit 21: OSCSICTRL Mirror Register Update */ +#define SCU_INT_OSCULSTAT (1 << 22) /* Bit 22: OSCULTAT Mirror Register Update */ +#define SCU_INT_OSCULCTRL (1 << 23) /* Bit 23: OSCULCTRL Mirror Register Update */ +#define SCU_INT_RTC_CTR (1 << 24) /* Bit 24: RTC CTR Mirror Register Update */ +#define SCU_INT_RTC_ATIM0 (1 << 25) /* Bit 25: RTC ATIM0 Mirror Register Update */ +#define SCU_INT_RTC_ATIM1 (1 << 26) /* Bit 26: RTC ATIM1 Mirror Register Update */ +#define SCU_INT_RTC_TIM0 (1 << 27) /* Bit 27: RTC TIM0 Mirror Register Update */ +#define SCU_INT_RTC_TIM1 (1 << 28) /* Bit 28: RTC TIM1 Mirror Register Update */ +#define SCU_INTT_RMX (1 << 29) /* Bit 29: Retention Memory Mirror Register */ + /* Enable Promoting Events to NMI Request */ -#define SCU_NMIREQEN_ + +#define SCU_NMIREQEN_PRWARN (1 << 0) /* Bit 0: Promote Pre-Warning Interrupt Request to NMI Request */ +#define SCU_NMIREQEN_PI (1 << 1) /* Bit 1: Promote RTC Periodic Interrupt request to NMI Request */ +#define SCU_NMIREQEN_AI (1 << 2) /* Bit 2: Promote RTC Alarm Interrupt Request to NMIRequest */ +#define SCU_NMIREQEN_ERU00 (1 << 16) /* Bit 16: Promote Channel 0 Interrupt of ERU0 Request to NMI Request */ +#define SCU_NMIREQEN_ERU01 (1 << 17) /* Bit 17: Promote Channel 1 Interrupt of ERU0 Request to NMI Request */ +#define SCU_NMIREQEN_ERU02 (1 << 18) /* Bit 18: Promote Channel 2 Interrupt of ERU0 Request to NMI Request */ +#define SCU_NMIREQEN_ERU03 (1 << 19) /* Bit 19: Promote Channel 3 Interrupt of ERU0 Request to NMI Request */ + /* Retention Memory Access Control Register */ #define SCU_RMACR_RDWR (1 << 0) /* Bit 0: Hibernate Retention Memory Register Update Control */ @@ -672,11 +692,25 @@ #define SCU_PWR_USBPUWQ (1 << 18) /* Bit 18: USB Weak Pull-Up at PADN State */ /* EVR Status Register */ -#define SCU_EVRSTAT_ + +#define SCU_EVRSTAT_OV13 (1 << 1) /* Bit 1: Regulator Overvoltage for 1.3 V */ + /* EVR VADC Status Register */ -#define SCU_EVRVADCSTAT_ + +#define SCU_EVRVADCSTAT_VADC13V_SHIFT (0) /* Bits 0-7: VADC 1.3 V Conversion Result */ +#define SCU_EVRVADCSTAT_VADC13V_MASK (0xff << SCU_EVRVADCSTAT_VADC13V_SHIFT) +#define SCU_EVRVADCSTAT_VADC33V_SHIFT (8) /* Bits 8-15: VADC 3.3 V Conversion Result */ +#define SCU_EVRVADCSTAT_VADC33V_MASK (0xff << SCU_EVRVADCSTAT_VADC33V_SHIFT) + /* Power Monitor Value */ -#define SCU_PWRMON_ + +#define SCU_PWRMON_THRS_SHIFT (0) /* Bits 0-7: Threshold */ +#define SCU_PWRMON_THRS_MASK (0xff << SCU_POWER_PWRMON_THRS_SHIFT) +# define SCU_PWRMON_THRS(n) ((uint32_t)(n) << SCU_POWER_PWRMON_THRS_SHIFT) +#define SCU_PWRMON_INTV_SHIFT (8) /* Bits 8-15: Interval */ +#define SCU_PWRMON_INTV_MASK (0xff << SCU_POWER_PWRMON_INTV_SHIFT) +# define SCU_PWRMON_INTV(n) ((uint32_t)(n) << SCU_POWER_PWRMON_INTV_SHIFT) +#define SCU_PWRMON_ENB (1 << 16) /* Bit 16: Enable */ /* Hibernation SCU Registers */ /* Hibernate Domain Status Register */ @@ -750,7 +784,8 @@ # define SCU_HDCR_HIBIO1SEL_ODGPIO (14 << SCU_HDCR_HIBIO1SEL_SHIFT) /* Open-drain GPIO output */ /* Internal 32.768 kHz Clock Source Control Register */ -#define SCU_OSCSICTRL_ + +#define SCU_OSCSICTRL_PWD (1 << 0) /* Bit 0: Turn OFF the fOSI Clock Source */ /* OSC_ULP Status Register */ -- GitLab From 47cd105e322040d20aafc1fd53b0803cf09141c5 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 18 Mar 2017 16:41:33 -0600 Subject: [PATCH 098/990] XMC4xxxx: Final clean-up of SCU heder file --- arch/arm/src/xmc4/chip/xmc4_scu.h | 401 ++++++++++++++---------------- 1 file changed, 190 insertions(+), 211 deletions(-) diff --git a/arch/arm/src/xmc4/chip/xmc4_scu.h b/arch/arm/src/xmc4/chip/xmc4_scu.h index fee8e55b8f..0618e7e02b 100644 --- a/arch/arm/src/xmc4/chip/xmc4_scu.h +++ b/arch/arm/src/xmc4/chip/xmc4_scu.h @@ -79,14 +79,11 @@ #define XMC4_SCU_SDMMCDEL_OFFSET 0x009c /* SD-MMC Delay Control Register */ #define XMC4_SCU_G0ORCEN_OFFSET 0x00a0 /* Out-Of-Range Comparator Enable Register 0 */ #define XMC4_SCU_G1ORCEN_OFFSET 0x00a4 /* Out-Of-Range Comparator Enable Register 1 */ +#define XMC4_SCU_SDMMCCON_OFFSET 0x00b4 /* SDMMC Configuration */ #define XMC4_SCU_MIRRSTS_OFFSET 0x00c4 /* Mirror Update Status Register */ #define XMC4_SCU_RMACR_OFFSET 0x00c8 /* Retention Memory Access Control Register */ #define XMC4_SCU_RMADATA_OFFSET 0x00cc /* Retention Memory Access Data Register */ -/* Ethernet Control SCU Resters */ - -#define XMC4_SCU_ETHCON_OFFSET 0x0000 /* Ethernet 0 Port Control Register */ - /* Interrupt Control SCU Registers */ #define XMC4_SCU_SRSTAT_OFFSET 0x0000 /* Service Request Status */ @@ -96,10 +93,6 @@ #define XMC4_SCU_SRSET_OFFSET 0x0010 /* Service Request Set */ #define XMC4_SCU_NMIREQEN_OFFSET 0x0014 /* Enable Promoting Events to NMI Request */ -/* SDMMC Control SCU Registers */ - -#define XMC4_SCU_SDMMCCON_OFFSET 0x0000 /* SDMMC Configuration */ - /* Parity Control Registers */ #define XMC4_SCU_PEEN_OFFSET 0x0000 /* Parity Error Enable Register */ @@ -215,14 +208,11 @@ #define XMC4_SCU_SDMMCDEL (XMC4_SCU_GENERAL_BASE+XMC4_SCU_SDMMCDEL_OFFSET) #define XMC4_SCU_G0ORCEN (XMC4_SCU_GENERAL_BASE+XMC4_SCU_G0ORCEN_OFFSET) #define XMC4_SCU_G1ORCEN (XMC4_SCU_GENERAL_BASE+XMC4_SCU_G1ORCEN_OFFSET) +#define XMC4_SCU_SDMMCCON (XMC4_SDMMC_CON_BASE+XMC4_SCU_SDMMCCON_OFFSET) #define XMC4_SCU_MIRRSTS (XMC4_SCU_GENERAL_BASE+XMC4_SCU_MIRRSTS_OFFSET) #define XMC4_SCU_RMACR (XMC4_SCU_GENERAL_BASE+XMC4_SCU_RMACR_OFFSET) #define XMC4_SCU_RMADATA (XMC4_SCU_GENERAL_BASE+XMC4_SCU_RMADATA_OFFSET) -/* Ethernet Control SCU Registers */ - -#define XMC4_SCU_ETHCON (XMC4_ETH0_CON_BASE+XMC4_SCU_ETHCON_OFFSET) - /* Parity Control Registers */ #define XMC4_SCU_PEEN (XMC4_SCU_PARITY_BASE+XMC4_SCU_PEEN_OFFSET) @@ -241,11 +231,6 @@ #define XMC4_SCU_TRAPCLR (XMC4_SCU_TRAP_BASE+XMC4_SCU_TRAPCLR_OFFSET) #define XMC4_SCU_TRAPSET (XMC4_SCU_TRAP_BASE+XMC4_SCU_TRAPSET_OFFSET) -/* Ethernet Control SCU Resters */ - -#define XMC4_SCU_ETHCON_OFFSET 0x0000 /* Ethernet 0 Port Control Register */ -#define XMC4_SCU_ETHCON_OFFSET 0x0000 /* Ethernet 0 Port Control Register */ - /* Interrupt Control SCU Registers */ #define XMC4_SCU_SRSTAT (XMC4_SCU_INTERRUPT_BASE+XMC4_SCU_SRSTAT_OFFSET) @@ -255,10 +240,6 @@ #define XMC4_SCU_SRSET (XMC4_SCU_INTERRUPT_BASE+XMC4_SCU_SRSET_OFFSET) #define XMC4_SCU_NMIREQEN (XMC4_SCU_INTERRUPT_BASE+XMC4_SCU_NMIREQEN_OFFSET) -/* SDMMC Control SCU Registers */ - -#define XMC4_SCU_SDMMCCON (XMC4_SDMMC_CON_BASE+XMC4_SCU_SDMMCCON_OFFSET) - /* Power control SCU Registers */ #define XMC4_SCU_PWRSTAT (XMC4_SCU_POWER_BASE+XMC4_SCU_PWRSTAT_OFFSET) @@ -346,159 +327,166 @@ /* Module Identification Register (32-bit Chip ID) */ -#define SCU_ID_MOD_REV_SHIFT (0) /* Bits 0-7: Module Revision Number */ -#define SCU_ID_MOD_REV_MASK (0xff << SCU_ID_MOD_REV_SHIFT) -#define SCU_ID_MOD_TYPE_SHIFT (8) /* Bits 8-15: Module Type */ -#define SCU_ID_MOD_TYPE_MASK (0xff << SCU_ID_MOD_REV_SHIFT) -#define SCU_ID_MOD_NUMBER_SHIFT (16) /* Bits 16-31: Module Number Value */ -#define SCU_ID_MOD_NUMBER_MASK (0xffff << SCU_ID_MOD_NUMBER_SHIFT) +#define SCU_ID_MOD_REV_SHIFT (0) /* Bits 0-7: Module Revision Number */ +#define SCU_ID_MOD_REV_MASK (0xff << SCU_ID_MOD_REV_SHIFT) +#define SCU_ID_MOD_TYPE_SHIFT (8) /* Bits 8-15: Module Type */ +#define SCU_ID_MOD_TYPE_MASK (0xff << SCU_ID_MOD_REV_SHIFT) +#define SCU_ID_MOD_NUMBER_SHIFT (16) /* Bits 16-31: Module Number Value */ +#define SCU_ID_MOD_NUMBER_MASK (0xffff << SCU_ID_MOD_NUMBER_SHIFT) /* Chip ID (32-bit Chip ID) */ /* Manufactory ID */ -#define SCU_IDMANUF_DEPT_SHIFT (0) /* Bits 0-4: Department Identification Number */ -#define SCU_IDMANUF_DEPT_MASK (31 << SCU_IDMANUF_MOD_DEPT_SHIFT) -#define SCU_IDMANUF_MANUF_SHIFT (5) /* Bits 5-15: Manufacturer Identification Number */ -#define SCU_IDMANUF_MANUF_MASK (0x7ff << SCU_IDMANUF_MOD_MANUF_SHIFT) +#define SCU_IDMANUF_DEPT_SHIFT (0) /* Bits 0-4: Department Identification Number */ +#define SCU_IDMANUF_DEPT_MASK (31 << SCU_IDMANUF_MOD_DEPT_SHIFT) +#define SCU_IDMANUF_MANUF_SHIFT (5) /* Bits 5-15: Manufacturer Identification Number */ +#define SCU_IDMANUF_MANUF_MASK (0x7ff << SCU_IDMANUF_MOD_MANUF_SHIFT) /* Start-up Control */ -#define SCU_STCON_HWCON_SHIFT (0) /* Bits 0-1: HW Configuration */ -#define SCU_STCON_HWCON_MASK (3 << SCU_STCON_HWCON_SHIFT) -# define SCU_STCON_HWCON_JTAG (0 << SCU_STCON_HWCON_SHIFT) /* Normal mode, JTAG */ -# define SCU_STCON_HWCON_ACBSL (1 << SCU_STCON_HWCON_SHIFT) /* ASC BSL enabled */ -# define SCU_STCON_HWCON_BMI (2 << SCU_STCON_HWCON_SHIFT) /* BMI customized boot enabled */ -# define SCU_STCON_HWCON_CANBSL (3 << SCU_STCON_HWCON_SHIFT) /* CAN BSL enabled */ -#define SCU_STCON_SWCON_SHIFT (8) /* Bits 8-11: SW Configuration */ -#define SCU_STCON_SWCON_MASK (15 << SCU_STCON_SWCON_SHIFT) -# define SCU_STCON_SWCON_ ROM (0 << SCU_STCON_SWCON_SHIFT) /* Normal boot from Boot ROM */ -# define SCU_STCON_SWCON_ASCBSL (1 << SCU_STCON_SWCON_SHIFT) /* ASC BSL enabled */ -# define SCU_STCON_SWCON_BMI (2 << SCU_STCON_SWCON_SHIFT) /* BMI customized boot enabled */ -# define SCU_STCON_SWCON_CANBSL (3 << SCU_STCON_SWCON_SHIFT) /* CAN BSL enabled */ -# define SCU_STCON_SWCON_SRAM (4 << SCU_STCON_SWCON_SHIFT) /* Boot from Code SRAM */ -# define SCU_STCON_SWCON_FLASH0 (8 << SCU_STCON_SWCON_SHIFT) /* Boot from alternate Flash Address 0 */ -# define SCU_STCON_SWCON_FLASH1 (12 << SCU_STCON_SWCON_SHIFT) /* Boot from alternate Flash Address 1 */ -# define SCU_STCON_SWCON_ABM (15 << SCU_STCON_SWCON_SHIFT) /* Enable fallback Alternate Boot Mode (ABM) */ +#define SCU_STCON_HWCON_SHIFT (0) /* Bits 0-1: HW Configuration */ +#define SCU_STCON_HWCON_MASK (3 << SCU_STCON_HWCON_SHIFT) +# define SCU_STCON_HWCON_JTAG (0 << SCU_STCON_HWCON_SHIFT) /* Normal mode, JTAG */ +# define SCU_STCON_HWCON_ACBSL (1 << SCU_STCON_HWCON_SHIFT) /* ASC BSL enabled */ +# define SCU_STCON_HWCON_BMI (2 << SCU_STCON_HWCON_SHIFT) /* BMI customized boot enabled */ +# define SCU_STCON_HWCON_CANBSL (3 << SCU_STCON_HWCON_SHIFT) /* CAN BSL enabled */ +#define SCU_STCON_SWCON_SHIFT (8) /* Bits 8-11: SW Configuration */ +#define SCU_STCON_SWCON_MASK (15 << SCU_STCON_SWCON_SHIFT) +# define SCU_STCON_SWCON_ ROM (0 << SCU_STCON_SWCON_SHIFT) /* Normal boot from Boot ROM */ +# define SCU_STCON_SWCON_ASCBSL (1 << SCU_STCON_SWCON_SHIFT) /* ASC BSL enabled */ +# define SCU_STCON_SWCON_BMI (2 << SCU_STCON_SWCON_SHIFT) /* BMI customized boot enabled */ +# define SCU_STCON_SWCON_CANBSL (3 << SCU_STCON_SWCON_SHIFT) /* CAN BSL enabled */ +# define SCU_STCON_SWCON_SRAM (4 << SCU_STCON_SWCON_SHIFT) /* Boot from Code SRAM */ +# define SCU_STCON_SWCON_FLASH0 (8 << SCU_STCON_SWCON_SHIFT) /* Boot from alternate Flash Address 0 */ +# define SCU_STCON_SWCON_FLASH1 (12 << SCU_STCON_SWCON_SHIFT) /* Boot from alternate Flash Address 1 */ +# define SCU_STCON_SWCON_ABM (15 << SCU_STCON_SWCON_SHIFT) /* Enable fallback Alternate Boot Mode (ABM) */ /* General Purpose Register 0 and General Purpose Register 1 (32-bit data) */ /* Ethernet 0 Port Control */ -#define SCU_ETH0CON_RXD0_SHIFT (0) /* Bits 0-1: MAC Receive Input 0 */ -#define SCU_ETH0CON_RXD0_MASK (3 << SCU_ETH0CON_RXD0_SHIFT) -# define SCU_ETH0CON_RXD0A (0 << SCU_ETH0CON_RXD0_SHIFT) /* Data input RXD0A is selected */ -# define SCU_ETH0CON_RXD0B (1 << SCU_ETH0CON_RXD0_SHIFT) /* Data input RXD0B is selected */ -# define SCU_ETH0CON_RXD0C (2 << SCU_ETH0CON_RXD0_SHIFT) /* Data input RXD0C is selected */ -# define SCU_ETH0CON_RXD0D (3 << SCU_ETH0CON_RXD0_SHIFT) /* Data input RXD0D is selected */ -#define SCU_ETH0CON_RXD1_SHIFT (2) /* Bits 2-3: MAC Receive Input 1 */ -#define SCU_ETH0CON_RXD1_MASK (3 << SCU_ETH0CON_RXD1_SHIFT) -# define SCU_ETH0CON_RXD1A (0 << SCU_ETH0CON_RXD1_SHIFT) /* Data input RXD1A is selected */ -# define SCU_ETH0CON_RXD1B (1 << SCU_ETH0CON_RXD1_SHIFT) /* Data input RXD1B is selected */ -# define SCU_ETH0CON_RXD1C (2 << SCU_ETH0CON_RXD1_SHIFT) /* Data input RXD1C is selected */ -# define SCU_ETH0CON_RXD1D (3 << SCU_ETH0CON_RXD1_SHIFT) /* Data input RXD1D is selected */ -#define SCU_ETH0CON_RXD2_SHIFT (4) /* Bits 4-5: MAC Receive Input 2 */ -#define SCU_ETH0CON_RXD2_MASK (3 << SCU_ETH0CON_RXD2_SHIFT) -# define SCU_ETH0CON_RXD2A (0 << SCU_ETH0CON_RXD2_SHIFT) /* Data input RXD2A is selected */ -# define SCU_ETH0CON_RXD2B (1 << SCU_ETH0CON_RXD2_SHIFT) /* Data input RXD2B is selected */ -# define SCU_ETH0CON_RXD2C (2 << SCU_ETH0CON_RXD2_SHIFT) /* Data input RXD2C is selected */ -# define SCU_ETH0CON_RXD2D (3 << SCU_ETH0CON_RXD2_SHIFT) /* Data input RXD2D is selected */ -#define SCU_ETH0CON_RXD3_SHIFT (6) /* Bits 6-7: MAC Receive Input 3 */ -#define SCU_ETH0CON_RXD3_MASK (3 << SCU_ETH0CON_RXD3_SHIFT) -# define SCU_ETH0CON_RXD3A (0 << SCU_ETH0CON_RXD3_SHIFT) /* Data input RXD3A is selected */ -# define SCU_ETH0CON_RXD3B (1 << SCU_ETH0CON_RXD3_SHIFT) /* Data input RXD3B is selected */ -# define SCU_ETH0CON_RXD3C (2 << SCU_ETH0CON_RXD3_SHIFT) /* Data input RXD3C is selected */ -# define SCU_ETH0CON_RXD3D (3 << SCU_ETH0CON_RXD3_SHIFT) /* Data input RXD3D is selected */ -#define SCU_ETH0CON_CLKRMII_SHIFT (8) /* Bits 8-9: RMII clock input */ -#define SCU_ETH0CON_CLKRMII_MASK (3 << SCU_ETH0CON_CLKRMII_SHIFT) -# define SCU_ETH0CON_CLKRMIIA (0 << SCU_ETH0CON_CLKRMII_SHIFT) /* Data input RMIIA is selected */ -# define SCU_ETH0CON_CLKRMIIB (1 << SCU_ETH0CON_CLKRMII_SHIFT) /* Data input RMIIB is selected */ -# define SCU_ETH0CON_CLKRMIIC (2 << SCU_ETH0CON_CLKRMII_SHIFT) /* Data input RMIIC is selected */ -# define SCU_ETH0CON_CLKRMIID (3 << SCU_ETH0CON_CLKRMII_SHIFT) /* Data input RMIID is selected */ -#define SCU_ETH0CON_CRSDV_SHIFT (10) /* Bits 10-11: CRS_DV input */ -#define SCU_ETH0CON_CRSDV_MASK (3 << SCU_ETH0CON_CRSDV_SHIFT) -# define SCU_ETH0CON_CRSDVA (0 << SCU_ETH0CON_CRSDV_SHIFT) /* Data input CRS_DVA is selected */ -# define SCU_ETH0CON_CRSDVB (1 << SCU_ETH0CON_CRSDV_SHIFT) /* Data input CRS_DVB is selected */ -# define SCU_ETH0CON_CRSDVC (2 << SCU_ETH0CON_CRSDV_SHIFT) /* Data input CRS_DVC is selected */ -# define SCU_ETH0CON_CRSDVD (3 << SCU_ETH0CON_CRSDV_SHIFT) /* Data input CRS_DVD is selected */ -#define SCU_ETH0CON_CRS_SHIFT (12) /* Bits 12-13: CRS input */ -#define SCU_ETH0CON_CRS_MASK (3 << SCU_ETH0CON_CRS_SHIFT) -# define SCU_ETH0CON_CRSA (0 << SCU_ETH0CON_CRS_SHIFT) /* Data input CRSA is selected */ -# define SCU_ETH0CON_CRSB (1 << SCU_ETH0CON_CRS_SHIFT) /* Data input CRSB is selected */ -# define SCU_ETH0CON_CRSC (2 << SCU_ETH0CON_CRS_SHIFT) /* Data input CRSC is selected */ -# define SCU_ETH0CON_CRSD (3 << SCU_ETH0CON_CRS_SHIFT) /* Data input CRSD is selected */ -#define SCU_ETH0CON_RXER_SHIFT (14) /* Bits 14-15: RXER Input */ -#define SCU_ETH0CON_RXER_MASK (3 << SCU_ETH0CON_RXER_SHIFT) -# define SCU_ETH0CON_RXERA (0 << SCU_ETH0CON_RXER_SHIFT) /* Data input RXERA is selected */ -# define SCU_ETH0CON_RXERB (1 << SCU_ETH0CON_RXER_SHIFT) /* Data input RXERB is selected */ -# define SCU_ETH0CON_RXERC (2 << SCU_ETH0CON_RXER_SHIFT) /* Data input RXERC is selected */ -# define SCU_ETH0CON_RXERD (3 << SCU_ETH0CON_RXER_SHIFT) /* Data input RXERD is selected */ -#define SCU_ETH0CON_COL_SHIFT (16) /* Bits 16-17: COL input */ -#define SCU_ETH0CON_COL_MASK (3 << SCU_ETH0CON_COL_SHIFT) -# define SCU_ETH0CON_COLA (0 << SCU_ETH0CON_COL_SHIFT) /* Data input COLA is selected */ -# define SCU_ETH0CON_COLB (1 << SCU_ETH0CON_COL_SHIFT) /* Data input COLB is selected */ -# define SCU_ETH0CON_COLC (2 << SCU_ETH0CON_COL_SHIFT) /* Data input COLC is selected */ -# define SCU_ETH0CON_COLD (3 << SCU_ETH0CON_COL_SHIFT) /* Data input COLD is selected */ -#define SCU_ETH0CON_CLKTX_SHIFT (18) /* Bits 18-19: CLK_TX input */ -#define SCU_ETH0CON_CLKTX_MASK (3 << SCU_ETH0CON_CLKTX_SHIFT) -# define SCU_ETH0CON_CLKTXA (0 << SCU_ETH0CON_CLKTX_SHIFT) /* Data input CLK_TXA is selected */ -# define SCU_ETH0CON_CLKTXB (1 << SCU_ETH0CON_CLKTX_SHIFT) /* Data input CLK_TXB is selected */ -# define SCU_ETH0CON_CLKTXC (2 << SCU_ETH0CON_CLKTX_SHIFT) /* Data input CLK_TXC is selected */ -# define SCU_ETH0CON_CLKTXD (3 << SCU_ETH0CON_CLKTX_SHIFT) /* Data input CLK_TXD is selected */ -#define SCU_ETH0CON_MDIO_SHIFT (22) /* Bits 22-23: MDIO Input Select */ -#define SCU_ETH0CON_MDIO_MASK (3 << SCU_ETH0CON_MDIO_SHIFT) -# define SCU_ETH0CON_MDIOA (0 << SCU_ETH0CON_MDIO_SHIFT) /* Data input MDIOA is selected */ -# define SCU_ETH0CON_MDIOB (1 << SCU_ETH0CON_MDIO_SHIFT) /* Data input MDIOB is selected */ -# define SCU_ETH0CON_MDIOC (2 << SCU_ETH0CON_MDIO_SHIFT) /* Data input MDIOC is selected */ -# define SCU_ETH0CON_MDIOD (3 << SCU_ETH0CON_MDIO_SHIFT) /* Data input MDIOD is selected */ -#define SCU_ETH0CON_INFSEL (1 << 26) /* Bit 26: Ethernet MAC Interface Selection */ -# define SCU_ETH0CON_INFSEL_MII (0) /* 0=MII */ -# define SCU_ETH0CON_INFSEL_RMII (1 << 26) /* 1=RMII */ +#define SCU_ETH0CON_RXD0_SHIFT (0) /* Bits 0-1: MAC Receive Input 0 */ +#define SCU_ETH0CON_RXD0_MASK (3 << SCU_ETH0CON_RXD0_SHIFT) +# define SCU_ETH0CON_RXD0A (0 << SCU_ETH0CON_RXD0_SHIFT) /* Data input RXD0A is selected */ +# define SCU_ETH0CON_RXD0B (1 << SCU_ETH0CON_RXD0_SHIFT) /* Data input RXD0B is selected */ +# define SCU_ETH0CON_RXD0C (2 << SCU_ETH0CON_RXD0_SHIFT) /* Data input RXD0C is selected */ +# define SCU_ETH0CON_RXD0D (3 << SCU_ETH0CON_RXD0_SHIFT) /* Data input RXD0D is selected */ +#define SCU_ETH0CON_RXD1_SHIFT (2) /* Bits 2-3: MAC Receive Input 1 */ +#define SCU_ETH0CON_RXD1_MASK (3 << SCU_ETH0CON_RXD1_SHIFT) +# define SCU_ETH0CON_RXD1A (0 << SCU_ETH0CON_RXD1_SHIFT) /* Data input RXD1A is selected */ +# define SCU_ETH0CON_RXD1B (1 << SCU_ETH0CON_RXD1_SHIFT) /* Data input RXD1B is selected */ +# define SCU_ETH0CON_RXD1C (2 << SCU_ETH0CON_RXD1_SHIFT) /* Data input RXD1C is selected */ +# define SCU_ETH0CON_RXD1D (3 << SCU_ETH0CON_RXD1_SHIFT) /* Data input RXD1D is selected */ +#define SCU_ETH0CON_RXD2_SHIFT (4) /* Bits 4-5: MAC Receive Input 2 */ +#define SCU_ETH0CON_RXD2_MASK (3 << SCU_ETH0CON_RXD2_SHIFT) +# define SCU_ETH0CON_RXD2A (0 << SCU_ETH0CON_RXD2_SHIFT) /* Data input RXD2A is selected */ +# define SCU_ETH0CON_RXD2B (1 << SCU_ETH0CON_RXD2_SHIFT) /* Data input RXD2B is selected */ +# define SCU_ETH0CON_RXD2C (2 << SCU_ETH0CON_RXD2_SHIFT) /* Data input RXD2C is selected */ +# define SCU_ETH0CON_RXD2D (3 << SCU_ETH0CON_RXD2_SHIFT) /* Data input RXD2D is selected */ +#define SCU_ETH0CON_RXD3_SHIFT (6) /* Bits 6-7: MAC Receive Input 3 */ +#define SCU_ETH0CON_RXD3_MASK (3 << SCU_ETH0CON_RXD3_SHIFT) +# define SCU_ETH0CON_RXD3A (0 << SCU_ETH0CON_RXD3_SHIFT) /* Data input RXD3A is selected */ +# define SCU_ETH0CON_RXD3B (1 << SCU_ETH0CON_RXD3_SHIFT) /* Data input RXD3B is selected */ +# define SCU_ETH0CON_RXD3C (2 << SCU_ETH0CON_RXD3_SHIFT) /* Data input RXD3C is selected */ +# define SCU_ETH0CON_RXD3D (3 << SCU_ETH0CON_RXD3_SHIFT) /* Data input RXD3D is selected */ +#define SCU_ETH0CON_CLKRMII_SHIFT (8) /* Bits 8-9: RMII clock input */ +#define SCU_ETH0CON_CLKRMII_MASK (3 << SCU_ETH0CON_CLKRMII_SHIFT) +# define SCU_ETH0CON_CLKRMIIA (0 << SCU_ETH0CON_CLKRMII_SHIFT) /* Data input RMIIA is selected */ +# define SCU_ETH0CON_CLKRMIIB (1 << SCU_ETH0CON_CLKRMII_SHIFT) /* Data input RMIIB is selected */ +# define SCU_ETH0CON_CLKRMIIC (2 << SCU_ETH0CON_CLKRMII_SHIFT) /* Data input RMIIC is selected */ +# define SCU_ETH0CON_CLKRMIID (3 << SCU_ETH0CON_CLKRMII_SHIFT) /* Data input RMIID is selected */ +#define SCU_ETH0CON_CRSDV_SHIFT (10) /* Bits 10-11: CRS_DV input */ +#define SCU_ETH0CON_CRSDV_MASK (3 << SCU_ETH0CON_CRSDV_SHIFT) +# define SCU_ETH0CON_CRSDVA (0 << SCU_ETH0CON_CRSDV_SHIFT) /* Data input CRS_DVA is selected */ +# define SCU_ETH0CON_CRSDVB (1 << SCU_ETH0CON_CRSDV_SHIFT) /* Data input CRS_DVB is selected */ +# define SCU_ETH0CON_CRSDVC (2 << SCU_ETH0CON_CRSDV_SHIFT) /* Data input CRS_DVC is selected */ +# define SCU_ETH0CON_CRSDVD (3 << SCU_ETH0CON_CRSDV_SHIFT) /* Data input CRS_DVD is selected */ +#define SCU_ETH0CON_CRS_SHIFT (12) /* Bits 12-13: CRS input */ +#define SCU_ETH0CON_CRS_MASK (3 << SCU_ETH0CON_CRS_SHIFT) +# define SCU_ETH0CON_CRSA (0 << SCU_ETH0CON_CRS_SHIFT) /* Data input CRSA is selected */ +# define SCU_ETH0CON_CRSB (1 << SCU_ETH0CON_CRS_SHIFT) /* Data input CRSB is selected */ +# define SCU_ETH0CON_CRSC (2 << SCU_ETH0CON_CRS_SHIFT) /* Data input CRSC is selected */ +# define SCU_ETH0CON_CRSD (3 << SCU_ETH0CON_CRS_SHIFT) /* Data input CRSD is selected */ +#define SCU_ETH0CON_RXER_SHIFT (14) /* Bits 14-15: RXER Input */ +#define SCU_ETH0CON_RXER_MASK (3 << SCU_ETH0CON_RXER_SHIFT) +# define SCU_ETH0CON_RXERA (0 << SCU_ETH0CON_RXER_SHIFT) /* Data input RXERA is selected */ +# define SCU_ETH0CON_RXERB (1 << SCU_ETH0CON_RXER_SHIFT) /* Data input RXERB is selected */ +# define SCU_ETH0CON_RXERC (2 << SCU_ETH0CON_RXER_SHIFT) /* Data input RXERC is selected */ +# define SCU_ETH0CON_RXERD (3 << SCU_ETH0CON_RXER_SHIFT) /* Data input RXERD is selected */ +#define SCU_ETH0CON_COL_SHIFT (16) /* Bits 16-17: COL input */ +#define SCU_ETH0CON_COL_MASK (3 << SCU_ETH0CON_COL_SHIFT) +# define SCU_ETH0CON_COLA (0 << SCU_ETH0CON_COL_SHIFT) /* Data input COLA is selected */ +# define SCU_ETH0CON_COLB (1 << SCU_ETH0CON_COL_SHIFT) /* Data input COLB is selected */ +# define SCU_ETH0CON_COLC (2 << SCU_ETH0CON_COL_SHIFT) /* Data input COLC is selected */ +# define SCU_ETH0CON_COLD (3 << SCU_ETH0CON_COL_SHIFT) /* Data input COLD is selected */ +#define SCU_ETH0CON_CLKTX_SHIFT (18) /* Bits 18-19: CLK_TX input */ +#define SCU_ETH0CON_CLKTX_MASK (3 << SCU_ETH0CON_CLKTX_SHIFT) +# define SCU_ETH0CON_CLKTXA (0 << SCU_ETH0CON_CLKTX_SHIFT) /* Data input CLK_TXA is selected */ +# define SCU_ETH0CON_CLKTXB (1 << SCU_ETH0CON_CLKTX_SHIFT) /* Data input CLK_TXB is selected */ +# define SCU_ETH0CON_CLKTXC (2 << SCU_ETH0CON_CLKTX_SHIFT) /* Data input CLK_TXC is selected */ +# define SCU_ETH0CON_CLKTXD (3 << SCU_ETH0CON_CLKTX_SHIFT) /* Data input CLK_TXD is selected */ +#define SCU_ETH0CON_MDIO_SHIFT (22) /* Bits 22-23: MDIO Input Select */ +#define SCU_ETH0CON_MDIO_MASK (3 << SCU_ETH0CON_MDIO_SHIFT) +# define SCU_ETH0CON_MDIOA (0 << SCU_ETH0CON_MDIO_SHIFT) /* Data input MDIOA is selected */ +# define SCU_ETH0CON_MDIOB (1 << SCU_ETH0CON_MDIO_SHIFT) /* Data input MDIOB is selected */ +# define SCU_ETH0CON_MDIOC (2 << SCU_ETH0CON_MDIO_SHIFT) /* Data input MDIOC is selected */ +# define SCU_ETH0CON_MDIOD (3 << SCU_ETH0CON_MDIO_SHIFT) /* Data input MDIOD is selected */ +#define SCU_ETH0CON_INFSEL (1 << 26) /* Bit 26: Ethernet MAC Interface Selection */ +# define SCU_ETH0CON_INFSEL_MII (0) /* 0=MII */ +# define SCU_ETH0CON_INFSEL_RMII (1 << 26) /* 1=RMII */ /* CCUx Global Start Control Register */ -#define SCU_CCUCON_GSC40 (1 << 0) /* Bit 0: Global Start Control CCU40 */ -#define SCU_CCUCON_GSC41 (1 << 1) /* Bit 1: Global Start Control CCU41 */ -#define SCU_CCUCON_GSC42 (1 << 2) /* Bit 2: Global Start Control CCU42 */ -#define SCU_CCUCON_GSC43 (1 << 3) /* Bit 3: Global Start Control CCU43 */ -#define SCU_CCUCON_GSC80 (1 << 8) /* Bit 8: Global Start Control CCU80 */ -#define SCU_CCUCON_GSC81 (1 << 9) /* Bit 9: Global Start Control CCU81 */ +#define SCU_CCUCON_GSC40 (1 << 0) /* Bit 0: Global Start Control CCU40 */ +#define SCU_CCUCON_GSC41 (1 << 1) /* Bit 1: Global Start Control CCU41 */ +#define SCU_CCUCON_GSC42 (1 << 2) /* Bit 2: Global Start Control CCU42 */ +#define SCU_CCUCON_GSC43 (1 << 3) /* Bit 3: Global Start Control CCU43 */ +#define SCU_CCUCON_GSC80 (1 << 8) /* Bit 8: Global Start Control CCU80 */ +#define SCU_CCUCON_GSC81 (1 << 9) /* Bit 9: Global Start Control CCU81 */ /* DTS Control */ -#define SCU_DTSCON_PWD (1 << 0) /* Bit 0: Sensor Power Down */ -#define SCU_DTSCON_START (1 << 1) /* Bit 1: Sensor Measurement Start */ -#define SCU_DTSCON_OFFSET_SHIFT (4) /* Bits 4-10: Offset Calibration Value */ -#define SCU_DTSCON_OFFSET_MASK (0x7f << SCU_DTSCON_OFFSET_SHIFT) -# define SCU_DTSCON_OFFSET(n) ((uint32_t)(n) << SCU_DTSCON_OFFSET_SHIFT) -#define SCU_DTSCON_GAIN_SHIFT (11) /* Bits 11-16: Gain Calibration Value */ -#define SCU_DTSCON_GAIN_MASK (0x3f << SCU_DTSCON_GAIN_SHIFT) -# define SCU_DTSCON_GAIN(n) ((uint32_t)(n) << SCU_DTSCON_GAIN_SHIFT) -#define SCU_DTSCON_REFTRIM_SHIFT (17) /* Bits 17-19: Reference Trim Calibration Value */ -#define SCU_DTSCON_REFTRIM_MASK (7 << SCU_DTSCON_REFTRIM_SHIFT) -# define SCU_DTSCON_REFTRIM(n) ((uint32_t)(n) << SCU_DTSCON_REFTRIM_SHIFT) -#define SCU_DTSCON_BGTRIM_SHIFT (20) /* Bits 20-23: Bandgap Trim Calibration Value */ -#define SCU_DTSCON_BGTRIM_MASK (15 << SCU_DTSCON_BGTRIM_SHIFT) -# define SCU_DTSCON_BGTRIM(n) ((uint32_t)(n) << SCU_DTSCON_BGTRIM_SHIFT) +#define SCU_DTSCON_PWD (1 << 0) /* Bit 0: Sensor Power Down */ +#define SCU_DTSCON_START (1 << 1) /* Bit 1: Sensor Measurement Start */ +#define SCU_DTSCON_OFFSET_SHIFT (4) /* Bits 4-10: Offset Calibration Value */ +#define SCU_DTSCON_OFFSET_MASK (0x7f << SCU_DTSCON_OFFSET_SHIFT) +# define SCU_DTSCON_OFFSET(n) ((uint32_t)(n) << SCU_DTSCON_OFFSET_SHIFT) +#define SCU_DTSCON_GAIN_SHIFT (11) /* Bits 11-16: Gain Calibration Value */ +#define SCU_DTSCON_GAIN_MASK (0x3f << SCU_DTSCON_GAIN_SHIFT) +# define SCU_DTSCON_GAIN(n) ((uint32_t)(n) << SCU_DTSCON_GAIN_SHIFT) +#define SCU_DTSCON_REFTRIM_SHIFT (17) /* Bits 17-19: Reference Trim Calibration Value */ +#define SCU_DTSCON_REFTRIM_MASK (7 << SCU_DTSCON_REFTRIM_SHIFT) +# define SCU_DTSCON_REFTRIM(n) ((uint32_t)(n) << SCU_DTSCON_REFTRIM_SHIFT) +#define SCU_DTSCON_BGTRIM_SHIFT (20) /* Bits 20-23: Bandgap Trim Calibration Value */ +#define SCU_DTSCON_BGTRIM_MASK (15 << SCU_DTSCON_BGTRIM_SHIFT) +# define SCU_DTSCON_BGTRIM(n) ((uint32_t)(n) << SCU_DTSCON_BGTRIM_SHIFT) /* DTS Status */ -#define SCU_DTSSTAT_RESULT_SHIFT (0) /* Bits 0-9: Result of the DTS Measurement */ -#define SCU_DTSSTAT_RESULT_MASK (0x3ff << SCU_DTSSTAT_RESULT_SHIFT) -#define SCU_DTSSTAT_RDY (1 << 14) /* Bit 14: Sensor Ready Status */ -#define SCU_DTSSTAT_BUSY (1 << 15) /* Bit 15: Sensor Busy Status */ +#define SCU_DTSSTAT_RESULT_SHIFT (0) /* Bits 0-9: Result of the DTS Measurement */ +#define SCU_DTSSTAT_RESULT_MASK (0x3ff << SCU_DTSSTAT_RESULT_SHIFT) +#define SCU_DTSSTAT_RDY (1 << 14) /* Bit 14: Sensor Ready Status */ +#define SCU_DTSSTAT_BUSY (1 << 15) /* Bit 15: Sensor Busy Status */ /* SD-MMC Delay Control Register */ -#define SCU_SDMMCDEL_TAPEN (1 << 0) /* Bit 0: Enable delay on the CMD/DAT out lines */ -#define SCU_SDMMCDEL_TAPDEL_SHIFT (4) /* Bitx 4-7: Number of Delay Elements Select */ -#define SCU_SDMMCDEL_TAPDEL_MASK (15 << SCU_SDMMCDEL_TAPDEL_SHIFT) -# define SCU_SDMMCDEL_TAPDEL(n) ((uint32_t)((n)-1) << SCU_SDMMCDEL_TAPDEL_SHIFT) +#define SCU_SDMMCDEL_TAPEN (1 << 0) /* Bit 0: Enable delay on the CMD/DAT out lines */ +#define SCU_SDMMCDEL_TAPDEL_SHIFT (4) /* Bitx 4-7: Number of Delay Elements Select */ +#define SCU_SDMMCDEL_TAPDEL_MASK (15 << SCU_SDMMCDEL_TAPDEL_SHIFT) +# define SCU_SDMMCDEL_TAPDEL(n) ((uint32_t)((n)-1) << SCU_SDMMCDEL_TAPDEL_SHIFT) /* Out-Of-Range Comparator Enable Register 0 and Out-Of-Range Comparator Enable Register 1 */ -#define SCU_GORCEN_ENORC6 (1 << 6) /* Bit 6: Enable Out of Range Comparator, Channel 6 */ -#define SCU_GORCEN_ENORC7 (1 << 7) /* Bit 7: Enable Out of Range Comparator, Channel 7 */ +#define SCU_GORCEN_ENORC6 (1 << 6) /* Bit 6: Enable Out of Range Comparator, Channel 6 */ +#define SCU_GORCEN_ENORC7 (1 << 7) /* Bit 7: Enable Out of Range Comparator, Channel 7 */ + +/* SDMMC Configuration */ + +#define SCU_SDMMCCON_WPSEL (1 << 0) /* Bit 0: SDMMC Write Protection Input Multiplexer Control */ +#define SCU_SDMMCCON_WPSVAL (1 << 4) /* Bit 4: SDMMC Write Protect Software Control */ +#define SCU_SDMMCCON_CDSEL (1 << 16) /* Bit 16: SDMMC Card Detection Control */ +#define SCU_SDMMCCON_CDSVAL (1 << 20) /* Bit 20: SDMMC Write Protect Software Control */ /* Mirror Update Status Register */ @@ -517,44 +505,39 @@ #define SCU_MIRRSTS_RTC_MSKSR (1 << 14) /* Bit 14: RTC MSKSSR Mirror Register Write Status */ #define SCU_MIRRSTS_RTC_CLRSR (1 << 15) /* Bit 15: RTC CLRSR Mirror Register Write Status */ -/* Ethernet Control SCU Resters */ - -/* Ethernet 0 Port Control Register */ -#define SCU_ETHCON_ - /* Interrupt Control SCU Registers */ /* Service Request Status, RAW Service Request Status, Service Request Mask, Service * Request Clear, Service Request Set */ -#define SCU_INT_PRWARN (1 << 0) /* Bit 0: WDT pre-warning Interrupt */ -#define SCU_INT_PI (1 << 1) /* Bit 1: RTC Periodic Interrupt */ -#define SCU_INT_AI (1 << 2) /* Bit 2: Alarm Interrupt */ -#define SCU_INT_DLROVR (1 << 3) /* Bit 3: DLR Request Overrun Interrupt */ -#define SCU_INT_HDSTAT (1 << 16) /* Bit 16: HDSTAT Mirror Register Update */ -#define SCU_INT_HDCLR (1 << 17) /* Bit 17: HDCLR Mirror Register Update */ -#define SCU_INT_HDSET (1 << 18) /* Bit 18: HDSET Mirror Register Update */ -#define SCU_INT_HDCR (1 << 19) /* Bit 19: HDCR Mirror Register Update */ -#define SCU_INT_OSCSICTRL (1 << 21) /* Bit 21: OSCSICTRL Mirror Register Update */ -#define SCU_INT_OSCULSTAT (1 << 22) /* Bit 22: OSCULTAT Mirror Register Update */ -#define SCU_INT_OSCULCTRL (1 << 23) /* Bit 23: OSCULCTRL Mirror Register Update */ -#define SCU_INT_RTC_CTR (1 << 24) /* Bit 24: RTC CTR Mirror Register Update */ -#define SCU_INT_RTC_ATIM0 (1 << 25) /* Bit 25: RTC ATIM0 Mirror Register Update */ -#define SCU_INT_RTC_ATIM1 (1 << 26) /* Bit 26: RTC ATIM1 Mirror Register Update */ -#define SCU_INT_RTC_TIM0 (1 << 27) /* Bit 27: RTC TIM0 Mirror Register Update */ -#define SCU_INT_RTC_TIM1 (1 << 28) /* Bit 28: RTC TIM1 Mirror Register Update */ -#define SCU_INTT_RMX (1 << 29) /* Bit 29: Retention Memory Mirror Register */ +#define SCU_INT_PRWARN (1 << 0) /* Bit 0: WDT pre-warning Interrupt */ +#define SCU_INT_PI (1 << 1) /* Bit 1: RTC Periodic Interrupt */ +#define SCU_INT_AI (1 << 2) /* Bit 2: Alarm Interrupt */ +#define SCU_INT_DLROVR (1 << 3) /* Bit 3: DLR Request Overrun Interrupt */ +#define SCU_INT_HDSTAT (1 << 16) /* Bit 16: HDSTAT Mirror Register Update */ +#define SCU_INT_HDCLR (1 << 17) /* Bit 17: HDCLR Mirror Register Update */ +#define SCU_INT_HDSET (1 << 18) /* Bit 18: HDSET Mirror Register Update */ +#define SCU_INT_HDCR (1 << 19) /* Bit 19: HDCR Mirror Register Update */ +#define SCU_INT_OSCSICTRL (1 << 21) /* Bit 21: OSCSICTRL Mirror Register Update */ +#define SCU_INT_OSCULSTAT (1 << 22) /* Bit 22: OSCULTAT Mirror Register Update */ +#define SCU_INT_OSCULCTRL (1 << 23) /* Bit 23: OSCULCTRL Mirror Register Update */ +#define SCU_INT_RTC_CTR (1 << 24) /* Bit 24: RTC CTR Mirror Register Update */ +#define SCU_INT_RTC_ATIM0 (1 << 25) /* Bit 25: RTC ATIM0 Mirror Register Update */ +#define SCU_INT_RTC_ATIM1 (1 << 26) /* Bit 26: RTC ATIM1 Mirror Register Update */ +#define SCU_INT_RTC_TIM0 (1 << 27) /* Bit 27: RTC TIM0 Mirror Register Update */ +#define SCU_INT_RTC_TIM1 (1 << 28) /* Bit 28: RTC TIM1 Mirror Register Update */ +#define SCU_INTT_RMX (1 << 29) /* Bit 29: Retention Memory Mirror Register */ /* Enable Promoting Events to NMI Request */ -#define SCU_NMIREQEN_PRWARN (1 << 0) /* Bit 0: Promote Pre-Warning Interrupt Request to NMI Request */ -#define SCU_NMIREQEN_PI (1 << 1) /* Bit 1: Promote RTC Periodic Interrupt request to NMI Request */ -#define SCU_NMIREQEN_AI (1 << 2) /* Bit 2: Promote RTC Alarm Interrupt Request to NMIRequest */ -#define SCU_NMIREQEN_ERU00 (1 << 16) /* Bit 16: Promote Channel 0 Interrupt of ERU0 Request to NMI Request */ -#define SCU_NMIREQEN_ERU01 (1 << 17) /* Bit 17: Promote Channel 1 Interrupt of ERU0 Request to NMI Request */ -#define SCU_NMIREQEN_ERU02 (1 << 18) /* Bit 18: Promote Channel 2 Interrupt of ERU0 Request to NMI Request */ -#define SCU_NMIREQEN_ERU03 (1 << 19) /* Bit 19: Promote Channel 3 Interrupt of ERU0 Request to NMI Request */ +#define SCU_NMIREQEN_PRWARN (1 << 0) /* Bit 0: Promote Pre-Warning Interrupt Request to NMI Request */ +#define SCU_NMIREQEN_PI (1 << 1) /* Bit 1: Promote RTC Periodic Interrupt request to NMI Request */ +#define SCU_NMIREQEN_AI (1 << 2) /* Bit 2: Promote RTC Alarm Interrupt Request to NMIRequest */ +#define SCU_NMIREQEN_ERU00 (1 << 16) /* Bit 16: Promote Channel 0 Interrupt of ERU0 Request to NMI Request */ +#define SCU_NMIREQEN_ERU01 (1 << 17) /* Bit 17: Promote Channel 1 Interrupt of ERU0 Request to NMI Request */ +#define SCU_NMIREQEN_ERU02 (1 << 18) /* Bit 18: Promote Channel 2 Interrupt of ERU0 Request to NMI Request */ +#define SCU_NMIREQEN_ERU03 (1 << 19) /* Bit 19: Promote Channel 3 Interrupt of ERU0 Request to NMI Request */ /* Retention Memory Access Control Register */ @@ -565,11 +548,6 @@ /* Retention Memory Access Data Register (32-bit data) */ -/* SDMMC Control SCU Registers */ - -/* SDMMC Configuration */ -#define SCU_SDMMCCON_ - /* Parity Control Registers */ /* Parity Error Enable Register */ @@ -715,11 +693,11 @@ /* Hibernation SCU Registers */ /* Hibernate Domain Status Register */ -#define SCU_HDSTAT_EPEV (1 << 0) /* Bit 0: Wake-up Pin Event Positive Edge Status */ -#define SCU_HDSTAT_ENEV (1 << 1) /* Bit 1: Wake-up Pin Event Negative Edge Status */ -#define SCU_HDSTAT_RTCEV (1 << 2) /* Bit 2: RTC Event Status */ -#define SCU_HDSTAT_ULPWDG (1 << 3) /* Bit 3: ULP WDG Alarm Status */ -#define SCU_HDSTAT_HIBNOUT (1 << 4) /* Bit 3: Hibernate Control Status */ +#define SCU_HDSTAT_EPEV (1 << 0) /* Bit 0: Wake-up Pin Event Positive Edge Status */ +#define SCU_HDSTAT_ENEV (1 << 1) /* Bit 1: Wake-up Pin Event Negative Edge Status */ +#define SCU_HDSTAT_RTCEV (1 << 2) /* Bit 2: RTC Event Status */ +#define SCU_HDSTAT_ULPWDG (1 << 3) /* Bit 3: ULP WDG Alarm Status */ +#define SCU_HDSTAT_HIBNOUT (1 << 4) /* Bit 3: Hibernate Control Status */ /* Hibernate Domain Status Clear Register */ @@ -981,41 +959,42 @@ /* Peripheral 0 Clock Gating Status, Peripheral 0 Clock Gating Set, Peripheral 0 Clock Gating Clear */ -#define SCU_CGAT0_VADC (1 << 0) /* Bit 0: */ -#define SCU_CGAT0_DSD (1 << 1) /* Bit 1: */ -#define SCU_CGAT0_CCU40 (1 << 2) /* Bit 2: */ -#define SCU_CGAT0_CCU41 (1 << 3) /* Bit 3: */ -#define SCU_CGAT0_CCU42 (1 << 4) /* Bit 4: */ -#define SCU_CGAT0_CCU80 (1 << 7) /* Bit 7: */ -#define SCU_CGAT0_CCU81 (1 << 8) /* Bit 8: */ -#define SCU_CGAT0_POSIF0 (1 << 9) /* Bit 9: */ -#define SCU_CGAT0_POSIF1 (1 << 10) /* Bit 10: */ -#define SCU_CGAT0_USIC0 (1 << 11) /* Bit 11: */ -#define SCU_CGAT0_ERU1_ (1 << 16) /* Bit 16: */ +#define SCU_CGAT0_VADC (1 << 0) /* Bit 0: VADC Gating Status */ +#define SCU_CGAT0_DSD (1 << 1) /* Bit 1: DSD Gating Status */ +#define SCU_CGAT0_CCU40 (1 << 2) /* Bit 2: CCU40 Gating Status */ +#define SCU_CGAT0_CCU41 (1 << 3) /* Bit 3: CCU41 Gating Status */ +#define SCU_CGAT0_CCU42 (1 << 4) /* Bit 4: CCU42 Gating Status */ +#define SCU_CGAT0_CCU80 (1 << 7) /* Bit 7: CCU80 Gating Status */ +#define SCU_CGAT0_CCU81 (1 << 8) /* Bit 8: CCU81 Gating Status */ +#define SCU_CGAT0_POSIF0 (1 << 9) /* Bit 9: POSIF0 Gating Status */ +#define SCU_CGAT0_POSIF1 (1 << 10) /* Bit 10: POSIF1 Gating Status */ +#define SCU_CGAT0_USIC0 (1 << 11) /* Bit 11: USIC0 Gating Status */ +#define SCU_CGAT0_ERU1_ (1 << 16) /* Bit 16: ERU1 Gating Status */ /* Peripheral 1 Clock Gating Status, Peripheral 1 Clock Gating Set, Peripheral 1 Clock Gating Clear */ -#define SCU_CGATSTAT1_CCU43 (1 << 0) /* Bit 0: */ -#define SCU_CGATSTAT1_LEDTSCU0 (1 << 3) /* Bit 3: */ -#define SCU_CGATSTAT1_MCAN0 (1 << 4) /* Bit 4: */ -#define SCU_CGATSTAT1_DAC (1 << 5) /* Bit 5: */ -#define SCU_CGATSTAT1_MMCI (1 << 6) /* Bit 6: */ -#define SCU_CGATSTAT1_USIC1 (1 << 7) /* Bit 7: */ -#define SCU_CGATSTAT1_USIC2 (1 << 8) /* Bit 8: */ -#define SCU_CGATSTAT1_PPORTS (1 << 9) /* Bit 9: */ +#define SCU_CGATSTAT1_CCU43 (1 << 0) /* Bit 0: CCU43 Gating Status */ +#define SCU_CGATSTAT1_LEDTSCU0 (1 << 3) /* Bit 3: LEDTS Gating Status */ +#define SCU_CGATSTAT1_MCAN0 (1 << 4) /* Bit 4: MultiCAN Gating Status */ +#define SCU_CGATSTAT1_DAC (1 << 5) /* Bit 5: DAC Gating Status */ +#define SCU_CGATSTAT1_MMCI (1 << 6) /* Bit 6: MMC Interface Gating Status */ +#define SCU_CGATSTAT1_USIC1 (1 << 7) /* Bit 7: USIC1 Gating Status */ +#define SCU_CGATSTAT1_USIC2 (1 << 8) /* Bit 8: USIC1 Gating Status */ +#define SCU_CGATSTAT1_PPORTS (1 << 9) /* Bit 9: PORTS Gating Status */ /* Peripheral 2 Clock Gating Status, Peripheral 2 Clock Gating Set, Peripheral 2 Clock Gating Clear */ -#define SCU_CGATSTAT2_WDT (1 << 1) /* Bit 1: */ -#define SCU_CGATSTAT2_ETH0 (1 << 2) /* Bit 2: */ -#define SCU_CGATSTAT2_DMA0 (1 << 4) /* Bit 4: */ -#define SCU_CGATSTAT2_DMA1 (1 << 5) /* Bit 5: */ -#define SCU_CGATSTAT2_FCE (1 << 6) /* Bit 6: */ -#define SCU_CGATSTAT2_USB (1 << 7) /* Bit 7: */ +#define SCU_CGATSTAT2_WDT (1 << 1) /* Bit 1: WDT Gating Status */ +#define SCU_CGATSTAT2_ETH0 (1 << 2) /* Bit 2: ETH0 Gating Status */ +#define SCU_CGATSTAT2_DMA0 (1 << 4) /* Bit 4: DMA0 Gating Status */ +#define SCU_CGATSTAT2_DMA1 (1 << 5) /* Bit 5: DMA1 Gating Status */ +#define SCU_CGATSTAT2_FCE (1 << 6) /* Bit 6: FCE Gating Status */ +#define SCU_CGATSTAT2_USB (1 << 7) /* Bit 7: USB Gating Status */ +#define SCU_CGATSTAT2_USB (1 << 10) /* Bit 10: ECAT Gating Status */ /* Peripheral 3 Clock Gating Status, Peripheral 3 Clock Gating Set, Peripheral 3 Clock Gating Clear */ -#define SCU_CGATSTAT3_EBU (1 << 2) /* Bit 2: */ +#define SCU_CGATSTAT3_EBU (1 << 2) /* Bit 2: EBU Gating Status */ /* Oscillator Control SCU Registers */ -- GitLab From 6b5dc4957374b7fa9404b668f4172d23ae5f6974 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 18 Mar 2017 19:16:29 -0600 Subject: [PATCH 099/990] XMC4xxx: Flesh out USIC header file. Still needs a little work. --- arch/arm/src/xmc4/chip/xmc4_usic.h | 535 ++++++++++++++++++++++++++--- 1 file changed, 492 insertions(+), 43 deletions(-) diff --git a/arch/arm/src/xmc4/chip/xmc4_usic.h b/arch/arm/src/xmc4/chip/xmc4_usic.h index 8b91e88583..8d204fcf8c 100644 --- a/arch/arm/src/xmc4/chip/xmc4_usic.h +++ b/arch/arm/src/xmc4/chip/xmc4_usic.h @@ -69,7 +69,7 @@ /* PMU Registers -- See ID register */ /* Prefetch Registers -- See PCON register */ -/* Kernal Registers */ +/* Kernel Registers */ #define XMC4_USIC_ID_OFFSET 0x0008 /* Kernel State Configuration Register */ @@ -399,79 +399,528 @@ /* USIC Channel Registers */ /* Channel Configuration Register */ -#define USIC_CCFG_ + +#define USIC_CCFG_SSC (1 << 0) /* Bit 0: */ +#define USIC_CCFG_ASC (1 << 1) /* Bit 1: */ +#define USIC_CCFG_IIC (1 << 2) /* Bit 2: */ +#define USIC_CCFG_IIS (1 << 3) /* Bit 3: */ +#define USIC_CCFG_RB (1 << 6) /* Bit 6: */ +#define USIC_CCFG_TB (1 << 7) /* Bit 7: */ + /* Kernel State Configuration Register */ -#define USIC_KSCFG_ + +#define USIC_KSCFG_MODEN (1 << 0) /* Bit 0: */ +#define USIC_KSCFG_BPMODEN (1 << 1) /* Bit 1: */ +#define USIC_KSCFG_NOMCFG_SHIFT (4) /* Bits 4-5: */ +#define USIC_KSCFG_NOMCFG_MASK (3 << USIC_KSCFG_NOMCFG_SHIFT) +#define USIC_KSCFG_BPNOM (1 << 7) /* Bit 7: */ +#define USIC_KSCFG_SUMCFG_SHIFT (8) /* Bits 8-9: */ +#define USIC_KSCFG_SUMCFG_MASK (3 << USIC_KSCFG_SUMCFG_SHIFT) +#define USIC_KSCFG_BPSUM (1 << 11) /* Bit 11: */ + /* Fractional Divider Register */ -#define USIC_FDR_ + +#define USIC_FDR_STEP_SHIFT (0) /* Bits 0-9: */ +#define USIC_FDR_STEP_MASK (0x3ff << USIC_FDR_STEP_SHIFT) +#define USIC_FDR_DM_SHIFT (14) /* Bits 14-15: */ +#define USIC_FDR_DM_MASK (3 << USIC_FDR_DM_SHIFT) +#define USIC_FDR_RESULT_SHIFT (16) /* Bits 16-25: */ +#define USIC_FDR_RESULT_MASK (0x3ff << USIC_FDR_RESULT_SHIFT) + /* Baud Rate Generator Register */ -#define USIC_BRG_ + +#define USIC_BRG_CLKSEL_SHIFT (0) /* Bits 0-1: */ +#define USIC_BRG_CLKSEL_MASK (3 << USIC_BRG_CLKSEL_SHIFT) +#define USIC_BRG_TMEN (1 << 3) /* Bit 3: */ +#define USIC_BRG_PPPEN (1 << 4) /* Bit 4: */ +#define USIC_BRG_CTQSEL_SHIFT (6) /* Bits 6-7: */ +#define USIC_BRG_CTQSEL_MASK (3 << USIC_BRG_CTQSEL_SHIFT) +#define USIC_BRG_PCTQ_SHIFT (8) /* Bits 8-9: */ +#define USIC_BRG_PCTQ_MASK (3 << USIC_BRG_PCTQ_SHIFT) +#define USIC_BRG_DCTQ_SHIFT (10) /* Bits 10-15: */ +#define USIC_BRG_DCTQ_MASK (0x3f << USIC_BRG_DCTQ_SHIFT) +#define USIC_BRG_PDIV_SHIFT (16) /* Bits 16-25: */ +#define USIC_BRG_PDIV_MASK (0x3ff << USIC_BRG_PDIV_SHIFT) +#define USIC_BRG_SCLKOSEL (1 << 28) /* Bit 28: */ +#define USIC_BRG_MCLKCFG (1 << 29) /* Bit 29: */ +#define USIC_BRG_SCLKCFG (1 << 30) /* Bit 30: */ + /* Interrupt Node Pointer Register */ -#define USIC_INPR_ -/* Input Control Register 0 */ -#define USIC_DX0CR_ -/* Input Control Register 1 */ -#define USIC_DX1CR_ -/* Input Control Register 2 */ -#define USIC_DX2CR_ -/* Input Control Register 3 */ -#define USIC_DX3CR_ -/* Input Control Register 4 */ -#define USIC_DX4CR_ -/* Input Control Register 5 */ -#define USIC_DX5CR_ + +#define USIC_INPR_TSINP_SHIFT (0) /* Bits 0-2: */ +#define USIC_INPR_TSINP_MASK (7 << USIC_INPR_TSINP_SHIFT) +#define USIC_INPR_TBINP_SHIFT (4) /* Bits 4-6: */ +#define USIC_INPR_TBINP_MASK (7 << USIC_INPR_TBINP_SHIFT) +#define USIC_INPR_RINP_SHIFT (8) /* Bits 8-10: */ +#define USIC_INPR_RINP_MASK (7 << USIC_INPR_RINP_SHIFT) +#define USIC_INPR_AINP_SHIFT (12) /* Bits 12-14: */ +#define USIC_INPR_AINP_MASK (7 << USIC_INPR_AINP_SHIFT) +#define USIC_INPR_PINP_SHIFT (16) /* Bits 16-18: */ +#define USIC_INPR_PINP_MASK (7 << USIC_INPR_PINP_SHIFT) + +/* Input Control Register 0, Input Control Register 1, Input Control Register 2, + * Input Control Register 3, Input Control Register 4, Input Control Register 5 + */ + +#define USIC_DXCR_DSEL_SHIFT (0) /* Bits 0-2: */ +#define USIC_DXCR_DSEL_MASK (7 << USIC_DX0CR_DSEL_SHIFT) +#define USIC_DX1CR_DCEN (1 << 3) /* Bit 3: (DX1CR only) */ +#define USIC_DXCR_INSW (1 << 4) /* Bit 4: */ +#define USIC_DXCR_DFEN (1 << 5) /* Bit 5: */ +#define USIC_DXCR_DSEN (1 << 6) /* Bit 6: */ +#define USIC_DXCR_DPOL (1 << 8) /* Bit 8: */ +#define USIC_DXCR_SFSEL (1 << 9) /* Bit 9: */ +#define USIC_DXCR_CM_SHIFT (10) /* Bits 10-12: */ +#define USIC_DXCR_CM_MASK (3 << USIC_DX0CR_CM_SHIFT) +#define USIC_DXCR_DXS (1 << 15) /* Bit 15: */ + /* Shift Control Register */ -#define USIC_SCTR_ + +#define USIC_SCTR_SDIR (1 << 0) /* Bit 0: */ +#define USIC_SCTR_PDL (1 << 1) /* Bit `: */ +#define USIC_SCTR_DSM_SHIFT (2) /* Bits 2-3: */ +#define USIC_SCTR_DSM_MASK (3 << USIC_SCTR_DSM_SHIFT) +#define USIC_SCTR_HPCDIR (1 << 4) /* Bit 4: */ +#define USIC_SCTR_DOCFG_SHIFT (6) /* Bits 6-7: */ +#define USIC_SCTR_DOCFG_MASK (3 << USIC_SCTR_DOCFG_SHIFT) +#define USIC_SCTR_TRM_SHIFT (8) /* Bits 8-9: */ +#define USIC_SCTR_TRM_MASK (3 << USIC_SCTR_TRM_SHIFT) +#define USIC_SCTR_FLE_SHIFT (16) /* Bits 16-21: */ +#define USIC_SCTR_FLE_MASK (0x3f << USIC_SCTR_FLE_SHIFT) +#define USIC_SCTR_WLE_SHIFT (24) /* Bits 24-27: */ +#define USIC_SCTR_WLE_MASK (15 << USIC_SCTR_WLE_SHIFT) + /* Transmit Control/Status Register */ -#define USIC_TCSR_ + +#define USIC_TCSR_WLEMD (1 << 0) /* Bit 0: */ +#define USIC_TCSR_SELMD (1 << 1) /* Bit 1: */ +#define USIC_TCSR_FLEMD (1 << 2) /* Bit 2: */ +#define USIC_TCSR_WAMD (1 << 3) /* Bit 3: */ +#define USIC_TCSR_HPCMD (1 << 4) /* Bit 4: */ +#define USIC_TCSR_SOF (1 << 5) /* Bit 5: */ +#define USIC_TCSR_EOF (1 << 6) /* Bit 6: */ +#define USIC_TCSR_TDV (1 << 7) /* Bit 7: */ +#define USIC_TCSR_TDSSM (1 << 8) /* Bit 8: */ +#define USIC_TCSR_TDEN_SHIFT (10) /* Bits 10-11: */ +#define USIC_TCSR_TDEN_MASK (3 << USIC_TCSR_TDEN_SHIFT) +#define USIC_TCSR_TDVTR (1 << 12) /* Bit 12: */ +#define USIC_TCSR_WA (1 << 13) /* Bit 13: */ +#define USIC_TCSR_TSOF (1 << 24) /* Bit 24: */ +#define USIC_TCSR_TV (1 << 26) /* Bit 26: */ +#define USIC_TCSR_TVC (1 << 27) /* Bit 27: */ +#define USIC_TCSR_TE (1 << 28) /* Bit 28: */ + /* Protocol Control Register */ -#define USIC_PCR_ + +#define USIC_PCR_CTR0 (1 << 0) /* Bit 0: */ +#define USIC_PCR_CTR1 (1 << 1) /* Bit 1: */ +#define USIC_PCR_CTR2 (1 << 2) /* Bit 2: */ +#define USIC_PCR_CTR3 (1 << 3) /* Bit 3: */ +#define USIC_PCR_CTR4 (1 << 4) /* Bit 4: */ +#define USIC_PCR_CTR5 (1 << 5) /* Bit 5: */ +#define USIC_PCR_CTR6 (1 << 6) /* Bit 6: */ +#define USIC_PCR_CTR7 (1 << 7) /* Bit 7: */ +#define USIC_PCR_CTR8 (1 << 8) /* Bit 8: */ +#define USIC_PCR_CTR9 (1 << 9) /* Bit 9: */ +#define USIC_PCR_CTR10 (1 << 10) /* Bit 10: */ +#define USIC_PCR_CTR11 (1 << 11) /* Bit 11: */ +#define USIC_PCR_CTR12 (1 << 12) /* Bit 12: */ +#define USIC_PCR_CTR13 (1 << 13) /* Bit 13: */ +#define USIC_PCR_CTR14 (1 << 14) /* Bit 14: */ +#define USIC_PCR_CTR15 (1 << 15) /* Bit 15: */ +#define USIC_PCR_CTR16 (1 << 16) /* Bit 16: */ +#define USIC_PCR_CTR17 (1 << 17) /* Bit 17: */ +#define USIC_PCR_CTR18 (1 << 18) /* Bit 18: */ +#define USIC_PCR_CTR19 (1 << 19) /* Bit 19: */ +#define USIC_PCR_CTR20 (1 << 20) /* Bit 20: */ +#define USIC_PCR_CTR21 (1 << 21) /* Bit 21: */ +#define USIC_PCR_CTR22 (1 << 22) /* Bit 22: */ +#define USIC_PCR_CTR23 (1 << 23) /* Bit 23: */ +#define USIC_PCR_CTR24 (1 << 24) /* Bit 24: */ +#define USIC_PCR_CTR25 (1 << 25) /* Bit 25: */ +#define USIC_PCR_CTR26 (1 << 26) /* Bit 26: */ +#define USIC_PCR_CTR27 (1 << 27) /* Bit 27: */ +#define USIC_PCR_CTR28 (1 << 28) /* Bit 28: */ +#define USIC_PCR_CTR29 (1 << 29) /* Bit 29: */ +#define USIC_PCR_CTR30 (1 << 30) /* Bit 30: */ +#define USIC_PCR_CTR31 (1 << 31) /* Bit 31: */ + +#define USIC_PCR_ASCMODE_SMD (1 << 0) /* Bit 0: */ +#define USIC_PCR_ASCMODE_STPB (1 << 1) /* Bit 1: */ +#define USIC_PCR_ASCMODE_IDM (1 << 2) /* Bit 2: */ +#define USIC_PCR_ASCMODE_SBIEN (1 << 3) /* Bit 3: */ +#define USIC_PCR_ASCMODE_CDEN (1 << 4) /* Bit 4: */ +#define USIC_PCR_ASCMODE_RNIEN (1 << 5) /* Bit 5: */ +#define USIC_PCR_ASCMODE_FEIEN (1 << 6) /* Bit 6: */ +#define USIC_PCR_ASCMODE_FFIEN (1 << 7) /* Bit 7: */ +#define USIC_PCR_ASCMODE_SP_SHIFT (8) /* Bits 8-12: */ +#define USIC_PCR_ASCMODE_SP_MASK (31 << USIC_PCR_ASCMODE_SP_SHIFT) +#define USIC_PCR_ASCMODE_PL_SHIFT (13) /* Bits 13-15: */ +#define USIC_PCR_ASCMODE_PL_MASK (7 << USIC_PCR_ASCMODE_PL_SHIFT) +#define USIC_PCR_ASCMODE_RSTEN (1 << 16) /* Bit 16: */ +#define USIC_PCR_ASCMODE_TSTEN (1 << 17) /* Bit 16: */ +#define USIC_PCR_ASCMODE_MCLK (1 << 31) /* Bit 31: */ + +#define USIC_PCR_SSCMODE_MSLSEN (1 << 0) /* Bit 0: */ +#define USIC_PCR_SSCMODE_SELCTR (1 << 1) /* Bit 1: */ +#define USIC_PCR_SSCMODE_SELINV (1 << 2) /* Bit 2: */ +#define USIC_PCR_SSCMODE_FEM (1 << 3) /* Bit 3: */ +#define USIC_PCR_SSCMODE_CTQSEL1_SHIFT (4) /* Bits 4-5: */ +#define USIC_PCR_SSCMODE_CTQSEL1_MASK (3 << USIC_PCR_SSCMODE_CTQSEL1_SHIFT) +#define USIC_PCR_SSCMODE_PCTQ1_SHIFT (6) /* Bits 6-7: */ +#define USIC_PCR_SSCMODE_PCTQ1_MASK (3 << USIC_PCR_SSCMODE_PCTQ1_SHIFT) +#define USIC_PCR_SSCMODE_DCTQ1_SHIFT (8) /* Bits 8-12: */ +#define USIC_PCR_SSCMODE_DCTQ1_MASK (0x1f << USIC_PCR_SSCMODE_DCTQ1_SHIFT) +#define USIC_PCR_SSCMODE_PARIEN (1 << 13) /* Bit 13: */ +#define USIC_PCR_SSCMODE_MSLSIEN (1 << 14) /* Bit 14: */ +#define USIC_PCR_SSCMODE_DX2TIEN (1 << 15) /* Bit 15: */ +#define USIC_PCR_SSCMODE_SELO_SHIFT (16) /* Bits 16-23: */ +#define USIC_PCR_SSCMODE_SELO_MASK (0xff << USIC_PCR_SSCMODE_SELO_SHIFT) +#define USIC_PCR_SSCMODE_TIWEN (1 << 24) /* Bit 24: */ +#define USIC_PCR_SSCMODE_SLPHSEL (1 << 25) /* Bit 25: */ +#define USIC_PCR_SSCMODE_MCLK (1 << 31) /* Bit 31: */ + +#define USIC_PCR_IICMODE_SLAD_SHIFT (0) /* Bits 0-15: */ +#define USIC_PCR_IICMODE_SLAD_MASK (0xffff << USIC_PCR_IICMODE_SLAD_SHIFT) +#define USIC_PCR_IICMODE_ACK00 (1 << 16) /* Bit 16: */ +#define USIC_PCR_IICMODE_STIM (1 << 17) /* Bit 17: */ +#define USIC_PCR_IICMODE_SCRIEN (1 << 18) /* Bit 18: */ +#define USIC_PCR_IICMODE_RSCRIEN (1 << 19) /* Bit 19: */ +#define USIC_PCR_IICMODE_PCRIEN (1 << 20) /* Bit 20: */ +#define USIC_PCR_IICMODE_NACKIEN (1 << 21) /* Bit 21: */ +#define USIC_PCR_IICMODE_ARLIEN (1 << 22) /* Bit 22: */ +#define USIC_PCR_IICMODE_SRRIEN (1 << 23) /* Bit 23: */ +#define USIC_PCR_IICMODE_ERRIEN (1 << 24) /* Bit 24: */ +#define USIC_PCR_IICMODE_SACKDIS (1 << 25) /* Bit 25: */ +#define USIC_PCR_IICMODE_HDEL_SHIFT (26) /* Bits 26-29: */ +#define USIC_PCR_IICMODE_HDEL_MASK (15 << USIC_PCR_IICMODE_HDEL_SHIFT) +#define USIC_PCR_IICMODE_ACKIEN (1 << 30) /* Bit 30: */ +#define USIC_PCR_IICMODE_MCLK (1 << 31) /* Bit 31: */ + +#define USIC_PCR_IISMODE_WAGEN (1 << 0) /* Bit 0: */ +#define USIC_PCR_IISMODE_DTEN (1 << 1) /* Bit 1: */ +#define USIC_PCR_IISMODE_SELINV (1 << 2) /* Bit 2: */ +#define USIC_PCR_IISMODE_WAFEIEN (1 << 4) /* Bit 4: */ +#define USIC_PCR_IISMODE_WAREIEN (1 << 5) /* Bit 5: */ +#define USIC_PCR_IISMODE_ENDIEN (1 << 6) /* Bit 6: */ +#define USIC_PCR_IISMODE_TDEL_SHIFT (16) /* Bits 15-21: */ +#define USIC_PCR_IISMODE_TDEL_MASK (0x3f << USIC_PCR_IISMODE_TDEL_SHIFT) +#define USIC_PCR_IISMODE_MCLK (1 << 31) /* Bit 31: */ + /* Channel Control Register */ -#define USIC_CCR_ + +#define USIC_CCR_MODE_SHIFT (0) /* Bits 0-3: */ +#define USIC_CCR_MODE_MASK (15 << USIC_CCR_MODE_SHIFT) +#define USIC_CCR_HPCEN_SHIFT (6) /* Bits 6-7: */ +#define USIC_CCR_HPCEN_MASK (3 << USIC_CCR_HPCEN_SHIFT) +#define USIC_CCR_PM_SHIFT (8) /* Bits 8-9: */ +#define USIC_CCR_PM_MASK (3 << USIC_CCR_PM_SHIFT) +#define USIC_CCR_RSIEN (1 << 10) /* Bit 10: */ +#define USIC_CCR_DLIEN (1 << 11) /* Bit 11: */ +#define USIC_CCR_TSIEN (1 << 12) /* Bit 12: */ +#define USIC_CCR_TBIEN (1 << 13) /* Bit 13: */ +#define USIC_CCR_RIEN (1 << 14) /* Bit 14: */ +#define USIC_CCR_AIEN (1 << 15) /* Bit 15: */ +#define USIC_CCR_BRGIEN (1 << 16) /* Bit 16: */ + /* Capture Mode Timer Register */ -#define USIC_CMTR_ + +#define USIC_CMTR_CTV_SHIFT (0) /* Bits 0-9: */ +#define USIC_CMTR_CTV_MASK (0x3ff << USIC_CMTR_CTV_SHIFT) + /* Protocol Status Register */ -#define USIC_PSR_ + +#define USIC_PSR_ST0 (1 << 0) /* Bit 0: */ +#define USIC_PSR_ST1 (1 << 1) /* Bit 1: */ +#define USIC_PSR_ST2 (1 << 2) /* Bit 2: */ +#define USIC_PSR_ST3 (1 << 3) /* Bit 3: */ +#define USIC_PSR_ST4 (1 << 4) /* Bit 4: */ +#define USIC_PSR_ST5 (1 << 5) /* Bit 5: */ +#define USIC_PSR_ST6 (1 << 6) /* Bit 6: */ +#define USIC_PSR_ST7 (1 << 7) /* Bit 7: */ +#define USIC_PSR_ST8 (1 << 8) /* Bit 8: */ +#define USIC_PSR_ST9 (1 << 9) /* Bit 9: */ +#define USIC_PSR_RSIF (1 << 10) /* Bit 10: */ +#define USIC_PSR_DLIF (1 << 11) /* Bit 11: */ +#define USIC_PSR_TSIF (1 << 12) /* Bit 12: */ +#define USIC_PSR_TBIF (1 << 13) /* Bit 13: */ +#define USIC_PSR_RIF (1 << 14) /* Bit 14: */ +#define USIC_PSR_AIF (1 << 15) /* Bit 15: */ +#define USIC_PSR_BRGIF (1 << 16) /* Bit 16: */ + +#define USIC_PSR_ASCMODE_TXIDLE (1 << 0) /* Bit 0: */ +#define USIC_PSR_ASCMODE_RXIDLE (1 << 1) /* Bit 1: */ +#define USIC_PSR_ASCMODE_SBD (1 << 2) /* Bit 2: */ +#define USIC_PSR_ASCMODE_COL (1 << 3) /* Bit 3: */ +#define USIC_PSR_ASCMODE_RNS (1 << 4) /* Bit 4: */ +#define USIC_PSR_ASCMODE_FER0 (1 << 5) /* Bit 5: */ +#define USIC_PSR_ASCMODE_FER1 (1 << 6) /* Bit 6: */ +#define USIC_PSR_ASCMODE_RFF (1 << 7) /* Bit 7: */ +#define USIC_PSR_ASCMODE_TFF (1 << 8) /* Bit 8: */ +#define USIC_PSR_ASCMODE_BUSY (1 << 9) /* Bit 9: */ +#define USIC_PSR_ASCMODE_RSIF (1 << 10) /* Bit 10: */ +#define USIC_PSR_ASCMODE_DLIF (1 << 11) /* Bit 11: */ +#define USIC_PSR_ASCMODE_TSIF (1 << 12) /* Bit 12: */ +#define USIC_PSR_ASCMODE_TBIF (1 << 13) /* Bit 13: */ +#define USIC_PSR_ASCMODE_RIF (1 << 14) /* Bit 14: */ +#define USIC_PSR_ASCMODE_AIF (1 << 15) /* Bit 15: */ +#define USIC_PSR_ASCMODE_BRGIF (1 << 16) /* Bit 16: */ + +#define USIC_PSR_SSCMODE_MSLS (1 << 0) /* Bit 0: */ +#define USIC_PSR_SSCMODE_DX2S (1 << 1) /* Bit 1: */ +#define USIC_PSR_SSCMODE_MSLSEV (1 << 2) /* Bit 2: */ +#define USIC_PSR_SSCMODE_DX2TEV (1 << 3) /* Bit 3: */ +#define USIC_PSR_SSCMODE_PARERR (1 << 4) /* Bit 4: */ +#define USIC_PSR_SSCMODE_RSIF (1 << 10) /* Bit 10: */ +#define USIC_PSR_SSCMODE_DLIF (1 << 11) /* Bit 11: */ +#define USIC_PSR_SSCMODE_TSIF (1 << 12) /* Bit 12: */ +#define USIC_PSR_SSCMODE_TBIF (1 << 13) /* Bit 13: */ +#define USIC_PSR_SSCMODE_RIF (1 << 14) /* Bit 14: */ +#define USIC_PSR_SSCMODE_AIF (1 << 15) /* Bit 15: */ +#define USIC_PSR_SSCMODE_BRGIF (1 << 16) /* Bit 16: */ + +#define USIC_PSR_IICMODE_SLSEL (1 << 0) /* Bit 0: */ +#define USIC_PSR_IICMODE_WTDF (1 << 1) /* Bit 1: */ +#define USIC_PSR_IICMODE_SCR (1 << 2) /* Bit 2: */ +#define USIC_PSR_IICMODE_RSCR (1 << 3) /* Bit 3: */ +#define USIC_PSR_IICMODE_PCR (1 << 4) /* Bit 4: */ +#define USIC_PSR_IICMODE_NACK (1 << 5) /* Bit 5: */ +#define USIC_PSR_IICMODE_ARL (1 << 6) /* Bit 6: */ +#define USIC_PSR_IICMODE_SRR (1 << 7) /* Bit 7: */ +#define USIC_PSR_IICMODE_ERR (1 << 8) /* Bit 8: */ +#define USIC_PSR_IICMODE_ACK (1 << 9) /* Bit 9: */ +#define USIC_PSR_IICMODE_RSIF (1 << 10) /* Bit 10: */ +#define USIC_PSR_IICMODE_DLIF (1 << 11) /* Bit 11: */ +#define USIC_PSR_IICMODE_TSIF (1 << 12) /* Bit 12: */ +#define USIC_PSR_IICMODE_TBIF (1 << 13) /* Bit 13: */ +#define USIC_PSR_IICMODE_RIF (1 << 14) /* Bit 14: */ +#define USIC_PSR_IICMODE_AIF (1 << 15) /* Bit 15: */ +#define USIC_PSR_IICMODE_BRGIF (1 << 16) /* Bit 16: */ + +#define USIC_PSR_IISMODE_WA (1 << 0) /* Bit 0: */ +#define USIC_PSR_IISMODE_DX2S (1 << 1) /* Bit 1: */ +#define USIC_PSR_IISMODE_DX2TEV (1 << 3) /* Bit 3: */ +#define USIC_PSR_IISMODE_WAFE (1 << 4) /* Bit 4: */ +#define USIC_PSR_IISMODE_WARE (1 << 5) /* Bit 5: */ +#define USIC_PSR_IISMODE_END (1 << 6) /* Bit 6: */ +#define USIC_PSR_IISMODE_RSIF (1 << 10) /* Bit 10: */ +#define USIC_PSR_IISMODE_DLIF (1 << 11) /* Bit 11: */ +#define USIC_PSR_IISMODE_TSIF (1 << 12) /* Bit 12: */ +#define USIC_PSR_IISMODE_TBIF (1 << 13) /* Bit 13: */ +#define USIC_PSR_IISMODE_RIF (1 << 14) /* Bit 14: */ +#define USIC_PSR_IISMODE_AIF (1 << 15) /* Bit 15: */ +#define USIC_PSR_IISMODE_BRGIF (1 << 16) /* Bit 16: */ + /* Protocol Status Clear Register */ -#define USIC_PSCR_ + +#define USIC_PSCR_CST0 (1 << 0) /* Bit 0: */ +#define USIC_PSCR_CST1 (1 << 1) /* Bit 1: */ +#define USIC_PSCR_CST2 (1 << 2) /* Bit 2: */ +#define USIC_PSCR_CST3 (1 << 3) /* Bit 3: */ +#define USIC_PSCR_CST4 (1 << 4) /* Bit 4: */ +#define USIC_PSCR_CST5 (1 << 5) /* Bit 5: */ +#define USIC_PSCR_CST6 (1 << 6) /* Bit 6: */ +#define USIC_PSCR_CST7 (1 << 7) /* Bit 7: */ +#define USIC_PSCR_CST8 (1 << 8) /* Bit 8: */ +#define USIC_PSCR_CST9 (1 << 9) /* Bit 9: */ +#define USIC_PSCR_CRSIF (1 << 10) /* Bit 10: */ +#define USIC_PSCR_CDLIF (1 << 11) /* Bit 11: */ +#define USIC_PSCR_CTSIF (1 << 12) /* Bit 12: */ +#define USIC_PSCR_CTBIF (1 << 13) /* Bit 13: */ +#define USIC_PSCR_CRIF (1 << 14) /* Bit 14: */ +#define USIC_PSCR_CAIF (1 << 15) /* Bit 15: */ +#define USIC_PSCR_CBRGIF (1 << 16) /* Bit 16: */ + /* Receiver Buffer Status Register */ -#define USIC_RBUFSR_ + +#define USIC_RBUFSR_WLEN_SHIFT (0) /* Bits 0-3: */ +#define USIC_RBUFSR_WLEN_MASK (15 << USIC_RBUFSR_WLEN_SHIFT) +#define USIC_RBUFSR_SOF (1 << 6) /* Bit 6: */ +#define USIC_RBUFSR_PAR (1 << 8) /* Bit 8: */ +#define USIC_RBUFSR_PERR (1 << 9) /* Bit 9: */ +#define USIC_RBUFSR_RDV0 (1 << 13) /* Bit 13: */ +#define USIC_RBUFSR_RDV1 (1 << 14) /* Bit 14: */ +#define USIC_RBUFSR_DS (1 << 15) /* Bit 15: */ + /* Receiver Buffer Register */ -#define USIC_RBUF_ + +#define USIC_RBUF_DSR_SHIFT (0) /* Bits 0-15: */ +#define USIC_RBUF_DSR_MASK (0xffff << USIC_RBUF_DSR_SHIFT) + /* Receiver Buffer Register for Debugger */ -#define USIC_RBUFD_ + +#define USIC_RBUFD_DSR_SHIFT (0) /* Bits 0-15: */ +#define USIC_RBUFD_DSR_MASK (0xffff << USIC_RBUFD_DSR_SHIFT) + /* Receiver Buffer Register 0 */ -#define USIC_RBUF0_ + +#define USIC_RBUF0_DSR0_SHIFT (0) /* Bits 0-15: */ +#define USIC_RBUF0_DSR0_MASK (0xffff << USIC_RBUF0_DSR0_SHIFT) + /* Receiver Buffer Register 1 */ -#define USIC_RBUF1_ + +#define USIC_RBUF1_DSR1_SHIFT (0) /* Bits 0-15: */ +#define USIC_RBUF1_DSR1_MASK (0xffff << USIC_RBUF1_DSR1_SHIFT) + /* Receiver Buffer 01 Status Register */ -#define USIC_RBUF01SR_ + +#define USIC_RBUF01SR_WLEN0_SHIFT (0) /* Bits 0-3: */ +#define USIC_RBUF01SR_WLEN0_MASK (15 << USIC_RBUF01SR_WLEN0_SHIFT) +#define USIC_RBUF01SR_SOF0 (1 << 6) /* Bit 6: */ +#define USIC_RBUF01SR_PAR0 (1 << 8) /* Bit 8: */ +#define USIC_RBUF01SR_PERR0 (1 << 9) /* Bit 9: */ +#define USIC_RBUF01SR_RDV00 (1 << 13) /* Bit 13: */ +#define USIC_RBUF01SR_RDV01 (1 << 14) /* Bit 14: */ +#define USIC_RBUF01SR_DS0 (1 << 15) /* Bit 15: */ +#define USIC_RBUF01SR_WLEN1_SHIFT (16) /* Bits 16-19: */ +#define USIC_RBUF01SR_WLEN1_MASK (15 << USIC_RBUF01SR_WLEN1_SHIFT) +#define USIC_RBUF01SR_SOF1 (1 << 22) /* Bit 22: */ +#define USIC_RBUF01SR_PAR1 (1 << 24) /* Bit 24: */ +#define USIC_RBUF01SR_PERR1 (1 << 25) /* Bit 25: */ +#define USIC_RBUF01SR_RDV10 (1 << 29) /* Bit 29: */ +#define USIC_RBUF01SR_RDV11 (1 << 30) /* Bit 30: */ +#define USIC_RBUF01SR_DS1 (1 << 31) /* Bit 31: */ + /* Flag Modification Register */ -#define USIC_FMR_ + +#define USIC_FMR_MTDV_SHIFT (0) /* Bits 0-1: */ +#define USIC_FMR_MTDV_MASK (3 << USIC_FMR_MTDV_SHIFT) +#define USIC_FMR_ATVC (1 << 4) /* Bit 4: */ +#define USIC_FMR_CRDV0 (1 << 14) /* Bit 14: */ +#define USIC_FMR_CRDV1 (1 << 15) /* Bit 15: */ +#define USIC_FMR_SIO0 (1 << 16) /* Bit 16: */ +#define USIC_FMR_SIO1 (1 << 17) /* Bit 17: */ +#define USIC_FMR_SIO2 (1 << 18) /* Bit 18: */ +#define USIC_FMR_SIO3 (1 << 19) /* Bit 19: */ +#define USIC_FMR_SIO4 (1 << 20) /* Bit 20: */ +#define USIC_FMR_SIO5 (1 << 21) /* Bit 21: */ + /* Transmit Buffer (32 x 4-bytes) */ -#define USIC_TBUF_ + +#define USIC_TBUF_TDATA_SHIFT (0) /* Bits 0-15: */ +#define USIC_TBUF_TDATA_MASK (0xffff << USIC_TBUF_TDATA_SHIFT) /* USIC FIFO Registers */ /* Bypass Data Register */ -#define USIC_BYP_ + +#define USIC_BYP_BDATA_SHIFT (0) /* Bits 0-15: */ +#define USIC_BYP_BDATA_MASK (0xffff << USIC_BYP_BDATA_SHIFT) + /* Bypass Control Register */ -#define USIC_BYPCR_ + +#define USIC_BYPCR_BWLE_SHIFT (0) /* Bits 0-3: */ +#define USIC_BYPCR_BWLE_MASK (15 << USIC_BYPCR_BWLE_SHIFT) +#define USIC_BYPCR_BDSSM (1 << 8) /* Bit 8: */ +#define USIC_BYPCR_BDEN_SHIFT (10) /* Bits 10-11: */ +#define USIC_BYPCR_BDEN_MASK (3 << USIC_BYPCR_BDEN_SHIFT) +#define USIC_BYPCR_BDVTR (1 << 12) /* Bit 12: */ +#define USIC_BYPCR_BPRIO (1 << 13) /* Bit 13: */ +#define USIC_BYPCR_BDV (1 << 15) /* Bit 15: */ +#define USIC_BYPCR_BSELO_SHIFT (16) /* Bits 16-20: */ +#define USIC_BYPCR_BSELO_MASK (31 << USIC_BYPCR_BSELO_SHIFT) +#define USIC_BYPCR_BHPC_SHIFT (21) /* Bits 21-23: */ +#define USIC_BYPCR_BHPC_MASK (7 << USIC_BYPCR_BHPC_SHIFT) + /* Transmitter Buffer Control Register */ -#define USIC_TBCTR_ + +#define USIC_TBCTR_DPTR_SHIFT (0) /* Bits 0-1: */ +#define USIC_TBCTR_DPTR_MASK (3 << USIC_TBCTR_DPTR_SHIFT) +#define USIC_TBCTR_LIMIT_SHIFT (8) /* Bits 8-13: */ +#define USIC_TBCTR_LIMIT_MASK (0x3f << USIC_TBCTR_LIMIT_SHIFT) +#define USIC_TBCTR_STBTM (1 << 14) /* Bit 14: */ +#define USIC_TBCTR_STBTEN (1 << 15) /* Bit 15: */ +#define USIC_TBCTR_STBINP_SHIFT (16) /* Bits 16-18: */ +#define USIC_TBCTR_STBINP_MASK (7 << USIC_TBCTR_STBINP_SHIFT) +#define USIC_TBCTR_ATBINP_SHIFT (19) /* Bits 19-21: */ +#define USIC_TBCTR_ATBINP_MASK (7 << USIC_TBCTR_ATBINP_SHIFT) +#define USIC_TBCTR_SIZE_SHIFT (24) /* Bits 24-26: */ +#define USIC_TBCTR_SIZE_MASK (7 << USIC_TBCTR_SIZE_SHIFT) +#define USIC_TBCTR_LOF (1 << 28) /* Bit 28: */ +#define USIC_TBCTR_STBIEN (1 << 30) /* Bit 30: */ +#define USIC_TBCTR_TBERIEN (1 << 31) /* Bit 31: */ + /* Receiver Buffer Control Register */ -#define USIC_RBCTR_ + +#define USIC_RBCTR_DPTR_SHIFT (0) /* Bits 0-5: */ +#define USIC_RBCTR_DPTR_MASK (0x3f << USIC_RBCTR_DPTR_SHIFT) +#define USIC_RBCTR_LIMIT_SHIFT (8) /* Bits 8-13: */ +#define USIC_RBCTR_LIMIT_MASK (0x3f << USIC_RBCTR_LIMIT_SHIFT) +#define USIC_RBCTR_SRBTM (1 << 14) /* Bit 14: */ +#define USIC_RBCTR_SRBTEN (1 << 15) /* Bit 15: */ +#define USIC_RBCTR_SRBINP_SHIFT (16) /* Bits 16-18: */ +#define USIC_RBCTR_SRBINP_MASK (7 << USIC_RBCTR_SRBINP_SHIFT) +#define USIC_RBCTR_ARBINP_SHIFT (19) /* Bits 19-21: */ +#define USIC_RBCTR_ARBINP_MASK (7 << USIC_RBCTR_ARBINP_SHIFT) +#define USIC_RBCTR_RCIM_SHIFT (22) /* Bits 22-23: */ +#define USIC_RBCTR_RCIM_MASK (3 << USIC_RBCTR_RCIM_SHIFT) +#define USIC_RBCTR_SIZE_SHIFT (24) /* Bits 24-26: */ +#define USIC_RBCTR_SIZE_MASK (7 << USIC_RBCTR_SIZE_SHIFT) +#define USIC_RBCTR_RNM (1 << 27) /* Bit 27: */ +#define USIC_RBCTR_LOF (1 << 28) /* Bit 28: */ +#define USIC_RBCTR_ARBIEN (1 << 29) /* Bit 29: */ +#define USIC_RBCTR_SRBIEN (1 << 30) /* Bit 30: */ +#define USIC_RBCTR_RBERIEN (1 << 31) /* Bit 31: */ + /* Transmit/Receive Buffer Pointer Register */ -#define USIC_TRBPTR_ + +#define USIC_TRBPTR_TDIPTR_SHIFT (0) /* Bits 0-5: */ +#define USIC_TRBPTR_TDIPTR_MASK (0x3f << USIC_TRBPTR_TDIPTR_SHIFT) +#define USIC_TRBPTR_TDOPTR_SHIFT (8) /* Bits 813xx: */ +#define USIC_TRBPTR_TDOPTR_MASK (0x3f << USIC_TRBPTR_TDOPTR_SHIFT) +#define USIC_TRBPTR_RDIPTR_SHIFT (16) /* Bits 16-21: */ +#define USIC_TRBPTR_RDIPTR_MASK (0x3f << USIC_TRBPTR_RDIPTR_SHIFT) +#define USIC_TRBPTR_RDOPTR_SHIFT (24) /* Bits 24-29: */ +#define USIC_TRBPTR_RDOPTR_MASK (0x3f << USIC_TRBPTR_RDOPTR_SHIFT) + /* Transmit/Receive Buffer Status Register */ -#define USIC_TRBSR_ + +#define USIC_TRBSR_SRBI (1 << 0) /* Bit 0: */ +#define USIC_TRBSR_RBERI (1 << 1) /* Bit 1: */ +#define USIC_TRBSR_ARBI (1 << 2) /* Bit 2: */ +#define USIC_TRBSR_REMPTY (1 << 3) /* Bit 3: */ +#define USIC_TRBSR_RFULL (1 << 4) /* Bit 4: */ +#define USIC_TRBSR_RBUS (1 << 5) /* Bit 5: */ +#define USIC_TRBSR_SRBT (1 << 6) /* Bit 6: */ +#define USIC_TRBSR_STBI (1 << 8) /* Bit 8: */ +#define USIC_TRBSR_TBERI (1 << 9) /* Bit 9: */ +#define USIC_TRBSR_TEMPTY (1 << 11) /* Bit 11: */ +#define USIC_TRBSR_TFULL (1 << 12) /* Bit 12: */ +#define USIC_TRBSR_TBUS (1 << 13) /* Bit 13: */ +#define USIC_TRBSR_STBT (1 << 14) /* Bit 14: */ +#define USIC_TRBSR_RBFLVL_SHIFT (16) /* Bits 16-22: */ +#define USIC_TRBSR_RBFLVL_MASK (0x7f << USIC_TRBSR_RBFLVL_SHIFT) +#define USIC_TRBSR_TBFLVL_SHIFT (24) /* Bits 22-28: */ +#define USIC_TRBSR_TBFLVL_MASK (0x7f << USIC_TRBSR_TBFLVL_SHIFT) + /* Transmit/Receive Buffer Status Clear Register */ -#define USIC_TRBSCR_ + +#define USIC_TRBSCR_CSRBI (1 << 0) /* Bit 0: */ +#define USIC_TRBSCR_CRBERI (1 << 1) /* Bit 1: */ +#define USIC_TRBSCR_CARBI (1 << 2) /* Bit 2: */ +#define USIC_TRBSCR_CSTBI (1 << 8) /* Bit 8: */ +#define USIC_TRBSCR_CTBERI (1 << 9) /* Bit 9: */ +#define USIC_TRBSCR_CBDV (1 << 10) /* Bit 10: */ +#define USIC_TRBSCR_FLUSHRB (1 << 14) /* Bit 14: */ +#define USIC_TRBSCR_FLUSHTB (1 << 15) /* Bit 15: */ + /* Receiver Buffer Output Register */ -#define USIC_OUTR_ + +#define USIC_OUTR_DSR_SHIFT (0) /* Bits 0-15: */ +#define USIC_OUTR_DSR_MASK (0xffff << USIC_OUTR_DSR_SHIFT) +#define USIC_OUTR_RCI_SHIFT (16) /* Bits 16-20: */ +#define USIC_OUTR_RCI_MASK (31 << USIC_OUTR_RCI_SHIFT) + /* Receiver Buffer Output Register L for Debugger */ -#define USIC_OUTDR_ + +#define USIC_OUTDR_DSR_SHIFT (0) /* Bits 0-15: */ +#define USIC_OUTDR_DSR_MASK (0xffff << USIC_OUTDR_DSR_SHIFT) +#define USIC_OUTDR_RCI_SHIFT (16) /* Bits 16-30: */ +#define USIC_OUTDR_RCI_MASK (31 << USIC_OUTDR_RCI_SHIFT) + /* Transmit FIFO Buffer (32 x 4-bytes) */ -#define USIC_IN_ + +#define USIC_IN_TDATA_SHIFT (0) /* Bits 0-15: */ +#define USIC_IN_TDATA_MASK (0xffff << USIC_IN_TDATA_SHIFT) #endif /* __ARCH_ARM_SRC_XMC4_CHIP_XMC4_USIC_H */ -- GitLab From 9110b7d45c799ec4acb191eafc03dc8f6da9f722 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 19 Mar 2017 08:44:28 -0600 Subject: [PATCH 100/990] XMC4xxxx: Add more definitions to USIC register definition header. --- arch/arm/src/xmc4/chip/xmc4_usic.h | 521 +++++++++++++++++------------ 1 file changed, 314 insertions(+), 207 deletions(-) diff --git a/arch/arm/src/xmc4/chip/xmc4_usic.h b/arch/arm/src/xmc4/chip/xmc4_usic.h index 8d204fcf8c..d6d5299cbd 100644 --- a/arch/arm/src/xmc4/chip/xmc4_usic.h +++ b/arch/arm/src/xmc4/chip/xmc4_usic.h @@ -400,150 +400,231 @@ /* Channel Configuration Register */ -#define USIC_CCFG_SSC (1 << 0) /* Bit 0: */ -#define USIC_CCFG_ASC (1 << 1) /* Bit 1: */ -#define USIC_CCFG_IIC (1 << 2) /* Bit 2: */ -#define USIC_CCFG_IIS (1 << 3) /* Bit 3: */ -#define USIC_CCFG_RB (1 << 6) /* Bit 6: */ -#define USIC_CCFG_TB (1 << 7) /* Bit 7: */ +#define USIC_CCFG_SSC (1 << 0) /* Bit 0: SSC Protocol Available */ +#define USIC_CCFG_ASC (1 << 1) /* Bit 1: ASC Protocol Available */ +#define USIC_CCFG_I2C (1 << 2) /* Bit 2: IIC Protocol Available */ +#define USIC_CCFG_I2S (1 << 3) /* Bit 3: IIS Protocol Available */ +#define USIC_CCFG_RB (1 << 6) /* Bit 6: Receive FIFO Buffer Available */ +#define USIC_CCFG_TB (1 << 7) /* Bit 7: Transmit FIFO Buffer Available */ /* Kernel State Configuration Register */ -#define USIC_KSCFG_MODEN (1 << 0) /* Bit 0: */ -#define USIC_KSCFG_BPMODEN (1 << 1) /* Bit 1: */ -#define USIC_KSCFG_NOMCFG_SHIFT (4) /* Bits 4-5: */ +#define USIC_KSCFG_MODEN (1 << 0) /* Bit 0: Module Enable */ +#define USIC_KSCFG_BPMODEN (1 << 1) /* Bit 1: Bit Protection for MODEN */ +#define USIC_KSCFG_NOMCFG_SHIFT (4) /* Bits 4-5: Normal Operation Mode Configuration */ #define USIC_KSCFG_NOMCFG_MASK (3 << USIC_KSCFG_NOMCFG_SHIFT) -#define USIC_KSCFG_BPNOM (1 << 7) /* Bit 7: */ -#define USIC_KSCFG_SUMCFG_SHIFT (8) /* Bits 8-9: */ +# define USIC_KSCFG_NOMCFG_RUN0 (0 << USIC_KSCFG_NOMCFG_SHIFT) /* Run mode 0 selected */ +# define USIC_KSCFG_NOMCFG_RUN1 (1 << USIC_KSCFG_NOMCFG_SHIFT) /* Run mode 1 selected */ +# define USIC_KSCFG_NOMCFG_STOP0 (2 << USIC_KSCFG_NOMCFG_SHIFT) /* Stop mode 0 selected */ +# define USIC_KSCFG_NOMCFG_STOP1 (3 << USIC_KSCFG_NOMCFG_SHIFT) /* Stop mode 1 selected */ +#define USIC_KSCFG_BPNOM (1 << 7) /* Bit 7: Bit Protection for NOMCFG */ +#define USIC_KSCFG_SUMCFG_SHIFT (8) /* Bits 8-9: Suspend Mode Configuration */ #define USIC_KSCFG_SUMCFG_MASK (3 << USIC_KSCFG_SUMCFG_SHIFT) -#define USIC_KSCFG_BPSUM (1 << 11) /* Bit 11: */ +# define USIC_KSCFG_SUMCFG_RUN0 (0 << USIC_KSCFG_SUMCFG_SHIFT) /* Run mode 0 selected */ +# define USIC_KSCFG_SUMCFG_RUN1 (1 << USIC_KSCFG_SUMCFG_SHIFT) /* Run mode 1 selected */ +# define USIC_KSCFG_SUMCFG_STOP0 (2 << USIC_KSCFG_SUMCFG_SHIFT) /* Stop mode 0 selected */ +# define USIC_KSCFG_SUMCFG_STOP1 (3 << USIC_KSCFG_SUMCFG_SHIFT) /* Stop mode 1 selected */ +#define USIC_KSCFG_BPSUM (1 << 11) /* Bit 11: Bit Protection for SUMCFG */ /* Fractional Divider Register */ -#define USIC_FDR_STEP_SHIFT (0) /* Bits 0-9: */ +#define USIC_FDR_STEP_SHIFT (0) /* Bits 0-9: Step Value */ #define USIC_FDR_STEP_MASK (0x3ff << USIC_FDR_STEP_SHIFT) -#define USIC_FDR_DM_SHIFT (14) /* Bits 14-15: */ +# define USIC_FDR_STEP(n) ((uint32_t)(n) << USIC_FDR_STEP_SHIFT) +#define USIC_FDR_DM_SHIFT (14) /* Bits 14-15: Divider Mode */ #define USIC_FDR_DM_MASK (3 << USIC_FDR_DM_SHIFT) -#define USIC_FDR_RESULT_SHIFT (16) /* Bits 16-25: */ +# define USIC_FDR_DM_ OFF (0 << USIC_FDR_DM_SHIFT) /* Divider switched off */ +# define USIC_FDR_DM_ NORMAL (1 << USIC_FDR_DM_SHIFT) /* Normal divider mode selected */ +# define USIC_FDR_DM_ FRACTIONAL (2 << USIC_FDR_DM_SHIFT) /* Fractional divider mode selected */ +#define USIC_FDR_RESULT_SHIFT (16) /* Bits 16-25: Result Value */ #define USIC_FDR_RESULT_MASK (0x3ff << USIC_FDR_RESULT_SHIFT) /* Baud Rate Generator Register */ -#define USIC_BRG_CLKSEL_SHIFT (0) /* Bits 0-1: */ +#define USIC_BRG_CLKSEL_SHIFT (0) /* Bits 0-1: Clock Selection */ #define USIC_BRG_CLKSEL_MASK (3 << USIC_BRG_CLKSEL_SHIFT) -#define USIC_BRG_TMEN (1 << 3) /* Bit 3: */ -#define USIC_BRG_PPPEN (1 << 4) /* Bit 4: */ -#define USIC_BRG_CTQSEL_SHIFT (6) /* Bits 6-7: */ +# define USIC_BRG_CLKSEL_FRAC (0 << USIC_BRG_CLKSEL_SHIFT) /* Fractional divider frequency fFD */ +# define USIC_BRG_CLKSEL_DX1T (2 << USIC_BRG_CLKSEL_SHIFT) /* Trigger signal DX1T defines fPIN */ +# define USIC_BRG_CLKSEL_DX1S (3 << USIC_BRG_CLKSEL_SHIFT) /* Frequency fPIN is derived from DX1S */ +#define USIC_BRG_TMEN (1 << 3) /* Bit 3: Timing Measurement Enable */ +#define USIC_BRG_PPPEN (1 << 4) /* Bit 4: Enable 2:1 Divider for fPPP */ +#define USIC_BRG_CTQSEL_SHIFT (6) /* Bits 6-7: Input Selection for CTQ */ #define USIC_BRG_CTQSEL_MASK (3 << USIC_BRG_CTQSEL_SHIFT) -#define USIC_BRG_PCTQ_SHIFT (8) /* Bits 8-9: */ +# define USIC_BRG_CTQSEL_FPDIV (0 << USIC_BRG_CTQSEL_SHIFT) /* fCTQIN = fPDIV */ +# define USIC_BRG_CTQSEL_FPPP (1 << USIC_BRG_CTQSEL_SHIFT) /* fCTQIN = fPPP */ +# define USIC_BRG_CTQSEL_FSCLK (2 << USIC_BRG_CTQSEL_SHIFT) /* fCTQIN = fSCLK */ +# define USIC_BRG_CTQSEL_FMCLK (3 << USIC_BRG_CTQSEL_SHIFT) /* fCTQIN = fMCLK */ +#define USIC_BRG_PCTQ_SHIFT (8) /* Bits 8-9: Pre-Divider for Time Quanta Counter */ #define USIC_BRG_PCTQ_MASK (3 << USIC_BRG_PCTQ_SHIFT) -#define USIC_BRG_DCTQ_SHIFT (10) /* Bits 10-15: */ +# define USIC_BRG_PCTQ(n) ((uint32_t)((n)-1) << USIC_BRG_PCTQ_SHIFT) +#define USIC_BRG_DCTQ_SHIFT (10) /* Bits 10-15: Denominator for Time Quanta Counter */ #define USIC_BRG_DCTQ_MASK (0x3f << USIC_BRG_DCTQ_SHIFT) -#define USIC_BRG_PDIV_SHIFT (16) /* Bits 16-25: */ +# define USIC_BRG_DCTQ(n) ((uint32_t)(n) << USIC_BRG_DCTQ_SHIFT) +#define USIC_BRG_PDIV_SHIFT (16) /* Bits 16-25: Divider Mode: Divider Factor to Generate fPDIV */ #define USIC_BRG_PDIV_MASK (0x3ff << USIC_BRG_PDIV_SHIFT) -#define USIC_BRG_SCLKOSEL (1 << 28) /* Bit 28: */ -#define USIC_BRG_MCLKCFG (1 << 29) /* Bit 29: */ -#define USIC_BRG_SCLKCFG (1 << 30) /* Bit 30: */ +# define USIC_BRG_PDIV(n) ((uint32_t)(n) << USIC_BRG_PDIV_SHIFT) +#define USIC_BRG_SCLKOSEL (1 << 28) /* Bit 28: Shift Clock Output Select */ +#define USIC_BRG_MCLKCFG (1 << 29) /* Bit 29: Master Clock Configuration */ +#define USIC_BRG_SCLKCFG (1 << 30) /* Bit 30: Shift Clock Output Configuration */ /* Interrupt Node Pointer Register */ -#define USIC_INPR_TSINP_SHIFT (0) /* Bits 0-2: */ +#define USIC_INPR_TSINP_SHIFT (0) /* Bits 0-2: Transmit Shift Interrupt Node Pointer */ #define USIC_INPR_TSINP_MASK (7 << USIC_INPR_TSINP_SHIFT) -#define USIC_INPR_TBINP_SHIFT (4) /* Bits 4-6: */ +# define USIC_INPR_TSINP_SR0 (0 << USIC_INPR_TSINP_SHIFT) /* Output SR0 activated */ +# define USIC_INPR_TSINP_SR1 (1 << USIC_INPR_TSINP_SHIFT) /* Output SR1 activated */ +# define USIC_INPR_TSINP_SR2 (2 << USIC_INPR_TSINP_SHIFT) /* Output SR2 activated */ +# define USIC_INPR_TSINP_SR3 (3 << USIC_INPR_TSINP_SHIFT) /* Output SR3 activated */ +# define USIC_INPR_TSINP_SR4 (4 << USIC_INPR_TSINP_SHIFT) /* Output SR4 activated */ +# define USIC_INPR_TSINP_SR5 (5 << USIC_INPR_TSINP_SHIFT) /* Output SR5 activated */ +#define USIC_INPR_TBINP_SHIFT (4) /* Bits 4-6: Transmit Buffer Interrupt Node Poi */ #define USIC_INPR_TBINP_MASK (7 << USIC_INPR_TBINP_SHIFT) -#define USIC_INPR_RINP_SHIFT (8) /* Bits 8-10: */ +# define USIC_INPR_TBINP_SR0 (0 << USIC_INPR_TBINP_SHIFT) /* Output SR0 activated */ +# define USIC_INPR_TBINP_SR1 (1 << USIC_INPR_TBINP_SHIFT) /* Output SR1 activated */ +# define USIC_INPR_TBINP_SR2 (2 << USIC_INPR_TBINP_SHIFT) /* Output SR2 activated */ +# define USIC_INPR_TBINP_SR3 (3 << USIC_INPR_TBINP_SHIFT) /* Output SR3 activated */ +# define USIC_INPR_TBINP_SR4 (4 << USIC_INPR_TBINP_SHIFT) /* Output SR4 activated */ +# define USIC_INPR_TBINP_SR5 (5 << USIC_INPR_TBINP_SHIFT) /* Output SR5 activated */ +#define USIC_INPR_RINP_SHIFT (8) /* Bits 8-10: Receive Interrupt Node Pointer */ #define USIC_INPR_RINP_MASK (7 << USIC_INPR_RINP_SHIFT) -#define USIC_INPR_AINP_SHIFT (12) /* Bits 12-14: */ +# define USIC_INPR_RINP_SR0 (0 << USIC_INPR_RINP_SHIFT) /* Output SR0 activated */ +# define USIC_INPR_RINP_SR1 (1 << USIC_INPR_RINP_SHIFT) /* Output SR1 activated */ +# define USIC_INPR_RINP_SR2 (2 << USIC_INPR_RINP_SHIFT) /* Output SR2 activated */ +# define USIC_INPR_RINP_SR3 (3 << USIC_INPR_RINP_SHIFT) /* Output SR3 activated */ +# define USIC_INPR_RINP_SR4 (4 << USIC_INPR_RINP_SHIFT) /* Output SR4 activated */ +# define USIC_INPR_RINP_SR5 (5 << USIC_INPR_RINP_SHIFT) /* Output SR5 activated */ +#define USIC_INPR_AINP_SHIFT (12) /* Bits 12-14: Alternative Receive Interrupt Node Pointer */ #define USIC_INPR_AINP_MASK (7 << USIC_INPR_AINP_SHIFT) -#define USIC_INPR_PINP_SHIFT (16) /* Bits 16-18: */ +# define USIC_INPR_AINP_SR0 (0 << USIC_INPR_AINP_SHIFT) /* Output SR0 activated */ +# define USIC_INPR_AINP_SR1 (1 << USIC_INPR_AINP_SHIFT) /* Output SR1 activated */ +# define USIC_INPR_AINP_SR2 (2 << USIC_INPR_AINP_SHIFT) /* Output SR2 activated */ +# define USIC_INPR_AINP_SR3 (3 << USIC_INPR_AINP_SHIFT) /* Output SR3 activated */ +# define USIC_INPR_AINP_SR4 (4 << USIC_INPR_AINP_SHIFT) /* Output SR4 activated */ +# define USIC_INPR_AINP_SR5 (5 << USIC_INPR_AINP_SHIFT) /* Output SR5 activated */ +#define USIC_INPR_PINP_SHIFT (16) /* Bits 16-18: Protocol Interrupt Node Pointer */ #define USIC_INPR_PINP_MASK (7 << USIC_INPR_PINP_SHIFT) +# define USIC_INPR_PINP_SR0 (0 << USIC_INPR_PINP_SHIFT) /* Output SR0 activated */ +# define USIC_INPR_PINP_SR1 (1 << USIC_INPR_PINP_SHIFT) /* Output SR1 activated */ +# define USIC_INPR_PINP_SR2 (2 << USIC_INPR_PINP_SHIFT) /* Output SR2 activated */ +# define USIC_INPR_PINP_SR3 (3 << USIC_INPR_PINP_SHIFT) /* Output SR3 activated */ +# define USIC_INPR_PINP_SR4 (4 << USIC_INPR_PINP_SHIFT) /* Output SR4 activated */ +# define USIC_INPR_PINP_SR5 (5 << USIC_INPR_PINP_SHIFT) /* Output SR5 activated */ /* Input Control Register 0, Input Control Register 1, Input Control Register 2, * Input Control Register 3, Input Control Register 4, Input Control Register 5 */ -#define USIC_DXCR_DSEL_SHIFT (0) /* Bits 0-2: */ +#define USIC_DXCR_DSEL_SHIFT (0) /* Bits 0-2: Data Selection for Input Signal */ #define USIC_DXCR_DSEL_MASK (7 << USIC_DX0CR_DSEL_SHIFT) -#define USIC_DX1CR_DCEN (1 << 3) /* Bit 3: (DX1CR only) */ -#define USIC_DXCR_INSW (1 << 4) /* Bit 4: */ -#define USIC_DXCR_DFEN (1 << 5) /* Bit 5: */ -#define USIC_DXCR_DSEN (1 << 6) /* Bit 6: */ -#define USIC_DXCR_DPOL (1 << 8) /* Bit 8: */ -#define USIC_DXCR_SFSEL (1 << 9) /* Bit 9: */ -#define USIC_DXCR_CM_SHIFT (10) /* Bits 10-12: */ +# define USIC_DXCR_DSEL_DXA (0 << USIC_DX0CR_DSEL_SHIFT) /* Data input DXnA selected */ +# define USIC_DXCR_DSEL_DXB (1 << USIC_DX0CR_DSEL_SHIFT) /* Data input DXnB selected */ +# define USIC_DXCR_DSEL_DXC (2 << USIC_DX0CR_DSEL_SHIFT) /* Data input DXnC selected */ +# define USIC_DXCR_DSEL_DXD (3 << USIC_DX0CR_DSEL_SHIFT) /* Data input DXnD selected */ +# define USIC_DXCR_DSEL_DXE (4 << USIC_DX0CR_DSEL_SHIFT) /* Data input DXnE selected */ +# define USIC_DXCR_DSEL_DXF (5 << USIC_DX0CR_DSEL_SHIFT) /* Data input DXnF selected */ +# define USIC_DXCR_DSEL_DXG (6 << USIC_DX0CR_DSEL_SHIFT) /* Data input DXnG selected */ +# define USIC_DXCR_DSEL_ONE (7 << USIC_DX0CR_DSEL_SHIFT) /* Data input is always 1 */ +#define USIC_DX1CR_DCEN (1 << 3) /* Bit 3: Delay Compensation Enable (DX1CR only) */ +#define USIC_DXCR_INSW (1 << 4) /* Bit 4: Input Switch */ +#define USIC_DXCR_DFEN (1 << 5) /* Bit 5: Digital Filter Enable */ +#define USIC_DXCR_DSEN (1 << 6) /* Bit 6: Data Synchronization Enable */ +#define USIC_DXCR_DPOL (1 << 8) /* Bit 8: Data Polarity for DXn */ +#define USIC_DXCR_SFSEL (1 << 9) /* Bit 9: Sampling Frequency Selection */ +#define USIC_DXCR_CM_SHIFT (10) /* Bits 10-11: Combination Mode */ #define USIC_DXCR_CM_MASK (3 << USIC_DX0CR_CM_SHIFT) +# define USIC_DXCR_CM_DISABLE (0 << USIC_DX0CR_CM_SHIFT) /* Trigger activation disabled */ +# define USIC_DXCR_CM_RISING (1 << USIC_DX0CR_CM_SHIFT) /* Rising edge activates DXnT */ +# define USIC_DXCR_CM_FALLING (2 << USIC_DX0CR_CM_SHIFT) /* Falling edge activates DXnT */ +# define USIC_DXCR_CM_BOTH (3 << USIC_DX0CR_CM_SHIFT) /* Both edges activate DXnT */ + #define USIC_DXCR_DXS (1 << 15) /* Bit 15: */ /* Shift Control Register */ -#define USIC_SCTR_SDIR (1 << 0) /* Bit 0: */ -#define USIC_SCTR_PDL (1 << 1) /* Bit `: */ -#define USIC_SCTR_DSM_SHIFT (2) /* Bits 2-3: */ +#define USIC_SCTR_SDIR (1 << 0) /* Bit 0: Shift Direction */ +#define USIC_SCTR_PDL (1 << 1) /* Bit 1: Passive Data Level */ +#define USIC_SCTR_DSM_SHIFT (2) /* Bits 2-3: Data Shift Mode */ #define USIC_SCTR_DSM_MASK (3 << USIC_SCTR_DSM_SHIFT) -#define USIC_SCTR_HPCDIR (1 << 4) /* Bit 4: */ -#define USIC_SCTR_DOCFG_SHIFT (6) /* Bits 6-7: */ +# define USIC_SCTR_DSM_1BIT (0 << USIC_SCTR_DSM_SHIFT) /* Data is shifted one bit at a time */ +# define USIC_SCTR_DSM_2BITS (2 << USIC_SCTR_DSM_SHIFT) /* Data is shifted two bits at a time */ +# define USIC_SCTR_DSM_4BITS (3 << USIC_SCTR_DSM_SHIFT) /* Data is shifted four bits at a time */ +#define USIC_SCTR_HPCDIR (1 << 4) /* Bit 4: Port Control Direction */ +#define USIC_SCTR_DOCFG_SHIFT (6) /* Bits 6-7: Data Output Configuration */ #define USIC_SCTR_DOCFG_MASK (3 << USIC_SCTR_DOCFG_SHIFT) -#define USIC_SCTR_TRM_SHIFT (8) /* Bits 8-9: */ + #define USIC_SCTR_DOCFG_SHIFT (0 << USIC_SCTR_DOCFG_SHIFT) /* DOUTx = shift data value */ + #define USIC_SCTR_DOCFG_INVERT (1 << USIC_SCTR_DOCFG_SHIFT) /* DOUTx = inverted shift data value */ +#define USIC_SCTR_TRM_SHIFT (8) /* Bits 8-9: Transmission Mode */ #define USIC_SCTR_TRM_MASK (3 << USIC_SCTR_TRM_SHIFT) -#define USIC_SCTR_FLE_SHIFT (16) /* Bits 16-21: */ +# define USIC_SCTR_TRM_INACTIVE (0 << USIC_SCTR_TRM_SHIFT) /* Inactive */ +# define USIC_SCTR_TRM_0LEVEL (1 << USIC_SCTR_TRM_SHIFT) /* Active at 1-level */ +# define USIC_SCTR_TRM_1LEVEL (2 << USIC_SCTR_TRM_SHIFT) /* Active if it is at 0-level */ +# define USIC_SCTR_TRM_ACTIVE (3 << USIC_SCTR_TRM_SHIFT) /* Active without regard to signal level */ +#define USIC_SCTR_FLE_SHIFT (16) /* Bits 16-21: Frame Length */ #define USIC_SCTR_FLE_MASK (0x3f << USIC_SCTR_FLE_SHIFT) -#define USIC_SCTR_WLE_SHIFT (24) /* Bits 24-27: */ +# define USIC_SCTR_FLE(n) ((uint32_t)(n) << USIC_SCTR_FLE_SHIFT) +#define USIC_SCTR_WLE_SHIFT (24) /* Bits 24-27: Word Length */ #define USIC_SCTR_WLE_MASK (15 << USIC_SCTR_WLE_SHIFT) +# define USIC_SCTR_WLE(n) ((uint32_t)((n)-1) << USIC_SCTR_WLE_SHIFT) /* Transmit Control/Status Register */ -#define USIC_TCSR_WLEMD (1 << 0) /* Bit 0: */ -#define USIC_TCSR_SELMD (1 << 1) /* Bit 1: */ -#define USIC_TCSR_FLEMD (1 << 2) /* Bit 2: */ -#define USIC_TCSR_WAMD (1 << 3) /* Bit 3: */ -#define USIC_TCSR_HPCMD (1 << 4) /* Bit 4: */ -#define USIC_TCSR_SOF (1 << 5) /* Bit 5: */ -#define USIC_TCSR_EOF (1 << 6) /* Bit 6: */ -#define USIC_TCSR_TDV (1 << 7) /* Bit 7: */ -#define USIC_TCSR_TDSSM (1 << 8) /* Bit 8: */ -#define USIC_TCSR_TDEN_SHIFT (10) /* Bits 10-11: */ +#define USIC_TCSR_WLEMD (1 << 0) /* Bit 0: WLE Mode */ +#define USIC_TCSR_SELMD (1 << 1) /* Bit 1: Select Mode */ +#define USIC_TCSR_FLEMD (1 << 2) /* Bit 2: FLE Mode */ +#define USIC_TCSR_WAMD (1 << 3) /* Bit 3: WA Mode */ +#define USIC_TCSR_HPCMD (1 << 4) /* Bit 4: Hardware Port Control Mode */ +#define USIC_TCSR_SOF (1 << 5) /* Bit 5: Start Of Frame */ +#define USIC_TCSR_EOF (1 << 6) /* Bit 6: End Of Frame */ +#define USIC_TCSR_TDV (1 << 7) /* Bit 7: Transmit Data Valid */ +#define USIC_TCSR_TDSSM (1 << 8) /* Bit 8: TBUF Data Single Shot Mode */ +#define USIC_TCSR_TDEN_SHIFT (10) /* Bits 10-11: TBUF Data Enable */ #define USIC_TCSR_TDEN_MASK (3 << USIC_TCSR_TDEN_SHIFT) -#define USIC_TCSR_TDVTR (1 << 12) /* Bit 12: */ -#define USIC_TCSR_WA (1 << 13) /* Bit 13: */ -#define USIC_TCSR_TSOF (1 << 24) /* Bit 24: */ -#define USIC_TCSR_TV (1 << 26) /* Bit 26: */ -#define USIC_TCSR_TVC (1 << 27) /* Bit 27: */ -#define USIC_TCSR_TE (1 << 28) /* Bit 28: */ +# define USIC_TCSR_TDEN_DISABLE (0 << USIC_TCSR_TDEN_SHIFT) /* Transmission of data word disabled */ +# define USIC_TCSR_TDEN_TDIV (1 << USIC_TCSR_TDEN_SHIFT) /* Transmission of data word if TDV = 1 */ +# define USIC_TCSR_TDEN_TDIVDX2S0 (2 << USIC_TCSR_TDEN_SHIFT) /* Transmission of data word if TDV = 1 while DX2S = 0 */ +# define USIC_TCSR_TDEN_TDIVDX2S1 (3 << USIC_TCSR_TDEN_SHIFT) /* Transmission of data word if TDV = 1 while DX2S = 1 */ +#define USIC_TCSR_TDVTR (1 << 12) /* Bit 12: TBUF Data Valid Trigger */ +#define USIC_TCSR_WA (1 << 13) /* Bit 13: Word Addre */ +#define USIC_TCSR_TSOF (1 << 24) /* Bit 24: Transmitted Start Of Frame */ +#define USIC_TCSR_TV (1 << 26) /* Bit 26: Transmission Valid */ +#define USIC_TCSR_TVC (1 << 27) /* Bit 27: Transmission Valid Cumulated */ +#define USIC_TCSR_TE (1 << 28) /* Bit 28: Trigger Event */ /* Protocol Control Register */ -#define USIC_PCR_CTR0 (1 << 0) /* Bit 0: */ -#define USIC_PCR_CTR1 (1 << 1) /* Bit 1: */ -#define USIC_PCR_CTR2 (1 << 2) /* Bit 2: */ -#define USIC_PCR_CTR3 (1 << 3) /* Bit 3: */ -#define USIC_PCR_CTR4 (1 << 4) /* Bit 4: */ -#define USIC_PCR_CTR5 (1 << 5) /* Bit 5: */ -#define USIC_PCR_CTR6 (1 << 6) /* Bit 6: */ -#define USIC_PCR_CTR7 (1 << 7) /* Bit 7: */ -#define USIC_PCR_CTR8 (1 << 8) /* Bit 8: */ -#define USIC_PCR_CTR9 (1 << 9) /* Bit 9: */ -#define USIC_PCR_CTR10 (1 << 10) /* Bit 10: */ -#define USIC_PCR_CTR11 (1 << 11) /* Bit 11: */ -#define USIC_PCR_CTR12 (1 << 12) /* Bit 12: */ -#define USIC_PCR_CTR13 (1 << 13) /* Bit 13: */ -#define USIC_PCR_CTR14 (1 << 14) /* Bit 14: */ -#define USIC_PCR_CTR15 (1 << 15) /* Bit 15: */ -#define USIC_PCR_CTR16 (1 << 16) /* Bit 16: */ -#define USIC_PCR_CTR17 (1 << 17) /* Bit 17: */ -#define USIC_PCR_CTR18 (1 << 18) /* Bit 18: */ -#define USIC_PCR_CTR19 (1 << 19) /* Bit 19: */ -#define USIC_PCR_CTR20 (1 << 20) /* Bit 20: */ -#define USIC_PCR_CTR21 (1 << 21) /* Bit 21: */ -#define USIC_PCR_CTR22 (1 << 22) /* Bit 22: */ -#define USIC_PCR_CTR23 (1 << 23) /* Bit 23: */ -#define USIC_PCR_CTR24 (1 << 24) /* Bit 24: */ -#define USIC_PCR_CTR25 (1 << 25) /* Bit 25: */ -#define USIC_PCR_CTR26 (1 << 26) /* Bit 26: */ -#define USIC_PCR_CTR27 (1 << 27) /* Bit 27: */ -#define USIC_PCR_CTR28 (1 << 28) /* Bit 28: */ -#define USIC_PCR_CTR29 (1 << 29) /* Bit 29: */ -#define USIC_PCR_CTR30 (1 << 30) /* Bit 30: */ -#define USIC_PCR_CTR31 (1 << 31) /* Bit 31: */ +#define USIC_PCR_CTR(n) (1 << (n))/* Bit n: Protocol Control Bit n */ +#define USIC_PCR_CTR0 (1 << 0) /* Bit 0: Protocol Control Bit 0 */ +#define USIC_PCR_CTR1 (1 << 1) /* Bit 1: Protocol Control Bit 1 */ +#define USIC_PCR_CTR2 (1 << 2) /* Bit 2: Protocol Control Bit 2 */ +#define USIC_PCR_CTR3 (1 << 3) /* Bit 3: Protocol Control Bit 3 */ +#define USIC_PCR_CTR4 (1 << 4) /* Bit 4: Protocol Control Bit 4 */ +#define USIC_PCR_CTR5 (1 << 5) /* Bit 5: Protocol Control Bit 5 */ +#define USIC_PCR_CTR6 (1 << 6) /* Bit 6: Protocol Control Bit 6 */ +#define USIC_PCR_CTR7 (1 << 7) /* Bit 7: Protocol Control Bit 7 */ +#define USIC_PCR_CTR8 (1 << 8) /* Bit 8: Protocol Control Bit 8 */ +#define USIC_PCR_CTR9 (1 << 9) /* Bit 9: Protocol Control Bit 9 */ +#define USIC_PCR_CTR10 (1 << 10) /* Bit 10: Protocol Control Bit 10 */ +#define USIC_PCR_CTR11 (1 << 11) /* Bit 11: Protocol Control Bit 11 */ +#define USIC_PCR_CTR12 (1 << 12) /* Bit 12: Protocol Control Bit 12 */ +#define USIC_PCR_CTR13 (1 << 13) /* Bit 13: Protocol Control Bit 13 */ +#define USIC_PCR_CTR14 (1 << 14) /* Bit 14: Protocol Control Bit 14 */ +#define USIC_PCR_CTR15 (1 << 15) /* Bit 15: Protocol Control Bit 15 */ +#define USIC_PCR_CTR16 (1 << 16) /* Bit 16: Protocol Control Bit 16 */ +#define USIC_PCR_CTR17 (1 << 17) /* Bit 17: Protocol Control Bit 17 */ +#define USIC_PCR_CTR18 (1 << 18) /* Bit 18: Protocol Control Bit 18 */ +#define USIC_PCR_CTR19 (1 << 19) /* Bit 19: Protocol Control Bit 19 */ +#define USIC_PCR_CTR20 (1 << 20) /* Bit 20: Protocol Control Bit 20 */ +#define USIC_PCR_CTR21 (1 << 21) /* Bit 21: Protocol Control Bit 21 */ +#define USIC_PCR_CTR22 (1 << 22) /* Bit 22: Protocol Control Bit 22 */ +#define USIC_PCR_CTR23 (1 << 23) /* Bit 23: Protocol Control Bit 23 */ +#define USIC_PCR_CTR24 (1 << 24) /* Bit 24: Protocol Control Bit 24 */ +#define USIC_PCR_CTR25 (1 << 25) /* Bit 25: Protocol Control Bit 25 */ +#define USIC_PCR_CTR26 (1 << 26) /* Bit 26: Protocol Control Bit 26 */ +#define USIC_PCR_CTR27 (1 << 27) /* Bit 27: Protocol Control Bit 27 */ +#define USIC_PCR_CTR28 (1 << 28) /* Bit 28: Protocol Control Bit 28 */ +#define USIC_PCR_CTR29 (1 << 29) /* Bit 29: Protocol Control Bit 29 */ +#define USIC_PCR_CTR30 (1 << 30) /* Bit 30: Protocol Control Bit 30 */ +#define USIC_PCR_CTR31 (1 << 31) /* Bit 31: Protocol Control Bit 31 */ #define USIC_PCR_ASCMODE_SMD (1 << 0) /* Bit 0: */ #define USIC_PCR_ASCMODE_STPB (1 << 1) /* Bit 1: */ @@ -609,44 +690,57 @@ /* Channel Control Register */ -#define USIC_CCR_MODE_SHIFT (0) /* Bits 0-3: */ +#define USIC_CCR_MODE_SHIFT (0) /* Bits 0-3: Operating Mode */ #define USIC_CCR_MODE_MASK (15 << USIC_CCR_MODE_SHIFT) -#define USIC_CCR_HPCEN_SHIFT (6) /* Bits 6-7: */ +# define USIC_CCR_MODE_DISABLE (0 << USIC_CCR_MODE_SHIFT) /* USIC channel is disabled */ +# define USIC_CCR_MODE_SPI (1 << USIC_CCR_MODE_SHIFT) /* SSC (SPI) protocol is selected */ +# define USIC_CCR_MODE_ASC (2 << USIC_CCR_MODE_SHIFT) /* ASC (SCI, UART) protocol is selected */ +# define USIC_CCR_MODE_I2S (3 << USIC_CCR_MODE_SHIFT) /* IIS protocol is selected */ +# define USIC_CCR_MODE_I2C (4 << USIC_CCR_MODE_SHIFT) /* IIC protocol is selected */ +#define USIC_CCR_HPCEN_SHIFT (6) /* Bits 6-7: Hardware Port Control Enable */ #define USIC_CCR_HPCEN_MASK (3 << USIC_CCR_HPCEN_SHIFT) -#define USIC_CCR_PM_SHIFT (8) /* Bits 8-9: */ +# define USIC_CCR_HPCEN_DISABLE (0 << USIC_CCR_HPCEN_SHIFT) /* Port control disabled */ +# define USIC_CCR_HPCEN_DX0_1 (1 << USIC_CCR_HPCEN_SHIFT) /* Port control enabled for DX0 and DOUT0 */ +# define USIC_CCR_HPCEN_DX3 (2 << USIC_CCR_HPCEN_SHIFT) /* Port control enabled for DX3, DX0 and DOUT[1:0] */ +# define USIC_CCR_HPCEN_DX0_2 (3 << USIC_CCR_HPCEN_SHIFT) /* Port control enabled for DX0, DX[5:3] and DOUT[3:0] */ +#define USIC_CCR_PM_SHIFT (8) /* Bits 8-9: Parity Mode */ #define USIC_CCR_PM_MASK (3 << USIC_CCR_PM_SHIFT) -#define USIC_CCR_RSIEN (1 << 10) /* Bit 10: */ -#define USIC_CCR_DLIEN (1 << 11) /* Bit 11: */ -#define USIC_CCR_TSIEN (1 << 12) /* Bit 12: */ -#define USIC_CCR_TBIEN (1 << 13) /* Bit 13: */ -#define USIC_CCR_RIEN (1 << 14) /* Bit 14: */ -#define USIC_CCR_AIEN (1 << 15) /* Bit 15: */ -#define USIC_CCR_BRGIEN (1 << 16) /* Bit 16: */ +# define USIC_CCR_PM_ DISABLE (0 << USIC_CCR_PM_SHIFT) /* Parity generation is disabled */ +# define USIC_CCR_PM_ EVEN (2 << USIC_CCR_PM_SHIFT) /* Even parity is selected */ +# define USIC_CCR_PM_ ODD (3 << USIC_CCR_PM_SHIFT) /* Odd parity is selected */ +#define USIC_CCR_RSIEN (1 << 10) /* Bit 10: Receiver Start Interrupt Enable */ +#define USIC_CCR_DLIEN (1 << 11) /* Bit 11: Data Lost Interrupt Enable */ +#define USIC_CCR_TSIEN (1 << 12) /* Bit 12: Transmit Shift Interrupt Enable */ +#define USIC_CCR_TBIEN (1 << 13) /* Bit 13: Transmit Buffer Interrupt Enable */ +#define USIC_CCR_RIEN (1 << 14) /* Bit 14: Receive Interrupt Enable */ +#define USIC_CCR_AIEN (1 << 15) /* Bit 15: Alternative Receive Interrupt Enable */ +#define USIC_CCR_BRGIEN (1 << 16) /* Bit 16: Baud Rate Generator Interrupt Enable */ /* Capture Mode Timer Register */ -#define USIC_CMTR_CTV_SHIFT (0) /* Bits 0-9: */ +#define USIC_CMTR_CTV_SHIFT (0) /* Bits 0-9: Captured Timer Value */ #define USIC_CMTR_CTV_MASK (0x3ff << USIC_CMTR_CTV_SHIFT) /* Protocol Status Register */ -#define USIC_PSR_ST0 (1 << 0) /* Bit 0: */ -#define USIC_PSR_ST1 (1 << 1) /* Bit 1: */ -#define USIC_PSR_ST2 (1 << 2) /* Bit 2: */ -#define USIC_PSR_ST3 (1 << 3) /* Bit 3: */ -#define USIC_PSR_ST4 (1 << 4) /* Bit 4: */ -#define USIC_PSR_ST5 (1 << 5) /* Bit 5: */ -#define USIC_PSR_ST6 (1 << 6) /* Bit 6: */ -#define USIC_PSR_ST7 (1 << 7) /* Bit 7: */ -#define USIC_PSR_ST8 (1 << 8) /* Bit 8: */ -#define USIC_PSR_ST9 (1 << 9) /* Bit 9: */ -#define USIC_PSR_RSIF (1 << 10) /* Bit 10: */ -#define USIC_PSR_DLIF (1 << 11) /* Bit 11: */ -#define USIC_PSR_TSIF (1 << 12) /* Bit 12: */ -#define USIC_PSR_TBIF (1 << 13) /* Bit 13: */ -#define USIC_PSR_RIF (1 << 14) /* Bit 14: */ -#define USIC_PSR_AIF (1 << 15) /* Bit 15: */ -#define USIC_PSR_BRGIF (1 << 16) /* Bit 16: */ +#define USIC_PSR_ST(n) (1 << (n))/* Bit n: Protocol Status Flag n */ +#define USIC_PSR_ST0 (1 << 0) /* Bit 0: Protocol Status Flag 0 */ +#define USIC_PSR_ST1 (1 << 1) /* Bit 1: Protocol Status Flag 1 */ +#define USIC_PSR_ST2 (1 << 2) /* Bit 2: Protocol Status Flag 2 */ +#define USIC_PSR_ST3 (1 << 3) /* Bit 3: Protocol Status Flag 3 */ +#define USIC_PSR_ST4 (1 << 4) /* Bit 4: Protocol Status Flag 4 */ +#define USIC_PSR_ST5 (1 << 5) /* Bit 5: Protocol Status Flag 5 */ +#define USIC_PSR_ST6 (1 << 6) /* Bit 6: Protocol Status Flag 6 */ +#define USIC_PSR_ST7 (1 << 7) /* Bit 7: Protocol Status Flag 7 */ +#define USIC_PSR_ST8 (1 << 8) /* Bit 8: Protocol Status Flag 8 */ +#define USIC_PSR_ST9 (1 << 9) /* Bit 9: Protocol Status Flag 9 */ +#define USIC_PSR_RSIF (1 << 10) /* Bit 10: Receiver Start Indication Flag */ +#define USIC_PSR_DLIF (1 << 11) /* Bit 11: Data Lost Indication Flag */ +#define USIC_PSR_TSIF (1 << 12) /* Bit 12: Transmit Shift Indication Flag */ +#define USIC_PSR_TBIF (1 << 13) /* Bit 13: Transmit Buffer Indication Flag */ +#define USIC_PSR_RIF (1 << 14) /* Bit 14: Receive Indication Fla */ +#define USIC_PSR_AIF (1 << 15) /* Bit 15: Alternative Receive Indication Flag */ +#define USIC_PSR_BRGIF (1 << 16) /* Bit 16: Baud Rate Generator Indication Fl */ #define USIC_PSR_ASCMODE_TXIDLE (1 << 0) /* Bit 0: */ #define USIC_PSR_ASCMODE_RXIDLE (1 << 1) /* Bit 1: */ @@ -713,114 +807,125 @@ /* Protocol Status Clear Register */ -#define USIC_PSCR_CST0 (1 << 0) /* Bit 0: */ -#define USIC_PSCR_CST1 (1 << 1) /* Bit 1: */ -#define USIC_PSCR_CST2 (1 << 2) /* Bit 2: */ -#define USIC_PSCR_CST3 (1 << 3) /* Bit 3: */ -#define USIC_PSCR_CST4 (1 << 4) /* Bit 4: */ -#define USIC_PSCR_CST5 (1 << 5) /* Bit 5: */ -#define USIC_PSCR_CST6 (1 << 6) /* Bit 6: */ -#define USIC_PSCR_CST7 (1 << 7) /* Bit 7: */ -#define USIC_PSCR_CST8 (1 << 8) /* Bit 8: */ -#define USIC_PSCR_CST9 (1 << 9) /* Bit 9: */ -#define USIC_PSCR_CRSIF (1 << 10) /* Bit 10: */ -#define USIC_PSCR_CDLIF (1 << 11) /* Bit 11: */ -#define USIC_PSCR_CTSIF (1 << 12) /* Bit 12: */ -#define USIC_PSCR_CTBIF (1 << 13) /* Bit 13: */ -#define USIC_PSCR_CRIF (1 << 14) /* Bit 14: */ -#define USIC_PSCR_CAIF (1 << 15) /* Bit 15: */ -#define USIC_PSCR_CBRGIF (1 << 16) /* Bit 16: */ +#define USIC_PSCR_CST(n) (1 << (n))/* Bit n: Clear Status Flag n in PSR */ +#define USIC_PSCR_CST0 (1 << 0) /* Bit 0: Clear Status Flag 0 in PSR */ +#define USIC_PSCR_CST1 (1 << 1) /* Bit 1: Clear Status Flag 1 in PSR */ +#define USIC_PSCR_CST2 (1 << 2) /* Bit 2: Clear Status Flag 2 in PSR */ +#define USIC_PSCR_CST3 (1 << 3) /* Bit 3: Clear Status Flag 3 in PSR */ +#define USIC_PSCR_CST4 (1 << 4) /* Bit 4: Clear Status Flag 4 in PSR */ +#define USIC_PSCR_CST5 (1 << 5) /* Bit 5: Clear Status Flag 5 in PSR */ +#define USIC_PSCR_CST6 (1 << 6) /* Bit 6: Clear Status Flag 6 in PSR */ +#define USIC_PSCR_CST7 (1 << 7) /* Bit 7: Clear Status Flag 7 in PSR */ +#define USIC_PSCR_CST8 (1 << 8) /* Bit 8: Clear Status Flag 8 in PSR */ +#define USIC_PSCR_CST9 (1 << 9) /* Bit 9: Clear Status Flag 9 in PSR */ +#define USIC_PSCR_CRSIF (1 << 10) /* Bit 10: Clear Receiver Start Indication Flag */ +#define USIC_PSCR_CDLIF (1 << 11) /* Bit 11: Clear Data Lost Indication Flag */ +#define USIC_PSCR_CTSIF (1 << 12) /* Bit 12: Clear Transmit Shift Indication Flag */ +#define USIC_PSCR_CTBIF (1 << 13) /* Bit 13: Clear Transmit Buffer Indication Flag */ +#define USIC_PSCR_CRIF (1 << 14) /* Bit 14: Clear Receive Indication Flag */ +#define USIC_PSCR_CAIF (1 << 15) /* Bit 15: Clear Alternative Receive Indication Flag */ +#define USIC_PSCR_CBRGIF (1 << 16) /* Bit 16: Clear Baud Rate Generator Indication Flag */ /* Receiver Buffer Status Register */ -#define USIC_RBUFSR_WLEN_SHIFT (0) /* Bits 0-3: */ +#define USIC_RBUFSR_WLEN_SHIFT (0) /* Bits 0-3: Received Data Word Length in RBUF or RBUFD */ #define USIC_RBUFSR_WLEN_MASK (15 << USIC_RBUFSR_WLEN_SHIFT) -#define USIC_RBUFSR_SOF (1 << 6) /* Bit 6: */ -#define USIC_RBUFSR_PAR (1 << 8) /* Bit 8: */ -#define USIC_RBUFSR_PERR (1 << 9) /* Bit 9: */ -#define USIC_RBUFSR_RDV0 (1 << 13) /* Bit 13: */ -#define USIC_RBUFSR_RDV1 (1 << 14) /* Bit 14: */ -#define USIC_RBUFSR_DS (1 << 15) /* Bit 15: */ +#define USIC_RBUFSR_SOF (1 << 6) /* Bit 6: Start of Frame in RBUF or RBUFD */ +#define USIC_RBUFSR_PAR (1 << 8) /* Bit 8: Protocol-Related Argument in RBUF or RBUFD */ +#define USIC_RBUFSR_PERR (1 << 9) /* Bit 9: Protocol-related Error in RBUF or RBUFD */ +#define USIC_RBUFSR_RDV0 (1 << 13) /* Bit 13: Receive Data Valid in RBUF or RBUFD */ +#define USIC_RBUFSR_RDV1 (1 << 14) /* Bit 14: Receive Data Valid in RBUF or RBUFD */ +#define USIC_RBUFSR_DS (1 << 15) /* Bit 15: Data Source of RBUF or RBUFD */ /* Receiver Buffer Register */ -#define USIC_RBUF_DSR_SHIFT (0) /* Bits 0-15: */ +#define USIC_RBUF_DSR_SHIFT (0) /* Bits 0-15: Received Data */ #define USIC_RBUF_DSR_MASK (0xffff << USIC_RBUF_DSR_SHIFT) /* Receiver Buffer Register for Debugger */ -#define USIC_RBUFD_DSR_SHIFT (0) /* Bits 0-15: */ +#define USIC_RBUFD_DSR_SHIFT (0) /* Bits 0-15: Data from Shift Register */ #define USIC_RBUFD_DSR_MASK (0xffff << USIC_RBUFD_DSR_SHIFT) /* Receiver Buffer Register 0 */ -#define USIC_RBUF0_DSR0_SHIFT (0) /* Bits 0-15: */ +#define USIC_RBUF0_DSR0_SHIFT (0) /* Bits 0-15: Data of Shift Registers 0[3:0] */ #define USIC_RBUF0_DSR0_MASK (0xffff << USIC_RBUF0_DSR0_SHIFT) /* Receiver Buffer Register 1 */ -#define USIC_RBUF1_DSR1_SHIFT (0) /* Bits 0-15: */ +#define USIC_RBUF1_DSR1_SHIFT (0) /* Bits 0-15: Data of Shift Registers 1[3:0] */ #define USIC_RBUF1_DSR1_MASK (0xffff << USIC_RBUF1_DSR1_SHIFT) /* Receiver Buffer 01 Status Register */ -#define USIC_RBUF01SR_WLEN0_SHIFT (0) /* Bits 0-3: */ +#define USIC_RBUF01SR_WLEN0_SHIFT (0) /* Bits 0-3: Received Data Word Length in RBUF0 */ #define USIC_RBUF01SR_WLEN0_MASK (15 << USIC_RBUF01SR_WLEN0_SHIFT) -#define USIC_RBUF01SR_SOF0 (1 << 6) /* Bit 6: */ -#define USIC_RBUF01SR_PAR0 (1 << 8) /* Bit 8: */ -#define USIC_RBUF01SR_PERR0 (1 << 9) /* Bit 9: */ -#define USIC_RBUF01SR_RDV00 (1 << 13) /* Bit 13: */ -#define USIC_RBUF01SR_RDV01 (1 << 14) /* Bit 14: */ -#define USIC_RBUF01SR_DS0 (1 << 15) /* Bit 15: */ -#define USIC_RBUF01SR_WLEN1_SHIFT (16) /* Bits 16-19: */ +#define USIC_RBUF01SR_SOF0 (1 << 6) /* Bit 6: Start of Frame in RBUF0 */ +#define USIC_RBUF01SR_PAR0 (1 << 8) /* Bit 8: Protocol-Related Argument in RBUF0 */ +#define USIC_RBUF01SR_PERR0 (1 << 9) /* Bit 9: Protocol-related Error in RBUF0 */ +#define USIC_RBUF01SR_RDV00 (1 << 13) /* Bit 13: Receive Data Valid in RBUF0 */ +#define USIC_RBUF01SR_RDV01 (1 << 14) /* Bit 14: Receive Data Valid in RBUF1 */ +#define USIC_RBUF01SR_DS0 (1 << 15) /* Bit 15: Data Source */ +#define USIC_RBUF01SR_WLEN1_SHIFT (16) /* Bits 16-19: Received Data Word Length in RBUF1 */ #define USIC_RBUF01SR_WLEN1_MASK (15 << USIC_RBUF01SR_WLEN1_SHIFT) -#define USIC_RBUF01SR_SOF1 (1 << 22) /* Bit 22: */ -#define USIC_RBUF01SR_PAR1 (1 << 24) /* Bit 24: */ -#define USIC_RBUF01SR_PERR1 (1 << 25) /* Bit 25: */ -#define USIC_RBUF01SR_RDV10 (1 << 29) /* Bit 29: */ -#define USIC_RBUF01SR_RDV11 (1 << 30) /* Bit 30: */ -#define USIC_RBUF01SR_DS1 (1 << 31) /* Bit 31: */ +#define USIC_RBUF01SR_SOF1 (1 << 22) /* Bit 22: Start of Frame in RBUF1 */ +#define USIC_RBUF01SR_PAR1 (1 << 24) /* Bit 24: Protocol-Related Argument in RBUF1 */ +#define USIC_RBUF01SR_PERR1 (1 << 25) /* Bit 25: Protocol-related Error in RBU */ +#define USIC_RBUF01SR_RDV10 (1 << 29) /* Bit 29: Receive Data Valid in RBUF0 */ +#define USIC_RBUF01SR_RDV11 (1 << 30) /* Bit 30: Receive Data Valid in RBUF1 */ +#define USIC_RBUF01SR_DS1 (1 << 31) /* Bit 31: Data Source */ /* Flag Modification Register */ -#define USIC_FMR_MTDV_SHIFT (0) /* Bits 0-1: */ +#define USIC_FMR_MTDV_SHIFT (0) /* Bits 0-1: Modify Transmit Data Valid */ #define USIC_FMR_MTDV_MASK (3 << USIC_FMR_MTDV_SHIFT) -#define USIC_FMR_ATVC (1 << 4) /* Bit 4: */ -#define USIC_FMR_CRDV0 (1 << 14) /* Bit 14: */ -#define USIC_FMR_CRDV1 (1 << 15) /* Bit 15: */ -#define USIC_FMR_SIO0 (1 << 16) /* Bit 16: */ -#define USIC_FMR_SIO1 (1 << 17) /* Bit 17: */ -#define USIC_FMR_SIO2 (1 << 18) /* Bit 18: */ -#define USIC_FMR_SIO3 (1 << 19) /* Bit 19: */ -#define USIC_FMR_SIO4 (1 << 20) /* Bit 20: */ -#define USIC_FMR_SIO5 (1 << 21) /* Bit 21: */ +# define USIC_FMR_MTDV_NOACTION (0 << USIC_FMR_MTDV_SHIFT) /* No action */ +# define USIC_FMR_MTDV_TDV (1 << USIC_FMR_MTDV_SHIFT) /* Bit TDV is set, TE is unchanged */ +# define USIC_FMR_MTDV_TDVTE (2 << USIC_FMR_MTDV_SHIFT) /* Bits TDV and TE are cleared */ +#define USIC_FMR_ATVC (1 << 4) /* Bit 4: Activate Bit TVC */ +#define USIC_FMR_CRDV0 (1 << 14) /* Bit 14: Clear Bits RDV for RBUF0 */ +#define USIC_FMR_CRDV1 (1 << 15) /* Bit 15: Clear Bit RDV for RBUF1 */ +#define USIC_FMR_SIO0 (1 << 16) /* Bit 16: Set Interrupt Output SR0 */ +#define USIC_FMR_SIO1 (1 << 17) /* Bit 17: Set Interrupt Output SR1 */ +#define USIC_FMR_SIO2 (1 << 18) /* Bit 18: Set Interrupt Output SR2 */ +#define USIC_FMR_SIO3 (1 << 19) /* Bit 19: Set Interrupt Output SR3 */ +#define USIC_FMR_SIO4 (1 << 20) /* Bit 20: Set Interrupt Output SR4 */ +#define USIC_FMR_SIO5 (1 << 21) /* Bit 21: Set Interrupt Output SR5 */ /* Transmit Buffer (32 x 4-bytes) */ -#define USIC_TBUF_TDATA_SHIFT (0) /* Bits 0-15: */ +#define USIC_TBUF_TDATA_SHIFT (0) /* Bits 0-15: Transmit Data */ #define USIC_TBUF_TDATA_MASK (0xffff << USIC_TBUF_TDATA_SHIFT) /* USIC FIFO Registers */ /* Bypass Data Register */ -#define USIC_BYP_BDATA_SHIFT (0) /* Bits 0-15: */ +#define USIC_BYP_BDATA_SHIFT (0) /* Bits 0-15: Bypass Data */ #define USIC_BYP_BDATA_MASK (0xffff << USIC_BYP_BDATA_SHIFT) /* Bypass Control Register */ -#define USIC_BYPCR_BWLE_SHIFT (0) /* Bits 0-3: */ +#define USIC_BYPCR_BWLE_SHIFT (0) /* Bits 0-3: Bypass Word Length */ #define USIC_BYPCR_BWLE_MASK (15 << USIC_BYPCR_BWLE_SHIFT) -#define USIC_BYPCR_BDSSM (1 << 8) /* Bit 8: */ -#define USIC_BYPCR_BDEN_SHIFT (10) /* Bits 10-11: */ + #define USIC_BYPCR_BWLE(n) ((uint32_t)((n)-1) << USIC_BYPCR_BWLE_SHIFT) +#define USIC_BYPCR_BDSSM (1 << 8) /* Bit 8: Bypass Data Single Shot Mode */ +#define USIC_BYPCR_BDEN_SHIFT (10) /* Bits 10-11: Bypass Data Enable */ #define USIC_BYPCR_BDEN_MASK (3 << USIC_BYPCR_BDEN_SHIFT) -#define USIC_BYPCR_BDVTR (1 << 12) /* Bit 12: */ -#define USIC_BYPCR_BPRIO (1 << 13) /* Bit 13: */ -#define USIC_BYPCR_BDV (1 << 15) /* Bit 15: */ -#define USIC_BYPCR_BSELO_SHIFT (16) /* Bits 16-20: */ +# define USIC_BYPCR_BDEN_DISABLE (0 << USIC_BYPCR_BDEN_SHIFT) /* Transfer of bypass data is disabled */ +# define USIC_BYPCR_BDEN_ENABLED (1 << USIC_BYPCR_BDEN_SHIFT) /* Transfer of bypass data to TBUF if BDV = 1 */ +# define USIC_BYPCR_BDEN_GATED0 (2 << USIC_BYPCR_BDEN_SHIFT) /* Bypass data transferred if BDV = 1 and DX2S = 0 */ +# define USIC_BYPCR_BDEN_GATED1 (3 << USIC_BYPCR_BDEN_SHIFT) /* Bypass data transferred if BDV = 1 and DX2S = 1 */ +#define USIC_BYPCR_BDVTR (1 << 12) /* Bit 12: Bypass Data Valid Trigger */ +#define USIC_BYPCR_BPRIO (1 << 13) /* Bit 13: Bypass Priority */ +#define USIC_BYPCR_BDV (1 << 15) /* Bit 15: Bypass Data Valid */ +#define USIC_BYPCR_BSELO_SHIFT (16) /* Bits 16-20: Bypass Select Outputs */ #define USIC_BYPCR_BSELO_MASK (31 << USIC_BYPCR_BSELO_SHIFT) -#define USIC_BYPCR_BHPC_SHIFT (21) /* Bits 21-23: */ +# define USIC_BYPCR_BSELO(n) ((uint32_t)(n) << USIC_BYPCR_BSELO_SHIFT) +#define USIC_BYPCR_BHPC_SHIFT (21) /* Bits 21-23: Bypass Hardware Port Control */ #define USIC_BYPCR_BHPC_MASK (7 << USIC_BYPCR_BHPC_SHIFT) +# define USIC_BYPCR_BHPC(n) ((uint32_t)(n) << USIC_BYPCR_BHPC_SHIFT) /* Transmitter Buffer Control Register */ @@ -875,34 +980,36 @@ /* Transmit/Receive Buffer Status Register */ -#define USIC_TRBSR_SRBI (1 << 0) /* Bit 0: */ -#define USIC_TRBSR_RBERI (1 << 1) /* Bit 1: */ -#define USIC_TRBSR_ARBI (1 << 2) /* Bit 2: */ -#define USIC_TRBSR_REMPTY (1 << 3) /* Bit 3: */ -#define USIC_TRBSR_RFULL (1 << 4) /* Bit 4: */ -#define USIC_TRBSR_RBUS (1 << 5) /* Bit 5: */ -#define USIC_TRBSR_SRBT (1 << 6) /* Bit 6: */ -#define USIC_TRBSR_STBI (1 << 8) /* Bit 8: */ -#define USIC_TRBSR_TBERI (1 << 9) /* Bit 9: */ -#define USIC_TRBSR_TEMPTY (1 << 11) /* Bit 11: */ -#define USIC_TRBSR_TFULL (1 << 12) /* Bit 12: */ -#define USIC_TRBSR_TBUS (1 << 13) /* Bit 13: */ -#define USIC_TRBSR_STBT (1 << 14) /* Bit 14: */ -#define USIC_TRBSR_RBFLVL_SHIFT (16) /* Bits 16-22: */ +#define USIC_TRBSR_SRBI (1 << 0) /* Bit 0: Standard Receive Buffer Event */ +#define USIC_TRBSR_RBERI (1 << 1) /* Bit 1: Receive Buffer Error Event */ +#define USIC_TRBSR_ARBI (1 << 2) /* Bit 2: Alternative Receive Buffer Event */ +#define USIC_TRBSR_REMPTY (1 << 3) /* Bit 3: Receive Buffer Empty */ +#define USIC_TRBSR_RFULL (1 << 4) /* Bit 4: Receive Buffer Full */ +#define USIC_TRBSR_RBUS (1 << 5) /* Bit 5: Receive Buffer Busy */ +#define USIC_TRBSR_SRBT (1 << 6) /* Bit 6: Standard Receive Buffer Event Trigger */ +#define USIC_TRBSR_STBI (1 << 8) /* Bit 8: Standard Transmit Buffer Event */ +#define USIC_TRBSR_TBERI (1 << 9) /* Bit 9: Transmit Buffer Error Event */ +#define USIC_TRBSR_TEMPTY (1 << 11) /* Bit 11: Transmit Buffer Empty */ +#define USIC_TRBSR_TFULL (1 << 12) /* Bit 12: Transmit Buffer Full */ +#define USIC_TRBSR_TBUS (1 << 13) /* Bit 13: Transmit Buffer Busy */ +#define USIC_TRBSR_STBT (1 << 14) /* Bit 14: Standard Transmit Buffer Event Trigger */ +#define USIC_TRBSR_RBFLVL_SHIFT (16) /* Bits 16-22: Receive Buffer Filling Level */ #define USIC_TRBSR_RBFLVL_MASK (0x7f << USIC_TRBSR_RBFLVL_SHIFT) -#define USIC_TRBSR_TBFLVL_SHIFT (24) /* Bits 22-28: */ +# define USIC_TRBSR_RBFLVL(n) ((uint32_t)(n) << USIC_TRBSR_RBFLVL_SHIFT) +#define USIC_TRBSR_TBFLVL_SHIFT (24) /* Bits 22-28: Transmit Buffer Filling Level */ #define USIC_TRBSR_TBFLVL_MASK (0x7f << USIC_TRBSR_TBFLVL_SHIFT) +# define USIC_TRBSR_TBFLVL(n) ((uint32_t)(n) << USIC_TRBSR_TBFLVL_SHIFT) /* Transmit/Receive Buffer Status Clear Register */ -#define USIC_TRBSCR_CSRBI (1 << 0) /* Bit 0: */ -#define USIC_TRBSCR_CRBERI (1 << 1) /* Bit 1: */ -#define USIC_TRBSCR_CARBI (1 << 2) /* Bit 2: */ -#define USIC_TRBSCR_CSTBI (1 << 8) /* Bit 8: */ -#define USIC_TRBSCR_CTBERI (1 << 9) /* Bit 9: */ -#define USIC_TRBSCR_CBDV (1 << 10) /* Bit 10: */ -#define USIC_TRBSCR_FLUSHRB (1 << 14) /* Bit 14: */ -#define USIC_TRBSCR_FLUSHTB (1 << 15) /* Bit 15: */ +#define USIC_TRBSCR_CSRBI (1 << 0) /* Bit 0: Clear Standard Receive Buffer Event */ +#define USIC_TRBSCR_CRBERI (1 << 1) /* Bit 1: Clear Receive Buffer Error Event */ +#define USIC_TRBSCR_CARBI (1 << 2) /* Bit 2: Clear Alternative Receive Buffer Event */ +#define USIC_TRBSCR_CSTBI (1 << 8) /* Bit 8: Clear Standard Transmit Buffer Event */ +#define USIC_TRBSCR_CTBERI (1 << 9) /* Bit 9: Clear Transmit Buffer Error Event */ +#define USIC_TRBSCR_CBDV (1 << 10) /* Bit 10: Clear Bypass Data Valid */ +#define USIC_TRBSCR_FLUSHRB (1 << 14) /* Bit 14: Flush Receive Buffer */ +#define USIC_TRBSCR_FLUSHTB (1 << 15) /* Bit 15: Flush Transmit Buffer */ /* Receiver Buffer Output Register */ -- GitLab From 064ae17af5f6bd5ba21b83e0bf4afea48309d5ac Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 19 Mar 2017 09:46:57 -0600 Subject: [PATCH 101/990] XMC4xxx: Finishes UIC register definition header file. --- arch/arm/src/xmc4/chip/xmc4_usic.h | 357 +++++++++++++++++------------ 1 file changed, 208 insertions(+), 149 deletions(-) diff --git a/arch/arm/src/xmc4/chip/xmc4_usic.h b/arch/arm/src/xmc4/chip/xmc4_usic.h index d6d5299cbd..0b49ebfff4 100644 --- a/arch/arm/src/xmc4/chip/xmc4_usic.h +++ b/arch/arm/src/xmc4/chip/xmc4_usic.h @@ -536,8 +536,7 @@ # define USIC_DXCR_CM_RISING (1 << USIC_DX0CR_CM_SHIFT) /* Rising edge activates DXnT */ # define USIC_DXCR_CM_FALLING (2 << USIC_DX0CR_CM_SHIFT) /* Falling edge activates DXnT */ # define USIC_DXCR_CM_BOTH (3 << USIC_DX0CR_CM_SHIFT) /* Both edges activate DXnT */ - -#define USIC_DXCR_DXS (1 << 15) /* Bit 15: */ +#define USIC_DXCR_DXS (1 << 15) /* Bit 15: Synchronized Data Value */ /* Shift Control Register */ @@ -626,67 +625,80 @@ #define USIC_PCR_CTR30 (1 << 30) /* Bit 30: Protocol Control Bit 30 */ #define USIC_PCR_CTR31 (1 << 31) /* Bit 31: Protocol Control Bit 31 */ -#define USIC_PCR_ASCMODE_SMD (1 << 0) /* Bit 0: */ -#define USIC_PCR_ASCMODE_STPB (1 << 1) /* Bit 1: */ -#define USIC_PCR_ASCMODE_IDM (1 << 2) /* Bit 2: */ -#define USIC_PCR_ASCMODE_SBIEN (1 << 3) /* Bit 3: */ -#define USIC_PCR_ASCMODE_CDEN (1 << 4) /* Bit 4: */ -#define USIC_PCR_ASCMODE_RNIEN (1 << 5) /* Bit 5: */ -#define USIC_PCR_ASCMODE_FEIEN (1 << 6) /* Bit 6: */ -#define USIC_PCR_ASCMODE_FFIEN (1 << 7) /* Bit 7: */ -#define USIC_PCR_ASCMODE_SP_SHIFT (8) /* Bits 8-12: */ +#define USIC_PCR_ASCMODE_SMD (1 << 0) /* Bit 0: Sample Mode */ +#define USIC_PCR_ASCMODE_STPB (1 << 1) /* Bit 1: Stop Bits */ +#define USIC_PCR_ASCMODE_IDM (1 << 2) /* Bit 2: Idle Detection Mode */ +#define USIC_PCR_ASCMODE_SBIEN (1 << 3) /* Bit 3: Synchronization Break Interrupt Enable */ +#define USIC_PCR_ASCMODE_CDEN (1 << 4) /* Bit 4: Collision Detection Enable */ +#define USIC_PCR_ASCMODE_RNIEN (1 << 5) /* Bit 5: Receiver Noise Detection Interrupt Enable */ +#define USIC_PCR_ASCMODE_FEIEN (1 << 6) /* Bit 6: Format Error Interrupt Enable */ +#define USIC_PCR_ASCMODE_FFIEN (1 << 7) /* Bit 7: Frame Finished Interrupt Enable */ +#define USIC_PCR_ASCMODE_SP_SHIFT (8) /* Bits 8-12: Sample Point */ #define USIC_PCR_ASCMODE_SP_MASK (31 << USIC_PCR_ASCMODE_SP_SHIFT) -#define USIC_PCR_ASCMODE_PL_SHIFT (13) /* Bits 13-15: */ +# define USIC_PCR_ASCMODE_SP(n) ((uint32_t)(n) << USIC_PCR_ASCMODE_SP_SHIFT) +#define USIC_PCR_ASCMODE_PL_SHIFT (13) /* Bits 13-15: Pulse Length */ #define USIC_PCR_ASCMODE_PL_MASK (7 << USIC_PCR_ASCMODE_PL_SHIFT) -#define USIC_PCR_ASCMODE_RSTEN (1 << 16) /* Bit 16: */ -#define USIC_PCR_ASCMODE_TSTEN (1 << 17) /* Bit 16: */ -#define USIC_PCR_ASCMODE_MCLK (1 << 31) /* Bit 31: */ - -#define USIC_PCR_SSCMODE_MSLSEN (1 << 0) /* Bit 0: */ -#define USIC_PCR_SSCMODE_SELCTR (1 << 1) /* Bit 1: */ -#define USIC_PCR_SSCMODE_SELINV (1 << 2) /* Bit 2: */ -#define USIC_PCR_SSCMODE_FEM (1 << 3) /* Bit 3: */ -#define USIC_PCR_SSCMODE_CTQSEL1_SHIFT (4) /* Bits 4-5: */ -#define USIC_PCR_SSCMODE_CTQSEL1_MASK (3 << USIC_PCR_SSCMODE_CTQSEL1_SHIFT) -#define USIC_PCR_SSCMODE_PCTQ1_SHIFT (6) /* Bits 6-7: */ + #define USIC_PCR_ASCMODE_PL(n) ((uint32_t)((n)-1) << USIC_PCR_ASCMODE_PL_SHIFT) +#define USIC_PCR_ASCMODE_RSTEN (1 << 16) /* Bit 16: Receiver Status Enable */ +#define USIC_PCR_ASCMODE_TSTEN (1 << 17) /* Bit 17: Transmitter Status Enable */ +#define USIC_PCR_ASCMODE_MCLK (1 << 31) /* Bit 31: Master Clock Enable */ + +#define USIC_PCR_SSCMODE_MSLSEN (1 << 0) /* Bit 0: MSLS Enable */ +#define USIC_PCR_SSCMODE_SELCTR (1 << 1) /* Bit 1: Select Control */ +#define USIC_PCR_SSCMODE_SELINV (1 << 2) /* Bit 2: Select Inversion */ +#define USIC_PCR_SSCMODE_FEM (1 << 3) /* Bit 3: Frame End Mode */ +#define USIC_PCR_SSCMODE_CTQSEL1_SHIFT (4) /* Bits 4-5: Input Frequency Selection */ +#define USIC_PCR_SSCMODE_CTQSEL1_MASK (3 << USIC_PCR_SSCMODE_CTQSEL1_SHIFT) +# define USIC_PCR_SSCMODE_CTQSEL1_FPDIV (0 << USIC_PCR_SSCMODE_CTQSEL1_SHIFT) /* fCTQIN = fPDIV */ +# define USIC_PCR_SSCMODE_CTQSEL1_FPPP (1 << USIC_PCR_SSCMODE_CTQSEL1_SHIFT) /* fCTQIN = fPPP */ +# define USIC_PCR_SSCMODE_CTQSEL1_FSCLK (2 << USIC_PCR_SSCMODE_CTQSEL1_SHIFT) /* fCTQIN = fSCLK */ +# define USIC_PCR_SSCMODE_CTQSEL1_FMCLK (3 << USIC_PCR_SSCMODE_CTQSEL1_SHIFT) /* fCTQIN = fMCLK */ +#define USIC_PCR_SSCMODE_PCTQ1_SHIFT (6) /* Bits 6-7: Divider Factor PCTQ1 for Tiw and Tnf */ #define USIC_PCR_SSCMODE_PCTQ1_MASK (3 << USIC_PCR_SSCMODE_PCTQ1_SHIFT) -#define USIC_PCR_SSCMODE_DCTQ1_SHIFT (8) /* Bits 8-12: */ -#define USIC_PCR_SSCMODE_DCTQ1_MASK (0x1f << USIC_PCR_SSCMODE_DCTQ1_SHIFT) -#define USIC_PCR_SSCMODE_PARIEN (1 << 13) /* Bit 13: */ -#define USIC_PCR_SSCMODE_MSLSIEN (1 << 14) /* Bit 14: */ -#define USIC_PCR_SSCMODE_DX2TIEN (1 << 15) /* Bit 15: */ -#define USIC_PCR_SSCMODE_SELO_SHIFT (16) /* Bits 16-23: */ +# define USIC_PCR_SSCMODE_PCTQ1(n) ((uint32_t)((n)-1) << USIC_PCR_SSCMODE_PCTQ1_SHIFT) +#define USIC_PCR_SSCMODE_DCTQ1_SHIFT (8) /* Bits 8-12: Divider Factor DCTQ1 for Tiw and Tnf */ +# define USIC_PCR_SSCMODE_DCTQ1(n) (0x1f << USIC_PCR_SSCMODE_DCTQ1_SHIFT) +#define USIC_PCR_SSCMODE_DCTQ1_MASK ((uint32_t)((n)-1) << USIC_PCR_SSCMODE_DCTQ1_SHIFT) +#define USIC_PCR_SSCMODE_PARIEN (1 << 13) /* Bit 13: Parity Error Interrupt Enable */ +#define USIC_PCR_SSCMODE_MSLSIEN (1 << 14) /* Bit 14: MSLS Interrupt Enable */ +#define USIC_PCR_SSCMODE_DX2TIEN (1 << 15) /* Bit 15: DX2T Interrupt Enable */ +#define USIC_PCR_SSCMODE_SELO_SHIFT (16) /* Bits 16-23: Select Output */ #define USIC_PCR_SSCMODE_SELO_MASK (0xff << USIC_PCR_SSCMODE_SELO_SHIFT) -#define USIC_PCR_SSCMODE_TIWEN (1 << 24) /* Bit 24: */ -#define USIC_PCR_SSCMODE_SLPHSEL (1 << 25) /* Bit 25: */ -#define USIC_PCR_SSCMODE_MCLK (1 << 31) /* Bit 31: */ +# define USIC_PCR_SSCMODE_SELO(n) (1 << ((n) + USIC_PCR_SSCMODE_SELO_SHIFT)) +#define USIC_PCR_SSCMODE_TIWEN (1 << 24) /* Bit 24: Enable Inter-Word Delay Tiw */ +#define USIC_PCR_SSCMODE_SLPHSEL (1 << 25) /* Bit 25: Slave Mode Clock Phase Select */ +#define USIC_PCR_SSCMODE_MCLK (1 << 31) /* Bit 31: Master Clock Enable */ -#define USIC_PCR_IICMODE_SLAD_SHIFT (0) /* Bits 0-15: */ +#define USIC_PCR_IICMODE_SLAD_SHIFT (0) /* Bits 0-15: Slave Address */ #define USIC_PCR_IICMODE_SLAD_MASK (0xffff << USIC_PCR_IICMODE_SLAD_SHIFT) -#define USIC_PCR_IICMODE_ACK00 (1 << 16) /* Bit 16: */ -#define USIC_PCR_IICMODE_STIM (1 << 17) /* Bit 17: */ -#define USIC_PCR_IICMODE_SCRIEN (1 << 18) /* Bit 18: */ -#define USIC_PCR_IICMODE_RSCRIEN (1 << 19) /* Bit 19: */ -#define USIC_PCR_IICMODE_PCRIEN (1 << 20) /* Bit 20: */ -#define USIC_PCR_IICMODE_NACKIEN (1 << 21) /* Bit 21: */ -#define USIC_PCR_IICMODE_ARLIEN (1 << 22) /* Bit 22: */ -#define USIC_PCR_IICMODE_SRRIEN (1 << 23) /* Bit 23: */ -#define USIC_PCR_IICMODE_ERRIEN (1 << 24) /* Bit 24: */ -#define USIC_PCR_IICMODE_SACKDIS (1 << 25) /* Bit 25: */ -#define USIC_PCR_IICMODE_HDEL_SHIFT (26) /* Bits 26-29: */ +# define USIC_PCR_IICMODE_SLAD(n) ((uint32_t)(n) << USIC_PCR_IICMODE_SLAD_SHIFT) +#define USIC_PCR_IICMODE_ACK00 (1 << 16) /* Bit 16: Acknowledge 00H */ +#define USIC_PCR_IICMODE_STIM (1 << 17) /* Bit 17: Symbol Timing */ +#define USIC_PCR_IICMODE_SCRIEN (1 << 18) /* Bit 18: Start Condition Received Interrupt Enable */ +#define USIC_PCR_IICMODE_RSCRIEN (1 << 19) /* Bit 19: Repeated Start Condition Received Interrupt */ +#define USIC_PCR_IICMODE_PCRIEN (1 << 20) /* Bit 20: Stop Condition Received Interrupt Enable */ +#define USIC_PCR_IICMODE_NACKIEN (1 << 21) /* Bit 21: Non-Acknowledge Interrupt Enable */ +#define USIC_PCR_IICMODE_ARLIEN (1 << 22) /* Bit 22: Arbitration Lost Interrupt Enable */ +#define USIC_PCR_IICMODE_SRRIEN (1 << 23) /* Bit 23: Slave Read Request Interrupt Enable */ +#define USIC_PCR_IICMODE_ERRIEN (1 << 24) /* Bit 24: Error Interrupt Enable */ +#define USIC_PCR_IICMODE_SACKDIS (1 << 25) /* Bit 25: Slave Acknowledge Disable */ +#define USIC_PCR_IICMODE_HDEL_SHIFT (26) /* Bits 26-29: Hardware Delay */ #define USIC_PCR_IICMODE_HDEL_MASK (15 << USIC_PCR_IICMODE_HDEL_SHIFT) -#define USIC_PCR_IICMODE_ACKIEN (1 << 30) /* Bit 30: */ -#define USIC_PCR_IICMODE_MCLK (1 << 31) /* Bit 31: */ - -#define USIC_PCR_IISMODE_WAGEN (1 << 0) /* Bit 0: */ -#define USIC_PCR_IISMODE_DTEN (1 << 1) /* Bit 1: */ -#define USIC_PCR_IISMODE_SELINV (1 << 2) /* Bit 2: */ -#define USIC_PCR_IISMODE_WAFEIEN (1 << 4) /* Bit 4: */ -#define USIC_PCR_IISMODE_WAREIEN (1 << 5) /* Bit 5: */ -#define USIC_PCR_IISMODE_ENDIEN (1 << 6) /* Bit 6: */ -#define USIC_PCR_IISMODE_TDEL_SHIFT (16) /* Bits 15-21: */ +# define USIC_PCR_IICMODE_HDEL(n) ((uint32_t)(n) << USIC_PCR_IICMODE_HDEL_SHIFT) +#define USIC_PCR_IICMODE_ACKIEN (1 << 30) /* Bit 30: Acknowledge Interrupt Enable */ +#define USIC_PCR_IICMODE_MCLK (1 << 31) /* Bit 31: Master Clock Enable */ + +#define USIC_PCR_IISMODE_WAGEN (1 << 0) /* Bit 0: WA Generation Enable */ +#define USIC_PCR_IISMODE_DTEN (1 << 1) /* Bit 1: Data Transfers Enable */ +#define USIC_PCR_IISMODE_SELINV (1 << 2) /* Bit 2: Select Inversion */ +#define USIC_PCR_IISMODE_WAFEIEN (1 << 4) /* Bit 4: WA Falling Edge Interrupt Enable */ +#define USIC_PCR_IISMODE_WAREIEN (1 << 5) /* Bit 5: WA Rising Edge Interrupt Enable */ +#define USIC_PCR_IISMODE_ENDIEN (1 << 6) /* Bit 6: END Interrupt Enable */ +#define USIC_PCR_IISMODE_DX2TIEN (1 << 15) /* Bit 15: DX2T Interrupt Enable */ +#define USIC_PCR_IISMODE_TDEL_SHIFT (16) /* Bits 16-21: Transfer Delay */ #define USIC_PCR_IISMODE_TDEL_MASK (0x3f << USIC_PCR_IISMODE_TDEL_SHIFT) -#define USIC_PCR_IISMODE_MCLK (1 << 31) /* Bit 31: */ +# define USIC_PCR_IISMODE_TDEL(n) ((uint32_t)(n) << USIC_PCR_IISMODE_TDEL_SHIFT) +#define USIC_PCR_IISMODE_MCLK (1 << 31) /* Bit 31: Master Clock Enable */ /* Channel Control Register */ @@ -742,68 +754,68 @@ #define USIC_PSR_AIF (1 << 15) /* Bit 15: Alternative Receive Indication Flag */ #define USIC_PSR_BRGIF (1 << 16) /* Bit 16: Baud Rate Generator Indication Fl */ -#define USIC_PSR_ASCMODE_TXIDLE (1 << 0) /* Bit 0: */ -#define USIC_PSR_ASCMODE_RXIDLE (1 << 1) /* Bit 1: */ -#define USIC_PSR_ASCMODE_SBD (1 << 2) /* Bit 2: */ -#define USIC_PSR_ASCMODE_COL (1 << 3) /* Bit 3: */ -#define USIC_PSR_ASCMODE_RNS (1 << 4) /* Bit 4: */ -#define USIC_PSR_ASCMODE_FER0 (1 << 5) /* Bit 5: */ -#define USIC_PSR_ASCMODE_FER1 (1 << 6) /* Bit 6: */ -#define USIC_PSR_ASCMODE_RFF (1 << 7) /* Bit 7: */ -#define USIC_PSR_ASCMODE_TFF (1 << 8) /* Bit 8: */ -#define USIC_PSR_ASCMODE_BUSY (1 << 9) /* Bit 9: */ -#define USIC_PSR_ASCMODE_RSIF (1 << 10) /* Bit 10: */ -#define USIC_PSR_ASCMODE_DLIF (1 << 11) /* Bit 11: */ -#define USIC_PSR_ASCMODE_TSIF (1 << 12) /* Bit 12: */ -#define USIC_PSR_ASCMODE_TBIF (1 << 13) /* Bit 13: */ -#define USIC_PSR_ASCMODE_RIF (1 << 14) /* Bit 14: */ -#define USIC_PSR_ASCMODE_AIF (1 << 15) /* Bit 15: */ -#define USIC_PSR_ASCMODE_BRGIF (1 << 16) /* Bit 16: */ - -#define USIC_PSR_SSCMODE_MSLS (1 << 0) /* Bit 0: */ -#define USIC_PSR_SSCMODE_DX2S (1 << 1) /* Bit 1: */ -#define USIC_PSR_SSCMODE_MSLSEV (1 << 2) /* Bit 2: */ -#define USIC_PSR_SSCMODE_DX2TEV (1 << 3) /* Bit 3: */ -#define USIC_PSR_SSCMODE_PARERR (1 << 4) /* Bit 4: */ -#define USIC_PSR_SSCMODE_RSIF (1 << 10) /* Bit 10: */ -#define USIC_PSR_SSCMODE_DLIF (1 << 11) /* Bit 11: */ -#define USIC_PSR_SSCMODE_TSIF (1 << 12) /* Bit 12: */ -#define USIC_PSR_SSCMODE_TBIF (1 << 13) /* Bit 13: */ -#define USIC_PSR_SSCMODE_RIF (1 << 14) /* Bit 14: */ -#define USIC_PSR_SSCMODE_AIF (1 << 15) /* Bit 15: */ -#define USIC_PSR_SSCMODE_BRGIF (1 << 16) /* Bit 16: */ - -#define USIC_PSR_IICMODE_SLSEL (1 << 0) /* Bit 0: */ -#define USIC_PSR_IICMODE_WTDF (1 << 1) /* Bit 1: */ -#define USIC_PSR_IICMODE_SCR (1 << 2) /* Bit 2: */ -#define USIC_PSR_IICMODE_RSCR (1 << 3) /* Bit 3: */ -#define USIC_PSR_IICMODE_PCR (1 << 4) /* Bit 4: */ -#define USIC_PSR_IICMODE_NACK (1 << 5) /* Bit 5: */ -#define USIC_PSR_IICMODE_ARL (1 << 6) /* Bit 6: */ -#define USIC_PSR_IICMODE_SRR (1 << 7) /* Bit 7: */ -#define USIC_PSR_IICMODE_ERR (1 << 8) /* Bit 8: */ -#define USIC_PSR_IICMODE_ACK (1 << 9) /* Bit 9: */ -#define USIC_PSR_IICMODE_RSIF (1 << 10) /* Bit 10: */ -#define USIC_PSR_IICMODE_DLIF (1 << 11) /* Bit 11: */ -#define USIC_PSR_IICMODE_TSIF (1 << 12) /* Bit 12: */ -#define USIC_PSR_IICMODE_TBIF (1 << 13) /* Bit 13: */ -#define USIC_PSR_IICMODE_RIF (1 << 14) /* Bit 14: */ -#define USIC_PSR_IICMODE_AIF (1 << 15) /* Bit 15: */ -#define USIC_PSR_IICMODE_BRGIF (1 << 16) /* Bit 16: */ - -#define USIC_PSR_IISMODE_WA (1 << 0) /* Bit 0: */ -#define USIC_PSR_IISMODE_DX2S (1 << 1) /* Bit 1: */ -#define USIC_PSR_IISMODE_DX2TEV (1 << 3) /* Bit 3: */ -#define USIC_PSR_IISMODE_WAFE (1 << 4) /* Bit 4: */ -#define USIC_PSR_IISMODE_WARE (1 << 5) /* Bit 5: */ -#define USIC_PSR_IISMODE_END (1 << 6) /* Bit 6: */ -#define USIC_PSR_IISMODE_RSIF (1 << 10) /* Bit 10: */ -#define USIC_PSR_IISMODE_DLIF (1 << 11) /* Bit 11: */ -#define USIC_PSR_IISMODE_TSIF (1 << 12) /* Bit 12: */ -#define USIC_PSR_IISMODE_TBIF (1 << 13) /* Bit 13: */ -#define USIC_PSR_IISMODE_RIF (1 << 14) /* Bit 14: */ -#define USIC_PSR_IISMODE_AIF (1 << 15) /* Bit 15: */ -#define USIC_PSR_IISMODE_BRGIF (1 << 16) /* Bit 16: */ +#define USIC_PSR_ASCMODE_TXIDLE (1 << 0) /* Bit 0: Transmission Idle */ +#define USIC_PSR_ASCMODE_RXIDLE (1 << 1) /* Bit 1: Reception Idle */ +#define USIC_PSR_ASCMODE_SBD (1 << 2) /* Bit 2: Synchronization Break Detected */ +#define USIC_PSR_ASCMODE_COL (1 << 3) /* Bit 3: Collision Detected */ +#define USIC_PSR_ASCMODE_RNS (1 << 4) /* Bit 4: Receiver Noise Detected */ +#define USIC_PSR_ASCMODE_FER0 (1 << 5) /* Bit 5: Format Error in Stop Bit 0 */ +#define USIC_PSR_ASCMODE_FER1 (1 << 6) /* Bit 6: Format Error in Stop Bit 1 */ +#define USIC_PSR_ASCMODE_RFF (1 << 7) /* Bit 7: Receive Frame Finished */ +#define USIC_PSR_ASCMODE_TFF (1 << 8) /* Bit 8: Transmitter Frame Finished */ +#define USIC_PSR_ASCMODE_BUSY (1 << 9) /* Bit 9: Transfer Status BUSY */ +#define USIC_PSR_ASCMODE_RSIF (1 << 10) /* Bit 10: Receiver Start Indication Flag */ +#define USIC_PSR_ASCMODE_DLIF (1 << 11) /* Bit 11: Data Lost Indication Flag */ +#define USIC_PSR_ASCMODE_TSIF (1 << 12) /* Bit 12: Transmit Shift Indication Flag */ +#define USIC_PSR_ASCMODE_TBIF (1 << 13) /* Bit 13: Transmit Buffer Indication Flag */ +#define USIC_PSR_ASCMODE_RIF (1 << 14) /* Bit 14: Receive Indication Flag */ +#define USIC_PSR_ASCMODE_AIF (1 << 15) /* Bit 15: Alternative Receive Indication Flag */ +#define USIC_PSR_ASCMODE_BRGIF (1 << 16) /* Bit 16: Baud Rate Generator Indication Flag */ + +#define USIC_PSR_SSCMODE_MSLS (1 << 0) /* Bit 0: MSLS Status */ +#define USIC_PSR_SSCMODE_DX2S (1 << 1) /* Bit 1: DX2S Status */ +#define USIC_PSR_SSCMODE_MSLSEV (1 << 2) /* Bit 2: MSLS Event Detected */ +#define USIC_PSR_SSCMODE_DX2TEV (1 << 3) /* Bit 3: DX2T Event Detected */ +#define USIC_PSR_SSCMODE_PARERR (1 << 4) /* Bit 4: Parity Error Event Detected */ +#define USIC_PSR_SSCMODE_RSIF (1 << 10) /* Bit 10: Receiver Start Indication Flag */ +#define USIC_PSR_SSCMODE_DLIF (1 << 11) /* Bit 11: Data Lost Indication Flag */ +#define USIC_PSR_SSCMODE_TSIF (1 << 12) /* Bit 12: Transmit Shift Indication Flag */ +#define USIC_PSR_SSCMODE_TBIF (1 << 13) /* Bit 13: Transmit Buffer Indication Flag */ +#define USIC_PSR_SSCMODE_RIF (1 << 14) /* Bit 14: Receive Indication Flag */ +#define USIC_PSR_SSCMODE_AIF (1 << 15) /* Bit 15: Alternative Receive Indication Flag */ +#define USIC_PSR_SSCMODE_BRGIF (1 << 16) /* Bit 16: Baud Rate Generator Indication Flag */ + +#define USIC_PSR_IICMODE_SLSEL (1 << 0) /* Bit 0: Slave Select */ +#define USIC_PSR_IICMODE_WTDF (1 << 1) /* Bit 1: Wrong TDF Code Found */ +#define USIC_PSR_IICMODE_SCR (1 << 2) /* Bit 2: Start Condition Received */ +#define USIC_PSR_IICMODE_RSCR (1 << 3) /* Bit 3: Repeated Start Condition Received */ +#define USIC_PSR_IICMODE_PCR (1 << 4) /* Bit 4: Stop Condition Received */ +#define USIC_PSR_IICMODE_NACK (1 << 5) /* Bit 5: Non-Acknowledge Received */ +#define USIC_PSR_IICMODE_ARL (1 << 6) /* Bit 6: Arbitration Lost */ +#define USIC_PSR_IICMODE_SRR (1 << 7) /* Bit 7: Slave Read Request */ +#define USIC_PSR_IICMODE_ERR (1 << 8) /* Bit 8: Error */ +#define USIC_PSR_IICMODE_ACK (1 << 9) /* Bit 9: Acknowledge Received */ +#define USIC_PSR_IICMODE_RSIF (1 << 10) /* Bit 10: Receiver Start Indication Flag */ +#define USIC_PSR_IICMODE_DLIF (1 << 11) /* Bit 11: Data Lost Indication Flag */ +#define USIC_PSR_IICMODE_TSIF (1 << 12) /* Bit 12: Transmit Shift Indication Flag */ +#define USIC_PSR_IICMODE_TBIF (1 << 13) /* Bit 13: Transmit Buffer Indication Flag */ +#define USIC_PSR_IICMODE_RIF (1 << 14) /* Bit 14: Receive Indication Flag */ +#define USIC_PSR_IICMODE_AIF (1 << 15) /* Bit 15: Alternative Receive Indication Flag */ +#define USIC_PSR_IICMODE_BRGIF (1 << 16) /* Bit 16: Baud Rate Generator Indication Flag */ + +#define USIC_PSR_IISMODE_WA (1 << 0) /* Bit 0: Word Address */ +#define USIC_PSR_IISMODE_DX2S (1 << 1) /* Bit 1: DX2S Sta */ +#define USIC_PSR_IISMODE_DX2TEV (1 << 3) /* Bit 3: DX2T Event Detected */ +#define USIC_PSR_IISMODE_WAFE (1 << 4) /* Bit 4: WA Falling Edge Event */ +#define USIC_PSR_IISMODE_WARE (1 << 5) /* Bit 5: WA Rising Edge Event */ +#define USIC_PSR_IISMODE_END (1 << 6) /* Bit 6: WA Generation End */ +#define USIC_PSR_IISMODE_RSIF (1 << 10) /* Bit 10: Receiver Start Indication Flag */ +#define USIC_PSR_IISMODE_DLIF (1 << 11) /* Bit 11: Data Lost Indication Flag */ +#define USIC_PSR_IISMODE_TSIF (1 << 12) /* Bit 12: Transmit Shift Indication Flag */ +#define USIC_PSR_IISMODE_TBIF (1 << 13) /* Bit 13: Transmit Buffer Indication Flag */ +#define USIC_PSR_IISMODE_RIF (1 << 14) /* Bit 14: Receive Indication Flag */ +#define USIC_PSR_IISMODE_AIF (1 << 15) /* Bit 15: Alternative Receive Indication Flag */ +#define USIC_PSR_IISMODE_BRGIF (1 << 16) /* Bit 16: Baud Rate Generator Indication Flag */ /* Protocol Status Clear Register */ @@ -929,53 +941,100 @@ /* Transmitter Buffer Control Register */ -#define USIC_TBCTR_DPTR_SHIFT (0) /* Bits 0-1: */ +#define USIC_TBCTR_DPTR_SHIFT (0) /* Bits 0-1: Data Pointer */ #define USIC_TBCTR_DPTR_MASK (3 << USIC_TBCTR_DPTR_SHIFT) -#define USIC_TBCTR_LIMIT_SHIFT (8) /* Bits 8-13: */ +# define USIC_TBCTR_DPTR(n) ((uint32_t)(n) << USIC_TBCTR_DPTR_SHIFT) +#define USIC_TBCTR_LIMIT_SHIFT (8) /* Bits 8-13: Limit For Interrupt Generation */ #define USIC_TBCTR_LIMIT_MASK (0x3f << USIC_TBCTR_LIMIT_SHIFT) -#define USIC_TBCTR_STBTM (1 << 14) /* Bit 14: */ -#define USIC_TBCTR_STBTEN (1 << 15) /* Bit 15: */ -#define USIC_TBCTR_STBINP_SHIFT (16) /* Bits 16-18: */ +# define USIC_TBCTR_LIMIT(n) ((uint32_t)(n) << USIC_TBCTR_LIMIT_SHIFT) +#define USIC_TBCTR_STBTM (1 << 14) /* Bit 14: Standard Transmit Buffer Trigger Mode */ +#define USIC_TBCTR_STBTEN (1 << 15) /* Bit 15: Standard Transmit Buffer Trigger Enable */ +#define USIC_TBCTR_STBINP_SHIFT (16) /* Bits 16-18: Standard Transmit Buffer Interrupt Node Pointer */ #define USIC_TBCTR_STBINP_MASK (7 << USIC_TBCTR_STBINP_SHIFT) -#define USIC_TBCTR_ATBINP_SHIFT (19) /* Bits 19-21: */ +# define USIC_TBCTR_STBINP_SR0 (0 << USIC_TBCTR_STBINP_SHIFT) /* Output SR0 becomes activated */ +# define USIC_TBCTR_STBINP_SR1 (1 << USIC_TBCTR_STBINP_SHIFT) /* Output SR1 becomes activated */ +# define USIC_TBCTR_STBINP_SR2 (2 << USIC_TBCTR_STBINP_SHIFT) /* Output SR2 becomes activated */ +# define USIC_TBCTR_STBINP_SR3 (3 << USIC_TBCTR_STBINP_SHIFT) /* Output SR3 becomes activated */ +# define USIC_TBCTR_STBINP_SR4 (4 << USIC_TBCTR_STBINP_SHIFT) /* Output SR4 becomes activated */ +# define USIC_TBCTR_STBINP_SR5 (5 << USIC_TBCTR_STBINP_SHIFT) /* Output SR5 becomes activated */ +#define USIC_TBCTR_ATBINP_SHIFT (19) /* Bits 19-21: Alternative Transmit Buffer Interrupt Node Pointer */ #define USIC_TBCTR_ATBINP_MASK (7 << USIC_TBCTR_ATBINP_SHIFT) -#define USIC_TBCTR_SIZE_SHIFT (24) /* Bits 24-26: */ +# define USIC_TBCTR_ATBINP_SR0 (0 << USIC_TBCTR_ATBINP_SHIFT) /* Output SR0 becomes activated */ +# define USIC_TBCTR_ATBINP_SR1 (1 << USIC_TBCTR_ATBINP_SHIFT) /* Output SR1 becomes activated */ +# define USIC_TBCTR_ATBINP_SR2 (2 << USIC_TBCTR_ATBINP_SHIFT) /* Output SR2 becomes activated */ +# define USIC_TBCTR_ATBINP_SR3 (3 << USIC_TBCTR_ATBINP_SHIFT) /* Output SR3 becomes activated */ +# define USIC_TBCTR_ATBINP_SR4 (4 << USIC_TBCTR_ATBINP_SHIFT) /* Output SR4 becomes activated */ +# define USIC_TBCTR_ATBINP_SR5 (5 << USIC_TBCTR_ATBINP_SHIFT) /* Output SR5 becomes activated */ +#define USIC_TBCTR_SIZE_SHIFT (24) /* Bits 24-26: Buffer Size */ #define USIC_TBCTR_SIZE_MASK (7 << USIC_TBCTR_SIZE_SHIFT) -#define USIC_TBCTR_LOF (1 << 28) /* Bit 28: */ -#define USIC_TBCTR_STBIEN (1 << 30) /* Bit 30: */ -#define USIC_TBCTR_TBERIEN (1 << 31) /* Bit 31: */ +# define USIC_TBCTR_SIZE_DISABLE (0 << USIC_TBCTR_SIZE_SHIFT) /* FIFO mechanism is disabled */ +# define USIC_TBCTR_SIZE_2 (1 << USIC_TBCTR_SIZE_SHIFT) /* FIFO buffer contains 2 entries */ +# define USIC_TBCTR_SIZE_4 (2 << USIC_TBCTR_SIZE_SHIFT) /* FIFO buffer contains 4 entries */ +# define USIC_TBCTR_SIZE_8 (3 << USIC_TBCTR_SIZE_SHIFT) /* FIFO buffer contains 8 entries */ +# define USIC_TBCTR_SIZE_16 (4 << USIC_TBCTR_SIZE_SHIFT) /* FIFO buffer contains 16 entries */ +# define USIC_TBCTR_SIZE_32 (5 << USIC_TBCTR_SIZE_SHIFT) /* FIFO buffer contains 32 entries */ +# define USIC_TBCTR_SIZE_64 (6 << USIC_TBCTR_SIZE_SHIFT) /* FIFO buffer contains 64 entries */ +#define USIC_TBCTR_LOF (1 << 28) /* Bit 28: Buffer Event on Limit Overflow */ +#define USIC_TBCTR_STBIEN (1 << 30) /* Bit 30: Standard Transmit Buffer Interrupt Enable */ +#define USIC_TBCTR_TBERIEN (1 << 31) /* Bit 31: Transmit Buffer Error Interrupt Enable */ /* Receiver Buffer Control Register */ -#define USIC_RBCTR_DPTR_SHIFT (0) /* Bits 0-5: */ +#define USIC_RBCTR_DPTR_SHIFT (0) /* Bits 0-5: Data Pointer */ #define USIC_RBCTR_DPTR_MASK (0x3f << USIC_RBCTR_DPTR_SHIFT) -#define USIC_RBCTR_LIMIT_SHIFT (8) /* Bits 8-13: */ +# define USIC_RBCTR_DPTR(n) ((uint32_t)(n) << USIC_RBCTR_DPTR_SHIFT) +#define USIC_RBCTR_LIMIT_SHIFT (8) /* Bits 8-13: Limit For Interrupt Generation */ #define USIC_RBCTR_LIMIT_MASK (0x3f << USIC_RBCTR_LIMIT_SHIFT) -#define USIC_RBCTR_SRBTM (1 << 14) /* Bit 14: */ -#define USIC_RBCTR_SRBTEN (1 << 15) /* Bit 15: */ -#define USIC_RBCTR_SRBINP_SHIFT (16) /* Bits 16-18: */ +# define USIC_RBCTR_LIMIT(n) ((uint32_t)(n) << USIC_RBCTR_LIMIT_SHIFT) +#define USIC_RBCTR_SRBTM (1 << 14) /* Bit 14: Standard Receive Buffer Trigger Mode */ +#define USIC_RBCTR_SRBTEN (1 << 15) /* Bit 15: Standard Receive Buffer Trigger Enable */ +#define USIC_RBCTR_SRBINP_SHIFT (16) /* Bits 16-18: Standard Receive Buffer Interrupt Node Pointer */ #define USIC_RBCTR_SRBINP_MASK (7 << USIC_RBCTR_SRBINP_SHIFT) -#define USIC_RBCTR_ARBINP_SHIFT (19) /* Bits 19-21: */ +# define USIC_RBCTR_SRBINP_SR0 (0 << USIC_RBCTR_SRBINP_SHIFT) /* Output SR0 becomes activated */ +# define USIC_RBCTR_SRBINP_SR1 (1 << USIC_RBCTR_SRBINP_SHIFT) /* Output SR1 becomes activated */ +# define USIC_RBCTR_SRBINP_SR2 (2 << USIC_RBCTR_SRBINP_SHIFT) /* Output SR2 becomes activated */ +# define USIC_RBCTR_SRBINP_SR3 (3 << USIC_RBCTR_SRBINP_SHIFT) /* Output SR3 becomes activated */ +# define USIC_RBCTR_SRBINP_SR4 (4 << USIC_RBCTR_SRBINP_SHIFT) /* Output SR4 becomes activated */ +# define USIC_RBCTR_SRBINP_SR5 (5 << USIC_RBCTR_SRBINP_SHIFT) /* Output SR5 becomes activated */ +#define USIC_RBCTR_ARBINP_SHIFT (19) /* Bits 19-21: Alternative Receive Buffer Interrupt Node Pointer */ #define USIC_RBCTR_ARBINP_MASK (7 << USIC_RBCTR_ARBINP_SHIFT) -#define USIC_RBCTR_RCIM_SHIFT (22) /* Bits 22-23: */ +# define USIC_RBCTR_ARBINP_SR0 (0 << USIC_RBCTR_ARBINP_SHIFT) /* Output SR0 becomes activated */ +# define USIC_RBCTR_ARBINP_SR1 (1 << USIC_RBCTR_ARBINP_SHIFT) /* Output SR1 becomes activated */ +# define USIC_RBCTR_ARBINP_SR2 (2 << USIC_RBCTR_ARBINP_SHIFT) /* Output SR2 becomes activated */ +# define USIC_RBCTR_ARBINP_SR3 (3 << USIC_RBCTR_ARBINP_SHIFT) /* Output SR3 becomes activated */ +# define USIC_RBCTR_ARBINP_SR4 (4 << USIC_RBCTR_ARBINP_SHIFT) /* Output SR4 becomes activated */ +# define USIC_RBCTR_ARBINP_SR5 (5 << USIC_RBCTR_ARBINP_SHIFT) /* Output SR5 becomes activated */ +#define USIC_RBCTR_RCIM_SHIFT (22) /* Bits 22-23: Receiver Control Information Mode */ #define USIC_RBCTR_RCIM_MASK (3 << USIC_RBCTR_RCIM_SHIFT) -#define USIC_RBCTR_SIZE_SHIFT (24) /* Bits 24-26: */ +# define USIC_RBCTR_RCIM_MODE0 (0 << USIC_RBCTR_RCIM_SHIFT) /* RCI[4] = PERR, RCI[3:0] = WLEN */ +# define USIC_RBCTR_RCIM_MODE1 (1 << USIC_RBCTR_RCIM_SHIFT) /* RCI[4] = SOF, RCI[3:0] = WLEN */ +# define USIC_RBCTR_RCIM_MODE2 (2 << USIC_RBCTR_RCIM_SHIFT) /* RCI[4] = 0, RCI[3:0] = WLEN */ +# define USIC_RBCTR_RCIM_MODE3 (3 << USIC_RBCTR_RCIM_SHIFT) /* RCI[4] = PERR, RCI[3] = PAR, + * RCI[2:1] = 0, RCI[0] = SOF */ +#define USIC_RBCTR_SIZE_SHIFT (24) /* Bits 24-26: Buffer Size */ #define USIC_RBCTR_SIZE_MASK (7 << USIC_RBCTR_SIZE_SHIFT) -#define USIC_RBCTR_RNM (1 << 27) /* Bit 27: */ -#define USIC_RBCTR_LOF (1 << 28) /* Bit 28: */ -#define USIC_RBCTR_ARBIEN (1 << 29) /* Bit 29: */ -#define USIC_RBCTR_SRBIEN (1 << 30) /* Bit 30: */ -#define USIC_RBCTR_RBERIEN (1 << 31) /* Bit 31: */ +# define USIC_RBCTR_SIZE_DISABLE (0 << USIC_RBCTR_SIZE_SHIFT) /* FIFO mechanism is disabled */ +# define USIC_RBCTR_SIZE_2 (1 << USIC_RBCTR_SIZE_SHIFT) /* FIFO buffer contains 2 entries */ +# define USIC_RBCTR_SIZE_4 (2 << USIC_RBCTR_SIZE_SHIFT) /* FIFO buffer contains 4 entries */ +# define USIC_RBCTR_SIZE_8 (3 << USIC_RBCTR_SIZE_SHIFT) /* FIFO buffer contains 8 entries */ +# define USIC_RBCTR_SIZE_16 (4 << USIC_RBCTR_SIZE_SHIFT) /* FIFO buffer contains 16 entries */ +# define USIC_RBCTR_SIZE_32 (5 << USIC_RBCTR_SIZE_SHIFT) /* FIFO buffer contains 32 entries */ +# define USIC_RBCTR_SIZE_64 (6 << USIC_RBCTR_SIZE_SHIFT) /* FIFO buffer contains 64 entries */ +#define USIC_RBCTR_RNM (1 << 27) /* Bit 27: Receiver Notification Mode */ +#define USIC_RBCTR_LOF (1 << 28) /* Bit 28: Buffer Event on Limit Overflow */ +#define USIC_RBCTR_ARBIEN (1 << 29) /* Bit 29: Alternative Receive Buffer Interrupt Enable */ +#define USIC_RBCTR_SRBIEN (1 << 30) /* Bit 30: Standard Receive Buffer Interrupt Enable */ +#define USIC_RBCTR_RBERIEN (1 << 31) /* Bit 31: Receive Buffer Error Interrupt Enable */ /* Transmit/Receive Buffer Pointer Register */ -#define USIC_TRBPTR_TDIPTR_SHIFT (0) /* Bits 0-5: */ +#define USIC_TRBPTR_TDIPTR_SHIFT (0) /* Bits 0-5: Transmitter Data Input Pointer */ #define USIC_TRBPTR_TDIPTR_MASK (0x3f << USIC_TRBPTR_TDIPTR_SHIFT) -#define USIC_TRBPTR_TDOPTR_SHIFT (8) /* Bits 813xx: */ +#define USIC_TRBPTR_TDOPTR_SHIFT (8) /* Bits 8-13: Transmitter Data Output Pointer */ #define USIC_TRBPTR_TDOPTR_MASK (0x3f << USIC_TRBPTR_TDOPTR_SHIFT) -#define USIC_TRBPTR_RDIPTR_SHIFT (16) /* Bits 16-21: */ +#define USIC_TRBPTR_RDIPTR_SHIFT (16) /* Bits 16-21: Receiver Data Input Pointer */ #define USIC_TRBPTR_RDIPTR_MASK (0x3f << USIC_TRBPTR_RDIPTR_SHIFT) -#define USIC_TRBPTR_RDOPTR_SHIFT (24) /* Bits 24-29: */ +#define USIC_TRBPTR_RDOPTR_SHIFT (24) /* Bits 24-29: Receiver Data Output Pointer */ #define USIC_TRBPTR_RDOPTR_MASK (0x3f << USIC_TRBPTR_RDOPTR_SHIFT) /* Transmit/Receive Buffer Status Register */ @@ -1013,21 +1072,21 @@ /* Receiver Buffer Output Register */ -#define USIC_OUTR_DSR_SHIFT (0) /* Bits 0-15: */ +#define USIC_OUTR_DSR_SHIFT (0) /* Bits 0-15: Received Data */ #define USIC_OUTR_DSR_MASK (0xffff << USIC_OUTR_DSR_SHIFT) -#define USIC_OUTR_RCI_SHIFT (16) /* Bits 16-20: */ +#define USIC_OUTR_RCI_SHIFT (16) /* Bits 16-20: Receiver Control Information */ #define USIC_OUTR_RCI_MASK (31 << USIC_OUTR_RCI_SHIFT) /* Receiver Buffer Output Register L for Debugger */ -#define USIC_OUTDR_DSR_SHIFT (0) /* Bits 0-15: */ +#define USIC_OUTDR_DSR_SHIFT (0) /* Bits 0-15: Data from Shift Register */ #define USIC_OUTDR_DSR_MASK (0xffff << USIC_OUTDR_DSR_SHIFT) -#define USIC_OUTDR_RCI_SHIFT (16) /* Bits 16-30: */ +#define USIC_OUTDR_RCI_SHIFT (16) /* Bits 16-30: Receive Control Information from Shift Register */ #define USIC_OUTDR_RCI_MASK (31 << USIC_OUTDR_RCI_SHIFT) /* Transmit FIFO Buffer (32 x 4-bytes) */ -#define USIC_IN_TDATA_SHIFT (0) /* Bits 0-15: */ +#define USIC_IN_TDATA_SHIFT (0) /* Bits 0-15: Transmit Data */ #define USIC_IN_TDATA_MASK (0xffff << USIC_IN_TDATA_SHIFT) #endif /* __ARCH_ARM_SRC_XMC4_CHIP_XMC4_USIC_H */ -- GitLab From a9aa11f968d86db50ebd9f9ec6e37777f32f28ac Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 19 Mar 2017 10:03:31 -0600 Subject: [PATCH 102/990] XMC4xxx: A few compilation issues; still a long way to go. --- arch/arm/src/xmc4/chip/xmc4_pinmux.h | 4 ++-- arch/arm/src/xmc4/chip/xmc4_scu.h | 2 +- arch/arm/src/xmc4/chip/xmc4_usic.h | 14 +++++++------- arch/arm/src/xmc4/xmc4_lowputc.c | 2 +- arch/arm/src/xmc4/xmc4_serial.c | 3 ++- arch/arm/src/xmc4/xmc4_start.c | 1 + 6 files changed, 14 insertions(+), 12 deletions(-) diff --git a/arch/arm/src/xmc4/chip/xmc4_pinmux.h b/arch/arm/src/xmc4/chip/xmc4_pinmux.h index b4ba4b0e24..daece1f509 100644 --- a/arch/arm/src/xmc4/chip/xmc4_pinmux.h +++ b/arch/arm/src/xmc4/chip/xmc4_pinmux.h @@ -748,8 +748,8 @@ #define GPIO_U2C1_HWIN3 (GPIO_INPUT | GPIO_PINCTRL_HW0 | GPIO_PORT4 | GPIO_PIN4) #define GPIO_U2C1_MCLKOUT (GPIO_OUTPUT_ALT1 | GPIO_PORT3 | GPIO_PIN4) #define GPIO_U2C1_SCLKOUT_1 (GPIO_OUTPUT_ALT1 | GPIO_PORT3 | GPIO_PIN13) -#define GPIO_U2C1_SCLKOUT_1 (GPIO_OUTPUT_ALT1 | GPIO_PORT3 | GPIO_PIN6) -#define GPIO_U2C1_SCLKOUT_1 (GPIO_OUTPUT_ALT4 | GPIO_PORT4 | GPIO_PIN2) +#define GPIO_U2C1_SCLKOUT_2 (GPIO_OUTPUT_ALT1 | GPIO_PORT3 | GPIO_PIN6) +#define GPIO_U2C1_SCLKOUT_3 (GPIO_OUTPUT_ALT4 | GPIO_PORT4 | GPIO_PIN2) #define GPIO_U2C1_SELO0_1 (GPIO_OUTPUT_ALT1 | GPIO_PORT3 | GPIO_PIN0) #define GPIO_U2C1_SELO0_2 (GPIO_OUTPUT_ALT1 | GPIO_PORT4 | GPIO_PIN1) #define GPIO_U2C1_SELO1 (GPIO_OUTPUT_ALT1 | GPIO_PORT4 | GPIO_PIN2) diff --git a/arch/arm/src/xmc4/chip/xmc4_scu.h b/arch/arm/src/xmc4/chip/xmc4_scu.h index 0618e7e02b..49b74a3e48 100644 --- a/arch/arm/src/xmc4/chip/xmc4_scu.h +++ b/arch/arm/src/xmc4/chip/xmc4_scu.h @@ -990,7 +990,7 @@ #define SCU_CGATSTAT2_DMA1 (1 << 5) /* Bit 5: DMA1 Gating Status */ #define SCU_CGATSTAT2_FCE (1 << 6) /* Bit 6: FCE Gating Status */ #define SCU_CGATSTAT2_USB (1 << 7) /* Bit 7: USB Gating Status */ -#define SCU_CGATSTAT2_USB (1 << 10) /* Bit 10: ECAT Gating Status */ +#define SCU_CGATSTAT2_ECAT (1 << 10) /* Bit 10: ECAT Gating Status */ /* Peripheral 3 Clock Gating Status, Peripheral 3 Clock Gating Set, Peripheral 3 Clock Gating Clear */ diff --git a/arch/arm/src/xmc4/chip/xmc4_usic.h b/arch/arm/src/xmc4/chip/xmc4_usic.h index 0b49ebfff4..12d4bda2bc 100644 --- a/arch/arm/src/xmc4/chip/xmc4_usic.h +++ b/arch/arm/src/xmc4/chip/xmc4_usic.h @@ -433,9 +433,9 @@ # define USIC_FDR_STEP(n) ((uint32_t)(n) << USIC_FDR_STEP_SHIFT) #define USIC_FDR_DM_SHIFT (14) /* Bits 14-15: Divider Mode */ #define USIC_FDR_DM_MASK (3 << USIC_FDR_DM_SHIFT) -# define USIC_FDR_DM_ OFF (0 << USIC_FDR_DM_SHIFT) /* Divider switched off */ -# define USIC_FDR_DM_ NORMAL (1 << USIC_FDR_DM_SHIFT) /* Normal divider mode selected */ -# define USIC_FDR_DM_ FRACTIONAL (2 << USIC_FDR_DM_SHIFT) /* Fractional divider mode selected */ +# define USIC_FDR_DM_OFF (0 << USIC_FDR_DM_SHIFT) /* Divider switched off */ +# define USIC_FDR_DM_NORMAL (1 << USIC_FDR_DM_SHIFT) /* Normal divider mode selected */ +# define USIC_FDR_DM_FRACTIONAL (2 << USIC_FDR_DM_SHIFT) /* Fractional divider mode selected */ #define USIC_FDR_RESULT_SHIFT (16) /* Bits 16-25: Result Value */ #define USIC_FDR_RESULT_MASK (0x3ff << USIC_FDR_RESULT_SHIFT) @@ -550,7 +550,7 @@ #define USIC_SCTR_HPCDIR (1 << 4) /* Bit 4: Port Control Direction */ #define USIC_SCTR_DOCFG_SHIFT (6) /* Bits 6-7: Data Output Configuration */ #define USIC_SCTR_DOCFG_MASK (3 << USIC_SCTR_DOCFG_SHIFT) - #define USIC_SCTR_DOCFG_SHIFT (0 << USIC_SCTR_DOCFG_SHIFT) /* DOUTx = shift data value */ + #define USIC_SCTR_DOCFG_NORMAL (0 << USIC_SCTR_DOCFG_SHIFT) /* DOUTx = shift data value */ #define USIC_SCTR_DOCFG_INVERT (1 << USIC_SCTR_DOCFG_SHIFT) /* DOUTx = inverted shift data value */ #define USIC_SCTR_TRM_SHIFT (8) /* Bits 8-9: Transmission Mode */ #define USIC_SCTR_TRM_MASK (3 << USIC_SCTR_TRM_SHIFT) @@ -717,9 +717,9 @@ # define USIC_CCR_HPCEN_DX0_2 (3 << USIC_CCR_HPCEN_SHIFT) /* Port control enabled for DX0, DX[5:3] and DOUT[3:0] */ #define USIC_CCR_PM_SHIFT (8) /* Bits 8-9: Parity Mode */ #define USIC_CCR_PM_MASK (3 << USIC_CCR_PM_SHIFT) -# define USIC_CCR_PM_ DISABLE (0 << USIC_CCR_PM_SHIFT) /* Parity generation is disabled */ -# define USIC_CCR_PM_ EVEN (2 << USIC_CCR_PM_SHIFT) /* Even parity is selected */ -# define USIC_CCR_PM_ ODD (3 << USIC_CCR_PM_SHIFT) /* Odd parity is selected */ +# define USIC_CCR_PM_DISABLE (0 << USIC_CCR_PM_SHIFT) /* Parity generation is disabled */ +# define USIC_CCR_PM_EVEN (2 << USIC_CCR_PM_SHIFT) /* Even parity is selected */ +# define USIC_CCR_PM_ODD (3 << USIC_CCR_PM_SHIFT) /* Odd parity is selected */ #define USIC_CCR_RSIEN (1 << 10) /* Bit 10: Receiver Start Interrupt Enable */ #define USIC_CCR_DLIEN (1 << 11) /* Bit 11: Data Lost Interrupt Enable */ #define USIC_CCR_TSIEN (1 << 12) /* Bit 12: Transmit Shift Interrupt Enable */ diff --git a/arch/arm/src/xmc4/xmc4_lowputc.c b/arch/arm/src/xmc4/xmc4_lowputc.c index ec44caba54..28ae38195b 100644 --- a/arch/arm/src/xmc4/xmc4_lowputc.c +++ b/arch/arm/src/xmc4/xmc4_lowputc.c @@ -50,6 +50,7 @@ #include "xmc4_config.h" #include "chip/xmc4_usic.h" #include "chip/xmc4_pinmux.h" +#include "xmc4_lowputc.h" /**************************************************************************** * Pre-processor Definitions @@ -232,4 +233,3 @@ void xmc4_uart_configure(uintptr_t uart_base, uint32_t baud, #warning Missing logic } #endif - diff --git a/arch/arm/src/xmc4/xmc4_serial.c b/arch/arm/src/xmc4/xmc4_serial.c index 509cca5615..4992ddaeb8 100644 --- a/arch/arm/src/xmc4/xmc4_serial.c +++ b/arch/arm/src/xmc4/xmc4_serial.c @@ -57,9 +57,10 @@ #include "up_arch.h" #include "up_internal.h" -#include "xmc4_config.h" #include "chip.h" +#include "xmc4_config.h" #include "chip/xmc4_usic.h" +#include "xmc4_lowputc.h" /**************************************************************************** * Pre-processor Definitions diff --git a/arch/arm/src/xmc4/xmc4_start.c b/arch/arm/src/xmc4/xmc4_start.c index 7bf76f1fae..aade30978f 100644 --- a/arch/arm/src/xmc4/xmc4_start.c +++ b/arch/arm/src/xmc4/xmc4_start.c @@ -52,6 +52,7 @@ #include "chip/xmc4_flash.h" #include "xmc4_userspace.h" +#include "xmc4_lowputc.h" #include "xmc4_start.h" #ifdef CONFIG_ARCH_FPU -- GitLab From 59b9ef8fdcc94e5f376cd8544512eb226baca0bc Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 19 Mar 2017 11:10:31 -0600 Subject: [PATCH 103/990] XMC4xxx: Revise configuration for USICs. Three USICs but 4 UARTs possible with each channel of USIC. --- arch/arm/src/xmc4/Kconfig | 233 +++++++++++++++------------- arch/arm/src/xmc4/xmc4_config.h | 57 ++++--- arch/arm/src/xmc4/xmc4_lowputc.c | 14 +- arch/arm/src/xmc4/xmc4_lowputc.h | 90 +++++++++++ arch/arm/src/xmc4/xmc4_serial.c | 76 ++++----- arch/arm/src/xmc4/xmc4_usic.h | 109 +++++++++++++ configs/xmc4500-relax/nsh/defconfig | 21 ++- 7 files changed, 417 insertions(+), 183 deletions(-) create mode 100644 arch/arm/src/xmc4/xmc4_lowputc.h create mode 100644 arch/arm/src/xmc4/xmc4_usic.h diff --git a/arch/arm/src/xmc4/Kconfig b/arch/arm/src/xmc4/Kconfig index 096a65fb85..c73e281fb5 100644 --- a/arch/arm/src/xmc4/Kconfig +++ b/arch/arm/src/xmc4/Kconfig @@ -66,263 +66,272 @@ config XMC4_USIC1 Support USIC1 config XMC4_USIC2 - bool "USIC3" + bool "USIC2" default n select XMC4_USIC ---help--- Support USIC2 -config XMC4_USIC3 - bool "USIC3" - default n - select XMC4_USIC - ---help--- - Support USIC3 - -config XMC4_USIC4 - bool "USIC4" - default n - select XMC4_USIC - ---help--- - Support USIC4 - -config XMC4_USIC5 - bool "USIC5" - default n - select XMC4_USIC - ---help--- - Support USIC5 - endmenu menu "XMC4xxx USIC Configuration" depends on XMC4_USIC choice - prompt "USIC0 Configuration" - default XMC4_USIC0_ISUART + prompt "USIC0 Channel 0 Configuration" + default XMC4_USIC0_CHAN0_ISUART depends on XMC4_USIC0 -config XMC4_USIC0_ISUART - bool "UART" +config XMC4_USIC0_CHAN0_NONE + bool "Not used" + ---help--- + USIC0 Channel 0 will not be enabled + +config XMC4_USIC0_CHAN0_ISUART + bool "UART0" select UART0_SERIALDRIVER select XMC4_USCI_UART ---help--- - Configure USIC0 as a UART + Configure USIC0 Channel 0 as a UART -config XMC4_USIC0_ISLIN +config XMC4_USIC0_CHAN0_ISLIN bool "LIN" select XMC4_USCI_LIN ---help--- - Configure USIC0 as a LIN UART + Configure USIC0 Channel 0 as a LIN UART -config XMC4_USIC0_ISSPI +config XMC4_USIC0_CHAN0_ISSPI bool "SPI" select XMC4_USCI_SPI ---help--- - Configure USIC0 For SPI communications + Configure USIC0 Channel 0 for SPI communications -config XMC4_USIC0_ISI2C +config XMC4_USIC0_CHAN0_ISI2C bool "I2C" select XMC4_USCI_I2C ---help--- - Configure USIC0 For I2C communications + Configure USIC0 Channel 0 for I2C communications -config XMC4_USIC0_ISI2S +config XMC4_USIC0_CHAN0_ISI2S bool "I2S" select XMC4_USCI_I2S ---help--- - Configure USIC0 For I2S audio + Configure USIC0 Channel 0 for I2S audio -endchoice # USIC0 Configuration +endchoice # USIC0 Channel 0 Configuration choice - prompt "USIC1 Configuration" - default XMC4_USIC1_ISUART - depends on XMC4_USIC1 + prompt "USIC0 Channel 1 Configuration" + default XMC4_USIC0_CHAN1_ISUART + depends on XMC4_USIC0 -config XMC4_USIC1_ISUART - bool "UART" +config XMC4_USIC0_CHAN1_NONE + bool "Not used" + ---help--- + USIC0 Channel 1 will not be enabled + +config XMC4_USIC0_CHAN1_ISUART + bool "UART1" select UART1_SERIALDRIVER select XMC4_USCI_UART ---help--- - Configure USIC1 as a UART + Configure USIC0 Channel 1 as a UART -config XMC4_USIC1_ISLIN +config XMC4_USIC0_CHAN1_ISLIN bool "LIN" select XMC4_USCI_LIN ---help--- - Configure USIC1 as a LIN UART + Configure USIC0 Channel 1 as a LIN UART -config XMC4_USIC1_ISSPI +config XMC4_USIC0_CHAN1_ISSPI bool "SPI" select XMC4_USCI_SPI ---help--- - Configure USIC1 For SPI communications + Configure USIC0 Channel 1 for SPI communications -config XMC4_USIC1_ISI2C +config XMC4_USIC0_CHAN1_ISI2C bool "I2C" select XMC4_USCI_I2C ---help--- - Configure USIC1 For I2C communications + Configure USIC0 Channel 1 for I2C communications -config XMC4_USIC1_ISI2S +config XMC4_USIC0_CHAN1_ISI2S bool "I2S" select XMC4_USCI_I2S ---help--- - Configure USIC1 For I2S audio + Configure USIC0 Channel 1 for I2S audio -endchoice # USIC1 Configuration +endchoice # USIC0 Channel 1 Configuration choice - prompt "USIC2 Configuration" - default XMC4_USIC2_ISUART - depends on XMC4_USIC2 + prompt "USIC1 Channel 0 Configuration" + default XMC4_USIC1_CHAN0_ISUART + depends on XMC4_USIC1 -config XMC4_USIC2_ISUART - bool "UART" +config XMC4_USIC1_CHAN0_NONE + bool "Not used" + ---help--- + USIC0 Channel 0 will not be enabled + +config XMC4_USIC1_CHAN0_ISUART + bool "UART2" select UART2_SERIALDRIVER select XMC4_USCI_UART ---help--- - Configure USIC2 as a UART + Configure USIC1 Channel 0 as a UART -config XMC4_USIC2_ISLIN +config XMC4_USIC1_CHAN0_ISLIN bool "LIN" select XMC4_USCI_LIN ---help--- - Configure USIC2 as a LIN UART + Configure USIC1 Channel 0 as a LIN UART -config XMC4_USIC2_ISSPI +config XMC4_USIC1_CHAN0_ISSPI bool "SPI" select XMC4_USCI_SPI ---help--- - Configure USIC2 For SPI communications + Configure USIC1 Channel 0 for SPI communications -config XMC4_USIC2_ISI2C +config XMC4_USIC1_CHAN0_ISI2C bool "I2C" select XMC4_USCI_I2C ---help--- - Configure USIC2 For I2C communications + Configure USIC1 Channel 0 for I2C communications -config XMC4_USIC2_ISI2S +config XMC4_USIC1_CHAN0_ISI2S bool "I2S" select XMC4_USCI_I2S ---help--- - Configure USIC2 For I2S audio + Configure USIC1 Channel 0 for I2S audio -endchoice # USIC2 Configuration +endchoice # USIC1 Channel 0 Configuration choice - prompt "USIC3 Configuration" - default XMC4_USIC3_ISUART - depends on XMC4_USIC3 + prompt "USIC1 Channel 1 Configuration" + default XMC4_USIC1_CHAN1_ISUART + depends on XMC4_USIC1 + +config XMC4_USIC1_CHAN1_NONE + bool "Not used" + ---help--- + USIC0 Channel 1 will not be enabled -config XMC4_USIC3_ISUART - bool "UART" +config XMC4_USIC1_CHAN1_ISUART + bool "UART3" select UART3_SERIALDRIVER select XMC4_USCI_UART ---help--- - Configure USIC3 as a UART + Configure USIC1 Channel 1 as a UART -config XMC4_USIC3_ISLIN +config XMC4_USIC1_CHAN1_ISLIN bool "LIN" select XMC4_USCI_LIN ---help--- - Configure USIC3 as a LIN UART + Configure USIC1 Channel 1 as a LIN UART -config XMC4_USIC3_ISSPI +config XMC4_USIC1_CHAN1_ISSPI bool "SPI" select XMC4_USCI_SPI ---help--- - Configure USIC3 For SPI communications + Configure USIC1 Channel 1 for SPI communications -config XMC4_USIC3_ISI2C +config XMC4_USIC1_CHAN1_ISI2C bool "I2C" select XMC4_USCI_I2C ---help--- - Configure USIC3 For I2C communications + Configure USIC1 Channel 1 for I2C communications -config XMC4_USIC3_ISI2S +config XMC4_USIC1_CHAN1_ISI2S bool "I2S" select XMC4_USCI_I2S ---help--- - Configure USIC3 For I2S audio + Configure USIC1 Channel 1 for I2S audio -endchoice # USIC3 Configuration +endchoice # USIC1 Channel 1 Configuration choice - prompt "USIC4 Configuration" - default XMC4_USIC4_ISUART - depends on XMC4_USIC4 + prompt "USIC2 Channel 0 Configuration" + default XMC4_USIC2_CHAN0_ISUART + depends on XMC4_USIC2 + +config XMC4_USIC2_CHAN0_NONE + bool "Not used" + ---help--- + USIC0 Channel 0 will not be enabled -config XMC4_USIC4_ISUART - bool "UART" +config XMC4_USIC2_CHAN0_ISUART + bool "UART4" select UART4_SERIALDRIVER select XMC4_USCI_UART ---help--- - Configure USIC4 as a UART + Configure USIC2 Channel 0 as a UART -config XMC4_USIC4_ISLIN +config XMC4_USIC2_CHAN0_ISLIN bool "LIN" select XMC4_USCI_LIN ---help--- - Configure USIC4 as a LIN UART + Configure USIC2 Channel 0 as a LIN UART -config XMC4_USIC4_ISSPI +config XMC4_USIC2_CHAN0_ISSPI bool "SPI" select XMC4_USCI_SPI ---help--- - Configure USIC4 For SPI communications + Configure USIC2 Channel 0 for SPI communications -config XMC4_USIC4_ISI2C +config XMC4_USIC2_CHAN0_ISI2C bool "I2C" select XMC4_USCI_I2C ---help--- - Configure USIC4 For I2C communications + Configure USIC2 Channel 0 for I2C communications -config XMC4_USIC4_ISI2S +config XMC4_USIC2_CHAN0_ISI2S bool "I2S" select XMC4_USCI_I2S ---help--- - Configure USIC4 For I2S audio + Configure USIC2 Channel 0 for I2S audio -endchoice # USIC4 Configuration +endchoice # USIC2 Channel 0 Configuration choice - prompt "USIC5 Configuration" - default XMC4_USIC5_ISUART - depends on XMC4_USIC5 + prompt "USIC2 Channel 1 Configuration" + default XMC4_USIC2_CHAN1_ISUART + depends on XMC4_USIC2 -config XMC4_USIC5_ISUART - bool "UART" - select UART0_SERIALDRIVER +config XMC4_USIC2_CHAN1_NONE + bool "Not used" + ---help--- + USIC0 Channel 1 will not be enabled + +config XMC4_USIC2_CHAN1_ISUART + bool "UART5" + select UART5_SERIALDRIVER select XMC4_USCI_UART ---help--- - Configure USIC5 as a UART + Configure USIC2 Channel 1 as a UART -config XMC4_USIC5_ISLIN +config XMC4_USIC2_CHAN1_ISLIN bool "LIN" select XMC4_USCI_LIN ---help--- - Configure USIC5 as a LIN UART + Configure USIC2 Channel 1 as a LIN UART -config XMC4_USIC5_ISSPI +config XMC4_USIC2_CHAN1_ISSPI bool "SPI" select XMC4_USCI_SPI ---help--- - Configure USIC5 For SPI communications + Configure USIC2 Channel 1 for SPI communications -config XMC4_USIC5_ISI2C +config XMC4_USIC2_CHAN1_ISI2C bool "I2C" select XMC4_USCI_I2C ---help--- - Configure USIC5 For I2C communications + Configure USIC2 Channel 1 for I2C communications -config XMC4_USIC5_ISI2S +config XMC4_USIC2_CHAN1_ISI2S bool "I2S" select XMC4_USCI_I2S ---help--- - Configure USIC5 For I2S audio + Configure USIC2 Channel 1 for I2S audio -endchoice # USIC5 Configuration +endchoice # USIC2 Channel 1 Configuration endmenu # XMC4xxx USIC Configuration diff --git a/arch/arm/src/xmc4/xmc4_config.h b/arch/arm/src/xmc4/xmc4_config.h index e81932569e..0a9c204268 100644 --- a/arch/arm/src/xmc4/xmc4_config.h +++ b/arch/arm/src/xmc4/xmc4_config.h @@ -53,30 +53,51 @@ /* Make sure that no unsupported UARTs are enabled */ #ifndef CONFIG_XMC4_USIC0 -# undef CONFIG_XMC4_USIC0_ISUART +# undef CONFIG_XMC4_USIC0_CHAN0_ISUART +# undef CONFIG_XMC4_USIC0_CHAN1_ISUART #endif #ifndef CONFIG_XMC4_USIC1 -# undef CONFIG_XMC4_USIC1_ISUART +# undef CONFIG_XMC4_USIC1_CHAN0_ISUART +# undef CONFIG_XMC4_USIC1_CHAN1_ISUART #endif #ifndef CONFIG_XMC4_USIC2 -# undef CONFIG_XMC4_USIC2_ISUART +# undef CONFIG_XMC4_USIC2_CHAN0_ISUART +# undef CONFIG_XMC4_USIC2_CHAN1_ISUART #endif -#ifndef CONFIG_XMC4_USIC3 -# undef CONFIG_XMC4_USIC3_ISUART + +/* Map logical UART names (Just for simplicity of naming) */ + +#undef HAVE_UART0 +#undef HAVE_UART1 +#undef HAVE_UART2 +#undef HAVE_UART3 +#undef HAVE_UART4 +#undef HAVE_UART5 + +#ifdef CONFIG_XMC4_USIC0_CHAN0_ISUART +# define HAVE_UART0 +#endif +#ifdef CONFIG_XMC4_USIC0_CHAN1_ISUART +# define HAVE_UART1 +#endif +#ifdef CONFIG_XMC4_USIC1_CHAN0_ISUART +# define HAVE_UART2 +#endif +#ifdef CONFIG_XMC4_USIC1_CHAN1_ISUART +# define HAVE_UART3 #endif -#ifndef CONFIG_XMC4_USIC4 -# undef CONFIG_XMC4_USIC4_ISUART +#ifdef CONFIG_XMC4_USIC2_CHAN0_ISUART +# define HAVE_UART4 #endif -#ifndef CONFIG_XMC4_USIC5 -# undef CONFIG_XMC4_USIC5_ISUART +#ifdef CONFIG_XMC4_USIC2_CHAN1_ISUART +# define HAVE_UART5 #endif /* Are any UARTs enabled? */ #undef HAVE_UART_DEVICE -#if defined(CONFIG_XMC4_USIC0_ISUART) || defined(CONFIG_XMC4_USIC1_ISUART) || \ - defined(CONFIG_XMC4_USIC2_ISUART) || defined(CONFIG_XMC4_USIC3_ISUART) || \ - defined(CONFIG_XMC4_USIC3_ISUART) || defined(CONFIG_XMC4_USIC4_ISUART) +#if defined(HAVE_UART0) || defined(HAVE_UART1) || defined(HAVE_UART2) || \ + defined(HAVE_UART3) || defined(HAVE_UART4) || defined(HAVE_UART5) # define HAVE_UART_DEVICE 1 #endif @@ -94,42 +115,42 @@ # undef CONFIG_UART4_SERIAL_CONSOLE # undef CONFIG_UART5_SERIAL_CONSOLE #else -# if defined(CONFIG_UART0_SERIAL_CONSOLE) && defined(CONFIG_XMC4_USIC0_ISUART) +# if defined(CONFIG_UART0_SERIAL_CONSOLE) && defined(HAVE_UART0) # undef CONFIG_UART1_SERIAL_CONSOLE # undef CONFIG_UART2_SERIAL_CONSOLE # undef CONFIG_UART3_SERIAL_CONSOLE # undef CONFIG_UART4_SERIAL_CONSOLE # undef CONFIG_UART5_SERIAL_CONSOLE # define HAVE_UART_CONSOLE 1 -# elif defined(CONFIG_UART1_SERIAL_CONSOLE) && defined(CONFIG_XMC4_USIC1_ISUART) +# elif defined(CONFIG_UART1_SERIAL_CONSOLE) && defined(HAVE_UART1) # undef CONFIG_UART0_SERIAL_CONSOLE # undef CONFIG_UART2_SERIAL_CONSOLE # undef CONFIG_UART3_SERIAL_CONSOLE # undef CONFIG_UART4_SERIAL_CONSOLE # undef CONFIG_UART5_SERIAL_CONSOLE # define HAVE_UART_CONSOLE 1 -# elif defined(CONFIG_UART2_SERIAL_CONSOLE) && defined(CONFIG_XMC4_USIC2_ISUART) +# elif defined(CONFIG_UART2_SERIAL_CONSOLE) && defined(HAVE_UART2) # undef CONFIG_UART0_SERIAL_CONSOLE # undef CONFIG_UART1_SERIAL_CONSOLE # undef CONFIG_UART3_SERIAL_CONSOLE # undef CONFIG_UART4_SERIAL_CONSOLE # undef CONFIG_UART5_SERIAL_CONSOLE # define HAVE_UART_CONSOLE 1 -# elif defined(CONFIG_UART3_SERIAL_CONSOLE) && defined(CONFIG_XMC4_USIC3_ISUART) +# elif defined(CONFIG_UART3_SERIAL_CONSOLE) && defined(HAVE_UART3) # undef CONFIG_UART0_SERIAL_CONSOLE # undef CONFIG_UART1_SERIAL_CONSOLE # undef CONFIG_UART2_SERIAL_CONSOLE # undef CONFIG_UART4_SERIAL_CONSOLE # undef CONFIG_UART5_SERIAL_CONSOLE # define HAVE_UART_CONSOLE 1 -# elif defined(CONFIG_UART4_SERIAL_CONSOLE) && defined(CONFIG_XMC4_USIC4_ISUART) +# elif defined(CONFIG_UART4_SERIAL_CONSOLE) && defined(HAVE_UART4) # undef CONFIG_UART0_SERIAL_CONSOLE # undef CONFIG_UART1_SERIAL_CONSOLE # undef CONFIG_UART2_SERIAL_CONSOLE # undef CONFIG_UART3_SERIAL_CONSOLE # undef CONFIG_UART5_SERIAL_CONSOLE # define HAVE_UART_CONSOLE 1 -# elif defined(CONFIG_UART5_SERIAL_CONSOLE) && defined(CONFIG_XMC4_USIC5_ISUART) +# elif defined(CONFIG_UART5_SERIAL_CONSOLE) && defined(HAVE_UART5) # undef CONFIG_UART0_SERIAL_CONSOLE # undef CONFIG_UART1_SERIAL_CONSOLE # undef CONFIG_UART2_SERIAL_CONSOLE diff --git a/arch/arm/src/xmc4/xmc4_lowputc.c b/arch/arm/src/xmc4/xmc4_lowputc.c index 28ae38195b..6df364565c 100644 --- a/arch/arm/src/xmc4/xmc4_lowputc.c +++ b/arch/arm/src/xmc4/xmc4_lowputc.c @@ -60,42 +60,42 @@ #if defined(HAVE_UART_CONSOLE) # if defined(CONFIG_UART0_SERIAL_CONSOLE) -# define CONSOLE_BASE XMC4_UART0_BASE +# define CONSOLE_BASE XMC4_USIC0_CH0_BASE # define CONSOLE_FREQ BOARD_CORECLK_FREQ # define CONSOLE_BAUD CONFIG_UART0_BAUD # define CONSOLE_BITS CONFIG_UART0_BITS # define CONSOLE_2STOP CONFIG_UART0_2STOP # define CONSOLE_PARITY CONFIG_UART0_PARITY # elif defined(CONFIG_UART1_SERIAL_CONSOLE) -# define CONSOLE_BASE XMC4_UART1_BASE +# define CONSOLE_BASE XMC4_USIC0_CH1_BASE # define CONSOLE_FREQ BOARD_CORECLK_FREQ # define CONSOLE_BAUD CONFIG_UART1_BAUD # define CONSOLE_BITS CONFIG_UART1_BITS # define CONSOLE_2STOP CONFIG_UART1_2STOP # define CONSOLE_PARITY CONFIG_UART1_PARITY # elif defined(CONFIG_UART2_SERIAL_CONSOLE) -# define CONSOLE_BASE XMC4_UART2_BASE +# define CONSOLE_BASE XMC4_USIC1_CH0_BASE # define CONSOLE_FREQ BOARD_BUS_FREQ # define CONSOLE_BAUD CONFIG_UART2_BAUD # define CONSOLE_BITS CONFIG_UART2_BITS # define CONSOLE_2STOP CONFIG_UART2_2STOP # define CONSOLE_PARITY CONFIG_UART2_PARITY # elif defined(CONFIG_UART3_SERIAL_CONSOLE) -# define CONSOLE_BASE XMC4_UART3_BASE +# define CONSOLE_BASE XMC4_USIC1_CH1_BASE # define CONSOLE_FREQ BOARD_BUS_FREQ # define CONSOLE_BAUD CONFIG_UART3_BAUD # define CONSOLE_BITS CONFIG_UART3_BITS # define CONSOLE_2STOP CONFIG_UART3_2STOP # define CONSOLE_PARITY CONFIG_UART3_PARITY # elif defined(CONFIG_UART4_SERIAL_CONSOLE) -# define CONSOLE_BASE XMC4_UART4_BASE +# define CONSOLE_BASE XMC4_USIC2_CH0_BASE # define CONSOLE_FREQ BOARD_BUS_FREQ # define CONSOLE_BAUD CONFIG_UART4_BAUD # define CONSOLE_BITS CONFIG_UART4_BITS # define CONSOLE_2STOP CONFIG_UART4_2STOP # define CONSOLE_PARITY CONFIG_UART4_PARITY # elif defined(CONFIG_UART5_SERIAL_CONSOLE) -# define CONSOLE_BASE XMC4_UART5_BASE +# define CONSOLE_BASE XMC4_USIC2_CH1_BASE # define CONSOLE_FREQ BOARD_BUS_FREQ # define CONSOLE_BAUD CONFIG_UART5_BAUD # define CONSOLE_BITS CONFIG_UART5_BITS @@ -161,7 +161,7 @@ void xmc4_lowsetup(void) uint32_t regval; /* Enable peripheral clocking for all enabled UARTs. */ -#wanring Missing logic +#warning Missing logic /* Configure UART pins for the all enabled UARTs */ diff --git a/arch/arm/src/xmc4/xmc4_lowputc.h b/arch/arm/src/xmc4/xmc4_lowputc.h new file mode 100644 index 0000000000..7287855a7b --- /dev/null +++ b/arch/arm/src/xmc4/xmc4_lowputc.h @@ -0,0 +1,90 @@ +/**************************************************************************** + * arch/arm/src/xmc4/xmc4_lowputc.h + * + * 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. + * + ****************************************************************************/ + +#ifndef __ARCH_ARM_SRC_XMC4_XMC4_LOWPUTC_H +#define __ARCH_ARM_SRC_XMC4_XMC4_LOWPUTC_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include "xmc4_config.h" + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Name: xmc4_lowsetup + * + * Description: + * This performs basic initialization of the UART used for the serial + * console. Its purpose is to get the console output available as soon + * as possible. + * + ****************************************************************************/ + +void xmc4_lowsetup(void); + +/**************************************************************************** + * Name: xmc4_uart_reset + * + * Description: + * Reset a UART. + * + ****************************************************************************/ + +#ifdef HAVE_UART_DEVICE +void xmc4_uart_reset(uintptr_t uart_base); +#endif + +/**************************************************************************** + * Name: xmc4_uart_configure + * + * Description: + * Configure a UART as a RS-232 UART. + * + ****************************************************************************/ + +#ifdef HAVE_UART_DEVICE +void xmc4_uart_configure(uintptr_t uart_base, uint32_t baud, + uint32_t clock, unsigned int parity, + unsigned int nbits, unsigned int stop2); +#endif + + +#endif /* __ARCH_ARM_SRC_XMC4_XMC4_LOWPUTC_H */ diff --git a/arch/arm/src/xmc4/xmc4_serial.c b/arch/arm/src/xmc4/xmc4_serial.c index 4992ddaeb8..e09a23ef55 100644 --- a/arch/arm/src/xmc4/xmc4_serial.c +++ b/arch/arm/src/xmc4/xmc4_serial.c @@ -110,22 +110,22 @@ # define UART5_ASSIGNED 1 #else # undef CONSOLE_DEV /* No console */ -# if defined(CONFIG_XMC4_USIC0_ISUART) +# if defined(HAVE_UART0) # define TTYS0_DEV g_uart0port /* UART0 is ttyS0 */ # define UART0_ASSIGNED 1 -# elif defined(CONFIG_XMC4_USIC1_ISUART) +# elif defined(HAVE_UART1) # define TTYS0_DEV g_uart1port /* UART1 is ttyS0 */ # define UART1_ASSIGNED 1 -# elif defined(CONFIG_XMC4_USIC2_ISUART) +# elif defined(HAVE_UART2) # define TTYS0_DEV g_uart2port /* UART2 is ttyS0 */ # define UART2_ASSIGNED 1 -# elif defined(CONFIG_XMC4_USIC3_ISUART) +# elif defined(HAVE_UART3) # define TTYS0_DEV g_uart3port /* UART3 is ttyS0 */ # define UART3_ASSIGNED 1 -# elif defined(CONFIG_XMC4_USIC4_ISUART) +# elif defined(HAVE_UART4) # define TTYS0_DEV g_uart4port /* UART4 is ttyS0 */ # define UART4_ASSIGNED 1 -# elif defined(CONFIG_XMC4_USIC5_ISUART) +# elif defined(HAVE_UART5) # define TTYS0_DEV g_uart5port /* UART5 is ttyS0 */ # define UART5_ASSIGNED 1 # endif @@ -133,22 +133,22 @@ /* Pick ttys1. This could be any of UART0-5 excluding the console UART. */ -#if defined(CONFIG_XMC4_USIC0_ISUART) && !defined(UART0_ASSIGNED) +#if defined(HAVE_UART0) && !defined(UART0_ASSIGNED) # define TTYS1_DEV g_uart0port /* UART0 is ttyS1 */ # define UART0_ASSIGNED 1 -#elif defined(CONFIG_XMC4_USIC1_ISUART) && !defined(UART1_ASSIGNED) +#elif defined(HAVE_UART1) && !defined(UART1_ASSIGNED) # define TTYS1_DEV g_uart1port /* UART1 is ttyS1 */ # define UART1_ASSIGNED 1 -#elif defined(CONFIG_XMC4_USIC2_ISUART) && !defined(UART2_ASSIGNED) +#elif defined(HAVE_UART2) && !defined(UART2_ASSIGNED) # define TTYS1_DEV g_uart2port /* UART2 is ttyS1 */ # define UART2_ASSIGNED 1 -#elif defined(CONFIG_XMC4_USIC3_ISUART) && !defined(UART3_ASSIGNED) +#elif defined(HAVE_UART3) && !defined(UART3_ASSIGNED) # define TTYS1_DEV g_uart3port /* UART3 is ttyS1 */ # define UART3_ASSIGNED 1 -#elif defined(CONFIG_XMC4_USIC4_ISUART) && !defined(UART4_ASSIGNED) +#elif defined(HAVE_UART4) && !defined(UART4_ASSIGNED) # define TTYS1_DEV g_uart4port /* UART4 is ttyS1 */ # define UART4_ASSIGNED 1 -#elif defined(CONFIG_XMC4_USIC5_ISUART) && !defined(UART5_ASSIGNED) +#elif defined(HAVE_UART5) && !defined(UART5_ASSIGNED) # define TTYS1_DEV g_uart5port /* UART5 is ttyS1 */ # define UART5_ASSIGNED 1 #endif @@ -158,19 +158,19 @@ * console. */ -#if defined(CONFIG_XMC4_USIC1_ISUART) && !defined(UART1_ASSIGNED) +#if defined(HAVE_UART1) && !defined(UART1_ASSIGNED) # define TTYS2_DEV g_uart1port /* UART1 is ttyS2 */ # define UART1_ASSIGNED 1 -#elif defined(CONFIG_XMC4_USIC2_ISUART) && !defined(UART2_ASSIGNED) +#elif defined(HAVE_UART2) && !defined(UART2_ASSIGNED) # define TTYS2_DEV g_uart2port /* UART2 is ttyS2 */ # define UART2_ASSIGNED 1 -#elif defined(CONFIG_XMC4_USIC3_ISUART) && !defined(UART3_ASSIGNED) +#elif defined(HAVE_UART3) && !defined(UART3_ASSIGNED) # define TTYS2_DEV g_uart3port /* UART3 is ttyS2 */ # define UART3_ASSIGNED 1 -#elif defined(CONFIG_XMC4_USIC4_ISUART) && !defined(UART4_ASSIGNED) +#elif defined(HAVE_UART4) && !defined(UART4_ASSIGNED) # define TTYS2_DEV g_uart4port /* UART4 is ttyS2 */ # define UART4_ASSIGNED 1 -#elif defined(CONFIG_XMC4_USIC5_ISUART) && !defined(UART5_ASSIGNED) +#elif defined(HAVE_UART5) && !defined(UART5_ASSIGNED) # define TTYS2_DEV g_uart5port /* UART5 is ttyS2 */ # define UART5_ASSIGNED 1 #endif @@ -180,16 +180,16 @@ * UART 2-5 could also be the console. */ -#if defined(CONFIG_XMC4_USIC2_ISUART) && !defined(UART2_ASSIGNED) +#if defined(HAVE_UART2) && !defined(UART2_ASSIGNED) # define TTYS3_DEV g_uart2port /* UART2 is ttyS3 */ # define UART2_ASSIGNED 1 -#elif defined(CONFIG_XMC4_USIC3_ISUART) && !defined(UART3_ASSIGNED) +#elif defined(HAVE_UART3) && !defined(UART3_ASSIGNED) # define TTYS3_DEV g_uart3port /* UART3 is ttyS3 */ # define UART3_ASSIGNED 1 -#elif defined(CONFIG_XMC4_USIC4_ISUART) && !defined(UART4_ASSIGNED) +#elif defined(HAVE_UART4) && !defined(UART4_ASSIGNED) # define TTYS3_DEV g_uart4port /* UART4 is ttyS3 */ # define UART4_ASSIGNED 1 -#elif defined(CONFIG_XMC4_USIC5_ISUART) && !defined(UART5_ASSIGNED) +#elif defined(HAVE_UART5) && !defined(UART5_ASSIGNED) # define TTYS3_DEV g_uart5port /* UART5 is ttyS3 */ # define UART5_ASSIGNED 1 #endif @@ -199,13 +199,13 @@ * UART 3-5 could also be the console. */ -#if defined(CONFIG_XMC4_USIC3_ISUART) && !defined(UART3_ASSIGNED) +#if defined(HAVE_UART3) && !defined(UART3_ASSIGNED) # define TTYS4_DEV g_uart3port /* UART3 is ttyS4 */ # define UART3_ASSIGNED 1 -#elif defined(CONFIG_XMC4_USIC4_ISUART) && !defined(UART4_ASSIGNED) +#elif defined(HAVE_UART4) && !defined(UART4_ASSIGNED) # define TTYS4_DEV g_uart4port /* UART4 is ttyS4 */ # define UART4_ASSIGNED 1 -#elif defined(CONFIG_XMC4_USIC5_ISUART) && !defined(UART5_ASSIGNED) +#elif defined(HAVE_UART5) && !defined(UART5_ASSIGNED) # define TTYS4_DEV g_uart5port /* UART5 is ttyS4 */ # define UART5_ASSIGNED 1 #endif @@ -215,10 +215,10 @@ * UART 4-5 could also be the console. */ -#if defined(CONFIG_XMC4_USIC4_ISUART) && !defined(UART4_ASSIGNED) +#if defined(HAVE_UART4) && !defined(UART4_ASSIGNED) # define TTYS5_DEV g_uart4port /* UART4 is ttyS5 */ # define UART4_ASSIGNED 1 -#elif defined(CONFIG_XMC4_USIC5_ISUART) && !defined(UART5_ASSIGNED) +#elif defined(HAVE_UART5) && !defined(UART5_ASSIGNED) # define TTYS5_DEV g_uart5port /* UART5 is ttyS5 */ # define UART5_ASSIGNED 1 #endif @@ -282,34 +282,34 @@ static const struct uart_ops_s g_uart_ops = /* I/O buffers */ -#ifdef CONFIG_XMC4_USIC0_ISUART +#ifdef HAVE_UART0 static char g_uart0rxbuffer[CONFIG_UART0_RXBUFSIZE]; static char g_uart0txbuffer[CONFIG_UART0_TXBUFSIZE]; #endif -#ifdef CONFIG_XMC4_USIC1_ISUART +#ifdef HAVE_UART1 static char g_uart1rxbuffer[CONFIG_UART1_RXBUFSIZE]; static char g_uart1txbuffer[CONFIG_UART1_TXBUFSIZE]; #endif -#ifdef CONFIG_XMC4_USIC2_ISUART +#ifdef HAVE_UART2 static char g_uart2rxbuffer[CONFIG_UART2_RXBUFSIZE]; static char g_uart2txbuffer[CONFIG_UART2_TXBUFSIZE]; #endif -#ifdef CONFIG_XMC4_USIC3_ISUART +#ifdef HAVE_UART3 static char g_uart3rxbuffer[CONFIG_UART3_RXBUFSIZE]; static char g_uart3txbuffer[CONFIG_UART3_TXBUFSIZE]; #endif -#ifdef CONFIG_XMC4_USIC4_ISUART +#ifdef HAVE_UART4 static char g_uart4rxbuffer[CONFIG_UART4_RXBUFSIZE]; static char g_uart4txbuffer[CONFIG_UART4_TXBUFSIZE]; #endif -#ifdef CONFIG_XMC4_USIC5_ISUART +#ifdef HAVE_UART5 static char g_uart5rxbuffer[CONFIG_UART5_RXBUFSIZE]; static char g_uart5txbuffer[CONFIG_UART5_TXBUFSIZE]; #endif /* This describes the state of the Kinetis UART0 port. */ -#ifdef CONFIG_XMC4_USIC0_ISUART +#ifdef HAVE_UART0 static struct xmc4_dev_s g_uart0priv = { .uartbase = XMC4_UART0_BASE, @@ -340,7 +340,7 @@ static uart_dev_t g_uart0port = /* This describes the state of the Kinetis UART1 port. */ -#ifdef CONFIG_XMC4_USIC1_ISUART +#ifdef HAVE_UART1 static struct xmc4_dev_s g_uart1priv = { .uartbase = XMC4_UART1_BASE, @@ -371,7 +371,7 @@ static uart_dev_t g_uart1port = /* This describes the state of the Kinetis UART2 port. */ -#ifdef CONFIG_XMC4_USIC2_ISUART +#ifdef HAVE_UART2 static struct xmc4_dev_s g_uart2priv = { .uartbase = XMC4_UART2_BASE, @@ -402,7 +402,7 @@ static uart_dev_t g_uart2port = /* This describes the state of the Kinetis UART3 port. */ -#ifdef CONFIG_XMC4_USIC3_ISUART +#ifdef HAVE_UART3 static struct xmc4_dev_s g_uart3priv = { .uartbase = XMC4_UART3_BASE, @@ -433,7 +433,7 @@ static uart_dev_t g_uart3port = /* This describes the state of the Kinetis UART4 port. */ -#ifdef CONFIG_XMC4_USIC4_ISUART +#ifdef HAVE_UART4 static struct xmc4_dev_s g_uart4priv = { .uartbase = XMC4_UART4_BASE, @@ -464,7 +464,7 @@ static uart_dev_t g_uart4port = /* This describes the state of the Kinetis UART5 port. */ -#ifdef CONFIG_XMC4_USIC5_ISUART +#ifdef HAVE_UART5 static struct xmc4_dev_s g_uart5priv = { .uartbase = XMC4_UART5_BASE, diff --git a/arch/arm/src/xmc4/xmc4_usic.h b/arch/arm/src/xmc4/xmc4_usic.h new file mode 100644 index 0000000000..d589459037 --- /dev/null +++ b/arch/arm/src/xmc4/xmc4_usic.h @@ -0,0 +1,109 @@ +/**************************************************************************** + * arch/arm/src/xmc4/xmc4_usic.h + * + * 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. + * + ****************************************************************************/ + +#ifndef __ARCH_ARM_SRC_XMC4_XMC4_USIC_H +#define __ARCH_ARM_SRC_XMC4_XMC4_USIC_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include "xmc4_config.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* This enumeration identifies the USIC */ + +enum usic_e +{ + USIC0 = 0, /* USIC0 */ + USIC1 = 1, /* USIC1 */ + USIC2 = 2 /* USIC2 */ +}; + +/* This enumeration identifies USIC channels */ + +enum usic_channel_e +{ + USIC0_CHAN0 = 0, /* USIC0, Channel 0 */ + USIC0_CHAN1 = 1, /* USIC0, Channel 1 */ + USIC1_CHAN0 = 0, /* USIC1, Channel 0 */ + USIC1_CHAN1 = 1, /* USIC1, Channel 1 */ + USIC2_CHAN0 = 0, /* USIC2, Channel 0 */ + USIC2_CHAN1 = 1 /* USIC2, Channel 1 */ +}; + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Name: xmc4_enable_usic + * + * Description: + * Enable the USIC module indicated by the 'usic' enumeration value + * + * Returned Value: + * Zero (OK) is returned on success; A negated errno value is returned to + * indicate the nature of any failure. + * + ****************************************************************************/ + +int xmc4_enable_usic(enum usic_e usic); + +/**************************************************************************** + * Name: xmc4_enable_usic_channel + * + * Description: + * Enable the USIC channel indicated by 'channel'. Also enable and reset + * the USIC module if it is not already enabled. + * + * Returned Value: + * Zero (OK) is returned on success; A negated errno value is returned to + * indicate the nature of any failure. + * + ****************************************************************************/ + +int xmc4_enable_usic_channel(enum usic_channel_e channel); + +#endif /* __ARCH_ARM_SRC_XMC4_XMC4_USIC_H */ diff --git a/configs/xmc4500-relax/nsh/defconfig b/configs/xmc4500-relax/nsh/defconfig index 54bd16a392..f938e18bc4 100644 --- a/configs/xmc4500-relax/nsh/defconfig +++ b/configs/xmc4500-relax/nsh/defconfig @@ -177,18 +177,22 @@ CONFIG_XMC4_USCI_UART=y CONFIG_XMC4_USIC0=y # CONFIG_XMC4_USIC1 is not set # CONFIG_XMC4_USIC2 is not set -# CONFIG_XMC4_USIC3 is not set -# CONFIG_XMC4_USIC4 is not set -# CONFIG_XMC4_USIC5 is not set # # XMC4xxx USIC Configuration # -CONFIG_XMC4_USIC0_ISUART=y -# CONFIG_XMC4_USIC0_ISLIN is not set -# CONFIG_XMC4_USIC0_ISSPI is not set -# CONFIG_XMC4_USIC0_ISI2C is not set -# CONFIG_XMC4_USIC0_ISI2S is not set +# CONFIG_XMC4_USIC0_CHAN0_NONE is not set +CONFIG_XMC4_USIC0_CHAN0_ISUART=y +# CONFIG_XMC4_USIC0_CHAN0_ISLIN is not set +# CONFIG_XMC4_USIC0_CHAN0_ISSPI is not set +# CONFIG_XMC4_USIC0_CHAN0_ISI2C is not set +# CONFIG_XMC4_USIC0_CHAN0_ISI2S is not set +CONFIG_XMC4_USIC0_CHAN1_NONE=y +# CONFIG_XMC4_USIC0_CHAN1_ISUART is not set +# CONFIG_XMC4_USIC0_CHAN1_ISLIN is not set +# CONFIG_XMC4_USIC0_CHAN1_ISSPI is not set +# CONFIG_XMC4_USIC0_CHAN1_ISI2C is not set +# CONFIG_XMC4_USIC0_CHAN1_ISI2S is not set # # Architecture Options @@ -554,6 +558,7 @@ CONFIG_STANDARD_SERIAL=y # CONFIG_SERIAL_DMA is not set # CONFIG_ARCH_HAVE_SERIAL_TERMIOS is not set CONFIG_UART0_SERIAL_CONSOLE=y +# CONFIG_UART1_SERIAL_CONSOLE is not set # CONFIG_OTHER_SERIAL_CONSOLE is not set # CONFIG_NO_SERIAL_CONSOLE is not set -- GitLab From c760d00158044e1b9fbfbb8000e17362e8232407 Mon Sep 17 00:00:00 2001 From: raiden00pl Date: Sun, 19 Mar 2017 18:27:31 +0100 Subject: [PATCH 104/990] stm32f33xx_comp.h: fix typos --- arch/arm/src/stm32/chip/stm32f33xxx_comp.h | 33 +++++++++++----------- 1 file changed, 17 insertions(+), 16 deletions(-) diff --git a/arch/arm/src/stm32/chip/stm32f33xxx_comp.h b/arch/arm/src/stm32/chip/stm32f33xxx_comp.h index a0803ea04b..0e83a1c965 100644 --- a/arch/arm/src/stm32/chip/stm32f33xxx_comp.h +++ b/arch/arm/src/stm32/chip/stm32f33xxx_comp.h @@ -72,7 +72,8 @@ # define COMP_CSR_INMSEL_1P2VREF (1 << COMP_CSR_INMSEL_SHIFT) /* 0001: 1/2 of Vrefint */ # define COMP_CSR_INMSEL_3P4VREF (2 << COMP_CSR_INMSEL_SHIFT) /* 0010: 3/4 of Vrefint */ # define COMP_CSR_INMSEL_VREF (3 << COMP_CSR_INMSEL_SHIFT) /* 0011: Vrefint */ -# define COMP_CSR_INMSEL_PA4 (4 << COMP_CSR_INMSEL_SHIFT) /* 0100: PA4 or DAC1_CH output if enabled */ +# define COMP_CSR_INMSEL_PA4 (4 << COMP_CSR_INMSEL_SHIFT) /* 0100: PA4 or */ +# define COMP_CSR_INMSEL_DAC1CH1 (4 << COMP_CSR_INMSEL_SHIFT) /* 0100: DAC1_CH1 output if enabled */ # define COMP_CSR_INMSEL_DAC1CH2 (5 << COMP_CSR_INMSEL_SHIFT) /* 0101: DAC1_CH2 output */ # define COMP_CSR_INMSEL_PA2 (6 << COMP_CSR_INMSEL_SHIFT) /* 0110: PA2 (COMP2 only) */ # define COMP_CSR_INMSEL_PB2 (7 << COMP4_CSR_INMSEL_SHIFT) /* 0111: PB2 (COMP4 only) */ @@ -87,32 +88,32 @@ /* 0011: Reserved */ /* 0100: Reserved */ # define COMP_CSR_OUTSEL_BRK2_ (5 << COMP_CSR_INMSEL_SHIFT) /* 0101: Timer 1 break input2 */ -# define COMP_CSR_OUTSEL_T1OCCC (6 << COMP_CSR_INMSEL_SHIFT) /* 0110: Timer 1 OCREF_CLR input (COMP2 only) */ +# define COMP_CSR_OUTSEL_T1OCC (6 << COMP_CSR_INMSEL_SHIFT) /* 0110: Timer 1 OCREF_CLR input (COMP2 only) */ # define COMP_CSR_OUTSEL_T3CAP3 (6 << COMP_CSR_INMSEL_SHIFT) /* 0110: Timer 3 input apture 3 (COMP4 only) */ # define COMP_CSR_OUTSEL_T2CAP2 (6 << COMP_CSR_INMSEL_SHIFT) /* 0110: Timer 2 input apture 2 (COMP6 only) */ # define COMP_CSR_OUTSEL_T1CAP1 (7 << COMP_CSR_INMSEL_SHIFT) /* 0111: Timer 1 input capture 1 (COMP2 only) */ # define COMP_CSR_OUTSEL_T2CAP4 (8 << COMP_CSR_INMSEL_SHIFT) /* 1000: Timer 2 input capture 4 (COMP2 only) */ # define COMP_CSR_OUTSEL_T15CAP2 (8 << COMP_CSR_INMSEL_SHIFT) /* 1000: Timer 15 input capture 2 (COMP4 only) */ -# define COMP_CSR_OUTSEL_T2OCC (8 << COMP_CSR_INMSEL_SHIFT) /* 1000: Timer 2 OCREF CLR input (COMP6 only) */ -# define COMP_CSR_OUTSEL_T2OCC (9 << COMP_CSR_INMSEL_SHIFT) /* 1001: Timer 2 OCREF_CLR input (COMP2 only) */ +# define COMP6_CSR_OUTSEL_T2OCC (8 << COMP_CSR_INMSEL_SHIFT) /* 1000: Timer 2 OCREF CLR input (COMP6 only) */ +# define COMP2_CSR_OUTSEL_T2OCC (9 << COMP_CSR_INMSEL_SHIFT) /* 1001: Timer 2 OCREF_CLR input (COMP2 only) */ # define COMP_CSR_OUTSEL_T16OCC (9 << COMP_CSR_INMSEL_SHIFT) /* 1001: Timer 16 OCREF_CLR input (COMP6 only) */ # define COMP_CSR_OUTSEL_T3CAP1 (10 << COMP_CSR_INMSEL_SHIFT) /* 1010: Timer 3 input capture 1 (COMP2 only) */ -# define COMP_CSR_OUTSEL_T3CAP1 (10 << COMP_CSR_INMSEL_SHIFT) /* 1010: Timer 15 OCREF_CLR input (COMP4 only) */ -# define COMP_CSR_OUTSEL_T3CAP1 (10 << COMP_CSR_INMSEL_SHIFT) /* 1010: Timer 16 input capture 1 (COMP6 only) */ +# define COMP_CSR_OUTSEL_T15OCC (10 << COMP_CSR_INMSEL_SHIFT) /* 1010: Timer 15 OCREF_CLR input (COMP4 only) */ +# define COMP_CSR_OUTSEL_T16CAP1 (10 << COMP_CSR_INMSEL_SHIFT) /* 1010: Timer 16 input capture 1 (COMP6 only) */ # define COMP_CSR_OUTSEL_T3OCC (11 << COMP_CSR_INMSEL_SHIFT) /* 1011: Timer 3 OCREF_CLR input (COMP2,COMP4 only) */ /* Bit 14: Reserved */ #define COMP_CSR_POL (1 << 15) /* Bit 15: comparator output polarity */ /* Bits 16-17: Reserved */ -#define COMP_CSR_BLANCKING_SHIFT (18) /* Bit 18-20: comparator output blanking source */ -#define COMP_CSR_BLANCKING_MASK (7 << COMP_CSR_BLANCKING_SHIFT) -# define COMP_CSR_BLANCKING_DIS (0 << COMP_CSR_BLANCKING_SHIFT) /* 000: No blanking */ -# define COMP_CSR_BLANCKING_T1OC5 (1 << COMP_CSR_BLANCKING_SHIFT) /* 001: TIM1 OC5 as blanking source (COMP2 only) */ -# define COMP_CSR_BLANCKING_T3OC4 (1 << COMP_CSR_BLANCKING_SHIFT) /* 001: TIM3 OC4 as blanking source (COMP4 only) */ -# define COMP_CSR_BLANCKING_T2OC3 (2 << COMP_CSR_BLANCKING_SHIFT) /* 010: TIM2 OC3 as blanking source (COMP2 only) */ -# define COMP_CSR_BLANCKING_T3OC3 (3 << COMP_CSR_BLANCKING_SHIFT) /* 011: TIM3 OC3 as blanking source (COMP2 only) */ -# define COMP_CSR_BLANCKING_T15OC1 (3 << COMP_CSR_BLANCKING_SHIFT) /* 011: TIM15 OC1 as blanking source (COMP4 only) */ -# define COMP_CSR_BLANCKING_T2OC4 (3 << COMP_CSR_BLANCKING_SHIFT) /* 011: TIM2 OC4 as blanking source (COMP6 only) */ -# define COMP_CSR_BLANCKING_T15OC2 (4 << COMP_CSR_BLANCKING_SHIFT) /* 011: TIM15 OC2 as blanking source (COMP6 only) */ +#define COMP_CSR_BLANKING_SHIFT (18) /* Bit 18-20: comparator output blanking source */ +#define COMP_CSR_BLANKING_MASK (7 << COMP_CSR_BLANKING_SHIFT) +# define COMP_CSR_BLANKING_DIS (0 << COMP_CSR_BLANKING_SHIFT) /* 000: No blanking */ +# define COMP_CSR_BLANKING_T1OC5 (1 << COMP_CSR_BLANKING_SHIFT) /* 001: TIM1 OC5 as blanking source (COMP2 only) */ +# define COMP_CSR_BLANKING_T3OC4 (1 << COMP_CSR_BLANKING_SHIFT) /* 001: TIM3 OC4 as blanking source (COMP4 only) */ +# define COMP_CSR_BLANKING_T2OC3 (2 << COMP_CSR_BLANKING_SHIFT) /* 010: TIM2 OC3 as blanking source (COMP2 only) */ +# define COMP_CSR_BLANKING_T3OC3 (3 << COMP_CSR_BLANKING_SHIFT) /* 011: TIM3 OC3 as blanking source (COMP2 only) */ +# define COMP_CSR_BLANKING_T15OC1 (3 << COMP_CSR_BLANKING_SHIFT) /* 011: TIM15 OC1 as blanking source (COMP4 only) */ +# define COMP_CSR_BLANKING_T2OC4 (3 << COMP_CSR_BLANKING_SHIFT) /* 011: TIM2 OC4 as blanking source (COMP6 only) */ +# define COMP_CSR_BLANKING_T15OC2 (4 << COMP_CSR_BLANKING_SHIFT) /* 011: TIM15 OC2 as blanking source (COMP6 only) */ /* Bit 21: Reserved */ #define COMP_CSR_INMSEL_DAC2CH1 (1 << 22) /* Bit 22: used with bits 4-6, DAC2_CH1 output */ /* Bits 23-29: Reserved */ -- GitLab From 651b8360c6d25039d76104c3a40a5d66916896e5 Mon Sep 17 00:00:00 2001 From: raiden00pl Date: Sun, 19 Mar 2017 18:36:44 +0100 Subject: [PATCH 105/990] STM32F33: Add COMP support --- arch/arm/src/stm32/Make.defs | 4 + arch/arm/src/stm32/stm32.h | 1 + arch/arm/src/stm32/stm32_comp.c | 838 ++++++++++++++++++++++++++++++++ arch/arm/src/stm32/stm32_comp.h | 281 +++++++++++ 4 files changed, 1124 insertions(+) create mode 100644 arch/arm/src/stm32/stm32_comp.c create mode 100644 arch/arm/src/stm32/stm32_comp.h diff --git a/arch/arm/src/stm32/Make.defs b/arch/arm/src/stm32/Make.defs index 1558c8417d..970ce3ba0c 100644 --- a/arch/arm/src/stm32/Make.defs +++ b/arch/arm/src/stm32/Make.defs @@ -217,6 +217,10 @@ ifeq ($(CONFIG_DAC),y) CHIP_CSRCS += stm32_dac.c endif +ifeq ($(CONFIG_COMP),y) +CHIP_CSRCS += stm32_comp.c +endif + ifeq ($(CONFIG_STM32_1WIREDRIVER),y) CHIP_CSRCS += stm32_1wire.c endif diff --git a/arch/arm/src/stm32/stm32.h b/arch/arm/src/stm32/stm32.h index 6680e81293..534d30246c 100644 --- a/arch/arm/src/stm32/stm32.h +++ b/arch/arm/src/stm32/stm32.h @@ -59,6 +59,7 @@ #include "stm32_adc.h" //#include "stm32_bkp.h" #include "stm32_can.h" +#include "stm32_comp.h" #include "stm32_dbgmcu.h" #include "stm32_dma.h" #include "stm32_dac.h" diff --git a/arch/arm/src/stm32/stm32_comp.c b/arch/arm/src/stm32/stm32_comp.c new file mode 100644 index 0000000000..59a3abacbc --- /dev/null +++ b/arch/arm/src/stm32/stm32_comp.c @@ -0,0 +1,838 @@ +/**************************************************************************** + * arch/arm/src/stm32/stm32_comp.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Mateusz Szafoni + * + * 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 "chip.h" +#include "stm32_gpio.h" +#include "stm32_comp.h" + +#ifdef CONFIG_STM32_COMP + +/* Some COMP peripheral must be enabled */ +/* Up to 7 comparators in STM32F2 Series */ + +#if defined(CONFIG_STM32_COMP1) || defined(CONFIG_STM32_COMP2) || \ + defined(CONFIG_STM32_COMP3) || defined(CONFIG_STM32_COMP4) || \ + defined(CONFIG_STM32_COMP5) || defined(CONFIG_STM32_COMP6) || \ + defined(CONFIG_STM32_COMP7) + +/* @TODO: support for STM32F30XX and STM32F37XX comparators */ + +#if defined(CONFIG_STM32_STM32F30XX) || defined(CONFIG_STM32_STM32F33XX) || \ + defined(CONFIG_STM32_STM32F37XX) + +/* Currently only STM32F33XX supported */ + +#if defined(CONFIG_STM32_STM32F30XX) || defined(CONFIG_STM32_STM32F37XX) +# error "Not supported yet" +#endif + +#if defined(CONFIG_STM32_STM32F33XX) +# if defined(CONFIG_STM32_COMP1) || defined(CONFIG_STM32_COMP3) || \ + defined(CONFIG_STM32_COMP5) || defined(CONFIG_STM32_COMP7) +# error "STM32F33 supports only COMP2, COMP4 and COMP6" +# endif +#endif + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ +/* COMP2 default configuration **********************************************/ + +#ifdef CONFIG_STM32_COMP2 +# ifndef COMP2_BLANLKING +# define COMP2_BLANKING COMP_BLANKING_DEFAULT +# endif +# ifndef COMP2_POL +# define COMP2_POL COMP_BLANKING_DEFAULT +# endif +# ifndef COMP2_INM +# define COMP2_INM COMP_INM_DEFAULT +# endif +# ifndef COMP2_OUTSEL +# define COMP2_OUTSEL COMP_OUTSEL_DEFAULT +# endif +# ifndef COMP2_LOCK +# define COMP2_LOCK COMP_LOCK_DEFAULT +# endif +#endif + +/* COMP4 default configuration **********************************************/ + +#ifdef CONFIG_STM32_COMP4 +# ifndef COMP4_BLANLKING +# define COMP4_BLANKING COMP_BLANKING_DEFAULT +# endif +# ifndef COMP4_POL +# define COMP4_POL COMP_BLANKING_DEFAULT +# endif +# ifndef COMP4_INM +# define COMP4_INM COMP_INM_DEFAULT +# endif +# ifndef COMP4_OUTSEL +# define COMP4_OUTSEL COMP_OUTSEL_DEFAULT +# endif +# ifndef COMP4_LOCK +# define COMP4_LOCK COMP_LOCK_DEFAULT +# endif +#endif + +/* COMP6 default configuration **********************************************/ + +#ifdef CONFIG_STM32_COMP6 +# ifndef COMP6_BLANLKING +# define COMP6_BLANKING COMP_BLANKING_DEFAULT +# endif +# ifndef COMP6_POL +# define COMP6_POL COMP_BLANKING_DEFAULT +# endif +# ifndef COMP6_INM +# define COMP6_INM COMP_INM_DEFAULT +# endif +# ifndef COMP6_OUTSEL +# define COMP6_OUTSEL COMP_OUTSEL_DEFAULT +# endif +# ifndef COMP6_LOCK +# define COMP6_LOCK COMP_LOCK_DEFAULT +# endif +#endif + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +#ifdef CONFIG_STM32_COMP1 +static struct stm32_comp_s g_comp1priv = + { + .blanking = COMP1_BLANKING, + .pol = COMP1_POL, + .inm = COMP1_INM, + .out = COMP1_OUTSEL, + .lock = COMP1_LOCK, + .csr = STM32_COMP1_CSR, +#ifndef CONFIG_STM32_STM32F33XX + .mode = COMP1_MODE, + .hyst = COMP1_HYST, +#endif + }; +#endif + +#ifdef CONFIG_STM32_COMP2 +static struct stm32_comp_s g_comp2priv = + { + .blanking = COMP2_BLANKING, + .pol = COMP2_POL, + .inm = COMP2_INM, + .out = COMP2_OUTSEL, + .lock = COMP2_LOCK, + .csr = STM32_COMP2_CSR, +#ifndef CONFIG_STM32_STM32F33XX + .mode = COMP2_MODE, + .hyst = COMP2_HYST, +#endif + }; +#endif + +#ifdef CONFIG_STM32_COMP3 + static struct stm32_comp_s g_comp3priv = + { + .blanking = COMP3_BLANKING, + .pol = COMP3_POL, + .inm = COMP3_INM, + .out = COMP3_OUTSEL, + .lock = COMP3_LOCK, + .csr = STM32_COMP3_CSR, +#ifndef CONFIG_STM32_STM32F33XX + .mode = COMP3_MODE, + .hyst = COMP3_HYST, +#endif + }; +#endif + +#ifdef CONFIG_STM32_COMP4 + static struct stm32_comp_s g_comp4priv = + { + .blanking = COMP4_BLANKING, + .pol = COMP4_POL, + .inm = COMP4_INM, + .out = COMP4_OUTSEL, + .lock = COMP4_LOCK, + .csr = STM32_COMP4_CSR, +#ifndef CONFIG_STM32_STM32F33XX + .mode = COMP4_MODE, + .hyst = COMP4_HYST, +#endif + }; +#endif + +#ifdef CONFIG_STM32_COMP5 + static struct stm32_comp_s g_comp5priv = + { + .blanking = COMP5_BLANKING, + .pol = COMP5_POL, + .inm = COMP5_INM, + .out = COMP5_OUTSEL, + .lock = COMP5_LOCK, + .csr = STM32_COMP5_CSR, +#ifndef CONFIG_STM32_STM32F33XX + .mode = COMP5_MODE, + .hyst = COMP5_HYST, +#endif + }; +#endif + +#ifdef CONFIG_STM32_COMP6 + static struct stm32_comp_s g_comp6priv = + { + .blanking = COMP6_BLANKING, + .pol = COMP6_POL, + .inm = COMP6_INM, + .out = COMP6_OUTSEL, + .lock = COMP6_LOCK, + .csr = STM32_COMP6_CSR, +#ifndef CONFIG_STM32_STM32F33XX + .mode = COMP6_MODE, + .hyst = COMP6_HYST, +#endif + }; +#endif + +#ifdef CONFIG_STM32_COMP7 + static struct stm32_comp_s g_comp7priv = + { + .blanking = COMP7_BLANKING, + .pol = COMP7_POL, + .inm = COMP7_INM, + .out = COMP7_OUTSEL, + .lock = COMP7_LOCK, + .csr = STM32_COMP7_CSR, +#ifndef CONFIG_STM32_STM32F33XX + .mode = COMP7_MODE, + .hyst = COMP7_HYST, +#endif + }; +#endif + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static inline void comp_modify_csr(FAR struct stm32_comp_s *priv, + uint32_t clearbits, uint32_t setbits); +static inline uint32_t comp_getreg_csr(FAR struct stm32_comp_s *priv); +static inline void comp_putreg_csr(FAR struct stm32_comp_s *priv, + uint32_t value); +static bool stm32_complock_get(FAR struct stm32_comp_s *priv); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: comp_modify_csr + * + * Description: + * Modify the value of a 32-bit COMP CSR register (not atomic). + * + * Input Parameters: + * priv - A reference to the COMP structure + * clrbits - The bits to clear + * setbits - The bits to set + * + * Returned Value: + * None + * + ****************************************************************************/ + +static inline void comp_modify_csr(FAR struct stm32_comp_s *priv, + uint32_t clearbits, uint32_t setbits) +{ + uint32_t csr = priv->csr; + + modifyreg32(csr, clearbits, setbits); +} + +/**************************************************************************** + * Name: comp_getreg_csr + * + * Description: + * Read the value of an COMP CSR register + * + * Input Parameters: + * priv - A reference to the COMP structure + * + * Returned Value: + * The current contents of the COMP CSR register + * + ****************************************************************************/ + +static inline uint32_t comp_getreg_csr(FAR struct stm32_comp_s *priv) +{ + uint32_t csr = priv->csr; + + return getreg32(csr); +} + +/**************************************************************************** + * Name: comp_putreg_csr + * + * Description: + * Write a value to an COMP register. + * + * Input Parameters: + * priv - A reference to the COMP structure + * value - The value to write to the COMP CSR register + * + * Returned Value: + * None + * + ****************************************************************************/ + +static inline void comp_putreg_csr(FAR struct stm32_comp_s *priv, + uint32_t value) +{ + uint32_t csr = priv->csr; + + putreg32(value, csr); +} + +/**************************************************************************** + * Name: stm32_comp_complock_get + * + * Description: + * Get COMP lock bit state + * + * Input Parameters: + * priv - A reference to the COMP structure + * + * Returned Value: + * True if COMP locked, false if not locked + * + ****************************************************************************/ + +static bool stm32_complock_get(FAR struct stm32_comp_s *priv) +{ + uint32_t regval; + + regval = comp_getreg_csr(priv); + + return ((regval & COMP_CSR_LOCK == 0) ? false : true); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_compconfig + * + * Description: + * Configure comparator and used I/Os + * + * Input Parameters: + * priv - A reference to the COMP structure + * + * Returned Value: + * 0 on success, a negated errno value on failure + * + * REVISIT: Where to config comparator output pin ? + * + ****************************************************************************/ + +int stm32_compconfig(FAR struct stm32_comp_s *priv) +{ + uint32_t regval; + int index; + + /* Get comparator index */ + + switch (priv->csr) + { +#ifdef CONFIG_STM32_COMP1 + case STM32_COMP1_CSR: + index = 1; + break; +#endif + case STM32_COMP2_CSR: + index = 2; + break; +#ifdef CONFIG_STM32_COMP3 + case STM32_COMP3_CSR: + index = 3; + break; +#endif + case STM32_COMP4_CSR: + index = 4; + break; +#ifdef CONFIG_STM32_COMP5 + case STM32_COMP5_CSR: + index = 5; + break; +#endif + case STM32_COMP6_CSR: + index = 6; + break; +#ifdef CONFIG_STM32_COMP7 + case STM32_COMP7_CSR: + index = 7; + break; +#endif + default: + return -EINVAL; + } + + /* Configure non inverting input */ + + switch (index) + { +#ifdef CONFIG_STM32_COMP2 + case 2: + stm32_configgpio(GPIO_COMP2_INP); + break; +#endif +#ifdef CONFIG_STM32_COMP4 + case 4: + stm32_configgpio(GPIO_COMP4_INP); + break; +#endif +#ifdef CONFIG_STM32_COMP6 + case 6: + stm32_configgpio(GPIO_COMP6_INP); + break; +#endif + default: + return -EINVAL; + } + + /* Set Comparator inverting input */ + + switch (priv->inm) + { + case COMP_INMSEL_1P4VREF: + regval |= COMP_CSR_INMSEL_1P4VREF; + break; + + case COMP_INMSEL_1P2VREF: + regval |= COMP_CSR_INMSEL_1P2VREF; + break; + + case COMP_INMSEL_3P4VREF: + regval |= COMP_CSR_INMSEL_3P4VREF; + break; + + case COMP_INMSEL_VREF: + regval |= COMP_CSR_INMSEL_VREF; + break; + + case COMP_INMSEL_DAC1CH1: + regval |= COMP_CSR_INMSEL_DAC1CH1; + break; + + case COMP_INMSEL_DAC1CH2: + regval |= COMP_CSR_INMSEL_DAC1CH2; + break; + + case COMP_INMSEL_PIN: + { + /* INMSEL PIN configuration dependent on COMP index */ + + switch (index) + { +#ifdef CONFIG_STM32_COMP2 + case 2: + { + stm32_configgpio(GPIO_COMP2_INM); + regval |= COMP_CSR_INMSEL_PA2; + break; + } +#endif +#ifdef CONFIG_STM32_COMP4 + case 4: + { + /* COMP4_INM can be PB2 or PA4 */ + + stm32_configgpio(GPIO_COMP4_INM); + regval |= (GPIO_COMP4_INM == GPIO_COMP4_INM_1 ? COMP_CSR_INMSEL_PB2 : COMP_CSR_INMSEL_PA4); + break; + } +#endif +#ifdef CONFIG_STM32_COMP6 + case 6: + { + /* COMP6_INM can be PB15 or PA4 */ + + stm32_configgpio(GPIO_COMP6_INM); + regval |= (GPIO_COMP6_INM == GPIO_COMP6_INM_1 ? COMP_CSR_INMSEL_PB15 : COMP_CSR_INMSEL_PA4); + break; + } +#endif + default : + return -EINVAL; + } + + break; + } + + default: + return -EINVAL; + } + + /* Set Comparator output selection */ + + switch (priv->out) + { + case COMP_OUTSEL_NOSEL: + regval |= COMP_CSR_OUTSEL_NOSEL; + break; + + case COMP_OUTSEL_BRKACTH: + regval |= COMP_CSR_OUTSEL_BRKACTH; + break; + + case COMP_OUTSEL_BRK2: + regval |= COMP_CSR_OUTSEL_BRK2; + break; + + case COMP_OUTSEL_T1OCC: + regval |= COMP_CSR_OUTSEL_T1OCC; + break; + + case COMP_OUTSEL_T3CAP3: + regval |= COMP_CSR_OUTSEL_T3CAP3; + break; + + case COMP_OUTSEL_T2CAP2: + regval |= COMP_CSR_OUTSEL_T2CAP2; + break; + + case COMP_OUTSEL_T1CAP1: + regval |= COMP_CSR_OUTSEL_T1CAP1; + break; + + case COMP_OUTSEL_T2CAP4: + regval |= COMP_CSR_OUTSEL_T2CAP4; + break; + + case COMP_OUTSEL_T15CAP2: + regval |= COMP_CSR_OUTSEL_T15CAP2; + break; + + case COMP_OUTSEL_T2OCC: + if (index == 2) + regval |= COMP2_CSR_OUTSEL_T2OCC; + else if (index == 6) + regval |= COMP6_CSR_OUTSEL_T2OCC; + break; + + case COMP_OUTSEL_T16OCC: + regval |= COMP_CSR_OUTSEL_T16OCC; + break; + + case COMP_OUTSEL_T3CAP1: + regval |= COMP_CSR_OUTSEL_T3CAP1; + break; + + case COMP_OUTSEL_T15OCC: + regval |= COMP_CSR_OUTSEL_T15OCC; + break; + + case COMP_OUTSEL_T16CAP1: + regval |= COMP_CSR_OUTSEL_T16CAP1; + break; + + case COMP_OUTSEL_T3OCC: + regval |= COMP_CSR_OUTSEL_T3OCC; + break; + + default: + return -EINVAL; + + } + + /* Set Comparator output polarity */ + + regval |= (priv->pol == COMP_POL_INVERTED ? COMP_CSR_POL : 0); + + /* Set Comparator output blanking source */ + + switch (priv->blanking) + { + case COMP_BLANKING_DIS: + regval |= COMP_CSR_BLANKING_DIS; + break; + + case COMP_BLANKING_T1OC5: + regval |= COMP_CSR_BLANKING_T1OC5; + break; + + case COMP_BLANKING_T3OC4: + regval |= COMP_CSR_BLANKING_T3OC4; + break; + + case COMP_BLANKING_T2OC3: + regval |= COMP_CSR_BLANKING_T2OC3; + break; + + case COMP_BLANKING_T15OC1: + regval |= COMP_CSR_BLANKING_T15OC1; + break; + + case COMP_BLANKING_T2OC4: + regval |= COMP_CSR_BLANKING_T2OC4; + break; + + case COMP_BLANKING_T15OC2: + regval |= COMP_CSR_BLANKING_T15OC1; + break; + + default: + return -EINVAL; + } + + /* Save CSR register */ + + comp_putreg_csr(priv, regval); + + /* Enable Comparator */ + + stm32_compenable(priv, true); + + /* Lock Comparator if needed */ + + if (priv->lock == COMP_LOCK_RO) + stm32_complock(priv, true); + + return OK; +} + +/**************************************************************************** + * Name: stm32_compinitialize + * + * Description: + * Initialize the COMP. + * + * Input Parameters: + * intf - The COMP interface number. + * + * Returned Value: + * Valid COMP device structure reference on succcess; a NULL on failure. + * + * Assumptions: + * 1. Clock to the COMP block has enabled, + * 2. Board-specific logic has already configured + * + ****************************************************************************/ + +FAR struct stm32_comp_s* stm32_compinitialize(int intf) +{ + FAR struct stm32_comp_s *priv; + int ret; + + switch (intf) + { +#ifdef CONFIG_STM32_COMP1 + case 1: + ainfo("COMP1 selected\n"); + priv = &g_comp1priv; + break; +#endif +#ifdef CONFIG_STM32_COMP2 + case 2: + ainfo("COMP2 selected\n"); + priv = &g_comp2priv; + break; +#endif +#ifdef CONFIG_STM32_COMP3 + case 3: + ainfo("COMP3 selected\n"); + priv = &g_comp3priv; + break; +#endif +#ifdef CONFIG_STM32_COMP4 + case 4: + ainfo("COMP4 selected\n"); + priv = &g_comp4priv; + break; +#endif +#ifdef CONFIG_STM32_COMP5 + case 5: + ainfo("COMP5 selected\n"); + priv = &g_comp5priv; + break; +#endif +#ifdef CONFIG_STM32_COMP6 + case 6: + ainfo("COMP6 selected\n"); + priv = &g_comp6priv; + break; +#endif +#ifdef CONFIG_STM32_COMP7 + case 7: + ainfo("COMP7 selected\n"); + priv = &g_comp7priv; + break; +#endif + default: + aerr("ERROR: No COMP interface defined\n"); + return NULL; + } + + /* Configure selected comparator */ + + ret = stm32_compconfig(priv); + if (ret < 0) + { + aerr("ERROR: Failed to initialize COMP%d: %d\n", intf, ret); + errno = -ret; + return NULL; + } + + return priv; +} + +/**************************************************************************** + * Name: stm32_compenable + * + * Description: + * Enable/disable comparator + * + * Input Parameters: + * priv - A reference to the COMP structure + * enable - enable/disable flag + * + * Returned Value: + * 0 on success, a negated errno value on failure + * + ****************************************************************************/ + +int stm32_compenable(FAR struct stm32_comp_s *priv, bool enable) +{ + bool lock; + + ainfo("enable: %d\n", enable ? 1 : 0); + + lock = stm32_complock_get(priv); + + if (lock) + { + aerr("ERROR: Comparator locked!\n"); + + return -EPERM; + } + else + { + if (enable) + { + /* Enable the COMP */ + + comp_modify_csr(priv, COMP_CSR_COMPEN, 0); + } + else + { + /* Disable the COMP */ + + comp_modify_csr(priv, 0, COMP_CSR_COMPEN); + } + } + + return OK; +} + +/**************************************************************************** + * Name: stm32_complock + * + * Description: + * Lock comparator CSR register + * + * Input Parameters: + * priv - A reference to the COMP structure + * enable - lock flag + * + * Returned Value: + * 0 on success, a negated errno value on failure + * + ****************************************************************************/ + +int stm32_complock(FAR struct stm32_comp_s *priv, bool lock) +{ + bool current; + + current = stm32_complock_get(priv); + + if (current) + { + if (lock == false) + { + aerr("ERROR: COMP LOCK can be cleared only by a system reset\n"); + + return -EPERM; + } + } + else + { + if (lock == true) + { + comp_modify_csr(priv, COMP_CSR_LOCK, 0); + + priv->lock = COMP_LOCK_RO; + } + } + + return OK; +} + +#endif /* CONFIG_STM32_STM32F30XX || CONFIG_STM32_STM32F33XX || + * CONFIG_STM32_STM32F37XX*/ + +#endif /* CONFIG_STM32_COMP2 || CONFIG_STM32_COMP4 || + * CONFIG_STM32_COMP6 */ + +#endif /* CONFIG_STM32_COMP */ diff --git a/arch/arm/src/stm32/stm32_comp.h b/arch/arm/src/stm32/stm32_comp.h new file mode 100644 index 0000000000..3b858dbcc3 --- /dev/null +++ b/arch/arm/src/stm32/stm32_comp.h @@ -0,0 +1,281 @@ +/************************************************************************************ + * arch/arm/src/stm32/stm32_comp.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Mateusz Szafoni + * + * 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 __ARCH_ARM_SRC_STM32_STM32_COMP_H +#define __ARCH_ARM_SRC_STM32_STM32_COMP_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include "chip.h" + +#if defined(CONFIG_STM32_STM32F30XX) +# error "COMP support for STM32F30XX not implemented yet" +#elif defined(CONFIG_STM32_STM32F33XX) +# include "chip/stm32f33xxx_comp.h" +#elif defined(CONFIG_STM32_STM32F37XX) +# error "COMP support for STM32F37XX ot implemented yet" +#endif + +/************************************************************************************ + * Pre-processor definitions + ************************************************************************************/ + +#define COMP_BLANKING_DEFAULT COMP_BLANKING_DIS /* No blanking */ +#define COMP_POL_DEFAULT COMP_POL_NONINVERT /* Output is not inverted */ +#define COMP_INM_DEFAULT COMP_INMSEL_1P4VREF /* 1/4 of Vrefint as INM */ +#define COMP_OUTSEL_DEFAULT COMP_OUTSEL_NOSEL /* Output not selected */ +#define COMP_LOCK_DEFAULT COMP_LOCK_RO /* Do not lock CSR register */ + +#ifndef CONFIG_STM32_STM32F33XX +#define COMP_MODE_DEFAULT +#define COMP_HYST_DEFAULT +#define COMP_WINMODE_DEFAULT +#endif + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/* Blanking source */ + +enum stm32_comp_blanking_e + { + COMP_BLANKING_DIS, +#if defined(CONFIG_STM32_STM32F33XX) + COMP_BLANKING_T1OC5, + COMP_BLANKING_T3OC4, + COMP_BLANKING_T2OC3, + COMP_BLANKING_T3OC3, + COMP_BLANKING_T15OC1, + COMP_BLANKING_T2OC4, + COMP_BLANKING_T15OC2, +#endif + }; + +/* Output polarisation */ + +enum stm32_comp_pol_e + { + COMP_POL_NONINVERT, + COMP_POL_INVERTED + }; + +/* Inverting input */ + +enum stm32_comp_inm_e + { + COMP_INMSEL_1P4VREF, + COMP_INMSEL_1P2VREF, + COMP_INMSEL_3P4VREF, + COMP_INMSEL_VREF, + COMP_INMSEL_DAC1CH1, + COMP_INMSEL_DAC1CH2, + COMP_INMSEL_PIN + }; + +/* Output selection */ + +enum stm32_comp_outsel_e + { + COMP_OUTSEL_NOSEL, +#if defined(CONFIG_STM32_STM32F33XX) + COMP_OUTSEL_BRKACTH, + COMP_OUTSEL_BRK2, + COMP_OUTSEL_T1OCC, /* COMP2 only */ + COMP_OUTSEL_T3CAP3, /* COMP4 only */ + COMP_OUTSEL_T2CAP2, /* COMP6 only */ + COMP_OUTSEL_T1CAP1, /* COMP2 only */ + COMP_OUTSEL_T2CAP4, /* COMP2 only */ + COMP_OUTSEL_T15CAP2, /* COMP4 only */ + COMP_OUTSEL_T2OCC, /* COMP6 only */ + COMP_OUTSEL_T16OCC, /* COMP2 only */ + COMP_OUTSEL_T3CAP1, /* COMP2 only */ + COMP_OUTSEL_T15OCC, /* COMP4 only */ + COMP_OUTSEL_T16CAP1, /* COMP6 only */ + COMP_OUTSEL_T3OCC, /* COMP2 and COMP4 only */ +#endif + }; + +/* CSR register lock state */ + +enum stm32_comp_lock_e + { + COMP_LOCK_RW, + COMP_LOCK_RO + }; + +#ifndef CONFIG_STM32_STM32F33XX + +/* Hysteresis */ + +enum stm32_comp_hyst_e + { + COMP_HYST_DIS, + COMP_HYST_LOW, + COMP_HYST_MEDIUM, + COMP_HYST_HIGH + }, + +/* Power/Speed Modes */ + +enum stm32_comp_mode_e + { + COMP_MODE_HIGHSPEED, + COMP_MODE_MEDIUMSPEED, + COMP_MODE_LOWPOWER, + COMP_MODE_ULTRALOWPOWER + }; + +/* Window mode */ + +enum stm32_comp_winmode_e + { + COMP_WINMODE_DIS, + COMP_WINMODE_EN + }; + +#endif + +/* Comparator configuration ***********************************************************/ + +struct stm32_comp_s +{ + uint8_t blanking; /* Blanking source */ + uint8_t pol; /* Output polarity */ + uint8_t inm; /* Inverting input selection */ + uint8_t out; /* Comparator output */ + uint8_t lock; /* Comparator Lock */ + uint32_t csr; /* Control and status register */ +#ifndef CONFIG_STM32_STM32F33XX + uint8_t mode; /* Comparator mode */ + uint8_t hyst; /* Comparator hysteresis */ + /* @TODO: Window mode + INP selection */ +#endif +}; + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +#ifndef __ASSEMBLY__ +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/**************************************************************************** +* Name: stm32_compconfig +* +* Description: +* Configure comparator and used I/Os +* +* Input Parameters: +* priv - A reference to the COMP structure +* +* Returned Value: +* 0 on success, a negated errno value on failure +* +****************************************************************************/ + +int stm32_compconfig(FAR struct stm32_comp_s *priv); + +/**************************************************************************** +* Name: stm32_compinitialize +* +* Description: +* Initialize the COMP. +* +* Input Parameters: +* intf - The COMP interface number. +* +* Returned Value: +* Valid COMP device structure reference on succcess; a NULL on failure. +* +* Assumptions: +* 1. Clock to the COMP block has enabled, +* 2. Board-specific logic has already configured +* +****************************************************************************/ + +FAR struct stm32_comp_s* stm32_compinitialize(int intf); + +/**************************************************************************** +* Name: stm32_compenable +* +* Description: +* Enable/disable comparator +* +* Input Parameters: +* priv - A reference to the COMP structure +* enable - enable/disable flag +* +* Returned Value: +* 0 on success, a negated errno value on failure +* +****************************************************************************/ + +int stm32_compenable(FAR struct stm32_comp_s *priv, bool enable); + +/**************************************************************************** +* Name: stm32_complock +* +* Description: +* Lock comparator CSR register +* +* Input Parameters: +* priv - A reference to the COMP structure +* enable - lock flag +* +* Returned Value: +* 0 on success, a negated errno value on failure +* +****************************************************************************/ + +int stm32_complock(FAR struct stm32_comp_s *priv, bool lock); + +#undef EXTERN +#ifdef __cplusplus +} +#endif +#endif /* __ASSEMBLY__ */ + +#endif /* __ARCH_ARM_SRC_STM32_STM32_COMP_H */ -- GitLab From 726fd224db92602ed93a48f83779f01c8d9679fe Mon Sep 17 00:00:00 2001 From: raiden00pl Date: Sun, 19 Mar 2017 18:39:41 +0100 Subject: [PATCH 106/990] nucleo-f334r8: Add COMP support --- configs/nucleo-f334r8/src/nucleo-f334r8.h | 12 ++ configs/nucleo-f334r8/src/stm32_appinit.c | 10 ++ configs/nucleo-f334r8/src/stm32_comp.c | 140 ++++++++++++++++++++++ 3 files changed, 162 insertions(+) diff --git a/configs/nucleo-f334r8/src/nucleo-f334r8.h b/configs/nucleo-f334r8/src/nucleo-f334r8.h index d9cd2e1cf7..20b2dbbd5b 100644 --- a/configs/nucleo-f334r8/src/nucleo-f334r8.h +++ b/configs/nucleo-f334r8/src/nucleo-f334r8.h @@ -190,4 +190,16 @@ int stm32_adc_setup(void); int stm32_can_setup(void); #endif +/**************************************************************************** + * Name: stm32_comp_setup + * + * Description: + * Initialize COMP peripheral for the board. + * + ****************************************************************************/ + +#ifdef CONFIG_COMP +int stm32_comp_setup(void); +#endif + #endif /* __CONFIGS_NUCLEO_F334R8_SRC_NUCLEO_F334R8_H */ diff --git a/configs/nucleo-f334r8/src/stm32_appinit.c b/configs/nucleo-f334r8/src/stm32_appinit.c index 3579835c63..2eb43b85b0 100644 --- a/configs/nucleo-f334r8/src/stm32_appinit.c +++ b/configs/nucleo-f334r8/src/stm32_appinit.c @@ -127,6 +127,16 @@ int board_app_initialize(uintptr_t arg) } #endif +#ifdef CONFIG_COMP + /* Initialize COMP and register the COMP driver. */ + + ret = stm32_comp_setup(); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: stm32_comp_setup failed: %d\n", ret); + } +#endif + UNUSED(ret); return OK; } diff --git a/configs/nucleo-f334r8/src/stm32_comp.c b/configs/nucleo-f334r8/src/stm32_comp.c index e69de29bb2..392dd92d7a 100644 --- a/configs/nucleo-f334r8/src/stm32_comp.c +++ b/configs/nucleo-f334r8/src/stm32_comp.c @@ -0,0 +1,140 @@ +/**************************************************************************** + * configs/nucleo-f334r8/src/stm32_comp.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Mateusz Szafoni + * + * 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 "stm32.h" + +#if defined(CONFIG_COMP) && (defined(CONFIG_STM32_COMP2) || \ + defined(CONFIG_STM32_COMP4) || \ + defined(CONFIG_STM32_COMP6)) + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_comp_setup + * + * Description: + * Initialize COMP + * + ****************************************************************************/ + +int stm32_comp_setup(void) +{ + static bool initialized = false; + struct stm32_comp_s* comp = NULL; + int ret; + UNUSED(ret); + + if (!initialized) + { +#ifdef CONFIG_STM32_COMP2 + comp = stm32_compinitialize(2); + if (comp == NULL) + { + aerr("ERROR: Failed to get COMP%d interface\n", 2); + return -ENODEV; + } +#endif + +#ifdef CONFIG_STM32_COMP4 + comp = stm32_compinitialize(4); + if (comp == NULL) + { + aerr("ERROR: Failed to get COMP%d interface\n", 4); + return -ENODEV; + } +#endif + +#ifdef CONFIG_STM32_COMP6 + comp = stm32_compinitialize(6); + if (comp == NULL) + { + aerr("ERROR: Failed to get COMP%d interface\n", 6); + return -ENODEV; + } +#endif + + +#if 0 + /* COMP driver not implemented yet */ + + ret = comp_register("/dev/comp0", comp); + if (ret < 0) + { + aerr("ERROR: comp_register failed: %d\n", ret); + return ret; + } +#endif + + initialized = true; + } + + return OK; +} + + +#endif /* CONFIG_COMP && (CONFIG_STM32_COMP1 || + * CONFIG_STM32_COMP2 + * CONFIG_STM32_COMP6) */ -- GitLab From 5c0be816a5742fb3158c1a6f18eefdf84b7f445d Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 19 Mar 2017 12:48:37 -0600 Subject: [PATCH 107/990] XMC4xxx: Add commin USIC support logic for use in all USIC configurations. --- arch/arm/include/xmc4/chip.h | 8 +- arch/arm/src/xmc4/Make.defs | 2 +- arch/arm/src/xmc4/chip/xmc4_scu.h | 34 +-- arch/arm/src/xmc4/xmc4_clrpend.c | 16 -- arch/arm/src/xmc4/xmc4_serial.c | 19 +- arch/arm/src/xmc4/xmc4_usic.c | 397 ++++++++++++++++++++++++++++++ arch/arm/src/xmc4/xmc4_usic.h | 37 ++- 7 files changed, 465 insertions(+), 48 deletions(-) create mode 100644 arch/arm/src/xmc4/xmc4_usic.c diff --git a/arch/arm/include/xmc4/chip.h b/arch/arm/include/xmc4/chip.h index 019c107823..76cd0c4cd6 100644 --- a/arch/arm/include/xmc4/chip.h +++ b/arch/arm/include/xmc4/chip.h @@ -33,8 +33,8 @@ * ************************************************************************************/ -#ifndef __ARCH_ARM_INCLUDE_XM4_CHIP_H -#define __ARCH_ARM_INCLUDE_XM4_CHIP_H +#ifndef __ARCH_ARM_INCLUDE_XMC4_CHIP_H +#define __ARCH_ARM_INCLUDE_XMC4_CHIP_H /************************************************************************************ * Included Files @@ -49,7 +49,7 @@ /* Get customizations for each supported chip */ #if defined(CONFIG_ARCH_CHIP_XMC4500) -# define XM4_NUSIC 3 /* Three USIC modules: USCI0-2 */ +# define XMC4_NUSIC 3 /* Three USIC modules: USCI0-2 */ #else # error "Unsupported XMC4xxx chip" @@ -127,4 +127,4 @@ * Public Functions ************************************************************************************/ -#endif /* __ARCH_ARM_INCLUDE_XM4_CHIP_H */ +#endif /* __ARCH_ARM_INCLUDE_XMC4_CHIP_H */ diff --git a/arch/arm/src/xmc4/Make.defs b/arch/arm/src/xmc4/Make.defs index 63998a7133..76ddb95391 100644 --- a/arch/arm/src/xmc4/Make.defs +++ b/arch/arm/src/xmc4/Make.defs @@ -112,7 +112,7 @@ CHIP_ASRCS = CHIP_CSRCS = xmc4_allocateheap.c xmc4_clockconfig.c xmc4_clockutils.c CHIP_CSRCS += xmc4_clrpend.c xmc4_idle.c xmc4_irq.c xmc4_lowputc.c -CHIP_CSRCS += xmc4_gpio.c xmc4_serial.c xmc4_start.c +CHIP_CSRCS += xmc4_gpio.c xmc4_serial.c xmc4_start.c xmc4_usic.c # Configuration-dependent Kinetis files diff --git a/arch/arm/src/xmc4/chip/xmc4_scu.h b/arch/arm/src/xmc4/chip/xmc4_scu.h index 49b74a3e48..d916b8330c 100644 --- a/arch/arm/src/xmc4/chip/xmc4_scu.h +++ b/arch/arm/src/xmc4/chip/xmc4_scu.h @@ -969,32 +969,32 @@ #define SCU_CGAT0_POSIF0 (1 << 9) /* Bit 9: POSIF0 Gating Status */ #define SCU_CGAT0_POSIF1 (1 << 10) /* Bit 10: POSIF1 Gating Status */ #define SCU_CGAT0_USIC0 (1 << 11) /* Bit 11: USIC0 Gating Status */ -#define SCU_CGAT0_ERU1_ (1 << 16) /* Bit 16: ERU1 Gating Status */ +#define SCU_CGAT0_ERU1 (1 << 16) /* Bit 16: ERU1 Gating Status */ /* Peripheral 1 Clock Gating Status, Peripheral 1 Clock Gating Set, Peripheral 1 Clock Gating Clear */ -#define SCU_CGATSTAT1_CCU43 (1 << 0) /* Bit 0: CCU43 Gating Status */ -#define SCU_CGATSTAT1_LEDTSCU0 (1 << 3) /* Bit 3: LEDTS Gating Status */ -#define SCU_CGATSTAT1_MCAN0 (1 << 4) /* Bit 4: MultiCAN Gating Status */ -#define SCU_CGATSTAT1_DAC (1 << 5) /* Bit 5: DAC Gating Status */ -#define SCU_CGATSTAT1_MMCI (1 << 6) /* Bit 6: MMC Interface Gating Status */ -#define SCU_CGATSTAT1_USIC1 (1 << 7) /* Bit 7: USIC1 Gating Status */ -#define SCU_CGATSTAT1_USIC2 (1 << 8) /* Bit 8: USIC1 Gating Status */ -#define SCU_CGATSTAT1_PPORTS (1 << 9) /* Bit 9: PORTS Gating Status */ +#define SCU_CGAT1_CCU43 (1 << 0) /* Bit 0: CCU43 Gating Status */ +#define SCU_CGAT1_LEDTSCU0 (1 << 3) /* Bit 3: LEDTS Gating Status */ +#define SCU_CGAT1_MCAN0 (1 << 4) /* Bit 4: MultiCAN Gating Status */ +#define SCU_CGAT1_DAC (1 << 5) /* Bit 5: DAC Gating Status */ +#define SCU_CGAT1_MMCI (1 << 6) /* Bit 6: MMC Interface Gating Status */ +#define SCU_CGAT1_USIC1 (1 << 7) /* Bit 7: USIC1 Gating Status */ +#define SCU_CGAT1_USIC2 (1 << 8) /* Bit 8: USIC1 Gating Status */ +#define SCU_CGAT1_PPORTS (1 << 9) /* Bit 9: PORTS Gating Status */ /* Peripheral 2 Clock Gating Status, Peripheral 2 Clock Gating Set, Peripheral 2 Clock Gating Clear */ -#define SCU_CGATSTAT2_WDT (1 << 1) /* Bit 1: WDT Gating Status */ -#define SCU_CGATSTAT2_ETH0 (1 << 2) /* Bit 2: ETH0 Gating Status */ -#define SCU_CGATSTAT2_DMA0 (1 << 4) /* Bit 4: DMA0 Gating Status */ -#define SCU_CGATSTAT2_DMA1 (1 << 5) /* Bit 5: DMA1 Gating Status */ -#define SCU_CGATSTAT2_FCE (1 << 6) /* Bit 6: FCE Gating Status */ -#define SCU_CGATSTAT2_USB (1 << 7) /* Bit 7: USB Gating Status */ -#define SCU_CGATSTAT2_ECAT (1 << 10) /* Bit 10: ECAT Gating Status */ +#define SCU_CGAT2_WDT (1 << 1) /* Bit 1: WDT Gating Status */ +#define SCU_CGAT2_ETH0 (1 << 2) /* Bit 2: ETH0 Gating Status */ +#define SCU_CGAT2_DMA0 (1 << 4) /* Bit 4: DMA0 Gating Status */ +#define SCU_CGAT2_DMA1 (1 << 5) /* Bit 5: DMA1 Gating Status */ +#define SCU_CGAT2_FCE (1 << 6) /* Bit 6: FCE Gating Status */ +#define SCU_CGAT2_USB (1 << 7) /* Bit 7: USB Gating Status */ +#define SCU_CGAT2_ECAT (1 << 10) /* Bit 10: ECAT Gating Status */ /* Peripheral 3 Clock Gating Status, Peripheral 3 Clock Gating Set, Peripheral 3 Clock Gating Clear */ -#define SCU_CGATSTAT3_EBU (1 << 2) /* Bit 2: EBU Gating Status */ +#define SCU_CGAT3_EBU (1 << 2) /* Bit 2: EBU Gating Status */ /* Oscillator Control SCU Registers */ diff --git a/arch/arm/src/xmc4/xmc4_clrpend.c b/arch/arm/src/xmc4/xmc4_clrpend.c index 2eab7d6ffa..33422ea5e2 100644 --- a/arch/arm/src/xmc4/xmc4_clrpend.c +++ b/arch/arm/src/xmc4/xmc4_clrpend.c @@ -44,22 +44,6 @@ #include "nvic.h" #include "up_arch.h" -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Public Data - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - /**************************************************************************** * Public Functions ****************************************************************************/ diff --git a/arch/arm/src/xmc4/xmc4_serial.c b/arch/arm/src/xmc4/xmc4_serial.c index e09a23ef55..78db3fd792 100644 --- a/arch/arm/src/xmc4/xmc4_serial.c +++ b/arch/arm/src/xmc4/xmc4_serial.c @@ -232,6 +232,7 @@ struct xmc4_dev_s uintptr_t uartbase; /* Base address of UART registers */ uint32_t baud; /* Configured baud */ uint32_t clock; /* Clocking frequency of the UART module */ + uint8_t channel; /* USIC channel identification */ uint8_t irqs; /* Status IRQ associated with this UART (for enable) */ uint8_t ie; /* Interrupts enabled */ uint8_t parity; /* 0=none, 1=odd, 2=even */ @@ -312,8 +313,9 @@ static char g_uart5txbuffer[CONFIG_UART5_TXBUFSIZE]; #ifdef HAVE_UART0 static struct xmc4_dev_s g_uart0priv = { - .uartbase = XMC4_UART0_BASE, + .uartbase = XMC4_USIC0_CH0_BASE, .clock = BOARD_CORECLK_FREQ, + .channel = (uint8_t)USIC0_CHAN0, .baud = CONFIG_UART0_BAUD, .irqs = XMC4_IRQ_USIC0, .parity = CONFIG_UART0_PARITY, @@ -343,8 +345,9 @@ static uart_dev_t g_uart0port = #ifdef HAVE_UART1 static struct xmc4_dev_s g_uart1priv = { - .uartbase = XMC4_UART1_BASE, + .uartbase = XMC4_USIC0_CH1_BASE, .clock = BOARD_CORECLK_FREQ, + .channel = (uint8_t)USIC0_CHAN1, .baud = CONFIG_UART1_BAUD, .irqs = XMC4_IRQ_USIC1, .parity = CONFIG_UART1_PARITY, @@ -374,8 +377,9 @@ static uart_dev_t g_uart1port = #ifdef HAVE_UART2 static struct xmc4_dev_s g_uart2priv = { - .uartbase = XMC4_UART2_BASE, + .uartbase = XMC4_USIC1_CH0_BASE, .clock = BOARD_BUS_FREQ, + .channel = (uint8_t)USIC1_CHAN0, .baud = CONFIG_UART2_BAUD, .irqs = XMC4_IRQ_USIC2, .parity = CONFIG_UART2_PARITY, @@ -405,8 +409,9 @@ static uart_dev_t g_uart2port = #ifdef HAVE_UART3 static struct xmc4_dev_s g_uart3priv = { - .uartbase = XMC4_UART3_BASE, + .uartbase = XMC4_USIC1_CH1_BASE, .clock = BOARD_BUS_FREQ, + .channel = (uint8_t)USIC1_CHAN1, .baud = CONFIG_UART3_BAUD, .irqs = XMC4_IRQ_USIC3, .parity = CONFIG_UART3_PARITY, @@ -436,8 +441,9 @@ static uart_dev_t g_uart3port = #ifdef HAVE_UART4 static struct xmc4_dev_s g_uart4priv = { - .uartbase = XMC4_UART4_BASE, + .uartbase = XMC4_USIC2_CH0_BASE, .clock = BOARD_BUS_FREQ, + .channel = (uint8_t)USIC2_CHAN0, .baud = CONFIG_UART4_BAUD, .irqs = XMC4_IRQ_USIC4, .parity = CONFIG_UART4_PARITY, @@ -467,8 +473,9 @@ static uart_dev_t g_uart4port = #ifdef HAVE_UART5 static struct xmc4_dev_s g_uart5priv = { - .uartbase = XMC4_UART5_BASE, + .uartbase = XMC4_USIC2_CH1_BASE, .clock = BOARD_BUS_FREQ, + .channel = (uint8_t)USIC2_CHAN1, .baud = CONFIG_UART5_BAUD, .irqs = XMC4_IRQ_USIC5, .parity = CONFIG_UART5_PARITY, diff --git a/arch/arm/src/xmc4/xmc4_usic.c b/arch/arm/src/xmc4/xmc4_usic.c new file mode 100644 index 0000000000..f252bb1a49 --- /dev/null +++ b/arch/arm/src/xmc4/xmc4_usic.c @@ -0,0 +1,397 @@ +/**************************************************************************** + * arch/arm/src/xmc4/xmc4_usic.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include + +#include "up_arch.h" +#include "chip/xmc4_usic.h" +#include "chip/xmc4_scu.h" +#include "xmc4_usic.h" + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: xmc4_enable_usic + * + * Description: + * Enable the USIC module indicated by the 'usic' enumeration value + * + * Returned Value: + * Zero (OK) is returned on success; A negated errno value is returned to + * indicate the nature of any failure. + * + ****************************************************************************/ + +int xmc4_enable_usic(enum usic_e usic) +{ + switch (usic) + { + case USIC0: + /* Check if USIC0 is already ungated */ + + if ((getreg32(XMC4_SCU_CGATSTAT0) & SCU_CGAT0_USIC0) == 0) + { + /* Ungate USIC0 clocking */ + + putreg32(SCU_CGAT0_USIC0, XMC4_SCU_CGATCLR0); + + /* De-assert peripheral reset USIC0 */ + + putreg32(SCU_PR0_USIC0RS, XMC4_SCU_PRCLR0); + } + + break; + +#if XMC4_NUSIC > 1 + case USIC1: + /* Check if USIC1 is already ungated */ + + if ((getreg32(XMC4_SCU_CGATSTAT1) & SCU_CGAT1_USIC1) == 0) + { + /* Ungate USIC1 clocking */ + + putreg32(SCU_CGAT1_USIC1, XMC4_SCU_CGATCLR1); + + /* De-assert peripheral reset USIC1 */ + + putreg32(SCU_PR1_USIC1RS, XMC4_SCU_PRCLR1); + } + + break; + +#if XMC4_NUSIC > 2 + case USIC2: + /* Check if USIC2 is already ungated */ + + if ((getreg32(XMC4_SCU_CGATSTAT1) & SCU_CGAT1_USIC2) == 0) + { + /* Ungate USIC2 clocking */ + + putreg32(SCU_CGAT1_USIC2, XMC4_SCU_CGATCLR1); + + /* De-assert peripheral reset USIC2 */ + + putreg32(SCU_PR1_USIC2RS, XMC4_SCU_PRCLR1); + } + + break; +#endif +#endif + + default: + return -EINVAL; + } + + return OK; +} + +/**************************************************************************** + * Name: xmc4_disable_usic + * + * Description: + * Disable the USIC module indicated by the 'usic' enumeration value + * + * Returned Value: + * Zero (OK) is returned on success; A negated errno value is returned to + * indicate the nature of any failure. + * + ****************************************************************************/ + +int xmc4_disable_usic(enum usic_e usic) +{ + switch (usic) + { + case USIC0: + /* Assert peripheral reset USIC0 */ + + putreg32(SCU_PR0_USIC0RS, XMC4_SCU_PRSET0); + + /* Gate USIC0 clocking */ + + putreg32(SCU_CGAT0_USIC0, XMC4_SCU_CGATSET0); + break; + +#if XMC4_NUSIC > 1 + case USIC1: + /* Assert peripheral reset USIC0 */ + + putreg32(SCU_PR1_USIC1RS, XMC4_SCU_PRSET1); + + /* Gate USIC0 clocking */ + + putreg32(SCU_CGAT1_USIC1, XMC4_SCU_CGATSET1); + break; + +#if XMC4_NUSIC > 2 + case USIC2: + /* Assert peripheral reset USIC0 */ + + putreg32(SCU_PR1_USIC2RS, XMC4_SCU_PRSET1); + + /* Gate USIC0 clocking */ + + putreg32(SCU_CGAT1_USIC2, XMC4_SCU_CGATSET1); + break; +#endif +#endif + + default: + return -EINVAL; + } + + return OK; +} + +/**************************************************************************** + * Name: xmc4_enable_usic_channel + * + * Description: + * Enable the USIC channel indicated by 'channel'. Also enable and reset + * the USIC module if it is not already enabled. + * + * Returned Value: + * Zero (OK) is returned on success; A negated errno value is returned to + * indicate the nature of any failure. + * + ****************************************************************************/ + +int xmc4_enable_usic_channel(enum usic_channel_e channel) +{ + uintptr_t base; + uintptr_t regaddr; + uint32_t regval; + + switch (channel) + { + case USIC0_CHAN0: + /* USIC0 Channel 0 base address */ + + base = XMC4_USIC0_CH0_BASE; + + /* Enable USIC0 */ + + xmc4_enable_usic(USIC0); + break; + + case USIC0_CHAN1: + /* USIC0 Channel 1 base address */ + + base = XMC4_USIC0_CH1_BASE; + + /* Enable USIC0 */ + + xmc4_enable_usic(USIC0); + break; + +#if XMC4_NUSIC > 1 + case USIC1_CHAN0: + /* USIC1 Channel 0 base address */ + + base = XMC4_USIC1_CH0_BASE; + + /* Enable USIC1 */ + + xmc4_enable_usic(USIC1); + break; + + case USIC1_CHAN1: + /* USIC1 Channel 1 base address */ + + base = XMC4_USIC1_CH1_BASE; + + /* Enable USIC1 */ + + xmc4_enable_usic(USIC1); + break; + +#if XMC4_NUSIC > 2 + case USIC2_CHAN0: + /* USIC2 Channel 0 base address */ + + base = XMC4_USIC2_CH0_BASE; + + /* Enable USIC2 */ + + xmc4_enable_usic(USIC2); + break; + + case USIC2_CHAN1: + /* USIC2 Channel 1 base address */ + + base = XMC4_USIC2_CH1_BASE; + + /* Enable USIC2 */ + + xmc4_enable_usic(USIC2); + break; +#endif +#endif + + default: + return -EINVAL; + } + + /* Enable USIC channel */ + + regaddr = base + XMC4_USIC_KSCFG_OFFSET; + putreg32(USIC_KSCFG_MODEN | USIC_KSCFG_BPMODEN, regaddr); + + /* Wait for the channel to become fully enabled */ + + while ((getreg32(regaddr) & USIC_KSCFG_MODEN) == 0) + { + } + + /* Set USIC channel in IDLE mode */ + + regaddr = base + XMC4_USIC_CCR_OFFSET; + regval = getreg32(regaddr); + regval &= ~USIC_CCR_MODE_MASK; + putreg32(regval, regaddr); + + return OK; +} + +/**************************************************************************** + * Name: xmc4_disable_usic_channel + * + * Description: + * Disable the USIC channel indicated by 'channel'. Also disable and reset + * the USIC module if both channels have been disabled. + * + * Returned Value: + * Zero (OK) is returned on success; A negated errno value is returned to + * indicate the nature of any failure. + * + ****************************************************************************/ + +int xmc4_disable_usic_channel(enum usic_channel_e channel) +{ + uintptr_t base; + uintptr_t other; + uintptr_t regaddr; + uint32_t regval; + enum usic_e usic; + + switch (channel) + { + case USIC0_CHAN0: + /* Enable USIC0 Channel 0 base address */ + + base = XMC4_USIC0_CH0_BASE; + other = XMC4_USIC0_CH1_BASE; + usic = USIC0; + break; + + case USIC0_CHAN1: + /* Enable USIC0 Channel 1 base address */ + + base = XMC4_USIC0_CH1_BASE; + other = XMC4_USIC0_CH0_BASE; + usic = USIC0; + break; + +#if XMC4_NUSIC > 1 + case USIC1_CHAN0: + /* Enable USIC1 Channel 0 base address */ + + base = XMC4_USIC1_CH0_BASE; + other = XMC4_USIC1_CH1_BASE; + usic = USIC1; + break; + + case USIC1_CHAN1: + /* Enable USIC1 Channel 1 base address */ + + base = XMC4_USIC1_CH1_BASE; + other = XMC4_USIC1_CH0_BASE; + usic = USIC1; + break; + +#if XMC4_NUSIC > 2 + case USIC2_CHAN0: + /* Enable USIC2 Channel 0 base address */ + + base = XMC4_USIC2_CH0_BASE; + other = XMC4_USIC2_CH1_BASE; + usic = USIC2; + break; + + case USIC2_CHAN1: + /* Enable USIC2 Channel 1 base address */ + + base = XMC4_USIC2_CH1_BASE; + other = XMC4_USIC2_CH0_BASE; + usic = USIC2; + break; +#endif +#endif + + default: + return -EINVAL; + } + + /* Disable this channel */ + + regaddr = base + XMC4_USIC_KSCFG_OFFSET; + regval = getreg32(regaddr); + regval &= ~USIC_KSCFG_MODEN; + regval |= USIC_KSCFG_BPMODEN; + putreg32(regval, regaddr); + + /* Check if the other channel has also been disabled */ + + regaddr = other + XMC4_USIC_KSCFG_OFFSET; + if ((getreg32(regaddr) & USIC_KSCFG_MODEN) == 0) + { + /* Yes... Disable the USIC module */ + + xmc4_disable_usic(usic); + } + + return OK; +} \ No newline at end of file diff --git a/arch/arm/src/xmc4/xmc4_usic.h b/arch/arm/src/xmc4/xmc4_usic.h index d589459037..e1bf78dc07 100644 --- a/arch/arm/src/xmc4/xmc4_usic.h +++ b/arch/arm/src/xmc4/xmc4_usic.h @@ -67,10 +67,10 @@ enum usic_channel_e { USIC0_CHAN0 = 0, /* USIC0, Channel 0 */ USIC0_CHAN1 = 1, /* USIC0, Channel 1 */ - USIC1_CHAN0 = 0, /* USIC1, Channel 0 */ - USIC1_CHAN1 = 1, /* USIC1, Channel 1 */ - USIC2_CHAN0 = 0, /* USIC2, Channel 0 */ - USIC2_CHAN1 = 1 /* USIC2, Channel 1 */ + USIC1_CHAN0 = 2, /* USIC1, Channel 0 */ + USIC1_CHAN1 = 3, /* USIC1, Channel 1 */ + USIC2_CHAN0 = 4, /* USIC2, Channel 0 */ + USIC2_CHAN1 = 5 /* USIC2, Channel 1 */ }; /**************************************************************************** @@ -91,6 +91,20 @@ enum usic_channel_e int xmc4_enable_usic(enum usic_e usic); +/**************************************************************************** + * Name: xmc4_disable_usic + * + * Description: + * Disable the USIC module indicated by the 'usic' enumeration value + * + * Returned Value: + * Zero (OK) is returned on success; A negated errno value is returned to + * indicate the nature of any failure. + * + ****************************************************************************/ + +int xmc4_disable_usic(enum usic_e usic); + /**************************************************************************** * Name: xmc4_enable_usic_channel * @@ -106,4 +120,19 @@ int xmc4_enable_usic(enum usic_e usic); int xmc4_enable_usic_channel(enum usic_channel_e channel); +/**************************************************************************** + * Name: xmc4_disable_usic_channel + * + * Description: + * Disable the USIC channel indicated by 'channel'. Also disable and reset + * the USIC module if both channels have been disabled. + * + * Returned Value: + * Zero (OK) is returned on success; A negated errno value is returned to + * indicate the nature of any failure. + * + ****************************************************************************/ + +int xmc4_disable_usic_channel(enum usic_channel_e channel); + #endif /* __ARCH_ARM_SRC_XMC4_XMC4_USIC_H */ -- GitLab From e8a30890f2229a9849ed59fc856b82d01f066f80 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 19 Mar 2017 13:05:31 -0600 Subject: [PATCH 108/990] Cosmetic changes from review of last PR. --- arch/arm/src/stm32/stm32_comp.c | 187 ++++++++++++++----------- arch/arm/src/stm32/stm32_comp.h | 120 ++++++++-------- configs/nucleo-f334r8/src/stm32_comp.c | 18 --- 3 files changed, 163 insertions(+), 162 deletions(-) diff --git a/arch/arm/src/stm32/stm32_comp.c b/arch/arm/src/stm32/stm32_comp.c index 59a3abacbc..548baa9b11 100644 --- a/arch/arm/src/stm32/stm32_comp.c +++ b/arch/arm/src/stm32/stm32_comp.c @@ -147,114 +147,114 @@ #ifdef CONFIG_STM32_COMP1 static struct stm32_comp_s g_comp1priv = - { - .blanking = COMP1_BLANKING, - .pol = COMP1_POL, - .inm = COMP1_INM, - .out = COMP1_OUTSEL, - .lock = COMP1_LOCK, - .csr = STM32_COMP1_CSR, +{ + .blanking = COMP1_BLANKING, + .pol = COMP1_POL, + .inm = COMP1_INM, + .out = COMP1_OUTSEL, + .lock = COMP1_LOCK, + .csr = STM32_COMP1_CSR, #ifndef CONFIG_STM32_STM32F33XX - .mode = COMP1_MODE, - .hyst = COMP1_HYST, + .mode = COMP1_MODE, + .hyst = COMP1_HYST, #endif - }; +}; #endif #ifdef CONFIG_STM32_COMP2 static struct stm32_comp_s g_comp2priv = - { - .blanking = COMP2_BLANKING, - .pol = COMP2_POL, - .inm = COMP2_INM, - .out = COMP2_OUTSEL, - .lock = COMP2_LOCK, - .csr = STM32_COMP2_CSR, +{ + .blanking = COMP2_BLANKING, + .pol = COMP2_POL, + .inm = COMP2_INM, + .out = COMP2_OUTSEL, + .lock = COMP2_LOCK, + .csr = STM32_COMP2_CSR, #ifndef CONFIG_STM32_STM32F33XX - .mode = COMP2_MODE, - .hyst = COMP2_HYST, + .mode = COMP2_MODE, + .hyst = COMP2_HYST, #endif - }; +}; #endif #ifdef CONFIG_STM32_COMP3 - static struct stm32_comp_s g_comp3priv = - { - .blanking = COMP3_BLANKING, - .pol = COMP3_POL, - .inm = COMP3_INM, - .out = COMP3_OUTSEL, - .lock = COMP3_LOCK, - .csr = STM32_COMP3_CSR, +static struct stm32_comp_s g_comp3priv = +{ + .blanking = COMP3_BLANKING, + .pol = COMP3_POL, + .inm = COMP3_INM, + .out = COMP3_OUTSEL, + .lock = COMP3_LOCK, + .csr = STM32_COMP3_CSR, #ifndef CONFIG_STM32_STM32F33XX - .mode = COMP3_MODE, - .hyst = COMP3_HYST, + .mode = COMP3_MODE, + .hyst = COMP3_HYST, #endif - }; +}; #endif #ifdef CONFIG_STM32_COMP4 - static struct stm32_comp_s g_comp4priv = - { - .blanking = COMP4_BLANKING, - .pol = COMP4_POL, - .inm = COMP4_INM, - .out = COMP4_OUTSEL, - .lock = COMP4_LOCK, - .csr = STM32_COMP4_CSR, +static struct stm32_comp_s g_comp4priv = +{ + .blanking = COMP4_BLANKING, + .pol = COMP4_POL, + .inm = COMP4_INM, + .out = COMP4_OUTSEL, + .lock = COMP4_LOCK, + .csr = STM32_COMP4_CSR, #ifndef CONFIG_STM32_STM32F33XX - .mode = COMP4_MODE, - .hyst = COMP4_HYST, + .mode = COMP4_MODE, + .hyst = COMP4_HYST, #endif - }; +}; #endif #ifdef CONFIG_STM32_COMP5 - static struct stm32_comp_s g_comp5priv = - { - .blanking = COMP5_BLANKING, - .pol = COMP5_POL, - .inm = COMP5_INM, - .out = COMP5_OUTSEL, - .lock = COMP5_LOCK, - .csr = STM32_COMP5_CSR, +static struct stm32_comp_s g_comp5priv = +{ + .blanking = COMP5_BLANKING, + .pol = COMP5_POL, + .inm = COMP5_INM, + .out = COMP5_OUTSEL, + .lock = COMP5_LOCK, + .csr = STM32_COMP5_CSR, #ifndef CONFIG_STM32_STM32F33XX - .mode = COMP5_MODE, - .hyst = COMP5_HYST, + .mode = COMP5_MODE, + .hyst = COMP5_HYST, #endif - }; +}; #endif #ifdef CONFIG_STM32_COMP6 - static struct stm32_comp_s g_comp6priv = - { - .blanking = COMP6_BLANKING, - .pol = COMP6_POL, - .inm = COMP6_INM, - .out = COMP6_OUTSEL, - .lock = COMP6_LOCK, - .csr = STM32_COMP6_CSR, +static struct stm32_comp_s g_comp6priv = +{ + .blanking = COMP6_BLANKING, + .pol = COMP6_POL, + .inm = COMP6_INM, + .out = COMP6_OUTSEL, + .lock = COMP6_LOCK, + .csr = STM32_COMP6_CSR, #ifndef CONFIG_STM32_STM32F33XX - .mode = COMP6_MODE, - .hyst = COMP6_HYST, + .mode = COMP6_MODE, + .hyst = COMP6_HYST, #endif - }; +}; #endif #ifdef CONFIG_STM32_COMP7 - static struct stm32_comp_s g_comp7priv = - { - .blanking = COMP7_BLANKING, - .pol = COMP7_POL, - .inm = COMP7_INM, - .out = COMP7_OUTSEL, - .lock = COMP7_LOCK, - .csr = STM32_COMP7_CSR, +static struct stm32_comp_s g_comp7priv = +{ + .blanking = COMP7_BLANKING, + .pol = COMP7_POL, + .inm = COMP7_INM, + .out = COMP7_OUTSEL, + .lock = COMP7_LOCK, + .csr = STM32_COMP7_CSR, #ifndef CONFIG_STM32_STM32F33XX - .mode = COMP7_MODE, - .hyst = COMP7_HYST, + .mode = COMP7_MODE, + .hyst = COMP7_HYST, #endif - }; +}; #endif /**************************************************************************** @@ -268,10 +268,6 @@ static inline void comp_putreg_csr(FAR struct stm32_comp_s *priv, uint32_t value); static bool stm32_complock_get(FAR struct stm32_comp_s *priv); -/**************************************************************************** - * Private Data - ****************************************************************************/ - /**************************************************************************** * Private Functions ****************************************************************************/ @@ -401,30 +397,37 @@ int stm32_compconfig(FAR struct stm32_comp_s *priv) index = 1; break; #endif + case STM32_COMP2_CSR: index = 2; break; + #ifdef CONFIG_STM32_COMP3 case STM32_COMP3_CSR: index = 3; break; #endif + case STM32_COMP4_CSR: index = 4; break; + #ifdef CONFIG_STM32_COMP5 case STM32_COMP5_CSR: index = 5; break; #endif + case STM32_COMP6_CSR: index = 6; break; + #ifdef CONFIG_STM32_COMP7 case STM32_COMP7_CSR: index = 7; break; #endif + default: return -EINVAL; } @@ -438,16 +441,19 @@ int stm32_compconfig(FAR struct stm32_comp_s *priv) stm32_configgpio(GPIO_COMP2_INP); break; #endif + #ifdef CONFIG_STM32_COMP4 case 4: stm32_configgpio(GPIO_COMP4_INP); break; #endif + #ifdef CONFIG_STM32_COMP6 case 6: stm32_configgpio(GPIO_COMP6_INP); break; #endif + default: return -EINVAL; } @@ -518,7 +524,7 @@ int stm32_compconfig(FAR struct stm32_comp_s *priv) return -EINVAL; } - break; + break; } default: @@ -567,9 +573,14 @@ int stm32_compconfig(FAR struct stm32_comp_s *priv) case COMP_OUTSEL_T2OCC: if (index == 2) - regval |= COMP2_CSR_OUTSEL_T2OCC; + { + regval |= COMP2_CSR_OUTSEL_T2OCC; + } else if (index == 6) - regval |= COMP6_CSR_OUTSEL_T2OCC; + { + regval |= COMP6_CSR_OUTSEL_T2OCC; + } + break; case COMP_OUTSEL_T16OCC: @@ -594,7 +605,6 @@ int stm32_compconfig(FAR struct stm32_comp_s *priv) default: return -EINVAL; - } /* Set Comparator output polarity */ @@ -648,7 +658,9 @@ int stm32_compconfig(FAR struct stm32_comp_s *priv) /* Lock Comparator if needed */ if (priv->lock == COMP_LOCK_RO) - stm32_complock(priv, true); + { + stm32_complock(priv, true); + } return OK; } @@ -684,42 +696,49 @@ FAR struct stm32_comp_s* stm32_compinitialize(int intf) priv = &g_comp1priv; break; #endif + #ifdef CONFIG_STM32_COMP2 case 2: ainfo("COMP2 selected\n"); priv = &g_comp2priv; break; #endif + #ifdef CONFIG_STM32_COMP3 case 3: ainfo("COMP3 selected\n"); priv = &g_comp3priv; break; #endif + #ifdef CONFIG_STM32_COMP4 case 4: ainfo("COMP4 selected\n"); priv = &g_comp4priv; break; #endif + #ifdef CONFIG_STM32_COMP5 case 5: ainfo("COMP5 selected\n"); priv = &g_comp5priv; break; #endif + #ifdef CONFIG_STM32_COMP6 case 6: ainfo("COMP6 selected\n"); priv = &g_comp6priv; break; #endif + #ifdef CONFIG_STM32_COMP7 case 7: ainfo("COMP7 selected\n"); priv = &g_comp7priv; break; #endif + default: aerr("ERROR: No COMP interface defined\n"); return NULL; diff --git a/arch/arm/src/stm32/stm32_comp.h b/arch/arm/src/stm32/stm32_comp.h index 3b858dbcc3..99d45bad63 100644 --- a/arch/arm/src/stm32/stm32_comp.h +++ b/arch/arm/src/stm32/stm32_comp.h @@ -75,100 +75,100 @@ /* Blanking source */ enum stm32_comp_blanking_e - { - COMP_BLANKING_DIS, +{ + COMP_BLANKING_DIS, #if defined(CONFIG_STM32_STM32F33XX) - COMP_BLANKING_T1OC5, - COMP_BLANKING_T3OC4, - COMP_BLANKING_T2OC3, - COMP_BLANKING_T3OC3, - COMP_BLANKING_T15OC1, - COMP_BLANKING_T2OC4, - COMP_BLANKING_T15OC2, + COMP_BLANKING_T1OC5, + COMP_BLANKING_T3OC4, + COMP_BLANKING_T2OC3, + COMP_BLANKING_T3OC3, + COMP_BLANKING_T15OC1, + COMP_BLANKING_T2OC4, + COMP_BLANKING_T15OC2, #endif - }; +}; /* Output polarisation */ enum stm32_comp_pol_e - { - COMP_POL_NONINVERT, - COMP_POL_INVERTED - }; +{ + COMP_POL_NONINVERT, + COMP_POL_INVERTED +}; /* Inverting input */ enum stm32_comp_inm_e - { - COMP_INMSEL_1P4VREF, - COMP_INMSEL_1P2VREF, - COMP_INMSEL_3P4VREF, - COMP_INMSEL_VREF, - COMP_INMSEL_DAC1CH1, - COMP_INMSEL_DAC1CH2, - COMP_INMSEL_PIN - }; +{ + COMP_INMSEL_1P4VREF, + COMP_INMSEL_1P2VREF, + COMP_INMSEL_3P4VREF, + COMP_INMSEL_VREF, + COMP_INMSEL_DAC1CH1, + COMP_INMSEL_DAC1CH2, + COMP_INMSEL_PIN +}; /* Output selection */ enum stm32_comp_outsel_e - { - COMP_OUTSEL_NOSEL, +{ + COMP_OUTSEL_NOSEL, #if defined(CONFIG_STM32_STM32F33XX) - COMP_OUTSEL_BRKACTH, - COMP_OUTSEL_BRK2, - COMP_OUTSEL_T1OCC, /* COMP2 only */ - COMP_OUTSEL_T3CAP3, /* COMP4 only */ - COMP_OUTSEL_T2CAP2, /* COMP6 only */ - COMP_OUTSEL_T1CAP1, /* COMP2 only */ - COMP_OUTSEL_T2CAP4, /* COMP2 only */ - COMP_OUTSEL_T15CAP2, /* COMP4 only */ - COMP_OUTSEL_T2OCC, /* COMP6 only */ - COMP_OUTSEL_T16OCC, /* COMP2 only */ - COMP_OUTSEL_T3CAP1, /* COMP2 only */ - COMP_OUTSEL_T15OCC, /* COMP4 only */ - COMP_OUTSEL_T16CAP1, /* COMP6 only */ - COMP_OUTSEL_T3OCC, /* COMP2 and COMP4 only */ + COMP_OUTSEL_BRKACTH, + COMP_OUTSEL_BRK2, + COMP_OUTSEL_T1OCC, /* COMP2 only */ + COMP_OUTSEL_T3CAP3, /* COMP4 only */ + COMP_OUTSEL_T2CAP2, /* COMP6 only */ + COMP_OUTSEL_T1CAP1, /* COMP2 only */ + COMP_OUTSEL_T2CAP4, /* COMP2 only */ + COMP_OUTSEL_T15CAP2, /* COMP4 only */ + COMP_OUTSEL_T2OCC, /* COMP6 only */ + COMP_OUTSEL_T16OCC, /* COMP2 only */ + COMP_OUTSEL_T3CAP1, /* COMP2 only */ + COMP_OUTSEL_T15OCC, /* COMP4 only */ + COMP_OUTSEL_T16CAP1, /* COMP6 only */ + COMP_OUTSEL_T3OCC, /* COMP2 and COMP4 only */ #endif - }; +}; /* CSR register lock state */ enum stm32_comp_lock_e - { - COMP_LOCK_RW, - COMP_LOCK_RO - }; +{ + COMP_LOCK_RW, + COMP_LOCK_RO +}; #ifndef CONFIG_STM32_STM32F33XX /* Hysteresis */ enum stm32_comp_hyst_e - { - COMP_HYST_DIS, - COMP_HYST_LOW, - COMP_HYST_MEDIUM, - COMP_HYST_HIGH - }, +{ + COMP_HYST_DIS, + COMP_HYST_LOW, + COMP_HYST_MEDIUM, + COMP_HYST_HIGH +}, /* Power/Speed Modes */ enum stm32_comp_mode_e - { - COMP_MODE_HIGHSPEED, - COMP_MODE_MEDIUMSPEED, - COMP_MODE_LOWPOWER, - COMP_MODE_ULTRALOWPOWER - }; +{ + COMP_MODE_HIGHSPEED, + COMP_MODE_MEDIUMSPEED, + COMP_MODE_LOWPOWER, + COMP_MODE_ULTRALOWPOWER +}; /* Window mode */ enum stm32_comp_winmode_e - { - COMP_WINMODE_DIS, - COMP_WINMODE_EN - }; +{ + COMP_WINMODE_DIS, + COMP_WINMODE_EN +}; #endif diff --git a/configs/nucleo-f334r8/src/stm32_comp.c b/configs/nucleo-f334r8/src/stm32_comp.c index 392dd92d7a..0f775e1f3d 100644 --- a/configs/nucleo-f334r8/src/stm32_comp.c +++ b/configs/nucleo-f334r8/src/stm32_comp.c @@ -52,22 +52,6 @@ defined(CONFIG_STM32_COMP4) || \ defined(CONFIG_STM32_COMP6)) -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - /**************************************************************************** * Public Functions ****************************************************************************/ @@ -116,7 +100,6 @@ int stm32_comp_setup(void) } #endif - #if 0 /* COMP driver not implemented yet */ @@ -134,7 +117,6 @@ int stm32_comp_setup(void) return OK; } - #endif /* CONFIG_COMP && (CONFIG_STM32_COMP1 || * CONFIG_STM32_COMP2 * CONFIG_STM32_COMP6) */ -- GitLab From c023d41522496c0049a0a1c2202bab2478f6059c Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 19 Mar 2017 13:47:27 -0600 Subject: [PATCH 109/990] XMC4xxx: Beginning of Ethernet register header file --- arch/arm/src/xmc4/chip/xmc4_ethernet.h | 223 +++++++++++++++++++++++++ 1 file changed, 223 insertions(+) create mode 100644 arch/arm/src/xmc4/chip/xmc4_ethernet.h diff --git a/arch/arm/src/xmc4/chip/xmc4_ethernet.h b/arch/arm/src/xmc4/chip/xmc4_ethernet.h new file mode 100644 index 0000000000..26291fa45c --- /dev/null +++ b/arch/arm/src/xmc4/chip/xmc4_ethernet.h @@ -0,0 +1,223 @@ +/******************************************************************************************************************** + * arch/arm/src/xmc4/chip/xmc4_ethernet.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Reference: XMC4500 Reference Manual V1.5 2014-07 Microcontrollers. + * + * 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. + * + * May include some logic from sample code provided by Infineon: + * + * Copyright (C) 2011-2015 Infineon Technologies AG. All rights reserved. + * + * Infineon Technologies AG (Infineon) is supplying this software for use with + * Infineon's microcontrollers. This file can be freely distributed within + * development tools that are supporting such microcontrollers. + * + * THIS SOFTWARE IS PROVIDED AS IS. NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * INFINEON SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, + * OR CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ********************************************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_XMC4_CHIP_XMC4_ETHERNET_H +#define __ARCH_ARM_SRC_XMC4_CHIP_XMC4_ETHERNET_H + +/******************************************************************************************************************** + * Included Files + ********************************************************************************************************************/ + +#include + +#include "chip/xmc4_memorymap.h" + +/******************************************************************************************************************** + * Pre-processor Definitions + ********************************************************************************************************************/ + +/* Register Offsets *************************************************************************************************/ + +/* MAC Configuration Registers */ + +#define XMC4_ETH_MAC_CONFIGURATION_OFFSET 0x0000 /* MAC Configuration Register */ +#define XMC4_ETH_MAC_FRAME_FILTER_OFFSET 0x0004 /* MAC Frame Filter */ +#define XMC4_ETH_HASH_TABLE_HIGH_OFFSET 0x0008 /* Hash Table High Register */ +#define XMC4_ETH_HASH_TABLE_LOW_OFFSET 0x000c /* Hash Table Low Register */ +#define XMC4_ETH_GMII_ADDRESS_OFFSET 0x0010 /* MII Address Register */ +#define XMC4_ETH_GMII_DATA_OFFSET 0x0014 /* MII Data Register */ +#define XMC4_ETH_FLOW_CONTROL_OFFSET 0x0018 /* Flow Control Register */ +#define XMC4_ETH_VLAN_TAG_OFFSET 0x001c /* VLAN Tag Register */ +#define XMC4_ETH_VERSION_OFFSET 0x0020 /* Version Register */ +#define XMC4_ETH_DEBUG_OFFSET 0x0024 /* Debug Register */ +#define XMC4_ETH_REMOTE_WAKE_UP_FRAME_FILTER_OFFSET 0x0028 /* Remote Wake Up Frame Filter Register */ +#define XMC4_ETH_PMT_CONTROL_STATUS_OFFSET 0x002c /* PMT Control and Status Register */ +#define XMC4_ETH_INTERRUPT_STATUS_OFFSET 0x0038 /* Interrupt Register */ +#define XMC4_ETH_INTERRUPT_MASK_OFFSET 0x003c /* Interrupt Mask Register */ +#define XMC4_ETH_MAC_ADDRESS0_HIGH_OFFSET 0x0040 /* MAC Address0 High Register */ +#define XMC4_ETH_MAC_ADDRESS0_LOW_OFFSET 0x0044 /* MAC Address0 Low Register */ +#define XMC4_ETH_MAC_ADDRESS1_HIGH_OFFSET 0x0048 /* MAC Address1 High Register */ +#define XMC4_ETH_MAC_ADDRESS1_LOW_OFFSET 0x004c /* MAC Address1 Low Register */ +#define XMC4_ETH_MAC_ADDRESS2_HIGH_OFFSET 0x0050 /* MAC Address2 High Register */ +#define XMC4_ETH_MAC_ADDRESS2_LOW_OFFSET 0x0054 /* MAC Address2 Low Register */ +#define XMC4_ETH_MAC_ADDRESS3_HIGH_OFFSET 0x0058 /* MAC Address3 High Register */ +#define XMC4_ETH_MAC_ADDRESS3_LOW_OFFSET 0x005c /* MAC Address3 Low Register */ + +/* MAC Management Counters */ + +#define XMC4_ETH_MMC_CONTROL_OFFSET 0x0100 /* MMC Control Register */ +#define XMC4_ETH_MMC_RECEIVE_INTERRUPT_OFFSET 0x0104 /* MMC Receive Interrupt Register */ +#define XMC4_ETH_MMC_TRANSMIT_INTERRUPT_OFFSET 0x0108 /* MMC Transmit Interrupt Register */ +#define XMC4_ETH_MMC_RECEIVE_INTERRUPT_MASK_OFFSET 0x010c /* MMC Reveive Interrupt Mask Register */ +#define XMC4_ETH_MMC_TRANSMIT_INTERRUPT_MASK_OFFSET 0x0110 /* MMC Transmit Interrupt Mask Register */ +#define XMC4_ETH_TX_OCTET_COUNT_OFFSET 0x0114 /* Transmit Octet Count for Good and Bad Frames Register */ +#define XMC4_ETH_TX_FRAME_COUNT_OFFSET 0x0118 /* Transmit Frame Count for Goodand Bad Frames Register */ +#define XMC4_ETH_TX_BROADCAST_FRAMES_OFFSET 0x011c /* Transmit Frame Count for Good Broadcast Frames */ +#define XMC4_ETH_TX_MULTICAST_FRAMES_OFFSET 0x0120 /* Transmit Frame Count for Good Multicast Frames */ +#define XMC4_ETH_TX_64OCTETS_FRAMES_OFFSET 0x0124 /* Transmit Octet Count for Good and Bad 64 Byte Frames */ +#define XMC4_ETH_TX_65TO127OCTETS_FRAMES_OFFSET 0x0128 /* Transmit Octet Count for Good and Bad 65 to 127 Bytes Frames */ +#define XMC4_ETH_TX_128TO255OCTETS_FRAMES_OFFSET 0x012c /* Transmit Octet Count for Good and Bad 128 to 255 Bytes Frames */ +#define XMC4_ETH_TX_256TO511OCTETS_FRAMES_OFFSET 0x0130 /* Transmit Octet Count for Good and Bad 256 to 511 Bytes Frames */ +#define XMC4_ETH_TX_512TO1023OCTETS_FRAMES_OFFSET 0x0134 /* Transmit Octet Count for Good and Bad 512 to 1023 Bytes Frames */ +#define XMC4_ETH_TX_1024TOMAXOCTETS_FRAMES_OFFSET 0x0138 /* Transmit Octet Count for Good and Bad 1024 to Maxsize Bytes Frames */ +#define XMC4_ETH_TX_UNICAST_FRAMES_OFFSET 0x013c /* Transmit Frame Count for Good and Bad Unicast Frames */ +#define XMC4_ETH_TX_MULTICAST_FRAMES_OFFSET 0x0140 /* Transmit Frame Count for Good and Bad Multicast Frames */ +#define XMC4_ETH_TX_BROADCAST_FRAMES_OFFSET 0x0144 /* Transmit Frame Count for Good and Bad Broadcast Frames */ +#define XMC4_ETH_TX_UNDERFLOW_ERROR_FRAMES_OFFSET 0x0148 /* Transmit Frame Count for Underflow Error Frames */ +#define XMC4_ETH_TX_SINGLE_COLLISION_FRAMES_OFFSET 0x014c /* Transmit Frame Count for Frames Transmitted after Single Collision */ +#define XMC4_ETH_TX_MULTIPLE_COLLISION_FRAMES_OFFSET 0x0150 /* Transmit Frame Count for Frames Transmitted after Multiple Collision */ +#define XMC4_ETH_TX_DEFERRED_FRAMES_OFFSET 0x0154 /* Tx Deferred Frames Register */ +#define XMC4_ETH_TX_LATE_COLLISION_FRAMES_OFFSET 0x0158 /* Transmit Frame Count for Late Collision Error Frames */ +#define XMC4_ETH_TX_EXCESSIVE_COLLISION_FRAMES_OFFSET 0x015c /* Transmit Frame Count for Excessive Collision Error Frames */ +#define XMC4_ETH_TX_CARRIER_ERROR_FRAMES_OFFSET 0x0160 /* Transmit Frame Count for Carrier Sense Error Frames */ +#define XMC4_ETH_TX_OCTET_COUNT_OFFSET 0x0164 /* Tx Octet Count Good Register */ +#define XMC4_ETH_TX_FRAME_COUNT_OFFSET 0x0168 /* Tx Frame Count Good Register */ +#define XMC4_ETH_TX_EXCESSIVE_DEFERRAL_ERROR_OFFSET 0x016c /* Transmit Frame Count for Excessive Deferral Error Frames */ +#define XMC4_ETH_TX_PAUSE_FRAMES_OFFSET 0x0170 /* Transmit Frame Count for Good PAUSE Frames */ +#define XMC4_ETH_TX_VLAN_FRAMES_OFFSET 0x0174 /* Transmit Frame Count for Good VLAN Frames */ +#define XMC4_ETH_TX_OSIZE_FRAMES_OFFSET 0x0178 /* Transmit Frame Count for Good Oversize Frames */ + +#define XMC4_ETH_RX_FRAMES_COUNT_OFFSET 0x0180 /* Receive Frame Count for Good and Bad Frames */ +#define XMC4_ETH_RX_OCTET_COUNT_OFFSET 0x0184 /* Receive Octet Count for Good and Bad Frames */ +#define XMC4_ETH_RX_OCTET_COUNT_OFFSET 0x0188 /* Rx Octet Count Good Register */ +#define XMC4_ETH_RX_BROADCAST_FRAMES_OFFSET 0x018c /* Receive Frame Count for Good Broadcast Frames */ +#define XMC4_ETH_RX_MULTICAST_FRAMES_OFFSET 0x0190 /* Receive Frame Count for Good Multicast Frames */ +#define XMC4_ETH_RX_CRC_ERROR_FRAMES_OFFSET 0x0194 /* Receive Frame Count for CRC Error Frames */ +#define XMC4_ETH_RX_ALIGNMENT_ERROR_FRAMES_OFFSET 0x0198 /* Receive Frame Count for Alignment Error Frames */ +#define XMC4_ETH_RX_RUNT_ERROR_FRAMES_OFFSET 0x019c /* Receive Frame Count for Runt Error Frames */ +#define XMC4_ETH_RX_JABBER_ERROR_FRAMES_OFFSET 0x01a0 /* Receive Frame Count for Jabber Error Frames */ +#define XMC4_ETH_RX_UNDERSIZE_FRAMES_OFFSET 0x01a4 /* Receive Frame Count for Undersize Frames */ +#define XMC4_ETH_RX_OVERSIZE_FRAMES_OFFSET 0x01a8 /* Rx Oversize Frames Good Register */ +#define XMC4_ETH_RX_64OCTETS_FRAMES_OFFSET 0x01ac /* Receive Frame Count for Good and Bad 64 Byte Frames */ +#define XMC4_ETH_RX_65TO127OCTETS_FRAMES_OFFSET 0x01b0 /* Receive Frame Count for Good and Bad 65 to 127 Bytes Frames */ +#define XMC4_ETH_RX_128TO255OCTETS_FRAMES_OFFSET 0x01b4 /* Receive Frame Count for Good and Bad 128 to 255 Bytes Frames */ +#define XMC4_ETH_RX_256TO511OCTETS_FRAMES_OFFSET 0x01b8 /* Receive Frame Count for Good and Bad 256 to 511 Bytes Frames */ +#define XMC4_ETH_RX_512TO1023OCTETS_FRAMES_OFFSET 0x01bc /* Receive Frame Count for Good and Bad 512 to 1,023 Bytes Frames */ +#define XMC4_ETH_RX_1024TOMAXOCTETS_FRAMES_OFFSET 0x01c0 /* Receive Frame Count for Good and Bad 1,024 to Maxsize Bytes Frames */ +#define XMC4_ETH_RX_UNICAST_FRAMES_OFFSET 0x01c4 /* Receive Frame Count for Good Unicast Frames */ +#define XMC4_ETH_RX_LENGTH_ERROR_FRAMES_OFFSET 0x01c8 /* Receive Frame Count for Length Error Frames */ +#define XMC4_ETH_RX_OUT_OF_RANGE_TYPE_FRAMES_OFFSET 0x01cc /* Receive Frame Count for Out of Range Frames */ +#define XMC4_ETH_RX_PAUSE_FRAMES_OFFSET 0x01d0 /* Receive Frame Count for PAUSE Frames */ +#define XMC4_ETH_RX_FIFO_OVERFLOW_FRAMES_OFFSET 0x01d4 /* Receive Frame Count for FIFO Overflow Frames */ +#define XMC4_ETH_RX_VLAN_FRAMES_OFFSET 0x01d8 /* Receive Frame Count for Good and Bad VLAN Frames */ +#define XMC4_ETH_RX_WATCHDOG_ERROR_FRAMES_OFFSET 0x01dc /* Receive Frame Count for Watchdog Error Frames */ +#define XMC4_ETH_RX_RECEIVE_ERROR_FRAMES_OFFSET 0x01e0 /* Receive Frame Count for Receive Error Frames */ +#define XMC4_ETH_RX_CONTROL_FRAMES_OFFSET 0x01e4 /* Receive Frame Count for Good Control Frames Frames */ +#define XMC4_ETH_MMC_IPC_RECEIVE_INTERRUPT_MASK_OFFSET 0x0200 /* MMC Receive Checksum Offload Interrupt Mask Register */ +#define XMC4_ETH_MMC_IPC_RECEIVE_INTERRUPT_OFFSET 0x0208 /* MMC Receive Checksum Offload Interrupt Register */ +#define XMC4_ETH_RXIPV4_GOOD_FRAMES_OFFSET 0x0210 /* RxIPv4 Good Frames Register */ +#define XMC4_ETH_RXIPV4_HEADER_ERROR_FRAMES_OFFSET 0x0214 /* Receive IPV4 Header Error Frame Counter Register */ +#define XMC4_ETH_RXIPV4_NO_PAYLOAD_FRAMES_OFFSET 0x0218 /* Receive IPV4 No Payload Frame Counter Register */ +#define XMC4_ETH_RXIPV4_FRAGMENTED_FRAMES_OFFSET 0x021c /* Receive IPV4 Fragmented Frame Counter Register */ +#define XMC4_ETH_RXIPV4_UDP_CHECKSUM_DISABLED_FRAMES_OFFSET 0x0220 /* Receive IPV4 UDP Checksum Disabled Frame Counter Register */ +#define XMC4_ETH_RXIPV6_GOOD_FRAMES_OFFSET 0x0224 /* RxIPv6 Good Frames Register */ +#define XMC4_ETH_RXIPV6_HEADER_ERROR_FRAMES_OFFSET 0x0228 /* Receive IPV6 Header Error Frame Counter Register */ +#define XMC4_ETH_RXIPV6_NO_PAYLOAD_FRAMES_OFFSET 0x022c /* Receive IPV6 No Payload Frame Counter Register */ +#define XMC4_ETH_RXUDP_GOOD_FRAMES_OFFSET 0x0230 /* RxUDP Good Frames Register */ +#define XMC4_ETH_RXUDP_ERROR_FRAMES_OFFSET 0x0234 /* RxUDP Error Frames Register */ +#define XMC4_ETH_RXTCP_GOOD_FRAMES_OFFSET 0x0238 /* RxTCP Good Frames Register */ +#define XMC4_ETH_RXTCP_ERROR_FRAMES_OFFSET 0x023c /* RxTCP Error Frames Register */ +#define XMC4_ETH_RXICMP_GOOD_FRAMES_OFFSET 0x0240 /* RxICMP Good Frames Register */ +#define XMC4_ETH_RXICMP_ERROR_FRAMES_OFFSET 0x0244 /* RxICMP Error Frames Register */ +#define XMC4_ETH_RXIPV4_GOOD_OCTETS_OFFSET 0x0250 /* RxIPv4 Good Octets Register */ +#define XMC4_ETH_RXIPV4_HEADER_ERROR_OCTETS_OFFSET 0x0254 /* Receive IPV4 Header Error Octet Counter Register */ +#define XMC4_ETH_RXIPV4_NO_PAYLOAD_OCTETS_OFFSET 0x0258 /* Receive IPV4 No Payload Octet Counter Register */ +#define XMC4_ETH_RXIPV4_FRAGMENTED_OCTETS_OFFSET 0x025c /* Receive IPV4 Fragmented Octet Counter Register */ +#define XMC4_ETH_RXIPV4_UDP_CHECKSUM_DISABLE_OCTETS_OFFSET 0x0260 /* Receive IPV4 Fragmented Octet Counter Register */ +#define XMC4_ETH_RXIPV6_GOOD_OCTETS_OFFSET 0x0264 /* RxIPv6 Good Octets Register */ +#define XMC4_ETH_RXIPV6_HEADER_ERROR_OCTETS_OFFSET 0x0268 /* Receive IPV6 Header Error Octet Counter Register */ +#define XMC4_ETH_RXIPV6_NO_PAYLOAD_OCTETS_OFFSET 0x026c /* Receive IPV6 No Payload Octet Counter Register */ +#define XMC4_ETH_RXUDP_GOOD_OCTETS_OFFSET 0x0270 /* Receive UDP Good Octets Register */ +#define XMC4_ETH_RXUDP_ERROR_OCTETS_OFFSET 0x0274 /* Receive UDP Error Octets Register */ +#define XMC4_ETH_RXTCP_GOOD_OCTETS_OFFSET 0x0278 /* Receive TCP Good Octets Register */ +#define XMC4_ETH_RXTCP_ERROR_OCTETS_OFFSET 0x027c /* Receive TCP Error Octets Register */ +#define XMC4_ETH_RXICMP_GOOD_OCTETS_OFFSET 0x0280 /* Receive ICMP Good Octets Register */ +#define XMC4_ETH_RXICMP_ERROR_OCTETS_OFFSET 0x0284 /* Receive ICMP Error Octets Register */ + +/* System Time Registers */ + +#define XMC4_ETH_TIMESTAMP_CONTROL_OFFSET 0x0700 /* Timestamp Control Register */ +#define XMC4_ETH_SUB_SECOND_INCREMENT_OFFSET 0x0704 /* Sub-Second Increment Register */ +#define XMC4_ETH_SYSTEM_TIME_SECONDS_OFFSET 0x0708 /* System Time - Seconds Register */ +#define XMC4_ETH_SYSTEM_TIME_NANOSECONDS_OFFSET 0x070c /* System Time Nanoseconds Register */ +#define XMC4_ETH_SYSTEM_TIME_SECONDS_UPDATE_OFFSET 0x0710 /* System Time - Seconds Update Register */ +#define XMC4_ETH_SYSTEM_TIME_NANOSECONDS_UPDATE_OFFSET 0x0714 /* System Time Nanoseconds Update Register */ +#define XMC4_ETH_TIMESTAMP_ADDEND_OFFSET 0x0718 /* Timestamp Addend Register */ +#define XMC4_ETH_TARGET_TIME_SECONDS_OFFSET 0x071c /* Target Time Seconds Register */ +#define XMC4_ETH_TARGET_TIME_NANOSECONDS_OFFSET 0x0720 /* Target Time Nanoseconds Register */ +#define XMC4_ETH_SYSTEM_TIME_HIGHER_WORD_SECONDS_OFFSET 0x0724 /* System Time - Higher Word Seconds Register */ +#define XMC4_ETH_TIMESTAMP_STATUS_OFFSET 0x0728 /* Timestamp Status Register */ + +/* DMA Registers*/ + +#define XMC4_ETH_BUS_MODE_OFFSET 0x1000 /* Bus Mode Register */ +#define XMC4_ETH_TRANSMIT_POLL_DEMAND_OFFSET 0x1004 /* Transmit Poll Demand Register */ +#define XMC4_ETH_RECEIVE_POLL_DEMAND_OFFSET 0x1008 /* Receive Poll Demand Register */ +#define XMC4_ETH_RECEIVE_DESCRIPTOR_LIST_ADDRESS_OFFSET 0x100c /* Receive Descriptor Address Register */ +#define XMC4_ETH_TRANSMIT_DESCRIPTOR_LIST_ADDRESS_OFFSET 0x1010 /* Transmit descripter Address Register */ +#define XMC4_ETH_STATUS_OFFSET 0x1014 /* Status Register */ +#define XMC4_ETH_OPERATION_MODE_OFFSET 0x1018 /* Operation Mode Register */ +#define XMC4_ETH_INTERRUPT_ENABLE_OFFSET 0x101c /* Interrupt Enable Register */ +#define XMC4_ETH_MISSED_FRAME_BUFFER_OVERFLOW_COUNTER_OFFSET 0x1020 /* Missed Frame and Buffer Overflow Counter Register */ +#define XMC4_ETH_RECEIVE_INTERRUPT_WATCHDOG_TIMER_OFFSET 0x1024 /* Receive Interrupt Watchdog Timer Register */ +#define XMC4_ETH_AHB_STATUS_OFFSET 0x102c /* AHB Status Register */ +#define XMC4_ETH_CURRENT_HOST_TRANSMIT_DESCRIPTOR_OFFSET 0x1048 /* Current Host Transmit Descriptor Register */ +#define XMC4_ETH_CURRENT_HOST_RECEIVE_DESCRIPTOR_OFFSET 0x104c /* Current Host Receive Descriptor Register */ +#define XMC4_ETH_CURRENT_HOST_TRANSMIT_BUFFER_ADDRESS_OFFSET 0x1050 /* Current Host Transmit Buffer Address Register */ +#define XMC4_ETH_CURRENT_HOST_RECEIVE_BUFFER_ADDRESS_OFFSET 0x1054 /* Current Host Receive Buffer Address Register */ +#define XMC4_ETH_HW_FEATURE_OFFSET 0x1058 /* HW Feature Register */ + +/* Register Addresses ***********************************************************************************************/ + +/* Register Bit-Field Definitions ***********************************************************************************/ + + +#endif /* __ARCH_ARM_SRC_XMC4_CHIP_XMC4_ETHERNET_H */ -- GitLab From e1e4af74542a51ff8a7f9403194d31a274e195b2 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 19 Mar 2017 16:25:46 -0600 Subject: [PATCH 110/990] XMC4xxx: More Ethernet definitions. --- arch/arm/src/xmc4/chip/xmc4_ethernet.h | 449 ++++++++++++++++++++++++- arch/arm/src/xmc4/xmc4_allocateheap.c | 12 - 2 files changed, 438 insertions(+), 23 deletions(-) diff --git a/arch/arm/src/xmc4/chip/xmc4_ethernet.h b/arch/arm/src/xmc4/chip/xmc4_ethernet.h index 26291fa45c..22c163b661 100644 --- a/arch/arm/src/xmc4/chip/xmc4_ethernet.h +++ b/arch/arm/src/xmc4/chip/xmc4_ethernet.h @@ -98,10 +98,10 @@ #define XMC4_ETH_MMC_TRANSMIT_INTERRUPT_OFFSET 0x0108 /* MMC Transmit Interrupt Register */ #define XMC4_ETH_MMC_RECEIVE_INTERRUPT_MASK_OFFSET 0x010c /* MMC Reveive Interrupt Mask Register */ #define XMC4_ETH_MMC_TRANSMIT_INTERRUPT_MASK_OFFSET 0x0110 /* MMC Transmit Interrupt Mask Register */ -#define XMC4_ETH_TX_OCTET_COUNT_OFFSET 0x0114 /* Transmit Octet Count for Good and Bad Frames Register */ -#define XMC4_ETH_TX_FRAME_COUNT_OFFSET 0x0118 /* Transmit Frame Count for Goodand Bad Frames Register */ -#define XMC4_ETH_TX_BROADCAST_FRAMES_OFFSET 0x011c /* Transmit Frame Count for Good Broadcast Frames */ -#define XMC4_ETH_TX_MULTICAST_FRAMES_OFFSET 0x0120 /* Transmit Frame Count for Good Multicast Frames */ +#define XMC4_ETH_TX_OCTET_OODBAD_COUNT_GOFFSET 0x0114 /* Transmit Octet Count for Good and Bad Frames Register */ +#define XMC4_ETH_TX_FRAME_GOODBAD_COUNT_OFFSET 0x0118 /* Transmit Frame Count for Good and Bad Frames Register */ +#define XMC4_ETH_TX_BROADCAST_GOOD_FRAMES_OFFSET 0x011c /* Transmit Frame Count for Good Broadcast Frames */ +#define XMC4_ETH_TX_MULTICAST_GOOD_FRAMES_OFFSET 0x0120 /* Transmit Frame Count for Good Multicast Frames */ #define XMC4_ETH_TX_64OCTETS_FRAMES_OFFSET 0x0124 /* Transmit Octet Count for Good and Bad 64 Byte Frames */ #define XMC4_ETH_TX_65TO127OCTETS_FRAMES_OFFSET 0x0128 /* Transmit Octet Count for Good and Bad 65 to 127 Bytes Frames */ #define XMC4_ETH_TX_128TO255OCTETS_FRAMES_OFFSET 0x012c /* Transmit Octet Count for Good and Bad 128 to 255 Bytes Frames */ @@ -109,8 +109,8 @@ #define XMC4_ETH_TX_512TO1023OCTETS_FRAMES_OFFSET 0x0134 /* Transmit Octet Count for Good and Bad 512 to 1023 Bytes Frames */ #define XMC4_ETH_TX_1024TOMAXOCTETS_FRAMES_OFFSET 0x0138 /* Transmit Octet Count for Good and Bad 1024 to Maxsize Bytes Frames */ #define XMC4_ETH_TX_UNICAST_FRAMES_OFFSET 0x013c /* Transmit Frame Count for Good and Bad Unicast Frames */ -#define XMC4_ETH_TX_MULTICAST_FRAMES_OFFSET 0x0140 /* Transmit Frame Count for Good and Bad Multicast Frames */ -#define XMC4_ETH_TX_BROADCAST_FRAMES_OFFSET 0x0144 /* Transmit Frame Count for Good and Bad Broadcast Frames */ +#define XMC4_ETH_TX_MULTICAST_GOODBAD_FRAMES_OFFSET 0x0140 /* Transmit Frame Count for Good and Bad Multicast Frames */ +#define XMC4_ETH_TX_BROADCAST_GOODBAD_FRAMES_OFFSET 0x0144 /* Transmit Frame Count for Good and Bad Broadcast Frames */ #define XMC4_ETH_TX_UNDERFLOW_ERROR_FRAMES_OFFSET 0x0148 /* Transmit Frame Count for Underflow Error Frames */ #define XMC4_ETH_TX_SINGLE_COLLISION_FRAMES_OFFSET 0x014c /* Transmit Frame Count for Frames Transmitted after Single Collision */ #define XMC4_ETH_TX_MULTIPLE_COLLISION_FRAMES_OFFSET 0x0150 /* Transmit Frame Count for Frames Transmitted after Multiple Collision */ @@ -118,16 +118,15 @@ #define XMC4_ETH_TX_LATE_COLLISION_FRAMES_OFFSET 0x0158 /* Transmit Frame Count for Late Collision Error Frames */ #define XMC4_ETH_TX_EXCESSIVE_COLLISION_FRAMES_OFFSET 0x015c /* Transmit Frame Count for Excessive Collision Error Frames */ #define XMC4_ETH_TX_CARRIER_ERROR_FRAMES_OFFSET 0x0160 /* Transmit Frame Count for Carrier Sense Error Frames */ -#define XMC4_ETH_TX_OCTET_COUNT_OFFSET 0x0164 /* Tx Octet Count Good Register */ -#define XMC4_ETH_TX_FRAME_COUNT_OFFSET 0x0168 /* Tx Frame Count Good Register */ +#define XMC4_ETH_TX_OCTET_GOOD_COUNT_OFFSET 0x0164 /* Tx Octet Count Good Register */ +#define XMC4_ETH_TX_FRAME_GOOD_COUNT_OFFSET 0x0168 /* Tx Frame Count Good Register */ #define XMC4_ETH_TX_EXCESSIVE_DEFERRAL_ERROR_OFFSET 0x016c /* Transmit Frame Count for Excessive Deferral Error Frames */ #define XMC4_ETH_TX_PAUSE_FRAMES_OFFSET 0x0170 /* Transmit Frame Count for Good PAUSE Frames */ #define XMC4_ETH_TX_VLAN_FRAMES_OFFSET 0x0174 /* Transmit Frame Count for Good VLAN Frames */ #define XMC4_ETH_TX_OSIZE_FRAMES_OFFSET 0x0178 /* Transmit Frame Count for Good Oversize Frames */ - #define XMC4_ETH_RX_FRAMES_COUNT_OFFSET 0x0180 /* Receive Frame Count for Good and Bad Frames */ -#define XMC4_ETH_RX_OCTET_COUNT_OFFSET 0x0184 /* Receive Octet Count for Good and Bad Frames */ -#define XMC4_ETH_RX_OCTET_COUNT_OFFSET 0x0188 /* Rx Octet Count Good Register */ +#define XMC4_ETH_RX_OCTET_GOODBAD_COUNT_OFFSET 0x0184 /* Receive Octet Count for Good and Bad Frames */ +#define XMC4_ETH_RX_OCTET_GOOD_COUNT_OFFSET 0x0188 /* Rx Octet Count Good Register */ #define XMC4_ETH_RX_BROADCAST_FRAMES_OFFSET 0x018c /* Receive Frame Count for Good Broadcast Frames */ #define XMC4_ETH_RX_MULTICAST_FRAMES_OFFSET 0x0190 /* Receive Frame Count for Good Multicast Frames */ #define XMC4_ETH_RX_CRC_ERROR_FRAMES_OFFSET 0x0194 /* Receive Frame Count for CRC Error Frames */ @@ -217,7 +216,435 @@ /* Register Addresses ***********************************************************************************************/ +/* MAC Configuration Registers */ + +#define XMC4_ETH_MAC_CONFIGURATION (XMC4_ETH0_BASE+XMC4_ETH_MAC_CONFIGURATION_OFFSET) +#define XMC4_ETH_MAC_FRAME_FILTER (XMC4_ETH0_BASE+XMC4_ETH_MAC_FRAME_FILTER_OFFSET) +#define XMC4_ETH_HASH_TABLE_HIGH (XMC4_ETH0_BASE+XMC4_ETH_HASH_TABLE_LOW_OFFSET) +#define XMC4_ETH_GMII_ADDRESS (XMC4_ETH0_BASE+XMC4_ETH_GMII_ADDRESS_OFFSET) +#define XMC4_ETH_GMII_DATA (XMC4_ETH0_BASE+XMC4_ETH_GMII_DATA_OFFSET) +#define XMC4_ETH_FLOW_CONTROL (XMC4_ETH0_BASE+XMC4_ETH_FLOW_CONTROL_OFFSET) +#define XMC4_ETH_VLAN_TAG (XMC4_ETH0_BASE+XMC4_ETH_VLAN_TAG_OFFSET) +#define XMC4_ETH_VERSION (XMC4_ETH0_BASE+XMC4_ETH_VERSION_OFFSET) +#define XMC4_ETH_DEBUG (XMC4_ETH0_BASE+XMC4_ETH_DEBUG_OFFSET) +#define XMC4_ETH_REMOTE_WAKE_UP_FRAME_FILTER (XMC4_ETH0_BASE+XMC4_ETH_REMOTE_WAKE_UP_FRAME_FILTER_OFFSET) +#define XMC4_ETH_PMT_CONTROL_STATUS (XMC4_ETH0_BASE+XMC4_ETH_PMT_CONTROL_STATUS_OFFSET) +#define XMC4_ETH_INTERRUPT_STATUS (XMC4_ETH0_BASE+XMC4_ETH_INTERRUPT_STATUS_OFFSET) +#define XMC4_ETH_INTERRUPT_MASK (XMC4_ETH0_BASE+XMC4_ETH_INTERRUPT_MASK_OFFSET) +#define XMC4_ETH_MAC_ADDRESS0_HIGH (XMC4_ETH0_BASE+XMC4_ETH_MAC_ADDRESS0_HIGH_OFFSET) +#define XMC4_ETH_MAC_ADDRESS0_LOW (XMC4_ETH0_BASE+XMC4_ETH_MAC_ADDRESS0_LOW_OFFSET) +#define XMC4_ETH_MAC_ADDRESS1_HIGH (XMC4_ETH0_BASE+XMC4_ETH_MAC_ADDRESS1_HIGH_OFFSET) +#define XMC4_ETH_MAC_ADDRESS1_LOW (XMC4_ETH0_BASE+XMC4_ETH_MAC_ADDRESS1_LOW_OFFSET) +#define XMC4_ETH_MAC_ADDRESS2_HIGH (XMC4_ETH0_BASE+XMC4_ETH_MAC_ADDRESS2_HIGH_OFFSET) +#define XMC4_ETH_MAC_ADDRESS2_LOW (XMC4_ETH0_BASE+XMC4_ETH_MAC_ADDRESS2_LOW_OFFSET) +#define XMC4_ETH_MAC_ADDRESS3_HIGH (XMC4_ETH0_BASE+XMC4_ETH_MAC_ADDRESS3_HIGH_OFFSET) +#define XMC4_ETH_MAC_ADDRESS3_LOW (XMC4_ETH0_BASE+XMC4_ETH_MAC_ADDRESS3_LOW_OFFSET) + +/* MAC Management Counters */ + +#define XMC4_ETH_MMC_CONTROL (XMC4_ETH0_BASE+XMC4_ETH_MMC_CONTROL_OFFSET) +#define XMC4_ETH_MMC_RECEIVE_INTERRUPT (XMC4_ETH0_BASE+XMC4_ETH_MMC_RECEIVE_INTERRUPT_OFFSET) +#define XMC4_ETH_MMC_TRANSMIT_INTERRUPT (XMC4_ETH0_BASE+XMC4_ETH_MMC_TRANSMIT_INTERRUPT_OFFSET) +#define XMC4_ETH_MMC_RECEIVE_INTERRUPT_MASK (XMC4_ETH0_BASE+XMC4_ETH_MMC_RECEIVE_INTERRUPT_MASK_OFFSET) +#define XMC4_ETH_MMC_TRANSMIT_INTERRUPT_MASK (XMC4_ETH0_BASE+XMC4_ETH_MMC_TRANSMIT_INTERRUPT_MASK_OFFSET) +#define XMC4_ETH_TX_OCTET_GOODBAD_COUNT (XMC4_ETH0_BASE+XMC4_ETH_TX_OCTET_GOODBAD_COUNT_OFFSET) +#define XMC4_ETH_TX_FRAME_GOODBAD_COUNT (XMC4_ETH0_BASE+XMC4_ETH_TX_FRAME_GOODBAD_COUNT_OFFSET) +#define XMC4_ETH_TX_BROADCAST_GOOD_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_TX_BROADCAST_GOOD_FRAMES_OFFSET) +#define XMC4_ETH_TX_MULTICAST_GOOD_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_TX_MULTICAST_GOOD_FRAMES_OFFSET) +#define XMC4_ETH_TX_64OCTETS_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_TX_64OCTETS_FRAMES_OFFSET) +#define XMC4_ETH_TX_65TO127OCTETS_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_TX_65TO127OCTETS_FRAMES_OFFSET) +#define XMC4_ETH_TX_128TO255OCTETS_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_TX_128TO255OCTETS_FRAMES_OFFSET) +#define XMC4_ETH_TX_256TO511OCTETS_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_TX_256TO511OCTETS_FRAMES_OFFSET) +#define XMC4_ETH_TX_512TO1023OCTETS_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_TX_512TO1023OCTETS_FRAMES_OFFSET) +#define XMC4_ETH_TX_1024TOMAXOCTETS_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_TX_1024TOMAXOCTETS_FRAMES_OFFSET) +#define XMC4_ETH_TX_UNICAST_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_TX_UNICAST_FRAMES_OFFSET) +#define XMC4_ETH_TX_MULTICAST_GOODBAD_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_TX_MULTICAST_GOODBAD_FRAMES_OFFSET) +#define XMC4_ETH_TX_BROADCAST_GOODBAD_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_TX_BROADCAST_GOODBAD_FRAMES_OFFSET) +#define XMC4_ETH_TX_UNDERFLOW_ERROR_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_TX_UNDERFLOW_ERROR_FRAMES_OFFSET) +#define XMC4_ETH_TX_SINGLE_COLLISION_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_TX_SINGLE_COLLISION_FRAMES_OFFSET) +#define XMC4_ETH_TX_MULTIPLE_COLLISION_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_TX_MULTIPLE_COLLISION_FRAMES_OFFSET) +#define XMC4_ETH_TX_DEFERRED_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_TX_DEFERRED_FRAMES_OFFSET) +#define XMC4_ETH_TX_LATE_COLLISION_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_TX_LATE_COLLISION_FRAMES_OFFSET) +#define XMC4_ETH_TX_EXCESSIVE_COLLISION_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_TX_EXCESSIVE_COLLISION_FRAMES_OFFSET) +#define XMC4_ETH_TX_CARRIER_ERROR_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_TX_CARRIER_ERROR_FRAMES_OFFSET) +#define XMC4_ETH_TX_OCTET_GOOD_COUNT (XMC4_ETH0_BASE+XMC4_ETH_TX_OCTET_GOOD_COUNT_OFFSET) +#define XMC4_ETH_TX_FRAME_GOOD_COUNT (XMC4_ETH0_BASE+XMC4_ETH_TX_FRAME_GOOD_COUNT_OFFSET) +#define XMC4_ETH_TX_EXCESSIVE_DEFERRAL_ERROR (XMC4_ETH0_BASE+XMC4_ETH_TX_EXCESSIVE_DEFERRAL_ERROR_OFFSET) +#define XMC4_ETH_TX_PAUSE_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_TX_PAUSE_FRAMES_OFFSET) +#define XMC4_ETH_TX_VLAN_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_TX_VLAN_FRAMES_OFFSET) +#define XMC4_ETH_TX_OSIZE_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_TX_OSIZE_FRAMES_OFFSET) +#define XMC4_ETH_RX_FRAMES_COUNT (XMC4_ETH0_BASE+XMC4_ETH_RX_FRAMES_COUNT_OFFSET) +#define XMC4_ETH_RX_OCTET_GOODBAD_COUNT (XMC4_ETH0_BASE+XMC4_ETH_RX_OCTET_GOODBAD_COUNT_OFFSET) +#define XMC4_ETH_RX_OCTET_GOOD_COUNT (XMC4_ETH0_BASE+XMC4_ETH_RX_OCTET_GOOD_COUNT_OFFSET) +#define XMC4_ETH_RX_BROADCAST_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RX_BROADCAST_FRAMES_OFFSET) +#define XMC4_ETH_RX_MULTICAST_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RX_MULTICAST_FRAMES_OFFSET) +#define XMC4_ETH_RX_CRC_ERROR_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RX_CRC_ERROR_FRAMES_OFFSET) +#define XMC4_ETH_RX_ALIGNMENT_ERROR (XMC4_ETH0_BASE+XMC4_ETH_RX_ALIGNMENT_ERROR_FRAMES_OFFSET) +#define XMC4_ETH_RX_RUNT_ERROR_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RX_RUNT_ERROR_FRAMES_OFFSET) +#define XMC4_ETH_RX_JABBER_ERROR_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RX_JABBER_ERROR_FRAMES_OFFSET) +#define XMC4_ETH_RX_UNDERSIZE_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RX_UNDERSIZE_FRAMES_OFFSET) +#define XMC4_ETH_RX_OVERSIZE_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RX_OVERSIZE_FRAMES_OFFSET) +#define XMC4_ETH_RX_64OCTETS_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RX_64OCTETS_FRAMES_OFFSET) +#define XMC4_ETH_RX_65TO127OCTETS_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RX_65TO127OCTETS_FRAMES_OFFSET) +#define XMC4_ETH_RX_128TO255OCTETS_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RX_128TO255OCTETS_FRAMES_OFFSET) +#define XMC4_ETH_RX_256TO511OCTETS_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RX_256TO511OCTETS_FRAMES_OFFSET) +#define XMC4_ETH_RX_512TO1023OCTETS_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RX_512TO1023OCTETS_FRAMES_OFFSET) +#define XMC4_ETH_RX_1024TOMAXOCTETS_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RX_1024TOMAXOCTETS_FRAMES_OFFSET) +#define XMC4_ETH_RX_UNICAST_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RX_UNICAST_FRAMES_OFFSET) +#define XMC4_ETH_RX_LENGTH_ERROR (XMC4_ETH0_BASE+XMC4_ETH_RX_LENGTH_ERROR_FRAMES_OFFSET) +#define XMC4_ETH_RX_OUT_OF_RANGE_TYPE_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RX_OUT_OF_RANGE_TYPE_FRAMES_OFFSET) +#define XMC4_ETH_RX_PAUSE_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RX_PAUSE_FRAMES_OFFSET) +#define XMC4_ETH_RX_FIFO_OVERFLOW_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RX_FIFO_OVERFLOW_FRAMES_OFFSET) +#define XMC4_ETH_RX_VLAN_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RX_VLAN_FRAMES_OFFSET) +#define XMC4_ETH_RX_WATCHDOG_ERROR_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RX_WATCHDOG_ERROR_FRAMES_OFFSET) +#define XMC4_ETH_RX_RECEIVE_ERROR_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RX_RECEIVE_ERROR_FRAMES_OFFSET) +#define XMC4_ETH_RX_CONTROL_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RX_CONTROL_FRAMES_OFFSET) +#define XMC4_ETH_MMC_IPC_RECEIVE_INTERRUPT_MASK (XMC4_ETH0_BASE+XMC4_ETH_MMC_IPC_RECEIVE_INTERRUPT_MASK_OFFSET) +#define XMC4_ETH_MMC_IPC_RECEIVE_INTERRUPT (XMC4_ETH0_BASE+XMC4_ETH_MMC_IPC_RECEIVE_INTERRUPT_OFFSET) +#define XMC4_ETH_RXIPV4_GOOD_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RXIPV4_GOOD_FRAMES_OFFSET) +#define XMC4_ETH_RXIPV4_HEADER_ERROR_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RXIPV4_HEADER_ERROR_FRAMES_OFFSET) +#define XMC4_ETH_RXIPV4_NO_PAYLOAD_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RXIPV4_NO_PAYLOAD_FRAMES_OFFSET) +#define XMC4_ETH_RXIPV4_FRAGMENTED_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RXIPV4_FRAGMENTED_FRAMES_OFFSET) +#define XMC4_ETH_RXIPV4_UDP_CHECKSUM_DISABLED_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RXIPV4_UDP_CHECKSUM_DISABLED_FRAMES_OFFSET) +#define XMC4_ETH_RXIPV6_GOOD_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RXIPV6_GOOD_FRAMES_OFFSET) +#define XMC4_ETH_RXIPV6_HEADER_ERROR_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RXIPV6_HEADER_ERROR_FRAMES_OFFSET) +#define XMC4_ETH_RXIPV6_NO_PAYLOAD_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RXIPV6_NO_PAYLOAD_FRAMES_OFFSET) +#define XMC4_ETH_RXUDP_GOOD_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RXUDP_GOOD_FRAMES_OFFSET) +#define XMC4_ETH_RXUDP_ERROR_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RXUDP_ERROR_FRAMES_OFFSET) +#define XMC4_ETH_RXTCP_GOOD_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RXTCP_GOOD_FRAMES_OFFSET) +#define XMC4_ETH_RXTCP_ERROR_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RXTCP_ERROR_FRAMES_OFFSET) +#define XMC4_ETH_RXICMP_GOOD_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RXICMP_GOOD_FRAMES_OFFSET) +#define XMC4_ETH_RXICMP_ERROR_FRAMES (XMC4_ETH0_BASE+XMC4_ETH_RXICMP_ERROR_FRAMES_OFFSET) +#define XMC4_ETH_RXIPV4_GOOD_OCTETS (XMC4_ETH0_BASE+XMC4_ETH_RXIPV4_GOOD_OCTETS_OFFSET) +#define XMC4_ETH_RXIPV4_HEADER_ERROR_OCTETS (XMC4_ETH0_BASE+XMC4_ETH_RXIPV4_HEADER_ERROR_OCTETS_OFFSET) +#define XMC4_ETH_RXIPV4_NO_PAYLOAD_OCTETS (XMC4_ETH0_BASE+XMC4_ETH_RXIPV4_NO_PAYLOAD_OCTETS_OFFSET) +#define XMC4_ETH_RXIPV4_FRAGMENTED_OCTETS (XMC4_ETH0_BASE+XMC4_ETH_RXIPV4_FRAGMENTED_OCTETS_OFFSET) +#define XMC4_ETH_RXIPV4_UDP_CHECKSUM_DISABLE_OCTETS (XMC4_ETH0_BASE+XMC4_ETH_RXIPV4_UDP_CHECKSUM_DISABLE_OCTETS_OFFSET) +#define XMC4_ETH_RXIPV6_GOOD_OCTETS (XMC4_ETH0_BASE+XMC4_ETH_RXIPV6_GOOD_OCTETS_OFFSET) +#define XMC4_ETH_RXIPV6_HEADER_ERROR_OCTETS (XMC4_ETH0_BASE+XMC4_ETH_RXIPV6_HEADER_ERROR_OCTETS_OFFSET) +#define XMC4_ETH_RXIPV6_NO_PAYLOAD_OCTETS (XMC4_ETH0_BASE+XMC4_ETH_RXIPV6_NO_PAYLOAD_OCTETS_OFFSET) +#define XMC4_ETH_RXUDP_GOOD_OCTETS (XMC4_ETH0_BASE+XMC4_ETH_RXUDP_GOOD_OCTETS_OFFSET) +#define XMC4_ETH_RXUDP_ERROR_OCTETS (XMC4_ETH0_BASE+XMC4_ETH_RXUDP_ERROR_OCTETS_OFFSET) +#define XMC4_ETH_RXTCP_GOOD_OCTETS (XMC4_ETH0_BASE+XMC4_ETH_RXTCP_GOOD_OCTETS_OFFSET) +#define XMC4_ETH_RXTCP_ERROR_OCTETS (XMC4_ETH0_BASE+XMC4_ETH_RXTCP_ERROR_OCTETS_OFFSET) +#define XMC4_ETH_RXICMP_GOOD_OCTETS (XMC4_ETH0_BASE+XMC4_ETH_RXICMP_GOOD_OCTETS_OFFSET) +#define XMC4_ETH_RXICMP_ERROR_OCTETS (XMC4_ETH0_BASE+XMC4_ETH_RXICMP_ERROR_OCTETS_OFFSET) + +/* System Time Registers */ + +#define XMC4_ETH_TIMESTAMP_CONTROL (XMC4_ETH0_BASE+XMC4_ETH_TIMESTAMP_CONTROL_OFFSET) +#define XMC4_ETH_SUB_SECOND_INCREMENT (XMC4_ETH0_BASE+XMC4_ETH_SUB_SECOND_INCREMENT_OFFSET) +#define XMC4_ETH_SYSTEM_TIME_SECONDS (XMC4_ETH0_BASE+XMC4_ETH_SYSTEM_TIME_SECONDS_OFFSET) +#define XMC4_ETH_SYSTEM_TIME_NANOSECONDS (XMC4_ETH0_BASE+XMC4_ETH_SYSTEM_TIME_NANOSECONDS_OFFSET) +#define XMC4_ETH_SYSTEM_TIME_SECONDS_UPDATE (XMC4_ETH0_BASE+XMC4_ETH_SYSTEM_TIME_SECONDS_UPDATE_OFFSET) +#define XMC4_ETH_SYSTEM_TIME_NANOSECONDS_UPDATE (XMC4_ETH0_BASE+XMC4_ETH_SYSTEM_TIME_NANOSECONDS_UPDATE_OFFSET) +#define XMC4_ETH_TIMESTAMP_ADDEND (XMC4_ETH0_BASE+XMC4_ETH_TIMESTAMP_ADDEND_OFFSET) +#define XMC4_ETH_TARGET_TIME_SECONDS (XMC4_ETH0_BASE+XMC4_ETH_TARGET_TIME_SECONDS_OFFSET) +#define XMC4_ETH_TARGET_TIME_NANOSECONDS (XMC4_ETH0_BASE+XMC4_ETH_TARGET_TIME_NANOSECONDS_OFFSET) +#define XMC4_ETH_SYSTEM_TIME_HIGHER_WORD_SECONDS (XMC4_ETH0_BASE+XMC4_ETH_SYSTEM_TIME_HIGHER_WORD_SECONDS_OFFSET) +#define XMC4_ETH_TIMESTAMP_STATUS (XMC4_ETH0_BASE+XMC4_ETH_TIMESTAMP_STATUS_OFFSET) + +/* DMA Registers*/ + +#define XMC4_ETH_BUS_MODE (XMC4_ETH0_BASE+XMC4_ETH_BUS_MODE_OFFSET) +#define XMC4_ETH_TRANSMIT_POLL_DEMAND (XMC4_ETH0_BASE+XMC4_ETH_TRANSMIT_POLL_DEMAND_OFFSET) +#define XMC4_ETH_RECEIVE_POLL_DEMAND (XMC4_ETH0_BASE+XMC4_ETH_RECEIVE_POLL_DEMAND_OFFSET) +#define XMC4_ETH_RECEIVE_DESCRIPTOR_LIST_ADDRESS (XMC4_ETH0_BASE+XMC4_ETH_RECEIVE_DESCRIPTOR_LIST_ADDRESS_OFFSET) +#define XMC4_ETH_TRANSMIT_DESCRIPTOR_LIST_ADDRESS (XMC4_ETH0_BASE+XMC4_ETH_TRANSMIT_DESCRIPTOR_LIST_ADDRESS_OFFSET) +#define XMC4_ETH_STATUS (XMC4_ETH0_BASE+XMC4_ETH_STATUS_OFFSET) +#define XMC4_ETH_OPERATION_MODE (XMC4_ETH0_BASE+XMC4_ETH_OPERATION_MODE_OFFSET) +#define XMC4_ETH_INTERRUPT_ENABLE (XMC4_ETH0_BASE+XMC4_ETH_INTERRUPT_ENABLE_OFFSET) +#define XMC4_ETH_MISSED_FRAME_BUFFER_OVERFLOW_COUNTER (XMC4_ETH0_BASE+XMC4_ETH_MISSED_FRAME_BUFFER_OVERFLOW_COUNTER_OFFSET) +#define XMC4_ETH_RECEIVE_INTERRUPT_WATCHDOG_TIMER (XMC4_ETH0_BASE+XMC4_ETH_RECEIVE_INTERRUPT_WATCHDOG_TIMER_OFFSET) +#define XMC4_ETH_AHB_STATUS (XMC4_ETH0_BASE+XMC4_ETH_AHB_STATUS_OFFSET) +#define XMC4_ETH_CURRENT_HOST_TRANSMIT_DESCRIPTOR (XMC4_ETH0_BASE+XMC4_ETH_CURRENT_HOST_TRANSMIT_DESCRIPTOR_OFFSET) +#define XMC4_ETH_CURRENT_HOST_RECEIVE_DESCRIPTOR (XMC4_ETH0_BASE+XMC4_ETH_CURRENT_HOST_RECEIVE_DESCRIPTOR_OFFSET) +#define XMC4_ETH_CURRENT_HOST_TRANSMIT_BUFFER_ADDRESS (XMC4_ETH0_BASE+XMC4_ETH_CURRENT_HOST_TRANSMIT_BUFFER_ADDRESS_OFFSET) +#define XMC4_ETH_CURRENT_HOST_RECEIVE_BUFFER_ADDRESS (XMC4_ETH0_BASE+XMC4_ETH_CURRENT_HOST_RECEIVE_BUFFER_ADDRESS_OFFSET) +#define XMC4_ETH_HW_FEATURE (XMC4_ETH0_BASE+XMC4_ETH_HW_FEATURE_OFFSET) + /* Register Bit-Field Definitions ***********************************************************************************/ +/* MAC Configuration Registers */ + +/* MAC Configuration Register */ +#define ETH_MAC_CONFIGURATION_ +/* MAC Frame Filter */ +#define ETH_MAC_FRAME_FILTER_ +/* Hash Table High Register */ +#define ETH_HASH_TABLE_LOW_ +/* MII Address Register */ +#define ETH_GMII_ADDRESS_ +/* MII Data Register */ +#define ETH_GMII_DATA_ +/* Flow Control Register */ +#define ETH_FLOW_CONTROL_ +/* VLAN Tag Register */ +#define ETH_VLAN_TAG_ +/* Version Register */ +#define ETH_VERSION_ +/* Debug Register */ +#define ETH_DEBUG_ +/* Remote Wake Up Frame Filter Register */ +#define ETH_REMOTE_WAKE_UP_FRAME_FILTER_ +/* PMT Control and Status Register */ +#define ETH_PMT_CONTROL_STATUS_ +/* Interrupt Register */ +#define ETH_INTERRUPT_STATUS_ +/* Interrupt Mask Register */ +#define ETH_INTERRUPT_MASK_ +/* MAC Address0 High Register */ +#define ETH_MAC_ADDRESS0_HIGH_ +/* MAC Address0 Low Register */ +#define ETH_MAC_ADDRESS0_LOW_ +/* MAC Address1 High Register */ +#define ETH_MAC_ADDRESS1_HIGH_ +/* MAC Address1 Low Register */ +#define ETH_MAC_ADDRESS1_LOW_ +/* MAC Address2 High Register */ +#define ETH_MAC_ADDRESS2_HIGH_ +/* MAC Address2 Low Register */ +#define ETH_MAC_ADDRESS2_LOW_ +/* MAC Address3 High Register */ +#define ETH_MAC_ADDRESS3_HIGH_ +/* MAC Address3 Low Register */ +#define ETH_MAC_ADDRESS3_LOW_ + +/* MAC Management Counters */ + +/* MMC Control Register */ +#define ETH_MMC_CONTROL_ +/* MMC Receive Interrupt Register */ +#define ETH_MMC_RECEIVE_INTERRUPT_ +/* MMC Transmit Interrupt Register */ +#define ETH_MMC_TRANSMIT_INTERRUPT_ +/* MMC Reveive Interrupt Mask Register */ +#define ETH_MMC_RECEIVE_INTERRUPT_MASK_ +/* MMC Transmit Interrupt Mask Register */ +#define ETH_MMC_TRANSMIT_INTERRUPT_MASK_ +/* Transmit Octet Count for Good and Bad Frames Register */ +#define ETH_TX_OCTET_GOODBAD_COUNT_ +/* Transmit Frame Count for Goodand Bad Frames Register */ +#define ETH_TX_FRAME_GOODBAD_COUNT_ +/* Transmit Frame Count for Good Broadcast Frames */ +#define ETH_TX_BROADCAST_GOOD_FRAMES_ +/* Transmit Frame Count for Good Multicast Frames */ +#define ETH_TX_MULTICAST_GOOD_FRAMES_ +/* Transmit Octet Count for Good and Bad 64 Byte Frames */ +#define ETH_TX_64OCTETS_FRAMES_ +/* Transmit Octet Count for Good and Bad 65 to 127 Bytes Frames */ +#define ETH_TX_65TO127OCTETS_FRAMES_ +/* Transmit Octet Count for Good and Bad 128 to 255 Bytes Frames */ +#define ETH_TX_128TO255OCTETS_FRAMES_ +/* Transmit Octet Count for Good and Bad 256 to 511 Bytes Frames */ +#define ETH_TX_256TO511OCTETS_FRAMES_ +/* Transmit Octet Count for Good and Bad 512 to 1023 Bytes Frames */ +#define ETH_TX_512TO1023OCTETS_FRAMES_ +/* Transmit Octet Count for Good and Bad 1024 to Maxsize Bytes Frames */ +#define ETH_TX_1024TOMAXOCTETS_FRAMES_ +/* Transmit Frame Count for Good and Bad Unicast Frames */ +#define ETH_TX_UNICAST_FRAMES_ +/* Transmit Frame Count for Good and Bad Multicast Frames */ +#define ETH_TX_MULTICAST_GOODBAD_FRAMES_ +/* Transmit Frame Count for Good and Bad Broadcast Frames */ +#define ETH_TX_BROADCAST_GOODBAD_FRAMES_ +/* Transmit Frame Count for Underflow Error Frames */ +#define ETH_TX_UNDERFLOW_ERROR_FRAMES_ +/* Transmit Frame Count for Frames Transmitted after Single Collision */ +#define ETH_TX_SINGLE_COLLISION_FRAMES_ +/* Transmit Frame Count for Frames Transmitted after Multiple Collision */ +#define ETH_TX_MULTIPLE_COLLISION_FRAMES_ +/* Tx Deferred Frames Register */ +#define ETH_TX_DEFERRED_FRAMES_ +/* Transmit Frame Count for Late Collision Error Frames */ +#define ETH_TX_LATE_COLLISION_FRAMES_ +/* Transmit Frame Count for Excessive Collision Error Frames */ +#define ETH_TX_EXCESSIVE_COLLISION_FRAMES_ +/* Transmit Frame Count for Carrier Sense Error Frames */ +#define ETH_TX_CARRIER_ERROR_FRAMES_ +/* Tx Octet Count Good Register */ +#define ETH_TX_OCTET_GOOD_COUNT_ +/* Tx Frame Count Good Register */ +#define ETH_TX_FRAME_GOOD_COUNT_ +/* Transmit Frame Count for Excessive Deferral Error Frames */ +#define ETH_TX_EXCESSIVE_DEFERRAL_ERROR_ +/* Transmit Frame Count for Good PAUSE Frames */ +#define ETH_TX_PAUSE_FRAMES_ +/* Transmit Frame Count for Good VLAN Frames */ +#define ETH_TX_VLAN_FRAMES_ +/* Transmit Frame Count for Good Oversize Frames */ +#define ETH_TX_OSIZE_FRAMES_ +/* Receive Frame Count for Goand Bad Frames */ +#define ETH_RX_FRAMES_COUNT_ +/* Receive Octet Count for Good and Bad Frames */ +#define ETH_RX_OCTET_GOODBAD_COUNT_ +/* Rx Octet Count Good Register */ +#define ETH_RX_OCTET_GOOD_COUNT_ +/* Receive Frame Count for Good Broadcast Frames */ +#define ETH_RX_BROADCAST_FRAMES_ +/* Receive Frame Count for Good Multicast Frames */ +#define ETH_RX_MULTICAST_FRAMES_ +/* Receive Frame Count for CRC Error Frames */ +#define ETH_RX_CRC_ERROR_FRAMES_ +/* Receive Frame Count for Alignment Error Frames */ +#define ETH_RX_ALIGNMENT_ERROR_FRAMES_ +/* Receive Frame Count for Runt Error Frames */ +#define ETH_RX_RUNT_ERROR_FRAMES_ +/* Receive Frame Count for Jabber Error Frames */ +#define ETH_RX_JABBER_ERROR_FRAMES_ +/* Receive Frame Count for Undersize Frames */ +#define ETH_RX_UNDERSIZE_FRAMES_ +/* Rx Oversize Frames Good Register */ +#define ETH_RX_OVERSIZE_FRAMES_ +/* Receive Frame Count for Good and Bad 64 Byte Frames */ +#define ETH_RX_64OCTETS_FRAMES_ +/* Receive Frame Count for Good and Bad 65 to 127 Bytes Frames */ +#define ETH_RX_65TO127OCTETS_FRAMES_ +/* Receive Frame Count for Good and Bad 128 to 255 Bytes Frames */ +#define ETH_RX_128TO255OCTETS_FRAMES_ +/* Receive Frame Count for Good and Bad 256 to 511 Bytes Frames */ +#define ETH_RX_256TO511OCTETS_FRAMES_ +/* Receive Frame Count for Good and Bad 512 to 1,023 Bytes Frames */ +#define ETH_RX_512TO1023OCTETS_FRAMES_ +/* Receive Frame Count for Good and Bad 1,024 to Maxsize Bytes Frames */ +#define ETH_RX_1024TOMAXOCTETS_FRAMES_ +/* Receive Frame Count for Good Unicast Frames */ +#define ETH_RX_UNICAST_FRAMES_ +/* Receive Frame Count for Length Error Frames */ +#define ETH_RX_LENGTH_ERROR_FRAMES_ +/* Receive Frame Count for Out of Range Frames */ +#define ETH_RX_OUT_OF_RANGE_TYPE_FRAMES_ +/* Receive Frame Count for PAUSE Frames */ +#define ETH_RX_PAUSE_FRAMES_ +/* Receive Frame Count for FIFO Overflow Frames */ +#define ETH_RX_FIFO_OVERFLOW_FRAMES_ +/* Receive Frame Count for Good and Bad VLAN Frames */ +#define ETH_RX_VLAN_FRAMES_ +/* Receive Frame Count for Watchdog Error Frames */ +#define ETH_RX_WATCHDOG_ERROR_FRAMES_ +/* Receive Frame Count for Receive Error Frames */ +#define ETH_RX_RECEIVE_ERROR_FRAMES_ +/* Receive Frame Count for Good Control Frames Frames */ +#define ETH_RX_CONTROL_FRAMES_ +/* MMC Receive Checksum Offload Interrupt Mask Register */ +#define ETH_MMC_IPC_RECEIVE_INTERRUPT_MASK_ +/* MMC Receive Checksum Offload Interrupt Register */ +#define ETH_MMC_IPC_RECEIVE_INTERRUPT_ +/* RxIPv4 Good Frames Register */ +#define ETH_RXIPV4_GOOD_FRAMES_ +/* Receive IPV4 Header Error Frame Counter Register */ +#define ETH_RXIPV4_HEADER_ERROR_FRAMES_ +/* Receive IPV4 No Payload Frame Counter Register */ +#define ETH_RXIPV4_NO_PAYLOAD_FRAMES_ +/* Receive IPV4 Fragmented Frame Counter Register */ +#define ETH_RXIPV4_FRAGMENTED_FRAMES_ +/* Receive IPV4 UDP Checksum Disabled Frame Counter Register */ +#define ETH_RXIPV4_UDP_CHECKSUM_DISABLED_FRAMES_ +/* RxIPv6 Good Frames Register */ +#define ETH_RXIPV6_GOOD_FRAMES_ +/* Receive IPV6 Header Error Frame Counter Register */ +#define ETH_RXIPV6_HEADER_ERROR_FRAMES_ +/* Receive IPV6 No Payload Frame Counter Register */ +#define ETH_RXIPV6_NO_PAYLOAD_FRAMES_ +/* RxUDP Good Frames Register */ +#define ETH_RXUDP_GOOD_FRAMES_ +/* RxUDP Error Frames Register */ +#define ETH_RXUDP_ERROR_FRAMES_ +/* RxTCP Good Frames Register */ +#define ETH_RXTCP_GOOD_FRAMES_ +/* RxTCP Error Frames Register */ +#define ETH_RXTCP_ERROR_FRAMES_ +/* RxICMP Good Frames Register */ +#define ETH_RXICMP_GOOD_FRAMES_ +/* RxICMP Error Frames Register */ +#define ETH_RXICMP_ERROR_FRAMES_ +/* RxIPv4 Good Octets Register */ +#define ETH_RXIPV4_GOOD_OCTETS_ +/* Receive IPV4 Header Error Octet Counter Register */ +#define ETH_RXIPV4_HEADER_ERROR_OCTETS_ +/* Receive IPV4 No Payload Octet Counter Register */ +#define ETH_RXIPV4_NO_PAYLOAD_OCTETS_ +/* Receive IPV4 Fragmented Octet Counter Register */ +#define ETH_RXIPV4_FRAGMENTED_OCTETS_ +/* Receive IPV4 Fragmented Octet Counter Register */ +#define ETH_RXIPV4_UDP_CHECKSUM_DISABLE_OCTETS_ +/* RxIPv6 Good Octets Register */ +#define ETH_RXIPV6_GOOD_OCTETS_ +/* Receive IPV6 Header Error Octet Counter Register */ +#define ETH_RXIPV6_HEADER_ERROR_OCTETS_ +/* Receive IPV6 No Payload Octet Counter Register */ +#define ETH_RXIPV6_NO_PAYLOAD_OCTETS_ +/* Receive UDP Good Octets Register */ +#define ETH_RXUDP_GOOD_OCTETS_ +/* Receive UDP Error Octets Register */ +#define ETH_RXUDP_ERROR_OCTETS_ +/* Receive TCP Good Octets Register */ +#define ETH_RXTCP_GOOD_OCTETS_ +/* Receive TCP Error Octets Register */ +#define ETH_RXTCP_ERROR_OCTETS_ +/* Receive ICMP Good Octets Register */ +#define ETH_RXICMP_GOOD_OCTETS_ +/* Receive ICMP Error Octets Register */ +#define ETH_RXICMP_ERROR_OCTETS_ + +/* System Time Registers */ + +/* Timestamp Control Register */ +#define ETH_TIMESTAMP_CONTROL_ +/* Sub-Second Increment Register */ +#define ETH_SUB_SECOND_INCREMENT_ +/* System Time - Seconds Register */ +#define ETH_SYSTEM_TIME_SECONDS_ +/* System Time Nanoseconds Register */ +#define ETH_SYSTEM_TIME_NANOSECONDS_ +/* System Time - Seconds Update Register */ +#define ETH_SYSTEM_TIME_SECONDS_UPDATE_ +/* System Time Nanoseconds Update Register */ +#define ETH_SYSTEM_TIME_NANOSECONDS_UPDATE_ +/* Timestamp Addend Register */ +#define ETH_TIMESTAMP_ADDEND_ +/* Target Time Seconds Register */ +#define ETH_TARGET_TIME_SECONDS_ +/* Target Time Nanoseconds Register */ +#define ETH_TARGET_TIME_NANOSECONDS_ +/* System Time - Higher Word Seconds Register */ +#define ETH_SYSTEM_TIME_HIGHER_WORD_SECONDS_ +/* Timestamp Status Register */ +#define ETH_TIMESTAMP_STATUS_ + +/* DMA Registers*/ + +/* Bus Mode Register */ +#define ETH_BUS_MODE_ +/* Transmit Poll Demand Register */ +#define ETH_TRANSMIT_POLL_DEMAND_ +/* Receive Poll Demand Register */ +#define ETH_RECEIVE_POLL_DEMAND_ +/* Receive Descriptor Address Register */ +#define ETH_RECEIVE_DESCRIPTOR_LIST_ADDRESS_ +/* Transmit descripter Address Register */ +#define ETH_TRANSMIT_DESCRIPTOR_LIST_ADDRESS_ +/* Status Register */ +#define ETH_STATUS_ +/* Operation Mode Register */ +#define ETH_OPERATION_MODE_ +/* Interrupt Enable Register */ +#define ETH_INTERRUPT_ENABLE_ +/* Missed Frame and Buffer Overflow Counter Register */ +#define ETH_MISSED_FRAME_BUFFER_OVERFLOW_COUNTER_ +/* Receive Interrupt Watchdog Timer Register */ +#define ETH_RECEIVE_INTERRUPT_WATCHDOG_TIMER_ +/* AHB Status Register */ +#define ETH_AHB_STATUS_ +/* Current Host Transmit Descriptor Register */ +#define ETH_CURRENT_HOST_TRANSMIT_DESCRIPTOR_ +/* Current Host Receive Descriptor Register */ +#define ETH_CURRENT_HOST_RECEIVE_DESCRIPTOR_ +/* Current Host Transmit Buffer Address Register */ +#define ETH_CURRENT_HOST_TRANSMIT_BUFFER_ADDRESS_ +/* Current Host Receive Buffer Address Register */ +#define ETH_CURRENT_HOST_RECEIVE_BUFFER_ADDRESS_ +/* HW Feature Register */ +#define ETH_HW_FEATURE_ #endif /* __ARCH_ARM_SRC_XMC4_CHIP_XMC4_ETHERNET_H */ diff --git a/arch/arm/src/xmc4/xmc4_allocateheap.c b/arch/arm/src/xmc4/xmc4_allocateheap.c index cdbc8ef2d1..37ae505466 100644 --- a/arch/arm/src/xmc4/xmc4_allocateheap.c +++ b/arch/arm/src/xmc4/xmc4_allocateheap.c @@ -55,18 +55,6 @@ #include "up_internal.h" #include "xmc4_mpuinit.h" -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - /**************************************************************************** * Public Functions ****************************************************************************/ -- GitLab From ae32905fe81fe8e3e85b49a67d4d6537493f412f Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 19 Mar 2017 17:06:44 -0600 Subject: [PATCH 111/990] XMC4xxx: Simply some USIC logic, add USIC interface to disable a channel. Add USIC enable logic to UART configuration (a lot more to do there). --- arch/arm/src/xmc4/xmc4_lowputc.c | 32 ++++- arch/arm/src/xmc4/xmc4_lowputc.h | 32 ++++- arch/arm/src/xmc4/xmc4_usic.c | 193 ++++++++++++------------------- arch/arm/src/xmc4/xmc4_usic.h | 32 +++++ 4 files changed, 157 insertions(+), 132 deletions(-) diff --git a/arch/arm/src/xmc4/xmc4_lowputc.c b/arch/arm/src/xmc4/xmc4_lowputc.c index 6df364565c..305a43f657 100644 --- a/arch/arm/src/xmc4/xmc4_lowputc.c +++ b/arch/arm/src/xmc4/xmc4_lowputc.c @@ -196,17 +196,37 @@ void xmc4_uart_reset(uintptr_t uart_base) * Name: xmc4_uart_configure * * Description: - * Configure a UART as a RS-232 UART. + * Enable and configure a USIC channel as a RS-232 UART. + * + * Returned Value: + * Zero (OK) is returned on success; A negated errno value is returned to + * indicate the nature of any failure. * ****************************************************************************/ #ifdef HAVE_UART_DEVICE -void xmc4_uart_configure(uintptr_t uart_base, uint32_t baud, - uint32_t clock, unsigned int parity, - unsigned int nbits, unsigned int stop2) +int xmc4_uart_configure(enum usic_channel_e channel, uint32_t baud, + uint32_t clock, unsigned int parity, + unsigned int nbits, unsigned int stop2) { - /* Disable the transmitter and receiver throughout the reconfiguration */ -#warning Missing logic + uintptr_t base; + int ret; + + /* Get the base address of the USIC registers associated with this channel */ + + base = uintptr_t xmc4_channel_baseaddress(channel); + if (base == 0) + { + return -EINVAL; + } + + /* Enable the USIC channel */ + + ret = xmc4_enable_usic_channel(channel); + if (ret < 0) + { + return ret; + } /* Configure number of bits, stop bits and parity */ #warning Missing logic diff --git a/arch/arm/src/xmc4/xmc4_lowputc.h b/arch/arm/src/xmc4/xmc4_lowputc.h index 7287855a7b..fa9d8ce16b 100644 --- a/arch/arm/src/xmc4/xmc4_lowputc.h +++ b/arch/arm/src/xmc4/xmc4_lowputc.h @@ -41,8 +41,11 @@ ****************************************************************************/ #include + #include + #include "xmc4_config.h" +#include "xmc4_usic.h" /**************************************************************************** * Public Function Prototypes @@ -76,15 +79,36 @@ void xmc4_uart_reset(uintptr_t uart_base); * Name: xmc4_uart_configure * * Description: - * Configure a UART as a RS-232 UART. + * Enable and configure a USIC channel as a RS-232 UART. + * + * Returned Value: + * Zero (OK) is returned on success; A negated errno value is returned to + * indicate the nature of any failure. * ****************************************************************************/ #ifdef HAVE_UART_DEVICE -void xmc4_uart_configure(uintptr_t uart_base, uint32_t baud, - uint32_t clock, unsigned int parity, - unsigned int nbits, unsigned int stop2); +int xmc4_uart_configure(enum usic_channel_e channel, uint32_t baud, + uint32_t clock, unsigned int parity, + unsigned int nbits, unsigned int stop2); #endif +/**************************************************************************** + * Name: xmc4_uart_disable + * + * Description: + * Disable a USIC channel previously configured as a RS-232 UART. it will + * be necessary to again call xmc4_uart_configure() in order to use this + * UART channel again. + * + * Returned Value: + * Zero (OK) is returned on success; A negated errno value is returned to + * indicate the nature of any failure. + * + ****************************************************************************/ + +#ifdef HAVE_UART_DEVICE +#define xmc4_uart_disable(c) xmc4_disable_usic_channel(c) +#endif #endif /* __ARCH_ARM_SRC_XMC4_XMC4_LOWPUTC_H */ diff --git a/arch/arm/src/xmc4/xmc4_usic.c b/arch/arm/src/xmc4/xmc4_usic.c index f252bb1a49..1480cdb7a8 100644 --- a/arch/arm/src/xmc4/xmc4_usic.c +++ b/arch/arm/src/xmc4/xmc4_usic.c @@ -50,6 +50,31 @@ #include "chip/xmc4_scu.h" #include "xmc4_usic.h" +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* Provides mapping of USIC enumeration value to USIC channel base address */ + +static uintptr_t g_channel_baseaddress[2 * XMC4_NUSIC] = +{ + XMC4_USIC0_CH0_BASE, + XMC4_USIC0_CH1_BASE +#if XMC4_NUSIC > 1 + , + XMC4_USIC1_CH0_BASE, + XMC4_USIC1_CH1_BASE +#if XMC4_NUSIC > 2 + , + XMC4_USIC2_CH0_BASE, + XMC4_USIC2_CH1_BASE +#if XMC4_NUSIC > 3 +# error Extend table values for addition USICs +#endif +#endif +#endif +}; + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -186,6 +211,29 @@ int xmc4_disable_usic(enum usic_e usic) return OK; } +/**************************************************************************** + * Name: xmc4_channel_baseaddress + * + * Description: + * Given a USIC channel enumeration value, return the base address of the + * channel registers. + * + * Returned Value: + * The non-zero address of the channel base registers is return on success. + * Zero is returned on any failure. + * + ****************************************************************************/ + +uintptr_t xmc4_channel_baseaddress(enum usic_channel_e channel) +{ + if ((usigned int)channel < (2 * XM4C_NUSICS)) + { + return g_channel_baseaddress[channel]; + } + + return 0; +} + /**************************************************************************** * Name: xmc4_enable_usic_channel * @@ -204,75 +252,22 @@ int xmc4_enable_usic_channel(enum usic_channel_e channel) uintptr_t base; uintptr_t regaddr; uint32_t regval; + int ret; - switch (channel) - { - case USIC0_CHAN0: - /* USIC0 Channel 0 base address */ - - base = XMC4_USIC0_CH0_BASE; - - /* Enable USIC0 */ - - xmc4_enable_usic(USIC0); - break; - - case USIC0_CHAN1: - /* USIC0 Channel 1 base address */ - - base = XMC4_USIC0_CH1_BASE; - - /* Enable USIC0 */ - - xmc4_enable_usic(USIC0); - break; - -#if XMC4_NUSIC > 1 - case USIC1_CHAN0: - /* USIC1 Channel 0 base address */ + /* Get the base address of the registers for this channel */ - base = XMC4_USIC1_CH0_BASE; - - /* Enable USIC1 */ - - xmc4_enable_usic(USIC1); - break; - - case USIC1_CHAN1: - /* USIC1 Channel 1 base address */ - - base = XMC4_USIC1_CH1_BASE; - - /* Enable USIC1 */ - - xmc4_enable_usic(USIC1); - break; - -#if XMC4_NUSIC > 2 - case USIC2_CHAN0: - /* USIC2 Channel 0 base address */ - - base = XMC4_USIC2_CH0_BASE; - - /* Enable USIC2 */ - - xmc4_enable_usic(USIC2); - break; - - case USIC2_CHAN1: - /* USIC2 Channel 1 base address */ - - base = XMC4_USIC2_CH1_BASE; - - /* Enable USIC2 */ + base = xmc4_channel_baseaddress(channel); + if (base == 0) + { + return -EINVAL; + } - xmc4_enable_usic(USIC2); - break; -#endif -#endif + /* Enable the USIC module */ - default: - return -EINVAL; + xmc4_enable_usic(xmc4_channel2usic(channel)); + if (ret < 0) + { + return ret; } /* Enable USIC channel */ @@ -315,64 +310,13 @@ int xmc4_disable_usic_channel(enum usic_channel_e channel) uintptr_t other; uintptr_t regaddr; uint32_t regval; - enum usic_e usic; - - switch (channel) - { - case USIC0_CHAN0: - /* Enable USIC0 Channel 0 base address */ - - base = XMC4_USIC0_CH0_BASE; - other = XMC4_USIC0_CH1_BASE; - usic = USIC0; - break; - - case USIC0_CHAN1: - /* Enable USIC0 Channel 1 base address */ - base = XMC4_USIC0_CH1_BASE; - other = XMC4_USIC0_CH0_BASE; - usic = USIC0; - break; - -#if XMC4_NUSIC > 1 - case USIC1_CHAN0: - /* Enable USIC1 Channel 0 base address */ - - base = XMC4_USIC1_CH0_BASE; - other = XMC4_USIC1_CH1_BASE; - usic = USIC1; - break; - - case USIC1_CHAN1: - /* Enable USIC1 Channel 1 base address */ - - base = XMC4_USIC1_CH1_BASE; - other = XMC4_USIC1_CH0_BASE; - usic = USIC1; - break; - -#if XMC4_NUSIC > 2 - case USIC2_CHAN0: - /* Enable USIC2 Channel 0 base address */ - - base = XMC4_USIC2_CH0_BASE; - other = XMC4_USIC2_CH1_BASE; - usic = USIC2; - break; - - case USIC2_CHAN1: - /* Enable USIC2 Channel 1 base address */ - - base = XMC4_USIC2_CH1_BASE; - other = XMC4_USIC2_CH0_BASE; - usic = USIC2; - break; -#endif -#endif + /* Get the base address of the registers for this channel */ - default: - return -EINVAL; + base = xmc4_channel_baseaddress(channel); + if (base == 0) + { + return -EINVAL; } /* Disable this channel */ @@ -383,6 +327,11 @@ int xmc4_disable_usic_channel(enum usic_channel_e channel) regval |= USIC_KSCFG_BPMODEN; putreg32(regval, regaddr); + /* Get the base address of other channel for this USIC module */ + + other = xmc4_channel_baseaddress(channel ^ 1); + DEBUASSERT(other != 0); + /* Check if the other channel has also been disabled */ regaddr = other + XMC4_USIC_KSCFG_OFFSET; @@ -390,7 +339,7 @@ int xmc4_disable_usic_channel(enum usic_channel_e channel) { /* Yes... Disable the USIC module */ - xmc4_disable_usic(usic); + xmc4_disable_usic(xmc4_channel2usic(channel)); } return OK; diff --git a/arch/arm/src/xmc4/xmc4_usic.h b/arch/arm/src/xmc4/xmc4_usic.h index e1bf78dc07..07ab1fc2de 100644 --- a/arch/arm/src/xmc4/xmc4_usic.h +++ b/arch/arm/src/xmc4/xmc4_usic.h @@ -105,6 +105,38 @@ int xmc4_enable_usic(enum usic_e usic); int xmc4_disable_usic(enum usic_e usic); +/**************************************************************************** + * Name: xmc4_channel2usic + * + * Description: + * Given a USIC channel enumeration value, return the corresponding USIC + * enumerication value. + * + * Returned Value: + * The corresponding USIC enumeration value. + * + ****************************************************************************/ + +static inline enum usic_e xmc4_channel2usic(enum usic_channel_e channel) +{ + return (enum usic_e)((unsigned int)channel >> 1); +} + +/**************************************************************************** + * Name: xmc4_channel_baseaddress + * + * Description: + * Given a USIC channel enumeration value, return the base address of the + * channel registers. + * + * Returned Value: + * The non-zero address of the channel base registers is return on success. + * Zero is returned on any failure. + * + ****************************************************************************/ + +uintptr_t xmc4_channel_baseaddress(enum usic_channel_e channel); + /**************************************************************************** * Name: xmc4_enable_usic_channel * -- GitLab From 5df421488c77ed48bb9521b1ddeca293adbcee83 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 19 Mar 2017 18:11:38 -0600 Subject: [PATCH 112/990] XMC4xxx: Add USIC baudrate calculation. --- arch/arm/src/xmc4/xmc4_clockconfig.h | 13 +++- arch/arm/src/xmc4/xmc4_clockutils.c | 76 +++++++++++++------ arch/arm/src/xmc4/xmc4_lowputc.c | 23 +++--- arch/arm/src/xmc4/xmc4_usic.c | 109 ++++++++++++++++++++++++++- arch/arm/src/xmc4/xmc4_usic.h | 15 ++++ 5 files changed, 200 insertions(+), 36 deletions(-) diff --git a/arch/arm/src/xmc4/xmc4_clockconfig.h b/arch/arm/src/xmc4/xmc4_clockconfig.h index 6e03989cad..5001683acc 100644 --- a/arch/arm/src/xmc4/xmc4_clockconfig.h +++ b/arch/arm/src/xmc4/xmc4_clockconfig.h @@ -70,10 +70,21 @@ void xmc4_clock_configure(void); * Name: xmc4_get_coreclock * * Description: - * Return the current core clock frequency. + * Return the current core clock frequency, fCPU. * ****************************************************************************/ uint32_t xmc4_get_coreclock(void); +/**************************************************************************** + * Name: xmc4_get_periphclock + * + * Description: + * The peripheral clock is either fCPU or fCPU/2, depending on the state + * of the peripheral divider. + * + ****************************************************************************/ + +uint32_t xmc4_get_periphclock(void); + #endif /* __ARCH_ARM_SRC_XMC4_XMC4_CLOCKCONFIG_H */ diff --git a/arch/arm/src/xmc4/xmc4_clockutils.c b/arch/arm/src/xmc4/xmc4_clockutils.c index cf9649099e..4d334eaef5 100644 --- a/arch/arm/src/xmc4/xmc4_clockutils.c +++ b/arch/arm/src/xmc4/xmc4_clockutils.c @@ -101,36 +101,36 @@ uint32_t xmc4_get_coreclock(void) temp = BOARD_XTAL_FREQUENCY; } - /* Check if PLL is locked */ + /* Check if PLL is locked */ - regval = getreg32(XMC4_SCU_PLLSTAT); - if ((regval & SCU_PLLSTAT_VCOLOCK) != 0) - { - /* PLL normal mode */ + regval = getreg32(XMC4_SCU_PLLSTAT); + if ((regval & SCU_PLLSTAT_VCOLOCK) != 0) + { + /* PLL normal mode */ - regval = getreg32(XMC4_SCU_PLLCON1); - pdiv = ((regval & SCU_PLLCON1_PDIV_MASK) >> SCU_PLLCON1_PDIV_SHIFT) + 1; - ndiv = ((regval & SCU_PLLCON1_NDIV_MASK) >> SCU_PLLCON1_NDIV_SHIFT) + 1; - kdiv = ((regval & SCU_PLLCON1_K2DIV_MASK) >> SCU_PLLCON1_K2DIV_SHIFT) + 1; + regval = getreg32(XMC4_SCU_PLLCON1); + pdiv = ((regval & SCU_PLLCON1_PDIV_MASK) >> SCU_PLLCON1_PDIV_SHIFT) + 1; + ndiv = ((regval & SCU_PLLCON1_NDIV_MASK) >> SCU_PLLCON1_NDIV_SHIFT) + 1; + kdiv = ((regval & SCU_PLLCON1_K2DIV_MASK) >> SCU_PLLCON1_K2DIV_SHIFT) + 1; - temp = (temp / (pdiv * kdiv)) * ndiv; - } - else - { - /* PLL prescalar mode */ + temp = (temp / (pdiv * kdiv)) * ndiv; + } + else + { + /* PLL prescalar mode */ - regval = getreg32(XMC4_SCU_PLLCON1); - kdiv = ((regval & SCU_PLLCON1_K1DIV_MASK) >> SCU_PLLCON1_K1DIV_SHIFT) + 1; + regval = getreg32(XMC4_SCU_PLLCON1); + kdiv = ((regval & SCU_PLLCON1_K1DIV_MASK) >> SCU_PLLCON1_K1DIV_SHIFT) + 1; - temp = (temp / kdiv); + temp = (temp / kdiv); + } } - } else - { - /* fOFI is clock source for fSYS */ + { + /* fOFI is clock source for fSYS */ - temp = OFI_FREQUENCY; - } + temp = OFI_FREQUENCY; + } /* Divide by SYSDIV to get fSYS */ @@ -148,3 +148,35 @@ uint32_t xmc4_get_coreclock(void) return temp; } + +/**************************************************************************** + * Name: xmc4_get_periphclock + * + * Description: + * The peripheral clock is either fCPU or fCPU/2, depending on the state + * of the peripheral divider. + * + ****************************************************************************/ + +uint32_t xmc4_get_periphclock(void) +{ + uint32_t periphclock; + + /* Get the CPU clock frequency. Unless it is divided down, this also the + * peripheral clock frequency. + */ + + periphclock = xmc4_get_coreclock(); + + /* Get the peripheral clock divider */ + + periphclock = getreg32(XMC4_SCU_PBCLKCR); + if ((periphclock & SCU_PBCLKCR_PBDIV) != 0) + { + /* The peripheral clock is fCPU/2 */ + + periphclock <<= 1; + } + + return periphclock; +} diff --git a/arch/arm/src/xmc4/xmc4_lowputc.c b/arch/arm/src/xmc4/xmc4_lowputc.c index 305a43f657..0c7a4fdc5e 100644 --- a/arch/arm/src/xmc4/xmc4_lowputc.c +++ b/arch/arm/src/xmc4/xmc4_lowputc.c @@ -40,6 +40,7 @@ #include #include +#include #include #include @@ -50,6 +51,7 @@ #include "xmc4_config.h" #include "chip/xmc4_usic.h" #include "chip/xmc4_pinmux.h" +#include "xmc4_usic.h" #include "xmc4_lowputc.h" /**************************************************************************** @@ -60,42 +62,42 @@ #if defined(HAVE_UART_CONSOLE) # if defined(CONFIG_UART0_SERIAL_CONSOLE) -# define CONSOLE_BASE XMC4_USIC0_CH0_BASE +# define CONSOLE_CHAN USIC0_CHAN0 # define CONSOLE_FREQ BOARD_CORECLK_FREQ # define CONSOLE_BAUD CONFIG_UART0_BAUD # define CONSOLE_BITS CONFIG_UART0_BITS # define CONSOLE_2STOP CONFIG_UART0_2STOP # define CONSOLE_PARITY CONFIG_UART0_PARITY # elif defined(CONFIG_UART1_SERIAL_CONSOLE) -# define CONSOLE_BASE XMC4_USIC0_CH1_BASE +# define CONSOLE_CHAN USIC0_CHAN1 # define CONSOLE_FREQ BOARD_CORECLK_FREQ # define CONSOLE_BAUD CONFIG_UART1_BAUD # define CONSOLE_BITS CONFIG_UART1_BITS # define CONSOLE_2STOP CONFIG_UART1_2STOP # define CONSOLE_PARITY CONFIG_UART1_PARITY # elif defined(CONFIG_UART2_SERIAL_CONSOLE) -# define CONSOLE_BASE XMC4_USIC1_CH0_BASE +# define CONSOLE_CHAN USIC1_CHAN0 # define CONSOLE_FREQ BOARD_BUS_FREQ # define CONSOLE_BAUD CONFIG_UART2_BAUD # define CONSOLE_BITS CONFIG_UART2_BITS # define CONSOLE_2STOP CONFIG_UART2_2STOP # define CONSOLE_PARITY CONFIG_UART2_PARITY # elif defined(CONFIG_UART3_SERIAL_CONSOLE) -# define CONSOLE_BASE XMC4_USIC1_CH1_BASE +# define CONSOLE_CHAN USIC1_CHAN1 # define CONSOLE_FREQ BOARD_BUS_FREQ # define CONSOLE_BAUD CONFIG_UART3_BAUD # define CONSOLE_BITS CONFIG_UART3_BITS # define CONSOLE_2STOP CONFIG_UART3_2STOP # define CONSOLE_PARITY CONFIG_UART3_PARITY # elif defined(CONFIG_UART4_SERIAL_CONSOLE) -# define CONSOLE_BASE XMC4_USIC2_CH0_BASE +# define CONSOLE_CHAN USIC2_CHAN0 # define CONSOLE_FREQ BOARD_BUS_FREQ # define CONSOLE_BAUD CONFIG_UART4_BAUD # define CONSOLE_BITS CONFIG_UART4_BITS # define CONSOLE_2STOP CONFIG_UART4_2STOP # define CONSOLE_PARITY CONFIG_UART4_PARITY # elif defined(CONFIG_UART5_SERIAL_CONSOLE) -# define CONSOLE_BASE XMC4_USIC2_CH1_BASE +# define CONSOLE_CHAN USIC2_CHAN1 # define CONSOLE_FREQ BOARD_BUS_FREQ # define CONSOLE_BAUD CONFIG_UART5_BAUD # define CONSOLE_BITS CONFIG_UART5_BITS @@ -107,7 +109,7 @@ #endif /* HAVE_UART_CONSOLE */ /**************************************************************************** - * Private Data + * Private Functions ****************************************************************************/ /**************************************************************************** @@ -169,7 +171,7 @@ void xmc4_lowsetup(void) * when the serial driver is opened. */ - xmc4_uart_configure(CONSOLE_BASE, CONSOLE_BAUD, CONSOLE_FREQ, \ + xmc4_uart_configure(CONSOLE_CHAN, CONSOLE_BAUD, CONSOLE_FREQ, \ CONSOLE_PARITY, CONSOLE_BITS, CONSOLE_2STOP); #endif /* HAVE_UART_DEVICE */ } @@ -210,11 +212,12 @@ int xmc4_uart_configure(enum usic_channel_e channel, uint32_t baud, unsigned int nbits, unsigned int stop2) { uintptr_t base; + uint32_t oversampling; int ret; /* Get the base address of the USIC registers associated with this channel */ - base = uintptr_t xmc4_channel_baseaddress(channel); + base = xmc4_channel_baseaddress(channel); if (base == 0) { return -EINVAL; @@ -228,6 +231,8 @@ int xmc4_uart_configure(enum usic_channel_e channel, uint32_t baud, return ret; } + ret = xmc4_uisc_baudrate(channel, baud, oversampling); + /* Configure number of bits, stop bits and parity */ #warning Missing logic diff --git a/arch/arm/src/xmc4/xmc4_usic.c b/arch/arm/src/xmc4/xmc4_usic.c index 1480cdb7a8..2634764240 100644 --- a/arch/arm/src/xmc4/xmc4_usic.c +++ b/arch/arm/src/xmc4/xmc4_usic.c @@ -31,6 +31,20 @@ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * + * May include some logic from sample code provided by Infineon: + * + * Copyright (C) 2011-2015 Infineon Technologies AG. All rights reserved. + * + * Infineon Technologies AG (Infineon) is supplying this software for use with + * Infineon's microcontrollers. This file can be freely distributed within + * development tools that are supporting such microcontrollers. + * + * THIS SOFTWARE IS PROVIDED AS IS. NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * INFINEON SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, + * OR CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * ****************************************************************************/ /**************************************************************************** @@ -42,12 +56,14 @@ #include #include #include +#include #include #include "up_arch.h" #include "chip/xmc4_usic.h" #include "chip/xmc4_scu.h" +#include "xmc4_clockconfig.h" #include "xmc4_usic.h" /**************************************************************************** @@ -226,7 +242,7 @@ int xmc4_disable_usic(enum usic_e usic) uintptr_t xmc4_channel_baseaddress(enum usic_channel_e channel) { - if ((usigned int)channel < (2 * XM4C_NUSICS)) + if ((unsigned int)channel < (2 * XMC4_NUSIC)) { return g_channel_baseaddress[channel]; } @@ -264,7 +280,7 @@ int xmc4_enable_usic_channel(enum usic_channel_e channel) /* Enable the USIC module */ - xmc4_enable_usic(xmc4_channel2usic(channel)); + ret = xmc4_enable_usic(xmc4_channel2usic(channel)); if (ret < 0) { return ret; @@ -330,7 +346,7 @@ int xmc4_disable_usic_channel(enum usic_channel_e channel) /* Get the base address of other channel for this USIC module */ other = xmc4_channel_baseaddress(channel ^ 1); - DEBUASSERT(other != 0); + DEBUGASSERT(other != 0); /* Check if the other channel has also been disabled */ @@ -343,4 +359,89 @@ int xmc4_disable_usic_channel(enum usic_channel_e channel) } return OK; -} \ No newline at end of file +} + +/**************************************************************************** + * Name: xmc4_uisc_baudrate + * + * Description: + * Set the USIC baudrate for the USIC channel + * + * Returned Value: + * Zero (OK) is returned on success; A negated errno value is returned to + * indicate the nature of any failure. + * + ****************************************************************************/ + +int xmc4_uisc_baudrate(enum usic_channel_e channel, uint32_t baud, + uint32_t oversampling) +{ + uintptr_t base; + uint32_t periphclock; + uint32_t clkdiv; + uint32_t clkdiv_min; + uint32_t pdiv; + uint32_t pdiv_int; + uint32_t pdiv_int_min; + uint32_t pdiv_frac; + uint32_t pdiv_frac_min; + uint32_t regval; + int ret; + + /* Get the base address of the registers for this channel */ + + base = xmc4_channel_baseaddress(channel); + if (base == 0) + { + return -EINVAL; + } + + /* The baud and peripheral clock are divided by 100 to be able to use only + * 32-bit arithmetic. + */ + + if (baud >= 100 && oversampling != 0) + { + periphclock = xmc4_get_periphclock() / 100; + baud = baud / 100; + + clkdiv_min = 1; + pdiv_int_min = 1; + pdiv_frac_min = 0x3ff; + + for (clkdiv = 1023; clkdiv > 0; --clkdiv) + { + pdiv = ((periphclock * clkdiv) / (baud * oversampling)); + pdiv_int = pdiv >> 10; + pdiv_frac = pdiv & 0x3ff; + + if (pdiv_int < 1024 && pdiv_frac < pdiv_frac_min) + { + pdiv_frac_min = pdiv_frac; + pdiv_int_min = pdiv_int; + clkdiv_min = clkdiv; + } + } + + /* Select and setup the fractional divider */ + + regval = USIC_FDR_DM_FRACTIONAL | (clkdiv_min << USIC_FDR_STEP_SHIFT); + putreg32(regval, base + XMC4_USIC_FDR_OFFSET); + + /* Setup and enable the baud rate generator */ + + regval = getreg32(base + XMC4_USIC_BRG_OFFSET); + regval &= ~(USIC_BRG_DCTQ_MASK | USIC_BRG_PDIV_MASK | USIC_BRG_PCTQ_MASK | USIC_BRG_PPPEN); + regval |= (USIC_BRG_DCTQ(oversampling - 1) | USIC_BRG_PDIV(pdiv_int_min - 1)); + putreg32(regval, base + XMC4_USIC_BRG_OFFSET); + + ret = OK; + } + else + { + ret = -ERANGE; + } + + return ret; +} + diff --git a/arch/arm/src/xmc4/xmc4_usic.h b/arch/arm/src/xmc4/xmc4_usic.h index 07ab1fc2de..5c5e78fdb9 100644 --- a/arch/arm/src/xmc4/xmc4_usic.h +++ b/arch/arm/src/xmc4/xmc4_usic.h @@ -167,4 +167,19 @@ int xmc4_enable_usic_channel(enum usic_channel_e channel); int xmc4_disable_usic_channel(enum usic_channel_e channel); +/**************************************************************************** + * Name: xmc4_uisc_baudrate + * + * Description: + * Set the USIC baudrate for the USIC channel + * + * Returned Value: + * Zero (OK) is returned on success; A negated errno value is returned to + * indicate the nature of any failure. + * + ****************************************************************************/ + +int xmc4_uisc_baudrate(enum usic_channel_e channel, uint32_t baud, + uint32_t oversampling); + #endif /* __ARCH_ARM_SRC_XMC4_XMC4_USIC_H */ -- GitLab From 7d6ee0f2220194282b910a5572b6ebd55f316330 Mon Sep 17 00:00:00 2001 From: no1wudi <757509347@qq.com> Date: Mon, 20 Mar 2017 09:50:27 +0800 Subject: [PATCH 113/990] fix a typo --- arch/arm/src/stm32/stm32_comp.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/arch/arm/src/stm32/stm32_comp.h b/arch/arm/src/stm32/stm32_comp.h index 99d45bad63..c703689d17 100644 --- a/arch/arm/src/stm32/stm32_comp.h +++ b/arch/arm/src/stm32/stm32_comp.h @@ -150,7 +150,7 @@ enum stm32_comp_hyst_e COMP_HYST_LOW, COMP_HYST_MEDIUM, COMP_HYST_HIGH -}, +}; /* Power/Speed Modes */ -- GitLab From 8a3422f837a923e1cf1247a708ab2f9382c9690f Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 20 Mar 2017 11:21:32 -0600 Subject: [PATCH 114/990] XMC4xxx: Complete lowputc logic --- arch/arm/src/xmc4/chip/xmc4_usic.h | 40 ++-- arch/arm/src/xmc4/xmc4_lowputc.c | 296 ++++++++++++++++++++------ arch/arm/src/xmc4/xmc4_lowputc.h | 32 +-- arch/arm/src/xmc4/xmc4_serial.c | 166 ++++++++------- arch/arm/src/xmc4/xmc4_usic.h | 23 +- configs/xmc4500-relax/include/board.h | 11 + 6 files changed, 384 insertions(+), 184 deletions(-) diff --git a/arch/arm/src/xmc4/chip/xmc4_usic.h b/arch/arm/src/xmc4/chip/xmc4_usic.h index 12d4bda2bc..462ac44c95 100644 --- a/arch/arm/src/xmc4/chip/xmc4_usic.h +++ b/arch/arm/src/xmc4/chip/xmc4_usic.h @@ -515,15 +515,16 @@ */ #define USIC_DXCR_DSEL_SHIFT (0) /* Bits 0-2: Data Selection for Input Signal */ -#define USIC_DXCR_DSEL_MASK (7 << USIC_DX0CR_DSEL_SHIFT) -# define USIC_DXCR_DSEL_DXA (0 << USIC_DX0CR_DSEL_SHIFT) /* Data input DXnA selected */ -# define USIC_DXCR_DSEL_DXB (1 << USIC_DX0CR_DSEL_SHIFT) /* Data input DXnB selected */ -# define USIC_DXCR_DSEL_DXC (2 << USIC_DX0CR_DSEL_SHIFT) /* Data input DXnC selected */ -# define USIC_DXCR_DSEL_DXD (3 << USIC_DX0CR_DSEL_SHIFT) /* Data input DXnD selected */ -# define USIC_DXCR_DSEL_DXE (4 << USIC_DX0CR_DSEL_SHIFT) /* Data input DXnE selected */ -# define USIC_DXCR_DSEL_DXF (5 << USIC_DX0CR_DSEL_SHIFT) /* Data input DXnF selected */ -# define USIC_DXCR_DSEL_DXG (6 << USIC_DX0CR_DSEL_SHIFT) /* Data input DXnG selected */ -# define USIC_DXCR_DSEL_ONE (7 << USIC_DX0CR_DSEL_SHIFT) /* Data input is always 1 */ +#define USIC_DXCR_DSEL_MASK (7 << USIC_DXCR_DSEL_SHIFT) +# define USIC_DXCR_DSEL_DX(m) ((uint32_t)(m) << USIC_DXCR_DSEL_SHIFT) /* Data input DXnm selected */ +# define USIC_DXCR_DSEL_DXA (0 << USIC_DXCR_DSEL_SHIFT) /* Data input DXnA selected */ +# define USIC_DXCR_DSEL_DXB (1 << USIC_DXCR_DSEL_SHIFT) /* Data input DXnB selected */ +# define USIC_DXCR_DSEL_DXC (2 << USIC_DXCR_DSEL_SHIFT) /* Data input DXnC selected */ +# define USIC_DXCR_DSEL_DXD (3 << USIC_DXCR_DSEL_SHIFT) /* Data input DXnD selected */ +# define USIC_DXCR_DSEL_DXE (4 << USIC_DXCR_DSEL_SHIFT) /* Data input DXnE selected */ +# define USIC_DXCR_DSEL_DXF (5 << USIC_DXCR_DSEL_SHIFT) /* Data input DXnF selected */ +# define USIC_DXCR_DSEL_DXG (6 << USIC_DXCR_DSEL_SHIFT) /* Data input DXnG selected */ +# define USIC_DXCR_DSEL_ONE (7 << USIC_DXCR_DSEL_SHIFT) /* Data input is always 1 */ #define USIC_DX1CR_DCEN (1 << 3) /* Bit 3: Delay Compensation Enable (DX1CR only) */ #define USIC_DXCR_INSW (1 << 4) /* Bit 4: Input Switch */ #define USIC_DXCR_DFEN (1 << 5) /* Bit 5: Digital Filter Enable */ @@ -531,17 +532,19 @@ #define USIC_DXCR_DPOL (1 << 8) /* Bit 8: Data Polarity for DXn */ #define USIC_DXCR_SFSEL (1 << 9) /* Bit 9: Sampling Frequency Selection */ #define USIC_DXCR_CM_SHIFT (10) /* Bits 10-11: Combination Mode */ -#define USIC_DXCR_CM_MASK (3 << USIC_DX0CR_CM_SHIFT) -# define USIC_DXCR_CM_DISABLE (0 << USIC_DX0CR_CM_SHIFT) /* Trigger activation disabled */ -# define USIC_DXCR_CM_RISING (1 << USIC_DX0CR_CM_SHIFT) /* Rising edge activates DXnT */ -# define USIC_DXCR_CM_FALLING (2 << USIC_DX0CR_CM_SHIFT) /* Falling edge activates DXnT */ -# define USIC_DXCR_CM_BOTH (3 << USIC_DX0CR_CM_SHIFT) /* Both edges activate DXnT */ +#define USIC_DXCR_CM_MASK (3 << USIC_DXCR_CM_SHIFT) +# define USIC_DXCR_CM_DISABLE (0 << USIC_DXCR_CM_SHIFT) /* Trigger activation disabled */ +# define USIC_DXCR_CM_RISING (1 << USIC_DXCR_CM_SHIFT) /* Rising edge activates DXnT */ +# define USIC_DXCR_CM_FALLING (2 << USIC_DXCR_CM_SHIFT) /* Falling edge activates DXnT */ +# define USIC_DXCR_CM_BOTH (3 << USIC_DXCR_CM_SHIFT) /* Both edges activate DXnT */ #define USIC_DXCR_DXS (1 << 15) /* Bit 15: Synchronized Data Value */ /* Shift Control Register */ #define USIC_SCTR_SDIR (1 << 0) /* Bit 0: Shift Direction */ #define USIC_SCTR_PDL (1 << 1) /* Bit 1: Passive Data Level */ +# define USIC_SCTR_PDL0 (0) /* 0=Passive data level is 0 */ +# define USIC_SCTR_PDL1 (1 << 1) /* 1=Passive data level is 1 */ #define USIC_SCTR_DSM_SHIFT (2) /* Bits 2-3: Data Shift Mode */ #define USIC_SCTR_DSM_MASK (3 << USIC_SCTR_DSM_SHIFT) # define USIC_SCTR_DSM_1BIT (0 << USIC_SCTR_DSM_SHIFT) /* Data is shifted one bit at a time */ @@ -555,8 +558,8 @@ #define USIC_SCTR_TRM_SHIFT (8) /* Bits 8-9: Transmission Mode */ #define USIC_SCTR_TRM_MASK (3 << USIC_SCTR_TRM_SHIFT) # define USIC_SCTR_TRM_INACTIVE (0 << USIC_SCTR_TRM_SHIFT) /* Inactive */ -# define USIC_SCTR_TRM_0LEVEL (1 << USIC_SCTR_TRM_SHIFT) /* Active at 1-level */ -# define USIC_SCTR_TRM_1LEVEL (2 << USIC_SCTR_TRM_SHIFT) /* Active if it is at 0-level */ +# define USIC_SCTR_TRM_1LEVEL (1 << USIC_SCTR_TRM_SHIFT) /* Active at 1-level */ +# define USIC_SCTR_TRM_0LEVEL (2 << USIC_SCTR_TRM_SHIFT) /* Active at 0-level */ # define USIC_SCTR_TRM_ACTIVE (3 << USIC_SCTR_TRM_SHIFT) /* Active without regard to signal level */ #define USIC_SCTR_FLE_SHIFT (16) /* Bits 16-21: Frame Length */ #define USIC_SCTR_FLE_MASK (0x3f << USIC_SCTR_FLE_SHIFT) @@ -638,7 +641,8 @@ # define USIC_PCR_ASCMODE_SP(n) ((uint32_t)(n) << USIC_PCR_ASCMODE_SP_SHIFT) #define USIC_PCR_ASCMODE_PL_SHIFT (13) /* Bits 13-15: Pulse Length */ #define USIC_PCR_ASCMODE_PL_MASK (7 << USIC_PCR_ASCMODE_PL_SHIFT) - #define USIC_PCR_ASCMODE_PL(n) ((uint32_t)((n)-1) << USIC_PCR_ASCMODE_PL_SHIFT) + #define USIC_PCR_ASCMODE_PLBIT (0 << USIC_PCR_ASCMODE_PL_SHIFT) /* Pulse length = bit length */ + #define USIC_PCR_ASCMODE_PL(n) ((uint32_t)((n)-1) << USIC_PCR_ASCMODE_PL_SHIFT) /* Pulse length = n quanta */ #define USIC_PCR_ASCMODE_RSTEN (1 << 16) /* Bit 16: Receiver Status Enable */ #define USIC_PCR_ASCMODE_TSTEN (1 << 17) /* Bit 17: Transmitter Status Enable */ #define USIC_PCR_ASCMODE_MCLK (1 << 31) /* Bit 31: Master Clock Enable */ @@ -717,7 +721,7 @@ # define USIC_CCR_HPCEN_DX0_2 (3 << USIC_CCR_HPCEN_SHIFT) /* Port control enabled for DX0, DX[5:3] and DOUT[3:0] */ #define USIC_CCR_PM_SHIFT (8) /* Bits 8-9: Parity Mode */ #define USIC_CCR_PM_MASK (3 << USIC_CCR_PM_SHIFT) -# define USIC_CCR_PM_DISABLE (0 << USIC_CCR_PM_SHIFT) /* Parity generation is disabled */ +# define USIC_CCR_PM_NONE (0 << USIC_CCR_PM_SHIFT) /* Parity generation is disabled */ # define USIC_CCR_PM_EVEN (2 << USIC_CCR_PM_SHIFT) /* Even parity is selected */ # define USIC_CCR_PM_ODD (3 << USIC_CCR_PM_SHIFT) /* Odd parity is selected */ #define USIC_CCR_RSIEN (1 << 10) /* Bit 10: Receiver Start Interrupt Enable */ diff --git a/arch/arm/src/xmc4/xmc4_lowputc.c b/arch/arm/src/xmc4/xmc4_lowputc.c index 0c7a4fdc5e..b92e723e66 100644 --- a/arch/arm/src/xmc4/xmc4_lowputc.c +++ b/arch/arm/src/xmc4/xmc4_lowputc.c @@ -52,6 +52,7 @@ #include "chip/xmc4_usic.h" #include "chip/xmc4_pinmux.h" #include "xmc4_usic.h" +#include "xmc4_gpio.h" #include "xmc4_lowputc.h" /**************************************************************************** @@ -64,6 +65,7 @@ # if defined(CONFIG_UART0_SERIAL_CONSOLE) # define CONSOLE_CHAN USIC0_CHAN0 # define CONSOLE_FREQ BOARD_CORECLK_FREQ +# define CONSOLE_DX BOARD_UART0_DX # define CONSOLE_BAUD CONFIG_UART0_BAUD # define CONSOLE_BITS CONFIG_UART0_BITS # define CONSOLE_2STOP CONFIG_UART0_2STOP @@ -71,6 +73,7 @@ # elif defined(CONFIG_UART1_SERIAL_CONSOLE) # define CONSOLE_CHAN USIC0_CHAN1 # define CONSOLE_FREQ BOARD_CORECLK_FREQ +# define CONSOLE_DX BOARD_UART1_DX # define CONSOLE_BAUD CONFIG_UART1_BAUD # define CONSOLE_BITS CONFIG_UART1_BITS # define CONSOLE_2STOP CONFIG_UART1_2STOP @@ -78,6 +81,7 @@ # elif defined(CONFIG_UART2_SERIAL_CONSOLE) # define CONSOLE_CHAN USIC1_CHAN0 # define CONSOLE_FREQ BOARD_BUS_FREQ +# define CONSOLE_DX BOARD_UART2_DX # define CONSOLE_BAUD CONFIG_UART2_BAUD # define CONSOLE_BITS CONFIG_UART2_BITS # define CONSOLE_2STOP CONFIG_UART2_2STOP @@ -85,6 +89,7 @@ # elif defined(CONFIG_UART3_SERIAL_CONSOLE) # define CONSOLE_CHAN USIC1_CHAN1 # define CONSOLE_FREQ BOARD_BUS_FREQ +# define CONSOLE_DX BOARD_UART3_DX # define CONSOLE_BAUD CONFIG_UART3_BAUD # define CONSOLE_BITS CONFIG_UART3_BITS # define CONSOLE_2STOP CONFIG_UART3_2STOP @@ -92,6 +97,7 @@ # elif defined(CONFIG_UART4_SERIAL_CONSOLE) # define CONSOLE_CHAN USIC2_CHAN0 # define CONSOLE_FREQ BOARD_BUS_FREQ +# define CONSOLE_DX BOARD_UART4_DX # define CONSOLE_BAUD CONFIG_UART4_BAUD # define CONSOLE_BITS CONFIG_UART4_BITS # define CONSOLE_2STOP CONFIG_UART4_2STOP @@ -99,6 +105,7 @@ # elif defined(CONFIG_UART5_SERIAL_CONSOLE) # define CONSOLE_CHAN USIC2_CHAN1 # define CONSOLE_FREQ BOARD_BUS_FREQ +# define CONSOLE_DX BOARD_UART5_DX # define CONSOLE_BAUD CONFIG_UART5_BAUD # define CONSOLE_BITS CONFIG_UART5_BITS # define CONSOLE_2STOP CONFIG_UART5_2STOP @@ -108,10 +115,27 @@ # endif #endif /* HAVE_UART_CONSOLE */ +/* REVISIT: Oversampling is hardcoded to 16 here. Perhaps this should be in + * the config structure. + */ + +#define UART_OVERSAMPLING 16 + /**************************************************************************** - * Private Functions + * Private Data ****************************************************************************/ +#ifdef HAVE_UART_CONSOLE +static const struct uart_config_s g_console_config = +{ + .baud = CONSOLE_BAUD, + .dx = CONSOLE_DX, + .parity = CONSOLE_PARITY, + .nbits = CONSOLE_BITS, + .stop2 = CONSOLE_2STOP +}; +#endif + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -127,25 +151,26 @@ void up_lowputc(char ch) { #ifdef HAVE_UART_CONSOLE - /* Wait until the transmit data register is "empty" (TDRE). This state - * depends on the TX watermark setting and may not mean that the transmit - * buffer is truly empty. It just means that we can now add another - * character to the transmit buffer without exceeding the watermark. - * - * NOTE: UART0 has an 8-byte deep FIFO; the other UARTs have no FIFOs - * (1-deep). There appears to be no way to know when the FIFO is not - * full (other than reading the FIFO length and comparing the FIFO count). - * Hence, the FIFOs are not used in this implementation and, as a result - * TDRE indeed mean that the single output buffer is available. - * - * Performance on UART0 could be improved by enabling the FIFO and by - * redesigning all of the FIFO status logic. - */ -#warning Missing logic + uintptr_t base; + uint32_t regval; + + /* Get the base address of the USIC registers associated with this channel */ - /* Then write the character to the UART data register */ + base = xmc4_channel_baseaddress(CONSOLE_CHAN); + DEBUGASSERT(base != 0); -#warning Missing logic + /* Wait for the transmit buffer/fifo to be "not full." */ + + do + { + regval = getreg32(base + XMC4_USIC_TRBSR_OFFSET); + } + while ((regval & USIC_TRBSR_TFULL) != 0); + + /* Then write the character to the USIC IN register */ + + putreg32((uint32_t)ch, base + XMC4_USIC_IN_OFFSET); +#endif } /**************************************************************************** @@ -160,39 +185,54 @@ void up_lowputc(char ch) void xmc4_lowsetup(void) { - uint32_t regval; - - /* Enable peripheral clocking for all enabled UARTs. */ -#warning Missing logic +#ifdef HAVE_UART_DEVICE + /* Configure UART pins for the all enabled UARTs. + * + * NOTE that the board must provide the definitions in the board.h header + * file of the form like: GPIO_UARTn_RXm and GPIO_UARTn_TXm where n is + * the USIC module, 0..(XMC_NUSIC-1), and m is the USIC channel number, 0 + * or 1. + * + * In additional, the board.h must provide the definition of + * BOARD_BOARD_UARTn_DX which indicates which input pin is selected, i.e. + * one of the 0=DXA, 1=DXB, ... 6=DXG. + */ - /* Configure UART pins for the all enabled UARTs */ +#ifdef HAVE_UART0 + (void)xmc4_gpio_config(GPIO_UART0_RXD0); + (void)xmc4_gpio_config(GPIO_UART0_TXD0); +#endif +#ifdef HAVE_UART1 + (void)xmc4_gpio_config(GPIO_UART0_RXD1); + (void)xmc4_gpio_config(GPIO_UART0_TXD1); +#endif +#ifdef HAVE_UART2 + (void)xmc4_gpio_config(GPIO_UART0_RXD2); + (void)xmc4_gpio_config(GPIO_UART0_TXD2); +#endif +#ifdef HAVE_UART3 + (void)xmc4_gpio_config(GPIO_UART0_RXD3); + (void)xmc4_gpio_config(GPIO_UART0_TXD3); +#endif +#ifdef HAVE_UART4 + (void)xmc4_gpio_config(GPIO_UART0_RXD4); + (void)xmc4_gpio_config(GPIO_UART0_TXD4); +#endif +#ifdef HAVE_UART5 + (void)xmc4_gpio_config(GPIO_UART0_RXD5); + (void)xmc4_gpio_config(GPIO_UART0_TXD5); +#endif +#ifdef HAVE_UART_CONSOLE /* Configure the console (only) now. Other UARTs will be configured * when the serial driver is opened. */ - xmc4_uart_configure(CONSOLE_CHAN, CONSOLE_BAUD, CONSOLE_FREQ, \ - CONSOLE_PARITY, CONSOLE_BITS, CONSOLE_2STOP); -#endif /* HAVE_UART_DEVICE */ -} - -/**************************************************************************** - * Name: xmc4_uart_reset - * - * Description: - * Reset a UART. - * - ****************************************************************************/ - -#ifdef HAVE_UART_DEVICE -void xmc4_uart_reset(uintptr_t uart_base) -{ - uint8_t regval; + xmc4_uart_configure(CONSOLE_CHAN, &g_console_config); - /* Just disable the transmitter and receiver */ -#warning Missing logic +#endif /* HAVE_UART_CONSOLE */ +#endif /* HAVE_UART_DEVICE */ } -#endif /**************************************************************************** * Name: xmc4_uart_configure @@ -207,12 +247,11 @@ void xmc4_uart_reset(uintptr_t uart_base) ****************************************************************************/ #ifdef HAVE_UART_DEVICE -int xmc4_uart_configure(enum usic_channel_e channel, uint32_t baud, - uint32_t clock, unsigned int parity, - unsigned int nbits, unsigned int stop2) +int xmc4_uart_configure(enum usic_channel_e channel, + FAR const struct uart_config_s *config) { uintptr_t base; - uint32_t oversampling; + uint32_t regval; int ret; /* Get the base address of the USIC registers associated with this channel */ @@ -231,30 +270,159 @@ int xmc4_uart_configure(enum usic_channel_e channel, uint32_t baud, return ret; } - ret = xmc4_uisc_baudrate(channel, baud, oversampling); + /* Configure the BAUD rate. + * REVISIT: Oversample is hardcoded to 16 here. Perhaps this should be in + * the config structure. + */ + + ret = xmc4_uisc_baudrate(channel, config->baud, UART_OVERSAMPLING); + + /* Configure frame format. + * + * - Pulse length for standard UART signaling, i.e. the 0 level is + * signaled during the complete bit time + * - Enable Sample Majority Decision sample mode + */ + + regval = USIC_PCR_ASCMODE_PLBIT | USIC_PCR_ASCMODE_SMD; + + /* - Sampling point set equal to the half of the oversampling period */ + + regval |= USIC_PCR_ASCMODE_SP((UART_OVERSAMPLING >> 1) + 1); + + /* - Configure the number of stop bits */ + + if (config->stop2) + { + regval |= USIC_PCR_ASCMODE_STPB; + } + + putreg32(regval, base + XMC4_USIC_PCR_OFFSET); - /* Configure number of bits, stop bits and parity */ -#warning Missing logic + /* Configure Shift Control Register: + * + * - Set passive data level, high + * - Transmission Mode: The shift control signal is considered active if + * it is at 1-level. This is the setting to be programmed to allow + * data transfers. + * - Set word length + * - Set frame length equal to the word length + */ - /* Check for odd parity */ -#warning Missing logic + regval = USIC_SCTR_PDL0 | USIC_SCTR_TRM_1LEVEL | + USIC_SCTR_FLE(config->nbits) | USIC_SCTR_WLE(config->nbits); + putreg32(regval, base + XMC4_USIC_SCTR_OFFSET); - /* Check for even parity */ -#warning Missing logic + /* Enable transfer buffer */ - /* Check for 9-bit operation */ -#warning Missing logic + regval = USIC_TCSR_TDEN_TDIV | USIC_TCSR_TDSSM; + putreg32(regval, base + XMC4_USIC_TCSR_OFFSET); - /* Calculate baud settings (truncating) */ -#warning Missing logic + /* Clear protocol status */ + + putreg32(0xffffffff, base + XMC4_USIC_PSCR_OFFSET); + + /* Configure parity */ + + if (config->parity == 1) + { + /* Odd parrity */ + + regval = USIC_CCR_PM_ODD; + } + else if (config->parity == 2) + { + /* Even parity */ + + regval = USIC_CCR_PM_EVEN; + } + else + { + /* No parity */ + + DEBUGASSERT(config->parity == 0); + regval = USIC_CCR_PM_NONE; + } - /* Configure FIFOs */ -#warning Missing logic + putreg32(regval, base + XMC4_USIC_CCR_OFFSET); - /* Enable RX and TX FIFOs */ -#warning Missing logic + /* Set DX0CR input source path */ + + regval = getreg32(base + XMC4_USIC_DX0CR_OFFSET); + regval &= ~USIC_DXCR_DSEL_MASK; + regval |= USIC_DXCR_DSEL_DX(config->dx); + putreg32(regval, base + XMC4_USIC_DX0CR_OFFSET); + + /* Disable transmit FIFO */ + + regval = getreg32(base + XMC4_USIC_TBCTR_OFFSET); + regval &= ~USIC_TBCTR_SIZE_MASK; + putreg32(regval, base + XMC4_USIC_TBCTR_OFFSET); + + /* Configure transmit FIFO + * + * - DPTR = 16 + * - LIMIT = 1 + * - STBTEN = 0, the trigger of the standard transmit buffer event is + * based on the transition of the fill level from equal to below the + * limit, not the fact being below + * - SIZE = 16 + * - LOF = 0, A standard transmit buffer event occurs when the filling + * level equals the limit value and gets lower due to transmission of + * a data word + */ + + regval &= ~(USIC_TBCTR_DPTR_MASK | USIC_TBCTR_LIMIT_MASK | USIC_RBCTR_SRBTEN | + USIC_TBCTR_SIZE_MASK | USIC_RBCTR_LOF); + regval |= (USIC_TBCTR_DPTR(16) | USIC_TBCTR_LIMIT(1) | USIC_TBCTR_SIZE_16); + putreg32(regval, base + XMC4_USIC_TBCTR_OFFSET); + + /* Disable the receive FIFO */ + + regval = getreg32(base + XMC4_USIC_RBCTR_OFFSET); + regval &= ~USIC_RBCTR_SIZE_MASK; + putreg32(regval, base + XMC4_USIC_RBCTR_OFFSET); + + /* Configure receive FIFO. + * + * - DPTR = 0 + * - LIMIT = 15 + * - SIZE = 16 + * - LOF = 1, A standard receive buffer event occurs when the filling + * level equals the limit value and gets bigger due to the reception + * of a new data word + */ + + regval &= ~(USIC_RBCTR_DPTR_MASK | USIC_RBCTR_LIMIT_MASK | USIC_RBCTR_SIZE_MASK); + regval |= (USIC_RBCTR_DPTR(0) | USIC_RBCTR_LIMIT(15) | USIC_RBCTR_SIZE_16 | USIC_RBCTR_LOF); + putreg32(regval, base + XMC4_USIC_RBCTR_OFFSET); + + /* Start UART */ + + regval = getreg32(base + XMC4_USIC_CCR_OFFSET); + regval &= ~USIC_CCR_MODE_MASK; + regval |= USIC_CCR_MODE_ASC; + putreg32(regval, base + XMC4_USIC_CCR_OFFSET); + + /* Set service request for UART protocol events. + * + * Set channel 0 protocol events on sevice request 0 + * Set channel 1 protocol events on sevice request 1 + */ + + regval = getreg32(base + XMC4_USIC_INPR_OFFSET); + regval &= ~USIC_INPR_PINP_MASK; + + if (((unsigned int)channel & 1) != 0) + { + regval |= USIC_INPR_PINP_SR0; + } + else + { + regval |= USIC_INPR_PINP_SR1; + } - /* Now we can (re-)enable the transmitter and receiver */ -#warning Missing logic + putreg32(regval, base + XMC4_USIC_INPR_OFFSET); + return OK; } #endif diff --git a/arch/arm/src/xmc4/xmc4_lowputc.h b/arch/arm/src/xmc4/xmc4_lowputc.h index fa9d8ce16b..f8016c3d78 100644 --- a/arch/arm/src/xmc4/xmc4_lowputc.h +++ b/arch/arm/src/xmc4/xmc4_lowputc.h @@ -47,6 +47,21 @@ #include "xmc4_config.h" #include "xmc4_usic.h" +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* This structure provides the configuration of one UART channel */ + +struct uart_config_s +{ + uint32_t baud; /* Desired BAUD rate */ + uint8_t dx; /* Input pin 0=DXA, 1=DXB, ... 6=DXG */ + uint8_t parity; /* Parity selection: 0=none, 1=odd, 2=even */ + uint8_t nbits; /* Number of bits per word */ + bool stop2; /* true=2 stop bits; false=1 stop bit */ +}; + /**************************************************************************** * Public Function Prototypes ****************************************************************************/ @@ -63,18 +78,6 @@ void xmc4_lowsetup(void); -/**************************************************************************** - * Name: xmc4_uart_reset - * - * Description: - * Reset a UART. - * - ****************************************************************************/ - -#ifdef HAVE_UART_DEVICE -void xmc4_uart_reset(uintptr_t uart_base); -#endif - /**************************************************************************** * Name: xmc4_uart_configure * @@ -88,9 +91,8 @@ void xmc4_uart_reset(uintptr_t uart_base); ****************************************************************************/ #ifdef HAVE_UART_DEVICE -int xmc4_uart_configure(enum usic_channel_e channel, uint32_t baud, - uint32_t clock, unsigned int parity, - unsigned int nbits, unsigned int stop2); +int xmc4_uart_configure(enum usic_channel_e channel, + FAR const struct uart_config_s *config); #endif /**************************************************************************** diff --git a/arch/arm/src/xmc4/xmc4_serial.c b/arch/arm/src/xmc4/xmc4_serial.c index 78db3fd792..f1cccd7809 100644 --- a/arch/arm/src/xmc4/xmc4_serial.c +++ b/arch/arm/src/xmc4/xmc4_serial.c @@ -227,17 +227,18 @@ * Private Types ****************************************************************************/ +/* This structure provides the state of one UART device */ + struct xmc4_dev_s { uintptr_t uartbase; /* Base address of UART registers */ - uint32_t baud; /* Configured baud */ - uint32_t clock; /* Clocking frequency of the UART module */ uint8_t channel; /* USIC channel identification */ uint8_t irqs; /* Status IRQ associated with this UART (for enable) */ uint8_t ie; /* Interrupts enabled */ - uint8_t parity; /* 0=none, 1=odd, 2=even */ - uint8_t bits; /* Number of bits (8 or 9) */ - uint8_t stop2; /* Use 2 stop bits */ + + /* UART configuration */ + + struct uart_config_s config; }; /**************************************************************************** @@ -314,13 +315,16 @@ static char g_uart5txbuffer[CONFIG_UART5_TXBUFSIZE]; static struct xmc4_dev_s g_uart0priv = { .uartbase = XMC4_USIC0_CH0_BASE, - .clock = BOARD_CORECLK_FREQ, .channel = (uint8_t)USIC0_CHAN0, - .baud = CONFIG_UART0_BAUD, - .irqs = XMC4_IRQ_USIC0, - .parity = CONFIG_UART0_PARITY, - .bits = CONFIG_UART0_BITS, - .stop2 = CONFIG_UART0_2STOP, + .irqs = XMC4_IRQ_USIC0_SR0, + .config = + { + .baud = CONFIG_UART0_BAUD, + .dx = BOARD_UART0_DX, + .parity = CONFIG_UART0_PARITY, + .nbits = CONFIG_UART0_BITS, + .stop2 = CONFIG_UART0_2STOP, + } }; static uart_dev_t g_uart0port = @@ -346,13 +350,16 @@ static uart_dev_t g_uart0port = static struct xmc4_dev_s g_uart1priv = { .uartbase = XMC4_USIC0_CH1_BASE, - .clock = BOARD_CORECLK_FREQ, .channel = (uint8_t)USIC0_CHAN1, - .baud = CONFIG_UART1_BAUD, - .irqs = XMC4_IRQ_USIC1, - .parity = CONFIG_UART1_PARITY, - .bits = CONFIG_UART1_BITS, - .stop2 = CONFIG_UART1_2STOP, + .irqs = XMC4_IRQ_USIC0_SR1, + .config = + { + .baud = CONFIG_UART1_BAUD, + .dx = BOARD_UART1_DX, + .parity = CONFIG_UART1_PARITY, + .nbits = CONFIG_UART1_BITS, + .stop2 = CONFIG_UART1_2STOP, + } }; static uart_dev_t g_uart1port = @@ -378,13 +385,16 @@ static uart_dev_t g_uart1port = static struct xmc4_dev_s g_uart2priv = { .uartbase = XMC4_USIC1_CH0_BASE, - .clock = BOARD_BUS_FREQ, .channel = (uint8_t)USIC1_CHAN0, - .baud = CONFIG_UART2_BAUD, - .irqs = XMC4_IRQ_USIC2, - .parity = CONFIG_UART2_PARITY, - .bits = CONFIG_UART2_BITS, - .stop2 = CONFIG_UART2_2STOP, + .irqs = XMC4_IRQ_USIC1_SR0, + .config = + { + .baud = CONFIG_UART2_BAUD, + .dx = BOARD_UART2_DX, + .parity = CONFIG_UART2_PARITY, + .nbits = CONFIG_UART2_BITS, + .stop2 = CONFIG_UART2_2STOP, + } }; static uart_dev_t g_uart2port = @@ -410,13 +420,16 @@ static uart_dev_t g_uart2port = static struct xmc4_dev_s g_uart3priv = { .uartbase = XMC4_USIC1_CH1_BASE, - .clock = BOARD_BUS_FREQ, .channel = (uint8_t)USIC1_CHAN1, - .baud = CONFIG_UART3_BAUD, - .irqs = XMC4_IRQ_USIC3, - .parity = CONFIG_UART3_PARITY, - .bits = CONFIG_UART3_BITS, - .stop2 = CONFIG_UART3_2STOP, + .irqs = XMC4_IRQ_USIC1_SR1, + .config = + { + .baud = CONFIG_UART3_BAUD, + .dx = BOARD_UART3_DX, + .parity = CONFIG_UART3_PARITY, + .nbits = CONFIG_UART3_BITS, + .stop2 = CONFIG_UART3_2STOP, + } }; static uart_dev_t g_uart3port = @@ -442,13 +455,16 @@ static uart_dev_t g_uart3port = static struct xmc4_dev_s g_uart4priv = { .uartbase = XMC4_USIC2_CH0_BASE, - .clock = BOARD_BUS_FREQ, .channel = (uint8_t)USIC2_CHAN0, - .baud = CONFIG_UART4_BAUD, - .irqs = XMC4_IRQ_USIC4, - .parity = CONFIG_UART4_PARITY, - .bits = CONFIG_UART4_BITS, - .stop2 = CONFIG_UART4_2STOP, + .irqs = XMC4_IRQ_USIC2_SR0, + .config = + { + .baud = CONFIG_UART4_BAUD, + .dx = BOARD_UART4_DX, + .parity = CONFIG_UART4_PARITY, + .nbits = CONFIG_UART4_BITS, + .stop2 = CONFIG_UART4_2STOP, + } }; static uart_dev_t g_uart4port = @@ -474,13 +490,16 @@ static uart_dev_t g_uart4port = static struct xmc4_dev_s g_uart5priv = { .uartbase = XMC4_USIC2_CH1_BASE, - .clock = BOARD_BUS_FREQ, .channel = (uint8_t)USIC2_CHAN1, - .baud = CONFIG_UART5_BAUD, - .irqs = XMC4_IRQ_USIC5, - .parity = CONFIG_UART5_PARITY, - .bits = CONFIG_UART5_BITS, - .stop2 = CONFIG_UART5_2STOP, + .irqs = XMC4_IRQ_USIC2_SR1, + .config = + { + .baud = CONFIG_UART5_BAUD, + .dx = BOARD_UART5_DX, + .parity = CONFIG_UART5_PARITY, + .nbits = CONFIG_UART5_BITS, + .stop2 = CONFIG_UART5_2STOP, + } }; static uart_dev_t g_uart5port = @@ -508,7 +527,7 @@ static uart_dev_t g_uart5port = * Name: up_serialin ****************************************************************************/ -static inline uint8_t up_serialin(struct xmc4_dev_s *priv, int offset) +static inline uint32_t up_serialin(struct xmc4_dev_s *priv, int offset) { return getreg8(priv->uartbase + offset); } @@ -517,7 +536,7 @@ static inline uint8_t up_serialin(struct xmc4_dev_s *priv, int offset) * Name: up_serialout ****************************************************************************/ -static inline void up_serialout(struct xmc4_dev_s *priv, int offset, uint8_t value) +static inline void up_serialout(struct xmc4_dev_s *priv, int offset, uint32_t value) { putreg8(value, priv->uartbase + offset); } @@ -586,8 +605,7 @@ static int xmc4_setup(struct uart_dev_s *dev) /* Configure the UART as an RS-232 UART */ - xmc4_uart_configure(priv->uartbase, priv->baud, priv->clock, - priv->parity, priv->bits, priv->stop2); + xmc4_uart_configure(priv->uartbase, &priv->config); #endif /* Make sure that all interrupts are disabled */ @@ -615,7 +633,7 @@ static void xmc4_shutdown(struct uart_dev_s *dev) /* Reset hardware and disable Rx and Tx */ - xmc4_uart_reset(priv->uartbase); + xmc4_uart_disable(priv->channel); } /**************************************************************************** @@ -807,32 +825,23 @@ static int xmc4_ioctl(struct file *filep, int cmd, unsigned long arg) static int xmc4_receive(struct uart_dev_s *dev, uint32_t *status) { struct xmc4_dev_s *priv = (struct xmc4_dev_s *)dev->priv; - uint8_t s1; - - /* Get error status information: - * - * FE: Framing error. To clear FE, read S1 with FE set and then read - * read UART data register (D). - * NF: Noise flag. To clear NF, read S1 and then read the UART data - * register (D). - * PF: Parity error flag. To clear PF, read S1 and then read the UART - * data register (D). - */ + uint32_t outr; - s1 = up_serialin(priv, XMC4_UART_S1_OFFSET); + /* Get input data along with receiver control information */ - /* Return status information */ + outr = up_serialin(priv, XMC4_UART_S1_OFFSET); + up_serialout(priv, XMC4_USIC_OUTR_OFFSET, (uint32_t)ch); + + /* Return receiver control information */ if (status) { - *status = (uint32_t)s1; + *status = outr >> USIC_OUTR_RCI_SHIFT; } - /* Then return the actual received byte. Reading S1 then D clears all - * RX errors. - */ + /* Then return the actual received data. */ - return (int)up_serialin(priv, XMC4_UART_D_OFFSET); + return outr & USIC_OUTR_DSR_MASK; } /**************************************************************************** @@ -885,14 +894,12 @@ static void xmc4_rxint(struct uart_dev_s *dev, bool enable) static bool xmc4_rxavailable(struct uart_dev_s *dev) { struct xmc4_dev_s *priv = (struct xmc4_dev_s *)dev->priv; - /* Return true if the receive data register is full (RDRF). NOTE: If - * FIFOS are enabled, this does not mean that the FIFO is full, - * rather, it means that the number of bytes in the RX FIFO has - * exceeded the watermark setting. There may actually be RX data - * available! - */ + uint32_t regval; + + /* Return true if the transmit buffer/fifo is not "empty." */ - return (up_serialin(priv, XMC4_UART_S1_OFFSET) & UART_S1_RDRF) != 0; + regval = up_serialin(priv, XMC4_UART_TRBSR_OFFSET); + return ((regval & USIC_TRBSR_REMPTY) == 0); } /**************************************************************************** @@ -906,7 +913,7 @@ static bool xmc4_rxavailable(struct uart_dev_s *dev) static void xmc4_send(struct uart_dev_s *dev, int ch) { struct xmc4_dev_s *priv = (struct xmc4_dev_s *)dev->priv; - up_serialout(priv, XMC4_UART_D_OFFSET, (uint8_t)ch); + up_serialout(priv, XMC4_USIC_IN_OFFSET, (uint32_t)ch); } /**************************************************************************** @@ -960,15 +967,12 @@ static void xmc4_txint(struct uart_dev_s *dev, bool enable) static bool xmc4_txready(struct uart_dev_s *dev) { struct xmc4_dev_s *priv = (struct xmc4_dev_s *)dev->priv; + uint32_t regval; - /* Return true if the transmit data register is "empty." NOTE: If - * FIFOS are enabled, this does not mean that the FIFO is empty, - * rather, it means that the number of bytes in the TX FIFO is - * below the watermark setting. There may actually be space for - * additional TX data. - */ + /* Return true if the transmit buffer/fifo is "not full." */ - return (up_serialin(priv, XMC4_UART_S1_OFFSET) & UART_S1_TDRE) != 0; + regval = up_serialin(priv, XMC4_UART_TRBSR_OFFSET); + return ((regval & USIC_TRBSR_TFULL) == 0); } /**************************************************************************** @@ -982,10 +986,12 @@ static bool xmc4_txready(struct uart_dev_s *dev) static bool xmc4_txempty(struct uart_dev_s *dev) { struct xmc4_dev_s *priv = (struct xmc4_dev_s *)dev->priv; + uint32_t regval; /* Return true if the transmit buffer/fifo is "empty." */ - return (up_serialin(priv, XMC4_UART_SFIFO_OFFSET) & UART_SFIFO_TXEMPT) != 0; + regval = up_serialin(priv, XMC4_UART_TRBSR_OFFSET); + return ((regval & USIC_TRBSR_TEMPTY) != 0); } /**************************************************************************** diff --git a/arch/arm/src/xmc4/xmc4_usic.h b/arch/arm/src/xmc4/xmc4_usic.h index 5c5e78fdb9..910846bc85 100644 --- a/arch/arm/src/xmc4/xmc4_usic.h +++ b/arch/arm/src/xmc4/xmc4_usic.h @@ -44,10 +44,6 @@ #include #include "xmc4_config.h" -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - /**************************************************************************** * Public Types ****************************************************************************/ @@ -56,9 +52,9 @@ enum usic_e { - USIC0 = 0, /* USIC0 */ - USIC1 = 1, /* USIC1 */ - USIC2 = 2 /* USIC2 */ + USIC0 = 0, /* USIC0 */ + USIC1 = 1, /* USIC1 */ + USIC2 = 2 /* USIC2 */ }; /* This enumeration identifies USIC channels */ @@ -73,6 +69,19 @@ enum usic_channel_e USIC2_CHAN1 = 5 /* USIC2, Channel 1 */ }; +/* This enumeration defines values for the dx input selection */ + +enum uart_dx_e +{ + USIC_DXA = 0, /* USICn_DXmA */ + USIC_DXB = 1, /* USICn_DXmB */ + USIC_DXC = 2, /* USICn_DXmC */ + USIC_DXD = 3, /* USICn_DXmD */ + USIC_DXE = 4, /* USICn_DXmE */ + USIC_DXF = 5, /* USICn_DXmF */ + USIC_DXG = 6 /* USICn_DXmG */ +}; + /**************************************************************************** * Public Function Prototypes ****************************************************************************/ diff --git a/configs/xmc4500-relax/include/board.h b/configs/xmc4500-relax/include/board.h index dbc2440902..e90e3f730c 100644 --- a/configs/xmc4500-relax/include/board.h +++ b/configs/xmc4500-relax/include/board.h @@ -192,6 +192,17 @@ #define BUTTON_0_BIT (1 << BUTTON_0) #define BUTTON_1_BIT (1 << BUTTON_1) +/* USIC0 ****************************************************************************/ +/* USIC0 CH0 is used as UART0 + * + * RX - P1.4 + * TX - P1.5 + */ + +#define BOARD_UART0_DX USIC_DXB +#define GPIO_UART0_RXD0 GPIO_U0C0_DX0B +#define GPIO_UART0_TXD0 (GPIO_U0C0_DOUT0_3 | GPIO_PADA1P_STRONGSOFT | GPIO_OUTPUT_SET) + /************************************************************************************ * Public Data ************************************************************************************/ -- GitLab From 4519b679af9c23df140469ba8ff39e0ed5b4d9fa Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 20 Mar 2017 12:47:26 -0600 Subject: [PATCH 115/990] XMC4xxx: Finish code for USIC serial driver. --- arch/arm/src/xmc4/xmc4_lowputc.c | 12 +- arch/arm/src/xmc4/xmc4_serial.c | 236 ++++++++++++++++--------------- 2 files changed, 128 insertions(+), 120 deletions(-) diff --git a/arch/arm/src/xmc4/xmc4_lowputc.c b/arch/arm/src/xmc4/xmc4_lowputc.c index b92e723e66..fcb930d1b9 100644 --- a/arch/arm/src/xmc4/xmc4_lowputc.c +++ b/arch/arm/src/xmc4/xmc4_lowputc.c @@ -404,22 +404,22 @@ int xmc4_uart_configure(enum usic_channel_e channel, regval |= USIC_CCR_MODE_ASC; putreg32(regval, base + XMC4_USIC_CCR_OFFSET); - /* Set service request for UART protocol events. + /* Set service request for UART protocol, receiver, and transmitter events. * - * Set channel 0 protocol events on sevice request 0 - * Set channel 1 protocol events on sevice request 1 + * Set channel 0 events on sevice request 0 + * Set channel 1 events on sevice request 1 */ regval = getreg32(base + XMC4_USIC_INPR_OFFSET); - regval &= ~USIC_INPR_PINP_MASK; + regval &= ~(USIC_INPR_TBINP_MASK | USIC_INPR_RINP_MASK | USIC_INPR_PINP_MASK); if (((unsigned int)channel & 1) != 0) { - regval |= USIC_INPR_PINP_SR0; + regval |= (USIC_INPR_TBINP_SR1 | USIC_INPR_RINP_SR1 | USIC_INPR_PINP_SR1); } else { - regval |= USIC_INPR_PINP_SR1; + regval |= (USIC_INPR_TBINP_SR0 | USIC_INPR_RINP_SR0 | USIC_INPR_PINP_SR0); } putreg32(regval, base + XMC4_USIC_INPR_OFFSET); diff --git a/arch/arm/src/xmc4/xmc4_serial.c b/arch/arm/src/xmc4/xmc4_serial.c index f1cccd7809..82d53b730b 100644 --- a/arch/arm/src/xmc4/xmc4_serial.c +++ b/arch/arm/src/xmc4/xmc4_serial.c @@ -223,6 +223,17 @@ # define UART5_ASSIGNED 1 #endif +/* Event sets */ + +#ifdef CONFIG_DEBUG_FEATURES +# define CCR_RX_EVENTS (USIC_CCR_RIEN | USIC_CCR_DLIEN) +#else +# define CCR_RX_EVENTS (USIC_CCR_RIEN) +#endif + +#define CCR_TX_EVENTS (USIC_CCR_TBIEN) +#define CCR_ALL_EVENTS (CCR_RX_EVENTS | CCR_TX_EVENTS) + /**************************************************************************** * Private Types ****************************************************************************/ @@ -233,8 +244,8 @@ struct xmc4_dev_s { uintptr_t uartbase; /* Base address of UART registers */ uint8_t channel; /* USIC channel identification */ - uint8_t irqs; /* Status IRQ associated with this UART (for enable) */ - uint8_t ie; /* Interrupts enabled */ + uint8_t irq; /* Status IRQ associated with this UART (for enable) */ + uint8_t ccr; /* Interrupts enabled in CCR */ /* UART configuration */ @@ -316,7 +327,7 @@ static struct xmc4_dev_s g_uart0priv = { .uartbase = XMC4_USIC0_CH0_BASE, .channel = (uint8_t)USIC0_CHAN0, - .irqs = XMC4_IRQ_USIC0_SR0, + .irq = XMC4_IRQ_USIC0_SR0, .config = { .baud = CONFIG_UART0_BAUD, @@ -351,7 +362,7 @@ static struct xmc4_dev_s g_uart1priv = { .uartbase = XMC4_USIC0_CH1_BASE, .channel = (uint8_t)USIC0_CHAN1, - .irqs = XMC4_IRQ_USIC0_SR1, + .irq = XMC4_IRQ_USIC0_SR1, .config = { .baud = CONFIG_UART1_BAUD, @@ -386,7 +397,7 @@ static struct xmc4_dev_s g_uart2priv = { .uartbase = XMC4_USIC1_CH0_BASE, .channel = (uint8_t)USIC1_CHAN0, - .irqs = XMC4_IRQ_USIC1_SR0, + .irq = XMC4_IRQ_USIC1_SR0, .config = { .baud = CONFIG_UART2_BAUD, @@ -421,7 +432,7 @@ static struct xmc4_dev_s g_uart3priv = { .uartbase = XMC4_USIC1_CH1_BASE, .channel = (uint8_t)USIC1_CHAN1, - .irqs = XMC4_IRQ_USIC1_SR1, + .irq = XMC4_IRQ_USIC1_SR1, .config = { .baud = CONFIG_UART3_BAUD, @@ -456,7 +467,7 @@ static struct xmc4_dev_s g_uart4priv = { .uartbase = XMC4_USIC2_CH0_BASE, .channel = (uint8_t)USIC2_CHAN0, - .irqs = XMC4_IRQ_USIC2_SR0, + .irq = XMC4_IRQ_USIC2_SR0, .config = { .baud = CONFIG_UART4_BAUD, @@ -491,7 +502,7 @@ static struct xmc4_dev_s g_uart5priv = { .uartbase = XMC4_USIC2_CH1_BASE, .channel = (uint8_t)USIC2_CHAN1, - .irqs = XMC4_IRQ_USIC2_SR1, + .irq = XMC4_IRQ_USIC2_SR1, .config = { .baud = CONFIG_UART5_BAUD, @@ -524,68 +535,96 @@ static uart_dev_t g_uart5port = ****************************************************************************/ /**************************************************************************** - * Name: up_serialin + * Name: xmc4_serialin ****************************************************************************/ -static inline uint32_t up_serialin(struct xmc4_dev_s *priv, int offset) +static inline uint32_t xmc4_serialin(struct xmc4_dev_s *priv, + unsigned int offset) { - return getreg8(priv->uartbase + offset); + return getreg32(priv->uartbase + offset); } /**************************************************************************** - * Name: up_serialout + * Name: xmc4_serialout ****************************************************************************/ -static inline void up_serialout(struct xmc4_dev_s *priv, int offset, uint32_t value) +static inline void xmc4_serialout(struct xmc4_dev_s *priv, + unsigned int offset, uint32_t value) { - putreg8(value, priv->uartbase + offset); + putreg32(value, priv->uartbase + offset); } /**************************************************************************** - * Name: up_setuartint + * Name: xmc4_modifyreg ****************************************************************************/ -static void up_setuartint(struct xmc4_dev_s *priv) +static inline void xmc4_modifyreg(struct xmc4_dev_s *priv, unsigned int offset, + uint32_t setbits, uint32_t clrbits) { irqstate_t flags; - uint8_t regval; + uintptr_t regaddr = priv->uartbase + offset; + uint32_t regval; + + flags = enter_critical_section(); - /* Re-enable/re-disable interrupts corresponding to the state of bits in ie */ -#warning Missing logic + regval = getreg32(regaddr); + regval &= ~clrbits; + regval |= setbits; + putreg32(regval, regaddr); leave_critical_section(flags); } /**************************************************************************** - * Name: up_restoreuartint + * Name: xmc4_setuartint ****************************************************************************/ -static void up_restoreuartint(struct xmc4_dev_s *priv, uint8_t ie) +static void xmc4_setuartint(struct xmc4_dev_s *priv) { irqstate_t flags; - /* Re-enable/re-disable interrupts corresponding to the state of bits in ie */ + /* Re-enable/re-disable event interrupts corresponding to the state of + * bits in priv->ccr. + */ - flags = enter_critical_section(); -#warning Missing logic + flags = enter_critical_section(); + xmc4_modifyreg(priv, XMC4_USIC_CCR_OFFSET, CCR_ALL_EVENTS, priv->ccr); + leave_critical_section(flags); +} + +/**************************************************************************** + * Name: xmc4_restoreuartint + ****************************************************************************/ + +static void xmc4_restoreuartint(struct xmc4_dev_s *priv, uint32_t ccr) +{ + irqstate_t flags; + + /* Re-enable/re-disable event interrupts corresponding to the state of bits + * in the ccr argument. + */ + + flags = enter_critical_section(); + priv->ccr = ccr; + xmc4_setuartint(priv); leave_critical_section(flags); } /**************************************************************************** - * Name: up_disableuartint + * Name: xmc4_disableuartint ****************************************************************************/ -static void up_disableuartint(struct xmc4_dev_s *priv, uint8_t *ie) +static void xmc4_disableuartint(struct xmc4_dev_s *priv, uint32_t *ccr) { irqstate_t flags; flags = enter_critical_section(); - if (ie) + if (ccr) { - *ie = priv->ie; + *ccr = priv->ccr; } - up_restoreuartint(priv, 0); + xmc4_restoreuartint(priv, 0); leave_critical_section(flags); } @@ -610,7 +649,7 @@ static int xmc4_setup(struct uart_dev_s *dev) /* Make sure that all interrupts are disabled */ - up_restoreuartint(priv, 0); + xmc4_restoreuartint(priv, 0); return OK; } @@ -629,7 +668,7 @@ static void xmc4_shutdown(struct uart_dev_s *dev) /* Disable interrupts */ - up_restoreuartint(priv, 0); + xmc4_restoreuartint(priv, 0); /* Reset hardware and disable Rx and Tx */ @@ -660,10 +699,10 @@ static int xmc4_attach(struct uart_dev_s *dev) * disabled in the C2 register. */ - ret = irq_attach(priv->irqs, xmc4_interrupt, dev); + ret = irq_attach(priv->irq, xmc4_interrupt, dev); if (ret == OK) { - up_enable_irq(priv->irqs); + up_enable_irq(priv->irq); } return ret; @@ -685,12 +724,12 @@ static void xmc4_detach(struct uart_dev_s *dev) /* Disable interrupts */ - up_restoreuartint(priv, 0); - up_disable_irq(priv->irqs); + xmc4_restoreuartint(priv, 0); + up_disable_irq(priv->irq); /* Detach from the interrupt(s) */ - irq_detach(priv->irqs); + irq_detach(priv->irq); } /**************************************************************************** @@ -708,10 +747,10 @@ static void xmc4_detach(struct uart_dev_s *dev) static int xmc4_interrupt(int irq, void *context, FAR void *arg) { struct uart_dev_s *dev = (struct uart_dev_s *)arg; - struct xmc4_dev_s *priv; - int passes; - uint8_t s1; - bool handled; + struct xmc4_dev_s *priv; + int passes; + uint32_t regval; + bool handled; DEBUGASSERT(dev != NULL && dev->priv != NULL); priv = (struct xmc4_dev_s *)dev->priv; @@ -725,23 +764,12 @@ static int xmc4_interrupt(int irq, void *context, FAR void *arg) { handled = false; - /* Read status register 1 */ - - s1 = up_serialin(priv, XMC4_UART_S1_OFFSET); - - /* Handle incoming, receive bytes */ - - /* Check if the receive data register is full (RDRF). NOTE: If - * FIFOS are enabled, this does not mean that the FIFO is full, - * rather, it means that the number of bytes in the RX FIFO has - * exceeded the watermark setting. There may actually be RX data - * available! - * - * The RDRF status indication is cleared when the data is read from - * the RX data register. + /* Handle incoming, receive bytes. + * Check if the received FIFO is not empty. */ -#warning Missing logic + regval = xmc4_serialin(priv, XMC4_USIC_TRBSR_OFFSET); + if ((regval & USIC_TRBSR_REMPTY) == 0) { /* Process incoming bytes */ @@ -749,25 +777,23 @@ static int xmc4_interrupt(int irq, void *context, FAR void *arg) handled = true; } - /* Handle outgoing, transmit bytes */ - - /* Check if the transmit data register is "empty." NOTE: If FIFOS - * are enabled, this does not mean that the FIFO is empty, rather, - * it means that the number of bytes in the TX FIFO is below the - * watermark setting. There could actually be space for additional TX - * data. - * - * The TDRE status indication is cleared when the data is written to - * the TX data register. + /* Handle outgoing, transmit bytes. + * Check if the received FIFO is not full. */ -#warning Missing logic + regval = xmc4_serialin(priv, XMC4_USIC_TRBSR_OFFSET); + if ((regval & USIC_TRBSR_TFULL) == 0) { /* Process outgoing bytes */ uart_xmitchars(dev); handled = true; } + +#ifdef CONFIG_DEBUG_FEATURES + /* Check for error conditions */ +#warning Misssing logic +#endif } return OK; @@ -829,8 +855,7 @@ static int xmc4_receive(struct uart_dev_s *dev, uint32_t *status) /* Get input data along with receiver control information */ - outr = up_serialin(priv, XMC4_UART_S1_OFFSET); - up_serialout(priv, XMC4_USIC_OUTR_OFFSET, (uint32_t)ch); + outr = xmc4_serialin(priv, XMC4_USIC_OUTR_OFFSET); /* Return receiver control information */ @@ -860,24 +885,19 @@ static void xmc4_rxint(struct uart_dev_s *dev, bool enable) flags = enter_critical_section(); if (enable) { +#ifndef CONFIG_SUPPRESS_SERIAL_INTS /* Receive an interrupt when their is anything in the Rx data register (or an Rx * timeout occurs). */ -#ifndef CONFIG_SUPPRESS_SERIAL_INTS - priv->ie |= UART_C2_RIE; - up_setuartint(priv); + priv->ccr |= CCR_RX_EVENTS; + xmc4_setuartint(priv); #endif } else { -#ifdef CONFIG_DEBUG_FEATURES -# warning "Revisit: How are errors enabled?" - priv->ie &= ~UART_C2_RIE; -#else - priv->ie &= ~UART_C2_RIE; -#endif - up_setuartint(priv); + priv->ccr &= ~CCR_RX_EVENTS; + xmc4_setuartint(priv); } leave_critical_section(flags); @@ -898,7 +918,7 @@ static bool xmc4_rxavailable(struct uart_dev_s *dev) /* Return true if the transmit buffer/fifo is not "empty." */ - regval = up_serialin(priv, XMC4_UART_TRBSR_OFFSET); + regval = xmc4_serialin(priv, XMC4_USIC_TRBSR_OFFSET); return ((regval & USIC_TRBSR_REMPTY) == 0); } @@ -913,7 +933,7 @@ static bool xmc4_rxavailable(struct uart_dev_s *dev) static void xmc4_send(struct uart_dev_s *dev, int ch) { struct xmc4_dev_s *priv = (struct xmc4_dev_s *)dev->priv; - up_serialout(priv, XMC4_USIC_IN_OFFSET, (uint32_t)ch); + xmc4_serialout(priv, XMC4_USIC_IN_OFFSET, (uint32_t)ch); } /**************************************************************************** @@ -932,11 +952,11 @@ static void xmc4_txint(struct uart_dev_s *dev, bool enable) flags = enter_critical_section(); if (enable) { +#ifndef CONFIG_SUPPRESS_SERIAL_INTS /* Enable the TX interrupt */ -#ifndef CONFIG_SUPPRESS_SERIAL_INTS - priv->ie |= UART_C2_TIE; - up_setuartint(priv); + priv->ccr |= CCR_TX_EVENTS; + xmc4_setuartint(priv); /* Fake a TX interrupt here by just calling uart_xmitchars() with * interrupts disabled (note this may recurse). @@ -949,8 +969,8 @@ static void xmc4_txint(struct uart_dev_s *dev, bool enable) { /* Disable the TX interrupt */ - priv->ie &= ~UART_C2_TIE; - up_setuartint(priv); + priv->ccr &= ~CCR_TX_EVENTS; + xmc4_setuartint(priv); } leave_critical_section(flags); @@ -971,7 +991,7 @@ static bool xmc4_txready(struct uart_dev_s *dev) /* Return true if the transmit buffer/fifo is "not full." */ - regval = up_serialin(priv, XMC4_UART_TRBSR_OFFSET); + regval = xmc4_serialin(priv, XMC4_USIC_TRBSR_OFFSET); return ((regval & USIC_TRBSR_TFULL) == 0); } @@ -990,7 +1010,7 @@ static bool xmc4_txempty(struct uart_dev_s *dev) /* Return true if the transmit buffer/fifo is "empty." */ - regval = up_serialin(priv, XMC4_UART_TRBSR_OFFSET); + regval = xmc4_serialin(priv, XMC4_USIC_TRBSR_OFFSET); return ((regval & USIC_TRBSR_TEMPTY) != 0); } @@ -1004,9 +1024,9 @@ static bool xmc4_txempty(struct uart_dev_s *dev) * Description: * Performs the low level UART initialization early in debug so that the * serial console will be available during bootup. This must be called - * before up_serialinit. NOTE: This function depends on GPIO pin - * configuration performed in up_consoleinit() and main clock iniialization - * performed in up_clkinitialize(). + * before xmc4_serialinit. NOTE: This function depends on GPIO pin + * configuration performed in xmc_lowsetup() and main clock iniialization + * performed in xmc_clock_configure(). * ****************************************************************************/ @@ -1017,21 +1037,21 @@ void xmc4_earlyserialinit(void) * pic32mx_consoleinit() */ - up_restoreuartint(TTYS0_DEV.priv, 0); + xmc4_restoreuartint(TTYS0_DEV.priv, 0); #ifdef TTYS1_DEV - up_restoreuartint(TTYS1_DEV.priv, 0); + xmc4_restoreuartint(TTYS1_DEV.priv, 0); #endif #ifdef TTYS2_DEV - up_restoreuartint(TTYS2_DEV.priv, 0); + xmc4_restoreuartint(TTYS2_DEV.priv, 0); #endif #ifdef TTYS3_DEV - up_restoreuartint(TTYS3_DEV.priv, 0); + xmc4_restoreuartint(TTYS3_DEV.priv, 0); #endif #ifdef TTYS4_DEV - up_restoreuartint(TTYS4_DEV.priv, 0); + xmc4_restoreuartint(TTYS4_DEV.priv, 0); #endif #ifdef TTYS5_DEV - up_restoreuartint(TTYS5_DEV.priv, 0); + xmc4_restoreuartint(TTYS5_DEV.priv, 0); #endif /* Configuration whichever one is the console */ @@ -1060,11 +1080,9 @@ void xmc4_earlyserialinit(void) void up_serialinit(void) { - char devname[] = "/dev/ttySx"; - - /* Register the console */ - #ifdef HAVE_UART_CONSOLE + /* Register the serial console */ + (void)uart_register("/dev/console", &CONSOLE_DEV); #endif @@ -1072,26 +1090,20 @@ void up_serialinit(void) (void)uart_register("/dev/ttyS0", &TTYS0_DEV); #ifdef TTYS1_DEV - devname[(sizeof(devname)/sizeof(devname[0]))-2] = '0' + first++; (void)uart_register("/dev/ttyS1", &TTYS1_DEV); #endif #ifdef TTYS2_DEV - devname[(sizeof(devname)/sizeof(devname[0]))-2] = '0' + first++; (void)uart_register("/dev/ttyS2", &TTYS2_DEV); #endif #ifdef TTYS3_DEV - devname[(sizeof(devname)/sizeof(devname[0]))-2] = '0' + first++; (void)uart_register("/dev/ttyS3", &TTYS3_DEV); #endif #ifdef TTYS4_DEV - devname[(sizeof(devname)/sizeof(devname[0]))-2] = '0' + first++; (void)uart_register("/dev/ttyS4", &TTYS4_DEV); #endif #ifdef TTYS5_DEV - devname[(sizeof(devname)/sizeof(devname[0]))-2] = '0' + first++; (void)uart_register("/dev/ttyS5", &TTYS5_DEV); #endif - return first; } /**************************************************************************** @@ -1102,14 +1114,13 @@ void up_serialinit(void) * ****************************************************************************/ -#ifdef HAVE_UART_PUTC int up_putc(int ch) { #ifdef HAVE_UART_CONSOLE struct xmc4_dev_s *priv = (struct xmc4_dev_s *)CONSOLE_DEV.priv; - uint8_t ie; + uint32_t ccr; - up_disableuartint(priv, &ie); + xmc4_disableuartint(priv, &ccr); /* Check for LF */ @@ -1121,11 +1132,11 @@ int up_putc(int ch) } up_lowputc(ch); - up_restoreuartint(priv, ie); + xmc4_restoreuartint(priv, ccr); #endif + return ch; } -#endif #else /* USE_SERIALDRIVER */ @@ -1137,7 +1148,6 @@ int up_putc(int ch) * ****************************************************************************/ -#ifdef HAVE_UART_PUTC int up_putc(int ch) { #ifdef HAVE_UART_CONSOLE @@ -1151,10 +1161,8 @@ int up_putc(int ch) } up_lowputc(ch); -#endif return ch; } #endif #endif /* HAVE_UART_DEVICE && USE_SERIALDRIVER */ - -- GitLab From 985c137b784e0a1e1f9c448567629d858275c27b Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 20 Mar 2017 13:20:31 -0600 Subject: [PATCH 116/990] XMC4xxx: Finishes system timer logic. --- arch/arm/src/xmc4/xmc4_serial.c | 4 +-- arch/arm/src/xmc4/xmc4_start.c | 6 ++-- arch/arm/src/xmc4/xmc4_timerisr.c | 39 +++++++++++++++++++----- configs/xmc4500-relax/include/board.h | 3 +- configs/xmc4500-relax/src/xmc4_appinit.c | 4 +++ configs/xmc4500-relax/src/xmc4_bringup.c | 2 ++ 6 files changed, 44 insertions(+), 14 deletions(-) diff --git a/arch/arm/src/xmc4/xmc4_serial.c b/arch/arm/src/xmc4/xmc4_serial.c index 82d53b730b..8f4fb4026d 100644 --- a/arch/arm/src/xmc4/xmc4_serial.c +++ b/arch/arm/src/xmc4/xmc4_serial.c @@ -1019,7 +1019,7 @@ static bool xmc4_txempty(struct uart_dev_s *dev) ****************************************************************************/ /**************************************************************************** - * Name: xmc4_earlyserialinit + * Name: up_earlyserialinit * * Description: * Performs the low level UART initialization early in debug so that the @@ -1031,7 +1031,7 @@ static bool xmc4_txempty(struct uart_dev_s *dev) ****************************************************************************/ #if defined(USE_EARLYSERIALINIT) -void xmc4_earlyserialinit(void) +void up_earlyserialinit(void) { /* Disable interrupts from all UARTS. The console is enabled in * pic32mx_consoleinit() diff --git a/arch/arm/src/xmc4/xmc4_start.c b/arch/arm/src/xmc4/xmc4_start.c index aade30978f..d1a1b4a1c3 100644 --- a/arch/arm/src/xmc4/xmc4_start.c +++ b/arch/arm/src/xmc4/xmc4_start.c @@ -51,8 +51,9 @@ #include "up_internal.h" #include "chip/xmc4_flash.h" -#include "xmc4_userspace.h" +#include "xmc4_clockconfig.h" #include "xmc4_lowputc.h" +#include "xmc4_userspace.h" #include "xmc4_start.h" #ifdef CONFIG_ARCH_FPU @@ -319,8 +320,7 @@ void __start(void) #endif /* Disable the watchdog timer */ - - xmc4_wddisable(); + /* TODO - add logic to disable the watchdog timer */ /* Enable unaligned memory access */ diff --git a/arch/arm/src/xmc4/xmc4_timerisr.c b/arch/arm/src/xmc4/xmc4_timerisr.c index ba9e98596c..dd23b8e2db 100644 --- a/arch/arm/src/xmc4/xmc4_timerisr.c +++ b/arch/arm/src/xmc4/xmc4_timerisr.c @@ -57,23 +57,41 @@ * Pre-processor Definitions ****************************************************************************/ +/* The SysTick counter runs on the clock selected by SYST_CSR.CLKSOURCE. + * That selection may be either: + * + * CLKSOURCE=0: fSTDBY / 2 + * CLKSOURCE=1: fCPU + * + * In the first case, the SysTick counter would run at 16.384Khz. The most + * common system clock of 10 msec/tick cannot be exactly represented with + * that value. + * + * In the second case, the SysTick counter may run to rapidly to support + * longer timer tick intervals. For example, if the CPU clock is 144Mhz, + * then that 10 msec interval would correspond to a reload value of 1,440,000 + * or 0x0015f900. + */ + /* The desired timer interrupt frequency is provided by the definition * CLK_TCK (see include/time.h). CLK_TCK defines the desired number of * system clock ticks per second. That value is a user configurable setting * that defaults to 100 (100 ticks per second = 10 MS interval). * - * The Clock Source: The System Tick Timer's clock source is always the core - * clock + * Lets try fCPU first: */ -#define SYSTICK_RELOAD ((BOARD_CORECLK_FREQ / CLK_TCK) - 1) +#define SYSTICK_RELOAD ((BOARD_CPU_FREQUENCY / CLK_TCK) - 1) +#undef USE_STDBY_CLOCK -/* The size of the reload field is 24 bits. Verify that the reload value - * will fit in the reload register. - */ +/* Verify that the reload value will fit in the reload register. */ #if SYSTICK_RELOAD > 0x00ffffff -# error SYSTICK_RELOAD exceeds the range of the RELOAD register + /* No, then revert to fSTDBY */ + +# undef SYSTICK_RELOAD +# define SYSTICK_RELOAD ((BOARD_STDBY_FREQUENCY / CLK_TCK) - 1) +# define USE_STDBY_CLOCK 1 #endif /**************************************************************************** @@ -121,12 +139,17 @@ void arm_timer_initialize(void) regval |= (NVIC_SYSH_PRIORITY_DEFAULT << NVIC_SYSH_PRIORITY_PR15_SHIFT); putreg32(regval, NVIC_SYSH12_15_PRIORITY); +#ifndef USE_STDBY_CLOCK /* Note that is should not be neccesary to set the SYSTICK clock source: * "The CLKSOURCE bit in SysTick Control and Status register is always set * to select the core clock." + * + * For the XMC4xx, fhat selection may be either: + * + * CLKSOURCE=0: fSTDBY / 2 + * CLKSOURCE=1: fCPU */ -#if 0 regval = getreg32(NVIC_SYSTICK_CTRL); regval |= NVIC_SYSTICK_CTRL_CLKSOURCE; putreg32(regval, NVIC_SYSTICK_CTRL); diff --git a/configs/xmc4500-relax/include/board.h b/configs/xmc4500-relax/include/board.h index e90e3f730c..6be8e787f2 100644 --- a/configs/xmc4500-relax/include/board.h +++ b/configs/xmc4500-relax/include/board.h @@ -107,12 +107,13 @@ /* Standby clock source selection * - * BOARD_STDBY_CLOCKSRC_OSI - Internal slow oscillator (32768Hz) + * BOARD_STDBY_CLOCKSRC_OSI - Internal 32.768KHz slow oscillator * BOARD_STDBY_CLOCKSRC_OSCULP - External 32.768KHz crystal */ #define BOARD_STDBY_CLOCKSRC_OSI 1 #undef BOARD_STDBY_CLOCKSRC_OSCULP +#define BOARD_STDBY_FREQUENCY 32768 /* USB PLL settings. * diff --git a/configs/xmc4500-relax/src/xmc4_appinit.c b/configs/xmc4500-relax/src/xmc4_appinit.c index 8e1fa87efe..0c8ffcf2c6 100644 --- a/configs/xmc4500-relax/src/xmc4_appinit.c +++ b/configs/xmc4500-relax/src/xmc4_appinit.c @@ -39,6 +39,10 @@ #include +#include + +#include + /**************************************************************************** * Public Functions ****************************************************************************/ diff --git a/configs/xmc4500-relax/src/xmc4_bringup.c b/configs/xmc4500-relax/src/xmc4_bringup.c index ae7b5a593e..151099f9ed 100644 --- a/configs/xmc4500-relax/src/xmc4_bringup.c +++ b/configs/xmc4500-relax/src/xmc4_bringup.c @@ -39,6 +39,8 @@ #include +#include + /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ -- GitLab From 3a91ba52647f63241c7a1343eaedcb594a30a687 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 20 Mar 2017 13:46:02 -0600 Subject: [PATCH 117/990] XMC4xxx: Plug last holes to get a first, clean build. --- arch/arm/src/xmc4/xmc4_lowputc.h | 17 +++ arch/arm/src/xmc4/xmc4_serial.c | 6 +- arch/arm/src/xmc4/xmc4_start.h | 6 +- configs/xmc4500-relax/nsh/Make.defs | 6 +- configs/xmc4500-relax/scripts/flash.ld | 134 +++++++++++++++++++++++ configs/xmc4500-relax/src/Makefile | 2 +- configs/xmc4500-relax/src/xmc4_appinit.c | 2 + configs/xmc4500-relax/src/xmc4_boot.c | 4 +- 8 files changed, 163 insertions(+), 14 deletions(-) create mode 100644 configs/xmc4500-relax/scripts/flash.ld diff --git a/arch/arm/src/xmc4/xmc4_lowputc.h b/arch/arm/src/xmc4/xmc4_lowputc.h index f8016c3d78..61d850f7ba 100644 --- a/arch/arm/src/xmc4/xmc4_lowputc.h +++ b/arch/arm/src/xmc4/xmc4_lowputc.h @@ -44,6 +44,7 @@ #include +#include "up_internal.h" #include "xmc4_config.h" #include "xmc4_usic.h" @@ -78,6 +79,22 @@ struct uart_config_s void xmc4_lowsetup(void); +/**************************************************************************** + * Name: xmc4_earlyserialinit + * + * Description: + * Performs the low level UART initialization early in debug so that the + * serial console will be available during bootup. This must be called + * before xmc4_serialinit. NOTE: This function depends on GPIO pin + * configuration performed in xmc_lowsetup() and main clock iniialization + * performed in xmc_clock_configure(). + * + ****************************************************************************/ + +#ifdef USE_EARLYSERIALINIT +void xmc4_earlyserialinit(void); +#endif + /**************************************************************************** * Name: xmc4_uart_configure * diff --git a/arch/arm/src/xmc4/xmc4_serial.c b/arch/arm/src/xmc4/xmc4_serial.c index 8f4fb4026d..d9eaf0db53 100644 --- a/arch/arm/src/xmc4/xmc4_serial.c +++ b/arch/arm/src/xmc4/xmc4_serial.c @@ -1019,7 +1019,7 @@ static bool xmc4_txempty(struct uart_dev_s *dev) ****************************************************************************/ /**************************************************************************** - * Name: up_earlyserialinit + * Name: xmc4_earlyserialinit * * Description: * Performs the low level UART initialization early in debug so that the @@ -1031,7 +1031,7 @@ static bool xmc4_txempty(struct uart_dev_s *dev) ****************************************************************************/ #if defined(USE_EARLYSERIALINIT) -void up_earlyserialinit(void) +void xmc4_earlyserialinit(void) { /* Disable interrupts from all UARTS. The console is enabled in * pic32mx_consoleinit() @@ -1068,7 +1068,7 @@ void up_earlyserialinit(void) * * Description: * Register serial console and serial ports. This assumes - * that up_earlyserialinit was called previously. + * that xmc4_earlyserialinit was called previously. * * Input Parameters: * None diff --git a/arch/arm/src/xmc4/xmc4_start.h b/arch/arm/src/xmc4/xmc4_start.h index 2be470640b..ec76e2bf64 100644 --- a/arch/arm/src/xmc4/xmc4_start.h +++ b/arch/arm/src/xmc4/xmc4_start.h @@ -33,8 +33,8 @@ * ************************************************************************************/ -#ifndef __ARCH_ARM_SRC_XMC4_XMC4_CLOCKCONFIG_H -#define __ARCH_ARM_SRC_XMC4_XMC4_CLOCKCONFIG_H +#ifndef __ARCH_ARM_SRC_XMC4_XMC4_START_H +#define __ARCH_ARM_SRC_XMC4_XMC4_START_H /************************************************************************************ * Included Files @@ -58,4 +58,4 @@ void xmc4_board_initialize(void); -#endif /* __ARCH_ARM_SRC_XMC4_XMC4_CLOCKCONFIG_H */ +#endif /* __ARCH_ARM_SRC_XMC4_XMC4_START_H */ diff --git a/configs/xmc4500-relax/nsh/Make.defs b/configs/xmc4500-relax/nsh/Make.defs index 2d795a8ee1..4f4b4d98c8 100644 --- a/configs/xmc4500-relax/nsh/Make.defs +++ b/configs/xmc4500-relax/nsh/Make.defs @@ -37,11 +37,7 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs -ifeq ($(CONFIG_ARMV7M_DTCM),y) - LDSCRIPT = flash-dtcm.ld -else - LDSCRIPT = flash-sram.ld -endif +LDSCRIPT = flash.ld ifeq ($(WINTOOL),y) # Windows-native toolchains diff --git a/configs/xmc4500-relax/scripts/flash.ld b/configs/xmc4500-relax/scripts/flash.ld new file mode 100644 index 0000000000..f805eeafaf --- /dev/null +++ b/configs/xmc4500-relax/scripts/flash.ld @@ -0,0 +1,134 @@ +/**************************************************************************** + * configs/xmc4500-relax/scripts/flash.ld + * + * 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. + * + ****************************************************************************/ + +/* The XMC4500 has 1024Kb of FLASH beginning at address 0x0800:0000 and + * 64Kb of SRAM beginning at 0x2000:0000. + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address + * range. + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x08000000, LENGTH = 1024K + sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K +} + +OUTPUT_ARCH(arm) +ENTRY(_stext) +SECTIONS +{ + .text : + { + _stext = ABSOLUTE(.); + *(.vectors) + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + } > flash + + .init_section : + { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : + { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : + { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : + { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : + { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + _ebss = ABSOLUTE(.); + } > sram + + /* Global data not cleared after reset. */ + + .noinit : + { + _snoinit = ABSOLUTE(.); + *(.noinit*) + _enoinit = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/configs/xmc4500-relax/src/Makefile b/configs/xmc4500-relax/src/Makefile index d609e49ac8..f7a63f4630 100644 --- a/configs/xmc4500-relax/src/Makefile +++ b/configs/xmc4500-relax/src/Makefile @@ -42,7 +42,7 @@ ifeq ($(CONFIG_BUTTONS),y) CSRCS += xmc4_buttons.c endif -ifeq ($(CONFIG_USERLED),y) +ifeq ($(CONFIG_ARCH_LEDS),y) CSRCS += xmc4_autoleds.c else CSRCS += xmc4_userleds.c diff --git a/configs/xmc4500-relax/src/xmc4_appinit.c b/configs/xmc4500-relax/src/xmc4_appinit.c index 0c8ffcf2c6..1621317d4d 100644 --- a/configs/xmc4500-relax/src/xmc4_appinit.c +++ b/configs/xmc4500-relax/src/xmc4_appinit.c @@ -43,6 +43,8 @@ #include +#include "xmc4500-relax.h" + /**************************************************************************** * Public Functions ****************************************************************************/ diff --git a/configs/xmc4500-relax/src/xmc4_boot.c b/configs/xmc4500-relax/src/xmc4_boot.c index 994cdf86c6..cc5fec0c19 100644 --- a/configs/xmc4500-relax/src/xmc4_boot.c +++ b/configs/xmc4500-relax/src/xmc4_boot.c @@ -49,7 +49,7 @@ ************************************************************************************/ /************************************************************************************ - * Name: xmc4_boardinitialize + * Name: xmc4_board_initialize * * Description: * All STM32 architectures must provide the following entry point. This entry point @@ -58,7 +58,7 @@ * ************************************************************************************/ -void xmc4_boardinitialize(void) +void xmc4_board_initialize(void) { #ifdef CONFIG_ARCH_LEDS /* Configure on-board LEDs if LED support has been selected. */ -- GitLab From e1f86f407feb482d5eb631dbb5c1588da876bc4f Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 20 Mar 2017 14:33:48 -0600 Subject: [PATCH 118/990] XMC4500-Relax: Add LED support. --- configs/xmc4500-relax/src/xmc4500-relax.h | 22 +++- configs/xmc4500-relax/src/xmc4_autoleds.c | 118 +++++++++++++++++++++- configs/xmc4500-relax/src/xmc4_userleds.c | 32 +++++- 3 files changed, 162 insertions(+), 10 deletions(-) diff --git a/configs/xmc4500-relax/src/xmc4500-relax.h b/configs/xmc4500-relax/src/xmc4500-relax.h index 7934462b70..156d6f8c17 100644 --- a/configs/xmc4500-relax/src/xmc4500-relax.h +++ b/configs/xmc4500-relax/src/xmc4500-relax.h @@ -42,6 +42,8 @@ #include +#include "xmc4_gpio.h" + /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ @@ -50,18 +52,30 @@ * * The XMC4500 Relax Lite v1 board has two LEDs: * - * LED1 P1.1 High output illuminates - * LED2 P1.0 High output illuminates + * LED1 P1.1, Pad type A1+, High output illuminates + * LED2 P1.0, Pad type A1+ High output illuminates */ +#define GPIO_LED1 (GPIO_OUTPUT | GPIO_OUTPUT_PUSHPULL | \ + GPIO_PADA1P_STRONGSOFT | GPIO_PINCTRL_SOFTWARE | \ + GPIO_OUTPUT_CLEAR | GPIO_PORT1 | GPIO_PIN1) +#define GPIO_LED2 (GPIO_OUTPUT | GPIO_OUTPUT_PUSHPULL | \ + GPIO_PADA1P_STRONGSOFT | GPIO_PINCTRL_SOFTWARE | \ + GPIO_OUTPUT_CLEAR | GPIO_PORT1 | GPIO_PIN0) + /* BUTTONS * * The XMC4500 Relax Lite v1 board has two buttons: * - * BUTTON1 P1.14 Low input sensed when button pressed - * BUTTON2 P1.15 Low input sensed when button pressed + * BUTTON1 P1.14, Pad type A2, Low input sensed when button pressed + * BUTTON2 P1.15, Pad type A2, Low input sensed when button pressed */ +#define GPIO_BUTTON1 (GPIO_INPUT | GPIO_PINCTRL_SOFTWARE | \ + GPIO_PORT1 | GPIO_PIN14) +#define GPIO_BUTTON2 (GPIO_INPUT | GPIO_PINCTRL_SOFTWARE | \ + GPIO_PORT1 | GPIO_PIN15) + /**************************************************************************** * Public Types ****************************************************************************/ diff --git a/configs/xmc4500-relax/src/xmc4_autoleds.c b/configs/xmc4500-relax/src/xmc4_autoleds.c index 7fd88f7866..694007c5e5 100644 --- a/configs/xmc4500-relax/src/xmc4_autoleds.c +++ b/configs/xmc4500-relax/src/xmc4_autoleds.c @@ -33,6 +33,30 @@ * ****************************************************************************/ +/* The XMC4500 Relax Lite v1 board has two LEDs: + * + * LED1 P1.1 High output illuminates + * LED2 P1.0 High output illuminates + * + * These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is + * defined. In that case, the usage by the board port is defined in + * include/board.h and src/sam_autoleds.c. The LEDs are used to encode + * OS-related events as follows: + * + * SYMBOL Meaning LED state + * LED2 LED1 + * --------------------- -------------------------- ------ ------ */ + +#define LED_STARTED 0 /* NuttX has been started OFF OFF */ +#define LED_HEAPALLOCATE 0 /* Heap has been allocated OFF OFF */ +#define LED_IRQSENABLED 0 /* Interrupts enabled OFF OFF */ +#define LED_STACKCREATED 1 /* Idle stack created ON OFF */ +#define LED_INIRQ 2 /* In an interrupt No change */ +#define LED_SIGNAL 2 /* In a signal handler No change */ +#define LED_ASSERTION 2 /* An assertion failed No change */ +#define LED_PANIC 3 /* The system has crashed N/C Blinking */ +#undef LED_IDLE /* MCU is is sleep mode Not used */ + /**************************************************************************** * Included Files ****************************************************************************/ @@ -42,10 +66,93 @@ #include #include +#include "xmc4_gpio.h" #include "xmc4500-relax.h" #ifdef CONFIG_ARCH_LEDS +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static void board_led1_on(int led) +{ + bool ledon = false; + + switch (led) + { + case 0: /* LED1=OFF */ + break; + + case 1: /* LED1=ON */ + ledon = true; + break; + + case 2: /* LED1=N/C */ + case 3: /* LED1=N/C */ + default: + return; + } + + xmc4_gpio_write(GPIO_LED1, ledon); +} + +static void board_led2_on(int led) +{ + bool ledon = false; + + switch (led) + { + case 0: /* LED2=OFF */ + case 1: /* LED2=OFF */ + break; + + case 3: /* LED2=ON */ + ledon = true; + break; + + case 2: /* LED2=N/C */ + default: + return; + } + + xmc4_gpio_write(GPIO_LED2, ledon); +} + +void board_led1_off(int led) +{ + switch (led) + { + case 0: /* LED1=OFF */ + case 1: /* LED1=OFF */ + break; + + case 2: /* LED1=N/C */ + case 3: /* LED1=N/C */ + default: + return; + } + + xmc4_gpio_write(GPIO_LED1, false); +} + +void board_led2_off(int led) +{ + switch (led) + { + case 0: /* LED2=OFF */ + case 1: /* LED2=OFF */ + case 3: /* LED2=OFF */ + break; + + case 2: /* LED2=N/C */ + default: + return; + } + + xmc4_gpio_write(GPIO_LED2, false); +} + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -56,7 +163,10 @@ void board_autoled_initialize(void) { -#warning Missing logic + /* Configure LED1-2 GPIOs for output */ + + (void)xmc4_gpio_config(GPIO_LED1); + (void)xmc4_gpio_config(GPIO_LED2); } /**************************************************************************** @@ -65,7 +175,8 @@ void board_autoled_initialize(void) void board_autoled_on(int led) { -#warning Missing logic + board_led1_on(led); + board_led2_on(led); } /**************************************************************************** @@ -74,7 +185,8 @@ void board_autoled_on(int led) void board_autoled_off(int led) { -#warning Missing logic + board_led1_off(led); + board_led2_off(led); } #endif /* CONFIG_ARCH_LEDS */ diff --git a/configs/xmc4500-relax/src/xmc4_userleds.c b/configs/xmc4500-relax/src/xmc4_userleds.c index 8bb69336f7..4d9d0cb090 100644 --- a/configs/xmc4500-relax/src/xmc4_userleds.c +++ b/configs/xmc4500-relax/src/xmc4_userleds.c @@ -41,6 +41,8 @@ #include #include + +#include "xmc4_gpio.h" #include "xmc4500-relax.h" /**************************************************************************** @@ -53,7 +55,10 @@ void board_userled_initialize(void) { -#warning Missing logic + /* Configure LED1-2 GPIOs for output */ + + (void)xmc4_gpio_config(GPIO_LED1); + (void)xmc4_gpio_config(GPIO_LED2); } /**************************************************************************** @@ -62,7 +67,22 @@ void board_userled_initialize(void) void board_userled(int led, bool ledon) { -#warning Missing logic + gpioconfig_t ledcfg; + + if (led == BOARD_LED1) + { + ledcfg = GPIO_LED1; + } + else if (led == BOARD_LED2) + { + ledcfg = GPIO_LED2; + } + else + { + return; + } + + xmc4_gpio_write(ledcfg, ledon); } /**************************************************************************** @@ -71,5 +91,11 @@ void board_userled(int led, bool ledon) void board_userled_all(uint8_t ledset) { -#warning Missing logic + bool ledon; + + ledon = ((ledset & BOARD_LED1_BIT) != 0); + xmc4_gpio_write(GPIO_LED1, ledon); + + ledon = ((ledset & BOARD_LED2_BIT) != 0); + xmc4_gpio_write(GPIO_LED2, ledon); } -- GitLab From 1f71c8ced87ff8ff74ca9e4ee3c3aeb276dbcd2c Mon Sep 17 00:00:00 2001 From: Simon Piriou Date: Mon, 20 Mar 2017 22:40:25 +0100 Subject: [PATCH 119/990] bcm: update driver --- drivers/wireless/ieee80211/bcmf_ioctl.h | 2770 +++++++++++++++++++ drivers/wireless/ieee80211/bcmf_sdio.c | 224 +- drivers/wireless/ieee80211/chip_constants.h | 421 +++ drivers/wireless/ieee80211/mmc_sdio.c | 180 +- 4 files changed, 3470 insertions(+), 125 deletions(-) create mode 100644 drivers/wireless/ieee80211/bcmf_ioctl.h create mode 100644 drivers/wireless/ieee80211/chip_constants.h diff --git a/drivers/wireless/ieee80211/bcmf_ioctl.h b/drivers/wireless/ieee80211/bcmf_ioctl.h new file mode 100644 index 0000000000..6940a5d344 --- /dev/null +++ b/drivers/wireless/ieee80211/bcmf_ioctl.h @@ -0,0 +1,2770 @@ +/* + * Copyright (c) 2015 Broadcom + * 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 of Broadcom nor the names of other contributors to this + * software may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * 4. This software may not be used as a standalone product, and may only be used as + * incorporated in your product or device that incorporates Broadcom wireless connectivity + * products and solely for the purpose of enabling the functionalities of such Broadcom products. + * + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + * ANY WARRANTIES OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + * WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT, ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER 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. + */ +/* + * Custom OID/ioctl definitions for + * Broadcom 802.11abg Networking Device Driver + */ +#ifndef _wlioctl_h_ +#define _wlioctl_h_ + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +#define ACTION_FRAME_SIZE 1040 +typedef uint16_t wl_chanspec_t; +typedef uint16_t chanspec_t; +#define ETHER_ADDR_LEN 6 +typedef struct ether_addr +{ + uint8_t octet[ETHER_ADDR_LEN]; +} wl_ether_addr_t; +struct wl_ether_header +{ + uint8_t ether_dhost[ETHER_ADDR_LEN]; + uint8_t ether_shost[ETHER_ADDR_LEN]; + uint16_t ether_type; +}; +typedef struct wl_action_frame +{ + wl_ether_addr_t da; + uint16_t len; + uint32_t packetId; + uint8_t data[ACTION_FRAME_SIZE]; +} wl_action_frame_t; +/* ether types */ +#define ETHER_TYPE_LEN 2 +#define ETHER_TYPE_MIN 0x0600 /* Anything less than MIN is a length */ +#define ETHER_TYPE_IP 0x0800 /* IP */ +#define ETHER_TYPE_ARP 0x0806 /* ARP */ +#define ETHER_TYPE_8021Q 0x8100 /* 802.1Q */ +#define ETHER_TYPE_802_1X 0x888e /* 802.1x */ +#ifdef BCMWAPI_WPI +#define ETHER_TYPE_WAI 0x88b4 /* WAPI WAI */ +#endif /* BCMWAPI_WPI */ +#define ETHER_TYPE_802_1X_PREAUTH 0x88c7 /* 802.1x preauthentication */ +#define WL_WIFI_ACTION_FRAME_SIZE sizeof(struct wl_action_frame) +#define BWL_DEFAULT_PACKING + +#define RWL_ACTION_WIFI_CATEGORY 127 +#define RWL_WIFI_OUI_BYTE1 0x90 +#define RWL_WIFI_OUI_BYTE2 0x4C +#define RWL_WIFI_OUI_BYTE3 0x0F +#define RWL_WIFI_ACTION_FRAME_SIZE sizeof(struct dot11_action_wifi_vendor_specific) +#define RWL_WIFI_DEFAULT 0x00 +#define RWL_WIFI_FIND_MY_PEER 0x09 +#define RWL_WIFI_FOUND_PEER 0x0A +#define RWL_ACTION_WIFI_FRAG_TYPE 0x55 +typedef struct ssid_info +{ + uint8_t ssid_len; + uint8_t ssid[32]; +} ssid_info_t; +typedef struct cnt_rx +{ + uint32_t cnt_rxundec; + uint32_t cnt_rxframe; +} cnt_rx_t; +#define RWL_REF_MAC_ADDRESS_OFFSET 17 +#define RWL_DUT_MAC_ADDRESS_OFFSET 23 +#define RWL_WIFI_CLIENT_CHANNEL_OFFSET 50 +#define RWL_WIFI_SERVER_CHANNEL_OFFSET 51 +#define WL_BSS_INFO_VERSION 108 +#define MCSSET_LEN 16 + +typedef struct { + uint32_t version; /* version field */ + uint32_t length; /* byte length of data in this record, */ + /* starting at version and including IEs */ + wl_ether_addr_t BSSID; + uint16_t beacon_period; /* units are Kusec */ + uint16_t capability; /* Capability information */ + uint8_t SSID_len; + uint8_t SSID[32]; + struct { + uint32_t count; /* # rates in this set */ + uint8_t rates[16]; /* rates in 500kbps units w/hi bit set if basic */ + } rateset; /* supported rates */ + wl_chanspec_t chanspec; /* chanspec for bss */ + uint16_t atim_window; /* units are Kusec */ + uint8_t dtim_period; /* DTIM period */ + int16_t RSSI; /* receive signal strength (in dBm) */ + int8_t phy_noise; /* noise (in dBm) */ + + uint8_t n_cap; /* BSS is 802.11N Capable */ + uint32_t nbss_cap; /* 802.11N BSS Capabilities (based on HT_CAP_*) */ + uint8_t ctl_ch; /* 802.11N BSS control channel number */ + uint32_t reserved32[1]; /* Reserved for expansion of BSS properties */ + uint8_t flags; /* flags */ + uint8_t reserved[3]; /* Reserved for expansion of BSS properties */ + uint8_t basic_mcs[MCSSET_LEN]; /* 802.11N BSS required MCS set */ + + uint16_t ie_offset; /* offset at which IEs start, from beginning */ + uint32_t ie_length; /* byte length of Information Elements */ + int16_t SNR; /* average SNR of during frame reception */ + /* Add new fields here */ + /* variable length Information Elements */ +} wl_bss_info_t; + +typedef struct wlc_ssid +{ + uint32_t SSID_len; + uint8_t SSID[32]; +} wlc_ssid_t; +#define WL_BSSTYPE_INFRA 1 +#define WL_BSSTYPE_INDEP 0 +#define WL_BSSTYPE_ANY 2 +#define WL_SCANFLAGS_PASSIVE 0x01 +#define WL_SCANFLAGS_PROHIBITED 0x04 +typedef struct wl_scan_params +{ + wlc_ssid_t ssid; + wl_ether_addr_t bssid; + int8_t bss_type; + int8_t scan_type; + int32_t nprobes; + int32_t active_time; + int32_t passive_time; + int32_t home_time; + int32_t channel_num; + uint16_t channel_list[1]; +} wl_scan_params_t; +#define WL_SCAN_PARAMS_FIXED_SIZE (64) +#define WL_SCAN_PARAMS_COUNT_MASK (0x0000ffff) +#define WL_SCAN_PARAMS_NSSID_SHIFT (16) +#define WL_SCAN_ACTION_START (1) +#define WL_SCAN_ACTION_CONTINUE (2) +#define WL_SCAN_ACTION_ABORT (3) +#define ISCAN_REQ_VERSION (1) +typedef struct wl_iscan_params +{ + uint32_t version; + uint16_t action; + uint16_t scan_duration; + wl_scan_params_t params; +} wl_iscan_params_t; +#define WL_ISCAN_PARAMS_FIXED_SIZE (offsetof(wl_iscan_params_t, params) + sizeof(wlc_ssid_t)) +typedef struct wl_scan_results +{ + uint32_t buflen; + uint32_t version; + uint32_t count; + wl_bss_info_t bss_info[1]; +} wl_scan_results_t; +#define WL_SCAN_RESULTS_FIXED_SIZE (12) +#define WL_SCAN_RESULTS_SUCCESS (0) +#define WL_SCAN_RESULTS_PARTIAL (1) +#define WL_SCAN_RESULTS_PENDING (2) +#define WL_SCAN_RESULTS_ABORTED (3) +#define WL_SCAN_RESULTS_NO_MEM (4) +#define ESCAN_REQ_VERSION 1 +typedef struct wl_escan_params +{ + uint32_t version; + uint16_t action; + uint16_t sync_id; + wl_scan_params_t params; +} wl_escan_params_t; +#define WL_ESCAN_PARAMS_FIXED_SIZE (offsetof(wl_escan_params_t, params) + sizeof(wlc_ssid_t)) +typedef struct wl_escan_result +{ + uint32_t buflen; + uint32_t version; + uint16_t sync_id; + uint16_t bss_count; + wl_bss_info_t bss_info[1]; +} wl_escan_result_t; +#define WL_ESCAN_RESULTS_FIXED_SIZE (sizeof(wl_escan_result_t) - sizeof(wl_bss_info_t)) +typedef struct wl_iscan_results +{ + uint32_t status; + wl_scan_results_t results; +} wl_iscan_results_t; +#define WL_ISCAN_RESULTS_FIXED_SIZE \ + (WL_SCAN_RESULTS_FIXED_SIZE + offsetof(wl_iscan_results_t, results)) +#define WL_MAXRATES_IN_SET 16 /* max # of rates in a rateset */ +typedef struct wl_rateset +{ + uint32_t count; /* # rates in this set */ + uint8_t rates[WL_MAXRATES_IN_SET]; /* rates in 500kbps units w/hi bit set if basic */ +} wl_rateset_t; + +typedef struct wl_uint32_list +{ + uint32_t count; + uint32_t element[1]; +} wl_uint32_list_t; + +typedef struct wl_join_scan_params { + uint8_t scan_type; /* 0 use default, active or passive scan */ + int32_t nprobes; /* -1 use default, number of probes per channel */ + int32_t active_time; /* -1 use default, dwell time per channel for + * active scanning + */ + int32_t passive_time; /* -1 use default, dwell time per channel + * for passive scanning + */ + int32_t home_time; /* -1 use default, dwell time for the home channel + * between channel scans + */ +} wl_join_scan_params_t; + +#if !defined(ESTA_POSTMOGRIFY_REMOVAL) +#define NRATE_MCS_INUSE (0x00000080) +#define NRATE_RATE_MASK (0x0000007f) +#define NRATE_STF_MASK (0x0000ff00) +#define NRATE_STF_SHIFT (8) +#define NRATE_OVERRIDE (0x80000000) +#define NRATE_OVERRIDE_MCS_ONLY (0x40000000) +#define NRATE_SGI_MASK (0x00800000) +#define NRATE_SGI_SHIFT (23) +#define NRATE_LDPC_CODING (0x00400000) +#define NRATE_LDPC_SHIFT (22) +#define NRATE_BCMC_OVERRIDE (0x00200000) +#define NRATE_BCMC_SHIFT (21) +#define NRATE_STF_SISO (0) +#define NRATE_STF_CDD (1) +#define NRATE_STF_STBC (2) +#define NRATE_STF_SDM (3) +#define ANTENNA_NUM_1 (1) +#define ANTENNA_NUM_2 (2) +#define ANTENNA_NUM_3 (3) +#define ANTENNA_NUM_4 (4) +#define ANT_SELCFG_AUTO (0x80) +#define ANT_SELCFG_MASK (0x33) +#define ANT_SELCFG_MAX (4) +#define ANT_SELCFG_TX_UNICAST (0) +#define ANT_SELCFG_RX_UNICAST (1) +#define ANT_SELCFG_TX_DEF (2) +#define ANT_SELCFG_RX_DEF (3) +typedef struct +{ + uint8_t ant_config[ANT_SELCFG_MAX]; + uint8_t num_antcfg; +} wlc_antselcfg_t; +#define HIGHEST_SINGLE_STREAM_MCS (7) +#define WLC_CNTRY_BUF_SZ (4) +typedef struct wl_country +{ + int8_t country_abbrev[WLC_CNTRY_BUF_SZ]; + int32_t rev; + int8_t ccode[WLC_CNTRY_BUF_SZ]; +} wl_country_t; +typedef struct wl_channels_in_country +{ + uint32_t buflen; + uint32_t band; + int8_t country_abbrev[WLC_CNTRY_BUF_SZ]; + uint32_t count; + uint32_t channel[1]; +} wl_channels_in_country_t; +typedef struct wl_country_list +{ + uint32_t buflen; + uint32_t band_set; + uint32_t band; + uint32_t count; + int8_t country_abbrev[1]; +} wl_country_list_t; +#define WL_NUM_RPI_BINS 8 +#define WL_RM_TYPE_BASIC 1 +#define WL_RM_TYPE_CCA 2 +#define WL_RM_TYPE_RPI 3 +#define WL_RM_FLAG_PARALLEL (1<<0) +#define WL_RM_FLAG_LATE (1<<1) +#define WL_RM_FLAG_INCAPABLE (1<<2) +#define WL_RM_FLAG_REFUSED (1<<3) +typedef struct wl_rm_req_elt +{ + int8_t type; + int8_t flags; + wl_chanspec_t chanspec; + uint32_t token; + uint32_t tsf_h; + uint32_t tsf_l; + uint32_t dur; +} wl_rm_req_elt_t; +typedef struct wl_rm_req +{ + uint32_t token; + uint32_t count; + void* cb; + void* cb_arg; + wl_rm_req_elt_t req[1]; +} wl_rm_req_t; +#define WL_RM_REQ_FIXED_LEN offsetof(wl_rm_req_t, req) +typedef struct wl_rm_rep_elt +{ + int8_t type; + int8_t flags; + wl_chanspec_t chanspec; + uint32_t token; + uint32_t tsf_h; + uint32_t tsf_l; + uint32_t dur; + uint32_t len; + uint8_t data[1]; +} wl_rm_rep_elt_t; +#define WL_RM_REP_ELT_FIXED_LEN 24 +#define WL_RPI_REP_BIN_NUM 8 +typedef struct wl_rm_rpi_rep +{ + uint8_t rpi[WL_RPI_REP_BIN_NUM]; + int8_t rpi_max[WL_RPI_REP_BIN_NUM]; +} wl_rm_rpi_rep_t; +typedef struct wl_rm_rep +{ + uint32_t token; + uint32_t len; + wl_rm_rep_elt_t rep[1]; +} wl_rm_rep_t; +#define WL_RM_REP_FIXED_LEN 8 +#endif +#define CRYPTO_ALGO_OFF 0 +#define CRYPTO_ALGO_WEP1 1 +#define CRYPTO_ALGO_TKIP 2 +#define CRYPTO_ALGO_WEP128 3 +#define CRYPTO_ALGO_AES_CCM 4 +#define CRYPTO_ALGO_AES_OCB_MSDU 5 +#define CRYPTO_ALGO_AES_OCB_MPDU 6 +#define CRYPTO_ALGO_NALG 7 +#define WSEC_GEN_MIC_ERROR 0x0001 +#define WSEC_GEN_REPLAY 0x0002 +#define WSEC_GEN_ICV_ERROR 0x0004 +#define WL_SOFT_KEY (1 << 0) +#define WL_PRIMARY_KEY (1 << 1) +#define WL_KF_RES_4 (1 << 4) +#define WL_KF_RES_5 (1 << 5) +#define WL_IBSS_PEER_GROUP_KEY (1 << 6) +#define DOT11_MAX_KEY_SIZE 32 +typedef struct wl_wsec_key +{ + uint32_t index; + uint32_t len; + uint8_t data[DOT11_MAX_KEY_SIZE]; + uint32_t pad_1[18]; + uint32_t algo; + uint32_t flags; + uint32_t pad_2[2]; + int32_t pad_3; + int32_t iv_initialized; + int32_t pad_4; + struct + { + uint32_t hi; + uint16_t lo; + } rxiv; + uint32_t pad_5[2]; + wl_ether_addr_t ea; +} wl_wsec_key_t; +#define WSEC_MIN_PSK_LEN 8 +#define WSEC_MAX_PSK_LEN 64 +#define WSEC_PASSPHRASE (1<<0) +typedef struct +{ + uint16_t key_len; + uint16_t flags; + uint8_t key[WSEC_MAX_PSK_LEN]; +} wsec_pmk_t; + +#define OPEN_AUTH 0x0000 +#define SHARED_AUTH 0x0001 +#define WEP_ENABLED 0x0001 +#define TKIP_ENABLED 0x0002 +#define AES_ENABLED 0x0004 +#define WSEC_SWFLAG 0x0008 +#ifdef BCMCCX +#define CKIP_KP_ENABLED 0x0010 +#define CKIP_MIC_ENABLED 0x0020 +#endif +#define SES_OW_ENABLED 0x0040 +#ifdef WLFIPS +#define FIPS_ENABLED 0x0080 +#endif +#ifdef BCMWAPI_WPI +#define SMS4_ENABLED 0x0100 +#endif +#define WPA_AUTH_DISABLED 0x0000 +#define WPA_AUTH_NONE 0x0001 +#define WPA_AUTH_UNSPECIFIED 0x0002 +#define WPA_AUTH_PSK 0x0004 +#if defined(BCMCCX) || defined(BCMEXTCCX) +#define WPA_AUTH_CCKM 0x0008 +#define WPA2_AUTH_CCKM 0x0010 +#endif +#define WPA2_AUTH_UNSPECIFIED 0x0040 +#define WPA2_AUTH_PSK 0x0080 +#define BRCM_AUTH_PSK 0x0100 +#define BRCM_AUTH_DPT 0x0200 +#ifdef BCMWAPI_WPI +#define WPA_AUTH_WAPI 0x0400 +#endif +#define WPA_AUTH_PFN_ANY 0xffffffff +#define MAXPMKID 16 +#define WPA2_PMKID_LEN 16 +typedef struct _pmkid +{ + wl_ether_addr_t BSSID; + uint8_t PMKID[WPA2_PMKID_LEN]; +} pmkid_t; +typedef struct _pmkid_list +{ + uint32_t npmkid; + pmkid_t pmkid[1]; +} pmkid_list_t; +typedef struct _pmkid_cand +{ + wl_ether_addr_t BSSID; + uint8_t preauth; +} pmkid_cand_t; +typedef struct _pmkid_cand_list +{ + uint32_t npmkid_cand; + pmkid_cand_t pmkid_cand[1]; +} pmkid_cand_list_t; +#if !defined(ESTA_POSTMOGRIFY_REMOVAL) +typedef struct wl_led_info +{ + uint32_t index; + uint32_t behavior; + uint8_t activehi; +} wl_led_info_t; +struct wl_dot11_assoc_req +{ + uint16_t capability; + uint16_t listen; +}; +struct wl_dot11_assoc_resp +{ + uint16_t capability; + uint16_t status; + uint16_t aid; +}; +typedef struct wl_assoc_info +{ + uint32_t req_len; + uint32_t resp_len; + uint32_t flags; + struct wl_dot11_assoc_req req; + wl_ether_addr_t reassoc_bssid; + struct wl_dot11_assoc_resp resp; +} wl_assoc_info_t; +#define WLC_ASSOC_REQ_IS_REASSOC 0x01 +typedef struct +{ + uint32_t byteoff; + uint32_t nbytes; + uint16_t buf[1]; +} srom_rw_t; +typedef struct +{ + uint32_t source; + uint32_t byteoff; + uint32_t nbytes; +} cis_rw_t; +#define WLC_CIS_DEFAULT 0 +#define WLC_CIS_SROM 1 +#define WLC_CIS_OTP 2 +typedef struct +{ + uint32_t byteoff; + uint32_t val; + uint32_t size; + uint32_t band; +} rw_reg_t; +#define WL_ATTEN_APP_INPUT_PCL_OFF 0 +#define WL_ATTEN_PCL_ON 1 +#define WL_ATTEN_PCL_OFF 2 +typedef struct +{ + uint16_t auto_ctrl; + uint16_t bb; + uint16_t radio; + uint16_t txctl1; +} atten_t; +struct wme_tx_params_s +{ + uint8_t short_retry; + uint8_t short_fallback; + uint8_t long_retry; + uint8_t long_fallback; + uint16_t max_rate; +}; +typedef struct wme_tx_params_s wme_tx_params_t; +#define WL_WME_TX_PARAMS_IO_BYTES (sizeof(wme_tx_params_t) * AC_COUNT) +#define WL_PWRIDX_PCL_OFF -2 +#define WL_PWRIDX_PCL_ON -1 +#define WL_PWRIDX_LOWER_LIMIT -2 +#define WL_PWRIDX_UPPER_LIMIT 63 +#endif +typedef struct +{ + uint32_t val; + wl_ether_addr_t ea; +} scb_val_t; +#if !defined(ESTA_POSTMOGRIFY_REMOVAL) +#define BCM_MAC_STATUS_INDICATION (0x40010200L) +typedef struct +{ + uint16_t ver; + uint16_t len; + uint16_t cap; + uint32_t flags; + uint32_t idle; + wl_ether_addr_t ea; + wl_rateset_t rateset; + uint32_t in; + uint32_t listen_interval_inms; + uint32_t tx_pkts; + uint32_t tx_failures; + uint32_t rx_ucast_pkts; + uint32_t rx_mcast_pkts; + uint32_t tx_rate; + uint32_t rx_rate; +} sta_info_t; +#define WL_OLD_STAINFO_SIZE offsetof(sta_info_t, tx_pkts) +#define WL_STA_VER 2 +#define WL_STA_BRCM 0x1 +#define WL_STA_WME 0x2 +#define WL_STA_ABCAP 0x4 +#define WL_STA_AUTHE 0x8 +#define WL_STA_ASSOC 0x10 +#define WL_STA_AUTHO 0x20 +#define WL_STA_WDS 0x40 +#define WL_STA_WDS_LINKUP 0x80 +#define WL_STA_PS 0x100 +#define WL_STA_APSD_BE 0x200 +#define WL_STA_APSD_BK 0x400 +#define WL_STA_APSD_VI 0x800 +#define WL_STA_APSD_VO 0x1000 +#define WL_STA_N_CAP 0x2000 +#define WL_STA_SCBSTATS 0x4000 +#define WL_WDS_LINKUP WL_STA_WDS_LINKUP +#endif +typedef struct channel_info +{ + int32_t hw_channel; + int32_t target_channel; + int32_t scan_channel; +} channel_info_t; +struct mac_list +{ + uint32_t count; + wl_ether_addr_t ea[1]; +}; +typedef struct get_pktcnt +{ + uint32_t rx_good_pkt; + uint32_t rx_bad_pkt; + uint32_t tx_good_pkt; + uint32_t tx_bad_pkt; + uint32_t rx_ocast_good_pkt; +} get_pktcnt_t; +typedef struct wl_ioctl +{ + uint32_t cmd; + void* buf; + uint32_t len; + uint8_t set; + uint32_t used; + uint32_t needed; +} wl_ioctl_t; +#if !defined(ESTA_POSTMOGRIFY_REMOVAL) +typedef struct wlc_rev_info +{ + uint32_t vendorid; + uint32_t deviceid; + uint32_t radiorev; + uint32_t chiprev; + uint32_t corerev; + uint32_t boardid; + uint32_t boardvendor; + uint32_t boardrev; + uint32_t driverrev; + uint32_t ucoderev; + uint32_t bus; + uint32_t chipnum; + uint32_t phytype; + uint32_t phyrev; + uint32_t anarev; +} wlc_rev_info_t; +#define WL_REV_INFO_LEGACY_LENGTH 48 +#define WL_BRAND_MAX 10 +typedef struct wl_instance_info +{ + uint32_t instance; + int8_t brand[WL_BRAND_MAX]; +} wl_instance_info_t; +typedef struct wl_txfifo_sz +{ + uint8_t fifo; + uint8_t size; +} wl_txfifo_sz_t; +#define WLC_IOV_NAME_LEN 30 +typedef struct wlc_iov_trx_s +{ + uint8_t module; + uint8_t type; + int8_t name[WLC_IOV_NAME_LEN]; +} wlc_iov_trx_t; +#endif + +#define IOVAR_STR_BSSCFG_WPA_AUTH "bsscfg:wpa_auth" +#define IOVAR_STR_BSSCFG_WSEC "bsscfg:wsec" +#define IOVAR_STR_BSSCFG_SSID "bsscfg:ssid" +#define IOVAR_STR_BSSCFG_EVENT_MSGS "bsscfg:event_msgs" +#define IOVAR_STR_BSSCFG_CUR_ETHERADDR "bsscfg:cur_etheraddr" +#define IOVAR_STR_BSSCFG_ACTFRAME "bsscfg:actframe" +#define IOVAR_STR_BSSCFG_ACTION_FRAME "bsscfg:wifiaction" +#define IOVAR_STR_BSSCFG_VENDOR_IE "bsscfg:vndr_ie" +#define IOVAR_STR_BSS "bss" +#define IOVAR_STR_BSS_RATESET "bss_rateset" +#define IOVAR_STR_CSA "csa" +#define IOVAR_STR_AMPDU_TID "ampdu_tid" +#define IOVAR_STR_APSTA "apsta" +#define IOVAR_STR_ALLMULTI "allmulti" +#define IOVAR_STR_COUNTRY "country" +#define IOVAR_STR_EVENT_MSGS "event_msgs" +#define IOVAR_STR_ESCAN "escan" +#define IOVAR_STR_SUP_WPA "sup_wpa" +#define IOVAR_STR_CUR_ETHERADDR "cur_etheraddr" +#define IOVAR_STR_QTXPOWER "qtxpower" +#define IOVAR_STR_MCAST_LIST "mcast_list" +#define IOVAR_STR_PM2_SLEEP_RET "pm2_sleep_ret" +#define IOVAR_STR_PM_LIMIT "pm_limit" +#define IOVAR_STR_LISTEN_INTERVAL_BEACON "bcn_li_bcn" +#define IOVAR_STR_LISTEN_INTERVAL_DTIM "bcn_li_dtim" +#define IOVAR_STR_LISTEN_INTERVAL_ASSOC "assoc_listen" +#define IOVAR_PSPOLL_PERIOD "pspoll_prd" +#define IOVAR_STR_VENDOR_IE "vndr_ie" +#define IOVAR_STR_TX_GLOM "bus:txglom" +#define IOVAR_STR_ACTION_FRAME "wifiaction" +#define IOVAR_STR_AC_PARAMS_STA "wme_ac_sta" +#define IOVAR_STR_COUNTERS "counters" +#define IOVAR_STR_PKT_FILTER_ADD "pkt_filter_add" +#define IOVAR_STR_PKT_FILTER_DELETE "pkt_filter_delete" +#define IOVAR_STR_PKT_FILTER_ENABLE "pkt_filter_enable" +#define IOVAR_STR_PKT_FILTER_MODE "pkt_filter_mode" +#define IOVAR_STR_PKT_FILTER_LIST "pkt_filter_list" +#define IOVAR_STR_PKT_FILTER_STATS "pkt_filter_stats" +#define IOVAR_STR_PKT_FILTER_CLEAR_STATS "pkt_filter_clear_stats" +#define IOVAR_STR_DUTY_CYCLE_CCK "dutycycle_cck" +#define IOVAR_STR_DUTY_CYCLE_OFDM "dutycycle_ofdm" +#define IOVAR_STR_MKEEP_ALIVE "mkeep_alive" +#define IOVAR_STR_VERSION "ver" +#define IOVAR_STR_SUP_WPA2_EAPVER "sup_wpa2_eapver" +#define IOVAR_STR_ROAM_OFF "roam_off" +#define IOVAR_STR_CLOSEDNET "closednet" +#define IOVAR_STR_P2P_DISC "p2p_disc" +#define IOVAR_STR_P2P_DEV "p2p_dev" +#define IOVAR_STR_P2P_IFADD "p2p_ifadd" +#define IOVAR_STR_P2P_IFDEL "p2p_ifdel" +#define IOVAR_STR_P2P_IFUPD "p2p_ifupd" +#define IOVAR_STR_P2P_SCAN "p2p_scan" +#define IOVAR_STR_P2P_STATE "p2p_state" +#define IOVAR_STR_P2P_SSID "p2p_ssid" +#define IOVAR_STR_NRATE "nrate" +#define IOVAR_STR_BGRATE "bg_rate" +#define IOVAR_STR_ARATE "a_rate" +#define IOVAR_STR_NMODE "nmode" +#define IOVAR_STR_MAX_ASSOC "maxassoc" +#define IOVAR_STR_2G_MULTICAST_RATE "2g_mrate" +#define IOVAR_STR_MPC "mpc" +#define IOVAR_STR_AMPDU_BA_WINDOW_SIZE "ampdu_ba_wsize" +#define IOVAR_STR_AMPDU_MPDU "ampdu_mpdu" +#define IOVAR_STR_AMPDU_RX_FACTOR "ampdu_rx_factor" +#define IOVAR_STR_MIMO_BW_CAP "mimo_bw_cap" + +#define WLC_IOCTL_MAGIC ( 0x14e46c77 ) +#define WLC_IOCTL_VERSION ( 1 ) +#define WLC_IOCTL_SMLEN ( 256 ) +#define WLC_IOCTL_MEDLEN ( 1536 ) +#define WLC_IOCTL_MAXLEN ( 8192 ) + +#define WLC_GET_MAGIC ( (uint32_t) 0 ) +#define WLC_GET_VERSION ( (uint32_t) 1 ) +#define WLC_UP ( (uint32_t) 2 ) +#define WLC_DOWN ( (uint32_t) 3 ) +#define WLC_GET_LOOP ( (uint32_t) 4 ) +#define WLC_SET_LOOP ( (uint32_t) 5 ) +#define WLC_DUMP ( (uint32_t) 6 ) +#define WLC_GET_MSGLEVEL ( (uint32_t) 7 ) +#define WLC_SET_MSGLEVEL ( (uint32_t) 8 ) +#define WLC_GET_PROMISC ( (uint32_t) 9 ) +#define WLC_SET_PROMISC ( (uint32_t) 10 ) +#define WLC_GET_RATE ( (uint32_t) 12 ) +#define WLC_GET_INSTANCE ( (uint32_t) 14 ) +#define WLC_GET_INFRA ( (uint32_t) 19 ) +#define WLC_SET_INFRA ( (uint32_t) 20 ) +#define WLC_GET_AUTH ( (uint32_t) 21 ) +#define WLC_SET_AUTH ( (uint32_t) 22 ) +#define WLC_GET_BSSID ( (uint32_t) 23 ) +#define WLC_SET_BSSID ( (uint32_t) 24 ) +#define WLC_GET_SSID ( (uint32_t) 25 ) +#define WLC_SET_SSID ( (uint32_t) 26 ) +#define WLC_RESTART ( (uint32_t) 27 ) +#define WLC_GET_CHANNEL ( (uint32_t) 29 ) +#define WLC_SET_CHANNEL ( (uint32_t) 30 ) +#define WLC_GET_SRL ( (uint32_t) 31 ) +#define WLC_SET_SRL ( (uint32_t) 32 ) +#define WLC_GET_LRL ( (uint32_t) 33 ) +#define WLC_SET_LRL ( (uint32_t) 34 ) +#define WLC_GET_PLCPHDR ( (uint32_t) 35 ) +#define WLC_SET_PLCPHDR ( (uint32_t) 36 ) +#define WLC_GET_RADIO ( (uint32_t) 37 ) +#define WLC_SET_RADIO ( (uint32_t) 38 ) +#define WLC_GET_PHYTYPE ( (uint32_t) 39 ) +#define WLC_DUMP_RATE ( (uint32_t) 40 ) +#define WLC_SET_RATE_PARAMS ( (uint32_t) 41 ) +#define WLC_GET_KEY ( (uint32_t) 44 ) +#define WLC_SET_KEY ( (uint32_t) 45 ) +#define WLC_GET_REGULATORY ( (uint32_t) 46 ) +#define WLC_SET_REGULATORY ( (uint32_t) 47 ) +#define WLC_GET_PASSIVE_SCAN ( (uint32_t) 48 ) +#define WLC_SET_PASSIVE_SCAN ( (uint32_t) 49 ) +#define WLC_SCAN ( (uint32_t) 50 ) +#define WLC_SCAN_RESULTS ( (uint32_t) 51 ) +#define WLC_DISASSOC ( (uint32_t) 52 ) +#define WLC_REASSOC ( (uint32_t) 53 ) +#define WLC_GET_ROAM_TRIGGER ( (uint32_t) 54 ) +#define WLC_SET_ROAM_TRIGGER ( (uint32_t) 55 ) +#define WLC_GET_ROAM_DELTA ( (uint32_t) 56 ) +#define WLC_SET_ROAM_DELTA ( (uint32_t) 57 ) +#define WLC_GET_ROAM_SCAN_PERIOD ( (uint32_t) 58 ) +#define WLC_SET_ROAM_SCAN_PERIOD ( (uint32_t) 59 ) +#define WLC_EVM ( (uint32_t) 60 ) +#define WLC_GET_TXANT ( (uint32_t) 61 ) +#define WLC_SET_TXANT ( (uint32_t) 62 ) +#define WLC_GET_ANTDIV ( (uint32_t) 63 ) +#define WLC_SET_ANTDIV ( (uint32_t) 64 ) +#define WLC_GET_CLOSED ( (uint32_t) 67 ) +#define WLC_SET_CLOSED ( (uint32_t) 68 ) +#define WLC_GET_MACLIST ( (uint32_t) 69 ) +#define WLC_SET_MACLIST ( (uint32_t) 70 ) +#define WLC_GET_RATESET ( (uint32_t) 71 ) +#define WLC_SET_RATESET ( (uint32_t) 72 ) +#define WLC_LONGTRAIN ( (uint32_t) 74 ) +#define WLC_GET_BCNPRD ( (uint32_t) 75 ) +#define WLC_SET_BCNPRD ( (uint32_t) 76 ) +#define WLC_GET_DTIMPRD ( (uint32_t) 77 ) +#define WLC_SET_DTIMPRD ( (uint32_t) 78 ) +#define WLC_GET_SROM ( (uint32_t) 79 ) +#define WLC_SET_SROM ( (uint32_t) 80 ) +#define WLC_GET_WEP_RESTRICT ( (uint32_t) 81 ) +#define WLC_SET_WEP_RESTRICT ( (uint32_t) 82 ) +#define WLC_GET_COUNTRY ( (uint32_t) 83 ) +#define WLC_SET_COUNTRY ( (uint32_t) 84 ) +#define WLC_GET_PM ( (uint32_t) 85 ) +#define WLC_SET_PM ( (uint32_t) 86 ) +#define WLC_GET_WAKE ( (uint32_t) 87 ) +#define WLC_SET_WAKE ( (uint32_t) 88 ) +#define WLC_GET_FORCELINK ( (uint32_t) 90 ) +#define WLC_SET_FORCELINK ( (uint32_t) 91 ) +#define WLC_FREQ_ACCURACY ( (uint32_t) 92 ) +#define WLC_CARRIER_SUPPRESS ( (uint32_t) 93 ) +#define WLC_GET_PHYREG ( (uint32_t) 94 ) +#define WLC_SET_PHYREG ( (uint32_t) 95 ) +#define WLC_GET_RADIOREG ( (uint32_t) 96 ) +#define WLC_SET_RADIOREG ( (uint32_t) 97 ) +#define WLC_GET_REVINFO ( (uint32_t) 98 ) +#define WLC_GET_UCANTDIV ( (uint32_t) 99 ) +#define WLC_SET_UCANTDIV ( (uint32_t) 100 ) +#define WLC_R_REG ( (uint32_t) 101 ) +#define WLC_W_REG ( (uint32_t) 102 ) +#define WLC_GET_MACMODE ( (uint32_t) 105 ) +#define WLC_SET_MACMODE ( (uint32_t) 106 ) +#define WLC_GET_MONITOR ( (uint32_t) 107 ) +#define WLC_SET_MONITOR ( (uint32_t) 108 ) +#define WLC_GET_GMODE ( (uint32_t) 109 ) +#define WLC_SET_GMODE ( (uint32_t) 110 ) +#define WLC_GET_LEGACY_ERP ( (uint32_t) 111 ) +#define WLC_SET_LEGACY_ERP ( (uint32_t) 112 ) +#define WLC_GET_RX_ANT ( (uint32_t) 113 ) +#define WLC_GET_CURR_RATESET ( (uint32_t) 114 ) +#define WLC_GET_SCANSUPPRESS ( (uint32_t) 115 ) +#define WLC_SET_SCANSUPPRESS ( (uint32_t) 116 ) +#define WLC_GET_AP ( (uint32_t) 117 ) +#define WLC_SET_AP ( (uint32_t) 118 ) +#define WLC_GET_EAP_RESTRICT ( (uint32_t) 119 ) +#define WLC_SET_EAP_RESTRICT ( (uint32_t) 120 ) +#define WLC_SCB_AUTHORIZE ( (uint32_t) 121 ) +#define WLC_SCB_DEAUTHORIZE ( (uint32_t) 122 ) +#define WLC_GET_WDSLIST ( (uint32_t) 123 ) +#define WLC_SET_WDSLIST ( (uint32_t) 124 ) +#define WLC_GET_ATIM ( (uint32_t) 125 ) +#define WLC_SET_ATIM ( (uint32_t) 126 ) +#define WLC_GET_RSSI ( (uint32_t) 127 ) +#define WLC_GET_PHYANTDIV ( (uint32_t) 128 ) +#define WLC_SET_PHYANTDIV ( (uint32_t) 129 ) +#define WLC_AP_RX_ONLY ( (uint32_t) 130 ) +#define WLC_GET_TX_PATH_PWR ( (uint32_t) 131 ) +#define WLC_SET_TX_PATH_PWR ( (uint32_t) 132 ) +#define WLC_GET_WSEC ( (uint32_t) 133 ) +#define WLC_SET_WSEC ( (uint32_t) 134 ) +#define WLC_GET_PHY_NOISE ( (uint32_t) 135 ) +#define WLC_GET_BSS_INFO ( (uint32_t) 136 ) +#define WLC_GET_PKTCNTS ( (uint32_t) 137 ) +#define WLC_GET_LAZYWDS ( (uint32_t) 138 ) +#define WLC_SET_LAZYWDS ( (uint32_t) 139 ) +#define WLC_GET_BANDLIST ( (uint32_t) 140 ) +#define WLC_GET_BAND ( (uint32_t) 141 ) +#define WLC_SET_BAND ( (uint32_t) 142 ) +#define WLC_SCB_DEAUTHENTICATE ( (uint32_t) 143 ) +#define WLC_GET_SHORTSLOT ( (uint32_t) 144 ) +#define WLC_GET_SHORTSLOT_OVERRIDE ( (uint32_t) 145 ) +#define WLC_SET_SHORTSLOT_OVERRIDE ( (uint32_t) 146 ) +#define WLC_GET_SHORTSLOT_RESTRICT ( (uint32_t) 147 ) +#define WLC_SET_SHORTSLOT_RESTRICT ( (uint32_t) 148 ) +#define WLC_GET_GMODE_PROTECTION ( (uint32_t) 149 ) +#define WLC_GET_GMODE_PROTECTION_OVERRIDE ( (uint32_t) 150 ) +#define WLC_SET_GMODE_PROTECTION_OVERRIDE ( (uint32_t) 151 ) +#define WLC_UPGRADE ( (uint32_t) 152 ) +#define WLC_GET_IGNORE_BCNS ( (uint32_t) 155 ) +#define WLC_SET_IGNORE_BCNS ( (uint32_t) 156 ) +#define WLC_GET_SCB_TIMEOUT ( (uint32_t) 157 ) +#define WLC_SET_SCB_TIMEOUT ( (uint32_t) 158 ) +#define WLC_GET_ASSOCLIST ( (uint32_t) 159 ) +#define WLC_GET_CLK ( (uint32_t) 160 ) +#define WLC_SET_CLK ( (uint32_t) 161 ) +#define WLC_GET_UP ( (uint32_t) 162 ) +#define WLC_OUT ( (uint32_t) 163 ) +#define WLC_GET_WPA_AUTH ( (uint32_t) 164 ) +#define WLC_SET_WPA_AUTH ( (uint32_t) 165 ) +#define WLC_GET_UCFLAGS ( (uint32_t) 166 ) +#define WLC_SET_UCFLAGS ( (uint32_t) 167 ) +#define WLC_GET_PWRIDX ( (uint32_t) 168 ) +#define WLC_SET_PWRIDX ( (uint32_t) 169 ) +#define WLC_GET_TSSI ( (uint32_t) 170 ) +#define WLC_GET_SUP_RATESET_OVERRIDE ( (uint32_t) 171 ) +#define WLC_SET_SUP_RATESET_OVERRIDE ( (uint32_t) 172 ) +#define WLC_GET_PROTECTION_CONTROL ( (uint32_t) 178 ) +#define WLC_SET_PROTECTION_CONTROL ( (uint32_t) 179 ) +#define WLC_GET_PHYLIST ( (uint32_t) 180 ) +#define WLC_ENCRYPT_STRENGTH ( (uint32_t) 181 ) +#define WLC_DECRYPT_STATUS ( (uint32_t) 182 ) +#define WLC_GET_KEY_SEQ ( (uint32_t) 183 ) +#define WLC_GET_SCAN_CHANNEL_TIME ( (uint32_t) 184 ) +#define WLC_SET_SCAN_CHANNEL_TIME ( (uint32_t) 185 ) +#define WLC_GET_SCAN_UNASSOC_TIME ( (uint32_t) 186 ) +#define WLC_SET_SCAN_UNASSOC_TIME ( (uint32_t) 187 ) +#define WLC_GET_SCAN_HOME_TIME ( (uint32_t) 188 ) +#define WLC_SET_SCAN_HOME_TIME ( (uint32_t) 189 ) +#define WLC_GET_SCAN_NPROBES ( (uint32_t) 190 ) +#define WLC_SET_SCAN_NPROBES ( (uint32_t) 191 ) +#define WLC_GET_PRB_RESP_TIMEOUT ( (uint32_t) 192 ) +#define WLC_SET_PRB_RESP_TIMEOUT ( (uint32_t) 193 ) +#define WLC_GET_ATTEN ( (uint32_t) 194 ) +#define WLC_SET_ATTEN ( (uint32_t) 195 ) +#define WLC_GET_SHMEM ( (uint32_t) 196 ) +#define WLC_SET_SHMEM ( (uint32_t) 197 ) +#define WLC_SET_WSEC_TEST ( (uint32_t) 200 ) +#define WLC_SCB_DEAUTHENTICATE_FOR_REASON ( (uint32_t) 201 ) +#define WLC_TKIP_COUNTERMEASURES ( (uint32_t) 202 ) +#define WLC_GET_PIOMODE ( (uint32_t) 203 ) +#define WLC_SET_PIOMODE ( (uint32_t) 204 ) +#define WLC_SET_ASSOC_PREFER ( (uint32_t) 205 ) +#define WLC_GET_ASSOC_PREFER ( (uint32_t) 206 ) +#define WLC_SET_ROAM_PREFER ( (uint32_t) 207 ) +#define WLC_GET_ROAM_PREFER ( (uint32_t) 208 ) +#define WLC_SET_LED ( (uint32_t) 209 ) +#define WLC_GET_LED ( (uint32_t) 210 ) +#define WLC_GET_INTERFERENCE_MODE ( (uint32_t) 211 ) +#define WLC_SET_INTERFERENCE_MODE ( (uint32_t) 212 ) +#define WLC_GET_CHANNEL_QA ( (uint32_t) 213 ) +#define WLC_START_CHANNEL_QA ( (uint32_t) 214 ) +#define WLC_GET_CHANNEL_SEL ( (uint32_t) 215 ) +#define WLC_START_CHANNEL_SEL ( (uint32_t) 216 ) +#define WLC_GET_VALID_CHANNELS ( (uint32_t) 217 ) +#define WLC_GET_FAKEFRAG ( (uint32_t) 218 ) +#define WLC_SET_FAKEFRAG ( (uint32_t) 219 ) +#define WLC_GET_PWROUT_PERCENTAGE ( (uint32_t) 220 ) +#define WLC_SET_PWROUT_PERCENTAGE ( (uint32_t) 221 ) +#define WLC_SET_BAD_FRAME_PREEMPT ( (uint32_t) 222 ) +#define WLC_GET_BAD_FRAME_PREEMPT ( (uint32_t) 223 ) +#define WLC_SET_LEAP_LIST ( (uint32_t) 224 ) +#define WLC_GET_LEAP_LIST ( (uint32_t) 225 ) +#define WLC_GET_CWMIN ( (uint32_t) 226 ) +#define WLC_SET_CWMIN ( (uint32_t) 227 ) +#define WLC_GET_CWMAX ( (uint32_t) 228 ) +#define WLC_SET_CWMAX ( (uint32_t) 229 ) +#define WLC_GET_WET ( (uint32_t) 230 ) +#define WLC_SET_WET ( (uint32_t) 231 ) +#define WLC_GET_PUB ( (uint32_t) 232 ) +#define WLC_GET_KEY_PRIMARY ( (uint32_t) 235 ) +#define WLC_SET_KEY_PRIMARY ( (uint32_t) 236 ) +#define WLC_GET_ACI_ARGS ( (uint32_t) 238 ) +#define WLC_SET_ACI_ARGS ( (uint32_t) 239 ) +#define WLC_UNSET_CALLBACK ( (uint32_t) 240 ) +#define WLC_SET_CALLBACK ( (uint32_t) 241 ) +#define WLC_GET_RADAR ( (uint32_t) 242 ) +#define WLC_SET_RADAR ( (uint32_t) 243 ) +#define WLC_SET_SPECT_MANAGMENT ( (uint32_t) 244 ) +#define WLC_GET_SPECT_MANAGMENT ( (uint32_t) 245 ) +#define WLC_WDS_GET_REMOTE_HWADDR ( (uint32_t) 246 ) +#define WLC_WDS_GET_WPA_SUP ( (uint32_t) 247 ) +#define WLC_SET_CS_SCAN_TIMER ( (uint32_t) 248 ) +#define WLC_GET_CS_SCAN_TIMER ( (uint32_t) 249 ) +#define WLC_MEASURE_REQUEST ( (uint32_t) 250 ) +#define WLC_INIT ( (uint32_t) 251 ) +#define WLC_SEND_QUIET ( (uint32_t) 252 ) +#define WLC_KEEPALIVE ( (uint32_t) 253 ) +#define WLC_SEND_PWR_CONSTRAINT ( (uint32_t) 254 ) +#define WLC_UPGRADE_STATUS ( (uint32_t) 255 ) +#define WLC_CURRENT_PWR ( (uint32_t) 256 ) +#define WLC_GET_SCAN_PASSIVE_TIME ( (uint32_t) 257 ) +#define WLC_SET_SCAN_PASSIVE_TIME ( (uint32_t) 258 ) +#define WLC_LEGACY_LINK_BEHAVIOR ( (uint32_t) 259 ) +#define WLC_GET_CHANNELS_IN_COUNTRY ( (uint32_t) 260 ) +#define WLC_GET_COUNTRY_LIST ( (uint32_t) 261 ) +#define WLC_GET_VAR ( (uint32_t) 262 ) +#define WLC_SET_VAR ( (uint32_t) 263 ) +#define WLC_NVRAM_GET ( (uint32_t) 264 ) +#define WLC_NVRAM_SET ( (uint32_t) 265 ) +#define WLC_NVRAM_DUMP ( (uint32_t) 266 ) +#define WLC_REBOOT ( (uint32_t) 267 ) +#define WLC_SET_WSEC_PMK ( (uint32_t) 268 ) +#define WLC_GET_AUTH_MODE ( (uint32_t) 269 ) +#define WLC_SET_AUTH_MODE ( (uint32_t) 270 ) +#define WLC_GET_WAKEENTRY ( (uint32_t) 271 ) +#define WLC_SET_WAKEENTRY ( (uint32_t) 272 ) +#define WLC_NDCONFIG_ITEM ( (uint32_t) 273 ) +#define WLC_NVOTPW ( (uint32_t) 274 ) +#define WLC_OTPW ( (uint32_t) 275 ) +#define WLC_IOV_BLOCK_GET ( (uint32_t) 276 ) +#define WLC_IOV_MODULES_GET ( (uint32_t) 277 ) +#define WLC_SOFT_RESET ( (uint32_t) 278 ) +#define WLC_GET_ALLOW_MODE ( (uint32_t) 279 ) +#define WLC_SET_ALLOW_MODE ( (uint32_t) 280 ) +#define WLC_GET_DESIRED_BSSID ( (uint32_t) 281 ) +#define WLC_SET_DESIRED_BSSID ( (uint32_t) 282 ) +#define WLC_DISASSOC_MYAP ( (uint32_t) 283 ) +#define WLC_GET_NBANDS ( (uint32_t) 284 ) +#define WLC_GET_BANDSTATES ( (uint32_t) 285 ) +#define WLC_GET_WLC_BSS_INFO ( (uint32_t) 286 ) +#define WLC_GET_ASSOC_INFO ( (uint32_t) 287 ) +#define WLC_GET_OID_PHY ( (uint32_t) 288 ) +#define WLC_SET_OID_PHY ( (uint32_t) 289 ) +#define WLC_SET_ASSOC_TIME ( (uint32_t) 290 ) +#define WLC_GET_DESIRED_SSID ( (uint32_t) 291 ) +#define WLC_GET_CHANSPEC ( (uint32_t) 292 ) +#define WLC_GET_ASSOC_STATE ( (uint32_t) 293 ) +#define WLC_SET_PHY_STATE ( (uint32_t) 294 ) +#define WLC_GET_SCAN_PENDING ( (uint32_t) 295 ) +#define WLC_GET_SCANREQ_PENDING ( (uint32_t) 296 ) +#define WLC_GET_PREV_ROAM_REASON ( (uint32_t) 297 ) +#define WLC_SET_PREV_ROAM_REASON ( (uint32_t) 298 ) +#define WLC_GET_BANDSTATES_PI ( (uint32_t) 299 ) +#define WLC_GET_PHY_STATE ( (uint32_t) 300 ) +#define WLC_GET_BSS_WPA_RSN ( (uint32_t) 301 ) +#define WLC_GET_BSS_WPA2_RSN ( (uint32_t) 302 ) +#define WLC_GET_BSS_BCN_TS ( (uint32_t) 303 ) +#define WLC_GET_INT_DISASSOC ( (uint32_t) 304 ) +#define WLC_SET_NUM_PEERS ( (uint32_t) 305 ) +#define WLC_GET_NUM_BSS ( (uint32_t) 306 ) +#define WLC_GET_WSEC_PMK ( (uint32_t) 318 ) +#define WLC_GET_RANDOM_BYTES ( (uint32_t) 319 ) +#define WLC_LAST ( (uint32_t) 320 ) + +#ifndef EPICTRL_COOKIE +#define EPICTRL_COOKIE 0xABADCEDE +#endif +#define CMN_IOCTL_OFF 0x180 +#define WL_OID_BASE 0xFFE41420 +#define OID_WL_GETINSTANCE (WL_OID_BASE + WLC_GET_INSTANCE) +#define OID_WL_GET_FORCELINK (WL_OID_BASE + WLC_GET_FORCELINK) +#define OID_WL_SET_FORCELINK (WL_OID_BASE + WLC_SET_FORCELINK) +#define OID_WL_ENCRYPT_STRENGTH (WL_OID_BASE + WLC_ENCRYPT_STRENGTH) +#define OID_WL_DECRYPT_STATUS (WL_OID_BASE + WLC_DECRYPT_STATUS) +#define OID_LEGACY_LINK_BEHAVIOR (WL_OID_BASE + WLC_LEGACY_LINK_BEHAVIOR) +#define OID_WL_NDCONFIG_ITEM (WL_OID_BASE + WLC_NDCONFIG_ITEM) +#define OID_STA_CHANSPEC (WL_OID_BASE + WLC_GET_CHANSPEC) +#define OID_STA_NBANDS (WL_OID_BASE + WLC_GET_NBANDS) +#define OID_STA_GET_PHY (WL_OID_BASE + WLC_GET_OID_PHY) +#define OID_STA_SET_PHY (WL_OID_BASE + WLC_SET_OID_PHY) +#define OID_STA_ASSOC_TIME (WL_OID_BASE + WLC_SET_ASSOC_TIME) +#define OID_STA_DESIRED_SSID (WL_OID_BASE + WLC_GET_DESIRED_SSID) +#define OID_STA_SET_PHY_STATE (WL_OID_BASE + WLC_SET_PHY_STATE) +#define OID_STA_SCAN_PENDING (WL_OID_BASE + WLC_GET_SCAN_PENDING) +#define OID_STA_SCANREQ_PENDING (WL_OID_BASE + WLC_GET_SCANREQ_PENDING) +#define OID_STA_GET_ROAM_REASON (WL_OID_BASE + WLC_GET_PREV_ROAM_REASON) +#define OID_STA_SET_ROAM_REASON (WL_OID_BASE + WLC_SET_PREV_ROAM_REASON) +#define OID_STA_GET_PHY_STATE (WL_OID_BASE + WLC_GET_PHY_STATE) +#define OID_STA_INT_DISASSOC (WL_OID_BASE + WLC_GET_INT_DISASSOC) +#define OID_STA_SET_NUM_PEERS (WL_OID_BASE + WLC_SET_NUM_PEERS) +#define OID_STA_GET_NUM_BSS (WL_OID_BASE + WLC_GET_NUM_BSS) +#define WL_DECRYPT_STATUS_SUCCESS 1 +#define WL_DECRYPT_STATUS_FAILURE 2 +#define WL_DECRYPT_STATUS_UNKNOWN 3 +#define WLC_UPGRADE_SUCCESS 0 +#define WLC_UPGRADE_PENDING 1 +#ifdef CONFIG_USBRNDIS_RETAIL +typedef struct +{ + int8_t* name; + void* param; +}ndconfig_item_t; +#endif +#ifdef EXT_STA +typedef struct _wl_assoc_result +{ + ulong associated; + ulong NDIS_auth; + ulong NDIS_infra; +}wl_assoc_result_t; +#endif +#define WL_RADIO_SW_DISABLE (1<<0) +#define WL_RADIO_HW_DISABLE (1<<1) +#define WL_RADIO_MPC_DISABLE (1<<2) +#define WL_RADIO_COUNTRY_DISABLE (1<<3) +#define WL_TXPWR_OVERRIDE (1U<<31) +#define WL_PHY_PAVARS_LEN (6) +#define WL_DIAG_INTERRUPT (1) +#define WL_DIAG_LOOPBACK (2) +#define WL_DIAG_MEMORY (3) +#define WL_DIAG_LED (4) +#define WL_DIAG_REG (5) +#define WL_DIAG_SROM (6) +#define WL_DIAG_DMA (7) +#define WL_DIAGERR_SUCCESS (0) +#define WL_DIAGERR_FAIL_TO_RUN (1) +#define WL_DIAGERR_NOT_SUPPORTED (2) +#define WL_DIAGERR_INTERRUPT_FAIL (3) +#define WL_DIAGERR_LOOPBACK_FAIL (4) +#define WL_DIAGERR_SROM_FAIL (5) +#define WL_DIAGERR_SROM_BADCRC (6) +#define WL_DIAGERR_REG_FAIL (7) +#define WL_DIAGERR_MEMORY_FAIL (8) +#define WL_DIAGERR_NOMEM (9) +#define WL_DIAGERR_DMA_FAIL (10) +#define WL_DIAGERR_MEMORY_TIMEOUT (11) +#define WL_DIAGERR_MEMORY_BADPATTERN (12) +#define WLC_BAND_AUTO (0) +#define WLC_BAND_5G (1) +#define WLC_BAND_2G (2) +#define WLC_BAND_ALL (3) +#define WL_CHAN_FREQ_RANGE_2G (0) +#define WL_CHAN_FREQ_RANGE_5GL (1) +#define WL_CHAN_FREQ_RANGE_5GM (2) +#define WL_CHAN_FREQ_RANGE_5GH (3) +#define WLC_PHY_TYPE_A (0) +#define WLC_PHY_TYPE_B (1) +#define WLC_PHY_TYPE_G (2) +#define WLC_PHY_TYPE_N (4) +#define WLC_PHY_TYPE_LP (5) +#define WLC_PHY_TYPE_SSN (6) +#define WLC_PHY_TYPE_NULL (0xf) +#define WLC_MACMODE_DISABLED (0) +#define WLC_MACMODE_DENY (1) +#define WLC_MACMODE_ALLOW (2) +#define GMODE_LEGACY_B (0) +#define GMODE_AUTO (1) +#define GMODE_ONLY (2) +#define GMODE_B_DEFERRED (3) +#define GMODE_PERFORMANCE (4) +#define GMODE_LRS (5) +#define GMODE_MAX (6) +#define WLC_PLCP_AUTO (-1) +#define WLC_PLCP_SHORT (0) +#define WLC_PLCP_LONG (1) +#define WLC_PROTECTION_AUTO (-1) +#define WLC_PROTECTION_OFF (0) +#define WLC_PROTECTION_ON (1) +#define WLC_PROTECTION_MMHDR_ONLY (2) +#define WLC_PROTECTION_CTS_ONLY (3) +#define WLC_PROTECTION_CTL_OFF (0) +#define WLC_PROTECTION_CTL_LOCAL (1) +#define WLC_PROTECTION_CTL_OVERLAP (2) +#define WLC_N_PROTECTION_OFF (0) +#define WLC_N_PROTECTION_OPTIONAL (1) +#define WLC_N_PROTECTION_20IN40 (2) +#define WLC_N_PROTECTION_MIXEDMODE (3) +#define WLC_N_PREAMBLE_MIXEDMODE (0) +#define WLC_N_PREAMBLE_GF (1) +#define WLC_N_BW_20ALL (0) +#define WLC_N_BW_40ALL (1) +#define WLC_N_BW_20IN2G_40IN5G (2) +#define WLC_N_TXRX_CHAIN0 (0) +#define WLC_N_TXRX_CHAIN1 (1) +#define WLC_N_SGI_20 (0x01) +#define WLC_N_SGI_40 (0x02) +#define PM_OFF (0) +#define PM_MAX (1) +#define PM_FAST (2) +#define INTERFERE_NONE (0) +#define NON_WLAN (1) +#define WLAN_MANUAL (2) +#define WLAN_AUTO (3) +#define AUTO_ACTIVE (1 << 7) +typedef struct wl_aci_args +{ + int32_t enter_aci_thresh; + int32_t exit_aci_thresh; + int32_t usec_spin; + int32_t glitch_delay; + uint16_t nphy_adcpwr_enter_thresh; + uint16_t nphy_adcpwr_exit_thresh; + uint16_t nphy_repeat_ctr; + uint16_t nphy_num_samples; + uint16_t nphy_undetect_window_sz; + uint16_t nphy_b_energy_lo_aci; + uint16_t nphy_b_energy_md_aci; + uint16_t nphy_b_energy_hi_aci; +} wl_aci_args_t; +#define WL_ACI_ARGS_LEGACY_LENGTH 16 +#if !defined(ESTA_POSTMOGRIFY_REMOVAL) +typedef struct +{ + int32_t npulses; + int32_t ncontig; + int32_t min_pw; + int32_t max_pw; + uint16_t thresh0; + uint16_t thresh1; + uint16_t blank; + uint16_t fmdemodcfg; + int32_t npulses_lp; + int32_t min_pw_lp; + int32_t max_pw_lp; + int32_t min_fm_lp; + int32_t max_deltat_lp; + int32_t min_deltat; + int32_t max_deltat; + uint16_t autocorr; + uint16_t st_level_time; + uint16_t t2_min; + uint32_t version; +} wl_radar_args_t; +#define WL_RADAR_ARGS_VERSION 1 +#define WL_RADAR_DETECTOR_OFF 0 +#define WL_RADAR_DETECTOR_ON 1 +#define WL_RADAR_SIMULATED 2 +#define WL_RSSI_ANT_VERSION 1 +#define WL_RSSI_ANT_MAX 4 +typedef struct +{ + uint32_t version; + uint32_t count; + int8_t rssi_ant[WL_RSSI_ANT_MAX]; +} wl_rssi_ant_t; +#define WL_DFS_CACSTATE_IDLE 0 +#define WL_DFS_CACSTATE_PREISM_CAC 1 +#define WL_DFS_CACSTATE_ISM 2 +#define WL_DFS_CACSTATE_CSA 3 +#define WL_DFS_CACSTATE_POSTISM_CAC 4 +#define WL_DFS_CACSTATE_PREISM_OOC 5 +#define WL_DFS_CACSTATE_POSTISM_OOC 6 +#define WL_DFS_CACSTATES 7 +typedef struct +{ + uint32_t state; + uint32_t duration; + wl_chanspec_t chanspec_cleared; + uint16_t pad; +} wl_dfs_status_t; +#define NUM_PWRCTRL_RATES 12 +typedef struct +{ + uint8_t txpwr_band_max[NUM_PWRCTRL_RATES]; + uint8_t txpwr_limit[NUM_PWRCTRL_RATES]; + uint8_t txpwr_local_max; + uint8_t txpwr_local_constraint; + uint8_t txpwr_chan_reg_max; + uint8_t txpwr_target[2][NUM_PWRCTRL_RATES]; + uint8_t txpwr_est_Pout[2]; + uint8_t txpwr_opo[NUM_PWRCTRL_RATES]; + uint8_t txpwr_bphy_cck_max[NUM_PWRCTRL_RATES]; + uint8_t txpwr_bphy_ofdm_max; + uint8_t txpwr_aphy_max[NUM_PWRCTRL_RATES]; + int8_t txpwr_antgain[2]; + uint8_t txpwr_est_Pout_gofdm; +} tx_power_legacy_t; +#define WL_TX_POWER_RATES 45 +#define WL_TX_POWER_CCK_FIRST 0 +#define WL_TX_POWER_CCK_NUM 4 +#define WL_TX_POWER_OFDM_FIRST 4 +#define WL_TX_POWER_OFDM_NUM 8 +#define WL_TX_POWER_MCS_SISO_NUM 8 +#define WL_TX_POWER_MCS20_FIRST 12 +#define WL_TX_POWER_MCS20_NUM 16 +#define WL_TX_POWER_MCS40_FIRST 28 +#define WL_TX_POWER_MCS40_NUM 17 +#define WL_TX_POWER_MCS20SISO_NUM 8 +#define WL_TX_POWER_MCS40_LAST 44 +#define WL_TX_POWER_F_ENABLED 1 +#define WL_TX_POWER_F_HW 2 +#define WL_TX_POWER_F_MIMO 4 +#define WL_TX_POWER_F_SISO 8 +#define WL_TX_POWER_F_40M_CAP 16 +typedef struct +{ + uint32_t flags; + wl_chanspec_t chanspec; + wl_chanspec_t local_chanspec; + uint8_t local_max; + uint8_t local_constraint; + int8_t antgain[2]; + uint8_t rf_cores; + uint8_t est_Pout[4]; + uint8_t est_Pout_cck; + uint8_t user_limit[WL_TX_POWER_RATES]; + uint8_t reg_limit[WL_TX_POWER_RATES]; + uint8_t board_limit[WL_TX_POWER_RATES]; + uint8_t target[WL_TX_POWER_RATES]; +} tx_power_t; +typedef struct tx_inst_power +{ + uint8_t txpwr_est_Pout[2]; + uint8_t txpwr_est_Pout_gofdm; +} tx_inst_power_t; +#define WLC_MEASURE_TPC 1 +#define WLC_MEASURE_CHANNEL_BASIC 2 +#define WLC_MEASURE_CHANNEL_CCA 3 +#define WLC_MEASURE_CHANNEL_RPI 4 +#define SPECT_MNGMT_OFF 0 +#define SPECT_MNGMT_LOOSE_11H 1 +#define SPECT_MNGMT_STRICT_11H 2 +#define SPECT_MNGMT_STRICT_11D 3 +#define SPECT_MNGMT_LOOSE_11H_D 4 +#define WL_CHAN_VALID_HW (1 << 0) +#define WL_CHAN_VALID_SW (1 << 1) +#define WL_CHAN_BAND_5G (1 << 2) +#define WL_CHAN_RADAR (1 << 3) +#define WL_CHAN_INACTIVE (1 << 4) +#define WL_CHAN_PASSIVE (1 << 5) +#define WL_CHAN_RESTRICTED (1 << 6) +#define WL_BTC_DISABLE 0 +#define WL_BTC_ENABLE (1 << 0) +#define WL_BTC_PREMPT (1 << 1) +#define WL_BTC_PARTIAL (1 << 2) +#define WL_BTC_DEFAULT (1 << 3) +#define WL_BTC_HYBRID (WL_BTC_ENABLE | WL_BTC_PARTIAL) +#define WL_INF_BTC_DISABLE 0 +#define WL_INF_BTC_ENABLE 1 +#define WL_INF_BTC_AUTO 3 +#define WL_BTC_DEFWIRE 0 +#define WL_BTC_2WIRE 2 +#define WL_BTC_3WIRE 3 +#define WL_BTC_4WIRE 4 +#define WL_BTC_FLAG_PREMPT (1 << 0) +#define WL_BTC_FLAG_BT_DEF (1 << 1) +#define WL_BTC_FLAG_ACTIVE_PROT (1 << 2) +#define WL_BTC_FLAG_SIM_RSP (1 << 3) +#define WL_BTC_FLAG_PS_PROTECT (1 << 4) +#define WL_BTC_FLAG_SIM_TX_LP (1 << 5) +#define WL_BTC_FLAG_ECI (1 << 6) +#endif +#define WL_ERROR_VAL 0x00000001 +#define WL_TRACE_VAL 0x00000002 +#define WL_PRHDRS_VAL 0x00000004 +#define WL_PRPKT_VAL 0x00000008 +#define WL_INFORM_VAL 0x00000010 +#define WL_TMP_VAL 0x00000020 +#define WL_OID_VAL 0x00000040 +#define WL_RATE_VAL 0x00000080 +#define WL_ASSOC_VAL 0x00000100 +#define WL_PRUSR_VAL 0x00000200 +#define WL_PS_VAL 0x00000400 +#define WL_TXPWR_VAL 0x00000800 +#define WL_PORT_VAL 0x00001000 +#define WL_DUAL_VAL 0x00002000 +#define WL_WSEC_VAL 0x00004000 +#define WL_WSEC_DUMP_VAL 0x00008000 +#define WL_LOG_VAL 0x00010000 +#define WL_NRSSI_VAL 0x00020000 +#define WL_LOFT_VAL 0x00040000 +#define WL_REGULATORY_VAL 0x00080000 +#define WL_PHYCAL_VAL 0x00100000 +#define WL_RADAR_VAL 0x00200000 +#define WL_MPC_VAL 0x00400000 +#define WL_APSTA_VAL 0x00800000 +#define WL_DFS_VAL 0x01000000 +#define WL_BA_VAL 0x02000000 +#if defined(WLNINTENDO) +#define WL_NITRO_VAL 0x04000000 +#endif +#define WL_MBSS_VAL 0x04000000 +#define WL_CAC_VAL 0x08000000 +#define WL_AMSDU_VAL 0x10000000 +#define WL_AMPDU_VAL 0x20000000 +#define WL_FFPLD_VAL 0x40000000 +#if defined(WLNINTENDO) +#define WL_NIN_VAL 0x80000000 +#endif +#define WL_DPT_VAL 0x00000001 +#define WL_SCAN_VAL 0x00000002 +#define WL_WOWL_VAL 0x00000004 +#define WL_COEX_VAL 0x00000008 +#define WL_RTDC_VAL 0x00000010 +#define WL_BTA_VAL 0x00000040 +#define WL_LED_NUMGPIO 16 +#define WL_LED_OFF 0 +#define WL_LED_ON 1 +#define WL_LED_ACTIVITY 2 +#define WL_LED_RADIO 3 +#define WL_LED_ARADIO 4 +#define WL_LED_BRADIO 5 +#define WL_LED_BGMODE 6 +#define WL_LED_WI1 7 +#define WL_LED_WI2 8 +#define WL_LED_WI3 9 +#define WL_LED_ASSOC 10 +#define WL_LED_INACTIVE 11 +#define WL_LED_ASSOCACT 12 +#define WL_LED_NUMBEHAVIOR 13 +#define WL_LED_BEH_MASK 0x7f +#define WL_LED_AL_MASK 0x80 +#define WL_NUMCHANNELS 64 +#define WL_NUMCHANSPECS 100 +#define WL_WDS_WPA_ROLE_AUTH 0 +#define WL_WDS_WPA_ROLE_SUP 1 +#define WL_WDS_WPA_ROLE_AUTO 255 +#define WL_EVENTING_MASK_LEN ((WLC_E_LAST + 7) / 8) + +#define VNDR_IE_CMD_LEN 4 +#define VNDR_IE_BEACON_FLAG 0x1 +#define VNDR_IE_PRBRSP_FLAG 0x2 +#define VNDR_IE_ASSOCRSP_FLAG 0x4 +#define VNDR_IE_AUTHRSP_FLAG 0x8 +#define VNDR_IE_PRBREQ_FLAG 0x10 +#define VNDR_IE_ASSOCREQ_FLAG 0x20 +#define VNDR_IE_CUSTOM_FLAG 0x100 +#define VNDR_IE_INFO_HDR_LEN (sizeof(uint32_t)) +struct wl_vndr_ie +{ + uint8_t id; + uint8_t len; + uint8_t oui[3]; + uint8_t data[1]; +}; +typedef struct wl_vndr_ie wl_vndr_ie_t; +typedef struct +{ + uint32_t pktflag; + wl_vndr_ie_t vndr_ie_data; +} vndr_ie_info_t; +typedef struct +{ + int32_t iecount; + vndr_ie_info_t vndr_ie_list[1]; +} vndr_ie_buf_t; +typedef struct +{ + int8_t cmd[VNDR_IE_CMD_LEN]; + vndr_ie_buf_t vndr_ie_buffer; +} vndr_ie_setbuf_t; +#define WL_JOIN_PREF_RSSI 1 +#define WL_JOIN_PREF_WPA 2 +#define WL_JOIN_PREF_BAND 3 +#define WLJP_BAND_ASSOC_PREF 255 +#define WL_WPA_ACP_MCS_ANY "\x00\x00\x00\x00" +struct tsinfo_arg +{ + uint8_t octets[3]; +}; +#define NFIFO 6 +#define WL_CNT_T_VERSION 6 +#define WL_CNT_EXT_T_VERSION 1 + + + +typedef struct +{ + uint16_t version; /* see definition of WL_CNT_T_VERSION */ + uint16_t length; /* length of entire structure */ + + /* transmit stat counters */ + uint32_t txframe; /* tx data frames */ + uint32_t txbyte; /* tx data bytes */ + uint32_t txretrans; /* tx mac retransmits */ + uint32_t txerror; /* tx data errors (derived: sum of others) */ + uint32_t txctl; /* tx management frames */ + uint32_t txprshort; /* tx short preamble frames */ + uint32_t txserr; /* tx status errors */ + uint32_t txnobuf; /* tx out of buffers errors */ + uint32_t txnoassoc; /* tx discard because we're not associated */ + uint32_t txrunt; /* tx runt frames */ + uint32_t txchit; /* tx header cache hit (fastpath) */ + uint32_t txcmiss; /* tx header cache miss (slowpath) */ + + /* transmit chip error counters */ + uint32_t txuflo; /* tx fifo underflows */ + uint32_t txphyerr; /* tx phy errors (indicated in tx status) */ + uint32_t txphycrs; /* PR8861/8963 counter */ + + /* receive stat counters */ + uint32_t rxframe; /* rx data frames */ + uint32_t rxbyte; /* rx data bytes */ + uint32_t rxerror; /* rx data errors (derived: sum of others) */ + uint32_t rxctl; /* rx management frames */ + uint32_t rxnobuf; /* rx out of buffers errors */ + uint32_t rxnondata; /* rx non data frames in the data channel errors */ + uint32_t rxbadds; /* rx bad DS errors */ + uint32_t rxbadcm; /* rx bad control or management frames */ + uint32_t rxfragerr; /* rx fragmentation errors */ + uint32_t rxrunt; /* rx runt frames */ + uint32_t rxgiant; /* rx giant frames */ + uint32_t rxnoscb; /* rx no scb error */ + uint32_t rxbadproto; /* rx invalid frames */ + uint32_t rxbadsrcmac; /* rx frames with Invalid Src Mac */ + uint32_t rxbadda; /* rx frames tossed for invalid da */ + uint32_t rxfilter; /* rx frames filtered out */ + + /* receive chip error counters */ + uint32_t rxoflo; /* rx fifo overflow errors */ + uint32_t rxuflo[NFIFO]; /* rx dma descriptor underflow errors */ + + uint32_t d11cnt_txrts_off; /* d11cnt txrts value when reset d11cnt */ + uint32_t d11cnt_rxcrc_off; /* d11cnt rxcrc value when reset d11cnt */ + uint32_t d11cnt_txnocts_off; /* d11cnt txnocts value when reset d11cnt */ + + /* misc counters */ + uint32_t dmade; /* tx/rx dma descriptor errors */ + uint32_t dmada; /* tx/rx dma data errors */ + uint32_t dmape; /* tx/rx dma descriptor protocol errors */ + uint32_t reset; /* reset count */ + uint32_t tbtt; /* cnts the TBTT int's */ + uint32_t txdmawar; /* # occurrences of PR15420 workaround */ + uint32_t pkt_callback_reg_fail; /* callbacks register failure */ + + /* MAC counters: 32-bit version of d11.h's macstat_t */ + uint32_t txallfrm; /* total number of frames sent, incl. Data, ACK, RTS, CTS, + * Control Management (includes retransmissions) + */ + uint32_t txrtsfrm; /* number of RTS sent out by the MAC */ + uint32_t txctsfrm; /* number of CTS sent out by the MAC */ + uint32_t txackfrm; /* number of ACK frames sent out */ + uint32_t txdnlfrm; /* Not used */ + uint32_t txbcnfrm; /* beacons transmitted */ + uint32_t txfunfl[8]; /* per-fifo tx underflows */ + uint32_t txtplunfl; /* Template underflows (mac was too slow to transmit ACK/CTS + * or BCN) + */ + uint32_t txphyerror; /* Transmit phy error, type of error is reported in tx-status for + * driver enqueued frames + */ + uint32_t rxfrmtoolong; /* Received frame longer than legal limit (2346 bytes) */ + uint32_t rxfrmtooshrt; /* Received frame did not contain enough bytes for its frame type */ + uint32_t rxinvmachdr; /* Either the protocol version != 0 or frame type not + * data/control/management + */ + uint32_t rxbadfcs; /* number of frames for which the CRC check failed in the MAC */ + uint32_t rxbadplcp; /* parity check of the PLCP header failed */ + uint32_t rxcrsglitch; /* PHY was able to correlate the preamble but not the header */ + uint32_t rxstrt; /* Number of received frames with a good PLCP + * (i.e. passing parity check) + */ + uint32_t rxdfrmucastmbss; /* Number of received DATA frames with good FCS and matching RA */ + uint32_t rxmfrmucastmbss; /* number of received mgmt frames with good FCS and matching RA */ + uint32_t rxcfrmucast; /* number of received CNTRL frames with good FCS and matching RA */ + uint32_t rxrtsucast; /* number of unicast RTS addressed to the MAC (good FCS) */ + uint32_t rxctsucast; /* number of unicast CTS addressed to the MAC (good FCS) */ + uint32_t rxackucast; /* number of ucast ACKS received (good FCS) */ + uint32_t rxdfrmocast; /* number of received DATA frames (good FCS and not matching RA) */ + uint32_t rxmfrmocast; /* number of received MGMT frames (good FCS and not matching RA) */ + uint32_t rxcfrmocast; /* number of received CNTRL frame (good FCS and not matching RA) */ + uint32_t rxrtsocast; /* number of received RTS not addressed to the MAC */ + uint32_t rxctsocast; /* number of received CTS not addressed to the MAC */ + uint32_t rxdfrmmcast; /* number of RX Data multicast frames received by the MAC */ + uint32_t rxmfrmmcast; /* number of RX Management multicast frames received by the MAC */ + uint32_t rxcfrmmcast; /* number of RX Control multicast frames received by the MAC + * (unlikely to see these) + */ + uint32_t rxbeaconmbss; /* beacons received from member of BSS */ + uint32_t rxdfrmucastobss; /* number of unicast frames addressed to the MAC from + * other BSS (WDS FRAME) + */ + uint32_t rxbeaconobss; /* beacons received from other BSS */ + uint32_t rxrsptmout; /* Number of response timeouts for transmitted frames + * expecting a response + */ + uint32_t bcntxcancl; /* transmit beacons canceled due to receipt of beacon (IBSS) */ + uint32_t rxf0ovfl; /* Number of receive fifo 0 overflows */ + uint32_t rxf1ovfl; /* Number of receive fifo 1 overflows (obsolete) */ + uint32_t rxf2ovfl; /* Number of receive fifo 2 overflows (obsolete) */ + uint32_t txsfovfl; /* Number of transmit status fifo overflows (obsolete) */ + uint32_t pmqovfl; /* Number of PMQ overflows */ + uint32_t rxcgprqfrm; /* Number of received Probe requests that made it into + * the PRQ fifo + */ + uint32_t rxcgprsqovfl; /* Rx Probe Request Que overflow in the AP */ + uint32_t txcgprsfail; /* Tx Probe Response Fail. AP sent probe response but did + * not get ACK + */ + uint32_t txcgprssuc; /* Tx Probe Response Success (ACK was received) */ + uint32_t prs_timeout; /* Number of probe requests that were dropped from the PRQ + * fifo because a probe response could not be sent out within + * the time limit defined in M_PRS_MAXTIME + */ + uint32_t rxnack; /* XXX Number of NACKS received (Afterburner) */ + uint32_t frmscons; /* XXX Number of frames completed without transmission because of an + * Afterburner re-queue + */ + uint32_t txnack; /* XXX Number of NACKs transmitted (Afterburner) */ + uint32_t txglitch_nack; /* obsolete */ + uint32_t txburst; /* obsolete */ + + /* 802.11 MIB counters, pp. 614 of 802.11 reaff doc. */ + uint32_t txfrag; /* dot11TransmittedFragmentCount */ + uint32_t txmulti; /* dot11MulticastTransmittedFrameCount */ + uint32_t txfail; /* dot11FailedCount */ + uint32_t txretry; /* dot11RetryCount */ + uint32_t txretrie; /* dot11MultipleRetryCount */ + uint32_t rxdup; /* dot11FrameduplicateCount */ + uint32_t txrts; /* dot11RTSSuccessCount */ + uint32_t txnocts; /* dot11RTSFailureCount */ + uint32_t txnoack; /* dot11ACKFailureCount */ + uint32_t rxfrag; /* dot11ReceivedFragmentCount */ + uint32_t rxmulti; /* dot11MulticastReceivedFrameCount */ + uint32_t rxcrc; /* dot11FCSErrorCount */ + uint32_t txfrmsnt; /* dot11TransmittedFrameCount (bogus MIB?) */ + uint32_t rxundec; /* dot11WEPUndecryptableCount */ + + /* WPA2 counters (see rxundec for DecryptFailureCount) */ + uint32_t tkipmicfaill; /* TKIPLocalMICFailures */ + uint32_t tkipcntrmsr; /* TKIPCounterMeasuresInvoked */ + uint32_t tkipreplay; /* TKIPReplays */ + uint32_t ccmpfmterr; /* CCMPFormatErrors */ + uint32_t ccmpreplay; /* CCMPReplays */ + uint32_t ccmpundec; /* CCMPDecryptErrors */ + uint32_t fourwayfail; /* FourWayHandshakeFailures */ + uint32_t wepundec; /* dot11WEPUndecryptableCount */ + uint32_t wepicverr; /* dot11WEPICVErrorCount */ + uint32_t decsuccess; /* DecryptSuccessCount */ + uint32_t tkipicverr; /* TKIPICVErrorCount */ + uint32_t wepexcluded; /* dot11WEPExcludedCount */ + + uint32_t rxundec_mcst; /* dot11WEPUndecryptableCount */ + + /* WPA2 counters (see rxundec for DecryptFailureCount) */ + uint32_t tkipmicfaill_mcst; /* TKIPLocalMICFailures */ + uint32_t tkipcntrmsr_mcst; /* TKIPCounterMeasuresInvoked */ + uint32_t tkipreplay_mcst; /* TKIPReplays */ + uint32_t ccmpfmterr_mcst; /* CCMPFormatErrors */ + uint32_t ccmpreplay_mcst; /* CCMPReplays */ + uint32_t ccmpundec_mcst; /* CCMPDecryptErrors */ + uint32_t fourwayfail_mcst; /* FourWayHandshakeFailures */ + uint32_t wepundec_mcst; /* dot11WEPUndecryptableCount */ + uint32_t wepicverr_mcst; /* dot11WEPICVErrorCount */ + uint32_t decsuccess_mcst; /* DecryptSuccessCount */ + uint32_t tkipicverr_mcst; /* TKIPICVErrorCount */ + uint32_t wepexcluded_mcst; /* dot11WEPExcludedCount */ + + uint32_t txchanrej; /* Tx frames suppressed due to channel rejection */ + uint32_t txexptime; /* Tx frames suppressed due to timer expiration */ + uint32_t psmwds; /* Count PSM watchdogs */ + uint32_t phywatchdog; /* Count Phy watchdogs (triggered by ucode) */ + + /* MBSS counters, AP only */ + uint32_t prq_entries_handled; /* PRQ entries read in */ + uint32_t prq_undirected_entries; /* which were bcast bss & ssid */ + uint32_t prq_bad_entries; /* which could not be translated to info */ + uint32_t atim_suppress_count; /* TX suppressions on ATIM fifo */ + uint32_t bcn_template_not_ready; /* Template marked in use on send bcn ... */ + uint32_t bcn_template_not_ready_done; /* ...but "DMA done" interrupt rcvd */ + uint32_t late_tbtt_dpc; /* TBTT DPC did not happen in time */ + + /* per-rate receive stat counters */ + uint32_t rx1mbps; /* packets rx at 1Mbps */ + uint32_t rx2mbps; /* packets rx at 2Mbps */ + uint32_t rx5mbps5; /* packets rx at 5.5Mbps */ + uint32_t rx6mbps; /* packets rx at 6Mbps */ + uint32_t rx9mbps; /* packets rx at 9Mbps */ + uint32_t rx11mbps; /* packets rx at 11Mbps */ + uint32_t rx12mbps; /* packets rx at 12Mbps */ + uint32_t rx18mbps; /* packets rx at 18Mbps */ + uint32_t rx24mbps; /* packets rx at 24Mbps */ + uint32_t rx36mbps; /* packets rx at 36Mbps */ + uint32_t rx48mbps; /* packets rx at 48Mbps */ + uint32_t rx54mbps; /* packets rx at 54Mbps */ + uint32_t rx108mbps; /* packets rx at 108mbps */ + uint32_t rx162mbps; /* packets rx at 162mbps */ + uint32_t rx216mbps; /* packets rx at 216 mbps */ + uint32_t rx270mbps; /* packets rx at 270 mbps */ + uint32_t rx324mbps; /* packets rx at 324 mbps */ + uint32_t rx378mbps; /* packets rx at 378 mbps */ + uint32_t rx432mbps; /* packets rx at 432 mbps */ + uint32_t rx486mbps; /* packets rx at 486 mbps */ + uint32_t rx540mbps; /* packets rx at 540 mbps */ + + /* pkteng rx frame stats */ + uint32_t pktengrxducast; /* unicast frames rxed by the pkteng code */ + uint32_t pktengrxdmcast; /* multicast frames rxed by the pkteng code */ + + uint32_t rfdisable; /* count of radio disables */ + uint32_t bphy_rxcrsglitch; /* PHY count of bphy glitches */ + + uint32_t txmpdu_sgi; /* count for sgi transmit */ + uint32_t rxmpdu_sgi; /* count for sgi received */ + uint32_t txmpdu_stbc; /* count for stbc transmit */ + uint32_t rxmpdu_stbc; /* count for stbc received */ +} wl_cnt_ver_six_t; + +typedef struct { + uint16_t version; /* see definition of WL_CNT_T_VERSION */ + uint16_t length; /* length of entire structure */ + + /* transmit stat counters */ + uint32_t txframe; /* tx data frames */ + uint32_t txbyte; /* tx data bytes */ + uint32_t txretrans; /* tx mac retransmits */ + uint32_t txerror; /* tx data errors (derived: sum of others) */ + uint32_t txctl; /* tx management frames */ + uint32_t txprshort; /* tx short preamble frames */ + uint32_t txserr; /* tx status errors */ + uint32_t txnobuf; /* tx out of buffers errors */ + uint32_t txnoassoc; /* tx discard because we're not associated */ + uint32_t txrunt; /* tx runt frames */ + uint32_t txchit; /* tx header cache hit (fastpath) */ + uint32_t txcmiss; /* tx header cache miss (slowpath) */ + + /* transmit chip error counters */ + uint32_t txuflo; /* tx fifo underflows */ + uint32_t txphyerr; /* tx phy errors (indicated in tx status) */ + uint32_t txphycrs; /* PR8861/8963 counter */ + + /* receive stat counters */ + uint32_t rxframe; /* rx data frames */ + uint32_t rxbyte; /* rx data bytes */ + uint32_t rxerror; /* rx data errors (derived: sum of others) */ + uint32_t rxctl; /* rx management frames */ + uint32_t rxnobuf; /* rx out of buffers errors */ + uint32_t rxnondata; /* rx non data frames in the data channel errors */ + uint32_t rxbadds; /* rx bad DS errors */ + uint32_t rxbadcm; /* rx bad control or management frames */ + uint32_t rxfragerr; /* rx fragmentation errors */ + uint32_t rxrunt; /* rx runt frames */ + uint32_t rxgiant; /* rx giant frames */ + uint32_t rxnoscb; /* rx no scb error */ + uint32_t rxbadproto; /* rx invalid frames */ + uint32_t rxbadsrcmac; /* rx frames with Invalid Src Mac */ + uint32_t rxbadda; /* rx frames tossed for invalid da */ + uint32_t rxfilter; /* rx frames filtered out */ + + /* receive chip error counters */ + uint32_t rxoflo; /* rx fifo overflow errors */ + uint32_t rxuflo[NFIFO]; /* rx dma descriptor underflow errors */ + + uint32_t d11cnt_txrts_off; /* d11cnt txrts value when reset d11cnt */ + uint32_t d11cnt_rxcrc_off; /* d11cnt rxcrc value when reset d11cnt */ + uint32_t d11cnt_txnocts_off; /* d11cnt txnocts value when reset d11cnt */ + + /* misc counters */ + uint32_t dmade; /* tx/rx dma descriptor errors */ + uint32_t dmada; /* tx/rx dma data errors */ + uint32_t dmape; /* tx/rx dma descriptor protocol errors */ + uint32_t reset; /* reset count */ + uint32_t tbtt; /* cnts the TBTT int's */ + uint32_t txdmawar; /* # occurrences of PR15420 workaround */ + uint32_t pkt_callback_reg_fail; /* callbacks register failure */ + + /* MAC counters: 32-bit version of d11.h's macstat_t */ + uint32_t txallfrm; /* total number of frames sent, incl. Data, ACK, RTS, CTS, + * Control Management (includes retransmissions) + */ + uint32_t txrtsfrm; /* number of RTS sent out by the MAC */ + uint32_t txctsfrm; /* number of CTS sent out by the MAC */ + uint32_t txackfrm; /* number of ACK frames sent out */ + uint32_t txdnlfrm; /* Not used */ + uint32_t txbcnfrm; /* beacons transmitted */ + uint32_t txfunfl[8]; /* per-fifo tx underflows */ + uint32_t txtplunfl; /* Template underflows (mac was too slow to transmit ACK/CTS + * or BCN) + */ + uint32_t txphyerror; /* Transmit phy error, type of error is reported in tx-status for + * driver enqueued frames + */ + uint32_t rxfrmtoolong; /* Received frame longer than legal limit (2346 bytes) */ + uint32_t rxfrmtooshrt; /* Received frame did not contain enough bytes for its frame type */ + uint32_t rxinvmachdr; /* Either the protocol version != 0 or frame type not + * data/control/management + */ + uint32_t rxbadfcs; /* number of frames for which the CRC check failed in the MAC */ + uint32_t rxbadplcp; /* parity check of the PLCP header failed */ + uint32_t rxcrsglitch; /* PHY was able to correlate the preamble but not the header */ + uint32_t rxstrt; /* Number of received frames with a good PLCP + * (i.e. passing parity check) + */ + uint32_t rxdfrmucastmbss; /* Number of received DATA frames with good FCS and matching RA */ + uint32_t rxmfrmucastmbss; /* number of received mgmt frames with good FCS and matching RA */ + uint32_t rxcfrmucast; /* number of received CNTRL frames with good FCS and matching RA */ + uint32_t rxrtsucast; /* number of unicast RTS addressed to the MAC (good FCS) */ + uint32_t rxctsucast; /* number of unicast CTS addressed to the MAC (good FCS) */ + uint32_t rxackucast; /* number of ucast ACKS received (good FCS) */ + uint32_t rxdfrmocast; /* number of received DATA frames (good FCS and not matching RA) */ + uint32_t rxmfrmocast; /* number of received MGMT frames (good FCS and not matching RA) */ + uint32_t rxcfrmocast; /* number of received CNTRL frame (good FCS and not matching RA) */ + uint32_t rxrtsocast; /* number of received RTS not addressed to the MAC */ + uint32_t rxctsocast; /* number of received CTS not addressed to the MAC */ + uint32_t rxdfrmmcast; /* number of RX Data multicast frames received by the MAC */ + uint32_t rxmfrmmcast; /* number of RX Management multicast frames received by the MAC */ + uint32_t rxcfrmmcast; /* number of RX Control multicast frames received by the MAC + * (unlikely to see these) + */ + uint32_t rxbeaconmbss; /* beacons received from member of BSS */ + uint32_t rxdfrmucastobss; /* number of unicast frames addressed to the MAC from + * other BSS (WDS FRAME) + */ + uint32_t rxbeaconobss; /* beacons received from other BSS */ + uint32_t rxrsptmout; /* Number of response timeouts for transmitted frames + * expecting a response + */ + uint32_t bcntxcancl; /* transmit beacons canceled due to receipt of beacon (IBSS) */ + uint32_t rxf0ovfl; /* Number of receive fifo 0 overflows */ + uint32_t rxf1ovfl; /* Number of receive fifo 1 overflows (obsolete) */ + uint32_t rxf2ovfl; /* Number of receive fifo 2 overflows (obsolete) */ + uint32_t txsfovfl; /* Number of transmit status fifo overflows (obsolete) */ + uint32_t pmqovfl; /* Number of PMQ overflows */ + uint32_t rxcgprqfrm; /* Number of received Probe requests that made it into + * the PRQ fifo + */ + uint32_t rxcgprsqovfl; /* Rx Probe Request Que overflow in the AP */ + uint32_t txcgprsfail; /* Tx Probe Response Fail. AP sent probe response but did + * not get ACK + */ + uint32_t txcgprssuc; /* Tx Probe Response Success (ACK was received) */ + uint32_t prs_timeout; /* Number of probe requests that were dropped from the PRQ + * fifo because a probe response could not be sent out within + * the time limit defined in M_PRS_MAXTIME + */ + uint32_t rxnack; /* obsolete */ + uint32_t frmscons; /* obsolete */ + uint32_t txnack; /* obsolete */ + uint32_t txglitch_nack; /* obsolete */ + uint32_t txburst; /* obsolete */ + + /* 802.11 MIB counters, pp. 614 of 802.11 reaff doc. */ + uint32_t txfrag; /* dot11TransmittedFragmentCount */ + uint32_t txmulti; /* dot11MulticastTransmittedFrameCount */ + uint32_t txfail; /* dot11FailedCount */ + uint32_t txretry; /* dot11RetryCount */ + uint32_t txretrie; /* dot11MultipleRetryCount */ + uint32_t rxdup; /* dot11FrameduplicateCount */ + uint32_t txrts; /* dot11RTSSuccessCount */ + uint32_t txnocts; /* dot11RTSFailureCount */ + uint32_t txnoack; /* dot11ACKFailureCount */ + uint32_t rxfrag; /* dot11ReceivedFragmentCount */ + uint32_t rxmulti; /* dot11MulticastReceivedFrameCount */ + uint32_t rxcrc; /* dot11FCSErrorCount */ + uint32_t txfrmsnt; /* dot11TransmittedFrameCount (bogus MIB?) */ + uint32_t rxundec; /* dot11WEPUndecryptableCount */ + + /* WPA2 counters (see rxundec for DecryptFailureCount) */ + uint32_t tkipmicfaill; /* TKIPLocalMICFailures */ + uint32_t tkipcntrmsr; /* TKIPCounterMeasuresInvoked */ + uint32_t tkipreplay; /* TKIPReplays */ + uint32_t ccmpfmterr; /* CCMPFormatErrors */ + uint32_t ccmpreplay; /* CCMPReplays */ + uint32_t ccmpundec; /* CCMPDecryptErrors */ + uint32_t fourwayfail; /* FourWayHandshakeFailures */ + uint32_t wepundec; /* dot11WEPUndecryptableCount */ + uint32_t wepicverr; /* dot11WEPICVErrorCount */ + uint32_t decsuccess; /* DecryptSuccessCount */ + uint32_t tkipicverr; /* TKIPICVErrorCount */ + uint32_t wepexcluded; /* dot11WEPExcludedCount */ + + uint32_t txchanrej; /* Tx frames suppressed due to channel rejection */ + uint32_t psmwds; /* Count PSM watchdogs */ + uint32_t phywatchdog; /* Count Phy watchdogs (triggered by ucode) */ + + /* MBSS counters, AP only */ + uint32_t prq_entries_handled; /* PRQ entries read in */ + uint32_t prq_undirected_entries; /* which were bcast bss & ssid */ + uint32_t prq_bad_entries; /* which could not be translated to info */ + uint32_t atim_suppress_count; /* TX suppressions on ATIM fifo */ + uint32_t bcn_template_not_ready; /* Template marked in use on send bcn ... */ + uint32_t bcn_template_not_ready_done; /* ...but "DMA done" interrupt rcvd */ + uint32_t late_tbtt_dpc; /* TBTT DPC did not happen in time */ + + /* per-rate receive stat counters */ + uint32_t rx1mbps; /* packets rx at 1Mbps */ + uint32_t rx2mbps; /* packets rx at 2Mbps */ + uint32_t rx5mbps5; /* packets rx at 5.5Mbps */ + uint32_t rx6mbps; /* packets rx at 6Mbps */ + uint32_t rx9mbps; /* packets rx at 9Mbps */ + uint32_t rx11mbps; /* packets rx at 11Mbps */ + uint32_t rx12mbps; /* packets rx at 12Mbps */ + uint32_t rx18mbps; /* packets rx at 18Mbps */ + uint32_t rx24mbps; /* packets rx at 24Mbps */ + uint32_t rx36mbps; /* packets rx at 36Mbps */ + uint32_t rx48mbps; /* packets rx at 48Mbps */ + uint32_t rx54mbps; /* packets rx at 54Mbps */ + uint32_t rx108mbps; /* packets rx at 108mbps */ + uint32_t rx162mbps; /* packets rx at 162mbps */ + uint32_t rx216mbps; /* packets rx at 216 mbps */ + uint32_t rx270mbps; /* packets rx at 270 mbps */ + uint32_t rx324mbps; /* packets rx at 324 mbps */ + uint32_t rx378mbps; /* packets rx at 378 mbps */ + uint32_t rx432mbps; /* packets rx at 432 mbps */ + uint32_t rx486mbps; /* packets rx at 486 mbps */ + uint32_t rx540mbps; /* packets rx at 540 mbps */ + + /* pkteng rx frame stats */ + uint32_t pktengrxducast; /* unicast frames rxed by the pkteng code */ + uint32_t pktengrxdmcast; /* multicast frames rxed by the pkteng code */ + + uint32_t rfdisable; /* count of radio disables */ + uint32_t bphy_rxcrsglitch; /* PHY count of bphy glitches */ + + uint32_t txexptime; /* Tx frames suppressed due to timer expiration */ + + uint32_t txmpdu_sgi; /* count for sgi transmit */ + uint32_t rxmpdu_sgi; /* count for sgi received */ + uint32_t txmpdu_stbc; /* count for stbc transmit */ + uint32_t rxmpdu_stbc; /* count for stbc received */ + + uint32_t rxundec_mcst; /* dot11WEPUndecryptableCount */ + + /* WPA2 counters (see rxundec for DecryptFailureCount) */ + uint32_t tkipmicfaill_mcst; /* TKIPLocalMICFailures */ + uint32_t tkipcntrmsr_mcst; /* TKIPCounterMeasuresInvoked */ + uint32_t tkipreplay_mcst; /* TKIPReplays */ + uint32_t ccmpfmterr_mcst; /* CCMPFormatErrors */ + uint32_t ccmpreplay_mcst; /* CCMPReplays */ + uint32_t ccmpundec_mcst; /* CCMPDecryptErrors */ + uint32_t fourwayfail_mcst; /* FourWayHandshakeFailures */ + uint32_t wepundec_mcst; /* dot11WEPUndecryptableCount */ + uint32_t wepicverr_mcst; /* dot11WEPICVErrorCount */ + uint32_t decsuccess_mcst; /* DecryptSuccessCount */ + uint32_t tkipicverr_mcst; /* TKIPICVErrorCount */ + uint32_t wepexcluded_mcst; /* dot11WEPExcludedCount */ + + uint32_t dma_hang; /* count for stbc received */ + } wl_cnt_ver_seven_t; + + +typedef struct { + uint16_t version; /* see definition of WL_CNT_T_VERSION */ + uint16_t length; /* length of entire structure */ + + /* transmit stat counters */ + uint32_t txframe; /* tx data frames */ + uint32_t txbyte; /* tx data bytes */ + uint32_t txretrans; /* tx mac retransmits */ + uint32_t txerror; /* tx data errors (derived: sum of others) */ + uint32_t txctl; /* tx management frames */ + uint32_t txprshort; /* tx short preamble frames */ + uint32_t txserr; /* tx status errors */ + uint32_t txnobuf; /* tx out of buffers errors */ + uint32_t txnoassoc; /* tx discard because we're not associated */ + uint32_t txrunt; /* tx runt frames */ + uint32_t txchit; /* tx header cache hit (fastpath) */ + uint32_t txcmiss; /* tx header cache miss (slowpath) */ + + /* transmit chip error counters */ + uint32_t txuflo; /* tx fifo underflows */ + uint32_t txphyerr; /* tx phy errors (indicated in tx status) */ + uint32_t txphycrs; /* PR8861/8963 counter */ + + /* receive stat counters */ + uint32_t rxframe; /* rx data frames */ + uint32_t rxbyte; /* rx data bytes */ + uint32_t rxerror; /* rx data errors (derived: sum of others) */ + uint32_t rxctl; /* rx management frames */ + uint32_t rxnobuf; /* rx out of buffers errors */ + uint32_t rxnondata; /* rx non data frames in the data channel errors */ + uint32_t rxbadds; /* rx bad DS errors */ + uint32_t rxbadcm; /* rx bad control or management frames */ + uint32_t rxfragerr; /* rx fragmentation errors */ + uint32_t rxrunt; /* rx runt frames */ + uint32_t rxgiant; /* rx giant frames */ + uint32_t rxnoscb; /* rx no scb error */ + uint32_t rxbadproto; /* rx invalid frames */ + uint32_t rxbadsrcmac; /* rx frames with Invalid Src Mac */ + uint32_t rxbadda; /* rx frames tossed for invalid da */ + uint32_t rxfilter; /* rx frames filtered out */ + + /* receive chip error counters */ + uint32_t rxoflo; /* rx fifo overflow errors */ + uint32_t rxuflo[NFIFO]; /* rx dma descriptor underflow errors */ + + uint32_t d11cnt_txrts_off; /* d11cnt txrts value when reset d11cnt */ + uint32_t d11cnt_rxcrc_off; /* d11cnt rxcrc value when reset d11cnt */ + uint32_t d11cnt_txnocts_off; /* d11cnt txnocts value when reset d11cnt */ + + /* misc counters */ + uint32_t dmade; /* tx/rx dma descriptor errors */ + uint32_t dmada; /* tx/rx dma data errors */ + uint32_t dmape; /* tx/rx dma descriptor protocol errors */ + uint32_t reset; /* reset count */ + uint32_t tbtt; /* cnts the TBTT int's */ + uint32_t txdmawar; /* # occurrences of PR15420 workaround */ + uint32_t pkt_callback_reg_fail; /* callbacks register failure */ + + /* MAC counters: 32-bit version of d11.h's macstat_t */ + uint32_t txallfrm; /* total number of frames sent, incl. Data, ACK, RTS, CTS, + * Control Management (includes retransmissions) + */ + uint32_t txrtsfrm; /* number of RTS sent out by the MAC */ + uint32_t txctsfrm; /* number of CTS sent out by the MAC */ + uint32_t txackfrm; /* number of ACK frames sent out */ + uint32_t txdnlfrm; /* Not used */ + uint32_t txbcnfrm; /* beacons transmitted */ + uint32_t txfunfl[6]; /* per-fifo tx underflows */ + uint32_t rxtoolate; /* receive too late */ + uint32_t txfbw; /* transmit at fallback bw (dynamic bw) */ + uint32_t txtplunfl; /* Template underflows (mac was too slow to transmit ACK/CTS + * or BCN) + */ + uint32_t txphyerror; /* Transmit phy error, type of error is reported in tx-status for + * driver enqueued frames + */ + uint32_t rxfrmtoolong; /* Received frame longer than legal limit (2346 bytes) */ + uint32_t rxfrmtooshrt; /* Received frame did not contain enough bytes for its frame type */ + uint32_t rxinvmachdr; /* Either the protocol version != 0 or frame type not + * data/control/management + */ + uint32_t rxbadfcs; /* number of frames for which the CRC check failed in the MAC */ + uint32_t rxbadplcp; /* parity check of the PLCP header failed */ + uint32_t rxcrsglitch; /* PHY was able to correlate the preamble but not the header */ + uint32_t rxstrt; /* Number of received frames with a good PLCP + * (i.e. passing parity check) + */ + uint32_t rxdfrmucastmbss; /* Number of received DATA frames with good FCS and matching RA */ + uint32_t rxmfrmucastmbss; /* number of received mgmt frames with good FCS and matching RA */ + uint32_t rxcfrmucast; /* number of received CNTRL frames with good FCS and matching RA */ + uint32_t rxrtsucast; /* number of unicast RTS addressed to the MAC (good FCS) */ + uint32_t rxctsucast; /* number of unicast CTS addressed to the MAC (good FCS) */ + uint32_t rxackucast; /* number of ucast ACKS received (good FCS) */ + uint32_t rxdfrmocast; /* number of received DATA frames (good FCS and not matching RA) */ + uint32_t rxmfrmocast; /* number of received MGMT frames (good FCS and not matching RA) */ + uint32_t rxcfrmocast; /* number of received CNTRL frame (good FCS and not matching RA) */ + uint32_t rxrtsocast; /* number of received RTS not addressed to the MAC */ + uint32_t rxctsocast; /* number of received CTS not addressed to the MAC */ + uint32_t rxdfrmmcast; /* number of RX Data multicast frames received by the MAC */ + uint32_t rxmfrmmcast; /* number of RX Management multicast frames received by the MAC */ + uint32_t rxcfrmmcast; /* number of RX Control multicast frames received by the MAC + * (unlikely to see these) + */ + uint32_t rxbeaconmbss; /* beacons received from member of BSS */ + uint32_t rxdfrmucastobss; /* number of unicast frames addressed to the MAC from + * other BSS (WDS FRAME) + */ + uint32_t rxbeaconobss; /* beacons received from other BSS */ + uint32_t rxrsptmout; /* Number of response timeouts for transmitted frames + * expecting a response + */ + uint32_t bcntxcancl; /* transmit beacons canceled due to receipt of beacon (IBSS) */ + uint32_t rxf0ovfl; /* Number of receive fifo 0 overflows */ + uint32_t rxf1ovfl; /* Number of receive fifo 1 overflows (obsolete) */ + uint32_t rxf2ovfl; /* Number of receive fifo 2 overflows (obsolete) */ + uint32_t txsfovfl; /* Number of transmit status fifo overflows (obsolete) */ + uint32_t pmqovfl; /* Number of PMQ overflows */ + uint32_t rxcgprqfrm; /* Number of received Probe requests that made it into + * the PRQ fifo + */ + uint32_t rxcgprsqovfl; /* Rx Probe Request Que overflow in the AP */ + uint32_t txcgprsfail; /* Tx Probe Response Fail. AP sent probe response but did + * not get ACK + */ + uint32_t txcgprssuc; /* Tx Probe Response Success (ACK was received) */ + uint32_t prs_timeout; /* Number of probe requests that were dropped from the PRQ + * fifo because a probe response could not be sent out within + * the time limit defined in M_PRS_MAXTIME + */ + uint32_t rxnack; /* obsolete */ + uint32_t frmscons; /* obsolete */ + uint32_t txnack; /* obsolete */ + uint32_t rxback; /* blockack rxcnt */ + uint32_t txback; /* blockack txcnt */ + + /* 802.11 MIB counters, pp. 614 of 802.11 reaff doc. */ + uint32_t txfrag; /* dot11TransmittedFragmentCount */ + uint32_t txmulti; /* dot11MulticastTransmittedFrameCount */ + uint32_t txfail; /* dot11FailedCount */ + uint32_t txretry; /* dot11RetryCount */ + uint32_t txretrie; /* dot11MultipleRetryCount */ + uint32_t rxdup; /* dot11FrameduplicateCount */ + uint32_t txrts; /* dot11RTSSuccessCount */ + uint32_t txnocts; /* dot11RTSFailureCount */ + uint32_t txnoack; /* dot11ACKFailureCount */ + uint32_t rxfrag; /* dot11ReceivedFragmentCount */ + uint32_t rxmulti; /* dot11MulticastReceivedFrameCount */ + uint32_t rxcrc; /* dot11FCSErrorCount */ + uint32_t txfrmsnt; /* dot11TransmittedFrameCount (bogus MIB?) */ + uint32_t rxundec; /* dot11WEPUndecryptableCount */ + + /* WPA2 counters (see rxundec for DecryptFailureCount) */ + uint32_t tkipmicfaill; /* TKIPLocalMICFailures */ + uint32_t tkipcntrmsr; /* TKIPCounterMeasuresInvoked */ + uint32_t tkipreplay; /* TKIPReplays */ + uint32_t ccmpfmterr; /* CCMPFormatErrors */ + uint32_t ccmpreplay; /* CCMPReplays */ + uint32_t ccmpundec; /* CCMPDecryptErrors */ + uint32_t fourwayfail; /* FourWayHandshakeFailures */ + uint32_t wepundec; /* dot11WEPUndecryptableCount */ + uint32_t wepicverr; /* dot11WEPICVErrorCount */ + uint32_t decsuccess; /* DecryptSuccessCount */ + uint32_t tkipicverr; /* TKIPICVErrorCount */ + uint32_t wepexcluded; /* dot11WEPExcludedCount */ + + uint32_t txchanrej; /* Tx frames suppressed due to channel rejection */ + uint32_t psmwds; /* Count PSM watchdogs */ + uint32_t phywatchdog; /* Count Phy watchdogs (triggered by ucode) */ + + /* MBSS counters, AP only */ + uint32_t prq_entries_handled; /* PRQ entries read in */ + uint32_t prq_undirected_entries; /* which were bcast bss & ssid */ + uint32_t prq_bad_entries; /* which could not be translated to info */ + uint32_t atim_suppress_count; /* TX suppressions on ATIM fifo */ + uint32_t bcn_template_not_ready; /* Template marked in use on send bcn ... */ + uint32_t bcn_template_not_ready_done; /* ...but "DMA done" interrupt rcvd */ + uint32_t late_tbtt_dpc; /* TBTT DPC did not happen in time */ + + /* per-rate receive stat counters */ + uint32_t rx1mbps; /* packets rx at 1Mbps */ + uint32_t rx2mbps; /* packets rx at 2Mbps */ + uint32_t rx5mbps5; /* packets rx at 5.5Mbps */ + uint32_t rx6mbps; /* packets rx at 6Mbps */ + uint32_t rx9mbps; /* packets rx at 9Mbps */ + uint32_t rx11mbps; /* packets rx at 11Mbps */ + uint32_t rx12mbps; /* packets rx at 12Mbps */ + uint32_t rx18mbps; /* packets rx at 18Mbps */ + uint32_t rx24mbps; /* packets rx at 24Mbps */ + uint32_t rx36mbps; /* packets rx at 36Mbps */ + uint32_t rx48mbps; /* packets rx at 48Mbps */ + uint32_t rx54mbps; /* packets rx at 54Mbps */ + uint32_t rx108mbps; /* packets rx at 108mbps */ + uint32_t rx162mbps; /* packets rx at 162mbps */ + uint32_t rx216mbps; /* packets rx at 216 mbps */ + uint32_t rx270mbps; /* packets rx at 270 mbps */ + uint32_t rx324mbps; /* packets rx at 324 mbps */ + uint32_t rx378mbps; /* packets rx at 378 mbps */ + uint32_t rx432mbps; /* packets rx at 432 mbps */ + uint32_t rx486mbps; /* packets rx at 486 mbps */ + uint32_t rx540mbps; /* packets rx at 540 mbps */ + + /* pkteng rx frame stats */ + uint32_t pktengrxducast; /* unicast frames rxed by the pkteng code */ + uint32_t pktengrxdmcast; /* multicast frames rxed by the pkteng code */ + + uint32_t rfdisable; /* count of radio disables */ + uint32_t bphy_rxcrsglitch; /* PHY count of bphy glitches */ + uint32_t bphy_badplcp; + + uint32_t txexptime; /* Tx frames suppressed due to timer expiration */ + + uint32_t txmpdu_sgi; /* count for sgi transmit */ + uint32_t rxmpdu_sgi; /* count for sgi received */ + uint32_t txmpdu_stbc; /* count for stbc transmit */ + uint32_t rxmpdu_stbc; /* count for stbc received */ + + uint32_t rxundec_mcst; /* dot11WEPUndecryptableCount */ + + /* WPA2 counters (see rxundec for DecryptFailureCount) */ + uint32_t tkipmicfaill_mcst; /* TKIPLocalMICFailures */ + uint32_t tkipcntrmsr_mcst; /* TKIPCounterMeasuresInvoked */ + uint32_t tkipreplay_mcst; /* TKIPReplays */ + uint32_t ccmpfmterr_mcst; /* CCMPFormatErrors */ + uint32_t ccmpreplay_mcst; /* CCMPReplays */ + uint32_t ccmpundec_mcst; /* CCMPDecryptErrors */ + uint32_t fourwayfail_mcst; /* FourWayHandshakeFailures */ + uint32_t wepundec_mcst; /* dot11WEPUndecryptableCount */ + uint32_t wepicverr_mcst; /* dot11WEPICVErrorCount */ + uint32_t decsuccess_mcst; /* DecryptSuccessCount */ + uint32_t tkipicverr_mcst; /* TKIPICVErrorCount */ + uint32_t wepexcluded_mcst; /* dot11WEPExcludedCount */ + + uint32_t dma_hang; /* count for dma hang */ + uint32_t reinit; /* count for reinit */ + + uint32_t pstatxucast; /* count of ucast frames xmitted on all psta assoc */ + uint32_t pstatxnoassoc; /* count of txnoassoc frames xmitted on all psta assoc */ + uint32_t pstarxucast; /* count of ucast frames received on all psta assoc */ + uint32_t pstarxbcmc; /* count of bcmc frames received on all psta */ + uint32_t pstatxbcmc; /* count of bcmc frames transmitted on all psta */ + + uint32_t cso_passthrough; /* hw cso required but passthrough */ + uint32_t cso_normal; /* hw cso hdr for normal process */ + uint32_t chained; /* number of frames chained */ + uint32_t chainedsz1; /* number of chain size 1 frames */ + uint32_t unchained; /* number of frames not chained */ + uint32_t maxchainsz; /* max chain size so far */ + uint32_t currchainsz; /* current chain size */ + + uint32_t rxdrop20s; /* drop secondary cnt */ + +} wl_cnt_ver_eight_t; + + +typedef struct +{ + uint16_t version; + uint16_t length; + uint32_t rxampdu_sgi; + uint32_t rxampdu_stbc; + uint32_t rxmpdu_sgi; + uint32_t rxmpdu_stbc; + uint32_t rxmcs0_40M; + uint32_t rxmcs1_40M; + uint32_t rxmcs2_40M; + uint32_t rxmcs3_40M; + uint32_t rxmcs4_40M; + uint32_t rxmcs5_40M; + uint32_t rxmcs6_40M; + uint32_t rxmcs7_40M; + uint32_t rxmcs32_40M; + uint32_t txfrmsnt_20Mlo; + uint32_t txfrmsnt_20Mup; + uint32_t txfrmsnt_40M; + uint32_t rx_20ul; +} wl_cnt_ext_t; +#define WL_RXDIV_STATS_T_VERSION 1 +typedef struct +{ + uint16_t version; + uint16_t length; + uint32_t rxant[4]; +} wl_rxdiv_stats_t; +#define WL_DELTA_STATS_T_VERSION 1 +typedef struct +{ + uint16_t version; + uint16_t length; + uint32_t txframe; + uint32_t txbyte; + uint32_t txretrans; + uint32_t txfail; + uint32_t rxframe; + uint32_t rxbyte; + uint32_t rx1mbps; + uint32_t rx2mbps; + uint32_t rx5mbps5; + uint32_t rx6mbps; + uint32_t rx9mbps; + uint32_t rx11mbps; + uint32_t rx12mbps; + uint32_t rx18mbps; + uint32_t rx24mbps; + uint32_t rx36mbps; + uint32_t rx48mbps; + uint32_t rx54mbps; + uint32_t rx108mbps; + uint32_t rx162mbps; + uint32_t rx216mbps; + uint32_t rx270mbps; + uint32_t rx324mbps; + uint32_t rx378mbps; + uint32_t rx432mbps; + uint32_t rx486mbps; + uint32_t rx540mbps; +} wl_delta_stats_t; +#define WL_WME_CNT_VERSION 1 +typedef struct +{ + uint32_t packets; + uint32_t bytes; +} wl_traffic_stats_t; +#define AC_COUNT 4 +typedef struct +{ + uint16_t version; + uint16_t length; + wl_traffic_stats_t tx[AC_COUNT]; + wl_traffic_stats_t tx_failed[AC_COUNT]; + wl_traffic_stats_t rx[AC_COUNT]; + wl_traffic_stats_t rx_failed[AC_COUNT]; + wl_traffic_stats_t forward[AC_COUNT]; + wl_traffic_stats_t tx_expired[AC_COUNT]; +} wl_wme_cnt_t; + +typedef struct wl_mkeep_alive_pkt { + uint16_t version; /* Version for mkeep_alive */ + uint16_t length; /* length of fixed parameters */ + uint32_t period_msec; /* repeat interval msecs */ + uint16_t len_bytes; /* packet length */ + uint8_t keep_alive_id; /* 0 - 3 for N = 4 */ + uint8_t data[1]; /* Packet data */ +} wl_mkeep_alive_pkt_t; + +#define WL_MKEEP_ALIVE_VERSION 1 +#define WL_MKEEP_ALIVE_FIXED_LEN offsetof(wl_mkeep_alive_pkt_t, data) +#define WL_MKEEP_ALIVE_PRECISION 500 + +#if !defined(ESTA_POSTMOGRIFY_REMOVAL) +#ifdef WLBA +#define WLC_BA_CNT_VERSION 1 +typedef struct wlc_ba_cnt +{ + uint16_t version; + uint16_t length; + uint32_t txpdu; + uint32_t txsdu; + uint32_t txfc; + uint32_t txfci; + uint32_t txretrans; + uint32_t txbatimer; + uint32_t txdrop; + uint32_t txaddbareq; + uint32_t txaddbaresp; + uint32_t txdelba; + uint32_t txba; + uint32_t txbar; + uint32_t txpad[4]; + uint32_t rxpdu; + uint32_t rxqed; + uint32_t rxdup; + uint32_t rxnobuf; + uint32_t rxaddbareq; + uint32_t rxaddbaresp; + uint32_t rxdelba; + uint32_t rxba; + uint32_t rxbar; + uint32_t rxinvba; + uint32_t rxbaholes; + uint32_t rxunexp; + uint32_t rxpad[4]; +}wlc_ba_cnt_t; +#endif +struct ampdu_tid_control +{ + uint8_t tid; + uint8_t enable; +}; +struct wl_msglevel2 +{ + uint32_t low; + uint32_t high; +}; +struct ampdu_ea_tid +{ + wl_ether_addr_t ea; + uint8_t tid; +}; +struct ampdu_retry_tid +{ + uint8_t tid; + uint8_t retry; +}; +struct ampdu_ba_sizes +{ + uint8_t ba_tx_wsize; + uint8_t ba_rx_wsize; +}; +#define DPT_DISCOVERY_MANUAL 0x01 +#define DPT_DISCOVERY_AUTO 0x02 +#define DPT_DISCOVERY_SCAN 0x04 +#define DPT_PATHSEL_AUTO 0 +#define DPT_PATHSEL_DIRECT 1 +#define DPT_PATHSEL_APPATH 2 +#define DPT_DENY_LIST_ADD 1 +#define DPT_DENY_LIST_REMOVE 2 +#define DPT_MANUAL_EP_CREATE 1 +#define DPT_MANUAL_EP_MODIFY 2 +#define DPT_MANUAL_EP_DELETE 3 +typedef struct dpt_iovar +{ + wl_ether_addr_t ea; + uint8_t mode; + uint32_t pad; +} dpt_iovar_t; +#define DPT_STATUS_ACTIVE 0x01 +#define DPT_STATUS_AES 0x02 +#define DPT_STATUS_FAILED 0x04 +#define DPT_FNAME_LEN 48 +typedef struct dpt_status +{ + uint8_t status; + uint8_t fnlen; + uint8_t name[DPT_FNAME_LEN]; + uint32_t rssi; + sta_info_t sta; +} dpt_status_t; +typedef struct dpt_list +{ + uint32_t num; + dpt_status_t status[1]; +} dpt_list_t; +typedef struct dpt_fname +{ + uint8_t len; + uint8_t name[DPT_FNAME_LEN]; +} dpt_fname_t; +#define BDD_FNAME_LEN 32 +typedef struct bdd_fname +{ + uint8_t len; + uint8_t name[BDD_FNAME_LEN]; +} bdd_fname_t; +struct ts_list +{ + int32_t count; + struct tsinfo_arg tsinfo[1]; +}; +typedef struct tspec_arg +{ + uint16_t version; + uint16_t length; + uint32_t flag; + struct tsinfo_arg tsinfo; + uint16_t nom_msdu_size; + uint16_t max_msdu_size; + uint32_t min_srv_interval; + uint32_t max_srv_interval; + uint32_t inactivity_interval; + uint32_t suspension_interval; + uint32_t srv_start_time; + uint32_t min_data_rate; + uint32_t mean_data_rate; + uint32_t peak_data_rate; + uint32_t max_burst_size; + uint32_t delay_bound; + uint32_t min_phy_rate; + uint16_t surplus_bw; + uint16_t medium_time; + uint8_t dialog_token; +} tspec_arg_t; +typedef struct tspec_per_sta_arg +{ + wl_ether_addr_t ea; + struct tspec_arg ts; +} tspec_per_sta_arg_t; +typedef struct wme_max_bandwidth +{ + uint32_t ac[AC_COUNT]; +} wme_max_bandwidth_t; +#define WL_WME_MBW_PARAMS_IO_BYTES (sizeof(wme_max_bandwidth_t)) +#define TSPEC_ARG_VERSION 2 +#define TSPEC_ARG_LENGTH 55 +#define TSPEC_DEFAULT_DIALOG_TOKEN 42 +#define TSPEC_DEFAULT_SBW_FACTOR 0x3000 +#define TSPEC_PENDING 0 +#define TSPEC_ACCEPTED 1 +#define TSPEC_REJECTED 2 +#define TSPEC_UNKNOWN 3 +#define TSPEC_STATUS_MASK 7 +#ifdef BCMCCX +#define WL_WLAN_ASSOC_REASON_NORMAL_NETWORK 0 +#define WL_WLAN_ASSOC_REASON_ROAM_FROM_CELLULAR_NETWORK 1 +#define WL_WLAN_ASSOC_REASON_ROAM_FROM_LAN 2 +#define WL_WLAN_ASSOC_REASON_MAX 2 +#endif +#ifdef WLAFTERBURNER +#define WL_SWFL_ABBFL 0x0001 +#define WL_SWFL_ABENCORE 0x0002 +#endif +#define WL_SWFL_NOHWRADIO 0x0004 +#define WL_LIFETIME_MAX 0xFFFF +typedef struct wl_lifetime +{ + uint32_t ac; + uint32_t lifetime; +} wl_lifetime_t; +typedef struct wl_chan_switch +{ + uint8_t mode; + uint8_t count; + wl_chanspec_t chspec; + uint8_t reg; +} wl_chan_switch_t; +#endif +#define WLC_ROAM_TRIGGER_DEFAULT 0 +#define WLC_ROAM_TRIGGER_BANDWIDTH 1 +#define WLC_ROAM_TRIGGER_DISTANCE 2 +#define WLC_ROAM_TRIGGER_MAX_VALUE 2 +enum +{ + PFN_LIST_ORDER, PFN_RSSI +}; +#define SORT_CRITERIA_BIT 0 +#define AUTO_NET_SWITCH_BIT 1 +#define ENABLE_BKGRD_SCAN_BIT 2 +#define IMMEDIATE_SCAN_BIT 3 +#define AUTO_CONNECT_BIT 4 +#define SORT_CRITERIA_MASK 0x01 +#define AUTO_NET_SWITCH_MASK 0x02 +#define ENABLE_BKGRD_SCAN_MASK 0x04 +#define IMMEDIATE_SCAN_MASK 0x08 +#define AUTO_CONNECT_MASK 0x10 +#define PFN_VERSION 1 +typedef struct wl_pfn_param +{ + int32_t version; + int32_t scan_freq; + int32_t lost_network_timeout; + int16_t flags; + int16_t rssi_margin; +} wl_pfn_param_t; +typedef struct wl_pfn +{ + wlc_ssid_t ssid; + int32_t bss_type; + int32_t infra; + int32_t auth; + uint32_t wpa_auth; + int32_t wsec; +#ifdef WLPFN_AUTO_CONNECT +union +{ + wl_wsec_key_t sec_key; + wsec_pmk_t wpa_sec_key; +}pfn_security; +#endif +} wl_pfn_t; +#define TOE_TX_CSUM_OL 0x00000001 +#define TOE_RX_CSUM_OL 0x00000002 +#define TOE_ERRTEST_TX_CSUM 0x00000001 +#define TOE_ERRTEST_RX_CSUM 0x00000002 +#define TOE_ERRTEST_RX_CSUM2 0x00000004 +struct toe_ol_stats_t +{ + uint32_t tx_summed; + uint32_t tx_iph_fill; + uint32_t tx_tcp_fill; + uint32_t tx_udp_fill; + uint32_t tx_icmp_fill; + uint32_t rx_iph_good; + uint32_t rx_iph_bad; + uint32_t rx_tcp_good; + uint32_t rx_tcp_bad; + uint32_t rx_udp_good; + uint32_t rx_udp_bad; + uint32_t rx_icmp_good; + uint32_t rx_icmp_bad; + uint32_t tx_tcp_errinj; + uint32_t tx_udp_errinj; + uint32_t tx_icmp_errinj; + uint32_t rx_tcp_errinj; + uint32_t rx_udp_errinj; + uint32_t rx_icmp_errinj; +}; +#define ARP_OL_AGENT 0x00000001 +#define ARP_OL_SNOOP 0x00000002 +#define ARP_OL_HOST_AUTO_REPLY 0x00000004 +#define ARP_OL_PEER_AUTO_REPLY 0x00000008 +#define ARP_ERRTEST_REPLY_PEER 0x1 +#define ARP_ERRTEST_REPLY_HOST 0x2 +#define ARP_MULTIHOMING_MAX 8 +struct arp_ol_stats_t +{ + uint32_t host_ip_entries; + uint32_t host_ip_overflow; + uint32_t arp_table_entries; + uint32_t arp_table_overflow; + uint32_t host_request; + uint32_t host_reply; + uint32_t host_service; + uint32_t peer_request; + uint32_t peer_request_drop; + uint32_t peer_reply; + uint32_t peer_reply_drop; + uint32_t peer_service; +}; +typedef struct wl_keep_alive_pkt +{ + uint32_t period_msec; + uint16_t len_bytes; + uint8_t data[1]; +} wl_keep_alive_pkt_t; +#define WL_KEEP_ALIVE_FIXED_LEN offsetof(wl_keep_alive_pkt_t, data) +typedef enum wl_pkt_filter_type +{ + WL_PKT_FILTER_TYPE_PATTERN_MATCH +} wl_pkt_filter_type_t; +#define WL_PKT_FILTER_TYPE wl_pkt_filter_type_t +typedef struct wl_pkt_filter_pattern +{ + uint32_t offset; + uint32_t size_bytes; + uint8_t mask_and_pattern[1]; +} wl_pkt_filter_pattern_t; +typedef struct wl_pkt_filter +{ + uint32_t id; + uint32_t type; + uint32_t negate_match; + union + { + wl_pkt_filter_pattern_t pattern; + } u; +} wl_pkt_filter_t; +#define WL_PKT_FILTER_FIXED_LEN offsetof(wl_pkt_filter_t, u) +#define WL_PKT_FILTER_PATTERN_FIXED_LEN offsetof(wl_pkt_filter_pattern_t, mask_and_pattern) +typedef struct wl_pkt_filter_enable +{ + uint32_t id; + uint32_t enable; +} wl_pkt_filter_enable_t; +typedef struct wl_pkt_filter_list +{ + uint32_t num; + wl_pkt_filter_t filter[1]; +} wl_pkt_filter_list_t; +#define WL_PKT_FILTER_LIST_FIXED_LEN offsetof(wl_pkt_filter_list_t, filter) +typedef struct wl_pkt_filter_stats +{ + uint32_t num_pkts_matched; + uint32_t num_pkts_forwarded; + uint32_t num_pkts_discarded; +} wl_pkt_filter_stats_t; +typedef struct wl_seq_cmd_ioctl +{ + uint32_t cmd; + uint32_t len; +} wl_seq_cmd_ioctl_t; +#define WL_SEQ_CMD_ALIGN_BYTES 4 +#define WL_SEQ_CMDS_GET_IOCTL_FILTER(cmd) \ + (((cmd) == WLC_GET_MAGIC) || \ + ((cmd) == WLC_GET_VERSION) || \ + ((cmd) == WLC_GET_AP) || \ + ((cmd) == WLC_GET_INSTANCE)) +#define WL_PKTENG_PER_TX_START 0x01 +#define WL_PKTENG_PER_TX_STOP 0x02 +#define WL_PKTENG_PER_RX_START 0x04 +#define WL_PKTENG_PER_RX_WITH_ACK_START 0x05 +#define WL_PKTENG_PER_TX_WITH_ACK_START 0x06 +#define WL_PKTENG_PER_RX_STOP 0x08 +#define WL_PKTENG_PER_MASK 0xff +#define WL_PKTENG_SYNCHRONOUS 0x100 +typedef struct wl_pkteng +{ + uint32_t flags; + uint32_t delay; + uint32_t nframes; + uint32_t length; + uint8_t seqno; + wl_ether_addr_t dest; + wl_ether_addr_t src; +} wl_pkteng_t; +#define NUM_80211b_RATES 4 +#define NUM_80211ag_RATES 8 +#define NUM_80211n_RATES 32 +#define NUM_80211_RATES (NUM_80211b_RATES+NUM_80211ag_RATES+NUM_80211n_RATES) +typedef struct wl_pkteng_stats +{ + uint32_t lostfrmcnt; + int32_t rssi; + int32_t snr; + uint16_t rxpktcnt[NUM_80211_RATES + 1]; +} wl_pkteng_stats_t; +#if !defined(BCMDONGLEHOST) || defined(BCMINTERNAL) || defined(WLTEST) +typedef struct wl_sslpnphy_papd_debug_data +{ + uint8_t psat_pwr; + uint8_t psat_indx; + uint8_t final_idx; + uint8_t start_idx; + int32_t min_phase; + int32_t voltage; + int8_t temperature; +} wl_sslpnphy_papd_debug_data_t; +typedef struct wl_sslpnphy_debug_data +{ + int16_t papdcompRe[64]; + int16_t papdcompIm[64]; +} wl_sslpnphy_debug_data_t; +typedef struct wl_sslpnphy_spbdump_data +{ + uint16_t tbl_length; + int16_t spbreal[256]; + int16_t spbimg[256]; +} wl_sslpnphy_spbdump_data_t; +typedef struct wl_sslpnphy_percal_debug_data +{ + uint32_t cur_idx; + uint32_t tx_drift; + uint8_t prev_cal_idx; + uint32_t percal_ctr; + int32_t nxt_cal_idx; + uint32_t force_1idxcal; + uint32_t onedxacl_req; + int32_t last_cal_volt; + int8_t last_cal_temp; + uint32_t vbat_ripple; + uint32_t exit_route; + int32_t volt_winner; +} wl_sslpnphy_percal_debug_data_t; +#endif +#define WL_WOWL_MAGIC (1 << 0) +#define WL_WOWL_NET (1 << 1) +#define WL_WOWL_DIS (1 << 2) +#define WL_WOWL_RETR (1 << 3) +#define WL_WOWL_BCN (1 << 4) +#define WL_WOWL_TST (1 << 5) +#define WL_WOWL_BCAST (1 << 15) +#define MAGIC_PKT_MINLEN 102 +typedef struct +{ + uint32_t masksize; + uint32_t offset; + uint32_t patternoffset; + uint32_t patternsize; +} wl_wowl_pattern_t; +typedef struct +{ + uint32_t count; + wl_wowl_pattern_t pattern[1]; +} wl_wowl_pattern_list_t; +typedef struct +{ + uint8_t pci_wakeind; + uint16_t ucode_wakeind; +} wl_wowl_wakeind_t; +typedef struct wl_txrate_class +{ + uint8_t init_rate; + uint8_t min_rate; + uint8_t max_rate; +} wl_txrate_class_t; +#if defined(DSLCPE_DELAY) +#define WL_DELAYMODE_DEFER 0 +#define WL_DELAYMODE_FORCE 1 +#define WL_DELAYMODE_AUTO 2 +#endif +#define WLC_OBSS_SCAN_PASSIVE_DWELL_DEFAULT 100 +#define WLC_OBSS_SCAN_PASSIVE_DWELL_MIN 5 +#define WLC_OBSS_SCAN_PASSIVE_DWELL_MAX 1000 +#define WLC_OBSS_SCAN_ACTIVE_DWELL_DEFAULT 20 +#define WLC_OBSS_SCAN_ACTIVE_DWELL_MIN 10 +#define WLC_OBSS_SCAN_ACTIVE_DWELL_MAX 1000 +#define WLC_OBSS_SCAN_WIDTHSCAN_INTERVAL_DEFAULT 300 +#define WLC_OBSS_SCAN_WIDTHSCAN_INTERVAL_MIN 10 +#define WLC_OBSS_SCAN_WIDTHSCAN_INTERVAL_MAX 900 +#define WLC_OBSS_SCAN_CHANWIDTH_TRANSITION_DLY_DEFAULT 5 +#define WLC_OBSS_SCAN_CHANWIDTH_TRANSITION_DLY_MIN 5 +#define WLC_OBSS_SCAN_CHANWIDTH_TRANSITION_DLY_MAX 100 +#define WLC_OBSS_SCAN_PASSIVE_TOTAL_PER_CHANNEL_DEFAULT 200 +#define WLC_OBSS_SCAN_PASSIVE_TOTAL_PER_CHANNEL_MIN 200 +#define WLC_OBSS_SCAN_PASSIVE_TOTAL_PER_CHANNEL_MAX 10000 +#define WLC_OBSS_SCAN_ACTIVE_TOTAL_PER_CHANNEL_DEFAULT 20 +#define WLC_OBSS_SCAN_ACTIVE_TOTAL_PER_CHANNEL_MIN 20 +#define WLC_OBSS_SCAN_ACTIVE_TOTAL_PER_CHANNEL_MAX 10000 +#define WLC_OBSS_SCAN_ACTIVITY_THRESHOLD_DEFAULT 25 +#define WLC_OBSS_SCAN_ACTIVITY_THRESHOLD_MIN 0 +#define WLC_OBSS_SCAN_ACTIVITY_THRESHOLD_MAX 100 +typedef struct wl_obss_scan_arg +{ + int16_t passive_dwell; + int16_t active_dwell; + int16_t bss_widthscan_interval; + int16_t passive_total; + int16_t active_total; + int16_t chanwidth_transition_delay; + int16_t activity_threshold; +} wl_obss_scan_arg_t; +#define WL_OBSS_SCAN_PARAM_LEN sizeof(wl_obss_scan_arg_t) +#define WL_MIN_NUM_OBSS_SCAN_ARG 7 +#define WL_COEX_INFO_MASK 0x07 +#define WL_COEX_INFO_REQ 0x01 +#define WL_COEX_40MHZ_INTOLERANT 0x02 +#define WL_COEX_WIDTH20 0x04 +typedef struct wl_action_obss_coex_req +{ + uint8_t info; + uint8_t num; + uint8_t ch_list[1]; +} wl_action_obss_coex_req_t; +#define MAX_RSSI_LEVELS 8 +typedef struct wl_rssi_event +{ + uint32_t rate_limit_msec; + uint8_t num_rssi_levels; + int8_t rssi_levels[MAX_RSSI_LEVELS]; +} wl_rssi_event_t; +#define WLFEATURE_DISABLE_11N 0x00000001 +#define WLFEATURE_DISABLE_11N_STBC_TX 0x00000002 +#define WLFEATURE_DISABLE_11N_STBC_RX 0x00000004 +#define WLFEATURE_DISABLE_11N_SGI_TX 0x00000008 +#define WLFEATURE_DISABLE_11N_SGI_RX 0x00000010 +#define WLFEATURE_DISABLE_11N_AMPDU_TX 0x00000020 +#define WLFEATURE_DISABLE_11N_AMPDU_RX 0x00000040 +#define WLFEATURE_DISABLE_11N_GF 0x00000080 + + + +#pragma pack(1) + +typedef struct sta_prbreq_wps_ie_hdr +{ + wl_ether_addr_t staAddr; + uint16_t ieLen; +} sta_prbreq_wps_ie_hdr_t; + +typedef struct sta_prbreq_wps_ie_data +{ + sta_prbreq_wps_ie_hdr_t hdr; + uint8_t ieData[1]; +} sta_prbreq_wps_ie_data_t; + +typedef struct sta_prbreq_wps_ie_list +{ + uint32_t totLen; + uint8_t ieDataList[1]; +} sta_prbreq_wps_ie_list_t; + + +/* EDCF related items from 802.11.h */ + +/* ACI from 802.11.h */ +#define EDCF_AIFSN_MIN 1 /* AIFSN minimum value */ +#define EDCF_AIFSN_MAX 15 /* AIFSN maximum value */ +#define EDCF_AIFSN_MASK 0x0f /* AIFSN mask */ +#define EDCF_ACM_MASK 0x10 /* ACM mask */ +#define EDCF_ACI_MASK 0x60 /* ACI mask */ +#define EDCF_ACI_SHIFT 5 /* ACI shift */ +#define EDCF_AIFSN_SHIFT 12 /* 4 MSB(0xFFF) in ifs_ctl for AC idx */ + +/* ECW from 802.11.h */ +#define EDCF_ECW_MIN 0 /* cwmin/cwmax exponent minimum value */ +#define EDCF_ECW_MAX 15 /* cwmin/cwmax exponent maximum value */ +#define EDCF_ECW2CW(exp) ((1 << (exp)) - 1) +#define EDCF_ECWMIN_MASK 0x0f /* cwmin exponent form mask */ +#define EDCF_ECWMAX_MASK 0xf0 /* cwmax exponent form mask */ +#define EDCF_ECWMAX_SHIFT 4 /* cwmax exponent form shift */ + +/* TXOP from 802.11.h */ +#define EDCF_TXOP_MIN 0 /* TXOP minimum value */ +#define EDCF_TXOP_MAX 65535 /* TXOP maximum value */ +#define EDCF_TXOP2USEC(txop) ((txop) << 5) + +struct edcf_acparam { + uint8_t ACI; + uint8_t ECW; + uint16_t TXOP; /* stored in network order (ls octet first) */ +} ; +typedef struct edcf_acparam edcf_acparam_t; + + +/* Stop packing structures */ +#pragma pack() + + + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif diff --git a/drivers/wireless/ieee80211/bcmf_sdio.c b/drivers/wireless/ieee80211/bcmf_sdio.c index dfa815863c..317102fc30 100644 --- a/drivers/wireless/ieee80211/bcmf_sdio.c +++ b/drivers/wireless/ieee80211/bcmf_sdio.c @@ -54,6 +54,8 @@ #include #include +#include "chip_constants.h" + /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ @@ -62,28 +64,38 @@ #define BCMF_DEVICE_START_DELAY_MS 10 #define BCMF_CLOCK_SETUP_DELAY_MS 500 -#define SDIO_FN1_CHIPCLKCSR 0x1000E /* Clock Control Source Register */ -#define SDIO_FN1_PULLUP 0x1000F /* Pull-up Control Register for cmd, D0-2 lines */ +/* Agent registers (common for every core) */ +#define BCMA_IOCTL 0x0408 /* IO control */ +#define BCMA_IOST 0x0500 /* IO status */ +#define BCMA_RESET_CTL 0x0800 /* Reset control */ +#define BCMA_RESET_ST 0x0804 + +#define BCMA_IOCTL_CLK 0x0001 +#define BCMA_IOCTL_FGC 0x0002 +#define BCMA_IOCTL_CORE_BITS 0x3FFC +#define BCMA_IOCTL_PME_EN 0x4000 +#define BCMA_IOCTL_BIST_EN 0x8000 + +#define BCMA_IOST_CORE_BITS 0x0FFF +#define BCMA_IOST_DMA64 0x1000 +#define BCMA_IOST_GATED_CLK 0x2000 +#define BCMA_IOST_BIST_ERROR 0x4000 +#define BCMA_IOST_BIST_DONE 0x8000 -#define SDIO_FN1_CHIPCLKCSR_FORCE_ALP 0x01 -#define SDIO_FN1_CHIPCLKCSR_FORCE_HT 0x02 -#define SDIO_FN1_CHIPCLKCSR_FORCE_ILP 0x04 -#define SDIO_FN1_CHIPCLKCSR_ALP_AVAIL_REQ 0x08 -#define SDIO_FN1_CHIPCLKCSR_HT_AVAIL_REQ 0x10 -#define SDIO_FN1_CHIPCLKCSR_FORCE_HW_CLKREQ_OFF 0x20 -#define SDIO_FN1_CHIPCLKCSR_ALP_AVAIL 0x40 -#define SDIO_FN1_CHIPCLKCSR_HT_AVAIL 0x80 +#define BCMA_RESET_CTL_RESET 0x0001 /**************************************************************************** * Private Types ****************************************************************************/ -/* This structure is contains the unique state of the Broadcom FullMAC driver */ +/* This structure contains the unique state of the Broadcom FullMAC driver */ struct bcmf_dev_s { FAR struct sdio_dev_s *sdio_dev; /* The SDIO device bound to this instance */ int minor; /* Device minor number */ + + uint32_t backplane_current_addr; /* Current function 1 backplane base addr */ }; /**************************************************************************** @@ -95,16 +107,23 @@ static int bcmf_transfer_bytes(FAR struct bcmf_dev_s *priv, bool write, uint8_t *buf, unsigned int len); static int bcmf_read_reg(FAR struct bcmf_dev_s *priv, uint8_t function, - uint32_t address, uint8_t *reg, - unsigned int len); + uint32_t address, uint8_t *reg); static int bcmf_write_reg(FAR struct bcmf_dev_s *priv, uint8_t function, - uint32_t address, uint32_t reg, - unsigned int len); + uint32_t address, uint8_t reg); + +static int bcmf_read_sbreg(FAR struct bcmf_dev_s *priv, uint32_t address, + uint32_t *reg); + +static int bcmf_write_sbreg(FAR struct bcmf_dev_s *priv, uint32_t address, + uint32_t reg); static int bcmf_probe(FAR struct bcmf_dev_s *priv); static int bcmf_hwinitialize(FAR struct bcmf_dev_s *priv); static void bcmf_hwuninitialize(FAR struct bcmf_dev_s *priv); +static int bcmf_chipinitialize(FAR struct bcmf_dev_s *priv); + +static int bcmf_set_backplane_window(FAR struct bcmf_dev_s *priv, uint32_t addr); /**************************************************************************** * Private Data @@ -130,9 +149,10 @@ int bcmf_transfer_bytes(FAR struct bcmf_dev_s *priv, bool write, function, address, *buf, buf); } - // return sdio_io_rw_extended(priv->sdio_dev, write, - // function, address, *buf, buf); - return -EINVAL; + return sdio_io_rw_extended(priv->sdio_dev, write, + function, address, true, buf, len, 1); + + // return -EINVAL; } /**************************************************************************** @@ -140,9 +160,9 @@ int bcmf_transfer_bytes(FAR struct bcmf_dev_s *priv, bool write, ****************************************************************************/ int bcmf_read_reg(FAR struct bcmf_dev_s *priv, uint8_t function, - uint32_t address, uint8_t *reg, unsigned int len) + uint32_t address, uint8_t *reg) { - return bcmf_transfer_bytes(priv, false, function, address, reg, len); + return bcmf_transfer_bytes(priv, false, function, address, reg, 1); } /**************************************************************************** @@ -150,15 +170,43 @@ int bcmf_read_reg(FAR struct bcmf_dev_s *priv, uint8_t function, ****************************************************************************/ int bcmf_write_reg(FAR struct bcmf_dev_s *priv, uint8_t function, - uint32_t address, uint32_t reg, unsigned int len) + uint32_t address, uint8_t reg) { - if (len > 4) + return bcmf_transfer_bytes(priv, true, function, address, ®, 1); +} + +/**************************************************************************** + * Name: bcmf_read_sbreg + ****************************************************************************/ + +int bcmf_read_sbreg(FAR struct bcmf_dev_s *priv, uint32_t address, + uint32_t *reg) +{ + int ret = bcmf_set_backplane_window(priv, address); + if (ret != OK) { - return -EINVAL; + return ret; } - return bcmf_transfer_bytes(priv, true, function, address, - (uint8_t*)®, len); + return bcmf_transfer_bytes(priv, false, 1, address, (uint8_t*)reg, 4); +} + +/**************************************************************************** + * Name: bcmf_write_sbreg + ****************************************************************************/ + +int bcmf_write_sbreg(FAR struct bcmf_dev_s *priv, uint32_t address, + uint32_t reg) +{ + + int ret = bcmf_set_backplane_window(priv, address); + if (ret != OK) + { + return ret; + } + + return bcmf_transfer_bytes(priv, true, 1, address, + (uint8_t*)®, 4); } /**************************************************************************** @@ -209,8 +257,10 @@ int bcmf_probe(FAR struct bcmf_dev_s *priv) /* Enable device interrupts for FN0, FN1 and FN2 */ - ret = sdio_io_rw_direct(priv->sdio_dev, true, 0, SDIO_CCCR_INTEN, - (1 << 0) | (1 << 1) | (1 << 2), NULL); + // ret = sdio_io_rw_direct(priv->sdio_dev, true, 0, SDIO_CCCR_INTEN, + // (1 << 0) | (1 << 1) | (1 << 2), NULL); + ret = bcmf_write_reg(priv, 0, SDIO_CCCR_INTEN, + (1 << 0) | (1 << 1) | (1 << 2)); if (ret != OK) { goto exit_error; @@ -230,7 +280,8 @@ int bcmf_probe(FAR struct bcmf_dev_s *priv) { up_mdelay(1); - ret = sdio_io_rw_direct(priv->sdio_dev, false, 0, SDIO_CCCR_IORDY, 0, &value); + // ret = sdio_io_rw_direct(priv->sdio_dev, false, 0, SDIO_CCCR_IORDY, 0, &value); + ret = bcmf_read_reg(priv, 0, SDIO_CCCR_IORDY, &value); if (ret != OK) { return ret; @@ -269,14 +320,14 @@ exit_error: /* Send Active Low-Power clock request */ - ret = bcmf_write_reg(priv, 1, SDIO_FN1_CHIPCLKCSR, - SDIO_FN1_CHIPCLKCSR_FORCE_HW_CLKREQ_OFF | - SDIO_FN1_CHIPCLKCSR_ALP_AVAIL_REQ | - SDIO_FN1_CHIPCLKCSR_FORCE_ALP, 1); + ret = bcmf_write_reg(priv, 1, SDIO_CHIP_CLOCK_CSR, + SBSDIO_FORCE_HW_CLKREQ_OFF | + SBSDIO_ALP_AVAIL_REQ | + SBSDIO_FORCE_ALP); if (ret != OK) { - return ret;; + return ret; } loops = 10; @@ -285,14 +336,14 @@ exit_error: uint8_t value; up_mdelay(10); - ret = bcmf_read_reg(priv, 1, SDIO_FN1_CHIPCLKCSR, &value, 1); + ret = bcmf_read_reg(priv, 1, SDIO_CHIP_CLOCK_CSR, &value); if (ret != OK) { return ret; } - if (value & SDIO_FN1_CHIPCLKCSR_ALP_AVAIL) + if (value & SBSDIO_ALP_AVAIL) { /* Active Low-Power clock is ready */ break; @@ -307,7 +358,7 @@ exit_error: /* Clear Active Low-Power clock request */ - ret = bcmf_write_reg(priv, 1, SDIO_FN1_CHIPCLKCSR, 0, 1); + ret = bcmf_write_reg(priv, 1, SDIO_CHIP_CLOCK_CSR, 0); if (ret != OK) { return ret; @@ -315,21 +366,21 @@ exit_error: /* Disable pull-ups on SDIO cmd, d0-2 lines */ - ret = bcmf_write_reg(priv, 1, SDIO_FN1_PULLUP, 0, 1); + ret = bcmf_write_reg(priv, 1, SDIO_PULL_UP, 0); if (ret != OK) { return ret; } - /* Enable oob gpio interrupt */ - - // bcmf_board_setup_oob_irq(priv->minor, bcmf_oob_irq, (void*)priv); - - /* Enable F2 interrupt only */ + /* Do chip specific initialization */ - /* Upload firmware */ + ret = bcmf_chipinitialize(priv); + if (ret != OK) + { + return ret; + } - /* Enable function 2 */ + // /* Enable function 2 */ // ret = sdio_enable_function(priv->sdio_dev, 2); // if (ret != OK) @@ -337,6 +388,33 @@ exit_error: // goto exit_error; // } + // /* Enable out-of-band interrupt signal */ + + // ret = sdio_io_rw_direct(priv->sdio_dev, true, 0, SDIOD_SEP_INT_CTL, + // SEP_INTR_CTL_MASK | SEP_INTR_CTL_EN | SEP_INTR_CTL_POL, NULL); + // if (ret != OK) + // { + // return ret; + // } + + // /* Enable function 2 interrupt */ + + // ret = sdio_enable_interrupt(priv->sdio_dev, 0); + // if (ret != OK) + // { + // return ret; + // } + // ret = sdio_enable_interrupt(priv->sdio_dev, 2); + // if (ret != OK) + // { + // return ret; + // } + + // bcmf_board_setup_oob_irq(priv->minor, bcmf_oob_irq, (void*)priv); + + /* Upload firmware */ + + _info("upload firmware\n"); return OK; } @@ -453,3 +531,61 @@ exit_free_priv: kmm_free(priv); return ret; } + +int bcmf_chipinitialize(FAR struct bcmf_dev_s *priv) +{ + int ret; + uint32_t value = 0; + + ret = bcmf_read_sbreg(priv, CHIPCOMMON_BASE_ADDRESS, &value); + if (ret != OK) + { + return ret; + } + _info("chip id is 0x%x\n", value); + + int chipid = value & 0xffff; + switch (chipid) + { + case BCM_43362_CHIP_ID: + _info("bcm43362 chip detected !!\n"); + break; + default: + _err("chip 0x%x is not supported\n", chipid); + return -ENODEV; + } + return OK; +} + +int bcmf_set_backplane_window(FAR struct bcmf_dev_s *priv, uint32_t address) +{ + int ret; + int i; + + address &= ~BACKPLANE_ADDRESS_MASK; + + for (i = 1; i < 4; i++) + { + uint8_t addr_part = (address >> (8*i)) & 0xff; + uint8_t cur_addr_part = (priv->backplane_current_addr >> (8*i)) & 0xff; + + if (addr_part != cur_addr_part) + { + /* Update current backplane base address */ + + ret = bcmf_write_reg(priv, 1, SDIO_BACKPLANE_ADDRESS_LOW+i-1, + addr_part); + + if (ret != OK) + { + return ret; + } + + priv->backplane_current_addr &= ~(0xff << (8*i)); + priv->backplane_current_addr |= addr_part << (8*i); + _info("update %d %08x\n", i, priv->backplane_current_addr); + } + } + + return OK; +} diff --git a/drivers/wireless/ieee80211/chip_constants.h b/drivers/wireless/ieee80211/chip_constants.h new file mode 100644 index 0000000000..b3f9f94c48 --- /dev/null +++ b/drivers/wireless/ieee80211/chip_constants.h @@ -0,0 +1,421 @@ +/* + * Copyright (c) 2015 Broadcom + * 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 of Broadcom nor the names of other contributors to this + * software may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * 4. This software may not be used as a standalone product, and may only be used as + * incorporated in your product or device that incorporates Broadcom wireless connectivity + * products and solely for the purpose of enabling the functionalities of such Broadcom products. + * + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + * ANY WARRANTIES OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + * WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT, ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER 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 INCLUDED_CHIP_CONSTANTS_H_ +#define INCLUDED_CHIP_CONSTANTS_H_ + +// #include "wwd_wlioctl.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/****************************************************** + * Chip Constants + ******************************************************/ + +#define BCM_43362_CHIP_ID 43362 + +/****************************************************** + * Architecture Constants + ******************************************************/ + +/* General chip stats */ +#define CHIP_RAM_SIZE 0x3C000 + +/* Backplane architecture */ +#define CHIPCOMMON_BASE_ADDRESS 0x18000000 /* Chipcommon core register region */ +#define DOT11MAC_BASE_ADDRESS 0x18001000 /* dot11mac core register region */ +#define SDIO_BASE_ADDRESS 0x18002000 /* SDIOD Device core register region */ +#define WLAN_ARMCM3_BASE_ADDRESS 0x18003000 /* ARMCM3 core register region */ +#define SOCSRAM_BASE_ADDRESS 0x18004000 /* SOCSRAM core register region */ +#define BACKPLANE_ADDRESS_MASK 0x7FFF + +#define CHIP_STA_INTERFACE 0 +#define CHIP_AP_INTERFACE 1 +#define CHIP_P2P_INTERFACE 2 + +/* Maximum value of bus data credit difference */ +#define CHIP_MAX_BUS_DATA_CREDIT_DIFF 7 + +/* Chipcommon registers */ +#define CHIPCOMMON_GPIO_CONTROL ((uint32_t) (CHIPCOMMON_BASE_ADDRESS + 0x6C) ) + +/****************************************************** + * SDIO Constants + ******************************************************/ +/* CurrentSdiodProgGuide r23 */ + +/* Base registers */ +#define SDIO_CORE ((uint32_t) (SDIO_BASE_ADDRESS + 0x00) ) +#define SDIO_INT_STATUS ((uint32_t) (SDIO_BASE_ADDRESS + 0x20) ) +#define SDIO_TO_SB_MAILBOX ((uint32_t) (SDIO_BASE_ADDRESS + 0x40) ) +#define SDIO_TO_SB_MAILBOX_DATA ((uint32_t) (SDIO_BASE_ADDRESS + 0x48) ) +#define SDIO_TO_HOST_MAILBOX_DATA ((uint32_t) (SDIO_BASE_ADDRESS + 0x4C) ) +#define SDIO_TO_SB_MAIL_BOX ((uint32_t) (SDIO_BASE_ADDRESS + 0x40) ) +#define SDIO_INT_HOST_MASK ((uint32_t) (SDIO_BASE_ADDRESS + 0x24) ) +#define SDIO_FUNCTION_INT_MASK ((uint32_t) (SDIO_BASE_ADDRESS + 0x34) ) + +/* SDIO Function 0 (SDIO Bus) register addresses */ + +/* SDIO Device CCCR offsets */ +/* TODO: What does CIS/CCCR stand for? */ +/* CCCR accesses do not require backpane clock */ +#define SDIOD_CCCR_REV ( (uint32_t) 0x00 ) /* CCCR/SDIO Revision */ +#define SDIOD_CCCR_SDREV ( (uint32_t) 0x01 ) /* SD Revision */ +#define SDIOD_CCCR_IOEN ( (uint32_t) 0x02 ) /* I/O Enable */ +#define SDIOD_CCCR_IORDY ( (uint32_t) 0x03 ) /* I/O Ready */ +#define SDIOD_CCCR_INTEN ( (uint32_t) 0x04 ) /* Interrupt Enable */ +#define SDIOD_CCCR_INTPEND ( (uint32_t) 0x05 ) /* Interrupt Pending */ +#define SDIOD_CCCR_IOABORT ( (uint32_t) 0x06 ) /* I/O Abort */ +#define SDIOD_CCCR_BICTRL ( (uint32_t) 0x07 ) /* Bus Interface control */ +#define SDIOD_CCCR_CAPABLITIES ( (uint32_t) 0x08 ) /* Card Capabilities */ +#define SDIOD_CCCR_CISPTR_0 ( (uint32_t) 0x09 ) /* Common CIS Base Address Pointer Register 0 (LSB) */ +#define SDIOD_CCCR_CISPTR_1 ( (uint32_t) 0x0A ) /* Common CIS Base Address Pointer Register 1 */ +#define SDIOD_CCCR_CISPTR_2 ( (uint32_t) 0x0B ) /* Common CIS Base Address Pointer Register 2 (MSB - only bit 1 valid)*/ +#define SDIOD_CCCR_BUSSUSP ( (uint32_t) 0x0C ) /* */ +#define SDIOD_CCCR_FUNCSEL ( (uint32_t) 0x0D ) /* */ +#define SDIOD_CCCR_EXECFLAGS ( (uint32_t) 0x0E ) /* */ +#define SDIOD_CCCR_RDYFLAGS ( (uint32_t) 0x0F ) /* */ +#define SDIOD_CCCR_BLKSIZE_0 ( (uint32_t) 0x10 ) /* Function 0 (Bus) SDIO Block Size Register 0 (LSB) */ +#define SDIOD_CCCR_BLKSIZE_1 ( (uint32_t) 0x11 ) /* Function 0 (Bus) SDIO Block Size Register 1 (MSB) */ +#define SDIOD_CCCR_POWER_CONTROL ( (uint32_t) 0x12 ) /* Power Control */ +#define SDIOD_CCCR_SPEED_CONTROL ( (uint32_t) 0x13 ) /* Bus Speed Select (control device entry into high-speed clocking mode) */ +#define SDIOD_CCCR_UHS_I ( (uint32_t) 0x14 ) /* UHS-I Support */ +#define SDIOD_CCCR_DRIVE ( (uint32_t) 0x15 ) /* Drive Strength */ +#define SDIOD_CCCR_INTEXT ( (uint32_t) 0x16 ) /* Interrupt Extension */ +#define SDIOD_SEP_INT_CTL ( (uint32_t) 0xF2 ) /* Separate Interrupt Control*/ +#define SDIOD_CCCR_F1INFO ( (uint32_t) 0x100 ) /* Function 1 (Backplane) Info */ +#define SDIOD_CCCR_F1HP ( (uint32_t) 0x102 ) /* Function 1 (Backplane) High Power */ +#define SDIOD_CCCR_F1CISPTR_0 ( (uint32_t) 0x109 ) /* Function 1 (Backplane) CIS Base Address Pointer Register 0 (LSB) */ +#define SDIOD_CCCR_F1CISPTR_1 ( (uint32_t) 0x10A ) /* Function 1 (Backplane) CIS Base Address Pointer Register 1 */ +#define SDIOD_CCCR_F1CISPTR_2 ( (uint32_t) 0x10B ) /* Function 1 (Backplane) CIS Base Address Pointer Register 2 (MSB - only bit 1 valid) */ +#define SDIOD_CCCR_F1BLKSIZE_0 ( (uint32_t) 0x110 ) /* Function 1 (Backplane) SDIO Block Size Register 0 (LSB) */ +#define SDIOD_CCCR_F1BLKSIZE_1 ( (uint32_t) 0x111 ) /* Function 1 (Backplane) SDIO Block Size Register 1 (MSB) */ +#define SDIOD_CCCR_F2INFO ( (uint32_t) 0x200 ) /* Function 2 (WLAN Data FIFO) Info */ +#define SDIOD_CCCR_F2HP ( (uint32_t) 0x202 ) /* Function 2 (WLAN Data FIFO) High Power */ +#define SDIOD_CCCR_F2CISPTR_0 ( (uint32_t) 0x209 ) /* Function 2 (WLAN Data FIFO) CIS Base Address Pointer Register 0 (LSB) */ +#define SDIOD_CCCR_F2CISPTR_1 ( (uint32_t) 0x20A ) /* Function 2 (WLAN Data FIFO) CIS Base Address Pointer Register 1 */ +#define SDIOD_CCCR_F2CISPTR_2 ( (uint32_t) 0x20B ) /* Function 2 (WLAN Data FIFO) CIS Base Address Pointer Register 2 (MSB - only bit 1 valid) */ +#define SDIOD_CCCR_F2BLKSIZE_0 ( (uint32_t) 0x210 ) /* Function 2 (WLAN Data FIFO) SDIO Block Size Register 0 (LSB) */ +#define SDIOD_CCCR_F2BLKSIZE_1 ( (uint32_t) 0x211 ) /* Function 2 (WLAN Data FIFO) SDIO Block Size Register 1 (MSB) */ +#define SDIOD_CCCR_F3INFO ( (uint32_t) 0x300 ) /* Function 3 (Bluetooth Data FIFO) Info */ +#define SDIOD_CCCR_F3HP ( (uint32_t) 0x302 ) /* Function 3 (Bluetooth Data FIFO) High Power */ +#define SDIOD_CCCR_F3CISPTR_0 ( (uint32_t) 0x309 ) /* Function 3 (Bluetooth Data FIFO) CIS Base Address Pointer Register 0 (LSB) */ +#define SDIOD_CCCR_F3CISPTR_1 ( (uint32_t) 0x30A ) /* Function 3 (Bluetooth Data FIFO) CIS Base Address Pointer Register 1 */ +#define SDIOD_CCCR_F3CISPTR_2 ( (uint32_t) 0x30B ) /* Function 3 (Bluetooth Data FIFO) CIS Base Address Pointer Register 2 (MSB - only bit 1 valid) */ +#define SDIOD_CCCR_F3BLKSIZE_0 ( (uint32_t) 0x310 ) /* Function 3 (Bluetooth Data FIFO) SDIO Block Size Register 0 (LSB) */ +#define SDIOD_CCCR_F3BLKSIZE_1 ( (uint32_t) 0x311 ) /* Function 3 (Bluetooth Data FIFO) SDIO Block Size Register 1 (MSB) */ + + +/* SDIO Function 1 (Backplane) register addresses */ +/* Addresses 0x00000000 - 0x0000FFFF are directly access the backplane + * throught the backplane window. Addresses above 0x0000FFFF are + * registers relating to backplane access, and do not require a backpane + * clock to access them + */ +#define SDIO_GPIO_SELECT ( (uint32_t) 0x10005 ) +#define SDIO_GPIO_OUTPUT ( (uint32_t) 0x10006 ) +#define SDIO_GPIO_ENABLE ( (uint32_t) 0x10007 ) +#define SDIO_FUNCTION2_WATERMARK ( (uint32_t) 0x10008 ) +#define SDIO_DEVICE_CONTROL ( (uint32_t) 0x10009 ) +#define SDIO_BACKPLANE_ADDRESS_LOW ( (uint32_t) 0x1000A ) +#define SDIO_BACKPLANE_ADDRESS_MID ( (uint32_t) 0x1000B ) +#define SDIO_BACKPLANE_ADDRESS_HIGH ( (uint32_t) 0x1000C ) +#define SDIO_FRAME_CONTROL ( (uint32_t) 0x1000D ) +#define SDIO_CHIP_CLOCK_CSR ( (uint32_t) 0x1000E ) +#define SDIO_PULL_UP ( (uint32_t) 0x1000F ) +#define SDIO_READ_FRAME_BC_LOW ( (uint32_t) 0x1001B ) +#define SDIO_READ_FRAME_BC_HIGH ( (uint32_t) 0x1001C ) + +#define I_HMB_SW_MASK ( (uint32_t) 0x000000F0 ) +#define I_HMB_FRAME_IND ( 1<<6 ) +#define FRAME_AVAILABLE_MASK I_HMB_SW_MASK + + +/****************************************************** + * SPI Constants + ******************************************************/ +/* GSPI v1 */ +#define SPI_FRAME_CONTROL ( (uint32_t) 0x1000D ) + +/* Register addresses */ +#define SPI_BUS_CONTROL ( (uint32_t) 0x0000 ) +#define SPI_RESPONSE_DELAY ( (uint32_t) 0x0001 ) +#define SPI_STATUS_ENABLE ( (uint32_t) 0x0002 ) +#define SPI_RESET_BP ( (uint32_t) 0x0003 ) /* (corerev >= 1) */ +#define SPI_INTERRUPT_REGISTER ( (uint32_t) 0x0004 ) /* 16 bits - Interrupt status */ +#define SPI_INTERRUPT_ENABLE_REGISTER ( (uint32_t) 0x0006 ) /* 16 bits - Interrupt mask */ +#define SPI_STATUS_REGISTER ( (uint32_t) 0x0008 ) /* 32 bits */ +#define SPI_FUNCTION1_INFO ( (uint32_t) 0x000C ) /* 16 bits */ +#define SPI_FUNCTION2_INFO ( (uint32_t) 0x000E ) /* 16 bits */ +#define SPI_FUNCTION3_INFO ( (uint32_t) 0x0010 ) /* 16 bits */ +#define SPI_READ_TEST_REGISTER ( (uint32_t) 0x0014 ) /* 32 bits */ +#define SPI_RESP_DELAY_F0 ( (uint32_t) 0x001c ) /* 8 bits (corerev >= 3) */ +#define SPI_RESP_DELAY_F1 ( (uint32_t) 0x001d ) /* 8 bits (corerev >= 3) */ +#define SPI_RESP_DELAY_F2 ( (uint32_t) 0x001e ) /* 8 bits (corerev >= 3) */ +#define SPI_RESP_DELAY_F3 ( (uint32_t) 0x001f ) /* 8 bits (corerev >= 3) */ + +/****************************************************** + * Bit Masks + ******************************************************/ + +/* SDIOD_CCCR_REV Bits */ +#define SDIO_REV_SDIOID_MASK ( (uint32_t) 0xF0 ) /* SDIO spec revision number */ +#define SDIO_REV_CCCRID_MASK ( (uint32_t) 0x0F ) /* CCCR format version number */ + +/* SDIOD_CCCR_SDREV Bits */ +#define SD_REV_PHY_MASK ( (uint32_t) 0x0F ) /* SD format version number */ + +/* SDIOD_CCCR_IOEN Bits */ +#define SDIO_FUNC_ENABLE_1 ( (uint32_t) 0x02 ) /* function 1 I/O enable */ +#define SDIO_FUNC_ENABLE_2 ( (uint32_t) 0x04 ) /* function 2 I/O enable */ +#define SDIO_FUNC_ENABLE_3 ( (uint32_t) 0x08 ) /* function 3 I/O enable */ + +/* SDIOD_CCCR_IORDY Bits */ +#define SDIO_FUNC_READY_1 ( (uint32_t) 0x02 ) /* function 1 I/O ready */ +#define SDIO_FUNC_READY_2 ( (uint32_t) 0x04 ) /* function 2 I/O ready */ +#define SDIO_FUNC_READY_3 ( (uint32_t) 0x08 ) /* function 3 I/O ready */ + +/* SDIOD_CCCR_INTEN Bits */ +#define INTR_CTL_MASTER_EN ( (uint32_t) 0x01 ) /* interrupt enable master */ +#define INTR_CTL_FUNC1_EN ( (uint32_t) 0x02 ) /* interrupt enable for function 1 */ +#define INTR_CTL_FUNC2_EN ( (uint32_t) 0x04 ) /* interrupt enable for function 2 */ + +/* SDIOD_SEP_INT_CTL Bits */ +#define SEP_INTR_CTL_MASK ( (uint32_t) 0x01 ) /* out-of-band interrupt mask */ +#define SEP_INTR_CTL_EN ( (uint32_t) 0x02 ) /* out-of-band interrupt output enable */ +#define SEP_INTR_CTL_POL ( (uint32_t) 0x04 ) /* out-of-band interrupt polarity */ + +/* SDIOD_CCCR_INTPEND Bits */ +#define INTR_STATUS_FUNC1 ( (uint32_t) 0x02 ) /* interrupt pending for function 1 */ +#define INTR_STATUS_FUNC2 ( (uint32_t) 0x04 ) /* interrupt pending for function 2 */ +#define INTR_STATUS_FUNC3 ( (uint32_t) 0x08 ) /* interrupt pending for function 3 */ + +/* SDIOD_CCCR_IOABORT Bits */ +#define IO_ABORT_RESET_ALL ( (uint32_t) 0x08 ) /* I/O card reset */ +#define IO_ABORT_FUNC_MASK ( (uint32_t) 0x07 ) /* abort selction: function x */ + +/* SDIOD_CCCR_BICTRL Bits */ +#define BUS_CARD_DETECT_DIS ( (uint32_t) 0x80 ) /* Card Detect disable */ +#define BUS_SPI_CONT_INTR_CAP ( (uint32_t) 0x40 ) /* support continuous SPI interrupt */ +#define BUS_SPI_CONT_INTR_EN ( (uint32_t) 0x20 ) /* continuous SPI interrupt enable */ +#define BUS_SD_DATA_WIDTH_MASK ( (uint32_t) 0x03 ) /* bus width mask */ +#define BUS_SD_DATA_WIDTH_4BIT ( (uint32_t) 0x02 ) /* bus width 4-bit mode */ +#define BUS_SD_DATA_WIDTH_1BIT ( (uint32_t) 0x00 ) /* bus width 1-bit mode */ + +/* SDIOD_CCCR_CAPABLITIES Bits */ +#define SDIO_CAP_4BLS ( (uint32_t) 0x80 ) /* 4-bit support for low speed card */ +#define SDIO_CAP_LSC ( (uint32_t) 0x40 ) /* low speed card */ +#define SDIO_CAP_E4MI ( (uint32_t) 0x20 ) /* enable interrupt between block of data in 4-bit mode */ +#define SDIO_CAP_S4MI ( (uint32_t) 0x10 ) /* support interrupt between block of data in 4-bit mode */ +#define SDIO_CAP_SBS ( (uint32_t) 0x08 ) /* support suspend/resume */ +#define SDIO_CAP_SRW ( (uint32_t) 0x04 ) /* support read wait */ +#define SDIO_CAP_SMB ( (uint32_t) 0x02 ) /* support multi-block transfer */ +#define SDIO_CAP_SDC ( (uint32_t) 0x01 ) /* Support Direct commands during multi-byte transfer */ + +/* SDIOD_CCCR_POWER_CONTROL Bits */ +#define SDIO_POWER_SMPC ( (uint32_t) 0x01 ) /* supports master power control (RO) */ +#define SDIO_POWER_EMPC ( (uint32_t) 0x02 ) /* enable master power control (allow > 200mA) (RW) */ + +/* SDIOD_CCCR_SPEED_CONTROL Bits */ +#define SDIO_SPEED_SHS ( (uint32_t) 0x01 ) /* supports high-speed [clocking] mode (RO) */ +#define SDIO_SPEED_EHS ( (uint32_t) 0x02 ) /* enable high-speed [clocking] mode (RW) */ + + + +/* GSPI */ +#define SPI_READ_TEST_REGISTER_VALUE ( (uint32_t) 0xFEEDBEAD ) +#define SPI_READ_TEST_REG_LSB ( ( ( SPI_READ_TEST_REGISTER_VALUE ) ) & 0xff ) +#define SPI_READ_TEST_REG_LSB_SFT1 ( ( ( SPI_READ_TEST_REGISTER_VALUE << 1 ) ) & 0xff ) +#define SPI_READ_TEST_REG_LSB_SFT2 ( ( ( SPI_READ_TEST_REGISTER_VALUE << 1 ) + 1 ) & 0xff ) +#define SPI_READ_TEST_REG_LSB_SFT3 ( ( ( SPI_READ_TEST_REGISTER_VALUE +1 ) << 1 ) & 0xff ) + + +/* SPI_BUS_CONTROL Bits */ +#define WORD_LENGTH_32 ( (uint32_t) 0x01 ) /* 0/1 16/32 bit word length */ +#define ENDIAN_BIG ( (uint32_t) 0x02 ) /* 0/1 Little/Big Endian */ +#define CLOCK_PHASE ( (uint32_t) 0x04 ) /* 0/1 clock phase delay */ +#define CLOCK_POLARITY ( (uint32_t) 0x08 ) /* 0/1 Idle state clock polarity is low/high */ +#define HIGH_SPEED_MODE ( (uint32_t) 0x10 ) /* 1/0 High Speed mode / Normal mode */ +#define INTR_POLARITY_HIGH ( (uint32_t) 0x20 ) /* 1/0 Interrupt active polarity is high/low */ +#define WAKE_UP ( (uint32_t) 0x80 ) /* 0/1 Wake-up command from Host to WLAN */ + +/* SPI_RESPONSE_DELAY Bit mask */ +#define RESPONSE_DELAY_MASK 0xFF /* Configurable rd response delay in multiples of 8 bits */ + +/* SPI_STATUS_ENABLE Bits */ +#define STATUS_ENABLE ( (uint32_t) 0x01 ) /* 1/0 Status sent/not sent to host after read/write */ +#define INTR_WITH_STATUS ( (uint32_t) 0x02 ) /* 0/1 Do-not / do-interrupt if status is sent */ +#define RESP_DELAY_ALL ( (uint32_t) 0x04 ) /* Applicability of resp delay to F1 or all func's read */ +#define DWORD_PKT_LEN_EN ( (uint32_t) 0x08 ) /* Packet len denoted in dwords instead of bytes */ +#define CMD_ERR_CHK_EN ( (uint32_t) 0x20 ) /* Command error check enable */ +#define DATA_ERR_CHK_EN ( (uint32_t) 0x40 ) /* Data error check enable */ + + + +/* SPI_RESET_BP Bits*/ +#define RESET_ON_WLAN_BP_RESET ( (uint32_t) 0x04 ) /* enable reset for WLAN backplane */ +#define RESET_ON_BT_BP_RESET ( (uint32_t) 0x08 ) /* enable reset for BT backplane */ +#define RESET_SPI ( (uint32_t) 0x80 ) /* reset the above enabled logic */ + + + +/* SPI_INTERRUPT_REGISTER and SPI_INTERRUPT_ENABLE_REGISTER Bits */ +#define DATA_UNAVAILABLE ( (uint32_t) 0x0001 ) /* Requested data not available; Clear by writing a "1" */ +#define F2_F3_FIFO_RD_UNDERFLOW ( (uint32_t) 0x0002 ) +#define F2_F3_FIFO_WR_OVERFLOW ( (uint32_t) 0x0004 ) +#define COMMAND_ERROR ( (uint32_t) 0x0008 ) /* Cleared by writing 1 */ +#define DATA_ERROR ( (uint32_t) 0x0010 ) /* Cleared by writing 1 */ +#define F2_PACKET_AVAILABLE ( (uint32_t) 0x0020 ) +#define F3_PACKET_AVAILABLE ( (uint32_t) 0x0040 ) +#define F1_OVERFLOW ( (uint32_t) 0x0080 ) /* Due to last write. Bkplane has pending write requests */ +#define MISC_INTR0 ( (uint32_t) 0x0100 ) +#define MISC_INTR1 ( (uint32_t) 0x0200 ) +#define MISC_INTR2 ( (uint32_t) 0x0400 ) +#define MISC_INTR3 ( (uint32_t) 0x0800 ) +#define MISC_INTR4 ( (uint32_t) 0x1000 ) +#define F1_INTR ( (uint32_t) 0x2000 ) +#define F2_INTR ( (uint32_t) 0x4000 ) +#define F3_INTR ( (uint32_t) 0x8000 ) + + + + +/* SPI_STATUS_REGISTER Bits */ +#define STATUS_DATA_NOT_AVAILABLE ( (uint32_t) 0x00000001 ) +#define STATUS_UNDERFLOW ( (uint32_t) 0x00000002 ) +#define STATUS_OVERFLOW ( (uint32_t) 0x00000004 ) +#define STATUS_F2_INTR ( (uint32_t) 0x00000008 ) +#define STATUS_F3_INTR ( (uint32_t) 0x00000010 ) +#define STATUS_F2_RX_READY ( (uint32_t) 0x00000020 ) +#define STATUS_F3_RX_READY ( (uint32_t) 0x00000040 ) +#define STATUS_HOST_CMD_DATA_ERR ( (uint32_t) 0x00000080 ) +#define STATUS_F2_PKT_AVAILABLE ( (uint32_t) 0x00000100 ) +#define STATUS_F2_PKT_LEN_MASK ( (uint32_t) 0x000FFE00 ) +#define STATUS_F2_PKT_LEN_SHIFT ( (uint32_t) 9 ) +#define STATUS_F3_PKT_AVAILABLE ( (uint32_t) 0x00100000 ) +#define STATUS_F3_PKT_LEN_MASK ( (uint32_t) 0xFFE00000 ) +#define STATUS_F3_PKT_LEN_SHIFT ( (uint32_t) 21 ) + + + + + +/* SDIO_CHIP_CLOCK_CSR Bits */ +#define SBSDIO_FORCE_ALP ( (uint32_t) 0x01 ) /* Force ALP request to backplane */ +#define SBSDIO_FORCE_HT ( (uint32_t) 0x02 ) /* Force HT request to backplane */ +#define SBSDIO_FORCE_ILP ( (uint32_t) 0x04 ) /* Force ILP request to backplane */ +#define SBSDIO_ALP_AVAIL_REQ ( (uint32_t) 0x08 ) /* Make ALP ready (power up xtal) */ +#define SBSDIO_HT_AVAIL_REQ ( (uint32_t) 0x10 ) /* Make HT ready (power up PLL) */ +#define SBSDIO_FORCE_HW_CLKREQ_OFF ( (uint32_t) 0x20 ) /* Squelch clock requests from HW */ +#define SBSDIO_ALP_AVAIL ( (uint32_t) 0x40 ) /* Status: ALP is ready */ +#define SBSDIO_HT_AVAIL ( (uint32_t) 0x80 ) /* Status: HT is ready */ +#define SBSDIO_Rev8_HT_AVAIL ( (uint32_t) 0x40 ) +#define SBSDIO_Rev8_ALP_AVAIL ( (uint32_t) 0x80 ) + + +/* SDIO_FRAME_CONTROL Bits */ +#define SFC_RF_TERM ( (uint32_t) (1 << 0) ) /* Read Frame Terminate */ +#define SFC_WF_TERM ( (uint32_t) (1 << 1) ) /* Write Frame Terminate */ +#define SFC_CRC4WOOS ( (uint32_t) (1 << 2) ) /* HW reports CRC error for write out of sync */ +#define SFC_ABORTALL ( (uint32_t) (1 << 3) ) /* Abort cancels all in-progress frames */ + +/* SDIO_TO_SB_MAIL_BOX bits corresponding to intstatus bits */ +#define SMB_NAK ( (uint32_t) (1 << 0) ) /* To SB Mailbox Frame NAK */ +#define SMB_INT_ACK ( (uint32_t) (1 << 1) ) /* To SB Mailbox Host Interrupt ACK */ +#define SMB_USE_OOB ( (uint32_t) (1 << 2) ) /* To SB Mailbox Use OOB Wakeup */ +#define SMB_DEV_INT ( (uint32_t) (1 << 3) ) /* To SB Mailbox Miscellaneous Interrupt */ + + +#define WL_CHANSPEC_BAND_MASK (0xf000) +#define WL_CHANSPEC_BAND_5G (0x1000) +#define WL_CHANSPEC_BAND_2G (0x2000) +#define WL_CHANSPEC_CTL_SB_MASK (0x0300) +#define WL_CHANSPEC_CTL_SB_LOWER (0x0100) +#define WL_CHANSPEC_CTL_SB_UPPER (0x0200) +#define WL_CHANSPEC_CTL_SB_NONE (0x0300) +#define WL_CHANSPEC_BW_MASK (0x0C00) +#define WL_CHANSPEC_BW_10 (0x0400) +#define WL_CHANSPEC_BW_20 (0x0800) +#define WL_CHANSPEC_BW_40 (0x0C00) + + +// /* CIS accesses require backpane clock */ +// +// +// #define CHIP_HAS_BSSID_CNT_IN_ASSOC_PARAMS +// #define CHIP_FIRMWARE_SUPPORTS_PM_LIMIT_IOVAR +// +// struct ether_addr; +// struct wl_join_scan_params; +// +// typedef struct wl_assoc_params +// { +// struct ether_addr bssid; +// #ifdef CHIP_HAS_BSSID_CNT_IN_ASSOC_PARAMS +// uint16_t bssid_cnt; +// #endif /* ifdef CHIP_HAS_BSSID_CNT_IN_ASSOC_PARAMS */ +// uint32_t chanspec_num; +// chanspec_t chanspec_list[1]; +// } wl_assoc_params_t; +// #define WL_ASSOC_PARAMS_FIXED_SIZE (sizeof(wl_assoc_params_t) - sizeof(wl_chanspec_t)) +// typedef wl_assoc_params_t wl_reassoc_params_t; +// #define WL_REASSOC_PARAMS_FIXED_SIZE WL_ASSOC_PARAMS_FIXED_SIZE +// typedef wl_assoc_params_t wl_join_assoc_params_t; +// #define WL_JOIN_ASSOC_PARAMS_FIXED_SIZE WL_ASSOC_PARAMS_FIXED_SIZE +// typedef struct wl_join_params +// { +// wlc_ssid_t ssid; +// struct wl_assoc_params params; +// } wl_join_params_t; +// #define WL_JOIN_PARAMS_FIXED_SIZE (sizeof(wl_join_params_t) - sizeof(wl_chanspec_t)) +// +// /* extended join params */ +// typedef struct wl_extjoin_params +// { +// wlc_ssid_t ssid; /* {0, ""}: wildcard scan */ +// struct wl_join_scan_params scan_params; +// wl_join_assoc_params_t assoc_params; /* optional field, but it must include the fixed portion of the wl_join_assoc_params_t struct when it does present. */ +// } wl_extjoin_params_t; +// #define WL_EXTJOIN_PARAMS_FIXED_SIZE (sizeof(wl_extjoin_params_t) - sizeof(chanspec_t)) +// +// typedef wl_cnt_ver_six_t wiced_counters_t; + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif /* ifndef INCLUDED_CHIP_CONSTANTS_H_ */ diff --git a/drivers/wireless/ieee80211/mmc_sdio.c b/drivers/wireless/ieee80211/mmc_sdio.c index 8674ae777c..6085afce89 100644 --- a/drivers/wireless/ieee80211/mmc_sdio.c +++ b/drivers/wireless/ieee80211/mmc_sdio.c @@ -116,87 +116,89 @@ int sdio_io_rw_direct(FAR struct sdio_dev_s *dev, bool write, return OK; } -// int sdio_io_rw_extended(FAR struct sdio_dev_s *dev, bool write, -// uint8_t function, uint32_t address, -// bool inc_addr, uint8_t *buf, -// unsigned int blocklen, unsigned int nblocks) -// { -// struct sdio_cmd53 arg; -// struct sdio_resp_R5 resp; -// int ret; -// sdio_eventset_t wkupevent; -// -// /* Setup CMD53 argument */ -// -// arg.byte_block_count = blocklen; -// arg.register_address = address & 0x1ff; -// arg.op_code = inc_addr; -// arg.function_number = function & 7; -// arg.rw_flag = write; -// -// if (nblocks <= 1 && blocklen < 512) -// { -// /* Use byte mode */ -// -// arg.block_mode = 0; -// nblocks = 1; -// } -// else -// { -// /* Use block mode */ -// -// arg.block_mode = 1; -// } -// -// /* Send CMD53 command */ -// -// SDIO_BLOCKSETUP(dev, blocklen, nblocks); -// SDIO_WAITENABLE(dev, -// SDIOWAIT_TRANSFERDONE | SDIOWAIT_TIMEOUT | SDIOWAIT_ERROR); -// -// sdio_sendcmdpoll(dev, SDIO_ACMD53, (uint32_t)arg); -// ret = SDIO_RECVR5(dev, SDIO_ACMD53, (uint32_t*)&resp); -// -// if (write) -// { -// sdio_sendcmdpoll(dev, SDIO_ACMD53, (uint32_t)arg); -// ret = SDIO_RECVR5(dev, SDIO_ACMD53, (uint32_t*)&resp); -// -// SDIO_SENDSETUP(dev, buf, blocklen * nblocks); -// wkupevent = SDIO_EVENTWAIT(dev, SDIO_CMD53_TIMEOUT_MS); -// } -// else -// { -// SDIO_RECVSETUP(dev, buf, blocklen * nblocks); -// SDIO_SENDCMD(dev, SDIO_ACMD53, (uint32_t)arg); -// -// wkupevent = SDIO_EVENTWAIT(dev, SDIO_CMD53_TIMEOUT_MS); -// ret = SDIO_RECVR5(dev, SDIO_ACMD53, (uint32_t*)&resp); -// } -// -// if (ret != OK) -// { -// _err("ERROR: SDIO_RECVR5 failed %d\n", ret); -// return ret; -// } -// -// /* Check for errors */ -// -// if (wkupevent & SDIOWAIT_TIMEOUT) -// { -// return -ETIMEDOUT; -// } -// if (resp.error || (wkupevent & SDIOWAIT_ERROR)) -// { -// return -EIO; -// } -// if (resp.function_number || resp.out_of_range) -// { -// return -EINVAL; -// } -// -// return OK; -// } +int sdio_io_rw_extended(FAR struct sdio_dev_s *dev, bool write, + uint8_t function, uint32_t address, + bool inc_addr, uint8_t *buf, + unsigned int blocklen, unsigned int nblocks) +{ + union sdio_cmd5x arg; + struct sdio_resp_R5 resp; + int ret; + sdio_eventset_t wkupevent; + + /* Setup CMD53 argument */ + + arg.cmd53.byte_block_count = blocklen; + arg.cmd53.register_address = address & 0x1ffff; + arg.cmd53.op_code = inc_addr; + arg.cmd53.function_number = function & 7; + arg.cmd53.rw_flag = write; + + if (nblocks <= 1 && blocklen < 512) + { + /* Use byte mode */ + + _info("byte mode\n"); + arg.cmd53.block_mode = 0; + nblocks = 1; + } + else + { + /* Use block mode */ + + arg.cmd53.block_mode = 1; + } + + /* Send CMD53 command */ + + SDIO_BLOCKSETUP(dev, blocklen, nblocks); + SDIO_WAITENABLE(dev, + SDIOWAIT_TRANSFERDONE | SDIOWAIT_TIMEOUT | SDIOWAIT_ERROR); + + if (write) + { + sdio_sendcmdpoll(dev, SDIO_ACMD53, (uint32_t)arg.value); + ret = SDIO_RECVR5(dev, SDIO_ACMD53, (uint32_t*)&resp); + + SDIO_SENDSETUP(dev, buf, blocklen * nblocks); + wkupevent = SDIO_EVENTWAIT(dev, SDIO_CMD53_TIMEOUT_MS); + } + else + { + _info("prep read %d\n", blocklen * nblocks); + SDIO_RECVSETUP(dev, buf, blocklen * nblocks); + SDIO_SENDCMD(dev, SDIO_ACMD53, (uint32_t)arg.value); + + wkupevent = SDIO_EVENTWAIT(dev, SDIO_CMD53_TIMEOUT_MS); + ret = SDIO_RECVR5(dev, SDIO_ACMD53, (uint32_t*)&resp); + } + + if (ret != OK) + { + _err("ERROR: SDIO_RECVR5 failed %d\n", ret); + return ret; + } + + /* Check for errors */ + + if (wkupevent & SDIOWAIT_TIMEOUT) + { + _err("timeout\n"); + return -ETIMEDOUT; + } + if (resp.flags.error || (wkupevent & SDIOWAIT_ERROR)) + { + _err("error 1\n"); + return -EIO; + } + if (resp.flags.function_number || resp.flags.out_of_range) + { + _err("error 2\n"); + return -EINVAL; + } + + return OK; +} int sdio_set_wide_bus(struct sdio_dev_s *dev) { @@ -353,3 +355,19 @@ int sdio_enable_function(FAR struct sdio_dev_s *dev, uint8_t function) } return -ETIMEDOUT; } + +int sdio_enable_interrupt(FAR struct sdio_dev_s *dev, uint8_t function) +{ + int ret; + uint8_t value; + + /* Read current Int Enable register */ + + ret = sdio_io_rw_direct(dev, false, 0, SDIO_CCCR_INTEN, 0, &value); + if (ret != OK) + { + return ret; + } + + return sdio_io_rw_direct(dev, true, 0, SDIO_CCCR_INTEN, value | (1 << function), NULL); +} -- GitLab From 4ba091933e9098db19e0ebe66ffe88a140ed2f82 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 20 Mar 2017 16:31:35 -0600 Subject: [PATCH 120/990] XMC4xxx: Fix for early bringup problems --- arch/arm/include/xmc4/chip.h | 5 +- arch/arm/src/xmc4/Kconfig | 3 + arch/arm/src/xmc4/chip/xmc4_scu.h | 114 +++++++++++++++------------ arch/arm/src/xmc4/xmc4_clockconfig.c | 6 +- arch/arm/src/xmc4/xmc4_usic.c | 31 +++++++- configs/xmc4500-relax/nsh/defconfig | 4 +- 6 files changed, 102 insertions(+), 61 deletions(-) diff --git a/arch/arm/include/xmc4/chip.h b/arch/arm/include/xmc4/chip.h index 76cd0c4cd6..c0ef4884a0 100644 --- a/arch/arm/include/xmc4/chip.h +++ b/arch/arm/include/xmc4/chip.h @@ -50,7 +50,10 @@ #if defined(CONFIG_ARCH_CHIP_XMC4500) # define XMC4_NUSIC 3 /* Three USIC modules: USCI0-2 */ - +# undef XMC4_SCU_GATING /* No clock gating registers */ +#elif defined(CONFIG_ARCH_CHIP_XMC4700) +# define XMC4_NUSIC 3 /* Three USIC modules: USCI0-2 */ +# define XMC4_SCU_GATING 1 /* Has clock gating registers */ #else # error "Unsupported XMC4xxx chip" #endif diff --git a/arch/arm/src/xmc4/Kconfig b/arch/arm/src/xmc4/Kconfig index c73e281fb5..99493b0401 100644 --- a/arch/arm/src/xmc4/Kconfig +++ b/arch/arm/src/xmc4/Kconfig @@ -13,6 +13,9 @@ choice config ARCH_CHIP_XMC4500 bool "XMC4500" +config ARCH_CHIP_XMC4700 + bool "XMC4700" + endchoice # These "hidden" settings determine is a peripheral option is available for diff --git a/arch/arm/src/xmc4/chip/xmc4_scu.h b/arch/arm/src/xmc4/chip/xmc4_scu.h index d916b8330c..38d26051b7 100644 --- a/arch/arm/src/xmc4/chip/xmc4_scu.h +++ b/arch/arm/src/xmc4/chip/xmc4_scu.h @@ -163,18 +163,20 @@ #define XMC4_SCU_EXTCLKCR_OFFSET 0x0028 /* External clock Control Register */ #define XMC4_SCU_SLEEPCR_OFFSET 0x0030 /* Sleep Control Register */ #define XMC4_SCU_DSLEEPCR_OFFSET 0x0034 /* Deep Sleep Control Register */ -#define XMC4_SCU_CGATSTAT0_OFFSET 0x0040 /* Peripheral 0 Clock Gating Status */ -#define XMC4_SCU_CGATSET0_OFFSET 0x0044 /* Peripheral 0 Clock Gating Set */ -#define XMC4_SCU_CGATCLR0_OFFSET 0x0048 /* Peripheral 0 Clock Gating Clear */ -#define XMC4_SCU_CGATSTAT1_OFFSET 0x004c /* Peripheral 1 Clock Gating Status */ -#define XMC4_SCU_CGATSET1_OFFSET 0x0050 /* Peripheral 1 Clock Gating Set */ -#define XMC4_SCU_CGATCLR1_OFFSET 0x0054 /* Peripheral 1 Clock Gating Clear */ -#define XMC4_SCU_CGATSTAT2_OFFSET 0x0058 /* Peripheral 2 Clock Gating Status */ -#define XMC4_SCU_CGATSET2_OFFSET 0x005c /* Peripheral 2 Clock Gating Set */ -#define XMC4_SCU_CGATCLR2_OFFSET 0x0060 /* Peripheral 2 Clock Gating Clear */ -#define XMC4_SCU_CGATSTAT3_OFFSET 0x0064 /* Peripheral 3 Clock Gating Status */ -#define XMC4_SCU_CGATSET3_OFFSET 0x0068 /* Peripheral 3 Clock Gating Set */ -#define XMC4_SCU_CGATCLR3_OFFSET 0x006c /* Peripheral 3 Clock Gating Clear */ +#ifdef XMC4_SCU_GATING +# define XMC4_SCU_CGATSTAT0_OFFSET 0x0040 /* Peripheral 0 Clock Gating Status */ +# define XMC4_SCU_CGATSET0_OFFSET 0x0044 /* Peripheral 0 Clock Gating Set */ +# define XMC4_SCU_CGATCLR0_OFFSET 0x0048 /* Peripheral 0 Clock Gating Clear */ +# define XMC4_SCU_CGATSTAT1_OFFSET 0x004c /* Peripheral 1 Clock Gating Status */ +# define XMC4_SCU_CGATSET1_OFFSET 0x0050 /* Peripheral 1 Clock Gating Set */ +# define XMC4_SCU_CGATCLR1_OFFSET 0x0054 /* Peripheral 1 Clock Gating Clear */ +# define XMC4_SCU_CGATSTAT2_OFFSET 0x0058 /* Peripheral 2 Clock Gating Status */ +# define XMC4_SCU_CGATSET2_OFFSET 0x005c /* Peripheral 2 Clock Gating Set */ +# define XMC4_SCU_CGATCLR2_OFFSET 0x0060 /* Peripheral 2 Clock Gating Clear */ +# define XMC4_SCU_CGATSTAT3_OFFSET 0x0064 /* Peripheral 3 Clock Gating Status */ +# define XMC4_SCU_CGATSET3_OFFSET 0x0068 /* Peripheral 3 Clock Gating Set */ +# define XMC4_SCU_CGATCLR3_OFFSET 0x006c /* Peripheral 3 Clock Gating Clear */ +#endif /* Oscillator Control SCU Registers */ @@ -292,18 +294,20 @@ #define XMC4_SCU_EXTCLKCR (XMC4_SCU_CLK_BASE+XMC4_SCU_EXTCLKCR_OFFSET) #define XMC4_SCU_SLEEPCR (XMC4_SCU_CLK_BASE+XMC4_SCU_SLEEPCR_OFFSET) #define XMC4_SCU_DSLEEPCR (XMC4_SCU_CLK_BASE+XMC4_SCU_DSLEEPCR_OFFSET) -#define XMC4_SCU_CGATSTAT0 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSTAT0_OFFSET) -#define XMC4_SCU_CGATSET0 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSET0_OFFSET) -#define XMC4_SCU_CGATCLR0 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATCLR0_OFFSET) -#define XMC4_SCU_CGATSTAT1 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSTAT1_OFFSET) -#define XMC4_SCU_CGATSET1 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSET1_OFFSET) -#define XMC4_SCU_CGATCLR1 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATCLR1_OFFSET) -#define XMC4_SCU_CGATSTAT2 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSTAT2_OFFSET) -#define XMC4_SCU_CGATSET2 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSET2_OFFSET) -#define XMC4_SCU_CGATCLR2 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATCLR2_OFFSET) -#define XMC4_SCU_CGATSTAT3 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSTAT3_OFFSET) -#define XMC4_SCU_CGATSET3 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSET3_OFFSET) -#define XMC4_SCU_CGATCLR3 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATCLR3_OFFSET) +#ifdef XMC4_SCU_GATING +# define XMC4_SCU_CGATSTAT0 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSTAT0_OFFSET) +# define XMC4_SCU_CGATSET0 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSET0_OFFSET) +# define XMC4_SCU_CGATCLR0 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATCLR0_OFFSET) +# define XMC4_SCU_CGATSTAT1 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSTAT1_OFFSET) +# define XMC4_SCU_CGATSET1 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSET1_OFFSET) +# define XMC4_SCU_CGATCLR1 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATCLR1_OFFSET) +# define XMC4_SCU_CGATSTAT2 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSTAT2_OFFSET) +# define XMC4_SCU_CGATSET2 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSET2_OFFSET) +# define XMC4_SCU_CGATCLR2 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATCLR2_OFFSET) +# define XMC4_SCU_CGATSTAT3 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSTAT3_OFFSET) +# define XMC4_SCU_CGATSET3 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATSET3_OFFSET) +# define XMC4_SCU_CGATCLR3 (XMC4_SCU_CLK_BASE+XMC4_SCU_CGATCLR3_OFFSET) +#endif /* Oscillator Control SCU Registers */ @@ -959,42 +963,50 @@ /* Peripheral 0 Clock Gating Status, Peripheral 0 Clock Gating Set, Peripheral 0 Clock Gating Clear */ -#define SCU_CGAT0_VADC (1 << 0) /* Bit 0: VADC Gating Status */ -#define SCU_CGAT0_DSD (1 << 1) /* Bit 1: DSD Gating Status */ -#define SCU_CGAT0_CCU40 (1 << 2) /* Bit 2: CCU40 Gating Status */ -#define SCU_CGAT0_CCU41 (1 << 3) /* Bit 3: CCU41 Gating Status */ -#define SCU_CGAT0_CCU42 (1 << 4) /* Bit 4: CCU42 Gating Status */ -#define SCU_CGAT0_CCU80 (1 << 7) /* Bit 7: CCU80 Gating Status */ -#define SCU_CGAT0_CCU81 (1 << 8) /* Bit 8: CCU81 Gating Status */ -#define SCU_CGAT0_POSIF0 (1 << 9) /* Bit 9: POSIF0 Gating Status */ -#define SCU_CGAT0_POSIF1 (1 << 10) /* Bit 10: POSIF1 Gating Status */ -#define SCU_CGAT0_USIC0 (1 << 11) /* Bit 11: USIC0 Gating Status */ -#define SCU_CGAT0_ERU1 (1 << 16) /* Bit 16: ERU1 Gating Status */ +#ifdef XMC4_SCU_GATING +# define SCU_CGAT0_VADC (1 << 0) /* Bit 0: VADC Gating Status */ +# define SCU_CGAT0_DSD (1 << 1) /* Bit 1: DSD Gating Status */ +# define SCU_CGAT0_CCU40 (1 << 2) /* Bit 2: CCU40 Gating Status */ +# define SCU_CGAT0_CCU41 (1 << 3) /* Bit 3: CCU41 Gating Status */ +# define SCU_CGAT0_CCU42 (1 << 4) /* Bit 4: CCU42 Gating Status */ +# define SCU_CGAT0_CCU80 (1 << 7) /* Bit 7: CCU80 Gating Status */ +# define SCU_CGAT0_CCU81 (1 << 8) /* Bit 8: CCU81 Gating Status */ +# define SCU_CGAT0_POSIF0 (1 << 9) /* Bit 9: POSIF0 Gating Status */ +# define SCU_CGAT0_POSIF1 (1 << 10) /* Bit 10: POSIF1 Gating Status */ +# define SCU_CGAT0_USIC0 (1 << 11) /* Bit 11: USIC0 Gating Status */ +# define SCU_CGAT0_ERU1 (1 << 16) /* Bit 16: ERU1 Gating Status */ +#endif /* Peripheral 1 Clock Gating Status, Peripheral 1 Clock Gating Set, Peripheral 1 Clock Gating Clear */ -#define SCU_CGAT1_CCU43 (1 << 0) /* Bit 0: CCU43 Gating Status */ -#define SCU_CGAT1_LEDTSCU0 (1 << 3) /* Bit 3: LEDTS Gating Status */ -#define SCU_CGAT1_MCAN0 (1 << 4) /* Bit 4: MultiCAN Gating Status */ -#define SCU_CGAT1_DAC (1 << 5) /* Bit 5: DAC Gating Status */ -#define SCU_CGAT1_MMCI (1 << 6) /* Bit 6: MMC Interface Gating Status */ -#define SCU_CGAT1_USIC1 (1 << 7) /* Bit 7: USIC1 Gating Status */ -#define SCU_CGAT1_USIC2 (1 << 8) /* Bit 8: USIC1 Gating Status */ -#define SCU_CGAT1_PPORTS (1 << 9) /* Bit 9: PORTS Gating Status */ +#ifdef XMC4_SCU_GATING +# define SCU_CGAT1_CCU43 (1 << 0) /* Bit 0: CCU43 Gating Status */ +# define SCU_CGAT1_LEDTSCU0 (1 << 3) /* Bit 3: LEDTS Gating Status */ +# define SCU_CGAT1_MCAN0 (1 << 4) /* Bit 4: MultiCAN Gating Status */ +# define SCU_CGAT1_DAC (1 << 5) /* Bit 5: DAC Gating Status */ +# define SCU_CGAT1_MMCI (1 << 6) /* Bit 6: MMC Interface Gating Status */ +# define SCU_CGAT1_USIC1 (1 << 7) /* Bit 7: USIC1 Gating Status */ +# define SCU_CGAT1_USIC2 (1 << 8) /* Bit 8: USIC1 Gating Status */ +# define SCU_CGAT1_PPORTS (1 << 9) /* Bit 9: PORTS Gating Status */ +#endif /* Peripheral 2 Clock Gating Status, Peripheral 2 Clock Gating Set, Peripheral 2 Clock Gating Clear */ -#define SCU_CGAT2_WDT (1 << 1) /* Bit 1: WDT Gating Status */ -#define SCU_CGAT2_ETH0 (1 << 2) /* Bit 2: ETH0 Gating Status */ -#define SCU_CGAT2_DMA0 (1 << 4) /* Bit 4: DMA0 Gating Status */ -#define SCU_CGAT2_DMA1 (1 << 5) /* Bit 5: DMA1 Gating Status */ -#define SCU_CGAT2_FCE (1 << 6) /* Bit 6: FCE Gating Status */ -#define SCU_CGAT2_USB (1 << 7) /* Bit 7: USB Gating Status */ -#define SCU_CGAT2_ECAT (1 << 10) /* Bit 10: ECAT Gating Status */ +#ifdef XMC4_SCU_GATING +# define SCU_CGAT2_WDT (1 << 1) /* Bit 1: WDT Gating Status */ +# define SCU_CGAT2_ETH0 (1 << 2) /* Bit 2: ETH0 Gating Status */ +# define SCU_CGAT2_DMA0 (1 << 4) /* Bit 4: DMA0 Gating Status */ +# define SCU_CGAT2_DMA1 (1 << 5) /* Bit 5: DMA1 Gating Status */ +# define SCU_CGAT2_FCE (1 << 6) /* Bit 6: FCE Gating Status */ +# define SCU_CGAT2_USB (1 << 7) /* Bit 7: USB Gating Status */ +# define SCU_CGAT2_ECAT (1 << 10) /* Bit 10: ECAT Gating Status */ +#endif /* Peripheral 3 Clock Gating Status, Peripheral 3 Clock Gating Set, Peripheral 3 Clock Gating Clear */ -#define SCU_CGAT3_EBU (1 << 2) /* Bit 2: EBU Gating Status */ +#ifdef XMC4_SCU_GATING +# define SCU_CGAT3_EBU (1 << 2) /* Bit 2: EBU Gating Status */ +#endif /* Oscillator Control SCU Registers */ diff --git a/arch/arm/src/xmc4/xmc4_clockconfig.c b/arch/arm/src/xmc4/xmc4_clockconfig.c index d663ea9f82..db72a3cdf9 100644 --- a/arch/arm/src/xmc4/xmc4_clockconfig.c +++ b/arch/arm/src/xmc4/xmc4_clockconfig.c @@ -313,9 +313,9 @@ void xmc4_clock_configure(void) { } - regval = getreg32(SCU_TRAP_SOSCWDGT); - regval &= ~bitset; - putreg32(regval, SCU_TRAP_SOSCWDGT); + regval = getreg32(XMC4_SCU_TRAPDIS); + regval &= ~SCU_TRAP_SOSCWDGT; + putreg32(regval, XMC4_SCU_TRAPDIS); } #else /* BOARD_PLL_CLOCKSRC_XTAL */ diff --git a/arch/arm/src/xmc4/xmc4_usic.c b/arch/arm/src/xmc4/xmc4_usic.c index 2634764240..dd69cf318d 100644 --- a/arch/arm/src/xmc4/xmc4_usic.c +++ b/arch/arm/src/xmc4/xmc4_usic.c @@ -112,6 +112,7 @@ int xmc4_enable_usic(enum usic_e usic) switch (usic) { case USIC0: +#ifdef XMC4_SCU_GATING /* Check if USIC0 is already ungated */ if ((getreg32(XMC4_SCU_CGATSTAT0) & SCU_CGAT0_USIC0) == 0) @@ -124,11 +125,16 @@ int xmc4_enable_usic(enum usic_e usic) putreg32(SCU_PR0_USIC0RS, XMC4_SCU_PRCLR0); } +#else + /* De-assert peripheral reset USIC0 */ + putreg32(SCU_PR0_USIC0RS, XMC4_SCU_PRCLR0); +#endif break; #if XMC4_NUSIC > 1 case USIC1: +#ifdef XMC4_SCU_GATING /* Check if USIC1 is already ungated */ if ((getreg32(XMC4_SCU_CGATSTAT1) & SCU_CGAT1_USIC1) == 0) @@ -141,11 +147,16 @@ int xmc4_enable_usic(enum usic_e usic) putreg32(SCU_PR1_USIC1RS, XMC4_SCU_PRCLR1); } +#else + /* De-assert peripheral reset USIC1 */ + putreg32(SCU_PR1_USIC1RS, XMC4_SCU_PRCLR1); +#endif break; #if XMC4_NUSIC > 2 case USIC2: +#ifdef XMC4_SCU_GATING /* Check if USIC2 is already ungated */ if ((getreg32(XMC4_SCU_CGATSTAT1) & SCU_CGAT1_USIC2) == 0) @@ -158,10 +169,15 @@ int xmc4_enable_usic(enum usic_e usic) putreg32(SCU_PR1_USIC2RS, XMC4_SCU_PRCLR1); } +#else + /* De-assert peripheral reset USIC2 */ - break; -#endif + putreg32(SCU_PR1_USIC2RS, XMC4_SCU_PRCLR1); #endif + break; + +#endif /* XMC4_NUSIC > 2 */ +#endif /* XMC4_NUSIC > 1 */ default: return -EINVAL; @@ -191,9 +207,11 @@ int xmc4_disable_usic(enum usic_e usic) putreg32(SCU_PR0_USIC0RS, XMC4_SCU_PRSET0); +#ifdef XMC4_SCU_GATING /* Gate USIC0 clocking */ putreg32(SCU_CGAT0_USIC0, XMC4_SCU_CGATSET0); +#endif break; #if XMC4_NUSIC > 1 @@ -202,9 +220,11 @@ int xmc4_disable_usic(enum usic_e usic) putreg32(SCU_PR1_USIC1RS, XMC4_SCU_PRSET1); +#ifdef XMC4_SCU_GATING /* Gate USIC0 clocking */ putreg32(SCU_CGAT1_USIC1, XMC4_SCU_CGATSET1); +#endif break; #if XMC4_NUSIC > 2 @@ -213,12 +233,15 @@ int xmc4_disable_usic(enum usic_e usic) putreg32(SCU_PR1_USIC2RS, XMC4_SCU_PRSET1); +#ifdef XMC4_SCU_GATING /* Gate USIC0 clocking */ putreg32(SCU_CGAT1_USIC2, XMC4_SCU_CGATSET1); - break; -#endif #endif + break; + +#endif /* XMC4_NUSIC > 2 */ +#endif /* XMC4_NUSIC > 1 */ default: return -EINVAL; diff --git a/configs/xmc4500-relax/nsh/defconfig b/configs/xmc4500-relax/nsh/defconfig index f938e18bc4..d554365209 100644 --- a/configs/xmc4500-relax/nsh/defconfig +++ b/configs/xmc4500-relax/nsh/defconfig @@ -250,8 +250,8 @@ CONFIG_BOOT_RUNFROMFLASH=y # # Boot Memory Configuration # -CONFIG_RAM_START=0x20400000 -CONFIG_RAM_SIZE=393216 +CONFIG_RAM_START=0x20000000 +CONFIG_RAM_SIZE=65536 # CONFIG_ARCH_HAVE_SDRAM is not set # -- GitLab From b9e29d108373e5fd0f300a47c4a9bdb2173d4b3f Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 20 Mar 2017 17:08:09 -0600 Subject: [PATCH 121/990] XMC4xxx: Clean up memory map --- arch/arm/include/xmc4/chip.h | 6 ++ arch/arm/src/xmc4/Kconfig | 3 + arch/arm/src/xmc4/chip/xmc4_memorymap.h | 106 +++++++++++++----------- 3 files changed, 68 insertions(+), 47 deletions(-) diff --git a/arch/arm/include/xmc4/chip.h b/arch/arm/include/xmc4/chip.h index c0ef4884a0..5c3fcdabfa 100644 --- a/arch/arm/include/xmc4/chip.h +++ b/arch/arm/include/xmc4/chip.h @@ -51,9 +51,15 @@ #if defined(CONFIG_ARCH_CHIP_XMC4500) # define XMC4_NUSIC 3 /* Three USIC modules: USCI0-2 */ # undef XMC4_SCU_GATING /* No clock gating registers */ +# define XMC4_NECATN 0 /* No EtherCAT support */ #elif defined(CONFIG_ARCH_CHIP_XMC4700) # define XMC4_NUSIC 3 /* Three USIC modules: USCI0-2 */ # define XMC4_SCU_GATING 1 /* Has clock gating registers */ +# define XMC4_NECATN 0 /* No EtherCAT support */ +#elif defined(CONFIG_ARCH_CHIP_XMC4700) +# define XMC4_NUSIC 3 /* Three USIC modules: USCI0-2 */ +# define XMC4_SCU_GATING 1 /* Has clock gating registers */ +# define XMC4_NECATN 1 /* One EtherCAT module */ #else # error "Unsupported XMC4xxx chip" #endif diff --git a/arch/arm/src/xmc4/Kconfig b/arch/arm/src/xmc4/Kconfig index 99493b0401..f50652cd96 100644 --- a/arch/arm/src/xmc4/Kconfig +++ b/arch/arm/src/xmc4/Kconfig @@ -16,6 +16,9 @@ config ARCH_CHIP_XMC4500 config ARCH_CHIP_XMC4700 bool "XMC4700" +config ARCH_CHIP_XMC4800 + bool "XMC4700" + endchoice # These "hidden" settings determine is a peripheral option is available for diff --git a/arch/arm/src/xmc4/chip/xmc4_memorymap.h b/arch/arm/src/xmc4/chip/xmc4_memorymap.h index fb8dcbf183..a2df7e405c 100644 --- a/arch/arm/src/xmc4/chip/xmc4_memorymap.h +++ b/arch/arm/src/xmc4/chip/xmc4_memorymap.h @@ -79,58 +79,58 @@ * USCI - Universal Serial Interface */ -#define XMC4_PBA0_BASE 0x40000000 -#define XMC4_VADC_BASE 0x40004000 +#define XMC4_PBA0_BASE 0x40000000 /* PBA0 */ +#define XMC4_VADC_BASE 0x40004000 /* VADC */ #define XMC4_VADC_G0_BASE 0x40004400 #define XMC4_VADC_G1_BASE 0x40004800 #define XMC4_VADC_G2_BASE 0x40004c00 #define XMC4_VADC_G3_BASE 0x40005000 -#define XMC4_DSD_BASE 0x40008000 +#define XMC4_DSD_BASE 0x40008000 /* DSD */ #define XMC4_DSD_CH0_BASE 0x40008100 #define XMC4_DSD_CH1_BASE 0x40008200 #define XMC4_DSD_CH2_BASE 0x40008300 #define XMC4_DSD_CH3_BASE 0x40008400 -#define XMC4_CCU40_BASE 0x4000c000 +#define XMC4_CCU40_BASE 0x4000c000 /* CCU40 */ #define XMC4_CCU40_CC40_BASE 0x4000c100 #define XMC4_CCU40_CC41_BASE 0x4000c200 #define XMC4_CCU40_CC42_BASE 0x4000c300 #define XMC4_CCU40_CC43_BASE 0x4000c400 -#define XMC4_CCU41_BASE 0x40010000 +#define XMC4_CCU41_BASE 0x40010000 /* CCU41 */ #define XMC4_CCU41_CC40_BASE 0x40010100 #define XMC4_CCU41_CC41_BASE 0x40010200 #define XMC4_CCU41_CC42_BASE 0x40010300 #define XMC4_CCU41_CC43_BASE 0x40010400 -#define XMC4_CCU42_BASE 0x40014000 +#define XMC4_CCU42_BASE 0x40014000 /* CCU42 */ #define XMC4_CCU42_CC40_BASE 0x40014100 #define XMC4_CCU42_CC41_BASE 0x40014200 #define XMC4_CCU42_CC42_BASE 0x40014300 #define XMC4_CCU42_CC43_BASE 0x40014400 -#define XMC4_CCU80_BASE 0x40020000 +#define XMC4_CCU80_BASE 0x40020000 /* CCU80 */ #define XMC4_CCU80_CC80_BASE 0x40020100 #define XMC4_CCU80_CC81_BASE 0x40020200 #define XMC4_CCU80_CC82_BASE 0x40020300 #define XMC4_CCU80_CC83_BASE 0x40020400 -#define XMC4_CCU81_BASE 0x40024000 +#define XMC4_CCU81_BASE 0x40024000 /* CCU81 */ #define XMC4_CCU81_CC80_BASE 0x40024100 #define XMC4_CCU81_CC81_BASE 0x40024200 #define XMC4_CCU81_CC82_BASE 0x40024300 #define XMC4_CCU81_CC83_BASE 0x40024400 -#define XMC4_POSIF0_BASE 0x40028000 -#define XMC4_POSIF1_BASE 0x4002c000 -#define XMC4_USIC0_BASE 0x40030000 +#define XMC4_POSIF0_BASE 0x40028000 /* POSIF0 */ +#define XMC4_POSIF1_BASE 0x4002c000 /* POSIF1 */ +#define XMC4_USIC0_BASE 0x40030000 /* USIC0 */ #define XMC4_USIC0_CH0_BASE 0x40030000 #define XMC4_USIC0_CH1_BASE 0x40030200 #define XMC4_USIC0_RAM_BASE 0x40030400 -#define XMC4_ERU1_BASE 0x40044000 +#define XMC4_ERU1_BASE 0x40044000 /* ERU1 */ -#define XMC4_PBA1_BASE 0x48000000 -#define XMC4_CCU43_BASE 0x48004000 +#define XMC4_PBA1_BASE 0x48000000 /* PBA1 */ +#define XMC4_CCU43_BASE 0x48004000 /* CCU43 */ #define XMC4_CCU43_CC40_BASE 0x48004100 #define XMC4_CCU43_CC41_BASE 0x48004200 #define XMC4_CCU43_CC42_BASE 0x48004300 #define XMC4_CCU43_CC43_BASE 0x48004400 -#define XMC4_LEDTS0_BASE 0x48010000 -#define XMC4_CAN_BASE 0x48014000 +#define XMC4_LEDTS0_BASE 0x48010000 /* LEDTS0 */ +#define XMC4_CAN_BASE 0x48014000 /* MultiCAN */ #define XMC4_CAN_NODE0_BASE 0x48014200 #define XMC4_CAN_NODE1_BASE 0x48014300 #define XMC4_CAN_NODE2_BASE 0x48014400 @@ -138,18 +138,18 @@ #define XMC4_CAN_NODE4_BASE 0x48014600 #define XMC4_CAN_NODE5_BASE 0x48014700 #define XMC4_CAN_MO_BASE 0x48015000 -#define XMC4_DAC_BASE 0x48018000 -#define XMC4_SDMMC_BASE 0x4801c000 -#define XMC4_USIC1_BASE 0x48020000 +#define XMC4_DAC_BASE 0x48018000 /* DAC */ +#define XMC4_SDMMC_BASE 0x4801c000 /* SDMMC */ +#define XMC4_USIC1_BASE 0x48020000 /* USIC1 */ #define XMC4_USIC1_CH0_BASE 0x48020000 #define XMC4_USIC1_CH1_BASE 0x48020200 #define XMC4_USIC1_RAM_BASE 0x48020400 -#define XMC4_USIC2_BASE 0x48024000 +#define XMC4_USIC2_BASE 0x48024000 /* USIC2 */ #define XMC4_USIC2_CH0_BASE 0x48024000 #define XMC4_USIC2_CH1_BASE 0x48024200 #define XMC4_USIC2_RAM_BASE 0x48024400 #define XMC4_PORT_BASE(n) (0x48028000 + ((n) << 8)) -#define XMC4_PORT0_BASE 0x48028000 +#define XMC4_PORT0_BASE 0x48028000 /* PORTS */ #define XMC4_PORT1_BASE 0x48028100 #define XMC4_PORT2_BASE 0x48028200 #define XMC4_PORT3_BASE 0x48028300 @@ -162,7 +162,8 @@ #define XMC4_PORT14_BASE 0x48028e00 #define XMC4_PORT15_BASE 0x48028f00 -#define XMC4_SCU_GENERAL_BASE 0x50004000 +#define XMC4_PBA2_BASE 0x50000000 /* PBA2 */ +#define XMC4_SCU_GENERAL_BASE 0x50004000 /* SCU & RTC */ #define XMC4_ETH0_CON_BASE 0x50004040 #define XMC4_SCU_INTERRUPT_BASE 0x50004074 #define XMC4_SDMMC_CON_BASE 0x500040b4 @@ -177,9 +178,28 @@ #define XMC4_ERU0_BASE 0x50004800 #define XMC4_DLR_BASE 0x50004900 #define XMC4_RTC_BASE 0x50004a00 -#define XMC4_WDT_BASE 0x50008000 -#define XMC4_ETH0_BASE 0x5000c000 -#define XMC4_USB0_BASE 0x50040000 +#define XMC4_WDT_BASE 0x50008000 /* WDT */ +#define XMC4_ETH0_BASE 0x5000c000 /* ETH */ +#define XMC4_GPDMA0_CH0_BASE 0x50014000 /* GPDMA0 */ +#define XMC4_GPDMA0_CH1_BASE 0x50014058 +#define XMC4_GPDMA0_CH2_BASE 0x500140b0 +#define XMC4_GPDMA0_CH3_BASE 0x50014108 +#define XMC4_GPDMA0_CH4_BASE 0x50014160 +#define XMC4_GPDMA0_CH5_BASE 0x500141b8 +#define XMC4_GPDMA0_CH6_BASE 0x50014210 +#define XMC4_GPDMA0_CH7_BASE 0x50014268 +#define XMC4_GPDMA0_BASE 0x500142c0 +#define XMC4_GPDMA1_CH0_BASE 0x50018000 /* GPDMA1 */ +#define XMC4_GPDMA1_CH1_BASE 0x50018058 +#define XMC4_GPDMA1_CH2_BASE 0x500180b0 +#define XMC4_GPDMA1_CH3_BASE 0x50018108 +#define XMC4_GPDMA1_BASE 0x500182c0 +#define XMC4_FCE_BASE 0x50020000 /* FCE */ +#define XMC4_FCE_KE0_BASE 0x50020020 +#define XMC4_FCE_KE1_BASE 0x50020040 +#define XMC4_FCE_KE2_BASE 0x50020060 +#define XMC4_FCE_KE3_BASE 0x50020080 +#define XMC4_USB0_BASE 0x50040000 /* USB0 */ #define XMC4_USB0_CH0_BASE 0x50040500 #define XMC4_USB0_CH1_BASE 0x50040520 #define XMC4_USB0_CH2_BASE 0x50040540 @@ -201,30 +221,22 @@ #define XMC4_USB0_EP4_BASE 0x50040980 #define XMC4_USB0_EP5_BASE 0x500409a0 #define XMC4_USB0_EP6_BASE 0x500409c0 -#define XMC4_GPDMA0_CH0_BASE 0x50014000 -#define XMC4_GPDMA0_CH1_BASE 0x50014058 -#define XMC4_GPDMA0_CH2_BASE 0x500140b0 -#define XMC4_GPDMA0_CH3_BASE 0x50014108 -#define XMC4_GPDMA0_CH4_BASE 0x50014160 -#define XMC4_GPDMA0_CH5_BASE 0x500141b8 -#define XMC4_GPDMA0_CH6_BASE 0x50014210 -#define XMC4_GPDMA0_CH7_BASE 0x50014268 -#define XMC4_GPDMA0_BASE 0x500142c0 -#define XMC4_GPDMA1_CH0_BASE 0x50018000 -#define XMC4_GPDMA1_CH1_BASE 0x50018058 -#define XMC4_GPDMA1_CH2_BASE 0x500180b0 -#define XMC4_GPDMA1_CH3_BASE 0x50018108 -#define XMC4_GPDMA1_BASE 0x500182c0 -#define XMC4_FCE_BASE 0x50020000 -#define XMC4_FCE_KE0_BASE 0x50020020 -#define XMC4_FCE_KE1_BASE 0x50020040 -#define XMC4_FCE_KE2_BASE 0x50020060 -#define XMC4_FCE_KE3_BASE 0x50020080 +#define XMC4_USB0_EP6_BASE 0x50100000 /* ECAT0 */ -#define XMC4_PMU0_BASE 0x58000500 +#define XMC4_PMU0_BASE 0x58000000 /* PMU0 registers */ #define XMC4_FLASH0_BASE 0x58001000 -#define XMC4_PREF_BASE 0x58004000 -#define XMC4_EBU_BASE 0x58008000 +#define XMC4_PREF_BASE 0x58004000 /* PMU0 prefetch */ +#define XMC4_EBU_BASE 0x58008000 /* EBU registers */ + +#define XMC4_EBUMEM_CS0 0x60000000 /* EBU memory CS0 */ +#define XMC4_EBUMEM_CS1 0x64000000 /* EBU memory CS1 */ +#define XMC4_EBUMEM_CS2 0x68000000 /* EBU memory CS2 */ +#define XMC4_EBUMEM_CS3 0x6c000000 /* EBU memory CS3 */ + +#define XMC4_EBUDEV_CS0 0xa0000000 /* EBU devices CS0 */ +#define XMC4_EBUDEV_CS1 0xa4000000 /* EBU devices CS1 */ +#define XMC4_EBUDEV_CS2 0xa8000000 /* EBU devices CS2 */ +#define XMC4_EBUDEV_CS3 0xac000000 /* EBU devices CS3 */ #define XMC4_PPB_BASE 0xe000e000 -- GitLab From 886dadae0aa4994cb092003a0c60a1423b90b409 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 20 Mar 2017 18:10:23 -0600 Subject: [PATCH 122/990] XMC4xxx: Minor updates to naming and comments --- arch/arm/include/xmc4/chip.h | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/arch/arm/include/xmc4/chip.h b/arch/arm/include/xmc4/chip.h index 5c3fcdabfa..6507917fe6 100644 --- a/arch/arm/include/xmc4/chip.h +++ b/arch/arm/include/xmc4/chip.h @@ -51,23 +51,23 @@ #if defined(CONFIG_ARCH_CHIP_XMC4500) # define XMC4_NUSIC 3 /* Three USIC modules: USCI0-2 */ # undef XMC4_SCU_GATING /* No clock gating registers */ -# define XMC4_NECATN 0 /* No EtherCAT support */ +# define XMC4_NECAT 0 /* No EtherCAT support */ #elif defined(CONFIG_ARCH_CHIP_XMC4700) # define XMC4_NUSIC 3 /* Three USIC modules: USCI0-2 */ # define XMC4_SCU_GATING 1 /* Has clock gating registers */ -# define XMC4_NECATN 0 /* No EtherCAT support */ +# define XMC4_NECAT 0 /* No EtherCAT support */ #elif defined(CONFIG_ARCH_CHIP_XMC4700) # define XMC4_NUSIC 3 /* Three USIC modules: USCI0-2 */ # define XMC4_SCU_GATING 1 /* Has clock gating registers */ -# define XMC4_NECATN 1 /* One EtherCAT module */ +# define XMC4_NECAT 1 /* One EtherCAT module */ #else # error "Unsupported XMC4xxx chip" #endif /* NVIC priority levels *************************************************************/ -/* Each priority field holds a priority value, 0-15. The lower the value, the greater - * the priority of the corresponding interrupt. The XMC4500 implements only - * bits[7:2] of this field, bits[1:0] read as zero and ignore writes. +/* Each priority field holds a priority value. The lower the value, the greater the + * priority of the corresponding interrupt. The XMC4500 implements only bits[7:2] + * of this field, bits[1:0] read as zero and ignore writes. */ #define NVIC_SYSH_PRIORITY_MIN 0xfc /* All bits[7:2] set is minimum priority */ -- GitLab From 591f91ebd33b2107880fdafbcca0c4b1d96a3677 Mon Sep 17 00:00:00 2001 From: Masayuki Ishikawa Date: Tue, 21 Mar 2017 15:30:23 +0900 Subject: [PATCH 123/990] drivers/lcd/st7565.c: Extend to include support for the AQM_1248A --- drivers/lcd/Kconfig | 6 ++++++ drivers/lcd/st7565.c | 21 +++++++++++++++++++++ drivers/lcd/st7565.h | 4 ++++ 3 files changed, 31 insertions(+) diff --git a/drivers/lcd/Kconfig b/drivers/lcd/Kconfig index b3abcaeabd..565ab07301 100644 --- a/drivers/lcd/Kconfig +++ b/drivers/lcd/Kconfig @@ -48,6 +48,7 @@ config LCD_NOGETRUN config LCD_MAXCONTRAST int "LCD maximum contrast" + default 31 if AQM_1248A default 63 if NOKIA6100_S1D15G10 || LCD_SHARP_MEMLCD default 127 if NOKIA6100_PCF8833 default 255 if LCD_P14201 || LCD_LCD1602 @@ -596,6 +597,9 @@ config NHD_C12864KGZ config ERC_12864_3 bool "like ERC12864-3" +config AQM_1248A + bool "like AQM1248A" + endchoice config ST7565_NINTERFACES @@ -613,6 +617,7 @@ config ST7565_XRES config ST7565_YRES int "ST7565 Y Resolution" + default 48 if AQM_1248A default 64 ---help--- Specifies the Y resolution of the LCD. @@ -625,6 +630,7 @@ config ST7565_MIRROR_X config ST7565_MIRROR_Y bool "ST7565 apply mirror on Y" + default y if AQM_1248A default n ---help--- Mirror Y on LCD. diff --git a/drivers/lcd/st7565.c b/drivers/lcd/st7565.c index 0e52b58a3e..1153c1568b 100644 --- a/drivers/lcd/st7565.c +++ b/drivers/lcd/st7565.c @@ -1030,6 +1030,27 @@ FAR struct lcd_dev_s *st7565_initialize(FAR struct st7565_lcd_s *lcd, (void)st7565_send_one_data(priv, ST7565_SETEVREG(0x24)); (void)st7565_send_one_data(priv, ST7565_SETSTARTLINE); +#elif defined(CONFIG_AQM_1248A) + + (void)st7565_send_one_data(priv, ST7565_DISPOFF); + (void)st7565_send_one_data(priv, ST7565_ADCNORMAL); + (void)st7565_send_one_data(priv, ST7565_SETCOMREVERSE); + (void)st7565_send_one_data(priv, ST7565_BIAS_1_7); + + (void)st7565_send_one_data(priv, ST7565_POWERCTRL_B); + up_mdelay(2); + (void)st7565_send_one_data(priv, ST7565_POWERCTRL_BR); + up_mdelay(2); + (void)st7565_send_one_data(priv, ST7565_POWERCTRL_BRF); + + (void)st7565_send_one_data(priv, ST7565_REG_RES_4_5); + (void)st7565_send_one_data(priv, ST7565_SETEVMODE); + (void)st7565_send_one_data(priv, ST7565_SETEVREG(0x1c)); + (void)st7565_send_one_data(priv, ST7565_DISPRAM); + (void)st7565_send_one_data(priv, ST7565_SETSTARTLINE); + (void)st7565_send_one_data(priv, ST7565_DISPNORMAL); + (void)st7565_send_one_data(priv, ST7565_DISPON); + #else # error "No initialization sequence selected" #endif diff --git a/drivers/lcd/st7565.h b/drivers/lcd/st7565.h index 0855f5e8ec..e4788379b9 100644 --- a/drivers/lcd/st7565.h +++ b/drivers/lcd/st7565.h @@ -100,6 +100,10 @@ #define ST7565_POWERCTRL_VR 0x2b /* 0x2b: Only the voltage regulator circuit and the * voltage follower circuit are used */ +#define ST7565_POWERCTRL_B 0x2c /* 0x2c: Booster=ON */ +#define ST7565_POWERCTRL_BR 0x2e /* 0x2e: Booster=ON V/R=ON */ +#define ST7565_POWERCTRL_BRF 0x2f /* 0x23: Booster=ON V/R=ON V/F=ON */ + #define ST7565_POWERCTRL_INT 0x2f /* 0x2f: Only the internal power supply is used */ /* Regulation Resistior ratio V0 = (1+Rb/Ra)*Vev */ -- GitLab From c3d9b86662ceec2f8e9e3c6fe0092fb7f11e0aa5 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Tue, 21 Mar 2017 07:12:07 -0600 Subject: [PATCH 124/990] input/mxt: prevent overriding i2c transfer return value put_reg/get_reg function was overriding i2c transfer error code with i2creset return value, that lead to OK status although actual transfer failed. Signed-off-by: Juha Niskanen Reported-by: Harri Luhtala --- drivers/input/mxt.c | 44 +++++++++++++++++++++++++++++--------------- 1 file changed, 29 insertions(+), 15 deletions(-) diff --git a/drivers/input/mxt.c b/drivers/input/mxt.c index f19c2bb0be..dcd26a2b19 100644 --- a/drivers/input/mxt.c +++ b/drivers/input/mxt.c @@ -88,6 +88,10 @@ #define INVALID_POSITION 0x1000 +/* Maximum number of retries */ + +#define MAX_RETRIES 3 + /* Get a 16-bit value in little endian order (not necessarily aligned). The * source data is in little endian order. The host byte order does not * matter in this case. @@ -311,7 +315,7 @@ static int mxt_getreg(FAR struct mxt_dev_s *priv, uint16_t regaddr, /* Try up to three times to read the register */ - for (retries = 1; retries <= 3; retries++) + for (retries = 1; retries <= MAX_RETRIES; retries++) { iinfo("retries=%d regaddr=%04x buflen=%d\n", retries, regaddr, buflen); @@ -342,15 +346,20 @@ static int mxt_getreg(FAR struct mxt_dev_s *priv, uint16_t regaddr, if (ret < 0) { #ifdef CONFIG_I2C_RESET - /* Perhaps the I2C bus is locked up? Try to shake the bus free */ - - iwarn("WARNING: I2C_TRANSFER failed: %d ... Resetting\n", ret); + /* Perhaps the I2C bus is locked up? Try to shake the bus free. + * Don't bother with the reset if this was the last attempt. + */ - ret = I2C_RESET(priv->i2c); - if (ret < 0) + if (retries < MAX_RETRIES) { - ierr("ERROR: I2C_RESET failed: %d\n", ret); - break; + iwarn("WARNING: I2C_TRANSFER failed: %d ... Resetting\n", ret); + + ret = I2C_RESET(priv->i2c); + if (ret < 0) + { + ierr("ERROR: I2C_RESET failed: %d\n", ret); + break; + } } #else ierr("ERROR: I2C_TRANSFER failed: %d\n", ret); @@ -385,7 +394,7 @@ static int mxt_putreg(FAR struct mxt_dev_s *priv, uint16_t regaddr, /* Try up to three times to read the register */ - for (retries = 1; retries <= 3; retries++) + for (retries = 1; retries <= MAX_RETRIES; retries++) { iinfo("retries=%d regaddr=%04x buflen=%d\n", retries, regaddr, buflen); @@ -416,14 +425,19 @@ static int mxt_putreg(FAR struct mxt_dev_s *priv, uint16_t regaddr, if (ret < 0) { #ifdef CONFIG_I2C_RESET - /* Perhaps the I2C bus is locked up? Try to shake the bus free */ - - iwarn("WARNING: I2C_TRANSFER failed: %d ... Resetting\n", ret); + /* Perhaps the I2C bus is locked up? Try to shake the bus free. + * Don't bother with the reset if this was the last attempt. + */ - ret = I2C_RESET(priv->i2c); - if (ret < 0) + if (retries < MAX_RETRIES) { - ierr("ERROR: I2C_RESET failed: %d\n", ret); + iwarn("WARNING: I2C_TRANSFER failed: %d ... Resetting\n", ret); + + ret = I2C_RESET(priv->i2c); + if (ret < 0) + { + ierr("ERROR: I2C_RESET failed: %d\n", ret); + } } #else ierr("ERROR: I2C_TRANSFER failed: %d\n", ret); -- GitLab From 3872055daa9e9d8410a3e356a0a61248239ed43f Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 21 Mar 2017 07:20:45 -0600 Subject: [PATCH 125/990] drivers/audio/wm8904: WM8904 has same problem as that fixed by Juha Niskanen in the MaxTouch driver. --- drivers/audio/wm8904.c | 52 ++++++++++++++++++++++++++++-------------- drivers/input/mxt.c | 2 +- 2 files changed, 36 insertions(+), 18 deletions(-) diff --git a/drivers/audio/wm8904.c b/drivers/audio/wm8904.c index 4489ae0f22..23da3ce9a9 100644 --- a/drivers/audio/wm8904.c +++ b/drivers/audio/wm8904.c @@ -3,7 +3,7 @@ * * Audio device driver for Wolfson Microelectronics WM8904 Audio codec. * - * Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved. + * Copyright (C) 2014, 2016-2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * References: @@ -73,6 +73,14 @@ #include "wm8904.h" +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Maximum number of retries */ + +#define MAX_RETRIES 3 + /**************************************************************************** * Private Function Prototypes ****************************************************************************/ @@ -251,7 +259,7 @@ uint16_t wm8904_readreg(FAR struct wm8904_dev_s *priv, uint8_t regaddr) /* Try up to three times to read the register */ - for (retries = 1; retries <= 3; retries++) + for (retries = 1; retries <= MAX_RETRIES; retries++) { struct i2c_msg_s msg[2]; uint8_t data[2]; @@ -281,15 +289,20 @@ uint16_t wm8904_readreg(FAR struct wm8904_dev_s *priv, uint8_t regaddr) if (ret < 0) { #ifdef CONFIG_I2C_RESET - /* Perhaps the I2C bus is locked up? Try to shake the bus free */ - - audwarn("WARNING: I2C_TRANSFER failed: %d ... Resetting\n", ret); + /* Perhaps the I2C bus is locked up? Try to shake the bus free. + * Don't bother with the reset if this was the last attempt. + */ - ret = I2C_RESET(priv->i2c); - if (ret < 0) + if (retries < MAX_RETRIES) { - auderr("ERROR: I2C_RESET failed: %d\n", ret); - break; + audwarn("WARNING: I2C_TRANSFER failed: %d ... Resetting\n", ret); + + ret = I2C_RESET(priv->i2c); + if (ret < 0) + { + auderr("ERROR: I2C_RESET failed: %d\n", ret); + break; + } } #else auderr("ERROR: I2C_TRANSFER failed: %d\n", ret); @@ -338,7 +351,7 @@ static void wm8904_writereg(FAR struct wm8904_dev_s *priv, uint8_t regaddr, /* Try up to three times to read the register */ - for (retries = 1; retries <= 3; retries++) + for (retries = 1; retries <= MAX_RETRIES; retries++) { uint8_t data[3]; int ret; @@ -357,15 +370,20 @@ static void wm8904_writereg(FAR struct wm8904_dev_s *priv, uint8_t regaddr, if (ret < 0) { #ifdef CONFIG_I2C_RESET - /* Perhaps the I2C bus is locked up? Try to shake the bus free */ - - audwarn("WARNING: i2c_write failed: %d ... Resetting\n", ret); + /* Perhaps the I2C bus is locked up? Try to shake the bus free. + * Don't bother with the reset if this was the last attempt. + */ - ret = I2C_RESET(priv->i2c); - if (ret < 0) + if (retries < MAX_RETRIES) { - auderr("ERROR: I2C_RESET failed: %d\n", ret); - break; + audwarn("WARNING: i2c_write failed: %d ... Resetting\n", ret); + + ret = I2C_RESET(priv->i2c); + if (ret < 0) + { + auderr("ERROR: I2C_RESET failed: %d\n", ret); + break; + } } #else auderr("ERROR: I2C_TRANSFER failed: %d\n", ret); diff --git a/drivers/input/mxt.c b/drivers/input/mxt.c index dcd26a2b19..e115285171 100644 --- a/drivers/input/mxt.c +++ b/drivers/input/mxt.c @@ -1,7 +1,7 @@ /**************************************************************************** * drivers/input/mxt.c * - * Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved. + * Copyright (C) 2014, 2016-2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without -- GitLab From 805a4f65e97f1f082bb66f8c5f2a7cd684620a40 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 21 Mar 2017 09:31:44 -0600 Subject: [PATCH 126/990] XMC4xxx: Fixes to HIB domain setup, GPIO pin configuration. --- arch/arm/include/xmc4/xmc4500_irq.h | 2 +- arch/arm/src/xmc4/chip/xmc4_memorymap.h | 2 +- arch/arm/src/xmc4/chip/xmc4_ports.h | 4 ++-- arch/arm/src/xmc4/xmc4_clockconfig.c | 8 ++++---- arch/arm/src/xmc4/xmc4_gpio.h | 8 ++++---- 5 files changed, 12 insertions(+), 12 deletions(-) diff --git a/arch/arm/include/xmc4/xmc4500_irq.h b/arch/arm/include/xmc4/xmc4500_irq.h index dfd21d6c21..b35a1b3f8a 100644 --- a/arch/arm/include/xmc4/xmc4500_irq.h +++ b/arch/arm/include/xmc4/xmc4500_irq.h @@ -184,7 +184,7 @@ #define XMC4_IRQ_SDMMC_SR0 (XMC4_IRQ_FIRST+106) /* 106: SDMMC, SR0 */ #define XMC4_IRQ_USB0_SR0 (XMC4_IRQ_FIRST+107) /* 107: USB, SR0 */ #define XMC4_IRQ_ETH0_SR0 (XMC4_IRQ_FIRST+108) /* 108: Ethernet, module 0, SR0 */ -#define XMC4_IRQ_RESVD109 (XMC4_IRQ_FIRST+109) /* 109: Reserved */ +#define XMC4_IRQ_ECAT0_SR0 (XMC4_IRQ_FIRST+109) /* 109: EtherCAT, module 0, SR0 */ #define XMC4_IRQ_GPCMA1_SR0 (XMC4_IRQ_FIRST+110) /* 110: GPDMA1, SR0 */ #define XMC4_IRQ_RESVD111 (XMC4_IRQ_FIRST+111) /* 111: Reserved */ diff --git a/arch/arm/src/xmc4/chip/xmc4_memorymap.h b/arch/arm/src/xmc4/chip/xmc4_memorymap.h index a2df7e405c..a326460cc7 100644 --- a/arch/arm/src/xmc4/chip/xmc4_memorymap.h +++ b/arch/arm/src/xmc4/chip/xmc4_memorymap.h @@ -221,7 +221,7 @@ #define XMC4_USB0_EP4_BASE 0x50040980 #define XMC4_USB0_EP5_BASE 0x500409a0 #define XMC4_USB0_EP6_BASE 0x500409c0 -#define XMC4_USB0_EP6_BASE 0x50100000 /* ECAT0 */ +#define XMC4_ECAT0_BASE 0x50100000 /* ECAT0 */ #define XMC4_PMU0_BASE 0x58000000 /* PMU0 registers */ #define XMC4_FLASH0_BASE 0x58001000 diff --git a/arch/arm/src/xmc4/chip/xmc4_ports.h b/arch/arm/src/xmc4/chip/xmc4_ports.h index bdd90c2902..d42665b908 100644 --- a/arch/arm/src/xmc4/chip/xmc4_ports.h +++ b/arch/arm/src/xmc4/chip/xmc4_ports.h @@ -71,7 +71,7 @@ #define XMC4_PORT_OUT_OFFSET 0x0000 /* Port Output Register */ #define XMC4_PORT_OMR_OFFSET 0x0004 /* Port Output Modification Register */ -#define XMC4_PORT_IOCR_OFFSET(n) (0x0010 + ((n) & 3)) +#define XMC4_PORT_IOCR_OFFSET(n) (0x0010 + ((n) & ~3)) #define XMC4_PORT_IOCR0_OFFSET 0x0010 /* Port Input/Output Control Register 0 */ #define XMC4_PORT_IOCR4_OFFSET 0x0014 /* Port Input/Output Control Register 4 */ #define XMC4_PORT_IOCR8_OFFSET 0x0018 /* Port Input/Output Control Register 8 */ @@ -79,7 +79,7 @@ #define XMC4_PORT_IN_OFFSET 0x0024 /* Port Input Register */ -#define XMC4_PORT_PDR_OFFSET(n) (0x0010 + (((n) >> 1) & 3)) +#define XMC4_PORT_PDR_OFFSET(n) (0x0010 + (((n) >> 1) & ~3)) #define XMC4_PORT_PDR0_OFFSET 0x0040 /* Port Pad Driver Mode 0 Register */ #define XMC4_PORT_PDR1_OFFSET 0x0044 /* Port Pad Driver Mode 1 Register */ diff --git a/arch/arm/src/xmc4/xmc4_clockconfig.c b/arch/arm/src/xmc4/xmc4_clockconfig.c index db72a3cdf9..a28cf7fd51 100644 --- a/arch/arm/src/xmc4/xmc4_clockconfig.c +++ b/arch/arm/src/xmc4/xmc4_clockconfig.c @@ -182,9 +182,9 @@ void xmc4_clock_configure(void) regval = getreg32(XMC4_SCU_PWRSTAT); if ((regval & SCU_PWR_HIBEN) == 0) { - regval = getreg32(XMC4_SCU_PWRSET); - regval |= SCU_PWR_HIBEN; - putreg32(regval, XMC4_SCU_PWRSTAT); + /* Enable the HIB domain */ + + putreg32(SCU_PWR_HIBEN, XMC4_SCU_PWRSET); /* Wait until HIB domain is enabled */ @@ -193,7 +193,7 @@ void xmc4_clock_configure(void) } } - /* Remove the reset only if HIB domain were in a state of reset */ + /* Remove the reset only if HIB domain was in a state of reset */ regval = getreg32(XMC4_SCU_RSTSTAT); if ((regval & SCU_RSTSTAT_HIBRS) != 0) diff --git a/arch/arm/src/xmc4/xmc4_gpio.h b/arch/arm/src/xmc4/xmc4_gpio.h index 4595fe6a79..0dce7af73c 100644 --- a/arch/arm/src/xmc4/xmc4_gpio.h +++ b/arch/arm/src/xmc4/xmc4_gpio.h @@ -79,8 +79,8 @@ # define GPIO_OUTPUT_ALT4 (IOCR_OUTPUT_ALT4 << GPIO_PINTYPE_SHIFT) # define _GPIO_OUTPUT_BIT (16 << GPIO_PINTYPE_SHIFT) -# define GPIO_ISINPUT(p) (((p) & _GPIO_OUTPUT_BIT) != 0) -# define GPIO_ISOUTPUT(p) (((p) & _GPIO_OUTPUT_BIT) == 0) +# define GPIO_ISINPUT(p) (((p) & _GPIO_OUTPUT_BIT) == 0) +# define GPIO_ISOUTPUT(p) (((p) & _GPIO_OUTPUT_BIT) != 0) /* Pin type modifier: * @@ -160,7 +160,7 @@ */ #define GPIO_PORT_SHIFT (4) /* Bit 4-7: Port number */ -#define GPIO_PORT_MASK (7 << GPIO_PORT_SHIFT) +#define GPIO_PORT_MASK (15 << GPIO_PORT_SHIFT) # define GPIO_PORT0 (0 << GPIO_PORT_SHIFT) # define GPIO_PORT1 (1 << GPIO_PORT_SHIFT) # define GPIO_PORT2 (2 << GPIO_PORT_SHIFT) @@ -180,7 +180,7 @@ */ #define GPIO_PIN_SHIFT (0) /* Bits 0-3: GPIO pin: 0-15 */ -#define GPIO_PIN_MASK (31 << GPIO_PIN_SHIFT) +#define GPIO_PIN_MASK (15 << GPIO_PIN_SHIFT) #define GPIO_PIN0 (0 << GPIO_PIN_SHIFT) #define GPIO_PIN1 (1 << GPIO_PIN_SHIFT) #define GPIO_PIN2 (2 << GPIO_PIN_SHIFT) -- GitLab From 1e9bc166d4d658491a8f1f353402172f70cfe510 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 21 Mar 2017 10:02:23 -0600 Subject: [PATCH 127/990] XMC4500 Relax: Add README.txt file. Fix some comments. --- Documentation/README.html | 4 +- README.txt | 2 + configs/xmc4500-relax/README.txt | 154 ++++++++++++++++++++++ configs/xmc4500-relax/include/board.h | 7 +- configs/xmc4500-relax/src/xmc4_autoleds.c | 26 ++-- 5 files changed, 174 insertions(+), 19 deletions(-) create mode 100644 configs/xmc4500-relax/README.txt diff --git a/Documentation/README.html b/Documentation/README.html index 2f9ba9066b..4430ef211f 100644 --- a/Documentation/README.html +++ b/Documentation/README.html @@ -8,7 +8,7 @@

NuttX README Files

-

Last Updated: February 19, 2017

+

Last Updated: March 21, 2017

@@ -297,6 +297,8 @@ nuttx/ | | `- README.txt | |- viewtool-stm32f107/ | | `- README.txt + | |- xmc4500-relax/ + | | `- README.txt | |- xtrs/ | | `- README.txt | |- z16f2800100zcog/ diff --git a/README.txt b/README.txt index ed3d41c30f..4bab1306ff 100644 --- a/README.txt +++ b/README.txt @@ -1681,6 +1681,8 @@ nuttx/ | | `- README.txt | |- viewtool-stm32f107/ | | `- README.txt + | |- xmc5400-relax/ + | | `- README.txt | |- xtrs/ | | `- README.txt | |- z16f2800100zcog/ diff --git a/configs/xmc4500-relax/README.txt b/configs/xmc4500-relax/README.txt new file mode 100644 index 0000000000..0ee63341d4 --- /dev/null +++ b/configs/xmc4500-relax/README.txt @@ -0,0 +1,154 @@ +README for the XMC4500 Relax +============================ + + The directory provides board support for the Infinion XMC4500 Relax v1 + boards. There are to variants of this board: There is a Lite version + that has fewer features, for example, no 32.768KHz crystal. + + The current configurations support only the Lite version of the board. + +Serial Console +============== + + Be default, UART0 (aka, USIC0, channel 0) is used as the serial console. + The RX and TX pins is available: + + RX - P1.4, Connector X2, pin 17 + TX - P1.5, Connector X2, pin 17 + GND - Available on pins 1-4 of either connector X1 or X2 + VDD3.3 - Available on pins 37-38 of either connector X1 or X2 + VDD5 - Available on pins 39-40 of either connector X1 or X2 + +LEDs +==== + + The XMC4500 Relax Lite v1 board has two LEDs: + + LED1 P1.1 High output illuminates + LED2 P1.0 High output illuminates + + If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in + any way. The definitions provided in the board.h header file can be used + to access individual LEDs. + + These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is + defined. In that case, the usage by the board port is defined in + include/board.h and src/sam_autoleds.c. The LEDs are used to encode + OS-related events as follows: + + SYMBOL Meaning LED state + LED1 LED2 + ------------------ ------------------------ ------ ------ + LED_STARTED NuttX has been started OFF OFF + LED_HEAPALLOCATE Heap has been allocated OFF OFF + LED_IRQSENABLED Interrupts enabled OFF OFF + LED_STACKCREATED Idle stack created ON OFF + LED_INIRQ In an interrupt No change + LED_SIGNAL In a signal handler No change + LED_ASSERTION An assertion failed No change + LED_PANIC The system has crashed N/C Blinking + LED_IDLE MCU is is sleep mode Not used + + Thus if LED1 is statically on, NuttX has successfully booted and is, + apparently, running normally. If LED2 is flashing at approximately + 2Hz, then a fatal error has been detected and the system has halted. + +Buttons +======= + + The XMC4500 Relax Lite v1 board has two buttons: + + BUTTON1 P1.14 Low input sensed when button pressed + BUTTON2 P1.15 Low input sensed when button pressed + +Configurations +============== + + Information Common to All Configurations + ---------------------------------------- + Each XMC4500 Relax configuration is maintained in a sub-directory and + can be selected as follow: + + cd tools + ./configure.sh xmc5400-relax/ + cd - + . ./setenv.sh + + Before sourcing the setenv.sh file above, you should examine it and + perform edits as necessary so that TOOLCHAIN_BIN is the correct path + to the directory than holds your toolchain binaries. + + And then build NuttX by simply typing the following. At the conclusion of + the make, the nuttx binary will reside in an ELF file called, simply, nuttx. + + make oldconfig + make + + The that is provided above as an argument to the tools/configure.sh + must be is one of the following. + + NOTES: + + 1. These configurations use the mconf-based configuration tool. To + change any of these configurations using that tool, you should: + + a. Build and install the kconfig-mconf tool. See nuttx/README.txt + see additional README.txt files in the NuttX tools repository. + + b. Execute 'make menuconfig' in nuttx/ in order to start the + reconfiguration process. + + 2. Unless stated otherwise, all configurations generate console + output on UART0 (aka USIC0, channel 0) as described above under + "Serial Console". The relevant configuration settings are listed + below: + + CONFIG_XMC4_USIC0=y + CONFIG_XMC4_USIC0_CHAN0_ISUART=y + CONFIG_XMC4_USIC0_CHAN1_NONE=y + + CONFIG_UART0_SERIALDRIVER=y + CONFIG_UART0_SERIAL_CONSOLE=y + + CONFIG_UART0_RXBUFSIZE=256 + CONFIG_UART0_TXBUFSIZE=256 + CONFIG_UART0_BAUD=115200 + CONFIG_UART0_BITS=8 + CONFIG_UART0_PARITY=0 + CONFIG_UART0_2STOP=0 + + + 3. All of these configurations are set up to build under Windows using the + "GNU Tools for ARM Embedded Processors" that is maintained by ARM + (unless stated otherwise in the description of the configuration). + + https://launchpad.net/gcc-arm-embedded + + That toolchain selection can easily be reconfigured using + 'make menuconfig'. Here are the relevant current settings: + + Build Setup: + CONFIG_HOST_WINDOWS=y : Window environment + CONFIG_WINDOWS_CYGWIN=y : Cywin under Windows + + System Type -> Toolchain: + CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIW=y : GNU ARM EABI toolchain + + Configuration sub-directories + ----------------------------- + + nsh: + + Configures the NuttShell (nsh) located at examples/nsh. This + configuration is focused on low level, command-line driver testing. It + has no network. + + NOTES: + + 1. NSH built-in applications are supported. + + Binary Formats: + CONFIG_BUILTIN=y : Enable support for built-in programs + + Application Configuration: + CONFIG_NSH_BUILTIN_APPS=y : Enable starting apps from NSH command line diff --git a/configs/xmc4500-relax/include/board.h b/configs/xmc4500-relax/include/board.h index 6be8e787f2..9c3121a4b6 100644 --- a/configs/xmc4500-relax/include/board.h +++ b/configs/xmc4500-relax/include/board.h @@ -171,12 +171,9 @@ #define LED_PANIC 3 /* The system has crashed N/C Blinking */ #undef LED_IDLE /* MCU is is sleep mode Not used */ -/* Thus if LED0 is statically on, NuttX has successfully booted and is, - * apparently, running normally. If LED1 is flashing at approximately +/* Thus if LED1 is statically on, NuttX has successfully booted and is, + * apparently, running normally. If LED2 is flashing at approximately * 2Hz, then a fatal error has been detected and the system has halted. - * - * NOTE: That LED0 is not used after completion of booting and may - * be used by other board-specific logic. */ /* Button definitions ***************************************************************/ diff --git a/configs/xmc4500-relax/src/xmc4_autoleds.c b/configs/xmc4500-relax/src/xmc4_autoleds.c index 694007c5e5..69eda6dee9 100644 --- a/configs/xmc4500-relax/src/xmc4_autoleds.c +++ b/configs/xmc4500-relax/src/xmc4_autoleds.c @@ -43,19 +43,19 @@ * include/board.h and src/sam_autoleds.c. The LEDs are used to encode * OS-related events as follows: * - * SYMBOL Meaning LED state - * LED2 LED1 - * --------------------- -------------------------- ------ ------ */ - -#define LED_STARTED 0 /* NuttX has been started OFF OFF */ -#define LED_HEAPALLOCATE 0 /* Heap has been allocated OFF OFF */ -#define LED_IRQSENABLED 0 /* Interrupts enabled OFF OFF */ -#define LED_STACKCREATED 1 /* Idle stack created ON OFF */ -#define LED_INIRQ 2 /* In an interrupt No change */ -#define LED_SIGNAL 2 /* In a signal handler No change */ -#define LED_ASSERTION 2 /* An assertion failed No change */ -#define LED_PANIC 3 /* The system has crashed N/C Blinking */ -#undef LED_IDLE /* MCU is is sleep mode Not used */ + * SYMBOL Meaning LED state + * LED1 LED2 + * ------------------ ------------------------ ------ ------ + * LED_STARTED NuttX has been started OFF OFF + * LED_HEAPALLOCATE Heap has been allocated OFF OFF + * LED_IRQSENABLED Interrupts enabled OFF OFF + * LED_STACKCREATED Idle stack created ON OFF + * LED_INIRQ In an interrupt No change + * LED_SIGNAL In a signal handler No change + * LED_ASSERTION An assertion failed No change + * LED_PANIC The system has crashed N/C Blinking + * LED_IDLE MCU is is sleep mode Not used + */ /**************************************************************************** * Included Files -- GitLab From 21a626878a75f2fd2915ec2bb882443e35485fb7 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 21 Mar 2017 10:55:52 -0600 Subject: [PATCH 128/990] XMC4xxx: Clean up problems associated with USIC initialization. USIC still does not work in UART mode. --- arch/arm/src/xmc4/xmc4_clockutils.c | 7 ++++--- arch/arm/src/xmc4/xmc4_gpio.c | 15 ++++++++++----- arch/arm/src/xmc4/xmc4_usic.c | 18 +++++++++--------- configs/xmc4500-relax/README.txt | 4 +++- 4 files changed, 26 insertions(+), 18 deletions(-) diff --git a/arch/arm/src/xmc4/xmc4_clockutils.c b/arch/arm/src/xmc4/xmc4_clockutils.c index 4d334eaef5..2a391ca386 100644 --- a/arch/arm/src/xmc4/xmc4_clockutils.c +++ b/arch/arm/src/xmc4/xmc4_clockutils.c @@ -161,6 +161,7 @@ uint32_t xmc4_get_coreclock(void) uint32_t xmc4_get_periphclock(void) { uint32_t periphclock; + uint32_t regval; /* Get the CPU clock frequency. Unless it is divided down, this also the * peripheral clock frequency. @@ -170,12 +171,12 @@ uint32_t xmc4_get_periphclock(void) /* Get the peripheral clock divider */ - periphclock = getreg32(XMC4_SCU_PBCLKCR); - if ((periphclock & SCU_PBCLKCR_PBDIV) != 0) + regval = getreg32(XMC4_SCU_PBCLKCR); + if ((regval & SCU_PBCLKCR_PBDIV) != 0) { /* The peripheral clock is fCPU/2 */ - periphclock <<= 1; + periphclock >>= 1; } return periphclock; diff --git a/arch/arm/src/xmc4/xmc4_gpio.c b/arch/arm/src/xmc4/xmc4_gpio.c index e26967f06f..b104def53c 100644 --- a/arch/arm/src/xmc4/xmc4_gpio.c +++ b/arch/arm/src/xmc4/xmc4_gpio.c @@ -234,7 +234,7 @@ static inline void xmc4_gpio_hwsel(uintptr_t portbase, unsigned int pin, ****************************************************************************/ static inline void xmc4_gpio_pdisc(uintptr_t portbase, unsigned int pin, - bool value) + bool enable) { uint32_t regval; uint32_t mask; @@ -243,16 +243,21 @@ static inline void xmc4_gpio_pdisc(uintptr_t portbase, unsigned int pin, regval = xmc4_gpio_getreg(portbase, XMC4_PORT_PDISC_OFFSET); - /* Set/clear the enable/disable (or analg) value for this field */ + /* Set or clear the pin field in the PDISC register. + * + * Disable = set + * Analog = set + * Enable = clear + */ mask = PORT_PIN(pin); - if (value) + if (enable) { - regval |= mask; + regval &= ~mask; } else { - regval &= ~mask; + regval |= mask; } xmc4_gpio_putreg(portbase, XMC4_PORT_PDISC_OFFSET, regval); diff --git a/arch/arm/src/xmc4/xmc4_usic.c b/arch/arm/src/xmc4/xmc4_usic.c index dd69cf318d..1b82b9e16d 100644 --- a/arch/arm/src/xmc4/xmc4_usic.c +++ b/arch/arm/src/xmc4/xmc4_usic.c @@ -121,12 +121,12 @@ int xmc4_enable_usic(enum usic_e usic) putreg32(SCU_CGAT0_USIC0, XMC4_SCU_CGATCLR0); - /* De-assert peripheral reset USIC0 */ + /* Set bit in PRCLR0 to de-assert USIC0 peripheral reset */ putreg32(SCU_PR0_USIC0RS, XMC4_SCU_PRCLR0); } #else - /* De-assert peripheral reset USIC0 */ + /* Set bit in PRCLR0 to de-assert USIC0 peripheral reset */ putreg32(SCU_PR0_USIC0RS, XMC4_SCU_PRCLR0); #endif @@ -143,12 +143,12 @@ int xmc4_enable_usic(enum usic_e usic) putreg32(SCU_CGAT1_USIC1, XMC4_SCU_CGATCLR1); - /* De-assert peripheral reset USIC1 */ + /* Set bit in PRCLR1 to de-assert USIC1 peripheral reset */ putreg32(SCU_PR1_USIC1RS, XMC4_SCU_PRCLR1); } #else - /* De-assert peripheral reset USIC1 */ + /* Set bit in PRCLR1 to de-assert USIC1 peripheral reset */ putreg32(SCU_PR1_USIC1RS, XMC4_SCU_PRCLR1); #endif @@ -165,12 +165,12 @@ int xmc4_enable_usic(enum usic_e usic) putreg32(SCU_CGAT1_USIC2, XMC4_SCU_CGATCLR1); - /* De-assert peripheral reset USIC2 */ + /* Set bit in PRCLR1 to de-assert USIC2 peripheral reset */ putreg32(SCU_PR1_USIC2RS, XMC4_SCU_PRCLR1); } #else - /* De-assert peripheral reset USIC2 */ + /* Set bit in PRCLR1 to de-assert USIC2 peripheral reset */ putreg32(SCU_PR1_USIC2RS, XMC4_SCU_PRCLR1); #endif @@ -203,7 +203,7 @@ int xmc4_disable_usic(enum usic_e usic) switch (usic) { case USIC0: - /* Assert peripheral reset USIC0 */ + /* Set bit in PRSET0 to assert USIC0 peripheral reset */ putreg32(SCU_PR0_USIC0RS, XMC4_SCU_PRSET0); @@ -216,7 +216,7 @@ int xmc4_disable_usic(enum usic_e usic) #if XMC4_NUSIC > 1 case USIC1: - /* Assert peripheral reset USIC0 */ + /* Set bit in PRSET1 to assert USIC1 peripheral reset */ putreg32(SCU_PR1_USIC1RS, XMC4_SCU_PRSET1); @@ -229,7 +229,7 @@ int xmc4_disable_usic(enum usic_e usic) #if XMC4_NUSIC > 2 case USIC2: - /* Assert peripheral reset USIC0 */ + /* Set bit in PRSET1 to assert USIC2 peripheral reset */ putreg32(SCU_PR1_USIC2RS, XMC4_SCU_PRSET1); diff --git a/configs/xmc4500-relax/README.txt b/configs/xmc4500-relax/README.txt index 0ee63341d4..c6d014b666 100644 --- a/configs/xmc4500-relax/README.txt +++ b/configs/xmc4500-relax/README.txt @@ -14,11 +14,13 @@ Serial Console The RX and TX pins is available: RX - P1.4, Connector X2, pin 17 - TX - P1.5, Connector X2, pin 17 + TX - P1.5, Connector X2, pin 16 GND - Available on pins 1-4 of either connector X1 or X2 VDD3.3 - Available on pins 37-38 of either connector X1 or X2 VDD5 - Available on pins 39-40 of either connector X1 or X2 + A TTL to RS-232 convertor or a USB TTL-to-USB serial adaptor is required. + LEDs ==== -- GitLab From 602bdd13fb6b7981fa587a409fef791f4b9de338 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 21 Mar 2017 11:24:04 -0600 Subject: [PATCH 129/990] XMC4xxx: Fix a pin configuration problem. Fix some mispellings. --- arch/arm/src/xmc4/chip/xmc4_ports.h | 22 +++++++++++----------- arch/arm/src/xmc4/xmc4_gpio.c | 18 +++++++++--------- arch/arm/src/xmc4/xmc4_lowputc.c | 2 +- arch/arm/src/xmc4/xmc4_usic.c | 4 ++-- arch/arm/src/xmc4/xmc4_usic.h | 4 ++-- 5 files changed, 25 insertions(+), 25 deletions(-) diff --git a/arch/arm/src/xmc4/chip/xmc4_ports.h b/arch/arm/src/xmc4/chip/xmc4_ports.h index d42665b908..a769ddf73c 100644 --- a/arch/arm/src/xmc4/chip/xmc4_ports.h +++ b/arch/arm/src/xmc4/chip/xmc4_ports.h @@ -79,7 +79,7 @@ #define XMC4_PORT_IN_OFFSET 0x0024 /* Port Input Register */ -#define XMC4_PORT_PDR_OFFSET(n) (0x0010 + (((n) >> 1) & ~3)) +#define XMC4_PORT_PDR_OFFSET(n) (0x0040 + (((n) >> 1) & ~3)) #define XMC4_PORT_PDR0_OFFSET 0x0040 /* Port Pad Driver Mode 0 Register */ #define XMC4_PORT_PDR1_OFFSET 0x0044 /* Port Pad Driver Mode 1 Register */ @@ -399,19 +399,19 @@ #define PORT_PDR0_PD2_SHIFT (8) /* Bit 8-10: Pad Driver Mode for Port n Pin 2 */ #define PORT_PDR0_PD2_MASK (7 << PORT_PDR0_PD2_SHIFT) # define PORT_PDR0_PD2(n) ((uint32_t)(n) << PORT_PDR0_PD2_SHIFT) -#define PORT_PDR0_PD3_SHIFT (12) /* Bit 12-14: Pad Driver Mode for Port 0 Pin 3 */ +#define PORT_PDR0_PD3_SHIFT (12) /* Bit 12-14: Pad Driver Mode for Port n Pin 3 */ #define PORT_PDR0_PD3_MASK (7 << PORT_PDR0_PD3_SHIFT) # define PORT_PDR0_PD3(n) ((uint32_t)(n) << PORT_PDR0_PD3_SHIFT) -#define PORT_PDR0_PD4_SHIFT (16) /* Bit 16-18: Pad Driver Mode for Port 0 Pin 4 */ +#define PORT_PDR0_PD4_SHIFT (16) /* Bit 16-18: Pad Driver Mode for Port n Pin 4 */ #define PORT_PDR0_PD4_MASK (7 << PORT_PDR0_PD4_SHIFT) # define PORT_PDR0_PD4(n) ((uint32_t)(n) << PORT_PDR0_PD4_SHIFT) -#define PORT_PDR0_PD5_SHIFT (20) /* Bit 20-22: Pad Driver Mode for Port 0 Pin 5 */ +#define PORT_PDR0_PD5_SHIFT (20) /* Bit 20-22: Pad Driver Mode for Port n Pin 5 */ #define PORT_PDR0_PD5_MASK (7 << PORT_PDR0_PD5_SHIFT) # define PORT_PDR0_PD5(n) ((uint32_t)(n) << PORT_PDR0_PD5_SHIFT) -#define PORT_PDR0_PD6_SHIFT (24) /* Bit 24-26: Pad Driver Mode for Port 0 Pin 6 */ +#define PORT_PDR0_PD6_SHIFT (24) /* Bit 24-26: Pad Driver Mode for Port n Pin 6 */ #define PORT_PDR0_PD6_MASK (7 << PORT_PDR0_PD6_SHIFT) # define PORT_PDR0_PD6(n) ((uint32_t)(n) << PORT_PDR0_PD6_SHIFT) -#define PORT_PDR0_PD7_SHIFT (28) /* Bit 28-30: Pad Driver Mode for Port 0 Pin 7 */ +#define PORT_PDR0_PD7_SHIFT (28) /* Bit 28-30: Pad Driver Mode for Port n Pin 7 */ #define PORT_PDR0_PD7_MASK (7 << PORT_PDR0_PD7_SHIFT) # define PORT_PDR0_PD7(n) ((uint32_t)(n) << PORT_PDR0_PD7_SHIFT) @@ -429,19 +429,19 @@ #define PORT_PDR1_PD10_SHIFT (8) /* Bit 8-10: Pad Driver Mode for Port n Pin 10 */ #define PORT_PDR1_PD10_MASK (7 << PORT_PDR1_PD10_SHIFT) # define PORT_PDR1_PD10(n) ((uint32_t)(n) << PORT_PDR1_PD10_SHIFT) -#define PORT_PDR1_PD11_SHIFT (12) /* Bit 12-14: Pad Driver Mode for Port 0 Pin 11 */ +#define PORT_PDR1_PD11_SHIFT (12) /* Bit 12-14: Pad Driver Mode for Port n Pin 11 */ #define PORT_PDR1_PD11_MASK (7 << PORT_PDR1_PD11_SHIFT) # define PORT_PDR1_PD11(n) ((uint32_t)(n) << PORT_PDR1_PD11_SHIFT) -#define PORT_PDR1_PD12_SHIFT (16) /* Bit 16-18: Pad Driver Mode for Port 0 Pin 12 */ +#define PORT_PDR1_PD12_SHIFT (16) /* Bit 16-18: Pad Driver Mode for Port n Pin 12 */ #define PORT_PDR1_PD12_MASK (7 << PORT_PDR1_PD12_SHIFT) # define PORT_PDR1_PD12(n) ((uint32_t)(n) << PORT_PDR1_PD12_SHIFT) -#define PORT_PDR1_PD13_SHIFT (20) /* Bit 20-22: Pad Driver Mode for Port 0 Pin 13 */ +#define PORT_PDR1_PD13_SHIFT (20) /* Bit 20-22: Pad Driver Mode for Port n Pin 13 */ #define PORT_PDR1_PD13_MASK (7 << PORT_PDR1_PD13_SHIFT) # define PORT_PDR1_PD13(n) ((uint32_t)(n) << PORT_PDR1_PD13_SHIFT) -#define PORT_PDR1_PD14_SHIFT (24) /* Bit 24-26: Pad Driver Mode for Port 0 Pin 14 */ +#define PORT_PDR1_PD14_SHIFT (24) /* Bit 24-26: Pad Driver Mode for Port n Pin 14 */ #define PORT_PDR1_PD14_MASK (7 << PORT_PDR1_PD14_SHIFT) # define PORT_PDR1_PD14(n) ((uint32_t)(n) << PORT_PDR1_PD14_SHIFT) -#define PORT_PDR1_PD15_SHIFT (28) /* Bit 28-30: Pad Driver Mode for Port 0 Pin 15 */ +#define PORT_PDR1_PD15_SHIFT (28) /* Bit 28-30: Pad Driver Mode for Port n Pin 15 */ #define PORT_PDR1_PD15_MASK (7 << PORT_PDR1_PD15_SHIFT) # define PORT_PDR1_PD15(n) ((uint32_t)(n) << PORT_PDR1_PD15_SHIFT) diff --git a/arch/arm/src/xmc4/xmc4_gpio.c b/arch/arm/src/xmc4/xmc4_gpio.c index b104def53c..d88e73c7ad 100644 --- a/arch/arm/src/xmc4/xmc4_gpio.c +++ b/arch/arm/src/xmc4/xmc4_gpio.c @@ -247,7 +247,7 @@ static inline void xmc4_gpio_pdisc(uintptr_t portbase, unsigned int pin, * * Disable = set * Analog = set - * Enable = clear + * Enable = clear */ mask = PORT_PIN(pin); @@ -272,7 +272,7 @@ static inline void xmc4_gpio_pdisc(uintptr_t portbase, unsigned int pin, ****************************************************************************/ static inline void xmc4_gpio_pps(uintptr_t portbase, unsigned int pin, - bool value) + bool powersave) { uint32_t regval; uint32_t mask; @@ -281,10 +281,10 @@ static inline void xmc4_gpio_pps(uintptr_t portbase, unsigned int pin, regval = xmc4_gpio_getreg(portbase, XMC4_PORT_PPS_OFFSET); - /* Set/clear the enable/disable (or analg) value for this field */ + /* Set/clear the enable/disable power save value for this field */ mask = PORT_PIN(pin); - if (value) + if (powersave) { regval |= mask; } @@ -312,7 +312,7 @@ static void xmc4_gpio_pdr(uintptr_t portbase, unsigned int pin, unsigned int offset; unsigned int shift; - /* Read the PDRregister */ + /* Read the PDR register */ offset = XMC4_PORT_PDR_OFFSET(pin); regval = xmc4_gpio_getreg(portbase, offset); @@ -417,18 +417,18 @@ int xmc4_gpio_config(gpioconfig_t pinconfig) value = xmc4_gpio_pinctrl(pinconfig); xmc4_gpio_hwsel(portbase, pin, value); - /* Select drive strength */ + /* Select drive strength (PDR) */ value = xmc4_gpio_padtype(pinconfig); xmc4_gpio_pdr(portbase, pin, value); /* Enable/enable pad or Analog only (PDISC) */ - xmc4_gpio_pdisc(portbase, pin, ((pinconfig & GPIO_PAD_DISABLE) != 0)); + xmc4_gpio_pdisc(portbase, pin, ((pinconfig & GPIO_PAD_DISABLE) == 0)); - /* Make sure pin is not in power save mode (PDR) */ + /* Make sure pin is not in power save mode (PPS) */ - xmc4_gpio_pdisc(portbase, pin, false); + xmc4_gpio_pps(portbase, pin, false); leave_critical_section(flags); return OK; diff --git a/arch/arm/src/xmc4/xmc4_lowputc.c b/arch/arm/src/xmc4/xmc4_lowputc.c index fcb930d1b9..c1416194fc 100644 --- a/arch/arm/src/xmc4/xmc4_lowputc.c +++ b/arch/arm/src/xmc4/xmc4_lowputc.c @@ -275,7 +275,7 @@ int xmc4_uart_configure(enum usic_channel_e channel, * the config structure. */ - ret = xmc4_uisc_baudrate(channel, config->baud, UART_OVERSAMPLING); + ret = xmc4_usic_baudrate(channel, config->baud, UART_OVERSAMPLING); /* Configure frame format. * diff --git a/arch/arm/src/xmc4/xmc4_usic.c b/arch/arm/src/xmc4/xmc4_usic.c index 1b82b9e16d..e22434a637 100644 --- a/arch/arm/src/xmc4/xmc4_usic.c +++ b/arch/arm/src/xmc4/xmc4_usic.c @@ -385,7 +385,7 @@ int xmc4_disable_usic_channel(enum usic_channel_e channel) } /**************************************************************************** - * Name: xmc4_uisc_baudrate + * Name: xmc4_usic_baudrate * * Description: * Set the USIC baudrate for the USIC channel @@ -396,7 +396,7 @@ int xmc4_disable_usic_channel(enum usic_channel_e channel) * ****************************************************************************/ -int xmc4_uisc_baudrate(enum usic_channel_e channel, uint32_t baud, +int xmc4_usic_baudrate(enum usic_channel_e channel, uint32_t baud, uint32_t oversampling) { uintptr_t base; diff --git a/arch/arm/src/xmc4/xmc4_usic.h b/arch/arm/src/xmc4/xmc4_usic.h index 910846bc85..291fb81fb0 100644 --- a/arch/arm/src/xmc4/xmc4_usic.h +++ b/arch/arm/src/xmc4/xmc4_usic.h @@ -177,7 +177,7 @@ int xmc4_enable_usic_channel(enum usic_channel_e channel); int xmc4_disable_usic_channel(enum usic_channel_e channel); /**************************************************************************** - * Name: xmc4_uisc_baudrate + * Name: xmc4_usic_baudrate * * Description: * Set the USIC baudrate for the USIC channel @@ -188,7 +188,7 @@ int xmc4_disable_usic_channel(enum usic_channel_e channel); * ****************************************************************************/ -int xmc4_uisc_baudrate(enum usic_channel_e channel, uint32_t baud, +int xmc4_usic_baudrate(enum usic_channel_e channel, uint32_t baud, uint32_t oversampling); #endif /* __ARCH_ARM_SRC_XMC4_XMC4_USIC_H */ -- GitLab From d76157db7bd22595be5bdb5822031d68106806bf Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Tue, 21 Mar 2017 08:03:06 -1000 Subject: [PATCH 130/990] sem_holder:Clean up from Review Spelling and backward DEBUGASSERT along with one gem if (sem->holder[0].htcb != NULL || sem->holder[**1**].htcb != NULL) --- sched/semaphore/sem_holder.c | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/sched/semaphore/sem_holder.c b/sched/semaphore/sem_holder.c index bc5c186e6b..7b4e3e3dd1 100644 --- a/sched/semaphore/sem_holder.c +++ b/sched/semaphore/sem_holder.c @@ -156,7 +156,7 @@ static FAR struct semholder_s *sem_findholder(sem_t *sem, int i; pholder = NULL; - /* We have two hard-allocated holder structuse in sem_t */ + /* We have two hard-allocated holder structures in sem_t */ for (i = 0; i < 2; i++) { @@ -338,7 +338,7 @@ static int sem_boostholderprio(FAR struct semholder_s *pholder, if (!sched_verifytcb(htcb)) { serr("ERROR: TCB 0x%08x is a stale handle, counts lost\n", htcb); - DEBUGASSERT(!sched_verifytcb(htcb)); + DEBUGASSERT(sched_verifytcb(htcb)); sem_freeholder(sem, pholder); } @@ -498,7 +498,7 @@ static int sem_restoreholderprio(FAR struct tcb_s *htcb, if (!sched_verifytcb(htcb)) { serr("ERROR: TCB 0x%08x is a stale handle, counts lost\n", htcb); - DEBUGASSERT(!sched_verifytcb(htcb)); + DEBUGASSERT(sched_verifytcb(htcb)); pholder = sem_findholder(sem, htcb); if (pholder != NULL) { @@ -905,13 +905,13 @@ void sem_destroyholder(FAR sem_t *sem) if (sem->hhead != NULL) { serr("ERROR: Semaphore destroyed with holders\n"); - DEBUGASSERT(sem->hhead != NULL); + DEBUGASSERT(sem->hhead == NULL); (void)sem_foreachholder(sem, sem_recoverholders, NULL); } #else - if (sem->holder[0].htcb != NULL || sem->holder[0].htcb != NULL) + if (sem->holder[0].htcb != NULL || sem->holder[1].htcb != NULL) { - DEBUGASSERT(sem->holder[0].htcb != NULL || sem->holder[0].htcb != NULL); + DEBUGASSERT(sem->holder[0].htcb == NULL || sem->holder[1].htcb == NULL); serr("ERROR: Semaphore destroyed with holder\n"); } -- GitLab From 248c821730429333cbb37588b5971866dc7805f0 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 21 Mar 2017 12:28:34 -0600 Subject: [PATCH 131/990] Update a README file. --- configs/xmc4500-relax/README.txt | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/configs/xmc4500-relax/README.txt b/configs/xmc4500-relax/README.txt index c6d014b666..e1fd46fa83 100644 --- a/configs/xmc4500-relax/README.txt +++ b/configs/xmc4500-relax/README.txt @@ -7,6 +7,15 @@ README for the XMC4500 Relax The current configurations support only the Lite version of the board. +Status +====== + + 2017-03-21: The XMC4500 Relax boots into NSH, provides the NSH prompt, + and the LEDs are working. But there is a problem with the USIC baud + (probably); I get garbage on the serial console. This probably means + that either the peripheral clocking is wrong or the baud configuration + is wrong. + Serial Console ============== @@ -20,6 +29,9 @@ Serial Console VDD5 - Available on pins 39-40 of either connector X1 or X2 A TTL to RS-232 convertor or a USB TTL-to-USB serial adaptor is required. + The notion of what is TX and what is RX depends on your point of view. + With the TTL to RS-232 converter, I connect pin 17 to the pin labeled + TX on the converter and pin 16 to the RX pin on the converter. LEDs ==== -- GitLab From e8e3c2f362e228f162cb939c62361ac5b6d769b3 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 21 Mar 2017 13:34:17 -0600 Subject: [PATCH 132/990] sched/semaphore: Convert strange use of DEBUGASSERT to DEBUGPANIC. --- sched/semaphore/sem_holder.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/sched/semaphore/sem_holder.c b/sched/semaphore/sem_holder.c index 7b4e3e3dd1..a9159c1537 100644 --- a/sched/semaphore/sem_holder.c +++ b/sched/semaphore/sem_holder.c @@ -338,7 +338,7 @@ static int sem_boostholderprio(FAR struct semholder_s *pholder, if (!sched_verifytcb(htcb)) { serr("ERROR: TCB 0x%08x is a stale handle, counts lost\n", htcb); - DEBUGASSERT(sched_verifytcb(htcb)); + DEBUGPANIC(); sem_freeholder(sem, pholder); } @@ -498,7 +498,7 @@ static int sem_restoreholderprio(FAR struct tcb_s *htcb, if (!sched_verifytcb(htcb)) { serr("ERROR: TCB 0x%08x is a stale handle, counts lost\n", htcb); - DEBUGASSERT(sched_verifytcb(htcb)); + DEBUGPANIC(); pholder = sem_findholder(sem, htcb); if (pholder != NULL) { @@ -905,14 +905,14 @@ void sem_destroyholder(FAR sem_t *sem) if (sem->hhead != NULL) { serr("ERROR: Semaphore destroyed with holders\n"); - DEBUGASSERT(sem->hhead == NULL); + DEBUGPANIC(); (void)sem_foreachholder(sem, sem_recoverholders, NULL); } #else if (sem->holder[0].htcb != NULL || sem->holder[1].htcb != NULL) { - DEBUGASSERT(sem->holder[0].htcb == NULL || sem->holder[1].htcb == NULL); serr("ERROR: Semaphore destroyed with holder\n"); + DEBUGPANIC(); } sem->holder[0].htcb = NULL; -- GitLab From 6893843cc516bd211b4da257a2d86e831024ee56 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 21 Mar 2017 13:47:56 -0600 Subject: [PATCH 133/990] sched/semaphore: Fix a warning aout an unused variable when priority inheritance is enabled. --- sched/semaphore/sem_holder.c | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/sched/semaphore/sem_holder.c b/sched/semaphore/sem_holder.c index a9159c1537..a46cf3a8be 100644 --- a/sched/semaphore/sem_holder.c +++ b/sched/semaphore/sem_holder.c @@ -787,7 +787,6 @@ static inline void sem_restorebaseprio_task(FAR struct tcb_s *stcb, FAR sem_t *sem) { FAR struct tcb_s *rtcb = this_task(); - FAR struct semholder_s *pholder; /* Perform the following actions only if a new thread was given a count. * The thread that received the count should be the highest priority @@ -831,7 +830,6 @@ static inline void sem_restorebaseprio_task(FAR struct tcb_s *stcb, */ sem_findandfreeholder(sem, rtcb); - } /**************************************************************************** @@ -908,6 +906,7 @@ void sem_destroyholder(FAR sem_t *sem) DEBUGPANIC(); (void)sem_foreachholder(sem, sem_recoverholders, NULL); } + #else if (sem->holder[0].htcb != NULL || sem->holder[1].htcb != NULL) { -- GitLab From 343f7ceab24c9551717c4a151356756c11c65b8b Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 21 Mar 2017 15:05:17 -0600 Subject: [PATCH 134/990] XMC4xxx: Misc clock clean-up; PBDIV should be controllable from board.h --- arch/arm/src/xmc4/xmc4_clockconfig.c | 9 +++++++-- arch/arm/src/xmc4/xmc4_usic.c | 4 ++-- configs/xmc4500-relax/include/board.h | 21 +++++++++++++-------- 3 files changed, 22 insertions(+), 12 deletions(-) diff --git a/arch/arm/src/xmc4/xmc4_clockconfig.c b/arch/arm/src/xmc4/xmc4_clockconfig.c index a28cf7fd51..519276f2cd 100644 --- a/arch/arm/src/xmc4/xmc4_clockconfig.c +++ b/arch/arm/src/xmc4/xmc4_clockconfig.c @@ -105,13 +105,18 @@ #define CLKSET_VALUE (0x00000000) #define SYSCLKCR_VALUE (0x00010001) #define CPUCLKCR_VALUE (0x00000000) -#define PBCLKCR_VALUE (0x00000000) #define CCUCLKCR_VALUE (0x00000000) #define WDTCLKCR_VALUE (0x00000000) #define EBUCLKCR_VALUE (0x00000003) #define USBCLKCR_VALUE (0x00010000) #define EXTCLKCR_VALUE (0x01200003) +#if BOARD_PBDIV == 1 +# define PBCLKCR_VALUE SCU_PBCLKCR_PBDIV_FCPU +#else /* BOARD_PBDIV == 2 */ +# define PBCLKCR_VALUE SCU_PBCLKCR_PBDIV_DIV2 +#endif + #if ((USBCLKCR_VALUE & SCU_USBCLKCR_USBSEL) == SCU_USBCLKCR_USBSEL_USBPLL) # define USB_DIV 3 #else @@ -387,7 +392,7 @@ void xmc4_clock_configure(void) /* Before scaling to final frequency we need to setup the clock dividers */ putreg32(SYSCLKCR_VALUE, XMC4_SCU_SYSCLKCR); - putreg32(PBCLKCR_VALUE, XMC4_SCU_PBCLKCR); + putreg32(PBCLKCR_VALUE, XMC4_SCU_PBCLKCR); putreg32(CPUCLKCR_VALUE, XMC4_SCU_CPUCLKCR); putreg32(CCUCLKCR_VALUE, XMC4_SCU_CCUCLKCR); putreg32(WDTCLKCR_VALUE, XMC4_SCU_WDTCLKCR); diff --git a/arch/arm/src/xmc4/xmc4_usic.c b/arch/arm/src/xmc4/xmc4_usic.c index e22434a637..925c9c0f41 100644 --- a/arch/arm/src/xmc4/xmc4_usic.c +++ b/arch/arm/src/xmc4/xmc4_usic.c @@ -448,14 +448,14 @@ int xmc4_usic_baudrate(enum usic_channel_e channel, uint32_t baud, /* Select and setup the fractional divider */ - regval = USIC_FDR_DM_FRACTIONAL | (clkdiv_min << USIC_FDR_STEP_SHIFT); + regval = USIC_FDR_DM_FRACTIONAL | USIC_FDR_STEP(clkdiv_min); putreg32(regval, base + XMC4_USIC_FDR_OFFSET); /* Setup and enable the baud rate generator */ regval = getreg32(base + XMC4_USIC_BRG_OFFSET); regval &= ~(USIC_BRG_DCTQ_MASK | USIC_BRG_PDIV_MASK | USIC_BRG_PCTQ_MASK | USIC_BRG_PPPEN); - regval |= (USIC_BRG_DCTQ(oversampling - 1) | USIC_BRG_PDIV(pdiv_int_min - 1)); + regval |= (USIC_BRG_DCTQ(oversampling - 1) | USIC_BRG_PDIV(pdiv_int_min - 1)); putreg32(regval, base + XMC4_USIC_BRG_OFFSET); ret = OK; diff --git a/configs/xmc4500-relax/include/board.h b/configs/xmc4500-relax/include/board.h index 9c3121a4b6..f45120a0f2 100644 --- a/configs/xmc4500-relax/include/board.h +++ b/configs/xmc4500-relax/include/board.h @@ -53,10 +53,10 @@ /* Clocking *************************************************************************/ /* Default clock initialization - * fPLL = 288MHz => fSYS = 288MHz => fCPU = 144MHz - * => fPB = 144MHz - * => fCCU = 144MHz - * => fETH = 72MHz + * fPLL = 288MHz => fSYS = 288MHz => fCPU = 144MHz + * => fPERIPH = 144MHz + * => fCCU = 144MHz + * => fETH = 72MHz * => fUSB = 48MHz * => fEBU = 72MHz * @@ -79,7 +79,7 @@ /* Select the external crystal as the PLL clock source */ #define BOARD_PLL_CLOCKSRC_XTAL 1 /* PLL Clock source == extnernal crystal */ -#undef BOARD_PLL_CLOCKSRC_OFI /* PLL Clock source != internal fast oscillator */ +#undef BOARD_PLL_CLOCKSRC_OFI /* PLL Clock source != internal fast oscillator */ /* PLL Configuration: * @@ -95,16 +95,21 @@ #define BOARD_PLL_K2DIV 1 #define BOARD_PLL_FREQUENCY 288000000 -/* System frequency is divided down from PLL output */ +/* System frequency, fSYS, is divided down from PLL output */ #define BOARD_SYSDIV 1 /* PLL Output divider to get fSYS */ #define BOARD_SYS_FREQUENCY 288000000 -/* CPU frequency may be divided down from system frequency */ +/* CPU frequency, fCPU, may be divided down from system frequency */ #define BOARD_CPUDIV_ENABLE 1 /* Enable PLL dive by 2 for fCPU */ #define BOARD_CPU_FREQUENCY 144000000 +/* The peripheral clock, fPERIPH, derives from fCPU with no division */ + +#define BOARD_PBDIV 1 /* No division */ +#define BOARD_PERIPH_FREQUENCY 144000000 + /* Standby clock source selection * * BOARD_STDBY_CLOCKSRC_OSI - Internal 32.768KHz slow oscillator @@ -112,7 +117,7 @@ */ #define BOARD_STDBY_CLOCKSRC_OSI 1 -#undef BOARD_STDBY_CLOCKSRC_OSCULP +#undef BOARD_STDBY_CLOCKSRC_OSCULP #define BOARD_STDBY_FREQUENCY 32768 /* USB PLL settings. -- GitLab From 3b5c6da01424f40bf6d5a7807bb2859b2e008928 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Tue, 21 Mar 2017 17:27:08 -0400 Subject: [PATCH 135/990] WIP: Add support for Mikroelektronika Clicker 2 for STM32 --- configs/clicker2-stm32/include/board.h | 418 +++++++++++++++++++++++++ 1 file changed, 418 insertions(+) create mode 100644 configs/clicker2-stm32/include/board.h diff --git a/configs/clicker2-stm32/include/board.h b/configs/clicker2-stm32/include/board.h new file mode 100644 index 0000000000..7f6100d5db --- /dev/null +++ b/configs/clicker2-stm32/include/board.h @@ -0,0 +1,418 @@ +/************************************************************************************ + * configs/clicker2-stm32/include/board.h + * + * Copyright (C) 2017 Verge Inc. All rights reserved. + * Author: Anthony Merlino + * + * Modified from: + * configs/stm32f4discovery/include/board.h + * Copyright (C) 2012, 2014-2016 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. + * + ************************************************************************************/ + +#ifndef __CONFIG_CLICKER2_STM32_INCLUDE_BOARD_H +#define __CONFIG_CLICKER2_STM32_INCLUDE_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#ifndef __ASSEMBLY__ +# include +# include +#endif + +#ifdef __KERNEL__ +# include "stm32_rcc.h" +# include "stm32_sdio.h" +# include "stm32.h" +#endif + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ +/* The Clicker 2 for STM32 board features a 25Hz crystal and 32.768kHz RTC crystal. + * + * This is the canonical configuration: + * System Clock source : PLL (HSE) + * SYSCLK(Hz) : 168000000 Determined by PLL configuration + * HCLK(Hz) : 168000000 (STM32_RCC_CFGR_HPRE) + * AHB Prescaler : 1 (STM32_RCC_CFGR_HPRE) + * APB1 Prescaler : 4 (STM32_RCC_CFGR_PPRE1) + * APB2 Prescaler : 2 (STM32_RCC_CFGR_PPRE2) + * HSE Frequency(Hz) : 25000000 (STM32_BOARD_XTAL) + * PLLM : 25 (STM32_PLLCFG_PLLM) + * PLLN : 336 (STM32_PLLCFG_PLLN) + * PLLP : 2 (STM32_PLLCFG_PLLP) + * PLLQ : 7 (STM32_PLLCFG_PLLQ) + * Main regulator output voltage : Scale1 mode Needed for high speed SYSCLK + * Flash Latency(WS) : 5 + * Prefetch Buffer : OFF + * Instruction cache : ON + * Data cache : ON + * Require 48MHz for USB OTG FS, : Enabled + * SDIO and RNG clock + */ + +/* HSI - 16 MHz RC factory-trimmed + * LSI - 32 KHz RC + * HSE - On-board crystal frequency is 25MHz + * LSE - 32.768 kHz + */ + +#define STM32_BOARD_XTAL 25000000ul + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL +#define STM32_LSE_FREQUENCY 32768 + +/* Main PLL Configuration. + * + * PLL source is HSE + * PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN + * = (25,000,000 / 25) * 336 + * = 336,000,000 + * SYSCLK = PLL_VCO / PLLP + * = 336,000,000 / 2 = 168,000,000 + * USB OTG FS, SDIO and RNG Clock + * = PLL_VCO / PLLQ + * = 48,000,000 + */ + +#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(25) +#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(336) +#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2 +#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(7) + +#define STM32_SYSCLK_FREQUENCY 168000000ul + +/* AHB clock (HCLK) is SYSCLK (168MHz) */ + +#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */ +#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/4 (42MHz) */ + +#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd4 /* PCLK1 = HCLK / 4 */ +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/4) + +/* Timers driven from APB1 will be twice PCLK1 */ + +#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) + +/* APB2 clock (PCLK2) is HCLK/2 (84MHz) */ + +#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */ +#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* Timers driven from APB2 will be twice PCLK2 */ + +#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM9_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM10_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM11_CLKIN (2*STM32_PCLK2_FREQUENCY) + +/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx + * otherwise frequency is 2xAPBx. + * Note: TIM1,8 are on APB2, others on APB1 + */ + +#define BOARD_TIM1_FREQUENCY STM32_HCLK_FREQUENCY +#define BOARD_TIM2_FREQUENCY (STM32_HCLK_FREQUENCY / 2) +#define BOARD_TIM3_FREQUENCY (STM32_HCLK_FREQUENCY / 2) +#define BOARD_TIM4_FREQUENCY (STM32_HCLK_FREQUENCY / 2) +#define BOARD_TIM5_FREQUENCY (STM32_HCLK_FREQUENCY / 2) +#define BOARD_TIM6_FREQUENCY (STM32_HCLK_FREQUENCY / 2) +#define BOARD_TIM7_FREQUENCY (STM32_HCLK_FREQUENCY / 2) +#define BOARD_TIM8_FREQUENCY STM32_HCLK_FREQUENCY + +/* SDIO dividers. Note that slower clocking is required when DMA is disabled + * in order to avoid RX overrun/TX underrun errors due to delayed responses + * to service FIFOs in interrupt driven mode. These values have not been + * tuned!!! + * + * SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(118+2)=400 KHz + */ + +#define SDIO_INIT_CLKDIV (118 << SDIO_CLKCR_CLKDIV_SHIFT) + +/* DMA ON: SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(1+2)=16 MHz + * DMA OFF: SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(2+2)=12 MHz + */ + +#ifdef CONFIG_SDIO_DMA +# define SDIO_MMCXFR_CLKDIV (1 << SDIO_CLKCR_CLKDIV_SHIFT) +#else +# define SDIO_MMCXFR_CLKDIV (2 << SDIO_CLKCR_CLKDIV_SHIFT) +#endif + +/* DMA ON: SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(1+2)=16 MHz + * DMA OFF: SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(2+2)=12 MHz + */ + +#ifdef CONFIG_SDIO_DMA +# define SDIO_SDXFR_CLKDIV (1 << SDIO_CLKCR_CLKDIV_SHIFT) +#else +# define SDIO_SDXFR_CLKDIV (2 << SDIO_CLKCR_CLKDIV_SHIFT) +#endif + +/* LED definitions ******************************************************************/ +/* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any + * way. The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +#define BOARD_LED1 0 +#define BOARD_LED2 1 +#define BOARD_NLEDS 2 + +/* LED bits for use with board_userled_all() */ + +#define BOARD_LED1_BIT (1 << BOARD_LED1) +#define BOARD_LED2_BIT (1 << BOARD_LED2) + +/* If CONFIG_ARCH_LEDs is defined, then NuttX will control the 2 LEDs on board the + * Clicker2 for STM32. The following definitions describe how NuttX controls the LEDs: + * + * SYMBOL Meaning LED state + * LED1 LED2 + * ------------------- ----------------------- -------- -------- + * LED_STARTED NuttX has been started OFF OFF + * LED_HEAPALLOCATE Heap has been allocated OFF OFF + * LED_IRQSENABLED Interrupts enabled OFF OFF + * LED_STACKCREATED Idle stack created ON OFF + * LED_INIRQ In an interrupt N/C ON + * LED_SIGNAL In a signal handler No change + * LED_ASSERTION An assertion failed No change + * LED_PANIC The system has crashed OFF Blinking + * LED_IDLE STM32 is is sleep mode Not used + */ + +#define LED_STARTED 0 +#define LED_HEAPALLOCATE 0 +#define LED_IRQSENABLED 0 +#define LED_STACKCREATED 1 +#define LED_INIRQ 2 +#define LED_SIGNAL 3 +#define LED_ASSERTION 3 +#define LED_PANIC 4 + +/* Button definitions ***************************************************************/ +/* The STM32F4 Discovery supports one button: */ + +#define BUTTON_LEFT 0 +#define BUTTON_RIGHT 1 +#define NUM_BUTTONS 2 + +#define BUTTON_LEFT_BIT (1 << BUTTON_LEFT) +#define BUTTON_RIGHT_BIT (1 << BUTTON_RIGHT) + + + + + + + + + + + + + + +/* Alternate function pin selections ************************************************/ +/* CAN */ + +#ifndef CONFIG_STM32_FSMC +# define GPIO_CAN1_RX GPIO_CAN1_RX_3 +# define GPIO_CAN1_TX GPIO_CAN1_TX_3 +#endif + +#ifndef CONFIG_STM32_ETHMAC +# define GPIO_CAN2_RX GPIO_CAN2_RX_1 +# define GPIO_CAN2_TX GPIO_CAN2_TX_1 +#endif + +/* UART2: + * + * The board breaks out pins PD5 and PD6 for UART2 on Click board slot 1. + */ + +#ifndef CONFIG_STM32F4DISBB +# define GPIO_USART2_RX GPIO_USART2_RX_2 +# define GPIO_USART2_TX GPIO_USART2_TX_2 +#endif + +/* UART3: (Used in pseudoterm configuration) */ + +#define GPIO_USART3_TX GPIO_USART3_TX_1 +#define GPIO_USART3_RX GPIO_USART3_RX_1 + +/* UART6: + * + * The STM32F4DIS-BB base board provides RS-232 drivers and a DB9 connector + * for USART6. This is the preferred serial console for use with the STM32F4DIS-BB. + */ + +#define GPIO_USART6_RX GPIO_USART6_RX_1 +#define GPIO_USART6_TX GPIO_USART6_TX_1 + +/* PWM + * + * The STM32F4 Discovery has no real on-board PWM devices, but the board can be + * configured to output a pulse train using TIM4 CH2 on PD13. + */ + +#define GPIO_TIM4_CH2OUT GPIO_TIM4_CH2OUT_2 + +/* RGB LED + * + * R = TIM1 CH1 on PE9 | G = TIM2 CH2 on PA1 | B = TIM3 CH3 on PB0 + */ + +#define GPIO_TIM1_CH1OUT GPIO_TIM1_CH1OUT_2 +#define GPIO_TIM2_CH2OUT GPIO_TIM2_CH2OUT_1 +#define GPIO_TIM3_CH3OUT GPIO_TIM3_CH3OUT_1 + +/* SPI - There is a MEMS device on SPI1 using these pins: */ + +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 +#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1 + +/* SPI2 - Test MAX31855 on SPI2 PB10 = SCK, PB14 = MISO */ + +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1 +#define GPIO_SPI2_SCK GPIO_SPI2_SCK_1 + +/* I2C config to use with Nunchuk PB7 (SDA) and PB8 (SCL) */ + +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_1 + +/* Timer Inputs/Outputs (see the README.txt file for options) */ + +#define GPIO_TIM2_CH1IN GPIO_TIM2_CH1IN_2 +#define GPIO_TIM2_CH2IN GPIO_TIM2_CH2IN_1 + +#define GPIO_TIM8_CH1IN GPIO_TIM8_CH1IN_1 +#define GPIO_TIM8_CH2IN GPIO_TIM8_CH2IN_1 + +/* Ethernet *************************************************************************/ + +#if defined(CONFIG_STM32F4DISBB) && defined(CONFIG_STM32_ETHMAC) + /* RMII interface to the LAN8720 PHY */ + +# ifndef CONFIG_STM32_RMII +# error CONFIG_STM32_RMII must be defined +# endif + + /* Clocking is provided by an external 25Mhz XTAL */ + +# ifndef CONFIG_STM32_RMII_EXTCLK +# error CONFIG_STM32_RMII_EXTCLK must be defined +# endif + + /* Pin disambiguation */ + +# define GPIO_ETH_RMII_TX_EN GPIO_ETH_RMII_TX_EN_1 +# define GPIO_ETH_RMII_TXD0 GPIO_ETH_RMII_TXD0_1 +# define GPIO_ETH_RMII_TXD1 GPIO_ETH_RMII_TXD1_1 +# define GPIO_ETH_PPS_OUT GPIO_ETH_PPS_OUT_1 + +#endif + +/* DMA Channl/Stream Selections *****************************************************/ +/* Stream selections are arbitrary for now but might become important in the future + * if we set aside more DMA channels/streams. + * + * SDIO DMA + * DMAMAP_SDIO_1 = Channel 4, Stream 3 + * DMAMAP_SDIO_2 = Channel 4, Stream 6 + */ + +#define DMAMAP_SDIO DMAMAP_SDIO_1 + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +void stm32_boardinitialize(void); + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __CONFIG_CLICKER2_STM32_INCLUDE_BOARD_H */ -- GitLab From 9919e33705c6912f3ab482cf383db5fbeee4c671 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 21 Mar 2017 15:31:53 -0600 Subject: [PATCH 136/990] Trivial changes to comments. --- configs/xmc4500-relax/include/board.h | 19 ++++++++++++------- 1 file changed, 12 insertions(+), 7 deletions(-) diff --git a/configs/xmc4500-relax/include/board.h b/configs/xmc4500-relax/include/board.h index f45120a0f2..751e803170 100644 --- a/configs/xmc4500-relax/include/board.h +++ b/configs/xmc4500-relax/include/board.h @@ -53,16 +53,21 @@ /* Clocking *************************************************************************/ /* Default clock initialization - * fPLL = 288MHz => fSYS = 288MHz => fCPU = 144MHz - * => fPERIPH = 144MHz - * => fCCU = 144MHz - * => fETH = 72MHz - * => fUSB = 48MHz - * => fEBU = 72MHz + * + * fXTAL = 12Mhz + * -> fPLL = (fXTAL / (2 * 1) * 48) = 288MHz + * -> fSYS = (fPLL / 1) = 288MHz + * -> fCPU = (fSYS / 2) = 144MHz + * -> fPERIPH = (fCPU / 1) = 144MHz + * -> fCCU = (fSYS / 2) = 144MHz + * -> fETH = 72MHz (REVISIT) + * -> fUSB = 48MHz (REVISIT) + * -> fEBU = 72MHz (REVISIT) * * fUSBPLL Disabled, only enabled if SCU_CLK_USBCLKCR_USBSEL_USBPLL is selected * - * fOFI = 24MHz => fWDT = 24MHz + * fOFI = 24MHz + * -> fWDT = 24MHz (REVISIT) */ #undef BOARD_FOFI_CALIBRATION /* Enable factory calibration */ -- GitLab From 6bc83dd53c4e786c7eb1325ef08d50c0c0d69c49 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 21 Mar 2017 15:35:12 -0600 Subject: [PATCH 137/990] Cosmetic changes from review of last PR. --- configs/clicker2-stm32/include/board.h | 25 ------------------------- 1 file changed, 25 deletions(-) diff --git a/configs/clicker2-stm32/include/board.h b/configs/clicker2-stm32/include/board.h index 7f6100d5db..4af984b607 100644 --- a/configs/clicker2-stm32/include/board.h +++ b/configs/clicker2-stm32/include/board.h @@ -251,19 +251,6 @@ #define BUTTON_LEFT_BIT (1 << BUTTON_LEFT) #define BUTTON_RIGHT_BIT (1 << BUTTON_RIGHT) - - - - - - - - - - - - - /* Alternate function pin selections ************************************************/ /* CAN */ @@ -397,18 +384,6 @@ extern "C" * Public Function Prototypes ************************************************************************************/ -/************************************************************************************ - * Name: stm32_boardinitialize - * - * Description: - * All STM32 architectures must provide the following entry point. This entry point - * is called early in the initialization -- after all memory has been configured - * and mapped but before any devices have been initialized. - * - ************************************************************************************/ - -void stm32_boardinitialize(void); - #undef EXTERN #if defined(__cplusplus) } -- GitLab From 82a5dfddb4a4bab6211f142857b87cdb3375ac32 Mon Sep 17 00:00:00 2001 From: rg Date: Tue, 21 Mar 2017 16:44:11 -0600 Subject: [PATCH 138/990] The attached .patch implements DMA support for the stm32f4 I2C. Max and I have verified that it works on our systems. --- arch/arm/src/stm32/Kconfig | 10 + arch/arm/src/stm32/stm32f40xxx_i2c.c | 347 +++++++++++++++++++++++++-- 2 files changed, 332 insertions(+), 25 deletions(-) diff --git a/arch/arm/src/stm32/Kconfig b/arch/arm/src/stm32/Kconfig index 8dea045fda..de2c8fe23b 100644 --- a/arch/arm/src/stm32/Kconfig +++ b/arch/arm/src/stm32/Kconfig @@ -6190,6 +6190,16 @@ config STM32_I2C_DUTY16_9 default n depends on STM32_I2C +config STM32_I2C_DMA + bool "I2C DMA Support" + default n + depends on STM32_I2C && STM32_STM32F40XX && STM32_DMA1 + ---help--- + This option enables the DMA for I2C transfers. + Note: The user can define CONFIG_I2C_DMAPRIO: a custom priority value for the + I2C dma streams, else the default priority level is set to medium. + Note: This option is compatible with CONFIG_I2C_POLLED. + endmenu menu "SDIO Configuration" diff --git a/arch/arm/src/stm32/stm32f40xxx_i2c.c b/arch/arm/src/stm32/stm32f40xxx_i2c.c index c0d1a2d6fd..3d7d5567f8 100644 --- a/arch/arm/src/stm32/stm32f40xxx_i2c.c +++ b/arch/arm/src/stm32/stm32f40xxx_i2c.c @@ -63,7 +63,6 @@ * - 1 x 10 bit addresses + 1 x 7 bit address (?) * - plus the broadcast address (general call) * - Multi-master support - * - DMA (to get rid of too many CPU wake-ups and interventions) * - Be ready for IPMI */ @@ -95,6 +94,7 @@ #include "stm32_rcc.h" #include "stm32_i2c.h" #include "stm32_waste.h" +#include "stm32_dma.h" /* At least one I2C peripheral must be enabled */ @@ -162,6 +162,21 @@ #define MKI2C_OUTPUT(p) (((p) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | I2C_OUTPUT) +/* I2C DMA priority */ + +#ifdef CONFIG_STM32_I2C_DMA + +# if defined(CONFIG_I2C_DMAPRIO) +# if (CONFIG_I2C_DMAPRIO & ~DMA_SCR_PL_MASK) != 0 +# error "Illegal value for CONFIG_I2C_DMAPRIO" +# endif +# define I2C_DMA_PRIO CONFIG_I2C_DMAPRIO +# else +# define I2C_DMA_PRIO DMA_SCR_PRIMED +# endif + +#endif + /* Debug ****************************************************************************/ /* I2C event trace logic. NOTE: trace uses the internal, non-standard, low-level @@ -253,7 +268,7 @@ struct stm32_i2c_priv_s struct i2c_msg_s *msgv; /* Message list */ uint8_t *ptr; /* Current message buffer */ uint32_t frequency; /* Current I2C frequency */ - int dcnt; /* Current message length */ + volatile int dcnt; /* Current message length */ uint16_t flags; /* Current message flags */ bool check_addr_ACK; /* Flag to signal if on next interrupt address has ACKed */ uint8_t total_msg_len; /* Flag to signal a short read sequence */ @@ -270,6 +285,15 @@ struct stm32_i2c_priv_s #endif uint32_t status; /* End of transfer SR2|SR1 status */ + + /* I2C DMA support */ + +#ifdef CONFIG_STM32_I2C_DMA + DMA_HANDLE txdma; /* TX DMA handle */ + DMA_HANDLE rxdma; /* RX DMA handle */ + uint8_t txch; /* TX DMA channel */ + uint8_t rxch; /* RX DMA channel */ +#endif }; /************************************************************************************ @@ -337,6 +361,13 @@ static int stm32_i2c_transfer(FAR struct i2c_master_s *dev, FAR struct i2c_msg_s static int stm32_i2c_reset(FAR struct i2c_master_s *dev); #endif +/* DMA support */ + +#ifdef CONFIG_STM32_I2C_DMA +static void stm32_i2c_dmarxcallback(DMA_HANDLE handle, uint8_t isr, void *arg); +static void stm32_i2c_dmatxcallback(DMA_HANDLE handle, uint8_t isr, void *arg); +#endif + /************************************************************************************ * Private Data ************************************************************************************/ @@ -398,7 +429,16 @@ static struct stm32_i2c_priv_s stm32_i2c1_priv = .ptr = NULL, .dcnt = 0, .flags = 0, - .status = 0 + .status = 0, +#ifdef CONFIG_STM32_I2C_DMA +# ifndef CONFIG_STM32_DMA1 +# error "I2C1 enabled with DMA but corresponding DMA controller 1 is not enabled!" +# endif + /* TODO: ch for i2c 1 and 2 could be *X_2 based on stream priority */ + + .rxch = DMAMAP_I2C1_RX, + .txch = DMAMAP_I2C1_TX, +#endif }; #endif @@ -428,7 +468,14 @@ static struct stm32_i2c_priv_s stm32_i2c2_priv = .ptr = NULL, .dcnt = 0, .flags = 0, - .status = 0 + .status = 0, +#ifdef CONFIG_STM32_I2C_DMA +# ifndef CONFIG_STM32_DMA1 +# error "I2C2 enabled with DMA but corresponding DMA controller 1 is not enabled!" +# endif + .rxch = DMAMAP_I2C2_RX, + .txch = DMAMAP_I2C2_TX, +#endif }; #endif @@ -458,7 +505,14 @@ static struct stm32_i2c_priv_s stm32_i2c3_priv = .ptr = NULL, .dcnt = 0, .flags = 0, - .status = 0 + .status = 0, +#ifdef CONFIG_STM32_I2C_DMA +# ifndef CONFIG_STM32_DMA1 +# error "I2C3 enabled with DMA but corresponding DMA controller 1 is not enabled!" +# endif + .rxch = DMAMAP_I2C3_RX, + .txch = DMAMAP_I2C3_TX, +#endif }; #endif @@ -521,7 +575,7 @@ static inline void stm32_i2c_sem_wait(FAR struct stm32_i2c_priv_s *priv) { while (sem_wait(&priv->sem_excl) != 0) { - ASSERT(errno == EINTR); + DEBUGASSERT(errno == EINTR); } } @@ -1185,6 +1239,12 @@ static inline void stm32_i2c_enablefsmc(uint32_t ahbenr) static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv) { uint32_t status; +#ifndef CONFIG_I2C_POLLED + uint32_t regval; +#endif +#ifdef CONFIG_STM32_I2C_DMA + uint16_t cr2; +#endif i2cinfo("I2C ISR called\n"); @@ -1228,6 +1288,23 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv) * stm32_i2c_sem_waitdone() waiting process. */ +#ifdef CONFIG_STM32_I2C_DMA + /* If ISR gets called (ex. polling mode) while DMA is still in + * progress, we should just return and let the DMA finish. + */ + + cr2 = stm32_i2c_getreg(priv, STM32_I2C_CR2_OFFSET); + if ((cr2 & I2C_CR2_DMAEN) != 0) + { +#ifdef CONFIG_DEBUG_I2C_INFO + size_t left = stm32_dmaresidual(priv->rxdma); + + i2cinfo("DMA in progress: %ld [bytes] remainining. Returning.\n", left); +#endif + return OK; + } +#endif + if (priv->dcnt == -1 && priv->msgc > 0) { i2cinfo("Switch to new message\n"); @@ -1484,6 +1561,46 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv) /* Trace */ stm32_i2c_traceevent(priv, I2CEVENT_ADDRESS_ACKED, 0); + +#ifdef CONFIG_STM32_I2C_DMA + /* DMA only when not doing a short read */ + + i2cinfo("Starting dma transfer and disabling interrupts\n"); + + /* The DMA must be initialized and enabled before the I2C data transfer. + * The DMAEN bit must be set in the I2C_CR2 register before the ADDR event. + */ + + stm32_dmasetup(priv->rxdma, priv->config->base+STM32_I2C_DR_OFFSET, + (uint32_t) priv->ptr, priv->dcnt, + DMA_SCR_DIR_P2M | + DMA_SCR_MSIZE_8BITS | + DMA_SCR_PSIZE_8BITS | + DMA_SCR_MINC | + I2C_DMA_PRIO); + + /* Do not enable the ITBUFEN bit in the I2C_CR2 register if DMA is + * used. + */ + + stm32_i2c_modifyreg(priv, STM32_I2C_CR2_OFFSET, I2C_CR2_ITBUFEN, 0); + +#ifndef CONFIG_I2C_POLLED + /* Now let DMA do all the work, disable i2c interrupts */ + + regval = stm32_i2c_getreg(priv, STM32_I2C_CR2_OFFSET); + regval &= ~I2C_CR2_ALLINTS; + stm32_i2c_putreg(priv, STM32_I2C_CR2_OFFSET, regval); +#endif + + /* The user can generate a Stop condition in the DMA Transfer Complete + * interrupt routine if enabled. This will be done in the dma rx callback + * Start DMA. + */ + + stm32_dmastart(priv->rxdma, stm32_i2c_dmarxcallback, priv, false); + stm32_i2c_modifyreg(priv, STM32_I2C_CR2_OFFSET, 0, I2C_CR2_DMAEN); +#endif } } @@ -1520,19 +1637,67 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv) if (priv->dcnt >= 1) { - /* Transmitting message. Send byte == write data into write register */ +#ifdef CONFIG_STM32_I2C_DMA + /* if DMA is enabled, only makes sense to make use of it for longer + than 1 B transfers.. */ - stm32_i2c_putreg(priv, STM32_I2C_DR_OFFSET, *priv->ptr++); + if (priv->dcnt > 1) + { + i2cinfo("Starting dma transfer and disabling interrupts\n"); - /* Decrease current message length */ + /* The DMA must be initialized and enabled before the I2C data transfer. + * The DMAEN bit must be set in the I2C_CR2 register before the ADDR event. + */ - stm32_i2c_traceevent(priv, I2CEVENT_WRITE_TO_DR, priv->dcnt); - priv->dcnt--; + stm32_dmasetup(priv->txdma, priv->config->base+STM32_I2C_DR_OFFSET, + (uint32_t) priv->ptr, priv->dcnt, + DMA_SCR_DIR_M2P | + DMA_SCR_MSIZE_8BITS | + DMA_SCR_PSIZE_8BITS | + DMA_SCR_MINC | + I2C_DMA_PRIO ); + + /* Do not enable the ITBUFEN bit in the I2C_CR2 register if DMA is + * used. + */ + + stm32_i2c_modifyreg(priv, STM32_I2C_CR2_OFFSET, I2C_CR2_ITBUFEN, 0); + +#ifndef CONFIG_I2C_POLLED + /* Now let DMA do all the work, disable i2c interrupts */ + regval = stm32_i2c_getreg(priv, STM32_I2C_CR2_OFFSET); + regval &= ~I2C_CR2_ALLINTS; + stm32_i2c_putreg(priv, STM32_I2C_CR2_OFFSET, regval); +#endif + + /* In the interrupt routine after the EOT interrupt, disable DMA + * requests then wait for a BTF event before programming the Stop + * condition. To do this, we'll just call the ISR again in + * dma tx callback, in which point we fall into the msgc==0 case + * which ultimately sends the stop..TODO: but we don't explicitly + * wait for BTF bit being set... + * Start DMA. + */ + + stm32_i2c_modifyreg(priv, STM32_I2C_CR2_OFFSET, 0, I2C_CR2_DMAEN); + stm32_dmastart(priv->txdma, stm32_i2c_dmatxcallback, priv, false); + } + else +#endif /* CONFIG_STM32_I2C_DMA */ + { + /* Transmitting message. Send byte == write data into write register */ + + stm32_i2c_putreg(priv, STM32_I2C_DR_OFFSET, *priv->ptr++); + + /* Decrease current message length */ + + stm32_i2c_traceevent(priv, I2CEVENT_WRITE_TO_DR, priv->dcnt); + priv->dcnt--; + } } else if (priv->dcnt == 0) { - /* After last byte, check what to do based on next message flags */ if (priv->msgc == 0) @@ -1678,6 +1843,7 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv) stm32_i2c_traceevent(priv, I2CEVENT_READ_2, 0); } +#ifndef CONFIG_STM32_I2C_DMA /* Case total message length >= 3 */ else if (priv->dcnt >= 4 && priv->total_msg_len >= 3) @@ -1757,6 +1923,7 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv) priv->dcnt = -1; } +#endif /* CONFIG_STM32_I2C_DMA */ /* Error handling for read mode */ @@ -1765,7 +1932,8 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv) i2cinfo("I2C read mode no correct state detected\n"); i2cinfo(" state %i, dcnt=%i\n", status, priv->dcnt); - /* set condition to terminate ISR and wake waiting thread */ + /* Set condition to terminate ISR and wake waiting thread */ + priv->dcnt = -1; priv->msgc = 0; stm32_i2c_traceevent(priv, I2CEVENT_READ_ERROR, 0); @@ -1804,9 +1972,9 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv) else { - #ifdef CONFIG_I2C_POLLED +#ifdef CONFIG_I2C_POLLED stm32_i2c_traceevent(priv, I2CEVENT_POLL_DEV_NOT_RDY, 0); - #else +#else /* Read rest of the state */ status |= (stm32_i2c_getreg(priv, STM32_I2C_SR2_OFFSET) << 16); @@ -1814,12 +1982,12 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv) i2cinfo(" No correct state detected(start bit, read or write) \n"); i2cinfo(" state %i\n", status); - /* set condition to terminate ISR and wake waiting thread */ + /* Set condition to terminate ISR and wake waiting thread */ priv->dcnt = -1; priv->msgc = 0; stm32_i2c_traceevent(priv, I2CEVENT_STATE_ERROR, 0); - #endif +#endif } /* Messages handling(2/2) @@ -1842,9 +2010,9 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv) priv->msgv = NULL; - #ifdef CONFIG_I2C_POLLED +#ifdef CONFIG_I2C_POLLED priv->intstate = INTSTATE_DONE; - #else +#else /* Clear all interrupts */ uint32_t regval; @@ -1863,12 +2031,98 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv) sem_post(&priv->sem_isr); priv->intstate = INTSTATE_DONE; } - #endif +#endif } return OK; } +/***************************************************************************** + * Name: stm32_i2c_dmarxcallback + * + * Description: + * Called when the RX DMA completes + * + *****************************************************************************/ + +#ifdef CONFIG_STM32_I2C_DMA +static void stm32_i2c_dmarxcallback(DMA_HANDLE handle, uint8_t status, void *arg) +{ +#ifndef CONFIG_I2C_POLLED + uint32_t regval; +#endif + + i2cinfo("DMA rx callback, status = %d \n", status); + + FAR struct stm32_i2c_priv_s *priv = (FAR struct stm32_i2c_priv_s *)arg; + + priv->dcnt = -1; + + /* The user can generate a Stop condition in the DMA Transfer Complete + * interrupt routine if enabled. + */ + + stm32_i2c_sendstop(priv); + + /* Let the I2C periph know to stop DMA transfers, also is used by ISR to check + * if DMA is done. + */ + + stm32_i2c_modifyreg(priv, STM32_I2C_CR2_OFFSET, I2C_CR2_DMAEN, 0); + +#ifndef CONFIG_I2C_POLLED + /* Re-enable interrupts */ + + regval = stm32_i2c_getreg(priv, STM32_I2C_CR2_OFFSET); + regval |= (I2C_CR2_ITERREN | I2C_CR2_ITEVFEN); + stm32_i2c_putreg(priv, STM32_I2C_CR2_OFFSET, regval); +#endif + + /* let the ISR routine take care of shutting down or switching to next msg */ + + stm32_i2c_isr(priv); +} +#endif /* ifdef CONFIG_STM32_I2C_DMA */ + +/***************************************************************************** + * Name: stm32_i2c_dmarxcallback + * + * Description: + * Called when the RX DMA completes + * + *****************************************************************************/ + +#ifdef CONFIG_STM32_I2C_DMA +static void stm32_i2c_dmatxcallback(DMA_HANDLE handle, uint8_t status, void *arg) +{ +#ifndef CONFIG_I2C_POLLED + uint32_t regval; +#endif + + i2cinfo("DMA tx callback, status = %d \n", status); + + FAR struct stm32_i2c_priv_s *priv = (FAR struct stm32_i2c_priv_s *)arg; + + priv->dcnt = 0; + + /* In the interrupt routine after the EOT interrupt, disable DMA requests */ + + stm32_i2c_modifyreg(priv, STM32_I2C_CR2_OFFSET, I2C_CR2_DMAEN, 0); + +#ifndef CONFIG_I2C_POLLED + /* re-enable interrupts */ + + regval = stm32_i2c_getreg(priv, STM32_I2C_CR2_OFFSET); + regval |= (I2C_CR2_ITERREN | I2C_CR2_ITEVFEN); + stm32_i2c_putreg(priv, STM32_I2C_CR2_OFFSET, regval); +#endif + + /* let the ISR routine take care of shutting down or switching to next msg */ + + stm32_i2c_isr(priv); +} +#endif /* ifdef CONFIG_STM32_I2C_DMA */ + /************************************************************************************ * Name: stm32_i2c1_isr * @@ -1914,7 +2168,7 @@ static int stm32_i2c3_isr(int irq, void *context, FAR void *arg) return stm32_i2c_isr(&stm32_i2c3_priv); } #endif -#endif +#endif /* CONFIG_I2C_POLLED */ /************************************************************************************ * Private Initialization and Deinitialization @@ -1972,6 +2226,15 @@ static int stm32_i2c_init(FAR struct stm32_i2c_priv_s *priv) stm32_i2c_setclock(priv, 100000); +#ifdef CONFIG_STM32_I2C_DMA + /* If, in the I2C_CR2 register, the LAST bit is set, I2C automatically + * sends a NACK after the next byte following EOT_1. + * Clear DMA en just in case. + */ + + stm32_i2c_modifyreg(priv, STM32_I2C_CR2_OFFSET, I2C_CR2_DMAEN, I2C_CR2_LAST); +#endif + /* Enable I2C */ stm32_i2c_putreg(priv, STM32_I2C_CR1_OFFSET, I2C_CR1_PE); @@ -1991,6 +2254,7 @@ static int stm32_i2c_deinit(FAR struct stm32_i2c_priv_s *priv) /* Disable I2C */ stm32_i2c_putreg(priv, STM32_I2C_CR1_OFFSET, 0); + stm32_i2c_putreg(priv, STM32_I2C_CR2_OFFSET, 0); /* Unconfigure GPIO pins */ @@ -2006,6 +2270,13 @@ static int stm32_i2c_deinit(FAR struct stm32_i2c_priv_s *priv) irq_detach(priv->config->er_irq); #endif +#ifdef CONFIG_STM32_I2C_DMA + /* Disable DMA */ + + stm32_dmastop(priv->txdma); + stm32_dmastop(priv->rxdma); +#endif + /* Disable clocking */ modifyreg32(STM32_RCC_APB1ENR, priv->config->clk_bit, 0); @@ -2035,7 +2306,15 @@ static int stm32_i2c_transfer(FAR struct i2c_master_s *dev, FAR struct i2c_msg_s #endif int ret = 0; - ASSERT(count); + DEBUGASSERT(count); + +#ifdef CONFIG_STM32_I2C_DMA + /* stop DMA just in case */ + + stm32_i2c_modifyreg(priv, STM32_I2C_CR2_OFFSET, I2C_CR2_DMAEN, 0); + stm32_dmastop(priv->rxdma); + stm32_dmastop(priv->txdma); +#endif #ifdef I2C1_FSMC_CONFLICT /* Disable FSMC that shares a pin with I2C1 (LBAR) */ @@ -2246,11 +2525,11 @@ static int stm32_i2c_reset(FAR struct i2c_master_s *dev) uint32_t frequency; int ret = ERROR; - ASSERT(dev); + DEBUGASSERT(dev); /* Our caller must own a ref */ - ASSERT(priv->refs > 0); + DEBUGASSERT(priv->refs > 0); /* Lock out other clients */ @@ -2412,6 +2691,19 @@ FAR struct i2c_master_s *stm32_i2cbus_initialize(int port) { stm32_i2c_sem_init(priv); stm32_i2c_init(priv); + +#ifdef CONFIG_STM32_I2C_DMA + /* Get DMA channels. NOTE: stm32_dmachannel() will always assign the DMA channel. + * if the channel is not available, then stm32_dmachannel() will block and wait + * until the channel becomes available. WARNING: If you have another device sharing + * a DMA channel with SPI and the code never releases that channel, then the call + * to stm32_dmachannel() will hang forever in this function! Don't let your + * design do that! + */ + priv->rxdma = stm32_dmachannel(priv->rxch); + priv->txdma = stm32_dmachannel(priv->txch); + DEBUGASSERT(priv->rxdma && priv->txdma); +#endif /* #ifdef CONFIG_STM32_I2C_DMA */ } leave_critical_section(flags); @@ -2431,7 +2723,7 @@ int stm32_i2cbus_uninitialize(FAR struct i2c_master_s *dev) FAR struct stm32_i2c_priv_s *priv = (struct stm32_i2c_priv_s *)dev; irqstate_t flags; - ASSERT(dev); + DEBUGASSERT(dev); /* Decrement reference count and check for underflow */ @@ -2454,6 +2746,11 @@ int stm32_i2cbus_uninitialize(FAR struct i2c_master_s *dev) stm32_i2c_deinit(priv); +#ifdef CONFIG_STM32_I2C_DMA + stm32_dmafree(priv->rxdma); + stm32_dmafree(priv->txdma); +#endif + /* Release unused resources */ stm32_i2c_sem_destroy(priv); -- GitLab From ea93357a1ede3e82e7333f4790b322ad3d1ec5d2 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 21 Mar 2017 17:05:47 -0600 Subject: [PATCH 139/990] XMC4xxx: Fix a typo in the SCU header file --- arch/arm/src/xmc4/chip/xmc4_scu.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/arch/arm/src/xmc4/chip/xmc4_scu.h b/arch/arm/src/xmc4/chip/xmc4_scu.h index 38d26051b7..2d22084252 100644 --- a/arch/arm/src/xmc4/chip/xmc4_scu.h +++ b/arch/arm/src/xmc4/chip/xmc4_scu.h @@ -889,7 +889,7 @@ #define SCU_PBCLKCR_PBDIV (1 << 0) /* Bit 0: PB Clock Divider Enable */ # define SCU_PBCLKCR_PBDIV_FCPU (0) /* 0=fCPU */ -# define SCU_PBCLKCR_PBDIV_DIV2 ((1 << 0) /* 1=fCPU/2 */ +# define SCU_PBCLKCR_PBDIV_DIV2 (1 << 0) /* 1=fCPU/2 */ /* USB Clock Control */ -- GitLab From e336d248980a9514dbeac11946a49670d6d2ee41 Mon Sep 17 00:00:00 2001 From: Masayuki Ishikawa Date: Wed, 22 Mar 2017 08:21:22 +0900 Subject: [PATCH 140/990] drivers/lcd/st7565.c: Use ST7565_POWERCTRL_INT instead of ST7565_POWERCTRL_BRF --- drivers/lcd/st7565.c | 2 +- drivers/lcd/st7565.h | 2 -- 2 files changed, 1 insertion(+), 3 deletions(-) diff --git a/drivers/lcd/st7565.c b/drivers/lcd/st7565.c index 1153c1568b..d25583a745 100644 --- a/drivers/lcd/st7565.c +++ b/drivers/lcd/st7565.c @@ -1041,7 +1041,7 @@ FAR struct lcd_dev_s *st7565_initialize(FAR struct st7565_lcd_s *lcd, up_mdelay(2); (void)st7565_send_one_data(priv, ST7565_POWERCTRL_BR); up_mdelay(2); - (void)st7565_send_one_data(priv, ST7565_POWERCTRL_BRF); + (void)st7565_send_one_data(priv, ST7565_POWERCTRL_INT); (void)st7565_send_one_data(priv, ST7565_REG_RES_4_5); (void)st7565_send_one_data(priv, ST7565_SETEVMODE); diff --git a/drivers/lcd/st7565.h b/drivers/lcd/st7565.h index e4788379b9..cc9d17dd0f 100644 --- a/drivers/lcd/st7565.h +++ b/drivers/lcd/st7565.h @@ -102,8 +102,6 @@ */ #define ST7565_POWERCTRL_B 0x2c /* 0x2c: Booster=ON */ #define ST7565_POWERCTRL_BR 0x2e /* 0x2e: Booster=ON V/R=ON */ -#define ST7565_POWERCTRL_BRF 0x2f /* 0x23: Booster=ON V/R=ON V/F=ON */ - #define ST7565_POWERCTRL_INT 0x2f /* 0x2f: Only the internal power supply is used */ /* Regulation Resistior ratio V0 = (1+Rb/Ra)*Vev */ -- GitLab From 3f3aa73b8f7bea426f10c3085cf7ed0379a8e464 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 21 Mar 2017 17:51:55 -0600 Subject: [PATCH 141/990] XMC4xxx: USIC SCTR register, appears taht both WLE and FLE fields hold value - 1. --- arch/arm/src/xmc4/chip/xmc4_usic.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/arch/arm/src/xmc4/chip/xmc4_usic.h b/arch/arm/src/xmc4/chip/xmc4_usic.h index 462ac44c95..274d0fae53 100644 --- a/arch/arm/src/xmc4/chip/xmc4_usic.h +++ b/arch/arm/src/xmc4/chip/xmc4_usic.h @@ -563,7 +563,7 @@ # define USIC_SCTR_TRM_ACTIVE (3 << USIC_SCTR_TRM_SHIFT) /* Active without regard to signal level */ #define USIC_SCTR_FLE_SHIFT (16) /* Bits 16-21: Frame Length */ #define USIC_SCTR_FLE_MASK (0x3f << USIC_SCTR_FLE_SHIFT) -# define USIC_SCTR_FLE(n) ((uint32_t)(n) << USIC_SCTR_FLE_SHIFT) +# define USIC_SCTR_FLE(n) ((uint32_t)((n)-1) << USIC_SCTR_FLE_SHIFT) #define USIC_SCTR_WLE_SHIFT (24) /* Bits 24-27: Word Length */ #define USIC_SCTR_WLE_MASK (15 << USIC_SCTR_WLE_SHIFT) # define USIC_SCTR_WLE(n) ((uint32_t)((n)-1) << USIC_SCTR_WLE_SHIFT) -- GitLab From 4af55cee6e377f5fddf287f8e1d7fc4a9cca206f Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 22 Mar 2017 00:55:44 +0000 Subject: [PATCH 142/990] README.txt edited online with Bitbucket --- configs/xmc4500-relax/README.txt | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/configs/xmc4500-relax/README.txt b/configs/xmc4500-relax/README.txt index e1fd46fa83..9fb7e29c2e 100644 --- a/configs/xmc4500-relax/README.txt +++ b/configs/xmc4500-relax/README.txt @@ -11,10 +11,8 @@ Status ====== 2017-03-21: The XMC4500 Relax boots into NSH, provides the NSH prompt, - and the LEDs are working. But there is a problem with the USIC baud - (probably); I get garbage on the serial console. This probably means - that either the peripheral clocking is wrong or the baud configuration - is wrong. + and the LEDs are working. But there is a problem with sserial input. + The most likely reason for this is there are no serial RX interripts. Serial Console ============== -- GitLab From a1f0802855d995d1202bdaed42844b07c4077673 Mon Sep 17 00:00:00 2001 From: Masayuki Ishikawa Date: Wed, 22 Mar 2017 10:04:37 +0900 Subject: [PATCH 143/990] Kconfig: Change the minimum SMP_NCPUS to 1 --- sched/Kconfig | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sched/Kconfig b/sched/Kconfig index 3dc0e91eba..68eea620cf 100644 --- a/sched/Kconfig +++ b/sched/Kconfig @@ -263,7 +263,7 @@ if SMP config SMP_NCPUS int "Number of CPUs" default 4 - range 2 32 + range 1 32 ---help--- This value identifies the number of CPUs supported by the processor that will be used for SMP. -- GitLab From f5a957158d1e6469efe7435008cc12919aa61cc1 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 22 Mar 2017 06:29:38 -0600 Subject: [PATCH 144/990] Review of last PR: Setting CONFIG_SMP_NCPUS=1 should only be permitted in a debug configuration. --- sched/Kconfig | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/sched/Kconfig b/sched/Kconfig index 68eea620cf..3a5807d4dc 100644 --- a/sched/Kconfig +++ b/sched/Kconfig @@ -263,11 +263,17 @@ if SMP config SMP_NCPUS int "Number of CPUs" default 4 - range 1 32 + range 1 32 if DEBUG_FEATURES + range 2 32 if !DEBUG_FEATURES ---help--- This value identifies the number of CPUs supported by the processor that will be used for SMP. + If CONFIG_DEBUG_FEATURES is enbled, then the value one is permitted + for CONFIG_SMP_NCPUS. This is not normally a valid setting for an + SMP configuration. However, running the SMP logic in a single CPU + configuration is useful during certain testing. + config SMP_IDLETHREAD_STACKSIZE int "CPU IDLE stack size" default 2048 -- GitLab From 5fb85451cb873579262dcf5ad4cb630f243ed21d Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 22 Mar 2017 08:08:43 -0600 Subject: [PATCH 145/990] Update some comments --- sched/pthread/pthread_mutexlock.c | 10 +++++++--- sched/pthread/pthread_mutexunlock.c | 15 +++++++++++++-- 2 files changed, 20 insertions(+), 5 deletions(-) diff --git a/sched/pthread/pthread_mutexlock.c b/sched/pthread/pthread_mutexlock.c index f94890505d..d5c8af2db2 100644 --- a/sched/pthread/pthread_mutexlock.c +++ b/sched/pthread/pthread_mutexlock.c @@ -136,8 +136,13 @@ int pthread_mutex_lock(FAR pthread_mutex_t *mutex) else #endif { - /* No, then we would deadlock... return an error (default behavior - * is like PTHREAD_MUTEX_ERRORCHECK) + /* No, then we would deadlock... return an error (default + * behavior is like PTHREAD_MUTEX_ERRORCHECK) + * + * NOTE: This is non-compliant behavior for the case of a + * NORMAL mutex. In that case, it the deadlock condition should + * not be detected and the thread should be permitted to + * deadlock. */ serr("ERROR: Returning EDEADLK\n"); @@ -169,4 +174,3 @@ int pthread_mutex_lock(FAR pthread_mutex_t *mutex) sinfo("Returning %d\n", ret); return ret; } - diff --git a/sched/pthread/pthread_mutexunlock.c b/sched/pthread/pthread_mutexunlock.c index 078d9094b9..56c14bb036 100644 --- a/sched/pthread/pthread_mutexunlock.c +++ b/sched/pthread/pthread_mutexunlock.c @@ -100,13 +100,22 @@ int pthread_mutex_unlock(FAR pthread_mutex_t *mutex) if (mutex->pid != (int)getpid()) { - /* No... return an error (default behavior is like PTHREAD_MUTEX_ERRORCHECK) */ + /* No... return an EPERM error. + * + * Per POSIX: "EPERM should be returned if the mutex type is + * PTHREAD_MUTEX_ERRORCHECK or PTHREAD_MUTEX_RECURSIVE, or the + * mutex is a robust mutex, and the current thread does not own + * the mutex." + * + * For the case of the non-robust PTHREAD_MUTEX_NORMAL mutex, + * the behavior is undefined. Here we treat that type as though + * it were PTHREAD_MUTEX_ERRORCHECK type and just return an error. + */ serr("ERROR: Holder=%d returning EPERM\n", mutex->pid); ret = EPERM; } - /* Yes, the caller owns the semaphore.. Is this a recursive mutex? */ #ifdef CONFIG_MUTEX_TYPES @@ -116,6 +125,7 @@ int pthread_mutex_unlock(FAR pthread_mutex_t *mutex) * the mutex lock, just decrement the count of locks held, and return * success. */ + mutex->nlocks--; } #endif @@ -134,6 +144,7 @@ int pthread_mutex_unlock(FAR pthread_mutex_t *mutex) #endif ret = pthread_givesemaphore((FAR sem_t *)&mutex->sem); } + sched_unlock(); } -- GitLab From cfa55cb1bca997cb080c3ea847c8a6effa396600 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 22 Mar 2017 08:26:01 -0600 Subject: [PATCH 146/990] Clicker2: Add kernel and scripts directories. --- configs/clicker2-stm32/kernel/.gitignore | 2 + configs/clicker2-stm32/kernel/Makefile | 122 +++++++++++++++ .../clicker2-stm32/kernel/stm32_userspace.c | 133 +++++++++++++++++ configs/clicker2-stm32/scripts/flash.ld | 129 ++++++++++++++++ configs/clicker2-stm32/scripts/gnu-elf.ld | 139 ++++++++++++++++++ .../clicker2-stm32/scripts/kernel-space.ld | 115 +++++++++++++++ configs/clicker2-stm32/scripts/memory.ld | 100 +++++++++++++ configs/clicker2-stm32/scripts/user-space.ld | 118 +++++++++++++++ 8 files changed, 858 insertions(+) create mode 100644 configs/clicker2-stm32/kernel/.gitignore create mode 100644 configs/clicker2-stm32/kernel/Makefile create mode 100644 configs/clicker2-stm32/kernel/stm32_userspace.c create mode 100644 configs/clicker2-stm32/scripts/flash.ld create mode 100644 configs/clicker2-stm32/scripts/gnu-elf.ld create mode 100644 configs/clicker2-stm32/scripts/kernel-space.ld create mode 100644 configs/clicker2-stm32/scripts/memory.ld create mode 100644 configs/clicker2-stm32/scripts/user-space.ld diff --git a/configs/clicker2-stm32/kernel/.gitignore b/configs/clicker2-stm32/kernel/.gitignore new file mode 100644 index 0000000000..7bacd5aee3 --- /dev/null +++ b/configs/clicker2-stm32/kernel/.gitignore @@ -0,0 +1,2 @@ +/nuttx_user.elf + diff --git a/configs/clicker2-stm32/kernel/Makefile b/configs/clicker2-stm32/kernel/Makefile new file mode 100644 index 0000000000..6493f3e5d1 --- /dev/null +++ b/configs/clicker2-stm32/kernel/Makefile @@ -0,0 +1,122 @@ +############################################################################ +# configs/clicker2-stm32/kernel/Makefile +# +# 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. +# +############################################################################ + +-include $(TOPDIR)/Make.defs + +# This is the directory for the board-specific header files + +BOARD_INCLUDE = $(TOPDIR)$(DELIM)configs$(DELIM)$(CONFIG_ARCH_BOARD)$(DELIM)include + +# The entry point name (if none is provided in the .config file) + +CONFIG_USER_ENTRYPOINT ?= user_start +ENTRYPT = $(patsubst "%",%,$(CONFIG_USER_ENTRYPOINT)) + +# Get the paths to the libraries and the links script path in format that +# is appropriate for the host OS + +ifeq ($(WINTOOL),y) + # Windows-native toolchains + USER_LIBPATHS = ${shell for path in $(USERLIBS); do dir=`dirname $(TOPDIR)$(DELIM)$$path`;echo "-L\"`cygpath -w $$dir`\"";done} + USER_LDSCRIPT = -T "${shell cygpath -w $(TOPDIR)$(DELIM)configs$(DELIM)$(CONFIG_ARCH_BOARD)$(DELIM)scripts$(DELIM)memory.ld}" + USER_LDSCRIPT += -T "${shell cygpath -w $(TOPDIR)$(DELIM)configs$(DELIM)$(CONFIG_ARCH_BOARD)$(DELIM)scripts$(DELIM)user-space.ld}" + USER_HEXFILE += "${shell cygpath -w $(TOPDIR)$(DELIM)nuttx_user.hex}" + USER_SRECFILE += "${shell cygpath -w $(TOPDIR)$(DELIM)nuttx_user.srec}" + USER_BINFILE += "${shell cygpath -w $(TOPDIR)$(DELIM)nuttx_user.bin}" +else + # Linux/Cygwin-native toolchain + USER_LIBPATHS = $(addprefix -L$(TOPDIR)$(DELIM),$(dir $(USERLIBS))) + USER_LDSCRIPT = -T$(TOPDIR)$(DELIM)configs$(DELIM)$(CONFIG_ARCH_BOARD)$(DELIM)scripts$(DELIM)memory.ld + USER_LDSCRIPT += -T$(TOPDIR)$(DELIM)configs$(DELIM)$(CONFIG_ARCH_BOARD)$(DELIM)scripts$(DELIM)user-space.ld + USER_HEXFILE += "$(TOPDIR)$(DELIM)nuttx_user.hex" + USER_SRECFILE += "$(TOPDIR)$(DELIM)nuttx_user.srec" + USER_BINFILE += "$(TOPDIR)$(DELIM)nuttx_user.bin" +endif + +USER_LDFLAGS = --undefined=$(ENTRYPT) --entry=$(ENTRYPT) $(USER_LDSCRIPT) +USER_LDLIBS = $(patsubst lib%,-l%,$(basename $(notdir $(USERLIBS)))) +USER_LIBGCC = "${shell "$(CC)" $(ARCHCPUFLAGS) -print-libgcc-file-name}" + +# Source files + +CSRCS = stm32_userspace.c +COBJS = $(CSRCS:.c=$(OBJEXT)) +OBJS = $(COBJS) + +# Targets: + +all: $(TOPDIR)$(DELIM)nuttx_user.elf $(TOPDIR)$(DELIM)User.map +.PHONY: nuttx_user.elf depend clean distclean + +$(COBJS): %$(OBJEXT): %.c + $(call COMPILE, $<, $@) + +# Create the nuttx_user.elf file containing all of the user-mode code + +nuttx_user.elf: $(OBJS) + $(Q) $(LD) -o $@ $(USER_LDFLAGS) $(USER_LIBPATHS) $(OBJS) --start-group $(USER_LDLIBS) --end-group $(USER_LIBGCC) + +$(TOPDIR)$(DELIM)nuttx_user.elf: nuttx_user.elf + @echo "LD: nuttx_user.elf" + $(Q) cp -a nuttx_user.elf $(TOPDIR)$(DELIM)nuttx_user.elf +ifeq ($(CONFIG_INTELHEX_BINARY),y) + @echo "CP: nuttx_user.hex" + $(Q) $(OBJCOPY) $(OBJCOPYARGS) -O ihex nuttx_user.elf $(USER_HEXFILE) +endif +ifeq ($(CONFIG_MOTOROLA_SREC),y) + @echo "CP: nuttx_user.srec" + $(Q) $(OBJCOPY) $(OBJCOPYARGS) -O srec nuttx_user.elf $(USER_SRECFILE) +endif +ifeq ($(CONFIG_RAW_BINARY),y) + @echo "CP: nuttx_user.bin" + $(Q) $(OBJCOPY) $(OBJCOPYARGS) -O binary nuttx_user.elf $(USER_BINFILE) +endif + +$(TOPDIR)$(DELIM)User.map: nuttx_user.elf + @echo "MK: User.map" + $(Q) $(NM) nuttx_user.elf >$(TOPDIR)$(DELIM)User.map + $(Q) $(CROSSDEV)size nuttx_user.elf + +.depend: + +depend: .depend + +clean: + $(call DELFILE, nuttx_user.elf) + $(call DELFILE, "$(TOPDIR)$(DELIM)nuttx_user.*") + $(call DELFILE, "$(TOPDIR)$(DELIM)User.map") + $(call CLEAN) + +distclean: clean diff --git a/configs/clicker2-stm32/kernel/stm32_userspace.c b/configs/clicker2-stm32/kernel/stm32_userspace.c new file mode 100644 index 0000000000..cc8f207c56 --- /dev/null +++ b/configs/clicker2-stm32/kernel/stm32_userspace.c @@ -0,0 +1,133 @@ +/**************************************************************************** + * configs/clicker2-stm32/kernel/stm32_userspace.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include +#include +#include +#include + +#if defined(CONFIG_BUILD_PROTECTED) && !defined(__KERNEL__) + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ +/* Configuration ************************************************************/ + +#ifndef CONFIG_NUTTX_USERSPACE +# error "CONFIG_NUTTX_USERSPACE not defined" +#endif + +#if CONFIG_NUTTX_USERSPACE != 0x08020000 +# error "CONFIG_NUTTX_USERSPACE must be 0x08020000 to match memory.ld" +#endif + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/* These 'addresses' of these values are setup by the linker script. They are + * not actual uint32_t storage locations! They are only used meaningfully in the + * following way: + * + * - The linker script defines, for example, the symbol_sdata. + * - The declaration extern uint32_t _sdata; makes C happy. C will believe + * that the value _sdata is the address of a uint32_t variable _data (it is + * not!). + * - We can recover the linker value then by simply taking the address of + * of _data. like: uint32_t *pdata = &_sdata; + */ + +extern uint32_t _stext; /* Start of .text */ +extern uint32_t _etext; /* End_1 of .text + .rodata */ +extern const uint32_t _eronly; /* End+1 of read only section (.text + .rodata) */ +extern uint32_t _sdata; /* Start of .data */ +extern uint32_t _edata; /* End+1 of .data */ +extern uint32_t _sbss; /* Start of .bss */ +extern uint32_t _ebss; /* End+1 of .bss */ + +/* This is the user space entry point */ + +int CONFIG_USER_ENTRYPOINT(int argc, char *argv[]); + +const struct userspace_s userspace __attribute__ ((section (".userspace"))) = +{ + /* General memory map */ + + .us_entrypoint = (main_t)CONFIG_USER_ENTRYPOINT, + .us_textstart = (uintptr_t)&_stext, + .us_textend = (uintptr_t)&_etext, + .us_datasource = (uintptr_t)&_eronly, + .us_datastart = (uintptr_t)&_sdata, + .us_dataend = (uintptr_t)&_edata, + .us_bssstart = (uintptr_t)&_sbss, + .us_bssend = (uintptr_t)&_ebss, + + /* Memory manager heap structure */ + + .us_heap = &g_mmheap, + + /* Task/thread startup routines */ + + .task_startup = task_startup, +#ifndef CONFIG_DISABLE_PTHREAD + .pthread_startup = pthread_startup, +#endif + + /* Signal handler trampoline */ + +#ifndef CONFIG_DISABLE_SIGNALS + .signal_handler = up_signal_handler, +#endif + + /* User-space work queue support (declared in include/nuttx/wqueue.h) */ + +#ifdef CONFIG_LIB_USRWORK + .work_usrstart = work_usrstart, +#endif +}; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +#endif /* CONFIG_BUILD_PROTECTED && !__KERNEL__ */ diff --git a/configs/clicker2-stm32/scripts/flash.ld b/configs/clicker2-stm32/scripts/flash.ld new file mode 100644 index 0000000000..ca2e7eefcf --- /dev/null +++ b/configs/clicker2-stm32/scripts/flash.ld @@ -0,0 +1,129 @@ +/**************************************************************************** + * configs/clicker2-stm32/scripts/flash.ld + * + * 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. + * + ****************************************************************************/ + +/* The STM32F407VG has 1024Kb of FLASH beginning at address 0x0800:0000 and + * 192Kb of SRAM. SRAM is split up into three blocks: + * + * 1) 112Kb of SRAM beginning at address 0x2000:0000 + * 2) 16Kb of SRAM beginning at address 0x2001:c000 + * 3) 64Kb of CCM SRAM beginning at address 0x1000:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address + * range. + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x08000000, LENGTH = 1024K + sram (rwx) : ORIGIN = 0x20000000, LENGTH = 112K +} + +OUTPUT_ARCH(arm) +ENTRY(_stext) +SECTIONS +{ + .text : + { + _stext = ABSOLUTE(.); + *(.vectors) + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + } > flash + + .init_section : + { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : + { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : + { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : + { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : + { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/configs/clicker2-stm32/scripts/gnu-elf.ld b/configs/clicker2-stm32/scripts/gnu-elf.ld new file mode 100644 index 0000000000..d10b5aaf89 --- /dev/null +++ b/configs/clicker2-stm32/scripts/gnu-elf.ld @@ -0,0 +1,139 @@ +/**************************************************************************** + * configs/clicker2-stm32/scripts/gnu-elf.ld + * + * 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. + * + ****************************************************************************/ + +SECTIONS +{ + .text 0x00000000 : + { + _stext = . ; + *(.text) + *(.text.*) + *(.gnu.warning) + *(.stub) + *(.glue_7) + *(.glue_7t) + *(.jcr) + + /* C++ support: The .init and .fini sections contain specific logic + * to manage static constructors and destructors. + */ + + *(.gnu.linkonce.t.*) + *(.init) /* Old ABI */ + *(.fini) /* Old ABI */ + _etext = . ; + } + + .ARM.extab : + { + *(.ARM.extab*) + } + + .ARM.exidx : + { + *(.ARM.exidx*) + } + + .rodata : + { + _srodata = . ; + *(.rodata) + *(.rodata1) + *(.rodata.*) + *(.gnu.linkonce.r*) + _erodata = . ; + } + + .data : + { + _sdata = . ; + *(.data) + *(.data1) + *(.data.*) + *(.gnu.linkonce.d*) + _edata = . ; + } + + /* C++ support. For each global and static local C++ object, + * GCC creates a small subroutine to construct the object. Pointers + * to these routines (not the routines themselves) are stored as + * simple, linear arrays in the .ctors section of the object file. + * Similarly, pointers to global/static destructor routines are + * stored in .dtors. + */ + + .ctors : + { + _sctors = . ; + *(.ctors) /* Old ABI: Unallocated */ + *(.init_array) /* New ABI: Allocated */ + _edtors = . ; + } + + .dtors : + { + _sdtors = . ; + *(.dtors) /* Old ABI: Unallocated */ + *(.fini_array) /* New ABI: Allocated */ + _edtors = . ; + } + + .bss : + { + _sbss = . ; + *(.bss) + *(.bss.*) + *(.sbss) + *(.sbss.*) + *(.gnu.linkonce.b*) + *(COMMON) + _ebss = . ; + } + + /* Stabs debugging sections. */ + + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/configs/clicker2-stm32/scripts/kernel-space.ld b/configs/clicker2-stm32/scripts/kernel-space.ld new file mode 100644 index 0000000000..eacdb017ea --- /dev/null +++ b/configs/clicker2-stm32/scripts/kernel-space.ld @@ -0,0 +1,115 @@ +/**************************************************************************** + * configs/clicker2-stm32/scripts/kernel-space.ld + * + * 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. + * + ****************************************************************************/ + +/* NOTE: This depends on the memory.ld script having been included prior to + * this script. + */ + +OUTPUT_ARCH(arm) +ENTRY(_stext) +SECTIONS +{ + .text : + { + _stext = ABSOLUTE(.); + *(.vectors) + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + } > kflash + + .init_section : + { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > kflash + + .ARM.extab : + { + *(.ARM.extab*) + } > kflash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : + { + *(.ARM.exidx*) + } > kflash + + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : + { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > ksram AT > kflash + + .bss : + { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + _ebss = ABSOLUTE(.); + } > ksram + + /* Stabs debugging sections */ + + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/configs/clicker2-stm32/scripts/memory.ld b/configs/clicker2-stm32/scripts/memory.ld new file mode 100644 index 0000000000..8a67bca4cd --- /dev/null +++ b/configs/clicker2-stm32/scripts/memory.ld @@ -0,0 +1,100 @@ +/**************************************************************************** + * configs/clicker2-stm32/scripts/memory.ld + * + * 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. + * + ****************************************************************************/ + +/* The STM32F407VG has 1024Kb of FLASH beginning at address 0x0800:0000 and + * 192Kb of SRAM. SRAM is split up into three blocks: + * + * 1) 112KB of SRAM beginning at address 0x2000:0000 + * 2) 16KB of SRAM beginning at address 0x2001:c000 + * 3) 64KB of CCM SRAM beginning at address 0x1000:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + * + * For MPU support, the kernel-mode NuttX section is assumed to be 128Kb of + * FLASH and 4Kb of SRAM. That is an excessive amount for the kernel which + * should fit into 64KB and, of course, can be optimized as needed (See + * also configs/clicker2-stm32/scripts/kernel-space.ld). Allowing the + * additional does permit addition debug instrumentation to be added to the + * kernel space without overflowing the partition. + * + * Alignment of the user space FLASH partition is also a critical factor: + * The user space FLASH partition will be spanned with a single region of + * size 2**n bytes. The alignment of the user-space region must be the same. + * As a consequence, as the user-space increases in size, the alignmment + * requirement also increases. + * + * This alignment requirement means that the largest user space FLASH region + * you can have will be 512KB at it would have to be positioned at + * 0x08800000. If you change this address, don't forget to change the + * CONFIG_NUTTX_USERSPACE configuration setting to match and to modify + * the check in kernel/userspace.c. + * + * For the same reasons, the maximum size of the SRAM mapping is limited to + * 4KB. Both of these alignment limitations could be reduced by using + * multiple regions to map the FLASH/SDRAM range or perhaps with some + * clever use of subregions. + * + * A detailed memory map for the 112KB SRAM region is as follows: + * + * 0x20000 0000: Kernel .data region. Typical size: 0.1KB + * ------- ---- Kernel .bss region. Typical size: 1.8KB + * 0x20000 0800: Kernel IDLE thread stack (approximate). Size is + * determined by CONFIG_IDLETHREAD_STACKSIZE and + * adjustments for alignment. Typical is 1KB. + * ------- ---- Padded to 4KB + * 0x20000 1000: User .data region. Size is variable. + * ------- ---- User .bss region Size is variable. + * 0x20000 2000: Beginning of kernel heap. Size determined by + * CONFIG_MM_KERNEL_HEAPSIZE. + * ------- ---- Beginning of user heap. Can vary with other settings. + * 0x20001 c000: End+1 of CPU RAM + */ + +MEMORY +{ + /* 1024Kb FLASH */ + + kflash (rx) : ORIGIN = 0x08000000, LENGTH = 128K + uflash (rx) : ORIGIN = 0x08020000, LENGTH = 128K + xflash (rx) : ORIGIN = 0x08040000, LENGTH = 768K + + /* 112Kb of contiguous SRAM */ + + ksram (rwx) : ORIGIN = 0x20000000, LENGTH = 4K + usram (rwx) : ORIGIN = 0x20001000, LENGTH = 4K + xsram (rwx) : ORIGIN = 0x20002000, LENGTH = 104K +} diff --git a/configs/clicker2-stm32/scripts/user-space.ld b/configs/clicker2-stm32/scripts/user-space.ld new file mode 100644 index 0000000000..b7e9f0f8f8 --- /dev/null +++ b/configs/clicker2-stm32/scripts/user-space.ld @@ -0,0 +1,118 @@ +/**************************************************************************** + * configs/clicker2-stm32/scripts/user-space.ld + * + * 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. + * + ****************************************************************************/ + +/* NOTE: This depends on the memory.ld script having been included prior to + * this script. + */ + +OUTPUT_ARCH(arm) +SECTIONS +{ + .userspace : + { + *(.userspace) + } > uflash + + .text : + { + _stext = ABSOLUTE(.); + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + } > uflash + + .init_section : + { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > uflash + + .ARM.extab : + { + *(.ARM.extab*) + } > uflash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : + { + *(.ARM.exidx*) + } > uflash + + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : + { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > usram AT > uflash + + .bss : + { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + _ebss = ABSOLUTE(.); + } > usram + + /* Stabs debugging sections */ + + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} -- GitLab From 3f4c4c36f6d7a023e4da1f9a376e07087e0e1b6d Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 22 Mar 2017 09:33:26 -0600 Subject: [PATCH 147/990] clicker2-stm32: Add src/ directory --- configs/clicker2-stm32/include/board.h | 23 +- configs/clicker2-stm32/src/.gitignore | 2 + configs/clicker2-stm32/src/Makefile | 67 ++++++ configs/clicker2-stm32/src/clicker2-stm32.h | 228 ++++++++++++++++++++ configs/clicker2-stm32/src/stm32_adc.c | 161 ++++++++++++++ configs/clicker2-stm32/src/stm32_appinit.c | 98 +++++++++ configs/clicker2-stm32/src/stm32_autoleds.c | 204 ++++++++++++++++++ configs/clicker2-stm32/src/stm32_boot.c | 109 ++++++++++ configs/clicker2-stm32/src/stm32_bringup.c | 168 +++++++++++++++ configs/clicker2-stm32/src/stm32_buttons.c | 132 ++++++++++++ configs/clicker2-stm32/src/stm32_can.c | 112 ++++++++++ configs/clicker2-stm32/src/stm32_usb.c | 105 +++++++++ configs/clicker2-stm32/src/stm32_userleds.c | 97 +++++++++ 13 files changed, 1499 insertions(+), 7 deletions(-) create mode 100644 configs/clicker2-stm32/src/.gitignore create mode 100644 configs/clicker2-stm32/src/Makefile create mode 100644 configs/clicker2-stm32/src/clicker2-stm32.h create mode 100644 configs/clicker2-stm32/src/stm32_adc.c create mode 100644 configs/clicker2-stm32/src/stm32_appinit.c create mode 100644 configs/clicker2-stm32/src/stm32_autoleds.c create mode 100644 configs/clicker2-stm32/src/stm32_boot.c create mode 100644 configs/clicker2-stm32/src/stm32_bringup.c create mode 100644 configs/clicker2-stm32/src/stm32_buttons.c create mode 100644 configs/clicker2-stm32/src/stm32_can.c create mode 100644 configs/clicker2-stm32/src/stm32_usb.c create mode 100644 configs/clicker2-stm32/src/stm32_userleds.c diff --git a/configs/clicker2-stm32/include/board.h b/configs/clicker2-stm32/include/board.h index 4af984b607..967f601fa9 100644 --- a/configs/clicker2-stm32/include/board.h +++ b/configs/clicker2-stm32/include/board.h @@ -200,7 +200,12 @@ #endif /* LED definitions ******************************************************************/ -/* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any +/* The Mikroe Clicker2 STM32 has two user controllable LEDs: + * + * LD1 - PE12, Active high output illuminates + * LD2 - PE15, Active high output illuminates + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any * way. The following definitions are used to access individual LEDs. */ @@ -218,7 +223,7 @@ /* If CONFIG_ARCH_LEDs is defined, then NuttX will control the 2 LEDs on board the * Clicker2 for STM32. The following definitions describe how NuttX controls the LEDs: * - * SYMBOL Meaning LED state + * SYMBOL Meaning LED state * LED1 LED2 * ------------------- ----------------------- -------- -------- * LED_STARTED NuttX has been started OFF OFF @@ -242,14 +247,18 @@ #define LED_PANIC 4 /* Button definitions ***************************************************************/ -/* The STM32F4 Discovery supports one button: */ +/* The Mikroe Clicker2 STM32 has two buttons available to software: + * + * T2 - PE0, Low sensed when pressed + * T3 - PA10, Low sensed when pressed + */ -#define BUTTON_LEFT 0 -#define BUTTON_RIGHT 1 +#define BUTTON_T2 0 +#define BUTTON_T3 1 #define NUM_BUTTONS 2 -#define BUTTON_LEFT_BIT (1 << BUTTON_LEFT) -#define BUTTON_RIGHT_BIT (1 << BUTTON_RIGHT) +#define BUTTON_T2_BIT (1 << BUTTON_T2) +#define BUTTON_T3_BIT (1 << BUTTON_T3) /* Alternate function pin selections ************************************************/ /* CAN */ diff --git a/configs/clicker2-stm32/src/.gitignore b/configs/clicker2-stm32/src/.gitignore new file mode 100644 index 0000000000..726d936e1e --- /dev/null +++ b/configs/clicker2-stm32/src/.gitignore @@ -0,0 +1,2 @@ +/.depend +/Make.dep diff --git a/configs/clicker2-stm32/src/Makefile b/configs/clicker2-stm32/src/Makefile new file mode 100644 index 0000000000..80f87f8af0 --- /dev/null +++ b/configs/clicker2-stm32/src/Makefile @@ -0,0 +1,67 @@ +############################################################################ +# configs/clicker2-stm32/src/Makefile +# +# 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. +# +############################################################################ + +-include $(TOPDIR)/Make.defs + +ASRCS = +CSRCS = stm32_boot.c stm32_bringup.c + +ifeq ($(CONFIG_ARCH_LEDS),y) +CSRCS += stm32_autoleds.c +else +CSRCS += stm32_userleds.c +endif + +ifeq ($(CONFIG_ARCH_BUTTONS),y) +CSRCS += stm32_buttons.c +endif + +ifeq ($(CONFIG_STM32_OTGFS),y) +CSRCS += stm32_usb.c +endif + +ifeq ($(CONFIG_LIB_BOARDCTL),y) +CSRCS += stm32_appinit.c +endif + +ifeq ($(CONFIG_ADC),y) +CSRCS += stm32_adc.c +endif + +ifeq ($(CONFIG_CAN),y) +CSRCS += stm32_can.c +endif + +include $(TOPDIR)/configs/Board.mk diff --git a/configs/clicker2-stm32/src/clicker2-stm32.h b/configs/clicker2-stm32/src/clicker2-stm32.h new file mode 100644 index 0000000000..a7be1085e9 --- /dev/null +++ b/configs/clicker2-stm32/src/clicker2-stm32.h @@ -0,0 +1,228 @@ +/**************************************************************************** + * configs/clicker2-stm32/src/clicker2-stm32.h + * + * 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. + * + ****************************************************************************/ + +#ifndef __CONFIGS_OLIMEX_STM32_P407_SRC_H +#define __CONFIGS_OLIMEX_STM32_P407_SRC_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +/* Assume that we support everything until convinced otherwise */ + +#define HAVE_MMCSD 1 +#define HAVE_USBDEV 1 +#define HAVE_USBMONITOR 1 + +/* Can't support MMC/SD features if mountpoints are disabled or if SDIO support + * is not enabled. + */ + +#if defined(CONFIG_DISABLE_MOUNTPOINT) || !defined(CONFIG_STM32_SDIO) || \ + !defined(CONFIG_MMCSD_SDIO) +# undef HAVE_MMCSD +#endif + +/* Default MMC/SD minor number */ + +#ifdef HAVE_MMCSD + +/* Default MMC/SD SLOT number */ + +# if defined(CONFIG_NSH_MMCSDSLOTNO) && CONFIG_NSH_MMCSDSLOTNO != 0 +# error Only one MMC/SD slot +# undef CONFIG_NSH_MMCSDSLOTNO +# endif + +# ifdef CONFIG_NSH_MMCSDSLOTNO +# define MMCSD_SLOTNO CONFIG_NSH_MMCSDSLOTNO +# else +# define MMCSD_SLOTNO 0 +# endif + +/* Default minor device number */ + +# ifdef CONFIG_NSH_MMCSDMINOR +# define MMCSD_MINOR CONFIG_NSH_MMCSDMINOR +# else +# define MMCSD_MINOR 0 +# endif +#endif + +/* Can't support USB device feature if USB OTG FS is not enabled */ + +#ifndef CONFIG_STM32_OTGFS +# undef HAVE_USBDEV +# undef HAVE_USBMONITOR +#endif + +/* Can't support USB device monitor if USB device is not enabled */ + +#ifndef CONFIG_USBDEV +# undef HAVE_USBDEV +# undef HAVE_USBMONITOR +#endif + +/* Check if we should enable the USB monitor before starting NSH */ + +#if !defined(CONFIG_USBDEV_TRACE) || !defined(CONFIG_USBMONITOR) +# undef HAVE_USBMONITOR +#endif + + +/* Mickroe Clicker2 STM32 GPIOs *********************************************/ +/* LEDs + * + * The Mikroe Clicker2 STM32 has two user controllable LEDs: + * + * LD1 - PE12, Active high output illuminates + * LD2 - PE15, Active high output illuminates + */ + +#define GPIO_LED1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN12) +#define GPIO_LED2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN15) + +/* BUTTONs + * + * The Mikroe Clicker2 STM32 has two buttons available to software: + * + * T2 - PE0, Low sensed when pressed + * T3 - PA10, Low sensed when pressed + * + * NOTE that all have EXTI interrupts configured + */ + +#define GPIO_BTN_T2 (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTE|GPIO_PIN0) +#define GPIO_BTN_T3 (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTA|GPIO_PIN10) + +/* USB OTG FS + * + * USB device. VBUS sensing is provided: + * + * PA9 OTG_FS_VBUS VBUS sensing (USB-DET) + * + * USB host does not appear to be supported. My interpretation is that power + * is provided via LTC3586 which can be driven either from USB VBUS or from PWR-EN + * (controlled by SW1). But I don't see any capability to drive VBUS power. + * + * Overcurrent and battery status are provided by the LTC3586, but not USB power. + * + * PC6 Overcurrent detection (PC6-FAULT) + * PD4 Battery status (PD4-BATSTAT) + */ + +/* USB device */ +/* USB device */ + +#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN9) + +/* Power status */ + +#define GPIO_PWR_FAULT (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN6) +#define GPIO_PWR_BATSTAT (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN4) + +#ifndef __ASSEMBLY__ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_bringup + * + * Description: + * Perform architecture-specific initialization + * + * CONFIG_BOARD_INITIALIZE=y : + * Called from board_initialize(). + * + * CONFIG_BOARD_INITIALIZE=y && CONFIG_LIB_BOARDCTL=y : + * Called from the NSH library + * + ************************************************************************************/ + +int stm32_bringup(void); + +/************************************************************************************ + * Name: stm32_usb_configure + * + * Description: + * Called from stm32_boardinitialize very early in inialization to setup USB-related + * GPIO pins for the Olimex STM32 P407 board. + * + ************************************************************************************/ + +#ifdef CONFIG_STM32_OTGFS +void stm32_usb_configure(void); +#endif + +/************************************************************************************ + * Name: stm32_adc_setup + * + * Description: + * Initialize ADC and register the ADC driver. + * + ************************************************************************************/ + +#ifdef CONFIG_ADC +int stm32_adc_setup(void); +#endif + +/**************************************************************************** + * Name: stm32_can_setup + * + * Description: + * Initialize CAN and register the CAN device + * + ****************************************************************************/ + +#ifdef CONFIG_CAN +int stm32_can_setup(void); +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __CONFIGS_OLIMEX_STM32_P407_SRC_H */ diff --git a/configs/clicker2-stm32/src/stm32_adc.c b/configs/clicker2-stm32/src/stm32_adc.c new file mode 100644 index 0000000000..e2f86c9e6b --- /dev/null +++ b/configs/clicker2-stm32/src/stm32_adc.c @@ -0,0 +1,161 @@ +/************************************************************************************ + * configs/clicker2-stm32/src/stm32_adc.c + * + * Copyright (C) 2016 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. + * + ************************************************************************************/ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include + +#include +#include +#include + +#include "chip.h" +#include "stm32_adc.h" +#include "clicker2-stm32.h" + +#ifdef CONFIG_ADC + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Configuration ********************************************************************/ +/* Up to 3 ADC interfaces are supported */ + +#if STM32_NADC < 3 +# undef CONFIG_STM32_ADC3 +#endif + +#if STM32_NADC < 2 +# undef CONFIG_STM32_ADC2 +#endif + +#if STM32_NADC < 1 +# undef CONFIG_STM32_ADC1 +#endif + +#if defined(CONFIG_STM32_ADC1) || defined(CONFIG_STM32_ADC2) || defined(CONFIG_STM32_ADC3) +#ifndef CONFIG_STM32_ADC1 +# warning "Channel information only available for ADC1" +#endif + +/* The number of ADC channels in the conversion list */ + +#define ADC1_NCHANNELS 1 + +/************************************************************************************ + * Private Data + ************************************************************************************/ +/* The Olimex STM32-P407 has a 10 Kohm potentiometer AN_TR connected to PC0 + * ADC123_IN10 + */ + +/* Identifying number of each ADC channel: Variable Resistor. */ + +#ifdef CONFIG_STM32_ADC1 +static const uint8_t g_chanlist[ADC1_NCHANNELS] = {10}; + +/* Configurations of pins used byte each ADC channels */ + +static const uint32_t g_pinlist[ADC1_NCHANNELS] = {GPIO_ADC1_IN10}; +#endif + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_adc_setup + * + * Description: + * Initialize ADC and register the ADC driver. + * + ************************************************************************************/ + +int stm32_adc_setup(void) +{ +#ifdef CONFIG_STM32_ADC1 + static bool initialized = false; + struct adc_dev_s *adc; + int ret; + int i; + + /* Check if we have already initialized */ + + if (!initialized) + { + /* Configure the pins as analog inputs for the selected channels */ + + for (i = 0; i < ADC1_NCHANNELS; i++) + { + stm32_configgpio(g_pinlist[i]); + } + + /* Call stm32_adcinitialize() to get an instance of the ADC interface */ + + adc = stm32_adcinitialize(1, g_chanlist, ADC1_NCHANNELS); + if (adc == NULL) + { + aerr("ERROR: Failed to get ADC interface\n"); + return -ENODEV; + } + + /* Register the ADC driver at "/dev/adc0" */ + + ret = adc_register("/dev/adc0", adc); + if (ret < 0) + { + aerr("ERROR: adc_register failed: %d\n", ret); + return ret; + } + + /* Now we are initialized */ + + initialized = true; + } + + return OK; +#else + return -ENOSYS; +#endif +} + +#endif /* CONFIG_STM32_ADC1 || CONFIG_STM32_ADC2 || CONFIG_STM32_ADC3 */ +#endif /* CONFIG_ADC */ diff --git a/configs/clicker2-stm32/src/stm32_appinit.c b/configs/clicker2-stm32/src/stm32_appinit.c new file mode 100644 index 0000000000..74c8a2142b --- /dev/null +++ b/configs/clicker2-stm32/src/stm32_appinit.c @@ -0,0 +1,98 @@ +/**************************************************************************** + * config/clicker2-stm32/src/stm32_appinit.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include + +#include "clicker2-stm32.h" + +#ifdef CONFIG_LIB_BOARDCTL + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * CONFIG_LIB_BOARDCTL=y : + * Called from the NSH library + * + * CONFIG_BOARD_INITIALIZE=y, CONFIG_NSH_LIBRARY=y, && + * CONFIG_LIB_BOARDCTL=n : + * Called from board_initialize(). + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; the meaning of the argument is a contract + * between the board-specific initalization logic and the the + * matching application logic. The value cold be such things as a + * mode enumeration value, a set of DIP switch switch settings, a + * pointer to configuration data read from a file or serial FLASH, + * or whatever you would like to do with it. Every implementation + * should accept zero/NULL as a default configuration. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ + +int board_app_initialize(uintptr_t arg) +{ + /* Did we already initialize via board_initialize()? */ + +#ifndef CONFIG_BOARD_INITIALIZE + return stm32_bringup(); +#else + return OK; +#endif +} + +#endif /* CONFIG_LIB_BOARDCTL */ diff --git a/configs/clicker2-stm32/src/stm32_autoleds.c b/configs/clicker2-stm32/src/stm32_autoleds.c new file mode 100644 index 0000000000..e559c60efc --- /dev/null +++ b/configs/clicker2-stm32/src/stm32_autoleds.c @@ -0,0 +1,204 @@ +/**************************************************************************** + * configs/clicker2-stm32/src/stm32_autoleds.c + * + * 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. + * + ****************************************************************************/ +/* If CONFIG_ARCH_LEDs is defined, then NuttX will control the 2 LEDs on + * board the Clicker2 for STM32. The following definitions describe how + * NuttX controls the LEDs: + * + * SYMBOL Meaning LED state + * LED1 LED2 + * ------------------- ----------------------- -------- -------- + * LED_STARTED NuttX has been started OFF OFF + * LED_HEAPALLOCATE Heap has been allocated OFF OFF + * LED_IRQSENABLED Interrupts enabled OFF OFF + * LED_STACKCREATED Idle stack created ON OFF + * LED_INIRQ In an interrupt N/C ON + * LED_SIGNAL In a signal handler No change + * LED_ASSERTION An assertion failed No change + * LED_PANIC The system has crashed OFF Blinking + * LED_IDLE STM32 is is sleep mode Not used + * + * VALUE + * -------------------------------------------- -------- -------- + * 0 OFF OFF + * 1 ON OFF + * 2 N/C ON + * 3 N/C N/C + * 4 OFF ON + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include +#include + +#include "stm32.h" +#include "clicker2-stm32.h" + +#ifdef CONFIG_ARCH_LEDS + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static +static static void board_led1_on(int led) +{ + bool ledon = false; + + switch (led) + { + case 0: /* LED1=OFF */ + case 4: /* LED1=OFF */ + break; + + case 1: /* LED1=ON */ + ledon = true; + break; + + case 2: /* LED1=N/C */ + case 3: /* LED1=N/C */ + default: + return; + } + + stm32_gpiowrite(GPIO_LED1, ledon); +} + +static static void board_led2_on(int led) +{ + bool ledon = false; + + switch (led) + { + case 0: /* LED2=OFF */ + case 1: /* LED2=OFF */ + break; + + case 2: /* LED2=ON */ + case 4: /* LED2=ON */ + ledon = true; + break; + + case 3: /* LED2=N/C */ + default: + return; + } + + stm32_gpiowrite(GPIO_LED2, ledon); +} + +static void board_led1_off(int led) +{ + switch (led) + { + case 0: /* LED1=OFF */ + case 1: /* LED1=OFF */ + case 4: /* LED1=OFF */ + break; + + case 2: /* LED1=N/C */ + case 3: /* LED1=N/C */ + default: + return; + } + + stm32_gpiowrite(GPIO_LED1, false); +} + +static void board_led2_off(int led) +{ + switch (led) + { + case 0: /* LED2=OFF */ + case 1: /* LED2=OFF */ + case 2: /* LED2=OFF */ + case 4: /* LED2=OFF */ + break; + + case 3: /* LED2=N/C */ + default: + return; + } + + stm32_gpiowrite(GPIO_LED2, false); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_autoled_initialize + ****************************************************************************/ + +void board_autoled_initialize(void) +{ + /* Configure LED1-4 GPIOs for output */ + + stm32_configgpio(GPIO_LED1); + stm32_configgpio(GPIO_LED2); + stm32_configgpio(GPIO_LED3); + stm32_configgpio(GPIO_LED4); +} + +/**************************************************************************** + * Name: board_autoled_on + ****************************************************************************/ + +void board_autoled_on(int led) +{ + board_led1_on(led); + board_led2_on(led); +} + +/**************************************************************************** + * Name: board_autoled_off + ****************************************************************************/ + +void board_autoled_off(int led) +{ + board_led1_off(led); + board_led2_off(led); +} + +#endif /* CONFIG_ARCH_LEDS */ diff --git a/configs/clicker2-stm32/src/stm32_boot.c b/configs/clicker2-stm32/src/stm32_boot.c new file mode 100644 index 0000000000..fff7bb8764 --- /dev/null +++ b/configs/clicker2-stm32/src/stm32_boot.c @@ -0,0 +1,109 @@ +/************************************************************************************ + * configs/clicker2-stm32/src/stm32_boot.c + * + * 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. + * + ************************************************************************************/ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include + +#include +#include +#include + +#include "clicker2-stm32.h" + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the intitialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +void stm32_boardinitialize(void) +{ +#ifdef CONFIG_STM32_OTGFS + /* Initialize USB if the 1) OTG FS controller is in the configuration and 2) + * disabled, and 3) the weak function stm32_usb_configure() has been brought + * into the build. Presumeably either CONFIG_USBDEV or CONFIG_USBHOST is also + * selected. + */ + + stm32_usb_configure(); +#endif + +#ifdef CONFIG_ARCH_LEDS + /* Configure on-board LEDs if LED support has been selected. */ + + board_autoled_initialize(); +#endif + +#ifdef CONFIG_ARCH_BUTTONS + /* Configure on-board BUTTONs if BUTTON support has been selected. */ + + board_button_initialize(); +#endif +} + +/**************************************************************************** + * Name: board_initialize + * + * Description: + * If CONFIG_BOARD_INITIALIZE is selected, then an additional + * initialization call will be performed in the boot-up sequence to a + * function called board_initialize(). board_initialize() will be + * called immediately after up_initialize() is called and just before the + * initial application is started. This additional initialization phase + * may be used, for example, to initialize board-specific device drivers. + * + ****************************************************************************/ + +#ifdef CONFIG_BOARD_INITIALIZE +void board_initialize(void) +{ + /* Perform board-specific initialization here if so configured */ + + (void)stm32_bringup(); +} +#endif diff --git a/configs/clicker2-stm32/src/stm32_bringup.c b/configs/clicker2-stm32/src/stm32_bringup.c new file mode 100644 index 0000000000..1dcc276812 --- /dev/null +++ b/configs/clicker2-stm32/src/stm32_bringup.c @@ -0,0 +1,168 @@ +/**************************************************************************** + * config/clicker2-stm32/src/stm32_bringup.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#include +#include +#include + +#ifdef CONFIG_USBMONITOR +# include +#endif + +#include "stm32.h" +#include "clicker2-stm32.h" + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_bringup + * + * Description: + * Perform architecture-specific initialization + * + * CONFIG_BOARD_INITIALIZE=y : + * Called from board_initialize(). + * + * CONFIG_BOARD_INITIALIZE=n && CONFIG_LIB_BOARDCTL=y : + * Called from the NSH library + * + ****************************************************************************/ + +int stm32_bringup(void) +{ +#ifdef HAVE_MMCSD + FAR struct sdio_dev_s *sdio; +#endif + int ret; + +#ifdef CONFIG_FS_PROCFS + /* Mount the procfs file system */ + + ret = mount(NULL, "/proc", "procfs", 0, NULL); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: Failed to mount procfs at /proc: %d\n", ret); + } +#endif + +#ifdef HAVE_MMCSD + /* Mount the SDIO-based MMC/SD block driver */ + /* First, get an instance of the SDIO interface */ + + sdio = sdio_initialize(MMCSD_SLOTNO); + if (!sdio) + { + syslog(LOG_ERR, + "ERROR: Failed to initialize SDIO slot %d\n", + MMCSD_SLOTNO); + return -ENODEV; + } + + /* Now bind the SDIO interface to the MMC/SD driver */ + + ret = mmcsd_slotinitialize(MMCSD_MINOR, sdio); + if (ret != OK) + { + syslog(LOG_ERR, + "ERROR: Failed to bind SDIO to the MMC/SD driver: %d\n", + ret); + return ret; + } + + /* Then let's guess and say that there is a card in the slot. The Olimex + * STM32 P407 does not support a GPIO to detect if there is a card in + * the slot so we are reduced to guessing. + */ + + sdio_mediachange(sdio, true); +#endif + +#ifdef CONFIG_CAN + /* Initialize CAN and register the CAN driver. */ + + ret = stm32_can_setup(); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: stm32_can_setup failed: %d\n", ret); + } +#endif + +#ifdef CONFIG_ADC + /* Initialize ADC and register the ADC driver. */ + + ret = stm32_adc_setup(); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: stm32_adc_setup failed: %d\n", ret); + } +#endif + +#ifdef HAVE_USBMONITOR + /* Start the USB Monitor */ + + ret = usbmonitor_start(); + if (ret != OK) + { + syslog(LOG_ERR, "ERROR: Failed to start USB monitor: %d\n", ret); + } +#endif + +#ifdef CONFIG_BUTTONS + /* Register the BUTTON driver */ + + ret = btn_lower_initialize("/dev/buttons"); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: btn_lower_initialize() failed: %d\n", ret); + } +#endif + + UNUSED(ret); + return OK; +} diff --git a/configs/clicker2-stm32/src/stm32_buttons.c b/configs/clicker2-stm32/src/stm32_buttons.c new file mode 100644 index 0000000000..6ef612ce6d --- /dev/null +++ b/configs/clicker2-stm32/src/stm32_buttons.c @@ -0,0 +1,132 @@ +/**************************************************************************** + * configs/clicker2-stm32/src/stm32_buttons.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include +#include +#include + +#include "stm32_gpio.h" + +#include "clicker2-stm32.h" + +#ifdef CONFIG_ARCH_BUTTONS + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_button_initialize + * + * Description: + * board_button_initialize() must be called to initialize button resources. After + * that, board_buttons() may be called to collect the current state of all + * buttons or board_button_irq() may be called to register button interrupt + * handlers. + * + ****************************************************************************/ + +void board_button_initialize(void) +{ + /* Configure BUTTONS T2-T3 GPIOs for input */ + + stm32_configgpio(GPIO_BTN_T2); + stm32_configgpio(GPIO_BTN_T3); +} + +/**************************************************************************** + * Name: board_buttons + ****************************************************************************/ + +uint8_t board_buttons(void) +{ + uint8_t ret = 0; + + /* Check that state of each key */ + + if (!stm32_gpioread(g_buttons[GPIO_BTN_T2])) + { + ret |= BUTTON_T2_BIT; + } + + if (stm32_gpioread(g_buttons[GPIO_BTN_T2])) + { + ret |= BUTTON_T3_BIT; + } + + return ret; +} + +/************************************************************************************ + * Button support. + * + * Description: + * board_button_initialize() must be called to initialize button resources. After + * that, board_buttons() may be called to collect the current state of all + * buttons or board_button_irq() may be called to register button interrupt + * handlers. + * + * After board_button_initialize() has been called, board_buttons() may be called to + * collect the state of all buttons. board_buttons() returns an 8-bit bit set + * with each bit associated with a button. See the BUTTON_*_BIT + * definitions in board.h for the meaning of each bit. + * + * board_button_irq() may be called to register an interrupt handler that will + * be called when a button is depressed or released. The ID value is a + * button enumeration value that uniquely identifies a button resource. See the + * BUTTON_* definitions in board.h for the meaning of enumeration + * value. + * + ************************************************************************************/ + +#ifdef CONFIG_ARCH_IRQBUTTONS +int board_button_irq(int id, xcpt_t irqhandler, FAR void *arg) +{ + uint32_t btncfg; + + btncfg = (id == BUTTON_T2) ? GPIO_BTN_T2 : GPIO_BTN_T3; + return stm32_gpiosetevent(g_buttons[id], true, true, true, irqhandler, arg); +} +#endif +#endif /* CONFIG_ARCH_BUTTONS */ diff --git a/configs/clicker2-stm32/src/stm32_can.c b/configs/clicker2-stm32/src/stm32_can.c new file mode 100644 index 0000000000..2c3b98ea6f --- /dev/null +++ b/configs/clicker2-stm32/src/stm32_can.c @@ -0,0 +1,112 @@ +/************************************************************************************ + * configs/clicker2-stm32/src/stm32_can.c + * + * 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. + * + ************************************************************************************/ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include + +#include +#include + +#include "stm32.h" +#include "stm32_can.h" +#include "clicker2-stm32.h" + +#ifdef CONFIG_CAN + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* Configuration ********************************************************************/ + +#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2) +# warning "Both CAN1 and CAN2 are enabled. Only CAN1 is connected." +# undef CONFIG_STM32_CAN2 +#endif + +#ifdef CONFIG_STM32_CAN1 +# define CAN_PORT 1 +#else +# define CAN_PORT 2 +#endif + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_can_setup + * + * Description: + * Initialize CAN and register the CAN device + * + ************************************************************************************/ + +int stm32_can_setup(void) +{ +#if defined(CONFIG_STM32_CAN1) || defined(CONFIG_STM32_CAN2) + struct can_dev_s *can; + int ret; + + /* Call stm32_caninitialize() to get an instance of the CAN interface */ + + can = stm32_caninitialize(CAN_PORT); + if (can == NULL) + { + canerr("ERROR: Failed to get CAN interface\n"); + return -ENODEV; + } + + /* Register the CAN driver at "/dev/can0" */ + + ret = can_register("/dev/can0", can); + if (ret < 0) + { + canerr("ERROR: can_register failed: %d\n", ret); + return ret; + } + + return OK; +#else + return -ENODEV; +#endif +} + +#endif /* CONFIG_CAN */ diff --git a/configs/clicker2-stm32/src/stm32_usb.c b/configs/clicker2-stm32/src/stm32_usb.c new file mode 100644 index 0000000000..1eae6f6a8e --- /dev/null +++ b/configs/clicker2-stm32/src/stm32_usb.c @@ -0,0 +1,105 @@ +/************************************************************************************ + * configs/clicker2-stm32/src/stm32_usb.c + * + * 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. + * + ************************************************************************************/ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include +#include +#include + +#include "stm32_otgfs.h" +#include "clicker2-stm32.h" + +#ifdef CONFIG_STM32_OTGFS + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +#ifdef CONFIG_USBDEV +# define HAVE_USB 1 +#else +# warning "CONFIG_STM32_OTGFS is enabled but CONFIG_USBDEV is not" +# undef HAVE_USB +#endif + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_usb_configure + * + * Description: + * Called from stm32_boardinitialize very early in inialization to setup USB-related + * GPIO pins for the Olimex STM32 P407 board. + * + ************************************************************************************/ + +void stm32_usb_configure(void) +{ +#ifdef CONFIG_STM32_OTGFS + /* The OTG FS has an internal soft pull-up. No GPIO configuration is required */ + + /* Configure the OTG FS VBUS sensing GPIO */ + + stm32_configgpio(GPIO_OTGFS_VBUS); +#endif +} + +/************************************************************************************ + * Name: stm32_usbsuspend + * + * Description: + * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is + * used. This function is called whenever the USB enters or leaves suspend mode. + * This is an opportunity for the board logic to shutdown clocks, power, etc. + * while the USB is suspended. + * + ************************************************************************************/ + +#ifdef CONFIG_USBDEV +void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) +{ + uinfo("resume: %d\n", resume); +} +#endif + +#endif /* CONFIG_STM32_OTGFS */ diff --git a/configs/clicker2-stm32/src/stm32_userleds.c b/configs/clicker2-stm32/src/stm32_userleds.c new file mode 100644 index 0000000000..4398f4444f --- /dev/null +++ b/configs/clicker2-stm32/src/stm32_userleds.c @@ -0,0 +1,97 @@ +/**************************************************************************** + * configs/clicker2-stm32/src/stm32_userleds.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include "stm32.h" +#include "clicker2-stm32.h" + +#ifndef CONFIG_ARCH_LEDS + +/**************************************************************************** + * Name: board_userled_initialize + ****************************************************************************/ + +void board_userled_initialize(void) +{ + /* Configure LED1-2 GPIOs for output */ + + stm32_configgpio(GPIO_LED1); + stm32_configgpio(GPIO_LED2); +} + +/**************************************************************************** + * Name: board_userled + ****************************************************************************/ + +void board_userled(int led, bool ledon) +{ + gpioconfig_t ledcfg; + + if (led == BOARD_LED1) + { + ledcfg = GPIO_LED1; + } + else if (led == BOARD_LED2) + { + ledcfg = GPIO_LED2; + } + else + { + return; + } + + stm32_gpiowrite(ledcfg, true); +} + +/**************************************************************************** + * Name: board_userled_all + ****************************************************************************/ + +void board_userled_all(uint8_t ledset) +{ + stm32_gpiowrite(GPIO_LED1, (ledset & BOARD_LED1_BIT) != 0); + stm32_gpiowrite(GPIO_LED2, (ledset & BOARD_LED2_BIT) != 0); +} + +#endif /* !CONFIG_ARCH_LEDS */ -- GitLab From 5861d9610cebe408bfe38066754dedd0ee13a26b Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 22 Mar 2017 09:46:17 -0600 Subject: [PATCH 148/990] Clicker2-STM32: Add an NSH configuration --- configs/Kconfig | 13 + configs/README.txt | 3 + configs/clicker2-stm32/Kconfig | 4 + configs/clicker2-stm32/nsh/Make.defs | 122 +++ configs/clicker2-stm32/nsh/defconfig | 1325 ++++++++++++++++++++++++++ configs/clicker2-stm32/nsh/setenv.sh | 80 ++ 6 files changed, 1547 insertions(+) create mode 100644 configs/clicker2-stm32/Kconfig create mode 100644 configs/clicker2-stm32/nsh/Make.defs create mode 100644 configs/clicker2-stm32/nsh/defconfig create mode 100644 configs/clicker2-stm32/nsh/setenv.sh diff --git a/configs/Kconfig b/configs/Kconfig index d4bb9fe5bd..aef29eecd6 100644 --- a/configs/Kconfig +++ b/configs/Kconfig @@ -60,6 +60,15 @@ config ARCH_BOARD_C5471EVM NuttX runs on the ARM core and is built with a GNU arm-nuttx-elf toolchain*. This port is complete and verified. +config ARCH_BOARD_CLICKER2_STM32 + bool "Mikrow Clicker2 STM32" + depends on ARCH_CHIP_STM32F407VG + select ARCH_HAVE_LEDS + select ARCH_HAVE_BUTTONS + select ARCH_HAVE_IRQBUTTONS + ---help--- + Mikroe Clicker2 STM32 board based on the STMicro STM32F407VGT6 MCU. + config ARCH_BOARD_CLOUDCTRL bool "Darcy's CloudController stm32f10x board" depends on ARCH_CHIP_STM32F107VC @@ -1423,6 +1432,7 @@ config ARCH_BOARD default "avr32dev1" if ARCH_BOARD_AVR32DEV1 default "bambino-200e" if ARCH_BOARD_BAMBINO_200E default "c5471evm" if ARCH_BOARD_C5471EVM + default "clicker2-stm32" if ARCH_BOARD_CLICKER2_STM32 default "cloudctrl" if ARCH_BOARD_CLOUDCTRL default "demo9s12ne64" if ARCH_BOARD_DEMOS92S12NEC64 default "dk-tm4c129x" if ARCH_BOARD_DK_TM4C129X @@ -1604,6 +1614,9 @@ endif if ARCH_BOARD_C5471EVM source "configs/c5471evm/Kconfig" endif +if ARCH_BOARD_CLICKER2_STM32 +source "configs/clicker2-stm32/Kconfig" +endif if ARCH_BOARD_CLOUDCTRL source "configs/cloudctrl/Kconfig" endif diff --git a/configs/README.txt b/configs/README.txt index 316108f877..f33e3a0692 100644 --- a/configs/README.txt +++ b/configs/README.txt @@ -201,6 +201,9 @@ configs/c5471evm NuttX runs on the ARM core and is built with a GNU arm-nuttx-elf toolchain*. This port is complete and verified. +config/clicker2-stm32 + Mikroe Clicker2 STM32 board based on the STMicro STM32F407VGT6 MCU. + configs/cloudctrl Darcy's CloudController board. This is a small network relay development board. Based on the Shenzhou IV development board design. It is based on diff --git a/configs/clicker2-stm32/Kconfig b/configs/clicker2-stm32/Kconfig new file mode 100644 index 0000000000..f72f3c094c --- /dev/null +++ b/configs/clicker2-stm32/Kconfig @@ -0,0 +1,4 @@ +# +# For a description of the syntax of this configuration file, +# see the file kconfig-language.txt in the NuttX tools repository. +# diff --git a/configs/clicker2-stm32/nsh/Make.defs b/configs/clicker2-stm32/nsh/Make.defs new file mode 100644 index 0000000000..53d64dcf36 --- /dev/null +++ b/configs/clicker2-stm32/nsh/Make.defs @@ -0,0 +1,122 @@ +############################################################################ +# configs/clicker2-stm32/nsh/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. +# +############################################################################ + +include ${TOPDIR}/.config +include ${TOPDIR}/tools/Config.mk +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs + +LDSCRIPT = flash.ld + +ifeq ($(WINTOOL),y) + # Windows-native toolchains + DIRLINK = $(TOPDIR)/tools/copydir.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mkwindeps.sh + ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" + ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" +else + # Linux/Cygwin-native toolchain + MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT) + ARCHINCLUDES = -I. -isystem $(TOPDIR)/include + ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) +endif + +CC = $(CROSSDEV)gcc +CXX = $(CROSSDEV)g++ +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(CROSSDEV)ar rcs +NM = $(CROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump + +ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} +ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} + +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + ARCHOPTIMIZATION = -g +endif + +ifneq ($(CONFIG_DEBUG_NOOPT),y) + ARCHOPTIMIZATION += $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer +endif + +ARCHCFLAGS = -fno-builtin +ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fcheck-new -fno-rtti +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow -Wundef +ARCHWARNINGSXX = -Wall -Wshadow -Wundef +ARCHDEFINES = +ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 + +CFLAGS = $(ARCHCFLAGS) $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) +CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +NXFLATLDFLAGS1 = -r -d -warn-common +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections +LDNXFLATFLAGS = -e main -s 2048 + +# Loadable module definitions + +CMODULEFLAGS = $(CFLAGS) -mlong-calls # --target1-abs + +LDMODULEFLAGS = -r -e module_initialize +ifeq ($(WINTOOL),y) + LDMODULEFLAGS += -T "${shell cygpath -w $(TOPDIR)/libc/modlib/gnu-elf.ld}" +else + LDMODULEFLAGS += -T $(TOPDIR)/libc/modlib/gnu-elf.ld +endif + +ASMEXT = .S +OBJEXT = .o +LIBEXT = .a +EXEEXT = + +ifneq ($(CROSSDEV),arm-nuttx-elf-) + LDFLAGS += -nostartfiles -nodefaultlibs +endif +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + LDFLAGS += -g +endif + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -Wundef -g -pipe +HOSTLDFLAGS = diff --git a/configs/clicker2-stm32/nsh/defconfig b/configs/clicker2-stm32/nsh/defconfig new file mode 100644 index 0000000000..7ae63061f9 --- /dev/null +++ b/configs/clicker2-stm32/nsh/defconfig @@ -0,0 +1,1325 @@ +# +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# + +# +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set +# CONFIG_DEFAULT_SMALL is not set +CONFIG_HOST_LINUX=y +# CONFIG_HOST_OSX is not set +# CONFIG_HOST_WINDOWS is not set +# CONFIG_HOST_OTHER is not set + +# +# Build Configuration +# +# CONFIG_APPS_DIR="../apps" +CONFIG_BUILD_FLAT=y +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +CONFIG_INTELHEX_BINARY=y +# CONFIG_MOTOROLA_SREC is not set +CONFIG_RAW_BINARY=y +# CONFIG_UBOOT_UIMAGE is not set + +# +# Customize Header Files +# +# CONFIG_ARCH_STDINT_H is not set +# CONFIG_ARCH_STDBOOL_H is not set +# CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_FLOAT_H is not set +# CONFIG_ARCH_STDARG_H is not set +# CONFIG_ARCH_DEBUG_H is not set + +# +# Debug Options +# +CONFIG_DEBUG_ALERT=y +# CONFIG_DEBUG_FEATURES is not set +CONFIG_ARCH_HAVE_STACKCHECK=y +# CONFIG_STACK_COLORATION is not set +CONFIG_ARCH_HAVE_HEAPCHECK=y +# CONFIG_HEAP_COLORATION is not set +# CONFIG_DEBUG_SYMBOLS is not set +CONFIG_ARCH_HAVE_CUSTOMOPT=y +# CONFIG_DEBUG_NOOPT is not set +# CONFIG_DEBUG_CUSTOMOPT is not set +CONFIG_DEBUG_FULLOPT=y + +# +# System Type +# +CONFIG_ARCH_ARM=y +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_MISOC is not set +# CONFIG_ARCH_RENESAS is not set +# CONFIG_ARCH_RISCV is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_XTENSA is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="arm" + +# +# ARM Options +# +# CONFIG_ARCH_CHIP_A1X is not set +# CONFIG_ARCH_CHIP_C5471 is not set +# CONFIG_ARCH_CHIP_DM320 is not set +# CONFIG_ARCH_CHIP_EFM32 is not set +# CONFIG_ARCH_CHIP_IMX1 is not set +# CONFIG_ARCH_CHIP_IMX6 is not set +# CONFIG_ARCH_CHIP_KINETIS is not set +# CONFIG_ARCH_CHIP_KL is not set +# CONFIG_ARCH_CHIP_LM is not set +# CONFIG_ARCH_CHIP_TIVA is not set +# CONFIG_ARCH_CHIP_LPC11XX is not set +# CONFIG_ARCH_CHIP_LPC17XX is not set +# CONFIG_ARCH_CHIP_LPC214X is not set +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_NUC1XX is not set +# CONFIG_ARCH_CHIP_SAMA5 is not set +# CONFIG_ARCH_CHIP_SAMD is not set +# CONFIG_ARCH_CHIP_SAML is not set +# CONFIG_ARCH_CHIP_SAM34 is not set +# CONFIG_ARCH_CHIP_SAMV7 is not set +CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F7 is not set +# CONFIG_ARCH_CHIP_STM32L4 is not set +# CONFIG_ARCH_CHIP_STR71X is not set +# CONFIG_ARCH_CHIP_TMS570 is not set +# CONFIG_ARCH_CHIP_XMC4 is not set +# CONFIG_ARCH_ARM7TDMI is not set +# CONFIG_ARCH_ARM926EJS is not set +# CONFIG_ARCH_ARM920T is not set +# CONFIG_ARCH_CORTEXM0 is not set +# CONFIG_ARCH_CORTEXM23 is not set +# CONFIG_ARCH_CORTEXM3 is not set +# CONFIG_ARCH_CORTEXM33 is not set +CONFIG_ARCH_CORTEXM4=y +# CONFIG_ARCH_CORTEXM7 is not set +# CONFIG_ARCH_CORTEXA5 is not set +# CONFIG_ARCH_CORTEXA8 is not set +# CONFIG_ARCH_CORTEXA9 is not set +# CONFIG_ARCH_CORTEXR4 is not set +# CONFIG_ARCH_CORTEXR4F is not set +# CONFIG_ARCH_CORTEXR5 is not set +# CONFIG_ARCH_CORTEX5F is not set +# CONFIG_ARCH_CORTEXR7 is not set +# CONFIG_ARCH_CORTEXR7F is not set +CONFIG_ARCH_FAMILY="armv7-m" +CONFIG_ARCH_CHIP="stm32" +# CONFIG_ARM_TOOLCHAIN_IAR is not set +CONFIG_ARM_TOOLCHAIN_GNU=y +# CONFIG_ARMV7M_USEBASEPRI is not set +CONFIG_ARCH_HAVE_CMNVECTOR=y +# CONFIG_ARMV7M_CMNVECTOR is not set +# CONFIG_ARMV7M_LAZYFPU is not set +CONFIG_ARCH_HAVE_FPU=y +# CONFIG_ARCH_HAVE_DPFPU is not set +CONFIG_ARCH_FPU=y +# CONFIG_ARCH_HAVE_TRUSTZONE is not set +CONFIG_ARM_HAVE_MPU_UNIFIED=y +# CONFIG_ARM_MPU is not set + +# +# ARMV7M Configuration Options +# +# CONFIG_ARMV7M_HAVE_ICACHE is not set +# CONFIG_ARMV7M_HAVE_DCACHE is not set +# CONFIG_ARMV7M_HAVE_ITCM is not set +# CONFIG_ARMV7M_HAVE_DTCM is not set +# CONFIG_ARMV7M_TOOLCHAIN_IARL is not set +CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y +# CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set +# CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL is not set +# CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL is not set +# CONFIG_ARMV7M_OABI_TOOLCHAIN is not set +CONFIG_ARMV7M_HAVE_STACKCHECK=y +# CONFIG_ARMV7M_STACKCHECK is not set +# CONFIG_ARMV7M_ITMSYSLOG is not set +# CONFIG_SERIAL_TERMIOS is not set +# CONFIG_USBHOST_BULK_DISABLE is not set +# CONFIG_USBHOST_INT_DISABLE is not set +# CONFIG_USBHOST_ISOC_DISABLE is not set + +# +# STM32 Configuration Options +# +# CONFIG_ARCH_CHIP_STM32L151C6 is not set +# CONFIG_ARCH_CHIP_STM32L151C8 is not set +# CONFIG_ARCH_CHIP_STM32L151CB is not set +# CONFIG_ARCH_CHIP_STM32L151R6 is not set +# CONFIG_ARCH_CHIP_STM32L151R8 is not set +# CONFIG_ARCH_CHIP_STM32L151RB is not set +# CONFIG_ARCH_CHIP_STM32L151V6 is not set +# CONFIG_ARCH_CHIP_STM32L151V8 is not set +# CONFIG_ARCH_CHIP_STM32L151VB is not set +# CONFIG_ARCH_CHIP_STM32L152C6 is not set +# CONFIG_ARCH_CHIP_STM32L152C8 is not set +# CONFIG_ARCH_CHIP_STM32L152CB is not set +# CONFIG_ARCH_CHIP_STM32L152R6 is not set +# CONFIG_ARCH_CHIP_STM32L152R8 is not set +# CONFIG_ARCH_CHIP_STM32L152RB is not set +# CONFIG_ARCH_CHIP_STM32L152V6 is not set +# CONFIG_ARCH_CHIP_STM32L152V8 is not set +# CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L162ZD is not set +# CONFIG_ARCH_CHIP_STM32L162VE is not set +# CONFIG_ARCH_CHIP_STM32F100C8 is not set +# CONFIG_ARCH_CHIP_STM32F100CB is not set +# CONFIG_ARCH_CHIP_STM32F100R8 is not set +# CONFIG_ARCH_CHIP_STM32F100RB is not set +# CONFIG_ARCH_CHIP_STM32F100RC is not set +# CONFIG_ARCH_CHIP_STM32F100RD is not set +# CONFIG_ARCH_CHIP_STM32F100RE is not set +# CONFIG_ARCH_CHIP_STM32F100V8 is not set +# CONFIG_ARCH_CHIP_STM32F100VB is not set +# CONFIG_ARCH_CHIP_STM32F100VC is not set +# CONFIG_ARCH_CHIP_STM32F100VD is not set +# CONFIG_ARCH_CHIP_STM32F100VE is not set +# CONFIG_ARCH_CHIP_STM32F102CB is not set +# CONFIG_ARCH_CHIP_STM32F103T8 is not set +# CONFIG_ARCH_CHIP_STM32F103TB is not set +# CONFIG_ARCH_CHIP_STM32F103C4 is not set +# CONFIG_ARCH_CHIP_STM32F103C8 is not set +# CONFIG_ARCH_CHIP_STM32F103CB is not set +# CONFIG_ARCH_CHIP_STM32F103R8 is not set +# CONFIG_ARCH_CHIP_STM32F103RB is not set +# CONFIG_ARCH_CHIP_STM32F103RC is not set +# CONFIG_ARCH_CHIP_STM32F103RD is not set +# CONFIG_ARCH_CHIP_STM32F103RE is not set +# CONFIG_ARCH_CHIP_STM32F103RG is not set +# CONFIG_ARCH_CHIP_STM32F103V8 is not set +# CONFIG_ARCH_CHIP_STM32F103VB is not set +# CONFIG_ARCH_CHIP_STM32F103VC is not set +# CONFIG_ARCH_CHIP_STM32F103VE is not set +# CONFIG_ARCH_CHIP_STM32F103ZE is not set +# CONFIG_ARCH_CHIP_STM32F105VB is not set +# CONFIG_ARCH_CHIP_STM32F105RB is not set +# CONFIG_ARCH_CHIP_STM32F107VC is not set +# CONFIG_ARCH_CHIP_STM32F205RG is not set +# CONFIG_ARCH_CHIP_STM32F207IG is not set +# CONFIG_ARCH_CHIP_STM32F207ZE is not set +# CONFIG_ARCH_CHIP_STM32F302K6 is not set +# CONFIG_ARCH_CHIP_STM32F302K8 is not set +# CONFIG_ARCH_CHIP_STM32F302CB is not set +# CONFIG_ARCH_CHIP_STM32F302CC is not set +# CONFIG_ARCH_CHIP_STM32F302RB is not set +# CONFIG_ARCH_CHIP_STM32F302RC is not set +# CONFIG_ARCH_CHIP_STM32F302VB is not set +# CONFIG_ARCH_CHIP_STM32F302VC is not set +# CONFIG_ARCH_CHIP_STM32F303K6 is not set +# CONFIG_ARCH_CHIP_STM32F303K8 is not set +# CONFIG_ARCH_CHIP_STM32F303C6 is not set +# CONFIG_ARCH_CHIP_STM32F303C8 is not set +# CONFIG_ARCH_CHIP_STM32F303CB is not set +# CONFIG_ARCH_CHIP_STM32F303CC is not set +# CONFIG_ARCH_CHIP_STM32F303RB is not set +# CONFIG_ARCH_CHIP_STM32F303RC is not set +# CONFIG_ARCH_CHIP_STM32F303RD is not set +# CONFIG_ARCH_CHIP_STM32F303RE is not set +# CONFIG_ARCH_CHIP_STM32F303VB is not set +# CONFIG_ARCH_CHIP_STM32F303VC is not set +# CONFIG_ARCH_CHIP_STM32F334K4 is not set +# CONFIG_ARCH_CHIP_STM32F334K6 is not set +# CONFIG_ARCH_CHIP_STM32F334K8 is not set +# CONFIG_ARCH_CHIP_STM32F334C4 is not set +# CONFIG_ARCH_CHIP_STM32F334C6 is not set +# CONFIG_ARCH_CHIP_STM32F334C8 is not set +# CONFIG_ARCH_CHIP_STM32F334R4 is not set +# CONFIG_ARCH_CHIP_STM32F334R6 is not set +# CONFIG_ARCH_CHIP_STM32F334R8 is not set +# CONFIG_ARCH_CHIP_STM32F372C8 is not set +# CONFIG_ARCH_CHIP_STM32F372R8 is not set +# CONFIG_ARCH_CHIP_STM32F372V8 is not set +# CONFIG_ARCH_CHIP_STM32F372CB is not set +# CONFIG_ARCH_CHIP_STM32F372RB is not set +# CONFIG_ARCH_CHIP_STM32F372VB is not set +# CONFIG_ARCH_CHIP_STM32F372CC is not set +# CONFIG_ARCH_CHIP_STM32F372RC is not set +# CONFIG_ARCH_CHIP_STM32F372VC is not set +# CONFIG_ARCH_CHIP_STM32F373C8 is not set +# CONFIG_ARCH_CHIP_STM32F373R8 is not set +# CONFIG_ARCH_CHIP_STM32F373V8 is not set +# CONFIG_ARCH_CHIP_STM32F373CB is not set +# CONFIG_ARCH_CHIP_STM32F373RB is not set +# CONFIG_ARCH_CHIP_STM32F373VB is not set +# CONFIG_ARCH_CHIP_STM32F373CC is not set +# CONFIG_ARCH_CHIP_STM32F373RC is not set +# CONFIG_ARCH_CHIP_STM32F373VC is not set +# CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F411RE is not set +# CONFIG_ARCH_CHIP_STM32F411VE is not set +# CONFIG_ARCH_CHIP_STM32F405RG is not set +# CONFIG_ARCH_CHIP_STM32F405VG is not set +# CONFIG_ARCH_CHIP_STM32F405ZG is not set +# CONFIG_ARCH_CHIP_STM32F407VE is not set +CONFIG_ARCH_CHIP_STM32F407VG=y +# CONFIG_ARCH_CHIP_STM32F407ZE is not set +# CONFIG_ARCH_CHIP_STM32F407ZG is not set +# CONFIG_ARCH_CHIP_STM32F407IE is not set +# CONFIG_ARCH_CHIP_STM32F407IG is not set +# CONFIG_ARCH_CHIP_STM32F427V is not set +# CONFIG_ARCH_CHIP_STM32F427Z is not set +# CONFIG_ARCH_CHIP_STM32F427I is not set +# CONFIG_ARCH_CHIP_STM32F429V is not set +# CONFIG_ARCH_CHIP_STM32F429Z is not set +# CONFIG_ARCH_CHIP_STM32F429I is not set +# CONFIG_ARCH_CHIP_STM32F429B is not set +# CONFIG_ARCH_CHIP_STM32F429N is not set +# CONFIG_ARCH_CHIP_STM32F446M is not set +# CONFIG_ARCH_CHIP_STM32F446R is not set +# CONFIG_ARCH_CHIP_STM32F446V is not set +# CONFIG_ARCH_CHIP_STM32F446Z is not set +# CONFIG_ARCH_CHIP_STM32F469A is not set +# CONFIG_ARCH_CHIP_STM32F469I is not set +# CONFIG_ARCH_CHIP_STM32F469B is not set +# CONFIG_ARCH_CHIP_STM32F469N is not set +CONFIG_STM32_FLASH_CONFIG_DEFAULT=y +# CONFIG_STM32_FLASH_CONFIG_4 is not set +# CONFIG_STM32_FLASH_CONFIG_6 is not set +# CONFIG_STM32_FLASH_CONFIG_8 is not set +# CONFIG_STM32_FLASH_CONFIG_B is not set +# CONFIG_STM32_FLASH_CONFIG_C is not set +# CONFIG_STM32_FLASH_CONFIG_D is not set +# CONFIG_STM32_FLASH_CONFIG_E is not set +# CONFIG_STM32_FLASH_CONFIG_F is not set +# CONFIG_STM32_FLASH_CONFIG_G is not set +# CONFIG_STM32_FLASH_CONFIG_I is not set +# CONFIG_STM32_STM32L15XX is not set +# CONFIG_STM32_ENERGYLITE is not set +# CONFIG_STM32_STM32F10XX is not set +# CONFIG_STM32_VALUELINE is not set +# CONFIG_STM32_CONNECTIVITYLINE is not set +# CONFIG_STM32_PERFORMANCELINE is not set +# CONFIG_STM32_USBACCESSLINE is not set +# CONFIG_STM32_HIGHDENSITY is not set +# CONFIG_STM32_MEDIUMDENSITY is not set +# CONFIG_STM32_LOWDENSITY is not set +# CONFIG_STM32_STM32F20XX is not set +# CONFIG_STM32_STM32F205 is not set +# CONFIG_STM32_STM32F207 is not set +# CONFIG_STM32_STM32F30XX is not set +# CONFIG_STM32_STM32F302 is not set +# CONFIG_STM32_STM32F303 is not set +# CONFIG_STM32_STM32F33XX is not set +# CONFIG_STM32_STM32F37XX is not set +CONFIG_STM32_STM32F40XX=y +# CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F411 is not set +# CONFIG_STM32_STM32F405 is not set +CONFIG_STM32_STM32F407=y +# CONFIG_STM32_STM32F427 is not set +# CONFIG_STM32_STM32F429 is not set +# CONFIG_STM32_STM32F446 is not set +# CONFIG_STM32_STM32F469 is not set +# CONFIG_STM32_DFU is not set + +# +# STM32 Peripheral Support +# +CONFIG_STM32_HAVE_CCM=y +# CONFIG_STM32_HAVE_USBDEV is not set +CONFIG_STM32_HAVE_OTGFS=y +CONFIG_STM32_HAVE_FSMC=y +# CONFIG_STM32_HAVE_HRTIM1 is not set +# CONFIG_STM32_HAVE_LTDC is not set +CONFIG_STM32_HAVE_USART3=y +CONFIG_STM32_HAVE_UART4=y +CONFIG_STM32_HAVE_UART5=y +CONFIG_STM32_HAVE_USART6=y +# CONFIG_STM32_HAVE_UART7 is not set +# CONFIG_STM32_HAVE_UART8 is not set +CONFIG_STM32_HAVE_TIM1=y +CONFIG_STM32_HAVE_TIM2=y +CONFIG_STM32_HAVE_TIM3=y +CONFIG_STM32_HAVE_TIM4=y +CONFIG_STM32_HAVE_TIM5=y +CONFIG_STM32_HAVE_TIM6=y +CONFIG_STM32_HAVE_TIM7=y +CONFIG_STM32_HAVE_TIM8=y +CONFIG_STM32_HAVE_TIM9=y +CONFIG_STM32_HAVE_TIM10=y +CONFIG_STM32_HAVE_TIM11=y +CONFIG_STM32_HAVE_TIM12=y +CONFIG_STM32_HAVE_TIM13=y +CONFIG_STM32_HAVE_TIM14=y +# CONFIG_STM32_HAVE_TIM15 is not set +# CONFIG_STM32_HAVE_TIM16 is not set +# CONFIG_STM32_HAVE_TIM17 is not set +CONFIG_STM32_HAVE_ADC2=y +CONFIG_STM32_HAVE_ADC3=y +# CONFIG_STM32_HAVE_ADC4 is not set +# CONFIG_STM32_HAVE_ADC1_DMA is not set +# CONFIG_STM32_HAVE_ADC2_DMA is not set +# CONFIG_STM32_HAVE_ADC3_DMA is not set +# CONFIG_STM32_HAVE_ADC4_DMA is not set +# CONFIG_STM32_HAVE_SDADC1 is not set +# CONFIG_STM32_HAVE_SDADC2 is not set +# CONFIG_STM32_HAVE_SDADC3 is not set +# CONFIG_STM32_HAVE_SDADC1_DMA is not set +# CONFIG_STM32_HAVE_SDADC2_DMA is not set +# CONFIG_STM32_HAVE_SDADC3_DMA is not set +CONFIG_STM32_HAVE_CAN1=y +CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP6 is not set +CONFIG_STM32_HAVE_DAC1=y +CONFIG_STM32_HAVE_DAC2=y +CONFIG_STM32_HAVE_RNG=y +CONFIG_STM32_HAVE_ETHMAC=y +CONFIG_STM32_HAVE_I2C2=y +CONFIG_STM32_HAVE_I2C3=y +CONFIG_STM32_HAVE_SPI2=y +CONFIG_STM32_HAVE_SPI3=y +# CONFIG_STM32_HAVE_SPI4 is not set +# CONFIG_STM32_HAVE_SPI5 is not set +# CONFIG_STM32_HAVE_SPI6 is not set +# CONFIG_STM32_HAVE_SAIPLL is not set +# CONFIG_STM32_HAVE_I2SPLL is not set +# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_ADC1 is not set +# CONFIG_STM32_ADC2 is not set +# CONFIG_STM32_ADC3 is not set +# CONFIG_STM32_BKPSRAM is not set +# CONFIG_STM32_CAN1 is not set +# CONFIG_STM32_CAN2 is not set +# CONFIG_STM32_CCMDATARAM is not set +# CONFIG_STM32_CRC is not set +# CONFIG_STM32_CRYP is not set +# CONFIG_STM32_DMA1 is not set +# CONFIG_STM32_DMA2 is not set +# CONFIG_STM32_DAC1 is not set +# CONFIG_STM32_DAC2 is not set +# CONFIG_STM32_DCMI is not set +# CONFIG_STM32_ETHMAC is not set +# CONFIG_STM32_FSMC is not set +# CONFIG_STM32_HASH is not set +# CONFIG_STM32_I2C1 is not set +# CONFIG_STM32_I2C2 is not set +# CONFIG_STM32_I2C3 is not set +CONFIG_STM32_OTGFS=y +# CONFIG_STM32_OTGHS is not set +CONFIG_STM32_PWR=y +# CONFIG_STM32_RNG is not set +# CONFIG_STM32_SDIO is not set +# CONFIG_STM32_SPI1 is not set +# CONFIG_STM32_SPI2 is not set +# CONFIG_STM32_SPI3 is not set +CONFIG_STM32_SYSCFG=y +# CONFIG_STM32_TIM1 is not set +# CONFIG_STM32_TIM2 is not set +# CONFIG_STM32_TIM3 is not set +# CONFIG_STM32_TIM4 is not set +# CONFIG_STM32_TIM5 is not set +# CONFIG_STM32_TIM6 is not set +# CONFIG_STM32_TIM7 is not set +# CONFIG_STM32_TIM8 is not set +# CONFIG_STM32_TIM9 is not set +# CONFIG_STM32_TIM10 is not set +# CONFIG_STM32_TIM11 is not set +# CONFIG_STM32_TIM12 is not set +# CONFIG_STM32_TIM13 is not set +# CONFIG_STM32_TIM14 is not set +# CONFIG_STM32_USART1 is not set +# CONFIG_STM32_USART2 is not set +CONFIG_STM32_USART3=y +# CONFIG_STM32_UART4 is not set +# CONFIG_STM32_UART5 is not set +# CONFIG_STM32_USART6 is not set +# CONFIG_STM32_IWDG is not set +# CONFIG_STM32_WWDG is not set +# CONFIG_STM32_NOEXT_VECTORS is not set + +# +# Alternate Pin Mapping +# +# CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_JTAG_DISABLE is not set +# CONFIG_STM32_JTAG_FULL_ENABLE is not set +# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y +# CONFIG_STM32_FORCEPOWER is not set +# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set +CONFIG_STM32_CCMEXCLUDE=y + +# +# Timer Configuration +# +# CONFIG_STM32_ONESHOT is not set +# CONFIG_STM32_FREERUN is not set +# CONFIG_STM32_TIM1_CAP is not set +# CONFIG_STM32_TIM2_CAP is not set +# CONFIG_STM32_TIM3_CAP is not set +# CONFIG_STM32_TIM4_CAP is not set +# CONFIG_STM32_TIM5_CAP is not set +# CONFIG_STM32_TIM8_CAP is not set +# CONFIG_STM32_TIM9_CAP is not set +# CONFIG_STM32_TIM10_CAP is not set +# CONFIG_STM32_TIM11_CAP is not set +# CONFIG_STM32_TIM12_CAP is not set +# CONFIG_STM32_TIM13_CAP is not set +# CONFIG_STM32_TIM14_CAP is not set +CONFIG_STM32_USART=y +CONFIG_STM32_SERIALDRIVER=y + +# +# U[S]ART Configuration +# + +# +# U[S]ART Device Configuration +# +CONFIG_STM32_USART3_SERIALDRIVER=y +# CONFIG_STM32_USART3_1WIREDRIVER is not set +# CONFIG_USART3_RS485 is not set + +# +# Serial Driver Configuration +# +# CONFIG_SERIAL_DISABLE_REORDERING is not set +# CONFIG_STM32_FLOWCONTROL_BROKEN is not set +# CONFIG_STM32_USART_BREAKS is not set +# CONFIG_STM32_USART_SINGLEWIRE is not set +# CONFIG_STM32_HAVE_RTC_COUNTER is not set +# CONFIG_STM32_HAVE_RTC_SUBSECONDS is not set + +# +# USB FS Host Configuration +# +CONFIG_STM32_OTGFS_RXFIFO_SIZE=128 +CONFIG_STM32_OTGFS_NPTXFIFO_SIZE=96 +CONFIG_STM32_OTGFS_PTXFIFO_SIZE=128 +CONFIG_STM32_OTGFS_DESCSIZE=128 +# CONFIG_STM32_OTGFS_SOFINTR is not set + +# +# USB HS Host Configuration +# + +# +# USB Host Debug Configuration +# + +# +# USB Device Configuration +# + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_VECNOTIRQ is not set +# CONFIG_ARCH_DMA is not set +CONFIG_ARCH_HAVE_IRQPRIO=y +# CONFIG_ARCH_L2CACHE is not set +# CONFIG_ARCH_HAVE_COHERENT_DCACHE is not set +# CONFIG_ARCH_HAVE_ADDRENV is not set +# CONFIG_ARCH_NEED_ADDRENV_MAPPING is not set +# CONFIG_ARCH_HAVE_MULTICPU is not set +CONFIG_ARCH_HAVE_VFORK=y +# CONFIG_ARCH_HAVE_MMU is not set +CONFIG_ARCH_HAVE_MPU=y +# CONFIG_ARCH_NAND_HWECC is not set +# CONFIG_ARCH_HAVE_EXTCLK is not set +# CONFIG_ARCH_HAVE_POWEROFF is not set +CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_USE_MPU is not set +# CONFIG_ARCH_IRQPRIO is not set +CONFIG_ARCH_STACKDUMP=y +# CONFIG_ENDIAN_BIG is not set +# CONFIG_ARCH_IDLE_CUSTOM is not set +# CONFIG_ARCH_HAVE_RAMFUNCS is not set +CONFIG_ARCH_HAVE_RAMVECTORS=y +# CONFIG_ARCH_RAMVECTORS is not set +# CONFIG_ARCH_MINIMAL_VECTORTABLE is not set + +# +# Board Settings +# +CONFIG_BOARD_LOOPSPERMSEC=16717 +# CONFIG_ARCH_CALIBRATION is not set + +# +# Interrupt options +# +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y +CONFIG_ARCH_INTERRUPTSTACK=0 +CONFIG_ARCH_HAVE_HIPRI_INTERRUPT=y +# CONFIG_ARCH_HIPRI_INTERRUPT is not set + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Boot Memory Configuration +# +CONFIG_RAM_START=0x20000000 +CONFIG_RAM_SIZE=131072 +# CONFIG_ARCH_HAVE_SDRAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_CLICKER2_STM32=y +# CONFIG_ARCH_BOARD_STM32F4_DISCOVERY is not set +# CONFIG_ARCH_BOARD_MIKROE_STM32F4 is not set +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="clicker2-stm32" + +# +# Common Board Options +# +CONFIG_ARCH_HAVE_LEDS=y +CONFIG_ARCH_LEDS=y +CONFIG_ARCH_HAVE_BUTTONS=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_HAVE_IRQBUTTONS=y +CONFIG_ARCH_IRQBUTTONS=y + +# +# Board-Specific Options +# +# CONFIG_BOARD_CRASHDUMP is not set +CONFIG_LIB_BOARDCTL=y +# CONFIG_BOARDCTL_RESET is not set +# CONFIG_BOARDCTL_UNIQUEID is not set +# CONFIG_BOARDCTL_TSCTEST is not set +# CONFIG_BOARDCTL_GRAPHICS is not set +# CONFIG_BOARDCTL_IOCTL is not set + +# +# RTOS Features +# +CONFIG_DISABLE_OS_API=y +# CONFIG_DISABLE_POSIX_TIMERS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_DISABLE_SIGNALS is not set +# CONFIG_DISABLE_MQUEUE is not set +# CONFIG_DISABLE_ENVIRON is not set + +# +# Clocks and Timers +# +CONFIG_ARCH_HAVE_TICKLESS=y +# CONFIG_SCHED_TICKLESS is not set +CONFIG_USEC_PER_TICK=10000 +# CONFIG_SYSTEM_TIME64 is not set +# CONFIG_CLOCK_MONOTONIC is not set +CONFIG_ARCH_HAVE_TIMEKEEPING=y +# CONFIG_JULIAN_TIME is not set +CONFIG_START_YEAR=2013 +CONFIG_START_MONTH=1 +CONFIG_START_DAY=1 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=8 +CONFIG_WDOG_INTRESERVE=1 +CONFIG_PREALLOC_TIMERS=4 + +# +# Tasks and Scheduling +# +# CONFIG_SPINLOCK is not set +# CONFIG_INIT_NONE is not set +CONFIG_INIT_ENTRYPOINT=y +# CONFIG_INIT_FILEPATH is not set +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_RR_INTERVAL=200 +# CONFIG_SCHED_SPORADIC is not set +CONFIG_TASK_NAME_SIZE=32 +CONFIG_MAX_TASKS=16 +# CONFIG_SCHED_HAVE_PARENT is not set +CONFIG_SCHED_WAITPID=y + +# +# Pthread Options +# +# CONFIG_MUTEX_TYPES is not set +CONFIG_NPTHREAD_KEYS=4 +# CONFIG_PTHREAD_CLEANUP is not set +# CONFIG_CANCELLATION_POINTS is not set + +# +# Performance Monitoring +# +# CONFIG_SCHED_CPULOAD is not set +# CONFIG_SCHED_INSTRUMENTATION is not set + +# +# Files and I/O +# +CONFIG_DEV_CONSOLE=y +# CONFIG_FDCLONE_DISABLE is not set +# CONFIG_FDCLONE_STDIO is not set +CONFIG_SDCLONE_DISABLE=y +CONFIG_NFILE_DESCRIPTORS=8 +CONFIG_NFILE_STREAMS=8 +CONFIG_NAME_MAX=32 +# CONFIG_PRIORITY_INHERITANCE is not set + +# +# RTOS hooks +# +CONFIG_BOARD_INITIALIZE=y +# CONFIG_BOARD_INITTHREAD is not set +# CONFIG_SCHED_STARTHOOK is not set +# CONFIG_SCHED_ATEXIT is not set +# CONFIG_SCHED_ONEXIT is not set +# CONFIG_SIG_EVTHREAD is not set + +# +# Signal Numbers +# +CONFIG_SIG_SIGUSR1=1 +CONFIG_SIG_SIGUSR2=2 +CONFIG_SIG_SIGALARM=3 +CONFIG_SIG_SIGCONDTIMEDOUT=16 +CONFIG_SIG_SIGWORK=17 + +# +# POSIX Message Queue Options +# +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_MQ_MAXMSGSIZE=32 +# CONFIG_MODULE is not set + +# +# Work queue support +# +CONFIG_SCHED_WORKQUEUE=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=192 +CONFIG_SCHED_HPWORKPERIOD=50000 +CONFIG_SCHED_HPWORKSTACKSIZE=2048 +# CONFIG_SCHED_LPWORK is not set + +# +# Stack and heap information +# +CONFIG_IDLETHREAD_STACKSIZE=1024 +CONFIG_USERMAIN_STACKSIZE=2048 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=2048 +# CONFIG_LIB_SYSCALL is not set + +# +# Device Drivers +# +CONFIG_DISABLE_POLL=y +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_DEV_URANDOM is not set +# CONFIG_DEV_LOOP is not set + +# +# Buffering +# +# CONFIG_DRVR_WRITEBUFFER is not set +# CONFIG_DRVR_READAHEAD is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_ARCH_HAVE_PWM_PULSECOUNT is not set +# CONFIG_ARCH_HAVE_PWM_MULTICHAN is not set +# CONFIG_PWM is not set +CONFIG_ARCH_HAVE_I2CRESET=y +# CONFIG_I2C is not set +# CONFIG_ARCH_HAVE_SPI_CRCGENERATION is not set +# CONFIG_ARCH_HAVE_SPI_CS_CONTROL is not set +CONFIG_ARCH_HAVE_SPI_BITORDER=y +# CONFIG_SPI is not set +# CONFIG_I2S is not set + +# +# Timer Driver Support +# +# CONFIG_TIMER is not set +# CONFIG_ONESHOT is not set +# CONFIG_RTC is not set +# CONFIG_WATCHDOG is not set +# CONFIG_ANALOG is not set +# CONFIG_AUDIO_DEVICES is not set +# CONFIG_VIDEO_DEVICES is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set + +# +# IO Expander/GPIO Support +# +# CONFIG_IOEXPANDER is not set +# CONFIG_DEV_GPIO is not set + +# +# LCD Driver Support +# +# CONFIG_LCD is not set +# CONFIG_SLCD is not set + +# +# LED Support +# +# CONFIG_USERLED is not set +# CONFIG_RGBLED is not set +# CONFIG_PCA9635PW is not set +# CONFIG_NCP5623C is not set +# CONFIG_MMCSD is not set +# CONFIG_MODEM is not set +# CONFIG_MTD is not set +# CONFIG_EEPROM is not set +# CONFIG_PIPES is not set +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +CONFIG_SERIAL=y +# CONFIG_DEV_LOWCONSOLE is not set +# CONFIG_SERIAL_REMOVABLE is not set +CONFIG_SERIAL_CONSOLE=y +# CONFIG_16550_UART is not set +# CONFIG_UART_SERIALDRIVER is not set +# CONFIG_UART0_SERIALDRIVER is not set +# CONFIG_UART1_SERIALDRIVER is not set +# CONFIG_UART2_SERIALDRIVER is not set +# CONFIG_UART3_SERIALDRIVER is not set +# CONFIG_UART4_SERIALDRIVER is not set +# CONFIG_UART5_SERIALDRIVER is not set +# CONFIG_UART6_SERIALDRIVER is not set +# CONFIG_UART7_SERIALDRIVER is not set +# CONFIG_UART8_SERIALDRIVER is not set +# CONFIG_SCI0_SERIALDRIVER is not set +# CONFIG_SCI1_SERIALDRIVER is not set +# CONFIG_USART0_SERIALDRIVER is not set +# CONFIG_USART1_SERIALDRIVER is not set +# CONFIG_USART2_SERIALDRIVER is not set +CONFIG_USART3_SERIALDRIVER=y +# CONFIG_USART4_SERIALDRIVER is not set +# CONFIG_USART5_SERIALDRIVER is not set +# CONFIG_USART6_SERIALDRIVER is not set +# CONFIG_USART7_SERIALDRIVER is not set +# CONFIG_USART8_SERIALDRIVER is not set +# CONFIG_OTHER_UART_SERIALDRIVER is not set +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +# CONFIG_SERIAL_IFLOWCONTROL is not set +# CONFIG_SERIAL_OFLOWCONTROL is not set +# CONFIG_SERIAL_DMA is not set +CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y +CONFIG_USART3_SERIAL_CONSOLE=y +# CONFIG_OTHER_SERIAL_CONSOLE is not set +# CONFIG_NO_SERIAL_CONSOLE is not set + +# +# USART3 Configuration +# +CONFIG_USART3_RXBUFSIZE=256 +CONFIG_USART3_TXBUFSIZE=256 +CONFIG_USART3_BAUD=115200 +CONFIG_USART3_BITS=8 +CONFIG_USART3_PARITY=0 +CONFIG_USART3_2STOP=0 +# CONFIG_USART3_IFLOWCONTROL is not set +# CONFIG_USART3_OFLOWCONTROL is not set +# CONFIG_USART3_DMA is not set +# CONFIG_PSEUDOTERM is not set +# CONFIG_USBDEV is not set +CONFIG_USBHOST=y +CONFIG_USBHOST_NPREALLOC=4 +CONFIG_USBHOST_HAVE_ASYNCH=y +# CONFIG_USBHOST_ASYNCH is not set +# CONFIG_USBHOST_HUB is not set +# CONFIG_USBHOST_COMPOSITE is not set +CONFIG_USBHOST_MSC=y +# CONFIG_USBHOST_CDCACM is not set +# CONFIG_USBHOST_HIDKBD is not set +# CONFIG_USBHOST_HIDMOUSE is not set +# CONFIG_USBHOST_XBOXCONTROLLER is not set +# CONFIG_USBHOST_TRACE is not set +# CONFIG_HAVE_USBTRACE is not set +# CONFIG_DRIVERS_WIRELESS is not set +# CONFIG_DRIVERS_CONTACTLESS is not set + +# +# System Logging +# +# CONFIG_ARCH_SYSLOG is not set +# CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_INTBUFFER is not set +# CONFIG_SYSLOG_TIMESTAMP is not set +CONFIG_SYSLOG_SERIAL_CONSOLE=y +# CONFIG_SYSLOG_CHAR is not set +CONFIG_SYSLOG_CONSOLE=y +# CONFIG_SYSLOG_NONE is not set +# CONFIG_SYSLOG_FILE is not set +# CONFIG_SYSLOG_CHARDEV is not set + +# +# Networking Support +# +# CONFIG_ARCH_HAVE_NET is not set +# CONFIG_ARCH_HAVE_PHY is not set +# CONFIG_NET is not set + +# +# Crypto API +# +# CONFIG_CRYPTO is not set + +# +# File Systems +# + +# +# File system configuration +# +# CONFIG_DISABLE_MOUNTPOINT is not set +# CONFIG_FS_AUTOMOUNTER is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_PSEUDOFS_SOFTLINKS is not set +CONFIG_FS_READABLE=y +CONFIG_FS_WRITABLE=y +# CONFIG_FS_NAMED_SEMAPHORES is not set +CONFIG_FS_MQUEUE_MPATH="/var/mqueue" +# CONFIG_FS_RAMMAP is not set +CONFIG_FS_FAT=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_MAXFNAME=32 +# CONFIG_FS_FATTIME is not set +# CONFIG_FAT_FORCE_INDIRECT is not set +# CONFIG_FAT_DMAMEMORY is not set +# CONFIG_FAT_DIRECT_RETRY is not set +# CONFIG_FS_NXFFS is not set +# CONFIG_FS_ROMFS is not set +# CONFIG_FS_TMPFS is not set +# CONFIG_FS_SMARTFS is not set +# CONFIG_FS_BINFS is not set +CONFIG_FS_PROCFS=y +# CONFIG_FS_PROCFS_REGISTER is not set + +# +# Exclude individual procfs entries +# +# CONFIG_FS_PROCFS_EXCLUDE_PROCESS is not set +# CONFIG_FS_PROCFS_EXCLUDE_UPTIME is not set +# CONFIG_FS_PROCFS_EXCLUDE_MOUNTS is not set +# CONFIG_FS_UNIONFS is not set + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=1 +# CONFIG_ARCH_HAVE_HEAP2 is not set +# CONFIG_GRAN is not set + +# +# Audio Support +# +# CONFIG_AUDIO is not set + +# +# Wireless Support +# + +# +# Binary Loader +# +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_BINFMT_EXEPATH is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +CONFIG_BUILTIN=y +# CONFIG_PIC is not set +# CONFIG_SYMTAB_ORDEREDBYNAME is not set + +# +# Library Routines +# + +# +# Standard C Library Options +# + +# +# Standard C I/O +# +# CONFIG_STDIO_DISABLE_BUFFERING is not set +CONFIG_STDIO_BUFFER_SIZE=64 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +# CONFIG_NOPRINTF_FIELDWIDTH is not set +# CONFIG_LIBC_FLOATINGPOINT is not set +CONFIG_LIBC_LONG_LONG=y +# CONFIG_LIBC_SCANSET is not set +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_MEMCPY_VIK is not set +# CONFIG_LIBM is not set + +# +# Architecture-Specific Support +# +CONFIG_ARCH_LOWPUTC=y +# CONFIG_ARCH_ROMGETC is not set +# CONFIG_LIBC_ARCH_MEMCPY is not set +# CONFIG_LIBC_ARCH_MEMCMP is not set +# CONFIG_LIBC_ARCH_MEMMOVE is not set +# CONFIG_LIBC_ARCH_MEMSET is not set +# CONFIG_LIBC_ARCH_STRCHR is not set +# CONFIG_LIBC_ARCH_STRCMP is not set +# CONFIG_LIBC_ARCH_STRCPY is not set +# CONFIG_LIBC_ARCH_STRNCPY is not set +# CONFIG_LIBC_ARCH_STRLEN is not set +# CONFIG_LIBC_ARCH_STRNLEN is not set +# CONFIG_LIBC_ARCH_ELF is not set +# CONFIG_ARMV7M_MEMCPY is not set + +# +# stdlib Options +# +CONFIG_LIB_RAND_ORDER=1 +CONFIG_LIB_HOMEDIR="/" +CONFIG_LIBC_TMPDIR="/tmp" +CONFIG_LIBC_MAX_TMPFILE=32 + +# +# Program Execution Options +# +# CONFIG_LIBC_EXECFUNCS is not set +CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024 +CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=2048 + +# +# errno Decode Support +# +# CONFIG_LIBC_STRERROR is not set +# CONFIG_LIBC_PERROR_STDOUT is not set + +# +# memcpy/memset Options +# +# CONFIG_MEMSET_OPTSPEED is not set +# CONFIG_LIBC_DLLFCN is not set +# CONFIG_LIBC_MODLIB is not set +# CONFIG_LIBC_WCHAR is not set +# CONFIG_LIBC_LOCALE is not set + +# +# Time/Time Zone Support +# +# CONFIG_LIBC_LOCALTIME is not set +# CONFIG_TIME_EXTENDED is not set +CONFIG_ARCH_HAVE_TLS=y + +# +# Thread Local Storage (TLS) +# +# CONFIG_TLS is not set + +# +# Network-Related Options +# +# CONFIG_LIBC_IPv4_ADDRCONV is not set +# CONFIG_LIBC_IPv6_ADDRCONV is not set +# CONFIG_LIBC_NETDB is not set + +# +# NETDB Support +# +# CONFIG_NETDB_HOSTFILE is not set +# CONFIG_LIBC_IOCTL_VARIADIC is not set +CONFIG_LIB_SENDFILE_BUFSIZE=512 + +# +# Non-standard Library Support +# +# CONFIG_LIB_CRC64_FAST is not set +# CONFIG_LIB_KBDCODEC is not set +# CONFIG_LIB_SLCDCODEC is not set +# CONFIG_LIB_HEX2BIN is not set + +# +# Basic CXX Support +# +# CONFIG_C99_BOOL8 is not set +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +# CONFIG_CXX_NEWLONG is not set + +# +# LLVM C++ Library (libcxx) +# +# CONFIG_LIBCXX is not set + +# +# uClibc++ Standard C++ Library +# +# CONFIG_UCLIBCXX is not set + +# +# Application Configuration +# + +# +# Built-In Applications +# +CONFIG_BUILTIN_PROXY_STACKSIZE=1024 + +# +# CAN Utilities +# + +# +# Examples +# +# CONFIG_EXAMPLES_BUTTONS is not set +# CONFIG_EXAMPLES_CCTYPE is not set +# CONFIG_EXAMPLES_CHAT is not set +# CONFIG_EXAMPLES_CONFIGDATA is not set +# CONFIG_EXAMPLES_CXXTEST is not set +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FSTEST is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HELLOXX is not set +# CONFIG_EXAMPLES_HIDKBD is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_JSON is not set +# CONFIG_EXAMPLES_KEYPADTEST is not set +# CONFIG_EXAMPLES_MEDIA is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MODBUS is not set +# CONFIG_EXAMPLES_MOUNT is not set +CONFIG_EXAMPLES_NSH=y +CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NXLINES is not set +# CONFIG_EXAMPLES_NXTERM is not set +# CONFIG_EXAMPLES_NXTEXT is not set +# CONFIG_EXAMPLES_OSTEST is not set +# CONFIG_EXAMPLES_PCA9635 is not set +# CONFIG_EXAMPLES_POSIXSPAWN is not set +# CONFIG_EXAMPLES_PPPD is not set +# CONFIG_EXAMPLES_RFID_READUID is not set +# CONFIG_EXAMPLES_RGBLED is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERIALBLASTER is not set +# CONFIG_EXAMPLES_SERIALRX is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_SLCD is not set +# CONFIG_EXAMPLES_SMART is not set +# CONFIG_EXAMPLES_SMART_TEST is not set +# CONFIG_EXAMPLES_SMP is not set +# CONFIG_EXAMPLES_STAT is not set +# CONFIG_EXAMPLES_TCPECHO is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_USBSERIAL is not set +# CONFIG_EXAMPLES_WATCHDOG is not set +# CONFIG_EXAMPLES_WEBSERVER is not set + +# +# File System Utilities +# +# CONFIG_FSUTILS_INIFILE is not set +# CONFIG_FSUTILS_PASSWD is not set + +# +# GPS Utilities +# +# CONFIG_GPSUTILS_MINMEA_LIB is not set + +# +# Graphics Support +# +# CONFIG_TIFF is not set +# CONFIG_GRAPHICS_TRAVELER is not set + +# +# Interpreters +# +# CONFIG_INTERPRETERS_BAS is not set +# CONFIG_INTERPRETERS_FICL is not set +# CONFIG_INTERPRETERS_MICROPYTHON is not set +# CONFIG_INTERPRETERS_MINIBASIC is not set +# CONFIG_INTERPRETERS_PCODE is not set + +# +# FreeModBus +# +# CONFIG_MODBUS is not set + +# +# Network Utilities +# +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_ESP8266 is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_JSON is not set +# CONFIG_NETUTILS_SMTP is not set + +# +# NSH Library +# +CONFIG_NSH_LIBRARY=y +# CONFIG_NSH_MOTD is not set + +# +# Command Line Configuration +# +CONFIG_NSH_READLINE=y +# CONFIG_NSH_CLE is not set +CONFIG_NSH_LINELEN=64 +# CONFIG_NSH_DISABLE_SEMICOLON is not set +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_MAXARGUMENTS=6 +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_NESTDEPTH=3 +# CONFIG_NSH_DISABLEBG is not set +CONFIG_NSH_BUILTIN_APPS=y + +# +# Disable Individual commands +# +# CONFIG_NSH_DISABLE_ADDROUTE is not set +# CONFIG_NSH_DISABLE_BASENAME is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_CMP is not set +CONFIG_NSH_DISABLE_DATE=y +# CONFIG_NSH_DISABLE_DD is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_DELROUTE is not set +# CONFIG_NSH_DISABLE_DIRNAME is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_FREE is not set +CONFIG_NSH_DISABLE_GET=y +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_HEXDUMP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +CONFIG_NSH_DISABLE_IFUPDOWN=y +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOSETUP is not set +CONFIG_NSH_DISABLE_LOSMART=y +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MB is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MKRD is not set +# CONFIG_NSH_DISABLE_MH is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_MW is not set +CONFIG_NSH_DISABLE_PRINTF=y +# CONFIG_NSH_DISABLE_PS is not set +CONFIG_NSH_DISABLE_PUT=y +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SH is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNAME is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_NSH_DISABLE_WGET=y +# CONFIG_NSH_DISABLE_XD is not set +CONFIG_NSH_MMCSDMINOR=0 + +# +# Configure Command Options +# +# CONFIG_NSH_CMDOPT_DF_H is not set +# CONFIG_NSH_CMDOPT_DD_STATS is not set +CONFIG_NSH_CODECS_BUFSIZE=128 +CONFIG_NSH_CMDOPT_HEXDUMP=y +CONFIG_NSH_PROC_MOUNTPOINT="/proc" +CONFIG_NSH_FILEIOSIZE=512 + +# +# Scripting Support +# +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_LOOPS is not set + +# +# Console Configuration +# +CONFIG_NSH_CONSOLE=y +# CONFIG_NSH_ALTCONDEV is not set +# CONFIG_NSH_ARCHINIT is not set +# CONFIG_NSH_LOGIN is not set +# CONFIG_NSH_CONSOLE_LOGIN is not set + +# +# NxWidgets/NxWM +# + +# +# Platform-specific Support +# +# CONFIG_PLATFORM_CONFIGDATA is not set + +# +# System Libraries and NSH Add-Ons +# +# CONFIG_SYSTEM_CLE is not set +# CONFIG_SYSTEM_CUTERM is not set +# CONFIG_SYSTEM_FREE is not set +# CONFIG_SYSTEM_HEX2BIN is not set +# CONFIG_SYSTEM_HEXED is not set +# CONFIG_SYSTEM_INSTALL is not set +# CONFIG_SYSTEM_RAMTEST is not set +CONFIG_READLINE_HAVE_EXTMATCH=y +CONFIG_SYSTEM_READLINE=y +CONFIG_READLINE_ECHO=y +# CONFIG_READLINE_TABCOMPLETION is not set +# CONFIG_READLINE_CMD_HISTORY is not set +# CONFIG_SYSTEM_SUDOKU is not set +# CONFIG_SYSTEM_SYSTEM is not set +# CONFIG_SYSTEM_TEE is not set +# CONFIG_SYSTEM_UBLOXMODEM is not set +# CONFIG_SYSTEM_VI is not set +# CONFIG_SYSTEM_ZMODEM is not set diff --git a/configs/clicker2-stm32/nsh/setenv.sh b/configs/clicker2-stm32/nsh/setenv.sh new file mode 100644 index 0000000000..66b14fc7cf --- /dev/null +++ b/configs/clicker2-stm32/nsh/setenv.sh @@ -0,0 +1,80 @@ +#!/bin/bash +# configs/clicker2-stm32/nsh/setenv.sh +# +# 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. +# + +if [ "$_" = "$0" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +fi + +WD=`pwd` +if [ ! -x "setenv.sh" ]; then + echo "This script must be executed from the top-level NuttX build directory" + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then + export PATH_ORIG="${PATH}" +fi + +# This is the Cygwin path to the location where I installed the CodeSourcery +# toolchain under windows. You will also have to edit this if you install +# the CodeSourcery toolchain in any other location +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin" +# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin" + +# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors" +# You can this free toolchain here https://launchpad.net/gcc-arm-embedded +export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin" + +# This is the path to the location where I installed the devkitARM toolchain +# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/ +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin" + +# These are the Cygwin paths to the locations where I installed the Atollic +# toolchain under windows. You will also have to edit this if you install +# the Atollic toolchain in any other location. /usr/bin is added before +# the Atollic bin path because there is are binaries named gcc.exe and g++.exe +# at those locations as well. +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" + +# This is the Cygwin path to the location where I build the buildroot +# toolchain. +# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" + +# Add the path to the toolchain to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" + +echo "PATH : ${PATH}" -- GitLab From 1f13b21f87cd05945c19c733e1dd36b1fc66d8ea Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 22 Mar 2017 10:02:26 -0600 Subject: [PATCH 149/990] Clicker2-STM32: Fixes for a clean build --- configs/clicker2-stm32/include/board.h | 12 ++++++++++++ configs/clicker2-stm32/src/stm32_autoleds.c | 9 +++------ configs/clicker2-stm32/src/stm32_buttons.c | 10 ++++++---- 3 files changed, 21 insertions(+), 10 deletions(-) diff --git a/configs/clicker2-stm32/include/board.h b/configs/clicker2-stm32/include/board.h index 967f601fa9..bb03e08699 100644 --- a/configs/clicker2-stm32/include/board.h +++ b/configs/clicker2-stm32/include/board.h @@ -393,6 +393,18 @@ extern "C" * Public Function Prototypes ************************************************************************************/ +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the intitialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +void stm32_boardinitialize(void); + #undef EXTERN #if defined(__cplusplus) } diff --git a/configs/clicker2-stm32/src/stm32_autoleds.c b/configs/clicker2-stm32/src/stm32_autoleds.c index e559c60efc..9b55bb4c2e 100644 --- a/configs/clicker2-stm32/src/stm32_autoleds.c +++ b/configs/clicker2-stm32/src/stm32_autoleds.c @@ -80,8 +80,7 @@ * Private Functions ****************************************************************************/ -static -static static void board_led1_on(int led) +static void board_led1_on(int led) { bool ledon = false; @@ -104,7 +103,7 @@ static static void board_led1_on(int led) stm32_gpiowrite(GPIO_LED1, ledon); } -static static void board_led2_on(int led) +static void board_led2_on(int led) { bool ledon = false; @@ -173,12 +172,10 @@ static void board_led2_off(int led) void board_autoled_initialize(void) { - /* Configure LED1-4 GPIOs for output */ + /* Configure LED1-2 GPIOs for output */ stm32_configgpio(GPIO_LED1); stm32_configgpio(GPIO_LED2); - stm32_configgpio(GPIO_LED3); - stm32_configgpio(GPIO_LED4); } /**************************************************************************** diff --git a/configs/clicker2-stm32/src/stm32_buttons.c b/configs/clicker2-stm32/src/stm32_buttons.c index 6ef612ce6d..14da26b964 100644 --- a/configs/clicker2-stm32/src/stm32_buttons.c +++ b/configs/clicker2-stm32/src/stm32_buttons.c @@ -83,14 +83,16 @@ uint8_t board_buttons(void) { uint8_t ret = 0; - /* Check that state of each key */ + /* Check that state of each key. A low value will be sensed when the + * button is pressed. + */ - if (!stm32_gpioread(g_buttons[GPIO_BTN_T2])) + if (!stm32_gpioread(GPIO_BTN_T2)) { ret |= BUTTON_T2_BIT; } - if (stm32_gpioread(g_buttons[GPIO_BTN_T2])) + if (!stm32_gpioread(GPIO_BTN_T3)) { ret |= BUTTON_T3_BIT; } @@ -126,7 +128,7 @@ int board_button_irq(int id, xcpt_t irqhandler, FAR void *arg) uint32_t btncfg; btncfg = (id == BUTTON_T2) ? GPIO_BTN_T2 : GPIO_BTN_T3; - return stm32_gpiosetevent(g_buttons[id], true, true, true, irqhandler, arg); + return stm32_gpiosetevent(btncfg, true, true, true, irqhandler, arg); } #endif #endif /* CONFIG_ARCH_BUTTONS */ -- GitLab From c4579e775a069aa7acee11f5449e5ac5f8552ab6 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 22 Mar 2017 11:04:44 -0600 Subject: [PATCH 150/990] Fix some typos; Make sure some private functions have static storage class --- configs/olimex-stm32-p407/include/board.h | 1 + configs/olimex-stm32-p407/src/olimex-stm32-p407.h | 2 +- configs/xmc4500-relax/src/xmc4_autoleds.c | 4 ++-- 3 files changed, 4 insertions(+), 3 deletions(-) diff --git a/configs/olimex-stm32-p407/include/board.h b/configs/olimex-stm32-p407/include/board.h index 888ddad873..4b7429b3c6 100644 --- a/configs/olimex-stm32-p407/include/board.h +++ b/configs/olimex-stm32-p407/include/board.h @@ -334,6 +334,7 @@ extern "C" /************************************************************************************ * Public Function Prototypes ************************************************************************************/ + /************************************************************************************ * Name: stm32_boardinitialize * diff --git a/configs/olimex-stm32-p407/src/olimex-stm32-p407.h b/configs/olimex-stm32-p407/src/olimex-stm32-p407.h index 785fed0002..1c6d4b93e6 100644 --- a/configs/olimex-stm32-p407/src/olimex-stm32-p407.h +++ b/configs/olimex-stm32-p407/src/olimex-stm32-p407.h @@ -1,5 +1,5 @@ /**************************************************************************** - * configs/olimex-stm32-p107/src/olimex-stm32-p407.h + * configs/olimex-stm32-p407/src/olimex-stm32-p407.h * * Copyright (C) 2016-2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt diff --git a/configs/xmc4500-relax/src/xmc4_autoleds.c b/configs/xmc4500-relax/src/xmc4_autoleds.c index 69eda6dee9..8f584d66c9 100644 --- a/configs/xmc4500-relax/src/xmc4_autoleds.c +++ b/configs/xmc4500-relax/src/xmc4_autoleds.c @@ -119,7 +119,7 @@ static void board_led2_on(int led) xmc4_gpio_write(GPIO_LED2, ledon); } -void board_led1_off(int led) +static void board_led1_off(int led) { switch (led) { @@ -136,7 +136,7 @@ void board_led1_off(int led) xmc4_gpio_write(GPIO_LED1, false); } -void board_led2_off(int led) +static void board_led2_off(int led) { switch (led) { -- GitLab From 6168d43c2cd4cc7b8ab057f68c2b737e05ae2a8c Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 22 Mar 2017 11:58:19 -0600 Subject: [PATCH 151/990] Clicker2 STM32: Add SPI support --- configs/clicker2-stm32/Kconfig | 20 ++ configs/clicker2-stm32/include/board.h | 109 ++--------- configs/clicker2-stm32/src/Makefile | 2 +- configs/clicker2-stm32/src/clicker2-stm32.h | 10 + configs/clicker2-stm32/src/stm32_spi.c | 197 ++++++++++++++++++++ 5 files changed, 241 insertions(+), 97 deletions(-) create mode 100644 configs/clicker2-stm32/src/stm32_spi.c diff --git a/configs/clicker2-stm32/Kconfig b/configs/clicker2-stm32/Kconfig index f72f3c094c..b2e5965456 100644 --- a/configs/clicker2-stm32/Kconfig +++ b/configs/clicker2-stm32/Kconfig @@ -2,3 +2,23 @@ # For a description of the syntax of this configuration file, # see the file kconfig-language.txt in the NuttX tools repository. # + +if ARCH_BOARD_CLICKER2_STM32 + +config CLICKER2_STM32_MB1_SPI + bool "mikroBUS1 SPI" + default n if !STM32_SPI3 + default y if STM32_SPI3 + select STM32_SPI3 + ---help--- + Enable SPI support on mikroBUS1 (STM32 SPI3) + +config CLICKER2_STM32_MB2_SPI + bool "mikroBUS2 SPI" + default n if !STM32_SPI2 + default y if STM32_SPI2 + select STM32_SPI2 + ---help--- + Enable SPI support on mikroBUS1 (STM32 SPI2) + +endif # ARCH_BOARD_CLICKER2_STM32 diff --git a/configs/clicker2-stm32/include/board.h b/configs/clicker2-stm32/include/board.h index bb03e08699..7059e703ef 100644 --- a/configs/clicker2-stm32/include/board.h +++ b/configs/clicker2-stm32/include/board.h @@ -261,107 +261,24 @@ #define BUTTON_T3_BIT (1 << BUTTON_T3) /* Alternate function pin selections ************************************************/ -/* CAN */ +/* UART3: Assuming RS-232 connverted connected on mikroMB2 */ -#ifndef CONFIG_STM32_FSMC -# define GPIO_CAN1_RX GPIO_CAN1_RX_3 -# define GPIO_CAN1_TX GPIO_CAN1_TX_3 -#endif - -#ifndef CONFIG_STM32_ETHMAC -# define GPIO_CAN2_RX GPIO_CAN2_RX_1 -# define GPIO_CAN2_TX GPIO_CAN2_TX_1 -#endif - -/* UART2: - * - * The board breaks out pins PD5 and PD6 for UART2 on Click board slot 1. - */ - -#ifndef CONFIG_STM32F4DISBB -# define GPIO_USART2_RX GPIO_USART2_RX_2 -# define GPIO_USART2_TX GPIO_USART2_TX_2 -#endif - -/* UART3: (Used in pseudoterm configuration) */ - -#define GPIO_USART3_TX GPIO_USART3_TX_1 -#define GPIO_USART3_RX GPIO_USART3_RX_1 - -/* UART6: - * - * The STM32F4DIS-BB base board provides RS-232 drivers and a DB9 connector - * for USART6. This is the preferred serial console for use with the STM32F4DIS-BB. - */ - -#define GPIO_USART6_RX GPIO_USART6_RX_1 -#define GPIO_USART6_TX GPIO_USART6_TX_1 - -/* PWM - * - * The STM32F4 Discovery has no real on-board PWM devices, but the board can be - * configured to output a pulse train using TIM4 CH2 on PD13. - */ - -#define GPIO_TIM4_CH2OUT GPIO_TIM4_CH2OUT_2 +#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */ +#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 / -/* RGB LED +/* SPI * - * R = TIM1 CH1 on PE9 | G = TIM2 CH2 on PA1 | B = TIM3 CH3 on PB0 + * SPI2 - mikroBUS2 + * SPI3 - mikroBUS1 */ -#define GPIO_TIM1_CH1OUT GPIO_TIM1_CH1OUT_2 -#define GPIO_TIM2_CH2OUT GPIO_TIM2_CH2OUT_1 -#define GPIO_TIM3_CH3OUT GPIO_TIM3_CH3OUT_1 +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 /* PC12 */ +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1 /* PC11 */ +#define GPIO_SPI2_SCK GPIO_SPI2_SCK_2 /* PC10 */ -/* SPI - There is a MEMS device on SPI1 using these pins: */ - -#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 -#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 -#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1 - -/* SPI2 - Test MAX31855 on SPI2 PB10 = SCK, PB14 = MISO */ - -#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 -#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1 -#define GPIO_SPI2_SCK GPIO_SPI2_SCK_1 - -/* I2C config to use with Nunchuk PB7 (SDA) and PB8 (SCL) */ - -#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 -#define GPIO_I2C1_SDA GPIO_I2C1_SDA_1 - -/* Timer Inputs/Outputs (see the README.txt file for options) */ - -#define GPIO_TIM2_CH1IN GPIO_TIM2_CH1IN_2 -#define GPIO_TIM2_CH2IN GPIO_TIM2_CH2IN_1 - -#define GPIO_TIM8_CH1IN GPIO_TIM8_CH1IN_1 -#define GPIO_TIM8_CH2IN GPIO_TIM8_CH2IN_1 - -/* Ethernet *************************************************************************/ - -#if defined(CONFIG_STM32F4DISBB) && defined(CONFIG_STM32_ETHMAC) - /* RMII interface to the LAN8720 PHY */ - -# ifndef CONFIG_STM32_RMII -# error CONFIG_STM32_RMII must be defined -# endif - - /* Clocking is provided by an external 25Mhz XTAL */ - -# ifndef CONFIG_STM32_RMII_EXTCLK -# error CONFIG_STM32_RMII_EXTCLK must be defined -# endif - - /* Pin disambiguation */ - -# define GPIO_ETH_RMII_TX_EN GPIO_ETH_RMII_TX_EN_1 -# define GPIO_ETH_RMII_TXD0 GPIO_ETH_RMII_TXD0_1 -# define GPIO_ETH_RMII_TXD1 GPIO_ETH_RMII_TXD1_1 -# define GPIO_ETH_PPS_OUT GPIO_ETH_PPS_OUT_1 - -#endif +#define GPIO_SPI3_MISO GPIO_SPI3_MISO_2 /* PB15 */ +#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_2 /* PB14 */ +#define GPIO_SPI3_SCK GPIO_SPI3_SCK_2 /* PB13 */ /* DMA Channl/Stream Selections *****************************************************/ /* Stream selections are arbitrary for now but might become important in the future @@ -372,7 +289,7 @@ * DMAMAP_SDIO_2 = Channel 4, Stream 6 */ -#define DMAMAP_SDIO DMAMAP_SDIO_1 +#define DMAMAP_SDIO DMAMAP_SDIO_1 /************************************************************************************ * Public Data diff --git a/configs/clicker2-stm32/src/Makefile b/configs/clicker2-stm32/src/Makefile index 80f87f8af0..bafc45bff1 100644 --- a/configs/clicker2-stm32/src/Makefile +++ b/configs/clicker2-stm32/src/Makefile @@ -36,7 +36,7 @@ -include $(TOPDIR)/Make.defs ASRCS = -CSRCS = stm32_boot.c stm32_bringup.c +CSRCS = stm32_boot.c stm32_bringup.c stm32_spi.c ifeq ($(CONFIG_ARCH_LEDS),y) CSRCS += stm32_autoleds.c diff --git a/configs/clicker2-stm32/src/clicker2-stm32.h b/configs/clicker2-stm32/src/clicker2-stm32.h index a7be1085e9..ecf53fcd77 100644 --- a/configs/clicker2-stm32/src/clicker2-stm32.h +++ b/configs/clicker2-stm32/src/clicker2-stm32.h @@ -165,6 +165,16 @@ #define GPIO_PWR_FAULT (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN6) #define GPIO_PWR_BATSTAT (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN4) +/* SPI Chip Selects + * + * mikroBUS1 Chipselect: SPI3 PE8 + * mikroBUS2 Chipselect: SPI2 PE11 + */ + +#define GPIO_MB1_CS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN8) +#define GPIO_MB2_CS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN11) #ifndef __ASSEMBLY__ /************************************************************************************ diff --git a/configs/clicker2-stm32/src/stm32_spi.c b/configs/clicker2-stm32/src/stm32_spi.c new file mode 100644 index 0000000000..7e231d108b --- /dev/null +++ b/configs/clicker2-stm32/src/stm32_spi.c @@ -0,0 +1,197 @@ +/************************************************************************************ + * configs/clicker2-stm32/src/stm32_spi.c + * + * 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. + * + ************************************************************************************/ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include + +#include "up_arch.h" +#include "chip.h" +#include "stm32.h" + +#include "clicker2-stm32.h" + +#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || defined(CONFIG_STM32_SPI3) + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_spidev_initialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the stm32f4discovery board. + * + ************************************************************************************/ + +void weak_function stm32_spidev_initialize(void) +{ +#if defined(CONFIG_STM32_SPI3) && defined(CONFIG_CLICKER2_STM32_MB1_SPI) + /* Enable chip select for mikroBUS1 */ + + (void)stm32_configgpio(GPIO_MB1_CS); +#endif +#if defined(CONFIG_STM32_SPI2) && defined(CONFIG_CLICKER2_STM32_MB2_SPI) + /* Enable chip select for mikroBUS2 */ + + (void)stm32_configgpio(GPIO_MB2_CS); +#endif +} + +/**************************************************************************** + * Name: stm32_spi1/2/3select and stm32_spi1/2/3status + * + * Description: + * The external functions, stm32_spi1/2/3select and stm32_spi1/2/3status must be + * provided by board-specific logic. They are implementations of the select + * and status methods of the SPI interface defined by struct spi_ops_s (see + * include/nuttx/spi/spi.h). All other methods (including stm32_spibus_initialize()) + * are provided by common STM32 logic. To use this common SPI logic on your + * board: + * + * 1. Provide logic in stm32_boardinitialize() to configure SPI chip select + * pins. + * 2. Provide stm32_spi1/2/3select() and stm32_spi1/2/3status() functions in your + * board-specific logic. These functions will perform chip selection and + * status operations using GPIOs in the way your board is configured. + * 3. Add a calls to stm32_spibus_initialize() in your low level application + * initialization logic + * 4. The handle returned by stm32_spibus_initialize() may then be used to bind the + * SPI driver to higher level logic (e.g., calling + * mmcsd_spislotinitialize(), for example, will bind the SPI driver to + * the SPI MMC/SD driver). + * + ****************************************************************************/ + +#ifdef CONFIG_STM32_SPI1 +void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +{ + spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); +} + +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +{ + return 0; +} +#endif + +#ifdef CONFIG_STM32_SPI2 +void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +{ + spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); + /* To be provided */ +} + +uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +{ + return 0; +} +#endif + +#ifdef CONFIG_STM32_SPI3 +void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +{ + spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); + /* To be provided */ +} + +uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +{ + return 0; +} +#endif + +/**************************************************************************** + * Name: stm32_spi1cmddata + * + * Description: + * Set or clear the SH1101A A0 or SD1306 D/C n bit to select data (true) + * or command (false). This function must be provided by platform-specific + * logic. This is an implementation of the cmddata method of the SPI + * interface defined by struct spi_ops_s (see include/nuttx/spi/spi.h). + * + * Input Parameters: + * + * spi - SPI device that controls the bus the device that requires the CMD/ + * DATA selection. + * devid - If there are multiple devices on the bus, this selects which one + * to select cmd or data. NOTE: This design restricts, for example, + * one one SPI display per SPI bus. + * cmd - true: select command; false: select data + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_SPI_CMDDATA +#ifdef CONFIG_STM32_SPI1 +int stm32_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +{ + return -ENODEV; +} +#endif + +#ifdef CONFIG_STM32_SPI2 +int stm32_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +{ + /* To be provided */ + + return -ENODEV; +} +#endif + +#ifdef CONFIG_STM32_SPI3 +int stm32_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +{ + /* To be provided */ + + return -ENODEV; +} +#endif +#endif /* CONFIG_SPI_CMDDATA */ + +#endif /* CONFIG_STM32_SPI1 || CONFIG_STM32_SPI2 */ -- GitLab From 7f2c4c4274bdc54ae81af65b048388d6e1f2d0c7 Mon Sep 17 00:00:00 2001 From: "David S. Alessio" Date: Wed, 22 Mar 2017 12:04:32 -0600 Subject: [PATCH 152/990] XMC4xxx: Add FPU support --- arch/arm/include/xmc4/chip.h | 2 +- arch/arm/src/xmc4/Kconfig | 5 ++++- configs/xmc4500-relax/nsh/defconfig | 2 +- 3 files changed, 6 insertions(+), 3 deletions(-) diff --git a/arch/arm/include/xmc4/chip.h b/arch/arm/include/xmc4/chip.h index 6507917fe6..8ee065ffc3 100644 --- a/arch/arm/include/xmc4/chip.h +++ b/arch/arm/include/xmc4/chip.h @@ -56,7 +56,7 @@ # define XMC4_NUSIC 3 /* Three USIC modules: USCI0-2 */ # define XMC4_SCU_GATING 1 /* Has clock gating registers */ # define XMC4_NECAT 0 /* No EtherCAT support */ -#elif defined(CONFIG_ARCH_CHIP_XMC4700) +#elif defined(CONFIG_ARCH_CHIP_XMC4800) # define XMC4_NUSIC 3 /* Three USIC modules: USCI0-2 */ # define XMC4_SCU_GATING 1 /* Has clock gating registers */ # define XMC4_NECAT 1 /* One EtherCAT module */ diff --git a/arch/arm/src/xmc4/Kconfig b/arch/arm/src/xmc4/Kconfig index f50652cd96..5a83e363b9 100644 --- a/arch/arm/src/xmc4/Kconfig +++ b/arch/arm/src/xmc4/Kconfig @@ -12,12 +12,15 @@ choice config ARCH_CHIP_XMC4500 bool "XMC4500" + select ARCH_HAVE_FPU config ARCH_CHIP_XMC4700 bool "XMC4700" + select ARCH_HAVE_FPU config ARCH_CHIP_XMC4800 - bool "XMC4700" + bool "XMC4800" + select ARCH_HAVE_FPU endchoice diff --git a/configs/xmc4500-relax/nsh/defconfig b/configs/xmc4500-relax/nsh/defconfig index d554365209..14643afe8f 100644 --- a/configs/xmc4500-relax/nsh/defconfig +++ b/configs/xmc4500-relax/nsh/defconfig @@ -134,7 +134,7 @@ CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y CONFIG_ARMV7M_LAZYFPU=y -# CONFIG_ARCH_HAVE_FPU is not set +CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set CONFIG_ARM_HAVE_MPU_UNIFIED=y -- GitLab From 4c6646ad5db0ff05607cb4003ae70f92d18b7a3b Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 22 Mar 2017 13:28:16 -0600 Subject: [PATCH 153/990] Clicker2-STM32: Add definitions for remaining mikroBUS pins. --- configs/clicker2-stm32/include/board.h | 38 ++++++++++++- configs/clicker2-stm32/src/clicker2-stm32.h | 60 +++++++++++++++++++-- 2 files changed, 93 insertions(+), 5 deletions(-) diff --git a/configs/clicker2-stm32/include/board.h b/configs/clicker2-stm32/include/board.h index 7059e703ef..fa271666cb 100644 --- a/configs/clicker2-stm32/include/board.h +++ b/configs/clicker2-stm32/include/board.h @@ -261,7 +261,16 @@ #define BUTTON_T3_BIT (1 << BUTTON_T3) /* Alternate function pin selections ************************************************/ -/* UART3: Assuming RS-232 connverted connected on mikroMB2 */ +/* U[S]ARTs + * + * USART2 - mikroBUS1 + * USART3 - mikroBUS2 + * + * Assuming RS-232 connverted connected on mikroMB1/12 + */ + +#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */ +#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */ #define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */ #define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 / @@ -280,6 +289,33 @@ #define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_2 /* PB14 */ #define GPIO_SPI3_SCK GPIO_SPI3_SCK_2 /* PB13 */ +/* I2C + * + * I2C2 - mikroBUS2 + * I2C3 - mikroBUS1 + */ + +#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1 /* PB10 */ +#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1 /* PB11 */ + +#define GPIO_I2C3_SCL GPIO_I2C3_SCL_1 /* PA8 */ +#define GPIO_I2C3_SDA GPIO_I2C3_SDA_1 /* PC9 */ + +/* Analog + * + * mikroBUS1 ADC: PA2-MB1_AN + * mikroBUS1 ADC: PA3-MB2_AN + */ + +/* PWM + * + * mikroBUS1 ADC: PE9-MB1-PWM (TIM1, channel 1) + * mikroBUS1 ADC: PD12-MB2-PWM (TIM4, channel 1) + */ + +#define GPIO_TIM1_CH1OUT GPIO_TIM1_CH1OUT_2 /* PE9 */ +#define GPIO_TIM4_CH1OUT GPIO_TIM4_CH1OUT_2 /* PD12 */ + /* DMA Channl/Stream Selections *****************************************************/ /* Stream selections are arbitrary for now but might become important in the future * if we set aside more DMA channels/streams. diff --git a/configs/clicker2-stm32/src/clicker2-stm32.h b/configs/clicker2-stm32/src/clicker2-stm32.h index ecf53fcd77..544366c8dd 100644 --- a/configs/clicker2-stm32/src/clicker2-stm32.h +++ b/configs/clicker2-stm32/src/clicker2-stm32.h @@ -132,8 +132,8 @@ * * T2 - PE0, Low sensed when pressed * T3 - PA10, Low sensed when pressed - * - * NOTE that all have EXTI interrupts configured + * + * NOTE that all have EXTI interrupts configured */ #define GPIO_BTN_T2 (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTE|GPIO_PIN0) @@ -165,16 +165,68 @@ #define GPIO_PWR_FAULT (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN6) #define GPIO_PWR_BATSTAT (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN4) +/* mikroBUS *************************************************************************/ +/* U[S]ARTs + * + * USART2 - mikroBUS1 + * USART3 - mikroBUS2 + */ + /* SPI Chip Selects * - * mikroBUS1 Chipselect: SPI3 PE8 - * mikroBUS2 Chipselect: SPI2 PE11 + * mikroBUS1 Chipselect: PE8-MB1_CS (SPI3) + * mikroBUS2 Chipselect: PE11-MB2_CS (SPI2) */ #define GPIO_MB1_CS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN8) #define GPIO_MB2_CS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN11) + +/* I2C + * + * mikroBUS1 I2C: PA8-I2C3_SCL, PC9-I2C3_SDA (I2C3) + * mikroBUS2 I2C: PB10-I2C2_SCL, PB11-I2C2_SDA () + */ + +/* Analog + * + * mikroBUS1 ADC: PA2-MB1_AN + * mikroBUS1 ADC: PA3-MB2_AN + */ + +/* PWM + * + * mikroBUS1 ADC: PE9-MB1-PWM (TIM1, channel 1) + * mikroBUS1 ADC: PD12-MB2-PWM (TIM4, channel 1) + */ + +/* Reset + * + * mikroBUS1 Interrupt: PE7-MB1_RST + * mikroBUS2 Interrupt: PE13-MB2_RST + * + * I assume that the interrupt lines are active low. The initial state holds the + * device in reset. + */ + +#define GPIO_MB1_RST (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN7) +#define GPIO_MB1_RST (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ + GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN13) + +/* Interrupts + * + * mikroBUS1 Interrupt: PE10-MB1_INT + * mikroBUS2 Interrupt: PE14-MB2_INT + * + * I assume that the interrupt lines are active low. No pull-ups are provided on + * board so pull-ups ar provided in the pin configurations. + */ + +#define GPIO_MB1_INT (GPIO_INPUT|GPIO_PULLUP|GPIO_EXTI|GPIO_PORTE|GPIO_PIN10) +#define GPIO_MB2_INT (GPIO_INPUT|GPIO_PULLUP|GPIO_EXTI|GPIO_PORTE|GPIO_PIN14) + #ifndef __ASSEMBLY__ /************************************************************************************ -- GitLab From 80f56e75f95f8ba248b9271f55d9907f1c6771e3 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jos=C3=A9=20Roberto=20de=20Souza?= Date: Wed, 22 Mar 2017 10:33:59 -0700 Subject: [PATCH 154/990] stm32: Fix erase sector number for microcontrolers with more than 11 sectors Erase a sector from the second bank cause the bit 4 of SNB being set but never unsed, so trying to erase a sector from the first bank was acually eraseing a sector from the second bank. --- arch/arm/src/stm32/chip/stm32_flash.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/arch/arm/src/stm32/chip/stm32_flash.h b/arch/arm/src/stm32/chip/stm32_flash.h index 218ba05fcf..32eeaf90dd 100644 --- a/arch/arm/src/stm32/chip/stm32_flash.h +++ b/arch/arm/src/stm32/chip/stm32_flash.h @@ -328,10 +328,11 @@ # define FLASH_CR_SER (1 << 1) /* Bit 1: Sector Erase */ # define FLASH_CR_MER (1 << 2) /* Bit 2: Mass Erase sectors 0..11 */ # define FLASH_CR_SNB_SHIFT (3) /* Bits 3-6: Sector number */ -# define FLASH_CR_SNB_MASK (15 << FLASH_CR_SNB_SHIFT) #if defined(CONFIG_STM32_STM32F427) || defined(CONFIG_STM32_STM32F429) +# define FLASH_CR_SNB_MASK (31 << FLASH_CR_SNB_SHIFT) # define FLASH_CR_SNB(n) (((n % 12) << FLASH_CR_SNB_SHIFT) | ((n / 12) << 7)) /* Sector n, n=0..23 */ #else +# define FLASH_CR_SNB_MASK (15 << FLASH_CR_SNB_SHIFT) # define FLASH_CR_SNB(n) ((n) << FLASH_CR_SNB_SHIFT) /* Sector n, n=0..11 */ #endif # define FLASH_CR_PSIZE_SHIFT (8) /* Bits 8-9: Program size */ -- GitLab From 09f70c462de80ad1492838cc2bc08912a7e118b4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jos=C3=A9=20Roberto=20de=20Souza?= Date: Wed, 22 Mar 2017 10:56:37 -0700 Subject: [PATCH 155/990] stm32: Make up_progmem thread safe Writing to a flash sector while starting the erase of other sector have a undefined behavior so lets add a semaphore and syncronize access to Flash registers. But for the semaphore to work it needs to be initialized so each board needs call stm32_flash_initialize() on initialization, so to avoid runtime problems it is only using semaphore and making it thread safe if initialized, after all boards starts to call stm32_flash_initialize() we can remove the boolean and the check. --- arch/arm/src/stm32/chip/stm32_flash.h | 1 + arch/arm/src/stm32/stm32_flash.c | 70 ++++++++++++++++++++++++--- 2 files changed, 64 insertions(+), 7 deletions(-) diff --git a/arch/arm/src/stm32/chip/stm32_flash.h b/arch/arm/src/stm32/chip/stm32_flash.h index 32eeaf90dd..16c67a933e 100644 --- a/arch/arm/src/stm32/chip/stm32_flash.h +++ b/arch/arm/src/stm32/chip/stm32_flash.h @@ -392,6 +392,7 @@ * Public Functions ************************************************************************************/ +void stm32_flash_initialize(void); void stm32_flash_lock(void); void stm32_flash_unlock(void); diff --git a/arch/arm/src/stm32/stm32_flash.c b/arch/arm/src/stm32/stm32_flash.c index 9ac38a19a1..7f0b53ee60 100644 --- a/arch/arm/src/stm32/stm32_flash.c +++ b/arch/arm/src/stm32/stm32_flash.c @@ -47,7 +47,9 @@ #include #include + #include +#include #include "stm32_flash.h" #include "stm32_rcc.h" @@ -84,10 +86,30 @@ * Private Functions ************************************************************************************/ -/************************************************************************************ - * Public Functions - ************************************************************************************/ -void stm32_flash_unlock(void) +static sem_t g_sem; +/* + * After all SMT32 boards starts calling stm32_flash_initialize() this can + * be removed. + */ +static bool g_initialized = false; + +static void sem_lock(void) +{ + if (g_initialized) + { + sem_wait(&g_sem); + } +} + +static void sem_unlock(void) +{ + if (g_initialized) + { + sem_post(&g_sem); + } +} + +static void flash_unlock(void) { while (getreg32(STM32_FLASH_SR) & FLASH_SR_BSY) { @@ -103,11 +125,36 @@ void stm32_flash_unlock(void) } } -void stm32_flash_lock(void) +static void flash_lock(void) { modifyreg32(STM32_FLASH_CR, 0, FLASH_CR_LOCK); } +/************************************************************************************ + * Public Functions + ************************************************************************************/ +void stm32_flash_initialize(void) +{ + g_initialized = true; + /* + * Initialize the semaphore that manages exclusive access flash registers + */ + sem_init(&g_sem, 0, 1); +} + +void stm32_flash_unlock(void) +{ + sem_lock(); + flash_unlock(); + sem_unlock(); +} + +void stm32_flash_lock(void) +{ + sem_lock(); + flash_lock(); + sem_unlock(); +} #if defined(CONFIG_STM32_STM32F10XX) || defined(CONFIG_STM32_STM32F30XX) @@ -231,6 +278,8 @@ ssize_t up_progmem_erasepage(size_t page) return -EFAULT; } + sem_lock(); + #if !defined(CONFIG_STM32_STM32F40XX) if (!(getreg32(STM32_RCC_CR) & RCC_CR_HSION)) { @@ -240,7 +289,7 @@ ssize_t up_progmem_erasepage(size_t page) /* Get flash ready and begin erasing single page */ - stm32_flash_unlock(); + flash_unlock(); modifyreg32(STM32_FLASH_CR, 0, FLASH_CR_PAGE_ERASE); @@ -259,6 +308,7 @@ ssize_t up_progmem_erasepage(size_t page) while (getreg32(STM32_FLASH_SR) & FLASH_SR_BSY) up_waste(); modifyreg32(STM32_FLASH_CR, FLASH_CR_PAGE_ERASE, 0); + sem_unlock(); /* Verify */ if (up_progmem_ispageerased(page) == 0) @@ -320,16 +370,19 @@ ssize_t up_progmem_write(size_t addr, const void *buf, size_t count) return -EFAULT; } + sem_lock(); + #if !defined(CONFIG_STM32_STM32F40XX) if (!(getreg32(STM32_RCC_CR) & RCC_CR_HSION)) { + sem_unlock(); return -EPERM; } #endif /* Get flash ready and begin flashing */ - stm32_flash_unlock(); + flash_unlock(); modifyreg32(STM32_FLASH_CR, 0, FLASH_CR_PG); @@ -351,17 +404,20 @@ ssize_t up_progmem_write(size_t addr, const void *buf, size_t count) if (getreg32(STM32_FLASH_SR) & FLASH_SR_WRITE_PROTECTION_ERROR) { modifyreg32(STM32_FLASH_CR, FLASH_CR_PG, 0); + sem_unlock(); return -EROFS; } if (getreg16(addr) != *hword) { modifyreg32(STM32_FLASH_CR, FLASH_CR_PG, 0); + sem_unlock(); return -EIO; } } modifyreg32(STM32_FLASH_CR, FLASH_CR_PG, 0); + sem_unlock(); return written; } -- GitLab From b9b4f184a7a014ec324f50fabdc4c6539e676b10 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jos=C3=A9=20Roberto=20de=20Souza?= Date: Wed, 22 Mar 2017 11:12:17 -0700 Subject: [PATCH 156/990] stm32: Add workaround for flash data cache corruption on read-while-write This is a know hardware issue on some STM32 see the errata of your model and if you make use of both memory banks you should enable it. --- arch/arm/src/stm32/Kconfig | 6 ++++++ arch/arm/src/stm32/stm32_flash.c | 23 +++++++++++++++++++++++ 2 files changed, 29 insertions(+) diff --git a/arch/arm/src/stm32/Kconfig b/arch/arm/src/stm32/Kconfig index de2c8fe23b..72f8a17fbb 100644 --- a/arch/arm/src/stm32/Kconfig +++ b/arch/arm/src/stm32/Kconfig @@ -2633,6 +2633,12 @@ config STM32_FLASH_PREFETCH on F1 parts). Some early revisions of F4 parts do not support FLASH pre-fetch properly and enabling this option may interfere with ADC accuracy. +config STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW + bool "Enable the workaround to fix flash data cache corruption when reading from one flash bank while writing on other flash bank" + default n + ---help--- + See your STM32 errata to check if your STM32 is affected by this problem. + choice prompt "JTAG Configuration" default STM32_JTAG_DISABLE diff --git a/arch/arm/src/stm32/stm32_flash.c b/arch/arm/src/stm32/stm32_flash.c index 7f0b53ee60..4907aa9f0a 100644 --- a/arch/arm/src/stm32/stm32_flash.c +++ b/arch/arm/src/stm32/stm32_flash.c @@ -130,6 +130,20 @@ static void flash_lock(void) modifyreg32(STM32_FLASH_CR, 0, FLASH_CR_LOCK); } +static void data_cache_disable(void) +{ + modifyreg32(STM32_FLASH_ACR, FLASH_ACR_DCEN, 0); +} + +static void data_cache_enable(void) +{ + /* reset data cache */ + modifyreg32(STM32_FLASH_ACR, 0, FLASH_ACR_DCRST); + + /* enable data cache */ + modifyreg32(STM32_FLASH_ACR, 0, FLASH_ACR_DCEN); +} + /************************************************************************************ * Public Functions ************************************************************************************/ @@ -384,6 +398,10 @@ ssize_t up_progmem_write(size_t addr, const void *buf, size_t count) flash_unlock(); +#if defined(CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW) + data_cache_disable(); +#endif + modifyreg32(STM32_FLASH_CR, 0, FLASH_CR_PG); #if defined(CONFIG_STM32_STM32F40XX) @@ -417,6 +435,11 @@ ssize_t up_progmem_write(size_t addr, const void *buf, size_t count) } modifyreg32(STM32_FLASH_CR, FLASH_CR_PG, 0); + +#if defined(CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW) + data_cache_enable(); +#endif + sem_unlock(); return written; } -- GitLab From 22651dcae22d0cc3c2dadcb1f38e433839d2cbf9 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 22 Mar 2017 15:20:05 -0600 Subject: [PATCH 157/990] Clicker2-STM32: Add framework for MRF24J40 support. Untested and still some missing logic. --- configs/clicker2-stm32/Kconfig | 16 + configs/clicker2-stm32/src/Makefile | 4 + configs/clicker2-stm32/src/clicker2-stm32.h | 16 + configs/clicker2-stm32/src/stm32_bringup.c | 10 + configs/clicker2-stm32/src/stm32_buttons.c | 1 + configs/clicker2-stm32/src/stm32_mrf24j40.c | 291 +++++++++++++++++++ include/nuttx/wireless/ieee802154/mrf24j40.h | 12 +- 7 files changed, 344 insertions(+), 6 deletions(-) create mode 100644 configs/clicker2-stm32/src/stm32_mrf24j40.c diff --git a/configs/clicker2-stm32/Kconfig b/configs/clicker2-stm32/Kconfig index b2e5965456..a5d3a68cbc 100644 --- a/configs/clicker2-stm32/Kconfig +++ b/configs/clicker2-stm32/Kconfig @@ -21,4 +21,20 @@ config CLICKER2_STM32_MB2_SPI ---help--- Enable SPI support on mikroBUS1 (STM32 SPI2) +config CLICKER2_STM32_MB1_BEE + bool "mikroBUS1 MRF24J40 BEE" + default y + depends on IEEE802154_MRF24J40 + select CLICKER2_STM32_MB1_SPI + ---help--- + Enable support for MRF24J40 BEE on mikroBUS1 + +config CLICKER2_STM32_MB2_BEE + bool "mikroBUS2 MRF24J40 BEE" + default n + depends on IEEE802154_MRF24J40 + select CLICKER2_STM32_MB2_SPI + ---help--- + Enable support for MRF24J40 BEE on mikroBUS2 + endif # ARCH_BOARD_CLICKER2_STM32 diff --git a/configs/clicker2-stm32/src/Makefile b/configs/clicker2-stm32/src/Makefile index bafc45bff1..3980c3ac7d 100644 --- a/configs/clicker2-stm32/src/Makefile +++ b/configs/clicker2-stm32/src/Makefile @@ -56,6 +56,10 @@ ifeq ($(CONFIG_LIB_BOARDCTL),y) CSRCS += stm32_appinit.c endif +ifeq ($(CONFIG_IEEE802154_MRF24J40),y) +CSRCS += stm32_mrf24j40.c +endif + ifeq ($(CONFIG_ADC),y) CSRCS += stm32_adc.c endif diff --git a/configs/clicker2-stm32/src/clicker2-stm32.h b/configs/clicker2-stm32/src/clicker2-stm32.h index 544366c8dd..41081ae794 100644 --- a/configs/clicker2-stm32/src/clicker2-stm32.h +++ b/configs/clicker2-stm32/src/clicker2-stm32.h @@ -286,5 +286,21 @@ int stm32_adc_setup(void); int stm32_can_setup(void); #endif +/**************************************************************************** + * Name: stm32_mrf24j40_initialize + * + * Description: + * Initialize the MRF24J40 device. + * + * Returned Value: + * Zero is returned on success. Otherwise, a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +#if defined(CONFIG_CLICKER2_STM32_MB1_BEE) || defined(CONFIG_CLICKER2_STM32_MB2_BEE) +int stm32_mrf24j40_initialize(void) +#endif + #endif /* __ASSEMBLY__ */ #endif /* __CONFIGS_OLIMEX_STM32_P407_SRC_H */ diff --git a/configs/clicker2-stm32/src/stm32_bringup.c b/configs/clicker2-stm32/src/stm32_bringup.c index 1dcc276812..b7adf9dcc1 100644 --- a/configs/clicker2-stm32/src/stm32_bringup.c +++ b/configs/clicker2-stm32/src/stm32_bringup.c @@ -153,6 +153,16 @@ int stm32_bringup(void) } #endif +#if defined(CONFIG_CLICKER2_STM32_MB1_BEE) || defined(CONFIG_CLICKER2_STM32_MB2_BEE) + /* Configure MRF24J40 wireless */ + + ret = stm32_mrf24j40_initialize(); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: stm32_mrf24j40_initialize() failed: %d\n", ret); + } +#endif + #ifdef CONFIG_BUTTONS /* Register the BUTTON driver */ diff --git a/configs/clicker2-stm32/src/stm32_buttons.c b/configs/clicker2-stm32/src/stm32_buttons.c index 14da26b964..3d8122d2ae 100644 --- a/configs/clicker2-stm32/src/stm32_buttons.c +++ b/configs/clicker2-stm32/src/stm32_buttons.c @@ -47,6 +47,7 @@ #include #include "stm32_gpio.h" +#include "stm32_exti.h" #include "clicker2-stm32.h" diff --git a/configs/clicker2-stm32/src/stm32_mrf24j40.c b/configs/clicker2-stm32/src/stm32_mrf24j40.c new file mode 100644 index 0000000000..ef36bc4b3e --- /dev/null +++ b/configs/clicker2-stm32/src/stm32_mrf24j40.c @@ -0,0 +1,291 @@ +/**************************************************************************** + * configs/freedom-kl25z/src/stm32_mrf24j40.c + * + * Copyright (C) 2017 Gregory Nutt, All rights reserver + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "stm32_gpio.h" +#include "stm32_exti.h" +#include "stm32_spi.h" + +#include "clicker2-stm32.h" + +#ifdef CONFIG_IEEE802154_MRF24J40 + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#ifndef CONFIG_DRIVERS_WIRELESS +# error Wireless support requires CONFIG_DRIVERS_WIRELESS +#endif + +#if !defined(CONFIG_CLICKER2_STM32_MB1_BEE) && !defined(CONFIG_CLICKER2_STM32_MB2_BEE) +# error Only the Mikroe BEE board is supported +#endif + +#ifdef CONFIG_CLICKER2_STM32_MB1_BEE +# ifndef CONFIG_STM32_SPI3 +# error Mikroe BEE on mikroBUS1 requires CONFIG_STM32_SPI3 +# endif +#endif + +#ifdef CONFIG_CLICKER2_STM32_MB2_BEE +# ifndef CONFIG_STM32_SPI2 +# error Mikroe BEE on mikroBUS1 requires CONFIG_STM32_SPI2 +# endif +#endif + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct stm32_priv_s +{ + struct mrf24j40_lower_s dev; + xcpt_t handler; + uint32_t intcfg; + uint8_t spidev; +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* IRQ/GPIO access callbacks. These operations all hidden behind callbacks + * to isolate the MRF24J40 driver from differences in GPIO interrupt handling + * varying boards and MCUs. + * + * irq_attach - Attach the MRF24J40 interrupt handler to the GPIO + interrupt + * irq_enable - Enable or disable the GPIO interrupt + */ + +static int stm32_attach_irq(FAR const struct mrf24j40_lower_s *lower, + xcpt_t handler); +static void stm32_enable_irq(FAR const struct mrf24j40_lower_s *lower, + int state); +static int stm32_mrf24j40_devsetup(FAR struct stm32_priv_s *priv)' + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* A reference to a structure of this type must be passed to the MRF24J40 + * driver. This structure provides information about the configuration + * of the MRF24J40 and provides some board-specific hooks. + * + * Memory for this structure is provided by the caller. It is not copied + * by the driver and is presumed to persist while the driver is active. The + * memory must be writable because, under certain circumstances, the driver + * may modify frequency or X plate resistance values. + */ + +#ifdef CONFIG_CLICKER2_STM32_MB1_BEE +static struct stm32_priv_s g_mrf24j40_mb1_priv = +{ + .dev.attach = stm32_attach_irq, + .dev.enable = stm32_enable_irq, + .handler = NULL, + .intcfg = GPIO_MB1_INT, + .spidev = 3, +}; +#endif + +#ifdef CONFIG_CLICKER2_STM32_MB2_BEE +static struct stm32_priv_s g_mrf24j40_mb2_priv = +{ + .dev.attach = stm32_attach_irq, + .dev.enable = stm32_enable_irq, + .uint32_t = GPIO_MB2_INT, + .spidev = 2, +}; +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/* IRQ/GPIO access callbacks. These operations all hidden behind + * callbacks to isolate the MRF24J40 driver from differences in GPIO + * interrupt handling by varying boards and MCUs. If possible, + * interrupts should be configured on both rising and falling edges + * so that contact and loss-of-contact events can be detected. + * + * irq_attach - Attach the MRF24J40 interrupt handler to the GPIO + * interrupt + * irq_enable - Enable or disable the GPIO interrupt + */ + +static int stm32_attach_irq(FAR struct mrf24j40_lower_s *lower, + xcpt_t handler) +{ + FAR struct stm32_priv_s *priv = (FAR struct mrf24j40_lower_s *)lower; + + DEBUASSERT(priv != NULL); + + /* Just save the handler for use when the interrupt is enabled */ + + priv->handler = handler; + return OK; +} + +static void stm32_enable_irq(FAR struct mrf24j40_lower_s *lower, int state) +{ + FAR struct stm32_priv_s *priv = (FAR struct mrf24j40_lower_s *)lower; + + /* The caller should not attempt to enable interrupts if the handler + * has not yet been 'attached' + */ + + DEBUGASSERT(priv != NULL && (priv->handler != NULL || state == 0)); + + /* Attach and enable, or detach and disable */ + + wlinfo("state:%d\n", state); + if (state != 0) + { + (void)stm32_gpiosetevent(priv->intcfg, true, true, true, + priv->handler, lower); + } + else + { + (void)stm32_gpiosetevent(priv->intcfg, false, false, false, + NULL, NULL); + } +} + +/**************************************************************************** + * Name: stm32_mrf24j40_devsetup + * + * Description: + * Initialize one the MRF24J40 device in one mikroBUS slot + * + * Returned Value: + * Zero is returned on success. Otherwise, a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +static int stm32_mrf24j40_devsetup(FAR struct stm32_priv_s *priv) +{ + FAR struct ieee802154_radio_s *radio; + FAR struct spi_dev_s *spi; + + /* Configure the interrupt pin */ + + stm32_configgpio(priv->intcfg); + + /* Initialize the SPI bus and get an instance of the SPI interface */ + + spi = stm32_spibus_initialize(priv->spidev); + if (spi == NULL) + { + wlerr("ERROR: Failed to initialize SPI bus %d\n", priv->spidev); + return -ENODEV; + } + + /* Initialize and register the SPI MRF24J40 device */ + + radio = mrf24j40_init(spi, &priv->dev); + if (radio == NULL) + { + wlerr("ERROR: Failed to initialize SPI bus %d\n", priv->spidev); + return -ENODEV; + } + + /* Now.. do what with the MRF24J40 instance? */ +#warning Missing logic + + return OK; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_mrf24j40_initialize + * + * Description: + * Initialize the MRF24J40 device. + * + * Returned Value: + * Zero is returned on success. Otherwise, a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +int stm32_mrf24j40_initialize(void) +{ + int ret; + +#ifdef CONFIG_CLICKER2_STM32_MB1_BEE + wlinfo("Configuring BEE in mikroBUS1\n"); + + ret = stm32_mrf24j40_devsetup(&g_mrf24j40_mb1_priv); + if (ret < 0) + { + wlerr("ERROR: Failed to initialize BD in mikroBUS1: %d\n", ret); + } +#endif + +#ifdef CONFIG_CLICKER2_STM32_MB2_BEE + wlinfo("Configuring BEE in mikroBUS2\n"); + + ret = stm32_mrf24j40_devsetup(&g_mrf24j40_mb2_priv); + if (ret < 0) + { + wlerr("ERROR: Failed to initialize BD in mikroBUS2: %d\n", ret); + } +#endif + + UNUSED(ret); + return OK; +} +#endif /* CONFIG_IEEE802154_MRF24J40 */ diff --git a/include/nuttx/wireless/ieee802154/mrf24j40.h b/include/nuttx/wireless/ieee802154/mrf24j40.h index 1871769c82..8f86abcfcb 100644 --- a/include/nuttx/wireless/ieee802154/mrf24j40.h +++ b/include/nuttx/wireless/ieee802154/mrf24j40.h @@ -52,12 +52,12 @@ * * The MRF24J40 interrupt is an active low, *level* interrupt. From Datasheet: * "Note 1: The INTEDGE polarity defaults to: - * 0 = Falling Edge. Ensure that the inter- - * rupt polarity matches the interrupt pin - * polarity of the host microcontroller. - * Note 2: The INT pin will remain high or low, - * depending on INTEDGE polarity setting, - * until INTSTAT register is read." + * + * 0 = Falling Edge. Ensure that the interrupt polarity matches the + * interrupt pin polarity of the host microcontroller. + * + * Note 2: The INT pin will remain high or low, depending on INTEDGE + * polarity setting, until INTSTAT register is read." */ struct mrf24j40_lower_s -- GitLab From 947acd6c1a1eef21c97f147b58224fd85e8dc880 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 22 Mar 2017 15:53:12 -0600 Subject: [PATCH 158/990] Small changes from review of last PR --- arch/arm/src/stm32/Kconfig | 10 +++--- arch/arm/src/stm32/chip/stm32_flash.h | 1 - arch/arm/src/stm32/stm32_flash.c | 43 ++++++++++---------------- configs/clicker2-stm32/src/stm32_spi.c | 2 +- 4 files changed, 24 insertions(+), 32 deletions(-) diff --git a/arch/arm/src/stm32/Kconfig b/arch/arm/src/stm32/Kconfig index 72f8a17fbb..9e3ce56127 100644 --- a/arch/arm/src/stm32/Kconfig +++ b/arch/arm/src/stm32/Kconfig @@ -2634,10 +2634,12 @@ config STM32_FLASH_PREFETCH properly and enabling this option may interfere with ADC accuracy. config STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW - bool "Enable the workaround to fix flash data cache corruption when reading from one flash bank while writing on other flash bank" - default n - ---help--- - See your STM32 errata to check if your STM32 is affected by this problem. + bool "Workaround for FLASH data cache corruption" + default n + ---help--- + Enable the workaround to fix flash data cache corruption when reading + from one flash bank while writing on other flash bank. See your STM32 + errata to check if your STM32 is affected by this problem. choice prompt "JTAG Configuration" diff --git a/arch/arm/src/stm32/chip/stm32_flash.h b/arch/arm/src/stm32/chip/stm32_flash.h index 16c67a933e..32eeaf90dd 100644 --- a/arch/arm/src/stm32/chip/stm32_flash.h +++ b/arch/arm/src/stm32/chip/stm32_flash.h @@ -392,7 +392,6 @@ * Public Functions ************************************************************************************/ -void stm32_flash_initialize(void); void stm32_flash_lock(void); void stm32_flash_unlock(void); diff --git a/arch/arm/src/stm32/stm32_flash.c b/arch/arm/src/stm32/stm32_flash.c index 4907aa9f0a..8ba48a8262 100644 --- a/arch/arm/src/stm32/stm32_flash.c +++ b/arch/arm/src/stm32/stm32_flash.c @@ -48,8 +48,10 @@ #include #include -#include #include +#include +#include +#include #include "stm32_flash.h" #include "stm32_rcc.h" @@ -83,30 +85,26 @@ #endif /************************************************************************************ - * Private Functions + * Private Data ************************************************************************************/ -static sem_t g_sem; -/* - * After all SMT32 boards starts calling stm32_flash_initialize() this can - * be removed. - */ -static bool g_initialized = false; +static sem_t g_sem = SEM_INITIALIZER(1); + +/************************************************************************************ + * Private Functions + ************************************************************************************/ static void sem_lock(void) { - if (g_initialized) + while (sem_wait(&g_sem) < 0) { - sem_wait(&g_sem); + DEBUGASSERT(errno == EINTR); } } -static void sem_unlock(void) +static inline void sem_unlock(void) { - if (g_initialized) - { - sem_post(&g_sem); - } + sem_post(&g_sem); } static void flash_unlock(void) @@ -137,24 +135,18 @@ static void data_cache_disable(void) static void data_cache_enable(void) { - /* reset data cache */ + /* Reset data cache */ + modifyreg32(STM32_FLASH_ACR, 0, FLASH_ACR_DCRST); - /* enable data cache */ + /* Enable data cache */ + modifyreg32(STM32_FLASH_ACR, 0, FLASH_ACR_DCEN); } /************************************************************************************ * Public Functions ************************************************************************************/ -void stm32_flash_initialize(void) -{ - g_initialized = true; - /* - * Initialize the semaphore that manages exclusive access flash registers - */ - sem_init(&g_sem, 0, 1); -} void stm32_flash_unlock(void) { @@ -171,7 +163,6 @@ void stm32_flash_lock(void) } #if defined(CONFIG_STM32_STM32F10XX) || defined(CONFIG_STM32_STM32F30XX) - size_t up_progmem_pagesize(size_t page) { return STM32_FLASH_PAGESIZE; diff --git a/configs/clicker2-stm32/src/stm32_spi.c b/configs/clicker2-stm32/src/stm32_spi.c index 7e231d108b..87e6e8d1d1 100644 --- a/configs/clicker2-stm32/src/stm32_spi.c +++ b/configs/clicker2-stm32/src/stm32_spi.c @@ -63,7 +63,7 @@ * Name: stm32_spidev_initialize * * Description: - * Called to configure SPI chip select GPIO pins for the stm32f4discovery board. + * Called to configure SPI chip select GPIO pins for the Mikroe Clicker2 STM32 board. * ************************************************************************************/ -- GitLab From 3fb0a00c356d39f7ea2b4a330868941711eee987 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 22 Mar 2017 17:32:52 -0600 Subject: [PATCH 159/990] Small changes from review of last PR. Plus spacing and typo fix. --- arch/arm/src/stm32/Kconfig | 6 +++--- arch/arm/src/stm32/chip/stm32_flash.h | 24 ++++++++++++------------ configs/Makefile | 2 +- include/semaphore.h | 4 ++-- 4 files changed, 18 insertions(+), 18 deletions(-) diff --git a/arch/arm/src/stm32/Kconfig b/arch/arm/src/stm32/Kconfig index 9e3ce56127..557f8434f0 100644 --- a/arch/arm/src/stm32/Kconfig +++ b/arch/arm/src/stm32/Kconfig @@ -2629,9 +2629,9 @@ config STM32_FLASH_PREFETCH default y if STM32_STM32F427 || STM32_STM32F429 || STM32_STM32F446 default n ---help--- - Enable FLASH prefetch and F2 and F4 parts (FLASH pre-fetch is always enabled - on F1 parts). Some early revisions of F4 parts do not support FLASH pre-fetch - properly and enabling this option may interfere with ADC accuracy. + Enable FLASH prefetch and F2 and F4 parts (FLASH pre-fetch is always enabled + on F1 parts). Some early revisions of F4 parts do not support FLASH pre-fetch + properly and enabling this option may interfere with ADC accuracy. config STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW bool "Workaround for FLASH data cache corruption" diff --git a/arch/arm/src/stm32/chip/stm32_flash.h b/arch/arm/src/stm32/chip/stm32_flash.h index 32eeaf90dd..6bc1085bd1 100644 --- a/arch/arm/src/stm32/chip/stm32_flash.h +++ b/arch/arm/src/stm32/chip/stm32_flash.h @@ -324,10 +324,10 @@ # define FLASH_CR_OBL_LAUNCH (1 << 13) /* Bit 13: Force option byte loading */ # endif #elif defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX) -# define FLASH_CR_PG (1 << 0) /* Bit 0: Programming */ -# define FLASH_CR_SER (1 << 1) /* Bit 1: Sector Erase */ -# define FLASH_CR_MER (1 << 2) /* Bit 2: Mass Erase sectors 0..11 */ -# define FLASH_CR_SNB_SHIFT (3) /* Bits 3-6: Sector number */ +# define FLASH_CR_PG (1 << 0) /* Bit 0: Programming */ +# define FLASH_CR_SER (1 << 1) /* Bit 1: Sector Erase */ +# define FLASH_CR_MER (1 << 2) /* Bit 2: Mass Erase sectors 0..11 */ +# define FLASH_CR_SNB_SHIFT (3) /* Bits 3-6: Sector number */ #if defined(CONFIG_STM32_STM32F427) || defined(CONFIG_STM32_STM32F429) # define FLASH_CR_SNB_MASK (31 << FLASH_CR_SNB_SHIFT) # define FLASH_CR_SNB(n) (((n % 12) << FLASH_CR_SNB_SHIFT) | ((n / 12) << 7)) /* Sector n, n=0..23 */ @@ -335,19 +335,19 @@ # define FLASH_CR_SNB_MASK (15 << FLASH_CR_SNB_SHIFT) # define FLASH_CR_SNB(n) ((n) << FLASH_CR_SNB_SHIFT) /* Sector n, n=0..11 */ #endif -# define FLASH_CR_PSIZE_SHIFT (8) /* Bits 8-9: Program size */ +# define FLASH_CR_PSIZE_SHIFT (8) /* Bits 8-9: Program size */ # define FLASH_CR_PSIZE_MASK (3 << FLASH_CR_PSIZE_SHIFT) # define FLASH_CR_PSIZE_X8 (0 << FLASH_CR_PSIZE_SHIFT) /* 00 program x8 */ # define FLASH_CR_PSIZE_X16 (1 << FLASH_CR_PSIZE_SHIFT) /* 01 program x16 */ # define FLASH_CR_PSIZE_X32 (2 << FLASH_CR_PSIZE_SHIFT) /* 10 program x32 */ # define FLASH_CR_PSIZE_X64 (3 << FLASH_CR_PSIZE_SHIFT) /* 11 program x64 */ -# define FLASH_CR_STRT (1 << 16) /* Bit 16: Start Erase */ -# define FLASH_CR_EOPIE (1 << 24) /* Bit 24: End of operation interrupt enable */ -# define FLASH_CR_ERRIE (1 << 25) /* Bit 25: Error interrupt enable */ -# define FLASH_CR_LOCK (1 << 31) /* Bit 31: Lock */ +# define FLASH_CR_STRT (1 << 16) /* Bit 16: Start Erase */ +# define FLASH_CR_EOPIE (1 << 24) /* Bit 24: End of operation interrupt enable */ +# define FLASH_CR_ERRIE (1 << 25) /* Bit 25: Error interrupt enable */ +# define FLASH_CR_LOCK (1 << 31) /* Bit 31: Lock */ #endif #if defined(CONFIG_STM32_STM32F427) || defined(CONFIG_STM32_STM32F429) -# define FLASH_CR_MER1 (1 << 15) /* Bit 15: Mass Erase sectors 12..23 */ +# define FLASH_CR_MER1 (1 << 15) /* Bit 15: Mass Erase sectors 12..23 */ #endif /* Flash Option Control Register (OPTCR) */ @@ -375,7 +375,7 @@ /* Flash Option Control Register (OPTCR1) */ #if defined(CONFIG_STM32_STM32F427) || defined(CONFIG_STM32_STM32F429) -# define FLASH_OPTCR1_NWRP_SHIFT (16) /* Bits 16-27: Not write protect (high bank) */ +# define FLASH_OPTCR1_NWRP_SHIFT (16) /* Bits 16-27: Not write protect (high bank) */ # define FLASH_OPTCR1_NWRP_MASK (0xfff << FLASH_OPTCR_NWRP_SHIFT) # define FLASH_OPTCR1_BFB2_SHIFT (4) /* Bits 4: Dual-bank Boot option byte */ @@ -384,7 +384,7 @@ #endif #if defined(CONFIG_STM32_STM32F446) -# define FLASH_OPTCR1_NWRP_SHIFT (16) /* Bits 16-23: Not write protect (high bank) */ +# define FLASH_OPTCR1_NWRP_SHIFT (16) /* Bits 16-23: Not write protect (high bank) */ # define FLASH_OPTCR1_NWRP_MASK (0xff << FLASH_OPTCR_NWRP_SHIFT) #endif diff --git a/configs/Makefile b/configs/Makefile index f430e137e8..31de5604e0 100644 --- a/configs/Makefile +++ b/configs/Makefile @@ -89,7 +89,7 @@ OBJS = $(AOBJS) $(COBJS) BIN = libconfigs$(LIBEXT) all: $(BIN) -.PHONY: depend ccontext clean_context clean distclean +.PHONY: depend context clean_context clean distclean $(AOBJS): %$(OBJEXT): %.S $(call ASSEMBLE, $<, $@) diff --git a/include/semaphore.h b/include/semaphore.h index 0056909db6..e14b1aa409 100644 --- a/include/semaphore.h +++ b/include/semaphore.h @@ -105,14 +105,14 @@ typedef struct sem_s sem_t; #ifdef CONFIG_PRIORITY_INHERITANCE # if CONFIG_SEM_PREALLOCHOLDERS > 0 # define SEM_INITIALIZER(c) \ - {(c), 0, NULL} /* semcount, flags, hhead */ + {(c), 0, NULL} /* semcount, flags, hhead */ # else # define SEM_INITIALIZER(c) \ {(c), 0, {SEMHOLDER_INITIALIZER, SEMHOLDER_INITIALIZER}} /* semcount, flags, holder[2] */ # endif #else # define SEM_INITIALIZER(c) \ - {(c)} /* semcount */ + {(c)} /* semcount */ #endif /**************************************************************************** -- GitLab From c73b65c9b9ad777b122cf99eecb2c559a1420b79 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Wed, 22 Mar 2017 23:56:54 +0000 Subject: [PATCH 160/990] stm32f7:stm32_allocateheap.c There are 5 configurations --- arch/arm/src/stm32f7/stm32_allocateheap.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/arch/arm/src/stm32f7/stm32_allocateheap.c b/arch/arm/src/stm32f7/stm32_allocateheap.c index ffa6d27455..4714b53f3d 100644 --- a/arch/arm/src/stm32f7/stm32_allocateheap.c +++ b/arch/arm/src/stm32f7/stm32_allocateheap.c @@ -126,7 +126,7 @@ # endif #endif -/* There are 4 possible heap configurations: +/* There are 5 possible heap configurations: * * Configuration 1. System SRAM1 (only) * CONFIG_MM_REGIONS == 1 -- GitLab From 45f5d30e2eccd1da4f7e5253d1ac637d4cecd02d Mon Sep 17 00:00:00 2001 From: no1wudi <757509347@qq.com> Date: Thu, 23 Mar 2017 13:38:26 +0800 Subject: [PATCH 161/990] fix compile error when disabled the flash data cache corruption for stm32 f1xx --- arch/arm/src/stm32/stm32_flash.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/arch/arm/src/stm32/stm32_flash.c b/arch/arm/src/stm32/stm32_flash.c index 8ba48a8262..f955085a27 100644 --- a/arch/arm/src/stm32/stm32_flash.c +++ b/arch/arm/src/stm32/stm32_flash.c @@ -127,6 +127,7 @@ static void flash_lock(void) { modifyreg32(STM32_FLASH_CR, 0, FLASH_CR_LOCK); } +#if defined(CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW) static void data_cache_disable(void) { @@ -144,6 +145,7 @@ static void data_cache_enable(void) modifyreg32(STM32_FLASH_ACR, 0, FLASH_ACR_DCEN); } +#endif /************************************************************************************ * Public Functions ************************************************************************************/ -- GitLab From 40a8ef3c009c0fb813e506e7cd0cf2c69cedb717 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 23 Mar 2017 06:58:54 -0600 Subject: [PATCH 162/990] Clicker2-STM32: Add logic to register the MRF24J40 radio character device. --- configs/clicker2-stm32/src/stm32_mrf24j40.c | 24 ++++++++++++++++--- include/nuttx/wireless/ieee802154/at86rf23x.h | 5 ++-- .../wireless/ieee802154/ieee802154_radio.h | 22 +++++++++++++++++ wireless/ieee802154/radio802154_device.c | 4 ++++ 4 files changed, 50 insertions(+), 5 deletions(-) diff --git a/configs/clicker2-stm32/src/stm32_mrf24j40.c b/configs/clicker2-stm32/src/stm32_mrf24j40.c index ef36bc4b3e..99ad2faa06 100644 --- a/configs/clicker2-stm32/src/stm32_mrf24j40.c +++ b/configs/clicker2-stm32/src/stm32_mrf24j40.c @@ -65,7 +65,12 @@ # error Wireless support requires CONFIG_DRIVERS_WIRELESS #endif -#if !defined(CONFIG_CLICKER2_STM32_MB1_BEE) && !defined(CONFIG_CLICKER2_STM32_MB2_BEE) +#ifndef CONFIG_IEEE802154_DEV +# error IEEE802.15.4 radio character device required (CONFIG_IEEE802154_DEV) +#endif + +#if !defined(CONFIG_CLICKER2_STM32_MB1_BEE) && \ + !defined(CONFIG_CLICKER2_STM32_MB2_BEE) # error Only the Mikroe BEE board is supported #endif @@ -81,6 +86,8 @@ # endif #endif +#define RADIO_DEVNAME "/dev/mrf24j40" + /**************************************************************************** * Private Types ****************************************************************************/ @@ -239,8 +246,19 @@ static int stm32_mrf24j40_devsetup(FAR struct stm32_priv_s *priv) return -ENODEV; } - /* Now.. do what with the MRF24J40 instance? */ -#warning Missing logic +#ifdef CONFIG_IEEE802154_DEV + /* Register a character driver to access the IEEE 802.15.4 radio from + * user-space + */ + + ret = radio802154dev_register(radio, RADIO_DEVNAME); + if (ret < 0) + { + wlerr("ERROR: Failed to register the radio device %s: %d\n", + RADIO_DEVNAME, ret); + return ret; + } +#endif return OK; } diff --git a/include/nuttx/wireless/ieee802154/at86rf23x.h b/include/nuttx/wireless/ieee802154/at86rf23x.h index b33e58020f..7d6f1fe0ce 100644 --- a/include/nuttx/wireless/ieee802154/at86rf23x.h +++ b/include/nuttx/wireless/ieee802154/at86rf23x.h @@ -91,8 +91,9 @@ extern "C" * ****************************************************************************/ -FAR struct ieee802154_radio_s *at86rf23x_init(FAR struct spi_dev_s *spi, - FAR const struct at86rf23x_lower_s *lower); +FAR struct ieee802154_radio_s * + at86rf23x_init(FAR struct spi_dev_s *spi, + FAR const struct at86rf23x_lower_s *lower); #undef EXTERN #ifdef __cplusplus diff --git a/include/nuttx/wireless/ieee802154/ieee802154_radio.h b/include/nuttx/wireless/ieee802154/ieee802154_radio.h index 7adbbfd7ae..3e64aa5c60 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_radio.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_radio.h @@ -170,6 +170,28 @@ extern "C" * Public Function Prototypes ****************************************************************************/ +/**************************************************************************** + * Name: radio802154dev_register + * + * Description: + * Register a character driver to access the IEEE 802.15.4 radio from + * user-space + * + * Input Parameters: + * radio - Pointer to the radio struct to be registerd. + * devname - The name of the IEEE 802.15.4 radio to be registered. + * + * Returned Values: + * Zero (OK) is returned on success. Otherwise a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +#ifdef CONFIG_IEEE802154_DEV +int radio802154dev_register(FAR struct ieee802154_radio_s *radio, + FAR char *devname); +#endif + #undef EXTERN #ifdef __cplusplus } diff --git a/wireless/ieee802154/radio802154_device.c b/wireless/ieee802154/radio802154_device.c index feb4410465..bdd1e07c81 100644 --- a/wireless/ieee802154/radio802154_device.c +++ b/wireless/ieee802154/radio802154_device.c @@ -466,6 +466,10 @@ static int radio802154dev_ioctl(FAR struct file *filep, int cmd, return ret; } +/**************************************************************************** + * Public Functions + ****************************************************************************/ + /**************************************************************************** * Name: radio802154dev_register * -- GitLab From 9e4052e506f863904bc6c5d9a282a94da105f4d6 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 23 Mar 2017 07:20:10 -0600 Subject: [PATCH 163/990] Clicker2-STM32: Add some mostly bogus MAC initializatinon logic. --- configs/clicker2-stm32/src/stm32_mrf24j40.c | 31 +++++++++++++++++-- .../wireless/ieee802154/ieee802154_mac.h | 31 ++++++++++++------- wireless/ieee802154/mac802154.c | 18 ++++++++++- wireless/ieee802154/radio802154_device.c | 3 +- 4 files changed, 68 insertions(+), 15 deletions(-) diff --git a/configs/clicker2-stm32/src/stm32_mrf24j40.c b/configs/clicker2-stm32/src/stm32_mrf24j40.c index 99ad2faa06..8d28c54854 100644 --- a/configs/clicker2-stm32/src/stm32_mrf24j40.c +++ b/configs/clicker2-stm32/src/stm32_mrf24j40.c @@ -47,6 +47,8 @@ #include #include +#include +#include #include #include "stm32_gpio.h" @@ -87,6 +89,7 @@ #endif #define RADIO_DEVNAME "/dev/mrf24j40" +#define MAC_DEVNAME "/dev/mrf24j40mac" /**************************************************************************** * Private Types @@ -222,6 +225,9 @@ static void stm32_enable_irq(FAR struct mrf24j40_lower_s *lower, int state) static int stm32_mrf24j40_devsetup(FAR struct stm32_priv_s *priv) { FAR struct ieee802154_radio_s *radio; +#ifdef CONFIG_IEEE802154_MAC + FAR struct ieee802154_mac_s *mac; +#endif FAR struct spi_dev_s *spi; /* Configure the interrupt pin */ @@ -246,9 +252,9 @@ static int stm32_mrf24j40_devsetup(FAR struct stm32_priv_s *priv) return -ENODEV; } -#ifdef CONFIG_IEEE802154_DEV +#if defined(CONFIG_IEEE802154_DEV) /* Register a character driver to access the IEEE 802.15.4 radio from - * user-space + * user-space */ ret = radio802154dev_register(radio, RADIO_DEVNAME); @@ -258,6 +264,27 @@ static int stm32_mrf24j40_devsetup(FAR struct stm32_priv_s *priv) RADIO_DEVNAME, ret); return ret; } + +#elif 0 /* defined(CONFIG_IEEE802154_MAC) */ + /* Create a 802.15.4 MAC device from a 802.15.4 compatible radio device. */ + + mac = mac802154_register(radio, 0); + if (radio == NULL) + { + wlerr("ERROR: Failed to initialize IEEE802.15.4 MAC\n"); + return -ENODEV; + } + + /* If want to call these APIs from userspace, you have to wrap your mac + * in a character device via mac802154_device.c. + */ + + ret = mac802154dev_register(mac, MAC_DEVNAME); + if (ret < 0) + { + wlerr("ERROR: Failed to register the radio device %s: %d\n", + RADIO_DEVNAME, ret); + return ret; #endif return OK; diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index 0cddb694bf..3e0200e7a3 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -378,17 +378,26 @@ extern "C" * Public Function Prototypes ****************************************************************************/ -/* Instanciate a 802.15.4 MAC from a 802.15.4 radio device. - * To create a 802.15.4 MAC, you need to pass: - * - an instance of a radio driver in radiodev - * - a pointer to a structure that contains MAC callback routines to - * handle confirmations and indications. NULL entries indicate no callback. - * In return you get a mac structure that has pointers to MAC operations and - * responses. - * This API does not create any device accessible to userspace. If you want to - * call these APIs from userspace, you have to wrap your mac in a character - * device via mac802154_device.c . - */ +/**************************************************************************** + * Name: mac802154_register + * + * Description: + * Create a 802.15.4 MAC device from a 802.15.4 compatible radio device. + * To create a 802.15.4 MAC, you need to pass: + * + * - an instance of a radio driver in radiodev + * - a pointer to a structure that contains MAC callback routines to + * handle confirmations and indications. NULL entries indicate no + * callback. + * + * In return you get a mac structure that has pointers to MAC operations + * and responses. + * + * This API does not create any device accessible to userspace. If you + * want to call these APIs from userspace, you have to wrap your mac in a + * character device via mac802154_device.c. + * + ****************************************************************************/ FAR struct ieee802154_mac_s * mac802154_register(FAR struct ieee802154_radio_s *radiodev, diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index 3de16fb374..cfa199d54b 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -524,6 +524,19 @@ static int mac802154_rsporphan(FAR struct ieee802154_mac_s *mac, * * Description: * Create a 802.15.4 MAC device from a 802.15.4 compatible radio device. + * To create a 802.15.4 MAC, you need to pass: + * + * - an instance of a radio driver in radiodev + * - a pointer to a structure that contains MAC callback routines to + * handle confirmations and indications. NULL entries indicate no + * callback. + * + * In return you get a mac structure that has pointers to MAC operations + * and responses. + * + * This API does not create any device accessible to userspace. If you + * want to call these APIs from userspace, you have to wrap your mac in a + * character device via mac802154_device.c. * ****************************************************************************/ @@ -537,7 +550,8 @@ FAR struct ieee802154_mac_s * mac = (FAR struct ieee802154_privmac_s *) kmm_zalloc(sizeof(struct ieee802154_privmac_s)); - if(!mac) + + if (mac == NULL) { return NULL; } @@ -546,7 +560,9 @@ FAR struct ieee802154_mac_s * mac->pubmac.radio = radiodev; mac->pubmac.ops = mac802154ops; + mac802154_defaultmib(mac); mac802154_applymib(mac); + return &mac->pubmac; } diff --git a/wireless/ieee802154/radio802154_device.c b/wireless/ieee802154/radio802154_device.c index bdd1e07c81..2bab563e5b 100644 --- a/wireless/ieee802154/radio802154_device.c +++ b/wireless/ieee802154/radio802154_device.c @@ -487,7 +487,8 @@ static int radio802154dev_ioctl(FAR struct file *filep, int cmd, * ****************************************************************************/ -int radio802154dev_register(FAR struct ieee802154_radio_s *radio, FAR char *devname) +int radio802154dev_register(FAR struct ieee802154_radio_s *radio, + FAR char *devname) { FAR struct radio802154_devwrapper_s *dev; -- GitLab From 23b472f907ddae042cc771bba5167ab17793d859 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Wed, 22 Mar 2017 14:13:28 -0400 Subject: [PATCH 164/990] wireless/ieee802154: Removes unused ieee802154.h header --- .../nuttx/wireless/ieee802154/ieee802154.h | 62 ------------------- 1 file changed, 62 deletions(-) delete mode 100644 include/nuttx/wireless/ieee802154/ieee802154.h diff --git a/include/nuttx/wireless/ieee802154/ieee802154.h b/include/nuttx/wireless/ieee802154/ieee802154.h deleted file mode 100644 index 0211940414..0000000000 --- a/include/nuttx/wireless/ieee802154/ieee802154.h +++ /dev/null @@ -1,62 +0,0 @@ -/**************************************************************************** - * include/nuttx/net/ieee802154.h - * - * Copyright (C) 2016 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Includes some definitions that a compatible with the LGPL GNU C Library - * header file of the same name. - * - * 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_WIRELESS_IEEE802154_IEEE802154_H -#define __INCLUDE_NUTTX_WIRELESS_IEEE802154_IEEE802154_H - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include - -/**************************************************************************** - * Public Type Definitions - ****************************************************************************/ - -/**************************************************************************** - * Public Data - ****************************************************************************/ - -/**************************************************************************** - * Public Function Prototypes - ****************************************************************************/ - -#endif /* __INCLUDE_NUTTX_WIRELESS_IEEE802154_IEEE802154_H */ -- GitLab From 06af125e45c721a9191348466fb692bf8daaefa3 Mon Sep 17 00:00:00 2001 From: Aleksandr Vyhovanec Date: Thu, 23 Mar 2017 17:34:45 +0300 Subject: [PATCH 165/990] The interrupt occurs over the counter overflow --- arch/arm/src/stm32/stm32_qencoder.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/arch/arm/src/stm32/stm32_qencoder.c b/arch/arm/src/stm32/stm32_qencoder.c index e2245075b9..126ef24987 100644 --- a/arch/arm/src/stm32/stm32_qencoder.c +++ b/arch/arm/src/stm32/stm32_qencoder.c @@ -693,17 +693,17 @@ static int stm32_interrupt(int irq, FAR void *context, FAR void *arg) stm32_putreg16(priv, STM32_GTIM_SR_OFFSET, regval & ~GTIM_SR_UIF); /* Check the direction bit in the CR1 register and add or subtract the - * maximum value, as appropriate. + * maximum value + 1, as appropriate. */ regval = stm32_getreg16(priv, STM32_GTIM_CR1_OFFSET); if ((regval & ATIM_CR1_DIR) != 0) { - priv->position -= (int32_t)0x0000ffff; + priv->position -= (int32_t)0x00010000; } else { - priv->position += (int32_t)0x0000ffff; + priv->position += (int32_t)0x00010000; } return OK; -- GitLab From 2ec72c8f9421c17682ff4229bbeb5ea6275a8bf0 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 23 Mar 2017 11:17:17 -0600 Subject: [PATCH 166/990] Clicker2-STM32: Add a README file --- Documentation/README.html | 4 +- README.txt | 2 + configs/clicker2-stm32/README.txt | 160 ++++++++++++++++++++++++ configs/clicker2-stm32/nsh/defconfig | 4 +- configs/clicker2-stm32/scripts/flash.ld | 3 +- 5 files changed, 168 insertions(+), 5 deletions(-) create mode 100644 configs/clicker2-stm32/README.txt diff --git a/Documentation/README.html b/Documentation/README.html index 4430ef211f..01a27ce644 100644 --- a/Documentation/README.html +++ b/Documentation/README.html @@ -8,7 +8,7 @@

NuttX README Files

-

Last Updated: March 21, 2017

+

Last Updated: March 23, 2017

@@ -68,6 +68,8 @@ nuttx/ | | `- README.txt | |- cc3200-launchpad/ | | `- README.txt + | |- clicker2-stm32/ + | | `- README.txt | |- cloudctrl/ | | `- README.txt | |- demo9s12ne64/ diff --git a/README.txt b/README.txt index 4bab1306ff..3db07e882a 100644 --- a/README.txt +++ b/README.txt @@ -1453,6 +1453,8 @@ nuttx/ | | `- README.txt | |- cc3200-launchpad/ | | `- README.txt + | |- clicker2-stm32 + | | `- README.txt | |- cloudctrl | | `- README.txt | |- demo0s12ne64/ diff --git a/configs/clicker2-stm32/README.txt b/configs/clicker2-stm32/README.txt new file mode 100644 index 0000000000..935ea41201 --- /dev/null +++ b/configs/clicker2-stm32/README.txt @@ -0,0 +1,160 @@ +README +====== + + This is the README file for the port of NuttX to the Mikroe Clicker2 STM32 + board based on the STMicro STM32F407VGT6 MCU. + + Reference: https://shop.mikroe.com/development-boards/starter/clicker-2/stm32f4 + +Serial Console +============== + + The are no RS-232 drivers on-board. An RS-232 Click board is available: + https://shop.mikroe.com/click/interface/rs232 or you can cannot an off- + board TTL-to-RS-232 converter as follows: + + USART2: mikroBUS1 PD6/RX and PD5/TX + USART3: mikroBUS2 PD9/RX and PD8TX + + GND, 3.3V, and 5V. Are also available + + By default, USART3 on mikroBUS2 is used as the serial console in each + configuration unless stated otherwise in the description of the + configuration. + +LEDs +==== + + The Mikroe Clicker2 STM32 has two user controllable LEDs: + + LD1/PE12, Active high output illuminates + LD2/PE15, Active high output illuminates + + If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any + way. If CONFIG_ARCH_LEDs is defined, then NuttX will control the 2 LEDs on + board the Clicker2 for STM32. The following definitions describe how NuttX + controls the LEDs: + + SYMBOL Meaning LED state + LD1 LD2 + ------------------- ----------------------- -------- -------- + LED_STARTED NuttX has been started OFF OFF + LED_HEAPALLOCATE Heap has been allocated OFF OFF + LED_IRQSENABLED Interrupts enabled OFF OFF + LED_STACKCREATED Idle stack created ON OFF + LED_INIRQ In an interrupt N/C ON + LED_SIGNAL In a signal handler No change + LED_ASSERTION An assertion failed No change + LED_PANIC The system has crashed OFF Blinking + LED_IDLE STM32 is is sleep mode Not used + + Thus is LD1 is illuminated, the Clicker2 has completed boot-up. IF LD2 + is glowly softly, then interrupts are being taken; the level of illumination + depends amount of time processing interupts. If LD1 is off and LD2 is + blinking at about 2Hz, then the system has crashed. + +Buttons +======= + + The Mikroe Clicker2 STM32 has two buttons available to software: + + T2/E0, Low sensed when pressed + T3/PA10, Low sensed when pressed + +onfigurations +============== + + Information Common to All Configurations + ---------------------------------------- + Each Clicker2 configuration is maintained in a sub-directory and can be + selected as follow: + + cd tools + ./configure.sh clicker2-stm32/ + cd - + . ./setenv.sh + + Before sourcing the setenv.sh file above, you should examine it and + perform edits as necessary so that TOOLCHAIN_BIN is the correct path + to the directory than holds your toolchain binaries. + + And then build NuttX by simply typing the following. At the conclusion of + the make, the nuttx binary will reside in an ELF file called, simply, nuttx. + + make oldconfig + make + + The that is provided above as an argument to the tools/configure.sh + must be is one of the following. + + NOTES: + + 1. These configurations use the mconf-based configuration tool. To + change any of these configurations using that tool, you should: + + a. Build and install the kconfig-mconf tool. See nuttx/README.txt + see additional README.txt files in the NuttX tools repository. + + b. Execute 'make menuconfig' in nuttx/ in order to start the + reconfiguration process. + + 2. Unless stated otherwise, all configurations generate console + output on USART3, channel 0) as described above under "Serial + Console". The relevant configuration settings are listed below: + + CONFIG_STM32_USART3=y + CONFIG_STM32_USART3_SERIALDRIVER=y + CONFIG_STM32_USART=y + + CONFIG_USART3_SERIALDRIVER=y + CONFIG_USART3_SERIAL_CONSOLE=y + + CONFIG_USART3_RXBUFSIZE=256 + CONFIG_USART3_TXBUFSIZE=256 + CONFIG_USART3_BAUD=115200 + CONFIG_USART3_BITS=8 + CONFIG_USART3_PARITY=0 + CONFIG_USART3_2STOP=0 + + + 3. All of these configurations are set up to build under Linux using the + "GNU Tools for ARM Embedded Processors" that is maintained by ARM + (unless stated otherwise in the description of the configuration). + + https://launchpad.net/gcc-arm-embedded + + That toolchain selection can easily be reconfigured using + 'make menuconfig'. Here are the relevant current settings: + + Build Setup: + CONFIG_HOST_LINUX =y : Linux environment + + System Type -> Toolchain: + CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL=y : GNU ARM EABI toolchain + + Configuration sub-directories + ----------------------------- + + nsh: + + Configures the NuttShell (nsh) located at examples/nsh. This + configuration is focused on low level, command-line driver testing. It + has no network. + + NOTES: + + 1. Support for NSH built-in applications is provided: + + Binary Formats: + CONFIG_BUILTIN=y : Enable support for built-in programs + + Application Configuration: + CONFIG_NSH_BUILTIN_APPS=y : Enable starting apps from NSH command line + + No built applications are enabled in the base configuration, however. + + 2. C++ support for applications is enabled: + + CONFIG_HAVE_CXX=y + CONFIG_HAVE_CXXINITIALIZE=y + CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y diff --git a/configs/clicker2-stm32/nsh/defconfig b/configs/clicker2-stm32/nsh/defconfig index 7ae63061f9..764b16372c 100644 --- a/configs/clicker2-stm32/nsh/defconfig +++ b/configs/clicker2-stm32/nsh/defconfig @@ -144,10 +144,10 @@ CONFIG_ARM_HAVE_MPU_UNIFIED=y # CONFIG_ARMV7M_HAVE_ITCM is not set # CONFIG_ARMV7M_HAVE_DTCM is not set # CONFIG_ARMV7M_TOOLCHAIN_IARL is not set -CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y +# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set # CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set # CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL is not set -# CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL is not set +CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL=y # CONFIG_ARMV7M_OABI_TOOLCHAIN is not set CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARMV7M_STACKCHECK is not set diff --git a/configs/clicker2-stm32/scripts/flash.ld b/configs/clicker2-stm32/scripts/flash.ld index ca2e7eefcf..6bb3aabadd 100644 --- a/configs/clicker2-stm32/scripts/flash.ld +++ b/configs/clicker2-stm32/scripts/flash.ld @@ -42,8 +42,7 @@ * * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 * where the code expects to begin execution by jumping to the entry point in - * the 0x0800:0000 address - * range. + * the 0x0800:0000 address range. */ MEMORY -- GitLab From 9353ca6039930d4b497f963e1912fb416b06b0a9 Mon Sep 17 00:00:00 2001 From: rg Date: Thu, 23 Mar 2017 11:24:18 -0600 Subject: [PATCH 167/990] STM32 I2C: Do not allow CONFIG_I2C_POLLED and CONFIG_I2C_DMA --- arch/arm/src/stm32/Kconfig | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/arch/arm/src/stm32/Kconfig b/arch/arm/src/stm32/Kconfig index 557f8434f0..eba911dfc5 100644 --- a/arch/arm/src/stm32/Kconfig +++ b/arch/arm/src/stm32/Kconfig @@ -6201,12 +6201,11 @@ config STM32_I2C_DUTY16_9 config STM32_I2C_DMA bool "I2C DMA Support" default n - depends on STM32_I2C && STM32_STM32F40XX && STM32_DMA1 + depends on STM32_I2C && STM32_STM32F40XX && STM32_DMA1 && !I2C_POLLED ---help--- This option enables the DMA for I2C transfers. Note: The user can define CONFIG_I2C_DMAPRIO: a custom priority value for the I2C dma streams, else the default priority level is set to medium. - Note: This option is compatible with CONFIG_I2C_POLLED. endmenu -- GitLab From 123a057be9c78147394a3f9463af875249c36c3a Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 23 Mar 2017 11:43:32 -0600 Subject: [PATCH 168/990] Update README --- configs/clicker2-stm32/README.txt | 34 ++++++++++++++++++++++++++++++- 1 file changed, 33 insertions(+), 1 deletion(-) diff --git a/configs/clicker2-stm32/README.txt b/configs/clicker2-stm32/README.txt index 935ea41201..f97be665d4 100644 --- a/configs/clicker2-stm32/README.txt +++ b/configs/clicker2-stm32/README.txt @@ -6,6 +6,15 @@ README Reference: https://shop.mikroe.com/development-boards/starter/clicker-2/stm32f4 +Contents +======== + + o Serial Console + o LEDs + o Buttons + o Using JTAG + o Configurations + Serial Console ============== @@ -61,7 +70,30 @@ Buttons T2/E0, Low sensed when pressed T3/PA10, Low sensed when pressed -onfigurations +Using JTAG +========== + + The Clicker2 comes with the mikroBootloader installed. But it also offers + a 2x5 JTAG connector. You may use Dupont jumpers to connect this port to + JTAG as described here: + + https://www.mikroe.com/how-to-use-st-link-v2-with-clicker-2-for-stm32-a-detailed-walkthrough/ + http://www.playembedded.org/blog/en/2016/02/06/mikroe-clicker-2-for-stm32-and-stlink-v2/ + + NOTE that the FLASH is locked. You may need to follow the instructions at + the second link to unlock it (although I think you can do this with the ST-Micro + ST-Link Utility as well). + + You can avoid the mess of jumpers using the mikroProg to ST-Link v2 adapte + along with a 2x5, 10-wire ribbon cable connector: + + https://shop.mikroe.com/add-on-boards/adapter/mikroprog-st-link-v2-adapter + + OpenOCD can be used with the ST-Link to provide a debug environment. I suspect, + however, that adapter can be used with other JTAG debuggers such as J-Link, + but that remains to be verified. + +Configurations ============== Information Common to All Configurations -- GitLab From 0658f26a18585a3ddd40759f383bf77a5f55aa97 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Thu, 23 Mar 2017 14:00:45 -0400 Subject: [PATCH 169/990] wireless/ieee802154: Moves common types to ieee802154.h Since the MAC layer or the PHY radio layer can be accessed independently, common types that are used in both layers should go in a common ieee802154.h file --- .../nuttx/wireless/ieee802154/ieee802154.h | 106 ++++++++++++++++++ .../wireless/ieee802154/ieee802154_mac.h | 23 ---- 2 files changed, 106 insertions(+), 23 deletions(-) create mode 100644 include/nuttx/wireless/ieee802154/ieee802154.h diff --git a/include/nuttx/wireless/ieee802154/ieee802154.h b/include/nuttx/wireless/ieee802154/ieee802154.h new file mode 100644 index 0000000000..1866b9db02 --- /dev/null +++ b/include/nuttx/wireless/ieee802154/ieee802154.h @@ -0,0 +1,106 @@ +/**************************************************************************** + * include/nuttx/wireless/ieee802154/ieee802154.h + * + * Copyright (C) 2014-2016 Sebastien Lorquet. All rights reserved. + * Copyright (C) 2017 Verge Inc. All rights reserved. + * Author: Sebastien Lorquet + * Author: Anthony Merlino + * + * 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_WIRELESS_IEEE802154_IEEE802154_H +#define __INCLUDE_NUTTX_WIRELESS_IEEE802154_IEEE802154_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +struct ieee802154_packet_s +{ + uint8_t len; + uint8_t data[127]; + uint8_t lqi; + uint8_t rssi; +}; + +/* IEEE 802.15.4 Device address + * The addresses in ieee802154 have several formats: + * No address : [none] + * Short address + PAN id : PPPP/SSSS + * Extended address + PAN id : PPPP/LLLLLLLLLLLLLLLL + */ + +struct ieee802154_addr_s +{ + uint8_t ia_len; /* structure length, 0/2/8 */ + uint16_t ia_panid; /* PAN identifier, can be IEEE802154_PAN_UNSPEC */ + union + { + uint16_t _ia_saddr; /* short address */ + uint8_t _ia_eaddr[8]; /* extended address */ + } ia_addr; + +#define ia_saddr ia_addr._ia_saddr +#define ia_eaddr ia_addr._ia_eaddr +}; + +#define IEEE802154_ADDRSTRLEN 22 /* (2*2+1+8*2, PPPP/EEEEEEEEEEEEEEEE) */ + + +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* __INCLUDE_NUTTX_WIRELESS_IEEE802154_IEEE802154_H*/ diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index 3e0200e7a3..d39aa887cb 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -161,29 +161,6 @@ enum * Public Types ****************************************************************************/ -/* IEEE 802.15.4 Device address - * The addresses in ieee802154 have several formats: - * No address : [none] - * Short address + PAN id : PPPP/SSSS - * Extended address + PAN id : PPPP/LLLLLLLLLLLLLLLL - */ - -struct ieee802154_addr_s -{ - uint8_t ia_len; /* structure length, 0/2/8 */ - uint16_t ia_panid; /* PAN identifier, can be IEEE802154_PAN_UNSPEC */ - union - { - uint16_t _ia_saddr; /* short address */ - uint8_t _ia_eaddr[8]; /* extended address */ - } ia_addr; - -#define ia_saddr ia_addr._ia_saddr -#define ia_eaddr ia_addr._ia_eaddr -}; - -#define IEEE802154_ADDRSTRLEN 22 /* (2*2+1+8*2, PPPP/EEEEEEEEEEEEEEEE) */ - /* Operations */ struct ieee802154_mac_s; /* Forward reference */ -- GitLab From 2150619d370a44837e8ce6d3bbfdb0196075d755 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Thu, 23 Mar 2017 14:04:06 -0400 Subject: [PATCH 170/990] fs/ioctl.h: Renames RAD802154 to PHY802154 --- include/nuttx/fs/ioctl.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/include/nuttx/fs/ioctl.h b/include/nuttx/fs/ioctl.h index df69f56af1..4f6bab1aa1 100644 --- a/include/nuttx/fs/ioctl.h +++ b/include/nuttx/fs/ioctl.h @@ -87,7 +87,7 @@ #define _GPIOBASE (0x2200) /* GPIO driver commands */ #define _CLIOCBASE (0x2300) /* Contactless modules ioctl commands */ #define _MAC802154BASE (0x2400) /* 802.15.4 MAC ioctl commands */ -#define _RAD802154BASE (0x2500) /* 802.15.4 Radio ioctl commands */ +#define _PHY802154BASE (0x2500) /* 802.15.4 Radio ioctl commands */ /* boardctl() commands share the same number space */ @@ -412,8 +412,8 @@ /* 802.15.4 Radio driver ioctl definitions *******************************************/ /* (see nuttx/ieee802154/wireless/ieee802154_radio.h */ -#define _RAD802154IOCVALID(c) (_IOC_TYPE(c)==_RADIO802154BASE) -#define _RAD802154IOC(nr) _IOC(_RADIO802154BASE,nr) +#define _PHY802154IOCVALID(c) (_IOC_TYPE(c)==_PHY802154BASE) +#define _PHY802154IOC(nr) _IOC(_PHY802154BASE,nr) /* boardctl() command definitions *******************************************/ -- GitLab From 20b8ccd9d451ee28c8aa87b3a067f445b9bd2692 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 23 Mar 2017 13:43:48 -0600 Subject: [PATCH 171/990] More updates to README.txt --- configs/clicker2-stm32/README.txt | 19 +++++++++++++------ 1 file changed, 13 insertions(+), 6 deletions(-) diff --git a/configs/clicker2-stm32/README.txt b/configs/clicker2-stm32/README.txt index f97be665d4..14046a208b 100644 --- a/configs/clicker2-stm32/README.txt +++ b/configs/clicker2-stm32/README.txt @@ -73,18 +73,25 @@ Buttons Using JTAG ========== - The Clicker2 comes with the mikroBootloader installed. But it also offers - a 2x5 JTAG connector. You may use Dupont jumpers to connect this port to - JTAG as described here: + The Clicker2 comes with the mikroBootloader installed. That bootloader + has not been used and is possibly incompatible with the Clicker2-STM32 + linker script at configs/clicker2-stm32/scripts/flash.ld. Often code must + be built to execute at an offset in to FLASH when a bootloader is used. + Certainly that is the case for the ST-Micro DFU bootloader but I am not + aware of the requirements for use with the mikroBootloader. + + JTAG has been used in the development of this board support. The + Clicker2-STM32 board offers a 2x5 JTAG connector. You may use Dupont + jumpers to connect this port to JTAG as described here: https://www.mikroe.com/how-to-use-st-link-v2-with-clicker-2-for-stm32-a-detailed-walkthrough/ http://www.playembedded.org/blog/en/2016/02/06/mikroe-clicker-2-for-stm32-and-stlink-v2/ NOTE that the FLASH is locked. You may need to follow the instructions at - the second link to unlock it (although I think you can do this with the ST-Micro - ST-Link Utility as well). + the second link to unlock it (although I think you may be able to do this + with the ST-Micro ST-Link Utility as well). - You can avoid the mess of jumpers using the mikroProg to ST-Link v2 adapte + You can avoid the mess of jumpers using the mikroProg to ST-Link v2 adapter along with a 2x5, 10-wire ribbon cable connector: https://shop.mikroe.com/add-on-boards/adapter/mikroprog-st-link-v2-adapter -- GitLab From c2a1b719be908673377454d5634a8d2e19bdbabf Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Thu, 23 Mar 2017 11:33:32 -1000 Subject: [PATCH 172/990] stm32_flash:Need conditinal on non F4 targets --- arch/arm/src/stm32/stm32_flash.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/arch/arm/src/stm32/stm32_flash.c b/arch/arm/src/stm32/stm32_flash.c index 8ba48a8262..3b4ebd8a10 100644 --- a/arch/arm/src/stm32/stm32_flash.c +++ b/arch/arm/src/stm32/stm32_flash.c @@ -128,6 +128,7 @@ static void flash_lock(void) modifyreg32(STM32_FLASH_CR, 0, FLASH_CR_LOCK); } +#if defined(CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW) static void data_cache_disable(void) { modifyreg32(STM32_FLASH_ACR, FLASH_ACR_DCEN, 0); @@ -143,6 +144,7 @@ static void data_cache_enable(void) modifyreg32(STM32_FLASH_ACR, 0, FLASH_ACR_DCEN); } +#endif /************************************************************************************ * Public Functions -- GitLab From f5cf22d871c04891a79f7e1059f739649b07b528 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Thu, 23 Mar 2017 11:36:44 -1000 Subject: [PATCH 173/990] stm32_i2c_alt:Duplicate non CS dev of regval --- arch/arm/src/stm32/stm32_i2c_alt.c | 1 - 1 file changed, 1 deletion(-) diff --git a/arch/arm/src/stm32/stm32_i2c_alt.c b/arch/arm/src/stm32/stm32_i2c_alt.c index 9112b08407..ca64656d8c 100644 --- a/arch/arm/src/stm32/stm32_i2c_alt.c +++ b/arch/arm/src/stm32/stm32_i2c_alt.c @@ -1867,7 +1867,6 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv) #else /* Clear all interrupts */ - uint32_t regval; regval = stm32_i2c_getreg(priv, STM32_I2C_CR2_OFFSET); regval &= ~I2C_CR2_ALLINTS; stm32_i2c_putreg(priv, STM32_I2C_CR2_OFFSET, regval); -- GitLab From d25f8710d2085fb05a348634fe44ef7c6f68a01e Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Thu, 23 Mar 2017 11:37:12 -1000 Subject: [PATCH 174/990] stm32f40xxx_i2c:Duplicate non CS dev of regval --- arch/arm/src/stm32/stm32f40xxx_i2c.c | 1 - 1 file changed, 1 deletion(-) diff --git a/arch/arm/src/stm32/stm32f40xxx_i2c.c b/arch/arm/src/stm32/stm32f40xxx_i2c.c index 3d7d5567f8..8d3a9fa84d 100644 --- a/arch/arm/src/stm32/stm32f40xxx_i2c.c +++ b/arch/arm/src/stm32/stm32f40xxx_i2c.c @@ -2015,7 +2015,6 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv) #else /* Clear all interrupts */ - uint32_t regval; regval = stm32_i2c_getreg(priv, STM32_I2C_CR2_OFFSET); regval &= ~I2C_CR2_ALLINTS; stm32_i2c_putreg(priv, STM32_I2C_CR2_OFFSET, regval); -- GitLab From 7e3bec635b3e9591569be75a933bc8139a03b443 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Thu, 23 Mar 2017 11:50:37 -1000 Subject: [PATCH 175/990] stm32_i2c_alt:Move def of regval to top func def per CS --- arch/arm/src/stm32/stm32_i2c_alt.c | 3 +++ 1 file changed, 3 insertions(+) diff --git a/arch/arm/src/stm32/stm32_i2c_alt.c b/arch/arm/src/stm32/stm32_i2c_alt.c index ca64656d8c..b115ce2795 100644 --- a/arch/arm/src/stm32/stm32_i2c_alt.c +++ b/arch/arm/src/stm32/stm32_i2c_alt.c @@ -1204,6 +1204,9 @@ static inline void stm32_i2c_enablefsmc(uint32_t ahbenr) static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv) { +#ifndef CONFIG_I2C_POLLED + uint32_t regval; +#endif uint32_t status; i2cinfo("I2C ISR called\n"); -- GitLab From 66910577beb4735b0e19ba72dd28be9c5594d91f Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Thu, 23 Mar 2017 14:22:45 -1000 Subject: [PATCH 176/990] stm322_flash:missing unlock on F1 HSI off path --- arch/arm/src/stm32/stm32_flash.c | 1 + 1 file changed, 1 insertion(+) diff --git a/arch/arm/src/stm32/stm32_flash.c b/arch/arm/src/stm32/stm32_flash.c index 3b4ebd8a10..3f079442d8 100644 --- a/arch/arm/src/stm32/stm32_flash.c +++ b/arch/arm/src/stm32/stm32_flash.c @@ -290,6 +290,7 @@ ssize_t up_progmem_erasepage(size_t page) #if !defined(CONFIG_STM32_STM32F40XX) if (!(getreg32(STM32_RCC_CR) & RCC_CR_HSION)) { + sem_unlock(); return -EPERM; } #endif -- GitLab From fd76a3db05d18989f1c49fb539b62ef3e22d8ae7 Mon Sep 17 00:00:00 2001 From: no1wudi <757509347@qq.com> Date: Fri, 24 Mar 2017 08:52:46 +0800 Subject: [PATCH 177/990] fix spacing --- arch/arm/src/stm32/stm32_flash.c | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/arch/arm/src/stm32/stm32_flash.c b/arch/arm/src/stm32/stm32_flash.c index 0267d58eb2..85a3fb1804 100644 --- a/arch/arm/src/stm32/stm32_flash.c +++ b/arch/arm/src/stm32/stm32_flash.c @@ -127,7 +127,6 @@ static void flash_lock(void) { modifyreg32(STM32_FLASH_CR, 0, FLASH_CR_LOCK); } -#if defined(CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW) #if defined(CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW) static void data_cache_disable(void) @@ -145,9 +144,8 @@ static void data_cache_enable(void) modifyreg32(STM32_FLASH_ACR, 0, FLASH_ACR_DCEN); } -#endif +#endif /* defined(CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW) */ -#endif /************************************************************************************ * Public Functions ************************************************************************************/ -- GitLab From 61ff3c6b8424b24eade7bbd522ad3b96ea0b7797 Mon Sep 17 00:00:00 2001 From: Alexander Oryshchenko Date: Fri, 24 Mar 2017 06:43:40 -0600 Subject: [PATCH 178/990] =?UTF-8?q?I=20needed=20to=20use=20DS3231,=C2=A0I?= =?UTF-8?q?=20remember=C2=A0that=C2=A0in=20past=20it=20worked=20ok,=20but?= =?UTF-8?q?=20now=20for=20stm32f4xx=20is=20used=20another=20driver=20(chip?= =?UTF-8?q?=20specific,=C2=A0stm32f40xxx=5Fi2c.c)=20and=20DS3231=20driver?= =?UTF-8?q?=20doesn't=20work.=20After=20investigating=20a=20problem=20I=20?= =?UTF-8?q?found=20that=20I2C=20driver=20(isr=20routine)=20has=20a=20few?= =?UTF-8?q?=20places=20there=20it=20sends=20stop=20bit=20even=20if=20not?= =?UTF-8?q?=20all=20messages=20are=20managed.=20So,=20e.g.,=20removing=20s?= =?UTF-8?q?tm32=5Fi2c=5Fsendstop=20(#1744)=20and=20adding=20stm32=5Fi2c=5F?= =?UTF-8?q?sendstart=20after=20data=20reading=20helps=20to=20make=20DS3231?= =?UTF-8?q?=20working.=20=20Verified=20by=20David=20Sidrane.?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- arch/arm/src/stm32/stm32f40xxx_i2c.c | 56 +++++++++++++++++++++++----- 1 file changed, 46 insertions(+), 10 deletions(-) diff --git a/arch/arm/src/stm32/stm32f40xxx_i2c.c b/arch/arm/src/stm32/stm32f40xxx_i2c.c index 8d3a9fa84d..12080928c2 100644 --- a/arch/arm/src/stm32/stm32f40xxx_i2c.c +++ b/arch/arm/src/stm32/stm32f40xxx_i2c.c @@ -1261,6 +1261,15 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv) priv->status = status; + /* Any new message should begin with "Start" condition + * Situation priv->msgc == 0 came from DMA RX handler and should be managed + */ + + if (priv->dcnt == -1 && priv->msgc != 0 && (status & I2C_SR1_SB) == 0) + { + return OK; + } + /* Check if this is a new transmission so to set up the * trace table accordingly. */ @@ -1516,9 +1525,16 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv) status |= (stm32_i2c_getreg(priv, STM32_I2C_SR2_OFFSET) << 16); - /* Send Stop */ + /* Send Stop/Restart */ - stm32_i2c_sendstop(priv); + if (priv->msgc > 0) + { + stm32_i2c_sendstart(priv); + } + else + { + stm32_i2c_sendstop(priv); + } i2cinfo("Address ACKed beginning data reception\n"); i2cinfo("short read N=1: programming stop bit\n"); @@ -1828,7 +1844,17 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv) { i2cinfo("short read N=2: DR and SR full setting stop bit and reading twice\n"); - stm32_i2c_sendstop(priv); + /* Send Stop/Restart */ + + if (priv->msgc > 0) + { + stm32_i2c_sendstart(priv); + } + else + { + stm32_i2c_sendstop(priv); + } + *priv->ptr++ = stm32_i2c_getreg(priv, STM32_I2C_DR_OFFSET); priv->dcnt--; *priv->ptr++ = stm32_i2c_getreg(priv, STM32_I2C_DR_OFFSET); @@ -1905,9 +1931,16 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv) stm32_i2c_traceevent(priv, I2CEVENT_READ_3, priv->dcnt); - /* Program stop */ + /* Program Stop/Restart */ - stm32_i2c_sendstop(priv); + if (priv->msgc > 0) + { + stm32_i2c_sendstart(priv); + } + else + { + stm32_i2c_sendstop(priv); + } /* read dcnt = 2 */ @@ -2061,7 +2094,14 @@ static void stm32_i2c_dmarxcallback(DMA_HANDLE handle, uint8_t status, void *arg * interrupt routine if enabled. */ - stm32_i2c_sendstop(priv); + if (priv->msgc > 0) + { + stm32_i2c_sendstart(priv); + } + else + { + stm32_i2c_sendstop(priv); + } /* Let the I2C periph know to stop DMA transfers, also is used by ISR to check * if DMA is done. @@ -2115,10 +2155,6 @@ static void stm32_i2c_dmatxcallback(DMA_HANDLE handle, uint8_t status, void *arg regval |= (I2C_CR2_ITERREN | I2C_CR2_ITEVFEN); stm32_i2c_putreg(priv, STM32_I2C_CR2_OFFSET, regval); #endif - - /* let the ISR routine take care of shutting down or switching to next msg */ - - stm32_i2c_isr(priv); } #endif /* ifdef CONFIG_STM32_I2C_DMA */ -- GitLab From f5926bd3305282c88e5e0f7f1f5ef4b6905518e0 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Fri, 24 Mar 2017 11:06:18 -0400 Subject: [PATCH 179/990] wireless/ieee802154: Adds ieee802154_addr_mode_e enumeration --- include/nuttx/wireless/ieee802154/ieee802154.h | 15 ++++++++++----- 1 file changed, 10 insertions(+), 5 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154.h b/include/nuttx/wireless/ieee802154/ieee802154.h index 1866b9db02..1b89748c1d 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154.h +++ b/include/nuttx/wireless/ieee802154/ieee802154.h @@ -69,14 +69,20 @@ struct ieee802154_packet_s * Extended address + PAN id : PPPP/LLLLLLLLLLLLLLLL */ +enum ieee802154_addr_mode_e { + IEEE802154_ADDRMODE_NONE = 0, + IEEE802154_ADDRMODE_SHORT = 2, + IEEE802154_ADDRMODE_EXTENDED +}; + struct ieee802154_addr_s { - uint8_t ia_len; /* structure length, 0/2/8 */ - uint16_t ia_panid; /* PAN identifier, can be IEEE802154_PAN_UNSPEC */ + enum ieee802154_addr_mode_e ia_mode; /* Address mode. Short or Extended */ + uint16_t ia_panid; /* PAN identifier, can be IEEE802154_PAN_UNSPEC */ union { - uint16_t _ia_saddr; /* short address */ - uint8_t _ia_eaddr[8]; /* extended address */ + uint16_t _ia_saddr; /* short address */ + uint8_t _ia_eaddr[8]; /* extended address */ } ia_addr; #define ia_saddr ia_addr._ia_saddr @@ -85,7 +91,6 @@ struct ieee802154_addr_s #define IEEE802154_ADDRSTRLEN 22 /* (2*2+1+8*2, PPPP/EEEEEEEEEEEEEEEE) */ - #ifdef __cplusplus #define EXTERN extern "C" extern "C" -- GitLab From a702d6b6381c0e6c1b5aa137d45f369713197eea Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Fri, 24 Mar 2017 11:06:59 -0400 Subject: [PATCH 180/990] wireless/ieee802154: Fixes build and configuration setup --- wireless/ieee802154/Kconfig | 6 +++--- wireless/ieee802154/Make.defs | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/wireless/ieee802154/Kconfig b/wireless/ieee802154/Kconfig index 638f887cab..770bbe0381 100644 --- a/wireless/ieee802154/Kconfig +++ b/wireless/ieee802154/Kconfig @@ -10,12 +10,12 @@ config WIRELESS_IEEE802154 ---help--- Enables support for the IEEE 802.14.5 Wireless library. -if IEEE802154 +if WIRELESS_IEEE802154 config IEEE802154_MAC bool "Generic Media Access Control layer for 802.15.4 radios" default n - depends on IEEE802154 + depends on WIRELESS_IEEE802154 ---help--- Enables a Media Access Controller for any IEEE802.15.4 radio device. This in turn can be used by higher layer entities @@ -25,7 +25,7 @@ config IEEE802154_MAC config IEEE802154_DEV bool "Debug character driver for ieee802.15.4 radio interfaces" default n - depends on IEEE802154 + depends on WIRELESS_IEEE802154 ---help--- Enables a device driver to expose ieee802.15.4 radio controls to user space as IOCTLs. diff --git a/wireless/ieee802154/Make.defs b/wireless/ieee802154/Make.defs index 42856a85ab..5d54b0004d 100644 --- a/wireless/ieee802154/Make.defs +++ b/wireless/ieee802154/Make.defs @@ -45,7 +45,7 @@ CSRCS += ieee802154/mac802154.c endif ifeq ($(CONFIG_IEEE802154_DEV),y) -CSRCS += ieee802154/ieee802154_device.c +CSRCS += ieee802154/radio802154_device.c endif DEPPATH += --dep-path wireless/ieee802154 -- GitLab From 7a95cc62b4dc8a42c5b81c226bedc80d3577f475 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Fri, 24 Mar 2017 11:08:31 -0400 Subject: [PATCH 181/990] wireless/ieee802154: Moves and renames MAC preprocessor definitions --- .../wireless/ieee802154/ieee802154_mac.h | 452 ++++++++++++++---- wireless/ieee802154/mac802154.c | 20 +- 2 files changed, 370 insertions(+), 102 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index d39aa887cb..992b03e0e8 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -41,9 +41,13 @@ ****************************************************************************/ #include + #include #include +#include +#include + /**************************************************************************** * Pre-Processor Definitions ****************************************************************************/ @@ -51,8 +55,63 @@ /* Configuration ************************************************************/ /* None at the moment */ + +/* IEEE 802.15.4 MAC Character Driver IOCTL Commands ************************/ + +/* The IEEE 802.15.4 standard specifies a MLME Service Access Point (SAP) + * including a series of primitives that are used as an interface between + * the MLME and the next highest layer. There are 4 types of primitives: + * - Request + * - Indication + * - Response + * - Confirm + * + * Of these, Request and Response primitives are sent from the next highest layer + * to the MLME. Indication and Confirm primitives are used to notify the next + * highest layer of changes or actions that have taken place. + * + * The MAC802154 character driver exposed here provides IOCTL hooks for all + * Request and Response primitives. + */ + +#define MAC802154IOC_MLME_ASSOC_REQUEST _MAC802154IOC(0x0001) +#define MAC802154IOC_MLME_ASSOC_RESPONSE _MAC802154IOC(0x0002) +#define MAC802154IOC_MLME_DISASSOC_REQUEST _MAC802154IOC(0x0003) +#define MAC802154IOC_MLME_GET_REQUEST _MAC802154IOC(0x0004) +#define MAC802154IOC_MLME_GTS_REQUEST _MAC802154IOC(0x0005) +#define MAC802154IOC_MLME_ORPHAN_RESPONSE _MAC802154IOC(0x0006) +#define MAC802154IOC_MLME_RESET_REQUEST _MAC802154IOC(0x0007) +#define MAC802154IOC_MLME_RXENABLE_REQUEST _MAC802154IOC(0x0008) +#define MAC802154IOC_MLME_SCAN_REQUEST _MAC802154IOC(0x0009) +#define MAC802154IOC_MLME_SET_REQUEST _MAC802154IOC(0x000A) +#define MAC802154IOC_MLME_START_REQUEST _MAC802154IOC(0x000B) +#define MAC802154IOC_MLME_SYNC_REQUEST _MAC802154IOC(0x000C) +#define MAC802154IOC_MLME_POLL_REQUEST _MAC802154IOC(0x000D) +#define MAC802154IOC_MLME_DPS_REQUEST _MAC802154IOC(0x000E) +#define MAC802154IOC_MLME_SOUNDING_REQUEST _MAC802154IOC(0x000F) +#define MAC802154IOC_MLME_CALIBRATE_REQUEST _MAC802154IOC(0x0010) + /* IEEE 802.15.4 MAC Interface **********************************************/ +/* Frame Type */ + +#define IEEE802154_FRAME_BEACON 0x00 +#define IEEE802154_FRAME_DATA 0x01 +#define IEEE802154_FRAME_ACK 0x02 +#define IEEE802154_FRAME_COMMAND 0x03 + +/* MAC commands */ + +#define IEEE802154_CMD_ASSOC_REQ 0x01 +#define IEEE802154_CMD_ASSOC_RSP 0x02 +#define IEEE802154_CMD_DISASSOC_NOT 0x03 +#define IEEE802154_CMD_DATA_REQ 0x04 +#define IEEE802154_CMD_PANID_CONF_NOT 0x05 +#define IEEE802154_CMD_ORPHAN_NOT 0x06 +#define IEEE802154_CMD_BEACON_REQ 0x07 +#define IEEE802154_CMD_COORD_REALIGN 0x08 +#define IEEE802154_CMD_GTS_REQ 0x09 + /* Some addresses */ #define IEEE802154_PAN_UNSPEC (uint16_t)0xFFFF @@ -60,31 +119,53 @@ #define IEEE802154_SADDR_BCAST (uint16_t)0xFFFE #define IEEE802154_EADDR_UNSPEC (uint8_t*)"\xff\xff\xff\xff\xff\xff\xff\xff" +/* Frame control field masks, 2 bytes + * Seee IEEE 802.15.4/2011 5.2.1.1 page 57 + */ + +#define IEEE802154_FRAMECTRL_FTYPE 0x0007 /* Frame type, bits 0-2 */ +#define IEEE802154_FRAMECTRL_SEC 0x0008 /* Security Enabled, bit 3 */ +#define IEEE802154_FRAMECTRL_PEND 0x0010 /* Frame pending, bit 4 */ +#define IEEE802154_FRAMECTRL_ACKREQ 0x0020 /* Acknowledge request, bit 5 */ +#define IEEE802154_FRAMECTRL_INTRA 0x0040 /* Intra PAN, bit 6 */ +#define IEEE802154_FRAMECTRL_DADDR 0x0C00 /* Dest addressing mode, bits 10-11 */ +#define IEEE802154_FRAMECTRL_VERSION 0x3000 /* Source addressing mode, bits 12-13 */ +#define IEEE802154_FRAMECTRL_SADDR 0xC000 /* Source addressing mode, bits 14-15 */ + +#define IEEE802154_FRAMECTRL_SHIFT_FTYPE 0 /* Frame type, bits 0-2 */ +#define IEEE802154_FRAMECTRL_SHIFT_SEC 3 /* Security Enabled, bit 3 */ +#define IEEE802154_FRAMECTRL_SHIFT_PEND 4 /* Frame pending, bit 4 */ +#define IEEE802154_FRAMECTRL_SHIFT_ACKREQ 5 /* Acknowledge request, bit 5 */ +#define IEEE802154_FRAMECTRL_SHIFT_INTRA 6 /* Intra PAN, bit 6 */ +#define IEEE802154_FRAMECTRL_SHIFT_DADDR 10 /* Dest addressing mode, bits 10-11 */ +#define IEEE802154_FRAMECTRL_SHIFT_VERSION 12 /* Source addressing mode, bits 12-13 */ +#define IEEE802154_FRAMECTRL_SHIFT_SADDR 14 /* Source addressing mode, bits 14-15 */ + /* IEEE 802.15.4 PHY constants */ -#define MAC802154_aMaxPHYPacketSize 127 -#define MAC802154_aTurnaroundTime 12 /*symbol periods*/ +#define IEEE802154_aMaxPHYPacketSize 127 +#define IEEE802154_aTurnaroundTime 12 /*symbol periods*/ /* IEEE 802.15.4 MAC constants */ -#define MAC802154_aBaseSlotDuration 60 -#define MAC802154_aNumSuperframeSlots 16 -#define MAC802154_aBaseSuperframeDuration (MAC802154_aBaseSlotDuration * MAC802154_aNumSuperframeSlots) -#define MAC802154_aMaxBE 5 -#define MAC802154_aMaxBeaconOverhead 75 -#define MAC802154_aMaxBeaconPayloadLength (MAC802154_aMaxPHYPacketSize - MAC802154_aMaxBeaconOverhead) -#define MAC802154_aGTSDescPersistenceTime 4 -#define MAC802154_aMaxFrameOverhead 25 -#define MAC802154_aMaxFrameResponseTime 1220 -#define MAC802154_aMaxFrameRetries 3 -#define MAC802154_aMaxLostBeacons 4 -#define MAC802154_aMaxMACFrameSize (MAC802154_aMaxPHYPacketSize - MAC802154_aMaxFrameOverhead) -#define MAC802154_aMaxSIFSFrameSize 18 -#define MAC802154_aMinCAPLength 440 -#define MAC802154_aMinLIFSPeriod 40 -#define MAC802154_aMinSIFSPeriod 12 -#define MAC802154_aResponseWaitTime (32 * MAC802154_aBaseSuperframeDuration) -#define MAC802154_aUnitBackoffPeriod 20 +#define IEEE802154_aBaseSlotDuration 60 +#define IEEE802154_aNumSuperframeSlots 16 +#define IEEE802154_aBaseSuperframeDuration (IEEE802154_aBaseSlotDuration * IEEE802154_aNumSuperframeSlots) +#define IEEE802154_aMaxBE 5 +#define IEEE802154_aMaxBeaconOverhead 75 +#define IEEE802154_aMaxBeaconPayloadLength (IEEE802154_aMaxPHYPacketSize - IEEE802154_aMaxBeaconOverhead) +#define IEEE802154_aGTSDescPersistenceTime 4 +#define IEEE802154_aMaxFrameOverhead 25 +#define IEEE802154_aMaxFrameResponseTime 1220 +#define IEEE802154_aMaxFrameRetries 3 +#define IEEE802154_aMaxLostBeacons 4 +#define IEEE802154_aMaxMACFrameSize (IEEE802154_aMaxPHYPacketSize - IEEE802154_aMaxFrameOverhead) +#define IEEE802154_aMaxSIFSFrameSize 18 +#define IEEE802154_aMinCAPLength 440 +#define IEEE802154_aMinLIFSPeriod 40 +#define IEEE802154_aMinSIFSPeriod 12 +#define IEEE802154_aResponseWaitTime (32 * IEEE802154_aBaseSuperframeDuration) +#define IEEE802154_aUnitBackoffPeriod 20 /**************************************************************************** * Public Types @@ -92,74 +173,279 @@ /* IEEE 802.15.4 MAC status codes */ -enum +enum ieee802154_status_e { - MAC802154_STATUS_OK = 0, - MAC802154_STATUS_BEACON_LOSS = 0xE0, - MAC802154_STATUS_CHANNEL_ACCESS_FAILURE, - MAC802154_STATUS_DENIED, - MAC802154_STATUS_DISABLE_TRX_FAILURE, - MAC802154_STATUS_FAILED_SECURITY_CHECK, - MAC802154_STATUS_FRAME_TOO_LONG, - MAC802154_STATUS_INVALID_GTS, - MAC802154_STATUS_INVALID_HANDLE, - MAC802154_STATUS_INVALID_PARAMETER, - MAC802154_STATUS_NO_ACK, - MAC802154_STATUS_NO_BEACON, - MAC802154_STATUS_NO_DATA, - MAC802154_STATUS_NO_SHORT_ADDRESS, - MAC802154_STATUS_OUT_OF_CAP, - MAC802154_STATUS_PAN_ID_CONFLICT, - MAC802154_STATUS_REALIGNMENT, - MAC802154_STATUS_TRANSACTION_EXPIRED, - MAC802154_STATUS_TRANSACTION_OVERFLOW, - MAC802154_STATUS_TX_ACTIVE, - MAC802154_STATUS_UNAVAILABLE_KEY, - MAC802154_STATUS_UNSUPPORTED_ATTRIBUTE + IEEE802154_STATUS_OK = 0, + IEEE802154_STATUS_BEACON_LOSS = 0xE0, + IEEE802154_STATUS_CHANNEL_ACCESS_FAILURE, + IEEE802154_STATUS_DENIED, + IEEE802154_STATUS_DISABLE_TRX_FAILURE, + IEEE802154_STATUS_FAILED_SECURITY_CHECK, + IEEE802154_STATUS_FRAME_TOO_LONG, + IEEE802154_STATUS_INVALID_GTS, + IEEE802154_STATUS_INVALID_HANDLE, + IEEE802154_STATUS_INVALID_PARAMETER, + IEEE802154_STATUS_NO_ACK, + IEEE802154_STATUS_NO_BEACON, + IEEE802154_STATUS_NO_DATA, + IEEE802154_STATUS_NO_SHORT_ADDRESS, + IEEE802154_STATUS_OUT_OF_CAP, + IEEE802154_STATUS_PAN_ID_CONFLICT, + IEEE802154_STATUS_REALIGNMENT, + IEEE802154_STATUS_TRANSACTION_EXPIRED, + IEEE802154_STATUS_TRANSACTION_OVERFLOW, + IEEE802154_STATUS_TX_ACTIVE, + IEEE802154_STATUS_UNAVAILABLE_KEY, + IEEE802154_STATUS_UNSUPPORTED_ATTRIBUTE }; /* IEEE 802.15.4 PHY/MAC PIB attributes IDs */ enum { - MAC802154_phyCurrentChannel = 0x00, - MAC802154_phyChannelsSupported, - MAC802154_phyTransmitPower, - MAC802154_phyCCAMode, - MAC802154_macAckWaitDuration = 0x40, - MAC802154_macAssociationPermit, - MAC802154_macAutoRequest, - MAC802154_macBattLifeExt, - MAC802154_macBattLifeExtPeriods, - MAC802154_macBeaconPayload, - MAC802154_macBeaconPayloadLength, - MAC802154_macBeaconOrder, - MAC802154_macBeaconTxTime, - MAC802154_macBSN, - MAC802154_macCoordExtendedAddress, - MAC802154_macCoordShortAddress, - MAC802154_macDSN, - MAC802154_macGTSPermit, - MAC802154_macMaxCSMABackoffs, - MAC802154_macMinBE, - MAC802154_macPANId, - MAC802154_macPromiscuousMode, - MAC802154_macRxOnWhenIdle, - MAC802154_macShortAddress, - MAC802154_macSuperframeOrder, - MAC802154_macTransactionPersistenceTime, - MAC802154_macACLEntryDescriptorSet = 0x70, - MAC802154_macACLEntryDescriptorSetSize, - MAC802154_macDefaultSecurity, - MAC802154_macDefaultSecurityMaterialLength, - MAC802154_macDefaultSecurityMaterial, - MAC802154_macDefaultSecuritySuite, - MAC802154_macSecurityMode + IEEE802154_phyCurrentChannel = 0x00, + IEEE802154_phyChannelsSupported, + IEEE802154_phyTransmitPower, + IEEE802154_phyCCAMode, + IEEE802154_macAckWaitDuration = 0x40, + IEEE802154_macAssociationPermit, + IEEE802154_macAutoRequest, + IEEE802154_macBattLifeExt, + IEEE802154_macBattLifeExtPeriods, + IEEE802154_macBeaconPayload, + IEEE802154_macBeaconPayloadLength, + IEEE802154_macBeaconOrder, + IEEE802154_macBeaconTxTime, + IEEE802154_macBSN, + IEEE802154_macCoordExtendedAddress, + IEEE802154_macCoordShortAddress, + IEEE802154_macDSN, + IEEE802154_macGTSPermit, + IEEE802154_macMaxCSMABackoffs, + IEEE802154_macMinBE, + IEEE802154_macPANId, + IEEE802154_macPromiscuousMode, + IEEE802154_macRxOnWhenIdle, + IEEE802154_macShortAddress, + IEEE802154_macSuperframeOrder, + IEEE802154_macTransactionPersistenceTime, + IEEE802154_macACLEntryDescriptorSet = 0x70, + IEEE802154_macACLEntryDescriptorSetSize, + IEEE802154_macDefaultSecurity, + IEEE802154_macDefaultSecurityMaterialLength, + IEEE802154_macDefaultSecurityMaterial, + IEEE802154_macDefaultSecuritySuite, + IEEE802154_macSecurityMode }; -/**************************************************************************** - * Public Types - ****************************************************************************/ +struct ieee802154_capability_info_s +{ + uint8_t reserved_0 : 1; /* Reserved */ + uint8_t device_type : 1; /* 0=RFD, 1=FFD */ + uint8_t power_source : 1; /* 1=AC, 0=Other */ + uint8_t rx_on_idle : 1; /* 0=Receiver off when idle + * 1=Receiver on when idle */ + uint8_t reserved_45 : 2; /* Reserved */ + uint8_t security : 1; /* 0=disabled, 1=enabled */ + uint8_t allocate_addr : 1; /* 1=Coordinator allocates short address + * 0=otherwise */ +}; + +#ifdef CONFIG_IEEE802154_SECURITY +struct ieee802154_security_s +{ + uint8_t level; /* Security level to be used */ + uint8_t key_id_mode; /* Mode used to identify the key to be used */ + uint8_t key_source[8]; /* Originator of the key to be used */ + uint8_t key_index; /* Index of the key to be used */ +}; +#endif + +struct ieee802154_superframe_spec_s +{ + uint16_t beacon_order : 4; /* Transmission interval of beacon */ + uint16_t superframe_order : 4; /* Length of superframe */ + uint16_t final_cap_slot : 4; /* Last slot utilized by CAP */ + uint16_t ble : 1; /* Battery Life Extension (BLE) */ + uint16_t reserved : 1; /* Reserved bit */ + uint16_t pan_coordinator : 1; /* 1 if beacon sent by pan coordinator */ + uint16_t assoc_permit : 1; /* 1 if coordinator is accepting associaton */ +}; + +struct ieee802154_pan_desc_s +{ + /* The coordinator address of the received beacon frame */ + + struct ieee802154_addr_s coord_addr; + + uint8_t channel; /* current channel occupied by the network */ + uint8_t channel_page; /* current channel page occupied by the network */ + + /* The superframe specifications received in the beacon frame */ + + struct ieee802154_superframe_spec_s superframe_spec; + + uint8_t gts_permit; /* 0=No GTS requests allowed + * 1=GTS request allowed */ + uint8_t link_quality; /* LQI at which beacon was received */ + uint32_t timestamp; /* Time at which the beacon frame was received + * in symbols */ +}; + +struct ieee802154_pend_addr_s +{ + union { + uint8_t pa_spec; + struct { + uint8_t num_short_addr : 3; /* Number of short addresses pending */ + uint8_t reserved_3 : 1; /* Reserved bit */ + uint8_t num_ext_addr : 3; /* Number of extended addresses pending */ + uint8_t reserved_7 : 1; /* Reserved bit */ + }; + }; + struct ieee802154_addr_s addr[7]; /* Array of at most 7 addresses */ +}; + +/* Primitive Semantics */ + +struct ieee802154_assoc_request_s +{ + uint8_t channel; /* Channel number to attempt association */ + uint8_t channel_page; /* Channel page to attempt association */ + + /* Coordinator Address with which to associate */ + + struct ieee802154_addr_s coord_addr; + + /* Capabilities of associating device */ + + struct ieee802154_capability_info_s capabilities; + +#ifdef CONFIG_IEEE802154_SECURITY + /* Security information if enabled */ + + struct ieee802154_security_s security; +#endif +}; + +struct ieee802154_assoc_indication_s +{ + /* Address of device requesting association. Always in extended mode */ + + struct ieee802154_addr_s dev_addr; + + /* Capabilities of associating device */ + + struct ieee802154_capability_info_s capabilities; + +#ifdef CONFIG_IEEE802154_SECURITY + /* Security information if enabled */ + + struct ieee802154_security_s security; +#endif +}; + +struct ieee802154_assoc_response_s +{ + /* Address of device requesting association. Always in extended mode */ + + struct ieee802154_addr_s dev_addr; + + /* Status of association attempt */ + + enum ieee802154_status_e status; + +#ifdef CONFIG_IEEE802154_SECURITY + /* Security information if enabled */ + + struct ieee802154_security_s security; +#endif +}; + +struct ieee802154_assoc_confirm_s +{ + /* Associated device address ALWAYS passed in short address mode. The + * address will be IEEE802154_SADDR_UNSPEC if association was unsuccessful */ + + struct ieee802154_addr_s dev_addr; + + /* Status of association attempt */ + + enum ieee802154_status_e status; + +#ifdef CONFIG_IEEE802154_SECURITY + /* Security information if enabled */ + + struct ieee802154_security_s security; +#endif +}; + +struct ieee802154_disassoc_request_s +{ + /* Address of device to send disassociation notification */ + + struct ieee802154_addr_s dev_addr; + + /* Reason for the disassosiation */ + + enum ieee802154_status_e disassoc_reason; + + uint8_t tx_indirect; /* 0=Send Direct, 1=Send Indirect */ + +#ifdef CONFIG_IEEE802154_SECURITY + /* Security information if enabled */ + + struct ieee802154_security_s security; +#endif +}; + +struct ieee802154_disassoc_indication_s +{ + /* Address of device requesting disassociation. Always extended mode */ + + struct ieee802154_addr_s dev_addr; + + /* Reason for the disassosiation */ + + enum ieee802154_status_e disassoc_reason; + +#ifdef CONFIG_IEEE802154_SECURITY + /* Security information if enabled */ + + struct ieee802154_security_s security; +#endif +}; + +struct ieee802154_disassoc_confirm_s +{ + /* Status of the disassociation attempt */ + + enum ieee802154_status_e status; + + /* Address of device either requesting or being intructed to disassociate */ + + struct ieee802154_addr_s dev_addr; +}; + +struct ieee802154_beaconnotify_indication_s +{ + uint8_t bsn; /* Beacon sequence number */ + + /* PAN descriptor for the received beacon */ + + struct ieee802154_pan_desc_s pan_desc; + + /* Beacon pending addresses */ + + struct ieee802154_pend_addr_s pend_addr; + + uint8_t sdu_length; /* Number of octets contained in the beacon + * payload of the received beacond frame */ + + /* Beacon payload */ + + uint8_t sdu[IEEE802154_aMaxBeaconPayloadLength]; +}; /* Operations */ @@ -180,13 +466,13 @@ struct ieee802154_macops_s /* Start association with coordinator */ - CODE int (*req_associate)(FAR struct ieee802154_mac_s *mac, uint16_t panid, - uint8_t *coordeadr); + CODE int (*req_associate)(FAR struct ieee802154_mac_s *mac, + FAR struct ieee802154_assoc_request_s *request); /* Start disassociation with coordinator */ CODE int (*req_disassociate)(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *eadr, uint8_t reason); + FAR struct ieee802154_disassoc_request_s *request); /* Read the PIB */ @@ -314,7 +600,7 @@ struct ieee802154_maccb_s /* Beacon notification */ CODE int (*ind_beaconnotify)(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *bsn, FAR uint_t *pandesc, + FAR uint8_t *bsn, FAR struct ieee802154_pan_desc_s *pandesc, FAR uint8_t *sdu, int sdulen); /* GTS management request received */ diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index cfa199d54b..da4a711910 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -48,24 +48,6 @@ * Pre-processor Definitions ****************************************************************************/ -/* Frame Type */ - -#define IEEE802154_FRAME_BEACON 0x00 -#define IEEE802154_FRAME_DATA 0x01 -#define IEEE802154_FRAME_ACK 0x02 -#define IEEE802154_FRAME_COMMAND 0x03 - -/* MAC commands */ - -#define IEEE802154_CMD_ASSOC_REQ 0x01 -#define IEEE802154_CMD_ASSOC_RSP 0x02 -#define IEEE802154_CMD_DIS_NOT 0x03 -#define IEEE802154_CMD_DATA_REQ 0x04 -#define IEEE802154_CMD_PANID_CONF_NOT 0x05 -#define IEEE802154_CMD_ORPHAN_NOT 0x06 -#define IEEE802154_CMD_BEACON_REQ 0x07 -#define IEEE802154_CMD_COORD_REALIGN 0x08 -#define IEEE802154_CMD_GTS_REQ 0x09 /**************************************************************************** * Private Types @@ -97,7 +79,7 @@ struct ieee802154_privmac_s uint32_t macPad : 3; /* 0x48 */ uint32_t macBeaconTxTime : 24; - /* 0x45 */ uint8_t macBeaconPayload[MAC802154_aMaxBeaconPayloadLength]; + /* 0x45 */ uint8_t macBeaconPayload[IEEE802154_aMaxBeaconPayloadLength]; /* 0x46 */ uint8_t macBeaconPayloadLength; /* 0x49 */ uint8_t macBSN; /* 0x4A */ uint8_t macCoordExtendedAddress[8]; -- GitLab From 10d7baca10a98805f6c0388023239747930e2861 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Fri, 24 Mar 2017 11:09:18 -0400 Subject: [PATCH 182/990] wireless/ieee802154: Adds IOCTL definitions for accessing PHY layer --- .../wireless/ieee802154/ieee802154_radio.h | 40 +++++++++++++++---- wireless/ieee802154/radio802154_device.c | 37 +++++++++-------- 2 files changed, 50 insertions(+), 27 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_radio.h b/include/nuttx/wireless/ieee802154/ieee802154_radio.h index 3e64aa5c60..f87c2010c2 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_radio.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_radio.h @@ -2,7 +2,9 @@ * include/nuttx/wireless/ieee802154/ieee802154_radio.h * * Copyright (C) 2014-2016 Sebastien Lorquet. All rights reserved. + * Copyright (C) 2017 Verge Inc. All rights reserved. * Author: Sebastien Lorquet + * Author: Anthony Merlino * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -44,6 +46,8 @@ #include #include #include +#include +#include /**************************************************************************** * Pre-Processor Definitions @@ -62,18 +66,38 @@ #define IEEE802154_MODE_COORD 0x01 /* avail in mrf24j40, but why? */ #define IEEE802154_MODE_PANCOORD 0x02 +/* IEEE 802.15.4 Radio Character Driver IOCTL ********************************/ + +#define PHY802154IOC_SET_CHAN _PHY802154IOC(0x0001) +#define PHY802154IOC_GET_CHAN _PHY802154IOC(0x0002) + +#define PHY802154IOC_SET_PANID _PHY802154IOC(0x0003) +#define PHY802154IOC_GET_PANID _PHY802154IOC(0x0004) + +#define PHY802154IOC_SET_SADDR _PHY802154IOC(0x0005) +#define PHY802154IOC_GET_SADDR _PHY802154IOC(0x0006) + +#define PHY802154IOC_SET_EADDR _PHY802154IOC(0x0007) +#define PHY802154IOC_GET_EADDR _PHY802154IOC(0x0008) + +#define PHY802154IOC_SET_PROMISC _PHY802154IOC(0x0009) +#define PHY802154IOC_GET_PROMISC _PHY802154IOC(0x000A) + +#define PHY802154IOC_SET_DEVMODE _PHY802154IOC(0x000B) +#define PHY802154IOC_GET_DEVMODE _PHY802154IOC(0x000C) + +#define PHY802154IOC_SET_TXPWR _PHY802154IOC(0x000D) +#define PHY802154IOC_GET_TXPWR _PHY802154IOC(0x000E) + +#define PHY802154IOC_SET_CCA _PHY802154IOC(0x000F) +#define PHY802154IOC_GET_CCA _PHY802154IOC(0x0010) + +#define PHY802154IOC_ENERGYDETECT _PHY802154IOC(0x0011) + /**************************************************************************** * Public Types ****************************************************************************/ -struct ieee802154_packet_s -{ - uint8_t len; - uint8_t data[127]; - uint8_t lqi; - uint8_t rssi; -}; - struct ieee802154_cca_s { uint8_t use_ed : 1; /* CCA using ED */ diff --git a/wireless/ieee802154/radio802154_device.c b/wireless/ieee802154/radio802154_device.c index 2bab563e5b..a3a4161ffc 100644 --- a/wireless/ieee802154/radio802154_device.c +++ b/wireless/ieee802154/radio802154_device.c @@ -51,7 +51,6 @@ #include #include #include -#include /**************************************************************************** * Private Types @@ -383,78 +382,78 @@ static int radio802154dev_ioctl(FAR struct file *filep, int cmd, DEBUGASSERT(filep != NULL && filep->f_inode != NULL); inode = filep->f_inode; dev = inode->i_private; - DEBUGASSERT(dev != NULL && dev->child != NULL; + DEBUGASSERT(dev != NULL && dev->child != NULL); child = dev->child; /* Get exclusive access to the driver data structures */ switch (cmd) { - case MAC854IOCSCHAN: + case PHY802154IOC_SET_CHAN: ret = child->ops->setchannel(child, (uint8_t)arg); break; - case MAC854IOCGCHAN: + case PHY802154IOC_GET_CHAN: ret = child->ops->getchannel(child, (FAR uint8_t*)arg); break; - case MAC854IOCSPANID: + case PHY802154IOC_SET_PANID: ret = child->ops->setpanid(child, (uint16_t)arg); break; - case MAC854IOCGPANID: + case PHY802154IOC_GET_PANID: ret = child->ops->getpanid(child, (FAR uint16_t*)arg); break; - case MAC854IOCSSADDR: + case PHY802154IOC_SET_SADDR: ret = child->ops->setsaddr(child, (uint16_t)arg); break; - case MAC854IOCGSADDR: + case PHY802154IOC_GET_SADDR: ret = child->ops->getsaddr(child, (FAR uint16_t*)arg); break; - case MAC854IOCSEADDR: + case PHY802154IOC_SET_EADDR: ret = child->ops->seteaddr(child, (FAR uint8_t*)arg); break; - case MAC854IOCGEADDR: + case PHY802154IOC_GET_EADDR: ret = child->ops->geteaddr(child, (FAR uint8_t*)arg); break; - case MAC854IOCSPROMISC: + case PHY802154IOC_SET_PROMISC: ret = child->ops->setpromisc(child, (bool)arg); break; - case MAC854IOCGPROMISC: + case PHY802154IOC_GET_PROMISC: ret = child->ops->getpromisc(child, (FAR bool*)arg); break; - case MAC854IOCSDEVMODE: + case PHY802154IOC_SET_DEVMODE: ret = child->ops->setdevmode(child, (uint8_t)arg); break; - case MAC854IOCGDEVMODE: + case PHY802154IOC_GET_DEVMODE: ret = child->ops->getdevmode(child, (FAR uint8_t*)arg); break; - case MAC854IOCSTXP: + case PHY802154IOC_SET_TXPWR: ret = child->ops->settxpower(child, (int32_t)arg); break; - case MAC854IOCGTXP: + case PHY802154IOC_GET_TXPWR: ret = child->ops->gettxpower(child, (FAR int32_t*)arg); break; - case MAC854IOCSCCA: + case PHY802154IOC_SET_CCA: ret = child->ops->setcca(child, (FAR struct ieee802154_cca_s*)arg); break; - case MAC854IOCGCCA: + case PHY802154IOC_GET_CCA: ret = child->ops->getcca(child, (FAR struct ieee802154_cca_s*)arg); break; - case MAC854IOCGED: + case PHY802154IOC_ENERGYDETECT: ret = child->ops->energydetect(child, (FAR uint8_t*)arg); break; -- GitLab From 73888166293a42e3ee9e488671c7185cf8260adc Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Fri, 24 Mar 2017 11:10:35 -0400 Subject: [PATCH 183/990] drivers/ieee802154: Moves defines to MAC layer and adjusts some addressing functionality --- drivers/wireless/ieee802154/mrf24j40.c | 72 +++++--------------------- 1 file changed, 13 insertions(+), 59 deletions(-) diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c index 4cb4ed9934..c4c353ce00 100644 --- a/drivers/wireless/ieee802154/mrf24j40.c +++ b/drivers/wireless/ieee802154/mrf24j40.c @@ -57,6 +57,7 @@ #include #include +#include #include "mrf24j40.h" @@ -92,44 +93,6 @@ #define MRF24J40_PA_ED 2 #define MRF24J40_PA_SLEEP 3 -/* IEEE 802.15.4 frame specifics */ - -/* Security Enabled */ - -#define IEEE802154_SEC_OFF 0x00 -#define IEEE802154_SEC_ON 0x08 - -/* Flags */ - -#define IEEE802154_PEND 0x10 -#define IEEE802154_ACK_REQ 0x20 -#define IEEE802154_INTRA 0x40 - -/* Dest Addressing modes */ - -#define IEEE802154_DADDR_NONE 0x00 -#define IEEE802154_DADDR_SHORT 0x08 -#define IEEE802154_DADDR_EXT 0x0A - -/* Src Addressing modes */ - -#define IEEE802154_SADDR_NONE 0x00 -#define IEEE802154_SADDR_SHORT 0x80 -#define IEEE802154_SADDR_EXT 0xA0 - -/* Frame control field masks, 2 bytes - * Seee IEEE 802.15.4/2003 7.2.1.1 page 112 - */ - -#define IEEE802154_FC1_FTYPE 0x03 /* Frame type, bits 0-2 */ -#define IEEE802154_FC1_SEC 0x08 /* Security Enabled, bit 3 */ -#define IEEE802154_FC1_PEND 0x10 /* Frame pending, bit 4 */ -#define IEEE802154_FC1_ACKREQ 0x20 /* Acknowledge request, bit 5 */ -#define IEEE802154_FC1_INTRA 0x40 /* Intra PAN, bit 6 */ -#define IEEE802154_FC2_DADDR 0x0C /* Dest addressing mode, bits 10-11 */ -#define IEEE802154_FC2_VERSION 0x30 /* Source addressing mode, bits 12-13 */ -#define IEEE802154_FC2_SADDR 0xC0 /* Source addressing mode, bits 14-15 */ - /**************************************************************************** * Private Types ****************************************************************************/ @@ -1110,7 +1073,7 @@ static int mrf24j40_transmit(FAR struct ieee802154_radio_s *ieee, uint8_t reg; int ret; int hlen = 3; /* Include frame control and seq number */ - uint8_t fc1, fc2; + uint16_t frame_ctrl; mrf24j40_pacontrol(dev, MRF24J40_PA_AUTO); @@ -1124,41 +1087,32 @@ static int mrf24j40_transmit(FAR struct ieee802154_radio_s *ieee, /* Analyze frame control to compute header length */ - fc1 = packet->data[0]; - fc2 = packet->data[1]; - - //wlinfo("fc1 %02X fc2 %02X\n", fc1,fc2); + frame_ctrl = packet->data[0]; + frame_ctrl |= packet->data[1] << 8; - if ((fc2 & IEEE802154_FC2_DADDR) == IEEE802154_DADDR_SHORT) + if ((frame_ctrl & IEEE802154_FRAMECTRL_DADDR)== IEEE802154_ADDRMODE_SHORT) { hlen += 2 + 2; /* Destination PAN + shortaddr */ } - else if ((fc2 & IEEE802154_FC2_DADDR) == IEEE802154_DADDR_EXT) + else if ((frame_ctrl & IEEE802154_FRAMECTRL_DADDR) == IEEE802154_ADDRMODE_EXTENDED) { hlen += 2 + 8; /* Destination PAN + extaddr */ } - if ((fc2 & IEEE802154_FC2_SADDR) == IEEE802154_SADDR_SHORT) + if (!(frame_ctrl & IEEE802154_FRAMECTRL_INTRA)) { - if ((fc1 & IEEE802154_FC1_INTRA) != IEEE802154_INTRA) - { - hlen += 2; /* No PAN compression, source PAN is different from dest PAN */ - } + hlen += 2; /* No PAN compression, source PAN is different from dest PAN */ + } + if ((frame_ctrl & IEEE802154_FRAMECTRL_SADDR)== IEEE802154_ADDRMODE_SHORT) + { hlen += 2; /* Source saddr */ } - else if ((fc2 & IEEE802154_FC2_SADDR) == IEEE802154_SADDR_EXT) + else if ((frame_ctrl & IEEE802154_FRAMECTRL_SADDR) == IEEE802154_ADDRMODE_EXTENDED) { - if ((fc1 & IEEE802154_FC1_INTRA) != IEEE802154_INTRA) - { - hlen += 2; /* No PAN compression, source PAN is different from dest PAN */ - } - hlen += 8; /* Ext saddr */ } - //wlinfo("hlen %d\n",hlen); - /* Header len, 0, TODO for security modes */ mrf24j40_setreg(dev->spi, addr++, hlen); @@ -1180,7 +1134,7 @@ static int mrf24j40_transmit(FAR struct ieee802154_radio_s *ieee, */ reg = MRF24J40_TXNCON_TXNTRIG; - if (fc1 & IEEE802154_FC1_ACKREQ) + if (frame_ctrl & IEEE802154_FRAMECTRL_ACKREQ) { reg |= MRF24J40_TXNCON_TXNACKREQ; } -- GitLab From 4a4805da88c2d3174ffc48e09632944a434f10fb Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Fri, 24 Mar 2017 11:11:04 -0400 Subject: [PATCH 184/990] configs/clicker2-stm32: Fixes issues with stm32_mrf24j40 --- configs/clicker2-stm32/src/stm32_mrf24j40.c | 22 +++++++++++---------- 1 file changed, 12 insertions(+), 10 deletions(-) diff --git a/configs/clicker2-stm32/src/stm32_mrf24j40.c b/configs/clicker2-stm32/src/stm32_mrf24j40.c index 8d28c54854..12131190fb 100644 --- a/configs/clicker2-stm32/src/stm32_mrf24j40.c +++ b/configs/clicker2-stm32/src/stm32_mrf24j40.c @@ -47,9 +47,9 @@ #include #include -#include -#include -#include +#include +#include +#include #include "stm32_gpio.h" #include "stm32_exti.h" @@ -120,7 +120,7 @@ static int stm32_attach_irq(FAR const struct mrf24j40_lower_s *lower, xcpt_t handler); static void stm32_enable_irq(FAR const struct mrf24j40_lower_s *lower, int state); -static int stm32_mrf24j40_devsetup(FAR struct stm32_priv_s *priv)' +static int stm32_mrf24j40_devsetup(FAR struct stm32_priv_s *priv); /**************************************************************************** * Private Data @@ -172,12 +172,12 @@ static struct stm32_priv_s g_mrf24j40_mb2_priv = * irq_enable - Enable or disable the GPIO interrupt */ -static int stm32_attach_irq(FAR struct mrf24j40_lower_s *lower, +static int stm32_attach_irq(FAR const struct mrf24j40_lower_s *lower, xcpt_t handler) { - FAR struct stm32_priv_s *priv = (FAR struct mrf24j40_lower_s *)lower; + FAR struct stm32_priv_s *priv = (FAR struct stm32_priv_s *)lower; - DEBUASSERT(priv != NULL); + DEBUGASSERT(priv != NULL); /* Just save the handler for use when the interrupt is enabled */ @@ -185,9 +185,9 @@ static int stm32_attach_irq(FAR struct mrf24j40_lower_s *lower, return OK; } -static void stm32_enable_irq(FAR struct mrf24j40_lower_s *lower, int state) +static void stm32_enable_irq(FAR const struct mrf24j40_lower_s *lower, int state) { - FAR struct stm32_priv_s *priv = (FAR struct mrf24j40_lower_s *)lower; + FAR struct stm32_priv_s *priv = (FAR struct stm32_priv_s *)lower; /* The caller should not attempt to enable interrupts if the handler * has not yet been 'attached' @@ -201,7 +201,7 @@ static void stm32_enable_irq(FAR struct mrf24j40_lower_s *lower, int state) if (state != 0) { (void)stm32_gpiosetevent(priv->intcfg, true, true, true, - priv->handler, lower); + priv->handler, NULL); } else { @@ -230,6 +230,8 @@ static int stm32_mrf24j40_devsetup(FAR struct stm32_priv_s *priv) #endif FAR struct spi_dev_s *spi; + int ret; + /* Configure the interrupt pin */ stm32_configgpio(priv->intcfg); -- GitLab From e82600681834a993ac6759e86275da9aa00c73be Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Fri, 24 Mar 2017 11:14:40 -0400 Subject: [PATCH 185/990] configs/clicker2-stm32: Fixes missing semicolon on function prototype --- configs/clicker2-stm32/src/clicker2-stm32.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/configs/clicker2-stm32/src/clicker2-stm32.h b/configs/clicker2-stm32/src/clicker2-stm32.h index 41081ae794..9848165b83 100644 --- a/configs/clicker2-stm32/src/clicker2-stm32.h +++ b/configs/clicker2-stm32/src/clicker2-stm32.h @@ -299,7 +299,7 @@ int stm32_can_setup(void); ****************************************************************************/ #if defined(CONFIG_CLICKER2_STM32_MB1_BEE) || defined(CONFIG_CLICKER2_STM32_MB2_BEE) -int stm32_mrf24j40_initialize(void) +int stm32_mrf24j40_initialize(void); #endif #endif /* __ASSEMBLY__ */ -- GitLab From 77b9f72083f83bb88208f553bfd40b5a469d4e56 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Fri, 24 Mar 2017 11:33:46 -0400 Subject: [PATCH 186/990] configs/clicker2-stm32: Cleans up minor issues --- configs/clicker2-stm32/src/clicker2-stm32.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/configs/clicker2-stm32/src/clicker2-stm32.h b/configs/clicker2-stm32/src/clicker2-stm32.h index 544366c8dd..24dd9e54dc 100644 --- a/configs/clicker2-stm32/src/clicker2-stm32.h +++ b/configs/clicker2-stm32/src/clicker2-stm32.h @@ -33,8 +33,8 @@ * ****************************************************************************/ -#ifndef __CONFIGS_OLIMEX_STM32_P407_SRC_H -#define __CONFIGS_OLIMEX_STM32_P407_SRC_H +#ifndef __CONFIGS_CLICKER2_STM32_SRC_CLICKER2_H +#define __CONFIGS_CLICKER2_STM32_SRC_CLICKER2_H /**************************************************************************** * Included Files @@ -212,7 +212,7 @@ #define GPIO_MB1_RST (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN7) -#define GPIO_MB1_RST (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ +#define GPIO_MB2_RST (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\ GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN13) /* Interrupts @@ -287,4 +287,4 @@ int stm32_can_setup(void); #endif #endif /* __ASSEMBLY__ */ -#endif /* __CONFIGS_OLIMEX_STM32_P407_SRC_H */ +#endif /* __CONFIGS_CLICKER2_STM32_SRC_CLICKER2_H */ -- GitLab From d0c54039dcafd360bbb7ecaf2d406778b7a2547c Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Fri, 24 Mar 2017 09:41:31 -0600 Subject: [PATCH 187/990] Add ffsl(), ffsll(), fls(), flsl(), flsll() and use GCC's __builtin_ctz/__builtin_clz for faster implementation of these --- include/nuttx/compiler.h | 12 +++++ include/strings.h | 11 +++++ libc/string/Make.defs | 3 +- libc/string/lib_ffs.c | 12 +++-- libc/string/lib_ffsl.c | 93 ++++++++++++++++++++++++++++++++++++++ libc/string/lib_ffsll.c | 97 +++++++++++++++++++++++++++++++++++++++ libc/string/lib_fls.c | 93 ++++++++++++++++++++++++++++++++++++++ libc/string/lib_flsl.c | 93 ++++++++++++++++++++++++++++++++++++++ libc/string/lib_flsll.c | 98 ++++++++++++++++++++++++++++++++++++++++ 9 files changed, 508 insertions(+), 4 deletions(-) create mode 100644 libc/string/lib_ffsl.c create mode 100644 libc/string/lib_ffsll.c create mode 100644 libc/string/lib_fls.c create mode 100644 libc/string/lib_flsl.c create mode 100644 libc/string/lib_flsll.c diff --git a/include/nuttx/compiler.h b/include/nuttx/compiler.h index 5c5c25be29..15a0f059a9 100644 --- a/include/nuttx/compiler.h +++ b/include/nuttx/compiler.h @@ -64,6 +64,18 @@ # define UNUSED(a) ((void)(a)) +/* Built-in functions */ + +/* GCC 4.x have __builtin_ctz(|l|ll) and __builtin_clz(|l|ll). These count + * trailing/leading zeros of input number and typically will generate few + * fast bit-counting instructions. Inputting zero to these functions is + * undefined and needs to be taken care of by the caller. */ + +#if __GNUC__ >= 4 +# define CONFIG_HAVE_BUILTIN_CTZ 1 +# define CONFIG_HAVE_BUILTIN_CLZ 1 +#endif + /* Attributes * * GCC supports weak symbols which can be used to reduce code size because diff --git a/include/strings.h b/include/strings.h index 4b7fc439da..54be5dd380 100644 --- a/include/strings.h +++ b/include/strings.h @@ -114,6 +114,17 @@ static inline FAR char *rindex(FAR const char *s, int c) ****************************************************************************/ int ffs(int j); +int ffsl(long j); +#ifdef CONFIG_HAVE_LONG_LONG +int ffsll(long long j); +#endif + +int fls(int j); +int flsl(long j); +#ifdef CONFIG_HAVE_LONG_LONG +int flsll(long long j); +#endif + int strcasecmp(FAR const char *, FAR const char *); int strncasecmp(FAR const char *, FAR const char *, size_t); diff --git a/libc/string/Make.defs b/libc/string/Make.defs index defedcfb60..72cb8354d5 100644 --- a/libc/string/Make.defs +++ b/libc/string/Make.defs @@ -35,7 +35,8 @@ # Add the string C files to the build -CSRCS += lib_ffs.c lib_isbasedigit.c lib_memset.c lib_memchr.c +CSRCS += lib_ffs.c lib_ffsl.c lib_ffsll.c lib_fls.c lib_flsl.c +CSRCS += lib_flsll.c lib_isbasedigit.c lib_memset.c lib_memchr.c CSRCS += lib_memccpy.c lib_memcmp.c lib_memmove.c lib_skipspace.c CSRCS += lib_stpcpy.c lib_strcasecmp.c lib_strcat.c lib_strchr.c CSRCS += lib_strcpy.c lib_strcmp.c lib_strcspn.c lib_strdup.c diff --git a/libc/string/lib_ffs.c b/libc/string/lib_ffs.c index c52a9c43b2..885718ba49 100644 --- a/libc/string/lib_ffs.c +++ b/libc/string/lib_ffs.c @@ -33,11 +33,11 @@ * ****************************************************************************/ - /**************************************************************************** * Included Files ****************************************************************************/ +#include #include /**************************************************************************** @@ -55,11 +55,11 @@ * * Description: * The ffs() function will find the first bit set (beginning with the least - * significant bit) in i, and return the index of that bit. Bits are + * significant bit) in j, and return the index of that bit. Bits are * numbered starting at one (the least significant bit). * * Returned Value: - * The ffs() function will return the index of the first bit set. If i is + * The ffs() function will return the index of the first bit set. If j is * 0, then ffs() will return 0. * ****************************************************************************/ @@ -70,6 +70,11 @@ int ffs(int j) if (j != 0) { +#ifdef CONFIG_HAVE_BUILTIN_CTZ + /* Count trailing zeros function can be used to implement ffs. */ + + ret = __builtin_ctz(j) + 1; +#else unsigned int value = (unsigned int)j; int bitno; @@ -81,6 +86,7 @@ int ffs(int j) break; } } +#endif } return ret; diff --git a/libc/string/lib_ffsl.c b/libc/string/lib_ffsl.c new file mode 100644 index 0000000000..4d5739cc03 --- /dev/null +++ b/libc/string/lib_ffsl.c @@ -0,0 +1,93 @@ +/**************************************************************************** + * libc/string/lib_ffsl.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define NBITS (8 * sizeof(unsigned long)) + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: ffsl + * + * Description: + * The ffsl() function will find the first bit set (beginning with the least + * significant bit) in j, and return the index of that bit. Bits are + * numbered starting at one (the least significant bit). + * + * Returned Value: + * The ffsl() function will return the index of the first bit set. If j is + * 0, then ffsl() will return 0. + * + ****************************************************************************/ + +int ffsl(long j) +{ + int ret = 0; + + if (j != 0) + { +#ifdef CONFIG_HAVE_BUILTIN_CTZ + /* Count trailing zeros function can be used to implement ffs. */ + + ret = __builtin_ctzl(j) + 1; +#else + unsigned long value = (unsigned long)j; + int bitno; + + for (bitno = 1; bitno <= NBITS; bitno++, value >>= 1) + { + if ((value & 1) != 0) + { + ret = bitno; + break; + } + } +#endif + } + + return ret; +} diff --git a/libc/string/lib_ffsll.c b/libc/string/lib_ffsll.c new file mode 100644 index 0000000000..111e664d42 --- /dev/null +++ b/libc/string/lib_ffsll.c @@ -0,0 +1,97 @@ +/**************************************************************************** + * libc/string/lib_ffsll.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define NBITS (8 * sizeof(unsigned long long)) + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +#ifdef CONFIG_HAVE_LONG_LONG + +/**************************************************************************** + * Name: ffsll + * + * Description: + * The ffsll() function will find the first bit set (beginning with the least + * significant bit) in i, and return the index of that bit. Bits are + * numbered starting at one (the least significant bit). + * + * Returned Value: + * The ffsll() function will return the index of the first bit set. If j is + * 0, then ffsll() will return 0. + * + ****************************************************************************/ + +int ffsll(long long j) +{ + int ret = 0; + + if (j != 0) + { +#ifdef CONFIG_HAVE_BUILTIN_CTZ + /* Count trailing zeros function can be used to implement ffs. */ + + ret = __builtin_ctzll(j) + 1; +#else + unsigned long long value = (unsigned long long)j; + int bitno; + + for (bitno = 1; bitno <= NBITS; bitno++, value >>= 1) + { + if ((value & 1) != 0) + { + ret = bitno; + break; + } + } +#endif + } + + return ret; +} + +#endif diff --git a/libc/string/lib_fls.c b/libc/string/lib_fls.c new file mode 100644 index 0000000000..5894fb1953 --- /dev/null +++ b/libc/string/lib_fls.c @@ -0,0 +1,93 @@ +/**************************************************************************** + * libc/string/lib_fls.c + * + * Copyright (C) 2017 Haltian Ltd. All rights reserved. + * Author: Jussi Kivilinna + * + * 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 + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define NBITS (8 * sizeof(unsigned int)) + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: fls + * + * Description: + * The fls() function will find the last bit set in value and return + * the index of that bit. Bits are numbered starting at one (the least + * significant bit). + * + * Returned Value: + * The fls() function will return the index of the last bit set. If j is + * 0, then fls() will return 0. + * + ****************************************************************************/ + +int fls(int j) +{ + int ret = 0; + + if (j != 0) + { +#ifdef CONFIG_HAVE_BUILTIN_CLZ + /* Count leading zeros function can be used to implement fls. */ + + ret = NBITS - __builtin_clz(j); +#else + unsigned int value = (unsigned int)j; + int bitno; + + for (bitno = 1; bitno <= NBITS; bitno++, value >>= 1) + { + if (value == 1) + { + ret = bitno; + break; + } + } +#endif + } + + return ret; +} diff --git a/libc/string/lib_flsl.c b/libc/string/lib_flsl.c new file mode 100644 index 0000000000..2a3837ddc7 --- /dev/null +++ b/libc/string/lib_flsl.c @@ -0,0 +1,93 @@ +/**************************************************************************** + * libc/string/lib_fls.c + * + * Copyright (C) 2017 Haltian Ltd. All rights reserved. + * Author: Jussi Kivilinna + * + * 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 + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define NBITS (8 * sizeof(unsigned long)) + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: flsl + * + * Description: + * The flsl() function will find the last bit set in value and return + * the index of that bit. Bits are numbered starting at one (the least + * significant bit). + * + * Returned Value: + * The flsl() function will return the index of the last bit set. If j is + * 0, then flsl() will return 0. + * + ****************************************************************************/ + +int flsl(long j) +{ + int ret = 0; + + if (j != 0) + { +#ifdef CONFIG_HAVE_BUILTIN_CLZ + /* Count leading zeros function can be used to implement fls. */ + + ret = NBITS - __builtin_clzl(j); +#else + unsigned long value = (unsigned long)j; + int bitno; + + for (bitno = 1; bitno <= NBITS; bitno++, value >>= 1) + { + if (value == 1) + { + ret = bitno; + break; + } + } +#endif + } + + return ret; +} diff --git a/libc/string/lib_flsll.c b/libc/string/lib_flsll.c new file mode 100644 index 0000000000..2f30f8142e --- /dev/null +++ b/libc/string/lib_flsll.c @@ -0,0 +1,98 @@ +/**************************************************************************** + * libc/string/lib_fls.c + * + * Copyright (C) 2017 Haltian Ltd. All rights reserved. + * Author: Jussi Kivilinna + * + * 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 + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define NBITS (8 * sizeof(unsigned long long)) + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +#ifdef CONFIG_HAVE_LONG_LONG + +/**************************************************************************** + * Name: flsll + * + * Description: + * The flsll() function will find the last bit set in value and return + * the index of that bit. Bits are numbered starting at one (the least + * significant bit). + * + * Returned Value: + * The flsll() function will return the index of the last bit set. If j is + * 0, then flsll() will return 0. + * + ****************************************************************************/ + +int flsll(long long j) +{ + int ret = 0; + + if (j != 0) + { +#ifdef CONFIG_HAVE_BUILTIN_CLZ + /* Count leading zeros function can be used to implement fls. */ + + ret = NBITS - __builtin_clzll(j); +#else + unsigned long long value = (unsigned long long)j; + int bitno; + + for (bitno = 1; bitno <= NBITS; bitno++, value >>= 1) + { + if (value == 1) + { + ret = bitno; + break; + } + } +#endif + } + + return ret; +} + +#endif + -- GitLab From 3a07455493130243b72f85d899a92f4abb094f6b Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 24 Mar 2017 10:16:18 -0600 Subject: [PATCH 188/990] Trivial changes from review of last PR --- configs/clicker2-stm32/src/stm32_mrf24j40.c | 1 - include/nuttx/wireless/ieee802154/ieee802154.h | 3 ++- .../nuttx/wireless/ieee802154/ieee802154_mac.h | 16 +++++++++------- 3 files changed, 11 insertions(+), 9 deletions(-) diff --git a/configs/clicker2-stm32/src/stm32_mrf24j40.c b/configs/clicker2-stm32/src/stm32_mrf24j40.c index 12131190fb..5c61750f46 100644 --- a/configs/clicker2-stm32/src/stm32_mrf24j40.c +++ b/configs/clicker2-stm32/src/stm32_mrf24j40.c @@ -229,7 +229,6 @@ static int stm32_mrf24j40_devsetup(FAR struct stm32_priv_s *priv) FAR struct ieee802154_mac_s *mac; #endif FAR struct spi_dev_s *spi; - int ret; /* Configure the interrupt pin */ diff --git a/include/nuttx/wireless/ieee802154/ieee802154.h b/include/nuttx/wireless/ieee802154/ieee802154.h index 1b89748c1d..38410a622f 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154.h +++ b/include/nuttx/wireless/ieee802154/ieee802154.h @@ -69,7 +69,8 @@ struct ieee802154_packet_s * Extended address + PAN id : PPPP/LLLLLLLLLLLLLLLL */ -enum ieee802154_addr_mode_e { +enum ieee802154_addr_mode_e +{ IEEE802154_ADDRMODE_NONE = 0, IEEE802154_ADDRMODE_SHORT = 2, IEEE802154_ADDRMODE_EXTENDED diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index 992b03e0e8..f4b408fdb9 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -55,16 +55,16 @@ /* Configuration ************************************************************/ /* None at the moment */ - /* IEEE 802.15.4 MAC Character Driver IOCTL Commands ************************/ /* The IEEE 802.15.4 standard specifies a MLME Service Access Point (SAP) * including a series of primitives that are used as an interface between * the MLME and the next highest layer. There are 4 types of primitives: - * - Request - * - Indication - * - Response - * - Confirm + * + * - Request + * - Indication + * - Response + * - Confirm * * Of these, Request and Response primitives are sent from the next highest layer * to the MLME. Indication and Confirm primitives are used to notify the next @@ -294,9 +294,11 @@ struct ieee802154_pan_desc_s struct ieee802154_pend_addr_s { - union { + union + { uint8_t pa_spec; - struct { + struct + { uint8_t num_short_addr : 3; /* Number of short addresses pending */ uint8_t reserved_3 : 1; /* Reserved bit */ uint8_t num_ext_addr : 3; /* Number of extended addresses pending */ -- GitLab From c12b066f14797658bc5096385744e230481cd2c6 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 24 Mar 2017 12:11:31 -0600 Subject: [PATCH 189/990] Update README file --- configs/clicker2-stm32/README.txt | 62 ++++++++++++++++++++++++++++--- 1 file changed, 56 insertions(+), 6 deletions(-) diff --git a/configs/clicker2-stm32/README.txt b/configs/clicker2-stm32/README.txt index 14046a208b..3a8b7db14c 100644 --- a/configs/clicker2-stm32/README.txt +++ b/configs/clicker2-stm32/README.txt @@ -87,18 +87,68 @@ Using JTAG https://www.mikroe.com/how-to-use-st-link-v2-with-clicker-2-for-stm32-a-detailed-walkthrough/ http://www.playembedded.org/blog/en/2016/02/06/mikroe-clicker-2-for-stm32-and-stlink-v2/ - NOTE that the FLASH is locked. You may need to follow the instructions at - the second link to unlock it (although I think you may be able to do this - with the ST-Micro ST-Link Utility as well). + NOTE that the FLASH probably has read protection enabled locked. You may + need to follow the instructions at the second link to unlock it. You can + also use the STM32 ST-Link CLI tool to remove the read protection using + the -OB command: + + $ ./ST-LINK_CLI.exe -c SN=53FF6F064966545035320387 SWD LPM + STM32 ST-LINK CLI v2.3.0 + STM32 ST-LINK Command Line Interface + + ST-LINK SN : 53FF6F064966545035320387 + ST-LINK Firmware version : V2J24S4 + Connected via SWD. + SWD Frequency = 4000K. + Target voltage = 3.2 V. + Connection mode : Normal. + Debug in Low Power mode enabled. + Device ID:0x413 + Device family :STM32F40xx/F41xx + + $ ./ST-LINK_CLI.exe -OB RDP=0 + STM32 ST-LINK CLI v2.3.0 + STM32 ST-LINK Command Line Interface + + ST-LINK SN : 53FF6F064966545035320387 + ST-LINK Firmware version : V2J24S4 + Connected via SWD. + SWD Frequency = 4000K. + Target voltage = 3.2 V. + Connection mode : Normal. + Device ID:0x413 + Device family :STM32F40xx/F41xx + Updating option bytes... + Option bytes updated successfully. + + NOTE: + 1. The ST-LINK Utility command line interface is located at: + [Install_Directory]\STM32 ST-LINK Utility\ST-LINK Utility\ST-LINK_CLI.exe + 2. You can get a summary of all of the command options by running + ST-LINK_CLI.exe with no arguments. + 3. You can get the serial number of the ST-Link when from the information + window if you connect via the ST-Link Utility: + + 11:04:28 : ST-LINK SN : 53FF6F064966545035320387 + 11:04:28 : ST-LINK Firmware version : V2J24S4 + 11:04:28 : Connected via SWD. + 11:04:28 : SWD Frequency = 100 KHz. + 11:04:28 : Connection mode : Normal. + 11:04:28 : Debug in Low Power mode enabled. + 11:04:30 : Device ID:0x413 + 11:04:30 : Device family :STM32F40xx/F41xx + 11:04:30 : Can not read memory! + Disable Read Out Protection and retry. You can avoid the mess of jumpers using the mikroProg to ST-Link v2 adapter along with a 2x5, 10-wire ribbon cable connector: https://shop.mikroe.com/add-on-boards/adapter/mikroprog-st-link-v2-adapter - OpenOCD can be used with the ST-Link to provide a debug environment. I suspect, - however, that adapter can be used with other JTAG debuggers such as J-Link, - but that remains to be verified. + Then you can use the ST-Link Utility or other debugger software to write + the NuttX binary to FLASH. OpenOCD can be used with the ST-Link to provide + a debug environment. The debug adaptor is NOT compatible with other JTAG + debuggers such as the Segger J-Link. Configurations ============== -- GitLab From c3990e1b7f441039a87e67bb20e4f3238011e327 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 24 Mar 2017 12:46:01 -0600 Subject: [PATCH 190/990] Update README and some comments --- configs/clicker2-stm32/README.txt | 12 +++++++----- configs/clicker2-stm32/include/board.h | 4 ++-- 2 files changed, 9 insertions(+), 7 deletions(-) diff --git a/configs/clicker2-stm32/README.txt b/configs/clicker2-stm32/README.txt index 3a8b7db14c..c412c11435 100644 --- a/configs/clicker2-stm32/README.txt +++ b/configs/clicker2-stm32/README.txt @@ -89,8 +89,8 @@ Using JTAG NOTE that the FLASH probably has read protection enabled locked. You may need to follow the instructions at the second link to unlock it. You can - also use the STM32 ST-Link CLI tool to remove the read protection using - the -OB command: + also use the STM32 ST-Link CLI tool on Windows to remove the read protection + using the -OB command: $ ./ST-LINK_CLI.exe -c SN=53FF6F064966545035320387 SWD LPM STM32 ST-LINK CLI v2.3.0 @@ -122,11 +122,13 @@ Using JTAG Option bytes updated successfully. NOTE: - 1. The ST-LINK Utility command line interface is located at: + 1. You can get the ST-Link Utilies here: + http://www.st.com/en/embedded-software/stsw-link004.html + 2. The ST-LINK Utility command line interface is located at: [Install_Directory]\STM32 ST-LINK Utility\ST-LINK Utility\ST-LINK_CLI.exe - 2. You can get a summary of all of the command options by running + 3. You can get a summary of all of the command options by running ST-LINK_CLI.exe with no arguments. - 3. You can get the serial number of the ST-Link when from the information + 4. You can get the serial number of the ST-Link when from the information window if you connect via the ST-Link Utility: 11:04:28 : ST-LINK SN : 53FF6F064966545035320387 diff --git a/configs/clicker2-stm32/include/board.h b/configs/clicker2-stm32/include/board.h index fa271666cb..7f757d4951 100644 --- a/configs/clicker2-stm32/include/board.h +++ b/configs/clicker2-stm32/include/board.h @@ -269,8 +269,8 @@ * Assuming RS-232 connverted connected on mikroMB1/12 */ -#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */ -#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */ +#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */ +#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */ #define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */ #define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 / -- GitLab From e97a13ea900b63ffcd14ff98874ba391d8047ec0 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 24 Mar 2017 13:49:17 -0600 Subject: [PATCH 191/990] MRF24J40/Clicker2: Add an MRF24J40 device configuration to the Clicker2 STM32 board. Fix a few errors discovered during build. --- configs/clicker2-stm32/Kconfig | 6 +- configs/clicker2-stm32/mrf24j40_dev/Make.defs | 122 ++ configs/clicker2-stm32/mrf24j40_dev/defconfig | 1365 +++++++++++++++++ configs/clicker2-stm32/mrf24j40_dev/setenv.sh | 80 + drivers/wireless/Kconfig | 2 - drivers/wireless/ieee802154/mrf24j40.c | 15 +- wireless/Kconfig | 1 - wireless/ieee802154/Kconfig | 1 - 8 files changed, 1581 insertions(+), 11 deletions(-) create mode 100644 configs/clicker2-stm32/mrf24j40_dev/Make.defs create mode 100644 configs/clicker2-stm32/mrf24j40_dev/defconfig create mode 100644 configs/clicker2-stm32/mrf24j40_dev/setenv.sh diff --git a/configs/clicker2-stm32/Kconfig b/configs/clicker2-stm32/Kconfig index a5d3a68cbc..9344f015da 100644 --- a/configs/clicker2-stm32/Kconfig +++ b/configs/clicker2-stm32/Kconfig @@ -7,16 +7,14 @@ if ARCH_BOARD_CLICKER2_STM32 config CLICKER2_STM32_MB1_SPI bool "mikroBUS1 SPI" - default n if !STM32_SPI3 - default y if STM32_SPI3 + default n select STM32_SPI3 ---help--- Enable SPI support on mikroBUS1 (STM32 SPI3) config CLICKER2_STM32_MB2_SPI bool "mikroBUS2 SPI" - default n if !STM32_SPI2 - default y if STM32_SPI2 + default n select STM32_SPI2 ---help--- Enable SPI support on mikroBUS1 (STM32 SPI2) diff --git a/configs/clicker2-stm32/mrf24j40_dev/Make.defs b/configs/clicker2-stm32/mrf24j40_dev/Make.defs new file mode 100644 index 0000000000..d86e64844f --- /dev/null +++ b/configs/clicker2-stm32/mrf24j40_dev/Make.defs @@ -0,0 +1,122 @@ +############################################################################ +# configs/clicker2-stm32/mrf24j40_dev/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. +# +############################################################################ + +include ${TOPDIR}/.config +include ${TOPDIR}/tools/Config.mk +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs + +LDSCRIPT = flash.ld + +ifeq ($(WINTOOL),y) + # Windows-native toolchains + DIRLINK = $(TOPDIR)/tools/copydir.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mkwindeps.sh + ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" + ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" +else + # Linux/Cygwin-native toolchain + MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT) + ARCHINCLUDES = -I. -isystem $(TOPDIR)/include + ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) +endif + +CC = $(CROSSDEV)gcc +CXX = $(CROSSDEV)g++ +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(CROSSDEV)ar rcs +NM = $(CROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump + +ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} +ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} + +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + ARCHOPTIMIZATION = -g +endif + +ifneq ($(CONFIG_DEBUG_NOOPT),y) + ARCHOPTIMIZATION += $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer +endif + +ARCHCFLAGS = -fno-builtin +ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fcheck-new -fno-rtti +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow -Wundef +ARCHWARNINGSXX = -Wall -Wshadow -Wundef +ARCHDEFINES = +ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 + +CFLAGS = $(ARCHCFLAGS) $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) +CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +NXFLATLDFLAGS1 = -r -d -warn-common +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections +LDNXFLATFLAGS = -e main -s 2048 + +# Loadable module definitions + +CMODULEFLAGS = $(CFLAGS) -mlong-calls # --target1-abs + +LDMODULEFLAGS = -r -e module_initialize +ifeq ($(WINTOOL),y) + LDMODULEFLAGS += -T "${shell cygpath -w $(TOPDIR)/libc/modlib/gnu-elf.ld}" +else + LDMODULEFLAGS += -T $(TOPDIR)/libc/modlib/gnu-elf.ld +endif + +ASMEXT = .S +OBJEXT = .o +LIBEXT = .a +EXEEXT = + +ifneq ($(CROSSDEV),arm-nuttx-elf-) + LDFLAGS += -nostartfiles -nodefaultlibs +endif +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + LDFLAGS += -g +endif + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -Wundef -g -pipe +HOSTLDFLAGS = diff --git a/configs/clicker2-stm32/mrf24j40_dev/defconfig b/configs/clicker2-stm32/mrf24j40_dev/defconfig new file mode 100644 index 0000000000..5b6ec741f5 --- /dev/null +++ b/configs/clicker2-stm32/mrf24j40_dev/defconfig @@ -0,0 +1,1365 @@ +# +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# + +# +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set +# CONFIG_DEFAULT_SMALL is not set +CONFIG_HOST_LINUX=y +# CONFIG_HOST_OSX is not set +# CONFIG_HOST_WINDOWS is not set +# CONFIG_HOST_OTHER is not set + +# +# Build Configuration +# +# CONFIG_APPS_DIR="../apps" +CONFIG_BUILD_FLAT=y +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +CONFIG_INTELHEX_BINARY=y +# CONFIG_MOTOROLA_SREC is not set +CONFIG_RAW_BINARY=y +# CONFIG_UBOOT_UIMAGE is not set + +# +# Customize Header Files +# +# CONFIG_ARCH_STDINT_H is not set +# CONFIG_ARCH_STDBOOL_H is not set +# CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_FLOAT_H is not set +# CONFIG_ARCH_STDARG_H is not set +# CONFIG_ARCH_DEBUG_H is not set + +# +# Debug Options +# +CONFIG_DEBUG_ALERT=y +# CONFIG_DEBUG_FEATURES is not set +CONFIG_ARCH_HAVE_STACKCHECK=y +# CONFIG_STACK_COLORATION is not set +CONFIG_ARCH_HAVE_HEAPCHECK=y +# CONFIG_HEAP_COLORATION is not set +# CONFIG_DEBUG_SYMBOLS is not set +CONFIG_ARCH_HAVE_CUSTOMOPT=y +# CONFIG_DEBUG_NOOPT is not set +# CONFIG_DEBUG_CUSTOMOPT is not set +CONFIG_DEBUG_FULLOPT=y + +# +# System Type +# +CONFIG_ARCH_ARM=y +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_MISOC is not set +# CONFIG_ARCH_RENESAS is not set +# CONFIG_ARCH_RISCV is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_XTENSA is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="arm" + +# +# ARM Options +# +# CONFIG_ARCH_CHIP_A1X is not set +# CONFIG_ARCH_CHIP_C5471 is not set +# CONFIG_ARCH_CHIP_DM320 is not set +# CONFIG_ARCH_CHIP_EFM32 is not set +# CONFIG_ARCH_CHIP_IMX1 is not set +# CONFIG_ARCH_CHIP_IMX6 is not set +# CONFIG_ARCH_CHIP_KINETIS is not set +# CONFIG_ARCH_CHIP_KL is not set +# CONFIG_ARCH_CHIP_LM is not set +# CONFIG_ARCH_CHIP_TIVA is not set +# CONFIG_ARCH_CHIP_LPC11XX is not set +# CONFIG_ARCH_CHIP_LPC17XX is not set +# CONFIG_ARCH_CHIP_LPC214X is not set +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_NUC1XX is not set +# CONFIG_ARCH_CHIP_SAMA5 is not set +# CONFIG_ARCH_CHIP_SAMD is not set +# CONFIG_ARCH_CHIP_SAML is not set +# CONFIG_ARCH_CHIP_SAM34 is not set +# CONFIG_ARCH_CHIP_SAMV7 is not set +CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F7 is not set +# CONFIG_ARCH_CHIP_STM32L4 is not set +# CONFIG_ARCH_CHIP_STR71X is not set +# CONFIG_ARCH_CHIP_TMS570 is not set +# CONFIG_ARCH_CHIP_XMC4 is not set +# CONFIG_ARCH_ARM7TDMI is not set +# CONFIG_ARCH_ARM926EJS is not set +# CONFIG_ARCH_ARM920T is not set +# CONFIG_ARCH_CORTEXM0 is not set +# CONFIG_ARCH_CORTEXM23 is not set +# CONFIG_ARCH_CORTEXM3 is not set +# CONFIG_ARCH_CORTEXM33 is not set +CONFIG_ARCH_CORTEXM4=y +# CONFIG_ARCH_CORTEXM7 is not set +# CONFIG_ARCH_CORTEXA5 is not set +# CONFIG_ARCH_CORTEXA8 is not set +# CONFIG_ARCH_CORTEXA9 is not set +# CONFIG_ARCH_CORTEXR4 is not set +# CONFIG_ARCH_CORTEXR4F is not set +# CONFIG_ARCH_CORTEXR5 is not set +# CONFIG_ARCH_CORTEX5F is not set +# CONFIG_ARCH_CORTEXR7 is not set +# CONFIG_ARCH_CORTEXR7F is not set +CONFIG_ARCH_FAMILY="armv7-m" +CONFIG_ARCH_CHIP="stm32" +# CONFIG_ARM_TOOLCHAIN_IAR is not set +CONFIG_ARM_TOOLCHAIN_GNU=y +# CONFIG_ARMV7M_USEBASEPRI is not set +CONFIG_ARCH_HAVE_CMNVECTOR=y +# CONFIG_ARMV7M_CMNVECTOR is not set +# CONFIG_ARMV7M_LAZYFPU is not set +CONFIG_ARCH_HAVE_FPU=y +# CONFIG_ARCH_HAVE_DPFPU is not set +CONFIG_ARCH_FPU=y +# CONFIG_ARCH_HAVE_TRUSTZONE is not set +CONFIG_ARM_HAVE_MPU_UNIFIED=y +# CONFIG_ARM_MPU is not set + +# +# ARMV7M Configuration Options +# +# CONFIG_ARMV7M_HAVE_ICACHE is not set +# CONFIG_ARMV7M_HAVE_DCACHE is not set +# CONFIG_ARMV7M_HAVE_ITCM is not set +# CONFIG_ARMV7M_HAVE_DTCM is not set +# CONFIG_ARMV7M_TOOLCHAIN_IARL is not set +# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set +# CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set +# CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL is not set +CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL=y +CONFIG_ARMV7M_HAVE_STACKCHECK=y +# CONFIG_ARMV7M_STACKCHECK is not set +# CONFIG_ARMV7M_ITMSYSLOG is not set +# CONFIG_SERIAL_TERMIOS is not set +# CONFIG_USBHOST_BULK_DISABLE is not set +# CONFIG_USBHOST_INT_DISABLE is not set +# CONFIG_USBHOST_ISOC_DISABLE is not set + +# +# STM32 Configuration Options +# +# CONFIG_ARCH_CHIP_STM32L151C6 is not set +# CONFIG_ARCH_CHIP_STM32L151C8 is not set +# CONFIG_ARCH_CHIP_STM32L151CB is not set +# CONFIG_ARCH_CHIP_STM32L151R6 is not set +# CONFIG_ARCH_CHIP_STM32L151R8 is not set +# CONFIG_ARCH_CHIP_STM32L151RB is not set +# CONFIG_ARCH_CHIP_STM32L151V6 is not set +# CONFIG_ARCH_CHIP_STM32L151V8 is not set +# CONFIG_ARCH_CHIP_STM32L151VB is not set +# CONFIG_ARCH_CHIP_STM32L152C6 is not set +# CONFIG_ARCH_CHIP_STM32L152C8 is not set +# CONFIG_ARCH_CHIP_STM32L152CB is not set +# CONFIG_ARCH_CHIP_STM32L152R6 is not set +# CONFIG_ARCH_CHIP_STM32L152R8 is not set +# CONFIG_ARCH_CHIP_STM32L152RB is not set +# CONFIG_ARCH_CHIP_STM32L152V6 is not set +# CONFIG_ARCH_CHIP_STM32L152V8 is not set +# CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L162ZD is not set +# CONFIG_ARCH_CHIP_STM32L162VE is not set +# CONFIG_ARCH_CHIP_STM32F100C8 is not set +# CONFIG_ARCH_CHIP_STM32F100CB is not set +# CONFIG_ARCH_CHIP_STM32F100R8 is not set +# CONFIG_ARCH_CHIP_STM32F100RB is not set +# CONFIG_ARCH_CHIP_STM32F100RC is not set +# CONFIG_ARCH_CHIP_STM32F100RD is not set +# CONFIG_ARCH_CHIP_STM32F100RE is not set +# CONFIG_ARCH_CHIP_STM32F100V8 is not set +# CONFIG_ARCH_CHIP_STM32F100VB is not set +# CONFIG_ARCH_CHIP_STM32F100VC is not set +# CONFIG_ARCH_CHIP_STM32F100VD is not set +# CONFIG_ARCH_CHIP_STM32F100VE is not set +# CONFIG_ARCH_CHIP_STM32F102CB is not set +# CONFIG_ARCH_CHIP_STM32F103T8 is not set +# CONFIG_ARCH_CHIP_STM32F103TB is not set +# CONFIG_ARCH_CHIP_STM32F103C4 is not set +# CONFIG_ARCH_CHIP_STM32F103C8 is not set +# CONFIG_ARCH_CHIP_STM32F103CB is not set +# CONFIG_ARCH_CHIP_STM32F103R8 is not set +# CONFIG_ARCH_CHIP_STM32F103RB is not set +# CONFIG_ARCH_CHIP_STM32F103RC is not set +# CONFIG_ARCH_CHIP_STM32F103RD is not set +# CONFIG_ARCH_CHIP_STM32F103RE is not set +# CONFIG_ARCH_CHIP_STM32F103RG is not set +# CONFIG_ARCH_CHIP_STM32F103V8 is not set +# CONFIG_ARCH_CHIP_STM32F103VB is not set +# CONFIG_ARCH_CHIP_STM32F103VC is not set +# CONFIG_ARCH_CHIP_STM32F103VE is not set +# CONFIG_ARCH_CHIP_STM32F103ZE is not set +# CONFIG_ARCH_CHIP_STM32F105VB is not set +# CONFIG_ARCH_CHIP_STM32F105RB is not set +# CONFIG_ARCH_CHIP_STM32F107VC is not set +# CONFIG_ARCH_CHIP_STM32F205RG is not set +# CONFIG_ARCH_CHIP_STM32F207IG is not set +# CONFIG_ARCH_CHIP_STM32F207ZE is not set +# CONFIG_ARCH_CHIP_STM32F302K6 is not set +# CONFIG_ARCH_CHIP_STM32F302K8 is not set +# CONFIG_ARCH_CHIP_STM32F302CB is not set +# CONFIG_ARCH_CHIP_STM32F302CC is not set +# CONFIG_ARCH_CHIP_STM32F302RB is not set +# CONFIG_ARCH_CHIP_STM32F302RC is not set +# CONFIG_ARCH_CHIP_STM32F302VB is not set +# CONFIG_ARCH_CHIP_STM32F302VC is not set +# CONFIG_ARCH_CHIP_STM32F303K6 is not set +# CONFIG_ARCH_CHIP_STM32F303K8 is not set +# CONFIG_ARCH_CHIP_STM32F303C6 is not set +# CONFIG_ARCH_CHIP_STM32F303C8 is not set +# CONFIG_ARCH_CHIP_STM32F303CB is not set +# CONFIG_ARCH_CHIP_STM32F303CC is not set +# CONFIG_ARCH_CHIP_STM32F303RB is not set +# CONFIG_ARCH_CHIP_STM32F303RC is not set +# CONFIG_ARCH_CHIP_STM32F303RD is not set +# CONFIG_ARCH_CHIP_STM32F303RE is not set +# CONFIG_ARCH_CHIP_STM32F303VB is not set +# CONFIG_ARCH_CHIP_STM32F303VC is not set +# CONFIG_ARCH_CHIP_STM32F334K4 is not set +# CONFIG_ARCH_CHIP_STM32F334K6 is not set +# CONFIG_ARCH_CHIP_STM32F334K8 is not set +# CONFIG_ARCH_CHIP_STM32F334C4 is not set +# CONFIG_ARCH_CHIP_STM32F334C6 is not set +# CONFIG_ARCH_CHIP_STM32F334C8 is not set +# CONFIG_ARCH_CHIP_STM32F334R4 is not set +# CONFIG_ARCH_CHIP_STM32F334R6 is not set +# CONFIG_ARCH_CHIP_STM32F334R8 is not set +# CONFIG_ARCH_CHIP_STM32F372C8 is not set +# CONFIG_ARCH_CHIP_STM32F372R8 is not set +# CONFIG_ARCH_CHIP_STM32F372V8 is not set +# CONFIG_ARCH_CHIP_STM32F372CB is not set +# CONFIG_ARCH_CHIP_STM32F372RB is not set +# CONFIG_ARCH_CHIP_STM32F372VB is not set +# CONFIG_ARCH_CHIP_STM32F372CC is not set +# CONFIG_ARCH_CHIP_STM32F372RC is not set +# CONFIG_ARCH_CHIP_STM32F372VC is not set +# CONFIG_ARCH_CHIP_STM32F373C8 is not set +# CONFIG_ARCH_CHIP_STM32F373R8 is not set +# CONFIG_ARCH_CHIP_STM32F373V8 is not set +# CONFIG_ARCH_CHIP_STM32F373CB is not set +# CONFIG_ARCH_CHIP_STM32F373RB is not set +# CONFIG_ARCH_CHIP_STM32F373VB is not set +# CONFIG_ARCH_CHIP_STM32F373CC is not set +# CONFIG_ARCH_CHIP_STM32F373RC is not set +# CONFIG_ARCH_CHIP_STM32F373VC is not set +# CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F411RE is not set +# CONFIG_ARCH_CHIP_STM32F411VE is not set +# CONFIG_ARCH_CHIP_STM32F405RG is not set +# CONFIG_ARCH_CHIP_STM32F405VG is not set +# CONFIG_ARCH_CHIP_STM32F405ZG is not set +# CONFIG_ARCH_CHIP_STM32F407VE is not set +CONFIG_ARCH_CHIP_STM32F407VG=y +# CONFIG_ARCH_CHIP_STM32F407ZE is not set +# CONFIG_ARCH_CHIP_STM32F407ZG is not set +# CONFIG_ARCH_CHIP_STM32F407IE is not set +# CONFIG_ARCH_CHIP_STM32F407IG is not set +# CONFIG_ARCH_CHIP_STM32F427V is not set +# CONFIG_ARCH_CHIP_STM32F427Z is not set +# CONFIG_ARCH_CHIP_STM32F427I is not set +# CONFIG_ARCH_CHIP_STM32F429V is not set +# CONFIG_ARCH_CHIP_STM32F429Z is not set +# CONFIG_ARCH_CHIP_STM32F429I is not set +# CONFIG_ARCH_CHIP_STM32F429B is not set +# CONFIG_ARCH_CHIP_STM32F429N is not set +# CONFIG_ARCH_CHIP_STM32F446M is not set +# CONFIG_ARCH_CHIP_STM32F446R is not set +# CONFIG_ARCH_CHIP_STM32F446V is not set +# CONFIG_ARCH_CHIP_STM32F446Z is not set +# CONFIG_ARCH_CHIP_STM32F469A is not set +# CONFIG_ARCH_CHIP_STM32F469I is not set +# CONFIG_ARCH_CHIP_STM32F469B is not set +# CONFIG_ARCH_CHIP_STM32F469N is not set +CONFIG_STM32_FLASH_CONFIG_DEFAULT=y +# CONFIG_STM32_FLASH_CONFIG_4 is not set +# CONFIG_STM32_FLASH_CONFIG_6 is not set +# CONFIG_STM32_FLASH_CONFIG_8 is not set +# CONFIG_STM32_FLASH_CONFIG_B is not set +# CONFIG_STM32_FLASH_CONFIG_C is not set +# CONFIG_STM32_FLASH_CONFIG_D is not set +# CONFIG_STM32_FLASH_CONFIG_E is not set +# CONFIG_STM32_FLASH_CONFIG_F is not set +# CONFIG_STM32_FLASH_CONFIG_G is not set +# CONFIG_STM32_FLASH_CONFIG_I is not set +# CONFIG_STM32_STM32L15XX is not set +# CONFIG_STM32_ENERGYLITE is not set +# CONFIG_STM32_STM32F10XX is not set +# CONFIG_STM32_VALUELINE is not set +# CONFIG_STM32_CONNECTIVITYLINE is not set +# CONFIG_STM32_PERFORMANCELINE is not set +# CONFIG_STM32_USBACCESSLINE is not set +# CONFIG_STM32_HIGHDENSITY is not set +# CONFIG_STM32_MEDIUMDENSITY is not set +# CONFIG_STM32_LOWDENSITY is not set +# CONFIG_STM32_STM32F20XX is not set +# CONFIG_STM32_STM32F205 is not set +# CONFIG_STM32_STM32F207 is not set +# CONFIG_STM32_STM32F30XX is not set +# CONFIG_STM32_STM32F302 is not set +# CONFIG_STM32_STM32F303 is not set +# CONFIG_STM32_STM32F33XX is not set +# CONFIG_STM32_STM32F37XX is not set +CONFIG_STM32_STM32F40XX=y +# CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F411 is not set +# CONFIG_STM32_STM32F405 is not set +CONFIG_STM32_STM32F407=y +# CONFIG_STM32_STM32F427 is not set +# CONFIG_STM32_STM32F429 is not set +# CONFIG_STM32_STM32F446 is not set +# CONFIG_STM32_STM32F469 is not set +# CONFIG_STM32_DFU is not set + +# +# STM32 Peripheral Support +# +CONFIG_STM32_HAVE_CCM=y +# CONFIG_STM32_HAVE_USBDEV is not set +CONFIG_STM32_HAVE_OTGFS=y +CONFIG_STM32_HAVE_FSMC=y +# CONFIG_STM32_HAVE_HRTIM1 is not set +# CONFIG_STM32_HAVE_LTDC is not set +CONFIG_STM32_HAVE_USART3=y +CONFIG_STM32_HAVE_UART4=y +CONFIG_STM32_HAVE_UART5=y +CONFIG_STM32_HAVE_USART6=y +# CONFIG_STM32_HAVE_UART7 is not set +# CONFIG_STM32_HAVE_UART8 is not set +CONFIG_STM32_HAVE_TIM1=y +CONFIG_STM32_HAVE_TIM2=y +CONFIG_STM32_HAVE_TIM3=y +CONFIG_STM32_HAVE_TIM4=y +CONFIG_STM32_HAVE_TIM5=y +CONFIG_STM32_HAVE_TIM6=y +CONFIG_STM32_HAVE_TIM7=y +CONFIG_STM32_HAVE_TIM8=y +CONFIG_STM32_HAVE_TIM9=y +CONFIG_STM32_HAVE_TIM10=y +CONFIG_STM32_HAVE_TIM11=y +CONFIG_STM32_HAVE_TIM12=y +CONFIG_STM32_HAVE_TIM13=y +CONFIG_STM32_HAVE_TIM14=y +# CONFIG_STM32_HAVE_TIM15 is not set +# CONFIG_STM32_HAVE_TIM16 is not set +# CONFIG_STM32_HAVE_TIM17 is not set +CONFIG_STM32_HAVE_ADC2=y +CONFIG_STM32_HAVE_ADC3=y +# CONFIG_STM32_HAVE_ADC4 is not set +# CONFIG_STM32_HAVE_ADC1_DMA is not set +# CONFIG_STM32_HAVE_ADC2_DMA is not set +# CONFIG_STM32_HAVE_ADC3_DMA is not set +# CONFIG_STM32_HAVE_ADC4_DMA is not set +# CONFIG_STM32_HAVE_SDADC1 is not set +# CONFIG_STM32_HAVE_SDADC2 is not set +# CONFIG_STM32_HAVE_SDADC3 is not set +# CONFIG_STM32_HAVE_SDADC1_DMA is not set +# CONFIG_STM32_HAVE_SDADC2_DMA is not set +# CONFIG_STM32_HAVE_SDADC3_DMA is not set +CONFIG_STM32_HAVE_CAN1=y +CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP6 is not set +CONFIG_STM32_HAVE_DAC1=y +CONFIG_STM32_HAVE_DAC2=y +CONFIG_STM32_HAVE_RNG=y +CONFIG_STM32_HAVE_ETHMAC=y +CONFIG_STM32_HAVE_I2C2=y +CONFIG_STM32_HAVE_I2C3=y +CONFIG_STM32_HAVE_SPI2=y +CONFIG_STM32_HAVE_SPI3=y +# CONFIG_STM32_HAVE_SPI4 is not set +# CONFIG_STM32_HAVE_SPI5 is not set +# CONFIG_STM32_HAVE_SPI6 is not set +# CONFIG_STM32_HAVE_SAIPLL is not set +# CONFIG_STM32_HAVE_I2SPLL is not set +# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_ADC1 is not set +# CONFIG_STM32_ADC2 is not set +# CONFIG_STM32_ADC3 is not set +# CONFIG_STM32_BKPSRAM is not set +# CONFIG_STM32_CAN1 is not set +# CONFIG_STM32_CAN2 is not set +# CONFIG_STM32_CCMDATARAM is not set +# CONFIG_STM32_CRC is not set +# CONFIG_STM32_CRYP is not set +# CONFIG_STM32_DMA1 is not set +# CONFIG_STM32_DMA2 is not set +# CONFIG_STM32_DAC1 is not set +# CONFIG_STM32_DAC2 is not set +# CONFIG_STM32_DCMI is not set +# CONFIG_STM32_ETHMAC is not set +# CONFIG_STM32_FSMC is not set +# CONFIG_STM32_HASH is not set +# CONFIG_STM32_I2C1 is not set +# CONFIG_STM32_I2C2 is not set +# CONFIG_STM32_I2C3 is not set +CONFIG_STM32_OTGFS=y +# CONFIG_STM32_OTGHS is not set +CONFIG_STM32_PWR=y +# CONFIG_STM32_RNG is not set +# CONFIG_STM32_SDIO is not set +# CONFIG_STM32_SPI1 is not set +# CONFIG_STM32_SPI2 is not set +CONFIG_STM32_SPI3=y +CONFIG_STM32_SYSCFG=y +# CONFIG_STM32_TIM1 is not set +# CONFIG_STM32_TIM2 is not set +# CONFIG_STM32_TIM3 is not set +# CONFIG_STM32_TIM4 is not set +# CONFIG_STM32_TIM5 is not set +# CONFIG_STM32_TIM6 is not set +# CONFIG_STM32_TIM7 is not set +# CONFIG_STM32_TIM8 is not set +# CONFIG_STM32_TIM9 is not set +# CONFIG_STM32_TIM10 is not set +# CONFIG_STM32_TIM11 is not set +# CONFIG_STM32_TIM12 is not set +# CONFIG_STM32_TIM13 is not set +# CONFIG_STM32_TIM14 is not set +# CONFIG_STM32_USART1 is not set +# CONFIG_STM32_USART2 is not set +CONFIG_STM32_USART3=y +# CONFIG_STM32_UART4 is not set +# CONFIG_STM32_UART5 is not set +# CONFIG_STM32_USART6 is not set +# CONFIG_STM32_IWDG is not set +# CONFIG_STM32_WWDG is not set +CONFIG_STM32_SPI=y +# CONFIG_STM32_NOEXT_VECTORS is not set + +# +# Alternate Pin Mapping +# +# CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set +# CONFIG_STM32_JTAG_DISABLE is not set +# CONFIG_STM32_JTAG_FULL_ENABLE is not set +# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y +# CONFIG_STM32_FORCEPOWER is not set +# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set +CONFIG_STM32_CCMEXCLUDE=y + +# +# Timer Configuration +# +# CONFIG_STM32_ONESHOT is not set +# CONFIG_STM32_FREERUN is not set +# CONFIG_STM32_TIM1_CAP is not set +# CONFIG_STM32_TIM2_CAP is not set +# CONFIG_STM32_TIM3_CAP is not set +# CONFIG_STM32_TIM4_CAP is not set +# CONFIG_STM32_TIM5_CAP is not set +# CONFIG_STM32_TIM8_CAP is not set +# CONFIG_STM32_TIM9_CAP is not set +# CONFIG_STM32_TIM10_CAP is not set +# CONFIG_STM32_TIM11_CAP is not set +# CONFIG_STM32_TIM12_CAP is not set +# CONFIG_STM32_TIM13_CAP is not set +# CONFIG_STM32_TIM14_CAP is not set +CONFIG_STM32_USART=y +CONFIG_STM32_SERIALDRIVER=y + +# +# U[S]ART Configuration +# + +# +# U[S]ART Device Configuration +# +CONFIG_STM32_USART3_SERIALDRIVER=y +# CONFIG_STM32_USART3_1WIREDRIVER is not set +# CONFIG_USART3_RS485 is not set + +# +# Serial Driver Configuration +# +# CONFIG_SERIAL_DISABLE_REORDERING is not set +# CONFIG_STM32_FLOWCONTROL_BROKEN is not set +# CONFIG_STM32_USART_BREAKS is not set +# CONFIG_STM32_USART_SINGLEWIRE is not set + +# +# SPI Configuration +# +# CONFIG_STM32_SPI_INTERRUPTS is not set +# CONFIG_STM32_SPI_DMA is not set +# CONFIG_STM32_HAVE_RTC_COUNTER is not set +# CONFIG_STM32_HAVE_RTC_SUBSECONDS is not set + +# +# USB FS Host Configuration +# +CONFIG_STM32_OTGFS_RXFIFO_SIZE=128 +CONFIG_STM32_OTGFS_NPTXFIFO_SIZE=96 +CONFIG_STM32_OTGFS_PTXFIFO_SIZE=128 +CONFIG_STM32_OTGFS_DESCSIZE=128 +# CONFIG_STM32_OTGFS_SOFINTR is not set + +# +# USB HS Host Configuration +# + +# +# USB Host Debug Configuration +# + +# +# USB Device Configuration +# + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_VECNOTIRQ is not set +# CONFIG_ARCH_DMA is not set +CONFIG_ARCH_HAVE_IRQPRIO=y +# CONFIG_ARCH_L2CACHE is not set +# CONFIG_ARCH_HAVE_COHERENT_DCACHE is not set +# CONFIG_ARCH_HAVE_ADDRENV is not set +# CONFIG_ARCH_NEED_ADDRENV_MAPPING is not set +# CONFIG_ARCH_HAVE_MULTICPU is not set +CONFIG_ARCH_HAVE_VFORK=y +# CONFIG_ARCH_HAVE_MMU is not set +CONFIG_ARCH_HAVE_MPU=y +# CONFIG_ARCH_NAND_HWECC is not set +# CONFIG_ARCH_HAVE_EXTCLK is not set +# CONFIG_ARCH_HAVE_POWEROFF is not set +CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_USE_MPU is not set +# CONFIG_ARCH_IRQPRIO is not set +CONFIG_ARCH_STACKDUMP=y +# CONFIG_ENDIAN_BIG is not set +# CONFIG_ARCH_IDLE_CUSTOM is not set +# CONFIG_ARCH_HAVE_RAMFUNCS is not set +CONFIG_ARCH_HAVE_RAMVECTORS=y +# CONFIG_ARCH_RAMVECTORS is not set +# CONFIG_ARCH_MINIMAL_VECTORTABLE is not set + +# +# Board Settings +# +CONFIG_BOARD_LOOPSPERMSEC=16717 +# CONFIG_ARCH_CALIBRATION is not set + +# +# Interrupt options +# +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y +CONFIG_ARCH_INTERRUPTSTACK=0 +CONFIG_ARCH_HAVE_HIPRI_INTERRUPT=y +# CONFIG_ARCH_HIPRI_INTERRUPT is not set + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Boot Memory Configuration +# +CONFIG_RAM_START=0x20000000 +CONFIG_RAM_SIZE=131072 +# CONFIG_ARCH_HAVE_SDRAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_CLICKER2_STM32=y +# CONFIG_ARCH_BOARD_STM32F4_DISCOVERY is not set +# CONFIG_ARCH_BOARD_MIKROE_STM32F4 is not set +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="clicker2-stm32" + +# +# Common Board Options +# +CONFIG_ARCH_HAVE_LEDS=y +CONFIG_ARCH_LEDS=y +CONFIG_ARCH_HAVE_BUTTONS=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_HAVE_IRQBUTTONS=y +CONFIG_ARCH_IRQBUTTONS=y + +# +# Board-Specific Options +# +CONFIG_CLICKER2_STM32_MB1_SPI=y +# CONFIG_CLICKER2_STM32_MB2_SPI is not set +CONFIG_CLICKER2_STM32_MB1_BEE=y +# CONFIG_CLICKER2_STM32_MB2_BEE is not set +# CONFIG_BOARD_CRASHDUMP is not set +CONFIG_LIB_BOARDCTL=y +# CONFIG_BOARDCTL_RESET is not set +# CONFIG_BOARDCTL_UNIQUEID is not set +# CONFIG_BOARDCTL_TSCTEST is not set +# CONFIG_BOARDCTL_GRAPHICS is not set +# CONFIG_BOARDCTL_IOCTL is not set + +# +# RTOS Features +# +CONFIG_DISABLE_OS_API=y +# CONFIG_DISABLE_POSIX_TIMERS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_DISABLE_SIGNALS is not set +# CONFIG_DISABLE_MQUEUE is not set +# CONFIG_DISABLE_ENVIRON is not set + +# +# Clocks and Timers +# +CONFIG_ARCH_HAVE_TICKLESS=y +# CONFIG_SCHED_TICKLESS is not set +CONFIG_USEC_PER_TICK=10000 +# CONFIG_SYSTEM_TIME64 is not set +# CONFIG_CLOCK_MONOTONIC is not set +CONFIG_ARCH_HAVE_TIMEKEEPING=y +# CONFIG_JULIAN_TIME is not set +CONFIG_START_YEAR=2013 +CONFIG_START_MONTH=1 +CONFIG_START_DAY=1 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=8 +CONFIG_WDOG_INTRESERVE=1 +CONFIG_PREALLOC_TIMERS=4 + +# +# Tasks and Scheduling +# +# CONFIG_SPINLOCK is not set +# CONFIG_INIT_NONE is not set +CONFIG_INIT_ENTRYPOINT=y +# CONFIG_INIT_FILEPATH is not set +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_RR_INTERVAL=200 +# CONFIG_SCHED_SPORADIC is not set +CONFIG_TASK_NAME_SIZE=32 +CONFIG_MAX_TASKS=16 +# CONFIG_SCHED_HAVE_PARENT is not set +CONFIG_SCHED_WAITPID=y + +# +# Pthread Options +# +# CONFIG_MUTEX_TYPES is not set +CONFIG_NPTHREAD_KEYS=4 +# CONFIG_PTHREAD_CLEANUP is not set +# CONFIG_CANCELLATION_POINTS is not set + +# +# Performance Monitoring +# +# CONFIG_SCHED_CPULOAD is not set +# CONFIG_SCHED_INSTRUMENTATION is not set + +# +# Files and I/O +# +CONFIG_DEV_CONSOLE=y +# CONFIG_FDCLONE_DISABLE is not set +# CONFIG_FDCLONE_STDIO is not set +CONFIG_SDCLONE_DISABLE=y +CONFIG_NFILE_DESCRIPTORS=8 +CONFIG_NFILE_STREAMS=8 +CONFIG_NAME_MAX=32 +# CONFIG_PRIORITY_INHERITANCE is not set + +# +# RTOS hooks +# +CONFIG_BOARD_INITIALIZE=y +# CONFIG_BOARD_INITTHREAD is not set +# CONFIG_SCHED_STARTHOOK is not set +# CONFIG_SCHED_ATEXIT is not set +# CONFIG_SCHED_ONEXIT is not set +# CONFIG_SIG_EVTHREAD is not set + +# +# Signal Numbers +# +CONFIG_SIG_SIGUSR1=1 +CONFIG_SIG_SIGUSR2=2 +CONFIG_SIG_SIGALARM=3 +CONFIG_SIG_SIGCONDTIMEDOUT=16 +CONFIG_SIG_SIGWORK=17 + +# +# POSIX Message Queue Options +# +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_MQ_MAXMSGSIZE=32 +# CONFIG_MODULE is not set + +# +# Work queue support +# +CONFIG_SCHED_WORKQUEUE=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=192 +CONFIG_SCHED_HPWORKPERIOD=50000 +CONFIG_SCHED_HPWORKSTACKSIZE=2048 +# CONFIG_SCHED_LPWORK is not set + +# +# Stack and heap information +# +CONFIG_IDLETHREAD_STACKSIZE=1024 +CONFIG_USERMAIN_STACKSIZE=2048 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=2048 +# CONFIG_LIB_SYSCALL is not set + +# +# Device Drivers +# +CONFIG_DISABLE_POLL=y +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_DEV_URANDOM is not set +# CONFIG_DEV_LOOP is not set + +# +# Buffering +# +# CONFIG_DRVR_WRITEBUFFER is not set +# CONFIG_DRVR_READAHEAD is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_ARCH_HAVE_PWM_PULSECOUNT is not set +# CONFIG_ARCH_HAVE_PWM_MULTICHAN is not set +# CONFIG_PWM is not set +CONFIG_ARCH_HAVE_I2CRESET=y +# CONFIG_I2C is not set +# CONFIG_ARCH_HAVE_SPI_CRCGENERATION is not set +# CONFIG_ARCH_HAVE_SPI_CS_CONTROL is not set +CONFIG_ARCH_HAVE_SPI_BITORDER=y +CONFIG_SPI=y +# CONFIG_SPI_SLAVE is not set +CONFIG_SPI_EXCHANGE=y +# CONFIG_SPI_CMDDATA is not set +# CONFIG_SPI_CALLBACK is not set +# CONFIG_SPI_HWFEATURES is not set +# CONFIG_SPI_BITORDER is not set +# CONFIG_SPI_CS_DELAY_CONTROL is not set +# CONFIG_SPI_DRIVER is not set +# CONFIG_SPI_BITBANG is not set +# CONFIG_I2S is not set + +# +# Timer Driver Support +# +# CONFIG_TIMER is not set +# CONFIG_ONESHOT is not set +# CONFIG_RTC is not set +# CONFIG_WATCHDOG is not set +# CONFIG_ANALOG is not set +# CONFIG_AUDIO_DEVICES is not set +# CONFIG_VIDEO_DEVICES is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set + +# +# IO Expander/GPIO Support +# +# CONFIG_IOEXPANDER is not set +# CONFIG_DEV_GPIO is not set + +# +# LCD Driver Support +# +# CONFIG_LCD is not set +# CONFIG_SLCD is not set + +# +# LED Support +# +# CONFIG_USERLED is not set +# CONFIG_RGBLED is not set +# CONFIG_PCA9635PW is not set +# CONFIG_NCP5623C is not set +# CONFIG_MMCSD is not set +# CONFIG_MODEM is not set +# CONFIG_MTD is not set +# CONFIG_EEPROM is not set +# CONFIG_PIPES is not set +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +CONFIG_SERIAL=y +# CONFIG_DEV_LOWCONSOLE is not set +# CONFIG_SERIAL_REMOVABLE is not set +CONFIG_SERIAL_CONSOLE=y +# CONFIG_16550_UART is not set +# CONFIG_UART_SERIALDRIVER is not set +# CONFIG_UART0_SERIALDRIVER is not set +# CONFIG_UART1_SERIALDRIVER is not set +# CONFIG_UART2_SERIALDRIVER is not set +# CONFIG_UART3_SERIALDRIVER is not set +# CONFIG_UART4_SERIALDRIVER is not set +# CONFIG_UART5_SERIALDRIVER is not set +# CONFIG_UART6_SERIALDRIVER is not set +# CONFIG_UART7_SERIALDRIVER is not set +# CONFIG_UART8_SERIALDRIVER is not set +# CONFIG_SCI0_SERIALDRIVER is not set +# CONFIG_SCI1_SERIALDRIVER is not set +# CONFIG_USART0_SERIALDRIVER is not set +# CONFIG_USART1_SERIALDRIVER is not set +# CONFIG_USART2_SERIALDRIVER is not set +CONFIG_USART3_SERIALDRIVER=y +# CONFIG_USART4_SERIALDRIVER is not set +# CONFIG_USART5_SERIALDRIVER is not set +# CONFIG_USART6_SERIALDRIVER is not set +# CONFIG_USART7_SERIALDRIVER is not set +# CONFIG_USART8_SERIALDRIVER is not set +# CONFIG_OTHER_UART_SERIALDRIVER is not set +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +# CONFIG_SERIAL_IFLOWCONTROL is not set +# CONFIG_SERIAL_OFLOWCONTROL is not set +# CONFIG_SERIAL_DMA is not set +CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y +CONFIG_USART3_SERIAL_CONSOLE=y +# CONFIG_OTHER_SERIAL_CONSOLE is not set +# CONFIG_NO_SERIAL_CONSOLE is not set + +# +# USART3 Configuration +# +CONFIG_USART3_RXBUFSIZE=256 +CONFIG_USART3_TXBUFSIZE=256 +CONFIG_USART3_BAUD=115200 +CONFIG_USART3_BITS=8 +CONFIG_USART3_PARITY=0 +CONFIG_USART3_2STOP=0 +# CONFIG_USART3_IFLOWCONTROL is not set +# CONFIG_USART3_OFLOWCONTROL is not set +# CONFIG_USART3_DMA is not set +# CONFIG_PSEUDOTERM is not set +# CONFIG_USBDEV is not set +CONFIG_USBHOST=y +CONFIG_USBHOST_NPREALLOC=4 +CONFIG_USBHOST_HAVE_ASYNCH=y +# CONFIG_USBHOST_ASYNCH is not set +# CONFIG_USBHOST_HUB is not set +# CONFIG_USBHOST_COMPOSITE is not set +CONFIG_USBHOST_MSC=y +# CONFIG_USBHOST_CDCACM is not set +# CONFIG_USBHOST_HIDKBD is not set +# CONFIG_USBHOST_HIDMOUSE is not set +# CONFIG_USBHOST_XBOXCONTROLLER is not set +# CONFIG_USBHOST_TRACE is not set +# CONFIG_HAVE_USBTRACE is not set +CONFIG_DRIVERS_WIRELESS=y +# CONFIG_WL_CC1101 is not set +# CONFIG_WL_CC3000 is not set +CONFIG_DRIVERS_IEEE802154=y +CONFIG_IEEE802154_MRF24J40=y +# CONFIG_IEEE802154_AT86RF233 is not set +# CONFIG_DRIVERS_IEEE80211 is not set +# CONFIG_WL_NRF24L01 is not set +# CONFIG_DRIVERS_CONTACTLESS is not set + +# +# System Logging +# +# CONFIG_ARCH_SYSLOG is not set +# CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_INTBUFFER is not set +# CONFIG_SYSLOG_TIMESTAMP is not set +CONFIG_SYSLOG_SERIAL_CONSOLE=y +# CONFIG_SYSLOG_CHAR is not set +CONFIG_SYSLOG_CONSOLE=y +# CONFIG_SYSLOG_NONE is not set +# CONFIG_SYSLOG_FILE is not set +# CONFIG_SYSLOG_CHARDEV is not set + +# +# Networking Support +# +# CONFIG_ARCH_HAVE_NET is not set +# CONFIG_ARCH_HAVE_PHY is not set +# CONFIG_NET is not set + +# +# Crypto API +# +# CONFIG_CRYPTO is not set + +# +# File Systems +# + +# +# File system configuration +# +# CONFIG_DISABLE_MOUNTPOINT is not set +# CONFIG_FS_AUTOMOUNTER is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_PSEUDOFS_SOFTLINKS is not set +CONFIG_FS_READABLE=y +CONFIG_FS_WRITABLE=y +# CONFIG_FS_NAMED_SEMAPHORES is not set +CONFIG_FS_MQUEUE_MPATH="/var/mqueue" +# CONFIG_FS_RAMMAP is not set +CONFIG_FS_FAT=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_MAXFNAME=32 +# CONFIG_FS_FATTIME is not set +# CONFIG_FAT_FORCE_INDIRECT is not set +# CONFIG_FAT_DMAMEMORY is not set +# CONFIG_FAT_DIRECT_RETRY is not set +# CONFIG_FS_NXFFS is not set +# CONFIG_FS_ROMFS is not set +# CONFIG_FS_TMPFS is not set +# CONFIG_FS_SMARTFS is not set +# CONFIG_FS_BINFS is not set +CONFIG_FS_PROCFS=y +# CONFIG_FS_PROCFS_REGISTER is not set + +# +# Exclude individual procfs entries +# +# CONFIG_FS_PROCFS_EXCLUDE_PROCESS is not set +# CONFIG_FS_PROCFS_EXCLUDE_UPTIME is not set +# CONFIG_FS_PROCFS_EXCLUDE_MOUNTS is not set +# CONFIG_FS_UNIONFS is not set + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=1 +# CONFIG_ARCH_HAVE_HEAP2 is not set +# CONFIG_GRAN is not set + +# +# Audio Support +# +# CONFIG_AUDIO is not set + +# +# Wireless Support +# +CONFIG_WIRELESS=y +CONFIG_WIRELESS_IEEE802154=y +CONFIG_IEEE802154_MAC=y +CONFIG_IEEE802154_DEV=y + +# +# Binary Loader +# +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_BINFMT_EXEPATH is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +CONFIG_BUILTIN=y +# CONFIG_PIC is not set +# CONFIG_SYMTAB_ORDEREDBYNAME is not set + +# +# Library Routines +# + +# +# Standard C Library Options +# + +# +# Standard C I/O +# +# CONFIG_STDIO_DISABLE_BUFFERING is not set +CONFIG_STDIO_BUFFER_SIZE=64 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +# CONFIG_NOPRINTF_FIELDWIDTH is not set +# CONFIG_LIBC_FLOATINGPOINT is not set +CONFIG_LIBC_LONG_LONG=y +# CONFIG_LIBC_SCANSET is not set +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_MEMCPY_VIK is not set +# CONFIG_LIBM is not set + +# +# Architecture-Specific Support +# +CONFIG_ARCH_LOWPUTC=y +# CONFIG_ARCH_ROMGETC is not set +# CONFIG_LIBC_ARCH_MEMCPY is not set +# CONFIG_LIBC_ARCH_MEMCMP is not set +# CONFIG_LIBC_ARCH_MEMMOVE is not set +# CONFIG_LIBC_ARCH_MEMSET is not set +# CONFIG_LIBC_ARCH_STRCHR is not set +# CONFIG_LIBC_ARCH_STRCMP is not set +# CONFIG_LIBC_ARCH_STRCPY is not set +# CONFIG_LIBC_ARCH_STRNCPY is not set +# CONFIG_LIBC_ARCH_STRLEN is not set +# CONFIG_LIBC_ARCH_STRNLEN is not set +# CONFIG_LIBC_ARCH_ELF is not set +# CONFIG_ARMV7M_MEMCPY is not set + +# +# stdlib Options +# +CONFIG_LIB_RAND_ORDER=1 +CONFIG_LIB_HOMEDIR="/" +CONFIG_LIBC_TMPDIR="/tmp" +CONFIG_LIBC_MAX_TMPFILE=32 + +# +# Program Execution Options +# +# CONFIG_LIBC_EXECFUNCS is not set +CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024 +CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=2048 + +# +# errno Decode Support +# +# CONFIG_LIBC_STRERROR is not set +# CONFIG_LIBC_PERROR_STDOUT is not set + +# +# memcpy/memset Options +# +# CONFIG_MEMSET_OPTSPEED is not set +# CONFIG_LIBC_DLLFCN is not set +# CONFIG_LIBC_MODLIB is not set +# CONFIG_LIBC_WCHAR is not set +# CONFIG_LIBC_LOCALE is not set + +# +# Time/Time Zone Support +# +# CONFIG_LIBC_LOCALTIME is not set +# CONFIG_TIME_EXTENDED is not set +CONFIG_ARCH_HAVE_TLS=y + +# +# Thread Local Storage (TLS) +# +# CONFIG_TLS is not set + +# +# Network-Related Options +# +# CONFIG_LIBC_IPv4_ADDRCONV is not set +# CONFIG_LIBC_IPv6_ADDRCONV is not set +# CONFIG_LIBC_NETDB is not set + +# +# NETDB Support +# +# CONFIG_NETDB_HOSTFILE is not set +# CONFIG_LIBC_IOCTL_VARIADIC is not set +CONFIG_LIB_SENDFILE_BUFSIZE=512 + +# +# Non-standard Library Support +# +# CONFIG_LIB_CRC64_FAST is not set +# CONFIG_LIB_KBDCODEC is not set +# CONFIG_LIB_SLCDCODEC is not set +# CONFIG_LIB_HEX2BIN is not set + +# +# Basic CXX Support +# +# CONFIG_C99_BOOL8 is not set +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +# CONFIG_CXX_NEWLONG is not set + +# +# LLVM C++ Library (libcxx) +# +# CONFIG_LIBCXX is not set + +# +# uClibc++ Standard C++ Library +# +# CONFIG_UCLIBCXX is not set + +# +# Application Configuration +# + +# +# Built-In Applications +# +CONFIG_BUILTIN_PROXY_STACKSIZE=1024 + +# +# CAN Utilities +# + +# +# Examples +# +# CONFIG_EXAMPLES_BUTTONS is not set +# CONFIG_EXAMPLES_CCTYPE is not set +# CONFIG_EXAMPLES_CHAT is not set +# CONFIG_EXAMPLES_CONFIGDATA is not set +# CONFIG_EXAMPLES_CXXTEST is not set +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FSTEST is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HELLOXX is not set +# CONFIG_EXAMPLES_HIDKBD is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_JSON is not set +# CONFIG_EXAMPLES_KEYPADTEST is not set +# CONFIG_EXAMPLES_MEDIA is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MODBUS is not set +# CONFIG_EXAMPLES_MOUNT is not set +# CONFIG_EXAMPLES_NRF24L01TERM is not set +CONFIG_EXAMPLES_NSH=y +CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NXLINES is not set +# CONFIG_EXAMPLES_NXTERM is not set +# CONFIG_EXAMPLES_NXTEXT is not set +# CONFIG_EXAMPLES_OSTEST is not set +# CONFIG_EXAMPLES_PCA9635 is not set +# CONFIG_EXAMPLES_POSIXSPAWN is not set +# CONFIG_EXAMPLES_PPPD is not set +# CONFIG_EXAMPLES_RFID_READUID is not set +# CONFIG_EXAMPLES_RGBLED is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERIALBLASTER is not set +# CONFIG_EXAMPLES_SERIALRX is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_SLCD is not set +# CONFIG_EXAMPLES_SMART is not set +# CONFIG_EXAMPLES_SMART_TEST is not set +# CONFIG_EXAMPLES_SMP is not set +# CONFIG_EXAMPLES_STAT is not set +# CONFIG_EXAMPLES_TCPECHO is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_USBSERIAL is not set +# CONFIG_EXAMPLES_WATCHDOG is not set +# CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set + +# +# File System Utilities +# +# CONFIG_FSUTILS_INIFILE is not set +# CONFIG_FSUTILS_PASSWD is not set + +# +# GPS Utilities +# +# CONFIG_GPSUTILS_MINMEA_LIB is not set + +# +# Graphics Support +# +# CONFIG_TIFF is not set +# CONFIG_GRAPHICS_TRAVELER is not set + +# +# IEEE 802.15.4 applications +# +CONFIG_IEEE802154_COMMON=y +CONFIG_IEEE802154_COORD=y +CONFIG_IEEE802154_I8SAK=y + +# +# Interpreters +# +# CONFIG_INTERPRETERS_BAS is not set +# CONFIG_INTERPRETERS_FICL is not set +# CONFIG_INTERPRETERS_MICROPYTHON is not set +# CONFIG_INTERPRETERS_MINIBASIC is not set +# CONFIG_INTERPRETERS_PCODE is not set + +# +# FreeModBus +# +# CONFIG_MODBUS is not set + +# +# Network Utilities +# +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_ESP8266 is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_JSON is not set +# CONFIG_NETUTILS_SMTP is not set + +# +# NSH Library +# +CONFIG_NSH_LIBRARY=y +# CONFIG_NSH_MOTD is not set + +# +# Command Line Configuration +# +CONFIG_NSH_READLINE=y +# CONFIG_NSH_CLE is not set +CONFIG_NSH_LINELEN=64 +# CONFIG_NSH_DISABLE_SEMICOLON is not set +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_MAXARGUMENTS=6 +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_NESTDEPTH=3 +# CONFIG_NSH_DISABLEBG is not set +CONFIG_NSH_BUILTIN_APPS=y + +# +# Disable Individual commands +# +# CONFIG_NSH_DISABLE_ADDROUTE is not set +# CONFIG_NSH_DISABLE_BASENAME is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_CMP is not set +CONFIG_NSH_DISABLE_DATE=y +# CONFIG_NSH_DISABLE_DD is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_DELROUTE is not set +# CONFIG_NSH_DISABLE_DIRNAME is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_FREE is not set +CONFIG_NSH_DISABLE_GET=y +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_HEXDUMP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +CONFIG_NSH_DISABLE_IFUPDOWN=y +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOSETUP is not set +CONFIG_NSH_DISABLE_LOSMART=y +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MB is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MKRD is not set +# CONFIG_NSH_DISABLE_MH is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_MW is not set +CONFIG_NSH_DISABLE_PRINTF=y +# CONFIG_NSH_DISABLE_PS is not set +CONFIG_NSH_DISABLE_PUT=y +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SH is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNAME is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_NSH_DISABLE_WGET=y +# CONFIG_NSH_DISABLE_XD is not set +CONFIG_NSH_MMCSDMINOR=0 + +# +# Configure Command Options +# +# CONFIG_NSH_CMDOPT_DF_H is not set +# CONFIG_NSH_CMDOPT_DD_STATS is not set +CONFIG_NSH_CODECS_BUFSIZE=128 +CONFIG_NSH_CMDOPT_HEXDUMP=y +CONFIG_NSH_PROC_MOUNTPOINT="/proc" +CONFIG_NSH_FILEIOSIZE=512 + +# +# Scripting Support +# +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_LOOPS is not set + +# +# Console Configuration +# +CONFIG_NSH_CONSOLE=y +# CONFIG_NSH_ALTCONDEV is not set +CONFIG_NSH_ARCHINIT=y +# CONFIG_NSH_LOGIN is not set +# CONFIG_NSH_CONSOLE_LOGIN is not set + +# +# NxWidgets/NxWM +# + +# +# Platform-specific Support +# +# CONFIG_PLATFORM_CONFIGDATA is not set + +# +# System Libraries and NSH Add-Ons +# +# CONFIG_SYSTEM_CLE is not set +# CONFIG_SYSTEM_CUTERM is not set +# CONFIG_SYSTEM_FREE is not set +# CONFIG_SYSTEM_HEX2BIN is not set +# CONFIG_SYSTEM_HEXED is not set +# CONFIG_SYSTEM_INSTALL is not set +# CONFIG_SYSTEM_RAMTEST is not set +CONFIG_READLINE_HAVE_EXTMATCH=y +CONFIG_SYSTEM_READLINE=y +CONFIG_READLINE_ECHO=y +# CONFIG_READLINE_TABCOMPLETION is not set +# CONFIG_READLINE_CMD_HISTORY is not set +# CONFIG_SYSTEM_SUDOKU is not set +# CONFIG_SYSTEM_SYSTEM is not set +# CONFIG_SYSTEM_TEE is not set +# CONFIG_SYSTEM_UBLOXMODEM is not set +# CONFIG_SYSTEM_VI is not set +# CONFIG_SYSTEM_ZMODEM is not set diff --git a/configs/clicker2-stm32/mrf24j40_dev/setenv.sh b/configs/clicker2-stm32/mrf24j40_dev/setenv.sh new file mode 100644 index 0000000000..21d46fcc15 --- /dev/null +++ b/configs/clicker2-stm32/mrf24j40_dev/setenv.sh @@ -0,0 +1,80 @@ +#!/bin/bash +# configs/clicker2-stm32/mrf24j40_dev/setenv.sh +# +# 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. +# + +if [ "$_" = "$0" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +fi + +WD=`pwd` +if [ ! -x "setenv.sh" ]; then + echo "This script must be executed from the top-level NuttX build directory" + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then + export PATH_ORIG="${PATH}" +fi + +# This is the Cygwin path to the location where I installed the CodeSourcery +# toolchain under windows. You will also have to edit this if you install +# the CodeSourcery toolchain in any other location +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin" +# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin" + +# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors" +# You can this free toolchain here https://launchpad.net/gcc-arm-embedded +export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin" + +# This is the path to the location where I installed the devkitARM toolchain +# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/ +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin" + +# These are the Cygwin paths to the locations where I installed the Atollic +# toolchain under windows. You will also have to edit this if you install +# the Atollic toolchain in any other location. /usr/bin is added before +# the Atollic bin path because there is are binaries named gcc.exe and g++.exe +# at those locations as well. +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" + +# This is the Cygwin path to the location where I build the buildroot +# toolchain. +# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" + +# Add the path to the toolchain to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" + +echo "PATH : ${PATH}" diff --git a/drivers/wireless/Kconfig b/drivers/wireless/Kconfig index a3bab81d21..39622d66fd 100644 --- a/drivers/wireless/Kconfig +++ b/drivers/wireless/Kconfig @@ -20,7 +20,6 @@ source drivers/wireless/cc3000/Kconfig menuconfig DRIVERS_IEEE802154 bool "IEEE 802.15.4 Device Support" default n - depends on EXPERIMENTAL ---help--- This directory holds implementations of IEEE802.15.4 device drivers. @@ -29,7 +28,6 @@ source drivers/wireless/ieee802154/Kconfig menuconfig DRIVERS_IEEE80211 bool "IEEE 802.11 Device Support" default n - depends on EXPERIMENTAL ---help--- This directory holds implementations of IEEE802.11 device drivers. diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c index c4c353ce00..09365ebc83 100644 --- a/drivers/wireless/ieee802154/mrf24j40.c +++ b/drivers/wireless/ieee802154/mrf24j40.c @@ -138,7 +138,7 @@ static int mrf24j40_regdump(FAR struct mrf24j40_radio_s *dev); static void mrf24j40_irqwork_rx(FAR struct mrf24j40_radio_s *dev); static void mrf24j40_irqwork_tx(FAR struct mrf24j40_radio_s *dev); static void mrf24j40_irqworker(FAR void *arg); -static int mrf24j40_interrupt(int irq, FAR void *context); +static int mrf24j40_interrupt(int irq, FAR void *context, FAR void *arg); /* Driver operations */ @@ -1344,10 +1344,15 @@ static void mrf24j40_irqworker(FAR void *arg) * ****************************************************************************/ -static int mrf24j40_interrupt(int irq, FAR void *context) +static int mrf24j40_interrupt(int irq, FAR void *context, FAR void *arg) { /* To support multiple devices, * retrieve the priv structure using the irq number + * + * REVISIT: This will not handler multiple MRF24J40 devices. The correct + * solutions is to pass the struct mrf24j40_radio_s in the call to + * irq_attach() as the third 'arg' parameter. That will be provided here + * and the correct instance can be obtained with a simply case of 'arg'. */ register FAR struct mrf24j40_radio_s *dev = &g_mrf24j40_devices[0]; @@ -1398,7 +1403,11 @@ FAR struct ieee802154_radio_s *mrf24j40_init(FAR struct spi_dev_s *spi, dev = &g_mrf24j40_devices[0]; #endif - /* Attach irq */ + /* Attach irq. + * + * REVISIT: A third argument is required to pass the instance of 'lower' + * to the interrupt handler. + */ if (lower->attach(lower, mrf24j40_interrupt) != OK) { diff --git a/wireless/Kconfig b/wireless/Kconfig index 440e30a665..75f4ae1289 100644 --- a/wireless/Kconfig +++ b/wireless/Kconfig @@ -6,7 +6,6 @@ config WIRELESS bool "Wireless Support" default n - depends on EXPERIMENTAL ---help--- Enables overall support for Wireless library. diff --git a/wireless/ieee802154/Kconfig b/wireless/ieee802154/Kconfig index 770bbe0381..fa8793af3d 100644 --- a/wireless/ieee802154/Kconfig +++ b/wireless/ieee802154/Kconfig @@ -6,7 +6,6 @@ config WIRELESS_IEEE802154 bool "IEEE 802.15.4 Wireless Support" default n - depends on EXPERIMENTAL ---help--- Enables support for the IEEE 802.14.5 Wireless library. -- GitLab From fca35f7e5200a3f481e66376cb89c3abc191d784 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 24 Mar 2017 14:15:13 -0600 Subject: [PATCH 192/990] ieee80154: A few changes (some just guesses) to get a clean compilation. --- .../wireless/ieee802154/ieee802154_mac.h | 11 ++++- wireless/ieee802154/mac802154.c | 44 ++++++++++--------- 2 files changed, 33 insertions(+), 22 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index f4b408fdb9..407360d815 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -95,6 +95,7 @@ /* Frame Type */ +#define IEEE802154_FC1_FTYPE 0x03 #define IEEE802154_FRAME_BEACON 0x00 #define IEEE802154_FRAME_DATA 0x01 #define IEEE802154_FRAME_ACK 0x02 @@ -469,12 +470,12 @@ struct ieee802154_macops_s /* Start association with coordinator */ CODE int (*req_associate)(FAR struct ieee802154_mac_s *mac, - FAR struct ieee802154_assoc_request_s *request); + uint16_t panid, FAR uint8_t *coordeadr); /* Start disassociation with coordinator */ CODE int (*req_disassociate)(FAR struct ieee802154_mac_s *mac, - FAR struct ieee802154_disassoc_request_s *request); + FAR uint8_t *eadr, uint8_t reason); /* Read the PIB */ @@ -664,9 +665,15 @@ extern "C" * ****************************************************************************/ +#if 0 /* REVISIT: This form is not currently used by the driver */ FAR struct ieee802154_mac_s * mac802154_register(FAR struct ieee802154_radio_s *radiodev, FAR struct ieee802154_maccb_s *callbacks); +#else /* This is the form used by the driver */ +FAR struct ieee802154_mac_s * + mac802154_register(FAR struct ieee802154_radio_s *radiodev, + unsigned int minor); +#endif #undef EXTERN #ifdef __cplusplus diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index da4a711910..9703a0fe97 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -38,17 +38,19 @@ ****************************************************************************/ #include + +#include #include +#include #include -#include +#include #include /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ - /**************************************************************************** * Private Types ****************************************************************************/ @@ -143,21 +145,21 @@ static int mac802154_rsporphan(FAR struct ieee802154_mac_s *mac, static const struct ieee802154_macops_s mac802154ops = { - .req_data = mac802154_reqdata - .req_purge = mac802154_reqpurge - .req_associate = mac802154_reqassociate - .req_disassociate= mac802154_reqdisassociate - .req_get = mac802154_reqget - .req_gts = mac802154_reqgts - .req_reset = mac802154_reqreset - .req_rxenable = mac802154_reqrxenable - .req_scan = mac802154_reqscan - .req_set = mac802154_reqset - .req_start = mac802154_reqstart - .req_sync = mac802154_reqsync - .req_poll = mac802154_reqpoll - .rsp_associate = mac802154_rspassociate - .rsp_orphan = mac802154_rsporphan + .req_data = mac802154_reqdata, + .req_purge = mac802154_reqpurge, + .req_associate = mac802154_reqassociate, + .req_disassociate = mac802154_reqdisassociate, + .req_get = mac802154_reqget, + .req_gts = mac802154_reqgts, + .req_reset = mac802154_reqreset, + .req_rxenable = mac802154_reqrxenable, + .req_scan = mac802154_reqscan, + .req_set = mac802154_reqset, + .req_start = mac802154_reqstart, + .req_sync = mac802154_reqsync, + .req_poll = mac802154_reqpoll, + .rsp_associate = mac802154_rspassociate, + .rsp_orphan = mac802154_rsporphan, }; /**************************************************************************** @@ -192,12 +194,13 @@ static int mac802154_defaultmib(FAR struct ieee802154_privmac_s *priv) priv->macBeaconPayloadLength = 0; priv->macBSN = 0; /* Shall be random */ - priv->macCoordExtendedAddress[8]; + //priv->macCoordExtendedAddress[8]; priv->macCoordShortAddress = 0xffff; priv->macDSN = 0; /* Shall be random */ priv->macPANId = 0xffff; priv->macShortAddress = 0xffff; priv->macTransactionPersistenceTime = 0x01f4; + #if 0 /* Security MIB */ @@ -207,6 +210,8 @@ static int mac802154_defaultmib(FAR struct ieee802154_privmac_s *priv) priv->macDefaultSecurityMaterialLength = 0x15; priv->macSecurityMode = 0; #endif + + return OK; } /**************************************************************************** @@ -274,8 +279,7 @@ static int mac802154_reqpurge(FAR struct ieee802154_mac_s *mac, ****************************************************************************/ static int mac802154_reqassociate(FAR struct ieee802154_mac_s *mac, - uint16_t panid, - uint8_t *coordeadr) + uint16_t panid, FAR uint8_t *coordeadr) { FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; -- GitLab From 532940ae56a18e2e85adbc7cf0263a92d8d16571 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 24 Mar 2017 17:21:28 -0600 Subject: [PATCH 193/990] configs/: Rename all stm32_wireless.c files to stm32_cc3000.c. --- configs/nucleo-l476rg/src/Makefile | 2 +- configs/nucleo-l476rg/src/{stm32_wireless.c => stm32_cc3000.c} | 2 +- configs/spark/src/Makefile | 2 +- configs/spark/src/{stm32_wireless.c => stm32_cc3000.c} | 2 +- configs/stm32_tiny/src/Makefile | 2 +- configs/stm32_tiny/src/{stm32_wireless.c => stm32_cc3000.c} | 2 +- configs/stm32f103-minimum/src/Makefile | 2 +- .../stm32f103-minimum/src/{stm32_wireless.c => stm32_cc3000.c} | 2 +- 8 files changed, 8 insertions(+), 8 deletions(-) rename configs/nucleo-l476rg/src/{stm32_wireless.c => stm32_cc3000.c} (99%) rename configs/spark/src/{stm32_wireless.c => stm32_cc3000.c} (99%) rename configs/stm32_tiny/src/{stm32_wireless.c => stm32_cc3000.c} (99%) rename configs/stm32f103-minimum/src/{stm32_wireless.c => stm32_cc3000.c} (98%) diff --git a/configs/nucleo-l476rg/src/Makefile b/configs/nucleo-l476rg/src/Makefile index a27b0f3b84..7c90843527 100644 --- a/configs/nucleo-l476rg/src/Makefile +++ b/configs/nucleo-l476rg/src/Makefile @@ -49,7 +49,7 @@ CSRCS += stm32_buttons.c endif ifeq ($(CONFIG_WL_CC3000),y) -CSRCS += stm32_wireless.c +CSRCS += stm32_cc3000.c ifeq ($(CONFIG_CC3000_PROBES),) CSRCS += stm32_io.c endif diff --git a/configs/nucleo-l476rg/src/stm32_wireless.c b/configs/nucleo-l476rg/src/stm32_cc3000.c similarity index 99% rename from configs/nucleo-l476rg/src/stm32_wireless.c rename to configs/nucleo-l476rg/src/stm32_cc3000.c index b65a5eaae5..d1c94b338e 100644 --- a/configs/nucleo-l476rg/src/stm32_wireless.c +++ b/configs/nucleo-l476rg/src/stm32_cc3000.c @@ -1,5 +1,5 @@ /************************************************************************************ - * configs/nucleo-l476rg/src/stm32_wireless.c + * configs/nucleo-l476rg/src/stm32_cc3000.c * * Copyright (C) 2014 Gregory Nutt. All rights reserved. * Author: Laurent Latil diff --git a/configs/spark/src/Makefile b/configs/spark/src/Makefile index 51ee3a0280..70a7879f15 100644 --- a/configs/spark/src/Makefile +++ b/configs/spark/src/Makefile @@ -66,7 +66,7 @@ CSRCS += stm32_composite.c endif ifeq ($(CONFIG_WL_CC3000),y) -CSRCS += stm32_wireless.c +CSRCS += stm32_cc3000.c endif ifeq ($(CONFIG_CC3000_PROBES),) diff --git a/configs/spark/src/stm32_wireless.c b/configs/spark/src/stm32_cc3000.c similarity index 99% rename from configs/spark/src/stm32_wireless.c rename to configs/spark/src/stm32_cc3000.c index afd0f9a819..7f384213e4 100644 --- a/configs/spark/src/stm32_wireless.c +++ b/configs/spark/src/stm32_cc3000.c @@ -1,5 +1,5 @@ /************************************************************************************ - * configs/spark/src/stm32_wireless.c + * configs/spark/src/stm32_cc3000.c * * Copyright (C) 2009, 2013 Gregory Nutt. All rights reserved. * Author: Laurent Latil diff --git a/configs/stm32_tiny/src/Makefile b/configs/stm32_tiny/src/Makefile index 14ee306846..02062684c6 100644 --- a/configs/stm32_tiny/src/Makefile +++ b/configs/stm32_tiny/src/Makefile @@ -44,7 +44,7 @@ CSRCS += stm32_pwm.c endif ifeq ($(CONFIG_WL_NRF24L01),y) -CSRCS += stm32_wireless.c +CSRCS += stm32_cc3000.c endif ifeq ($(CONFIG_LIB_BOARDCTL),y) diff --git a/configs/stm32_tiny/src/stm32_wireless.c b/configs/stm32_tiny/src/stm32_cc3000.c similarity index 99% rename from configs/stm32_tiny/src/stm32_wireless.c rename to configs/stm32_tiny/src/stm32_cc3000.c index a08e48a65a..9a8a0d3619 100644 --- a/configs/stm32_tiny/src/stm32_wireless.c +++ b/configs/stm32_tiny/src/stm32_cc3000.c @@ -1,5 +1,5 @@ /************************************************************************************ - * configs/stm32_tiny/src/stm32_wireless.c + * configs/stm32_tiny/src/stm32_cc3000.c * * Copyright (C) 2009, 2013, 2017 Gregory Nutt. All rights reserved. * Author: Laurent Latil diff --git a/configs/stm32f103-minimum/src/Makefile b/configs/stm32f103-minimum/src/Makefile index 7eaf2d9c27..75b6cb2953 100644 --- a/configs/stm32f103-minimum/src/Makefile +++ b/configs/stm32f103-minimum/src/Makefile @@ -86,7 +86,7 @@ CSRCS += stm32_veml6070.c endif ifeq ($(CONFIG_WL_NRF24L01),y) -CSRCS += stm32_wireless.c +CSRCS += stm32_cc3000.c endif ifeq ($(CONFIG_USBDEV),y) diff --git a/configs/stm32f103-minimum/src/stm32_wireless.c b/configs/stm32f103-minimum/src/stm32_cc3000.c similarity index 98% rename from configs/stm32f103-minimum/src/stm32_wireless.c rename to configs/stm32f103-minimum/src/stm32_cc3000.c index c3ddcff784..23b1144ef5 100644 --- a/configs/stm32f103-minimum/src/stm32_wireless.c +++ b/configs/stm32f103-minimum/src/stm32_cc3000.c @@ -1,5 +1,5 @@ /************************************************************************************ - * configs/stm32f103-minimum//src/stm32_wireless.c + * configs/stm32f103-minimum//src/stm32_cc3000.c * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Laurent Latil -- GitLab From e77a511a13aeebbee7a4b078ef299994dac34dd1 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 24 Mar 2017 17:30:58 -0600 Subject: [PATCH 194/990] configs/: Rename all xyz_wifi.c files to stm32_cc3000.c. --- .../include/{kl_wifi.h => kl_cc3000.h} | 35 ++++++++++--------- configs/freedom-kl25z/src/Makefile | 2 +- .../src/{kl_wifi.c => kl_cc3000.c} | 4 +-- 3 files changed, 22 insertions(+), 19 deletions(-) rename configs/freedom-kl25z/include/{kl_wifi.h => kl_cc3000.h} (82%) rename configs/freedom-kl25z/src/{kl_wifi.c => kl_cc3000.c} (99%) diff --git a/configs/freedom-kl25z/include/kl_wifi.h b/configs/freedom-kl25z/include/kl_cc3000.h similarity index 82% rename from configs/freedom-kl25z/include/kl_wifi.h rename to configs/freedom-kl25z/include/kl_cc3000.h index ab9ac43564..117fc57eef 100644 --- a/configs/freedom-kl25z/include/kl_wifi.h +++ b/configs/freedom-kl25z/include/kl_cc3000.h @@ -1,5 +1,5 @@ /**************************************************************************** - * configs/freedom-kl25z/include/kl_wifi.h + * configs/freedom-kl25z/include/kl_cc300.h * * Copyright (C) 2013 Alan Carvalho de Assis * Author: Alan Carvalho de Assis @@ -38,34 +38,36 @@ * ****************************************************************************/ +#ifndef __CONFIGS_FREEDOM_KL25Z_INCLUDE_KL_CC3000_H +#define __CONFIGS_FREEDOM_KL25Z_INCLUDE_KL_CC3000_H 1 + /**************************************************************************** * Included Files ****************************************************************************/ + #include #include +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ long ReadWlanInterruptPin(void); -/* - * Enable WiFi Interrupt - */ +/* Enable WiFi Interrupt */ void WlanInterruptEnable(void); -/* - * Disable WiFi Interrupt - */ +/* Disable WiFi Interrupt */ + void WlanInterruptDisable(void); -/* - * Enable/Disable WiFi - */ +/* Enable/Disable WiFi */ + void WriteWlanEnablePin(uint8_t val); -/* - * Assert CC3000 CS - */ +/* Assert CC3000 CS */ + void AssertWlanCS(void); /* @@ -73,8 +75,9 @@ void AssertWlanCS(void); */ void DeassertWlanCS(void); -/* - * Setup needed pins - */ +/* Setup needed pins */ + void Wlan_Setup(void); +#endif /* __CONFIGS_FREEDOM_KL25Z_INCLUDE_KL_CC3000_H */ + diff --git a/configs/freedom-kl25z/src/Makefile b/configs/freedom-kl25z/src/Makefile index 2105da1101..37f83bc1ff 100644 --- a/configs/freedom-kl25z/src/Makefile +++ b/configs/freedom-kl25z/src/Makefile @@ -43,7 +43,7 @@ CSRCS += kl_appinit.c endif ifeq ($(CONFIG_WL_CC3000),y) -CSRCS += kl_wifi.c +CSRCS += kl_cc3000.c endif ifeq ($(CONFIG_KL_TSI),y) diff --git a/configs/freedom-kl25z/src/kl_wifi.c b/configs/freedom-kl25z/src/kl_cc3000.c similarity index 99% rename from configs/freedom-kl25z/src/kl_wifi.c rename to configs/freedom-kl25z/src/kl_cc3000.c index 0f1810da37..55e96721f3 100644 --- a/configs/freedom-kl25z/src/kl_wifi.c +++ b/configs/freedom-kl25z/src/kl_cc3000.c @@ -1,5 +1,5 @@ /**************************************************************************** - * configs/freedom-kl25z/src/kl_tsi.c + * configs/freedom-kl25z/src/kl_cc3000.c * * Copyright (C) 2014 Alan Carvalho de Assis * Author: Alan Carvalho de Assis @@ -38,7 +38,7 @@ ****************************************************************************/ #include -#include +#include #include #include -- GitLab From 2506eb32a770477d957e2374fc8a3b188cf48675 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 24 Mar 2017 17:59:09 -0600 Subject: [PATCH 195/990] Fix a comment --- configs/freedom-kl25z/include/kl_cc3000.h | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/configs/freedom-kl25z/include/kl_cc3000.h b/configs/freedom-kl25z/include/kl_cc3000.h index 117fc57eef..ce252a67a0 100644 --- a/configs/freedom-kl25z/include/kl_cc3000.h +++ b/configs/freedom-kl25z/include/kl_cc3000.h @@ -70,9 +70,8 @@ void WriteWlanEnablePin(uint8_t val); void AssertWlanCS(void); -/* - * Deassert CC3000 CS - */ +/* Deassert CC3000 CS */ + void DeassertWlanCS(void); /* Setup needed pins */ -- GitLab From 3949ab38fd740bc57423f7c9aef0b223e983a661 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 24 Mar 2017 17:21:28 -0600 Subject: [PATCH 196/990] configs/: Rename all stm32_wireless.c files to stm32_cc3000.c. --- configs/nucleo-l476rg/src/Makefile | 2 +- configs/nucleo-l476rg/src/{stm32_wireless.c => stm32_cc3000.c} | 2 +- configs/spark/src/Makefile | 2 +- configs/spark/src/{stm32_wireless.c => stm32_cc3000.c} | 2 +- configs/stm32_tiny/src/Makefile | 2 +- configs/stm32_tiny/src/{stm32_wireless.c => stm32_cc3000.c} | 2 +- configs/stm32f103-minimum/src/Makefile | 2 +- .../stm32f103-minimum/src/{stm32_wireless.c => stm32_cc3000.c} | 2 +- 8 files changed, 8 insertions(+), 8 deletions(-) rename configs/nucleo-l476rg/src/{stm32_wireless.c => stm32_cc3000.c} (99%) rename configs/spark/src/{stm32_wireless.c => stm32_cc3000.c} (99%) rename configs/stm32_tiny/src/{stm32_wireless.c => stm32_cc3000.c} (99%) rename configs/stm32f103-minimum/src/{stm32_wireless.c => stm32_cc3000.c} (98%) diff --git a/configs/nucleo-l476rg/src/Makefile b/configs/nucleo-l476rg/src/Makefile index a27b0f3b84..7c90843527 100644 --- a/configs/nucleo-l476rg/src/Makefile +++ b/configs/nucleo-l476rg/src/Makefile @@ -49,7 +49,7 @@ CSRCS += stm32_buttons.c endif ifeq ($(CONFIG_WL_CC3000),y) -CSRCS += stm32_wireless.c +CSRCS += stm32_cc3000.c ifeq ($(CONFIG_CC3000_PROBES),) CSRCS += stm32_io.c endif diff --git a/configs/nucleo-l476rg/src/stm32_wireless.c b/configs/nucleo-l476rg/src/stm32_cc3000.c similarity index 99% rename from configs/nucleo-l476rg/src/stm32_wireless.c rename to configs/nucleo-l476rg/src/stm32_cc3000.c index b65a5eaae5..d1c94b338e 100644 --- a/configs/nucleo-l476rg/src/stm32_wireless.c +++ b/configs/nucleo-l476rg/src/stm32_cc3000.c @@ -1,5 +1,5 @@ /************************************************************************************ - * configs/nucleo-l476rg/src/stm32_wireless.c + * configs/nucleo-l476rg/src/stm32_cc3000.c * * Copyright (C) 2014 Gregory Nutt. All rights reserved. * Author: Laurent Latil diff --git a/configs/spark/src/Makefile b/configs/spark/src/Makefile index 51ee3a0280..70a7879f15 100644 --- a/configs/spark/src/Makefile +++ b/configs/spark/src/Makefile @@ -66,7 +66,7 @@ CSRCS += stm32_composite.c endif ifeq ($(CONFIG_WL_CC3000),y) -CSRCS += stm32_wireless.c +CSRCS += stm32_cc3000.c endif ifeq ($(CONFIG_CC3000_PROBES),) diff --git a/configs/spark/src/stm32_wireless.c b/configs/spark/src/stm32_cc3000.c similarity index 99% rename from configs/spark/src/stm32_wireless.c rename to configs/spark/src/stm32_cc3000.c index afd0f9a819..7f384213e4 100644 --- a/configs/spark/src/stm32_wireless.c +++ b/configs/spark/src/stm32_cc3000.c @@ -1,5 +1,5 @@ /************************************************************************************ - * configs/spark/src/stm32_wireless.c + * configs/spark/src/stm32_cc3000.c * * Copyright (C) 2009, 2013 Gregory Nutt. All rights reserved. * Author: Laurent Latil diff --git a/configs/stm32_tiny/src/Makefile b/configs/stm32_tiny/src/Makefile index 14ee306846..02062684c6 100644 --- a/configs/stm32_tiny/src/Makefile +++ b/configs/stm32_tiny/src/Makefile @@ -44,7 +44,7 @@ CSRCS += stm32_pwm.c endif ifeq ($(CONFIG_WL_NRF24L01),y) -CSRCS += stm32_wireless.c +CSRCS += stm32_cc3000.c endif ifeq ($(CONFIG_LIB_BOARDCTL),y) diff --git a/configs/stm32_tiny/src/stm32_wireless.c b/configs/stm32_tiny/src/stm32_cc3000.c similarity index 99% rename from configs/stm32_tiny/src/stm32_wireless.c rename to configs/stm32_tiny/src/stm32_cc3000.c index a08e48a65a..9a8a0d3619 100644 --- a/configs/stm32_tiny/src/stm32_wireless.c +++ b/configs/stm32_tiny/src/stm32_cc3000.c @@ -1,5 +1,5 @@ /************************************************************************************ - * configs/stm32_tiny/src/stm32_wireless.c + * configs/stm32_tiny/src/stm32_cc3000.c * * Copyright (C) 2009, 2013, 2017 Gregory Nutt. All rights reserved. * Author: Laurent Latil diff --git a/configs/stm32f103-minimum/src/Makefile b/configs/stm32f103-minimum/src/Makefile index 7eaf2d9c27..75b6cb2953 100644 --- a/configs/stm32f103-minimum/src/Makefile +++ b/configs/stm32f103-minimum/src/Makefile @@ -86,7 +86,7 @@ CSRCS += stm32_veml6070.c endif ifeq ($(CONFIG_WL_NRF24L01),y) -CSRCS += stm32_wireless.c +CSRCS += stm32_cc3000.c endif ifeq ($(CONFIG_USBDEV),y) diff --git a/configs/stm32f103-minimum/src/stm32_wireless.c b/configs/stm32f103-minimum/src/stm32_cc3000.c similarity index 98% rename from configs/stm32f103-minimum/src/stm32_wireless.c rename to configs/stm32f103-minimum/src/stm32_cc3000.c index c3ddcff784..23b1144ef5 100644 --- a/configs/stm32f103-minimum/src/stm32_wireless.c +++ b/configs/stm32f103-minimum/src/stm32_cc3000.c @@ -1,5 +1,5 @@ /************************************************************************************ - * configs/stm32f103-minimum//src/stm32_wireless.c + * configs/stm32f103-minimum//src/stm32_cc3000.c * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Laurent Latil -- GitLab From 210ac0f77d96b4f9fe460c0f406ae316dbe42663 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 24 Mar 2017 17:30:58 -0600 Subject: [PATCH 197/990] configs/: Rename all xyz_wifi.c files to stm32_cc3000.c. --- .../include/{kl_wifi.h => kl_cc3000.h} | 35 ++++++++++--------- configs/freedom-kl25z/src/Makefile | 2 +- .../src/{kl_wifi.c => kl_cc3000.c} | 4 +-- 3 files changed, 22 insertions(+), 19 deletions(-) rename configs/freedom-kl25z/include/{kl_wifi.h => kl_cc3000.h} (82%) rename configs/freedom-kl25z/src/{kl_wifi.c => kl_cc3000.c} (99%) diff --git a/configs/freedom-kl25z/include/kl_wifi.h b/configs/freedom-kl25z/include/kl_cc3000.h similarity index 82% rename from configs/freedom-kl25z/include/kl_wifi.h rename to configs/freedom-kl25z/include/kl_cc3000.h index ab9ac43564..117fc57eef 100644 --- a/configs/freedom-kl25z/include/kl_wifi.h +++ b/configs/freedom-kl25z/include/kl_cc3000.h @@ -1,5 +1,5 @@ /**************************************************************************** - * configs/freedom-kl25z/include/kl_wifi.h + * configs/freedom-kl25z/include/kl_cc300.h * * Copyright (C) 2013 Alan Carvalho de Assis * Author: Alan Carvalho de Assis @@ -38,34 +38,36 @@ * ****************************************************************************/ +#ifndef __CONFIGS_FREEDOM_KL25Z_INCLUDE_KL_CC3000_H +#define __CONFIGS_FREEDOM_KL25Z_INCLUDE_KL_CC3000_H 1 + /**************************************************************************** * Included Files ****************************************************************************/ + #include #include +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ long ReadWlanInterruptPin(void); -/* - * Enable WiFi Interrupt - */ +/* Enable WiFi Interrupt */ void WlanInterruptEnable(void); -/* - * Disable WiFi Interrupt - */ +/* Disable WiFi Interrupt */ + void WlanInterruptDisable(void); -/* - * Enable/Disable WiFi - */ +/* Enable/Disable WiFi */ + void WriteWlanEnablePin(uint8_t val); -/* - * Assert CC3000 CS - */ +/* Assert CC3000 CS */ + void AssertWlanCS(void); /* @@ -73,8 +75,9 @@ void AssertWlanCS(void); */ void DeassertWlanCS(void); -/* - * Setup needed pins - */ +/* Setup needed pins */ + void Wlan_Setup(void); +#endif /* __CONFIGS_FREEDOM_KL25Z_INCLUDE_KL_CC3000_H */ + diff --git a/configs/freedom-kl25z/src/Makefile b/configs/freedom-kl25z/src/Makefile index 2105da1101..37f83bc1ff 100644 --- a/configs/freedom-kl25z/src/Makefile +++ b/configs/freedom-kl25z/src/Makefile @@ -43,7 +43,7 @@ CSRCS += kl_appinit.c endif ifeq ($(CONFIG_WL_CC3000),y) -CSRCS += kl_wifi.c +CSRCS += kl_cc3000.c endif ifeq ($(CONFIG_KL_TSI),y) diff --git a/configs/freedom-kl25z/src/kl_wifi.c b/configs/freedom-kl25z/src/kl_cc3000.c similarity index 99% rename from configs/freedom-kl25z/src/kl_wifi.c rename to configs/freedom-kl25z/src/kl_cc3000.c index 0f1810da37..55e96721f3 100644 --- a/configs/freedom-kl25z/src/kl_wifi.c +++ b/configs/freedom-kl25z/src/kl_cc3000.c @@ -1,5 +1,5 @@ /**************************************************************************** - * configs/freedom-kl25z/src/kl_tsi.c + * configs/freedom-kl25z/src/kl_cc3000.c * * Copyright (C) 2014 Alan Carvalho de Assis * Author: Alan Carvalho de Assis @@ -38,7 +38,7 @@ ****************************************************************************/ #include -#include +#include #include #include -- GitLab From af85aca1aa0da7bbd329d3541b71272be31d9a35 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 24 Mar 2017 12:46:01 -0600 Subject: [PATCH 198/990] Remove some whitespace at the end of some lines --- configs/freedom-kl25z/src/kl_cc3000.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/configs/freedom-kl25z/src/kl_cc3000.c b/configs/freedom-kl25z/src/kl_cc3000.c index 55e96721f3..e233a64d06 100644 --- a/configs/freedom-kl25z/src/kl_cc3000.c +++ b/configs/freedom-kl25z/src/kl_cc3000.c @@ -212,12 +212,12 @@ static void wl_enable_irq(FAR struct cc3000_config_s *state, bool enable) if (enable) { (void)kl_gpioirqattach(GPIO_WIFI_INT, priv->handler, priv->arg); - kl_gpioirqenable(GPIO_WIFI_INT); + kl_gpioirqenable(GPIO_WIFI_INT); } else { (void)kl_gpioirqattach(GPIO_WIFI_INT, NULL, NULL); - kl_gpioirqdisable(GPIO_WIFI_INT); + kl_gpioirqdisable(GPIO_WIFI_INT); } } -- GitLab From b47e1888f56be4748346f6417d75d20e583405c9 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 25 Mar 2017 06:59:27 -0600 Subject: [PATCH 199/990] Clicker2-STM32: Add usbnsh configuration. --- configs/clicker2-stm32/README.txt | 52 + configs/clicker2-stm32/nsh/defconfig | 28 +- configs/clicker2-stm32/usbnsh/Make.defs | 122 ++ configs/clicker2-stm32/usbnsh/defconfig | 1353 +++++++++++++++++++++++ configs/clicker2-stm32/usbnsh/setenv.sh | 80 ++ 5 files changed, 1613 insertions(+), 22 deletions(-) create mode 100644 configs/clicker2-stm32/usbnsh/Make.defs create mode 100644 configs/clicker2-stm32/usbnsh/defconfig create mode 100644 configs/clicker2-stm32/usbnsh/setenv.sh diff --git a/configs/clicker2-stm32/README.txt b/configs/clicker2-stm32/README.txt index c412c11435..e265d475c0 100644 --- a/configs/clicker2-stm32/README.txt +++ b/configs/clicker2-stm32/README.txt @@ -249,3 +249,55 @@ Configurations CONFIG_HAVE_CXX=y CONFIG_HAVE_CXXINITIALIZE=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y + + usbnsh: + ------- + + This is another NSH example. If differs from other 'nsh' configurations + in that this configurations uses a USB serial device for console I/O. + Such a configuration is useful on the Clicker2 STM32 which has no + builtin RS-232 drivers. + + NOTES: + + 1. This configuration does have USART3 output enabled and set up as + the system logging device: + + CONFIG_SYSLOG_CHAR=y : Use a character device for system logging + CONFIG_SYSLOG_DEVPATH="/dev/ttyS0" : USART3 will be /dev/ttyS0 + + However, there is nothing to generate SYLOG output in the default + configuration so nothing should appear on USART3 unless you enable + some debug output or enable the USB monitor. + + 2. Enabling USB monitor SYSLOG output. If tracing is enabled, the USB + device will save encoded trace output in in-memory buffer; if the + USB monitor is enabled, that trace buffer will be periodically + emptied and dumped to the system logging device (USART3 in this + configuration): + + CONFIG_USBDEV_TRACE=y : Enable USB trace feature + CONFIG_USBDEV_TRACE_NRECORDS=128 : Buffer 128 records in memory + CONFIG_NSH_USBDEV_TRACE=n : No builtin tracing from NSH + CONFIG_NSH_ARCHINIT=y : Automatically start the USB monitor + CONFIG_USBMONITOR=y : Enable the USB monitor daemon + CONFIG_USBMONITOR_STACKSIZE=2048 : USB monitor daemon stack size + CONFIG_USBMONITOR_PRIORITY=50 : USB monitor daemon priority + CONFIG_USBMONITOR_INTERVAL=2 : Dump trace data every 2 seconds + + CONFIG_USBMONITOR_TRACEINIT=y : Enable TRACE output + CONFIG_USBMONITOR_TRACECLASS=y + CONFIG_USBMONITOR_TRACETRANSFERS=y + CONFIG_USBMONITOR_TRACECONTROLLER=y + CONFIG_USBMONITOR_TRACEINTERRUPTS=y + + Using the Prolifics PL2303 Emulation + ------------------------------------ + You could also use the non-standard PL2303 serial device instead of + the standard CDC/ACM serial device by changing: + + CONFIG_CDCACM=n : Disable the CDC/ACM serial device class + CONFIG_CDCACM_CONSOLE=n : The CDC/ACM serial device is NOT the console + CONFIG_PL2303=y : The Prolifics PL2303 emulation is enabled + CONFIG_PL2303_CONSOLE=y : The PL2303 serial device is the console + diff --git a/configs/clicker2-stm32/nsh/defconfig b/configs/clicker2-stm32/nsh/defconfig index 764b16372c..1b5c06b7d3 100644 --- a/configs/clicker2-stm32/nsh/defconfig +++ b/configs/clicker2-stm32/nsh/defconfig @@ -148,14 +148,10 @@ CONFIG_ARM_HAVE_MPU_UNIFIED=y # CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set # CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL is not set CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL=y -# CONFIG_ARMV7M_OABI_TOOLCHAIN is not set CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARMV7M_STACKCHECK is not set # CONFIG_ARMV7M_ITMSYSLOG is not set # CONFIG_SERIAL_TERMIOS is not set -# CONFIG_USBHOST_BULK_DISABLE is not set -# CONFIG_USBHOST_INT_DISABLE is not set -# CONFIG_USBHOST_ISOC_DISABLE is not set # # STM32 Configuration Options @@ -414,7 +410,7 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set -CONFIG_STM32_OTGFS=y +# CONFIG_STM32_OTGFS is not set # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y # CONFIG_STM32_RNG is not set @@ -451,6 +447,7 @@ CONFIG_STM32_USART3=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -504,11 +501,6 @@ CONFIG_STM32_USART3_SERIALDRIVER=y # # USB FS Host Configuration # -CONFIG_STM32_OTGFS_RXFIFO_SIZE=128 -CONFIG_STM32_OTGFS_NPTXFIFO_SIZE=96 -CONFIG_STM32_OTGFS_PTXFIFO_SIZE=128 -CONFIG_STM32_OTGFS_DESCSIZE=128 -# CONFIG_STM32_OTGFS_SOFINTR is not set # # USB HS Host Configuration @@ -603,6 +595,8 @@ CONFIG_ARCH_IRQBUTTONS=y # # Board-Specific Options # +# CONFIG_CLICKER2_STM32_MB1_SPI is not set +# CONFIG_CLICKER2_STM32_MB2_SPI is not set # CONFIG_BOARD_CRASHDUMP is not set CONFIG_LIB_BOARDCTL=y # CONFIG_BOARDCTL_RESET is not set @@ -843,18 +837,7 @@ CONFIG_USART3_2STOP=0 # CONFIG_USART3_DMA is not set # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set -CONFIG_USBHOST=y -CONFIG_USBHOST_NPREALLOC=4 -CONFIG_USBHOST_HAVE_ASYNCH=y -# CONFIG_USBHOST_ASYNCH is not set -# CONFIG_USBHOST_HUB is not set -# CONFIG_USBHOST_COMPOSITE is not set -CONFIG_USBHOST_MSC=y -# CONFIG_USBHOST_CDCACM is not set -# CONFIG_USBHOST_HIDKBD is not set -# CONFIG_USBHOST_HIDMOUSE is not set -# CONFIG_USBHOST_XBOXCONTROLLER is not set -# CONFIG_USBHOST_TRACE is not set +# CONFIG_USBHOST is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -1152,6 +1135,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities diff --git a/configs/clicker2-stm32/usbnsh/Make.defs b/configs/clicker2-stm32/usbnsh/Make.defs new file mode 100644 index 0000000000..c2982852db --- /dev/null +++ b/configs/clicker2-stm32/usbnsh/Make.defs @@ -0,0 +1,122 @@ +############################################################################ +# configs/clicker2-stm32/usbnsh/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. +# +############################################################################ + +include ${TOPDIR}/.config +include ${TOPDIR}/tools/Config.mk +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs + +LDSCRIPT = flash.ld + +ifeq ($(WINTOOL),y) + # Windows-native toolchains + DIRLINK = $(TOPDIR)/tools/copydir.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mkwindeps.sh + ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" + ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" +else + # Linux/Cygwin-native toolchain + MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT) + ARCHINCLUDES = -I. -isystem $(TOPDIR)/include + ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) +endif + +CC = $(CROSSDEV)gcc +CXX = $(CROSSDEV)g++ +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(CROSSDEV)ar rcs +NM = $(CROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump + +ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} +ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} + +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + ARCHOPTIMIZATION = -g +endif + +ifneq ($(CONFIG_DEBUG_NOOPT),y) + ARCHOPTIMIZATION += $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer +endif + +ARCHCFLAGS = -fno-builtin +ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fcheck-new -fno-rtti +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow -Wundef +ARCHWARNINGSXX = -Wall -Wshadow -Wundef +ARCHDEFINES = +ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 + +CFLAGS = $(ARCHCFLAGS) $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) +CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +NXFLATLDFLAGS1 = -r -d -warn-common +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections +LDNXFLATFLAGS = -e main -s 2048 + +# Loadable module definitions + +CMODULEFLAGS = $(CFLAGS) -mlong-calls # --target1-abs + +LDMODULEFLAGS = -r -e module_initialize +ifeq ($(WINTOOL),y) + LDMODULEFLAGS += -T "${shell cygpath -w $(TOPDIR)/libc/modlib/gnu-elf.ld}" +else + LDMODULEFLAGS += -T $(TOPDIR)/libc/modlib/gnu-elf.ld +endif + +ASMEXT = .S +OBJEXT = .o +LIBEXT = .a +EXEEXT = + +ifneq ($(CROSSDEV),arm-nuttx-elf-) + LDFLAGS += -nostartfiles -nodefaultlibs +endif +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + LDFLAGS += -g +endif + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -Wundef -g -pipe +HOSTLDFLAGS = diff --git a/configs/clicker2-stm32/usbnsh/defconfig b/configs/clicker2-stm32/usbnsh/defconfig new file mode 100644 index 0000000000..32bf16050c --- /dev/null +++ b/configs/clicker2-stm32/usbnsh/defconfig @@ -0,0 +1,1353 @@ +# +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# + +# +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set +# CONFIG_DEFAULT_SMALL is not set +CONFIG_HOST_LINUX=y +# CONFIG_HOST_OSX is not set +# CONFIG_HOST_WINDOWS is not set +# CONFIG_HOST_OTHER is not set + +# +# Build Configuration +# +# CONFIG_APPS_DIR="../apps" +CONFIG_BUILD_FLAT=y +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +CONFIG_INTELHEX_BINARY=y +# CONFIG_MOTOROLA_SREC is not set +CONFIG_RAW_BINARY=y +# CONFIG_UBOOT_UIMAGE is not set + +# +# Customize Header Files +# +# CONFIG_ARCH_STDINT_H is not set +# CONFIG_ARCH_STDBOOL_H is not set +# CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_FLOAT_H is not set +# CONFIG_ARCH_STDARG_H is not set +# CONFIG_ARCH_DEBUG_H is not set + +# +# Debug Options +# +CONFIG_DEBUG_ALERT=y +# CONFIG_DEBUG_FEATURES is not set +CONFIG_ARCH_HAVE_STACKCHECK=y +# CONFIG_STACK_COLORATION is not set +CONFIG_ARCH_HAVE_HEAPCHECK=y +# CONFIG_HEAP_COLORATION is not set +# CONFIG_DEBUG_SYMBOLS is not set +CONFIG_ARCH_HAVE_CUSTOMOPT=y +# CONFIG_DEBUG_NOOPT is not set +# CONFIG_DEBUG_CUSTOMOPT is not set +CONFIG_DEBUG_FULLOPT=y + +# +# System Type +# +CONFIG_ARCH_ARM=y +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_MISOC is not set +# CONFIG_ARCH_RENESAS is not set +# CONFIG_ARCH_RISCV is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_XTENSA is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="arm" + +# +# ARM Options +# +# CONFIG_ARCH_CHIP_A1X is not set +# CONFIG_ARCH_CHIP_C5471 is not set +# CONFIG_ARCH_CHIP_DM320 is not set +# CONFIG_ARCH_CHIP_EFM32 is not set +# CONFIG_ARCH_CHIP_IMX1 is not set +# CONFIG_ARCH_CHIP_IMX6 is not set +# CONFIG_ARCH_CHIP_KINETIS is not set +# CONFIG_ARCH_CHIP_KL is not set +# CONFIG_ARCH_CHIP_LM is not set +# CONFIG_ARCH_CHIP_TIVA is not set +# CONFIG_ARCH_CHIP_LPC11XX is not set +# CONFIG_ARCH_CHIP_LPC17XX is not set +# CONFIG_ARCH_CHIP_LPC214X is not set +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_NUC1XX is not set +# CONFIG_ARCH_CHIP_SAMA5 is not set +# CONFIG_ARCH_CHIP_SAMD is not set +# CONFIG_ARCH_CHIP_SAML is not set +# CONFIG_ARCH_CHIP_SAM34 is not set +# CONFIG_ARCH_CHIP_SAMV7 is not set +CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F7 is not set +# CONFIG_ARCH_CHIP_STM32L4 is not set +# CONFIG_ARCH_CHIP_STR71X is not set +# CONFIG_ARCH_CHIP_TMS570 is not set +# CONFIG_ARCH_CHIP_XMC4 is not set +# CONFIG_ARCH_ARM7TDMI is not set +# CONFIG_ARCH_ARM926EJS is not set +# CONFIG_ARCH_ARM920T is not set +# CONFIG_ARCH_CORTEXM0 is not set +# CONFIG_ARCH_CORTEXM23 is not set +# CONFIG_ARCH_CORTEXM3 is not set +# CONFIG_ARCH_CORTEXM33 is not set +CONFIG_ARCH_CORTEXM4=y +# CONFIG_ARCH_CORTEXM7 is not set +# CONFIG_ARCH_CORTEXA5 is not set +# CONFIG_ARCH_CORTEXA8 is not set +# CONFIG_ARCH_CORTEXA9 is not set +# CONFIG_ARCH_CORTEXR4 is not set +# CONFIG_ARCH_CORTEXR4F is not set +# CONFIG_ARCH_CORTEXR5 is not set +# CONFIG_ARCH_CORTEX5F is not set +# CONFIG_ARCH_CORTEXR7 is not set +# CONFIG_ARCH_CORTEXR7F is not set +CONFIG_ARCH_FAMILY="armv7-m" +CONFIG_ARCH_CHIP="stm32" +# CONFIG_ARM_TOOLCHAIN_IAR is not set +CONFIG_ARM_TOOLCHAIN_GNU=y +# CONFIG_ARMV7M_USEBASEPRI is not set +CONFIG_ARCH_HAVE_CMNVECTOR=y +# CONFIG_ARMV7M_CMNVECTOR is not set +# CONFIG_ARMV7M_LAZYFPU is not set +CONFIG_ARCH_HAVE_FPU=y +# CONFIG_ARCH_HAVE_DPFPU is not set +CONFIG_ARCH_FPU=y +# CONFIG_ARCH_HAVE_TRUSTZONE is not set +CONFIG_ARM_HAVE_MPU_UNIFIED=y +# CONFIG_ARM_MPU is not set + +# +# ARMV7M Configuration Options +# +# CONFIG_ARMV7M_HAVE_ICACHE is not set +# CONFIG_ARMV7M_HAVE_DCACHE is not set +# CONFIG_ARMV7M_HAVE_ITCM is not set +# CONFIG_ARMV7M_HAVE_DTCM is not set +# CONFIG_ARMV7M_TOOLCHAIN_IARL is not set +# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set +# CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set +# CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL is not set +CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL=y +CONFIG_ARMV7M_HAVE_STACKCHECK=y +# CONFIG_ARMV7M_STACKCHECK is not set +# CONFIG_ARMV7M_ITMSYSLOG is not set +# CONFIG_SERIAL_TERMIOS is not set + +# +# STM32 Configuration Options +# +# CONFIG_ARCH_CHIP_STM32L151C6 is not set +# CONFIG_ARCH_CHIP_STM32L151C8 is not set +# CONFIG_ARCH_CHIP_STM32L151CB is not set +# CONFIG_ARCH_CHIP_STM32L151R6 is not set +# CONFIG_ARCH_CHIP_STM32L151R8 is not set +# CONFIG_ARCH_CHIP_STM32L151RB is not set +# CONFIG_ARCH_CHIP_STM32L151V6 is not set +# CONFIG_ARCH_CHIP_STM32L151V8 is not set +# CONFIG_ARCH_CHIP_STM32L151VB is not set +# CONFIG_ARCH_CHIP_STM32L152C6 is not set +# CONFIG_ARCH_CHIP_STM32L152C8 is not set +# CONFIG_ARCH_CHIP_STM32L152CB is not set +# CONFIG_ARCH_CHIP_STM32L152R6 is not set +# CONFIG_ARCH_CHIP_STM32L152R8 is not set +# CONFIG_ARCH_CHIP_STM32L152RB is not set +# CONFIG_ARCH_CHIP_STM32L152V6 is not set +# CONFIG_ARCH_CHIP_STM32L152V8 is not set +# CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L162ZD is not set +# CONFIG_ARCH_CHIP_STM32L162VE is not set +# CONFIG_ARCH_CHIP_STM32F100C8 is not set +# CONFIG_ARCH_CHIP_STM32F100CB is not set +# CONFIG_ARCH_CHIP_STM32F100R8 is not set +# CONFIG_ARCH_CHIP_STM32F100RB is not set +# CONFIG_ARCH_CHIP_STM32F100RC is not set +# CONFIG_ARCH_CHIP_STM32F100RD is not set +# CONFIG_ARCH_CHIP_STM32F100RE is not set +# CONFIG_ARCH_CHIP_STM32F100V8 is not set +# CONFIG_ARCH_CHIP_STM32F100VB is not set +# CONFIG_ARCH_CHIP_STM32F100VC is not set +# CONFIG_ARCH_CHIP_STM32F100VD is not set +# CONFIG_ARCH_CHIP_STM32F100VE is not set +# CONFIG_ARCH_CHIP_STM32F102CB is not set +# CONFIG_ARCH_CHIP_STM32F103T8 is not set +# CONFIG_ARCH_CHIP_STM32F103TB is not set +# CONFIG_ARCH_CHIP_STM32F103C4 is not set +# CONFIG_ARCH_CHIP_STM32F103C8 is not set +# CONFIG_ARCH_CHIP_STM32F103CB is not set +# CONFIG_ARCH_CHIP_STM32F103R8 is not set +# CONFIG_ARCH_CHIP_STM32F103RB is not set +# CONFIG_ARCH_CHIP_STM32F103RC is not set +# CONFIG_ARCH_CHIP_STM32F103RD is not set +# CONFIG_ARCH_CHIP_STM32F103RE is not set +# CONFIG_ARCH_CHIP_STM32F103RG is not set +# CONFIG_ARCH_CHIP_STM32F103V8 is not set +# CONFIG_ARCH_CHIP_STM32F103VB is not set +# CONFIG_ARCH_CHIP_STM32F103VC is not set +# CONFIG_ARCH_CHIP_STM32F103VE is not set +# CONFIG_ARCH_CHIP_STM32F103ZE is not set +# CONFIG_ARCH_CHIP_STM32F105VB is not set +# CONFIG_ARCH_CHIP_STM32F105RB is not set +# CONFIG_ARCH_CHIP_STM32F107VC is not set +# CONFIG_ARCH_CHIP_STM32F205RG is not set +# CONFIG_ARCH_CHIP_STM32F207IG is not set +# CONFIG_ARCH_CHIP_STM32F207ZE is not set +# CONFIG_ARCH_CHIP_STM32F302K6 is not set +# CONFIG_ARCH_CHIP_STM32F302K8 is not set +# CONFIG_ARCH_CHIP_STM32F302CB is not set +# CONFIG_ARCH_CHIP_STM32F302CC is not set +# CONFIG_ARCH_CHIP_STM32F302RB is not set +# CONFIG_ARCH_CHIP_STM32F302RC is not set +# CONFIG_ARCH_CHIP_STM32F302VB is not set +# CONFIG_ARCH_CHIP_STM32F302VC is not set +# CONFIG_ARCH_CHIP_STM32F303K6 is not set +# CONFIG_ARCH_CHIP_STM32F303K8 is not set +# CONFIG_ARCH_CHIP_STM32F303C6 is not set +# CONFIG_ARCH_CHIP_STM32F303C8 is not set +# CONFIG_ARCH_CHIP_STM32F303CB is not set +# CONFIG_ARCH_CHIP_STM32F303CC is not set +# CONFIG_ARCH_CHIP_STM32F303RB is not set +# CONFIG_ARCH_CHIP_STM32F303RC is not set +# CONFIG_ARCH_CHIP_STM32F303RD is not set +# CONFIG_ARCH_CHIP_STM32F303RE is not set +# CONFIG_ARCH_CHIP_STM32F303VB is not set +# CONFIG_ARCH_CHIP_STM32F303VC is not set +# CONFIG_ARCH_CHIP_STM32F334K4 is not set +# CONFIG_ARCH_CHIP_STM32F334K6 is not set +# CONFIG_ARCH_CHIP_STM32F334K8 is not set +# CONFIG_ARCH_CHIP_STM32F334C4 is not set +# CONFIG_ARCH_CHIP_STM32F334C6 is not set +# CONFIG_ARCH_CHIP_STM32F334C8 is not set +# CONFIG_ARCH_CHIP_STM32F334R4 is not set +# CONFIG_ARCH_CHIP_STM32F334R6 is not set +# CONFIG_ARCH_CHIP_STM32F334R8 is not set +# CONFIG_ARCH_CHIP_STM32F372C8 is not set +# CONFIG_ARCH_CHIP_STM32F372R8 is not set +# CONFIG_ARCH_CHIP_STM32F372V8 is not set +# CONFIG_ARCH_CHIP_STM32F372CB is not set +# CONFIG_ARCH_CHIP_STM32F372RB is not set +# CONFIG_ARCH_CHIP_STM32F372VB is not set +# CONFIG_ARCH_CHIP_STM32F372CC is not set +# CONFIG_ARCH_CHIP_STM32F372RC is not set +# CONFIG_ARCH_CHIP_STM32F372VC is not set +# CONFIG_ARCH_CHIP_STM32F373C8 is not set +# CONFIG_ARCH_CHIP_STM32F373R8 is not set +# CONFIG_ARCH_CHIP_STM32F373V8 is not set +# CONFIG_ARCH_CHIP_STM32F373CB is not set +# CONFIG_ARCH_CHIP_STM32F373RB is not set +# CONFIG_ARCH_CHIP_STM32F373VB is not set +# CONFIG_ARCH_CHIP_STM32F373CC is not set +# CONFIG_ARCH_CHIP_STM32F373RC is not set +# CONFIG_ARCH_CHIP_STM32F373VC is not set +# CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F411RE is not set +# CONFIG_ARCH_CHIP_STM32F411VE is not set +# CONFIG_ARCH_CHIP_STM32F405RG is not set +# CONFIG_ARCH_CHIP_STM32F405VG is not set +# CONFIG_ARCH_CHIP_STM32F405ZG is not set +# CONFIG_ARCH_CHIP_STM32F407VE is not set +CONFIG_ARCH_CHIP_STM32F407VG=y +# CONFIG_ARCH_CHIP_STM32F407ZE is not set +# CONFIG_ARCH_CHIP_STM32F407ZG is not set +# CONFIG_ARCH_CHIP_STM32F407IE is not set +# CONFIG_ARCH_CHIP_STM32F407IG is not set +# CONFIG_ARCH_CHIP_STM32F427V is not set +# CONFIG_ARCH_CHIP_STM32F427Z is not set +# CONFIG_ARCH_CHIP_STM32F427I is not set +# CONFIG_ARCH_CHIP_STM32F429V is not set +# CONFIG_ARCH_CHIP_STM32F429Z is not set +# CONFIG_ARCH_CHIP_STM32F429I is not set +# CONFIG_ARCH_CHIP_STM32F429B is not set +# CONFIG_ARCH_CHIP_STM32F429N is not set +# CONFIG_ARCH_CHIP_STM32F446M is not set +# CONFIG_ARCH_CHIP_STM32F446R is not set +# CONFIG_ARCH_CHIP_STM32F446V is not set +# CONFIG_ARCH_CHIP_STM32F446Z is not set +# CONFIG_ARCH_CHIP_STM32F469A is not set +# CONFIG_ARCH_CHIP_STM32F469I is not set +# CONFIG_ARCH_CHIP_STM32F469B is not set +# CONFIG_ARCH_CHIP_STM32F469N is not set +CONFIG_STM32_FLASH_CONFIG_DEFAULT=y +# CONFIG_STM32_FLASH_CONFIG_4 is not set +# CONFIG_STM32_FLASH_CONFIG_6 is not set +# CONFIG_STM32_FLASH_CONFIG_8 is not set +# CONFIG_STM32_FLASH_CONFIG_B is not set +# CONFIG_STM32_FLASH_CONFIG_C is not set +# CONFIG_STM32_FLASH_CONFIG_D is not set +# CONFIG_STM32_FLASH_CONFIG_E is not set +# CONFIG_STM32_FLASH_CONFIG_F is not set +# CONFIG_STM32_FLASH_CONFIG_G is not set +# CONFIG_STM32_FLASH_CONFIG_I is not set +# CONFIG_STM32_STM32L15XX is not set +# CONFIG_STM32_ENERGYLITE is not set +# CONFIG_STM32_STM32F10XX is not set +# CONFIG_STM32_VALUELINE is not set +# CONFIG_STM32_CONNECTIVITYLINE is not set +# CONFIG_STM32_PERFORMANCELINE is not set +# CONFIG_STM32_USBACCESSLINE is not set +# CONFIG_STM32_HIGHDENSITY is not set +# CONFIG_STM32_MEDIUMDENSITY is not set +# CONFIG_STM32_LOWDENSITY is not set +# CONFIG_STM32_STM32F20XX is not set +# CONFIG_STM32_STM32F205 is not set +# CONFIG_STM32_STM32F207 is not set +# CONFIG_STM32_STM32F30XX is not set +# CONFIG_STM32_STM32F302 is not set +# CONFIG_STM32_STM32F303 is not set +# CONFIG_STM32_STM32F33XX is not set +# CONFIG_STM32_STM32F37XX is not set +CONFIG_STM32_STM32F40XX=y +# CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F411 is not set +# CONFIG_STM32_STM32F405 is not set +CONFIG_STM32_STM32F407=y +# CONFIG_STM32_STM32F427 is not set +# CONFIG_STM32_STM32F429 is not set +# CONFIG_STM32_STM32F446 is not set +# CONFIG_STM32_STM32F469 is not set +# CONFIG_STM32_DFU is not set + +# +# STM32 Peripheral Support +# +CONFIG_STM32_HAVE_CCM=y +# CONFIG_STM32_HAVE_USBDEV is not set +CONFIG_STM32_HAVE_OTGFS=y +CONFIG_STM32_HAVE_FSMC=y +# CONFIG_STM32_HAVE_HRTIM1 is not set +# CONFIG_STM32_HAVE_LTDC is not set +CONFIG_STM32_HAVE_USART3=y +CONFIG_STM32_HAVE_UART4=y +CONFIG_STM32_HAVE_UART5=y +CONFIG_STM32_HAVE_USART6=y +# CONFIG_STM32_HAVE_UART7 is not set +# CONFIG_STM32_HAVE_UART8 is not set +CONFIG_STM32_HAVE_TIM1=y +CONFIG_STM32_HAVE_TIM2=y +CONFIG_STM32_HAVE_TIM3=y +CONFIG_STM32_HAVE_TIM4=y +CONFIG_STM32_HAVE_TIM5=y +CONFIG_STM32_HAVE_TIM6=y +CONFIG_STM32_HAVE_TIM7=y +CONFIG_STM32_HAVE_TIM8=y +CONFIG_STM32_HAVE_TIM9=y +CONFIG_STM32_HAVE_TIM10=y +CONFIG_STM32_HAVE_TIM11=y +CONFIG_STM32_HAVE_TIM12=y +CONFIG_STM32_HAVE_TIM13=y +CONFIG_STM32_HAVE_TIM14=y +# CONFIG_STM32_HAVE_TIM15 is not set +# CONFIG_STM32_HAVE_TIM16 is not set +# CONFIG_STM32_HAVE_TIM17 is not set +CONFIG_STM32_HAVE_ADC2=y +CONFIG_STM32_HAVE_ADC3=y +# CONFIG_STM32_HAVE_ADC4 is not set +# CONFIG_STM32_HAVE_ADC1_DMA is not set +# CONFIG_STM32_HAVE_ADC2_DMA is not set +# CONFIG_STM32_HAVE_ADC3_DMA is not set +# CONFIG_STM32_HAVE_ADC4_DMA is not set +# CONFIG_STM32_HAVE_SDADC1 is not set +# CONFIG_STM32_HAVE_SDADC2 is not set +# CONFIG_STM32_HAVE_SDADC3 is not set +# CONFIG_STM32_HAVE_SDADC1_DMA is not set +# CONFIG_STM32_HAVE_SDADC2_DMA is not set +# CONFIG_STM32_HAVE_SDADC3_DMA is not set +CONFIG_STM32_HAVE_CAN1=y +CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP6 is not set +CONFIG_STM32_HAVE_DAC1=y +CONFIG_STM32_HAVE_DAC2=y +CONFIG_STM32_HAVE_RNG=y +CONFIG_STM32_HAVE_ETHMAC=y +CONFIG_STM32_HAVE_I2C2=y +CONFIG_STM32_HAVE_I2C3=y +CONFIG_STM32_HAVE_SPI2=y +CONFIG_STM32_HAVE_SPI3=y +# CONFIG_STM32_HAVE_SPI4 is not set +# CONFIG_STM32_HAVE_SPI5 is not set +# CONFIG_STM32_HAVE_SPI6 is not set +# CONFIG_STM32_HAVE_SAIPLL is not set +# CONFIG_STM32_HAVE_I2SPLL is not set +# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_ADC1 is not set +# CONFIG_STM32_ADC2 is not set +# CONFIG_STM32_ADC3 is not set +# CONFIG_STM32_BKPSRAM is not set +# CONFIG_STM32_CAN1 is not set +# CONFIG_STM32_CAN2 is not set +# CONFIG_STM32_CCMDATARAM is not set +# CONFIG_STM32_CRC is not set +# CONFIG_STM32_CRYP is not set +# CONFIG_STM32_DMA1 is not set +# CONFIG_STM32_DMA2 is not set +# CONFIG_STM32_DAC1 is not set +# CONFIG_STM32_DAC2 is not set +# CONFIG_STM32_DCMI is not set +# CONFIG_STM32_ETHMAC is not set +# CONFIG_STM32_FSMC is not set +# CONFIG_STM32_HASH is not set +# CONFIG_STM32_I2C1 is not set +# CONFIG_STM32_I2C2 is not set +# CONFIG_STM32_I2C3 is not set +CONFIG_STM32_OTGFS=y +# CONFIG_STM32_OTGHS is not set +CONFIG_STM32_PWR=y +# CONFIG_STM32_RNG is not set +# CONFIG_STM32_SDIO is not set +# CONFIG_STM32_SPI1 is not set +# CONFIG_STM32_SPI2 is not set +# CONFIG_STM32_SPI3 is not set +CONFIG_STM32_SYSCFG=y +# CONFIG_STM32_TIM1 is not set +# CONFIG_STM32_TIM2 is not set +# CONFIG_STM32_TIM3 is not set +# CONFIG_STM32_TIM4 is not set +# CONFIG_STM32_TIM5 is not set +# CONFIG_STM32_TIM6 is not set +# CONFIG_STM32_TIM7 is not set +# CONFIG_STM32_TIM8 is not set +# CONFIG_STM32_TIM9 is not set +# CONFIG_STM32_TIM10 is not set +# CONFIG_STM32_TIM11 is not set +# CONFIG_STM32_TIM12 is not set +# CONFIG_STM32_TIM13 is not set +# CONFIG_STM32_TIM14 is not set +# CONFIG_STM32_USART1 is not set +# CONFIG_STM32_USART2 is not set +CONFIG_STM32_USART3=y +# CONFIG_STM32_UART4 is not set +# CONFIG_STM32_UART5 is not set +# CONFIG_STM32_USART6 is not set +# CONFIG_STM32_IWDG is not set +# CONFIG_STM32_WWDG is not set +# CONFIG_STM32_NOEXT_VECTORS is not set + +# +# Alternate Pin Mapping +# +# CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set +# CONFIG_STM32_JTAG_DISABLE is not set +# CONFIG_STM32_JTAG_FULL_ENABLE is not set +# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y +# CONFIG_STM32_FORCEPOWER is not set +# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set +CONFIG_STM32_CCMEXCLUDE=y + +# +# Timer Configuration +# +# CONFIG_STM32_ONESHOT is not set +# CONFIG_STM32_FREERUN is not set +# CONFIG_STM32_TIM1_CAP is not set +# CONFIG_STM32_TIM2_CAP is not set +# CONFIG_STM32_TIM3_CAP is not set +# CONFIG_STM32_TIM4_CAP is not set +# CONFIG_STM32_TIM5_CAP is not set +# CONFIG_STM32_TIM8_CAP is not set +# CONFIG_STM32_TIM9_CAP is not set +# CONFIG_STM32_TIM10_CAP is not set +# CONFIG_STM32_TIM11_CAP is not set +# CONFIG_STM32_TIM12_CAP is not set +# CONFIG_STM32_TIM13_CAP is not set +# CONFIG_STM32_TIM14_CAP is not set +CONFIG_STM32_USART=y +CONFIG_STM32_SERIALDRIVER=y + +# +# U[S]ART Configuration +# + +# +# U[S]ART Device Configuration +# +CONFIG_STM32_USART3_SERIALDRIVER=y +# CONFIG_STM32_USART3_1WIREDRIVER is not set +# CONFIG_USART3_RS485 is not set + +# +# Serial Driver Configuration +# +# CONFIG_SERIAL_DISABLE_REORDERING is not set +# CONFIG_STM32_FLOWCONTROL_BROKEN is not set +# CONFIG_STM32_USART_BREAKS is not set +# CONFIG_STM32_USART_SINGLEWIRE is not set +# CONFIG_STM32_HAVE_RTC_COUNTER is not set +# CONFIG_STM32_HAVE_RTC_SUBSECONDS is not set + +# +# USB FS Host Configuration +# + +# +# USB HS Host Configuration +# + +# +# USB Host Debug Configuration +# + +# +# USB Device Configuration +# + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_VECNOTIRQ is not set +# CONFIG_ARCH_DMA is not set +CONFIG_ARCH_HAVE_IRQPRIO=y +# CONFIG_ARCH_L2CACHE is not set +# CONFIG_ARCH_HAVE_COHERENT_DCACHE is not set +# CONFIG_ARCH_HAVE_ADDRENV is not set +# CONFIG_ARCH_NEED_ADDRENV_MAPPING is not set +# CONFIG_ARCH_HAVE_MULTICPU is not set +CONFIG_ARCH_HAVE_VFORK=y +# CONFIG_ARCH_HAVE_MMU is not set +CONFIG_ARCH_HAVE_MPU=y +# CONFIG_ARCH_NAND_HWECC is not set +# CONFIG_ARCH_HAVE_EXTCLK is not set +# CONFIG_ARCH_HAVE_POWEROFF is not set +CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_USE_MPU is not set +# CONFIG_ARCH_IRQPRIO is not set +CONFIG_ARCH_STACKDUMP=y +# CONFIG_ENDIAN_BIG is not set +# CONFIG_ARCH_IDLE_CUSTOM is not set +# CONFIG_ARCH_HAVE_RAMFUNCS is not set +CONFIG_ARCH_HAVE_RAMVECTORS=y +# CONFIG_ARCH_RAMVECTORS is not set +# CONFIG_ARCH_MINIMAL_VECTORTABLE is not set + +# +# Board Settings +# +CONFIG_BOARD_LOOPSPERMSEC=16717 +# CONFIG_ARCH_CALIBRATION is not set + +# +# Interrupt options +# +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y +CONFIG_ARCH_INTERRUPTSTACK=0 +CONFIG_ARCH_HAVE_HIPRI_INTERRUPT=y +# CONFIG_ARCH_HIPRI_INTERRUPT is not set + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Boot Memory Configuration +# +CONFIG_RAM_START=0x20000000 +CONFIG_RAM_SIZE=131072 +# CONFIG_ARCH_HAVE_SDRAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_CLICKER2_STM32=y +# CONFIG_ARCH_BOARD_STM32F4_DISCOVERY is not set +# CONFIG_ARCH_BOARD_MIKROE_STM32F4 is not set +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="clicker2-stm32" + +# +# Common Board Options +# +CONFIG_ARCH_HAVE_LEDS=y +CONFIG_ARCH_LEDS=y +CONFIG_ARCH_HAVE_BUTTONS=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_HAVE_IRQBUTTONS=y +CONFIG_ARCH_IRQBUTTONS=y + +# +# Board-Specific Options +# +# CONFIG_CLICKER2_STM32_MB1_SPI is not set +# CONFIG_CLICKER2_STM32_MB2_SPI is not set +# CONFIG_BOARD_CRASHDUMP is not set +CONFIG_LIB_BOARDCTL=y +# CONFIG_BOARDCTL_RESET is not set +# CONFIG_BOARDCTL_UNIQUEID is not set +CONFIG_BOARDCTL_USBDEVCTRL=y +# CONFIG_BOARDCTL_TSCTEST is not set +# CONFIG_BOARDCTL_GRAPHICS is not set +# CONFIG_BOARDCTL_IOCTL is not set + +# +# RTOS Features +# +CONFIG_DISABLE_OS_API=y +# CONFIG_DISABLE_POSIX_TIMERS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_DISABLE_SIGNALS is not set +# CONFIG_DISABLE_MQUEUE is not set +# CONFIG_DISABLE_ENVIRON is not set + +# +# Clocks and Timers +# +CONFIG_ARCH_HAVE_TICKLESS=y +# CONFIG_SCHED_TICKLESS is not set +CONFIG_USEC_PER_TICK=10000 +# CONFIG_SYSTEM_TIME64 is not set +# CONFIG_CLOCK_MONOTONIC is not set +CONFIG_ARCH_HAVE_TIMEKEEPING=y +# CONFIG_JULIAN_TIME is not set +CONFIG_START_YEAR=2017 +CONFIG_START_MONTH=3 +CONFIG_START_DAY=25 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=16 +CONFIG_WDOG_INTRESERVE=4 +CONFIG_PREALLOC_TIMERS=4 + +# +# Tasks and Scheduling +# +# CONFIG_SPINLOCK is not set +# CONFIG_INIT_NONE is not set +CONFIG_INIT_ENTRYPOINT=y +# CONFIG_INIT_FILEPATH is not set +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_RR_INTERVAL=200 +# CONFIG_SCHED_SPORADIC is not set +CONFIG_TASK_NAME_SIZE=32 +CONFIG_MAX_TASKS=16 +# CONFIG_SCHED_HAVE_PARENT is not set +CONFIG_SCHED_WAITPID=y + +# +# Pthread Options +# +# CONFIG_MUTEX_TYPES is not set +CONFIG_NPTHREAD_KEYS=4 +# CONFIG_PTHREAD_CLEANUP is not set +# CONFIG_CANCELLATION_POINTS is not set + +# +# Performance Monitoring +# +# CONFIG_SCHED_CPULOAD is not set +# CONFIG_SCHED_INSTRUMENTATION is not set + +# +# Files and I/O +# +# CONFIG_DEV_CONSOLE is not set +# CONFIG_FDCLONE_DISABLE is not set +# CONFIG_FDCLONE_STDIO is not set +CONFIG_SDCLONE_DISABLE=y +CONFIG_NFILE_DESCRIPTORS=8 +CONFIG_NFILE_STREAMS=8 +CONFIG_NAME_MAX=32 +# CONFIG_PRIORITY_INHERITANCE is not set + +# +# RTOS hooks +# +CONFIG_BOARD_INITIALIZE=y +# CONFIG_BOARD_INITTHREAD is not set +# CONFIG_SCHED_STARTHOOK is not set +# CONFIG_SCHED_ATEXIT is not set +# CONFIG_SCHED_ONEXIT is not set +# CONFIG_SIG_EVTHREAD is not set + +# +# Signal Numbers +# +CONFIG_SIG_SIGUSR1=1 +CONFIG_SIG_SIGUSR2=2 +CONFIG_SIG_SIGALARM=3 +CONFIG_SIG_SIGCONDTIMEDOUT=16 +CONFIG_SIG_SIGWORK=17 + +# +# POSIX Message Queue Options +# +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_MQ_MAXMSGSIZE=32 +# CONFIG_MODULE is not set + +# +# Work queue support +# +CONFIG_SCHED_WORKQUEUE=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=192 +CONFIG_SCHED_HPWORKPERIOD=50000 +CONFIG_SCHED_HPWORKSTACKSIZE=2048 +# CONFIG_SCHED_LPWORK is not set + +# +# Stack and heap information +# +CONFIG_IDLETHREAD_STACKSIZE=1024 +CONFIG_USERMAIN_STACKSIZE=2048 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=2048 +# CONFIG_LIB_SYSCALL is not set + +# +# Device Drivers +# +CONFIG_DISABLE_POLL=y +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_DEV_URANDOM is not set +# CONFIG_DEV_LOOP is not set + +# +# Buffering +# +# CONFIG_DRVR_WRITEBUFFER is not set +# CONFIG_DRVR_READAHEAD is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_ARCH_HAVE_PWM_PULSECOUNT is not set +# CONFIG_ARCH_HAVE_PWM_MULTICHAN is not set +# CONFIG_PWM is not set +CONFIG_ARCH_HAVE_I2CRESET=y +# CONFIG_I2C is not set +# CONFIG_ARCH_HAVE_SPI_CRCGENERATION is not set +# CONFIG_ARCH_HAVE_SPI_CS_CONTROL is not set +CONFIG_ARCH_HAVE_SPI_BITORDER=y +# CONFIG_SPI is not set +# CONFIG_I2S is not set + +# +# Timer Driver Support +# +# CONFIG_TIMER is not set +# CONFIG_ONESHOT is not set +# CONFIG_RTC is not set +# CONFIG_WATCHDOG is not set +# CONFIG_ANALOG is not set +# CONFIG_AUDIO_DEVICES is not set +# CONFIG_VIDEO_DEVICES is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set + +# +# IO Expander/GPIO Support +# +# CONFIG_IOEXPANDER is not set +# CONFIG_DEV_GPIO is not set + +# +# LCD Driver Support +# +# CONFIG_LCD is not set +# CONFIG_SLCD is not set + +# +# LED Support +# +# CONFIG_USERLED is not set +# CONFIG_RGBLED is not set +# CONFIG_PCA9635PW is not set +# CONFIG_NCP5623C is not set +# CONFIG_MMCSD is not set +# CONFIG_MODEM is not set +# CONFIG_MTD is not set +# CONFIG_EEPROM is not set +# CONFIG_PIPES is not set +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +CONFIG_SERIAL=y +CONFIG_SERIAL_REMOVABLE=y +# CONFIG_SERIAL_CONSOLE is not set +# CONFIG_16550_UART is not set +# CONFIG_UART_SERIALDRIVER is not set +# CONFIG_UART0_SERIALDRIVER is not set +# CONFIG_UART1_SERIALDRIVER is not set +# CONFIG_UART2_SERIALDRIVER is not set +# CONFIG_UART3_SERIALDRIVER is not set +# CONFIG_UART4_SERIALDRIVER is not set +# CONFIG_UART5_SERIALDRIVER is not set +# CONFIG_UART6_SERIALDRIVER is not set +# CONFIG_UART7_SERIALDRIVER is not set +# CONFIG_UART8_SERIALDRIVER is not set +# CONFIG_SCI0_SERIALDRIVER is not set +# CONFIG_SCI1_SERIALDRIVER is not set +# CONFIG_USART0_SERIALDRIVER is not set +# CONFIG_USART1_SERIALDRIVER is not set +# CONFIG_USART2_SERIALDRIVER is not set +CONFIG_USART3_SERIALDRIVER=y +# CONFIG_USART4_SERIALDRIVER is not set +# CONFIG_USART5_SERIALDRIVER is not set +# CONFIG_USART6_SERIALDRIVER is not set +# CONFIG_USART7_SERIALDRIVER is not set +# CONFIG_USART8_SERIALDRIVER is not set +# CONFIG_OTHER_UART_SERIALDRIVER is not set +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +# CONFIG_SERIAL_IFLOWCONTROL is not set +# CONFIG_SERIAL_OFLOWCONTROL is not set +# CONFIG_SERIAL_DMA is not set +CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y +# CONFIG_USART3_SERIAL_CONSOLE is not set +# CONFIG_OTHER_SERIAL_CONSOLE is not set +CONFIG_NO_SERIAL_CONSOLE=y + +# +# USART3 Configuration +# +CONFIG_USART3_RXBUFSIZE=256 +CONFIG_USART3_TXBUFSIZE=256 +CONFIG_USART3_BAUD=115200 +CONFIG_USART3_BITS=8 +CONFIG_USART3_PARITY=0 +CONFIG_USART3_2STOP=0 +# CONFIG_USART3_IFLOWCONTROL is not set +# CONFIG_USART3_OFLOWCONTROL is not set +# CONFIG_USART3_DMA is not set +# CONFIG_PSEUDOTERM is not set +CONFIG_USBDEV=y + +# +# USB Device Controller Driver Options +# +# CONFIG_USBDEV_ISOCHRONOUS is not set +# CONFIG_USBDEV_DUALSPEED is not set +CONFIG_USBDEV_SELFPOWERED=y +# CONFIG_USBDEV_BUSPOWERED is not set +CONFIG_USBDEV_MAXPOWER=100 +# CONFIG_USBDEV_DMA is not set +# CONFIG_ARCH_USBDEV_STALLQUEUE is not set +# CONFIG_USBDEV_TRACE is not set + +# +# USB Device Class Driver Options +# +# CONFIG_USBDEV_COMPOSITE is not set +# CONFIG_PL2303 is not set +CONFIG_CDCACM=y +CONFIG_CDCACM_CONSOLE=y +CONFIG_CDCACM_EP0MAXPACKET=64 +CONFIG_CDCACM_EPINTIN=1 +CONFIG_CDCACM_EPINTIN_FSSIZE=64 +CONFIG_CDCACM_EPINTIN_HSSIZE=64 +CONFIG_CDCACM_EPBULKOUT=3 +CONFIG_CDCACM_EPBULKOUT_FSSIZE=64 +CONFIG_CDCACM_EPBULKOUT_HSSIZE=512 +CONFIG_CDCACM_EPBULKIN=2 +CONFIG_CDCACM_EPBULKIN_FSSIZE=64 +CONFIG_CDCACM_EPBULKIN_HSSIZE=512 +CONFIG_CDCACM_NRDREQS=4 +CONFIG_CDCACM_NWRREQS=4 +CONFIG_CDCACM_BULKIN_REQLEN=96 +CONFIG_CDCACM_RXBUFSIZE=256 +CONFIG_CDCACM_TXBUFSIZE=256 +CONFIG_CDCACM_VENDORID=0x0525 +CONFIG_CDCACM_PRODUCTID=0xa4a7 +CONFIG_CDCACM_VENDORSTR="NuttX" +CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial" +# CONFIG_USBMSC is not set +# CONFIG_USBHOST is not set +# CONFIG_HAVE_USBTRACE is not set +# CONFIG_DRIVERS_WIRELESS is not set +# CONFIG_DRIVERS_CONTACTLESS is not set + +# +# System Logging +# +# CONFIG_ARCH_SYSLOG is not set +# CONFIG_RAMLOG is not set +CONFIG_SYSLOG_INTBUFFER=y +CONFIG_SYSLOG_INTBUFSIZE=396 +# CONFIG_SYSLOG_TIMESTAMP is not set +# CONFIG_SYSLOG_SERIAL_CONSOLE is not set +CONFIG_SYSLOG_CHAR=y +# CONFIG_SYSLOG_NONE is not set +# CONFIG_SYSLOG_FILE is not set +CONFIG_SYSLOG_CHAR_CRLF=y +CONFIG_SYSLOG_DEVPATH="/dev/ttyS0" +# CONFIG_SYSLOG_CHARDEV is not set + +# +# Networking Support +# +# CONFIG_ARCH_HAVE_NET is not set +# CONFIG_ARCH_HAVE_PHY is not set +# CONFIG_NET is not set + +# +# Crypto API +# +# CONFIG_CRYPTO is not set + +# +# File Systems +# + +# +# File system configuration +# +# CONFIG_DISABLE_MOUNTPOINT is not set +# CONFIG_FS_AUTOMOUNTER is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_PSEUDOFS_SOFTLINKS is not set +CONFIG_FS_READABLE=y +CONFIG_FS_WRITABLE=y +# CONFIG_FS_NAMED_SEMAPHORES is not set +CONFIG_FS_MQUEUE_MPATH="/var/mqueue" +# CONFIG_FS_RAMMAP is not set +CONFIG_FS_FAT=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_MAXFNAME=32 +# CONFIG_FS_FATTIME is not set +# CONFIG_FAT_FORCE_INDIRECT is not set +# CONFIG_FAT_DMAMEMORY is not set +# CONFIG_FAT_DIRECT_RETRY is not set +# CONFIG_FS_NXFFS is not set +# CONFIG_FS_ROMFS is not set +# CONFIG_FS_TMPFS is not set +# CONFIG_FS_SMARTFS is not set +# CONFIG_FS_BINFS is not set +CONFIG_FS_PROCFS=y +# CONFIG_FS_PROCFS_REGISTER is not set + +# +# Exclude individual procfs entries +# +# CONFIG_FS_PROCFS_EXCLUDE_PROCESS is not set +# CONFIG_FS_PROCFS_EXCLUDE_UPTIME is not set +# CONFIG_FS_PROCFS_EXCLUDE_MOUNTS is not set +# CONFIG_FS_UNIONFS is not set + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=1 +# CONFIG_ARCH_HAVE_HEAP2 is not set +# CONFIG_GRAN is not set + +# +# Audio Support +# +# CONFIG_AUDIO is not set + +# +# Wireless Support +# + +# +# Binary Loader +# +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_BINFMT_EXEPATH is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +CONFIG_BUILTIN=y +# CONFIG_PIC is not set +# CONFIG_SYMTAB_ORDEREDBYNAME is not set + +# +# Library Routines +# + +# +# Standard C Library Options +# + +# +# Standard C I/O +# +# CONFIG_STDIO_DISABLE_BUFFERING is not set +CONFIG_STDIO_BUFFER_SIZE=64 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +# CONFIG_NOPRINTF_FIELDWIDTH is not set +# CONFIG_LIBC_FLOATINGPOINT is not set +CONFIG_LIBC_LONG_LONG=y +# CONFIG_LIBC_SCANSET is not set +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_MEMCPY_VIK is not set +# CONFIG_LIBM is not set + +# +# Architecture-Specific Support +# +CONFIG_ARCH_LOWPUTC=y +# CONFIG_ARCH_ROMGETC is not set +# CONFIG_LIBC_ARCH_MEMCPY is not set +# CONFIG_LIBC_ARCH_MEMCMP is not set +# CONFIG_LIBC_ARCH_MEMMOVE is not set +# CONFIG_LIBC_ARCH_MEMSET is not set +# CONFIG_LIBC_ARCH_STRCHR is not set +# CONFIG_LIBC_ARCH_STRCMP is not set +# CONFIG_LIBC_ARCH_STRCPY is not set +# CONFIG_LIBC_ARCH_STRNCPY is not set +# CONFIG_LIBC_ARCH_STRLEN is not set +# CONFIG_LIBC_ARCH_STRNLEN is not set +# CONFIG_LIBC_ARCH_ELF is not set +# CONFIG_ARMV7M_MEMCPY is not set + +# +# stdlib Options +# +CONFIG_LIB_RAND_ORDER=1 +CONFIG_LIB_HOMEDIR="/" +CONFIG_LIBC_TMPDIR="/tmp" +CONFIG_LIBC_MAX_TMPFILE=32 + +# +# Program Execution Options +# +# CONFIG_LIBC_EXECFUNCS is not set +CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024 +CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=2048 + +# +# errno Decode Support +# +# CONFIG_LIBC_STRERROR is not set +# CONFIG_LIBC_PERROR_STDOUT is not set + +# +# memcpy/memset Options +# +# CONFIG_MEMSET_OPTSPEED is not set +# CONFIG_LIBC_DLLFCN is not set +# CONFIG_LIBC_MODLIB is not set +# CONFIG_LIBC_WCHAR is not set +# CONFIG_LIBC_LOCALE is not set + +# +# Time/Time Zone Support +# +# CONFIG_LIBC_LOCALTIME is not set +# CONFIG_TIME_EXTENDED is not set +CONFIG_ARCH_HAVE_TLS=y + +# +# Thread Local Storage (TLS) +# +# CONFIG_TLS is not set + +# +# Network-Related Options +# +# CONFIG_LIBC_IPv4_ADDRCONV is not set +# CONFIG_LIBC_IPv6_ADDRCONV is not set +# CONFIG_LIBC_NETDB is not set + +# +# NETDB Support +# +# CONFIG_NETDB_HOSTFILE is not set +# CONFIG_LIBC_IOCTL_VARIADIC is not set +CONFIG_LIB_SENDFILE_BUFSIZE=512 + +# +# Non-standard Library Support +# +# CONFIG_LIB_CRC64_FAST is not set +# CONFIG_LIB_KBDCODEC is not set +# CONFIG_LIB_SLCDCODEC is not set +# CONFIG_LIB_HEX2BIN is not set + +# +# Basic CXX Support +# +# CONFIG_C99_BOOL8 is not set +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +# CONFIG_CXX_NEWLONG is not set + +# +# LLVM C++ Library (libcxx) +# +# CONFIG_LIBCXX is not set + +# +# uClibc++ Standard C++ Library +# +# CONFIG_UCLIBCXX is not set + +# +# Application Configuration +# + +# +# Built-In Applications +# +CONFIG_BUILTIN_PROXY_STACKSIZE=1024 + +# +# CAN Utilities +# + +# +# Examples +# +# CONFIG_EXAMPLES_BUTTONS is not set +# CONFIG_EXAMPLES_CCTYPE is not set +# CONFIG_EXAMPLES_CHAT is not set +# CONFIG_EXAMPLES_CONFIGDATA is not set +# CONFIG_EXAMPLES_CXXTEST is not set +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FSTEST is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HELLOXX is not set +# CONFIG_EXAMPLES_HIDKBD is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_JSON is not set +# CONFIG_EXAMPLES_KEYPADTEST is not set +# CONFIG_EXAMPLES_MEDIA is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MODBUS is not set +# CONFIG_EXAMPLES_MOUNT is not set +CONFIG_EXAMPLES_NSH=y +CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NXLINES is not set +# CONFIG_EXAMPLES_NXTERM is not set +# CONFIG_EXAMPLES_NXTEXT is not set +# CONFIG_EXAMPLES_OSTEST is not set +# CONFIG_EXAMPLES_PCA9635 is not set +# CONFIG_EXAMPLES_POSIXSPAWN is not set +# CONFIG_EXAMPLES_PPPD is not set +# CONFIG_EXAMPLES_RFID_READUID is not set +# CONFIG_EXAMPLES_RGBLED is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERIALBLASTER is not set +# CONFIG_EXAMPLES_SERIALRX is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_SLCD is not set +# CONFIG_EXAMPLES_SMART is not set +# CONFIG_EXAMPLES_SMART_TEST is not set +# CONFIG_EXAMPLES_SMP is not set +# CONFIG_EXAMPLES_STAT is not set +# CONFIG_EXAMPLES_TCPECHO is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_USBSERIAL is not set +# CONFIG_EXAMPLES_WATCHDOG is not set +# CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set + +# +# File System Utilities +# +# CONFIG_FSUTILS_INIFILE is not set +# CONFIG_FSUTILS_PASSWD is not set + +# +# GPS Utilities +# +# CONFIG_GPSUTILS_MINMEA_LIB is not set + +# +# Graphics Support +# +# CONFIG_TIFF is not set +# CONFIG_GRAPHICS_TRAVELER is not set + +# +# Interpreters +# +# CONFIG_INTERPRETERS_BAS is not set +# CONFIG_INTERPRETERS_FICL is not set +# CONFIG_INTERPRETERS_MICROPYTHON is not set +# CONFIG_INTERPRETERS_MINIBASIC is not set +# CONFIG_INTERPRETERS_PCODE is not set + +# +# FreeModBus +# +# CONFIG_MODBUS is not set + +# +# Network Utilities +# +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_ESP8266 is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_JSON is not set +# CONFIG_NETUTILS_SMTP is not set + +# +# NSH Library +# +CONFIG_NSH_LIBRARY=y +# CONFIG_NSH_MOTD is not set + +# +# Command Line Configuration +# +CONFIG_NSH_READLINE=y +# CONFIG_NSH_CLE is not set +CONFIG_NSH_LINELEN=64 +# CONFIG_NSH_DISABLE_SEMICOLON is not set +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_MAXARGUMENTS=6 +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_NESTDEPTH=3 +# CONFIG_NSH_DISABLEBG is not set +CONFIG_NSH_BUILTIN_APPS=y + +# +# Disable Individual commands +# +# CONFIG_NSH_DISABLE_ADDROUTE is not set +# CONFIG_NSH_DISABLE_BASENAME is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_CMP is not set +CONFIG_NSH_DISABLE_DATE=y +# CONFIG_NSH_DISABLE_DD is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_DELROUTE is not set +# CONFIG_NSH_DISABLE_DIRNAME is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_FREE is not set +CONFIG_NSH_DISABLE_GET=y +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_HEXDUMP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +CONFIG_NSH_DISABLE_IFUPDOWN=y +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOSETUP is not set +CONFIG_NSH_DISABLE_LOSMART=y +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MB is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MKRD is not set +# CONFIG_NSH_DISABLE_MH is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_MW is not set +CONFIG_NSH_DISABLE_PRINTF=y +# CONFIG_NSH_DISABLE_PS is not set +CONFIG_NSH_DISABLE_PUT=y +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SH is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNAME is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_NSH_DISABLE_WGET=y +# CONFIG_NSH_DISABLE_XD is not set +CONFIG_NSH_MMCSDMINOR=0 + +# +# Configure Command Options +# +# CONFIG_NSH_CMDOPT_DF_H is not set +# CONFIG_NSH_CMDOPT_DD_STATS is not set +CONFIG_NSH_CODECS_BUFSIZE=128 +CONFIG_NSH_CMDOPT_HEXDUMP=y +CONFIG_NSH_PROC_MOUNTPOINT="/proc" +CONFIG_NSH_FILEIOSIZE=512 + +# +# Scripting Support +# +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_LOOPS is not set + +# +# Console Configuration +# +CONFIG_NSH_CONSOLE=y +# CONFIG_NSH_USBCONSOLE is not set +# CONFIG_NSH_ALTCONDEV is not set +CONFIG_NSH_ARCHINIT=y +# CONFIG_NSH_LOGIN is not set +# CONFIG_NSH_CONSOLE_LOGIN is not set + +# +# NxWidgets/NxWM +# + +# +# Platform-specific Support +# +# CONFIG_PLATFORM_CONFIGDATA is not set + +# +# System Libraries and NSH Add-Ons +# +# CONFIG_SYSTEM_CDCACM is not set +# CONFIG_SYSTEM_CLE is not set +# CONFIG_SYSTEM_CUTERM is not set +# CONFIG_SYSTEM_FREE is not set +# CONFIG_SYSTEM_HEX2BIN is not set +# CONFIG_SYSTEM_HEXED is not set +# CONFIG_SYSTEM_INSTALL is not set +# CONFIG_SYSTEM_RAMTEST is not set +CONFIG_READLINE_HAVE_EXTMATCH=y +CONFIG_SYSTEM_READLINE=y +CONFIG_READLINE_ECHO=y +# CONFIG_READLINE_TABCOMPLETION is not set +# CONFIG_READLINE_CMD_HISTORY is not set +# CONFIG_SYSTEM_SUDOKU is not set +# CONFIG_SYSTEM_SYSTEM is not set +# CONFIG_SYSTEM_TEE is not set +# CONFIG_SYSTEM_UBLOXMODEM is not set +# CONFIG_SYSTEM_VI is not set +# CONFIG_SYSTEM_ZMODEM is not set diff --git a/configs/clicker2-stm32/usbnsh/setenv.sh b/configs/clicker2-stm32/usbnsh/setenv.sh new file mode 100644 index 0000000000..17b9fd2a3d --- /dev/null +++ b/configs/clicker2-stm32/usbnsh/setenv.sh @@ -0,0 +1,80 @@ +#!/bin/bash +# configs/clicker2-stm32/usbnsh/setenv.sh +# +# 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. +# + +if [ "$_" = "$0" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +fi + +WD=`pwd` +if [ ! -x "setenv.sh" ]; then + echo "This script must be executed from the top-level NuttX build directory" + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then + export PATH_ORIG="${PATH}" +fi + +# This is the Cygwin path to the location where I installed the CodeSourcery +# toolchain under windows. You will also have to edit this if you install +# the CodeSourcery toolchain in any other location +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin" +# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin" + +# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors" +# You can this free toolchain here https://launchpad.net/gcc-arm-embedded +export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin" + +# This is the path to the location where I installed the devkitARM toolchain +# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/ +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin" + +# These are the Cygwin paths to the locations where I installed the Atollic +# toolchain under windows. You will also have to edit this if you install +# the Atollic toolchain in any other location. /usr/bin is added before +# the Atollic bin path because there is are binaries named gcc.exe and g++.exe +# at those locations as well. +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" + +# This is the Cygwin path to the location where I build the buildroot +# toolchain. +# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" + +# Add the path to the toolchain to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" + +echo "PATH : ${PATH}" -- GitLab From dfb9fe9b67db4720401139c88a5c6fe6a9ad4808 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 25 Mar 2017 07:20:04 -0600 Subject: [PATCH 200/990] Clicker2-STM32: Rename configuration to mrf24j40-radio. Update remove. Remove some bad settings in the defconfig file (like OTGFS host support). --- configs/clicker2-stm32/README.txt | 42 +++++++++++++++++++ .../Make.defs | 2 +- .../defconfig | 33 ++------------- .../setenv.sh | 2 +- 4 files changed, 47 insertions(+), 32 deletions(-) rename configs/clicker2-stm32/{mrf24j40_dev => mrf24j40-radio}/Make.defs (98%) rename configs/clicker2-stm32/{mrf24j40_dev => mrf24j40-radio}/defconfig (97%) rename configs/clicker2-stm32/{mrf24j40_dev => mrf24j40-radio}/setenv.sh (98%) diff --git a/configs/clicker2-stm32/README.txt b/configs/clicker2-stm32/README.txt index e265d475c0..b2b4a54821 100644 --- a/configs/clicker2-stm32/README.txt +++ b/configs/clicker2-stm32/README.txt @@ -226,6 +226,48 @@ Configurations Configuration sub-directories ----------------------------- + mrf24j40-radio + + This is a version of nsh that was used for testing the MRF24J40 be as a + character device. The most important configuration differences are + summarized below: + + 1. Support for the BEE click and SPI are in enabled in the mikroBUS1 slot: + + CONFIG_CLICKER2_STM32_MB1_BEE=y + CONFIG_CLICKER2_STM32_MB1_SPI=y + + 2. SPI support and STM32 SPI3, in particular, are enabled: + + CONFIG_SPI=y + CONFIG_SPI_EXCHANGE=y + + CONFIG_STM32_SPI=y + CONFIG_STM32_SPI3=y + + 4. Support for the IEEE802.15.4 "upper half" character driver is enabled: + + CONFIG_WIRELESS=y + CONFIG_WIRELESS_IEEE802154=y + CONFIG_IEEE802154_DEV=y + + 5. Support for the lower half MRF24J40 character driver is enabled + + CONFIG_DRIVERS_WIRELESS=y + CONFIG_DRIVERS_IEEE802154=y + CONFIG_IEEE802154_MRF24J40=y + + 6. Support for the test program at apps/ieee802154 is enabled: + + CONFIG_IEEE802154_COMMON=y + CONFIG_IEEE802154_COORD=y + CONFIG_IEEE802154_I8SAK=y + + 7. Initialization hooks are provided to enable the MRF24J40 and to + register the radio character driver. + + CONFIG_NSH_ARCHINIT=y + nsh: Configures the NuttShell (nsh) located at examples/nsh. This diff --git a/configs/clicker2-stm32/mrf24j40_dev/Make.defs b/configs/clicker2-stm32/mrf24j40-radio/Make.defs similarity index 98% rename from configs/clicker2-stm32/mrf24j40_dev/Make.defs rename to configs/clicker2-stm32/mrf24j40-radio/Make.defs index d86e64844f..4aa245f38b 100644 --- a/configs/clicker2-stm32/mrf24j40_dev/Make.defs +++ b/configs/clicker2-stm32/mrf24j40-radio/Make.defs @@ -1,5 +1,5 @@ ############################################################################ -# configs/clicker2-stm32/mrf24j40_dev/Make.defs +# configs/clicker2-stm32/mrf24j40-radio/Make.defs # # Copyright (C) 2017 Gregory Nutt. All rights reserved. # Author: Gregory Nutt diff --git a/configs/clicker2-stm32/mrf24j40_dev/defconfig b/configs/clicker2-stm32/mrf24j40-radio/defconfig similarity index 97% rename from configs/clicker2-stm32/mrf24j40_dev/defconfig rename to configs/clicker2-stm32/mrf24j40-radio/defconfig index 5b6ec741f5..db009c3ed3 100644 --- a/configs/clicker2-stm32/mrf24j40_dev/defconfig +++ b/configs/clicker2-stm32/mrf24j40-radio/defconfig @@ -152,9 +152,6 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARMV7M_STACKCHECK is not set # CONFIG_ARMV7M_ITMSYSLOG is not set # CONFIG_SERIAL_TERMIOS is not set -# CONFIG_USBHOST_BULK_DISABLE is not set -# CONFIG_USBHOST_INT_DISABLE is not set -# CONFIG_USBHOST_ISOC_DISABLE is not set # # STM32 Configuration Options @@ -413,7 +410,7 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set -CONFIG_STM32_OTGFS=y +# CONFIG_STM32_OTGFS is not set # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y # CONFIG_STM32_RNG is not set @@ -511,11 +508,6 @@ CONFIG_STM32_USART3_SERIALDRIVER=y # # USB FS Host Configuration # -CONFIG_STM32_OTGFS_RXFIFO_SIZE=128 -CONFIG_STM32_OTGFS_NPTXFIFO_SIZE=96 -CONFIG_STM32_OTGFS_PTXFIFO_SIZE=128 -CONFIG_STM32_OTGFS_DESCSIZE=128 -# CONFIG_STM32_OTGFS_SOFINTR is not set # # USB HS Host Configuration @@ -863,18 +855,7 @@ CONFIG_USART3_2STOP=0 # CONFIG_USART3_DMA is not set # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set -CONFIG_USBHOST=y -CONFIG_USBHOST_NPREALLOC=4 -CONFIG_USBHOST_HAVE_ASYNCH=y -# CONFIG_USBHOST_ASYNCH is not set -# CONFIG_USBHOST_HUB is not set -# CONFIG_USBHOST_COMPOSITE is not set -CONFIG_USBHOST_MSC=y -# CONFIG_USBHOST_CDCACM is not set -# CONFIG_USBHOST_HIDKBD is not set -# CONFIG_USBHOST_HIDMOUSE is not set -# CONFIG_USBHOST_XBOXCONTROLLER is not set -# CONFIG_USBHOST_TRACE is not set +# CONFIG_USBHOST is not set # CONFIG_HAVE_USBTRACE is not set CONFIG_DRIVERS_WIRELESS=y # CONFIG_WL_CC1101 is not set @@ -928,14 +909,7 @@ CONFIG_FS_WRITABLE=y # CONFIG_FS_NAMED_SEMAPHORES is not set CONFIG_FS_MQUEUE_MPATH="/var/mqueue" # CONFIG_FS_RAMMAP is not set -CONFIG_FS_FAT=y -CONFIG_FAT_LCNAMES=y -CONFIG_FAT_LFN=y -CONFIG_FAT_MAXFNAME=32 -# CONFIG_FS_FATTIME is not set -# CONFIG_FAT_FORCE_INDIRECT is not set -# CONFIG_FAT_DMAMEMORY is not set -# CONFIG_FAT_DIRECT_RETRY is not set +# CONFIG_FS_FAT is not set # CONFIG_FS_NXFFS is not set # CONFIG_FS_ROMFS is not set # CONFIG_FS_TMPFS is not set @@ -1282,7 +1256,6 @@ CONFIG_NSH_DISABLE_LOSMART=y # CONFIG_NSH_DISABLE_LS is not set # CONFIG_NSH_DISABLE_MB is not set # CONFIG_NSH_DISABLE_MKDIR is not set -# CONFIG_NSH_DISABLE_MKFATFS is not set # CONFIG_NSH_DISABLE_MKRD is not set # CONFIG_NSH_DISABLE_MH is not set # CONFIG_NSH_DISABLE_MOUNT is not set diff --git a/configs/clicker2-stm32/mrf24j40_dev/setenv.sh b/configs/clicker2-stm32/mrf24j40-radio/setenv.sh similarity index 98% rename from configs/clicker2-stm32/mrf24j40_dev/setenv.sh rename to configs/clicker2-stm32/mrf24j40-radio/setenv.sh index 21d46fcc15..a235db68fb 100644 --- a/configs/clicker2-stm32/mrf24j40_dev/setenv.sh +++ b/configs/clicker2-stm32/mrf24j40-radio/setenv.sh @@ -1,5 +1,5 @@ #!/bin/bash -# configs/clicker2-stm32/mrf24j40_dev/setenv.sh +# configs/clicker2-stm32/mrf24j40-radio/setenv.sh # # Copyright (C) 2017 Gregory Nutt. All rights reserved. # Author: Gregory Nutt -- GitLab From 700d4e6580c04fdc0e101ff6961e606c6de356a8 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 25 Mar 2017 07:23:19 -0600 Subject: [PATCH 201/990] Clicker2 STM32: NSH configuration does not need FAT support. --- configs/clicker2-stm32/nsh/defconfig | 11 ++++------- 1 file changed, 4 insertions(+), 7 deletions(-) diff --git a/configs/clicker2-stm32/nsh/defconfig b/configs/clicker2-stm32/nsh/defconfig index 1b5c06b7d3..d13af3965b 100644 --- a/configs/clicker2-stm32/nsh/defconfig +++ b/configs/clicker2-stm32/nsh/defconfig @@ -625,9 +625,9 @@ CONFIG_USEC_PER_TICK=10000 # CONFIG_CLOCK_MONOTONIC is not set CONFIG_ARCH_HAVE_TIMEKEEPING=y # CONFIG_JULIAN_TIME is not set -CONFIG_START_YEAR=2013 -CONFIG_START_MONTH=1 -CONFIG_START_DAY=1 +CONFIG_START_YEAR=2017 +CONFIG_START_MONTH=3 +CONFIG_START_DAY=25 CONFIG_MAX_WDOGPARMS=2 CONFIG_PREALLOC_WDOGS=8 CONFIG_WDOG_INTRESERVE=1 @@ -884,10 +884,7 @@ CONFIG_FS_WRITABLE=y # CONFIG_FS_NAMED_SEMAPHORES is not set CONFIG_FS_MQUEUE_MPATH="/var/mqueue" # CONFIG_FS_RAMMAP is not set -CONFIG_FS_FAT=y -CONFIG_FAT_LCNAMES=y -CONFIG_FAT_LFN=y -CONFIG_FAT_MAXFNAME=32 +# CONFIG_FS_FAT is not set # CONFIG_FS_FATTIME is not set # CONFIG_FAT_FORCE_INDIRECT is not set # CONFIG_FAT_DMAMEMORY is not set -- GitLab From be8207d493e20d85834e82a9c76709445ac37299 Mon Sep 17 00:00:00 2001 From: raiden00pl Date: Sat, 25 Mar 2017 16:50:11 +0100 Subject: [PATCH 202/990] drivers/analog: Add basic COMP driver --- drivers/analog/Kconfig | 7 + drivers/analog/Make.defs | 16 +++ drivers/analog/comp.c | 259 ++++++++++++++++++++++++++++++++++++ include/nuttx/analog/comp.h | 113 ++++++++++++++++ 4 files changed, 395 insertions(+) create mode 100644 drivers/analog/comp.c create mode 100644 include/nuttx/analog/comp.h diff --git a/drivers/analog/Kconfig b/drivers/analog/Kconfig index 20d99f8acb..99ff6b8fba 100644 --- a/drivers/analog/Kconfig +++ b/drivers/analog/Kconfig @@ -109,6 +109,13 @@ config PGA11X_MULTIPLE endif # if ADC_PGA11X endif # ADC +config COMP + bool "Analog Comparator" + default n + ---help--- + Select to enable support for Analog Comparators (COMPs). + + config DAC bool "Digital-to-Analog Conversion" default n diff --git a/drivers/analog/Make.defs b/drivers/analog/Make.defs index 2d12a1695d..580a44ae84 100644 --- a/drivers/analog/Make.defs +++ b/drivers/analog/Make.defs @@ -50,6 +50,16 @@ ifeq ($(CONFIG_DAC_AD5410),y) endif endif +# Check for COMP devices + +ifeq ($(CONFIG_COMP),y) + +# Include the common COMP character driver + +CSRCS += comp.c + +endif + # Check for ADC devices ifeq ($(CONFIG_ADC),y) @@ -86,6 +96,12 @@ ifeq ($(CONFIG_ADC),y) DEPPATH += --dep-path analog VPATH += :analog CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)$(DELIM)drivers$(DELIM)analog} +else +ifeq ($(CONFIG_COMP),y) + DEPPATH += --dep-path analog + VPATH += :analog + CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)$(DELIM)drivers$(DELIM)analog} +endif endif endif diff --git a/drivers/analog/comp.c b/drivers/analog/comp.c new file mode 100644 index 0000000000..5ebc2e87c2 --- /dev/null +++ b/drivers/analog/comp.c @@ -0,0 +1,259 @@ +/**************************************************************************** + * drivers/analog/comp.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Mateusz Szafoni + * + * 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 +#include + +#include + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static int comp_open(FAR struct file *filep); +static int comp_close(FAR struct file *filep); +static ssize_t comp_read(FAR struct file *filep, FAR char *buffer, + size_t buflen); +static int comp_ioctl(FAR struct file *filep, int cmd, unsigned long arg); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const struct file_operations comp_fops = +{ + comp_open, /* open */ + comp_close, /* close */ + comp_read, /* read */ + NULL, /* write */ + NULL, /* seek */ + comp_ioctl /* ioctl */ +#ifndef CONFIG_DISABLE_POLL + , 0 +#endif +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ +/**************************************************************************** + * Name: comp_open + * + * Description: + * This function is called whenever the COMP device is opened. + * + ****************************************************************************/ + +static int comp_open(FAR struct file *filep) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct comp_dev_s *dev = inode->i_private; + uint8_t tmp; + int ret = OK; + + /* If the port is the middle of closing, wait until the close is finished */ + + if (sem_wait(&dev->ad_closesem) != OK) + { + ret = -errno; + } + else + { + /* Increment the count of references to the device. If this the first + * time that the driver has been opened for this device, then initialize + * the device. + */ + + tmp = dev->ad_ocount + 1; + if (tmp == 0) + { + /* More than 255 opens; uint8_t overflows to zero */ + + ret = -EMFILE; + } + else + { + /* Check if this is the first time that the driver has been opened. */ + + if (tmp == 1) + { + /* Yes.. perform one time hardware initialization. */ + + irqstate_t flags = enter_critical_section(); + ret = dev->ad_ops->ao_setup(dev); + if (ret == OK) + { + /* Save the new open count on success */ + + dev->ad_ocount = tmp; + } + + leave_critical_section(flags); + } + } + + sem_post(&dev->ad_closesem); + } + + return ret; +} + +/**************************************************************************** + * Name: comp_close + * + * Description: + * This routine is called when the COMP device is closed. + * It waits for the last remaining data to be sent. + * + ****************************************************************************/ + +static int comp_close(FAR struct file *filep) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct comp_dev_s *dev = inode->i_private; + irqstate_t flags; + int ret = OK; + + if (sem_wait(&dev->ad_closesem) != OK) + { + ret = -errno; + } + else + { + /* Decrement the references to the driver. If the reference count will + * decrement to 0, then uninitialize the driver. + */ + + if (dev->ad_ocount > 1) + { + dev->ad_ocount--; + sem_post(&dev->ad_closesem); + } + else + { + /* There are no more references to the port */ + + dev->ad_ocount = 0; + + /* Free the IRQ and disable the COMP device */ + + flags = enter_critical_section(); /* Disable interrupts */ + dev->ad_ops->ao_shutdown(dev); /* Disable the COMP */ + leave_critical_section(flags); + + sem_post(&dev->ad_closesem); + } + } + + return ret; +} + +/**************************************************************************** + * Name: comp_read + ****************************************************************************/ + +static ssize_t comp_read(FAR struct file *filep, FAR char *buffer, size_t buflen) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct comp_dev_s *dev = inode->i_private; + int ret; + + ret = dev->ad_ops->ao_read(dev); + + buffer[0] = (uint8_t)ret; + + return 1; +} + +/**************************************************************************** + * Name: comp_ioctl +****************************************************************************/ + +static int comp_ioctl(FAR struct file *filep, int cmd, unsigned long arg) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct comp_dev_s *dev = inode->i_private; + int ret; + + ret = dev->ad_ops->ao_ioctl(dev, cmd, arg); + return ret; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: comp_register + ****************************************************************************/ + +int comp_register(FAR const char *path, FAR struct comp_dev_s *dev) +{ + int ret; + + /* Initialize the COMP device structure */ + + dev->ad_ocount = 0; + + /* Initialize semaphores */ + + sem_init(&dev->ad_closesem, 0, 1); + + /* Register the COMP character driver */ + + ret = register_driver(path, &comp_fops, 0444, dev); + if (ret < 0) + { + sem_destroy(&dev->ad_closesem); + } + + return ret; +} diff --git a/include/nuttx/analog/comp.h b/include/nuttx/analog/comp.h new file mode 100644 index 0000000000..9934d831ea --- /dev/null +++ b/include/nuttx/analog/comp.h @@ -0,0 +1,113 @@ +/************************************************************************************ + * include/nuttx/analog/comp.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Mateusz Szafoni + * + * 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_ANALOG_COMP_H +#define __INCLUDE_NUTTX_ANALOG_COMP_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include + +#include +#include +#include +#include +#include + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +struct comp_dev_s; +struct comp_ops_s +{ + /* Configure the COMP. This method is called the first time that the COMP + * device is opened. This will occur when the port is first opened. + * This setup includes configuring and attaching COMP interrupts. Interrupts + * are all disabled upon return. + */ + + CODE int (*ao_setup)(FAR struct comp_dev_s *dev); + + /* Disable the COMP. This method is called when the COMP device is closed. + * This method reverses the operation the setup method. + * Works only if COMP device is not locked. + */ + + CODE void (*ao_shutdown)(FAR struct comp_dev_s *dev); + + /* Read COMP output state */ + + CODE int (*ao_read)(FAR struct comp_dev_s *dev); + + /* All ioctl calls will be routed through this method */ + + CODE int (*ao_ioctl)(FAR struct comp_dev_s *dev, int cmd, unsigned long arg); +}; + +struct comp_dev_s +{ +#ifdef CONFIG_COMP + /* Fields managed by common upper half COMP logic */ + + uint8_t ad_ocount; /* The number of times the device has been opened */ + sem_t ad_closesem; /* Locks out new opens while close is in progress */ +#endif + + /* Fields provided by lower half COMP logic */ + + FAR const struct comp_ops_s *ad_ops; /* Arch-specific operations */ + FAR void *ad_priv; /* Used by the arch-specific logic */ +}; + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +#if defined(__cplusplus) +extern "C" +{ +#endif + +int comp_register(FAR const char *path, FAR struct comp_dev_s *dev); + +#if defined(__cplusplus) +} +#endif + +#endif /* __INCLUDE_NUTTX_ANALOG_COMP_H */ -- GitLab From a806aedb13eb0c75e4cfc52f224745c88aa7a357 Mon Sep 17 00:00:00 2001 From: raiden00pl Date: Sat, 25 Mar 2017 16:57:43 +0100 Subject: [PATCH 203/990] STM32F33: Support for COMP character driver --- arch/arm/src/stm32/stm32_comp.c | 421 +++++++++++++++++++++++--------- arch/arm/src/stm32/stm32_comp.h | 71 +----- 2 files changed, 304 insertions(+), 188 deletions(-) diff --git a/arch/arm/src/stm32/stm32_comp.c b/arch/arm/src/stm32/stm32_comp.c index 548baa9b11..9486c77f21 100644 --- a/arch/arm/src/stm32/stm32_comp.c +++ b/arch/arm/src/stm32/stm32_comp.c @@ -45,6 +45,8 @@ #include #include +#include +#include #include "chip.h" #include "stm32_gpio.h" @@ -60,6 +62,10 @@ defined(CONFIG_STM32_COMP5) || defined(CONFIG_STM32_COMP6) || \ defined(CONFIG_STM32_COMP7) +#ifndef CONFIG_STM32_SYSCFG +# error "SYSCFG clock enable must be set" +#endif + /* @TODO: support for STM32F30XX and STM32F37XX comparators */ #if defined(CONFIG_STM32_STM32F30XX) || defined(CONFIG_STM32_STM32F33XX) || \ @@ -145,6 +151,61 @@ * Private Types ****************************************************************************/ +/* This structure describes the configuration of one COMP device */ + +struct stm32_comp_s +{ + uint8_t blanking; /* Blanking source */ + uint8_t pol; /* Output polarity */ + uint8_t inm; /* Inverting input selection */ + uint8_t out; /* Comparator output */ + uint8_t lock; /* Comparator Lock */ + uint32_t csr; /* Control and status register */ +#ifndef CONFIG_STM32_STM32F33XX + uint8_t mode; /* Comparator mode */ + uint8_t hyst; /* Comparator hysteresis */ + /* @TODO: Window mode + INP selection */ +#endif +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* COMP Register access */ + +static inline void comp_modify_csr(FAR struct stm32_comp_s *priv, + uint32_t clearbits, uint32_t setbits); +static inline uint32_t comp_getreg_csr(FAR struct stm32_comp_s *priv); +static inline void comp_putreg_csr(FAR struct stm32_comp_s *priv, + uint32_t value); +static bool stm32_complock_get(FAR struct stm32_comp_s *priv); +static int stm32_complock(FAR struct stm32_comp_s *priv, bool lock); + +/* COMP Driver Methods */ + +static void comp_shutdown(FAR struct comp_dev_s *dev); +static int comp_setup(FAR struct comp_dev_s *dev); +static int comp_read(FAR struct comp_dev_s *dev); +static int comp_ioctl(FAR struct comp_dev_s *dev, int cmd, unsigned long arg); + +/* Initialization */ + +static int stm32_compconfig(FAR struct stm32_comp_s *priv); +static int stm32_compenable(FAR struct stm32_comp_s *priv, bool enable); + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +static const struct comp_ops_s g_compops = +{ + .ao_shutdown = comp_shutdown, + .ao_setup = comp_setup, + .ao_read = comp_read, + .ao_ioctl = comp_ioctl, +}; + #ifdef CONFIG_STM32_COMP1 static struct stm32_comp_s g_comp1priv = { @@ -159,6 +220,12 @@ static struct stm32_comp_s g_comp1priv = .hyst = COMP1_HYST, #endif }; + +static struct comp_dev_s g_comp1dev = +{ + .ad_ops = &g_compops, + .ad_priv = &g_comp1priv, +}; #endif #ifdef CONFIG_STM32_COMP2 @@ -175,6 +242,12 @@ static struct stm32_comp_s g_comp2priv = .hyst = COMP2_HYST, #endif }; + +static struct comp_dev_s g_comp2dev = +{ + .ad_ops = &g_compops, + .ad_priv = &g_comp2priv, +}; #endif #ifdef CONFIG_STM32_COMP3 @@ -187,10 +260,16 @@ static struct stm32_comp_s g_comp3priv = .lock = COMP3_LOCK, .csr = STM32_COMP3_CSR, #ifndef CONFIG_STM32_STM32F33XX - .mode = COMP3_MODE, - .hyst = COMP3_HYST, + .mode = COMP3_MODE, + .hyst = COMP3_HYST, #endif }; + +static struct comp_dev_s g_comp3dev = +{ + .ad_ops = &g_compops, + .ad_priv = &g_comp3priv, +}; #endif #ifdef CONFIG_STM32_COMP4 @@ -207,6 +286,12 @@ static struct stm32_comp_s g_comp4priv = .hyst = COMP4_HYST, #endif }; + +static struct comp_dev_s g_comp4dev = +{ + .ad_ops = &g_compops, + .ad_priv = &g_comp4priv, +}; #endif #ifdef CONFIG_STM32_COMP5 @@ -223,6 +308,12 @@ static struct stm32_comp_s g_comp5priv = .hyst = COMP5_HYST, #endif }; + +static struct comp_dev_s g_comp5dev = +{ + .ad_ops = &g_compops, + .ad_priv = &g_comp5priv, +}; #endif #ifdef CONFIG_STM32_COMP6 @@ -239,6 +330,12 @@ static struct stm32_comp_s g_comp6priv = .hyst = COMP6_HYST, #endif }; + +static struct comp_dev_s g_comp6dev = +{ + .ad_ops = &g_compops, + .ad_priv = &g_comp6priv, +}; #endif #ifdef CONFIG_STM32_COMP7 @@ -255,18 +352,13 @@ static struct stm32_comp_s g_comp7priv = .hyst = COMP7_HYST, #endif }; -#endif -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -static inline void comp_modify_csr(FAR struct stm32_comp_s *priv, - uint32_t clearbits, uint32_t setbits); -static inline uint32_t comp_getreg_csr(FAR struct stm32_comp_s *priv); -static inline void comp_putreg_csr(FAR struct stm32_comp_s *priv, - uint32_t value); -static bool stm32_complock_get(FAR struct stm32_comp_s *priv); +static struct comp_dev_s g_comp7dev = +{ + .ad_ops = &g_compops, + .ad_priv = &g_comp7priv, +}; +#endif /**************************************************************************** * Private Functions @@ -360,13 +452,52 @@ static bool stm32_complock_get(FAR struct stm32_comp_s *priv) regval = comp_getreg_csr(priv); - return ((regval & COMP_CSR_LOCK == 0) ? false : true); + return (((regval & COMP_CSR_LOCK) == 0) ? false : true); } /**************************************************************************** - * Public Functions + * Name: stm32_complock + * + * Description: + * Lock comparator CSR register + * + * Input Parameters: + * priv - A reference to the COMP structure + * enable - lock flag + * + * Returned Value: + * 0 on success, a negated errno value on failure + * ****************************************************************************/ +static int stm32_complock(FAR struct stm32_comp_s *priv, bool lock) +{ + bool current; + + current = stm32_complock_get(priv); + + if (current) + { + if (lock == false) + { + aerr("ERROR: COMP LOCK can be cleared only by a system reset\n"); + + return -EPERM; + } + } + else + { + if (lock == true) + { + comp_modify_csr(priv, 0, COMP_CSR_LOCK); + + priv->lock = COMP_LOCK_RO; + } + } + + return OK; +} + /**************************************************************************** * Name: stm32_compconfig * @@ -383,9 +514,9 @@ static bool stm32_complock_get(FAR struct stm32_comp_s *priv) * ****************************************************************************/ -int stm32_compconfig(FAR struct stm32_comp_s *priv) +static int stm32_compconfig(FAR struct stm32_comp_s *priv) { - uint32_t regval; + uint32_t regval = 0; int index; /* Get comparator index */ @@ -665,6 +796,146 @@ int stm32_compconfig(FAR struct stm32_comp_s *priv) return OK; } +/**************************************************************************** + * Name: stm32_compenable + * + * Description: + * Enable/disable comparator + * + * Input Parameters: + * priv - A reference to the COMP structure + * enable - enable/disable flag + * + * Returned Value: + * 0 on success, a negated errno value on failure + * + ****************************************************************************/ + +static int stm32_compenable(FAR struct stm32_comp_s *priv, bool enable) +{ + bool lock; + + ainfo("enable: %d\n", enable ? 1 : 0); + + lock = stm32_complock_get(priv); + + if (lock) + { + aerr("ERROR: Comparator locked!\n"); + + return -EPERM; + } + else + { + if (enable) + { + /* Enable the COMP */ + + comp_modify_csr(priv, 0, COMP_CSR_COMPEN); + } + else + { + /* Disable the COMP */ + + comp_modify_csr(priv, COMP_CSR_COMPEN, 0); + } + } + + return OK; +} + +/**************************************************************************** + * Name: adc_setup + * + * Description: + * Configure the COMP. This method is called the first time that the COMP + * device is opened. This will occur when the port is first opened. + * This setup includes configuring and attaching COMP interrupts. + * Interrupts are all disabled upon return. + * + * Input Parameters: + * + * Returned Value: + * + ****************************************************************************/ + +static int comp_setup(FAR struct comp_dev_s *dev) +{ +#warning "Missing logic" + return OK; +} + +/**************************************************************************** + * Name: comp_shutdown + * + * Description: + * Disable the COMP. This method is called when the COMP device is closed. + * This method reverses the operation the setup method. + * Works only if COMP device is not locked. + * + * Input Parameters: + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void comp_shutdown(FAR struct comp_dev_s *dev) +{ +#warning "Missing logic" +} + +/**************************************************************************** + * Name: comp_read + * + * Description: + * Get the COMP output state. + * + * Input Parameters: + * + * Returned Value: + * 0 if output is low (non-inverting input below inverting input), + * 1 if output is high (non inverting input above inverting input). + * + ****************************************************************************/ + +static int comp_read(FAR struct comp_dev_s *dev) +{ + FAR struct stm32_comp_s *priv; + uint32_t regval; + + priv = dev->ad_priv; + regval = comp_getreg_csr(priv); + + return (((regval & COMP_CSR_OUT) == 0) ? 0 : 1); +} + +/**************************************************************************** + * Name: comp_ioctl + * + * Description: + * All ioctl calls will be routed through this method. + * + * Input Parameters: + * dev - pointer to device structure used by the driver + * cmd - command + * arg - arguments passed with command + * + * Returned Value: + * Zero on success; a negated errno value on failure. + * + ****************************************************************************/ + +static int comp_ioctl(FAR struct comp_dev_s *dev, int cmd, unsigned long arg) +{ +#warning "Missing logic" + return -ENOTTY; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + /**************************************************************************** * Name: stm32_compinitialize * @@ -683,9 +954,10 @@ int stm32_compconfig(FAR struct stm32_comp_s *priv) * ****************************************************************************/ -FAR struct stm32_comp_s* stm32_compinitialize(int intf) +FAR struct comp_dev_s* stm32_compinitialize(int intf) { - FAR struct stm32_comp_s *priv; + FAR struct comp_dev_s *dev; + FAR struct stm32_comp_s *comp; int ret; switch (intf) @@ -693,49 +965,49 @@ FAR struct stm32_comp_s* stm32_compinitialize(int intf) #ifdef CONFIG_STM32_COMP1 case 1: ainfo("COMP1 selected\n"); - priv = &g_comp1priv; + dev = &g_comp1dev; break; #endif #ifdef CONFIG_STM32_COMP2 case 2: ainfo("COMP2 selected\n"); - priv = &g_comp2priv; + dev = &g_comp2dev; break; #endif #ifdef CONFIG_STM32_COMP3 case 3: ainfo("COMP3 selected\n"); - priv = &g_comp3priv; + dev = &g_comp3dev; break; #endif #ifdef CONFIG_STM32_COMP4 case 4: ainfo("COMP4 selected\n"); - priv = &g_comp4priv; + dev = &g_comp4dev; break; #endif #ifdef CONFIG_STM32_COMP5 case 5: ainfo("COMP5 selected\n"); - priv = &g_comp5priv; + dev = &g_comp5dev; break; #endif #ifdef CONFIG_STM32_COMP6 case 6: ainfo("COMP6 selected\n"); - priv = &g_comp6priv; + dev = &g_comp6dev; break; #endif #ifdef CONFIG_STM32_COMP7 case 7: ainfo("COMP7 selected\n"); - priv = &g_comp7priv; + dev = &g_comp7dev; break; #endif @@ -746,7 +1018,9 @@ FAR struct stm32_comp_s* stm32_compinitialize(int intf) /* Configure selected comparator */ - ret = stm32_compconfig(priv); + comp = dev->ad_priv; + + ret = stm32_compconfig(comp); if (ret < 0) { aerr("ERROR: Failed to initialize COMP%d: %d\n", intf, ret); @@ -754,98 +1028,7 @@ FAR struct stm32_comp_s* stm32_compinitialize(int intf) return NULL; } - return priv; -} - -/**************************************************************************** - * Name: stm32_compenable - * - * Description: - * Enable/disable comparator - * - * Input Parameters: - * priv - A reference to the COMP structure - * enable - enable/disable flag - * - * Returned Value: - * 0 on success, a negated errno value on failure - * - ****************************************************************************/ - -int stm32_compenable(FAR struct stm32_comp_s *priv, bool enable) -{ - bool lock; - - ainfo("enable: %d\n", enable ? 1 : 0); - - lock = stm32_complock_get(priv); - - if (lock) - { - aerr("ERROR: Comparator locked!\n"); - - return -EPERM; - } - else - { - if (enable) - { - /* Enable the COMP */ - - comp_modify_csr(priv, COMP_CSR_COMPEN, 0); - } - else - { - /* Disable the COMP */ - - comp_modify_csr(priv, 0, COMP_CSR_COMPEN); - } - } - - return OK; -} - -/**************************************************************************** - * Name: stm32_complock - * - * Description: - * Lock comparator CSR register - * - * Input Parameters: - * priv - A reference to the COMP structure - * enable - lock flag - * - * Returned Value: - * 0 on success, a negated errno value on failure - * - ****************************************************************************/ - -int stm32_complock(FAR struct stm32_comp_s *priv, bool lock) -{ - bool current; - - current = stm32_complock_get(priv); - - if (current) - { - if (lock == false) - { - aerr("ERROR: COMP LOCK can be cleared only by a system reset\n"); - - return -EPERM; - } - } - else - { - if (lock == true) - { - comp_modify_csr(priv, COMP_CSR_LOCK, 0); - - priv->lock = COMP_LOCK_RO; - } - } - - return OK; + return dev; } #endif /* CONFIG_STM32_STM32F30XX || CONFIG_STM32_STM32F33XX || diff --git a/arch/arm/src/stm32/stm32_comp.h b/arch/arm/src/stm32/stm32_comp.h index c703689d17..16a0ad6971 100644 --- a/arch/arm/src/stm32/stm32_comp.h +++ b/arch/arm/src/stm32/stm32_comp.h @@ -60,7 +60,7 @@ #define COMP_POL_DEFAULT COMP_POL_NONINVERT /* Output is not inverted */ #define COMP_INM_DEFAULT COMP_INMSEL_1P4VREF /* 1/4 of Vrefint as INM */ #define COMP_OUTSEL_DEFAULT COMP_OUTSEL_NOSEL /* Output not selected */ -#define COMP_LOCK_DEFAULT COMP_LOCK_RO /* Do not lock CSR register */ +#define COMP_LOCK_DEFAULT COMP_LOCK_RW /* Do not lock CSR register */ #ifndef CONFIG_STM32_STM32F33XX #define COMP_MODE_DEFAULT @@ -172,23 +172,6 @@ enum stm32_comp_winmode_e #endif -/* Comparator configuration ***********************************************************/ - -struct stm32_comp_s -{ - uint8_t blanking; /* Blanking source */ - uint8_t pol; /* Output polarity */ - uint8_t inm; /* Inverting input selection */ - uint8_t out; /* Comparator output */ - uint8_t lock; /* Comparator Lock */ - uint32_t csr; /* Control and status register */ -#ifndef CONFIG_STM32_STM32F33XX - uint8_t mode; /* Comparator mode */ - uint8_t hyst; /* Comparator hysteresis */ - /* @TODO: Window mode + INP selection */ -#endif -}; - /************************************************************************************ * Public Function Prototypes ************************************************************************************/ @@ -202,22 +185,6 @@ extern "C" #define EXTERN extern #endif -/**************************************************************************** -* Name: stm32_compconfig -* -* Description: -* Configure comparator and used I/Os -* -* Input Parameters: -* priv - A reference to the COMP structure -* -* Returned Value: -* 0 on success, a negated errno value on failure -* -****************************************************************************/ - -int stm32_compconfig(FAR struct stm32_comp_s *priv); - /**************************************************************************** * Name: stm32_compinitialize * @@ -236,41 +203,7 @@ int stm32_compconfig(FAR struct stm32_comp_s *priv); * ****************************************************************************/ -FAR struct stm32_comp_s* stm32_compinitialize(int intf); - -/**************************************************************************** -* Name: stm32_compenable -* -* Description: -* Enable/disable comparator -* -* Input Parameters: -* priv - A reference to the COMP structure -* enable - enable/disable flag -* -* Returned Value: -* 0 on success, a negated errno value on failure -* -****************************************************************************/ - -int stm32_compenable(FAR struct stm32_comp_s *priv, bool enable); - -/**************************************************************************** -* Name: stm32_complock -* -* Description: -* Lock comparator CSR register -* -* Input Parameters: -* priv - A reference to the COMP structure -* enable - lock flag -* -* Returned Value: -* 0 on success, a negated errno value on failure -* -****************************************************************************/ - -int stm32_complock(FAR struct stm32_comp_s *priv, bool lock); +FAR struct comp_dev_s* stm32_compinitialize(int intf); #undef EXTERN #ifdef __cplusplus -- GitLab From 645a11ce65c776d9b3e6e4b3bd30ec6db107269b Mon Sep 17 00:00:00 2001 From: raiden00pl Date: Sat, 25 Mar 2017 16:59:20 +0100 Subject: [PATCH 204/990] nucleo-f334r8: Use new COMP driver --- configs/nucleo-f334r8/src/stm32_comp.c | 23 ++++++++++++++++------- 1 file changed, 16 insertions(+), 7 deletions(-) diff --git a/configs/nucleo-f334r8/src/stm32_comp.c b/configs/nucleo-f334r8/src/stm32_comp.c index 0f775e1f3d..7b45b385a4 100644 --- a/configs/nucleo-f334r8/src/stm32_comp.c +++ b/configs/nucleo-f334r8/src/stm32_comp.c @@ -44,7 +44,7 @@ #include #include -/* #include */ +#include #include "stm32.h" @@ -52,6 +52,20 @@ defined(CONFIG_STM32_COMP4) || \ defined(CONFIG_STM32_COMP6)) +#ifdef CONFIG_STM32_COMP2 +# if defined(CONFIG_STM32_COMP4) || defined(CONFIG_STM32_COMP6) +# error "Currently only one COMP device supported" +# endif +#elif CONFIG_STM32_COMP4 +# if defined(CONFIG_STM32_COMP2) || defined(CONFIG_STM32_COMP6) +# error "Currently only one COMP device supported" +# endif +#elif CONFIG_STM32_COMP6 +# if defined(CONFIG_STM32_COMP2) || defined(CONFIG_STM32_COMP4) +# error "Currently only one COMP device supported" +# endif +#endif + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -67,9 +81,8 @@ int stm32_comp_setup(void) { static bool initialized = false; - struct stm32_comp_s* comp = NULL; + struct comp_dev_s* comp = NULL; int ret; - UNUSED(ret); if (!initialized) { @@ -100,16 +113,12 @@ int stm32_comp_setup(void) } #endif -#if 0 - /* COMP driver not implemented yet */ - ret = comp_register("/dev/comp0", comp); if (ret < 0) { aerr("ERROR: comp_register failed: %d\n", ret); return ret; } -#endif initialized = true; } -- GitLab From 602546f8522b01a1e5de73acddb9b57445e717b6 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 25 Mar 2017 10:23:53 -0600 Subject: [PATCH 205/990] Minor typo fix --- arch/arm/src/lpc43xx/lpc43_allocateheap.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/arch/arm/src/lpc43xx/lpc43_allocateheap.c b/arch/arm/src/lpc43xx/lpc43_allocateheap.c index b7a947b668..a6a73284d1 100644 --- a/arch/arm/src/lpc43xx/lpc43_allocateheap.c +++ b/arch/arm/src/lpc43xx/lpc43_allocateheap.c @@ -186,7 +186,7 @@ #ifndef CONFIG_LPC43_BOOT_SRAM /* Configuration A */ -/* CONFIG_RAM_START shoudl be set to the base of local SRAM, Bank 0. */ +/* CONFIG_RAM_START should be set to the base of local SRAM, Bank 0. */ # if CONFIG_RAM_START != LPC43_LOCSRAM_BANK0_BASE # error "CONFIG_RAM_START must be set to the base address of RAM bank 0" -- GitLab From 7d57a2b2bd2a38fcd9305546dee0c102ae4bb27f Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 25 Mar 2017 10:38:41 -0600 Subject: [PATCH 206/990] Trivial changes from review of last PR. --- arch/arm/src/stm32/stm32_comp.c | 1 + configs/nucleo-f334r8/src/stm32_comp.c | 4 ++++ drivers/analog/Kconfig | 7 +++---- drivers/analog/Make.defs | 3 +-- drivers/analog/comp.c | 5 ++++- 5 files changed, 13 insertions(+), 7 deletions(-) diff --git a/arch/arm/src/stm32/stm32_comp.c b/arch/arm/src/stm32/stm32_comp.c index 9486c77f21..a03f6a767e 100644 --- a/arch/arm/src/stm32/stm32_comp.c +++ b/arch/arm/src/stm32/stm32_comp.c @@ -87,6 +87,7 @@ /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ + /* COMP2 default configuration **********************************************/ #ifdef CONFIG_STM32_COMP2 diff --git a/configs/nucleo-f334r8/src/stm32_comp.c b/configs/nucleo-f334r8/src/stm32_comp.c index 7b45b385a4..c6b8be8249 100644 --- a/configs/nucleo-f334r8/src/stm32_comp.c +++ b/configs/nucleo-f334r8/src/stm32_comp.c @@ -86,6 +86,8 @@ int stm32_comp_setup(void) if (!initialized) { + /* Get the comparator interface */ + #ifdef CONFIG_STM32_COMP2 comp = stm32_compinitialize(2); if (comp == NULL) @@ -113,6 +115,8 @@ int stm32_comp_setup(void) } #endif + /* Register the comparator character driver at /dev/comp0 */ + ret = comp_register("/dev/comp0", comp); if (ret < 0) { diff --git a/drivers/analog/Kconfig b/drivers/analog/Kconfig index 99ff6b8fba..c9a2334361 100644 --- a/drivers/analog/Kconfig +++ b/drivers/analog/Kconfig @@ -110,12 +110,11 @@ endif # if ADC_PGA11X endif # ADC config COMP - bool "Analog Comparator" - default n - ---help--- + bool "Analog Comparator" + default n + ---help--- Select to enable support for Analog Comparators (COMPs). - config DAC bool "Digital-to-Analog Conversion" default n diff --git a/drivers/analog/Make.defs b/drivers/analog/Make.defs index 580a44ae84..fbcc369a4c 100644 --- a/drivers/analog/Make.defs +++ b/drivers/analog/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # drivers/analog/Make.defs # -# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2011-2012, 2017 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -104,4 +104,3 @@ ifeq ($(CONFIG_COMP),y) endif endif endif - diff --git a/drivers/analog/comp.c b/drivers/analog/comp.c index 5ebc2e87c2..d2b95d7767 100644 --- a/drivers/analog/comp.c +++ b/drivers/analog/comp.c @@ -77,7 +77,10 @@ static const struct file_operations comp_fops = NULL, /* seek */ comp_ioctl /* ioctl */ #ifndef CONFIG_DISABLE_POLL - , 0 + , NULL /* poll */ +#endif +#ifndef CONFIG_DISABLE_PSEUDOFS_OPERATIONS + , NULL /* unlink */ #endif }; -- GitLab From 6594c65a77edf84f87ce918e823fb30f4c40b2ae Mon Sep 17 00:00:00 2001 From: raiden00pl Date: Sun, 26 Mar 2017 09:30:23 +0200 Subject: [PATCH 207/990] stm32_comp.c: cosmetic --- arch/arm/src/stm32/stm32_comp.c | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/arch/arm/src/stm32/stm32_comp.c b/arch/arm/src/stm32/stm32_comp.c index 9486c77f21..62400883e1 100644 --- a/arch/arm/src/stm32/stm32_comp.c +++ b/arch/arm/src/stm32/stm32_comp.c @@ -52,8 +52,6 @@ #include "stm32_gpio.h" #include "stm32_comp.h" -#ifdef CONFIG_STM32_COMP - /* Some COMP peripheral must be enabled */ /* Up to 7 comparators in STM32F2 Series */ @@ -195,7 +193,7 @@ static int stm32_compconfig(FAR struct stm32_comp_s *priv); static int stm32_compenable(FAR struct stm32_comp_s *priv, bool enable); /**************************************************************************** - * Private Types + * Private Data ****************************************************************************/ static const struct comp_ops_s g_compops = @@ -1036,5 +1034,3 @@ FAR struct comp_dev_s* stm32_compinitialize(int intf) #endif /* CONFIG_STM32_COMP2 || CONFIG_STM32_COMP4 || * CONFIG_STM32_COMP6 */ - -#endif /* CONFIG_STM32_COMP */ -- GitLab From c1090164f520d41d5fbcc79b020940e149abcf38 Mon Sep 17 00:00:00 2001 From: raiden00pl Date: Sun, 26 Mar 2017 09:34:17 +0200 Subject: [PATCH 208/990] stm32/Kconfig: update COMP and OPAMP definitions --- arch/arm/src/stm32/Kconfig | 73 ++++++++++++++++++++++++++++++++++++-- 1 file changed, 70 insertions(+), 3 deletions(-) diff --git a/arch/arm/src/stm32/Kconfig b/arch/arm/src/stm32/Kconfig index eba911dfc5..97f097fc65 100644 --- a/arch/arm/src/stm32/Kconfig +++ b/arch/arm/src/stm32/Kconfig @@ -1450,7 +1450,7 @@ config STM32_STM32F33XX select STM32_HAVE_COMP2 select STM32_HAVE_COMP4 select STM32_HAVE_COMP6 - select STM32_HAVE_OPAMP + select STM32_HAVE_OPAMP2 select STM32_HAVE_CCM select STM32_HAVE_TIM1 select STM32_HAVE_TIM15 @@ -1907,18 +1907,34 @@ config STM32_HAVE_CAN2 bool default n +config STM32_HAVE_COMP1 + bool + default n + config STM32_HAVE_COMP2 bool default n +config STM32_HAVE_COMP3 + bool + default n + config STM32_HAVE_COMP4 bool default n +config STM32_HAVE_COMP5 + bool + default n + config STM32_HAVE_COMP6 bool default n +config STM32_HAVE_COMP7 + bool + default n + config STM32_HAVE_DAC1 bool default n @@ -1971,7 +1987,19 @@ config STM32_HAVE_I2SPLL bool default n -config STM32_HAVE_OPAMP +config STM32_HAVE_OPAMP1 + bool + default n + +config STM32_HAVE_OPAMP2 + bool + default n + +config STM32_HAVE_OPAMP3 + bool + default n + +config STM32_HAVE_OPAMP4 bool default n @@ -2032,21 +2060,41 @@ config STM32_COMP default n depends on STM32_STM32L15XX +config STM32_COMP1 + bool "COMP1" + default n + depends on STM32_HAVE_COMP1 + config STM32_COMP2 bool "COMP2" default n depends on STM32_HAVE_COMP2 +config STM32_COMP3 + bool "COMP3" + default n + depends on STM32_HAVE_COMP3 + config STM32_COMP4 bool "COMP4" default n depends on STM32_HAVE_COMP4 +config STM32_COMP5 + bool "COMP5" + default n + depends on STM32_HAVE_COMP5 + config STM32_COMP6 bool "COMP6" default n depends on STM32_HAVE_COMP6 +config STM32_COMP7 + bool "COMP7" + default n + depends on STM32_HAVE_COMP6 + config STM32_BKP bool "BKP" default n @@ -2185,7 +2233,26 @@ config STM32_DMA2D config STM32_OPAMP bool "OPAMP" default n - depends on STM32_HAVE_OPAMP + +config STM32_OPAMP1 + bool "OPAMP1" + default n + depends on STM32_HAVE_OPAMP1 + +config STM32_OPAMP2 + bool "OPAMP2" + default n + depends on STM32_HAVE_OPAMP2 + +config STM32_OPAMP3 + bool "OPAMP3" + default n + depends on STM32_HAVE_OPAMP3 + +config STM32_OPAMP4 + bool "OPAMP4" + default n + depends on STM32_HAVE_OPAMP4 config STM32_OTGFS bool "OTG FS" -- GitLab From f3367233b6dd077a2082f8a0fb8a9cd747a0d8a7 Mon Sep 17 00:00:00 2001 From: raiden00pl Date: Sun, 26 Mar 2017 09:36:53 +0200 Subject: [PATCH 209/990] stm32_comp.c: typo --- arch/arm/src/stm32/stm32_comp.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/arch/arm/src/stm32/stm32_comp.c b/arch/arm/src/stm32/stm32_comp.c index 62400883e1..571e97f62d 100644 --- a/arch/arm/src/stm32/stm32_comp.c +++ b/arch/arm/src/stm32/stm32_comp.c @@ -53,7 +53,7 @@ #include "stm32_comp.h" /* Some COMP peripheral must be enabled */ -/* Up to 7 comparators in STM32F2 Series */ +/* Up to 7 comparators in STM32F3 Series */ #if defined(CONFIG_STM32_COMP1) || defined(CONFIG_STM32_COMP2) || \ defined(CONFIG_STM32_COMP3) || defined(CONFIG_STM32_COMP4) || \ -- GitLab From bacc4e9b93b1778d1a52ca4c4a4a72f3f110d478 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 26 Mar 2017 09:22:00 -0600 Subject: [PATCH 210/990] Update errno values. Add new values; remove obsolete values --- include/errno.h | 247 +++++++++++++++++++------------------ libc/string/lib_strerror.c | 154 ++++++++++++----------- 2 files changed, 211 insertions(+), 190 deletions(-) diff --git a/include/errno.h b/include/errno.h index d6d4ec8e19..fd701d79cd 100644 --- a/include/errno.h +++ b/include/errno.h @@ -156,7 +156,7 @@ #define ENOMEM_STR "Out of memory" #define EACCES 13 #define EACCES_STR "Permission denied" -#define EFAULT 14 +#define EFAULT 14 /* Linux errno extension */ #define EFAULT_STR "Bad address" #define ENOTBLK 15 #define ENOTBLK_STR "Block device required" @@ -198,53 +198,48 @@ #define EDOM_STR "Math argument out of domain of func" #define ERANGE 34 #define ERANGE_STR "Math result not representable" -#define EDEADLK 35 -#define EDEADLOCK EDEADLK -#define EDEADLK_STR "Resource deadlock would occur" -#define ENAMETOOLONG 36 -#define ENAMETOOLONG_STR "File name too long" -#define ENOLCK 37 -#define ENOLCK_STR "No record locks available" -#define ENOSYS 38 -#define ENOSYS_STR "Function not implemented" -#define ENOTEMPTY 39 -#define ENOTEMPTY_STR "Directory not empty" -#define ELOOP 40 -#define ELOOP_STR "Too many symbolic links encountered" -#define ENOMSG 42 +#define ENOMSG 35 #define ENOMSG_STR "No message of desired type" -#define EIDRM 43 +#define EIDRM 36 #define EIDRM_STR "Identifier removed" -#define ECHRNG 44 +#define ECHRNG 37 /* Linux errno extension */ #define ECHRNG_STR "Channel number out of range" -#define EL2NSYNC 45 +#define EL2NSYNC 38 /* Linux errno extension */ #define EL2NSYNC_STR "Level 2 not synchronized" -#define EL3HLT 46 +#define EL3HLT 39 /* Linux errno extension */ #define EL3HLT_STR "Level 3 halted" -#define EL3RST 47 +#define EL3RST 40 /* Linux errno extension */ #define EL3RST_STR "Level 3 reset" -#define ELNRNG 48 +#define ELNRNG 41 /* Linux errno extension */ #define ELNRNG_STR "Link number out of range" -#define EUNATCH 49 +#define EUNATCH 42 /* Linux errno extension */ #define EUNATCH_STR "Protocol driver not attached" -#define ENOCSI 50 +#define ENOCSI 43 /* Linux errno extension */ #define ENOCSI_STR "No CSI structure available" -#define EL2HLT 51 +#define EL2HLT 44 /* Linux errno extension */ #define EL2HLT_STR "Level 2 halted" -#define EBADE 52 +#define EDEADLK 45 +#define EDEADLK_STR "Resource deadlock would occur" +#define ENOLCK 46 +#define ENOLCK_STR "No record locks available" + +#define EBADE 50 /* Linux errno extension */ #define EBADE_STR "Invalid exchange" -#define EBADR 53 +#define EBADR 51 /* Linux errno extension */ #define EBADR_STR "Invalid request descriptor" -#define EXFULL 54 +#define EXFULL 52 /* Linux errno extension */ #define EXFULL_STR "Exchange full" -#define ENOANO 55 +#define ENOANO 53 /* Linux errno extension */ #define ENOANO_STR "No anode" -#define EBADRQC 56 +#define EBADRQC 54 /* Linux errno extension */ #define EBADRQC_STR "Invalid request code" -#define EBADSLT 57 +#define EBADSLT 55 /* Linux errno extension */ #define EBADSLT_STR "Invalid slot" -#define EBFONT 59 +#define EDEADLOCK 56 /* Linux errno extension */ +#define EDEADLOCK_STR "File locking deadlock error" +#define EBFONT 57 /* Linux errno extension */ #define EBFONT_STR "Bad font file format" + #define ENOSTR 60 #define ENOSTR_STR "Device not a stream" #define ENODATA 61 @@ -253,130 +248,148 @@ #define ETIME_STR "Timer expired" #define ENOSR 63 #define ENOSR_STR "Out of streams resources" -#define ENONET 64 +#define ENONET 64 /* Linux errno extension */ #define ENONET_STR "Machine is not on the network" -#define ENOPKG 65 +#define ENOPKG 65 /* Linux errno extension */ #define ENOPKG_STR "Package not installed" -#define EREMOTE 66 +#define EREMOTE 66 /* Linux errno extension */ #define EREMOTE_STR "Object is remote" #define ENOLINK 67 #define ENOLINK_STR "Link has been severed" -#define EADV 68 +#define EADV 68 /* Linux errno extension */ #define EADV_STR "Advertise error" -#define ESRMNT 69 +#define ESRMNT 69 /* Linux errno extension */ #define ESRMNT_STR "Srmount error" -#define ECOMM 70 +#define ECOMM 70 /* Linux errno extension */ #define ECOMM_STR "Communication error on send" #define EPROTO 71 #define EPROTO_STR "Protocol error" -#define EMULTIHOP 72 + +#define EMULTIHOP 74 #define EMULTIHOP_STR "Multihop attempted" -#define EDOTDOT 73 +#define ELBIN 75 /* Linux errno extension */ +#define ELBIN_STR "Inode is remote" +#define EDOTDOT 76 /* Linux errno extension */ #define EDOTDOT_STR "RFS specific error" -#define EBADMSG 74 +#define EBADMSG 77 #define EBADMSG_STR "Not a data message" -#define EOVERFLOW 75 -#define EOVERFLOW_STR "Value too large for defined data type" -#define ENOTUNIQ 76 + +#define EFTYPE 79 +#define EFTYPE_STR "Inappropriate file type or format" +#define ENOTUNIQ 80 /* Linux errno extension */ #define ENOTUNIQ_STR "Name not unique on network" -#define EBADFD 77 +#define EBADFD 81 /* Linux errno extension */ #define EBADFD_STR "File descriptor in bad state" -#define EREMCHG 78 +#define EREMCHG 82 /* Linux errno extension */ #define EREMCHG_STR "Remote address changed" -#define ELIBACC 79 +#define ELIBACC 83 /* Linux errno extension */ #define ELIBACC_STR "Can not access a needed shared library" -#define ELIBBAD 80 +#define ELIBBAD 84 /* Linux errno extension */ #define ELIBBAD_STR "Accessing a corrupted shared library" -#define ELIBSCN 81 +#define ELIBSCN 85 /* Linux errno extension */ #define ELIBSCN_STR ".lib section in a.out corrupted" -#define ELIBMAX 82 +#define ELIBMAX 86 /* Linux errno extension */ #define ELIBMAX_STR "Attempting to link in too many shared libraries" -#define ELIBEXEC 83 +#define ELIBEXEC 87 /* Linux errno extension */ #define ELIBEXEC_STR "Cannot exec a shared library directly" -#define EILSEQ 84 -#define EILSEQ_STR "Illegal byte sequence" -#define ERESTART 85 -#define ERESTART_STR "Interrupted system call should be restarted" -#define ESTRPIPE 86 -#define ESTRPIPE_STR "Streams pipe error" -#define EUSERS 87 -#define EUSERS_STR "Too many users" -#define ENOTSOCK 88 -#define ENOTSOCK_STR "Socket operation on non-socket" -#define EDESTADDRREQ 89 -#define EDESTADDRREQ_STR "Destination address required" -#define EMSGSIZE 90 -#define EMSGSIZE_STR "Message too long" -#define EPROTOTYPE 91 -#define EPROTOTYPE_STR "Protocol wrong type for socket" -#define ENOPROTOOPT 92 -#define ENOPROTOOPT_STR "Protocol not available" -#define EPROTONOSUPPORT 93 -#define EPROTONOSUPPORT_STR "Protocol not supported" -#define ESOCKTNOSUPPORT 94 -#define ESOCKTNOSUPPORT_STR "Socket type not supported" +#define ENOSYS 88 +#define ENOSYS_STR "Function not implemented" +#define ENMFILE 89 /* Cygwin */ +#define ENMFILE_STR "No more files" +#define ENOTEMPTY 90 +#define ENOTEMPTY_STR "Directory not empty" +#define ENAMETOOLONG 91 +#define ENAMETOOLONG_STR "File name too long" +#define ELOOP 92 +#define ELOOP_STR "Too many symbolic links encountered" + #define EOPNOTSUPP 95 #define EOPNOTSUPP_STR "Operation not supported on transport endpoint" #define EPFNOSUPPORT 96 #define EPFNOSUPPORT_STR "Protocol family not supported" -#define EAFNOSUPPORT 97 -#define EAFNOSUPPORT_STR "Address family not supported by protocol" -#define EADDRINUSE 98 -#define EADDRINUSE_STR "Address already in use" -#define EADDRNOTAVAIL 99 -#define EADDRNOTAVAIL_STR "Cannot assign requested address" -#define ENETDOWN 100 -#define ENETDOWN_STR "Network is down" -#define ENETUNREACH 101 -#define ENETUNREACH_STR "Network is unreachable" -#define ENETRESET 102 -#define ENETRESET_STR "Network dropped connection because of reset" -#define ECONNABORTED 103 -#define ECONNABORTED_STR "Software caused connection abort" + #define ECONNRESET 104 #define ECONNRESET_STR "Connection reset by peer" #define ENOBUFS 105 #define ENOBUFS_STR "No buffer space available" -#define EISCONN 106 -#define EISCONN_STR "Transport endpoint is already connected" -#define ENOTCONN 107 -#define ENOTCONN_STR "Transport endpoint is not connected" -#define ESHUTDOWN 108 +#define EAFNOSUPPORT 106 +#define EAFNOSUPPORT_STR "Address family not supported by protocol" +#define EPROTOTYPE 107 +#define EPROTOTYPE_STR "Protocol wrong type for socket" +#define ENOTSOCK 108 +#define ENOTSOCK_STR "Socket operation on non-socket" +#define ENOPROTOOPT 109 +#define ENOPROTOOPT_STR "Protocol not available" +#define ESHUTDOWN 110 /* Linux errno extension */ #define ESHUTDOWN_STR "Cannot send after transport endpoint shutdown" -#define ETOOMANYREFS 109 -#define ETOOMANYREFS_STR "Too many references: cannot splice" -#define ETIMEDOUT 110 -#define ETIMEDOUT_STR "Connection timed out" #define ECONNREFUSED 111 #define ECONNREFUSED_STR "Connection refused" -#define EHOSTDOWN 112 +#define EADDRINUSE 112 +#define EADDRINUSE_STR "Address already in use" +#define ECONNABORTED 113 +#define ECONNABORTED_STR "Software caused connection abort" +#define ENETUNREACH 114 +#define ENETUNREACH_STR "Network is unreachable" +#define ENETDOWN 115 +#define ENETDOWN_STR "Network is down" +#define ETIMEDOUT 116 +#define ETIMEDOUT_STR "Connection timed out" +#define EHOSTDOWN 117 #define EHOSTDOWN_STR "Host is down" -#define EHOSTUNREACH 113 +#define EHOSTUNREACH 118 #define EHOSTUNREACH_STR "No route to host" -#define EALREADY 114 -#define EALREADY_STR "Operation already in progress" -#define EINPROGRESS 115 +#define EINPROGRESS 119 #define EINPROGRESS_STR "Operation now in progress" -#define ESTALE 116 -#define ESTALE_STR "Stale NFS file handle" -#define EUCLEAN 117 -#define EUCLEAN_STR "Structure needs cleaning" -#define ENOTNAM 118 -#define ENOTNAM_STR "Not a XENIX named type file" -#define ENAVAIL 119 -#define ENAVAIL_STR "No XENIX semaphores available" -#define EISNAM 120 -#define EISNAM_STR "Is a named type file" -#define EREMOTEIO 121 -#define EREMOTEIO_STR "Remote I/O error" -#define EDQUOT 122 +#define EALREADY 120 +#define EALREADY_STR "Socket already connected" +#define EDESTADDRREQ 121 +#define EDESTADDRREQ_STR "Destination address required" +#define EMSGSIZE 122 +#define EMSGSIZE_STR "Message too long" +#define EPROTONOSUPPORT 123 +#define EPROTONOSUPPORT_STR "Protocol not supported" +#define ESOCKTNOSUPPORT 124 /* Linux errno extension */ +#define ESOCKTNOSUPPORT_STR "Socket type not supported" +#define EADDRNOTAVAIL 125 +#define EADDRNOTAVAIL_STR "Cannot assign requested address" +#define ENETRESET 126 +#define ENETRESET_STR "Network dropped connection because of reset" +#define EISCONN 127 +#define EISCONN_STR "Transport endpoint is already connected" +#define ENOTCONN 128 +#define ENOTCONN_STR "Transport endpoint is not connected" +#define ETOOMANYREFS 129 +#define ETOOMANYREFS_STR "Too many references: cannot splice" +#define EPROCLIM 130 +#define EPROCLIM_STR "Limit would be exceeded by attempted fork" +#define EUSERS 131 +#define EUSERS_STR "Too many users" +#define EDQUOT 132 #define EDQUOT_STR "Quota exceeded" -#define ENOMEDIUM 123 +#define ESTALE 133 +#define ESTALE_STR "Stale NFS file handle" +#define ENOTSUP 134 +#define ENOTSUP_STR "Not supported" +#define ENOMEDIUM 135 /* Linux errno extension */ #define ENOMEDIUM_STR "No medium found" -#define EMEDIUMTYPE 124 -#define EMEDIUMTYPE_STR "Wrong medium type" -#define ECANCELED 125 +#define ENOSHARE 136 /* Cygwin */ +#define ENOSHARE_STR "No such host or network path" +#define ECASECLASH 137 /* Cygwin */ +#define ECASECLASH_STR "Filename exists with different case" +#define EILSEQ 138 +#define EILSEQ_STR "Illegal byte sequence" +#define EOVERFLOW 139 +#define EOVERFLOW_STR "Value too large for defined data type" +#define ECANCELED 140 #define ECANCELED_STR "Operation cancelled" +#define ENOTRECOVERABLE 141 +#define ENOTRECOVERABLE_STR "State not recoverable" +#define EOWNERDEAD 142 +#define EOWNERDEAD_STR "Previous owner died" +#define ESTRPIPE 143 /* Linux errno extension */ +#define ESTRPIPE_STR "Streams pipe error" + +#define __ELASTERROR 2000 /* Users can add values starting here */ /**************************************************************************** * Public Type Definitions diff --git a/libc/string/lib_strerror.c b/libc/string/lib_strerror.c index 00eb2248a2..409501f390 100644 --- a/libc/string/lib_strerror.c +++ b/libc/string/lib_strerror.c @@ -110,12 +110,6 @@ static const struct errno_strmap_s g_errnomap[] = { EPIPE, EPIPE_STR }, { EDOM, EDOM_STR }, { ERANGE, ERANGE_STR }, - { EDEADLK, EDEADLK_STR }, - { ENAMETOOLONG, ENAMETOOLONG_STR }, - { ENOLCK, ENOLCK_STR }, - { ENOSYS, ENOSYS_STR }, - { ENOTEMPTY, ENOTEMPTY_STR }, - { ELOOP, ELOOP_STR }, { ENOMSG, ENOMSG_STR }, { EIDRM, EIDRM_STR }, { ECHRNG, ECHRNG_STR }, @@ -126,12 +120,15 @@ static const struct errno_strmap_s g_errnomap[] = { EUNATCH, EUNATCH_STR }, { ENOCSI, ENOCSI_STR }, { EL2HLT, EL2HLT_STR }, + { EDEADLK, EDEADLK_STR }, + { ENOLCK, ENOLCK_STR }, { EBADE, EBADE_STR }, { EBADR, EBADR_STR }, { EXFULL, EXFULL_STR }, { ENOANO, ENOANO_STR }, { EBADRQC, EBADRQC_STR }, { EBADSLT, EBADSLT_STR }, + { EDEADLOCK, EDEADLOCK_STR }, { EBFONT, EBFONT_STR }, { ENOSTR, ENOSTR_STR }, { ENODATA, ENODATA_STR }, @@ -146,9 +143,10 @@ static const struct errno_strmap_s g_errnomap[] = { ECOMM, ECOMM_STR }, { EPROTO, EPROTO_STR }, { EMULTIHOP, EMULTIHOP_STR }, + { ELBIN, ELBIN_STR }, { EDOTDOT, EDOTDOT_STR }, { EBADMSG, EBADMSG_STR }, - { EOVERFLOW, EOVERFLOW_STR }, + { EFTYPE, EFTYPE_STR }, { ENOTUNIQ, ENOTUNIQ_STR }, { EBADFD, EBADFD_STR }, { EREMCHG, EREMCHG_STR }, @@ -157,47 +155,53 @@ static const struct errno_strmap_s g_errnomap[] = { ELIBSCN, ELIBSCN_STR }, { ELIBMAX, ELIBMAX_STR }, { ELIBEXEC, ELIBEXEC_STR }, - { EILSEQ, EILSEQ_STR }, - { ERESTART, ERESTART_STR }, - { ESTRPIPE, ESTRPIPE_STR }, - { EUSERS, EUSERS_STR }, + { ENOSYS, ENOSYS_STR }, + { ENMFILE, ENMFILE_STR }, + { ENOTEMPTY, ENOTEMPTY_STR }, + { ENAMETOOLONG, ENAMETOOLONG_STR }, + { ELOOP, ELOOP_STR }, + { EOPNOTSUPP, EOPNOTSUPP_STR }, + { EPFNOSUPPORT, EPFNOSUPPORT_STR }, + { ECONNRESET, ECONNRESET_STR }, + { ENOBUFS, ENOBUFS_STR }, + { EAFNOSUPPORT, EAFNOSUPPORT_STR }, + { EPROTOTYPE, EPROTOTYPE_STR }, { ENOTSOCK, ENOTSOCK_STR }, + { ENOPROTOOPT, ENOPROTOOPT_STR }, + { ESHUTDOWN, ESHUTDOWN_STR }, + { ECONNREFUSED, ECONNREFUSED_STR }, + { EADDRINUSE, EADDRINUSE_STR }, + { ECONNABORTED, ECONNABORTED_STR }, + { ENETUNREACH, ENETUNREACH_STR }, + { ENETDOWN, ENETDOWN_STR }, + { ETIMEDOUT, ETIMEDOUT_STR }, + { EHOSTDOWN, EHOSTDOWN_STR }, + { EHOSTUNREACH, EHOSTUNREACH_STR }, + { EINPROGRESS, EINPROGRESS_STR }, + { EALREADY, EALREADY_STR }, { EDESTADDRREQ, EDESTADDRREQ_STR }, { EMSGSIZE, EMSGSIZE_STR }, - { EPROTOTYPE, EPROTOTYPE_STR }, - { ENOPROTOOPT, ENOPROTOOPT_STR }, { EPROTONOSUPPORT, EPROTONOSUPPORT_STR }, { ESOCKTNOSUPPORT, ESOCKTNOSUPPORT_STR }, - { EOPNOTSUPP, EOPNOTSUPP_STR }, - { EPFNOSUPPORT, EPFNOSUPPORT_STR }, - { EAFNOSUPPORT, EAFNOSUPPORT_STR }, - { EADDRINUSE, EADDRINUSE_STR }, { EADDRNOTAVAIL, EADDRNOTAVAIL_STR }, - { ENETDOWN, ENETDOWN_STR }, - { ENETUNREACH, ENETUNREACH_STR }, { ENETRESET, ENETRESET_STR }, - { ECONNABORTED, ECONNABORTED_STR }, - { ECONNRESET, ECONNRESET_STR }, - { ENOBUFS, ENOBUFS_STR }, { EISCONN, EISCONN_STR }, { ENOTCONN, ENOTCONN_STR }, - { ESHUTDOWN, ESHUTDOWN_STR }, { ETOOMANYREFS, ETOOMANYREFS_STR }, - { ETIMEDOUT, ETIMEDOUT_STR }, - { ECONNREFUSED, ECONNREFUSED_STR }, - { EHOSTDOWN, EHOSTDOWN_STR }, - { EHOSTUNREACH, EHOSTUNREACH_STR }, - { EALREADY, EALREADY_STR }, - { EINPROGRESS, EINPROGRESS_STR }, - { ESTALE, ESTALE_STR }, - { EUCLEAN, EUCLEAN_STR }, - { ENOTNAM, ENOTNAM_STR }, - { ENAVAIL, ENAVAIL_STR }, - { EISNAM, EISNAM_STR }, - { EREMOTEIO, EREMOTEIO_STR }, + { EPROCLIM, EPROCLIM_STR }, + { EUSERS, EUSERS_STR }, { EDQUOT, EDQUOT_STR }, + { ESTALE, ESTALE_STR }, + { ENOTSUP, ENOTSUP_STR }, { ENOMEDIUM, ENOMEDIUM_STR }, - { EMEDIUMTYPE, EMEDIUMTYPE_STR } + { ENOSHARE, ENOSHARE_STR }, + { ECASECLASH, ECASECLASH_STR }, + { EILSEQ, EILSEQ_STR }, + { EOVERFLOW, EOVERFLOW_STR }, + { ECANCELED, ECANCELED_STR }, + { ENOTRECOVERABLE, ENOTRECOVERABLE_STR }, + { EOWNERDEAD, EOWNERDEAD_STR }, + { ESTRPIPE, ESTRPIPE_STR } }; #else /* CONFIG_LIBC_STRERROR_SHORT */ @@ -238,28 +242,25 @@ static const struct errno_strmap_s g_errnomap[] = { EPIPE, "EPIPE" }, { EDOM, "EDOM" }, { ERANGE, "ERANGE" }, - { EDEADLK, "EDEADLK" }, - { ENAMETOOLONG, "ENAMETOOLONG" }, - { ENOLCK, "ENOLCK" }, - { ENOSYS, "ENOSYS" }, - { ENOTEMPTY, "ENOTEMPTY" }, - { ELOOP, "ELOOP" }, { ENOMSG, "ENOMSG" }, { EIDRM, "EIDRM" }, { ECHRNG, "ECHRNG" }, { EL2NSYNC, "EL2NSYNC" }, { EL3HLT, "EL3HLT" }, { EL3RST, "EL3RST" }, - { EL3RST, "EL3RST" }, + { ELNRNG, "ELNRNG" }, { EUNATCH, "EUNATCH" }, { ENOCSI, "ENOCSI" }, { EL2HLT, "EL2HLT" }, + { EDEADLK, "EDEADLK" }, + { ENOLCK, "ENOLCK" }, { EBADE, "EBADE" }, { EBADR, "EBADR" }, { EXFULL, "EXFULL" }, { ENOANO, "ENOANO" }, { EBADRQC, "EBADRQC" }, { EBADSLT, "EBADSLT" }, + { EDEADLOCK, "EDEADLOCK" }, { EBFONT, "EBFONT" }, { ENOSTR, "ENOSTR" }, { ENODATA, "ENODATA" }, @@ -274,9 +275,10 @@ static const struct errno_strmap_s g_errnomap[] = { ECOMM, "ECOMM" }, { EPROTO, "EPROTO" }, { EMULTIHOP, "EMULTIHOP" }, + { ELBIN, "ELBIN" }, { EDOTDOT, "EDOTDOT" }, { EBADMSG, "EBADMSG" }, - { EOVERFLOW, "EOVERFLOW" }, + { EFTYPE, "EFTYPE" }, { ENOTUNIQ, "ENOTUNIQ" }, { EBADFD, "EBADFD" }, { EREMCHG, "EREMCHG" }, @@ -285,47 +287,53 @@ static const struct errno_strmap_s g_errnomap[] = { ELIBSCN, "ELIBSCN" }, { ELIBMAX, "ELIBMAX" }, { ELIBEXEC, "ELIBEXEC" }, - { EILSEQ, "EILSEQ" }, - { ERESTART, "ERESTART" }, - { ESTRPIPE, "ESTRPIPE" }, - { EUSERS, "EUSERS" }, + { ENOSYS, "ENOSYS" }, + { ENMFILE, "ENMFILE" }, + { ENOTEMPTY, "ENOTEMPTY" }, + { ENAMETOOLONG, "ENAMETOOLONG" }, + { ELOOP, "ELOOP" }, + { EOPNOTSUPP, "EOPNOTSUPP" }, + { EPFNOSUPPORT, "EPFNOSUPPORT" }, + { ECONNRESET, "ECONNRESET" }, + { ENOBUFS, "ENOBUFS" }, + { EAFNOSUPPORT, "EAFNOSUPPORT" }, + { EPROTOTYPE, "EPROTOTYPE" }, { ENOTSOCK, "ENOTSOCK" }, + { ENOPROTOOPT, "ENOPROTOOPT" }, + { ESHUTDOWN, "ESHUTDOWN" }, + { ECONNREFUSED, "ECONNREFUSED" }, + { EADDRINUSE, "EADDRINUSE" }, + { ECONNABORTED, "ECONNABORTED" }, + { ENETUNREACH, "ENETUNREACH" }, + { ENETDOWN, "ENETDOWN" }, + { ETIMEDOUT, "ETIMEDOUT" }, + { EHOSTDOWN, "EHOSTDOWN" }, + { EHOSTUNREACH, "EHOSTUNREACH" }, + { EINPROGRESS, "EINPROGRESS" }, + { EALREADY, "EALREADY" }, { EDESTADDRREQ, "EDESTADDRREQ" }, { EMSGSIZE, "EMSGSIZE" }, - { EPROTOTYPE, "EPROTOTYPE" }, - { ENOPROTOOPT, "ENOPROTOOPT" }, { EPROTONOSUPPORT, "EPROTONOSUPPORT" }, { ESOCKTNOSUPPORT, "ESOCKTNOSUPPORT" }, - { EOPNOTSUPP, "EOPNOTSUPP" }, - { EPFNOSUPPORT, "EPFNOSUPPORT" }, - { EAFNOSUPPORT, "EAFNOSUPPORT" }, - { EADDRINUSE, "EADDRINUSE" }, { EADDRNOTAVAIL, "EADDRNOTAVAIL" }, - { ENETDOWN, "ENETDOWN" }, - { ENETUNREACH, "ENETUNREACH" }, { ENETRESET, "ENETRESET" }, - { ECONNABORTED, "ECONNABORTED" }, - { ECONNRESET, "ECONNRESET" }, - { ENOBUFS, "ENOBUFS" }, { EISCONN, "EISCONN" }, { ENOTCONN, "ENOTCONN" }, - { ESHUTDOWN, "ESHUTDOWN" }, { ETOOMANYREFS, "ETOOMANYREFS" }, - { ETIMEDOUT, "ETIMEDOUT" }, - { ECONNREFUSED, "ECONNREFUSED" }, - { EHOSTDOWN, "EHOSTDOWN" }, - { EHOSTUNREACH, "EHOSTUNREACH" }, - { EALREADY, "EALREADY" }, - { EINPROGRESS, "EINPROGRESS" }, - { ESTALE, "ESTALE" }, - { EUCLEAN, "EUCLEAN" }, - { ENOTNAM, "ENOTNAM" }, - { ENAVAIL, "ENAVAIL" }, - { EISNAM, "EISNAM" }, - { EREMOTEIO, "EREMOTEIO" }, + { EPROCLIM, "EPROCLIM" }, + { EUSERS, "EUSERS" }, { EDQUOT, "EDQUOT" }, + { ESTALE, "ESTALE" }, + { ENOTSUP, "ENOTSUP" }, { ENOMEDIUM, "ENOMEDIUM" }, - { EMEDIUMTYPE, "EMEDIUMTYPE" } + { ENOSHARE, "ENOSHARE" }, + { ECASECLASH, "ECASECLASH" }, + { EILSEQ, "EILSEQ" }, + { EOVERFLOW, "EOVERFLOW" }, + { ECANCELED, "ECANCELED" }, + { ENOTRECOVERABLE, "ENOTRECOVERABLE" }, + { EOWNERDEAD, "EOWNERDEAD" }, + { ESTRPIPE, "ESTRPIPE" } }; #endif /* CONFIG_LIBC_STRERROR_SHORT */ -- GitLab From 363403fb1f135319e0a2c401b2caa63539bfb080 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 26 Mar 2017 10:35:23 -0600 Subject: [PATCH 211/990] pthreads: Add more robustness characteristics: pthread_mutex_lock() and trylock() will now return EOWNERDEAD if the mutex is locked by a thread that no longer exists. Add pthread_mutex_consistent() to recover from this situation. --- TODO | 36 ++++++- include/pthread.h | 6 +- sched/pthread/Make.defs | 1 + sched/pthread/pthread_mutexconsistent.c | 138 ++++++++++++++++++++++++ sched/pthread/pthread_mutexdestroy.c | 96 +++++++++++------ sched/pthread/pthread_mutexlock.c | 53 ++++++--- sched/pthread/pthread_mutextrylock.c | 78 +++++++++----- sched/pthread/pthread_mutexunlock.c | 15 ++- 8 files changed, 337 insertions(+), 86 deletions(-) create mode 100644 sched/pthread/pthread_mutexconsistent.c diff --git a/TODO b/TODO index ad47655bf4..b0bb4f5017 100644 --- a/TODO +++ b/TODO @@ -1,4 +1,4 @@ -NuttX TODO List (Last updated March 14, 2017) +NuttX TODO List (Last updated March 26, 2017) ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ This file summarizes known NuttX bugs, limitations, inconsistencies with @@ -14,7 +14,7 @@ nuttx/: (1) Memory Management (mm/) (0) Power Management (drivers/pm) (3) Signals (sched/signal, arch/) - (2) pthreads (sched/pthread) + (4) pthreads (sched/pthread) (0) Message Queues (sched/mqueue) (8) Kernel/Protected Build (3) C++ Support @@ -346,7 +346,7 @@ o Signals (sched/signal, arch/) Priority: Low. Even if there are only 31 usable signals, that is still a lot. o pthreads (sched/pthreads) - ^^^^^^^^^^^^^^^^^ + ^^^^^^^^^^^^^^^^^^^^^^^^^ Title: PTHREAD_PRIO_PROTECT Description: Extend pthread_mutexattr_setprotocol(). It should support @@ -448,6 +448,36 @@ o pthreads (sched/pthreads) Status: Not really open. This is just the way it is. Priority: Nothing additional is planned. + Title: PTHREAD FILES IN WRONG LOCATTION + Description: There are many pthread interface functions in files located in + sched/pthread. These should be moved from that location to + libc/pthread. In the flat build, this really does not matter, + but in the protected build that location means that system calls + are required to access the pthread interface functions. + Status: Open + Priority: Medium-low. Priority may be higher if system call overheade becomes + an issue. + + Title: ROBUST MUTEX ATTRIBUTE NOT SUPPORTED + Description: In NuttX, all mutexes are 'robust' in the sense that an attmpt + to lock a mutex will return EOWNDERDEAD if the holder of the + mutex has died. Unlocking of a mutex will fail if the caller + is not the holder of the mutex. + + POSIX, however, requires that there be a mutex attribute called + robust that determines which behavior is supported. non-robust + should be the default. NuttX does not support this attribute + and robust behavior is the default and only supported behavior. + + The spec is not clear, but I think there there is also missing + logic when the thread exits. I believe that the next highest + prority thread waiting for the mutex should be awakend and + pthread_mutex_lock() should return EOWNERDEAD. + That does not happen now. They will just remain blocked. + Status: Open + Priority: Low. The non-robust behavior is dangerous and really should never + be used. + o Message Queues (sched/mqueue) ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/include/pthread.h b/include/pthread.h index d943a843e2..6fed93a837 100644 --- a/include/pthread.h +++ b/include/pthread.h @@ -1,7 +1,7 @@ /******************************************************************************** * include/pthread.h * - * Copyright (C) 2007-2009, 2011-2012, 2015-2016 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009, 2011-2012, 2015-2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -424,6 +424,10 @@ int pthread_mutex_lock(FAR pthread_mutex_t *mutex); int pthread_mutex_trylock(FAR pthread_mutex_t *mutex); int pthread_mutex_unlock(FAR pthread_mutex_t *mutex); +/* Make sure that the pthread mutex is in a consistent state */ + +int pthread_mutex_consistent(FAR pthread_mutex_t *mutex); + /* Operations on condition variables */ int pthread_condattr_init(FAR pthread_condattr_t *attr); diff --git a/sched/pthread/Make.defs b/sched/pthread/Make.defs index 6156dd5411..5a602d3e1f 100644 --- a/sched/pthread/Make.defs +++ b/sched/pthread/Make.defs @@ -39,6 +39,7 @@ CSRCS += pthread_create.c pthread_exit.c pthread_join.c pthread_detach.c CSRCS += pthread_yield.c pthread_getschedparam.c pthread_setschedparam.c CSRCS += pthread_mutexinit.c pthread_mutexdestroy.c CSRCS += pthread_mutexlock.c pthread_mutextrylock.c pthread_mutexunlock.c +CSRCS += pthread_mutexconsistent.c CSRCS += pthread_condinit.c pthread_conddestroy.c CSRCS += pthread_condwait.c pthread_condsignal.c pthread_condbroadcast.c CSRCS += pthread_barrierinit.c pthread_barrierdestroy.c pthread_barrierwait.c diff --git a/sched/pthread/pthread_mutexconsistent.c b/sched/pthread/pthread_mutexconsistent.c new file mode 100644 index 0000000000..0579cb3841 --- /dev/null +++ b/sched/pthread/pthread_mutexconsistent.c @@ -0,0 +1,138 @@ +/**************************************************************************** + * sched/pthread/pthread_mutexconsistent.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include + +#include "pthread/pthread.h" + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: pthread_mutex_consistent + * + * Description: + * If mutex is a robust mutex in an inconsistent state, the + * pthread_mutex_consistent() function can be used to mark the state + * protected by the mutex referenced by mutex as consistent again. + * + * If an owner of a robust mutex terminates while holding the mutex, the + * mutex becomes inconsistent and the next thread that acquires the mutex + * lock will be notified of the state by the return value EOWNERDEAD. + * In this case, the mutex does not become normally usable again until the + * state is marked consistent. + * + * If the thread which acquired the mutex lock with the return value + * EOWNERDEAD terminates before calling either pthread_mutex_consistent() + * or pthread_mutex_unlock(), the next thread that acquires the mutex lock + * will be notified about the state of the mutex by the return value + * EOWNERDEAD. + * + * The behavior is undefined if the value specified by the mutex argument + * to pthread_mutex_consistent() does not refer to an initialized mutex. + * + * Input Parameters: + * mutex -- a reference to the mutex to be made consistent + * + * Returned Value: + * Upon successful completion, the pthread_mutex_consistent() function + * will return zero. Otherwise, an error value will be returned to + * indicate the error. + * + ****************************************************************************/ + +int pthread_mutex_consistent(FAR pthread_mutex_t *mutex) +{ + int ret = EINVAL; + int status; + + sinfo("mutex=0x%p\n", mutex); + DEBUGASSERT(mutex != NULL); + + if (mutex != NULL) + { + /* Make sure the mutex is stable while we make the following checks. */ + + sched_lock(); + + /* Is the mutex available? */ + + DEBUGASSERT(mutex->pid != 0); /* < 0: available, >0 owned, ==0 error */ + if (mutex->pid >= 0) + { + /* No.. Verify that the PID still exists. We may be destroying + * the mutex after cancelling a pthread and the mutex may have + * been in a bad state owned by the dead pthread. NOTE: The + * folling is unspecified behavior (see pthread_mutex_consistent()). + * + * If the holding thread is still valid, then we should be able to + * map its PID to the underlying TCB. That is what sched_gettcb() + * does. + */ + + if (sched_gettcb(mutex->pid) == NULL) + { + /* The thread associated with the PID no longer exists */ + + mutex->pid = -1; + + /* Reset the semaphore. This has the same affect as if the + * dead task had called pthread_mutex_unlock(). + */ + + status = sem_reset((FAR sem_t *)&mutex->sem, 1); + ret = (status != OK) ? get_errno() : OK; + } + } + + sched_unlock(); + ret = OK; + } + + sinfo("Returning %d\n", ret); + return ret; +} diff --git a/sched/pthread/pthread_mutexdestroy.c b/sched/pthread/pthread_mutexdestroy.c index 8bab62c474..23905fd407 100644 --- a/sched/pthread/pthread_mutexdestroy.c +++ b/sched/pthread/pthread_mutexdestroy.c @@ -1,7 +1,7 @@ /**************************************************************************** * sched/pthread/pthread_mutexdestroy.c * - * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -46,6 +46,8 @@ #include #include +#include + #include "pthread/pthread.h" /**************************************************************************** @@ -70,60 +72,86 @@ int pthread_mutex_destroy(FAR pthread_mutex_t *mutex) { - int ret = OK; + int ret = EINVAL; int status; sinfo("mutex=0x%p\n", mutex); + DEBUGASSERT(mutex != NULL); - if (mutex == NULL) - { - ret = EINVAL; - } - else + if (mutex != NULL) { - /* Make sure the semaphore is stable while we make the following - * checks - */ + /* Make sure the semaphore is stable while we make the following checks */ sched_lock(); - /* Is the semaphore available? */ + /* Is the mutex available? */ - if (mutex->pid != -1) + if (mutex->pid >= 0) { -#ifndef CONFIG_DISABLE_SIGNALS - /* Verify that the PID still exists. We may be destroying the - * mutex after cancelling a pthread and the mutex may have been - * in a bad state owned by the dead pthread. + DEBUGASSERT(mutex->pid != 0); /* < 0: available, >0 owned, ==0 error */ + + /* No.. Verify that the PID still exists. We may be destroying + * the mutex after cancelling a pthread and the mutex may have + * been in a bad state owned by the dead pthread. NOTE: The + * following behavior is unspecified for pthread_mutex_destroy() + * (see pthread_mutex_consistent()). + * + * If the holding thread is still valid, then we should be able to + * map its PID to the underlying TCB. That is what sched_gettcb() + * does. */ - ret = kill(mutex->pid, 0); - if (ret < 0) - { - /* The thread associated with the PID no longer exists */ + if (sched_gettcb(mutex->pid) == NULL) + { + /* The thread associated with the PID no longer exists */ + + mutex->pid = -1; + + /* Reset the semaphore. If threads are were on this + * semaphore, then this will awakened them and make + * destruction of the semaphore impossible here. + */ + + status = sem_reset((FAR sem_t *)&mutex->sem, 1); + if (status < 0) + { + ret = -status; + } - mutex->pid = -1; + /* Check if the reset caused some other thread to lock the + * mutex. + */ - /* Destroy the semaphore */ + else if (mutex->pid != -1) + { + /* Yes.. then we cannot destroy the mutex now. */ - status = sem_destroy((FAR sem_t *)&mutex->sem); - ret = (status != OK) ? get_errno() : OK; + ret = EBUSY; + } + + /* Destroy the underlying semaphore */ + + else + { + status = sem_destroy((FAR sem_t *)&mutex->sem); + ret = (status != OK) ? get_errno() : OK; + } + } + else + { + ret = EBUSY; } - else -#endif - { - ret = EBUSY; - } } else { - /* Destroy the semaphore */ + /* Destroy the semaphore + * + * REVISIT: What if there are threads waiting on the semaphore? + * Perhaps this logic should all sem_reset() first? + */ status = sem_destroy((FAR sem_t *)&mutex->sem); - if (status != OK) - { - ret = get_errno(); - } + ret = ((status != OK) ? get_errno() : OK); } sched_unlock(); diff --git a/sched/pthread/pthread_mutexlock.c b/sched/pthread/pthread_mutexlock.c index d5c8af2db2..e14a7de17e 100644 --- a/sched/pthread/pthread_mutexlock.c +++ b/sched/pthread/pthread_mutexlock.c @@ -1,7 +1,7 @@ /**************************************************************************** * sched/pthread/pthread_mutexlock.c * - * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -42,9 +42,12 @@ #include #include #include +#include #include #include +#include + #include "pthread/pthread.h" /**************************************************************************** @@ -104,15 +107,12 @@ int pthread_mutex_lock(FAR pthread_mutex_t *mutex) { int mypid = (int)getpid(); - int ret = OK; + int ret = EINVAL; sinfo("mutex=0x%p\n", mutex); + DEBUGASSERT(mutex != NULL); - if (!mutex) - { - ret = EINVAL; - } - else + if (mutex != NULL) { /* Make sure the semaphore is stable while we make the following * checks. This all needs to be one atomic action. @@ -120,7 +120,7 @@ int pthread_mutex_lock(FAR pthread_mutex_t *mutex) sched_lock(); - /* Does this task already hold the semaphore? */ + /* Does this thread already hold the semaphore? */ if (mutex->pid == mypid) { @@ -129,9 +129,12 @@ int pthread_mutex_lock(FAR pthread_mutex_t *mutex) #ifdef CONFIG_MUTEX_TYPES if (mutex->type == PTHREAD_MUTEX_RECURSIVE) { - /* Yes... just increment the number of locks held and return success */ + /* Yes... just increment the number of locks held and return + * success. + */ mutex->nlocks++; + ret = OK; } else #endif @@ -139,19 +142,39 @@ int pthread_mutex_lock(FAR pthread_mutex_t *mutex) /* No, then we would deadlock... return an error (default * behavior is like PTHREAD_MUTEX_ERRORCHECK) * - * NOTE: This is non-compliant behavior for the case of a - * NORMAL mutex. In that case, it the deadlock condition should - * not be detected and the thread should be permitted to - * deadlock. + * NOTE: This is the correct behavior for a 'robust', NORMAL + * mutex. Compiant behavior for non-robust mutex should not + * include these checks. In that case, it the deadlock + * condition should not be detected and the thread should be + * permitted to deadlock. */ serr("ERROR: Returning EDEADLK\n"); ret = EDEADLK; } } + + /* The calling thread does not hold the semaphore. The correct + * behavior for the 'robust' mutex is to verify that the holder of the + * mutex is still valid. This is protection from the case + * where the holder of the mutex has exitted without unlocking it. + */ + + else if (mutex->pid > 0 && sched_gettcb(mutex->pid) == NULL) + { + DEBUGASSERT(mutex->pid != 0); /* < 0: available, >0 owned, ==0 error */ + + /* A thread holds the mutex, but there is no such thread. POSIX + * requires that the 'robust' mutex return EOWNERDEAD in this case. + * It is then the caller's responsibility to call pthread_mutx_consistent() + * fo fix the mutex. + */ + + ret = EOWNERDEAD; + } else { - /* Take the semaphore */ + /* Take the underlying semaphore, waiting if necessary */ ret = pthread_takesemaphore((FAR sem_t *)&mutex->sem); @@ -159,7 +182,7 @@ int pthread_mutex_lock(FAR pthread_mutex_t *mutex) * that we own it. */ - if (!ret) + if (ret == OK) { mutex->pid = mypid; #ifdef CONFIG_MUTEX_TYPES diff --git a/sched/pthread/pthread_mutextrylock.c b/sched/pthread/pthread_mutextrylock.c index 825cb992a1..a71e845f77 100644 --- a/sched/pthread/pthread_mutextrylock.c +++ b/sched/pthread/pthread_mutextrylock.c @@ -1,7 +1,7 @@ /**************************************************************************** * sched/pthread/pthread_mutextrylock.c * - * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -43,6 +43,7 @@ #include #include #include +#include #include #include @@ -83,15 +84,13 @@ int pthread_mutex_trylock(FAR pthread_mutex_t *mutex) { - int ret = OK; + int status; + int ret = EINVAL; sinfo("mutex=0x%p\n", mutex); + DEBUGASSERT(mutex != NULL); - if (!mutex) - { - ret = EINVAL; - } - else + if (mutex != NULL) { int mypid = (int)getpid(); @@ -103,7 +102,8 @@ int pthread_mutex_trylock(FAR pthread_mutex_t *mutex) /* Try to get the semaphore. */ - if (sem_trywait((FAR sem_t *)&mutex->sem) == OK) + status = sem_trywait((FAR sem_t *)&mutex->sem); + if (status == OK) { /* If we successfully obtained the semaphore, then indicate * that we own it. @@ -117,33 +117,63 @@ int pthread_mutex_trylock(FAR pthread_mutex_t *mutex) mutex->nlocks = 1; } #endif + ret = OK; } - /* Was it not available? */ + /* sem_trywait failed */ - else if (get_errno() == EAGAIN) + else { -#ifdef CONFIG_MUTEX_TYPES + /* Did it fail because the semaphore was not avaialabl? */ - /* Check if recursive mutex was locked by ourself. */ - - if (mutex->type == PTHREAD_MUTEX_RECURSIVE && mutex->pid == mypid) + int errcode = get_errno(); + if (errcode == EAGAIN) { - /* Increment the number of locks held and return successfully. */ +#ifdef CONFIG_MUTEX_TYPES + /* Check if recursive mutex was locked by the calling thread. */ + + if (mutex->type == PTHREAD_MUTEX_RECURSIVE && mutex->pid == mypid) + { + /* Increment the number of locks held and return successfully. */ - mutex->nlocks++; + mutex->nlocks++; + ret = OK; + } + else +#endif + /* The calling thread does not hold the semaphore. The correct + * behavior for the 'robust' mutex is to verify that the holder of + * the mutex is still valid. This is protection from the case + * where the holder of the mutex has exitted without unlocking it. + */ + + if (mutex->pid > 0 && sched_gettcb(mutex->pid) == NULL) + { + DEBUGASSERT(mutex->pid != 0); /* < 0: available, >0 owned, ==0 error */ + + /* A thread holds the mutex, but there is no such thread. + * POSIX requires that the 'robust' mutex return EOWNERDEAD + * in this case. It is then the caller's responsibility to + * call pthread_mutx_consistent() fo fix the mutex. + */ + + ret = EOWNERDEAD; + } + + /* The mutex is locked by another, active thread */ + + else + { + ret = EBUSY; + } } + + /* Some other, unhandled error occurred */ + else { - ret = EBUSY; + ret = errcode; } -#else - ret = EBUSY; -#endif - } - else - { - ret = EINVAL; } sched_unlock(); diff --git a/sched/pthread/pthread_mutexunlock.c b/sched/pthread/pthread_mutexunlock.c index 56c14bb036..9493d96e6c 100644 --- a/sched/pthread/pthread_mutexunlock.c +++ b/sched/pthread/pthread_mutexunlock.c @@ -1,7 +1,7 @@ /**************************************************************************** * sched/pthread/pthread_mutexunlock.c * - * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -80,15 +80,12 @@ int pthread_mutex_unlock(FAR pthread_mutex_t *mutex) { - int ret = OK; + int ret = EINVAL; sinfo("mutex=0x%p\n", mutex); + DEBUGASSERT(mutex != NULL); - if (!mutex) - { - ret = EINVAL; - } - else + if (mutex != NULL) { /* Make sure the semaphore is stable while we make the following * checks. This all needs to be one atomic action. @@ -108,8 +105,7 @@ int pthread_mutex_unlock(FAR pthread_mutex_t *mutex) * the mutex." * * For the case of the non-robust PTHREAD_MUTEX_NORMAL mutex, - * the behavior is undefined. Here we treat that type as though - * it were PTHREAD_MUTEX_ERRORCHECK type and just return an error. + * the behavior is undefined. */ serr("ERROR: Holder=%d returning EPERM\n", mutex->pid); @@ -127,6 +123,7 @@ int pthread_mutex_unlock(FAR pthread_mutex_t *mutex) */ mutex->nlocks--; + ret = OK; } #endif -- GitLab From 2c37d369abae9a963a9ee2e3b3f673c5956a8da1 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 26 Mar 2017 11:22:17 -0600 Subject: [PATCH 212/990] pthread: Fix return value of pthread_give/takesemaphore(). Add option to pthread_takesemaphore to ignore EINTR or not. --- sched/pthread/pthread.h | 2 +- sched/pthread/pthread_completejoin.c | 4 +-- sched/pthread/pthread_condtimedwait.c | 16 +++++------ sched/pthread/pthread_condwait.c | 21 +++++++++++++-- sched/pthread/pthread_create.c | 4 +-- sched/pthread/pthread_detach.c | 2 +- sched/pthread/pthread_initialize.c | 39 ++++++++++++++------------- sched/pthread/pthread_join.c | 6 ++--- sched/pthread/pthread_mutexlock.c | 10 ++++++- 9 files changed, 64 insertions(+), 40 deletions(-) diff --git a/sched/pthread/pthread.h b/sched/pthread/pthread.h index be7a20de2e..858e80ed07 100644 --- a/sched/pthread/pthread.h +++ b/sched/pthread/pthread.h @@ -108,7 +108,7 @@ FAR struct join_s *pthread_findjoininfo(FAR struct task_group_s *group, pid_t pid); void pthread_release(FAR struct task_group_s *group); int pthread_givesemaphore(sem_t *sem); -int pthread_takesemaphore(sem_t *sem); +int pthread_takesemaphore(sem_t *sem, bool intr); #ifdef CONFIG_MUTEX_TYPES int pthread_mutexattr_verifytype(int type); diff --git a/sched/pthread/pthread_completejoin.c b/sched/pthread/pthread_completejoin.c index b516c9defd..6053f6c1da 100644 --- a/sched/pthread/pthread_completejoin.c +++ b/sched/pthread/pthread_completejoin.c @@ -99,7 +99,7 @@ static bool pthread_notifywaiters(FAR struct join_s *pjoin) * value. */ - (void)pthread_takesemaphore(&pjoin->data_sem); + (void)pthread_takesemaphore(&pjoin->data_sem, false); return true; } @@ -210,7 +210,7 @@ int pthread_completejoin(pid_t pid, FAR void *exit_value) /* First, find thread's structure in the private data set. */ - (void)pthread_takesemaphore(&group->tg_joinsem); + (void)pthread_takesemaphore(&group->tg_joinsem, false); pjoin = pthread_findjoininfo(group, pid); if (!pjoin) { diff --git a/sched/pthread/pthread_condtimedwait.c b/sched/pthread/pthread_condtimedwait.c index 9027c305ef..960f46483c 100644 --- a/sched/pthread/pthread_condtimedwait.c +++ b/sched/pthread/pthread_condtimedwait.c @@ -156,12 +156,10 @@ static void pthread_condtimedout(int argc, uint32_t pid, uint32_t signo) * abstime - wait until this absolute time * * Return Value: - * OK (0) on success; ERROR (-1) on failure with errno - * set appropriately. + * OK (0) on success; A non-zero errno value is returned on failure. * * Assumptions: - * Timing is of resolution 1 msec, with +/-1 millisecond - * accuracy. + * Timing is of resolution 1 msec, with +/-1 millisecond accuracy. * ****************************************************************************/ @@ -236,7 +234,7 @@ int pthread_cond_timedwait(FAR pthread_cond_t *cond, FAR pthread_mutex_t *mutex, if (ret) { /* Restore interrupts (pre-emption will be enabled when - * we fall through the if/then/else + * we fall through the if/then/else) */ leave_critical_section(flags); @@ -263,7 +261,7 @@ int pthread_cond_timedwait(FAR pthread_cond_t *cond, FAR pthread_mutex_t *mutex, mutex->pid = -1; ret = pthread_givesemaphore((FAR sem_t *)&mutex->sem); - if (ret) + if (ret != 0) { /* Restore interrupts (pre-emption will be enabled when * we fall through the if/then/else) @@ -318,12 +316,12 @@ int pthread_cond_timedwait(FAR pthread_cond_t *cond, FAR pthread_mutex_t *mutex, /* Reacquire the mutex (retaining the ret). */ sinfo("Re-locking...\n"); - status = pthread_takesemaphore((FAR sem_t *)&mutex->sem); - if (!status) + status = pthread_takesemaphore((FAR sem_t *)&mutex->sem, false); + if (status == OK) { mutex->pid = mypid; } - else if (!ret) + else if (ret == 0) { ret = status; } diff --git a/sched/pthread/pthread_condwait.c b/sched/pthread/pthread_condwait.c index e7c6a9af25..a434f3032c 100644 --- a/sched/pthread/pthread_condwait.c +++ b/sched/pthread/pthread_condwait.c @@ -71,6 +71,7 @@ int pthread_cond_wait(FAR pthread_cond_t *cond, FAR pthread_mutex_t *mutex) { + int status; int ret; sinfo("cond=0x%p mutex=0x%p\n", cond, mutex); @@ -104,7 +105,14 @@ int pthread_cond_wait(FAR pthread_cond_t *cond, FAR pthread_mutex_t *mutex) /* Take the semaphore */ - ret |= pthread_takesemaphore((FAR sem_t *)&cond->sem); + status = pthread_takesemaphore((FAR sem_t *)&cond->sem, false); + if (ret == OK) + { + /* Report the first failure that occurs */ + + ret = status; + } + sched_unlock(); /* Reacquire the mutex. @@ -114,7 +122,16 @@ int pthread_cond_wait(FAR pthread_cond_t *cond, FAR pthread_mutex_t *mutex) */ sinfo("Reacquire mutex...\n"); - ret |= pthread_takesemaphore((FAR sem_t *)&mutex->sem); + status = pthread_takesemaphore((FAR sem_t *)&mutex->sem, false); + if (ret == OK) + { + /* Report the first failure that occurs */ + + ret = status; + } + + /* Was all of the above successful? */ + if (ret == OK) { mutex->pid = getpid(); diff --git a/sched/pthread/pthread_create.c b/sched/pthread/pthread_create.c index 957936cd82..4fbf646424 100644 --- a/sched/pthread/pthread_create.c +++ b/sched/pthread/pthread_create.c @@ -177,7 +177,7 @@ static void pthread_start(void) /* Sucessfully spawned, add the pjoin to our data set. */ - (void)pthread_takesemaphore(&group->tg_joinsem); + (void)pthread_takesemaphore(&group->tg_joinsem, false); pthread_addjoininfo(group, pjoin); (void)pthread_givesemaphore(&group->tg_joinsem); @@ -555,7 +555,7 @@ int pthread_create(FAR pthread_t *thread, FAR const pthread_attr_t *attr, * its join structure. */ - (void)pthread_takesemaphore(&pjoin->data_sem); + (void)pthread_takesemaphore(&pjoin->data_sem, false); /* Return the thread information to the caller */ diff --git a/sched/pthread/pthread_detach.c b/sched/pthread/pthread_detach.c index 0d165e2d23..9e3d900d7e 100644 --- a/sched/pthread/pthread_detach.c +++ b/sched/pthread/pthread_detach.c @@ -87,7 +87,7 @@ int pthread_detach(pthread_t thread) /* Find the entry associated with this pthread. */ - (void)pthread_takesemaphore(&group->tg_joinsem); + (void)pthread_takesemaphore(&group->tg_joinsem, false); pjoin = pthread_findjoininfo(group, (pid_t)thread); if (!pjoin) { diff --git a/sched/pthread/pthread_initialize.c b/sched/pthread/pthread_initialize.c index 0ced8d6181..e5965d8b60 100644 --- a/sched/pthread/pthread_initialize.c +++ b/sched/pthread/pthread_initialize.c @@ -40,7 +40,9 @@ #include #include +#include #include +#include #include #include "pthread/pthread.h" @@ -63,8 +65,6 @@ * Return Value: * None * - * Assumptions: - * ****************************************************************************/ void pthread_initialize(void) @@ -78,44 +78,45 @@ void pthread_initialize(void) * Support managed access to the private data sets. * * Parameters: - * None + * sem - The semaphore to lock or unlock + * intr - false: ignore EINTR errors when locking; true tread EINTR as + * other errors by returning the errno value * * Return Value: - * 0 on success or an ERROR on failure with errno value set to EINVAL. - * Note that the errno EINTR is never returned by this function. - * - * Assumptions: + * 0 on success or an errno value on failure. * ****************************************************************************/ -int pthread_takesemaphore(sem_t *sem) +int pthread_takesemaphore(sem_t *sem, bool intr) { /* Verify input parameters */ - if (sem) + DEBUGASSERT(sem != NULL); + if (sem != NULL) { /* Take the semaphore */ while (sem_wait(sem) != OK) { + int errcode = get_errno(); + /* Handle the special case where the semaphore wait was * awakened by the receipt of a signal. */ - if (get_errno() != EINTR) + if (intr || errcode != EINTR) { - set_errno(EINVAL); - return ERROR; + return errcode; } } + return OK; } else { /* NULL semaphore pointer! */ - set_errno(EINVAL); - return ERROR; + return EINVAL; } } @@ -123,7 +124,9 @@ int pthread_givesemaphore(sem_t *sem) { /* Verify input parameters */ - if (sem) + + DEBUGASSERT(sem != NULL); + if (sem != NULL) { /* Give the semaphore */ @@ -135,16 +138,14 @@ int pthread_givesemaphore(sem_t *sem) { /* sem_post() reported an error */ - set_errno(EINVAL); - return ERROR; + return get_errno(); } } else { /* NULL semaphore pointer! */ - set_errno(EINVAL); - return ERROR; + return EINVAL; } } diff --git a/sched/pthread/pthread_join.c b/sched/pthread/pthread_join.c index 01c1c713ea..6d2b48c81a 100644 --- a/sched/pthread/pthread_join.c +++ b/sched/pthread/pthread_join.c @@ -114,7 +114,7 @@ int pthread_join(pthread_t thread, FAR pthread_addr_t *pexit_value) * because it will also attempt to get this semaphore. */ - (void)pthread_takesemaphore(&group->tg_joinsem); + (void)pthread_takesemaphore(&group->tg_joinsem, false); /* Find the join information associated with this thread. * This can fail for one of three reasons: (1) There is no @@ -197,7 +197,7 @@ int pthread_join(pthread_t thread, FAR pthread_addr_t *pexit_value) * pthread to exit. */ - (void)pthread_takesemaphore(&pjoin->exit_sem); + (void)pthread_takesemaphore(&pjoin->exit_sem, false); /* The thread has exited! Get the thread exit value */ @@ -217,7 +217,7 @@ int pthread_join(pthread_t thread, FAR pthread_addr_t *pexit_value) * pthread_destroyjoin is called. */ - (void)pthread_takesemaphore(&group->tg_joinsem); + (void)pthread_takesemaphore(&group->tg_joinsem, false); } /* Pre-emption is okay now. The logic still cannot be re-entered diff --git a/sched/pthread/pthread_mutexlock.c b/sched/pthread/pthread_mutexlock.c index e14a7de17e..657bede370 100644 --- a/sched/pthread/pthread_mutexlock.c +++ b/sched/pthread/pthread_mutexlock.c @@ -176,7 +176,7 @@ int pthread_mutex_lock(FAR pthread_mutex_t *mutex) { /* Take the underlying semaphore, waiting if necessary */ - ret = pthread_takesemaphore((FAR sem_t *)&mutex->sem); + ret = pthread_takesemaphore((FAR sem_t *)&mutex->sem, true); /* If we successfully obtained the semaphore, then indicate * that we own it. @@ -189,6 +189,14 @@ int pthread_mutex_lock(FAR pthread_mutex_t *mutex) mutex->nlocks = 1; #endif } + + /* Check if we were awakened by a signal. This might happen if the + * tasking holding the mutex just exitted. + */ + + else if (ret == EINTR) + { + } } sched_unlock(); -- GitLab From 6e623ce06fab83d87879818dcaa3ec9c044117f8 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 26 Mar 2017 12:46:57 -0600 Subject: [PATCH 213/990] pthreads: Partial implementation of final part of robust mutexes: Keep list of all mutexes held by a thread in a list in the TCB. --- include/nuttx/sched.h | 4 ++++ include/pthread.h | 20 +++++++++++++++++--- sched/pthread/Make.defs | 2 +- sched/pthread/pthread.h | 4 +++- sched/pthread/pthread_condtimedwait.c | 4 ++-- sched/pthread/pthread_condwait.c | 4 ++-- sched/pthread/pthread_mutexlock.c | 21 ++++++++++----------- sched/pthread/pthread_mutextrylock.c | 11 +++++++++-- sched/pthread/pthread_mutexunlock.c | 2 +- 9 files changed, 49 insertions(+), 23 deletions(-) diff --git a/include/nuttx/sched.h b/include/nuttx/sched.h index 687d19dcf9..f618ac94ce 100644 --- a/include/nuttx/sched.h +++ b/include/nuttx/sched.h @@ -697,6 +697,10 @@ struct pthread_tcb_s pthread_addr_t arg; /* Startup argument */ FAR void *joininfo; /* Detach-able info to support join */ + /* Robust mutex support *******************************************************/ + + FAR struct pthread_mutex_s *mhead; /* List of mutexes held by thread */ + /* Clean-up stack *************************************************************/ #ifdef CONFIG_PTHREAD_CLEANUP diff --git a/include/pthread.h b/include/pthread.h index 6fed93a837..8f3c7bf37f 100644 --- a/include/pthread.h +++ b/include/pthread.h @@ -143,6 +143,13 @@ #define PTHREAD_PRIO_INHERIT SEM_PRIO_INHERIT #define PTHREAD_PRIO_PROTECT SEM_PRIO_PROTECT +/* Values for struct pthread_mutex_s flags. These are non-standard and + * intended only for internal use within the OS. + */ + +#define _PTHREAD_MFLAGS_INCONSISTENT (1 << 0) /* Mutex is in an inconsistent state */ +#define _PTHREAD_MFLAGS_NOTRECOVRABLE (1 << 1) /* Inconsistent mutex has been unlocked */ + /* Definitions to map some non-standard, BSD thread management interfaces to * the non-standard Linux-like prctl() interface. Since these are simple * mappings to prctl, they will return 0 on success and -1 on failure with the @@ -221,7 +228,7 @@ struct pthread_mutexattr_s { uint8_t pshared; /* PTHREAD_PROCESS_PRIVATE or PTHREAD_PROCESS_SHARED */ #ifdef CONFIG_PRIORITY_INHERITANCE - uint8_t proto; /* See PTHREAD_PRIO_* definitions */ + uint8_t proto; /* See _PTHREAD_PRIO_* definitions */ #endif #ifdef CONFIG_MUTEX_TYPES uint8_t type; /* Type of the mutex. See PTHREAD_MUTEX_* definitions */ @@ -233,11 +240,18 @@ typedef struct pthread_mutexattr_s pthread_mutexattr_t; struct pthread_mutex_s { - int pid; /* ID of the holder of the mutex */ + /* Supports a singly linked list */ + + FAR struct pthread_mutex_s *flink; + + /* Payload */ + sem_t sem; /* Semaphore underlying the implementation of the mutex */ + pid_t pid; /* ID of the holder of the mutex */ + uint8_t flags; /* See PTHREAD_MFLAGS_* */ #ifdef CONFIG_MUTEX_TYPES uint8_t type; /* Type of the mutex. See PTHREAD_MUTEX_* definitions */ - int nlocks; /* The number of recursive locks held */ + int16_t nlocks; /* The number of recursive locks held */ #endif }; diff --git a/sched/pthread/Make.defs b/sched/pthread/Make.defs index 5a602d3e1f..9f2c8c6479 100644 --- a/sched/pthread/Make.defs +++ b/sched/pthread/Make.defs @@ -37,7 +37,7 @@ ifneq ($(CONFIG_DISABLE_PTHREAD),y) CSRCS += pthread_create.c pthread_exit.c pthread_join.c pthread_detach.c CSRCS += pthread_yield.c pthread_getschedparam.c pthread_setschedparam.c -CSRCS += pthread_mutexinit.c pthread_mutexdestroy.c +CSRCS += pthread_mutexinit.c pthread_mutexdestroy.c pthread_mutex.c CSRCS += pthread_mutexlock.c pthread_mutextrylock.c pthread_mutexunlock.c CSRCS += pthread_mutexconsistent.c CSRCS += pthread_condinit.c pthread_conddestroy.c diff --git a/sched/pthread/pthread.h b/sched/pthread/pthread.h index 858e80ed07..79492d930d 100644 --- a/sched/pthread/pthread.h +++ b/sched/pthread/pthread.h @@ -107,8 +107,10 @@ void pthread_destroyjoin(FAR struct task_group_s *group, FAR struct join_s *pthread_findjoininfo(FAR struct task_group_s *group, pid_t pid); void pthread_release(FAR struct task_group_s *group); -int pthread_givesemaphore(sem_t *sem); int pthread_takesemaphore(sem_t *sem, bool intr); +int pthread_givesemaphore(sem_t *sem); +int pthread_takemutex(FAR struct pthread_mutex_s *mutex, bool intr); +int pthread_givemutex(FAR struct pthread_mutex_s *mutex); #ifdef CONFIG_MUTEX_TYPES int pthread_mutexattr_verifytype(int type); diff --git a/sched/pthread/pthread_condtimedwait.c b/sched/pthread/pthread_condtimedwait.c index 960f46483c..b03fc3a73f 100644 --- a/sched/pthread/pthread_condtimedwait.c +++ b/sched/pthread/pthread_condtimedwait.c @@ -260,7 +260,7 @@ int pthread_cond_timedwait(FAR pthread_cond_t *cond, FAR pthread_mutex_t *mutex, /* Give up the mutex */ mutex->pid = -1; - ret = pthread_givesemaphore((FAR sem_t *)&mutex->sem); + ret = pthread_givemutex(mutex); if (ret != 0) { /* Restore interrupts (pre-emption will be enabled when @@ -316,7 +316,7 @@ int pthread_cond_timedwait(FAR pthread_cond_t *cond, FAR pthread_mutex_t *mutex, /* Reacquire the mutex (retaining the ret). */ sinfo("Re-locking...\n"); - status = pthread_takesemaphore((FAR sem_t *)&mutex->sem, false); + status = pthread_takemutex(mutex, false); if (status == OK) { mutex->pid = mypid; diff --git a/sched/pthread/pthread_condwait.c b/sched/pthread/pthread_condwait.c index a434f3032c..88f39485aa 100644 --- a/sched/pthread/pthread_condwait.c +++ b/sched/pthread/pthread_condwait.c @@ -101,7 +101,7 @@ int pthread_cond_wait(FAR pthread_cond_t *cond, FAR pthread_mutex_t *mutex) sched_lock(); mutex->pid = -1; - ret = pthread_givesemaphore((FAR sem_t *)&mutex->sem); + ret = pthread_givemutex(mutex); /* Take the semaphore */ @@ -122,7 +122,7 @@ int pthread_cond_wait(FAR pthread_cond_t *cond, FAR pthread_mutex_t *mutex) */ sinfo("Reacquire mutex...\n"); - status = pthread_takesemaphore((FAR sem_t *)&mutex->sem, false); + status = pthread_takemutex(mutex, false); if (ret == OK) { /* Report the first failure that occurs */ diff --git a/sched/pthread/pthread_mutexlock.c b/sched/pthread/pthread_mutexlock.c index 657bede370..251f071b47 100644 --- a/sched/pthread/pthread_mutexlock.c +++ b/sched/pthread/pthread_mutexlock.c @@ -133,8 +133,15 @@ int pthread_mutex_lock(FAR pthread_mutex_t *mutex) * success. */ - mutex->nlocks++; - ret = OK; + if (mutex->nlocks < INT16_MAX) + { + mutex->nlocks++; + ret = OK; + } + else + { + ret = EOVERFLOW; + } } else #endif @@ -176,7 +183,7 @@ int pthread_mutex_lock(FAR pthread_mutex_t *mutex) { /* Take the underlying semaphore, waiting if necessary */ - ret = pthread_takesemaphore((FAR sem_t *)&mutex->sem, true); + ret = pthread_takemutex(mutex, true); /* If we successfully obtained the semaphore, then indicate * that we own it. @@ -189,14 +196,6 @@ int pthread_mutex_lock(FAR pthread_mutex_t *mutex) mutex->nlocks = 1; #endif } - - /* Check if we were awakened by a signal. This might happen if the - * tasking holding the mutex just exitted. - */ - - else if (ret == EINTR) - { - } } sched_unlock(); diff --git a/sched/pthread/pthread_mutextrylock.c b/sched/pthread/pthread_mutextrylock.c index a71e845f77..630de9e5fd 100644 --- a/sched/pthread/pthread_mutextrylock.c +++ b/sched/pthread/pthread_mutextrylock.c @@ -136,8 +136,15 @@ int pthread_mutex_trylock(FAR pthread_mutex_t *mutex) { /* Increment the number of locks held and return successfully. */ - mutex->nlocks++; - ret = OK; + if (mutex->nlocks < INT16_MAX) + { + mutex->nlocks++; + ret = OK; + } + else + { + ret = EOVERFLOW; + } } else #endif diff --git a/sched/pthread/pthread_mutexunlock.c b/sched/pthread/pthread_mutexunlock.c index 9493d96e6c..05f461605f 100644 --- a/sched/pthread/pthread_mutexunlock.c +++ b/sched/pthread/pthread_mutexunlock.c @@ -139,7 +139,7 @@ int pthread_mutex_unlock(FAR pthread_mutex_t *mutex) #ifdef CONFIG_MUTEX_TYPES mutex->nlocks = 0; #endif - ret = pthread_givesemaphore((FAR sem_t *)&mutex->sem); + ret = pthread_givemutex(mutex); } sched_unlock(); -- GitLab From fe03ef02c42a14741a6f5ad0ac2b3126245b2702 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 26 Mar 2017 13:37:05 -0600 Subject: [PATCH 214/990] when pthread exits or is cancelled, mutexes held by thread are marked inconsistent and the highest priority thread waiting for the mutex is awakened. --- sched/pthread/Make.defs | 2 +- sched/pthread/pthread.h | 1 + sched/pthread/pthread_cancel.c | 4 ++++ sched/pthread/pthread_exit.c | 4 ++++ sched/pthread/pthread_mutexinit.c | 6 +++++- 5 files changed, 15 insertions(+), 2 deletions(-) diff --git a/sched/pthread/Make.defs b/sched/pthread/Make.defs index 9f2c8c6479..a39a35d208 100644 --- a/sched/pthread/Make.defs +++ b/sched/pthread/Make.defs @@ -39,7 +39,7 @@ CSRCS += pthread_create.c pthread_exit.c pthread_join.c pthread_detach.c CSRCS += pthread_yield.c pthread_getschedparam.c pthread_setschedparam.c CSRCS += pthread_mutexinit.c pthread_mutexdestroy.c pthread_mutex.c CSRCS += pthread_mutexlock.c pthread_mutextrylock.c pthread_mutexunlock.c -CSRCS += pthread_mutexconsistent.c +CSRCS += pthread_mutexconsistent.c pthread_mutexinconsistent.c CSRCS += pthread_condinit.c pthread_conddestroy.c CSRCS += pthread_condwait.c pthread_condsignal.c pthread_condbroadcast.c CSRCS += pthread_barrierinit.c pthread_barrierdestroy.c pthread_barrierwait.c diff --git a/sched/pthread/pthread.h b/sched/pthread/pthread.h index 79492d930d..bf97c0c018 100644 --- a/sched/pthread/pthread.h +++ b/sched/pthread/pthread.h @@ -111,6 +111,7 @@ int pthread_takesemaphore(sem_t *sem, bool intr); int pthread_givesemaphore(sem_t *sem); int pthread_takemutex(FAR struct pthread_mutex_s *mutex, bool intr); int pthread_givemutex(FAR struct pthread_mutex_s *mutex); +void pthread_mutex_inconsistent(FAR struct pthread_tcb_s *tcb); #ifdef CONFIG_MUTEX_TYPES int pthread_mutexattr_verifytype(int type); diff --git a/sched/pthread/pthread_cancel.c b/sched/pthread/pthread_cancel.c index a9b7e8270b..3a520b1f93 100644 --- a/sched/pthread/pthread_cancel.c +++ b/sched/pthread/pthread_cancel.c @@ -162,6 +162,10 @@ int pthread_cancel(pthread_t thread) (void)pthread_completejoin((pid_t)thread, PTHREAD_CANCELED); + /* Recover any mutexes still held by the canceled thread */ + + pthread_mutex_inconsistent(tcb); + /* Then let task_terminate do the real work */ return task_terminate((pid_t)thread, false); diff --git a/sched/pthread/pthread_exit.c b/sched/pthread/pthread_exit.c index 40a5b7fb0d..4654d86371 100644 --- a/sched/pthread/pthread_exit.c +++ b/sched/pthread/pthread_exit.c @@ -123,6 +123,10 @@ void pthread_exit(FAR void *exit_value) exit(EXIT_FAILURE); } + /* Recover any mutexes still held by the canceled thread */ + + pthread_mutex_inconsistent(tcb); + /* Perform common task termination logic. This will get called again later * through logic kicked off by _exit(). However, we need to call it before * calling _exit() in order certain operations if this is the last thread diff --git a/sched/pthread/pthread_mutexinit.c b/sched/pthread/pthread_mutexinit.c index fe9620da0b..b521137683 100644 --- a/sched/pthread/pthread_mutexinit.c +++ b/sched/pthread/pthread_mutexinit.c @@ -1,7 +1,7 @@ /**************************************************************************** * sched/pthread/pthread_mutexinit.c * - * Copyright (C) 2007-2009, 2011, 2016 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009, 2011, 2016-2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -123,6 +123,10 @@ int pthread_mutex_init(FAR pthread_mutex_t *mutex, ret = get_errno(); } #endif + /* Initial internal fields of the mutex */ + + mutex->flink = NULL; + mutex->flags = 0; /* Set up attributes unique to the mutex type */ -- GitLab From 5a69453e167ca831f3304706aba9472be8e787b7 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 26 Mar 2017 13:54:43 -0600 Subject: [PATCH 215/990] pthreads: Add some assertions. --- sched/pthread/pthread_mutexlock.c | 4 +++- sched/pthread/pthread_mutextrylock.c | 4 +++- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/sched/pthread/pthread_mutexlock.c b/sched/pthread/pthread_mutexlock.c index 251f071b47..c39a384bed 100644 --- a/sched/pthread/pthread_mutexlock.c +++ b/sched/pthread/pthread_mutexlock.c @@ -170,6 +170,7 @@ int pthread_mutex_lock(FAR pthread_mutex_t *mutex) else if (mutex->pid > 0 && sched_gettcb(mutex->pid) == NULL) { DEBUGASSERT(mutex->pid != 0); /* < 0: available, >0 owned, ==0 error */ + DEBUGASSERT((mutex->flags & _PTHREAD_MFLAGS_INCONSISTENT) != 0); /* A thread holds the mutex, but there is no such thread. POSIX * requires that the 'robust' mutex return EOWNERDEAD in this case. @@ -177,7 +178,8 @@ int pthread_mutex_lock(FAR pthread_mutex_t *mutex) * fo fix the mutex. */ - ret = EOWNERDEAD; + mutex->flags |= _PTHREAD_MFLAGS_INCONSISTENT; + ret = EOWNERDEAD; } else { diff --git a/sched/pthread/pthread_mutextrylock.c b/sched/pthread/pthread_mutextrylock.c index 630de9e5fd..683909c859 100644 --- a/sched/pthread/pthread_mutextrylock.c +++ b/sched/pthread/pthread_mutextrylock.c @@ -157,6 +157,7 @@ int pthread_mutex_trylock(FAR pthread_mutex_t *mutex) if (mutex->pid > 0 && sched_gettcb(mutex->pid) == NULL) { DEBUGASSERT(mutex->pid != 0); /* < 0: available, >0 owned, ==0 error */ + DEBUGASSERT((mutex->flags & _PTHREAD_MFLAGS_INCONSISTENT) != 0); /* A thread holds the mutex, but there is no such thread. * POSIX requires that the 'robust' mutex return EOWNERDEAD @@ -164,7 +165,8 @@ int pthread_mutex_trylock(FAR pthread_mutex_t *mutex) * call pthread_mutx_consistent() fo fix the mutex. */ - ret = EOWNERDEAD; + mutex->flags |= _PTHREAD_MFLAGS_INCONSISTENT; + ret = EOWNERDEAD; } /* The mutex is locked by another, active thread */ -- GitLab From 34c5e1c18febcc48cfc9ad8f4216f5dd15544e9d Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 26 Mar 2017 14:04:07 -0600 Subject: [PATCH 216/990] Minor cleanup from recent changes. --- TODO | 6 ------ include/pthread.h | 4 ++-- sched/pthread/pthread.h | 4 ++-- sched/pthread/pthread_condtimedwait.c | 4 ++-- sched/pthread/pthread_condwait.c | 4 ++-- sched/pthread/pthread_mutexlock.c | 2 +- sched/pthread/pthread_mutexunlock.c | 2 +- 7 files changed, 10 insertions(+), 16 deletions(-) diff --git a/TODO b/TODO index b0bb4f5017..d19ac0f067 100644 --- a/TODO +++ b/TODO @@ -468,12 +468,6 @@ o pthreads (sched/pthreads) robust that determines which behavior is supported. non-robust should be the default. NuttX does not support this attribute and robust behavior is the default and only supported behavior. - - The spec is not clear, but I think there there is also missing - logic when the thread exits. I believe that the next highest - prority thread waiting for the mutex should be awakend and - pthread_mutex_lock() should return EOWNERDEAD. - That does not happen now. They will just remain blocked. Status: Open Priority: Low. The non-robust behavior is dangerous and really should never be used. diff --git a/include/pthread.h b/include/pthread.h index 8f3c7bf37f..305bb8db21 100644 --- a/include/pthread.h +++ b/include/pthread.h @@ -228,7 +228,7 @@ struct pthread_mutexattr_s { uint8_t pshared; /* PTHREAD_PROCESS_PRIVATE or PTHREAD_PROCESS_SHARED */ #ifdef CONFIG_PRIORITY_INHERITANCE - uint8_t proto; /* See _PTHREAD_PRIO_* definitions */ + uint8_t proto; /* See PTHREAD_PRIO_* definitions */ #endif #ifdef CONFIG_MUTEX_TYPES uint8_t type; /* Type of the mutex. See PTHREAD_MUTEX_* definitions */ @@ -248,7 +248,7 @@ struct pthread_mutex_s sem_t sem; /* Semaphore underlying the implementation of the mutex */ pid_t pid; /* ID of the holder of the mutex */ - uint8_t flags; /* See PTHREAD_MFLAGS_* */ + uint8_t flags; /* See _PTHREAD_MFLAGS_* */ #ifdef CONFIG_MUTEX_TYPES uint8_t type; /* Type of the mutex. See PTHREAD_MUTEX_* definitions */ int16_t nlocks; /* The number of recursive locks held */ diff --git a/sched/pthread/pthread.h b/sched/pthread/pthread.h index bf97c0c018..6ab044a3ba 100644 --- a/sched/pthread/pthread.h +++ b/sched/pthread/pthread.h @@ -109,8 +109,8 @@ FAR struct join_s *pthread_findjoininfo(FAR struct task_group_s *group, void pthread_release(FAR struct task_group_s *group); int pthread_takesemaphore(sem_t *sem, bool intr); int pthread_givesemaphore(sem_t *sem); -int pthread_takemutex(FAR struct pthread_mutex_s *mutex, bool intr); -int pthread_givemutex(FAR struct pthread_mutex_s *mutex); +int pthread_mutex_take(FAR struct pthread_mutex_s *mutex, bool intr); +int pthread_mutex_give(FAR struct pthread_mutex_s *mutex); void pthread_mutex_inconsistent(FAR struct pthread_tcb_s *tcb); #ifdef CONFIG_MUTEX_TYPES diff --git a/sched/pthread/pthread_condtimedwait.c b/sched/pthread/pthread_condtimedwait.c index b03fc3a73f..4ed8c5aed6 100644 --- a/sched/pthread/pthread_condtimedwait.c +++ b/sched/pthread/pthread_condtimedwait.c @@ -260,7 +260,7 @@ int pthread_cond_timedwait(FAR pthread_cond_t *cond, FAR pthread_mutex_t *mutex, /* Give up the mutex */ mutex->pid = -1; - ret = pthread_givemutex(mutex); + ret = pthread_mutex_give(mutex); if (ret != 0) { /* Restore interrupts (pre-emption will be enabled when @@ -316,7 +316,7 @@ int pthread_cond_timedwait(FAR pthread_cond_t *cond, FAR pthread_mutex_t *mutex, /* Reacquire the mutex (retaining the ret). */ sinfo("Re-locking...\n"); - status = pthread_takemutex(mutex, false); + status = pthread_mutex_take(mutex, false); if (status == OK) { mutex->pid = mypid; diff --git a/sched/pthread/pthread_condwait.c b/sched/pthread/pthread_condwait.c index 88f39485aa..9bcba234a5 100644 --- a/sched/pthread/pthread_condwait.c +++ b/sched/pthread/pthread_condwait.c @@ -101,7 +101,7 @@ int pthread_cond_wait(FAR pthread_cond_t *cond, FAR pthread_mutex_t *mutex) sched_lock(); mutex->pid = -1; - ret = pthread_givemutex(mutex); + ret = pthread_mutex_give(mutex); /* Take the semaphore */ @@ -122,7 +122,7 @@ int pthread_cond_wait(FAR pthread_cond_t *cond, FAR pthread_mutex_t *mutex) */ sinfo("Reacquire mutex...\n"); - status = pthread_takemutex(mutex, false); + status = pthread_mutex_take(mutex, false); if (ret == OK) { /* Report the first failure that occurs */ diff --git a/sched/pthread/pthread_mutexlock.c b/sched/pthread/pthread_mutexlock.c index c39a384bed..67b668bf9d 100644 --- a/sched/pthread/pthread_mutexlock.c +++ b/sched/pthread/pthread_mutexlock.c @@ -185,7 +185,7 @@ int pthread_mutex_lock(FAR pthread_mutex_t *mutex) { /* Take the underlying semaphore, waiting if necessary */ - ret = pthread_takemutex(mutex, true); + ret = pthread_mutex_take(mutex, true); /* If we successfully obtained the semaphore, then indicate * that we own it. diff --git a/sched/pthread/pthread_mutexunlock.c b/sched/pthread/pthread_mutexunlock.c index 05f461605f..7ab0c90469 100644 --- a/sched/pthread/pthread_mutexunlock.c +++ b/sched/pthread/pthread_mutexunlock.c @@ -139,7 +139,7 @@ int pthread_mutex_unlock(FAR pthread_mutex_t *mutex) #ifdef CONFIG_MUTEX_TYPES mutex->nlocks = 0; #endif - ret = pthread_givemutex(mutex); + ret = pthread_mutex_give(mutex); } sched_unlock(); -- GitLab From 8b23c16b9052deaa8ec83279676b73e49f5613a9 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 26 Mar 2017 14:44:57 -0600 Subject: [PATCH 217/990] pthreads: pthread_mutex_consistent() needs to clear flags. --- sched/pthread/pthread_mutexconsistent.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/sched/pthread/pthread_mutexconsistent.c b/sched/pthread/pthread_mutexconsistent.c index 0579cb3841..3febab2d0b 100644 --- a/sched/pthread/pthread_mutexconsistent.c +++ b/sched/pthread/pthread_mutexconsistent.c @@ -118,7 +118,8 @@ int pthread_mutex_consistent(FAR pthread_mutex_t *mutex) { /* The thread associated with the PID no longer exists */ - mutex->pid = -1; + mutex->pid = -1; + mutex->flags = 0; /* Reset the semaphore. This has the same affect as if the * dead task had called pthread_mutex_unlock(). -- GitLab From 86ab384d777533c7b0a1302137265415e79eaf46 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 26 Mar 2017 15:46:19 -0600 Subject: [PATCH 218/990] Forget to add some files in previous commits --- sched/pthread/pthread_mutex.c | 184 ++++++++++++++++++++++ sched/pthread/pthread_mutexinconsistent.c | 102 ++++++++++++ 2 files changed, 286 insertions(+) create mode 100644 sched/pthread/pthread_mutex.c create mode 100644 sched/pthread/pthread_mutexinconsistent.c diff --git a/sched/pthread/pthread_mutex.c b/sched/pthread/pthread_mutex.c new file mode 100644 index 0000000000..03bf35ea49 --- /dev/null +++ b/sched/pthread/pthread_mutex.c @@ -0,0 +1,184 @@ +/**************************************************************************** + * sched/pthread/pthread_mutex.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include + +#include "sched/sched.h" +#include "pthread/pthread.h" + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: pthread_mutex_take + * + * Description: + * Take the pthread_mutex and, if successful, add the mutex to the ist of + * mutexes held by this thread. + * + * Parameters: + * mutex - The mux to be locked + * intr - false: ignore EINTR errors when locking; true tread EINTR as + * other errors by returning the errno value + * + * Return Value: + * 0 on success or an errno value on failure. + * + ****************************************************************************/ + +int pthread_mutex_take(FAR struct pthread_mutex_s *mutex, bool intr) +{ + int ret = EINVAL; + + /* Verify input parameters */ + + DEBUGASSERT(mutex != NULL); + if (mutex != NULL) + { + /* Make sure that no unexpected context switches occur */ + + sched_lock(); + + /* Take semaphore underlying the mutex */ + + ret = pthread_takesemaphore(&mutex->sem, intr); + if (ret == OK) + { + DEBUGASSERT(mutex->flink == NULL); + + /* Check if the holder of the mutex has terminated. In that case, + * the state of the mutex is inconsistent and we return EOWNERDEAD. + */ + + if ((mutex->flags & _PTHREAD_MFLAGS_INCONSISTENT) != 0) + { + ret = EOWNERDEAD; + } + + /* Add the mutex to the list of mutexes held by this task */ + + else + { + FAR struct pthread_tcb_s *rtcb = (FAR struct pthread_tcb_s *)this_task(); + irqstate_t flags; + + flags = enter_critical_section(); + mutex->flink = rtcb->mhead; + rtcb->mhead = mutex; + leave_critical_section(flags); + } + } + } + + sched_unlock(); + return ret; +} + +/**************************************************************************** + * Name: pthread_mutex_give + * + * Description: + * Take the pthread_mutex and, if successful, add the mutex to the ist of + * mutexes held by this thread. + * + * Parameters: + * mutex - The mux to be unlocked + * + * Return Value: + * 0 on success or an errno value on failure. + * + ****************************************************************************/ + +int pthread_mutex_give(FAR struct pthread_mutex_s *mutex) +{ + FAR struct pthread_mutex_s *curr; + FAR struct pthread_mutex_s *prev; + int ret = EINVAL; + + /* Verify input parameters */ + + DEBUGASSERT(mutex != NULL); + if (mutex != NULL) + { + FAR struct pthread_tcb_s *rtcb = (FAR struct pthread_tcb_s *)this_task(); + irqstate_t flags; + + flags = enter_critical_section(); + + /* Remove the mutex from the list of mutexes held by this task */ + + for (prev = NULL, curr = rtcb->mhead; + curr != NULL && curr != mutex; + prev = curr, curr = curr->flink); + + DEBUGASSERT(curr == mutex); + + /* Remove the mutex from the list. prev == NULL means that the mutex + * to be removed is at the head of the list. + */ + + if (prev == NULL) + { + rtcb->mhead = mutex->flink; + } + else + { + prev->flink = mutex->flink; + } + + mutex->flink = NULL; + leave_critical_section(flags); + + /* Now release the underlying semaphore */ + + ret = pthread_givesemaphore(&mutex->sem); + } + + return ret; +} + diff --git a/sched/pthread/pthread_mutexinconsistent.c b/sched/pthread/pthread_mutexinconsistent.c new file mode 100644 index 0000000000..c9d2b20371 --- /dev/null +++ b/sched/pthread/pthread_mutexinconsistent.c @@ -0,0 +1,102 @@ +/**************************************************************************** + * sched/pthread/pthread_mutexinconsistent.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include + +#include "pthread/pthread.h" + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: pthread_mutex_inconsistent + * + * Description: + * This function is called when a pthread is terminated via either + * pthread_exit() or pthread_cancel(). It will check for any mutexes + * held by exitting thread. It will mark them as inconsistent and + * then wake up the highest priority waiter for the mutex. That + * instance of pthread_mutex_lock() will then return EOWNERDEAD. + * + * Input Parameters: + * tcb -- a reference to the TCB of the exitting pthread. + * + * Returned Value: + * None. + * + ****************************************************************************/ + +void pthread_mutex_inconsistent(FAR struct pthread_tcb_s *tcb) +{ + FAR struct pthread_mutex_s *mutex; + irqstate_t flags; + + DEBUGASSERT(tcb != NULL); + + sched_lock(); + + /* Remove and process each mutex from the list of mutexes held by this task */ + + while (tcb->mhead != NULL) + { + /* Remove the mutex from the TCB list */ + + flags = enter_critical_section(); + mutex = tcb->mhead; + tcb->mhead = mutex->flink; + mutex->flink = NULL; + leave_critical_section(flags); + + /* Mark the mutex as INCONSISTENT and wake up any waiting thread */ + + mutex->flags |= _PTHREAD_MFLAGS_INCONSISTENT; + (void)pthread_givesemaphore(&mutex->sem); + } + + sched_unlock(); +} -- GitLab From 8b3c554e45aa0cc643f80ae783b3852766a130c7 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 26 Mar 2017 17:37:28 -0600 Subject: [PATCH 219/990] pthreads: Add a configuration option to disable robust mutexes and revert to the traditional unsafe mutexes. --- include/nuttx/sched.h | 2 ++ include/pthread.h | 6 ++++++ sched/Kconfig | 20 ++++++++++++++++++++ sched/pthread/Make.defs | 7 +++++-- sched/pthread/pthread.h | 6 ++++++ sched/pthread/pthread_cancel.c | 2 ++ sched/pthread/pthread_exit.c | 4 +++- sched/pthread/pthread_mutexinit.c | 5 ++++- sched/pthread/pthread_mutexlock.c | 21 +++++++++++++++------ sched/pthread/pthread_mutextrylock.c | 6 +++++- sched/pthread/pthread_mutexunlock.c | 28 +++++++++++++++++++++++----- 11 files changed, 91 insertions(+), 16 deletions(-) diff --git a/include/nuttx/sched.h b/include/nuttx/sched.h index f618ac94ce..f8bc539e3d 100644 --- a/include/nuttx/sched.h +++ b/include/nuttx/sched.h @@ -699,7 +699,9 @@ struct pthread_tcb_s /* Robust mutex support *******************************************************/ +#ifndef CONFIG_PTHREAD_MUTEX_UNSAFE FAR struct pthread_mutex_s *mhead; /* List of mutexes held by thread */ +#endif /* Clean-up stack *************************************************************/ diff --git a/include/pthread.h b/include/pthread.h index 305bb8db21..214ad454fe 100644 --- a/include/pthread.h +++ b/include/pthread.h @@ -240,15 +240,19 @@ typedef struct pthread_mutexattr_s pthread_mutexattr_t; struct pthread_mutex_s { +#ifndef CONFIG_PTHREAD_MUTEX_UNSAFE /* Supports a singly linked list */ FAR struct pthread_mutex_s *flink; +#endif /* Payload */ sem_t sem; /* Semaphore underlying the implementation of the mutex */ pid_t pid; /* ID of the holder of the mutex */ +#ifndef CONFIG_PTHREAD_MUTEX_UNSAFE uint8_t flags; /* See _PTHREAD_MFLAGS_* */ +#endif #ifdef CONFIG_MUTEX_TYPES uint8_t type; /* Type of the mutex. See PTHREAD_MUTEX_* definitions */ int16_t nlocks; /* The number of recursive locks held */ @@ -438,9 +442,11 @@ int pthread_mutex_lock(FAR pthread_mutex_t *mutex); int pthread_mutex_trylock(FAR pthread_mutex_t *mutex); int pthread_mutex_unlock(FAR pthread_mutex_t *mutex); +#ifndef CONFIG_PTHREAD_MUTEX_UNSAFE /* Make sure that the pthread mutex is in a consistent state */ int pthread_mutex_consistent(FAR pthread_mutex_t *mutex); +#endif /* Operations on condition variables */ diff --git a/sched/Kconfig b/sched/Kconfig index 3a5807d4dc..369e9ac7cd 100644 --- a/sched/Kconfig +++ b/sched/Kconfig @@ -531,6 +531,26 @@ config MUTEX_TYPES: Set to enable support for recursive and errorcheck mutexes. Enables pthread_mutexattr_settype(). +choice + prompt "pthread mutex robustness" + default PTHREAD_MUTEX_ROBUST if !DEFAULT_SMALL + default PTHREAD_UNSAFE if DEFAULT_SMALL + + config PTHREAD_MUTEX_ROBUST + bool "Robust mutexes" + ---help--- + Support only the robust form of the NORMAL mutex. + + config PTHREAD_MUTEX_UNSAFE + bool "Traditional unsafe mutexes" + ---help--- + Support only the traditional non-robust form of the NORMAL mutex. + You should select this option only for backward compatibility with + software you may be porting or, perhaps, if you are trying to minimize + footprint. + +endchoice # thread mutex robustness + config NPTHREAD_KEYS int "Maximum number of pthread keys" default 4 diff --git a/sched/pthread/Make.defs b/sched/pthread/Make.defs index a39a35d208..20bc7e8d6c 100644 --- a/sched/pthread/Make.defs +++ b/sched/pthread/Make.defs @@ -37,9 +37,8 @@ ifneq ($(CONFIG_DISABLE_PTHREAD),y) CSRCS += pthread_create.c pthread_exit.c pthread_join.c pthread_detach.c CSRCS += pthread_yield.c pthread_getschedparam.c pthread_setschedparam.c -CSRCS += pthread_mutexinit.c pthread_mutexdestroy.c pthread_mutex.c +CSRCS += pthread_mutexinit.c pthread_mutexdestroy.c CSRCS += pthread_mutexlock.c pthread_mutextrylock.c pthread_mutexunlock.c -CSRCS += pthread_mutexconsistent.c pthread_mutexinconsistent.c CSRCS += pthread_condinit.c pthread_conddestroy.c CSRCS += pthread_condwait.c pthread_condsignal.c pthread_condbroadcast.c CSRCS += pthread_barrierinit.c pthread_barrierdestroy.c pthread_barrierwait.c @@ -49,6 +48,10 @@ CSRCS += pthread_keydelete.c CSRCS += pthread_initialize.c pthread_completejoin.c pthread_findjoininfo.c CSRCS += pthread_once.c pthread_release.c pthread_setschedprio.c +ifneq ($(CONFIG_PTHREAD_MUTEX_UNSAFE),y) +CSRCS += pthread_mutex.c pthread_mutexconsistent.c pthread_mutexinconsistent.c +endif + ifneq ($(CONFIG_DISABLE_SIGNALS),y) CSRCS += pthread_condtimedwait.c pthread_kill.c pthread_sigmask.c endif diff --git a/sched/pthread/pthread.h b/sched/pthread/pthread.h index 6ab044a3ba..2e7106495f 100644 --- a/sched/pthread/pthread.h +++ b/sched/pthread/pthread.h @@ -109,9 +109,15 @@ FAR struct join_s *pthread_findjoininfo(FAR struct task_group_s *group, void pthread_release(FAR struct task_group_s *group); int pthread_takesemaphore(sem_t *sem, bool intr); int pthread_givesemaphore(sem_t *sem); + +#ifndef CONFIG_PTHREAD_MUTEX_UNSAFE int pthread_mutex_take(FAR struct pthread_mutex_s *mutex, bool intr); int pthread_mutex_give(FAR struct pthread_mutex_s *mutex); void pthread_mutex_inconsistent(FAR struct pthread_tcb_s *tcb); +#else +# define pthread_mutex_take(m,i) pthread_takesemaphore(&(m)->sem,(i)) +# define pthread_mutex_give(m) pthread_givesemaphore(&(m)->sem) +#endif #ifdef CONFIG_MUTEX_TYPES int pthread_mutexattr_verifytype(int type); diff --git a/sched/pthread/pthread_cancel.c b/sched/pthread/pthread_cancel.c index 3a520b1f93..e2cad60ebb 100644 --- a/sched/pthread/pthread_cancel.c +++ b/sched/pthread/pthread_cancel.c @@ -162,9 +162,11 @@ int pthread_cancel(pthread_t thread) (void)pthread_completejoin((pid_t)thread, PTHREAD_CANCELED); +#ifndef CONFIG_PTHREAD_MUTEX_UNSAFE /* Recover any mutexes still held by the canceled thread */ pthread_mutex_inconsistent(tcb); +#endif /* Then let task_terminate do the real work */ diff --git a/sched/pthread/pthread_exit.c b/sched/pthread/pthread_exit.c index 4654d86371..bcc8e79c85 100644 --- a/sched/pthread/pthread_exit.c +++ b/sched/pthread/pthread_exit.c @@ -123,9 +123,11 @@ void pthread_exit(FAR void *exit_value) exit(EXIT_FAILURE); } +#ifndef CONFIG_PTHREAD_MUTEX_UNSAFE /* Recover any mutexes still held by the canceled thread */ - pthread_mutex_inconsistent(tcb); + pthread_mutex_inconsistent((FAR struct pthread_tcb_s *)tcb); +#endif /* Perform common task termination logic. This will get called again later * through logic kicked off by _exit(). However, we need to call it before diff --git a/sched/pthread/pthread_mutexinit.c b/sched/pthread/pthread_mutexinit.c index b521137683..46c9e67356 100644 --- a/sched/pthread/pthread_mutexinit.c +++ b/sched/pthread/pthread_mutexinit.c @@ -123,14 +123,17 @@ int pthread_mutex_init(FAR pthread_mutex_t *mutex, ret = get_errno(); } #endif + +#ifndef CONFIG_PTHREAD_MUTEX_UNSAFE /* Initial internal fields of the mutex */ mutex->flink = NULL; mutex->flags = 0; +#endif +#ifdef CONFIG_MUTEX_TYPES /* Set up attributes unique to the mutex type */ -#ifdef CONFIG_MUTEX_TYPES mutex->type = type; mutex->nlocks = 0; #endif diff --git a/sched/pthread/pthread_mutexlock.c b/sched/pthread/pthread_mutexlock.c index 67b668bf9d..ffc8eadad2 100644 --- a/sched/pthread/pthread_mutexlock.c +++ b/sched/pthread/pthread_mutexlock.c @@ -120,13 +120,15 @@ int pthread_mutex_lock(FAR pthread_mutex_t *mutex) sched_lock(); - /* Does this thread already hold the semaphore? */ +#ifdef CONFIG_MUTEX_TYPES + /* All mutex types except for NORMAL (and DEFAULT) will return + * and an error error if the caller does not hold the mutex. + */ - if (mutex->pid == mypid) + if (mutex->type != PTHREAD_MUTEX_NORMAL && mutex->pid == mypid) { /* Yes.. Is this a recursive mutex? */ -#ifdef CONFIG_MUTEX_TYPES if (mutex->type == PTHREAD_MUTEX_RECURSIVE) { /* Yes... just increment the number of locks held and return @@ -144,7 +146,6 @@ int pthread_mutex_lock(FAR pthread_mutex_t *mutex) } } else -#endif { /* No, then we would deadlock... return an error (default * behavior is like PTHREAD_MUTEX_ERRORCHECK) @@ -160,14 +161,17 @@ int pthread_mutex_lock(FAR pthread_mutex_t *mutex) ret = EDEADLK; } } + else +#endif /* CONFIG_MUTEX_TYPES */ +#ifndef CONFIG_PTHREAD_MUTEX_UNSAFE /* The calling thread does not hold the semaphore. The correct * behavior for the 'robust' mutex is to verify that the holder of the * mutex is still valid. This is protection from the case * where the holder of the mutex has exitted without unlocking it. */ - else if (mutex->pid > 0 && sched_gettcb(mutex->pid) == NULL) + if (mutex->pid > 0 && sched_gettcb(mutex->pid) == NULL) { DEBUGASSERT(mutex->pid != 0); /* < 0: available, >0 owned, ==0 error */ DEBUGASSERT((mutex->flags & _PTHREAD_MFLAGS_INCONSISTENT) != 0); @@ -182,8 +186,13 @@ int pthread_mutex_lock(FAR pthread_mutex_t *mutex) ret = EOWNERDEAD; } else +#endif /* !CONFIG_PTHREAD_MUTEX_UNSAFE */ + { - /* Take the underlying semaphore, waiting if necessary */ + /* Take the underlying semaphore, waiting if necessary. NOTE that + * is required to deadlock for the case of the non-robust NORMAL or + * default mutex. + */ ret = pthread_mutex_take(mutex, true); diff --git a/sched/pthread/pthread_mutextrylock.c b/sched/pthread/pthread_mutextrylock.c index 683909c859..6e21c74b44 100644 --- a/sched/pthread/pthread_mutextrylock.c +++ b/sched/pthread/pthread_mutextrylock.c @@ -124,7 +124,7 @@ int pthread_mutex_trylock(FAR pthread_mutex_t *mutex) else { - /* Did it fail because the semaphore was not avaialabl? */ + /* Did it fail because the semaphore was not avaialable? */ int errcode = get_errno(); if (errcode == EAGAIN) @@ -148,6 +148,8 @@ int pthread_mutex_trylock(FAR pthread_mutex_t *mutex) } else #endif + +#ifndef CONFIG_PTHREAD_MUTEX_UNSAFE /* The calling thread does not hold the semaphore. The correct * behavior for the 'robust' mutex is to verify that the holder of * the mutex is still valid. This is protection from the case @@ -172,6 +174,8 @@ int pthread_mutex_trylock(FAR pthread_mutex_t *mutex) /* The mutex is locked by another, active thread */ else +#endif /* CONFIG_PTHREAD_MUTEX_UNSAFE */ + { ret = EBUSY; } diff --git a/sched/pthread/pthread_mutexunlock.c b/sched/pthread/pthread_mutexunlock.c index 7ab0c90469..9efd9ed847 100644 --- a/sched/pthread/pthread_mutexunlock.c +++ b/sched/pthread/pthread_mutexunlock.c @@ -93,9 +93,20 @@ int pthread_mutex_unlock(FAR pthread_mutex_t *mutex) sched_lock(); - /* Does the calling thread own the semaphore? */ +#if !defined(CONFIG_PTHREAD_MUTEX_UNSAFE) || !defined(CONFIG_MUTEX_TYPES) + /* Does the calling thread own the semaphore? Should we report the + * EPERM error? This applies to robust NORMAL (and DEFAULT) mutexes + * as well as ERRORCHECK and RECURSIVE mutexes. + */ if (mutex->pid != (int)getpid()) +#else + /* Does the calling thread own the semaphore? Should we report the + * EPERM error? This applies to ERRORCHECK and RECURSIVE mutexes. + */ + + if (mutex->type != PTHREAD_MUTEX_NORMAL && mutex->pid != (int)getpid()) +#endif { /* No... return an EPERM error. * @@ -111,11 +122,12 @@ int pthread_mutex_unlock(FAR pthread_mutex_t *mutex) serr("ERROR: Holder=%d returning EPERM\n", mutex->pid); ret = EPERM; } + else +#ifdef CONFIG_MUTEX_TYPES /* Yes, the caller owns the semaphore.. Is this a recursive mutex? */ -#ifdef CONFIG_MUTEX_TYPES - else if (mutex->type == PTHREAD_MUTEX_RECURSIVE && mutex->nlocks > 1) + if (mutex->type == PTHREAD_MUTEX_RECURSIVE && mutex->nlocks > 1) { /* This is a recursive mutex and we there are multiple locks held. Retain * the mutex lock, just decrement the count of locks held, and return @@ -125,13 +137,19 @@ int pthread_mutex_unlock(FAR pthread_mutex_t *mutex) mutex->nlocks--; ret = OK; } -#endif + else + +#endif /* CONFIG_MUTEX_TYPES */ /* This is either a non-recursive mutex or is the outermost unlock of * a recursive mutex. + * + * In the case where the calling thread is NOT the holder of the thread, + * the behavior is undefined per POSIX. Here we do the same as GLIBC: + * We allow the other thread to release the mutex even though it does + * not own it. */ - else { /* Nullify the pid and lock count then post the semaphore */ -- GitLab From 666208cf237248e03ad13a730b8c4f3ea5ccef1a Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 26 Mar 2017 18:37:24 -0600 Subject: [PATCH 220/990] pthread mutexes: Add option to support both unsafe and robust mutexes via pthread_mutexattr_get/setrobust(). --- include/pthread.h | 47 ++++++++++++++++++++++++--- libc/pthread/Make.defs | 1 + libc/pthread/pthread_mutexattr_init.c | 10 ++++++ sched/Kconfig | 24 +++++++++++++- sched/pthread/pthread_mutexinit.c | 12 ++++++- 5 files changed, 87 insertions(+), 7 deletions(-) diff --git a/include/pthread.h b/include/pthread.h index 214ad454fe..30c96bab9c 100644 --- a/include/pthread.h +++ b/include/pthread.h @@ -143,12 +143,42 @@ #define PTHREAD_PRIO_INHERIT SEM_PRIO_INHERIT #define PTHREAD_PRIO_PROTECT SEM_PRIO_PROTECT +/* Values for robust argument of pthread_mutexattr_get/setrobust + * + * PTHREAD_MUTEX_STALLED - No special actions are taken if the owner of the + * mutex is terminated while holding the mutex lock. This can lead to + * deadlocks if no other thread can unlock the mutex. This is the standard + * default value (NuttX permits you to override that default behavior + * with a configuration option). + * + * PTHREAD_MUTEX_ROBUST - If the process containing the owning thread of a + * robust mutex terminates while holding the mutex lock, the next thread + * that acquires the mutex will be notified about the termination by the + * return value EOWNERDEAD from the locking function. If the owning thread + * of a robust mutex terminates while holding the mutex lock, the next + * thread that attempts to acquire the mutex may be notified about the + * termination by the return value EOWNERDEAD. The notified thread can + * then attempt to make the state protected by the mutex consistent again, + * and if successful can mark the mutex state as consistent by calling + * pthread_mutex_consistent(). After a subsequent successful call to + * pthread_mutex_unlock(), the mutex lock will be released and can be used + * normally by other threads. If the mutex is unlocked without a call to + * pthread_mutex_consistent(), it will be in a permanently unusable state + * and all attempts to lock the mutex will fail with the error + * ENOTRECOVERABLE. The only permissible operation on such a mutex is + * pthread_mutex_destroy(). + */ + +#define PTHREAD_MUTEX_STALLED 0 +#define PTHREAD_MUTEX_ROBUST 1 + /* Values for struct pthread_mutex_s flags. These are non-standard and * intended only for internal use within the OS. */ -#define _PTHREAD_MFLAGS_INCONSISTENT (1 << 0) /* Mutex is in an inconsistent state */ -#define _PTHREAD_MFLAGS_NOTRECOVRABLE (1 << 1) /* Inconsistent mutex has been unlocked */ +#define _PTHREAD_MFLAGS_ROBUST (1 << 0) /* Robust (NORMAL) mutex */ +#define _PTHREAD_MFLAGS_INCONSISTENT (1 << 1) /* Mutex is in an inconsistent state */ +#define _PTHREAD_MFLAGS_NOTRECOVRABLE (1 << 2) /* Inconsistent mutex has been unlocked */ /* Definitions to map some non-standard, BSD thread management interfaces to * the non-standard Linux-like prctl() interface. Since these are simple @@ -226,12 +256,15 @@ typedef struct pthread_cond_s pthread_cond_t; struct pthread_mutexattr_s { - uint8_t pshared; /* PTHREAD_PROCESS_PRIVATE or PTHREAD_PROCESS_SHARED */ + uint8_t pshared : 1; /* PTHREAD_PROCESS_PRIVATE or PTHREAD_PROCESS_SHARED */ #ifdef CONFIG_PRIORITY_INHERITANCE - uint8_t proto; /* See PTHREAD_PRIO_* definitions */ + uint8_t proto : 2; /* See PTHREAD_PRIO_* definitions */ #endif #ifdef CONFIG_MUTEX_TYPES - uint8_t type; /* Type of the mutex. See PTHREAD_MUTEX_* definitions */ + uint8_t type : 2; /* Type of the mutex. See PTHREAD_MUTEX_* definitions */ +#endif +#ifdef CONFIG_PTHREAD_MUTEX_BOTH + uint8_t robust : 1; /* PTHREAD_MUTEX_STALLED or PTHREAD_MUTEX_ROBUST */ #endif }; @@ -432,6 +465,10 @@ int pthread_mutexattr_getprotocol(FAR const pthread_mutexattr_t *attr, FAR int *protocol); int pthread_mutexattr_setprotocol(FAR pthread_mutexattr_t *attr, int protocol); +int pthread_mutexattr_getrobust(FAR const pthread_mutexattr_t *attr, + FAR int *robust); +int pthread_mutexattr_setrobust(FAR pthread_mutexattr_t *attr, + int robust); /* The following routines create, delete, lock and unlock mutexes. */ diff --git a/libc/pthread/Make.defs b/libc/pthread/Make.defs index 089845d8f7..b8be2927d2 100644 --- a/libc/pthread/Make.defs +++ b/libc/pthread/Make.defs @@ -49,6 +49,7 @@ CSRCS += pthread_mutexattr_init.c pthread_mutexattr_destroy.c CSRCS += pthread_mutexattr_getpshared.c pthread_mutexattr_setpshared.c CSRCS += pthread_mutexattr_setprotocol.c pthread_mutexattr_getprotocol.c CSRCS += pthread_mutexattr_settype.c pthread_mutexattr_gettype.c +CSRCS += pthread_mutexattr_setrobust.c pthread_mutexattr_getrobust.c CSRCS += pthread_setcancelstate.c pthread_setcanceltype.c CSRCS += pthread_testcancel.c diff --git a/libc/pthread/pthread_mutexattr_init.c b/libc/pthread/pthread_mutexattr_init.c index f1b6bca9c7..de6183e56c 100644 --- a/libc/pthread/pthread_mutexattr_init.c +++ b/libc/pthread/pthread_mutexattr_init.c @@ -76,11 +76,21 @@ int pthread_mutexattr_init(FAR pthread_mutexattr_t *attr) else { attr->pshared = 0; + #ifdef CONFIG_PRIORITY_INHERITANCE attr->proto = SEM_PRIO_INHERIT; #endif + #ifdef CONFIG_MUTEX_TYPES attr->type = PTHREAD_MUTEX_DEFAULT; +#endif + +#ifdef CONFIG_PTHREAD_MUTEX_BOTH +#ifdef CONFIG_PTHREAD_MUTEX_DEFAULT_UNSAFE + attr->robust = PTHREAD_MUTEX_STALLED; +#else + attr->robust = PTHREAD_MUTEX_ROBUST; +#endif #endif } diff --git a/sched/Kconfig b/sched/Kconfig index 369e9ac7cd..60183e67d2 100644 --- a/sched/Kconfig +++ b/sched/Kconfig @@ -549,7 +549,29 @@ choice software you may be porting or, perhaps, if you are trying to minimize footprint. -endchoice # thread mutex robustness + config PTHREAD_MUTEX_BOTH + bool "Both robust and unsafe mutexes" + ---help--- + Support both forms of NORMAL mutexes. + +endchoice # pthread mutex robustness + +choice + prompt "Default NORMAL mutex robustness" + default PTHREAD_MUTEX_DEFAULT_ROBUST + depends on PTHREAD_MUTEX_BOTH + + config PTHREAD_MUTEX_DEFAULT_ROBUST + bool "Robust default" + ---help--- + The default is robust NORMAL mutexes (non-standard) + + config PTHREAD_MUTEX_DEFAULT_UNSAFE + bool "Unsafe default" + ---help--- + The default is traditional unsafe NORMAL mutexes (standard) + +endchoice # Default NORMAL mutex robustness config NPTHREAD_KEYS int "Maximum number of pthread keys" diff --git a/sched/pthread/pthread_mutexinit.c b/sched/pthread/pthread_mutexinit.c index 46c9e67356..e6abe32900 100644 --- a/sched/pthread/pthread_mutexinit.c +++ b/sched/pthread/pthread_mutexinit.c @@ -77,6 +77,13 @@ int pthread_mutex_init(FAR pthread_mutex_t *mutex, #endif #ifdef CONFIG_PRIORITY_INHERITANCE uint8_t proto = PTHREAD_PRIO_INHERIT; +#endif +#ifndef CONFIG_PTHREAD_MUTEX_UNSAFE +#ifdef CONFIG_PTHREAD_MUTEX_DEFAULT_UNSAFE + uint8_t robust = PTHREAD_MUTEX_STALLED; +#else + uint8_t robust = PTHREAD_MUTEX_ROBUST; +#endif #endif int ret = OK; int status; @@ -99,6 +106,9 @@ int pthread_mutex_init(FAR pthread_mutex_t *mutex, #endif #ifdef CONFIG_MUTEX_TYPES type = attr->type; +#endif +#ifdef CONFIG_PTHREAD_MUTEX_BOTH + robust = attr->robust; #endif } @@ -128,7 +138,7 @@ int pthread_mutex_init(FAR pthread_mutex_t *mutex, /* Initial internal fields of the mutex */ mutex->flink = NULL; - mutex->flags = 0; + mutex->flags = (robust == PTHREAD_MUTEX_ROBUST ? _PTHREAD_MFLAGS_ROBUST : 0); #endif #ifdef CONFIG_MUTEX_TYPES -- GitLab From d1196ddb6072056c931f1f187ab20148dbebe943 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 27 Mar 2017 07:49:13 -0600 Subject: [PATCH 221/990] pthread mutex: Forgot to add files in last commit --- libc/pthread/pthread_mutexattr_getrobust.c | 82 ++++++++++++++++++ libc/pthread/pthread_mutexattr_setrobust.c | 96 ++++++++++++++++++++++ 2 files changed, 178 insertions(+) create mode 100644 libc/pthread/pthread_mutexattr_getrobust.c create mode 100644 libc/pthread/pthread_mutexattr_setrobust.c diff --git a/libc/pthread/pthread_mutexattr_getrobust.c b/libc/pthread/pthread_mutexattr_getrobust.c new file mode 100644 index 0000000000..8d5e4c1060 --- /dev/null +++ b/libc/pthread/pthread_mutexattr_getrobust.c @@ -0,0 +1,82 @@ +/**************************************************************************** + * libc/pthread/pthread_mutexattr_getrobust.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: pthread_mutexattr_getrobust + * + * Description: + * Return the mutex robustneess from the mutex attributes. + * + * Parameters: + * attr - The mutex attributes to query + * robust - Location to return the robustness indication + * + * Return Value: + * 0, if the robustness was successfully return in 'robust', or + * EINVAL, if any NULL pointers provided. + * + * Assumptions: + * + ****************************************************************************/ + +int pthread_mutexattr_getrobust(FAR const pthread_mutexattr_t *attr, + FAR int *robust) +{ + if (attr != NULL && robust != NULL) + { +#if defined(CONFIG_PTHREAD_MUTEX_UNSAFE) + *robust = PTHREAD_MUTEX_STALLED; +#elif defined(CONFIG_PTHREAD_MUTEX_BOTH) + *robust = attr->robust; +#else /* Default: CONFIG_PTHREAD_MUTEX_ROBUST */ + *robust = PTHREAD_MUTEX_ROBUST; +#endif + return 0; + } + + return EINVAL; +} diff --git a/libc/pthread/pthread_mutexattr_setrobust.c b/libc/pthread/pthread_mutexattr_setrobust.c new file mode 100644 index 0000000000..42930fa0b7 --- /dev/null +++ b/libc/pthread/pthread_mutexattr_setrobust.c @@ -0,0 +1,96 @@ +/**************************************************************************** + * libc/pthread/pthread_mutexattr_setrobust.c + * + * Copyright (C) 201t 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: pthread_mutexattr_setrobust + * + * Description: + * Set the mutex robustness in the mutex attributes. + * + * Parameters: + * attr - The mutex attributes in which to set the mutex type. + * robust - The mutex type value to set. + * + * Return Value: + * 0, if the mutex robustness was successfully set in 'attr', or + * EINVAL, if 'attr' is NULL or 'robust' unrecognized. + * + * Assumptions: + * + ****************************************************************************/ + +int pthread_mutexattr_setrobust(pthread_mutexattr_t *attr, int robust) +{ +#if defined(CONFIG_PTHREAD_MUTEX_UNSAFE) + + if (attr != NULL && robust == PTHREAD_MUTEX_STALLED) + { + return OK; + } + + return EINVAL; + +#elif defined(CONFIG_PTHREAD_MUTEX_BOTH) + + if (attr != NULL && (robust == PTHREAD_MUTEX_STALLED || robust == _PTHREAD_MFLAGS_ROBUST)) + { + attr->robust = robust; + return OK; + } + + return EINVAL; + +#else /* Default: CONFIG_PTHREAD_MUTEX_ROBUST */ + + if (attr != NULL && robust == _PTHREAD_MFLAGS_ROBUST) + { + return OK; + } + + return EINVAL; +#endif +} -- GitLab From f2f798cb2957582ab61d100aa0ab9b3680be24e8 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 27 Mar 2017 08:50:45 -0600 Subject: [PATCH 222/990] pthread mutexes: Finish logic to support configuration mutex robustness. --- include/pthread.h | 2 +- sched/pthread/pthread_mutexconsistent.c | 8 ++-- sched/pthread/pthread_mutexlock.c | 21 ++++++++++ sched/pthread/pthread_mutextrylock.c | 21 ++++++++++ sched/pthread/pthread_mutexunlock.c | 53 +++++++++++++++++++------ 5 files changed, 88 insertions(+), 17 deletions(-) diff --git a/include/pthread.h b/include/pthread.h index 30c96bab9c..53eaa0ddaa 100644 --- a/include/pthread.h +++ b/include/pthread.h @@ -178,7 +178,7 @@ #define _PTHREAD_MFLAGS_ROBUST (1 << 0) /* Robust (NORMAL) mutex */ #define _PTHREAD_MFLAGS_INCONSISTENT (1 << 1) /* Mutex is in an inconsistent state */ -#define _PTHREAD_MFLAGS_NOTRECOVRABLE (1 << 2) /* Inconsistent mutex has been unlocked */ +#define _PTHREAD_MFLAGS_NRECOVERABLE (1 << 2) /* Inconsistent mutex has been unlocked */ /* Definitions to map some non-standard, BSD thread management interfaces to * the non-standard Linux-like prctl() interface. Since these are simple diff --git a/sched/pthread/pthread_mutexconsistent.c b/sched/pthread/pthread_mutexconsistent.c index 3febab2d0b..86930e276c 100644 --- a/sched/pthread/pthread_mutexconsistent.c +++ b/sched/pthread/pthread_mutexconsistent.c @@ -118,9 +118,11 @@ int pthread_mutex_consistent(FAR pthread_mutex_t *mutex) { /* The thread associated with the PID no longer exists */ - mutex->pid = -1; - mutex->flags = 0; - + mutex->pid = -1; + mutex->flags &= _PTHREAD_MFLAGS_ROBUST; +#ifdef CONFIG_MUTEX_TYPES + mutex->nlocks = 0; +#endif /* Reset the semaphore. This has the same affect as if the * dead task had called pthread_mutex_unlock(). */ diff --git a/sched/pthread/pthread_mutexlock.c b/sched/pthread/pthread_mutexlock.c index ffc8eadad2..3013248842 100644 --- a/sched/pthread/pthread_mutexlock.c +++ b/sched/pthread/pthread_mutexlock.c @@ -171,7 +171,28 @@ int pthread_mutex_lock(FAR pthread_mutex_t *mutex) * where the holder of the mutex has exitted without unlocking it. */ +#ifdef CONFIG_PTHREAD_MUTEX_BOTH +#ifdef CONFIG_MUTEX_TYPES + /* Include check if this is a NORMAL mutex and that it is robust */ + + if (mutex->pid > 0 && + ((mutex->flags & _PTHREAD_MFLAGS_ROBUST) != 0 || + mutex->type != PTHREAD_MUTEX_NORMAL) && + sched_gettcb(mutex->pid) == NULL) + +#else /* CONFIG_MUTEX_TYPES */ + /* This can only be a NORMAL mutex. Include check if it is robust */ + + if (mutex->pid > 0 && + (mutex->flags & _PTHREAD_MFLAGS_ROBUST) != 0 && + sched_gettcb(mutex->pid) == NULL) + +#endif /* CONFIG_MUTEX_TYPES */ +#else /* CONFIG_PTHREAD_MUTEX_ROBUST */ + /* This mutex is always robust, whatever type it is. */ + if (mutex->pid > 0 && sched_gettcb(mutex->pid) == NULL) +#endif { DEBUGASSERT(mutex->pid != 0); /* < 0: available, >0 owned, ==0 error */ DEBUGASSERT((mutex->flags & _PTHREAD_MFLAGS_INCONSISTENT) != 0); diff --git a/sched/pthread/pthread_mutextrylock.c b/sched/pthread/pthread_mutextrylock.c index 6e21c74b44..50c3175de5 100644 --- a/sched/pthread/pthread_mutextrylock.c +++ b/sched/pthread/pthread_mutextrylock.c @@ -156,7 +156,28 @@ int pthread_mutex_trylock(FAR pthread_mutex_t *mutex) * where the holder of the mutex has exitted without unlocking it. */ +#ifdef CONFIG_PTHREAD_MUTEX_BOTH +#ifdef CONFIG_MUTEX_TYPES + /* Check if this NORMAL mutex is robust */ + + if (mutex->pid > 0 && + ((mutex->flags & _PTHREAD_MFLAGS_ROBUST) != 0 || + mutex->type != PTHREAD_MUTEX_NORMAL) && + sched_gettcb(mutex->pid) == NULL) + +#else /* CONFIG_MUTEX_TYPES */ + /* Check if this NORMAL mutex is robust */ + + if (mutex->pid > 0 && + (mutex->flags & _PTHREAD_MFLAGS_ROBUST) != 0 && + sched_gettcb(mutex->pid) == NULL) + +#endif /* CONFIG_MUTEX_TYPES */ +#else /* CONFIG_PTHREAD_MUTEX_ROBUST */ + /* This mutex is always robust, whatever type it is. */ + if (mutex->pid > 0 && sched_gettcb(mutex->pid) == NULL) +#endif { DEBUGASSERT(mutex->pid != 0); /* < 0: available, >0 owned, ==0 error */ DEBUGASSERT((mutex->flags & _PTHREAD_MFLAGS_INCONSISTENT) != 0); diff --git a/sched/pthread/pthread_mutexunlock.c b/sched/pthread/pthread_mutexunlock.c index 9efd9ed847..b27c9ecda0 100644 --- a/sched/pthread/pthread_mutexunlock.c +++ b/sched/pthread/pthread_mutexunlock.c @@ -85,27 +85,54 @@ int pthread_mutex_unlock(FAR pthread_mutex_t *mutex) sinfo("mutex=0x%p\n", mutex); DEBUGASSERT(mutex != NULL); + /* Make sure the semaphore is stable while we make the following checks. + * This all needs to be one atomic action. + */ + + sched_lock(); if (mutex != NULL) { - /* Make sure the semaphore is stable while we make the following - * checks. This all needs to be one atomic action. +#if !defined(CONFIG_PTHREAD_MUTEX_UNSAFE) || defined(CONFIG_MUTEX_TYPES) + /* Does the calling thread own the semaphore? If no, should we return + * an error? + * + * Error checking is always performed for ERRORCHECK and RECURSIVE + * mutex types. Error checking is only performed for NORMAL (or + * DEFAULT) mutex type if the NORMAL mutex is robust. That is either: + * + * 1. CONFIG_PTHREAD_MUTEX_ROBUST is defined, or + * 2. CONFIG_PTHREAD_MUTEX_BOTH is defined and the robust flag is set */ - sched_lock(); - -#if !defined(CONFIG_PTHREAD_MUTEX_UNSAFE) || !defined(CONFIG_MUTEX_TYPES) - /* Does the calling thread own the semaphore? Should we report the - * EPERM error? This applies to robust NORMAL (and DEFAULT) mutexes - * as well as ERRORCHECK and RECURSIVE mutexes. +#if defined(CONFIG_PTHREAD_MUTEX_ROBUST) + /* Not that error checking is always performed if the configuration has + * CONFIG_PTHREAD_MUTEX_ROBUST defined. Just check if the calling + * thread owns the semaphore. */ if (mutex->pid != (int)getpid()) -#else - /* Does the calling thread own the semaphore? Should we report the - * EPERM error? This applies to ERRORCHECK and RECURSIVE mutexes. + +#elif defined(CONFIG_PTHREAD_MUTEX_UNSAFE) && defined(CONFIG_MUTEX_TYPES) + /* If mutex types are not supported, then all mutexes are NORMAL (or + * DEFAULT). Error checking should never be performed for the + * non-robust NORMAL mutex type. */ if (mutex->type != PTHREAD_MUTEX_NORMAL && mutex->pid != (int)getpid()) + +#else /* CONFIG_PTHREAD_MUTEX_BOTH */ + /* Skip the error check if this is a non-robust NORMAL mutex */ + + bool errcheck = ((mutex->flags & _PTHREAD_MFLAGS_ROBUST) != 0); +#ifdef CONFIG_MUTEX_TYPES + errcheck |= (mutex->type != PTHREAD_MUTEX_NORMAL); +#endif + + /* Does the calling thread own the semaphore? If not should we report + * the EPERM error? + */ + + if (errcheck && mutex->pid != (int)getpid()) #endif { /* No... return an EPERM error. @@ -123,6 +150,7 @@ int pthread_mutex_unlock(FAR pthread_mutex_t *mutex) ret = EPERM; } else +#endif /* !CONFIG_PTHREAD_MUTEX_UNSAFE || CONFIG_MUTEX_TYPES */ #ifdef CONFIG_MUTEX_TYPES /* Yes, the caller owns the semaphore.. Is this a recursive mutex? */ @@ -159,10 +187,9 @@ int pthread_mutex_unlock(FAR pthread_mutex_t *mutex) #endif ret = pthread_mutex_give(mutex); } - - sched_unlock(); } + sched_unlock(); sinfo("Returning %d\n", ret); return ret; } -- GitLab From b07d3fc3058cc98ffb0319166bc9f5ca73b0df5f Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 27 Mar 2017 09:08:14 -0600 Subject: [PATCH 223/990] Rename CONFIG_MUTEX_TYPES to CONFIG_PTHREAD_MUTEX_TYPES --- Documentation/NuttxUserGuide.html | 4 ++-- configs/arduino-due/nsh/defconfig | 2 +- configs/avr32dev1/nsh/defconfig | 2 +- configs/avr32dev1/ostest/defconfig | 2 +- configs/bambino-200e/netnsh/defconfig | 2 +- configs/bambino-200e/nsh/defconfig | 2 +- configs/bambino-200e/usbnsh/defconfig | 2 +- configs/c5471evm/httpd/defconfig | 2 +- configs/c5471evm/nsh/defconfig | 2 +- configs/cc3200-launchpad/nsh/defconfig | 2 +- configs/clicker2-stm32/nsh/defconfig | 2 +- configs/clicker2-stm32/usbnsh/defconfig | 2 +- configs/cloudctrl/nsh/defconfig | 2 +- configs/dk-tm4c129x/ipv6/defconfig | 2 +- configs/dk-tm4c129x/nsh/defconfig | 2 +- configs/ea3131/nsh/defconfig | 2 +- configs/ea3131/pgnsh/defconfig | 2 +- configs/ea3131/usbserial/defconfig | 2 +- configs/ea3152/ostest/defconfig | 2 +- configs/eagle100/httpd/defconfig | 2 +- configs/eagle100/nsh/defconfig | 2 +- configs/eagle100/nxflat/defconfig | 2 +- configs/efm32-g8xx-stk/nsh/defconfig | 2 +- configs/efm32gg-stk3700/nsh/defconfig | 2 +- configs/ekk-lm3s9b96/nsh/defconfig | 2 +- configs/esp32-core/nsh/defconfig | 2 +- configs/esp32-core/ostest/defconfig | 2 +- configs/esp32-core/smp/defconfig | 2 +- configs/ez80f910200zco/httpd/defconfig | 2 +- configs/ez80f910200zco/nsh/defconfig | 2 +- configs/ez80f910200zco/poll/defconfig | 2 +- configs/fire-stm32v2/nsh/defconfig | 2 +- configs/freedom-k64f/netnsh/defconfig | 2 +- configs/freedom-k64f/nsh/defconfig | 2 +- configs/freedom-k66f/netnsh/defconfig | 2 +- configs/freedom-k66f/nsh/defconfig | 2 +- configs/freedom-kl25z/nsh/defconfig | 2 +- configs/freedom-kl26z/nsh/defconfig | 2 +- configs/hymini-stm32v/nsh/defconfig | 2 +- configs/hymini-stm32v/nsh2/defconfig | 2 +- configs/hymini-stm32v/usbmsc/defconfig | 2 +- configs/hymini-stm32v/usbnsh/defconfig | 2 +- configs/hymini-stm32v/usbserial/defconfig | 2 +- configs/kwikstik-k40/ostest/defconfig | 2 +- configs/launchxl-tms57004/nsh/defconfig | 2 +- configs/lincoln60/netnsh/defconfig | 2 +- configs/lincoln60/nsh/defconfig | 2 +- configs/lm3s6432-s2e/nsh/defconfig | 2 +- configs/lm3s6965-ek/discover/defconfig | 2 +- configs/lm3s6965-ek/nsh/defconfig | 2 +- configs/lm3s6965-ek/nx/defconfig | 2 +- configs/lm3s6965-ek/tcpecho/defconfig | 2 +- configs/lm3s8962-ek/nsh/defconfig | 2 +- configs/lm3s8962-ek/nx/defconfig | 2 +- configs/lm4f120-launchpad/nsh/defconfig | 2 +- configs/lpc4330-xplorer/nsh/defconfig | 2 +- configs/lpc4337-ws/nsh/defconfig | 2 +- configs/lpc4357-evb/nsh/defconfig | 2 +- configs/lpc4370-link2/nsh/defconfig | 2 +- configs/lpcxpresso-lpc1115/nsh/defconfig | 2 +- configs/lpcxpresso-lpc1768/nsh/defconfig | 2 +- configs/lpcxpresso-lpc1768/nx/defconfig | 2 +- configs/lpcxpresso-lpc1768/usbmsc/defconfig | 2 +- configs/maple/nsh/defconfig | 2 +- configs/maple/nx/defconfig | 2 +- configs/maple/usbnsh/defconfig | 2 +- configs/mbed/nsh/defconfig | 2 +- configs/mcu123-lpc214x/composite/defconfig | 2 +- configs/mcu123-lpc214x/nsh/defconfig | 2 +- configs/mcu123-lpc214x/usbmsc/defconfig | 2 +- configs/mcu123-lpc214x/usbserial/defconfig | 2 +- configs/mikroe-stm32f4/fulldemo/defconfig | 2 +- configs/mikroe-stm32f4/kostest/defconfig | 2 +- configs/mikroe-stm32f4/nsh/defconfig | 2 +- configs/mikroe-stm32f4/nx/defconfig | 2 +- configs/mikroe-stm32f4/nxlines/defconfig | 2 +- configs/mikroe-stm32f4/nxtext/defconfig | 2 +- configs/mikroe-stm32f4/usbnsh/defconfig | 2 +- configs/mirtoo/nsh/defconfig | 2 +- configs/misoc/hello/defconfig | 2 +- configs/moxa/nsh/defconfig | 2 +- configs/mx1ads/ostest/defconfig | 2 +- configs/nr5m100-nexys4/nsh/defconfig | 2 +- configs/ntosd-dm320/nsh/defconfig | 2 +- configs/ntosd-dm320/poll/defconfig | 2 +- configs/ntosd-dm320/webserver/defconfig | 2 +- configs/nucleo-144/f746-evalos/defconfig | 2 +- configs/nucleo-144/f746-nsh/defconfig | 2 +- configs/nucleo-144/f767-evalos/defconfig | 2 +- configs/nucleo-144/f767-nsh/defconfig | 2 +- configs/nucleo-f303re/adc/defconfig | 2 +- configs/nucleo-f303re/can/defconfig | 2 +- configs/nucleo-f303re/hello/defconfig | 2 +- configs/nucleo-f303re/nxlines/defconfig | 2 +- configs/nucleo-f303re/pwm/defconfig | 2 +- configs/nucleo-f303re/serialrx/defconfig | 2 +- configs/nucleo-f303re/uavcan/defconfig | 2 +- configs/nucleo-f4x1re/f401-nsh/defconfig | 2 +- configs/nucleo-f4x1re/f411-nsh/defconfig | 2 +- configs/nucleo-l476rg/nsh/defconfig | 2 +- configs/nutiny-nuc120/nsh/defconfig | 2 +- configs/olimex-efm32g880f128-stk/nsh/defconfig | 2 +- configs/olimex-lpc-h3131/nsh/defconfig | 2 +- configs/olimex-lpc1766stk/ftpc/defconfig | 2 +- configs/olimex-lpc1766stk/hidmouse/defconfig | 2 +- configs/olimex-lpc1766stk/nsh/defconfig | 2 +- configs/olimex-lpc1766stk/nx/defconfig | 2 +- configs/olimex-lpc1766stk/usbmsc/defconfig | 2 +- configs/olimex-lpc1766stk/usbserial/defconfig | 2 +- configs/olimex-lpc1766stk/zmodem/defconfig | 2 +- configs/olimex-lpc2378/nsh/defconfig | 2 +- configs/olimex-stm32-e407/discover/defconfig | 2 +- configs/olimex-stm32-e407/netnsh/defconfig | 2 +- configs/olimex-stm32-e407/nsh/defconfig | 2 +- configs/olimex-stm32-e407/telnetd/defconfig | 2 +- configs/olimex-stm32-e407/usbnsh/defconfig | 2 +- configs/olimex-stm32-e407/webserver/defconfig | 2 +- configs/olimex-stm32-h405/usbnsh/defconfig | 2 +- configs/olimex-stm32-h407/nsh/defconfig | 2 +- configs/olimex-stm32-p107/nsh/defconfig | 2 +- configs/olimex-stm32-p207/nsh/defconfig | 2 +- configs/olimex-stm32-p407/knsh/defconfig | 2 +- configs/olimex-stm32-p407/nsh/defconfig | 2 +- configs/olimex-strp711/nettest/defconfig | 2 +- configs/olimex-strp711/nsh/defconfig | 2 +- configs/olimexino-stm32/can/defconfig | 2 +- configs/olimexino-stm32/composite/defconfig | 2 +- configs/olimexino-stm32/nsh/defconfig | 2 +- configs/olimexino-stm32/smallnsh/defconfig | 2 +- configs/olimexino-stm32/tiny/defconfig | 2 +- configs/open1788/knsh/defconfig | 2 +- configs/open1788/nsh/defconfig | 2 +- configs/open1788/nxlines/defconfig | 2 +- configs/p112/ostest/defconfig | 2 +- configs/pcblogic-pic32mx/nsh/defconfig | 2 +- configs/pcduino-a10/nsh/defconfig | 2 +- configs/photon/nsh/defconfig | 2 +- configs/photon/usbnsh/defconfig | 2 +- configs/pic32mx-starterkit/nsh/defconfig | 2 +- configs/pic32mx-starterkit/nsh2/defconfig | 2 +- configs/pic32mx7mmb/nsh/defconfig | 2 +- configs/pic32mz-starterkit/nsh/defconfig | 2 +- configs/qemu-i486/nsh/defconfig | 2 +- configs/qemu-i486/ostest/defconfig | 2 +- configs/sabre-6quad/nsh/defconfig | 2 +- configs/sabre-6quad/smp/defconfig | 2 +- configs/sam3u-ek/knsh/defconfig | 2 +- configs/sam3u-ek/nsh/defconfig | 2 +- configs/sam3u-ek/nx/defconfig | 2 +- configs/sam3u-ek/nxwm/defconfig | 2 +- configs/sam4cmp-db/nsh/defconfig | 2 +- configs/sam4e-ek/nsh/defconfig | 2 +- configs/sam4e-ek/nxwm/defconfig | 2 +- configs/sam4e-ek/usbnsh/defconfig | 2 +- configs/sam4l-xplained/nsh/defconfig | 2 +- configs/sam4s-xplained-pro/nsh/defconfig | 2 +- configs/sam4s-xplained/nsh/defconfig | 2 +- configs/sama5d2-xult/nsh/defconfig | 2 +- configs/sama5d3-xplained/bridge/defconfig | 2 +- configs/sama5d3-xplained/nsh/defconfig | 2 +- configs/sama5d3x-ek/demo/defconfig | 2 +- configs/sama5d3x-ek/hello/defconfig | 2 +- configs/sama5d3x-ek/norboot/defconfig | 2 +- configs/sama5d3x-ek/nsh/defconfig | 2 +- configs/sama5d3x-ek/nx/defconfig | 2 +- configs/sama5d3x-ek/nxplayer/defconfig | 2 +- configs/sama5d3x-ek/nxwm/defconfig | 2 +- configs/sama5d3x-ek/ov2640/defconfig | 2 +- configs/sama5d4-ek/at25boot/defconfig | 2 +- configs/sama5d4-ek/bridge/defconfig | 2 +- configs/sama5d4-ek/dramboot/defconfig | 2 +- configs/sama5d4-ek/elf/defconfig | 2 +- configs/sama5d4-ek/ipv6/defconfig | 2 +- configs/sama5d4-ek/knsh/defconfig | 2 +- configs/sama5d4-ek/knsh/defconfig.ROMFS | 2 +- configs/sama5d4-ek/nsh/defconfig | 2 +- configs/sama5d4-ek/nxwm/defconfig | 2 +- configs/sama5d4-ek/ramtest/defconfig | 2 +- configs/samd20-xplained/nsh/defconfig | 2 +- configs/samd21-xplained/nsh/defconfig | 2 +- configs/same70-xplained/netnsh/defconfig | 2 +- configs/same70-xplained/nsh/defconfig | 2 +- configs/saml21-xplained/nsh/defconfig | 2 +- configs/samv71-xult/knsh/defconfig | 2 +- configs/samv71-xult/module/defconfig | 2 +- configs/samv71-xult/mxtxplnd/defconfig | 2 +- configs/samv71-xult/netnsh/defconfig | 2 +- configs/samv71-xult/nsh/defconfig | 2 +- configs/samv71-xult/nxwm/defconfig | 2 +- configs/samv71-xult/vnc/defconfig | 2 +- configs/samv71-xult/vnxwm/defconfig | 2 +- configs/shenzhou/nsh/defconfig | 2 +- configs/shenzhou/nxwm/defconfig | 2 +- configs/shenzhou/thttpd/defconfig | 2 +- configs/sim/bas/defconfig | 2 +- configs/sim/cxxtest/defconfig | 2 +- configs/sim/minibasic/defconfig | 2 +- configs/sim/mount/defconfig | 2 +- configs/sim/mtdrwb/defconfig | 2 +- configs/sim/nettest/defconfig | 2 +- configs/sim/nsh/defconfig | 2 +- configs/sim/nsh2/defconfig | 2 +- configs/sim/nx/defconfig | 2 +- configs/sim/nx11/defconfig | 2 +- configs/sim/nxlines/defconfig | 2 +- configs/sim/nxwm/defconfig | 2 +- configs/sim/ostest/defconfig | 2 +- configs/sim/pashello/defconfig | 2 +- configs/sim/touchscreen/defconfig | 2 +- configs/sim/traveler/defconfig | 2 +- configs/sim/udgram/defconfig | 2 +- configs/sim/unionfs/defconfig | 2 +- configs/sim/ustream/defconfig | 2 +- configs/skp16c26/ostest/defconfig | 2 +- configs/spark/composite/defconfig | 2 +- configs/spark/nsh/defconfig | 2 +- configs/spark/usbmsc/defconfig | 2 +- configs/spark/usbnsh/defconfig | 2 +- configs/spark/usbserial/defconfig | 2 +- configs/stm3210e-eval/composite/defconfig | 2 +- configs/stm3210e-eval/nsh/defconfig | 2 +- configs/stm3210e-eval/nsh2/defconfig | 2 +- configs/stm3210e-eval/nx/defconfig | 2 +- configs/stm3210e-eval/nxterm/defconfig | 2 +- configs/stm3210e-eval/pm/defconfig | 2 +- configs/stm3210e-eval/usbmsc/defconfig | 2 +- configs/stm3210e-eval/usbserial/defconfig | 2 +- configs/stm3220g-eval/nsh/defconfig | 2 +- configs/stm3220g-eval/nsh2/defconfig | 2 +- configs/stm3220g-eval/nxwm/defconfig | 2 +- configs/stm3240g-eval/discover/defconfig | 2 +- configs/stm3240g-eval/knxwm/defconfig | 2 +- configs/stm3240g-eval/nsh/defconfig | 2 +- configs/stm3240g-eval/nsh2/defconfig | 2 +- configs/stm3240g-eval/nxterm/defconfig | 2 +- configs/stm3240g-eval/nxwm/defconfig | 2 +- configs/stm3240g-eval/webserver/defconfig | 2 +- configs/stm3240g-eval/xmlrpc/defconfig | 2 +- configs/stm32_tiny/nsh/defconfig | 2 +- configs/stm32_tiny/usbnsh/defconfig | 2 +- configs/stm32butterfly2/nsh/defconfig | 2 +- configs/stm32butterfly2/nshnet/defconfig | 2 +- configs/stm32butterfly2/nshusbdev/defconfig | 2 +- configs/stm32butterfly2/nshusbhost/defconfig | 2 +- configs/stm32f103-minimum/audio_tone/defconfig | 2 +- configs/stm32f103-minimum/buttons/defconfig | 2 +- configs/stm32f103-minimum/jlx12864g/defconfig | 2 +- configs/stm32f103-minimum/nrf24/defconfig | 2 +- configs/stm32f103-minimum/nsh/defconfig | 2 +- configs/stm32f103-minimum/pwm/defconfig | 2 +- configs/stm32f103-minimum/rfid-rc522/defconfig | 2 +- configs/stm32f103-minimum/rgbled/defconfig | 2 +- configs/stm32f103-minimum/usbnsh/defconfig | 2 +- configs/stm32f103-minimum/userled/defconfig | 2 +- configs/stm32f103-minimum/veml6070/defconfig | 2 +- configs/stm32f3discovery/nsh/defconfig | 2 +- configs/stm32f3discovery/usbnsh/defconfig | 2 +- configs/stm32f411e-disco/nsh/defconfig | 2 +- configs/stm32f429i-disco/extflash/defconfig | 2 +- configs/stm32f429i-disco/lcd/defconfig | 2 +- configs/stm32f429i-disco/ltdc/defconfig | 2 +- configs/stm32f429i-disco/nsh/defconfig | 2 +- configs/stm32f429i-disco/nxwm/defconfig | 2 +- configs/stm32f429i-disco/usbmsc/defconfig | 2 +- configs/stm32f429i-disco/usbnsh/defconfig | 2 +- configs/stm32f4discovery/canard/defconfig | 2 +- configs/stm32f4discovery/cxxtest/defconfig | 2 +- configs/stm32f4discovery/elf/defconfig | 2 +- configs/stm32f4discovery/ipv6/defconfig | 2 +- configs/stm32f4discovery/kostest/defconfig | 2 +- configs/stm32f4discovery/netnsh/defconfig | 2 +- configs/stm32f4discovery/nsh/defconfig | 2 +- configs/stm32f4discovery/nxlines/defconfig | 2 +- configs/stm32f4discovery/pm/defconfig | 2 +- configs/stm32f4discovery/posix_spawn/defconfig | 2 +- configs/stm32f4discovery/pseudoterm/defconfig | 2 +- configs/stm32f4discovery/rgbled/defconfig | 2 +- configs/stm32f4discovery/uavcan/defconfig | 2 +- configs/stm32f4discovery/usbnsh/defconfig | 2 +- configs/stm32f4discovery/winbuild/defconfig | 2 +- configs/stm32f4discovery/xen1210/defconfig | 2 +- configs/stm32f746-ws/nsh/defconfig | 2 +- configs/stm32f746g-disco/nsh/defconfig | 2 +- configs/stm32l476-mdk/nsh/defconfig | 2 +- configs/stm32l476vg-disco/nsh/defconfig | 2 +- configs/stm32ldiscovery/nsh/defconfig | 2 +- configs/stm32vldiscovery/nsh/defconfig | 2 +- configs/sure-pic32mx/nsh/defconfig | 2 +- configs/sure-pic32mx/usbnsh/defconfig | 2 +- configs/teensy-2.0/usbmsc/defconfig | 2 +- configs/teensy-3.x/nsh/defconfig | 2 +- configs/teensy-3.x/usbnsh/defconfig | 2 +- configs/teensy-lc/nsh/defconfig | 2 +- configs/tm4c123g-launchpad/nsh/defconfig | 2 +- configs/tm4c1294-launchpad/ipv6/defconfig | 2 +- configs/tm4c1294-launchpad/nsh/defconfig | 2 +- configs/twr-k60n512/nsh/defconfig | 2 +- configs/twr-k64f120m/netnsh/defconfig | 2 +- configs/twr-k64f120m/nsh/defconfig | 2 +- configs/u-blox-c027/nsh/defconfig | 2 +- configs/ubw32/nsh/defconfig | 2 +- configs/viewtool-stm32f107/highpri/defconfig | 2 +- configs/viewtool-stm32f107/netnsh/defconfig | 2 +- configs/viewtool-stm32f107/nsh/defconfig | 2 +- configs/xmc4500-relax/nsh/defconfig | 2 +- configs/xtrs/nsh/defconfig | 2 +- configs/xtrs/ostest/defconfig | 2 +- configs/xtrs/pashello/defconfig | 2 +- configs/z16f2800100zcog/nsh/defconfig | 2 +- configs/z16f2800100zcog/ostest/defconfig | 2 +- configs/z16f2800100zcog/pashello/defconfig | 2 +- configs/z80sim/nsh/defconfig | 2 +- configs/z80sim/ostest/defconfig | 2 +- configs/z80sim/pashello/defconfig | 2 +- configs/zkit-arm-1769/nsh/defconfig | 2 +- configs/zkit-arm-1769/nxhello/defconfig | 2 +- configs/zp214xpa/nsh/defconfig | 2 +- configs/zp214xpa/nxlines/defconfig | 2 +- include/pthread.h | 6 +++--- libc/libc.csv | 4 ++-- libc/pthread/pthread_mutexattr_gettype.c | 2 +- libc/pthread/pthread_mutexattr_init.c | 2 +- libc/pthread/pthread_mutexattr_settype.c | 2 +- sched/Kconfig | 2 +- sched/pthread/pthread.h | 2 +- sched/pthread/pthread_mutexconsistent.c | 2 +- sched/pthread/pthread_mutexinit.c | 6 +++--- sched/pthread/pthread_mutexlock.c | 12 ++++++------ sched/pthread/pthread_mutextrylock.c | 10 +++++----- sched/pthread/pthread_mutexunlock.c | 14 +++++++------- 330 files changed, 351 insertions(+), 351 deletions(-) diff --git a/Documentation/NuttxUserGuide.html b/Documentation/NuttxUserGuide.html index 2a1109cdb7..1fc401217f 100644 --- a/Documentation/NuttxUserGuide.html +++ b/Documentation/NuttxUserGuide.html @@ -7037,7 +7037,7 @@ interface of the same name.

     #include <pthread.h>
-#ifdef CONFIG_MUTEX_TYPES
+#ifdef CONFIG_PTHREAD_MUTEX_TYPES
     int pthread_mutexattr_gettype(const pthread_mutexattr_t *attr, int *type);
 #endif
 
@@ -7072,7 +7072,7 @@ returned to indicate the error:

     #include <pthread.h>
-#ifdef CONFIG_MUTEX_TYPES
+#ifdef CONFIG_PTHREAD_MUTEX_TYPES
     int pthread_mutexattr_settype(pthread_mutexattr_t *attr, int type);
 #endif
 
diff --git a/configs/arduino-due/nsh/defconfig b/configs/arduino-due/nsh/defconfig index b41d96a19d..385592ef19 100644 --- a/configs/arduino-due/nsh/defconfig +++ b/configs/arduino-due/nsh/defconfig @@ -392,7 +392,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/avr32dev1/nsh/defconfig b/configs/avr32dev1/nsh/defconfig index 0536c98a8e..a7e210c221 100644 --- a/configs/avr32dev1/nsh/defconfig +++ b/configs/avr32dev1/nsh/defconfig @@ -242,7 +242,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/avr32dev1/ostest/defconfig b/configs/avr32dev1/ostest/defconfig index 1d47dd30b7..dfdd5a037d 100644 --- a/configs/avr32dev1/ostest/defconfig +++ b/configs/avr32dev1/ostest/defconfig @@ -242,7 +242,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/bambino-200e/netnsh/defconfig b/configs/bambino-200e/netnsh/defconfig index 55267ea9e9..d23e6e4685 100644 --- a/configs/bambino-200e/netnsh/defconfig +++ b/configs/bambino-200e/netnsh/defconfig @@ -400,7 +400,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/bambino-200e/nsh/defconfig b/configs/bambino-200e/nsh/defconfig index 4f62a210c2..61a12d8769 100644 --- a/configs/bambino-200e/nsh/defconfig +++ b/configs/bambino-200e/nsh/defconfig @@ -385,7 +385,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/bambino-200e/usbnsh/defconfig b/configs/bambino-200e/usbnsh/defconfig index 46a155e47e..c6047a9771 100644 --- a/configs/bambino-200e/usbnsh/defconfig +++ b/configs/bambino-200e/usbnsh/defconfig @@ -385,7 +385,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/c5471evm/httpd/defconfig b/configs/c5471evm/httpd/defconfig index 35ccf58008..6014c6ffda 100644 --- a/configs/c5471evm/httpd/defconfig +++ b/configs/c5471evm/httpd/defconfig @@ -288,7 +288,7 @@ CONFIG_MAX_TASKS=64 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/c5471evm/nsh/defconfig b/configs/c5471evm/nsh/defconfig index fce9fd4940..e0cf04b541 100644 --- a/configs/c5471evm/nsh/defconfig +++ b/configs/c5471evm/nsh/defconfig @@ -288,7 +288,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/cc3200-launchpad/nsh/defconfig b/configs/cc3200-launchpad/nsh/defconfig index 2be216cfef..27e88311f6 100644 --- a/configs/cc3200-launchpad/nsh/defconfig +++ b/configs/cc3200-launchpad/nsh/defconfig @@ -351,7 +351,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/clicker2-stm32/nsh/defconfig b/configs/clicker2-stm32/nsh/defconfig index d13af3965b..355a7217d1 100644 --- a/configs/clicker2-stm32/nsh/defconfig +++ b/configs/clicker2-stm32/nsh/defconfig @@ -651,7 +651,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/clicker2-stm32/usbnsh/defconfig b/configs/clicker2-stm32/usbnsh/defconfig index 32bf16050c..fda0234f36 100644 --- a/configs/clicker2-stm32/usbnsh/defconfig +++ b/configs/clicker2-stm32/usbnsh/defconfig @@ -652,7 +652,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/cloudctrl/nsh/defconfig b/configs/cloudctrl/nsh/defconfig index 0f138988ec..e39a9ca326 100644 --- a/configs/cloudctrl/nsh/defconfig +++ b/configs/cloudctrl/nsh/defconfig @@ -661,7 +661,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/dk-tm4c129x/ipv6/defconfig b/configs/dk-tm4c129x/ipv6/defconfig index 328b1ffd43..8cb7e11ce0 100644 --- a/configs/dk-tm4c129x/ipv6/defconfig +++ b/configs/dk-tm4c129x/ipv6/defconfig @@ -418,7 +418,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/dk-tm4c129x/nsh/defconfig b/configs/dk-tm4c129x/nsh/defconfig index 1032d72580..fed79d510e 100644 --- a/configs/dk-tm4c129x/nsh/defconfig +++ b/configs/dk-tm4c129x/nsh/defconfig @@ -418,7 +418,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/ea3131/nsh/defconfig b/configs/ea3131/nsh/defconfig index 06faf8210d..bcffd2bb37 100644 --- a/configs/ea3131/nsh/defconfig +++ b/configs/ea3131/nsh/defconfig @@ -311,7 +311,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/ea3131/pgnsh/defconfig b/configs/ea3131/pgnsh/defconfig index 205056e5c2..737846f7cf 100644 --- a/configs/ea3131/pgnsh/defconfig +++ b/configs/ea3131/pgnsh/defconfig @@ -331,7 +331,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/ea3131/usbserial/defconfig b/configs/ea3131/usbserial/defconfig index 16133499cc..b3e3461856 100644 --- a/configs/ea3131/usbserial/defconfig +++ b/configs/ea3131/usbserial/defconfig @@ -320,7 +320,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/ea3152/ostest/defconfig b/configs/ea3152/ostest/defconfig index 765553c8ed..3703c51789 100644 --- a/configs/ea3152/ostest/defconfig +++ b/configs/ea3152/ostest/defconfig @@ -307,7 +307,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/eagle100/httpd/defconfig b/configs/eagle100/httpd/defconfig index a1685a22e9..6b21f72a9f 100644 --- a/configs/eagle100/httpd/defconfig +++ b/configs/eagle100/httpd/defconfig @@ -392,7 +392,7 @@ CONFIG_MAX_TASKS=8 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/eagle100/nsh/defconfig b/configs/eagle100/nsh/defconfig index 5c9b615143..c7c0b278c5 100644 --- a/configs/eagle100/nsh/defconfig +++ b/configs/eagle100/nsh/defconfig @@ -397,7 +397,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/eagle100/nxflat/defconfig b/configs/eagle100/nxflat/defconfig index 6b1e90c7c9..17496d0a84 100644 --- a/configs/eagle100/nxflat/defconfig +++ b/configs/eagle100/nxflat/defconfig @@ -377,7 +377,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/efm32-g8xx-stk/nsh/defconfig b/configs/efm32-g8xx-stk/nsh/defconfig index 7d27d8a477..2b7cf9f9f8 100644 --- a/configs/efm32-g8xx-stk/nsh/defconfig +++ b/configs/efm32-g8xx-stk/nsh/defconfig @@ -342,7 +342,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/efm32gg-stk3700/nsh/defconfig b/configs/efm32gg-stk3700/nsh/defconfig index b52a063e1c..ea429d6a69 100644 --- a/configs/efm32gg-stk3700/nsh/defconfig +++ b/configs/efm32gg-stk3700/nsh/defconfig @@ -342,7 +342,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/ekk-lm3s9b96/nsh/defconfig b/configs/ekk-lm3s9b96/nsh/defconfig index 970a1bd97a..5439a38cfb 100644 --- a/configs/ekk-lm3s9b96/nsh/defconfig +++ b/configs/ekk-lm3s9b96/nsh/defconfig @@ -384,7 +384,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/esp32-core/nsh/defconfig b/configs/esp32-core/nsh/defconfig index b8b3ee020b..d1e291a106 100644 --- a/configs/esp32-core/nsh/defconfig +++ b/configs/esp32-core/nsh/defconfig @@ -224,7 +224,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/esp32-core/ostest/defconfig b/configs/esp32-core/ostest/defconfig index ab632aa629..4e49924f66 100644 --- a/configs/esp32-core/ostest/defconfig +++ b/configs/esp32-core/ostest/defconfig @@ -224,7 +224,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/esp32-core/smp/defconfig b/configs/esp32-core/smp/defconfig index cf95808659..90a3da7f79 100644 --- a/configs/esp32-core/smp/defconfig +++ b/configs/esp32-core/smp/defconfig @@ -226,7 +226,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/ez80f910200zco/httpd/defconfig b/configs/ez80f910200zco/httpd/defconfig index 9627243581..a969e62d1f 100644 --- a/configs/ez80f910200zco/httpd/defconfig +++ b/configs/ez80f910200zco/httpd/defconfig @@ -273,7 +273,7 @@ CONFIG_MAX_TASKS=8 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/ez80f910200zco/nsh/defconfig b/configs/ez80f910200zco/nsh/defconfig index 8fc46b9b99..e06e4044e6 100644 --- a/configs/ez80f910200zco/nsh/defconfig +++ b/configs/ez80f910200zco/nsh/defconfig @@ -273,7 +273,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/ez80f910200zco/poll/defconfig b/configs/ez80f910200zco/poll/defconfig index 4fbc368263..6f8033a9e4 100644 --- a/configs/ez80f910200zco/poll/defconfig +++ b/configs/ez80f910200zco/poll/defconfig @@ -273,7 +273,7 @@ CONFIG_MAX_TASKS=8 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/fire-stm32v2/nsh/defconfig b/configs/fire-stm32v2/nsh/defconfig index a7ec020931..3f877e06ca 100644 --- a/configs/fire-stm32v2/nsh/defconfig +++ b/configs/fire-stm32v2/nsh/defconfig @@ -670,7 +670,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/freedom-k64f/netnsh/defconfig b/configs/freedom-k64f/netnsh/defconfig index c94d75f438..6bcc276b71 100644 --- a/configs/freedom-k64f/netnsh/defconfig +++ b/configs/freedom-k64f/netnsh/defconfig @@ -413,7 +413,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/freedom-k64f/nsh/defconfig b/configs/freedom-k64f/nsh/defconfig index 83424e7838..bfbb82d082 100644 --- a/configs/freedom-k64f/nsh/defconfig +++ b/configs/freedom-k64f/nsh/defconfig @@ -408,7 +408,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/freedom-k66f/netnsh/defconfig b/configs/freedom-k66f/netnsh/defconfig index 67c13b3089..e1b82e0fa0 100644 --- a/configs/freedom-k66f/netnsh/defconfig +++ b/configs/freedom-k66f/netnsh/defconfig @@ -414,7 +414,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/freedom-k66f/nsh/defconfig b/configs/freedom-k66f/nsh/defconfig index 9605b84c9d..b6d2efa7f7 100644 --- a/configs/freedom-k66f/nsh/defconfig +++ b/configs/freedom-k66f/nsh/defconfig @@ -420,7 +420,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/freedom-kl25z/nsh/defconfig b/configs/freedom-kl25z/nsh/defconfig index 0061583e6f..84daa61608 100644 --- a/configs/freedom-kl25z/nsh/defconfig +++ b/configs/freedom-kl25z/nsh/defconfig @@ -319,7 +319,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/freedom-kl26z/nsh/defconfig b/configs/freedom-kl26z/nsh/defconfig index f54ed0d572..ba03c3d453 100644 --- a/configs/freedom-kl26z/nsh/defconfig +++ b/configs/freedom-kl26z/nsh/defconfig @@ -319,7 +319,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/hymini-stm32v/nsh/defconfig b/configs/hymini-stm32v/nsh/defconfig index 0a91779a14..1cfd9aae24 100644 --- a/configs/hymini-stm32v/nsh/defconfig +++ b/configs/hymini-stm32v/nsh/defconfig @@ -627,7 +627,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/hymini-stm32v/nsh2/defconfig b/configs/hymini-stm32v/nsh2/defconfig index fa837c2327..7d534b9ca1 100644 --- a/configs/hymini-stm32v/nsh2/defconfig +++ b/configs/hymini-stm32v/nsh2/defconfig @@ -646,7 +646,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/hymini-stm32v/usbmsc/defconfig b/configs/hymini-stm32v/usbmsc/defconfig index d80cc63e6f..93b6e551bd 100644 --- a/configs/hymini-stm32v/usbmsc/defconfig +++ b/configs/hymini-stm32v/usbmsc/defconfig @@ -633,7 +633,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/hymini-stm32v/usbnsh/defconfig b/configs/hymini-stm32v/usbnsh/defconfig index dc1652e6bd..934d297d66 100644 --- a/configs/hymini-stm32v/usbnsh/defconfig +++ b/configs/hymini-stm32v/usbnsh/defconfig @@ -620,7 +620,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/hymini-stm32v/usbserial/defconfig b/configs/hymini-stm32v/usbserial/defconfig index e1c0a80dc3..26e7fc63f2 100644 --- a/configs/hymini-stm32v/usbserial/defconfig +++ b/configs/hymini-stm32v/usbserial/defconfig @@ -624,7 +624,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/kwikstik-k40/ostest/defconfig b/configs/kwikstik-k40/ostest/defconfig index 874390fb7a..a4f8844e57 100644 --- a/configs/kwikstik-k40/ostest/defconfig +++ b/configs/kwikstik-k40/ostest/defconfig @@ -380,7 +380,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/launchxl-tms57004/nsh/defconfig b/configs/launchxl-tms57004/nsh/defconfig index c13d511f8a..c0ec78af86 100644 --- a/configs/launchxl-tms57004/nsh/defconfig +++ b/configs/launchxl-tms57004/nsh/defconfig @@ -309,7 +309,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lincoln60/netnsh/defconfig b/configs/lincoln60/netnsh/defconfig index 06961522e4..5f1c7134d2 100644 --- a/configs/lincoln60/netnsh/defconfig +++ b/configs/lincoln60/netnsh/defconfig @@ -375,7 +375,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lincoln60/nsh/defconfig b/configs/lincoln60/nsh/defconfig index a7f5e64b13..9a031ae641 100644 --- a/configs/lincoln60/nsh/defconfig +++ b/configs/lincoln60/nsh/defconfig @@ -353,7 +353,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lm3s6432-s2e/nsh/defconfig b/configs/lm3s6432-s2e/nsh/defconfig index e258aec958..0f700344cf 100644 --- a/configs/lm3s6432-s2e/nsh/defconfig +++ b/configs/lm3s6432-s2e/nsh/defconfig @@ -379,7 +379,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lm3s6965-ek/discover/defconfig b/configs/lm3s6965-ek/discover/defconfig index bdf565b3a6..8921e6a294 100644 --- a/configs/lm3s6965-ek/discover/defconfig +++ b/configs/lm3s6965-ek/discover/defconfig @@ -389,7 +389,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lm3s6965-ek/nsh/defconfig b/configs/lm3s6965-ek/nsh/defconfig index bdf565b3a6..8921e6a294 100644 --- a/configs/lm3s6965-ek/nsh/defconfig +++ b/configs/lm3s6965-ek/nsh/defconfig @@ -389,7 +389,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lm3s6965-ek/nx/defconfig b/configs/lm3s6965-ek/nx/defconfig index 4a54e8007f..5ca268e751 100644 --- a/configs/lm3s6965-ek/nx/defconfig +++ b/configs/lm3s6965-ek/nx/defconfig @@ -374,7 +374,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lm3s6965-ek/tcpecho/defconfig b/configs/lm3s6965-ek/tcpecho/defconfig index 2efa710813..f790652e65 100644 --- a/configs/lm3s6965-ek/tcpecho/defconfig +++ b/configs/lm3s6965-ek/tcpecho/defconfig @@ -378,7 +378,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lm3s8962-ek/nsh/defconfig b/configs/lm3s8962-ek/nsh/defconfig index 58a8f095ca..479e2b826f 100644 --- a/configs/lm3s8962-ek/nsh/defconfig +++ b/configs/lm3s8962-ek/nsh/defconfig @@ -401,7 +401,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lm3s8962-ek/nx/defconfig b/configs/lm3s8962-ek/nx/defconfig index 8c343bd1c6..bc2a3da9a6 100644 --- a/configs/lm3s8962-ek/nx/defconfig +++ b/configs/lm3s8962-ek/nx/defconfig @@ -386,7 +386,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lm4f120-launchpad/nsh/defconfig b/configs/lm4f120-launchpad/nsh/defconfig index 6f02848283..330e7b0e64 100644 --- a/configs/lm4f120-launchpad/nsh/defconfig +++ b/configs/lm4f120-launchpad/nsh/defconfig @@ -383,7 +383,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lpc4330-xplorer/nsh/defconfig b/configs/lpc4330-xplorer/nsh/defconfig index 89bc4fa73a..958f82ea84 100644 --- a/configs/lpc4330-xplorer/nsh/defconfig +++ b/configs/lpc4330-xplorer/nsh/defconfig @@ -386,7 +386,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lpc4337-ws/nsh/defconfig b/configs/lpc4337-ws/nsh/defconfig index 067cffc7ee..902865fca2 100644 --- a/configs/lpc4337-ws/nsh/defconfig +++ b/configs/lpc4337-ws/nsh/defconfig @@ -391,7 +391,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lpc4357-evb/nsh/defconfig b/configs/lpc4357-evb/nsh/defconfig index bd1bcc04c5..c02e95b9ad 100644 --- a/configs/lpc4357-evb/nsh/defconfig +++ b/configs/lpc4357-evb/nsh/defconfig @@ -377,7 +377,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lpc4370-link2/nsh/defconfig b/configs/lpc4370-link2/nsh/defconfig index 9a8ae1315d..e6dd94324c 100644 --- a/configs/lpc4370-link2/nsh/defconfig +++ b/configs/lpc4370-link2/nsh/defconfig @@ -387,7 +387,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lpcxpresso-lpc1115/nsh/defconfig b/configs/lpcxpresso-lpc1115/nsh/defconfig index d38217dc0a..1aac33b678 100644 --- a/configs/lpcxpresso-lpc1115/nsh/defconfig +++ b/configs/lpcxpresso-lpc1115/nsh/defconfig @@ -291,7 +291,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lpcxpresso-lpc1768/nsh/defconfig b/configs/lpcxpresso-lpc1768/nsh/defconfig index 981c237dc0..aebe91afd8 100644 --- a/configs/lpcxpresso-lpc1768/nsh/defconfig +++ b/configs/lpcxpresso-lpc1768/nsh/defconfig @@ -365,7 +365,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lpcxpresso-lpc1768/nx/defconfig b/configs/lpcxpresso-lpc1768/nx/defconfig index f8991bb731..41f8e7270d 100644 --- a/configs/lpcxpresso-lpc1768/nx/defconfig +++ b/configs/lpcxpresso-lpc1768/nx/defconfig @@ -353,7 +353,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lpcxpresso-lpc1768/usbmsc/defconfig b/configs/lpcxpresso-lpc1768/usbmsc/defconfig index 4258e43386..bb8b759084 100644 --- a/configs/lpcxpresso-lpc1768/usbmsc/defconfig +++ b/configs/lpcxpresso-lpc1768/usbmsc/defconfig @@ -365,7 +365,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/maple/nsh/defconfig b/configs/maple/nsh/defconfig index d5707caf97..5a9f920921 100644 --- a/configs/maple/nsh/defconfig +++ b/configs/maple/nsh/defconfig @@ -608,7 +608,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/maple/nx/defconfig b/configs/maple/nx/defconfig index 4badf8cce0..7a3e615430 100644 --- a/configs/maple/nx/defconfig +++ b/configs/maple/nx/defconfig @@ -639,7 +639,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/maple/usbnsh/defconfig b/configs/maple/usbnsh/defconfig index 4b61b62be7..b74195b592 100644 --- a/configs/maple/usbnsh/defconfig +++ b/configs/maple/usbnsh/defconfig @@ -614,7 +614,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/mbed/nsh/defconfig b/configs/mbed/nsh/defconfig index 91040faa58..8a252652ba 100644 --- a/configs/mbed/nsh/defconfig +++ b/configs/mbed/nsh/defconfig @@ -354,7 +354,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/mcu123-lpc214x/composite/defconfig b/configs/mcu123-lpc214x/composite/defconfig index 1867544145..e332f48619 100644 --- a/configs/mcu123-lpc214x/composite/defconfig +++ b/configs/mcu123-lpc214x/composite/defconfig @@ -302,7 +302,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/mcu123-lpc214x/nsh/defconfig b/configs/mcu123-lpc214x/nsh/defconfig index 602812eff3..b9af89a29b 100644 --- a/configs/mcu123-lpc214x/nsh/defconfig +++ b/configs/mcu123-lpc214x/nsh/defconfig @@ -292,7 +292,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/mcu123-lpc214x/usbmsc/defconfig b/configs/mcu123-lpc214x/usbmsc/defconfig index 46e3629c62..8835809819 100644 --- a/configs/mcu123-lpc214x/usbmsc/defconfig +++ b/configs/mcu123-lpc214x/usbmsc/defconfig @@ -302,7 +302,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/mcu123-lpc214x/usbserial/defconfig b/configs/mcu123-lpc214x/usbserial/defconfig index cbfecf5e66..fd0b0a3db1 100644 --- a/configs/mcu123-lpc214x/usbserial/defconfig +++ b/configs/mcu123-lpc214x/usbserial/defconfig @@ -301,7 +301,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/mikroe-stm32f4/fulldemo/defconfig b/configs/mikroe-stm32f4/fulldemo/defconfig index c41315b980..012a6452e3 100644 --- a/configs/mikroe-stm32f4/fulldemo/defconfig +++ b/configs/mikroe-stm32f4/fulldemo/defconfig @@ -669,7 +669,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/mikroe-stm32f4/kostest/defconfig b/configs/mikroe-stm32f4/kostest/defconfig index 627f3da390..28e61f6c2d 100644 --- a/configs/mikroe-stm32f4/kostest/defconfig +++ b/configs/mikroe-stm32f4/kostest/defconfig @@ -671,7 +671,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/mikroe-stm32f4/nsh/defconfig b/configs/mikroe-stm32f4/nsh/defconfig index 8389737436..fa6618f860 100644 --- a/configs/mikroe-stm32f4/nsh/defconfig +++ b/configs/mikroe-stm32f4/nsh/defconfig @@ -647,7 +647,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/mikroe-stm32f4/nx/defconfig b/configs/mikroe-stm32f4/nx/defconfig index 397c14892e..ddfed5178c 100644 --- a/configs/mikroe-stm32f4/nx/defconfig +++ b/configs/mikroe-stm32f4/nx/defconfig @@ -620,7 +620,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/mikroe-stm32f4/nxlines/defconfig b/configs/mikroe-stm32f4/nxlines/defconfig index 9c806f8868..3d4824dece 100644 --- a/configs/mikroe-stm32f4/nxlines/defconfig +++ b/configs/mikroe-stm32f4/nxlines/defconfig @@ -620,7 +620,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/mikroe-stm32f4/nxtext/defconfig b/configs/mikroe-stm32f4/nxtext/defconfig index ae61dcf829..9436d9681c 100644 --- a/configs/mikroe-stm32f4/nxtext/defconfig +++ b/configs/mikroe-stm32f4/nxtext/defconfig @@ -620,7 +620,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/mikroe-stm32f4/usbnsh/defconfig b/configs/mikroe-stm32f4/usbnsh/defconfig index 3a15a1f7df..86407369f4 100644 --- a/configs/mikroe-stm32f4/usbnsh/defconfig +++ b/configs/mikroe-stm32f4/usbnsh/defconfig @@ -655,7 +655,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/mirtoo/nsh/defconfig b/configs/mirtoo/nsh/defconfig index 287646a85d..1a2ba210f0 100644 --- a/configs/mirtoo/nsh/defconfig +++ b/configs/mirtoo/nsh/defconfig @@ -383,7 +383,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/misoc/hello/defconfig b/configs/misoc/hello/defconfig index bcd0724148..a0a54eceef 100644 --- a/configs/misoc/hello/defconfig +++ b/configs/misoc/hello/defconfig @@ -236,7 +236,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/moxa/nsh/defconfig b/configs/moxa/nsh/defconfig index 5d8bf233e3..f697f4e4fc 100644 --- a/configs/moxa/nsh/defconfig +++ b/configs/moxa/nsh/defconfig @@ -268,7 +268,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/mx1ads/ostest/defconfig b/configs/mx1ads/ostest/defconfig index 4885086e8e..351c5d15ef 100644 --- a/configs/mx1ads/ostest/defconfig +++ b/configs/mx1ads/ostest/defconfig @@ -273,7 +273,7 @@ CONFIG_MAX_TASKS=64 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/nr5m100-nexys4/nsh/defconfig b/configs/nr5m100-nexys4/nsh/defconfig index cd3d16c67b..9ad1b3ba9d 100644 --- a/configs/nr5m100-nexys4/nsh/defconfig +++ b/configs/nr5m100-nexys4/nsh/defconfig @@ -230,7 +230,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/ntosd-dm320/nsh/defconfig b/configs/ntosd-dm320/nsh/defconfig index 12651fcce7..cb775f31a8 100644 --- a/configs/ntosd-dm320/nsh/defconfig +++ b/configs/ntosd-dm320/nsh/defconfig @@ -270,7 +270,7 @@ CONFIG_MAX_TASKS=64 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/ntosd-dm320/poll/defconfig b/configs/ntosd-dm320/poll/defconfig index d7c104d42e..aa8de3c0be 100644 --- a/configs/ntosd-dm320/poll/defconfig +++ b/configs/ntosd-dm320/poll/defconfig @@ -270,7 +270,7 @@ CONFIG_MAX_TASKS=64 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/ntosd-dm320/webserver/defconfig b/configs/ntosd-dm320/webserver/defconfig index 1e5e452ceb..d2320bf672 100644 --- a/configs/ntosd-dm320/webserver/defconfig +++ b/configs/ntosd-dm320/webserver/defconfig @@ -270,7 +270,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/nucleo-144/f746-evalos/defconfig b/configs/nucleo-144/f746-evalos/defconfig index 98e5af1216..5603a1aaa2 100644 --- a/configs/nucleo-144/f746-evalos/defconfig +++ b/configs/nucleo-144/f746-evalos/defconfig @@ -489,7 +489,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/nucleo-144/f746-nsh/defconfig b/configs/nucleo-144/f746-nsh/defconfig index cabf00e30b..1a362372b1 100644 --- a/configs/nucleo-144/f746-nsh/defconfig +++ b/configs/nucleo-144/f746-nsh/defconfig @@ -489,7 +489,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/nucleo-144/f767-evalos/defconfig b/configs/nucleo-144/f767-evalos/defconfig index e2965f6489..57a3aeeed0 100644 --- a/configs/nucleo-144/f767-evalos/defconfig +++ b/configs/nucleo-144/f767-evalos/defconfig @@ -493,7 +493,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/nucleo-144/f767-nsh/defconfig b/configs/nucleo-144/f767-nsh/defconfig index e638ac71ec..c061f7f9b0 100644 --- a/configs/nucleo-144/f767-nsh/defconfig +++ b/configs/nucleo-144/f767-nsh/defconfig @@ -493,7 +493,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/nucleo-f303re/adc/defconfig b/configs/nucleo-f303re/adc/defconfig index 74668a9f05..1a8f828845 100644 --- a/configs/nucleo-f303re/adc/defconfig +++ b/configs/nucleo-f303re/adc/defconfig @@ -609,7 +609,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/nucleo-f303re/can/defconfig b/configs/nucleo-f303re/can/defconfig index f251bc9065..84d8e54188 100644 --- a/configs/nucleo-f303re/can/defconfig +++ b/configs/nucleo-f303re/can/defconfig @@ -612,7 +612,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/nucleo-f303re/hello/defconfig b/configs/nucleo-f303re/hello/defconfig index 42c6bc187b..80f265905f 100644 --- a/configs/nucleo-f303re/hello/defconfig +++ b/configs/nucleo-f303re/hello/defconfig @@ -619,7 +619,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/nucleo-f303re/nxlines/defconfig b/configs/nucleo-f303re/nxlines/defconfig index 9e7986d922..0082d94fcb 100644 --- a/configs/nucleo-f303re/nxlines/defconfig +++ b/configs/nucleo-f303re/nxlines/defconfig @@ -611,7 +611,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/nucleo-f303re/pwm/defconfig b/configs/nucleo-f303re/pwm/defconfig index c91563199f..efddd49b67 100644 --- a/configs/nucleo-f303re/pwm/defconfig +++ b/configs/nucleo-f303re/pwm/defconfig @@ -613,7 +613,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/nucleo-f303re/serialrx/defconfig b/configs/nucleo-f303re/serialrx/defconfig index 20333da3a5..88407d7671 100644 --- a/configs/nucleo-f303re/serialrx/defconfig +++ b/configs/nucleo-f303re/serialrx/defconfig @@ -624,7 +624,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/nucleo-f303re/uavcan/defconfig b/configs/nucleo-f303re/uavcan/defconfig index 9918c00815..2546b67d90 100644 --- a/configs/nucleo-f303re/uavcan/defconfig +++ b/configs/nucleo-f303re/uavcan/defconfig @@ -597,7 +597,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/nucleo-f4x1re/f401-nsh/defconfig b/configs/nucleo-f4x1re/f401-nsh/defconfig index 5783b024fc..9b043a844f 100644 --- a/configs/nucleo-f4x1re/f401-nsh/defconfig +++ b/configs/nucleo-f4x1re/f401-nsh/defconfig @@ -616,7 +616,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/nucleo-f4x1re/f411-nsh/defconfig b/configs/nucleo-f4x1re/f411-nsh/defconfig index ce765110b7..b289f3270d 100644 --- a/configs/nucleo-f4x1re/f411-nsh/defconfig +++ b/configs/nucleo-f4x1re/f411-nsh/defconfig @@ -618,7 +618,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/nucleo-l476rg/nsh/defconfig b/configs/nucleo-l476rg/nsh/defconfig index e851d0a797..3f842a38cc 100644 --- a/configs/nucleo-l476rg/nsh/defconfig +++ b/configs/nucleo-l476rg/nsh/defconfig @@ -441,7 +441,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/nutiny-nuc120/nsh/defconfig b/configs/nutiny-nuc120/nsh/defconfig index bf3c57c9f7..bb97150c70 100644 --- a/configs/nutiny-nuc120/nsh/defconfig +++ b/configs/nutiny-nuc120/nsh/defconfig @@ -343,7 +343,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-efm32g880f128-stk/nsh/defconfig b/configs/olimex-efm32g880f128-stk/nsh/defconfig index f9fab939a7..4013087ecb 100644 --- a/configs/olimex-efm32g880f128-stk/nsh/defconfig +++ b/configs/olimex-efm32g880f128-stk/nsh/defconfig @@ -336,7 +336,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-lpc-h3131/nsh/defconfig b/configs/olimex-lpc-h3131/nsh/defconfig index cb4e8d9305..a78090e013 100644 --- a/configs/olimex-lpc-h3131/nsh/defconfig +++ b/configs/olimex-lpc-h3131/nsh/defconfig @@ -309,7 +309,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-lpc1766stk/ftpc/defconfig b/configs/olimex-lpc1766stk/ftpc/defconfig index 7a855b94ca..44db4095a1 100644 --- a/configs/olimex-lpc1766stk/ftpc/defconfig +++ b/configs/olimex-lpc1766stk/ftpc/defconfig @@ -365,7 +365,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-lpc1766stk/hidmouse/defconfig b/configs/olimex-lpc1766stk/hidmouse/defconfig index 13a8958338..b278edfb1f 100644 --- a/configs/olimex-lpc1766stk/hidmouse/defconfig +++ b/configs/olimex-lpc1766stk/hidmouse/defconfig @@ -379,7 +379,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-lpc1766stk/nsh/defconfig b/configs/olimex-lpc1766stk/nsh/defconfig index 74c28f8946..2c8cf3c744 100644 --- a/configs/olimex-lpc1766stk/nsh/defconfig +++ b/configs/olimex-lpc1766stk/nsh/defconfig @@ -366,7 +366,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-lpc1766stk/nx/defconfig b/configs/olimex-lpc1766stk/nx/defconfig index c2aa80529b..bf4822c38c 100644 --- a/configs/olimex-lpc1766stk/nx/defconfig +++ b/configs/olimex-lpc1766stk/nx/defconfig @@ -364,7 +364,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-lpc1766stk/usbmsc/defconfig b/configs/olimex-lpc1766stk/usbmsc/defconfig index 75a87a0898..22e5d46346 100644 --- a/configs/olimex-lpc1766stk/usbmsc/defconfig +++ b/configs/olimex-lpc1766stk/usbmsc/defconfig @@ -366,7 +366,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-lpc1766stk/usbserial/defconfig b/configs/olimex-lpc1766stk/usbserial/defconfig index e84ff2871b..c018b34898 100644 --- a/configs/olimex-lpc1766stk/usbserial/defconfig +++ b/configs/olimex-lpc1766stk/usbserial/defconfig @@ -366,7 +366,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-lpc1766stk/zmodem/defconfig b/configs/olimex-lpc1766stk/zmodem/defconfig index f110982d33..706bf399a5 100644 --- a/configs/olimex-lpc1766stk/zmodem/defconfig +++ b/configs/olimex-lpc1766stk/zmodem/defconfig @@ -367,7 +367,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-lpc2378/nsh/defconfig b/configs/olimex-lpc2378/nsh/defconfig index 6c82afc55a..107dc433f2 100644 --- a/configs/olimex-lpc2378/nsh/defconfig +++ b/configs/olimex-lpc2378/nsh/defconfig @@ -279,7 +279,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-stm32-e407/discover/defconfig b/configs/olimex-stm32-e407/discover/defconfig index b3a6708d1c..45fe31dd49 100644 --- a/configs/olimex-stm32-e407/discover/defconfig +++ b/configs/olimex-stm32-e407/discover/defconfig @@ -664,7 +664,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-stm32-e407/netnsh/defconfig b/configs/olimex-stm32-e407/netnsh/defconfig index db9b5c84d9..34db63f2e4 100644 --- a/configs/olimex-stm32-e407/netnsh/defconfig +++ b/configs/olimex-stm32-e407/netnsh/defconfig @@ -664,7 +664,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-stm32-e407/nsh/defconfig b/configs/olimex-stm32-e407/nsh/defconfig index c5b7cc6458..a1cd1d5db7 100644 --- a/configs/olimex-stm32-e407/nsh/defconfig +++ b/configs/olimex-stm32-e407/nsh/defconfig @@ -642,7 +642,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-stm32-e407/telnetd/defconfig b/configs/olimex-stm32-e407/telnetd/defconfig index 003bbb2905..ab40706675 100644 --- a/configs/olimex-stm32-e407/telnetd/defconfig +++ b/configs/olimex-stm32-e407/telnetd/defconfig @@ -664,7 +664,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-stm32-e407/usbnsh/defconfig b/configs/olimex-stm32-e407/usbnsh/defconfig index e2079db38b..73b5b0f45a 100644 --- a/configs/olimex-stm32-e407/usbnsh/defconfig +++ b/configs/olimex-stm32-e407/usbnsh/defconfig @@ -648,7 +648,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-stm32-e407/webserver/defconfig b/configs/olimex-stm32-e407/webserver/defconfig index 4f369f8f8e..a20352448f 100644 --- a/configs/olimex-stm32-e407/webserver/defconfig +++ b/configs/olimex-stm32-e407/webserver/defconfig @@ -664,7 +664,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-stm32-h405/usbnsh/defconfig b/configs/olimex-stm32-h405/usbnsh/defconfig index 9037e4139f..e0079fda92 100644 --- a/configs/olimex-stm32-h405/usbnsh/defconfig +++ b/configs/olimex-stm32-h405/usbnsh/defconfig @@ -666,7 +666,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-stm32-h407/nsh/defconfig b/configs/olimex-stm32-h407/nsh/defconfig index 33847bcca9..fc5a113c74 100644 --- a/configs/olimex-stm32-h407/nsh/defconfig +++ b/configs/olimex-stm32-h407/nsh/defconfig @@ -642,7 +642,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-stm32-p107/nsh/defconfig b/configs/olimex-stm32-p107/nsh/defconfig index 430a2f84d7..3a77537c5c 100644 --- a/configs/olimex-stm32-p107/nsh/defconfig +++ b/configs/olimex-stm32-p107/nsh/defconfig @@ -631,7 +631,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-stm32-p207/nsh/defconfig b/configs/olimex-stm32-p207/nsh/defconfig index b4454d3756..a9b0e19e10 100644 --- a/configs/olimex-stm32-p207/nsh/defconfig +++ b/configs/olimex-stm32-p207/nsh/defconfig @@ -692,7 +692,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-stm32-p407/knsh/defconfig b/configs/olimex-stm32-p407/knsh/defconfig index 51699bf7d8..c1a5cb58bf 100644 --- a/configs/olimex-stm32-p407/knsh/defconfig +++ b/configs/olimex-stm32-p407/knsh/defconfig @@ -654,7 +654,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-stm32-p407/nsh/defconfig b/configs/olimex-stm32-p407/nsh/defconfig index f7fcfb08e2..bbf8b95d54 100644 --- a/configs/olimex-stm32-p407/nsh/defconfig +++ b/configs/olimex-stm32-p407/nsh/defconfig @@ -658,7 +658,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-strp711/nettest/defconfig b/configs/olimex-strp711/nettest/defconfig index 45b867aaad..6bde1e1f3b 100644 --- a/configs/olimex-strp711/nettest/defconfig +++ b/configs/olimex-strp711/nettest/defconfig @@ -298,7 +298,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-strp711/nsh/defconfig b/configs/olimex-strp711/nsh/defconfig index 6056494510..6a46e966b6 100644 --- a/configs/olimex-strp711/nsh/defconfig +++ b/configs/olimex-strp711/nsh/defconfig @@ -302,7 +302,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimexino-stm32/can/defconfig b/configs/olimexino-stm32/can/defconfig index 6a256641ce..25eaf0aefc 100644 --- a/configs/olimexino-stm32/can/defconfig +++ b/configs/olimexino-stm32/can/defconfig @@ -658,7 +658,7 @@ CONFIG_MAX_TASKS=12 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimexino-stm32/composite/defconfig b/configs/olimexino-stm32/composite/defconfig index 05c32536ed..8eb861aff4 100644 --- a/configs/olimexino-stm32/composite/defconfig +++ b/configs/olimexino-stm32/composite/defconfig @@ -658,7 +658,7 @@ CONFIG_MAX_TASKS=12 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimexino-stm32/nsh/defconfig b/configs/olimexino-stm32/nsh/defconfig index ec8a8eccd8..7fb0682188 100644 --- a/configs/olimexino-stm32/nsh/defconfig +++ b/configs/olimexino-stm32/nsh/defconfig @@ -657,7 +657,7 @@ CONFIG_MAX_TASKS=12 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimexino-stm32/smallnsh/defconfig b/configs/olimexino-stm32/smallnsh/defconfig index fd15121169..fc5194b8ec 100644 --- a/configs/olimexino-stm32/smallnsh/defconfig +++ b/configs/olimexino-stm32/smallnsh/defconfig @@ -639,7 +639,7 @@ CONFIG_MAX_TASKS=4 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimexino-stm32/tiny/defconfig b/configs/olimexino-stm32/tiny/defconfig index 3623a1cdba..9991232442 100644 --- a/configs/olimexino-stm32/tiny/defconfig +++ b/configs/olimexino-stm32/tiny/defconfig @@ -639,7 +639,7 @@ CONFIG_MAX_TASKS=4 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/open1788/knsh/defconfig b/configs/open1788/knsh/defconfig index d34c2b7ff8..f539625c3c 100644 --- a/configs/open1788/knsh/defconfig +++ b/configs/open1788/knsh/defconfig @@ -366,7 +366,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/open1788/nsh/defconfig b/configs/open1788/nsh/defconfig index aec3804257..d8fc7e13fb 100644 --- a/configs/open1788/nsh/defconfig +++ b/configs/open1788/nsh/defconfig @@ -364,7 +364,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/open1788/nxlines/defconfig b/configs/open1788/nxlines/defconfig index beda60dd82..c95b7d51f4 100644 --- a/configs/open1788/nxlines/defconfig +++ b/configs/open1788/nxlines/defconfig @@ -398,7 +398,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/p112/ostest/defconfig b/configs/p112/ostest/defconfig index a7fc5e7748..247254f1c6 100644 --- a/configs/p112/ostest/defconfig +++ b/configs/p112/ostest/defconfig @@ -206,7 +206,7 @@ CONFIG_START_YEAR=2007 CONFIG_START_MONTH=2 CONFIG_START_DAY=21 # CONFIG_DEV_CONSOLE is not set -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set # CONFIG_PRIORITY_INHERITANCE is not set # CONFIG_FDCLONE_DISABLE is not set # CONFIG_FDCLONE_STDIO is not set diff --git a/configs/pcblogic-pic32mx/nsh/defconfig b/configs/pcblogic-pic32mx/nsh/defconfig index d8c64680a6..015492f3c3 100644 --- a/configs/pcblogic-pic32mx/nsh/defconfig +++ b/configs/pcblogic-pic32mx/nsh/defconfig @@ -380,7 +380,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/pcduino-a10/nsh/defconfig b/configs/pcduino-a10/nsh/defconfig index f181819f2d..653a69aad8 100644 --- a/configs/pcduino-a10/nsh/defconfig +++ b/configs/pcduino-a10/nsh/defconfig @@ -367,7 +367,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/photon/nsh/defconfig b/configs/photon/nsh/defconfig index 9e808a75f3..0072a232eb 100644 --- a/configs/photon/nsh/defconfig +++ b/configs/photon/nsh/defconfig @@ -636,7 +636,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/photon/usbnsh/defconfig b/configs/photon/usbnsh/defconfig index c6326b54df..251914b079 100644 --- a/configs/photon/usbnsh/defconfig +++ b/configs/photon/usbnsh/defconfig @@ -637,7 +637,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/pic32mx-starterkit/nsh/defconfig b/configs/pic32mx-starterkit/nsh/defconfig index 6046b8b420..f89384e555 100644 --- a/configs/pic32mx-starterkit/nsh/defconfig +++ b/configs/pic32mx-starterkit/nsh/defconfig @@ -386,7 +386,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/pic32mx-starterkit/nsh2/defconfig b/configs/pic32mx-starterkit/nsh2/defconfig index c437b0d314..a8b36d84ce 100644 --- a/configs/pic32mx-starterkit/nsh2/defconfig +++ b/configs/pic32mx-starterkit/nsh2/defconfig @@ -397,7 +397,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/pic32mx7mmb/nsh/defconfig b/configs/pic32mx7mmb/nsh/defconfig index 5b0c7bb0e4..9b7faf1af7 100644 --- a/configs/pic32mx7mmb/nsh/defconfig +++ b/configs/pic32mx7mmb/nsh/defconfig @@ -406,7 +406,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/pic32mz-starterkit/nsh/defconfig b/configs/pic32mz-starterkit/nsh/defconfig index 6122f7b9e8..5090e2d447 100644 --- a/configs/pic32mz-starterkit/nsh/defconfig +++ b/configs/pic32mz-starterkit/nsh/defconfig @@ -313,7 +313,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/qemu-i486/nsh/defconfig b/configs/qemu-i486/nsh/defconfig index 33163950fa..4be4465d1a 100644 --- a/configs/qemu-i486/nsh/defconfig +++ b/configs/qemu-i486/nsh/defconfig @@ -206,7 +206,7 @@ CONFIG_MAX_TASKS=64 # # Pthread Options # -CONFIG_MUTEX_TYPES=y +CONFIG_PTHREAD_MUTEX_TYPES=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/qemu-i486/ostest/defconfig b/configs/qemu-i486/ostest/defconfig index 2aa95a3aa8..6a1b80f37f 100644 --- a/configs/qemu-i486/ostest/defconfig +++ b/configs/qemu-i486/ostest/defconfig @@ -206,7 +206,7 @@ CONFIG_MAX_TASKS=64 # # Pthread Options # -CONFIG_MUTEX_TYPES=y +CONFIG_PTHREAD_MUTEX_TYPES=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sabre-6quad/nsh/defconfig b/configs/sabre-6quad/nsh/defconfig index 015d44dc6d..dfa9dc689f 100644 --- a/configs/sabre-6quad/nsh/defconfig +++ b/configs/sabre-6quad/nsh/defconfig @@ -322,7 +322,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sabre-6quad/smp/defconfig b/configs/sabre-6quad/smp/defconfig index a2544273b9..21569e99cb 100644 --- a/configs/sabre-6quad/smp/defconfig +++ b/configs/sabre-6quad/smp/defconfig @@ -327,7 +327,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sam3u-ek/knsh/defconfig b/configs/sam3u-ek/knsh/defconfig index 6af0730c6c..fa70b85b3c 100644 --- a/configs/sam3u-ek/knsh/defconfig +++ b/configs/sam3u-ek/knsh/defconfig @@ -389,7 +389,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sam3u-ek/nsh/defconfig b/configs/sam3u-ek/nsh/defconfig index 0925cb868d..4f3af6a72a 100644 --- a/configs/sam3u-ek/nsh/defconfig +++ b/configs/sam3u-ek/nsh/defconfig @@ -388,7 +388,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sam3u-ek/nx/defconfig b/configs/sam3u-ek/nx/defconfig index 36987fc43b..7150bd5790 100644 --- a/configs/sam3u-ek/nx/defconfig +++ b/configs/sam3u-ek/nx/defconfig @@ -383,7 +383,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sam3u-ek/nxwm/defconfig b/configs/sam3u-ek/nxwm/defconfig index 32a587d239..cbb1614bab 100644 --- a/configs/sam3u-ek/nxwm/defconfig +++ b/configs/sam3u-ek/nxwm/defconfig @@ -395,7 +395,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sam4cmp-db/nsh/defconfig b/configs/sam4cmp-db/nsh/defconfig index 0fa5131213..5790893479 100644 --- a/configs/sam4cmp-db/nsh/defconfig +++ b/configs/sam4cmp-db/nsh/defconfig @@ -400,7 +400,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sam4e-ek/nsh/defconfig b/configs/sam4e-ek/nsh/defconfig index e1c0a93e79..11cea1f028 100644 --- a/configs/sam4e-ek/nsh/defconfig +++ b/configs/sam4e-ek/nsh/defconfig @@ -433,7 +433,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sam4e-ek/nxwm/defconfig b/configs/sam4e-ek/nxwm/defconfig index 1042d44996..27ee8c8d62 100644 --- a/configs/sam4e-ek/nxwm/defconfig +++ b/configs/sam4e-ek/nxwm/defconfig @@ -441,7 +441,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sam4e-ek/usbnsh/defconfig b/configs/sam4e-ek/usbnsh/defconfig index 5164a20c33..a9a085da8d 100644 --- a/configs/sam4e-ek/usbnsh/defconfig +++ b/configs/sam4e-ek/usbnsh/defconfig @@ -439,7 +439,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sam4l-xplained/nsh/defconfig b/configs/sam4l-xplained/nsh/defconfig index 05a66746b6..a814652926 100644 --- a/configs/sam4l-xplained/nsh/defconfig +++ b/configs/sam4l-xplained/nsh/defconfig @@ -406,7 +406,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sam4s-xplained-pro/nsh/defconfig b/configs/sam4s-xplained-pro/nsh/defconfig index 4c976fd603..b652a1e88f 100644 --- a/configs/sam4s-xplained-pro/nsh/defconfig +++ b/configs/sam4s-xplained-pro/nsh/defconfig @@ -427,7 +427,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sam4s-xplained/nsh/defconfig b/configs/sam4s-xplained/nsh/defconfig index 842ca37509..83ea926edb 100644 --- a/configs/sam4s-xplained/nsh/defconfig +++ b/configs/sam4s-xplained/nsh/defconfig @@ -386,7 +386,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d2-xult/nsh/defconfig b/configs/sama5d2-xult/nsh/defconfig index a8c89702f8..12fae8f490 100644 --- a/configs/sama5d2-xult/nsh/defconfig +++ b/configs/sama5d2-xult/nsh/defconfig @@ -462,7 +462,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d3-xplained/bridge/defconfig b/configs/sama5d3-xplained/bridge/defconfig index 7d9d6b72be..a4492196c5 100644 --- a/configs/sama5d3-xplained/bridge/defconfig +++ b/configs/sama5d3-xplained/bridge/defconfig @@ -460,7 +460,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d3-xplained/nsh/defconfig b/configs/sama5d3-xplained/nsh/defconfig index 16fae22584..bc5af1a452 100644 --- a/configs/sama5d3-xplained/nsh/defconfig +++ b/configs/sama5d3-xplained/nsh/defconfig @@ -425,7 +425,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d3x-ek/demo/defconfig b/configs/sama5d3x-ek/demo/defconfig index e9bcf44a91..6192d4e394 100644 --- a/configs/sama5d3x-ek/demo/defconfig +++ b/configs/sama5d3x-ek/demo/defconfig @@ -488,7 +488,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d3x-ek/hello/defconfig b/configs/sama5d3x-ek/hello/defconfig index 87c1c7fdce..8c94fe0d4f 100644 --- a/configs/sama5d3x-ek/hello/defconfig +++ b/configs/sama5d3x-ek/hello/defconfig @@ -407,7 +407,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d3x-ek/norboot/defconfig b/configs/sama5d3x-ek/norboot/defconfig index 9d3b19e90d..a2cd0cd6ce 100644 --- a/configs/sama5d3x-ek/norboot/defconfig +++ b/configs/sama5d3x-ek/norboot/defconfig @@ -421,7 +421,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d3x-ek/nsh/defconfig b/configs/sama5d3x-ek/nsh/defconfig index a0aef06837..8db191b838 100644 --- a/configs/sama5d3x-ek/nsh/defconfig +++ b/configs/sama5d3x-ek/nsh/defconfig @@ -424,7 +424,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d3x-ek/nx/defconfig b/configs/sama5d3x-ek/nx/defconfig index 84a38dafe2..fe0bf5e3ad 100644 --- a/configs/sama5d3x-ek/nx/defconfig +++ b/configs/sama5d3x-ek/nx/defconfig @@ -466,7 +466,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d3x-ek/nxplayer/defconfig b/configs/sama5d3x-ek/nxplayer/defconfig index 206402ce0b..b90e25e494 100644 --- a/configs/sama5d3x-ek/nxplayer/defconfig +++ b/configs/sama5d3x-ek/nxplayer/defconfig @@ -485,7 +485,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d3x-ek/nxwm/defconfig b/configs/sama5d3x-ek/nxwm/defconfig index 3441a0c134..7626a2b947 100644 --- a/configs/sama5d3x-ek/nxwm/defconfig +++ b/configs/sama5d3x-ek/nxwm/defconfig @@ -500,7 +500,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d3x-ek/ov2640/defconfig b/configs/sama5d3x-ek/ov2640/defconfig index fb54648635..57fa4dda6e 100644 --- a/configs/sama5d3x-ek/ov2640/defconfig +++ b/configs/sama5d3x-ek/ov2640/defconfig @@ -472,7 +472,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d4-ek/at25boot/defconfig b/configs/sama5d4-ek/at25boot/defconfig index fbd3b3db80..c19493d204 100644 --- a/configs/sama5d4-ek/at25boot/defconfig +++ b/configs/sama5d4-ek/at25boot/defconfig @@ -450,7 +450,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d4-ek/bridge/defconfig b/configs/sama5d4-ek/bridge/defconfig index 41e9f16108..85245101b0 100644 --- a/configs/sama5d4-ek/bridge/defconfig +++ b/configs/sama5d4-ek/bridge/defconfig @@ -478,7 +478,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d4-ek/dramboot/defconfig b/configs/sama5d4-ek/dramboot/defconfig index dca1c2fd9b..1150a6609f 100644 --- a/configs/sama5d4-ek/dramboot/defconfig +++ b/configs/sama5d4-ek/dramboot/defconfig @@ -443,7 +443,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d4-ek/elf/defconfig b/configs/sama5d4-ek/elf/defconfig index d6e280da0d..9632bcdff9 100644 --- a/configs/sama5d4-ek/elf/defconfig +++ b/configs/sama5d4-ek/elf/defconfig @@ -453,7 +453,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d4-ek/ipv6/defconfig b/configs/sama5d4-ek/ipv6/defconfig index 71cfd5ca4b..b2e488e00f 100644 --- a/configs/sama5d4-ek/ipv6/defconfig +++ b/configs/sama5d4-ek/ipv6/defconfig @@ -577,7 +577,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d4-ek/knsh/defconfig b/configs/sama5d4-ek/knsh/defconfig index f05ae86fbc..be1c9fd5b4 100644 --- a/configs/sama5d4-ek/knsh/defconfig +++ b/configs/sama5d4-ek/knsh/defconfig @@ -470,7 +470,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d4-ek/knsh/defconfig.ROMFS b/configs/sama5d4-ek/knsh/defconfig.ROMFS index a7fd05ca58..191c970fff 100644 --- a/configs/sama5d4-ek/knsh/defconfig.ROMFS +++ b/configs/sama5d4-ek/knsh/defconfig.ROMFS @@ -381,7 +381,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # diff --git a/configs/sama5d4-ek/nsh/defconfig b/configs/sama5d4-ek/nsh/defconfig index 37571f3a5a..820d434038 100644 --- a/configs/sama5d4-ek/nsh/defconfig +++ b/configs/sama5d4-ek/nsh/defconfig @@ -577,7 +577,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d4-ek/nxwm/defconfig b/configs/sama5d4-ek/nxwm/defconfig index a3086ea7d6..9f49ae3a7f 100644 --- a/configs/sama5d4-ek/nxwm/defconfig +++ b/configs/sama5d4-ek/nxwm/defconfig @@ -549,7 +549,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d4-ek/ramtest/defconfig b/configs/sama5d4-ek/ramtest/defconfig index c2d98e526f..943e794b2d 100644 --- a/configs/sama5d4-ek/ramtest/defconfig +++ b/configs/sama5d4-ek/ramtest/defconfig @@ -442,7 +442,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/samd20-xplained/nsh/defconfig b/configs/samd20-xplained/nsh/defconfig index 307e424afd..accfc04cc2 100644 --- a/configs/samd20-xplained/nsh/defconfig +++ b/configs/samd20-xplained/nsh/defconfig @@ -369,7 +369,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/samd21-xplained/nsh/defconfig b/configs/samd21-xplained/nsh/defconfig index 03026a8376..7d13c4909e 100644 --- a/configs/samd21-xplained/nsh/defconfig +++ b/configs/samd21-xplained/nsh/defconfig @@ -367,7 +367,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/same70-xplained/netnsh/defconfig b/configs/same70-xplained/netnsh/defconfig index d472559ad8..7e0b322e2c 100644 --- a/configs/same70-xplained/netnsh/defconfig +++ b/configs/same70-xplained/netnsh/defconfig @@ -452,7 +452,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/same70-xplained/nsh/defconfig b/configs/same70-xplained/nsh/defconfig index 80f1fbf9d2..95fc9237c7 100644 --- a/configs/same70-xplained/nsh/defconfig +++ b/configs/same70-xplained/nsh/defconfig @@ -437,7 +437,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/saml21-xplained/nsh/defconfig b/configs/saml21-xplained/nsh/defconfig index feb9aa82d4..44b619e305 100644 --- a/configs/saml21-xplained/nsh/defconfig +++ b/configs/saml21-xplained/nsh/defconfig @@ -355,7 +355,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/samv71-xult/knsh/defconfig b/configs/samv71-xult/knsh/defconfig index ebbb97e10d..756d20cf7a 100644 --- a/configs/samv71-xult/knsh/defconfig +++ b/configs/samv71-xult/knsh/defconfig @@ -445,7 +445,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/samv71-xult/module/defconfig b/configs/samv71-xult/module/defconfig index 414a1893b4..8f993004c8 100644 --- a/configs/samv71-xult/module/defconfig +++ b/configs/samv71-xult/module/defconfig @@ -420,7 +420,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/samv71-xult/mxtxplnd/defconfig b/configs/samv71-xult/mxtxplnd/defconfig index be79a3cec8..562257bd95 100644 --- a/configs/samv71-xult/mxtxplnd/defconfig +++ b/configs/samv71-xult/mxtxplnd/defconfig @@ -438,7 +438,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/samv71-xult/netnsh/defconfig b/configs/samv71-xult/netnsh/defconfig index a38656d9c1..7c5afb7acc 100644 --- a/configs/samv71-xult/netnsh/defconfig +++ b/configs/samv71-xult/netnsh/defconfig @@ -455,7 +455,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/samv71-xult/nsh/defconfig b/configs/samv71-xult/nsh/defconfig index ce85bb673b..4f2ecda618 100644 --- a/configs/samv71-xult/nsh/defconfig +++ b/configs/samv71-xult/nsh/defconfig @@ -440,7 +440,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/samv71-xult/nxwm/defconfig b/configs/samv71-xult/nxwm/defconfig index e5246ecafa..f50d5ff31f 100644 --- a/configs/samv71-xult/nxwm/defconfig +++ b/configs/samv71-xult/nxwm/defconfig @@ -439,7 +439,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/samv71-xult/vnc/defconfig b/configs/samv71-xult/vnc/defconfig index 00e4ca6bca..1402ffb99d 100644 --- a/configs/samv71-xult/vnc/defconfig +++ b/configs/samv71-xult/vnc/defconfig @@ -454,7 +454,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/samv71-xult/vnxwm/defconfig b/configs/samv71-xult/vnxwm/defconfig index 2606fbbcab..f7fef3296d 100644 --- a/configs/samv71-xult/vnxwm/defconfig +++ b/configs/samv71-xult/vnxwm/defconfig @@ -455,7 +455,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/shenzhou/nsh/defconfig b/configs/shenzhou/nsh/defconfig index 60caa4bafc..30c6547cff 100644 --- a/configs/shenzhou/nsh/defconfig +++ b/configs/shenzhou/nsh/defconfig @@ -651,7 +651,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/shenzhou/nxwm/defconfig b/configs/shenzhou/nxwm/defconfig index e82a839ed3..6306307a44 100644 --- a/configs/shenzhou/nxwm/defconfig +++ b/configs/shenzhou/nxwm/defconfig @@ -674,7 +674,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/shenzhou/thttpd/defconfig b/configs/shenzhou/thttpd/defconfig index b8feba27ea..6e40305a21 100644 --- a/configs/shenzhou/thttpd/defconfig +++ b/configs/shenzhou/thttpd/defconfig @@ -652,7 +652,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/bas/defconfig b/configs/sim/bas/defconfig index a5aece53f1..04f89c514f 100644 --- a/configs/sim/bas/defconfig +++ b/configs/sim/bas/defconfig @@ -208,7 +208,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/cxxtest/defconfig b/configs/sim/cxxtest/defconfig index 596267b579..7625148fcd 100644 --- a/configs/sim/cxxtest/defconfig +++ b/configs/sim/cxxtest/defconfig @@ -201,7 +201,7 @@ CONFIG_MAX_TASKS=64 # # Pthread Options # -CONFIG_MUTEX_TYPES=y +CONFIG_PTHREAD_MUTEX_TYPES=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/minibasic/defconfig b/configs/sim/minibasic/defconfig index 84aa2c94b9..0e582ed3cd 100644 --- a/configs/sim/minibasic/defconfig +++ b/configs/sim/minibasic/defconfig @@ -235,7 +235,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/mount/defconfig b/configs/sim/mount/defconfig index 5bae00f40b..c7a83e8908 100644 --- a/configs/sim/mount/defconfig +++ b/configs/sim/mount/defconfig @@ -201,7 +201,7 @@ CONFIG_MAX_TASKS=64 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/mtdrwb/defconfig b/configs/sim/mtdrwb/defconfig index c7ea3c4825..0debd96feb 100644 --- a/configs/sim/mtdrwb/defconfig +++ b/configs/sim/mtdrwb/defconfig @@ -201,7 +201,7 @@ CONFIG_MAX_TASKS=64 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/nettest/defconfig b/configs/sim/nettest/defconfig index 3209c63ae4..1e471fd063 100644 --- a/configs/sim/nettest/defconfig +++ b/configs/sim/nettest/defconfig @@ -201,7 +201,7 @@ CONFIG_MAX_TASKS=64 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/nsh/defconfig b/configs/sim/nsh/defconfig index 683dc18657..ff4efbb0f0 100644 --- a/configs/sim/nsh/defconfig +++ b/configs/sim/nsh/defconfig @@ -208,7 +208,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/nsh2/defconfig b/configs/sim/nsh2/defconfig index c9798d1df2..d6fd7c8e5b 100644 --- a/configs/sim/nsh2/defconfig +++ b/configs/sim/nsh2/defconfig @@ -216,7 +216,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/nx/defconfig b/configs/sim/nx/defconfig index 8450147a06..e9c94ef24d 100644 --- a/configs/sim/nx/defconfig +++ b/configs/sim/nx/defconfig @@ -205,7 +205,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/nx11/defconfig b/configs/sim/nx11/defconfig index 54d0ba8c5d..1176121728 100644 --- a/configs/sim/nx11/defconfig +++ b/configs/sim/nx11/defconfig @@ -206,7 +206,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/nxlines/defconfig b/configs/sim/nxlines/defconfig index a63927a3e3..fb547cc57f 100644 --- a/configs/sim/nxlines/defconfig +++ b/configs/sim/nxlines/defconfig @@ -216,7 +216,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/nxwm/defconfig b/configs/sim/nxwm/defconfig index 254409eab3..2749e54197 100644 --- a/configs/sim/nxwm/defconfig +++ b/configs/sim/nxwm/defconfig @@ -211,7 +211,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/ostest/defconfig b/configs/sim/ostest/defconfig index be0f68fdce..b76f88dfd0 100644 --- a/configs/sim/ostest/defconfig +++ b/configs/sim/ostest/defconfig @@ -202,7 +202,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -CONFIG_MUTEX_TYPES=y +CONFIG_PTHREAD_MUTEX_TYPES=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/pashello/defconfig b/configs/sim/pashello/defconfig index 2f30e200bb..5c329f978b 100644 --- a/configs/sim/pashello/defconfig +++ b/configs/sim/pashello/defconfig @@ -201,7 +201,7 @@ CONFIG_MAX_TASKS=64 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/touchscreen/defconfig b/configs/sim/touchscreen/defconfig index 5b1f3360d6..a8ad9b5f43 100644 --- a/configs/sim/touchscreen/defconfig +++ b/configs/sim/touchscreen/defconfig @@ -216,7 +216,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/traveler/defconfig b/configs/sim/traveler/defconfig index 9711d23431..db68d953a9 100644 --- a/configs/sim/traveler/defconfig +++ b/configs/sim/traveler/defconfig @@ -209,7 +209,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/udgram/defconfig b/configs/sim/udgram/defconfig index c92e6efaa9..aaf31194e1 100644 --- a/configs/sim/udgram/defconfig +++ b/configs/sim/udgram/defconfig @@ -208,7 +208,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/unionfs/defconfig b/configs/sim/unionfs/defconfig index 513b70747b..27dc23dd88 100644 --- a/configs/sim/unionfs/defconfig +++ b/configs/sim/unionfs/defconfig @@ -208,7 +208,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/ustream/defconfig b/configs/sim/ustream/defconfig index df0ab89e15..146cf9695f 100644 --- a/configs/sim/ustream/defconfig +++ b/configs/sim/ustream/defconfig @@ -208,7 +208,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/skp16c26/ostest/defconfig b/configs/skp16c26/ostest/defconfig index 0edccdc2b4..6869e4ca4c 100644 --- a/configs/skp16c26/ostest/defconfig +++ b/configs/skp16c26/ostest/defconfig @@ -196,7 +196,7 @@ CONFIG_MAX_TASKS=8 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/spark/composite/defconfig b/configs/spark/composite/defconfig index 2fc6bc1b43..4c53bfb69f 100644 --- a/configs/spark/composite/defconfig +++ b/configs/spark/composite/defconfig @@ -627,7 +627,7 @@ CONFIG_MAX_TASKS=12 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/spark/nsh/defconfig b/configs/spark/nsh/defconfig index 9a4ef0b4d4..2768858395 100644 --- a/configs/spark/nsh/defconfig +++ b/configs/spark/nsh/defconfig @@ -627,7 +627,7 @@ CONFIG_MAX_TASKS=12 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/spark/usbmsc/defconfig b/configs/spark/usbmsc/defconfig index 243b2b1d60..bf8b9101fc 100644 --- a/configs/spark/usbmsc/defconfig +++ b/configs/spark/usbmsc/defconfig @@ -627,7 +627,7 @@ CONFIG_MAX_TASKS=12 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/spark/usbnsh/defconfig b/configs/spark/usbnsh/defconfig index a64a14e621..cb810ac38a 100644 --- a/configs/spark/usbnsh/defconfig +++ b/configs/spark/usbnsh/defconfig @@ -626,7 +626,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/spark/usbserial/defconfig b/configs/spark/usbserial/defconfig index c2014af213..6813801980 100644 --- a/configs/spark/usbserial/defconfig +++ b/configs/spark/usbserial/defconfig @@ -632,7 +632,7 @@ CONFIG_MAX_TASKS=12 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3210e-eval/composite/defconfig b/configs/stm3210e-eval/composite/defconfig index 6cf922622e..c003251c1e 100644 --- a/configs/stm3210e-eval/composite/defconfig +++ b/configs/stm3210e-eval/composite/defconfig @@ -647,7 +647,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3210e-eval/nsh/defconfig b/configs/stm3210e-eval/nsh/defconfig index ddcf4b9d73..45d83032ce 100644 --- a/configs/stm3210e-eval/nsh/defconfig +++ b/configs/stm3210e-eval/nsh/defconfig @@ -648,7 +648,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3210e-eval/nsh2/defconfig b/configs/stm3210e-eval/nsh2/defconfig index 5b690bc2a6..c30a1bc7d2 100644 --- a/configs/stm3210e-eval/nsh2/defconfig +++ b/configs/stm3210e-eval/nsh2/defconfig @@ -664,7 +664,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3210e-eval/nx/defconfig b/configs/stm3210e-eval/nx/defconfig index bbb17b0c78..544b55c68c 100644 --- a/configs/stm3210e-eval/nx/defconfig +++ b/configs/stm3210e-eval/nx/defconfig @@ -651,7 +651,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3210e-eval/nxterm/defconfig b/configs/stm3210e-eval/nxterm/defconfig index d749e44f36..bd9a3c6f9d 100644 --- a/configs/stm3210e-eval/nxterm/defconfig +++ b/configs/stm3210e-eval/nxterm/defconfig @@ -644,7 +644,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3210e-eval/pm/defconfig b/configs/stm3210e-eval/pm/defconfig index b1156be57c..b8047456f1 100644 --- a/configs/stm3210e-eval/pm/defconfig +++ b/configs/stm3210e-eval/pm/defconfig @@ -664,7 +664,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3210e-eval/usbmsc/defconfig b/configs/stm3210e-eval/usbmsc/defconfig index 925f75940b..60950a454f 100644 --- a/configs/stm3210e-eval/usbmsc/defconfig +++ b/configs/stm3210e-eval/usbmsc/defconfig @@ -638,7 +638,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3210e-eval/usbserial/defconfig b/configs/stm3210e-eval/usbserial/defconfig index fc7bc98678..12f55502e5 100644 --- a/configs/stm3210e-eval/usbserial/defconfig +++ b/configs/stm3210e-eval/usbserial/defconfig @@ -630,7 +630,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3220g-eval/nsh/defconfig b/configs/stm3220g-eval/nsh/defconfig index a9fbdf2f6d..127c8723b5 100644 --- a/configs/stm3220g-eval/nsh/defconfig +++ b/configs/stm3220g-eval/nsh/defconfig @@ -670,7 +670,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3220g-eval/nsh2/defconfig b/configs/stm3220g-eval/nsh2/defconfig index 0d0ae9af74..6e9bc14fa8 100644 --- a/configs/stm3220g-eval/nsh2/defconfig +++ b/configs/stm3220g-eval/nsh2/defconfig @@ -671,7 +671,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3220g-eval/nxwm/defconfig b/configs/stm3220g-eval/nxwm/defconfig index 66c4046191..a339400d24 100644 --- a/configs/stm3220g-eval/nxwm/defconfig +++ b/configs/stm3220g-eval/nxwm/defconfig @@ -690,7 +690,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3240g-eval/discover/defconfig b/configs/stm3240g-eval/discover/defconfig index 59971c43a9..8f58437cc3 100644 --- a/configs/stm3240g-eval/discover/defconfig +++ b/configs/stm3240g-eval/discover/defconfig @@ -669,7 +669,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3240g-eval/knxwm/defconfig b/configs/stm3240g-eval/knxwm/defconfig index d7ed1665f3..e9b5edca2b 100644 --- a/configs/stm3240g-eval/knxwm/defconfig +++ b/configs/stm3240g-eval/knxwm/defconfig @@ -684,7 +684,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3240g-eval/nsh/defconfig b/configs/stm3240g-eval/nsh/defconfig index 6d23dd4164..c18a3e8462 100644 --- a/configs/stm3240g-eval/nsh/defconfig +++ b/configs/stm3240g-eval/nsh/defconfig @@ -684,7 +684,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3240g-eval/nsh2/defconfig b/configs/stm3240g-eval/nsh2/defconfig index 39db64c7ef..aa74992b4e 100644 --- a/configs/stm3240g-eval/nsh2/defconfig +++ b/configs/stm3240g-eval/nsh2/defconfig @@ -675,7 +675,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3240g-eval/nxterm/defconfig b/configs/stm3240g-eval/nxterm/defconfig index 1ed096c2a7..94440b32fa 100644 --- a/configs/stm3240g-eval/nxterm/defconfig +++ b/configs/stm3240g-eval/nxterm/defconfig @@ -694,7 +694,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3240g-eval/nxwm/defconfig b/configs/stm3240g-eval/nxwm/defconfig index 52b8e8f866..24e4a5db75 100644 --- a/configs/stm3240g-eval/nxwm/defconfig +++ b/configs/stm3240g-eval/nxwm/defconfig @@ -694,7 +694,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3240g-eval/webserver/defconfig b/configs/stm3240g-eval/webserver/defconfig index 3f70a1200a..923e8ac1ed 100644 --- a/configs/stm3240g-eval/webserver/defconfig +++ b/configs/stm3240g-eval/webserver/defconfig @@ -674,7 +674,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3240g-eval/xmlrpc/defconfig b/configs/stm3240g-eval/xmlrpc/defconfig index 9ccfb0bce1..cd3838b5c7 100644 --- a/configs/stm3240g-eval/xmlrpc/defconfig +++ b/configs/stm3240g-eval/xmlrpc/defconfig @@ -664,7 +664,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32_tiny/nsh/defconfig b/configs/stm32_tiny/nsh/defconfig index 86867909cb..cb39c3b326 100644 --- a/configs/stm32_tiny/nsh/defconfig +++ b/configs/stm32_tiny/nsh/defconfig @@ -616,7 +616,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32_tiny/usbnsh/defconfig b/configs/stm32_tiny/usbnsh/defconfig index 91f0ec630c..82b6a3f2fb 100644 --- a/configs/stm32_tiny/usbnsh/defconfig +++ b/configs/stm32_tiny/usbnsh/defconfig @@ -610,7 +610,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32butterfly2/nsh/defconfig b/configs/stm32butterfly2/nsh/defconfig index 4d265c86d5..cc58d6dc2f 100644 --- a/configs/stm32butterfly2/nsh/defconfig +++ b/configs/stm32butterfly2/nsh/defconfig @@ -636,7 +636,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32butterfly2/nshnet/defconfig b/configs/stm32butterfly2/nshnet/defconfig index fdd07367b5..018450beca 100644 --- a/configs/stm32butterfly2/nshnet/defconfig +++ b/configs/stm32butterfly2/nshnet/defconfig @@ -644,7 +644,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32butterfly2/nshusbdev/defconfig b/configs/stm32butterfly2/nshusbdev/defconfig index f91b4a43a6..cef7a6a75b 100644 --- a/configs/stm32butterfly2/nshusbdev/defconfig +++ b/configs/stm32butterfly2/nshusbdev/defconfig @@ -629,7 +629,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32butterfly2/nshusbhost/defconfig b/configs/stm32butterfly2/nshusbhost/defconfig index 4d265c86d5..cc58d6dc2f 100644 --- a/configs/stm32butterfly2/nshusbhost/defconfig +++ b/configs/stm32butterfly2/nshusbhost/defconfig @@ -636,7 +636,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f103-minimum/audio_tone/defconfig b/configs/stm32f103-minimum/audio_tone/defconfig index 3f25c9d311..18a2d09978 100644 --- a/configs/stm32f103-minimum/audio_tone/defconfig +++ b/configs/stm32f103-minimum/audio_tone/defconfig @@ -625,7 +625,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f103-minimum/buttons/defconfig b/configs/stm32f103-minimum/buttons/defconfig index 5b19cd63bc..0312f7554b 100644 --- a/configs/stm32f103-minimum/buttons/defconfig +++ b/configs/stm32f103-minimum/buttons/defconfig @@ -612,7 +612,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f103-minimum/jlx12864g/defconfig b/configs/stm32f103-minimum/jlx12864g/defconfig index 1dbd7601e9..4a8569c328 100644 --- a/configs/stm32f103-minimum/jlx12864g/defconfig +++ b/configs/stm32f103-minimum/jlx12864g/defconfig @@ -655,7 +655,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f103-minimum/nrf24/defconfig b/configs/stm32f103-minimum/nrf24/defconfig index 23927f4d88..a13598ba74 100644 --- a/configs/stm32f103-minimum/nrf24/defconfig +++ b/configs/stm32f103-minimum/nrf24/defconfig @@ -651,7 +651,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f103-minimum/nsh/defconfig b/configs/stm32f103-minimum/nsh/defconfig index 6c55648311..7664d88825 100644 --- a/configs/stm32f103-minimum/nsh/defconfig +++ b/configs/stm32f103-minimum/nsh/defconfig @@ -611,7 +611,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f103-minimum/pwm/defconfig b/configs/stm32f103-minimum/pwm/defconfig index 551c34e3e7..d8b9bc38da 100644 --- a/configs/stm32f103-minimum/pwm/defconfig +++ b/configs/stm32f103-minimum/pwm/defconfig @@ -619,7 +619,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f103-minimum/rfid-rc522/defconfig b/configs/stm32f103-minimum/rfid-rc522/defconfig index 475d5f3985..a8daaf44f6 100644 --- a/configs/stm32f103-minimum/rfid-rc522/defconfig +++ b/configs/stm32f103-minimum/rfid-rc522/defconfig @@ -619,7 +619,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f103-minimum/rgbled/defconfig b/configs/stm32f103-minimum/rgbled/defconfig index b0adc1cbb3..bae4f13a9f 100644 --- a/configs/stm32f103-minimum/rgbled/defconfig +++ b/configs/stm32f103-minimum/rgbled/defconfig @@ -639,7 +639,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f103-minimum/usbnsh/defconfig b/configs/stm32f103-minimum/usbnsh/defconfig index decc71aa16..e5319a27eb 100644 --- a/configs/stm32f103-minimum/usbnsh/defconfig +++ b/configs/stm32f103-minimum/usbnsh/defconfig @@ -613,7 +613,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f103-minimum/userled/defconfig b/configs/stm32f103-minimum/userled/defconfig index 5c93140792..d49398b75d 100644 --- a/configs/stm32f103-minimum/userled/defconfig +++ b/configs/stm32f103-minimum/userled/defconfig @@ -611,7 +611,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f103-minimum/veml6070/defconfig b/configs/stm32f103-minimum/veml6070/defconfig index f9b79252f7..3d2065e1fa 100644 --- a/configs/stm32f103-minimum/veml6070/defconfig +++ b/configs/stm32f103-minimum/veml6070/defconfig @@ -623,7 +623,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f3discovery/nsh/defconfig b/configs/stm32f3discovery/nsh/defconfig index 986acf8aa7..5b31d15483 100644 --- a/configs/stm32f3discovery/nsh/defconfig +++ b/configs/stm32f3discovery/nsh/defconfig @@ -634,7 +634,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f3discovery/usbnsh/defconfig b/configs/stm32f3discovery/usbnsh/defconfig index d53ceee3f3..1e7c46dc58 100644 --- a/configs/stm32f3discovery/usbnsh/defconfig +++ b/configs/stm32f3discovery/usbnsh/defconfig @@ -641,7 +641,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f411e-disco/nsh/defconfig b/configs/stm32f411e-disco/nsh/defconfig index 00551e986a..da44560a90 100644 --- a/configs/stm32f411e-disco/nsh/defconfig +++ b/configs/stm32f411e-disco/nsh/defconfig @@ -612,7 +612,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f429i-disco/extflash/defconfig b/configs/stm32f429i-disco/extflash/defconfig index 9fc151029c..193be96591 100644 --- a/configs/stm32f429i-disco/extflash/defconfig +++ b/configs/stm32f429i-disco/extflash/defconfig @@ -668,7 +668,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f429i-disco/lcd/defconfig b/configs/stm32f429i-disco/lcd/defconfig index ac6a69bf53..c7c072ee64 100644 --- a/configs/stm32f429i-disco/lcd/defconfig +++ b/configs/stm32f429i-disco/lcd/defconfig @@ -659,7 +659,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f429i-disco/ltdc/defconfig b/configs/stm32f429i-disco/ltdc/defconfig index 39417fd825..7d30ca9818 100644 --- a/configs/stm32f429i-disco/ltdc/defconfig +++ b/configs/stm32f429i-disco/ltdc/defconfig @@ -705,7 +705,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f429i-disco/nsh/defconfig b/configs/stm32f429i-disco/nsh/defconfig index 5f5b994e94..ac69c63817 100644 --- a/configs/stm32f429i-disco/nsh/defconfig +++ b/configs/stm32f429i-disco/nsh/defconfig @@ -648,7 +648,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f429i-disco/nxwm/defconfig b/configs/stm32f429i-disco/nxwm/defconfig index e7d1c8279a..5d89ad67f6 100644 --- a/configs/stm32f429i-disco/nxwm/defconfig +++ b/configs/stm32f429i-disco/nxwm/defconfig @@ -670,7 +670,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f429i-disco/usbmsc/defconfig b/configs/stm32f429i-disco/usbmsc/defconfig index 4a60f8b641..3d31281b67 100644 --- a/configs/stm32f429i-disco/usbmsc/defconfig +++ b/configs/stm32f429i-disco/usbmsc/defconfig @@ -663,7 +663,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f429i-disco/usbnsh/defconfig b/configs/stm32f429i-disco/usbnsh/defconfig index 39445ee4d8..3cd8e76c73 100644 --- a/configs/stm32f429i-disco/usbnsh/defconfig +++ b/configs/stm32f429i-disco/usbnsh/defconfig @@ -654,7 +654,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f4discovery/canard/defconfig b/configs/stm32f4discovery/canard/defconfig index 58b871fc8f..112de219fd 100644 --- a/configs/stm32f4discovery/canard/defconfig +++ b/configs/stm32f4discovery/canard/defconfig @@ -664,7 +664,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f4discovery/cxxtest/defconfig b/configs/stm32f4discovery/cxxtest/defconfig index 875b00c1be..d9cc9f6f7b 100644 --- a/configs/stm32f4discovery/cxxtest/defconfig +++ b/configs/stm32f4discovery/cxxtest/defconfig @@ -651,7 +651,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f4discovery/elf/defconfig b/configs/stm32f4discovery/elf/defconfig index 7d9209143d..23ecbe39e0 100644 --- a/configs/stm32f4discovery/elf/defconfig +++ b/configs/stm32f4discovery/elf/defconfig @@ -652,7 +652,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f4discovery/ipv6/defconfig b/configs/stm32f4discovery/ipv6/defconfig index 83ea38b94c..0a4728f555 100644 --- a/configs/stm32f4discovery/ipv6/defconfig +++ b/configs/stm32f4discovery/ipv6/defconfig @@ -694,7 +694,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f4discovery/kostest/defconfig b/configs/stm32f4discovery/kostest/defconfig index 6f2535b869..75487b4d9f 100644 --- a/configs/stm32f4discovery/kostest/defconfig +++ b/configs/stm32f4discovery/kostest/defconfig @@ -657,7 +657,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f4discovery/netnsh/defconfig b/configs/stm32f4discovery/netnsh/defconfig index f564769ca0..8702fa5338 100644 --- a/configs/stm32f4discovery/netnsh/defconfig +++ b/configs/stm32f4discovery/netnsh/defconfig @@ -694,7 +694,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f4discovery/nsh/defconfig b/configs/stm32f4discovery/nsh/defconfig index 389c07a67d..8e8128fc1d 100644 --- a/configs/stm32f4discovery/nsh/defconfig +++ b/configs/stm32f4discovery/nsh/defconfig @@ -659,7 +659,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f4discovery/nxlines/defconfig b/configs/stm32f4discovery/nxlines/defconfig index 36523d0d38..fbb2ec0dc2 100644 --- a/configs/stm32f4discovery/nxlines/defconfig +++ b/configs/stm32f4discovery/nxlines/defconfig @@ -660,7 +660,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f4discovery/pm/defconfig b/configs/stm32f4discovery/pm/defconfig index 3d080ba1d1..7d1bf73755 100644 --- a/configs/stm32f4discovery/pm/defconfig +++ b/configs/stm32f4discovery/pm/defconfig @@ -666,7 +666,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f4discovery/posix_spawn/defconfig b/configs/stm32f4discovery/posix_spawn/defconfig index fa13076f96..13863f2a46 100644 --- a/configs/stm32f4discovery/posix_spawn/defconfig +++ b/configs/stm32f4discovery/posix_spawn/defconfig @@ -652,7 +652,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f4discovery/pseudoterm/defconfig b/configs/stm32f4discovery/pseudoterm/defconfig index 761a2b013c..d18d1b560c 100644 --- a/configs/stm32f4discovery/pseudoterm/defconfig +++ b/configs/stm32f4discovery/pseudoterm/defconfig @@ -653,7 +653,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f4discovery/rgbled/defconfig b/configs/stm32f4discovery/rgbled/defconfig index 091fb6ff78..54780a62af 100644 --- a/configs/stm32f4discovery/rgbled/defconfig +++ b/configs/stm32f4discovery/rgbled/defconfig @@ -662,7 +662,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f4discovery/uavcan/defconfig b/configs/stm32f4discovery/uavcan/defconfig index 226fe4cb0e..caec09e638 100644 --- a/configs/stm32f4discovery/uavcan/defconfig +++ b/configs/stm32f4discovery/uavcan/defconfig @@ -620,7 +620,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f4discovery/usbnsh/defconfig b/configs/stm32f4discovery/usbnsh/defconfig index 06dc85dfde..88bfe30276 100644 --- a/configs/stm32f4discovery/usbnsh/defconfig +++ b/configs/stm32f4discovery/usbnsh/defconfig @@ -665,7 +665,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f4discovery/winbuild/defconfig b/configs/stm32f4discovery/winbuild/defconfig index 88058e6cfc..1eb0d0f671 100644 --- a/configs/stm32f4discovery/winbuild/defconfig +++ b/configs/stm32f4discovery/winbuild/defconfig @@ -551,7 +551,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # diff --git a/configs/stm32f4discovery/xen1210/defconfig b/configs/stm32f4discovery/xen1210/defconfig index 5e76fbf79e..bf4859a9ca 100644 --- a/configs/stm32f4discovery/xen1210/defconfig +++ b/configs/stm32f4discovery/xen1210/defconfig @@ -654,7 +654,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f746-ws/nsh/defconfig b/configs/stm32f746-ws/nsh/defconfig index 8edcdb6f87..e1bbfa82c6 100644 --- a/configs/stm32f746-ws/nsh/defconfig +++ b/configs/stm32f746-ws/nsh/defconfig @@ -516,7 +516,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f746g-disco/nsh/defconfig b/configs/stm32f746g-disco/nsh/defconfig index 4d1625b4b1..bf4b4b1501 100644 --- a/configs/stm32f746g-disco/nsh/defconfig +++ b/configs/stm32f746g-disco/nsh/defconfig @@ -493,7 +493,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32l476-mdk/nsh/defconfig b/configs/stm32l476-mdk/nsh/defconfig index 3f2ce702a5..8c6736985b 100644 --- a/configs/stm32l476-mdk/nsh/defconfig +++ b/configs/stm32l476-mdk/nsh/defconfig @@ -443,7 +443,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32l476vg-disco/nsh/defconfig b/configs/stm32l476vg-disco/nsh/defconfig index 2e443d717a..69414abb84 100644 --- a/configs/stm32l476vg-disco/nsh/defconfig +++ b/configs/stm32l476vg-disco/nsh/defconfig @@ -456,7 +456,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32ldiscovery/nsh/defconfig b/configs/stm32ldiscovery/nsh/defconfig index 4c3ba206d6..e287044d8e 100644 --- a/configs/stm32ldiscovery/nsh/defconfig +++ b/configs/stm32ldiscovery/nsh/defconfig @@ -618,7 +618,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32vldiscovery/nsh/defconfig b/configs/stm32vldiscovery/nsh/defconfig index 7de8efbc97..8f995dc8ec 100644 --- a/configs/stm32vldiscovery/nsh/defconfig +++ b/configs/stm32vldiscovery/nsh/defconfig @@ -628,7 +628,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sure-pic32mx/nsh/defconfig b/configs/sure-pic32mx/nsh/defconfig index 25a6a21966..45e9b428be 100644 --- a/configs/sure-pic32mx/nsh/defconfig +++ b/configs/sure-pic32mx/nsh/defconfig @@ -390,7 +390,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sure-pic32mx/usbnsh/defconfig b/configs/sure-pic32mx/usbnsh/defconfig index 87b387e3a1..604415e68d 100644 --- a/configs/sure-pic32mx/usbnsh/defconfig +++ b/configs/sure-pic32mx/usbnsh/defconfig @@ -392,7 +392,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/teensy-2.0/usbmsc/defconfig b/configs/teensy-2.0/usbmsc/defconfig index 5854699d35..508d46aa4b 100644 --- a/configs/teensy-2.0/usbmsc/defconfig +++ b/configs/teensy-2.0/usbmsc/defconfig @@ -231,7 +231,7 @@ CONFIG_MAX_TASKS=8 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/teensy-3.x/nsh/defconfig b/configs/teensy-3.x/nsh/defconfig index baafedd820..12b169e4c6 100644 --- a/configs/teensy-3.x/nsh/defconfig +++ b/configs/teensy-3.x/nsh/defconfig @@ -387,7 +387,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/teensy-3.x/usbnsh/defconfig b/configs/teensy-3.x/usbnsh/defconfig index e59d5d45dd..47f8eef746 100644 --- a/configs/teensy-3.x/usbnsh/defconfig +++ b/configs/teensy-3.x/usbnsh/defconfig @@ -384,7 +384,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/teensy-lc/nsh/defconfig b/configs/teensy-lc/nsh/defconfig index f121ca5247..b97c58114f 100644 --- a/configs/teensy-lc/nsh/defconfig +++ b/configs/teensy-lc/nsh/defconfig @@ -324,7 +324,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/tm4c123g-launchpad/nsh/defconfig b/configs/tm4c123g-launchpad/nsh/defconfig index 71362ab743..645949de1e 100644 --- a/configs/tm4c123g-launchpad/nsh/defconfig +++ b/configs/tm4c123g-launchpad/nsh/defconfig @@ -390,7 +390,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/tm4c1294-launchpad/ipv6/defconfig b/configs/tm4c1294-launchpad/ipv6/defconfig index df9138c111..e24c287f27 100644 --- a/configs/tm4c1294-launchpad/ipv6/defconfig +++ b/configs/tm4c1294-launchpad/ipv6/defconfig @@ -406,7 +406,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/tm4c1294-launchpad/nsh/defconfig b/configs/tm4c1294-launchpad/nsh/defconfig index 5690209be4..d42dc98a3e 100644 --- a/configs/tm4c1294-launchpad/nsh/defconfig +++ b/configs/tm4c1294-launchpad/nsh/defconfig @@ -406,7 +406,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/twr-k60n512/nsh/defconfig b/configs/twr-k60n512/nsh/defconfig index 2768335ce9..f34a9294a2 100644 --- a/configs/twr-k60n512/nsh/defconfig +++ b/configs/twr-k60n512/nsh/defconfig @@ -382,7 +382,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/twr-k64f120m/netnsh/defconfig b/configs/twr-k64f120m/netnsh/defconfig index 5f2d0910c3..e27f688271 100644 --- a/configs/twr-k64f120m/netnsh/defconfig +++ b/configs/twr-k64f120m/netnsh/defconfig @@ -421,7 +421,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/twr-k64f120m/nsh/defconfig b/configs/twr-k64f120m/nsh/defconfig index eccbd57164..bfd649af69 100644 --- a/configs/twr-k64f120m/nsh/defconfig +++ b/configs/twr-k64f120m/nsh/defconfig @@ -407,7 +407,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/u-blox-c027/nsh/defconfig b/configs/u-blox-c027/nsh/defconfig index 8fe80a00a6..529dcf7bda 100644 --- a/configs/u-blox-c027/nsh/defconfig +++ b/configs/u-blox-c027/nsh/defconfig @@ -372,7 +372,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/ubw32/nsh/defconfig b/configs/ubw32/nsh/defconfig index 2fe63ce051..da80577b85 100644 --- a/configs/ubw32/nsh/defconfig +++ b/configs/ubw32/nsh/defconfig @@ -389,7 +389,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/viewtool-stm32f107/highpri/defconfig b/configs/viewtool-stm32f107/highpri/defconfig index 15f574f6c3..7881989330 100644 --- a/configs/viewtool-stm32f107/highpri/defconfig +++ b/configs/viewtool-stm32f107/highpri/defconfig @@ -626,7 +626,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/viewtool-stm32f107/netnsh/defconfig b/configs/viewtool-stm32f107/netnsh/defconfig index 7362467a7f..a5a48b32ba 100644 --- a/configs/viewtool-stm32f107/netnsh/defconfig +++ b/configs/viewtool-stm32f107/netnsh/defconfig @@ -643,7 +643,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/viewtool-stm32f107/nsh/defconfig b/configs/viewtool-stm32f107/nsh/defconfig index 02c4e16ac0..037cecaeb9 100644 --- a/configs/viewtool-stm32f107/nsh/defconfig +++ b/configs/viewtool-stm32f107/nsh/defconfig @@ -623,7 +623,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/xmc4500-relax/nsh/defconfig b/configs/xmc4500-relax/nsh/defconfig index 14643afe8f..2ee3ed50ff 100644 --- a/configs/xmc4500-relax/nsh/defconfig +++ b/configs/xmc4500-relax/nsh/defconfig @@ -326,7 +326,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/xtrs/nsh/defconfig b/configs/xtrs/nsh/defconfig index f00bed1e28..f757520a04 100644 --- a/configs/xtrs/nsh/defconfig +++ b/configs/xtrs/nsh/defconfig @@ -127,7 +127,7 @@ CONFIG_START_YEAR=2012 CONFIG_START_MONTH=12 CONFIG_START_DAY=9 CONFIG_DEV_CONSOLE=y -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set # CONFIG_PRIORITY_INHERITANCE is not set # CONFIG_FDCLONE_DISABLE is not set # CONFIG_FDCLONE_STDIO is not set diff --git a/configs/xtrs/ostest/defconfig b/configs/xtrs/ostest/defconfig index 709e3dc7a1..e74b06c992 100644 --- a/configs/xtrs/ostest/defconfig +++ b/configs/xtrs/ostest/defconfig @@ -126,7 +126,7 @@ CONFIG_START_YEAR=2008 CONFIG_START_MONTH=2 CONFIG_START_DAY=21 # CONFIG_DEV_CONSOLE is not set -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set # CONFIG_PRIORITY_INHERITANCE is not set # CONFIG_FDCLONE_DISABLE is not set # CONFIG_FDCLONE_STDIO is not set diff --git a/configs/xtrs/pashello/defconfig b/configs/xtrs/pashello/defconfig index 8e4c51c211..c720f725f3 100644 --- a/configs/xtrs/pashello/defconfig +++ b/configs/xtrs/pashello/defconfig @@ -127,7 +127,7 @@ CONFIG_START_YEAR=2012 CONFIG_START_MONTH=12 CONFIG_START_DAY=9 CONFIG_DEV_CONSOLE=y -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set # CONFIG_PRIORITY_INHERITANCE is not set # CONFIG_FDCLONE_DISABLE is not set # CONFIG_FDCLONE_STDIO is not set diff --git a/configs/z16f2800100zcog/nsh/defconfig b/configs/z16f2800100zcog/nsh/defconfig index 7114acee80..377508de81 100644 --- a/configs/z16f2800100zcog/nsh/defconfig +++ b/configs/z16f2800100zcog/nsh/defconfig @@ -217,7 +217,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/z16f2800100zcog/ostest/defconfig b/configs/z16f2800100zcog/ostest/defconfig index 5fc5aa95b0..2f8cdad153 100644 --- a/configs/z16f2800100zcog/ostest/defconfig +++ b/configs/z16f2800100zcog/ostest/defconfig @@ -217,7 +217,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/z16f2800100zcog/pashello/defconfig b/configs/z16f2800100zcog/pashello/defconfig index 73cbcca1cd..e69a059f67 100644 --- a/configs/z16f2800100zcog/pashello/defconfig +++ b/configs/z16f2800100zcog/pashello/defconfig @@ -217,7 +217,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/z80sim/nsh/defconfig b/configs/z80sim/nsh/defconfig index 9d25de2742..a018632f27 100644 --- a/configs/z80sim/nsh/defconfig +++ b/configs/z80sim/nsh/defconfig @@ -127,7 +127,7 @@ CONFIG_START_YEAR=2012 CONFIG_START_MONTH=12 CONFIG_START_DAY=7 CONFIG_DEV_CONSOLE=y -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set # CONFIG_PRIORITY_INHERITANCE is not set # CONFIG_FDCLONE_DISABLE is not set # CONFIG_FDCLONE_STDIO is not set diff --git a/configs/z80sim/ostest/defconfig b/configs/z80sim/ostest/defconfig index 04cb098016..3ed03920a7 100644 --- a/configs/z80sim/ostest/defconfig +++ b/configs/z80sim/ostest/defconfig @@ -126,7 +126,7 @@ CONFIG_START_YEAR=2007 CONFIG_START_MONTH=2 CONFIG_START_DAY=21 # CONFIG_DEV_CONSOLE is not set -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set # CONFIG_PRIORITY_INHERITANCE is not set # CONFIG_FDCLONE_DISABLE is not set # CONFIG_FDCLONE_STDIO is not set diff --git a/configs/z80sim/pashello/defconfig b/configs/z80sim/pashello/defconfig index 8ffd9fda39..8bd794e872 100644 --- a/configs/z80sim/pashello/defconfig +++ b/configs/z80sim/pashello/defconfig @@ -126,7 +126,7 @@ CONFIG_START_YEAR=2012 CONFIG_START_MONTH=12 CONFIG_START_DAY=7 CONFIG_DEV_CONSOLE=y -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set # CONFIG_PRIORITY_INHERITANCE is not set # CONFIG_FDCLONE_DISABLE is not set # CONFIG_FDCLONE_STDIO is not set diff --git a/configs/zkit-arm-1769/nsh/defconfig b/configs/zkit-arm-1769/nsh/defconfig index df35f44bfc..ec99f4c3b6 100644 --- a/configs/zkit-arm-1769/nsh/defconfig +++ b/configs/zkit-arm-1769/nsh/defconfig @@ -366,7 +366,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/zkit-arm-1769/nxhello/defconfig b/configs/zkit-arm-1769/nxhello/defconfig index 464caa8316..60ef8992a9 100644 --- a/configs/zkit-arm-1769/nxhello/defconfig +++ b/configs/zkit-arm-1769/nxhello/defconfig @@ -366,7 +366,7 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/zp214xpa/nsh/defconfig b/configs/zp214xpa/nsh/defconfig index 27801bfb26..d066c3058b 100644 --- a/configs/zp214xpa/nsh/defconfig +++ b/configs/zp214xpa/nsh/defconfig @@ -285,7 +285,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/zp214xpa/nxlines/defconfig b/configs/zp214xpa/nxlines/defconfig index 0ff83a6c96..e0deb025fa 100644 --- a/configs/zp214xpa/nxlines/defconfig +++ b/configs/zp214xpa/nxlines/defconfig @@ -289,7 +289,7 @@ CONFIG_MAX_TASKS=16 # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/include/pthread.h b/include/pthread.h index 53eaa0ddaa..edf943c9bb 100644 --- a/include/pthread.h +++ b/include/pthread.h @@ -260,7 +260,7 @@ struct pthread_mutexattr_s #ifdef CONFIG_PRIORITY_INHERITANCE uint8_t proto : 2; /* See PTHREAD_PRIO_* definitions */ #endif -#ifdef CONFIG_MUTEX_TYPES +#ifdef CONFIG_PTHREAD_MUTEX_TYPES uint8_t type : 2; /* Type of the mutex. See PTHREAD_MUTEX_* definitions */ #endif #ifdef CONFIG_PTHREAD_MUTEX_BOTH @@ -286,7 +286,7 @@ struct pthread_mutex_s #ifndef CONFIG_PTHREAD_MUTEX_UNSAFE uint8_t flags; /* See _PTHREAD_MFLAGS_* */ #endif -#ifdef CONFIG_MUTEX_TYPES +#ifdef CONFIG_PTHREAD_MUTEX_TYPES uint8_t type; /* Type of the mutex. See PTHREAD_MUTEX_* definitions */ int16_t nlocks; /* The number of recursive locks held */ #endif @@ -295,7 +295,7 @@ struct pthread_mutex_s typedef struct pthread_mutex_s pthread_mutex_t; #define __PTHREAD_MUTEX_T_DEFINED 1 -#ifdef CONFIG_MUTEX_TYPES +#ifdef CONFIG_PTHREAD_MUTEX_TYPES # define PTHREAD_MUTEX_INITIALIZER {-1, SEM_INITIALIZER(1), PTHREAD_MUTEX_DEFAULT, 0} #else # define PTHREAD_MUTEX_INITIALIZER {-1, SEM_INITIALIZER(1)} diff --git a/libc/libc.csv b/libc/libc.csv index d38cc8b161..02cf739bd3 100644 --- a/libc/libc.csv +++ b/libc/libc.csv @@ -113,10 +113,10 @@ "pthread_condattr_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_condattr_t *" "pthread_mutexattr_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutexattr_t *" "pthread_mutexattr_getpshared","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutexattr_t *","FAR int *" -"pthread_mutexattr_gettype","pthread.h","!defined(CONFIG_DISABLE_PTHREAD) && defined(CONFIG_MUTEX_TYPES)","int","FAR const pthread_mutexattr_t *","int *" +"pthread_mutexattr_gettype","pthread.h","!defined(CONFIG_DISABLE_PTHREAD) && defined(CONFIG_PTHREAD_MUTEX_TYPES)","int","FAR const pthread_mutexattr_t *","int *" "pthread_mutexattr_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutexattr_t *" "pthread_mutexattr_setpshared","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutexattr_t *","int " -"pthread_mutexattr_settype","pthread.h","!defined(CONFIG_DISABLE_PTHREAD) && defined(CONFIG_MUTEX_TYPES)","int","pthread_mutexattr_t *","int" +"pthread_mutexattr_settype","pthread.h","!defined(CONFIG_DISABLE_PTHREAD) && defined(CONFIG_PTHREAD_MUTEX_TYPES)","int","pthread_mutexattr_t *","int" "puts","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR const char *" "qsort","stdlib.h","","void","void *","size_t","size_t","int(*)(const void *","FAR const void *)" "rand","stdlib.h","","int" diff --git a/libc/pthread/pthread_mutexattr_gettype.c b/libc/pthread/pthread_mutexattr_gettype.c index 9f057ae11d..784a347ce8 100644 --- a/libc/pthread/pthread_mutexattr_gettype.c +++ b/libc/pthread/pthread_mutexattr_gettype.c @@ -67,7 +67,7 @@ int pthread_mutexattr_gettype(const pthread_mutexattr_t *attr, int *type) { if (attr != NULL && type != NULL) { -#ifdef CONFIG_MUTEX_TYPES +#ifdef CONFIG_PTHREAD_MUTEX_TYPES *type = attr->type; #else *type = PTHREAD_MUTEX_NORMAL; diff --git a/libc/pthread/pthread_mutexattr_init.c b/libc/pthread/pthread_mutexattr_init.c index de6183e56c..895346a6cd 100644 --- a/libc/pthread/pthread_mutexattr_init.c +++ b/libc/pthread/pthread_mutexattr_init.c @@ -81,7 +81,7 @@ int pthread_mutexattr_init(FAR pthread_mutexattr_t *attr) attr->proto = SEM_PRIO_INHERIT; #endif -#ifdef CONFIG_MUTEX_TYPES +#ifdef CONFIG_PTHREAD_MUTEX_TYPES attr->type = PTHREAD_MUTEX_DEFAULT; #endif diff --git a/libc/pthread/pthread_mutexattr_settype.c b/libc/pthread/pthread_mutexattr_settype.c index b43e86fc12..6047f90ef2 100644 --- a/libc/pthread/pthread_mutexattr_settype.c +++ b/libc/pthread/pthread_mutexattr_settype.c @@ -67,7 +67,7 @@ int pthread_mutexattr_settype(pthread_mutexattr_t *attr, int type) { if (attr && type >= PTHREAD_MUTEX_NORMAL && type <= PTHREAD_MUTEX_RECURSIVE) { -#ifdef CONFIG_MUTEX_TYPES +#ifdef CONFIG_PTHREAD_MUTEX_TYPES attr->type = type; #else if (type != PTHREAD_MUTEX_NORMAL) diff --git a/sched/Kconfig b/sched/Kconfig index 60183e67d2..0a09c524fe 100644 --- a/sched/Kconfig +++ b/sched/Kconfig @@ -524,7 +524,7 @@ endmenu # Tasks and Scheduling menu "Pthread Options" depends on !DISABLE_PTHREAD -config MUTEX_TYPES: +config PTHREAD_MUTEX_TYPES bool "Enable mutex types" default n ---help--- diff --git a/sched/pthread/pthread.h b/sched/pthread/pthread.h index 2e7106495f..bc0238c903 100644 --- a/sched/pthread/pthread.h +++ b/sched/pthread/pthread.h @@ -119,7 +119,7 @@ void pthread_mutex_inconsistent(FAR struct pthread_tcb_s *tcb); # define pthread_mutex_give(m) pthread_givesemaphore(&(m)->sem) #endif -#ifdef CONFIG_MUTEX_TYPES +#ifdef CONFIG_PTHREAD_MUTEX_TYPES int pthread_mutexattr_verifytype(int type); #endif diff --git a/sched/pthread/pthread_mutexconsistent.c b/sched/pthread/pthread_mutexconsistent.c index 86930e276c..77d9bede3e 100644 --- a/sched/pthread/pthread_mutexconsistent.c +++ b/sched/pthread/pthread_mutexconsistent.c @@ -120,7 +120,7 @@ int pthread_mutex_consistent(FAR pthread_mutex_t *mutex) mutex->pid = -1; mutex->flags &= _PTHREAD_MFLAGS_ROBUST; -#ifdef CONFIG_MUTEX_TYPES +#ifdef CONFIG_PTHREAD_MUTEX_TYPES mutex->nlocks = 0; #endif /* Reset the semaphore. This has the same affect as if the diff --git a/sched/pthread/pthread_mutexinit.c b/sched/pthread/pthread_mutexinit.c index e6abe32900..ec84fef609 100644 --- a/sched/pthread/pthread_mutexinit.c +++ b/sched/pthread/pthread_mutexinit.c @@ -72,7 +72,7 @@ int pthread_mutex_init(FAR pthread_mutex_t *mutex, FAR const pthread_mutexattr_t *attr) { int pshared = 0; -#ifdef CONFIG_MUTEX_TYPES +#ifdef CONFIG_PTHREAD_MUTEX_TYPES uint8_t type = PTHREAD_MUTEX_DEFAULT; #endif #ifdef CONFIG_PRIORITY_INHERITANCE @@ -104,7 +104,7 @@ int pthread_mutex_init(FAR pthread_mutex_t *mutex, #ifdef CONFIG_PRIORITY_INHERITANCE proto = attr->proto; #endif -#ifdef CONFIG_MUTEX_TYPES +#ifdef CONFIG_PTHREAD_MUTEX_TYPES type = attr->type; #endif #ifdef CONFIG_PTHREAD_MUTEX_BOTH @@ -141,7 +141,7 @@ int pthread_mutex_init(FAR pthread_mutex_t *mutex, mutex->flags = (robust == PTHREAD_MUTEX_ROBUST ? _PTHREAD_MFLAGS_ROBUST : 0); #endif -#ifdef CONFIG_MUTEX_TYPES +#ifdef CONFIG_PTHREAD_MUTEX_TYPES /* Set up attributes unique to the mutex type */ mutex->type = type; diff --git a/sched/pthread/pthread_mutexlock.c b/sched/pthread/pthread_mutexlock.c index 3013248842..629c3fc0ad 100644 --- a/sched/pthread/pthread_mutexlock.c +++ b/sched/pthread/pthread_mutexlock.c @@ -120,7 +120,7 @@ int pthread_mutex_lock(FAR pthread_mutex_t *mutex) sched_lock(); -#ifdef CONFIG_MUTEX_TYPES +#ifdef CONFIG_PTHREAD_MUTEX_TYPES /* All mutex types except for NORMAL (and DEFAULT) will return * and an error error if the caller does not hold the mutex. */ @@ -162,7 +162,7 @@ int pthread_mutex_lock(FAR pthread_mutex_t *mutex) } } else -#endif /* CONFIG_MUTEX_TYPES */ +#endif /* CONFIG_PTHREAD_MUTEX_TYPES */ #ifndef CONFIG_PTHREAD_MUTEX_UNSAFE /* The calling thread does not hold the semaphore. The correct @@ -172,7 +172,7 @@ int pthread_mutex_lock(FAR pthread_mutex_t *mutex) */ #ifdef CONFIG_PTHREAD_MUTEX_BOTH -#ifdef CONFIG_MUTEX_TYPES +#ifdef CONFIG_PTHREAD_MUTEX_TYPES /* Include check if this is a NORMAL mutex and that it is robust */ if (mutex->pid > 0 && @@ -180,14 +180,14 @@ int pthread_mutex_lock(FAR pthread_mutex_t *mutex) mutex->type != PTHREAD_MUTEX_NORMAL) && sched_gettcb(mutex->pid) == NULL) -#else /* CONFIG_MUTEX_TYPES */ +#else /* CONFIG_PTHREAD_MUTEX_TYPES */ /* This can only be a NORMAL mutex. Include check if it is robust */ if (mutex->pid > 0 && (mutex->flags & _PTHREAD_MFLAGS_ROBUST) != 0 && sched_gettcb(mutex->pid) == NULL) -#endif /* CONFIG_MUTEX_TYPES */ +#endif /* CONFIG_PTHREAD_MUTEX_TYPES */ #else /* CONFIG_PTHREAD_MUTEX_ROBUST */ /* This mutex is always robust, whatever type it is. */ @@ -224,7 +224,7 @@ int pthread_mutex_lock(FAR pthread_mutex_t *mutex) if (ret == OK) { mutex->pid = mypid; -#ifdef CONFIG_MUTEX_TYPES +#ifdef CONFIG_PTHREAD_MUTEX_TYPES mutex->nlocks = 1; #endif } diff --git a/sched/pthread/pthread_mutextrylock.c b/sched/pthread/pthread_mutextrylock.c index 50c3175de5..9083fd465a 100644 --- a/sched/pthread/pthread_mutextrylock.c +++ b/sched/pthread/pthread_mutextrylock.c @@ -111,7 +111,7 @@ int pthread_mutex_trylock(FAR pthread_mutex_t *mutex) mutex->pid = mypid; -#ifdef CONFIG_MUTEX_TYPES +#ifdef CONFIG_PTHREAD_MUTEX_TYPES if (mutex->type == PTHREAD_MUTEX_RECURSIVE) { mutex->nlocks = 1; @@ -129,7 +129,7 @@ int pthread_mutex_trylock(FAR pthread_mutex_t *mutex) int errcode = get_errno(); if (errcode == EAGAIN) { -#ifdef CONFIG_MUTEX_TYPES +#ifdef CONFIG_PTHREAD_MUTEX_TYPES /* Check if recursive mutex was locked by the calling thread. */ if (mutex->type == PTHREAD_MUTEX_RECURSIVE && mutex->pid == mypid) @@ -157,7 +157,7 @@ int pthread_mutex_trylock(FAR pthread_mutex_t *mutex) */ #ifdef CONFIG_PTHREAD_MUTEX_BOTH -#ifdef CONFIG_MUTEX_TYPES +#ifdef CONFIG_PTHREAD_MUTEX_TYPES /* Check if this NORMAL mutex is robust */ if (mutex->pid > 0 && @@ -165,14 +165,14 @@ int pthread_mutex_trylock(FAR pthread_mutex_t *mutex) mutex->type != PTHREAD_MUTEX_NORMAL) && sched_gettcb(mutex->pid) == NULL) -#else /* CONFIG_MUTEX_TYPES */ +#else /* CONFIG_PTHREAD_MUTEX_TYPES */ /* Check if this NORMAL mutex is robust */ if (mutex->pid > 0 && (mutex->flags & _PTHREAD_MFLAGS_ROBUST) != 0 && sched_gettcb(mutex->pid) == NULL) -#endif /* CONFIG_MUTEX_TYPES */ +#endif /* CONFIG_PTHREAD_MUTEX_TYPES */ #else /* CONFIG_PTHREAD_MUTEX_ROBUST */ /* This mutex is always robust, whatever type it is. */ diff --git a/sched/pthread/pthread_mutexunlock.c b/sched/pthread/pthread_mutexunlock.c index b27c9ecda0..6a9bab3f8a 100644 --- a/sched/pthread/pthread_mutexunlock.c +++ b/sched/pthread/pthread_mutexunlock.c @@ -92,7 +92,7 @@ int pthread_mutex_unlock(FAR pthread_mutex_t *mutex) sched_lock(); if (mutex != NULL) { -#if !defined(CONFIG_PTHREAD_MUTEX_UNSAFE) || defined(CONFIG_MUTEX_TYPES) +#if !defined(CONFIG_PTHREAD_MUTEX_UNSAFE) || defined(CONFIG_PTHREAD_MUTEX_TYPES) /* Does the calling thread own the semaphore? If no, should we return * an error? * @@ -112,7 +112,7 @@ int pthread_mutex_unlock(FAR pthread_mutex_t *mutex) if (mutex->pid != (int)getpid()) -#elif defined(CONFIG_PTHREAD_MUTEX_UNSAFE) && defined(CONFIG_MUTEX_TYPES) +#elif defined(CONFIG_PTHREAD_MUTEX_UNSAFE) && defined(CONFIG_PTHREAD_MUTEX_TYPES) /* If mutex types are not supported, then all mutexes are NORMAL (or * DEFAULT). Error checking should never be performed for the * non-robust NORMAL mutex type. @@ -124,7 +124,7 @@ int pthread_mutex_unlock(FAR pthread_mutex_t *mutex) /* Skip the error check if this is a non-robust NORMAL mutex */ bool errcheck = ((mutex->flags & _PTHREAD_MFLAGS_ROBUST) != 0); -#ifdef CONFIG_MUTEX_TYPES +#ifdef CONFIG_PTHREAD_MUTEX_TYPES errcheck |= (mutex->type != PTHREAD_MUTEX_NORMAL); #endif @@ -150,9 +150,9 @@ int pthread_mutex_unlock(FAR pthread_mutex_t *mutex) ret = EPERM; } else -#endif /* !CONFIG_PTHREAD_MUTEX_UNSAFE || CONFIG_MUTEX_TYPES */ +#endif /* !CONFIG_PTHREAD_MUTEX_UNSAFE || CONFIG_PTHREAD_MUTEX_TYPES */ -#ifdef CONFIG_MUTEX_TYPES +#ifdef CONFIG_PTHREAD_MUTEX_TYPES /* Yes, the caller owns the semaphore.. Is this a recursive mutex? */ if (mutex->type == PTHREAD_MUTEX_RECURSIVE && mutex->nlocks > 1) @@ -167,7 +167,7 @@ int pthread_mutex_unlock(FAR pthread_mutex_t *mutex) } else -#endif /* CONFIG_MUTEX_TYPES */ +#endif /* CONFIG_PTHREAD_MUTEX_TYPES */ /* This is either a non-recursive mutex or is the outermost unlock of * a recursive mutex. @@ -182,7 +182,7 @@ int pthread_mutex_unlock(FAR pthread_mutex_t *mutex) /* Nullify the pid and lock count then post the semaphore */ mutex->pid = -1; -#ifdef CONFIG_MUTEX_TYPES +#ifdef CONFIG_PTHREAD_MUTEX_TYPES mutex->nlocks = 0; #endif ret = pthread_mutex_give(mutex); -- GitLab From c071e2a30c62d5a8e2a5a0332797e3b195acef56 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 27 Mar 2017 09:21:03 -0600 Subject: [PATCH 224/990] Make sure that CONFIG_PTHREAD_MUTEX_ROBUST=y is selected every configuration that enabled pthreads. --- configs/arduino-due/nsh/defconfig | 1 + configs/avr32dev1/nsh/defconfig | 1 + configs/avr32dev1/ostest/defconfig | 1 + configs/bambino-200e/netnsh/defconfig | 1 + configs/bambino-200e/nsh/defconfig | 1 + configs/bambino-200e/usbnsh/defconfig | 1 + configs/c5471evm/httpd/defconfig | 1 + configs/c5471evm/nsh/defconfig | 1 + configs/cc3200-launchpad/nsh/defconfig | 1 + configs/clicker2-stm32/nsh/defconfig | 1 + configs/clicker2-stm32/usbnsh/defconfig | 1 + configs/cloudctrl/nsh/defconfig | 1 + configs/dk-tm4c129x/ipv6/defconfig | 1 + configs/dk-tm4c129x/nsh/defconfig | 1 + configs/ea3131/nsh/defconfig | 1 + configs/ea3131/pgnsh/defconfig | 1 + configs/ea3131/usbserial/defconfig | 1 + configs/ea3152/ostest/defconfig | 1 + configs/eagle100/httpd/defconfig | 1 + configs/eagle100/nsh/defconfig | 1 + configs/eagle100/nxflat/defconfig | 1 + configs/efm32-g8xx-stk/nsh/defconfig | 1 + configs/efm32gg-stk3700/nsh/defconfig | 1 + configs/ekk-lm3s9b96/nsh/defconfig | 1 + configs/esp32-core/nsh/defconfig | 1 + configs/esp32-core/ostest/defconfig | 1 + configs/esp32-core/smp/defconfig | 1 + configs/ez80f910200zco/httpd/defconfig | 1 + configs/ez80f910200zco/nsh/defconfig | 1 + configs/ez80f910200zco/poll/defconfig | 1 + configs/fire-stm32v2/nsh/defconfig | 1 + configs/freedom-k64f/netnsh/defconfig | 1 + configs/freedom-k64f/nsh/defconfig | 1 + configs/freedom-k66f/netnsh/defconfig | 1 + configs/freedom-k66f/nsh/defconfig | 1 + configs/freedom-kl25z/nsh/defconfig | 1 + configs/freedom-kl26z/nsh/defconfig | 1 + configs/hymini-stm32v/nsh/defconfig | 1 + configs/hymini-stm32v/nsh2/defconfig | 1 + configs/hymini-stm32v/usbmsc/defconfig | 1 + configs/hymini-stm32v/usbnsh/defconfig | 1 + configs/hymini-stm32v/usbserial/defconfig | 1 + configs/kwikstik-k40/ostest/defconfig | 1 + configs/launchxl-tms57004/nsh/defconfig | 1 + configs/lincoln60/netnsh/defconfig | 1 + configs/lincoln60/nsh/defconfig | 1 + configs/lm3s6432-s2e/nsh/defconfig | 1 + configs/lm3s6965-ek/discover/defconfig | 1 + configs/lm3s6965-ek/nsh/defconfig | 1 + configs/lm3s6965-ek/nx/defconfig | 1 + configs/lm3s8962-ek/nsh/defconfig | 1 + configs/lm3s8962-ek/nx/defconfig | 1 + configs/lm4f120-launchpad/nsh/defconfig | 1 + configs/lpc4330-xplorer/nsh/defconfig | 1 + configs/lpc4337-ws/nsh/defconfig | 1 + configs/lpc4357-evb/nsh/defconfig | 1 + configs/lpc4370-link2/nsh/defconfig | 1 + configs/lpcxpresso-lpc1115/nsh/defconfig | 1 + configs/lpcxpresso-lpc1768/nsh/defconfig | 1 + configs/lpcxpresso-lpc1768/nx/defconfig | 1 + configs/lpcxpresso-lpc1768/usbmsc/defconfig | 1 + configs/mbed/nsh/defconfig | 1 + configs/mcu123-lpc214x/composite/defconfig | 1 + configs/mcu123-lpc214x/nsh/defconfig | 1 + configs/mcu123-lpc214x/usbmsc/defconfig | 1 + configs/mcu123-lpc214x/usbserial/defconfig | 1 + configs/mikroe-stm32f4/fulldemo/defconfig | 1 + configs/mikroe-stm32f4/kostest/defconfig | 1 + configs/mikroe-stm32f4/nx/defconfig | 1 + configs/mikroe-stm32f4/nxlines/defconfig | 1 + configs/mikroe-stm32f4/nxtext/defconfig | 1 + configs/mikroe-stm32f4/usbnsh/defconfig | 1 + configs/mirtoo/nsh/defconfig | 1 + configs/misoc/hello/defconfig | 1 + configs/moxa/nsh/defconfig | 1 + configs/mx1ads/ostest/defconfig | 1 + configs/nr5m100-nexys4/nsh/defconfig | 1 + configs/ntosd-dm320/nsh/defconfig | 1 + configs/ntosd-dm320/poll/defconfig | 1 + configs/ntosd-dm320/webserver/defconfig | 1 + configs/nucleo-144/f746-nsh/defconfig | 1 + configs/nucleo-144/f767-nsh/defconfig | 1 + configs/nucleo-f303re/adc/defconfig | 1 + configs/nucleo-f303re/can/defconfig | 1 + configs/nucleo-f303re/hello/defconfig | 1 + configs/nucleo-f303re/nxlines/defconfig | 1 + configs/nucleo-f303re/pwm/defconfig | 1 + configs/nucleo-f303re/serialrx/defconfig | 1 + configs/nucleo-f303re/uavcan/defconfig | 1 + configs/nucleo-f4x1re/f401-nsh/defconfig | 1 + configs/nucleo-f4x1re/f411-nsh/defconfig | 1 + configs/nucleo-l476rg/nsh/defconfig | 1 + configs/nutiny-nuc120/nsh/defconfig | 1 + configs/olimex-efm32g880f128-stk/nsh/defconfig | 1 + configs/olimex-lpc-h3131/nsh/defconfig | 1 + configs/olimex-lpc1766stk/ftpc/defconfig | 1 + configs/olimex-lpc1766stk/hidmouse/defconfig | 1 + configs/olimex-lpc1766stk/nsh/defconfig | 1 + configs/olimex-lpc1766stk/nx/defconfig | 1 + configs/olimex-lpc1766stk/usbmsc/defconfig | 1 + configs/olimex-lpc1766stk/usbserial/defconfig | 1 + configs/olimex-lpc1766stk/zmodem/defconfig | 1 + configs/olimex-lpc2378/nsh/defconfig | 1 + configs/olimex-stm32-e407/discover/defconfig | 1 + configs/olimex-stm32-e407/netnsh/defconfig | 1 + configs/olimex-stm32-e407/nsh/defconfig | 1 + configs/olimex-stm32-e407/telnetd/defconfig | 1 + configs/olimex-stm32-e407/usbnsh/defconfig | 1 + configs/olimex-stm32-e407/webserver/defconfig | 1 + configs/olimex-stm32-h405/usbnsh/defconfig | 1 + configs/olimex-stm32-h407/nsh/defconfig | 1 + configs/olimex-stm32-p107/nsh/defconfig | 1 + configs/olimex-stm32-p207/nsh/defconfig | 1 + configs/olimex-stm32-p407/knsh/defconfig | 1 + configs/olimex-stm32-p407/nsh/defconfig | 1 + configs/olimex-strp711/nettest/defconfig | 1 + configs/olimex-strp711/nsh/defconfig | 1 + configs/open1788/knsh/defconfig | 1 + configs/open1788/nsh/defconfig | 1 + configs/open1788/nxlines/defconfig | 1 + configs/pcblogic-pic32mx/nsh/defconfig | 1 + configs/pcduino-a10/nsh/defconfig | 1 + configs/photon/nsh/defconfig | 1 + configs/photon/usbnsh/defconfig | 1 + configs/pic32mx-starterkit/nsh/defconfig | 1 + configs/pic32mx-starterkit/nsh2/defconfig | 1 + configs/pic32mx7mmb/nsh/defconfig | 1 + configs/pic32mz-starterkit/nsh/defconfig | 1 + configs/qemu-i486/nsh/defconfig | 1 + configs/qemu-i486/ostest/defconfig | 1 + configs/sabre-6quad/nsh/defconfig | 1 + configs/sabre-6quad/smp/defconfig | 1 + configs/sam3u-ek/knsh/defconfig | 1 + configs/sam3u-ek/nsh/defconfig | 1 + configs/sam3u-ek/nx/defconfig | 1 + configs/sam3u-ek/nxwm/defconfig | 1 + configs/sam4cmp-db/nsh/defconfig | 1 + configs/sam4e-ek/nsh/defconfig | 1 + configs/sam4e-ek/usbnsh/defconfig | 1 + configs/sam4l-xplained/nsh/defconfig | 1 + configs/sam4s-xplained-pro/nsh/defconfig | 1 + configs/sam4s-xplained/nsh/defconfig | 1 + configs/sama5d2-xult/nsh/defconfig | 1 + configs/sama5d3-xplained/bridge/defconfig | 1 + configs/sama5d3-xplained/nsh/defconfig | 1 + configs/sama5d3x-ek/demo/defconfig | 1 + configs/sama5d3x-ek/hello/defconfig | 1 + configs/sama5d3x-ek/norboot/defconfig | 1 + configs/sama5d3x-ek/nsh/defconfig | 1 + configs/sama5d3x-ek/nx/defconfig | 1 + configs/sama5d3x-ek/nxplayer/defconfig | 1 + configs/sama5d3x-ek/nxwm/defconfig | 1 + configs/sama5d3x-ek/ov2640/defconfig | 1 + configs/sama5d4-ek/at25boot/defconfig | 1 + configs/sama5d4-ek/bridge/defconfig | 1 + configs/sama5d4-ek/dramboot/defconfig | 1 + configs/sama5d4-ek/elf/defconfig | 1 + configs/sama5d4-ek/ipv6/defconfig | 1 + configs/sama5d4-ek/knsh/defconfig | 1 + configs/sama5d4-ek/nsh/defconfig | 1 + configs/sama5d4-ek/nxwm/defconfig | 1 + configs/sama5d4-ek/ramtest/defconfig | 1 + configs/samd20-xplained/nsh/defconfig | 1 + configs/samd21-xplained/nsh/defconfig | 1 + configs/same70-xplained/netnsh/defconfig | 1 + configs/same70-xplained/nsh/defconfig | 1 + configs/saml21-xplained/nsh/defconfig | 1 + configs/samv71-xult/knsh/defconfig | 1 + configs/samv71-xult/module/defconfig | 1 + configs/samv71-xult/mxtxplnd/defconfig | 1 + configs/samv71-xult/netnsh/defconfig | 1 + configs/samv71-xult/nsh/defconfig | 1 + configs/samv71-xult/nxwm/defconfig | 1 + configs/samv71-xult/vnc/defconfig | 1 + configs/samv71-xult/vnxwm/defconfig | 1 + configs/shenzhou/nsh/defconfig | 1 + configs/shenzhou/nxwm/defconfig | 1 + configs/shenzhou/thttpd/defconfig | 1 + configs/sim/bas/defconfig | 1 + configs/sim/cxxtest/defconfig | 1 + configs/sim/minibasic/defconfig | 1 + configs/sim/mount/defconfig | 1 + configs/sim/mtdrwb/defconfig | 1 + configs/sim/nettest/defconfig | 1 + configs/sim/nsh/defconfig | 1 + configs/sim/nsh2/defconfig | 1 + configs/sim/nx/defconfig | 1 + configs/sim/nx11/defconfig | 1 + configs/sim/nxlines/defconfig | 1 + configs/sim/nxwm/defconfig | 1 + configs/sim/ostest/defconfig | 1 + configs/sim/pashello/defconfig | 1 + configs/sim/touchscreen/defconfig | 1 + configs/sim/traveler/defconfig | 1 + configs/sim/udgram/defconfig | 1 + configs/sim/unionfs/defconfig | 1 + configs/sim/ustream/defconfig | 1 + configs/skp16c26/ostest/defconfig | 1 + configs/spark/usbserial/defconfig | 1 + configs/stm3210e-eval/composite/defconfig | 1 + configs/stm3210e-eval/nsh/defconfig | 1 + configs/stm3210e-eval/nsh2/defconfig | 1 + configs/stm3210e-eval/nx/defconfig | 1 + configs/stm3210e-eval/nxterm/defconfig | 1 + configs/stm3210e-eval/pm/defconfig | 1 + configs/stm3210e-eval/usbmsc/defconfig | 1 + configs/stm3210e-eval/usbserial/defconfig | 1 + configs/stm3220g-eval/nsh/defconfig | 1 + configs/stm3220g-eval/nsh2/defconfig | 1 + configs/stm3220g-eval/nxwm/defconfig | 1 + configs/stm3240g-eval/discover/defconfig | 1 + configs/stm3240g-eval/knxwm/defconfig | 1 + configs/stm3240g-eval/nsh/defconfig | 1 + configs/stm3240g-eval/nsh2/defconfig | 1 + configs/stm3240g-eval/nxterm/defconfig | 1 + configs/stm3240g-eval/nxwm/defconfig | 1 + configs/stm3240g-eval/webserver/defconfig | 1 + configs/stm32f3discovery/nsh/defconfig | 1 + configs/stm32f3discovery/usbnsh/defconfig | 1 + configs/stm32f429i-disco/extflash/defconfig | 1 + configs/stm32f429i-disco/lcd/defconfig | 1 + configs/stm32f429i-disco/ltdc/defconfig | 1 + configs/stm32f429i-disco/nsh/defconfig | 1 + configs/stm32f429i-disco/nxwm/defconfig | 1 + configs/stm32f429i-disco/usbmsc/defconfig | 1 + configs/stm32f429i-disco/usbnsh/defconfig | 1 + configs/stm32f4discovery/canard/defconfig | 1 + configs/stm32f4discovery/cxxtest/defconfig | 1 + configs/stm32f4discovery/elf/defconfig | 1 + configs/stm32f4discovery/ipv6/defconfig | 1 + configs/stm32f4discovery/kostest/defconfig | 1 + configs/stm32f4discovery/netnsh/defconfig | 1 + configs/stm32f4discovery/nsh/defconfig | 1 + configs/stm32f4discovery/nxlines/defconfig | 1 + configs/stm32f4discovery/pm/defconfig | 1 + configs/stm32f4discovery/posix_spawn/defconfig | 1 + configs/stm32f4discovery/pseudoterm/defconfig | 1 + configs/stm32f4discovery/rgbled/defconfig | 1 + configs/stm32f4discovery/uavcan/defconfig | 1 + configs/stm32f4discovery/usbnsh/defconfig | 1 + configs/stm32f4discovery/winbuild/defconfig | 1 + configs/stm32f4discovery/xen1210/defconfig | 1 + configs/stm32f746-ws/nsh/defconfig | 1 + configs/stm32f746g-disco/nsh/defconfig | 1 + configs/stm32l476-mdk/nsh/defconfig | 1 + configs/stm32l476vg-disco/nsh/defconfig | 1 + configs/stm32ldiscovery/nsh/defconfig | 1 + configs/stm32vldiscovery/nsh/defconfig | 1 + configs/sure-pic32mx/nsh/defconfig | 1 + configs/sure-pic32mx/usbnsh/defconfig | 1 + configs/teensy-2.0/usbmsc/defconfig | 1 + configs/teensy-3.x/nsh/defconfig | 1 + configs/teensy-3.x/usbnsh/defconfig | 1 + configs/teensy-lc/nsh/defconfig | 1 + configs/tm4c123g-launchpad/nsh/defconfig | 1 + configs/tm4c1294-launchpad/ipv6/defconfig | 1 + configs/tm4c1294-launchpad/nsh/defconfig | 1 + configs/twr-k60n512/nsh/defconfig | 1 + configs/twr-k64f120m/netnsh/defconfig | 1 + configs/twr-k64f120m/nsh/defconfig | 1 + configs/u-blox-c027/nsh/defconfig | 1 + configs/ubw32/nsh/defconfig | 1 + configs/viewtool-stm32f107/highpri/defconfig | 1 + configs/viewtool-stm32f107/netnsh/defconfig | 1 + configs/viewtool-stm32f107/nsh/defconfig | 1 + configs/xmc4500-relax/nsh/defconfig | 1 + configs/z16f2800100zcog/nsh/defconfig | 1 + configs/z16f2800100zcog/ostest/defconfig | 1 + configs/z16f2800100zcog/pashello/defconfig | 1 + configs/zkit-arm-1769/nsh/defconfig | 1 + configs/zkit-arm-1769/nxhello/defconfig | 1 + configs/zp214xpa/nsh/defconfig | 1 + configs/zp214xpa/nxlines/defconfig | 1 + 273 files changed, 273 insertions(+) diff --git a/configs/arduino-due/nsh/defconfig b/configs/arduino-due/nsh/defconfig index 385592ef19..00694eb692 100644 --- a/configs/arduino-due/nsh/defconfig +++ b/configs/arduino-due/nsh/defconfig @@ -393,6 +393,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/avr32dev1/nsh/defconfig b/configs/avr32dev1/nsh/defconfig index a7e210c221..c561d5cfd7 100644 --- a/configs/avr32dev1/nsh/defconfig +++ b/configs/avr32dev1/nsh/defconfig @@ -243,6 +243,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/avr32dev1/ostest/defconfig b/configs/avr32dev1/ostest/defconfig index dfdd5a037d..2ad1f6896e 100644 --- a/configs/avr32dev1/ostest/defconfig +++ b/configs/avr32dev1/ostest/defconfig @@ -243,6 +243,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/bambino-200e/netnsh/defconfig b/configs/bambino-200e/netnsh/defconfig index d23e6e4685..a064c25486 100644 --- a/configs/bambino-200e/netnsh/defconfig +++ b/configs/bambino-200e/netnsh/defconfig @@ -401,6 +401,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/bambino-200e/nsh/defconfig b/configs/bambino-200e/nsh/defconfig index 61a12d8769..3d4282dbc8 100644 --- a/configs/bambino-200e/nsh/defconfig +++ b/configs/bambino-200e/nsh/defconfig @@ -386,6 +386,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/bambino-200e/usbnsh/defconfig b/configs/bambino-200e/usbnsh/defconfig index c6047a9771..01f5f86561 100644 --- a/configs/bambino-200e/usbnsh/defconfig +++ b/configs/bambino-200e/usbnsh/defconfig @@ -386,6 +386,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/c5471evm/httpd/defconfig b/configs/c5471evm/httpd/defconfig index 6014c6ffda..d72ae45b16 100644 --- a/configs/c5471evm/httpd/defconfig +++ b/configs/c5471evm/httpd/defconfig @@ -289,6 +289,7 @@ CONFIG_MAX_TASKS=64 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/c5471evm/nsh/defconfig b/configs/c5471evm/nsh/defconfig index e0cf04b541..014118ad61 100644 --- a/configs/c5471evm/nsh/defconfig +++ b/configs/c5471evm/nsh/defconfig @@ -289,6 +289,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/cc3200-launchpad/nsh/defconfig b/configs/cc3200-launchpad/nsh/defconfig index 27e88311f6..0c3ea5e93d 100644 --- a/configs/cc3200-launchpad/nsh/defconfig +++ b/configs/cc3200-launchpad/nsh/defconfig @@ -352,6 +352,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/clicker2-stm32/nsh/defconfig b/configs/clicker2-stm32/nsh/defconfig index 355a7217d1..22ba79f501 100644 --- a/configs/clicker2-stm32/nsh/defconfig +++ b/configs/clicker2-stm32/nsh/defconfig @@ -652,6 +652,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/clicker2-stm32/usbnsh/defconfig b/configs/clicker2-stm32/usbnsh/defconfig index fda0234f36..55d3bb7423 100644 --- a/configs/clicker2-stm32/usbnsh/defconfig +++ b/configs/clicker2-stm32/usbnsh/defconfig @@ -653,6 +653,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/cloudctrl/nsh/defconfig b/configs/cloudctrl/nsh/defconfig index e39a9ca326..9f9139982a 100644 --- a/configs/cloudctrl/nsh/defconfig +++ b/configs/cloudctrl/nsh/defconfig @@ -662,6 +662,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/dk-tm4c129x/ipv6/defconfig b/configs/dk-tm4c129x/ipv6/defconfig index 8cb7e11ce0..36d1a16a75 100644 --- a/configs/dk-tm4c129x/ipv6/defconfig +++ b/configs/dk-tm4c129x/ipv6/defconfig @@ -419,6 +419,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/dk-tm4c129x/nsh/defconfig b/configs/dk-tm4c129x/nsh/defconfig index fed79d510e..6e33f59d6d 100644 --- a/configs/dk-tm4c129x/nsh/defconfig +++ b/configs/dk-tm4c129x/nsh/defconfig @@ -419,6 +419,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/ea3131/nsh/defconfig b/configs/ea3131/nsh/defconfig index bcffd2bb37..dc4dd7bff8 100644 --- a/configs/ea3131/nsh/defconfig +++ b/configs/ea3131/nsh/defconfig @@ -312,6 +312,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/ea3131/pgnsh/defconfig b/configs/ea3131/pgnsh/defconfig index 737846f7cf..1d6a5864ac 100644 --- a/configs/ea3131/pgnsh/defconfig +++ b/configs/ea3131/pgnsh/defconfig @@ -332,6 +332,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/ea3131/usbserial/defconfig b/configs/ea3131/usbserial/defconfig index b3e3461856..4a502be9b7 100644 --- a/configs/ea3131/usbserial/defconfig +++ b/configs/ea3131/usbserial/defconfig @@ -321,6 +321,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/ea3152/ostest/defconfig b/configs/ea3152/ostest/defconfig index 3703c51789..74acabf1d2 100644 --- a/configs/ea3152/ostest/defconfig +++ b/configs/ea3152/ostest/defconfig @@ -308,6 +308,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/eagle100/httpd/defconfig b/configs/eagle100/httpd/defconfig index 6b21f72a9f..d12c0f1530 100644 --- a/configs/eagle100/httpd/defconfig +++ b/configs/eagle100/httpd/defconfig @@ -393,6 +393,7 @@ CONFIG_MAX_TASKS=8 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/eagle100/nsh/defconfig b/configs/eagle100/nsh/defconfig index c7c0b278c5..77155e25bc 100644 --- a/configs/eagle100/nsh/defconfig +++ b/configs/eagle100/nsh/defconfig @@ -398,6 +398,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/eagle100/nxflat/defconfig b/configs/eagle100/nxflat/defconfig index 17496d0a84..c6af5b59d5 100644 --- a/configs/eagle100/nxflat/defconfig +++ b/configs/eagle100/nxflat/defconfig @@ -378,6 +378,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/efm32-g8xx-stk/nsh/defconfig b/configs/efm32-g8xx-stk/nsh/defconfig index 2b7cf9f9f8..999021c231 100644 --- a/configs/efm32-g8xx-stk/nsh/defconfig +++ b/configs/efm32-g8xx-stk/nsh/defconfig @@ -343,6 +343,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/efm32gg-stk3700/nsh/defconfig b/configs/efm32gg-stk3700/nsh/defconfig index ea429d6a69..73141e3451 100644 --- a/configs/efm32gg-stk3700/nsh/defconfig +++ b/configs/efm32gg-stk3700/nsh/defconfig @@ -343,6 +343,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/ekk-lm3s9b96/nsh/defconfig b/configs/ekk-lm3s9b96/nsh/defconfig index 5439a38cfb..dc7faf5968 100644 --- a/configs/ekk-lm3s9b96/nsh/defconfig +++ b/configs/ekk-lm3s9b96/nsh/defconfig @@ -385,6 +385,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/esp32-core/nsh/defconfig b/configs/esp32-core/nsh/defconfig index d1e291a106..5b2d824242 100644 --- a/configs/esp32-core/nsh/defconfig +++ b/configs/esp32-core/nsh/defconfig @@ -225,6 +225,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/esp32-core/ostest/defconfig b/configs/esp32-core/ostest/defconfig index 4e49924f66..1add834b7a 100644 --- a/configs/esp32-core/ostest/defconfig +++ b/configs/esp32-core/ostest/defconfig @@ -225,6 +225,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/esp32-core/smp/defconfig b/configs/esp32-core/smp/defconfig index 90a3da7f79..e603eab3a7 100644 --- a/configs/esp32-core/smp/defconfig +++ b/configs/esp32-core/smp/defconfig @@ -227,6 +227,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/ez80f910200zco/httpd/defconfig b/configs/ez80f910200zco/httpd/defconfig index a969e62d1f..3985af46a6 100644 --- a/configs/ez80f910200zco/httpd/defconfig +++ b/configs/ez80f910200zco/httpd/defconfig @@ -274,6 +274,7 @@ CONFIG_MAX_TASKS=8 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/ez80f910200zco/nsh/defconfig b/configs/ez80f910200zco/nsh/defconfig index e06e4044e6..87f8bffe92 100644 --- a/configs/ez80f910200zco/nsh/defconfig +++ b/configs/ez80f910200zco/nsh/defconfig @@ -274,6 +274,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/ez80f910200zco/poll/defconfig b/configs/ez80f910200zco/poll/defconfig index 6f8033a9e4..26cc069f33 100644 --- a/configs/ez80f910200zco/poll/defconfig +++ b/configs/ez80f910200zco/poll/defconfig @@ -274,6 +274,7 @@ CONFIG_MAX_TASKS=8 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/fire-stm32v2/nsh/defconfig b/configs/fire-stm32v2/nsh/defconfig index 3f877e06ca..e7d49f2a4d 100644 --- a/configs/fire-stm32v2/nsh/defconfig +++ b/configs/fire-stm32v2/nsh/defconfig @@ -671,6 +671,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/freedom-k64f/netnsh/defconfig b/configs/freedom-k64f/netnsh/defconfig index 6bcc276b71..d546e3cdf8 100644 --- a/configs/freedom-k64f/netnsh/defconfig +++ b/configs/freedom-k64f/netnsh/defconfig @@ -414,6 +414,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/freedom-k64f/nsh/defconfig b/configs/freedom-k64f/nsh/defconfig index bfbb82d082..9494c766b7 100644 --- a/configs/freedom-k64f/nsh/defconfig +++ b/configs/freedom-k64f/nsh/defconfig @@ -409,6 +409,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/freedom-k66f/netnsh/defconfig b/configs/freedom-k66f/netnsh/defconfig index e1b82e0fa0..3ed87ae329 100644 --- a/configs/freedom-k66f/netnsh/defconfig +++ b/configs/freedom-k66f/netnsh/defconfig @@ -415,6 +415,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/freedom-k66f/nsh/defconfig b/configs/freedom-k66f/nsh/defconfig index b6d2efa7f7..c1b4346b06 100644 --- a/configs/freedom-k66f/nsh/defconfig +++ b/configs/freedom-k66f/nsh/defconfig @@ -421,6 +421,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/freedom-kl25z/nsh/defconfig b/configs/freedom-kl25z/nsh/defconfig index 84daa61608..44409adf6f 100644 --- a/configs/freedom-kl25z/nsh/defconfig +++ b/configs/freedom-kl25z/nsh/defconfig @@ -320,6 +320,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/freedom-kl26z/nsh/defconfig b/configs/freedom-kl26z/nsh/defconfig index ba03c3d453..fc1c40a759 100644 --- a/configs/freedom-kl26z/nsh/defconfig +++ b/configs/freedom-kl26z/nsh/defconfig @@ -320,6 +320,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/hymini-stm32v/nsh/defconfig b/configs/hymini-stm32v/nsh/defconfig index 1cfd9aae24..fe68926811 100644 --- a/configs/hymini-stm32v/nsh/defconfig +++ b/configs/hymini-stm32v/nsh/defconfig @@ -628,6 +628,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/hymini-stm32v/nsh2/defconfig b/configs/hymini-stm32v/nsh2/defconfig index 7d534b9ca1..ee5e4f93f1 100644 --- a/configs/hymini-stm32v/nsh2/defconfig +++ b/configs/hymini-stm32v/nsh2/defconfig @@ -647,6 +647,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/hymini-stm32v/usbmsc/defconfig b/configs/hymini-stm32v/usbmsc/defconfig index 93b6e551bd..eec91e46a4 100644 --- a/configs/hymini-stm32v/usbmsc/defconfig +++ b/configs/hymini-stm32v/usbmsc/defconfig @@ -634,6 +634,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/hymini-stm32v/usbnsh/defconfig b/configs/hymini-stm32v/usbnsh/defconfig index 934d297d66..239c6c2383 100644 --- a/configs/hymini-stm32v/usbnsh/defconfig +++ b/configs/hymini-stm32v/usbnsh/defconfig @@ -621,6 +621,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/hymini-stm32v/usbserial/defconfig b/configs/hymini-stm32v/usbserial/defconfig index 26e7fc63f2..e5ec56e3e1 100644 --- a/configs/hymini-stm32v/usbserial/defconfig +++ b/configs/hymini-stm32v/usbserial/defconfig @@ -625,6 +625,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/kwikstik-k40/ostest/defconfig b/configs/kwikstik-k40/ostest/defconfig index a4f8844e57..17e0f84d14 100644 --- a/configs/kwikstik-k40/ostest/defconfig +++ b/configs/kwikstik-k40/ostest/defconfig @@ -381,6 +381,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/launchxl-tms57004/nsh/defconfig b/configs/launchxl-tms57004/nsh/defconfig index c0ec78af86..22236f0c96 100644 --- a/configs/launchxl-tms57004/nsh/defconfig +++ b/configs/launchxl-tms57004/nsh/defconfig @@ -310,6 +310,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lincoln60/netnsh/defconfig b/configs/lincoln60/netnsh/defconfig index 5f1c7134d2..4e1fad4b0d 100644 --- a/configs/lincoln60/netnsh/defconfig +++ b/configs/lincoln60/netnsh/defconfig @@ -376,6 +376,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lincoln60/nsh/defconfig b/configs/lincoln60/nsh/defconfig index 9a031ae641..5151256ba6 100644 --- a/configs/lincoln60/nsh/defconfig +++ b/configs/lincoln60/nsh/defconfig @@ -354,6 +354,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lm3s6432-s2e/nsh/defconfig b/configs/lm3s6432-s2e/nsh/defconfig index 0f700344cf..11925f4139 100644 --- a/configs/lm3s6432-s2e/nsh/defconfig +++ b/configs/lm3s6432-s2e/nsh/defconfig @@ -380,6 +380,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lm3s6965-ek/discover/defconfig b/configs/lm3s6965-ek/discover/defconfig index 8921e6a294..d8f8639ebf 100644 --- a/configs/lm3s6965-ek/discover/defconfig +++ b/configs/lm3s6965-ek/discover/defconfig @@ -390,6 +390,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lm3s6965-ek/nsh/defconfig b/configs/lm3s6965-ek/nsh/defconfig index 8921e6a294..d8f8639ebf 100644 --- a/configs/lm3s6965-ek/nsh/defconfig +++ b/configs/lm3s6965-ek/nsh/defconfig @@ -390,6 +390,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lm3s6965-ek/nx/defconfig b/configs/lm3s6965-ek/nx/defconfig index 5ca268e751..890bf26a43 100644 --- a/configs/lm3s6965-ek/nx/defconfig +++ b/configs/lm3s6965-ek/nx/defconfig @@ -375,6 +375,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lm3s8962-ek/nsh/defconfig b/configs/lm3s8962-ek/nsh/defconfig index 479e2b826f..1c62f37b57 100644 --- a/configs/lm3s8962-ek/nsh/defconfig +++ b/configs/lm3s8962-ek/nsh/defconfig @@ -402,6 +402,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lm3s8962-ek/nx/defconfig b/configs/lm3s8962-ek/nx/defconfig index bc2a3da9a6..dfa2360292 100644 --- a/configs/lm3s8962-ek/nx/defconfig +++ b/configs/lm3s8962-ek/nx/defconfig @@ -387,6 +387,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lm4f120-launchpad/nsh/defconfig b/configs/lm4f120-launchpad/nsh/defconfig index 330e7b0e64..b62982b2d4 100644 --- a/configs/lm4f120-launchpad/nsh/defconfig +++ b/configs/lm4f120-launchpad/nsh/defconfig @@ -384,6 +384,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lpc4330-xplorer/nsh/defconfig b/configs/lpc4330-xplorer/nsh/defconfig index 958f82ea84..15fdeb23a5 100644 --- a/configs/lpc4330-xplorer/nsh/defconfig +++ b/configs/lpc4330-xplorer/nsh/defconfig @@ -387,6 +387,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lpc4337-ws/nsh/defconfig b/configs/lpc4337-ws/nsh/defconfig index 902865fca2..85c38182c0 100644 --- a/configs/lpc4337-ws/nsh/defconfig +++ b/configs/lpc4337-ws/nsh/defconfig @@ -392,6 +392,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lpc4357-evb/nsh/defconfig b/configs/lpc4357-evb/nsh/defconfig index c02e95b9ad..f12eb6b565 100644 --- a/configs/lpc4357-evb/nsh/defconfig +++ b/configs/lpc4357-evb/nsh/defconfig @@ -378,6 +378,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lpc4370-link2/nsh/defconfig b/configs/lpc4370-link2/nsh/defconfig index e6dd94324c..e8c417a638 100644 --- a/configs/lpc4370-link2/nsh/defconfig +++ b/configs/lpc4370-link2/nsh/defconfig @@ -388,6 +388,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lpcxpresso-lpc1115/nsh/defconfig b/configs/lpcxpresso-lpc1115/nsh/defconfig index 1aac33b678..deeddca94b 100644 --- a/configs/lpcxpresso-lpc1115/nsh/defconfig +++ b/configs/lpcxpresso-lpc1115/nsh/defconfig @@ -292,6 +292,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lpcxpresso-lpc1768/nsh/defconfig b/configs/lpcxpresso-lpc1768/nsh/defconfig index aebe91afd8..06ceda8cc1 100644 --- a/configs/lpcxpresso-lpc1768/nsh/defconfig +++ b/configs/lpcxpresso-lpc1768/nsh/defconfig @@ -366,6 +366,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lpcxpresso-lpc1768/nx/defconfig b/configs/lpcxpresso-lpc1768/nx/defconfig index 41f8e7270d..48816c4ef3 100644 --- a/configs/lpcxpresso-lpc1768/nx/defconfig +++ b/configs/lpcxpresso-lpc1768/nx/defconfig @@ -354,6 +354,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/lpcxpresso-lpc1768/usbmsc/defconfig b/configs/lpcxpresso-lpc1768/usbmsc/defconfig index bb8b759084..ef5d2b4b47 100644 --- a/configs/lpcxpresso-lpc1768/usbmsc/defconfig +++ b/configs/lpcxpresso-lpc1768/usbmsc/defconfig @@ -366,6 +366,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/mbed/nsh/defconfig b/configs/mbed/nsh/defconfig index 8a252652ba..98949e8db0 100644 --- a/configs/mbed/nsh/defconfig +++ b/configs/mbed/nsh/defconfig @@ -355,6 +355,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/mcu123-lpc214x/composite/defconfig b/configs/mcu123-lpc214x/composite/defconfig index e332f48619..4df7bb1f41 100644 --- a/configs/mcu123-lpc214x/composite/defconfig +++ b/configs/mcu123-lpc214x/composite/defconfig @@ -303,6 +303,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/mcu123-lpc214x/nsh/defconfig b/configs/mcu123-lpc214x/nsh/defconfig index b9af89a29b..eceeefccba 100644 --- a/configs/mcu123-lpc214x/nsh/defconfig +++ b/configs/mcu123-lpc214x/nsh/defconfig @@ -293,6 +293,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/mcu123-lpc214x/usbmsc/defconfig b/configs/mcu123-lpc214x/usbmsc/defconfig index 8835809819..8c544ff681 100644 --- a/configs/mcu123-lpc214x/usbmsc/defconfig +++ b/configs/mcu123-lpc214x/usbmsc/defconfig @@ -303,6 +303,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/mcu123-lpc214x/usbserial/defconfig b/configs/mcu123-lpc214x/usbserial/defconfig index fd0b0a3db1..a0e67fe99b 100644 --- a/configs/mcu123-lpc214x/usbserial/defconfig +++ b/configs/mcu123-lpc214x/usbserial/defconfig @@ -302,6 +302,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/mikroe-stm32f4/fulldemo/defconfig b/configs/mikroe-stm32f4/fulldemo/defconfig index 012a6452e3..bbf651b901 100644 --- a/configs/mikroe-stm32f4/fulldemo/defconfig +++ b/configs/mikroe-stm32f4/fulldemo/defconfig @@ -670,6 +670,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/mikroe-stm32f4/kostest/defconfig b/configs/mikroe-stm32f4/kostest/defconfig index 28e61f6c2d..821dbd9b9f 100644 --- a/configs/mikroe-stm32f4/kostest/defconfig +++ b/configs/mikroe-stm32f4/kostest/defconfig @@ -672,6 +672,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/mikroe-stm32f4/nx/defconfig b/configs/mikroe-stm32f4/nx/defconfig index ddfed5178c..762f5db69a 100644 --- a/configs/mikroe-stm32f4/nx/defconfig +++ b/configs/mikroe-stm32f4/nx/defconfig @@ -621,6 +621,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/mikroe-stm32f4/nxlines/defconfig b/configs/mikroe-stm32f4/nxlines/defconfig index 3d4824dece..0c3708e13a 100644 --- a/configs/mikroe-stm32f4/nxlines/defconfig +++ b/configs/mikroe-stm32f4/nxlines/defconfig @@ -621,6 +621,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/mikroe-stm32f4/nxtext/defconfig b/configs/mikroe-stm32f4/nxtext/defconfig index 9436d9681c..00091f13c8 100644 --- a/configs/mikroe-stm32f4/nxtext/defconfig +++ b/configs/mikroe-stm32f4/nxtext/defconfig @@ -621,6 +621,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/mikroe-stm32f4/usbnsh/defconfig b/configs/mikroe-stm32f4/usbnsh/defconfig index 86407369f4..6aff27e81a 100644 --- a/configs/mikroe-stm32f4/usbnsh/defconfig +++ b/configs/mikroe-stm32f4/usbnsh/defconfig @@ -656,6 +656,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/mirtoo/nsh/defconfig b/configs/mirtoo/nsh/defconfig index 1a2ba210f0..64d0001e69 100644 --- a/configs/mirtoo/nsh/defconfig +++ b/configs/mirtoo/nsh/defconfig @@ -384,6 +384,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/misoc/hello/defconfig b/configs/misoc/hello/defconfig index a0a54eceef..cf0c955efc 100644 --- a/configs/misoc/hello/defconfig +++ b/configs/misoc/hello/defconfig @@ -237,6 +237,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/moxa/nsh/defconfig b/configs/moxa/nsh/defconfig index f697f4e4fc..6cd8e330c1 100644 --- a/configs/moxa/nsh/defconfig +++ b/configs/moxa/nsh/defconfig @@ -269,6 +269,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/mx1ads/ostest/defconfig b/configs/mx1ads/ostest/defconfig index 351c5d15ef..7de94989e1 100644 --- a/configs/mx1ads/ostest/defconfig +++ b/configs/mx1ads/ostest/defconfig @@ -274,6 +274,7 @@ CONFIG_MAX_TASKS=64 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/nr5m100-nexys4/nsh/defconfig b/configs/nr5m100-nexys4/nsh/defconfig index 9ad1b3ba9d..d3e363576f 100644 --- a/configs/nr5m100-nexys4/nsh/defconfig +++ b/configs/nr5m100-nexys4/nsh/defconfig @@ -231,6 +231,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/ntosd-dm320/nsh/defconfig b/configs/ntosd-dm320/nsh/defconfig index cb775f31a8..02ff89e1cc 100644 --- a/configs/ntosd-dm320/nsh/defconfig +++ b/configs/ntosd-dm320/nsh/defconfig @@ -271,6 +271,7 @@ CONFIG_MAX_TASKS=64 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/ntosd-dm320/poll/defconfig b/configs/ntosd-dm320/poll/defconfig index aa8de3c0be..943fd679dc 100644 --- a/configs/ntosd-dm320/poll/defconfig +++ b/configs/ntosd-dm320/poll/defconfig @@ -271,6 +271,7 @@ CONFIG_MAX_TASKS=64 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/ntosd-dm320/webserver/defconfig b/configs/ntosd-dm320/webserver/defconfig index d2320bf672..4c6f2635f5 100644 --- a/configs/ntosd-dm320/webserver/defconfig +++ b/configs/ntosd-dm320/webserver/defconfig @@ -271,6 +271,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/nucleo-144/f746-nsh/defconfig b/configs/nucleo-144/f746-nsh/defconfig index 1a362372b1..98eb5c263e 100644 --- a/configs/nucleo-144/f746-nsh/defconfig +++ b/configs/nucleo-144/f746-nsh/defconfig @@ -490,6 +490,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/nucleo-144/f767-nsh/defconfig b/configs/nucleo-144/f767-nsh/defconfig index c061f7f9b0..772f1f89b6 100644 --- a/configs/nucleo-144/f767-nsh/defconfig +++ b/configs/nucleo-144/f767-nsh/defconfig @@ -494,6 +494,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/nucleo-f303re/adc/defconfig b/configs/nucleo-f303re/adc/defconfig index 1a8f828845..e5357a746b 100644 --- a/configs/nucleo-f303re/adc/defconfig +++ b/configs/nucleo-f303re/adc/defconfig @@ -610,6 +610,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/nucleo-f303re/can/defconfig b/configs/nucleo-f303re/can/defconfig index 84d8e54188..4db532a862 100644 --- a/configs/nucleo-f303re/can/defconfig +++ b/configs/nucleo-f303re/can/defconfig @@ -613,6 +613,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/nucleo-f303re/hello/defconfig b/configs/nucleo-f303re/hello/defconfig index 80f265905f..6a1e7fb7c4 100644 --- a/configs/nucleo-f303re/hello/defconfig +++ b/configs/nucleo-f303re/hello/defconfig @@ -620,6 +620,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/nucleo-f303re/nxlines/defconfig b/configs/nucleo-f303re/nxlines/defconfig index 0082d94fcb..60d56ecc84 100644 --- a/configs/nucleo-f303re/nxlines/defconfig +++ b/configs/nucleo-f303re/nxlines/defconfig @@ -612,6 +612,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/nucleo-f303re/pwm/defconfig b/configs/nucleo-f303re/pwm/defconfig index efddd49b67..630d14fa4e 100644 --- a/configs/nucleo-f303re/pwm/defconfig +++ b/configs/nucleo-f303re/pwm/defconfig @@ -614,6 +614,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/nucleo-f303re/serialrx/defconfig b/configs/nucleo-f303re/serialrx/defconfig index 88407d7671..b4ff9650dc 100644 --- a/configs/nucleo-f303re/serialrx/defconfig +++ b/configs/nucleo-f303re/serialrx/defconfig @@ -625,6 +625,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/nucleo-f303re/uavcan/defconfig b/configs/nucleo-f303re/uavcan/defconfig index 2546b67d90..090fcb42e8 100644 --- a/configs/nucleo-f303re/uavcan/defconfig +++ b/configs/nucleo-f303re/uavcan/defconfig @@ -598,6 +598,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/nucleo-f4x1re/f401-nsh/defconfig b/configs/nucleo-f4x1re/f401-nsh/defconfig index 9b043a844f..6ac098d6b0 100644 --- a/configs/nucleo-f4x1re/f401-nsh/defconfig +++ b/configs/nucleo-f4x1re/f401-nsh/defconfig @@ -617,6 +617,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/nucleo-f4x1re/f411-nsh/defconfig b/configs/nucleo-f4x1re/f411-nsh/defconfig index b289f3270d..ddbdc44dac 100644 --- a/configs/nucleo-f4x1re/f411-nsh/defconfig +++ b/configs/nucleo-f4x1re/f411-nsh/defconfig @@ -619,6 +619,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/nucleo-l476rg/nsh/defconfig b/configs/nucleo-l476rg/nsh/defconfig index 3f842a38cc..f78446519f 100644 --- a/configs/nucleo-l476rg/nsh/defconfig +++ b/configs/nucleo-l476rg/nsh/defconfig @@ -442,6 +442,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/nutiny-nuc120/nsh/defconfig b/configs/nutiny-nuc120/nsh/defconfig index bb97150c70..a2966eee96 100644 --- a/configs/nutiny-nuc120/nsh/defconfig +++ b/configs/nutiny-nuc120/nsh/defconfig @@ -344,6 +344,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-efm32g880f128-stk/nsh/defconfig b/configs/olimex-efm32g880f128-stk/nsh/defconfig index 4013087ecb..75527d42c7 100644 --- a/configs/olimex-efm32g880f128-stk/nsh/defconfig +++ b/configs/olimex-efm32g880f128-stk/nsh/defconfig @@ -337,6 +337,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-lpc-h3131/nsh/defconfig b/configs/olimex-lpc-h3131/nsh/defconfig index a78090e013..26a8a77162 100644 --- a/configs/olimex-lpc-h3131/nsh/defconfig +++ b/configs/olimex-lpc-h3131/nsh/defconfig @@ -310,6 +310,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-lpc1766stk/ftpc/defconfig b/configs/olimex-lpc1766stk/ftpc/defconfig index 44db4095a1..63cec7f15e 100644 --- a/configs/olimex-lpc1766stk/ftpc/defconfig +++ b/configs/olimex-lpc1766stk/ftpc/defconfig @@ -366,6 +366,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-lpc1766stk/hidmouse/defconfig b/configs/olimex-lpc1766stk/hidmouse/defconfig index b278edfb1f..f6cb6524a7 100644 --- a/configs/olimex-lpc1766stk/hidmouse/defconfig +++ b/configs/olimex-lpc1766stk/hidmouse/defconfig @@ -380,6 +380,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-lpc1766stk/nsh/defconfig b/configs/olimex-lpc1766stk/nsh/defconfig index 2c8cf3c744..8d7473910d 100644 --- a/configs/olimex-lpc1766stk/nsh/defconfig +++ b/configs/olimex-lpc1766stk/nsh/defconfig @@ -367,6 +367,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-lpc1766stk/nx/defconfig b/configs/olimex-lpc1766stk/nx/defconfig index bf4822c38c..5728b04b04 100644 --- a/configs/olimex-lpc1766stk/nx/defconfig +++ b/configs/olimex-lpc1766stk/nx/defconfig @@ -365,6 +365,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-lpc1766stk/usbmsc/defconfig b/configs/olimex-lpc1766stk/usbmsc/defconfig index 22e5d46346..47fffba1f5 100644 --- a/configs/olimex-lpc1766stk/usbmsc/defconfig +++ b/configs/olimex-lpc1766stk/usbmsc/defconfig @@ -367,6 +367,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-lpc1766stk/usbserial/defconfig b/configs/olimex-lpc1766stk/usbserial/defconfig index c018b34898..14ddc45c0b 100644 --- a/configs/olimex-lpc1766stk/usbserial/defconfig +++ b/configs/olimex-lpc1766stk/usbserial/defconfig @@ -367,6 +367,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-lpc1766stk/zmodem/defconfig b/configs/olimex-lpc1766stk/zmodem/defconfig index 706bf399a5..b1faa163ca 100644 --- a/configs/olimex-lpc1766stk/zmodem/defconfig +++ b/configs/olimex-lpc1766stk/zmodem/defconfig @@ -368,6 +368,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-lpc2378/nsh/defconfig b/configs/olimex-lpc2378/nsh/defconfig index 107dc433f2..7aa2abee46 100644 --- a/configs/olimex-lpc2378/nsh/defconfig +++ b/configs/olimex-lpc2378/nsh/defconfig @@ -280,6 +280,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-stm32-e407/discover/defconfig b/configs/olimex-stm32-e407/discover/defconfig index 45fe31dd49..6258b571f7 100644 --- a/configs/olimex-stm32-e407/discover/defconfig +++ b/configs/olimex-stm32-e407/discover/defconfig @@ -665,6 +665,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-stm32-e407/netnsh/defconfig b/configs/olimex-stm32-e407/netnsh/defconfig index 34db63f2e4..5b545509a9 100644 --- a/configs/olimex-stm32-e407/netnsh/defconfig +++ b/configs/olimex-stm32-e407/netnsh/defconfig @@ -665,6 +665,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-stm32-e407/nsh/defconfig b/configs/olimex-stm32-e407/nsh/defconfig index a1cd1d5db7..b74992be34 100644 --- a/configs/olimex-stm32-e407/nsh/defconfig +++ b/configs/olimex-stm32-e407/nsh/defconfig @@ -643,6 +643,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-stm32-e407/telnetd/defconfig b/configs/olimex-stm32-e407/telnetd/defconfig index ab40706675..95cd79b059 100644 --- a/configs/olimex-stm32-e407/telnetd/defconfig +++ b/configs/olimex-stm32-e407/telnetd/defconfig @@ -665,6 +665,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-stm32-e407/usbnsh/defconfig b/configs/olimex-stm32-e407/usbnsh/defconfig index 73b5b0f45a..ca08e311f8 100644 --- a/configs/olimex-stm32-e407/usbnsh/defconfig +++ b/configs/olimex-stm32-e407/usbnsh/defconfig @@ -649,6 +649,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-stm32-e407/webserver/defconfig b/configs/olimex-stm32-e407/webserver/defconfig index a20352448f..9c68bf47a3 100644 --- a/configs/olimex-stm32-e407/webserver/defconfig +++ b/configs/olimex-stm32-e407/webserver/defconfig @@ -665,6 +665,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-stm32-h405/usbnsh/defconfig b/configs/olimex-stm32-h405/usbnsh/defconfig index e0079fda92..5d02b51b90 100644 --- a/configs/olimex-stm32-h405/usbnsh/defconfig +++ b/configs/olimex-stm32-h405/usbnsh/defconfig @@ -667,6 +667,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-stm32-h407/nsh/defconfig b/configs/olimex-stm32-h407/nsh/defconfig index fc5a113c74..8c44dd395b 100644 --- a/configs/olimex-stm32-h407/nsh/defconfig +++ b/configs/olimex-stm32-h407/nsh/defconfig @@ -643,6 +643,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-stm32-p107/nsh/defconfig b/configs/olimex-stm32-p107/nsh/defconfig index 3a77537c5c..65d116da37 100644 --- a/configs/olimex-stm32-p107/nsh/defconfig +++ b/configs/olimex-stm32-p107/nsh/defconfig @@ -632,6 +632,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-stm32-p207/nsh/defconfig b/configs/olimex-stm32-p207/nsh/defconfig index a9b0e19e10..6f9a15d88f 100644 --- a/configs/olimex-stm32-p207/nsh/defconfig +++ b/configs/olimex-stm32-p207/nsh/defconfig @@ -693,6 +693,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-stm32-p407/knsh/defconfig b/configs/olimex-stm32-p407/knsh/defconfig index c1a5cb58bf..ec07cf7e05 100644 --- a/configs/olimex-stm32-p407/knsh/defconfig +++ b/configs/olimex-stm32-p407/knsh/defconfig @@ -655,6 +655,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-stm32-p407/nsh/defconfig b/configs/olimex-stm32-p407/nsh/defconfig index bbf8b95d54..ed41bffe55 100644 --- a/configs/olimex-stm32-p407/nsh/defconfig +++ b/configs/olimex-stm32-p407/nsh/defconfig @@ -659,6 +659,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-strp711/nettest/defconfig b/configs/olimex-strp711/nettest/defconfig index 6bde1e1f3b..80f439771a 100644 --- a/configs/olimex-strp711/nettest/defconfig +++ b/configs/olimex-strp711/nettest/defconfig @@ -299,6 +299,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/olimex-strp711/nsh/defconfig b/configs/olimex-strp711/nsh/defconfig index 6a46e966b6..84f66ba8c2 100644 --- a/configs/olimex-strp711/nsh/defconfig +++ b/configs/olimex-strp711/nsh/defconfig @@ -303,6 +303,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/open1788/knsh/defconfig b/configs/open1788/knsh/defconfig index f539625c3c..a4be59b062 100644 --- a/configs/open1788/knsh/defconfig +++ b/configs/open1788/knsh/defconfig @@ -367,6 +367,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/open1788/nsh/defconfig b/configs/open1788/nsh/defconfig index d8fc7e13fb..bcfeb085de 100644 --- a/configs/open1788/nsh/defconfig +++ b/configs/open1788/nsh/defconfig @@ -365,6 +365,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/open1788/nxlines/defconfig b/configs/open1788/nxlines/defconfig index c95b7d51f4..e419534665 100644 --- a/configs/open1788/nxlines/defconfig +++ b/configs/open1788/nxlines/defconfig @@ -399,6 +399,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/pcblogic-pic32mx/nsh/defconfig b/configs/pcblogic-pic32mx/nsh/defconfig index 015492f3c3..a7c11b2d0d 100644 --- a/configs/pcblogic-pic32mx/nsh/defconfig +++ b/configs/pcblogic-pic32mx/nsh/defconfig @@ -381,6 +381,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/pcduino-a10/nsh/defconfig b/configs/pcduino-a10/nsh/defconfig index 653a69aad8..c6402c0564 100644 --- a/configs/pcduino-a10/nsh/defconfig +++ b/configs/pcduino-a10/nsh/defconfig @@ -368,6 +368,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/photon/nsh/defconfig b/configs/photon/nsh/defconfig index 0072a232eb..f11b644af3 100644 --- a/configs/photon/nsh/defconfig +++ b/configs/photon/nsh/defconfig @@ -637,6 +637,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/photon/usbnsh/defconfig b/configs/photon/usbnsh/defconfig index 251914b079..8b0111b326 100644 --- a/configs/photon/usbnsh/defconfig +++ b/configs/photon/usbnsh/defconfig @@ -638,6 +638,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/pic32mx-starterkit/nsh/defconfig b/configs/pic32mx-starterkit/nsh/defconfig index f89384e555..6f887072a3 100644 --- a/configs/pic32mx-starterkit/nsh/defconfig +++ b/configs/pic32mx-starterkit/nsh/defconfig @@ -387,6 +387,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/pic32mx-starterkit/nsh2/defconfig b/configs/pic32mx-starterkit/nsh2/defconfig index a8b36d84ce..97f66c82f1 100644 --- a/configs/pic32mx-starterkit/nsh2/defconfig +++ b/configs/pic32mx-starterkit/nsh2/defconfig @@ -398,6 +398,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/pic32mx7mmb/nsh/defconfig b/configs/pic32mx7mmb/nsh/defconfig index 9b7faf1af7..929fecc497 100644 --- a/configs/pic32mx7mmb/nsh/defconfig +++ b/configs/pic32mx7mmb/nsh/defconfig @@ -407,6 +407,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/pic32mz-starterkit/nsh/defconfig b/configs/pic32mz-starterkit/nsh/defconfig index 5090e2d447..35589060bc 100644 --- a/configs/pic32mz-starterkit/nsh/defconfig +++ b/configs/pic32mz-starterkit/nsh/defconfig @@ -314,6 +314,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/qemu-i486/nsh/defconfig b/configs/qemu-i486/nsh/defconfig index 4be4465d1a..b925e48dcc 100644 --- a/configs/qemu-i486/nsh/defconfig +++ b/configs/qemu-i486/nsh/defconfig @@ -207,6 +207,7 @@ CONFIG_MAX_TASKS=64 # Pthread Options # CONFIG_PTHREAD_MUTEX_TYPES=y +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/qemu-i486/ostest/defconfig b/configs/qemu-i486/ostest/defconfig index 6a1b80f37f..5176deaa7e 100644 --- a/configs/qemu-i486/ostest/defconfig +++ b/configs/qemu-i486/ostest/defconfig @@ -207,6 +207,7 @@ CONFIG_MAX_TASKS=64 # Pthread Options # CONFIG_PTHREAD_MUTEX_TYPES=y +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sabre-6quad/nsh/defconfig b/configs/sabre-6quad/nsh/defconfig index dfa9dc689f..0caeea2138 100644 --- a/configs/sabre-6quad/nsh/defconfig +++ b/configs/sabre-6quad/nsh/defconfig @@ -323,6 +323,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sabre-6quad/smp/defconfig b/configs/sabre-6quad/smp/defconfig index 21569e99cb..1aec2d84ed 100644 --- a/configs/sabre-6quad/smp/defconfig +++ b/configs/sabre-6quad/smp/defconfig @@ -328,6 +328,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sam3u-ek/knsh/defconfig b/configs/sam3u-ek/knsh/defconfig index fa70b85b3c..1bac14a860 100644 --- a/configs/sam3u-ek/knsh/defconfig +++ b/configs/sam3u-ek/knsh/defconfig @@ -390,6 +390,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sam3u-ek/nsh/defconfig b/configs/sam3u-ek/nsh/defconfig index 4f3af6a72a..39d9271e1f 100644 --- a/configs/sam3u-ek/nsh/defconfig +++ b/configs/sam3u-ek/nsh/defconfig @@ -389,6 +389,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sam3u-ek/nx/defconfig b/configs/sam3u-ek/nx/defconfig index 7150bd5790..836d29844c 100644 --- a/configs/sam3u-ek/nx/defconfig +++ b/configs/sam3u-ek/nx/defconfig @@ -384,6 +384,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sam3u-ek/nxwm/defconfig b/configs/sam3u-ek/nxwm/defconfig index cbb1614bab..f6ac263211 100644 --- a/configs/sam3u-ek/nxwm/defconfig +++ b/configs/sam3u-ek/nxwm/defconfig @@ -396,6 +396,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sam4cmp-db/nsh/defconfig b/configs/sam4cmp-db/nsh/defconfig index 5790893479..c7e96c2425 100644 --- a/configs/sam4cmp-db/nsh/defconfig +++ b/configs/sam4cmp-db/nsh/defconfig @@ -401,6 +401,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sam4e-ek/nsh/defconfig b/configs/sam4e-ek/nsh/defconfig index 11cea1f028..7eff414e3d 100644 --- a/configs/sam4e-ek/nsh/defconfig +++ b/configs/sam4e-ek/nsh/defconfig @@ -434,6 +434,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sam4e-ek/usbnsh/defconfig b/configs/sam4e-ek/usbnsh/defconfig index a9a085da8d..68f8fe5e1f 100644 --- a/configs/sam4e-ek/usbnsh/defconfig +++ b/configs/sam4e-ek/usbnsh/defconfig @@ -440,6 +440,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sam4l-xplained/nsh/defconfig b/configs/sam4l-xplained/nsh/defconfig index a814652926..34b6e44043 100644 --- a/configs/sam4l-xplained/nsh/defconfig +++ b/configs/sam4l-xplained/nsh/defconfig @@ -407,6 +407,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sam4s-xplained-pro/nsh/defconfig b/configs/sam4s-xplained-pro/nsh/defconfig index b652a1e88f..1e32e6a8f6 100644 --- a/configs/sam4s-xplained-pro/nsh/defconfig +++ b/configs/sam4s-xplained-pro/nsh/defconfig @@ -428,6 +428,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sam4s-xplained/nsh/defconfig b/configs/sam4s-xplained/nsh/defconfig index 83ea926edb..2f62a8f4ba 100644 --- a/configs/sam4s-xplained/nsh/defconfig +++ b/configs/sam4s-xplained/nsh/defconfig @@ -387,6 +387,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d2-xult/nsh/defconfig b/configs/sama5d2-xult/nsh/defconfig index 12fae8f490..9ea5e61920 100644 --- a/configs/sama5d2-xult/nsh/defconfig +++ b/configs/sama5d2-xult/nsh/defconfig @@ -463,6 +463,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d3-xplained/bridge/defconfig b/configs/sama5d3-xplained/bridge/defconfig index a4492196c5..832bcc3d95 100644 --- a/configs/sama5d3-xplained/bridge/defconfig +++ b/configs/sama5d3-xplained/bridge/defconfig @@ -461,6 +461,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d3-xplained/nsh/defconfig b/configs/sama5d3-xplained/nsh/defconfig index bc5af1a452..6e7fed8017 100644 --- a/configs/sama5d3-xplained/nsh/defconfig +++ b/configs/sama5d3-xplained/nsh/defconfig @@ -426,6 +426,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d3x-ek/demo/defconfig b/configs/sama5d3x-ek/demo/defconfig index 6192d4e394..8f2c5d2cd3 100644 --- a/configs/sama5d3x-ek/demo/defconfig +++ b/configs/sama5d3x-ek/demo/defconfig @@ -489,6 +489,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d3x-ek/hello/defconfig b/configs/sama5d3x-ek/hello/defconfig index 8c94fe0d4f..db156cbd32 100644 --- a/configs/sama5d3x-ek/hello/defconfig +++ b/configs/sama5d3x-ek/hello/defconfig @@ -408,6 +408,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d3x-ek/norboot/defconfig b/configs/sama5d3x-ek/norboot/defconfig index a2cd0cd6ce..56ffd88c53 100644 --- a/configs/sama5d3x-ek/norboot/defconfig +++ b/configs/sama5d3x-ek/norboot/defconfig @@ -422,6 +422,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d3x-ek/nsh/defconfig b/configs/sama5d3x-ek/nsh/defconfig index 8db191b838..9854da0346 100644 --- a/configs/sama5d3x-ek/nsh/defconfig +++ b/configs/sama5d3x-ek/nsh/defconfig @@ -425,6 +425,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d3x-ek/nx/defconfig b/configs/sama5d3x-ek/nx/defconfig index fe0bf5e3ad..9d50e995e5 100644 --- a/configs/sama5d3x-ek/nx/defconfig +++ b/configs/sama5d3x-ek/nx/defconfig @@ -467,6 +467,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d3x-ek/nxplayer/defconfig b/configs/sama5d3x-ek/nxplayer/defconfig index b90e25e494..f5f62d6b77 100644 --- a/configs/sama5d3x-ek/nxplayer/defconfig +++ b/configs/sama5d3x-ek/nxplayer/defconfig @@ -486,6 +486,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d3x-ek/nxwm/defconfig b/configs/sama5d3x-ek/nxwm/defconfig index 7626a2b947..e8ae80a84a 100644 --- a/configs/sama5d3x-ek/nxwm/defconfig +++ b/configs/sama5d3x-ek/nxwm/defconfig @@ -501,6 +501,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d3x-ek/ov2640/defconfig b/configs/sama5d3x-ek/ov2640/defconfig index 57fa4dda6e..76c5dcf66d 100644 --- a/configs/sama5d3x-ek/ov2640/defconfig +++ b/configs/sama5d3x-ek/ov2640/defconfig @@ -473,6 +473,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d4-ek/at25boot/defconfig b/configs/sama5d4-ek/at25boot/defconfig index c19493d204..7eb4be0921 100644 --- a/configs/sama5d4-ek/at25boot/defconfig +++ b/configs/sama5d4-ek/at25boot/defconfig @@ -451,6 +451,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d4-ek/bridge/defconfig b/configs/sama5d4-ek/bridge/defconfig index 85245101b0..231ddb7907 100644 --- a/configs/sama5d4-ek/bridge/defconfig +++ b/configs/sama5d4-ek/bridge/defconfig @@ -479,6 +479,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d4-ek/dramboot/defconfig b/configs/sama5d4-ek/dramboot/defconfig index 1150a6609f..99a516b291 100644 --- a/configs/sama5d4-ek/dramboot/defconfig +++ b/configs/sama5d4-ek/dramboot/defconfig @@ -444,6 +444,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d4-ek/elf/defconfig b/configs/sama5d4-ek/elf/defconfig index 9632bcdff9..fcbad45992 100644 --- a/configs/sama5d4-ek/elf/defconfig +++ b/configs/sama5d4-ek/elf/defconfig @@ -454,6 +454,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d4-ek/ipv6/defconfig b/configs/sama5d4-ek/ipv6/defconfig index b2e488e00f..d83898fe04 100644 --- a/configs/sama5d4-ek/ipv6/defconfig +++ b/configs/sama5d4-ek/ipv6/defconfig @@ -578,6 +578,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d4-ek/knsh/defconfig b/configs/sama5d4-ek/knsh/defconfig index be1c9fd5b4..e617e8e206 100644 --- a/configs/sama5d4-ek/knsh/defconfig +++ b/configs/sama5d4-ek/knsh/defconfig @@ -471,6 +471,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d4-ek/nsh/defconfig b/configs/sama5d4-ek/nsh/defconfig index 820d434038..67627b5567 100644 --- a/configs/sama5d4-ek/nsh/defconfig +++ b/configs/sama5d4-ek/nsh/defconfig @@ -578,6 +578,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d4-ek/nxwm/defconfig b/configs/sama5d4-ek/nxwm/defconfig index 9f49ae3a7f..f2dbc256a6 100644 --- a/configs/sama5d4-ek/nxwm/defconfig +++ b/configs/sama5d4-ek/nxwm/defconfig @@ -550,6 +550,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sama5d4-ek/ramtest/defconfig b/configs/sama5d4-ek/ramtest/defconfig index 943e794b2d..b5466c4c02 100644 --- a/configs/sama5d4-ek/ramtest/defconfig +++ b/configs/sama5d4-ek/ramtest/defconfig @@ -443,6 +443,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/samd20-xplained/nsh/defconfig b/configs/samd20-xplained/nsh/defconfig index accfc04cc2..9985c9cc06 100644 --- a/configs/samd20-xplained/nsh/defconfig +++ b/configs/samd20-xplained/nsh/defconfig @@ -370,6 +370,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/samd21-xplained/nsh/defconfig b/configs/samd21-xplained/nsh/defconfig index 7d13c4909e..1f42da0c98 100644 --- a/configs/samd21-xplained/nsh/defconfig +++ b/configs/samd21-xplained/nsh/defconfig @@ -368,6 +368,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/same70-xplained/netnsh/defconfig b/configs/same70-xplained/netnsh/defconfig index 7e0b322e2c..804f41e4fc 100644 --- a/configs/same70-xplained/netnsh/defconfig +++ b/configs/same70-xplained/netnsh/defconfig @@ -453,6 +453,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/same70-xplained/nsh/defconfig b/configs/same70-xplained/nsh/defconfig index 95fc9237c7..106f249814 100644 --- a/configs/same70-xplained/nsh/defconfig +++ b/configs/same70-xplained/nsh/defconfig @@ -438,6 +438,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/saml21-xplained/nsh/defconfig b/configs/saml21-xplained/nsh/defconfig index 44b619e305..aab9988399 100644 --- a/configs/saml21-xplained/nsh/defconfig +++ b/configs/saml21-xplained/nsh/defconfig @@ -356,6 +356,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/samv71-xult/knsh/defconfig b/configs/samv71-xult/knsh/defconfig index 756d20cf7a..c23bda38ee 100644 --- a/configs/samv71-xult/knsh/defconfig +++ b/configs/samv71-xult/knsh/defconfig @@ -446,6 +446,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/samv71-xult/module/defconfig b/configs/samv71-xult/module/defconfig index 8f993004c8..e4172937e3 100644 --- a/configs/samv71-xult/module/defconfig +++ b/configs/samv71-xult/module/defconfig @@ -421,6 +421,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/samv71-xult/mxtxplnd/defconfig b/configs/samv71-xult/mxtxplnd/defconfig index 562257bd95..d34d7ffdac 100644 --- a/configs/samv71-xult/mxtxplnd/defconfig +++ b/configs/samv71-xult/mxtxplnd/defconfig @@ -439,6 +439,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/samv71-xult/netnsh/defconfig b/configs/samv71-xult/netnsh/defconfig index 7c5afb7acc..b651274195 100644 --- a/configs/samv71-xult/netnsh/defconfig +++ b/configs/samv71-xult/netnsh/defconfig @@ -456,6 +456,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/samv71-xult/nsh/defconfig b/configs/samv71-xult/nsh/defconfig index 4f2ecda618..99e63b5e88 100644 --- a/configs/samv71-xult/nsh/defconfig +++ b/configs/samv71-xult/nsh/defconfig @@ -441,6 +441,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/samv71-xult/nxwm/defconfig b/configs/samv71-xult/nxwm/defconfig index f50d5ff31f..19da1735ac 100644 --- a/configs/samv71-xult/nxwm/defconfig +++ b/configs/samv71-xult/nxwm/defconfig @@ -440,6 +440,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/samv71-xult/vnc/defconfig b/configs/samv71-xult/vnc/defconfig index 1402ffb99d..b547b6f685 100644 --- a/configs/samv71-xult/vnc/defconfig +++ b/configs/samv71-xult/vnc/defconfig @@ -455,6 +455,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/samv71-xult/vnxwm/defconfig b/configs/samv71-xult/vnxwm/defconfig index f7fef3296d..d8c8863cb6 100644 --- a/configs/samv71-xult/vnxwm/defconfig +++ b/configs/samv71-xult/vnxwm/defconfig @@ -456,6 +456,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/shenzhou/nsh/defconfig b/configs/shenzhou/nsh/defconfig index 30c6547cff..1f26e5a9ca 100644 --- a/configs/shenzhou/nsh/defconfig +++ b/configs/shenzhou/nsh/defconfig @@ -652,6 +652,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/shenzhou/nxwm/defconfig b/configs/shenzhou/nxwm/defconfig index 6306307a44..3fb83b792a 100644 --- a/configs/shenzhou/nxwm/defconfig +++ b/configs/shenzhou/nxwm/defconfig @@ -675,6 +675,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/shenzhou/thttpd/defconfig b/configs/shenzhou/thttpd/defconfig index 6e40305a21..e005e95bda 100644 --- a/configs/shenzhou/thttpd/defconfig +++ b/configs/shenzhou/thttpd/defconfig @@ -653,6 +653,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/bas/defconfig b/configs/sim/bas/defconfig index 04f89c514f..0c0dee9bf7 100644 --- a/configs/sim/bas/defconfig +++ b/configs/sim/bas/defconfig @@ -209,6 +209,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/cxxtest/defconfig b/configs/sim/cxxtest/defconfig index 7625148fcd..ba004c13cf 100644 --- a/configs/sim/cxxtest/defconfig +++ b/configs/sim/cxxtest/defconfig @@ -202,6 +202,7 @@ CONFIG_MAX_TASKS=64 # Pthread Options # CONFIG_PTHREAD_MUTEX_TYPES=y +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/minibasic/defconfig b/configs/sim/minibasic/defconfig index 0e582ed3cd..b676b55e19 100644 --- a/configs/sim/minibasic/defconfig +++ b/configs/sim/minibasic/defconfig @@ -236,6 +236,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/mount/defconfig b/configs/sim/mount/defconfig index c7a83e8908..e36e9cd8fb 100644 --- a/configs/sim/mount/defconfig +++ b/configs/sim/mount/defconfig @@ -202,6 +202,7 @@ CONFIG_MAX_TASKS=64 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/mtdrwb/defconfig b/configs/sim/mtdrwb/defconfig index 0debd96feb..24bd24353c 100644 --- a/configs/sim/mtdrwb/defconfig +++ b/configs/sim/mtdrwb/defconfig @@ -202,6 +202,7 @@ CONFIG_MAX_TASKS=64 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/nettest/defconfig b/configs/sim/nettest/defconfig index 1e471fd063..14b60be76e 100644 --- a/configs/sim/nettest/defconfig +++ b/configs/sim/nettest/defconfig @@ -202,6 +202,7 @@ CONFIG_MAX_TASKS=64 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/nsh/defconfig b/configs/sim/nsh/defconfig index ff4efbb0f0..3479b545db 100644 --- a/configs/sim/nsh/defconfig +++ b/configs/sim/nsh/defconfig @@ -209,6 +209,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/nsh2/defconfig b/configs/sim/nsh2/defconfig index d6fd7c8e5b..52984d9d7a 100644 --- a/configs/sim/nsh2/defconfig +++ b/configs/sim/nsh2/defconfig @@ -217,6 +217,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/nx/defconfig b/configs/sim/nx/defconfig index e9c94ef24d..22c51e7e58 100644 --- a/configs/sim/nx/defconfig +++ b/configs/sim/nx/defconfig @@ -206,6 +206,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/nx11/defconfig b/configs/sim/nx11/defconfig index 1176121728..96a4d28990 100644 --- a/configs/sim/nx11/defconfig +++ b/configs/sim/nx11/defconfig @@ -207,6 +207,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/nxlines/defconfig b/configs/sim/nxlines/defconfig index fb547cc57f..c162a7afcf 100644 --- a/configs/sim/nxlines/defconfig +++ b/configs/sim/nxlines/defconfig @@ -217,6 +217,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/nxwm/defconfig b/configs/sim/nxwm/defconfig index 2749e54197..18d7c70572 100644 --- a/configs/sim/nxwm/defconfig +++ b/configs/sim/nxwm/defconfig @@ -212,6 +212,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/ostest/defconfig b/configs/sim/ostest/defconfig index b76f88dfd0..d13dc5b991 100644 --- a/configs/sim/ostest/defconfig +++ b/configs/sim/ostest/defconfig @@ -203,6 +203,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # CONFIG_PTHREAD_MUTEX_TYPES=y +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/pashello/defconfig b/configs/sim/pashello/defconfig index 5c329f978b..60484d0992 100644 --- a/configs/sim/pashello/defconfig +++ b/configs/sim/pashello/defconfig @@ -202,6 +202,7 @@ CONFIG_MAX_TASKS=64 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/touchscreen/defconfig b/configs/sim/touchscreen/defconfig index a8ad9b5f43..c4a3c41837 100644 --- a/configs/sim/touchscreen/defconfig +++ b/configs/sim/touchscreen/defconfig @@ -217,6 +217,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/traveler/defconfig b/configs/sim/traveler/defconfig index db68d953a9..833646bb93 100644 --- a/configs/sim/traveler/defconfig +++ b/configs/sim/traveler/defconfig @@ -210,6 +210,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/udgram/defconfig b/configs/sim/udgram/defconfig index aaf31194e1..87e97419c1 100644 --- a/configs/sim/udgram/defconfig +++ b/configs/sim/udgram/defconfig @@ -209,6 +209,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/unionfs/defconfig b/configs/sim/unionfs/defconfig index 27dc23dd88..fbf56e5a9d 100644 --- a/configs/sim/unionfs/defconfig +++ b/configs/sim/unionfs/defconfig @@ -209,6 +209,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sim/ustream/defconfig b/configs/sim/ustream/defconfig index 146cf9695f..3b4cf6bdd2 100644 --- a/configs/sim/ustream/defconfig +++ b/configs/sim/ustream/defconfig @@ -209,6 +209,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/skp16c26/ostest/defconfig b/configs/skp16c26/ostest/defconfig index 6869e4ca4c..226e13967b 100644 --- a/configs/skp16c26/ostest/defconfig +++ b/configs/skp16c26/ostest/defconfig @@ -197,6 +197,7 @@ CONFIG_MAX_TASKS=8 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/spark/usbserial/defconfig b/configs/spark/usbserial/defconfig index 6813801980..c50bae0087 100644 --- a/configs/spark/usbserial/defconfig +++ b/configs/spark/usbserial/defconfig @@ -633,6 +633,7 @@ CONFIG_MAX_TASKS=12 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3210e-eval/composite/defconfig b/configs/stm3210e-eval/composite/defconfig index c003251c1e..7293f13d64 100644 --- a/configs/stm3210e-eval/composite/defconfig +++ b/configs/stm3210e-eval/composite/defconfig @@ -648,6 +648,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3210e-eval/nsh/defconfig b/configs/stm3210e-eval/nsh/defconfig index 45d83032ce..de6c8fbada 100644 --- a/configs/stm3210e-eval/nsh/defconfig +++ b/configs/stm3210e-eval/nsh/defconfig @@ -649,6 +649,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3210e-eval/nsh2/defconfig b/configs/stm3210e-eval/nsh2/defconfig index c30a1bc7d2..846aceb4f8 100644 --- a/configs/stm3210e-eval/nsh2/defconfig +++ b/configs/stm3210e-eval/nsh2/defconfig @@ -665,6 +665,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3210e-eval/nx/defconfig b/configs/stm3210e-eval/nx/defconfig index 544b55c68c..72cffd064c 100644 --- a/configs/stm3210e-eval/nx/defconfig +++ b/configs/stm3210e-eval/nx/defconfig @@ -652,6 +652,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3210e-eval/nxterm/defconfig b/configs/stm3210e-eval/nxterm/defconfig index bd9a3c6f9d..2b7d5531d0 100644 --- a/configs/stm3210e-eval/nxterm/defconfig +++ b/configs/stm3210e-eval/nxterm/defconfig @@ -645,6 +645,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3210e-eval/pm/defconfig b/configs/stm3210e-eval/pm/defconfig index b8047456f1..301b8afa07 100644 --- a/configs/stm3210e-eval/pm/defconfig +++ b/configs/stm3210e-eval/pm/defconfig @@ -665,6 +665,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3210e-eval/usbmsc/defconfig b/configs/stm3210e-eval/usbmsc/defconfig index 60950a454f..62b5513ad4 100644 --- a/configs/stm3210e-eval/usbmsc/defconfig +++ b/configs/stm3210e-eval/usbmsc/defconfig @@ -639,6 +639,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3210e-eval/usbserial/defconfig b/configs/stm3210e-eval/usbserial/defconfig index 12f55502e5..6506425af5 100644 --- a/configs/stm3210e-eval/usbserial/defconfig +++ b/configs/stm3210e-eval/usbserial/defconfig @@ -631,6 +631,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3220g-eval/nsh/defconfig b/configs/stm3220g-eval/nsh/defconfig index 127c8723b5..bf70159441 100644 --- a/configs/stm3220g-eval/nsh/defconfig +++ b/configs/stm3220g-eval/nsh/defconfig @@ -671,6 +671,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3220g-eval/nsh2/defconfig b/configs/stm3220g-eval/nsh2/defconfig index 6e9bc14fa8..a443c30f5c 100644 --- a/configs/stm3220g-eval/nsh2/defconfig +++ b/configs/stm3220g-eval/nsh2/defconfig @@ -672,6 +672,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3220g-eval/nxwm/defconfig b/configs/stm3220g-eval/nxwm/defconfig index a339400d24..50cf143791 100644 --- a/configs/stm3220g-eval/nxwm/defconfig +++ b/configs/stm3220g-eval/nxwm/defconfig @@ -691,6 +691,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3240g-eval/discover/defconfig b/configs/stm3240g-eval/discover/defconfig index 8f58437cc3..ce7c4a8083 100644 --- a/configs/stm3240g-eval/discover/defconfig +++ b/configs/stm3240g-eval/discover/defconfig @@ -670,6 +670,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3240g-eval/knxwm/defconfig b/configs/stm3240g-eval/knxwm/defconfig index e9b5edca2b..f1925469d8 100644 --- a/configs/stm3240g-eval/knxwm/defconfig +++ b/configs/stm3240g-eval/knxwm/defconfig @@ -685,6 +685,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3240g-eval/nsh/defconfig b/configs/stm3240g-eval/nsh/defconfig index c18a3e8462..9b5c354ee7 100644 --- a/configs/stm3240g-eval/nsh/defconfig +++ b/configs/stm3240g-eval/nsh/defconfig @@ -685,6 +685,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3240g-eval/nsh2/defconfig b/configs/stm3240g-eval/nsh2/defconfig index aa74992b4e..18727a8f64 100644 --- a/configs/stm3240g-eval/nsh2/defconfig +++ b/configs/stm3240g-eval/nsh2/defconfig @@ -676,6 +676,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3240g-eval/nxterm/defconfig b/configs/stm3240g-eval/nxterm/defconfig index 94440b32fa..6e37ea5759 100644 --- a/configs/stm3240g-eval/nxterm/defconfig +++ b/configs/stm3240g-eval/nxterm/defconfig @@ -695,6 +695,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3240g-eval/nxwm/defconfig b/configs/stm3240g-eval/nxwm/defconfig index 24e4a5db75..26bca3feb3 100644 --- a/configs/stm3240g-eval/nxwm/defconfig +++ b/configs/stm3240g-eval/nxwm/defconfig @@ -695,6 +695,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm3240g-eval/webserver/defconfig b/configs/stm3240g-eval/webserver/defconfig index 923e8ac1ed..ee8d9cded9 100644 --- a/configs/stm3240g-eval/webserver/defconfig +++ b/configs/stm3240g-eval/webserver/defconfig @@ -675,6 +675,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f3discovery/nsh/defconfig b/configs/stm32f3discovery/nsh/defconfig index 5b31d15483..2234c65bea 100644 --- a/configs/stm32f3discovery/nsh/defconfig +++ b/configs/stm32f3discovery/nsh/defconfig @@ -635,6 +635,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f3discovery/usbnsh/defconfig b/configs/stm32f3discovery/usbnsh/defconfig index 1e7c46dc58..c068636085 100644 --- a/configs/stm32f3discovery/usbnsh/defconfig +++ b/configs/stm32f3discovery/usbnsh/defconfig @@ -642,6 +642,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f429i-disco/extflash/defconfig b/configs/stm32f429i-disco/extflash/defconfig index 193be96591..763981c2b8 100644 --- a/configs/stm32f429i-disco/extflash/defconfig +++ b/configs/stm32f429i-disco/extflash/defconfig @@ -669,6 +669,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f429i-disco/lcd/defconfig b/configs/stm32f429i-disco/lcd/defconfig index c7c072ee64..f4510f5f18 100644 --- a/configs/stm32f429i-disco/lcd/defconfig +++ b/configs/stm32f429i-disco/lcd/defconfig @@ -660,6 +660,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f429i-disco/ltdc/defconfig b/configs/stm32f429i-disco/ltdc/defconfig index 7d30ca9818..d65a073981 100644 --- a/configs/stm32f429i-disco/ltdc/defconfig +++ b/configs/stm32f429i-disco/ltdc/defconfig @@ -706,6 +706,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f429i-disco/nsh/defconfig b/configs/stm32f429i-disco/nsh/defconfig index ac69c63817..c1c3bbce8d 100644 --- a/configs/stm32f429i-disco/nsh/defconfig +++ b/configs/stm32f429i-disco/nsh/defconfig @@ -649,6 +649,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f429i-disco/nxwm/defconfig b/configs/stm32f429i-disco/nxwm/defconfig index 5d89ad67f6..709795e9a0 100644 --- a/configs/stm32f429i-disco/nxwm/defconfig +++ b/configs/stm32f429i-disco/nxwm/defconfig @@ -671,6 +671,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f429i-disco/usbmsc/defconfig b/configs/stm32f429i-disco/usbmsc/defconfig index 3d31281b67..28f46a636e 100644 --- a/configs/stm32f429i-disco/usbmsc/defconfig +++ b/configs/stm32f429i-disco/usbmsc/defconfig @@ -664,6 +664,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f429i-disco/usbnsh/defconfig b/configs/stm32f429i-disco/usbnsh/defconfig index 3cd8e76c73..fce584c68c 100644 --- a/configs/stm32f429i-disco/usbnsh/defconfig +++ b/configs/stm32f429i-disco/usbnsh/defconfig @@ -655,6 +655,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f4discovery/canard/defconfig b/configs/stm32f4discovery/canard/defconfig index 112de219fd..f10465c2c0 100644 --- a/configs/stm32f4discovery/canard/defconfig +++ b/configs/stm32f4discovery/canard/defconfig @@ -665,6 +665,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f4discovery/cxxtest/defconfig b/configs/stm32f4discovery/cxxtest/defconfig index d9cc9f6f7b..9986935fc0 100644 --- a/configs/stm32f4discovery/cxxtest/defconfig +++ b/configs/stm32f4discovery/cxxtest/defconfig @@ -652,6 +652,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f4discovery/elf/defconfig b/configs/stm32f4discovery/elf/defconfig index 23ecbe39e0..332126c7c7 100644 --- a/configs/stm32f4discovery/elf/defconfig +++ b/configs/stm32f4discovery/elf/defconfig @@ -653,6 +653,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f4discovery/ipv6/defconfig b/configs/stm32f4discovery/ipv6/defconfig index 0a4728f555..07aec89561 100644 --- a/configs/stm32f4discovery/ipv6/defconfig +++ b/configs/stm32f4discovery/ipv6/defconfig @@ -695,6 +695,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f4discovery/kostest/defconfig b/configs/stm32f4discovery/kostest/defconfig index 75487b4d9f..0f4e7f2882 100644 --- a/configs/stm32f4discovery/kostest/defconfig +++ b/configs/stm32f4discovery/kostest/defconfig @@ -658,6 +658,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f4discovery/netnsh/defconfig b/configs/stm32f4discovery/netnsh/defconfig index 8702fa5338..b07e47493d 100644 --- a/configs/stm32f4discovery/netnsh/defconfig +++ b/configs/stm32f4discovery/netnsh/defconfig @@ -695,6 +695,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f4discovery/nsh/defconfig b/configs/stm32f4discovery/nsh/defconfig index 8e8128fc1d..dcf72ec51b 100644 --- a/configs/stm32f4discovery/nsh/defconfig +++ b/configs/stm32f4discovery/nsh/defconfig @@ -660,6 +660,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f4discovery/nxlines/defconfig b/configs/stm32f4discovery/nxlines/defconfig index fbb2ec0dc2..ec02af8c74 100644 --- a/configs/stm32f4discovery/nxlines/defconfig +++ b/configs/stm32f4discovery/nxlines/defconfig @@ -661,6 +661,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f4discovery/pm/defconfig b/configs/stm32f4discovery/pm/defconfig index 7d1bf73755..96432718e4 100644 --- a/configs/stm32f4discovery/pm/defconfig +++ b/configs/stm32f4discovery/pm/defconfig @@ -667,6 +667,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f4discovery/posix_spawn/defconfig b/configs/stm32f4discovery/posix_spawn/defconfig index 13863f2a46..1c8d37ccdd 100644 --- a/configs/stm32f4discovery/posix_spawn/defconfig +++ b/configs/stm32f4discovery/posix_spawn/defconfig @@ -653,6 +653,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f4discovery/pseudoterm/defconfig b/configs/stm32f4discovery/pseudoterm/defconfig index d18d1b560c..f894b7ace2 100644 --- a/configs/stm32f4discovery/pseudoterm/defconfig +++ b/configs/stm32f4discovery/pseudoterm/defconfig @@ -654,6 +654,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f4discovery/rgbled/defconfig b/configs/stm32f4discovery/rgbled/defconfig index 54780a62af..bd94652e9d 100644 --- a/configs/stm32f4discovery/rgbled/defconfig +++ b/configs/stm32f4discovery/rgbled/defconfig @@ -663,6 +663,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f4discovery/uavcan/defconfig b/configs/stm32f4discovery/uavcan/defconfig index caec09e638..72cdd50da0 100644 --- a/configs/stm32f4discovery/uavcan/defconfig +++ b/configs/stm32f4discovery/uavcan/defconfig @@ -621,6 +621,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f4discovery/usbnsh/defconfig b/configs/stm32f4discovery/usbnsh/defconfig index 88bfe30276..c76b16a4e9 100644 --- a/configs/stm32f4discovery/usbnsh/defconfig +++ b/configs/stm32f4discovery/usbnsh/defconfig @@ -666,6 +666,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f4discovery/winbuild/defconfig b/configs/stm32f4discovery/winbuild/defconfig index 1eb0d0f671..db8d26e2ff 100644 --- a/configs/stm32f4discovery/winbuild/defconfig +++ b/configs/stm32f4discovery/winbuild/defconfig @@ -552,6 +552,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # diff --git a/configs/stm32f4discovery/xen1210/defconfig b/configs/stm32f4discovery/xen1210/defconfig index bf4859a9ca..b1c87f136e 100644 --- a/configs/stm32f4discovery/xen1210/defconfig +++ b/configs/stm32f4discovery/xen1210/defconfig @@ -655,6 +655,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f746-ws/nsh/defconfig b/configs/stm32f746-ws/nsh/defconfig index e1bbfa82c6..cf198fc2f6 100644 --- a/configs/stm32f746-ws/nsh/defconfig +++ b/configs/stm32f746-ws/nsh/defconfig @@ -517,6 +517,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32f746g-disco/nsh/defconfig b/configs/stm32f746g-disco/nsh/defconfig index bf4b4b1501..f956e3bc16 100644 --- a/configs/stm32f746g-disco/nsh/defconfig +++ b/configs/stm32f746g-disco/nsh/defconfig @@ -494,6 +494,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32l476-mdk/nsh/defconfig b/configs/stm32l476-mdk/nsh/defconfig index 8c6736985b..a529cb5fbf 100644 --- a/configs/stm32l476-mdk/nsh/defconfig +++ b/configs/stm32l476-mdk/nsh/defconfig @@ -444,6 +444,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32l476vg-disco/nsh/defconfig b/configs/stm32l476vg-disco/nsh/defconfig index 69414abb84..76859b3105 100644 --- a/configs/stm32l476vg-disco/nsh/defconfig +++ b/configs/stm32l476vg-disco/nsh/defconfig @@ -457,6 +457,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32ldiscovery/nsh/defconfig b/configs/stm32ldiscovery/nsh/defconfig index e287044d8e..9c226c4dd4 100644 --- a/configs/stm32ldiscovery/nsh/defconfig +++ b/configs/stm32ldiscovery/nsh/defconfig @@ -619,6 +619,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/stm32vldiscovery/nsh/defconfig b/configs/stm32vldiscovery/nsh/defconfig index 8f995dc8ec..d838755522 100644 --- a/configs/stm32vldiscovery/nsh/defconfig +++ b/configs/stm32vldiscovery/nsh/defconfig @@ -629,6 +629,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sure-pic32mx/nsh/defconfig b/configs/sure-pic32mx/nsh/defconfig index 45e9b428be..1205b4587a 100644 --- a/configs/sure-pic32mx/nsh/defconfig +++ b/configs/sure-pic32mx/nsh/defconfig @@ -391,6 +391,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/sure-pic32mx/usbnsh/defconfig b/configs/sure-pic32mx/usbnsh/defconfig index 604415e68d..2f230bb6c9 100644 --- a/configs/sure-pic32mx/usbnsh/defconfig +++ b/configs/sure-pic32mx/usbnsh/defconfig @@ -393,6 +393,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/teensy-2.0/usbmsc/defconfig b/configs/teensy-2.0/usbmsc/defconfig index 508d46aa4b..bb0ac4127e 100644 --- a/configs/teensy-2.0/usbmsc/defconfig +++ b/configs/teensy-2.0/usbmsc/defconfig @@ -232,6 +232,7 @@ CONFIG_MAX_TASKS=8 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/teensy-3.x/nsh/defconfig b/configs/teensy-3.x/nsh/defconfig index 12b169e4c6..ce5428eb7e 100644 --- a/configs/teensy-3.x/nsh/defconfig +++ b/configs/teensy-3.x/nsh/defconfig @@ -388,6 +388,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/teensy-3.x/usbnsh/defconfig b/configs/teensy-3.x/usbnsh/defconfig index 47f8eef746..b8d5a1086b 100644 --- a/configs/teensy-3.x/usbnsh/defconfig +++ b/configs/teensy-3.x/usbnsh/defconfig @@ -385,6 +385,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/teensy-lc/nsh/defconfig b/configs/teensy-lc/nsh/defconfig index b97c58114f..a863cbaff9 100644 --- a/configs/teensy-lc/nsh/defconfig +++ b/configs/teensy-lc/nsh/defconfig @@ -325,6 +325,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/tm4c123g-launchpad/nsh/defconfig b/configs/tm4c123g-launchpad/nsh/defconfig index 645949de1e..b617f84f4a 100644 --- a/configs/tm4c123g-launchpad/nsh/defconfig +++ b/configs/tm4c123g-launchpad/nsh/defconfig @@ -391,6 +391,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/tm4c1294-launchpad/ipv6/defconfig b/configs/tm4c1294-launchpad/ipv6/defconfig index e24c287f27..04a6b92547 100644 --- a/configs/tm4c1294-launchpad/ipv6/defconfig +++ b/configs/tm4c1294-launchpad/ipv6/defconfig @@ -407,6 +407,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/tm4c1294-launchpad/nsh/defconfig b/configs/tm4c1294-launchpad/nsh/defconfig index d42dc98a3e..326bd96423 100644 --- a/configs/tm4c1294-launchpad/nsh/defconfig +++ b/configs/tm4c1294-launchpad/nsh/defconfig @@ -407,6 +407,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/twr-k60n512/nsh/defconfig b/configs/twr-k60n512/nsh/defconfig index f34a9294a2..f4b6bf7f5e 100644 --- a/configs/twr-k60n512/nsh/defconfig +++ b/configs/twr-k60n512/nsh/defconfig @@ -383,6 +383,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/twr-k64f120m/netnsh/defconfig b/configs/twr-k64f120m/netnsh/defconfig index e27f688271..22ef478b17 100644 --- a/configs/twr-k64f120m/netnsh/defconfig +++ b/configs/twr-k64f120m/netnsh/defconfig @@ -422,6 +422,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/twr-k64f120m/nsh/defconfig b/configs/twr-k64f120m/nsh/defconfig index bfd649af69..911905fe7c 100644 --- a/configs/twr-k64f120m/nsh/defconfig +++ b/configs/twr-k64f120m/nsh/defconfig @@ -408,6 +408,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/u-blox-c027/nsh/defconfig b/configs/u-blox-c027/nsh/defconfig index 529dcf7bda..87cb209018 100644 --- a/configs/u-blox-c027/nsh/defconfig +++ b/configs/u-blox-c027/nsh/defconfig @@ -373,6 +373,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/ubw32/nsh/defconfig b/configs/ubw32/nsh/defconfig index da80577b85..5aa5e4a841 100644 --- a/configs/ubw32/nsh/defconfig +++ b/configs/ubw32/nsh/defconfig @@ -390,6 +390,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/viewtool-stm32f107/highpri/defconfig b/configs/viewtool-stm32f107/highpri/defconfig index 7881989330..a77a31403d 100644 --- a/configs/viewtool-stm32f107/highpri/defconfig +++ b/configs/viewtool-stm32f107/highpri/defconfig @@ -627,6 +627,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/viewtool-stm32f107/netnsh/defconfig b/configs/viewtool-stm32f107/netnsh/defconfig index a5a48b32ba..64dfa3c7c5 100644 --- a/configs/viewtool-stm32f107/netnsh/defconfig +++ b/configs/viewtool-stm32f107/netnsh/defconfig @@ -644,6 +644,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/viewtool-stm32f107/nsh/defconfig b/configs/viewtool-stm32f107/nsh/defconfig index 037cecaeb9..d1231a7b2b 100644 --- a/configs/viewtool-stm32f107/nsh/defconfig +++ b/configs/viewtool-stm32f107/nsh/defconfig @@ -624,6 +624,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/xmc4500-relax/nsh/defconfig b/configs/xmc4500-relax/nsh/defconfig index 2ee3ed50ff..c6b5a1761b 100644 --- a/configs/xmc4500-relax/nsh/defconfig +++ b/configs/xmc4500-relax/nsh/defconfig @@ -327,6 +327,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/z16f2800100zcog/nsh/defconfig b/configs/z16f2800100zcog/nsh/defconfig index 377508de81..eff209f2be 100644 --- a/configs/z16f2800100zcog/nsh/defconfig +++ b/configs/z16f2800100zcog/nsh/defconfig @@ -218,6 +218,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/z16f2800100zcog/ostest/defconfig b/configs/z16f2800100zcog/ostest/defconfig index 2f8cdad153..0aa5129f8e 100644 --- a/configs/z16f2800100zcog/ostest/defconfig +++ b/configs/z16f2800100zcog/ostest/defconfig @@ -218,6 +218,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/z16f2800100zcog/pashello/defconfig b/configs/z16f2800100zcog/pashello/defconfig index e69a059f67..5b5a904ad0 100644 --- a/configs/z16f2800100zcog/pashello/defconfig +++ b/configs/z16f2800100zcog/pashello/defconfig @@ -218,6 +218,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/zkit-arm-1769/nsh/defconfig b/configs/zkit-arm-1769/nsh/defconfig index ec99f4c3b6..bad8467930 100644 --- a/configs/zkit-arm-1769/nsh/defconfig +++ b/configs/zkit-arm-1769/nsh/defconfig @@ -367,6 +367,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/zkit-arm-1769/nxhello/defconfig b/configs/zkit-arm-1769/nxhello/defconfig index 60ef8992a9..48b909ab66 100644 --- a/configs/zkit-arm-1769/nxhello/defconfig +++ b/configs/zkit-arm-1769/nxhello/defconfig @@ -367,6 +367,7 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/zp214xpa/nsh/defconfig b/configs/zp214xpa/nsh/defconfig index d066c3058b..10176fb054 100644 --- a/configs/zp214xpa/nsh/defconfig +++ b/configs/zp214xpa/nsh/defconfig @@ -286,6 +286,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set diff --git a/configs/zp214xpa/nxlines/defconfig b/configs/zp214xpa/nxlines/defconfig index e0deb025fa..49360faa84 100644 --- a/configs/zp214xpa/nxlines/defconfig +++ b/configs/zp214xpa/nxlines/defconfig @@ -290,6 +290,7 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set -- GitLab From 4800d3f5451e152696e82fc222f7b76f5904313d Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 27 Mar 2017 09:36:03 -0600 Subject: [PATCH 225/990] Add syscall support for pthread_mutex_consistent() --- include/sys/syscall.h | 20 +- syscall/syscall_lookup.h | 351 ++++++++++++++++++----------------- syscall/syscall_stublookup.c | 1 + 3 files changed, 192 insertions(+), 180 deletions(-) diff --git a/include/sys/syscall.h b/include/sys/syscall.h index 101816d7ff..56319b772d 100644 --- a/include/sys/syscall.h +++ b/include/sys/syscall.h @@ -418,12 +418,20 @@ # define SYS_pthread_mutex_lock (__SYS_pthread+19) # define SYS_pthread_mutex_trylock (__SYS_pthread+20) # define SYS_pthread_mutex_unlock (__SYS_pthread+21) -# define SYS_pthread_once (__SYS_pthread+22) -# define SYS_pthread_setschedparam (__SYS_pthread+23) -# define SYS_pthread_setschedprio (__SYS_pthread+24) -# define SYS_pthread_setspecific (__SYS_pthread+25) -# define SYS_pthread_yield (__SYS_pthread+26) -# define __SYS_pthread_smp (__SYS_pthread+27) + +#ifndef CONFIG_PTHREAD_MUTEX_UNSAFE +# define SYS_pthread_mutex_consistent (__SYS_pthread+22) +# define __SYS_pthread_once (__SYS_pthread+23) +#else +# define __SYS_pthread_once (__SYS_pthread+22) +#endif + +# define SYS_pthread_once (__SYS_pthread_once+0) +# define SYS_pthread_setschedparam (__SYS_pthread_once+1) +# define SYS_pthread_setschedprio (__SYS_pthread_once+2) +# define SYS_pthread_setspecific (__SYS_pthread_once+3) +# define SYS_pthread_yield (__SYS_pthread_once+4) +# define __SYS_pthread_smp (__SYS_pthread_once+5) # ifdef CONFIG_SMP # define SYS_pthread_setaffinity_np (__SYS_pthread_smp+0) diff --git a/syscall/syscall_lookup.h b/syscall/syscall_lookup.h index f7f87487c6..d89778f255 100644 --- a/syscall/syscall_lookup.h +++ b/syscall/syscall_lookup.h @@ -43,76 +43,76 @@ * configuration */ -SYSCALL_LOOKUP1(_exit, 1, STUB__exit) -SYSCALL_LOOKUP(exit, 1, STUB_exit) -SYSCALL_LOOKUP(get_errno, 0, STUB_get_errno) -SYSCALL_LOOKUP(getpid, 0, STUB_getpid) -SYSCALL_LOOKUP(sched_getparam, 2, STUB_sched_getparam) -SYSCALL_LOOKUP(sched_getscheduler, 1, STUB_sched_getscheduler) -SYSCALL_LOOKUP(sched_lock, 0, STUB_sched_lock) -SYSCALL_LOOKUP(sched_lockcount, 0, STUB_sched_lockcount) -SYSCALL_LOOKUP(sched_rr_get_interval, 2, STUB_sched_rr_get_interval) -SYSCALL_LOOKUP(sched_setparam, 2, STUB_sched_setparam) -SYSCALL_LOOKUP(sched_setscheduler, 3, STUB_sched_setscheduler) -SYSCALL_LOOKUP(sched_unlock, 0, STUB_sched_unlock) -SYSCALL_LOOKUP(sched_yield, 0, STUB_sched_yield) -SYSCALL_LOOKUP(set_errno, 1, STUB_set_errno) -SYSCALL_LOOKUP(uname, 1, STUB_uname) +SYSCALL_LOOKUP1(_exit, 1, STUB__exit) +SYSCALL_LOOKUP(exit, 1, STUB_exit) +SYSCALL_LOOKUP(get_errno, 0, STUB_get_errno) +SYSCALL_LOOKUP(getpid, 0, STUB_getpid) +SYSCALL_LOOKUP(sched_getparam, 2, STUB_sched_getparam) +SYSCALL_LOOKUP(sched_getscheduler, 1, STUB_sched_getscheduler) +SYSCALL_LOOKUP(sched_lock, 0, STUB_sched_lock) +SYSCALL_LOOKUP(sched_lockcount, 0, STUB_sched_lockcount) +SYSCALL_LOOKUP(sched_rr_get_interval, 2, STUB_sched_rr_get_interval) +SYSCALL_LOOKUP(sched_setparam, 2, STUB_sched_setparam) +SYSCALL_LOOKUP(sched_setscheduler, 3, STUB_sched_setscheduler) +SYSCALL_LOOKUP(sched_unlock, 0, STUB_sched_unlock) +SYSCALL_LOOKUP(sched_yield, 0, STUB_sched_yield) +SYSCALL_LOOKUP(set_errno, 1, STUB_set_errno) +SYSCALL_LOOKUP(uname, 1, STUB_uname) /* Semaphores */ -SYSCALL_LOOKUP(sem_destroy, 1, STUB_sem_destroy) -SYSCALL_LOOKUP(sem_post, 1, STUB_sem_post) -SYSCALL_LOOKUP(sem_timedwait, 2, STUB_sem_timedwait) -SYSCALL_LOOKUP(sem_trywait, 1, STUB_sem_trywait) -SYSCALL_LOOKUP(sem_wait, 1, STUB_sem_wait) +SYSCALL_LOOKUP(sem_destroy, 1, STUB_sem_destroy) +SYSCALL_LOOKUP(sem_post, 1, STUB_sem_post) +SYSCALL_LOOKUP(sem_timedwait, 2, STUB_sem_timedwait) +SYSCALL_LOOKUP(sem_trywait, 1, STUB_sem_trywait) +SYSCALL_LOOKUP(sem_wait, 1, STUB_sem_wait) #ifdef CONFIG_PRIORITY_INHERITANCE -SYSCALL_LOOKUP(sem_setprotocol, 2, STUB_sem_setprotocol) +SYSCALL_LOOKUP(sem_setprotocol, 2, STUB_sem_setprotocol) #endif /* Named semaphores */ #ifdef CONFIG_FS_NAMED_SEMAPHORES -SYSCALL_LOOKUP(sem_open, 6, STUB_sem_open) -SYSCALL_LOOKUP(sem_close, 1, STUB_sem_close) -SYSCALL_LOOKUP(sem_unlink, 1, STUB_sem_unlink) +SYSCALL_LOOKUP(sem_open, 6, STUB_sem_open) +SYSCALL_LOOKUP(sem_close, 1, STUB_sem_close) +SYSCALL_LOOKUP(sem_unlink, 1, STUB_sem_unlink) #endif #ifndef CONFIG_BUILD_KERNEL -SYSCALL_LOOKUP(task_create, 5, STUB_task_create) +SYSCALL_LOOKUP(task_create, 5, STUB_task_create) #else -SYSCALL_LOOKUP(pgalloc, 2, STUB_pgalloc) +SYSCALL_LOOKUP(pgalloc, 2, STUB_pgalloc) #endif -SYSCALL_LOOKUP(task_delete, 1, STUB_task_delete) -SYSCALL_LOOKUP(task_restart, 1, STUB_task_restart) -SYSCALL_LOOKUP(task_setcancelstate, 2, STUB_task_setcancelstate) -SYSCALL_LOOKUP(up_assert, 2, STUB_up_assert) +SYSCALL_LOOKUP(task_delete, 1, STUB_task_delete) +SYSCALL_LOOKUP(task_restart, 1, STUB_task_restart) +SYSCALL_LOOKUP(task_setcancelstate, 2, STUB_task_setcancelstate) +SYSCALL_LOOKUP(up_assert, 2, STUB_up_assert) # ifdef CONFIG_CANCELLATION_POINTS - SYSCALL_LOOKUP(task_setcanceltype, 2, STUB_task_setcanceltype) - SYSCALL_LOOKUP(task_testcancel, 0, STUB_task_testcancel) + SYSCALL_LOOKUP(task_setcanceltype, 2, STUB_task_setcanceltype) + SYSCALL_LOOKUP(task_testcancel, 0, STUB_task_testcancel) # endif /* The following can be individually enabled */ #ifdef CONFIG_ARCH_HAVE_VFORK - SYSCALL_LOOKUP(vfork, 0, STUB_vfork) + SYSCALL_LOOKUP(vfork, 0, STUB_vfork) #endif #ifdef CONFIG_SCHED_ATEXIT - SYSCALL_LOOKUP(atexit, 1, STUB_atexit) + SYSCALL_LOOKUP(atexit, 1, STUB_atexit) #endif #ifdef CONFIG_SCHED_ONEXIT - SYSCALL_LOOKUP(on_exit, 2, STUB_on_exit) + SYSCALL_LOOKUP(on_exit, 2, STUB_on_exit) #endif #ifdef CONFIG_SCHED_WAITPID - SYSCALL_LOOKUP(waitpid, 3, STUB_waitpid) + SYSCALL_LOOKUP(waitpid, 3, STUB_waitpid) # ifdef CONFIG_SCHED_HAVE_PARENT - SYSCALL_LOOKUP(wait, 1, STUB_wait) - SYSCALL_LOOKUP(waitid, 4, STUB_waitid) + SYSCALL_LOOKUP(wait, 1, STUB_wait) + SYSCALL_LOOKUP(waitid, 4, STUB_waitid) # endif #endif @@ -121,9 +121,9 @@ SYSCALL_LOOKUP(up_assert, 2, STUB_up_assert) */ #ifdef CONFIG_MODULE - SYSCALL_LOOKUP(insmod, 2, STUB_insmod) - SYSCALL_LOOKUP(rmmod, 1, STUB_rmmod) - SYSCALL_LOOKUP(modhandle, 1, STUB_modhandle) + SYSCALL_LOOKUP(insmod, 2, STUB_insmod) + SYSCALL_LOOKUP(rmmod, 1, STUB_rmmod) + SYSCALL_LOOKUP(modhandle, 1, STUB_modhandle) #endif /* The following can only be defined if we are configured to execute @@ -132,11 +132,11 @@ SYSCALL_LOOKUP(up_assert, 2, STUB_up_assert) #if !defined(CONFIG_BINFMT_DISABLE) && defined(CONFIG_LIBC_EXECFUNCS) # ifdef CONFIG_BINFMT_EXEPATH - SYSCALL_LOOKUP(posix_spawnp, 6, STUB_posix_spawnp) + SYSCALL_LOOKUP(posix_spawnp, 6, STUB_posix_spawnp) # else - SYSCALL_LOOKUP(posix_spawn, 6, STUB_posix_spawn) + SYSCALL_LOOKUP(posix_spawn, 6, STUB_posix_spawn) # endif - SYSCALL_LOOKUP(execv, 2, STUB_execv) + SYSCALL_LOOKUP(execv, 2, STUB_execv) #endif /* The following are only defined is signals are supported in the NuttX @@ -144,236 +144,239 @@ SYSCALL_LOOKUP(up_assert, 2, STUB_up_assert) */ #ifndef CONFIG_DISABLE_SIGNALS - SYSCALL_LOOKUP(kill, 2, STUB_kill) - SYSCALL_LOOKUP(sigaction, 3, STUB_sigaction) - SYSCALL_LOOKUP(sigpending, 1, STUB_sigpending) - SYSCALL_LOOKUP(sigprocmask, 3, STUB_sigprocmask) - SYSCALL_LOOKUP(sigqueue, 3, STUB_sigqueue) - SYSCALL_LOOKUP(sigsuspend, 1, STUB_sigsuspend) - SYSCALL_LOOKUP(sigtimedwait, 3, STUB_sigtimedwait) - SYSCALL_LOOKUP(sigwaitinfo, 2, STUB_sigwaitinfo) - SYSCALL_LOOKUP(nanosleep, 2, STUB_nanosleep) + SYSCALL_LOOKUP(kill, 2, STUB_kill) + SYSCALL_LOOKUP(sigaction, 3, STUB_sigaction) + SYSCALL_LOOKUP(sigpending, 1, STUB_sigpending) + SYSCALL_LOOKUP(sigprocmask, 3, STUB_sigprocmask) + SYSCALL_LOOKUP(sigqueue, 3, STUB_sigqueue) + SYSCALL_LOOKUP(sigsuspend, 1, STUB_sigsuspend) + SYSCALL_LOOKUP(sigtimedwait, 3, STUB_sigtimedwait) + SYSCALL_LOOKUP(sigwaitinfo, 2, STUB_sigwaitinfo) + SYSCALL_LOOKUP(nanosleep, 2, STUB_nanosleep) #endif /* The following are only defined if the system clock is enabled in the * NuttX configuration. */ - SYSCALL_LOOKUP(syscall_clock_systimer, 0, STUB_clock_systimer) - SYSCALL_LOOKUP(clock_getres, 2, STUB_clock_getres) - SYSCALL_LOOKUP(clock_gettime, 2, STUB_clock_gettime) - SYSCALL_LOOKUP(clock_settime, 2, STUB_clock_settime) + SYSCALL_LOOKUP(syscall_clock_systimer, 0, STUB_clock_systimer) + SYSCALL_LOOKUP(clock_getres, 2, STUB_clock_getres) + SYSCALL_LOOKUP(clock_gettime, 2, STUB_clock_gettime) + SYSCALL_LOOKUP(clock_settime, 2, STUB_clock_settime) #ifdef CONFIG_CLOCK_TIMEKEEPING - SYSCALL_LOOKUP(adjtime, 2, STUB_adjtime) + SYSCALL_LOOKUP(adjtime, 2, STUB_adjtime) #endif /* The following are defined only if POSIX timers are supported */ #ifndef CONFIG_DISABLE_POSIX_TIMERS - SYSCALL_LOOKUP(timer_create, 3, STUB_timer_create) - SYSCALL_LOOKUP(timer_delete, 1, STUB_timer_delete) - SYSCALL_LOOKUP(timer_getoverrun, 1, STUB_timer_getoverrun) - SYSCALL_LOOKUP(timer_gettime, 2, STUB_timer_gettime) - SYSCALL_LOOKUP(timer_settime, 4, STUB_timer_settime) + SYSCALL_LOOKUP(timer_create, 3, STUB_timer_create) + SYSCALL_LOOKUP(timer_delete, 1, STUB_timer_delete) + SYSCALL_LOOKUP(timer_getoverrun, 1, STUB_timer_getoverrun) + SYSCALL_LOOKUP(timer_gettime, 2, STUB_timer_gettime) + SYSCALL_LOOKUP(timer_settime, 4, STUB_timer_settime) #endif /* System logging */ - SYSCALL_LOOKUP(_vsyslog, 3, STUB__vsyslog) + SYSCALL_LOOKUP(_vsyslog, 3, STUB__vsyslog) /* The following are defined if either file or socket descriptor are * enabled. */ #if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 - SYSCALL_LOOKUP(close, 1, STUB_close) + SYSCALL_LOOKUP(close, 1, STUB_close) # ifdef CONFIG_LIBC_IOCTL_VARIADIC - SYSCALL_LOOKUP(fs_ioctl, 3, STUB_fs_ioctl) + SYSCALL_LOOKUP(fs_ioctl, 3, STUB_fs_ioctl) # else - SYSCALL_LOOKUP(ioctl, 3, STUB_ioctl) + SYSCALL_LOOKUP(ioctl, 3, STUB_ioctl) # endif - SYSCALL_LOOKUP(read, 3, STUB_read) - SYSCALL_LOOKUP(write, 3, STUB_write) - SYSCALL_LOOKUP(pread, 4, STUB_pread) - SYSCALL_LOOKUP(pwrite, 4, STUB_pwrite) + SYSCALL_LOOKUP(read, 3, STUB_read) + SYSCALL_LOOKUP(write, 3, STUB_write) + SYSCALL_LOOKUP(pread, 4, STUB_pread) + SYSCALL_LOOKUP(pwrite, 4, STUB_pwrite) # ifdef CONFIG_FS_AIO - SYSCALL_LOOKUP(aio_read, 1, STUB_aio_read) - SYSCALL_LOOKUP(aio_write, 1, STUB_aio_write) - SYSCALL_LOOKUP(aio_fsync, 2, STUB_aio_fsync) - SYSCALL_LOOKUP(aio_cancel, 2, STUB_aio_cancel) + SYSCALL_LOOKUP(aio_read, 1, STUB_aio_read) + SYSCALL_LOOKUP(aio_write, 1, STUB_aio_write) + SYSCALL_LOOKUP(aio_fsync, 2, STUB_aio_fsync) + SYSCALL_LOOKUP(aio_cancel, 2, STUB_aio_cancel) # endif # ifndef CONFIG_DISABLE_POLL - SYSCALL_LOOKUP(poll, 3, STUB_poll) - SYSCALL_LOOKUP(select, 5, STUB_select) + SYSCALL_LOOKUP(poll, 3, STUB_poll) + SYSCALL_LOOKUP(select, 5, STUB_select) # endif #endif /* Board support */ #ifdef CONFIG_LIB_BOARDCTL - SYSCALL_LOOKUP(boardctl, 2, STUB_boardctl) + SYSCALL_LOOKUP(boardctl, 2, STUB_boardctl) #endif /* The following are defined if file descriptors are enabled */ #if CONFIG_NFILE_DESCRIPTORS > 0 - SYSCALL_LOOKUP(closedir, 1, STUB_closedir) - SYSCALL_LOOKUP(dup, 1, STUB_dup) - SYSCALL_LOOKUP(dup2, 2, STUB_dup2) - SYSCALL_LOOKUP(fcntl, 6, STUB_fcntl) - SYSCALL_LOOKUP(lseek, 3, STUB_lseek) - SYSCALL_LOOKUP(mmap, 6, STUB_mmap) - SYSCALL_LOOKUP(open, 6, STUB_open) - SYSCALL_LOOKUP(opendir, 1, STUB_opendir) - SYSCALL_LOOKUP(readdir, 1, STUB_readdir) - SYSCALL_LOOKUP(rewinddir, 1, STUB_rewinddir) - SYSCALL_LOOKUP(seekdir, 2, STUB_seekdir) - SYSCALL_LOOKUP(stat, 2, STUB_stat) - SYSCALL_LOOKUP(fstat, 2, STUB_fstat) - SYSCALL_LOOKUP(statfs, 2, STUB_statfs) - SYSCALL_LOOKUP(fstatfs, 2, STUB_fstatfs) - SYSCALL_LOOKUP(telldir, 1, STUB_telldir) + SYSCALL_LOOKUP(closedir, 1, STUB_closedir) + SYSCALL_LOOKUP(dup, 1, STUB_dup) + SYSCALL_LOOKUP(dup2, 2, STUB_dup2) + SYSCALL_LOOKUP(fcntl, 6, STUB_fcntl) + SYSCALL_LOOKUP(lseek, 3, STUB_lseek) + SYSCALL_LOOKUP(mmap, 6, STUB_mmap) + SYSCALL_LOOKUP(open, 6, STUB_open) + SYSCALL_LOOKUP(opendir, 1, STUB_opendir) + SYSCALL_LOOKUP(readdir, 1, STUB_readdir) + SYSCALL_LOOKUP(rewinddir, 1, STUB_rewinddir) + SYSCALL_LOOKUP(seekdir, 2, STUB_seekdir) + SYSCALL_LOOKUP(stat, 2, STUB_stat) + SYSCALL_LOOKUP(fstat, 2, STUB_fstat) + SYSCALL_LOOKUP(statfs, 2, STUB_statfs) + SYSCALL_LOOKUP(fstatfs, 2, STUB_fstatfs) + SYSCALL_LOOKUP(telldir, 1, STUB_telldir) # if defined(CONFIG_PSEUDOFS_SOFTLINKS) - SYSCALL_LOOKUP(link, 2, STUB_link) - SYSCALL_LOOKUP(readlink, 3, STUB_readlink) + SYSCALL_LOOKUP(link, 2, STUB_link) + SYSCALL_LOOKUP(readlink, 3, STUB_readlink) # endif # if defined(CONFIG_PIPES) && CONFIG_DEV_PIPE_SIZE > 0 - SYSCALL_LOOKUP(pipe2, 2, STUB_pipe2) + SYSCALL_LOOKUP(pipe2, 2, STUB_pipe2) # endif # if defined(CONFIG_PIPES) && CONFIG_DEV_FIFO_SIZE > 0 - SYSCALL_LOOKUP(mkfifo2, 3, STUB_mkfifo2) + SYSCALL_LOOKUP(mkfifo2, 3, STUB_mkfifo2) # endif # if CONFIG_NFILE_STREAMS > 0 - SYSCALL_LOOKUP(fdopen, 3, STUB_fs_fdopen) - SYSCALL_LOOKUP(sched_getstreams, 0, STUB_sched_getstreams) + SYSCALL_LOOKUP(fdopen, 3, STUB_fs_fdopen) + SYSCALL_LOOKUP(sched_getstreams, 0, STUB_sched_getstreams) # endif # if defined(CONFIG_NET_SENDFILE) - SYSCALL_LOOKUP(sendfile, 4, STUB_fs_sendifile) + SYSCALL_LOOKUP(sendfile, 4, STUB_fs_sendifile) # endif # if !defined(CONFIG_DISABLE_MOUNTPOINT) # if defined(CONFIG_FS_READABLE) - SYSCALL_LOOKUP(mount, 5, STUB_mount) + SYSCALL_LOOKUP(mount, 5, STUB_mount) # endif - SYSCALL_LOOKUP(fsync, 1, STUB_fsync) - SYSCALL_LOOKUP(mkdir, 2, STUB_mkdir) - SYSCALL_LOOKUP(rename, 2, STUB_rename) - SYSCALL_LOOKUP(rmdir, 1, STUB_rmdir) - SYSCALL_LOOKUP(umount2, 2, STUB_umount2) - SYSCALL_LOOKUP(unlink, 1, STUB_unlink) + SYSCALL_LOOKUP(fsync, 1, STUB_fsync) + SYSCALL_LOOKUP(mkdir, 2, STUB_mkdir) + SYSCALL_LOOKUP(rename, 2, STUB_rename) + SYSCALL_LOOKUP(rmdir, 1, STUB_rmdir) + SYSCALL_LOOKUP(umount2, 2, STUB_umount2) + SYSCALL_LOOKUP(unlink, 1, STUB_unlink) # endif #endif /* Shared memory interfaces */ #ifdef CONFIG_MM_SHM - SYSCALL_LOOKUP(shmget, 3, STUB_shmget) - SYSCALL_LOOKUP(shmat, 3, STUB_shmat) - SYSCALL_LOOKUP(shmctl, 3, STUB_shmctl) - SYSCALL_LOOKUP(shmdt, 1, STUB_shmdt) + SYSCALL_LOOKUP(shmget, 3, STUB_shmget) + SYSCALL_LOOKUP(shmat, 3, STUB_shmat) + SYSCALL_LOOKUP(shmctl, 3, STUB_shmctl) + SYSCALL_LOOKUP(shmdt, 1, STUB_shmdt) #endif /* The following are defined if pthreads are enabled */ #ifndef CONFIG_DISABLE_PTHREAD - SYSCALL_LOOKUP(pthread_barrier_destroy, 1, STUB_pthread_barrier_destroy) - SYSCALL_LOOKUP(pthread_barrier_init, 3, STUB_pthread_barrier_init) - SYSCALL_LOOKUP(pthread_barrier_wait, 1, STUB_pthread_barrier_wait) - SYSCALL_LOOKUP(pthread_cancel, 1, STUB_pthread_cancel) - SYSCALL_LOOKUP(pthread_cond_broadcast, 1, STUB_pthread_cond_broadcast) - SYSCALL_LOOKUP(pthread_cond_destroy, 1, STUB_pthread_cond_destroy) - SYSCALL_LOOKUP(pthread_cond_init, 2, STUB_pthread_cond_init) - SYSCALL_LOOKUP(pthread_cond_signal, 1, STUB_pthread_cond_signal) - SYSCALL_LOOKUP(pthread_cond_wait, 2, STUB_pthread_cond_wait) - SYSCALL_LOOKUP(pthread_create, 4, STUB_pthread_create) - SYSCALL_LOOKUP(pthread_detach, 1, STUB_pthread_detach) - SYSCALL_LOOKUP(pthread_exit, 1, STUB_pthread_exit) - SYSCALL_LOOKUP(pthread_getschedparam, 3, STUB_pthread_getschedparam) - SYSCALL_LOOKUP(pthread_getspecific, 1, STUB_pthread_getspecific) - SYSCALL_LOOKUP(pthread_join, 2, STUB_pthread_join) - SYSCALL_LOOKUP(pthread_key_create, 2, STUB_pthread_key_create) - SYSCALL_LOOKUP(pthread_key_delete, 1, STUB_pthread_key_delete) - SYSCALL_LOOKUP(pthread_mutex_destroy, 1, STUB_pthread_mutex_destroy) - SYSCALL_LOOKUP(pthread_mutex_init, 2, STUB_pthread_mutex_init) - SYSCALL_LOOKUP(pthread_mutex_lock, 1, STUB_pthread_mutex_lock) - SYSCALL_LOOKUP(pthread_mutex_trylock, 1, STUB_pthread_mutex_trylock) - SYSCALL_LOOKUP(pthread_mutex_unlock, 1, STUB_pthread_mutex_unlock) - SYSCALL_LOOKUP(pthread_once, 2, STUB_pthread_once) - SYSCALL_LOOKUP(pthread_setschedparam, 3, STUB_pthread_setschedparam) - SYSCALL_LOOKUP(pthread_setschedprio, 2, STUB_pthread_setschedprio) - SYSCALL_LOOKUP(pthread_setspecific, 2, STUB_pthread_setspecific) - SYSCALL_LOOKUP(pthread_yield, 0, STUB_pthread_yield) + SYSCALL_LOOKUP(pthread_barrier_destroy, 1, STUB_pthread_barrier_destroy) + SYSCALL_LOOKUP(pthread_barrier_init, 3, STUB_pthread_barrier_init) + SYSCALL_LOOKUP(pthread_barrier_wait, 1, STUB_pthread_barrier_wait) + SYSCALL_LOOKUP(pthread_cancel, 1, STUB_pthread_cancel) + SYSCALL_LOOKUP(pthread_cond_broadcast, 1, STUB_pthread_cond_broadcast) + SYSCALL_LOOKUP(pthread_cond_destroy, 1, STUB_pthread_cond_destroy) + SYSCALL_LOOKUP(pthread_cond_init, 2, STUB_pthread_cond_init) + SYSCALL_LOOKUP(pthread_cond_signal, 1, STUB_pthread_cond_signal) + SYSCALL_LOOKUP(pthread_cond_wait, 2, STUB_pthread_cond_wait) + SYSCALL_LOOKUP(pthread_create, 4, STUB_pthread_create) + SYSCALL_LOOKUP(pthread_detach, 1, STUB_pthread_detach) + SYSCALL_LOOKUP(pthread_exit, 1, STUB_pthread_exit) + SYSCALL_LOOKUP(pthread_getschedparam, 3, STUB_pthread_getschedparam) + SYSCALL_LOOKUP(pthread_getspecific, 1, STUB_pthread_getspecific) + SYSCALL_LOOKUP(pthread_join, 2, STUB_pthread_join) + SYSCALL_LOOKUP(pthread_key_create, 2, STUB_pthread_key_create) + SYSCALL_LOOKUP(pthread_key_delete, 1, STUB_pthread_key_delete) + SYSCALL_LOOKUP(pthread_mutex_destroy, 1, STUB_pthread_mutex_destroy) + SYSCALL_LOOKUP(pthread_mutex_init, 2, STUB_pthread_mutex_init) + SYSCALL_LOOKUP(pthread_mutex_lock, 1, STUB_pthread_mutex_lock) + SYSCALL_LOOKUP(pthread_mutex_trylock, 1, STUB_pthread_mutex_trylock) + SYSCALL_LOOKUP(pthread_mutex_unlock, 1, STUB_pthread_mutex_unlock) +#ifndef CONFIG_PTHREAD_MUTEX_UNSAFE + SYSCALL_LOOKUP(pthread_mutex_consistent, 1, STUB_pthread_mutex_unlock) +#endif + SYSCALL_LOOKUP(pthread_once, 2, STUB_pthread_once) + SYSCALL_LOOKUP(pthread_setschedparam, 3, STUB_pthread_setschedparam) + SYSCALL_LOOKUP(pthread_setschedprio, 2, STUB_pthread_setschedprio) + SYSCALL_LOOKUP(pthread_setspecific, 2, STUB_pthread_setspecific) + SYSCALL_LOOKUP(pthread_yield, 0, STUB_pthread_yield) # ifdef CONFIG_SMP - SYSCALL_LOOKUP(pthread_setaffinity, 3, STUB_pthread_setaffinity) - SYSCALL_LOOKUP(pthread_getaffinity, 3, STUB_pthread_getaffinity) + SYSCALL_LOOKUP(pthread_setaffinity, 3, STUB_pthread_setaffinity) + SYSCALL_LOOKUP(pthread_getaffinity, 3, STUB_pthread_getaffinity) # endif # ifndef CONFIG_DISABLE_SIGNALS - SYSCALL_LOOKUP(pthread_cond_timedwait, 3, STUB_pthread_cond_timedwait) - SYSCALL_LOOKUP(pthread_kill, 2, STUB_pthread_kill) - SYSCALL_LOOKUP(pthread_sigmask, 3, STUB_pthread_sigmask) + SYSCALL_LOOKUP(pthread_cond_timedwait, 3, STUB_pthread_cond_timedwait) + SYSCALL_LOOKUP(pthread_kill, 2, STUB_pthread_kill) + SYSCALL_LOOKUP(pthread_sigmask, 3, STUB_pthread_sigmask) # endif # ifdef CONFIG_PTHREAD_CLEANUP - SYSCALL_LOOKUP(pthread_cleanup_push, 2, STUB_pthread_cleanup_push) - SYSCALL_LOOKUP(pthread_cleanup_pop, 1, STUB_pthread_cleanup_pop) + SYSCALL_LOOKUP(pthread_cleanup_push, 2, STUB_pthread_cleanup_push) + SYSCALL_LOOKUP(pthread_cleanup_pop, 1, STUB_pthread_cleanup_pop) # endif #endif /* The following are defined only if message queues are enabled */ #ifndef CONFIG_DISABLE_MQUEUE - SYSCALL_LOOKUP(mq_close, 1, STUB_mq_close) - SYSCALL_LOOKUP(mq_getattr, 2, STUB_mq_getattr) - SYSCALL_LOOKUP(mq_notify, 2, STUB_mq_notify) - SYSCALL_LOOKUP(mq_open, 6, STUB_mq_open) - SYSCALL_LOOKUP(mq_receive, 4, STUB_mq_receive) - SYSCALL_LOOKUP(mq_send, 4, STUB_mq_send) - SYSCALL_LOOKUP(mq_setattr, 3, STUB_mq_setattr) - SYSCALL_LOOKUP(mq_timedreceive, 5, STUB_mq_timedreceive) - SYSCALL_LOOKUP(mq_timedsend, 5, STUB_mq_timedsend) - SYSCALL_LOOKUP(mq_unlink, 1, STUB_mq_unlink) + SYSCALL_LOOKUP(mq_close, 1, STUB_mq_close) + SYSCALL_LOOKUP(mq_getattr, 2, STUB_mq_getattr) + SYSCALL_LOOKUP(mq_notify, 2, STUB_mq_notify) + SYSCALL_LOOKUP(mq_open, 6, STUB_mq_open) + SYSCALL_LOOKUP(mq_receive, 4, STUB_mq_receive) + SYSCALL_LOOKUP(mq_send, 4, STUB_mq_send) + SYSCALL_LOOKUP(mq_setattr, 3, STUB_mq_setattr) + SYSCALL_LOOKUP(mq_timedreceive, 5, STUB_mq_timedreceive) + SYSCALL_LOOKUP(mq_timedsend, 5, STUB_mq_timedsend) + SYSCALL_LOOKUP(mq_unlink, 1, STUB_mq_unlink) #endif /* The following are defined only if environment variables are supported */ #ifndef CONFIG_DISABLE_ENVIRON - SYSCALL_LOOKUP(clearenv, 0, STUB_clearenv) - SYSCALL_LOOKUP(getenv, 1, STUB_getenv) - SYSCALL_LOOKUP(putenv, 1, STUB_putenv) - SYSCALL_LOOKUP(setenv, 3, STUB_setenv) - SYSCALL_LOOKUP(unsetenv, 1, STUB_unsetenv) + SYSCALL_LOOKUP(clearenv, 0, STUB_clearenv) + SYSCALL_LOOKUP(getenv, 1, STUB_getenv) + SYSCALL_LOOKUP(putenv, 1, STUB_putenv) + SYSCALL_LOOKUP(setenv, 3, STUB_setenv) + SYSCALL_LOOKUP(unsetenv, 1, STUB_unsetenv) #endif /* The following are defined only if netdb is supported */ #ifdef CONFIG_LIBC_NETDB - SYSCALL_LOOKUP(sethostname, 2, STUB_sethostname) + SYSCALL_LOOKUP(sethostname, 2, STUB_sethostname) #endif /* The following are defined only if networking AND sockets are supported */ #if CONFIG_NSOCKET_DESCRIPTORS > 0 && defined(CONFIG_NET) - SYSCALL_LOOKUP(accept, 3, STUB_accept) - SYSCALL_LOOKUP(bind, 3, STUB_bind) - SYSCALL_LOOKUP(connect, 3, STUB_connect) - SYSCALL_LOOKUP(getsockopt, 5, STUB_getsockopt) - SYSCALL_LOOKUP(listen, 2, STUB_listen) - SYSCALL_LOOKUP(recv, 4, STUB_recv) - SYSCALL_LOOKUP(recvfrom, 6, STUB_recvfrom) - SYSCALL_LOOKUP(send, 4, STUB_send) - SYSCALL_LOOKUP(sendto, 6, STUB_sendto) - SYSCALL_LOOKUP(setsockopt, 5, STUB_setsockopt) - SYSCALL_LOOKUP(socket, 3, STUB_socket) + SYSCALL_LOOKUP(accept, 3, STUB_accept) + SYSCALL_LOOKUP(bind, 3, STUB_bind) + SYSCALL_LOOKUP(connect, 3, STUB_connect) + SYSCALL_LOOKUP(getsockopt, 5, STUB_getsockopt) + SYSCALL_LOOKUP(listen, 2, STUB_listen) + SYSCALL_LOOKUP(recv, 4, STUB_recv) + SYSCALL_LOOKUP(recvfrom, 6, STUB_recvfrom) + SYSCALL_LOOKUP(send, 4, STUB_send) + SYSCALL_LOOKUP(sendto, 6, STUB_sendto) + SYSCALL_LOOKUP(setsockopt, 5, STUB_setsockopt) + SYSCALL_LOOKUP(socket, 3, STUB_socket) #endif /* The following is defined only if CONFIG_TASK_NAME_SIZE > 0 */ #if CONFIG_TASK_NAME_SIZE > 0 - SYSCALL_LOOKUP(prctl, 5, STUB_prctl) + SYSCALL_LOOKUP(prctl, 5, STUB_prctl) #endif /**************************************************************************** diff --git a/syscall/syscall_stublookup.c b/syscall/syscall_stublookup.c index ab18f82878..ddcffd5506 100644 --- a/syscall/syscall_stublookup.c +++ b/syscall/syscall_stublookup.c @@ -302,6 +302,7 @@ uintptr_t STUB_pthread_mutex_init(int nbr, uintptr_t parm1, uintptr_t STUB_pthread_mutex_lock(int nbr, uintptr_t parm1); uintptr_t STUB_pthread_mutex_trylock(int nbr, uintptr_t parm1); uintptr_t STUB_pthread_mutex_unlock(int nbr, uintptr_t parm1); +uintptr_t STUB_pthread_mutex_consistent(int nbr, uintptr_t parm1); uintptr_t STUB_pthread_once(int nbr, uintptr_t parm1, uintptr_t parm2); uintptr_t STUB_pthread_setschedparam(int nbr, uintptr_t parm1, uintptr_t parm2, uintptr_t parm3); -- GitLab From 7dea99ff9d47f72fe59c30d80eaa15ea382cea45 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 27 Mar 2017 09:38:27 -0600 Subject: [PATCH 226/990] Parts of last syscall commit that were omitted. --- syscall/syscall.csv | 1 + syscall/syscall_lookup.h | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/syscall/syscall.csv b/syscall/syscall.csv index 18ff94fdc7..66babafb5e 100644 --- a/syscall/syscall.csv +++ b/syscall/syscall.csv @@ -91,6 +91,7 @@ "pthread_mutex_lock","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutex_t*" "pthread_mutex_trylock","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutex_t*" "pthread_mutex_unlock","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutex_t*" +"pthread_mutex_consistent","pthread.h","!defined(CONFIG_DISABLE_PTHREAD) && !defined(CONFIG_PTHREAD_MUTEX_UNSAFE)","int","FAR pthread_mutex_t*" "pthread_once","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_once_t*","CODE void (*)(void)" "pthread_setaffinity_np","pthread.h","!defined(CONFIG_DISABLE_PTHREAD) && defined(CONFIG_SMP)","int","pthread_t","size_t","FAR const cpu_set_t*" "pthread_setschedparam","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","pthread_t","int","FAR const struct sched_param*" diff --git a/syscall/syscall_lookup.h b/syscall/syscall_lookup.h index d89778f255..6ed2e54e78 100644 --- a/syscall/syscall_lookup.h +++ b/syscall/syscall_lookup.h @@ -304,7 +304,7 @@ SYSCALL_LOOKUP(up_assert, 2, STUB_up_assert) SYSCALL_LOOKUP(pthread_mutex_trylock, 1, STUB_pthread_mutex_trylock) SYSCALL_LOOKUP(pthread_mutex_unlock, 1, STUB_pthread_mutex_unlock) #ifndef CONFIG_PTHREAD_MUTEX_UNSAFE - SYSCALL_LOOKUP(pthread_mutex_consistent, 1, STUB_pthread_mutex_unlock) + SYSCALL_LOOKUP(pthread_mutex_consistent, 1, STUB_pthread_mutex_consistent) #endif SYSCALL_LOOKUP(pthread_once, 2, STUB_pthread_once) SYSCALL_LOOKUP(pthread_setschedparam, 3, STUB_pthread_setschedparam) -- GitLab From 77e4953fe37f452ecfdb6f3217576a580eb5f205 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 27 Mar 2017 09:42:36 -0600 Subject: [PATCH 227/990] Eliminate a 'make menuconfig' warning --- configs/clicker2-stm32/Kconfig | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/configs/clicker2-stm32/Kconfig b/configs/clicker2-stm32/Kconfig index b2e5965456..1ca0fbc9ee 100644 --- a/configs/clicker2-stm32/Kconfig +++ b/configs/clicker2-stm32/Kconfig @@ -7,16 +7,14 @@ if ARCH_BOARD_CLICKER2_STM32 config CLICKER2_STM32_MB1_SPI bool "mikroBUS1 SPI" - default n if !STM32_SPI3 - default y if STM32_SPI3 + default n select STM32_SPI3 ---help--- Enable SPI support on mikroBUS1 (STM32 SPI3) config CLICKER2_STM32_MB2_SPI bool "mikroBUS2 SPI" - default n if !STM32_SPI2 - default y if STM32_SPI2 + default n select STM32_SPI2 ---help--- Enable SPI support on mikroBUS1 (STM32 SPI2) -- GitLab From 5c56d8a41138cb53c7993a9ece7d1f015183cc30 Mon Sep 17 00:00:00 2001 From: Matias vo1d Date: Mon, 27 Mar 2017 09:47:02 -0600 Subject: [PATCH 228/990] Fix strange invisible characters in this declaration. --- include/sys/time.h | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/include/sys/time.h b/include/sys/time.h index 3d7139e754..ece75bc10f 100644 --- a/include/sys/time.h +++ b/include/sys/time.h @@ -77,13 +77,13 @@ #define timersub(tvp, uvp, vvp) \ do \ { \ -    (vvp)->tv_sec = (tvp)->tv_sec - (uvp)->tv_sec; \ -    (vvp)->tv_usec = (tvp)->tv_usec - (uvp)->tv_usec; \ -    if ((vvp)->tv_usec < 0) \ + (vvp)->tv_sec = (tvp)->tv_sec - (uvp)->tv_sec; \ + (vvp)->tv_usec = (tvp)->tv_usec - (uvp)->tv_usec; \ + if ((vvp)->tv_usec < 0) \ { \ -      (vvp)->tv_sec--; \ -      (vvp)->tv_usec += 1000000; \ -    } \ + (vvp)->tv_sec--; \ + (vvp)->tv_usec += 1000000; \ + } \ } \ while (0) -- GitLab From dbc074edab7e58bfb2723b2f34f65bb5ba4f53db Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Mon, 27 Mar 2017 09:49:44 -0600 Subject: [PATCH 229/990] Include wcstold in C++ cwchar header file --- include/cxx/cwchar | 1 + 1 file changed, 1 insertion(+) diff --git a/include/cxx/cwchar b/include/cxx/cwchar index 3ca4c6c1d8..167f5982ef 100755 --- a/include/cxx/cwchar +++ b/include/cxx/cwchar @@ -91,6 +91,7 @@ namespace std using ::vfwprintf; using ::vwprintf; using ::vswprintf; + using ::wcstold; using ::wcrtomb; using ::wcscat; using ::wcschr; -- GitLab From b315f0d851625709ed327b2bdb466818289025d9 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 27 Mar 2017 10:28:03 -0600 Subject: [PATCH 230/990] AT86RF23x: Clean-up, standardize lower half interface. Take advantage of new OS features for interrupt parameter passing. --- drivers/wireless/ieee802154/at86rf23x.c | 33 +++++++++---------- include/nuttx/wireless/ieee802154/at86rf23x.h | 31 +++++++++++------ 2 files changed, 36 insertions(+), 28 deletions(-) diff --git a/drivers/wireless/ieee802154/at86rf23x.c b/drivers/wireless/ieee802154/at86rf23x.c index 3bcf203373..45094e99ff 100644 --- a/drivers/wireless/ieee802154/at86rf23x.c +++ b/drivers/wireless/ieee802154/at86rf23x.c @@ -146,7 +146,7 @@ static int at86rf23x_regdump(FAR struct at86rf23x_dev_s *dev); static void at86rf23x_irqwork_rx(FAR struct at86rf23x_dev_s *dev); static void at86rf23x_irqwork_tx(FAR struct at86rf23x_dev_s *dev); static void at86rf23x_irqworker(FAR void *arg); -static int at86rf23x_interrupt(int irq, FAR void *context); +static int at86rf23x_interrupt(int irq, FAR void *context, FAR void *arg); /* Driver operations */ @@ -1221,11 +1221,11 @@ static int at86rf23x_resetrf(FAR struct at86rf23x_dev_s *dev) /* Reset the radio */ - lower->reset(lower, 0); - lower->slptr(lower, 0); + lower->reset(lower, false); + lower->slptr(lower, false); up_udelay(RF23X_TIME_RESET); - lower->reset(lower, 1); + lower->reset(lower, true); /* Dummy read of IRQ register */ @@ -1287,13 +1287,11 @@ static int at86rf23x_rxenable(FAR struct ieee802154_radio_s *ieee, bool state, * ****************************************************************************/ -static int at86rf23x_interrupt(int irq, FAR void *context) +static int at86rf23x_interrupt(int irq, FAR void *context, FAR void *arg) { - /* To support multiple devices, retrieve the priv structure using the irq - * number. - */ + FAR struct at86rf23x_dev_s *dev = (FAR struct at86rf23x_dev_s *)arg; - register FAR struct at86rf23x_dev_s *dev = &g_at86rf23x_devices[0]; + DEBUGASSERT(dev != NULL); /* In complex environments, we cannot do SPI transfers from the interrupt * handler because semaphores are probably used to lock the SPI bus. In @@ -1309,8 +1307,7 @@ static int at86rf23x_interrupt(int irq, FAR void *context) * Interrupts are re-enabled in enc_irqworker() when the work is completed. */ - dev->lower->irq(dev->lower, NULL, FALSE); - //dev->lower->enable(dev->lower, FALSE); + dev->lower->enable(dev->lower, false); return work_queue(HPWORK, &dev->irqwork, at86rf23x_irqworker, (FAR void *)dev, 0); @@ -1393,11 +1390,11 @@ static void at86rf23x_irqworker(FAR void *arg) { wlerr("ERROR: Unknown IRQ Status: %d\n", irq_status); - /* Re enable the IRQ even if we don't know how to handle previous + /* Re-enable the IRQ even if we don't know how to handle previous * status. */ - dev->lower->irq(dev->lower, NULL, true); + dev->lower->enable(dev->lower, true); } } @@ -1428,9 +1425,9 @@ static void at86rf23x_irqwork_rx(FAR struct at86rf23x_dev_s *dev) * soon. */ - /* Re enable the IRQ */ + /* Re-enable the IRQ */ - dev->lower->irq(dev->lower, NULL, true); + dev->lower->enable(dev->lower, true); } /**************************************************************************** @@ -1452,7 +1449,7 @@ static void at86rf23x_irqwork_tx(FAR struct at86rf23x_dev_s *dev) /* Re enable the IRQ */ - dev->lower->irq(dev->lower, NULL, true); + dev->lower->enable(dev->lower, true); sem_post(&dev->ieee.txsem); } @@ -1528,7 +1525,7 @@ FAR struct ieee802154_radio_s *at86rf23x_init(FAR struct spi_dev_s *spi, /* Attach irq */ - if (lower->irq(lower, at86rf23x_interrupt, false) != OK) + if (lower->attach(lower, at86rf23x_interrupt, dev) != OK) { return NULL; } @@ -1598,6 +1595,6 @@ FAR struct ieee802154_radio_s *at86rf23x_init(FAR struct spi_dev_s *spi, /* Enable Radio IRQ */ - lower->irq(lower, at86rf23x_interrupt, true); + lower->enable(lower, true); return &dev->ieee; } diff --git a/include/nuttx/wireless/ieee802154/at86rf23x.h b/include/nuttx/wireless/ieee802154/at86rf23x.h index 7d6f1fe0ce..2cdf6218cf 100644 --- a/include/nuttx/wireless/ieee802154/at86rf23x.h +++ b/include/nuttx/wireless/ieee802154/at86rf23x.h @@ -37,25 +37,36 @@ #ifndef __INCLUDE_NUTTX_IEEE802154_AT86RF23X_H #define __INCLUDE_NUTTX_IEEE802154_AT86RF23X_H +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +/**************************************************************************** + * Public Types + ****************************************************************************/ + /* The at86rf23x provides interrupts to the MCU via a GPIO pin. The * following structure provides an MCU-independent mechanixm for controlling * the at86rf23x GPIO interrupt. * * The at86rf23x interrupt is an active low, *level* interrupt. From Datasheet: - * "Note 1: The INTEDGE polarity defaults to: - * 0 = Falling Edge. Ensure that the inter- - * rupt polarity matches the interrupt pin - * polarity of the host microcontroller. - * Note 2: The INT pin will remain high or low, - * depending on INTEDGE polarity setting, - * until INTSTAT register is read." + * "Note 1: The INTEDGE polarity defaults to: 0 = Falling Edge. Ensure that + * the interrupt polarity matches the interrupt pin polarity of the host + * microcontroller. + * "Note 2: The INT pin will remain high or low, depending on INTEDGE polarity + * setting, until INTSTAT register is read." */ struct at86rf23x_lower_s { - int (*irq)(FAR const struct at86rf23x_lower_s *lower, xcpt_t handler, int state); - void (*slptr)(FAR const struct at86rf23x_lower_s *lower, int state); - void (*reset)(FAR const struct at86rf23x_lower_s *lower, int state); + int (*attach)(FAR const struct at86rf23x_lower_s *lower, xcpt_t handler, + FAR void *arg); + void (*enable)(FAR const struct at86rf23x_lower_s *lower, bool state); + void (*slptr)(FAR const struct at86rf23x_lower_s *lower, bool state); + void (*reset)(FAR const struct at86rf23x_lower_s *lower, bool state); }; #ifdef __cplusplus -- GitLab From 3fbf59e2bc7b0545d90c0efb728c850afd3e02fb Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 27 Mar 2017 10:48:58 -0600 Subject: [PATCH 231/990] MRF24J40: Take advantage of new OS features for interrupt parameter passing. --- configs/clicker2-stm32/src/stm32_mrf24j40.c | 19 +++++++------ drivers/wireless/ieee802154/mrf24j40.c | 30 ++++++-------------- include/nuttx/wireless/ieee802154/mrf24j40.h | 7 +++-- 3 files changed, 25 insertions(+), 31 deletions(-) diff --git a/configs/clicker2-stm32/src/stm32_mrf24j40.c b/configs/clicker2-stm32/src/stm32_mrf24j40.c index 5c61750f46..f32c9ed208 100644 --- a/configs/clicker2-stm32/src/stm32_mrf24j40.c +++ b/configs/clicker2-stm32/src/stm32_mrf24j40.c @@ -99,6 +99,7 @@ struct stm32_priv_s { struct mrf24j40_lower_s dev; xcpt_t handler; + FAR void *arg; uint32_t intcfg; uint8_t spidev; }; @@ -117,9 +118,9 @@ struct stm32_priv_s */ static int stm32_attach_irq(FAR const struct mrf24j40_lower_s *lower, - xcpt_t handler); + xcpt_t handler, FAR void *arg); static void stm32_enable_irq(FAR const struct mrf24j40_lower_s *lower, - int state); + bool state); static int stm32_mrf24j40_devsetup(FAR struct stm32_priv_s *priv); /**************************************************************************** @@ -173,7 +174,7 @@ static struct stm32_priv_s g_mrf24j40_mb2_priv = */ static int stm32_attach_irq(FAR const struct mrf24j40_lower_s *lower, - xcpt_t handler) + xcpt_t handler, FAR void *arg) { FAR struct stm32_priv_s *priv = (FAR struct stm32_priv_s *)lower; @@ -182,10 +183,12 @@ static int stm32_attach_irq(FAR const struct mrf24j40_lower_s *lower, /* Just save the handler for use when the interrupt is enabled */ priv->handler = handler; + priv->arg = arg; return OK; } -static void stm32_enable_irq(FAR const struct mrf24j40_lower_s *lower, int state) +static void stm32_enable_irq(FAR const struct mrf24j40_lower_s *lower, + bool state) { FAR struct stm32_priv_s *priv = (FAR struct stm32_priv_s *)lower; @@ -193,15 +196,15 @@ static void stm32_enable_irq(FAR const struct mrf24j40_lower_s *lower, int state * has not yet been 'attached' */ - DEBUGASSERT(priv != NULL && (priv->handler != NULL || state == 0)); + DEBUGASSERT(priv != NULL && (priv->handler != NULL || !state)); /* Attach and enable, or detach and disable */ - wlinfo("state:%d\n", state); - if (state != 0) + wlinfo("state:%d\n", (int)state); + if (state) { (void)stm32_gpiosetevent(priv->intcfg, true, true, true, - priv->handler, NULL); + priv->handler, priv->arg); } else { diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c index 09365ebc83..300e0d50e5 100644 --- a/drivers/wireless/ieee802154/mrf24j40.c +++ b/drivers/wireless/ieee802154/mrf24j40.c @@ -196,7 +196,7 @@ static int mrf24j40_transmit(FAR struct ieee802154_radio_s *ieee, static struct mrf24j40_radio_s g_mrf24j40_devices[1]; -static const struct ieee802154_radioops_s mrf24j40_devops = +static const struct ieee802154_radioops_s mrf24j40_devops = { mrf24j40_setchannel, mrf24j40_getchannel, mrf24j40_setpanid , mrf24j40_getpanid, @@ -1322,9 +1322,9 @@ static void mrf24j40_irqworker(FAR void *arg) mrf24j40_irqwork_tx(dev); } - /* Re-Enable GPIO interrupts */ + /* Re-enable GPIO interrupts */ - dev->lower->enable(dev->lower, TRUE); + dev->lower->enable(dev->lower, true); } /**************************************************************************** @@ -1346,16 +1346,9 @@ static void mrf24j40_irqworker(FAR void *arg) static int mrf24j40_interrupt(int irq, FAR void *context, FAR void *arg) { - /* To support multiple devices, - * retrieve the priv structure using the irq number - * - * REVISIT: This will not handler multiple MRF24J40 devices. The correct - * solutions is to pass the struct mrf24j40_radio_s in the call to - * irq_attach() as the third 'arg' parameter. That will be provided here - * and the correct instance can be obtained with a simply case of 'arg'. - */ + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)arg; - register FAR struct mrf24j40_radio_s *dev = &g_mrf24j40_devices[0]; + DEBUGASSERT(dev != NULL); /* In complex environments, we cannot do SPI transfers from the interrupt * handler because semaphores are probably used to lock the SPI bus. In @@ -1371,7 +1364,7 @@ static int mrf24j40_interrupt(int irq, FAR void *context, FAR void *arg) * Interrupts are re-enabled in enc_irqworker() when the work is completed. */ - dev->lower->enable(dev->lower, FALSE); + dev->lower->enable(dev->lower, false); return work_queue(HPWORK, &dev->irqwork, mrf24j40_irqworker, (FAR void *)dev, 0); } @@ -1403,13 +1396,9 @@ FAR struct ieee802154_radio_s *mrf24j40_init(FAR struct spi_dev_s *spi, dev = &g_mrf24j40_devices[0]; #endif - /* Attach irq. - * - * REVISIT: A third argument is required to pass the instance of 'lower' - * to the interrupt handler. - */ + /* Attach irq */ - if (lower->attach(lower, mrf24j40_interrupt) != OK) + if (lower->attach(lower, mrf24j40_interrupt, dev) != OK) { #if 0 free(dev); @@ -1454,7 +1443,6 @@ FAR struct ieee802154_radio_s *mrf24j40_init(FAR struct spi_dev_s *spi, mrf24j40_pacontrol(dev, MRF24J40_PA_AUTO); - dev->lower->enable(dev->lower, TRUE); - + dev->lower->enable(dev->lower, true); return &dev->ieee; } diff --git a/include/nuttx/wireless/ieee802154/mrf24j40.h b/include/nuttx/wireless/ieee802154/mrf24j40.h index 8f86abcfcb..c5d1375923 100644 --- a/include/nuttx/wireless/ieee802154/mrf24j40.h +++ b/include/nuttx/wireless/ieee802154/mrf24j40.h @@ -40,6 +40,8 @@ * Included files ****************************************************************************/ +#include +#include #include /**************************************************************************** @@ -62,8 +64,9 @@ struct mrf24j40_lower_s { - int (*attach)(FAR const struct mrf24j40_lower_s *lower, xcpt_t handler); - void (*enable)(FAR const struct mrf24j40_lower_s *lower, int state); + int (*attach)(FAR const struct mrf24j40_lower_s *lower, xcpt_t handler, + FAR void *arg); + void (*enable)(FAR const struct mrf24j40_lower_s *lower, bool state); }; #ifdef __cplusplus -- GitLab From 941360bf12e84b8c219201b5c21b81e6bb3f7608 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 27 Mar 2017 10:49:41 -0600 Subject: [PATCH 232/990] Correct some spacing --- sched/Kconfig | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/sched/Kconfig b/sched/Kconfig index 0a09c524fe..50613fb44d 100644 --- a/sched/Kconfig +++ b/sched/Kconfig @@ -536,12 +536,12 @@ choice default PTHREAD_MUTEX_ROBUST if !DEFAULT_SMALL default PTHREAD_UNSAFE if DEFAULT_SMALL - config PTHREAD_MUTEX_ROBUST +config PTHREAD_MUTEX_ROBUST bool "Robust mutexes" ---help--- Support only the robust form of the NORMAL mutex. - config PTHREAD_MUTEX_UNSAFE +config PTHREAD_MUTEX_UNSAFE bool "Traditional unsafe mutexes" ---help--- Support only the traditional non-robust form of the NORMAL mutex. @@ -549,7 +549,7 @@ choice software you may be porting or, perhaps, if you are trying to minimize footprint. - config PTHREAD_MUTEX_BOTH +config PTHREAD_MUTEX_BOTH bool "Both robust and unsafe mutexes" ---help--- Support both forms of NORMAL mutexes. @@ -561,12 +561,12 @@ choice default PTHREAD_MUTEX_DEFAULT_ROBUST depends on PTHREAD_MUTEX_BOTH - config PTHREAD_MUTEX_DEFAULT_ROBUST +config PTHREAD_MUTEX_DEFAULT_ROBUST bool "Robust default" ---help--- The default is robust NORMAL mutexes (non-standard) - config PTHREAD_MUTEX_DEFAULT_UNSAFE +config PTHREAD_MUTEX_DEFAULT_UNSAFE bool "Unsafe default" ---help--- The default is traditional unsafe NORMAL mutexes (standard) -- GitLab From 6c4dac459afcecc0aefdf982951262652069144e Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 27 Mar 2017 12:28:34 -0600 Subject: [PATCH 233/990] lcd/: PCF8574 backpack logic needs to include poll.h CONFIG_DISABLE_POLL is not set. --- README.txt | 3 +++ drivers/lcd/pcf8574_lcd_backpack.c | 3 ++- 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/README.txt b/README.txt index 3db07e882a..59648d01f4 100644 --- a/README.txt +++ b/README.txt @@ -197,6 +197,9 @@ Ubuntu Bash under Windows 10 C:\Users\Username\AppData\Local\lxss\rootfs + However, I am unable to see my files under the rootfs/home directory + so this is not very useful. + Install Linux Software. ----------------------- Use "sudo apt-get install ". As examples, this is how diff --git a/drivers/lcd/pcf8574_lcd_backpack.c b/drivers/lcd/pcf8574_lcd_backpack.c index ad107f1ff4..4729481a57 100644 --- a/drivers/lcd/pcf8574_lcd_backpack.c +++ b/drivers/lcd/pcf8574_lcd_backpack.c @@ -1,7 +1,7 @@ /**************************************************************************** * drivers/lcd/pcf8574_lcd_backpack.c * - * Copyright (C) 2016 Gregory Nutt. All rights reserved. + * Copyright (C) 2016-2017 Gregory Nutt. All rights reserved. * Author: dev@ziggurat29.com * * Redistribution and use in source and binary forms, with or without @@ -39,6 +39,7 @@ #include +#include #include #include #include -- GitLab From a522fc4f349c56c8c121ffa22ae9409256f6aa07 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 27 Mar 2017 14:53:52 -0600 Subject: [PATCH 234/990] 6loWPAN: Rename net/6lowpan to net/sixlowpan; Add Contike sixlowpan.h to include/nuttx/net --- include/nuttx/net/sixlowpan.h | 310 ++++++++++++++++++ net/Kconfig | 2 +- net/Makefile | 2 +- net/{6lowpan => sixlowpan}/Kconfig | 0 net/{6lowpan => sixlowpan}/Make.defs | 8 +- .../6lowpan.h => sixlowpan/sixlowpan.h} | 8 +- 6 files changed, 320 insertions(+), 10 deletions(-) create mode 100644 include/nuttx/net/sixlowpan.h rename net/{6lowpan => sixlowpan}/Kconfig (100%) rename net/{6lowpan => sixlowpan}/Make.defs (93%) rename net/{6lowpan/6lowpan.h => sixlowpan/sixlowpan.h} (94%) diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h new file mode 100644 index 0000000000..868d48076b --- /dev/null +++ b/include/nuttx/net/sixlowpan.h @@ -0,0 +1,310 @@ +/**************************************************************************** + * include/nuttx/net/sixlowpan.h + * Header file for the 6lowpan implementation (RFC4944 and draft-hui-6lowpan-hc-01) + * + * Copyright (C) 2017, Gregory Nutt, all rights reserved + * Author: Gregory Nutt + * + * Derives from Contiki: + * + * Copyright (c) 2008, Swedish Institute of Computer Science. + * All rights reserved. + * Authors: Adam Dunkels + * Nicolas Tsiftes + * Niclas Finne + * Mathilde Durvy + * Julien Abeille + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the Institute 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 INSTITUTE 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 INSTITUTE 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_NET_SIXLOWOAN_H +#define __INCLUDE_NUTTX_NET_SIXLOWOAN_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Min and Max compressible UDP ports - HC06 */ + +#define SIXLOWPAN_UDP_4_BIT_PORT_MIN 0xf0b0 +#define SIXLOWPAN_UDP_4_BIT_PORT_MAX 0xf0bf /* F0B0 + 15 */ +#define SIXLOWPAN_UDP_8_BIT_PORT_MIN 0xF000 +#define SIXLOWPAN_UDP_8_BIT_PORT_MAX 0xf0ff /* F000 + 255 */ + +/* 6lowpan compressions */ + +#define SIXLOWPAN_COMPRESSION_IPV6 0 +#define SIXLOWPAN_COMPRESSION_HC1 1 +#define SIXLOWPAN_COMPRESSION_HC06 2 + +/* 6lowpan dispatches */ + +#define SIXLOWPAN_DISPATCH_IPV6 0x41 /* 01000001 = 65 */ +#define SIXLOWPAN_DISPATCH_HC1 0x42 /* 01000010 = 66 */ +#define SIXLOWPAN_DISPATCH_IPHC 0x60 /* 011xxxxx = ... */ +#define SIXLOWPAN_DISPATCH_FRAG1 0xc0 /* 11000xxx */ +#define SIXLOWPAN_DISPATCH_FRAGN 0xe0 /* 11100xxx */ + +/* HC1 encoding */ + +#define SIXLOWPAN_HC1_NH_UDP 0x02 +#define SIXLOWPAN_HC1_NH_TCP 0x06 +#define SIXLOWPAN_HC1_NH_ICMP6 0x04 + +/* HC_UDP encoding (works together with HC1) */ + +#define SIXLOWPAN_HC_UDP_ALL_C 0xe0 + +/* IPHC encoding + * + * Values of fields within the IPHC encoding first byte (C stands for + * compressed and I for inline) + */ + +#define SIXLOWPAN_IPHC_FL_C 0x10 +#define SIXLOWPAN_IPHC_TC_C 0x08 +#define SIXLOWPAN_IPHC_NH_C 0x04 +#define SIXLOWPAN_IPHC_TTL_1 0x01 +#define SIXLOWPAN_IPHC_TTL_64 0x02 +#define SIXLOWPAN_IPHC_TTL_255 0x03 +#define SIXLOWPAN_IPHC_TTL_I 0x00 + + +/* Values of fields within the IPHC encoding second byte */ + +#define SIXLOWPAN_IPHC_CID 0x80 + +#define SIXLOWPAN_IPHC_SAC 0x40 +#define SIXLOWPAN_IPHC_SAM_00 0x00 +#define SIXLOWPAN_IPHC_SAM_01 0x10 +#define SIXLOWPAN_IPHC_SAM_10 0x20 +#define SIXLOWPAN_IPHC_SAM_11 0x30 + +#define SIXLOWPAN_IPHC_SAM_BIT 4 + +#define SIXLOWPAN_IPHC_M 0x08 +#define SIXLOWPAN_IPHC_DAC 0x04 +#define SIXLOWPAN_IPHC_DAM_00 0x00 +#define SIXLOWPAN_IPHC_DAM_01 0x01 +#define SIXLOWPAN_IPHC_DAM_10 0x02 +#define SIXLOWPAN_IPHC_DAM_11 0x03 + +#define SIXLOWPAN_IPHC_DAM_BIT 0 + +/* Link local context number */ + +#define SIXLOWPAN_IPHC_ADDR_CONTEXT_LL 0 + +/* 16-bit multicast addresses compression */ + +#define SIXLOWPAN_IPHC_MCAST_RANGE 0xa0 + +/* NHC_EXT_HDR */ + +#define SIXLOWPAN_NHC_MASK 0xf0 +#define SIXLOWPAN_NHC_EXT_HDR 0xe0 + +/* LOWPAN_UDP encoding (works together with IPHC) */ + +#define SIXLOWPAN_NHC_UDP_MASK 0xf8 +#define SIXLOWPAN_NHC_UDP_ID 0xf0 +#define SIXLOWPAN_NHC_UDP_CHECKSUMC 0x04 +#define SIXLOWPAN_NHC_UDP_CHECKSUMI 0x00 + +/* Values for port compression, _with checksum_ ie bit 5 set to 0 */ + +#define SIXLOWPAN_NHC_UDP_CS_P_00 0xf0 /* All inline */ +#define SIXLOWPAN_NHC_UDP_CS_P_01 0xf1 /* Source 16bit inline, dest = 0xf0 + 8 bit inline */ +#define SIXLOWPAN_NHC_UDP_CS_P_10 0xf2 /* Source = 0xf0 + 8bit inline, dest = 16 bit inline */ +#define SIXLOWPAN_NHC_UDP_CS_P_11 0xf3 /* Source & dest = 0xf0b + 4bit inline */ + +/* The 6lowpan "headers" length */ + +#define SIXLOWPAN_IPV6_HDR_LEN 1 /* One byte */ +#define SIXLOWPAN_HC1_HDR_LEN 3 +#define SIXLOWPAN_HC1_HC_UDP_HDR_LEN 7 +#define SIXLOWPAN_FRAG1_HDR_LEN 4 +#define SIXLOWPAN_FRAGN_HDR_LEN 5 + +/* Address compressibility test macros */ + +/* Check whether we can compress the IID in address 'a' to 16 bits. This is + * used for unicast addresses only, and is true if the address is on the + * format ::0000:00ff:fe00:XXXX + * + * NOTE: we currently assume 64-bits prefixes + */ + +#define SIXLOWPAN_IS_IID_16BIT_COMPRESSABLE(a) \ + ((((a)->u16[4]) == 0) && \ + // (((a)->u8[10]) == 0)&& \ + (((a)->u8[11]) == 0xff)&& \ + (((a)->u8[12]) == 0xfe)&& \ + (((a)->u8[13]) == 0)) + +/* Check whether the 9-bit group-id of the compressed multicast address is + * known. It is true if the 9-bit group is the all nodes or all routers + * group. Parameter 'a' is typed uint8_t * + */ + +#define SIXLOWPAN_IS_MCASTADDR_DECOMPRESSABLE(a) \ + (((*a & 0x01) == 0) && \ + ((*(a + 1) == 0x01) || (*(a + 1) == 0x02))) + +/* Check whether the 112-bit group-id of the multicast address is mappable + * to a 9-bit group-id. It is true if the group is the all nodes or all + * routers group. + */ + +#define SIXLOWPAN_IS_MCASTADDR_COMPRESSABLE(a) \ + ((((a)->u16[1]) == 0) && \ + (((a)->u16[2]) == 0) && \ + (((a)->u16[3]) == 0) && \ + (((a)->u16[4]) == 0) && \ + (((a)->u16[5]) == 0) && \ + (((a)->u16[6]) == 0) && \ + (((a)->u8[14]) == 0) && \ + ((((a)->u8[15]) == 1) || (((a)->u8[15]) == 2))) + +/* FFXX::00XX:XXXX:XXXX */ + +#define SIXLOWPAN_IS_MCASTADDR_COMPRESSABLE48(a) \ + ((((a)->u16[1]) == 0) && \ + (((a)->u16[2]) == 0) && \ + (((a)->u16[3]) == 0) && \ + (((a)->u16[4]) == 0) && \ + (((a)->u8[10]) == 0)) + +/* FFXX::00XX:XXXX */ + +#define SIXLOWPAN_IS_MCASTADDR_COMPRESSABLE32(a) \ + ((((a)->u16[1]) == 0) && \ + (((a)->u16[2]) == 0) && \ + (((a)->u16[3]) == 0) && \ + (((a)->u16[4]) == 0) && \ + (((a)->u16[5]) == 0) && \ + (((a)->u8[12]) == 0)) + +/* FF02::00XX */ + +#define SIXLOWPAN_IS_MCASTADDR_COMPRESSABLE8(a) \ + ((((a)->u8[1]) == 2) && \ + (((a)->u16[1]) == 0) && \ + (((a)->u16[2]) == 0) && \ + (((a)->u16[3]) == 0) && \ + (((a)->u16[4]) == 0) && \ + (((a)->u16[5]) == 0) && \ + (((a)->u16[6]) == 0) && \ + (((a)->u8[14]) == 0)) + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* The header for fragments + * + * NOTE: We do not define different structures for FRAG1 and FRAGN headers, + * which are different. For FRAG1, the offset field is just not used + */ + +struct sixlowpan_frag_hdr +{ + uint16_t dispatch_size; + uint16_t tag; + uint8_t offset; +}; + +/* The HC1 header when HC_UDP is not used + * + * When all fields are compressed and HC_UDP is not used, we use this + * structure. If HC_UDP is used, the ttl is in another spot, and we use the + * sixlowpan_hc1_hc_udp structure + */ + +struct sixlowpan_hc1_hdr +{ + uint8_t dispatch; + uint8_t encoding; + uint8_t ttl; +}; + +/* HC1 followed by HC_UDP */ + +struct sixlowpan_hc1_hc_udp_hdr +{ + uint8_t dispatch; + uint8_t hc1_encoding; + uint8_t hc_udp_encoding; + uint8_t ttl; + uint8_t ports; + uint16_t udpchksum; +}; + +/* An address context for IPHC address compression each context can have up + * to 8 bytes + */ + +struct sixlowpan_addr_context +{ + uint8_t used; /* Possibly use as prefix-length */ + uint8_t number; + uint8_t prefix[8]; +}; + + +/* The structure of a next header compressor. + * + * TODO: needs more parameters when compressing extension headers, etc. + */ + +struct sixlowpan_nhcompressor_s +{ + CODE int (*is_compressable)(uint8_t next_header); + + /* Compress next header (TCP/UDP, etc) - ptr points to next header to + * compress. + */ + + CODE int (*compress)(FAR uint8_t *compressed, FAR uint8_t *uncompressed_len); + + /* Uncompress next header (TCP/UDP, etc) - ptr points to next header to + * uncompress. + */ + + CODE int (*uncompress)(FAR uint8_t *compressed, FAR uint8_t *lowpanbuf, + FAR uint8_t *uncompressed_len); +}; + +#endif /* __INCLUDE_NUTTX_NET_SIXLOWOAN_H */ diff --git a/net/Kconfig b/net/Kconfig index 2fea54f86f..2741c67816 100644 --- a/net/Kconfig +++ b/net/Kconfig @@ -255,7 +255,7 @@ menuconfig NET_IPv6 Build in support for IPv6. source "net/neighbor/Kconfig" -source "net/6lowpan/Kconfig" +source "net/sixlowpan/Kconfig" endmenu # Internet Protocol Selection diff --git a/net/Makefile b/net/Makefile index 2487ce9609..6898bad40e 100644 --- a/net/Makefile +++ b/net/Makefile @@ -67,7 +67,7 @@ include pkt/Make.defs include local/Make.defs include tcp/Make.defs include udp/Make.defs -include 6lowpan/Make.defs +include sixlowpan/Make.defs include devif/Make.defs include loopback/Make.defs include route/Make.defs diff --git a/net/6lowpan/Kconfig b/net/sixlowpan/Kconfig similarity index 100% rename from net/6lowpan/Kconfig rename to net/sixlowpan/Kconfig diff --git a/net/6lowpan/Make.defs b/net/sixlowpan/Make.defs similarity index 93% rename from net/6lowpan/Make.defs rename to net/sixlowpan/Make.defs index e52060673a..f3e99c3504 100644 --- a/net/6lowpan/Make.defs +++ b/net/sixlowpan/Make.defs @@ -1,5 +1,5 @@ ############################################################################ -# net/6lowpan/Make.defs +# net/sixlowpan/Make.defs # # Copyright (C) 2016 Gregory Nutt. All rights reserved. # Author: Gregory Nutt @@ -41,9 +41,9 @@ ifeq ($(CONFIG_NET_6LOWPAN),y) # NET_CSRCS += -# Include the 6lowpan directory in the build +# Include the sixlowpan directory in the build -DEPPATH += --dep-path 6lowpan -VPATH += :6lowpan +DEPPATH += --dep-path sixlowpan +VPATH += :sixlowpan endif # CONFIG_NET_6LOWPAN diff --git a/net/6lowpan/6lowpan.h b/net/sixlowpan/sixlowpan.h similarity index 94% rename from net/6lowpan/6lowpan.h rename to net/sixlowpan/sixlowpan.h index 657b04c75b..38263bc31b 100644 --- a/net/6lowpan/6lowpan.h +++ b/net/sixlowpan/sixlowpan.h @@ -1,5 +1,5 @@ /**************************************************************************** - * net/6lowpan/6lowpan.h + * net/sixlowpan/sixlowpan.h * * Copyright (C) 2016 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -33,8 +33,8 @@ * ****************************************************************************/ -#ifndef __NET_6LOWPAN_6LOWPAN_H -#define __NET_6LOWPAN_6LOWPAN_H +#ifndef _NET_SIXLOWPAN_SIXLOWPAN_H +#define _NET_SIXLOWPAN_SIXLOWPAN_H /**************************************************************************** * Included Files @@ -53,4 +53,4 @@ ****************************************************************************/ #endif /* CONFIG_NET_6LOWPAN */ -#endif /* __NET_6LOWPAN_6LOWPAN_H */ +#endif /* _NET_SIXLOWPAN_SIXLOWPAN_H */ -- GitLab From dab2fb2eb3b62424fcf91838aae829326f7953a6 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 27 Mar 2017 16:19:46 -0600 Subject: [PATCH 235/990] Add a comment --- include/nuttx/net/sixlowpan.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index 868d48076b..06ba6ac5c6 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -307,4 +307,8 @@ struct sixlowpan_nhcompressor_s FAR uint8_t *uncompressed_len); }; +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + #endif /* __INCLUDE_NUTTX_NET_SIXLOWOAN_H */ -- GitLab From 65e95b95f23a2d654c017abd7f77c2b05dda1a09 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 27 Mar 2017 18:15:20 -0600 Subject: [PATCH 236/990] Add a little more 6loWPAN logic --- include/nuttx/net/netdev.h | 4 ++ include/nuttx/net/sixlowpan.h | 46 +++++++++++++- net/sixlowpan/Make.defs | 2 +- net/sixlowpan/sixlowpan.h | 13 ++++ net/sixlowpan/sixlowpan_compressor.c | 88 +++++++++++++++++++++++++++ net/sixlowpan/sixlowpan_sniffer.c | 89 ++++++++++++++++++++++++++++ 6 files changed, 240 insertions(+), 2 deletions(-) create mode 100644 net/sixlowpan/sixlowpan_compressor.c create mode 100644 net/sixlowpan/sixlowpan_sniffer.c diff --git a/include/nuttx/net/netdev.h b/include/nuttx/net/netdev.h index 6a529fb368..72bddc067c 100644 --- a/include/nuttx/net/netdev.h +++ b/include/nuttx/net/netdev.h @@ -418,6 +418,10 @@ int ipv4_input(FAR struct net_driver_s *dev); int ipv6_input(FAR struct net_driver_s *dev); #endif +#ifdef CONFIG_NET_6LOWPAN +int sixlowpan_input(FAR struct net_driver_s *dev); +#endif + /**************************************************************************** * Polling of connections * diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index 06ba6ac5c6..4b956db8aa 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -284,7 +284,8 @@ struct sixlowpan_addr_context }; -/* The structure of a next header compressor. +/* The structure of a next header compressor. This compressor is provided + * by architecture-specific logic outside of the network stack. * * TODO: needs more parameters when compressing extension headers, etc. */ @@ -307,8 +308,51 @@ struct sixlowpan_nhcompressor_s FAR uint8_t *uncompressed_len); }; +/* RIME sniffer callbacks */ + +struct sixlowpan_rime_sniffer_s +{ + CODE void (*input)(void); + CODE void (*output)(int mac_status); +}; + /**************************************************************************** * Public Function Prototypes ****************************************************************************/ +/**************************************************************************** + * Function: sixlowpan_set_compressor + * + * Description: + * Configure to use the architecture-specific compressor. + * + * Input parameters: + * compressor - A reference to the new compressor to be used. This may + * be a NULL value to disable the compressor. + * + * Returned Value: + * None + * + ****************************************************************************/ + +void sixlowpan_set_compressor(FAR struct sixlowpan_nhcompressor_s *compressor); + +/**************************************************************************** + * Function: sixlowpan_set_sniffer + * + * Description: + * Configure to use an architecture-specific sniffer to enable tracing of + * IP. + * + * Input parameters: + * sniffer - A reference to the new sniffer to be used. This may + * be a NULL value to disable the sniffer. + * + * Returned Value: + * None + * + ****************************************************************************/ + +void sixlowpan_set_sniffer(FAR struct sixlowpan_rime_sniffer_s *sniffer); + #endif /* __INCLUDE_NUTTX_NET_SIXLOWOAN_H */ diff --git a/net/sixlowpan/Make.defs b/net/sixlowpan/Make.defs index f3e99c3504..150cb6ec88 100644 --- a/net/sixlowpan/Make.defs +++ b/net/sixlowpan/Make.defs @@ -39,7 +39,7 @@ ifeq ($(CONFIG_NET_6LOWPAN),y) # Include IEEE 802.15.4 file in the build -# NET_CSRCS += +NET_CSRCS += sixlowpan_compressor.c sixlowpan_sniffer.c # Include the sixlowpan directory in the build diff --git a/net/sixlowpan/sixlowpan.h b/net/sixlowpan/sixlowpan.h index 38263bc31b..e85135e0cf 100644 --- a/net/sixlowpan/sixlowpan.h +++ b/net/sixlowpan/sixlowpan.h @@ -44,6 +44,19 @@ #ifdef CONFIG_NET_6LOWPAN +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/* A pointer to the optional, architecture-specific compressor */ + +struct sixlowpan_nhcompressor_s; /* Foward reference */ +extern FAR struct sixlowpan_nhcompressor_s *g_sixlowpan_compressor; + +/* Rime Sniffer support for one single listener to enable trace of IP */ + +extern struct sixlowpan_rime_sniffer_s *g_sixlopan_sniffer; + /**************************************************************************** * Public Types ****************************************************************************/ diff --git a/net/sixlowpan/sixlowpan_compressor.c b/net/sixlowpan/sixlowpan_compressor.c new file mode 100644 index 0000000000..0f78113802 --- /dev/null +++ b/net/sixlowpan/sixlowpan_compressor.c @@ -0,0 +1,88 @@ +/**************************************************************************** + * net/sixlowpan/sixlowpan_compressor.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include "nuttx/net/net.h" +#include "nuttx/net/sixlowpan.h" + +#include "sixlowpan/sixlopan.h" + +#ifdef CONFIG_NET_6LOWPAN + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/* A pointer to the optional, architecture-specific compressor */ + +FAR struct sixlowpan_nhcompressor_s *g_sixlowpan_compressor; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: sixlowpan_set_compressor + * + * Description: + * Configure to use the architecture-specific compressor. + * + * Input parameters: + * compressor - A reference to the new compressor to be used. This may + * be a NULL value to disable the compressor. + * + * Returned Value: + * None + * + ****************************************************************************/ + +void sixlowpan_set_compressor(FAR struct sixlowpan_nhcompressor_s *compressor) +{ + /* Make sure that the compressor is not in use */ + + net_lock(); + + /* Then instantiate the new compressor */ + + g_sixlowpan_compressor = compressor; + net_unlock(); +} + +#endif /* CONFIG_NET_6LOWPAN */ diff --git a/net/sixlowpan/sixlowpan_sniffer.c b/net/sixlowpan/sixlowpan_sniffer.c new file mode 100644 index 0000000000..9f00efe62a --- /dev/null +++ b/net/sixlowpan/sixlowpan_sniffer.c @@ -0,0 +1,89 @@ +/**************************************************************************** + * net/sixlowpan/sixlowpan_sniffer.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include "nuttx/net/net.h" +#include "nuttx/net/sixlowpan.h" + +#include "sixlowpan/sixlopan.h" + +#ifdef CONFIG_NET_6LOWPAN + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/* A pointer to the optional, architecture-specific sniffer */ + +FAR struct sixlowpan_rime_sniffer_s *g_sixlowpan_sniffer; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: sixlowpan_set_sniffer + * + * Description: + * Configure to use an architecture-specific sniffer to enable tracing of + * IP. + * + * Input parameters: + * sniffer - A reference to the new sniffer to be used. This may + * be a NULL value to disable the sniffer. + * + * Returned Value: + * None + * + ****************************************************************************/ + +void sixlowpan_set_sniffer(FAR struct sixlowpan_rime_sniffer_s *sniffer) +{ + /* Make sure that the sniffer is not in use */ + + net_lock(); + + /* Then instantiate the new sniffer */ + + g_sixlowpan_sniffer = sniffer; + net_unlock(); +} + +#endif /* CONFIG_NET_6LOWPAN */ -- GitLab From 91f96b6ecbf1396c47954664c5d5bb9ce5c185e1 Mon Sep 17 00:00:00 2001 From: Martin Lederhilger Date: Tue, 28 Mar 2017 06:34:37 -0600 Subject: [PATCH 237/990] drivers/analog: Add driver for the LTC1767L ADC. --- drivers/analog/Kconfig | 19 ++ drivers/analog/Make.defs | 4 + drivers/analog/ltc1867l.c | 380 ++++++++++++++++++++++++++++++++ include/nuttx/analog/ltc1867l.h | 137 ++++++++++++ 4 files changed, 540 insertions(+) create mode 100644 drivers/analog/ltc1867l.c create mode 100644 include/nuttx/analog/ltc1867l.h diff --git a/drivers/analog/Kconfig b/drivers/analog/Kconfig index c9a2334361..ec14bdcd05 100644 --- a/drivers/analog/Kconfig +++ b/drivers/analog/Kconfig @@ -66,6 +66,25 @@ config ADS1255_FREQUENCY endif # ADC_ADS125X +config ADC_LTC1867L + bool "LTC 1863L/1867L support" + default n + select SPI + ---help--- + Enable driver support for the LTC 1863L (12 bit) and LTC 1867L (16 bit) SPI powered ADC. + + Note that the ADC conversion is started via the ANIOC_TRIGGER iotcl. + +if ADC_LTC1867L + +config LTC1867L_FREQUENCY + int "LTC 1863L/1867L SPI frequency" + default 1000000 + ---help--- + LTC 1863L/1867L SPI frequency. Maximum is 20 MHz. + +endif # ADC_LTC1867L + config ADC_PGA11X bool "TI PGA112/3/6/7 support" default n diff --git a/drivers/analog/Make.defs b/drivers/analog/Make.defs index fbcc369a4c..01d5a2fe8e 100644 --- a/drivers/analog/Make.defs +++ b/drivers/analog/Make.defs @@ -83,6 +83,10 @@ endif ifeq ($(CONFIG_ADC_ADS125X),y) CSRCS += ads1255.c endif + +ifeq ($(CONFIG_ADC_LTC1867L),y) + CSRCS += ltc1867l.c +endif endif # Add analog driver build support (the nested if-then-else implements an OR) diff --git a/drivers/analog/ltc1867l.c b/drivers/analog/ltc1867l.c new file mode 100644 index 0000000000..0f5bf1a758 --- /dev/null +++ b/drivers/analog/ltc1867l.c @@ -0,0 +1,380 @@ +/**************************************************************************** + * arch/drivers/analog/ltc1867l.c + * + * Copyright (C) 2017 DS-Automotion GmbH. All rights reserved. + * Author: Martin Lederhilger + * + * This file is a part of NuttX: + * + * Copyright (C) 2017 Gregory Nutt. 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 + +#include +#include +#include +#include +#include + +#if defined(CONFIG_ADC_LTC1867L) + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Device uses SPI Mode 1: CKPOL = 0, CKPHA = 0 */ + +#define LTC1867L_SPI_MODE (SPIDEV_MODE0) + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct ltc1867l_dev_s +{ + FAR const struct adc_callback_s *cb; + FAR struct spi_dev_s *spi; + unsigned int devno; + FAR struct ltc1867l_channel_config_s *channel_config; + int channel_config_count; + sem_t sem; +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static void adc_lock(FAR struct spi_dev_s *spi); +static void adc_unlock(FAR struct spi_dev_s *spi); + +/* ADC methods */ + +static int adc_bind(FAR struct adc_dev_s *dev, + FAR const struct adc_callback_s *callback); +static void adc_reset(FAR struct adc_dev_s *dev); +static int adc_setup(FAR struct adc_dev_s *dev); +static void adc_shutdown(FAR struct adc_dev_s *dev); +static void adc_rxint(FAR struct adc_dev_s *dev, bool enable); +static int adc_ioctl(FAR struct adc_dev_s *dev, int cmd, unsigned long arg); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const struct adc_ops_s g_adcops = +{ + .ao_bind = adc_bind, /* ao_bind */ + .ao_reset = adc_reset, /* ao_reset */ + .ao_setup = adc_setup, /* ao_setup */ + .ao_shutdown = adc_shutdown, /* ao_shutdown */ + .ao_rxint = adc_rxint, /* ao_rxint */ + .ao_ioctl = adc_ioctl /* ao_read */ +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: adc_lock + * + * Description: + * Lock and configure the SPI bus. + * + ****************************************************************************/ + +static void adc_lock(FAR struct spi_dev_s *spi) +{ + (void)SPI_LOCK(spi, true); + SPI_SETMODE(spi, LTC1867L_SPI_MODE); + SPI_SETBITS(spi, 16); + (void)SPI_HWFEATURES(spi, 0); + SPI_SETFREQUENCY(spi, CONFIG_LTC1867L_FREQUENCY); +} + +/**************************************************************************** + * Name: adc_unlock + * + * Description: + * Unlock the SPI bus. + * + ****************************************************************************/ + +static void adc_unlock(FAR struct spi_dev_s *spi) +{ + (void)SPI_LOCK(spi, false); +} + +/**************************************************************************** + * Name: adc_bind + * + * Description: + * Bind the upper-half driver callbacks to the lower-half implementation. This + * must be called early in order to receive ADC event notifications. + * + ****************************************************************************/ + +static int adc_bind(FAR struct adc_dev_s *dev, + FAR const struct adc_callback_s *callback) +{ + FAR struct ltc1867l_dev_s *priv = (FAR struct ltc1867l_dev_s *)dev->ad_priv; + priv->cb = callback; + return OK; +} + +/**************************************************************************** + * Name: adc_reset + * + * Description: + * Reset the ADC device. Called early to initialize the hardware. This + * is called, before ao_setup() and on error conditions. + * + ****************************************************************************/ + +static void adc_reset(FAR struct adc_dev_s *dev) +{ +} + +/**************************************************************************** + * Name: adc_setup + * + * Description: + * Configure the ADC. This method is called the first time that the ADC + * device is opened. This will occur when the port is first opened. + * This setup includes configuring and attaching ADC interrupts. Interrupts + * are all disabled upon return. + * + ****************************************************************************/ + +static int adc_setup(FAR struct adc_dev_s *dev) +{ + return OK; +} + +/**************************************************************************** + * Name: adc_shutdown + * + * Description: + * Disable the ADC. This method is called when the ADC device is closed. + * This method reverses the operation the setup method. + * + ****************************************************************************/ + +static void adc_shutdown(FAR struct adc_dev_s *dev) +{ +} + +/**************************************************************************** + * Name: adc_rxint + * + * Description: + * Call to enable or disable RX interrupts + * + ****************************************************************************/ + +static void adc_rxint(FAR struct adc_dev_s *dev, bool enable) +{ +} + +/**************************************************************************** + * Name: adc_ioctl + * + * Description: + * All ioctl calls will be routed through this method + * + ****************************************************************************/ + +static int adc_ioctl(FAR struct adc_dev_s *dev, int cmd, unsigned long arg) +{ + FAR struct ltc1867l_dev_s *priv = (FAR struct ltc1867l_dev_s *)dev->ad_priv; + FAR struct spi_dev_s *spi = priv->spi; + int i; + uint16_t command; + uint16_t data; + int32_t dataToPost; + int ret = OK; + + if(cmd == ANIOC_TRIGGER) + { + while (sem_wait(&priv->sem) != OK); + + adc_lock(spi); + + for (i = 0; i <= priv->channel_config_count; i++) + { + SPI_SELECT(spi, priv->devno, true); + + if (i < priv->channel_config_count) + { + command = priv->channel_config[i].analog_multiplexer_config | + priv->channel_config[i].analog_inputMode; + command = command << 8; + } + else + { + command = 0; + } + + data = SPI_SEND(spi, command); + up_udelay(2); + SPI_SELECT(spi, priv->devno, false); + up_udelay(4); + + if (i > 0) + { + if (priv->channel_config[i-1].analog_inputMode == LTC1867L_UNIPOLAR || + (priv->channel_config[i-1].analog_inputMode == LTC1867L_BIPOLAR && + data >= 0 && data <= 0x7fff)) + { + dataToPost = data; + } + else + { + dataToPost = -(0xffff - data) - 1; + } + + priv->cb->au_receive(dev, priv->channel_config[i-1].channel, dataToPost); + } + } + + adc_unlock(spi); + sem_post(&priv->sem); + } + else + { + aerr("ERROR: Unrecognized cmd: %d\n", cmd); + ret = -ENOTTY; + } + + return ret; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: ltc1867l_register + * + * Description: + * Register the LTC1867L character device as 'devpath' + * + * Input Parameters: + * devpath - The full path to the driver to register. E.g., "/dev/adc0" + * spi - An instance of the SPI interface to use to communicate with + * LTC1867L + * devno - SPI device number + * channel_config - A pointer to an array which holds the configuration + * for each sampled channel. + * channel_config_count - Number of channels to sample + * + * Returned Value: + * Zero (OK) on success; a negated errno value on failure. + * + ****************************************************************************/ + +int ltc1867l_register(FAR const char *devpath, FAR struct spi_dev_s *spi, + unsigned int devno, + FAR struct ltc1867l_channel_config_s* channel_config, + int channel_config_count) +{ + FAR struct ltc1867l_dev_s *adcpriv; + FAR struct adc_dev_s *adcdev; + int ret; + + /* Sanity check */ + + DEBUGASSERT(spi != NULL); + DEBUGASSERT(channel_config != NULL); + + /* Initialize the LTC1867L device structure */ + + adcpriv = (FAR struct ltc1867l_dev_s *)kmm_malloc(sizeof(struct ltc1867l_dev_s)); + if (adcpriv == NULL) + { + aerr("ERROR: Failed to allocate ltc1867l_dev_s instance\n"); + return -ENOMEM; + } + + adcpriv->spi = spi; + adcpriv->devno = devno; + adcpriv->channel_config = channel_config; + adcpriv->channel_config_count = channel_config_count; + + ret = sem_init(&adcpriv->sem, 1, 1); + if(ret == -1) + { + kmm_free(adcpriv); + return -errno; + } + + adcdev = (FAR struct adc_dev_s *)kmm_malloc(sizeof(struct adc_dev_s)); + if (adcdev == NULL) + { + aerr("ERROR: Failed to allocate adc_dev_s instance\n"); + sem_destroy(&adcpriv->sem); + kmm_free(adcpriv); + return -ENOMEM; + } + + memset(adcdev, 0, sizeof(struct adc_dev_s)); + adcdev->ad_ops = &g_adcops; + adcdev->ad_priv = adcpriv; + + /* Register the character driver */ + + ret = adc_register(devpath, adcdev); + if (ret < 0) + { + aerr("ERROR: Failed to register adc driver: %d\n", ret); + kmm_free(adcdev); + sem_destroy(&adcpriv->sem); + kmm_free(adcpriv); + } + + return ret; +} +#endif diff --git a/include/nuttx/analog/ltc1867l.h b/include/nuttx/analog/ltc1867l.h new file mode 100644 index 0000000000..447ba494b1 --- /dev/null +++ b/include/nuttx/analog/ltc1867l.h @@ -0,0 +1,137 @@ +/**************************************************************************** + * include/nuttx/sensors/ltc1867l.h + * + * Copyright (C) 2017 DS-Automotion GmbH. All rights reserved. + * Author: Martin Lederhilger + * + * 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_ANALOG_LTC1867L_H +#define __INCLUDE_NUTTX_ANALOG_LTC1867L_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +#if defined(CONFIG_ADC_LTC1867L) + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* LTC1867L Configuration *******************************************/ + +#define LTC1867L_CONFIG_BIT_SLP (1 << 1) +#define LTC1867L_CONFIG_BIT_UNI (1 << 2) +#define LTC1867L_CONFIG_BIT_COM (1 << 3) +#define LTC1867L_CONFIG_BIT_S0 (1 << 4) +#define LTC1867L_CONFIG_BIT_S1 (1 << 5) +#define LTC1867L_CONFIG_BIT_OS (1 << 6) +#define LTC1867L_CONFIG_BIT_SD (1 << 7) + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +enum ltc1867l_analog_multiplexer_config_e +{ + LTC1867L_P_CH0_M_CH1 = 0, + LTC1867L_P_CH2_M_CH3 = LTC1867L_CONFIG_BIT_S0, + LTC1867L_P_CH4_M_CH5 = LTC1867L_CONFIG_BIT_S1, + LTC1867L_P_CH6_M_CH7 = LTC1867L_CONFIG_BIT_S1 | LTC1867L_CONFIG_BIT_S0, + LTC1867L_P_CH1_M_CH0 = LTC1867L_CONFIG_BIT_OS, + LTC1867L_P_CH3_M_CH2 = LTC1867L_CONFIG_BIT_OS | LTC1867L_CONFIG_BIT_S0, + LTC1867L_P_CH5_M_CH4 = LTC1867L_CONFIG_BIT_OS | LTC1867L_CONFIG_BIT_S1, + LTC1867L_P_CH7_M_CH6 = LTC1867L_CONFIG_BIT_OS |LTC1867L_CONFIG_BIT_S1 | LTC1867L_CONFIG_BIT_S0, + LTC1867L_P_CH0_M_GND = LTC1867L_CONFIG_BIT_SD, + LTC1867L_P_CH2_M_GND = LTC1867L_CONFIG_BIT_SD | LTC1867L_CONFIG_BIT_S0, + LTC1867L_P_CH4_M_GND = LTC1867L_CONFIG_BIT_SD | LTC1867L_CONFIG_BIT_S1, + LTC1867L_P_CH6_M_GND = LTC1867L_CONFIG_BIT_SD | LTC1867L_CONFIG_BIT_S1 | LTC1867L_CONFIG_BIT_S0, + LTC1867L_P_CH1_M_GND = LTC1867L_CONFIG_BIT_SD | LTC1867L_CONFIG_BIT_OS, + LTC1867L_P_CH3_M_GND = LTC1867L_CONFIG_BIT_SD | LTC1867L_CONFIG_BIT_OS | LTC1867L_CONFIG_BIT_S0, + LTC1867L_P_CH5_M_GND = LTC1867L_CONFIG_BIT_SD | LTC1867L_CONFIG_BIT_OS | LTC1867L_CONFIG_BIT_S1, + LTC1867L_P_CH7_M_GND = LTC1867L_CONFIG_BIT_SD | LTC1867L_CONFIG_BIT_OS | LTC1867L_CONFIG_BIT_S1 | LTC1867L_CONFIG_BIT_S0, + LTC1867L_P_CH0_M_CH7COM = LTC1867L_CONFIG_BIT_SD | LTC1867L_CONFIG_BIT_COM, + LTC1867L_P_CH2_M_CH7COM = LTC1867L_CONFIG_BIT_SD | LTC1867L_CONFIG_BIT_S0 | LTC1867L_CONFIG_BIT_COM, + LTC1867L_P_CH4_M_CH7COM = LTC1867L_CONFIG_BIT_SD | LTC1867L_CONFIG_BIT_S1 | LTC1867L_CONFIG_BIT_COM, + LTC1867L_P_CH6_M_CH7COM = LTC1867L_CONFIG_BIT_SD | LTC1867L_CONFIG_BIT_S1 | LTC1867L_CONFIG_BIT_S0 | LTC1867L_CONFIG_BIT_COM, + LTC1867L_P_CH1_M_CH7COM = LTC1867L_CONFIG_BIT_SD | LTC1867L_CONFIG_BIT_OS | LTC1867L_CONFIG_BIT_COM, + LTC1867L_P_CH3_M_CH7COM = LTC1867L_CONFIG_BIT_SD | LTC1867L_CONFIG_BIT_OS | LTC1867L_CONFIG_BIT_S0 | LTC1867L_CONFIG_BIT_COM, + LTC1867L_P_CH5_M_CH7COM = LTC1867L_CONFIG_BIT_SD | LTC1867L_CONFIG_BIT_OS | LTC1867L_CONFIG_BIT_S1 | LTC1867L_CONFIG_BIT_COM +}; + +enum ltc1867l_analog_input_mode_e +{ + LTC1867L_UNIPOLAR = LTC1867L_CONFIG_BIT_UNI, + LTC1867L_BIPOLAR = 0, +}; + +struct ltc1867l_channel_config_s +{ + uint8_t channel; /* This will be the channel number returned in struct adc_msg_s for a conversion */ + enum ltc1867l_analog_multiplexer_config_e analog_multiplexer_config; /* Analog multiplexer configuration */ + enum ltc1867l_analog_input_mode_e analog_inputMode; /* Analog input mode */ +} packed_struct; + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Name: ltc1867l_register + * + * Description: + * Register the LTC1867L character device as 'devpath' + * + * Input Parameters: + * devpath - The full path to the driver to register. E.g., "/dev/adc0" + * spi - An instance of the SPI interface to use to communicate with + * LTC1867L + * devno - SPI device number + * channel_config - A pointer to an array which holds the configuration + * for each sampled channel. + * channel_config_count - Number of channels to sample + * + * Returned Value: + * Zero (OK) on success; a negated errno value on failure. + * + ****************************************************************************/ + +int ltc1867l_register(FAR const char *devpath, FAR struct spi_dev_s *spi, + unsigned int devno, + FAR struct ltc1867l_channel_config_s* channel_config, + int channel_config_count); + +#endif /* CONFIG_ADC_LTC1867L */ +#endif /* __INCLUDE_NUTTX_ANALOG_LTC1867L_H */ -- GitLab From 0064dc52e549f68841e1e89ac272fcf518070ca0 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 28 Mar 2017 07:23:46 -0600 Subject: [PATCH 238/990] realloc(): When realloc() has to fall back to calling malloc(), size including overhead was being provided to malloc(), causing a slightly larger allocation than needed. Noted by initialkjc@yahoo.com --- mm/mm_heap/mm_realloc.c | 17 +++++++++-------- 1 file changed, 9 insertions(+), 8 deletions(-) diff --git a/mm/mm_heap/mm_realloc.c b/mm/mm_heap/mm_realloc.c index bf28ff62df..bf0effa54d 100644 --- a/mm/mm_heap/mm_realloc.c +++ b/mm/mm_heap/mm_realloc.c @@ -1,7 +1,7 @@ /**************************************************************************** * mm/mm_heap/mm_realloc.c * - * Copyright (C) 2007, 2009, 2013-2014 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2009, 2013-2014, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -79,6 +79,7 @@ FAR void *mm_realloc(FAR struct mm_heap_s *heap, FAR void *oldmem, FAR struct mm_allocnode_s *oldnode; FAR struct mm_freenode_s *prev; FAR struct mm_freenode_s *next; + size_t newsize; size_t oldsize; size_t prevsize = 0; size_t nextsize = 0; @@ -86,7 +87,7 @@ FAR void *mm_realloc(FAR struct mm_heap_s *heap, FAR void *oldmem, /* If oldmem is NULL, then realloc is equivalent to malloc */ - if (!oldmem) + if (oldmem == NULL) { return mm_malloc(heap, size); } @@ -103,7 +104,7 @@ FAR void *mm_realloc(FAR struct mm_heap_s *heap, FAR void *oldmem, * (2) to make sure that it is an even multiple of our granule size. */ - size = MM_ALIGN_UP(size + SIZEOF_MM_ALLOCNODE); + newsize = MM_ALIGN_UP(size + SIZEOF_MM_ALLOCNODE); /* Map the memory chunk into an allocated node structure */ @@ -116,15 +117,15 @@ FAR void *mm_realloc(FAR struct mm_heap_s *heap, FAR void *oldmem, /* Check if this is a request to reduce the size of the allocation. */ oldsize = oldnode->size; - if (size <= oldsize) + if (newsize <= oldsize) { /* Handle the special case where we are not going to change the size * of the allocation. */ - if (size < oldsize) + if (newsize < oldsize) { - mm_shrinkchunk(heap, oldnode, size); + mm_shrinkchunk(heap, oldnode, newsize); } /* Then return the original address */ @@ -152,9 +153,9 @@ FAR void *mm_realloc(FAR struct mm_heap_s *heap, FAR void *oldmem, /* Now, check if we can extend the current allocation or not */ - if (nextsize + prevsize + oldsize >= size) + if (nextsize + prevsize + oldsize >= newsize) { - size_t needed = size - oldsize; + size_t needed = newsize - oldsize; size_t takeprev = 0; size_t takenext = 0; -- GitLab From 9221e15811d2fd7f2403432b1517fc63b5778e1d Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Tue, 28 Mar 2017 07:28:55 -0600 Subject: [PATCH 239/990] STM32 L4: Fix some bad naming in the SPI driver. --- configs/nucleo-l476rg/src/stm32_spi.c | 28 +++++++++++++-------------- 1 file changed, 14 insertions(+), 14 deletions(-) diff --git a/configs/nucleo-l476rg/src/stm32_spi.c b/configs/nucleo-l476rg/src/stm32_spi.c index a400cd5267..d4ca68db1b 100644 --- a/configs/nucleo-l476rg/src/stm32_spi.c +++ b/configs/nucleo-l476rg/src/stm32_spi.c @@ -53,17 +53,17 @@ #include "nucleo-l476rg.h" -#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || defined(CONFIG_STM32_SPI3) +#if defined(CONFIG_STM32L4_SPI1) || defined(CONFIG_STM32L4_SPI2) || defined(CONFIG_STM32L4_SPI3) /************************************************************************************ * Public Data ************************************************************************************/ /* Global driver instances */ -#ifdef CONFIG_STM32_SPI1 +#ifdef CONFIG_STM32L4_SPI1 struct spi_dev_s *g_spi1; #endif -#ifdef CONFIG_STM32_SPI2 +#ifdef CONFIG_STM32L4_SPI2 struct spi_dev_s *g_spi2; #endif @@ -82,10 +82,10 @@ struct spi_dev_s *g_spi2; void weak_function stm32_spiinitialize(void) { -#ifdef CONFIG_STM32_SPI1 +#ifdef CONFIG_STM32L4_SPI1 /* Configure SPI-based devices */ - g_spi1 = up_spiinitialize(1); + g_spi1 = stm32l4_spibus_initialize(1); if (!g_spi1) { spierr("ERROR: FAILED to initialize SPI port 1\n"); @@ -100,10 +100,10 @@ void weak_function stm32_spiinitialize(void) #endif #endif -#ifdef CONFIG_STM32_SPI2 +#ifdef CONFIG_STM32L4_SPI2 /* Configure SPI-based devices */ - g_spi2 = up_spiinitialize(2); + g_spi2 = stm32l4_spibus_initialize(2); /* Setup CS, EN & IRQ line IOs */ @@ -140,7 +140,7 @@ void weak_function stm32_spiinitialize(void) * ****************************************************************************/ -#ifdef CONFIG_STM32_SPI1 +#ifdef CONFIG_STM32L4_SPI1 void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); @@ -166,7 +166,7 @@ uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) } #endif -#ifdef CONFIG_STM32_SPI2 +#ifdef CONFIG_STM32L4_SPI2 void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); @@ -185,7 +185,7 @@ uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) } #endif -#ifdef CONFIG_STM32_SPI3 +#ifdef CONFIG_STM32L4_SPI3 void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); @@ -221,21 +221,21 @@ uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) ****************************************************************************/ #ifdef CONFIG_SPI_CMDDATA -#ifdef CONFIG_STM32_SPI1 +#ifdef CONFIG_STM32L4_SPI1 int stm32_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) { return OK; } #endif -#ifdef CONFIG_STM32_SPI2 +#ifdef CONFIG_STM32L4_SPI2 int stm32_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) { return OK; } #endif -#ifdef CONFIG_STM32_SPI3 +#ifdef CONFIG_STM32L4_SPI3 int stm32_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) { return OK; @@ -243,4 +243,4 @@ int stm32_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) #endif #endif /* CONFIG_SPI_CMDDATA */ -#endif /* CONFIG_STM32_SPI1 || CONFIG_STM32_SPI2 || CONFIG_STM32_SPI3 */ +#endif /* CONFIG_STM32L4_SPI1 || CONFIG_STM32L4_SPI2 || CONFIG_STM32L4_SPI3 */ -- GitLab From 45a0af8c03a758622fce62856a1b1d654cf9baef Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Tue, 28 Mar 2017 08:52:49 -0600 Subject: [PATCH 240/990] STM32 L4: More SPI clean-up. Lower case replacements. --- include/nuttx/net/6lowpan.h | 62 ------------------------------------- 1 file changed, 62 deletions(-) delete mode 100644 include/nuttx/net/6lowpan.h diff --git a/include/nuttx/net/6lowpan.h b/include/nuttx/net/6lowpan.h deleted file mode 100644 index cbd7e071bf..0000000000 --- a/include/nuttx/net/6lowpan.h +++ /dev/null @@ -1,62 +0,0 @@ -/**************************************************************************** - * include/nuttx/net/6lowpan.h - * - * Copyright (C) 2016 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Includes some definitions that a compatible with the LGPL GNU C Library - * header file of the same name. - * - * 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_NET_6LOWPAN_H -#define __INCLUDE_NUTTX_NET_6LOWPAN_H - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include - -/**************************************************************************** - * Public Type Definitions - ****************************************************************************/ - -/**************************************************************************** - * Public Data - ****************************************************************************/ - -/**************************************************************************** - * Public Function Prototypes - ****************************************************************************/ - -#endif /* __INCLUDE_NUTTX_NET_6LOWPAN_H */ -- GitLab From db8b38f848cca049b96f7bd37f3d72dbbbf4524d Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Tue, 28 Mar 2017 08:58:43 -0600 Subject: [PATCH 241/990] STM32 L4: More SPI clean-up. Lower case replacements. --- configs/nucleo-l476rg/src/stm32_spi.c | 50 +++++++++++++-------------- 1 file changed, 25 insertions(+), 25 deletions(-) diff --git a/configs/nucleo-l476rg/src/stm32_spi.c b/configs/nucleo-l476rg/src/stm32_spi.c index d4ca68db1b..71d65d8a10 100644 --- a/configs/nucleo-l476rg/src/stm32_spi.c +++ b/configs/nucleo-l476rg/src/stm32_spi.c @@ -1,5 +1,5 @@ /**************************************************************************** - * configs/nucleo-l476rg/src/stm32_spi.c + * configs/nucleo-l476rg/src/stm32l4_spi.c * * Copyright (C) 2014 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -72,7 +72,7 @@ struct spi_dev_s *g_spi2; ************************************************************************************/ /************************************************************************************ - * Name: stm32_spiinitialize + * Name: stm32l4_spiinitialize * * Description: * Called to configure SPI chip select GPIO pins for the Nucleo-F401RE and @@ -80,7 +80,7 @@ struct spi_dev_s *g_spi2; * ************************************************************************************/ -void weak_function stm32_spiinitialize(void) +void weak_function stm32l4_spiinitialize(void) { #ifdef CONFIG_STM32L4_SPI1 /* Configure SPI-based devices */ @@ -92,11 +92,11 @@ void weak_function stm32_spiinitialize(void) } #ifdef CONFIG_WL_CC3000 - stm32_configgpio(GPIO_SPI_CS_WIFI); + stm32l4_configgpio(GPIO_SPI_CS_WIFI); #endif #ifdef HAVE_MMCSD - stm32_configgpio(GPIO_SPI_CS_SD_CARD); + stm32l4_configgpio(GPIO_SPI_CS_SD_CARD); #endif #endif @@ -108,27 +108,27 @@ void weak_function stm32_spiinitialize(void) /* Setup CS, EN & IRQ line IOs */ #ifdef CONFIG_WL_CC3000 - stm32_configgpio(GPIO_WIFI_CS); - stm32_configgpio(GPIO_WIFI_EN); - stm32_configgpio(GPIO_WIFI_INT); + stm32l4_configgpio(GPIO_WIFI_CS); + stm32l4_configgpio(GPIO_WIFI_EN); + stm32l4_configgpio(GPIO_WIFI_INT); #endif #endif } /**************************************************************************** - * Name: stm32_spi1/2/3select and stm32_spi1/2/3status + * Name: stm32l4_spi1/2/3select and stm32l4_spi1/2/3status * * Description: - * The external functions, stm32_spi1/2/3select and stm32_spi1/2/3status must be + * The external functions, stm32l4_spi1/2/3select and stm32l4_spi1/2/3status must be * provided by board-specific logic. They are implementations of the select * and status methods of the SPI interface defined by struct spi_ops_s (see * include/nuttx/spi/spi.h). All other methods (including up_spiinitialize()) * are provided by common STM32 logic. To use this common SPI logic on your * board: * - * 1. Provide logic in stm32_boardinitialize() to configure SPI chip select + * 1. Provide logic in stm32l4_boardinitialize() to configure SPI chip select * pins. - * 2. Provide stm32_spi1/2/3select() and stm32_spi1/2/3status() functions in your + * 2. Provide stm32l4_spi1/2/3select() and stm32l4_spi1/2/3status() functions in your * board-specific logic. These functions will perform chip selection and * status operations using GPIOs in the way your board is configured. * 3. Add a calls to up_spiinitialize() in your low level application @@ -141,64 +141,64 @@ void weak_function stm32_spiinitialize(void) ****************************************************************************/ #ifdef CONFIG_STM32L4_SPI1 -void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32l4_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #ifdef CONFIG_WL_CC3000 if (devid == SPIDEV_WIRELESS) { - stm32_gpiowrite(GPIO_SPI_CS_WIFI, !selected); + stm32l4_gpiowrite(GPIO_SPI_CS_WIFI, !selected); } else #endif #ifdef HAVE_MMCSD if (devid == SPIDEV_MMCSD) { - stm32_gpiowrite(GPIO_SPI_CS_SD_CARD, !selected); + stm32l4_gpiowrite(GPIO_SPI_CS_SD_CARD, !selected); } #endif } -uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32l4_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) { return 0; } #endif #ifdef CONFIG_STM32L4_SPI2 -void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32l4_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #ifdef CONFIG_WL_CC3000 if (devid == SPIDEV_WIRELESS) { - stm32_gpiowrite(GPIO_WIFI_CS, !selected); + stm32l4_gpiowrite(GPIO_WIFI_CS, !selected); } #endif } -uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32l4_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) { return 0; } #endif #ifdef CONFIG_STM32L4_SPI3 -void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32l4_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32l4_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) { return 0; } #endif /**************************************************************************** - * Name: stm32_spi1cmddata + * Name: stm32l4_spi1cmddata * * Description: * Set or clear the SH1101A A0 or SD1306 D/C n bit to select data (true) @@ -222,21 +222,21 @@ uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #ifdef CONFIG_SPI_CMDDATA #ifdef CONFIG_STM32L4_SPI1 -int stm32_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32l4_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) { return OK; } #endif #ifdef CONFIG_STM32L4_SPI2 -int stm32_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32l4_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) { return OK; } #endif #ifdef CONFIG_STM32L4_SPI3 -int stm32_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32l4_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) { return OK; } -- GitLab From 913daa908a3b76fab05537d3d2cbde6ecfa44662 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 28 Mar 2017 09:00:25 -0600 Subject: [PATCH 242/990] 6loWPAN: Add some more configuration settings that will be needed. --- include/nuttx/net/sixlowpan.h | 6 ----- net/sixlowpan/Kconfig | 36 ++++++++++++++++++++++++++++ net/sixlowpan/sixlowpan_compressor.c | 2 +- net/sixlowpan/sixlowpan_sniffer.c | 2 +- 4 files changed, 38 insertions(+), 8 deletions(-) diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index 4b956db8aa..5c94bb02b9 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -63,12 +63,6 @@ #define SIXLOWPAN_UDP_8_BIT_PORT_MIN 0xF000 #define SIXLOWPAN_UDP_8_BIT_PORT_MAX 0xf0ff /* F000 + 255 */ -/* 6lowpan compressions */ - -#define SIXLOWPAN_COMPRESSION_IPV6 0 -#define SIXLOWPAN_COMPRESSION_HC1 1 -#define SIXLOWPAN_COMPRESSION_HC06 2 - /* 6lowpan dispatches */ #define SIXLOWPAN_DISPATCH_IPV6 0x41 /* 01000001 = 65 */ diff --git a/net/sixlowpan/Kconfig b/net/sixlowpan/Kconfig index e72e42268b..cf29ed9abf 100644 --- a/net/sixlowpan/Kconfig +++ b/net/sixlowpan/Kconfig @@ -13,6 +13,42 @@ menuconfig NET_6LOWPAN if NET_6LOWPAN +config NET_6LOWPAN_FRAG + bool "6loWPAN Fragmentation" + default y + ---help--- + CONFIG_NET_6LOWPAN_FRAG specifies if 6lowpan fragmentation should be + used or not. Fragmentation is on by default. + +choice + prompt "6loWPAN Compression" + default NET_6LOWPAN_COMPRESSION_HC06 + +config NET_6LOWPAN_COMPRESSION_IPv6 + bool "IPv6 Dispatch" + ---help--- + Packets compression when only IPv6 dispatch is used. There is no + compression in this case, all fields are sent inline. We just add + the IPv6 dispatch byte before the packet. + +config NET_6LOWPAN_COMPRESSION_HC1 + bool "6loWPAN HC1" + ---help--- + Compress IP/UDP header using HC1 and HC_UDP + +config NET_6LOWPAN_COMPRESSION_HC06 + bool "6loWPAN HC06" + ---help--- + Compress IP/UDP header using HC06 compression + +endchoice # 6loWPAN Compression + +config NET_6LOWPAN_MAXADDRCONTEXT + int "Maximum address contexts" + default 1 + ---help--- + If we use IPHC compression, how many address contexts do we support? + config NET_6LOWPAN_MTU int "6LoWPAN packet buffer size (MTU)" default 1294 diff --git a/net/sixlowpan/sixlowpan_compressor.c b/net/sixlowpan/sixlowpan_compressor.c index 0f78113802..ffaa64ae2e 100644 --- a/net/sixlowpan/sixlowpan_compressor.c +++ b/net/sixlowpan/sixlowpan_compressor.c @@ -42,7 +42,7 @@ #include "nuttx/net/net.h" #include "nuttx/net/sixlowpan.h" -#include "sixlowpan/sixlopan.h" +#include "sixlowpan/sixlowpan.h" #ifdef CONFIG_NET_6LOWPAN diff --git a/net/sixlowpan/sixlowpan_sniffer.c b/net/sixlowpan/sixlowpan_sniffer.c index 9f00efe62a..d9ffadc973 100644 --- a/net/sixlowpan/sixlowpan_sniffer.c +++ b/net/sixlowpan/sixlowpan_sniffer.c @@ -42,7 +42,7 @@ #include "nuttx/net/net.h" #include "nuttx/net/sixlowpan.h" -#include "sixlowpan/sixlopan.h" +#include "sixlowpan/sixlowpan.h" #ifdef CONFIG_NET_6LOWPAN -- GitLab From 1879f5127b7cd33ce0d5b89ce293f08d1b06bb7c Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Tue, 28 Mar 2017 09:07:32 -0600 Subject: [PATCH 243/990] Fix PTHREAD_MUTEX_INITIALIZER which was not updated with last mutex changes. --- include/pthread.h | 22 +++++++++++++++++++--- 1 file changed, 19 insertions(+), 3 deletions(-) diff --git a/include/pthread.h b/include/pthread.h index edf943c9bb..af6ef51e23 100644 --- a/include/pthread.h +++ b/include/pthread.h @@ -295,10 +295,26 @@ struct pthread_mutex_s typedef struct pthread_mutex_s pthread_mutex_t; #define __PTHREAD_MUTEX_T_DEFINED 1 -#ifdef CONFIG_PTHREAD_MUTEX_TYPES -# define PTHREAD_MUTEX_INITIALIZER {-1, SEM_INITIALIZER(1), PTHREAD_MUTEX_DEFAULT, 0} +#ifndef CONFIG_PTHREAD_MUTEX_UNSAFE +# ifdef CONFIG_PTHREAD_MUTEX_DEFAULT_UNSAFE +# define __PTHREAD_MUTEX_DEFAULT_FLAGS 0 +# else +# define __PTHREAD_MUTEX_DEFAULT_FLAGS _PTHREAD_MFLAGS_ROBUST +# endif +#endif + +#if defined(CONFIG_PTHREAD_MUTEX_TYPES) && !defined(CONFIG_PTHREAD_MUTEX_UNSAFE) +# define PTHREAD_MUTEX_INITIALIZER {NULL, SEM_INITIALIZER(1), -1, \ + __PTHREAD_MUTEX_DEFAULT_FLAGS, \ + PTHREAD_MUTEX_DEFAULT, 0} +#elif defined(CONFIG_PTHREAD_MUTEX_TYPES) +# define PTHREAD_MUTEX_INITIALIZER {SEM_INITIALIZER(1), -1, \ + PTHREAD_MUTEX_DEFAULT, 0} +#elif !defined(CONFIG_PTHREAD_MUTEX_UNSAFE) +# define PTHREAD_MUTEX_INITIALIZER {NULL, SEM_INITIALIZER(1), -1,\ + __PTHREAD_MUTEX_DEFAULT_FLAGS} #else -# define PTHREAD_MUTEX_INITIALIZER {-1, SEM_INITIALIZER(1)} +# define PTHREAD_MUTEX_INITIALIZER {SEM_INITIALIZER(1), -1} #endif struct pthread_barrierattr_s -- GitLab From 898b7699100b83141d13e29155fbb2bc62aea2f9 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 28 Mar 2017 09:32:52 -0600 Subject: [PATCH 244/990] 6loWPAN: Add framework for initialization; move globals into a separate file. --- net/net_initialize.c | 31 ++++-------- net/sixlowpan/Make.defs | 1 + net/sixlowpan/sixlowpan.h | 25 +++++++++- net/sixlowpan/sixlowpan_compressor.c | 8 --- net/sixlowpan/sixlowpan_globals.c | 60 ++++++++++++++++++++++ net/sixlowpan/sixlowpan_initialize.c | 74 ++++++++++++++++++++++++++++ net/sixlowpan/sixlowpan_sniffer.c | 8 --- 7 files changed, 168 insertions(+), 39 deletions(-) create mode 100644 net/sixlowpan/sixlowpan_globals.c create mode 100644 net/sixlowpan/sixlowpan_initialize.c diff --git a/net/net_initialize.c b/net/net_initialize.c index df3a72226d..988faf6b54 100644 --- a/net/net_initialize.c +++ b/net/net_initialize.c @@ -1,7 +1,7 @@ /**************************************************************************** - * net/net_sockets.c + * net/net_initialize.c * - * Copyright (C) 2007-2009, 2011-2015 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009, 2011-2015, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -49,6 +49,7 @@ #include "devif/devif.h" #include "netdev/netdev.h" #include "arp/arp.h" +#include "sixlowpan/sixlowpan.h" #include "neighbor/neighbor.h" #include "tcp/tcp.h" #include "udp/udp.h" @@ -58,26 +59,6 @@ #include "route/route.h" #include "utils/utils.h" -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Public Types - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - /**************************************************************************** * Public Functions ****************************************************************************/ @@ -119,7 +100,13 @@ void net_setup(void) /* Initialize the Neighbor Table data structures */ neighbor_initialize(); + +#ifdef CONFIG_NET_6LOWPAN + /* Initialize 6loWPAN data structures */ + + sixlowpan_initialize(); #endif +#endif /* CONFIG_NET_IPv6 */ #ifdef CONFIG_NET_IOB /* Initialize I/O buffering */ diff --git a/net/sixlowpan/Make.defs b/net/sixlowpan/Make.defs index 150cb6ec88..ffe1351f94 100644 --- a/net/sixlowpan/Make.defs +++ b/net/sixlowpan/Make.defs @@ -39,6 +39,7 @@ ifeq ($(CONFIG_NET_6LOWPAN),y) # Include IEEE 802.15.4 file in the build +NET_CSRCS += sixlowpan_initialize.c sixlowpan_globals.c NET_CSRCS += sixlowpan_compressor.c sixlowpan_sniffer.c # Include the sixlowpan directory in the build diff --git a/net/sixlowpan/sixlowpan.h b/net/sixlowpan/sixlowpan.h index e85135e0cf..37d8bb597c 100644 --- a/net/sixlowpan/sixlowpan.h +++ b/net/sixlowpan/sixlowpan.h @@ -41,6 +41,7 @@ ****************************************************************************/ #include +#include #ifdef CONFIG_NET_6LOWPAN @@ -55,7 +56,8 @@ extern FAR struct sixlowpan_nhcompressor_s *g_sixlowpan_compressor; /* Rime Sniffer support for one single listener to enable trace of IP */ -extern struct sixlowpan_rime_sniffer_s *g_sixlopan_sniffer; +struct sixlowpan_rime_sniffer_s; /* Foward reference */ +extern FAR struct sixlowpan_rime_sniffer_s *g_sixlowpan_sniffer; /**************************************************************************** * Public Types @@ -65,5 +67,26 @@ extern struct sixlowpan_rime_sniffer_s *g_sixlopan_sniffer; * Public Function Prototypes ****************************************************************************/ +/**************************************************************************** + * Name: sixlowpan_initialize + * + * Description: + * sixlowpan_initialize() is called during OS initialization at power-up + * reset. It is called from the common net_setup() function. + * sixlowpan_initialize() configures 6loWPAN networking data structures. + * It is called prior to platform-specific driver initialization so that + * the 6loWPAN networking subsystem is prepared to deal with network + * driver initialization actions. + * + * Input Parameters: + * None + * + * Returned Value: + * None + * + ****************************************************************************/ + +void sixlowpan_initialize(void); + #endif /* CONFIG_NET_6LOWPAN */ #endif /* _NET_SIXLOWPAN_SIXLOWPAN_H */ diff --git a/net/sixlowpan/sixlowpan_compressor.c b/net/sixlowpan/sixlowpan_compressor.c index ffaa64ae2e..3457530b79 100644 --- a/net/sixlowpan/sixlowpan_compressor.c +++ b/net/sixlowpan/sixlowpan_compressor.c @@ -46,14 +46,6 @@ #ifdef CONFIG_NET_6LOWPAN -/**************************************************************************** - * Public Data - ****************************************************************************/ - -/* A pointer to the optional, architecture-specific compressor */ - -FAR struct sixlowpan_nhcompressor_s *g_sixlowpan_compressor; - /**************************************************************************** * Public Functions ****************************************************************************/ diff --git a/net/sixlowpan/sixlowpan_globals.c b/net/sixlowpan/sixlowpan_globals.c new file mode 100644 index 0000000000..e289d88c0c --- /dev/null +++ b/net/sixlowpan/sixlowpan_globals.c @@ -0,0 +1,60 @@ +/**************************************************************************** + * net/sixlowpan/sixlowpan_sniffer.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include "nuttx/net/sixlowpan.h" + +#include "sixlowpan/sixlowpan.h" + +#ifdef CONFIG_NET_6LOWPAN + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/* A pointer to the optional, architecture-specific compressor */ + +FAR struct sixlowpan_nhcompressor_s *g_sixlowpan_compressor; + +/* A pointer to the optional, architecture-specific sniffer */ + +FAR struct sixlowpan_rime_sniffer_s *g_sixlowpan_sniffer; + +#endif /* CONFIG_NET_6LOWPAN */ diff --git a/net/sixlowpan/sixlowpan_initialize.c b/net/sixlowpan/sixlowpan_initialize.c new file mode 100644 index 0000000000..53180f0a90 --- /dev/null +++ b/net/sixlowpan/sixlowpan_initialize.c @@ -0,0 +1,74 @@ +/**************************************************************************** + * net/net_sockets.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include "sixlowpan/sixlowpan.h" + +#ifdef CONFIG_NET_6LOWPAN + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: sixlowpan_initialize + * + * Description: + * sixlowpan_initialize() is called during OS initialization at power-up + * reset. It is called from the common net_setup() function. + * sixlowpan_initialize() configures 6loWPAN networking data structures. + * It is called prior to platform-specific driver initialization so that + * the 6loWPAN networking subsystem is prepared to deal with network + * driver initialization actions. + * + * Input Parameters: + * None + * + * Returned Value: + * None + * + ****************************************************************************/ + +void sixlowpan_initialize(void) +{ + /* REVIST: To be provided */ +} + +#endif /* CONFIG_NET_6LOWPAN */ diff --git a/net/sixlowpan/sixlowpan_sniffer.c b/net/sixlowpan/sixlowpan_sniffer.c index d9ffadc973..baf3acc09c 100644 --- a/net/sixlowpan/sixlowpan_sniffer.c +++ b/net/sixlowpan/sixlowpan_sniffer.c @@ -46,14 +46,6 @@ #ifdef CONFIG_NET_6LOWPAN -/**************************************************************************** - * Public Data - ****************************************************************************/ - -/* A pointer to the optional, architecture-specific sniffer */ - -FAR struct sixlowpan_rime_sniffer_s *g_sixlowpan_sniffer; - /**************************************************************************** * Public Functions ****************************************************************************/ -- GitLab From f32fe172d42f954cac67b389873bf3e3a22908b2 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 28 Mar 2017 10:47:25 -0600 Subject: [PATCH 245/990] 6loWPAN: Add HC06 initialization --- include/nuttx/net/sixlowpan.h | 16 +-- net/sixlowpan/Kconfig | 70 +++++++++++ net/sixlowpan/Make.defs | 4 + net/sixlowpan/sixlowpan.h | 23 ++++ net/sixlowpan/sixlowpan_hc06.c | 169 +++++++++++++++++++++++++++ net/sixlowpan/sixlowpan_initialize.c | 8 +- 6 files changed, 274 insertions(+), 16 deletions(-) create mode 100644 net/sixlowpan/sixlowpan_hc06.c diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index 5c94bb02b9..8901b453d1 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -247,7 +247,7 @@ struct sixlowpan_frag_hdr * sixlowpan_hc1_hc_udp structure */ -struct sixlowpan_hc1_hdr +struct sixlowpan_hc1hdr_s { uint8_t dispatch; uint8_t encoding; @@ -256,7 +256,7 @@ struct sixlowpan_hc1_hdr /* HC1 followed by HC_UDP */ -struct sixlowpan_hc1_hc_udp_hdr +struct sixlowpan_hc1_hcudp_hdr_s { uint8_t dispatch; uint8_t hc1_encoding; @@ -266,18 +266,6 @@ struct sixlowpan_hc1_hc_udp_hdr uint16_t udpchksum; }; -/* An address context for IPHC address compression each context can have up - * to 8 bytes - */ - -struct sixlowpan_addr_context -{ - uint8_t used; /* Possibly use as prefix-length */ - uint8_t number; - uint8_t prefix[8]; -}; - - /* The structure of a next header compressor. This compressor is provided * by architecture-specific logic outside of the network stack. * diff --git a/net/sixlowpan/Kconfig b/net/sixlowpan/Kconfig index cf29ed9abf..b89d1345d9 100644 --- a/net/sixlowpan/Kconfig +++ b/net/sixlowpan/Kconfig @@ -43,12 +43,82 @@ config NET_6LOWPAN_COMPRESSION_HC06 endchoice # 6loWPAN Compression +if NET_6LOWPAN_COMPRESSION_HC06 + config NET_6LOWPAN_MAXADDRCONTEXT int "Maximum address contexts" default 1 ---help--- If we use IPHC compression, how many address contexts do we support? +config NET_6LOWPAN_MAXADDRCONTEXT_PREFIX_0_0 + hex "Address context 0 Prefix 0" + default 0xaa + ---help--- + Prefix 0 for address context ze0ro (assumes CONFIG_NET_6LOWPAN_MAXADDRCONTEXT >= 0) + +config NET_6LOWPAN_MAXADDRCONTEXT_PREFIX_0_1 + hex "Address context 0 Prefix 1" + default 0xaa + ---help--- + Prefix 1 for address context 0 (assumes CONFIG_NET_6LOWPAN_MAXADDRCONTEXT >= 0) + +config NET_6LOWPAN_MAXADDRCONTEXT_PREINIT_1 + bool "Pre-initialize address context 1" + default n + ---help--- + Preinitialize address context 1 for better header compression + (Saves up to 13 bytes per 6lowpan packet). Assumes + CONFIG_NET_6LOWPAN_MAXADDRCONTEXT >= 1) + +if NET_6LOWPAN_MAXADDRCONTEXT_PREINIT_1 + +config NET_6LOWPAN_MAXADDRCONTEXT_PREFIX_1_0 + hex "Address context 1 Prefix 0" + default 0xaa + ---help--- + Prefix 0 for address context 1 (assumes CONFIG_NET_6LOWPAN_MAXADDRCONTEXT >= 1) + +config NET_6LOWPAN_MAXADDRCONTEXT_PREFIX_1_1 + hex "Address context 1 Prefix 1" + default 0xaa + ---help--- + Prefix 1 for address context 1 (assumes CONFIG_NET_6LOWPAN_MAXADDRCONTEXT >= 1) + +endif # NET_6LOWPAN_MAXADDRCONTEXT_PREINIT_1 + +config NET_6LOWPAN_MAXADDRCONTEXT_PREINIT_2 + bool "Pre-initialize address context 2" + default n + depends on NET_6LOWPAN_MAXADDRCONTEXT_PREINIT_1 + ---help--- + Preinitialize any address contexts for better header compression + (Saves up to 13 bytes per 6lowpan packet). Assumes + CONFIG_NET_6LOWPAN_MAXADDRCONTEXT >= 2) + +if NET_6LOWPAN_MAXADDRCONTEXT_PREINIT_2 + +config NET_6LOWPAN_MAXADDRCONTEXT_PREFIX_2_0 + hex "Address context 2 Prefix 0" + default 0xaa + ---help--- + Prefix 0 for address context 2 (assumes CONFIG_NET_6LOWPAN_MAXADDRCONTEXT >= 2) + +config NET_6LOWPAN_MAXADDRCONTEXT_PREFIX_2_1 + hex "Address context 2 Prefix 1" + default 0xaa + ---help--- + Prefix 1 for address context 2 (assumes CONFIG_NET_6LOWPAN_MAXADDRCONTEXT >= 2) + +endif # NET_6LOWPAN_MAXADDRCONTEXT_PREINIT_0 +endif # NET_6LOWPAN_COMPRESSION_HC06 + +config NET_SIXLOWPAN_MAXAGE + int "Packet reassembly timeout" + default 20 + ---help--- + Timeout for packet reassembly at the 6lowpan layer (should be < 60s) + config NET_6LOWPAN_MTU int "6LoWPAN packet buffer size (MTU)" default 1294 diff --git a/net/sixlowpan/Make.defs b/net/sixlowpan/Make.defs index ffe1351f94..0ddebc0b20 100644 --- a/net/sixlowpan/Make.defs +++ b/net/sixlowpan/Make.defs @@ -42,6 +42,10 @@ ifeq ($(CONFIG_NET_6LOWPAN),y) NET_CSRCS += sixlowpan_initialize.c sixlowpan_globals.c NET_CSRCS += sixlowpan_compressor.c sixlowpan_sniffer.c +ifeq ($(CONFIG_NET_6LOWPAN_COMPRESSION_HC06),y) +NET_CSRCS += sixlowpan_hc06.c +endif + # Include the sixlowpan directory in the build DEPPATH += --dep-path sixlowpan diff --git a/net/sixlowpan/sixlowpan.h b/net/sixlowpan/sixlowpan.h index 37d8bb597c..31a858205d 100644 --- a/net/sixlowpan/sixlowpan.h +++ b/net/sixlowpan/sixlowpan.h @@ -88,5 +88,28 @@ extern FAR struct sixlowpan_rime_sniffer_s *g_sixlowpan_sniffer; void sixlowpan_initialize(void); +/**************************************************************************** + * Name: sixlowpan_hc06_initialize + * + * Description: + * sixlowpan_hc06_initialize() is called during OS initialization at power-up + * reset. It is called from the common sixlowpan_initialize() function. + * sixlowpan_hc06_initialize() configures HC06 networking data structures. + * It is called prior to platform-specific driver initialization so that + * the 6loWPAN networking subsystem is prepared to deal with network + * driver initialization actions. + * + * Input Parameters: + * None + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 +void sixlowpan_hc06_initialize(void); +#endif + #endif /* CONFIG_NET_6LOWPAN */ #endif /* _NET_SIXLOWPAN_SIXLOWPAN_H */ diff --git a/net/sixlowpan/sixlowpan_hc06.c b/net/sixlowpan/sixlowpan_hc06.c new file mode 100644 index 0000000000..f992676ef9 --- /dev/null +++ b/net/sixlowpan/sixlowpan_hc06.c @@ -0,0 +1,169 @@ +/**************************************************************************** + * net/sixlowpan/sixlowpan_hc06.c + * 6lowpan HC06 implementation (draft-ietf-6lowpan-hc-06) + * + * Copyright (C) 2017, Gregory Nutt, all rights reserved + * Author: Gregory Nutt + * + * Derives from Contiki: + * + * Copyright (c) 2008, Swedish Institute of Computer Science. + * All rights reserved. + * Authors: Adam Dunkels + * Nicolas Tsiftes + * Niclas Finne + * Mathilde Durvy + * Julien Abeille + * Joakim Eriksson + * Joel Hoglund + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the Institute 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 INSTITUTE 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 INSTITUTE 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. + * + ****************************************************************************/ + +/* FOR HC-06 COMPLIANCE TODO: + * + * -Add compression options to UDP, currently only supports + * both ports compressed or both ports elided + * -Verify TC/FL compression works + * -Add stateless multicast option + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include "sixlowpan/sixlowpan.h" + +#ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/* An address context for IPHC address compression each context can have up + * to 8 bytes + */ + +struct sixlowpan_addrcontext_s +{ + uint8_t used; /* Possibly use as prefix-length */ + uint8_t number; + uint8_t prefix[8]; +}; + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* HC06 specific variables */ + +#if CONFIG_NET_6LOWPAN_MAXADDRCONTEXT > 0 +/* Addresses contexts for IPHC. */ + +static struct sixlowpan_addrcontext_s + g_hc06_addrcontexts[CONFIG_NET_6LOWPAN_MAXADDRCONTEXT]; +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: sixlowpan_hc06_initialize + * + * Description: + * sixlowpan_hc06_initialize() is called during OS initialization at power-up + * reset. It is called from the common sixlowpan_initialize() function. + * sixlowpan_hc06_initialize() configures HC06 networking data structures. + * It is called prior to platform-specific driver initialization so that + * the 6loWPAN networking subsystem is prepared to deal with network + * driver initialization actions. + * + * Input Parameters: + * None + * + * Returned Value: + * None + * + ****************************************************************************/ + +void sixlowpan_hc06_initialize(void) +{ +#if CONFIG_NET_6LOWPAN_MAXADDRCONTEXT > 0 +#if CONFIG_NET_6LOWPAN_MAXADDRCONTEXT > 1 + int i; +#endif + + /* Preinitialize any address contexts for better header compression + * (Saves up to 13 bytes per 6lowpan packet). + */ + + g_hc06_addrcontexts[0].used = 1; + g_hc06_addrcontexts[0].number = 0; + + g_hc06_addrcontexts[0].prefix[0] = CONFIG_NET_6LOWPAN_MAXADDRCONTEXT_PREFIX_0_0; + g_hc06_addrcontexts[0].prefix[1] = CONFIG_NET_6LOWPAN_MAXADDRCONTEXT_PREFIX_0_1; + +#if CONFIG_NET_6LOWPAN_MAXADDRCONTEXT > 1 + for (i = 1; i < CONFIG_NET_6LOWPAN_MAXADDRCONTEXT; i++) + { +#ifdef CONFIG_NET_6LOWPAN_MAXADDRCONTEXT_PREINIT_1 + if (i == 1) + { + g_hc06_addrcontexts[1].used = 1; + g_hc06_addrcontexts[1].number = 1; + + g_hc06_addrcontexts[1].prefix[0] = CONFIG_NET_6LOWPAN_MAXADDRCONTEXT_PREFIX_1_0; + g_hc06_addrcontexts[1].prefix[1] = CONFIG_NET_6LOWPAN_MAXADDRCONTEXT_PREFIX_1_1; + } + else +#ifdef CONFIG_NET_6LOWPAN_MAXADDRCONTEXT_PREINIT_2 + if (i == 2) + { + g_hc06_addrcontexts[2].used = 1; + g_hc06_addrcontexts[2].number = 2; + + g_hc06_addrcontexts[2].prefix[0] = CONFIG_NET_6LOWPAN_MAXADDRCONTEXT_PREFIX_1_0; + g_hc06_addrcontexts[2].prefix[1] = CONFIG_NET_6LOWPAN_MAXADDRCONTEXT_PREFIX_1_1; + } + else +#endif /* SIXLOWPAN_CONF_ADDR_CONTEXT_2 */ + { + g_hc06_addrcontexts[i].used = 0; + } +#else + g_hc06_addrcontexts[i].used = 0; +#endif /* SIXLOWPAN_CONF_ADDR_CONTEXT_1 */ + } +#endif /* CONFIG_NET_6LOWPAN_MAXADDRCONTEXT > 1 */ +#endif /* CONFIG_NET_6LOWPAN_MAXADDRCONTEXT > 0 */ +} + +#endif /* CONFIG_NET_6LOWPAN_COMPRESSION_HC06 */ diff --git a/net/sixlowpan/sixlowpan_initialize.c b/net/sixlowpan/sixlowpan_initialize.c index 53180f0a90..ccf0cefed4 100644 --- a/net/sixlowpan/sixlowpan_initialize.c +++ b/net/sixlowpan/sixlowpan_initialize.c @@ -1,5 +1,5 @@ /**************************************************************************** - * net/net_sockets.c + * net/sixlowpan/sixlowpan_initialize.c * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -68,7 +68,11 @@ void sixlowpan_initialize(void) { - /* REVIST: To be provided */ +#ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 + /* Initialize HC06 data data structures */ + + sixlowpan_hc06_initialize(); +#endif } #endif /* CONFIG_NET_6LOWPAN */ -- GitLab From d9e32ee337d6b29baaace654cb5dd13a77f59015 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 28 Mar 2017 11:16:28 -0600 Subject: [PATCH 246/990] 6loWPAN: More configurtion settings. --- include/nuttx/net/sixlowpan.h | 4 ++++ net/netdev/netdev_register.c | 2 +- net/sixlowpan/Kconfig | 40 ++++++++++++++++++++++------------ net/sixlowpan/sixlowpan_hc06.c | 4 ++-- 4 files changed, 33 insertions(+), 17 deletions(-) diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index 8901b453d1..4887d255f0 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -223,6 +223,10 @@ (((a)->u16[6]) == 0) && \ (((a)->u8[14]) == 0)) +/* Maximum size of an IEEE802.15.4 frame */ + +#define SIXLOWPAN_MAC_MAXFRAME 127 + /**************************************************************************** * Public Types ****************************************************************************/ diff --git a/net/netdev/netdev_register.c b/net/netdev/netdev_register.c index dafc17dcc3..d275f6abfd 100644 --- a/net/netdev/netdev_register.c +++ b/net/netdev/netdev_register.c @@ -230,7 +230,7 @@ int netdev_register(FAR struct net_driver_s *dev, enum net_lltype_e lltype) #ifdef CONFIG_NET_6LOWPAN case NET_LL_6LOWPAN: /* IEEE 802.15.4 */ dev->d_llhdrlen = 0; /* REVISIT */ - dev->d_mtu = CONFIG_NET_6LOWPAN_MTU; + dev->d_mtu = SIXLOWPAN_MAC_MAXFRAME; #ifdef CONFIG_NET_TCP dev->d_recvwndo = CONFIG_NET_6LOWPAN_TCP_RECVWNDO; #endif diff --git a/net/sixlowpan/Kconfig b/net/sixlowpan/Kconfig index b89d1345d9..ff47838489 100644 --- a/net/sixlowpan/Kconfig +++ b/net/sixlowpan/Kconfig @@ -43,6 +43,14 @@ config NET_6LOWPAN_COMPRESSION_HC06 endchoice # 6loWPAN Compression +config NET_6LOWPAN_COMPRESSION_THRESHOLD + int "Lower compression threshold" + default 63 + depends on !NET_6LOWPAN_COMPRESSION_IPv6 + ---help--- + CONFIG_NET_6LOWPAN_COMPRESSION_THRESHOLD sets a lower threshold for + when packets should not be compressed. + if NET_6LOWPAN_COMPRESSION_HC06 config NET_6LOWPAN_MAXADDRCONTEXT @@ -119,27 +127,31 @@ config NET_SIXLOWPAN_MAXAGE ---help--- Timeout for packet reassembly at the 6lowpan layer (should be < 60s) -config NET_6LOWPAN_MTU - int "6LoWPAN packet buffer size (MTU)" - default 1294 - range 590 1518 +config NET_6LOWPAN_MAX_MACTRANSMITS + int "Max MAC transmissions" + default 4 ---help--- - Packet buffer size. This size includes the TCP/UDP payload plus the - size of TCP/UDP header, the IP header, and data link layer headers. - This value is normally referred to as the MTU (Maximum Transmission - Unit); the payload is the MSS (Maximum Segment Size). + CONFIG_NET_6LOWPAN_MAX_MACTRANSMITS specifies how many times the MAC + layer should resend packets if no link-layer ACK wasreceived. This + only makes sense with the csma_driver. - IPv6 hosts are required to be able to handle an MSS of 1220 octets, - resulting in a minimum buffer size of of 1220+20+40+xx = xx. REVISIT! +config NET_SIXLOWPAN_MAXPAYLOAD + int "Max packet size" + default 102 + ---help--- + CONFIG_NET_SIXLOWPAN_MAXPAYLOAD specifies the maximum size of packets + before they get fragmented. The default is 127 bytes (the maximum size + 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_TCP_RECVWNDO int "6LoWPAN TCP receive window size" - default 1220 + default 102 depends on NET_TCP ---help--- The size of the advertised receiver's window. Should be set low - (i.e., to the size of the MSS) 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 frame payload) if the application + is slow to process incoming data, or high (32768 bytes) if the + application processes data quickly. REVISIT! endif # NET_6LOWPAN diff --git a/net/sixlowpan/sixlowpan_hc06.c b/net/sixlowpan/sixlowpan_hc06.c index f992676ef9..8ce6518bc4 100644 --- a/net/sixlowpan/sixlowpan_hc06.c +++ b/net/sixlowpan/sixlowpan_hc06.c @@ -150,8 +150,8 @@ void sixlowpan_hc06_initialize(void) g_hc06_addrcontexts[2].used = 1; g_hc06_addrcontexts[2].number = 2; - g_hc06_addrcontexts[2].prefix[0] = CONFIG_NET_6LOWPAN_MAXADDRCONTEXT_PREFIX_1_0; - g_hc06_addrcontexts[2].prefix[1] = CONFIG_NET_6LOWPAN_MAXADDRCONTEXT_PREFIX_1_1; + g_hc06_addrcontexts[2].prefix[0] = CONFIG_NET_6LOWPAN_MAXADDRCONTEXT_PREFIX_2_0; + g_hc06_addrcontexts[2].prefix[1] = CONFIG_NET_6LOWPAN_MAXADDRCONTEXT_PREFIX_2_1; } else #endif /* SIXLOWPAN_CONF_ADDR_CONTEXT_2 */ -- GitLab From 25496936cc7ba438802ab3e18109f3e41b137625 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 28 Mar 2017 11:35:46 -0600 Subject: [PATCH 247/990] 6loWPAN: Add dummy files to handle 6loWPAN formmatted input and output packets. --- net/sixlowpan/Make.defs | 1 + net/sixlowpan/sixlowpan.h | 2 +- net/sixlowpan/sixlowpan_initialize.c | 2 +- net/sixlowpan/sixlowpan_input.c | 83 ++++++++++++++++++++++++++++ net/sixlowpan/sixlowpan_output.c | 77 ++++++++++++++++++++++++++ 5 files changed, 163 insertions(+), 2 deletions(-) create mode 100644 net/sixlowpan/sixlowpan_input.c create mode 100644 net/sixlowpan/sixlowpan_output.c diff --git a/net/sixlowpan/Make.defs b/net/sixlowpan/Make.defs index 0ddebc0b20..ceda75dc6d 100644 --- a/net/sixlowpan/Make.defs +++ b/net/sixlowpan/Make.defs @@ -40,6 +40,7 @@ ifeq ($(CONFIG_NET_6LOWPAN),y) # Include IEEE 802.15.4 file in the build NET_CSRCS += sixlowpan_initialize.c sixlowpan_globals.c +NET_CSRCS += sixlowpan_input.c sixlowpan_output.c NET_CSRCS += sixlowpan_compressor.c sixlowpan_sniffer.c ifeq ($(CONFIG_NET_6LOWPAN_COMPRESSION_HC06),y) diff --git a/net/sixlowpan/sixlowpan.h b/net/sixlowpan/sixlowpan.h index 31a858205d..6fe0efe99f 100644 --- a/net/sixlowpan/sixlowpan.h +++ b/net/sixlowpan/sixlowpan.h @@ -76,7 +76,7 @@ extern FAR struct sixlowpan_rime_sniffer_s *g_sixlowpan_sniffer; * sixlowpan_initialize() configures 6loWPAN networking data structures. * It is called prior to platform-specific driver initialization so that * the 6loWPAN networking subsystem is prepared to deal with network - * driver initialization actions. + * driver initialization actions. * * Input Parameters: * None diff --git a/net/sixlowpan/sixlowpan_initialize.c b/net/sixlowpan/sixlowpan_initialize.c index ccf0cefed4..07e10b6a37 100644 --- a/net/sixlowpan/sixlowpan_initialize.c +++ b/net/sixlowpan/sixlowpan_initialize.c @@ -56,7 +56,7 @@ * sixlowpan_initialize() configures 6loWPAN networking data structures. * It is called prior to platform-specific driver initialization so that * the 6loWPAN networking subsystem is prepared to deal with network - * driver initialization actions. + * driver initialization actions. * * Input Parameters: * None diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c new file mode 100644 index 0000000000..df02dbece9 --- /dev/null +++ b/net/sixlowpan/sixlowpan_input.c @@ -0,0 +1,83 @@ +/**************************************************************************** + * net/sixlowpan/sixlowpan_initialize.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include "nuttx/net/netdev.h" +#include "sixlowpan/sixlowpan.h" + +#ifdef CONFIG_NET_6LOWPAN + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: sixlowpan_input + * + * Description: + * Process an incoming IP packet. + * + * This function is called when the device driver has received a 6loWPAN + * packet from the network. The packet from the device driver must be + * present in the d_buf buffer, and the length of the packet should be + * placed in the d_len field. + * + * When the function returns, there may be an outbound packet placed + * in the d_buf packet buffer. If so, the d_len field is set to + * the length of the packet. If no packet is to be sent out, the + * d_len field is set to 0. + * + * Input Parameters: + * dev - The IEEE802.15.4 MAC network driver interface. + * + * Returned Value: + * Ok is returned on success; Othewise a negated errno value is returned. + * + ****************************************************************************/ + +int sixlowpan_input(FAR struct net_driver_s *dev) +{ + /* REVISIT: To be provided */ + return -ENOSYS; +} + +#endif /* CONFIG_NET_6LOWPAN */ diff --git a/net/sixlowpan/sixlowpan_output.c b/net/sixlowpan/sixlowpan_output.c new file mode 100644 index 0000000000..af4b7c9d63 --- /dev/null +++ b/net/sixlowpan/sixlowpan_output.c @@ -0,0 +1,77 @@ +/**************************************************************************** + * net/sixlowpan/sixlowpan_output.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include "nuttx/net/netdev.h" +#include "sixlowpan/sixlowpan.h" + +#ifdef CONFIG_NET_6LOWPAN + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: sixlowpan_output + * + * Description: + * Process an outgoing UDP or TCP packet. Called from UDP/TCP logic to + * determine if the the packet should be formatted for 6loWPAN output. + * + * Input Parameters: + * dev - The IEEE802.15.4 MAC network driver interface. + * + * Returned Value: + * Ok is returned on success; Othewise a negated errno value is returned. + * This function is expected to fail if the driver is not an IEEE802.15.4 + * MAC network driver. In that case, the UDP/TCP will fall back to normal + * IPv4/IPv6 formatting. + * + ****************************************************************************/ + +int sixlowpan_output(FAR struct net_driver_s *dev) +{ + /* REVISIT: To be provided */ + return -ENOSYS; +} + +#endif /* CONFIG_NET_6LOWPAN */ -- GitLab From 75a8ad636c26faabc59abef36d94fae98d1df709 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 28 Mar 2017 12:23:19 -0600 Subject: [PATCH 248/990] 6loWPAN: Framework to support commpress/uncompress operations. --- net/sixlowpan/Kconfig | 4 + net/sixlowpan/Make.defs | 4 + net/sixlowpan/sixlowpan.h | 143 ++++++++++++++++++++++++++++ net/sixlowpan/sixlowpan_globals.c | 2 +- net/sixlowpan/sixlowpan_hc06.c | 81 ++++++++++++++++ net/sixlowpan/sixlowpan_hc1.c | 149 ++++++++++++++++++++++++++++++ net/sixlowpan/sixlowpan_input.c | 2 +- 7 files changed, 383 insertions(+), 2 deletions(-) create mode 100644 net/sixlowpan/sixlowpan_hc1.c diff --git a/net/sixlowpan/Kconfig b/net/sixlowpan/Kconfig index ff47838489..4505a7ee88 100644 --- a/net/sixlowpan/Kconfig +++ b/net/sixlowpan/Kconfig @@ -121,6 +121,10 @@ config NET_6LOWPAN_MAXADDRCONTEXT_PREFIX_2_1 endif # NET_6LOWPAN_MAXADDRCONTEXT_PREINIT_0 endif # NET_6LOWPAN_COMPRESSION_HC06 +config NET_6LOWPAN_RIMEADDR_SIZE + int "Rime address size" + default 2 + config NET_SIXLOWPAN_MAXAGE int "Packet reassembly timeout" default 20 diff --git a/net/sixlowpan/Make.defs b/net/sixlowpan/Make.defs index ceda75dc6d..703f89cf52 100644 --- a/net/sixlowpan/Make.defs +++ b/net/sixlowpan/Make.defs @@ -43,6 +43,10 @@ NET_CSRCS += sixlowpan_initialize.c sixlowpan_globals.c NET_CSRCS += sixlowpan_input.c sixlowpan_output.c NET_CSRCS += sixlowpan_compressor.c sixlowpan_sniffer.c +ifeq ($(CONFIG_NET_6LOWPAN_COMPRESSION_HC1),y) +NET_CSRCS += sixlowpan_hc1.c +endif + ifeq ($(CONFIG_NET_6LOWPAN_COMPRESSION_HC06),y) NET_CSRCS += sixlowpan_hc06.c endif diff --git a/net/sixlowpan/sixlowpan.h b/net/sixlowpan/sixlowpan.h index 6fe0efe99f..ab36cf86d4 100644 --- a/net/sixlowpan/sixlowpan.h +++ b/net/sixlowpan/sixlowpan.h @@ -45,6 +45,15 @@ #ifdef CONFIG_NET_6LOWPAN +/**************************************************************************** + * Public Types + ****************************************************************************/ + +struct rimeaddr_s +{ + uint8_t u8[CONFIG_NET_6LOWPAN_RIMEADDR_SIZE]; +}; + /**************************************************************************** * Public Data ****************************************************************************/ @@ -67,6 +76,8 @@ extern FAR struct sixlowpan_rime_sniffer_s *g_sixlowpan_sniffer; * Public Function Prototypes ****************************************************************************/ +struct net_driver_s; /* Forward reference */ + /**************************************************************************** * Name: sixlowpan_initialize * @@ -88,6 +99,26 @@ extern FAR struct sixlowpan_rime_sniffer_s *g_sixlowpan_sniffer; void sixlowpan_initialize(void); +/**************************************************************************** + * Name: sixlowpan_output + * + * Description: + * Process an outgoing UDP or TCP packet. Called from UDP/TCP logic to + * determine if the the packet should be formatted for 6loWPAN output. + * + * Input Parameters: + * dev - The IEEE802.15.4 MAC network driver interface. + * + * Returned Value: + * Ok is returned on success; Othewise a negated errno value is returned. + * This function is expected to fail if the driver is not an IEEE802.15.4 + * MAC network driver. In that case, the UDP/TCP will fall back to normal + * IPv4/IPv6 formatting. + * + ****************************************************************************/ + +int sixlowpan_output(FAR struct net_driver_s *dev); + /**************************************************************************** * Name: sixlowpan_hc06_initialize * @@ -111,5 +142,117 @@ void sixlowpan_initialize(void); void sixlowpan_hc06_initialize(void); #endif +/**************************************************************************** + * Name: sixlowpan_hc06_initialize + * + * Description: + * Compress IP/UDP header + * + * This function is called by the 6lowpan code to create a compressed + * 6lowpan packet in the packetbuf buffer from a full IPv6 packet in the + * uip_buf buffer. + * + * HC-06 (draft-ietf-6lowpan-hc, version 6) + * http://tools.ietf.org/html/draft-ietf-6lowpan-hc-06 + * + * NOTE: sixlowpan_compresshdr_hc06() does not support ISA100_UDP header + * compression + * + * Input Parameters: + * dev - A reference to the IEE802.15.4 network device state + * destaddr - L2 destination address, needed to compress IP dest + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 +void sixlowpan_compresshdr_hc06(FAR struct net_driver_s *dev, + FAR struct rimeaddr_s *destaddr); +#endif + +/**************************************************************************** + * Name: sixlowpan_hc06_initialize + * + * Description: + * Uncompress HC06 (i.e., IPHC and LOWPAN_UDP) headers and put them in + * sixlowpan_buf + * + * This function is called by the input function when the dispatch is HC06. + * We process the packet in the rime buffer, uncompress the header fields, + * and copy the result in the sixlowpan buffer. At the end of the + * decompression, g_rime_hdrlen and g_uncompressed_hdrlen are set to the + * appropriate values + * + * Input Parmeters: + * dev - A reference to the IEE802.15.4 network device state + * iplen - Equal to 0 if the packet is not a fragment (IP length is then + * inferred from the L2 length), non 0 if the packet is a 1st + * fragment. + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 +void sixlowpan_uncompresshdr_hc06(FAR struct net_driver_s *dev, + uint16_t iplen); +#endif + +/**************************************************************************** + * Name: sixlowpan_compresshdr_hc1 + * + * Description: + * Compress IP/UDP header using HC1 and HC_UDP + * + * This function is called by the 6lowpan code to create a compressed + * 6lowpan packet in the packetbuf buffer from a full IPv6 packet in the + * uip_buf buffer. + * + * Input Parmeters: + * dev - A reference to the IEE802.15.4 network device state + * destaddr - L2 destination address, needed to compress the IP + * destination field + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC1 +void sixlowpan_compresshdr_hc1(FAR struct net_driver_s *dev, + FAR struct rimeaddr_s *destaddr); +#endif + +/**************************************************************************** + * Name: sixlowpan_uncompresshdr_hc1 + * + * Description: + * Uncompress HC1 (and HC_UDP) headers and put them in sixlowpan_buf + * + * This function is called by the input function when the dispatch is + * HC1. It processes the packet in the rime buffer, uncompresses the + * header fields, and copies the result in the sixlowpan buffer. At the + * end of the decompression, g_rime_hdrlen and uncompressed_hdr_len + * are set to the appropriate values + * + * Input Parameters: + * dev - A reference to the IEE802.15.4 network device state + * iplen - Equal to 0 if the packet is not a fragment (IP length is then + * inferred from the L2 length), non 0 if the packet is a 1st + * fragment. + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC1 +void sixlowpan_uncompresshdr_hc1(FAR struct net_driver_s *dev, + uint16_t ip_len); +#endif + #endif /* CONFIG_NET_6LOWPAN */ #endif /* _NET_SIXLOWPAN_SIXLOWPAN_H */ diff --git a/net/sixlowpan/sixlowpan_globals.c b/net/sixlowpan/sixlowpan_globals.c index e289d88c0c..6a5729d619 100644 --- a/net/sixlowpan/sixlowpan_globals.c +++ b/net/sixlowpan/sixlowpan_globals.c @@ -1,5 +1,5 @@ /**************************************************************************** - * net/sixlowpan/sixlowpan_sniffer.c + * net/sixlowpan/sixlowpan_globals.c * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt diff --git a/net/sixlowpan/sixlowpan_hc06.c b/net/sixlowpan/sixlowpan_hc06.c index 8ce6518bc4..733edc900b 100644 --- a/net/sixlowpan/sixlowpan_hc06.c +++ b/net/sixlowpan/sixlowpan_hc06.c @@ -57,6 +57,7 @@ #include +#include #include #include "sixlowpan/sixlowpan.h" @@ -166,4 +167,84 @@ void sixlowpan_hc06_initialize(void) #endif /* CONFIG_NET_6LOWPAN_MAXADDRCONTEXT > 0 */ } +/**************************************************************************** + * Name: sixlowpan_hc06_initialize + * + * Description: + * Compress IP/UDP header + * + * This function is called by the 6lowpan code to create a compressed + * 6lowpan packet in the packetbuf buffer from a full IPv6 packet in the + * uip_buf buffer. + * + * HC-06 (draft-ietf-6lowpan-hc, version 6) + * http://tools.ietf.org/html/draft-ietf-6lowpan-hc-06 + * + * NOTE: sixlowpan_compresshdr_hc06() does not support ISA100_UDP header + * compression + * + * For LOWPAN_UDP compression, we either compress both ports or none. + * General format with LOWPAN_UDP compression is + * 1 2 3 + * 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + * |0|1|1|TF |N|HLI|C|S|SAM|M|D|DAM| SCI | DCI | comp. IPv6 hdr| + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + * | compressed IPv6 fields ..... | + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + * | LOWPAN_UDP | non compressed UDP fields ... | + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + * | L4 data ... | + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + * + * NOTE: The g_addr_context number 00 is reserved for the link local prefix. + * For unicast addresses, if we cannot compress the prefix, we neither + * compress the IID. + * + * Input Parameters: + * dev - A reference to the IEE802.15.4 network device state + * destaddr - L2 destination address, needed to compress IP dest + * + * Returned Value: + * None + * + ****************************************************************************/ + +void sixlowpan_compresshdr_hc06(FAR struct net_driver_s *dev, + FAR struct rimeaddr_s *destaddr) +{ + /* REVISIT: To be provided */ +} + +/**************************************************************************** + * Name: sixlowpan_hc06_initialize + * + * Description: + * Uncompress HC06 (i.e., IPHC and LOWPAN_UDP) headers and put them in + * sixlowpan_buf + * + * This function is called by the input function when the dispatch is HC06. + * We process the packet in the rime buffer, uncompress the header fields, + * and copy the result in the sixlowpan buffer. At the end of the + * decompression, g_rime_hdrlen and g_uncompressed_hdrlen are set to the + * appropriate values + * + * Input Parmeters: + * dev - A reference to the IEE802.15.4 network device state + * iplen - Equal to 0 if the packet is not a fragment (IP length is then + * inferred from the L2 length), non 0 if the packet is a 1st + * fragment. + * + * Returned Value: + * None + * + ****************************************************************************/ + +void sixlowpan_uncompresshdr_hc06(FAR struct net_driver_s *dev, + uint16_t iplen) +{ + /* REVISIT: To be provided */ +} + + #endif /* CONFIG_NET_6LOWPAN_COMPRESSION_HC06 */ diff --git a/net/sixlowpan/sixlowpan_hc1.c b/net/sixlowpan/sixlowpan_hc1.c new file mode 100644 index 0000000000..3f9b93f17d --- /dev/null +++ b/net/sixlowpan/sixlowpan_hc1.c @@ -0,0 +1,149 @@ +/**************************************************************************** + * net/sixlowpan/sixlowpan_hc1.c + * + * Copyright (C) 2017, Gregory Nutt, all rights reserved + * Author: Gregory Nutt + * + * Derives from Contiki: + * + * Copyright (c) 2008, Swedish Institute of Computer Science. + * All rights reserved. + * Authors: Adam Dunkels + * Nicolas Tsiftes + * Niclas Finne + * Mathilde Durvy + * Julien Abeille + * Joakim Eriksson + * Joel Hoglund + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the Institute 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 INSTITUTE 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 INSTITUTE 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 "sixlowpan/sixlowpan.h" + +#ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC1 + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: sixlowpan_compresshdr_hc1 + * + * Description: + * Compress IP/UDP header using HC1 and HC_UDP + * + * This function is called by the 6lowpan code to create a compressed + * 6lowpan packet in the packetbuf buffer from a full IPv6 packet in the + * uip_buf buffer. + * + * If we can compress everything, we use HC1 dispatch, if not we use + * IPv6 dispatch. We can compress everything if: + * + * - IP version is + * - Flow label and traffic class are 0 + * - Both src and dest ip addresses are link local + * - Both src and dest interface ID are recoverable from lower layer + * header + * - Next header is either ICMP, UDP or TCP + * + * Moreover, if next header is UDP, we try to compress it using HC_UDP. + * This is feasible is both ports are between F0B0 and F0B0 + 15\n\n + * + * Resulting header structure: + * - For ICMP, TCP, non compressed UDP\n + * HC1 encoding = 11111010 (UDP) 11111110 (TCP) 11111100 (ICMP)\n + * 1 2 3 + * 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + * | LoWPAN HC1 Dsp | HC1 encoding | IPv6 Hop limit| L4 hdr + data| + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + * | ... + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + * + * - For compressed UDP + * HC1 encoding = 11111011, HC_UDP encoding = 11100000\n + * 1 2 3 + * 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + * | LoWPAN HC1 Dsp| HC1 encoding | HC_UDP encod.| IPv6 Hop limit| + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + * | src p.| dst p.| UDP checksum | L4 data... + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + * + * Input Parmeters: + * dev - A reference to the IEE802.15.4 network device state + * destaddr - L2 destination address, needed to compress the IP + * destination field + * + * Returned Value: + * None + * + ****************************************************************************/ + +void sixlowpan_compresshdr_hc1(FAR struct net_driver_s *dev, + FAR struct rimeaddr_s *destaddr) +{ +/* REVISIT: To be provided */ +} + +/**************************************************************************** + * Name: sixlowpan_uncompresshdr_hc1 + * + * Description: + * Uncompress HC1 (and HC_UDP) headers and put them in sixlowpan_buf + * + * This function is called by the input function when the dispatch is + * HC1. It processes the packet in the rime buffer, uncompresses the + * header fields, and copies the result in the sixlowpan buffer. At the + * end of the decompression, g_rime_hdrlen and uncompressed_hdr_len + * are set to the appropriate values + * + * Input Parameters: + * dev - A reference to the IEE802.15.4 network device state + * iplen - Equal to 0 if the packet is not a fragment (IP length is then + * inferred from the L2 length), non 0 if the packet is a 1st + * fragment. + * + * Returned Value: + * None + * + ****************************************************************************/ + +void sixlowpan_uncompresshdr_hc1(FAR struct net_driver_s *dev, + uint16_t iplen) +{ +/* REVISIT: To be provided */ +} + +#endif /* CONFIG_NET_6LOWPAN_COMPRESSION_HC1 */ diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index df02dbece9..f28c0eafda 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -1,5 +1,5 @@ /**************************************************************************** - * net/sixlowpan/sixlowpan_initialize.c + * net/sixlowpan/sixlowpan_input.c * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt -- GitLab From 64933246c34fef9b10d9930005e633227e889548 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 28 Mar 2017 14:08:54 -0600 Subject: [PATCH 249/990] 6loWPAN: Tie 6loWPAN send into common socket send logic. --- include/nuttx/net/net.h | 2 +- net/netdev/netdev_register.c | 2 +- net/sixlowpan/Make.defs | 2 +- net/sixlowpan/sixlowpan.h | 51 +++++ net/sixlowpan/sixlowpan_output.c | 77 -------- net/sixlowpan/sixlowpan_send.c | 309 +++++++++++++++++++++++++++++++ net/socket/send.c | 32 +++- net/tcp/tcp_send.c | 14 +- net/tcp/tcp_send_buffered.c | 2 +- net/tcp/tcp_send_unbuffered.c | 2 +- 10 files changed, 401 insertions(+), 92 deletions(-) delete mode 100644 net/sixlowpan/sixlowpan_output.c create mode 100644 net/sixlowpan/sixlowpan_send.c diff --git a/include/nuttx/net/net.h b/include/nuttx/net/net.h index 1c64351fe2..337e0a6366 100644 --- a/include/nuttx/net/net.h +++ b/include/nuttx/net/net.h @@ -79,7 +79,7 @@ enum net_lltype_e NET_LL_SLIP, /* Serial Line Internet Protocol (SLIP) */ NET_LL_TUN, /* TUN Virtual Network Device */ NET_LL_IEEE80211, /* IEEE 802.11 */ - NET_LL_6LOWPAN /* IEEE 802.15.4 6LoWPAN */ + NET_LL_IEEE805154 /* IEEE 802.15.4 MAC */ }; /* This defines a bitmap big enough for one bit for each socket option */ diff --git a/net/netdev/netdev_register.c b/net/netdev/netdev_register.c index d275f6abfd..9a3a01c66d 100644 --- a/net/netdev/netdev_register.c +++ b/net/netdev/netdev_register.c @@ -228,7 +228,7 @@ int netdev_register(FAR struct net_driver_s *dev, enum net_lltype_e lltype) #endif #ifdef CONFIG_NET_6LOWPAN - case NET_LL_6LOWPAN: /* IEEE 802.15.4 */ + case NET_LL_IEEE802154: /* IEEE 802.15.4 MAC */ dev->d_llhdrlen = 0; /* REVISIT */ dev->d_mtu = SIXLOWPAN_MAC_MAXFRAME; #ifdef CONFIG_NET_TCP diff --git a/net/sixlowpan/Make.defs b/net/sixlowpan/Make.defs index 703f89cf52..1e58151731 100644 --- a/net/sixlowpan/Make.defs +++ b/net/sixlowpan/Make.defs @@ -40,7 +40,7 @@ ifeq ($(CONFIG_NET_6LOWPAN),y) # Include IEEE 802.15.4 file in the build NET_CSRCS += sixlowpan_initialize.c sixlowpan_globals.c -NET_CSRCS += sixlowpan_input.c sixlowpan_output.c +NET_CSRCS += sixlowpan_input.c sixlowpan_send.c NET_CSRCS += sixlowpan_compressor.c sixlowpan_sniffer.c ifeq ($(CONFIG_NET_6LOWPAN_COMPRESSION_HC1),y) diff --git a/net/sixlowpan/sixlowpan.h b/net/sixlowpan/sixlowpan.h index ab36cf86d4..46a282b41d 100644 --- a/net/sixlowpan/sixlowpan.h +++ b/net/sixlowpan/sixlowpan.h @@ -77,6 +77,7 @@ extern FAR struct sixlowpan_rime_sniffer_s *g_sixlowpan_sniffer; ****************************************************************************/ struct net_driver_s; /* Forward reference */ +struct socket; /* Forward reference */ /**************************************************************************** * Name: sixlowpan_initialize @@ -99,6 +100,56 @@ struct net_driver_s; /* Forward reference */ void sixlowpan_initialize(void); +/**************************************************************************** + * Function: psock_6lowpan_tcp_send + * + * Description: + * psock_6lowpan_tcp_send() call may be used only when the TCP socket is in a + * connected state (so that the intended recipient is known). + * + * Parameters: + * psock - An instance of the internal socket structure. + * buf - Data to send + * len - Length of data to send + * + * Returned Value: + * On success, returns the number of characters sent. On error, + * -1 is returned, and errno is set appropriately. Returned error numbers + * must be consistent with definition of errors reported by send() or + * sendto(). + * + ****************************************************************************/ + +#ifdef CONFIG_NET_TCP +ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, + size_t len); +#endif + +/**************************************************************************** + * Function: psock_6lowpan_udp_send + * + * Description: + * psock_6lowpan_udp_send() call may be used with connectionlesss UDP + * sockets. + * + * Parameters: + * psock - An instance of the internal socket structure. + * buf - Data to send + * len - Length of data to send + * + * Returned Value: + * On success, returns the number of characters sent. On error, + * -1 is returned, and errno is set appropriately. Returned error numbers + * must be consistent with definition of errors reported by send() or + * sendto(). + * + ****************************************************************************/ + +#ifdef CONFIG_NET_UDP +ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, + size_t len); +#endif + /**************************************************************************** * Name: sixlowpan_output * diff --git a/net/sixlowpan/sixlowpan_output.c b/net/sixlowpan/sixlowpan_output.c deleted file mode 100644 index af4b7c9d63..0000000000 --- a/net/sixlowpan/sixlowpan_output.c +++ /dev/null @@ -1,77 +0,0 @@ -/**************************************************************************** - * net/sixlowpan/sixlowpan_output.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include - -#include "nuttx/net/netdev.h" -#include "sixlowpan/sixlowpan.h" - -#ifdef CONFIG_NET_6LOWPAN - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: sixlowpan_output - * - * Description: - * Process an outgoing UDP or TCP packet. Called from UDP/TCP logic to - * determine if the the packet should be formatted for 6loWPAN output. - * - * Input Parameters: - * dev - The IEEE802.15.4 MAC network driver interface. - * - * Returned Value: - * Ok is returned on success; Othewise a negated errno value is returned. - * This function is expected to fail if the driver is not an IEEE802.15.4 - * MAC network driver. In that case, the UDP/TCP will fall back to normal - * IPv4/IPv6 formatting. - * - ****************************************************************************/ - -int sixlowpan_output(FAR struct net_driver_s *dev) -{ - /* REVISIT: To be provided */ - return -ENOSYS; -} - -#endif /* CONFIG_NET_6LOWPAN */ diff --git a/net/sixlowpan/sixlowpan_send.c b/net/sixlowpan/sixlowpan_send.c new file mode 100644 index 0000000000..de33894597 --- /dev/null +++ b/net/sixlowpan/sixlowpan_send.c @@ -0,0 +1,309 @@ +/**************************************************************************** + * net/sixlowpan/sixlowpan_send.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include "nuttx/net/net.h" +#include "nuttx/net/netdev.h" + +#include "netdev/netdev.h" +#include "socket/socket.h" +#include "tcp/tcp.h" +#include "udp/udp.h" +#include "sixlowpan/sixlowpan.h" + +#ifdef CONFIG_NET_6LOWPAN + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: sixlowpan_send + * + * Description: + * Process an outgoing UDP or TCP packet. Called from UDP/TCP logic to + * determine if the the packet should be formatted for 6loWPAN output. + * + * Input Parameters: + * dev - The IEEE802.15.4 MAC network driver interface. + * + * Returned Value: + * Ok is returned on success; Othewise a negated errno value is returned. + * This function is expected to fail if the driver is not an IEEE802.15.4 + * MAC network driver. In that case, the UDP/TCP will fall back to normal + * IPv4/IPv6 formatting. + * + * Assumptions: + * Called with the network locked. + * + ****************************************************************************/ + +int sixlowpan_send(FAR struct net_driver_s *dev) +{ + net_lock(); + /* REVISIT: To be provided */ + net_unlock(); + return -ENOSYS; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: psock_6lowpan_tcp_send + * + * Description: + * psock_6lowpan_tcp_send() call may be used only when the TCP socket is in a + * connected state (so that the intended recipient is known). + * + * Parameters: + * psock - An instance of the internal socket structure. + * buf - Data to send + * len - Length of data to send + * + * Returned Value: + * On success, returns the number of characters sent. On error, + * -1 is returned, and errno is set appropriately. Returned error numbers + * must be consistent with definition of errors reported by send() or + * sendto(). + * + ****************************************************************************/ + +#ifdef CONFIG_NET_TCP +ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, + size_t len) +{ + FAR struct tcp_conn_s *conn; + FAR struct net_driver_s *dev; + int ret; + + DEBUGASSERT(psock != NULL && psock->s_crefs > 0); + DEBUGASSERT(psock->s_type == SOCK_STREAM); + + /* Make sure that this is a valid socket */ + + if (psock != NULL || psock->s_crefs <= 0) + { + nerr("ERROR: Invalid socket\n"); + return (ssize_t)-EBADF; + } + + /* Make sure that this is a connected TCP socket */ + + if (psock->s_type != SOCK_STREAM || !_SS_ISCONNECTED(psock->s_flags)) + { + nerr("ERROR: Not connected\n"); + return (ssize_t)-ENOTCONN; + } + + /* Get the underlying TCP connection structure */ + + conn = (FAR struct tcp_conn_s *)psock->s_conn; + DEBUGASSERT(conn != NULL); + + /* Ignore if not IPv6 domain */ + + if (conn->domain != PF_INET6) + { + nwarn("WARNING: Not IPv6\n"); + return (ssize_t)-EPROTOTYPE; + } + + /* Route outgoing message to the correct device */ + +#ifdef CONFIG_NETDEV_MULTINIC + dev = netdev_findby_ipv6addr(conn->u.ipv6.laddr, conn->u.ipv6.raddr); + if (dev == NULL || dev->d_lltype != NET_LL_IEEE805154) + { + nwarn("WARNING: Not routable or not IEEE802.15.4 MAC\n"); + return (ssize_t)-ENETUNREACH; + } +#else + dev = netdev_findby_ipv6addr(conn->u.ipv6.raddr); + if (dev == NULL) + { + nwarn("WARNING: Not routable\n"); + return (ssize_t)-ENETUNREACH; + } +#endif + +#ifdef CONFIG_NET_ICMPv6_NEIGHBOR + /* Make sure that the IP address mapping is in the Neighbor Table */ + + ret = icmpv6_neighbor(conn->u.ipv6.raddr); + if (ret < 0) + { + nerr("ERROR: Not reachable\n"); + return (ssize_t)-ENETUNREACH; + } +#endif + + /* Set the socket state to sending */ + + psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_SEND); + + /* If routable, then call sixlowpan_send() to format and send the 6loWPAN + * packet. + */ + + ret = sixlowpan_send(dev); + if (ret < 0) + { + nerr("ERROR: sixlowpan_send() failed: %d\n", ret); + } + + return ret; +} +#endif + +/**************************************************************************** + * Function: psock_6lowpan_udp_send + * + * Description: + * psock_6lowpan_udp_send() call may be used with connectionlesss UDP + * sockets. + * + * Parameters: + * psock - An instance of the internal socket structure. + * buf - Data to send + * len - Length of data to send + * + * Returned Value: + * On success, returns the number of characters sent. On error, + * -1 is returned, and errno is set appropriately. Returned error numbers + * must be consistent with definition of errors reported by send() or + * sendto(). + * + ****************************************************************************/ + +#ifdef CONFIG_NET_UDP +ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, + size_t len) +{ + FAR struct udp_conn_s *conn; + FAR struct net_driver_s *dev; + int ret; + + DEBUGASSERT(psock != NULL && psock->s_crefs > 0); + DEBUGASSERT(psock->s_type == SOCK_DGRAM); + + /* Make sure that this is a valid socket */ + + if (psock != NULL || psock->s_crefs <= 0) + { + nerr("ERROR: Invalid socket\n"); + return (ssize_t)-EBADF; + } + + /* Was the UDP socket connected via connect()? */ + + if (psock->s_type != SOCK_DGRAM || !_SS_ISCONNECTED(psock->s_flags)) + { + /* No, then it is not legal to call send() with this socket. */ + + return -ENOTCONN; + } + + /* Get the underlying UDP "connection" structure */ + + conn = (FAR struct udp_conn_s *)psock->s_conn; + DEBUGASSERT(conn != NULL); + + /* Ignore if not IPv6 domain */ + + if (conn->domain != PF_INET6) + { + nwarn("WARNING: Not IPv6\n"); + return (ssize_t)-EPROTOTYPE; + } + + /* Route outgoing message to the correct device */ + +#ifdef CONFIG_NETDEV_MULTINIC + dev = netdev_findby_ipv6addr(conn->u.ipv6.laddr, conn->u.ipv6.raddr); + if (dev == NULL || dev->d_lltype != NET_LL_IEEE805154) + { + nwarn("WARNING: Not routable or not IEEE802.15.4 MAC\n"); + return (ssize_t)-ENETUNREACH; + } +#else + dev = netdev_findby_ipv6addr(conn->u.ipv6.raddr); + if (dev == NULL) + { + nwarn("WARNING: Not routable\n"); + return (ssize_t)-ENETUNREACH; + } +#endif + +#ifdef CONFIG_NET_ICMPv6_NEIGHBOR + /* Make sure that the IP address mapping is in the Neighbor Table */ + + ret = icmpv6_neighbor(conn->u.ipv6.raddr); + if (ret < 0) + { + nerr("ERROR: Not reachable\n"); + return (ssize_t)-ENETUNREACH; + } +#endif + + /* Set the socket state to sending */ + + psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_SEND); + + /* If routable, then call sixlowpan_send() to format and send the 6loWPAN + * packet. + */ + + ret = sixlowpan_send(dev); + if (ret < 0) + { + nerr("ERROR: sixlowpan_send() failed: %d\n", ret); + } + + return ret; +} +#endif + +#endif /* CONFIG_NET_6LOWPAN */ diff --git a/net/socket/send.c b/net/socket/send.c index e90b27b116..20252fcdae 100644 --- a/net/socket/send.c +++ b/net/socket/send.c @@ -45,9 +45,10 @@ #include +#include "pkt/pkt.h" #include "tcp/tcp.h" #include "udp/udp.h" -#include "pkt/pkt.h" +#include "sixlowpan/sixlowpan.h" #include "local/local.h" #include "socket/socket.h" @@ -133,6 +134,8 @@ ssize_t psock_send(FAR struct socket *psock, FAR const void *buf, size_t len, #if defined(CONFIG_NET_PKT) case SOCK_RAW: { + /* Raw packet send */ + ret = psock_pkt_send(psock, buf, len); } break; @@ -146,6 +149,8 @@ ssize_t psock_send(FAR struct socket *psock, FAR const void *buf, size_t len, if (psock->s_domain == PF_LOCAL) #endif { + /* Local TCP packet send */ + ret = psock_local_send(psock, buf, len, flags); } #endif /* CONFIG_NET_LOCAL_STREAM */ @@ -155,7 +160,17 @@ ssize_t psock_send(FAR struct socket *psock, FAR const void *buf, size_t len, else #endif { - ret = psock_tcp_send(psock, buf, len); +#ifdef CONFIG_NET_6LOWPAN + /* Try 6loWPAN TCP packet send */ + + ret = psock_6lowpan_tcp_send(psock, buf, len); + if (ret < 0) +#endif + { + /* Try TCP/IP packet send */ + + ret = psock_tcp_send(psock, buf, len); + } } #endif /* CONFIG_NET_TCP */ } @@ -170,6 +185,7 @@ ssize_t psock_send(FAR struct socket *psock, FAR const void *buf, size_t len, if (psock->s_domain == PF_LOCAL) #endif { + /* Local UDP packet send */ #warning Missing logic ret = -ENOSYS; } @@ -180,7 +196,17 @@ ssize_t psock_send(FAR struct socket *psock, FAR const void *buf, size_t len, else #endif { - ret = psock_udp_send(psock, buf, len); +#ifdef CONFIG_NET_6LOWPAN + /* Try 6loWPAN UDP packet send */ + + ret = psock_6lowpan_udp_send(psock, buf, len); + if (ret < 0) +#endif + { + /* UDP/IP packet send */ + + ret = psock_udp_send(psock, buf, len); + } } #endif /* CONFIG_NET_UDP */ } diff --git a/net/tcp/tcp_send.c b/net/tcp/tcp_send.c index edce06a196..a68394b24c 100644 --- a/net/tcp/tcp_send.c +++ b/net/tcp/tcp_send.c @@ -121,7 +121,7 @@ static inline FAR struct tcp_hdr_s *tcp_header(FAR struct net_driver_s *dev) * None * * Assumptions: - * Called from the interrupt level or with interrupts disabled. + * Called with the network locked. * ****************************************************************************/ @@ -189,7 +189,7 @@ static inline void tcp_ipv4_sendcomplete(FAR struct net_driver_s *dev, * None * * Assumptions: - * Called from the interrupt level or with interrupts disabled. + * Called with the network locked. * ****************************************************************************/ @@ -252,7 +252,7 @@ static inline void tcp_ipv6_sendcomplete(FAR struct net_driver_s *dev, * None * * Assumptions: - * Called from the interrupt level or with interrupts disabled. + * Called with the network locked. * ****************************************************************************/ @@ -300,7 +300,7 @@ static void tcp_sendcomplete(FAR struct net_driver_s *dev, * None * * Assumptions: - * Called from the interrupt level or with interrupts disabled. + * Called with the network locked. * ****************************************************************************/ @@ -383,7 +383,7 @@ static void tcp_sendcommon(FAR struct net_driver_s *dev, * None * * Assumptions: - * Called from the interrupt level or with interrupts disabled. + * Called with the network locked. * ****************************************************************************/ @@ -411,7 +411,7 @@ void tcp_send(FAR struct net_driver_s *dev, FAR struct tcp_conn_s *conn, * None * * Assumptions: - * Called from the interrupt level or with interrupts disabled. + * Called with the network locked. * ****************************************************************************/ @@ -528,7 +528,7 @@ void tcp_reset(FAR struct net_driver_s *dev) * None * * Assumptions: - * Called from the interrupt level or with interrupts disabled. + * Called with the network locked. * ****************************************************************************/ diff --git a/net/tcp/tcp_send_buffered.c b/net/tcp/tcp_send_buffered.c index e3c12aed7e..76941f3a99 100644 --- a/net/tcp/tcp_send_buffered.c +++ b/net/tcp/tcp_send_buffered.c @@ -952,7 +952,7 @@ ssize_t psock_tcp_send(FAR struct socket *psock, FAR const void *buf, int errcode; int ret = OK; - if (!psock || psock->s_crefs <= 0) + if (psock == NULL || psock->s_crefs <= 0) { nerr("ERROR: Invalid socket\n"); errcode = EBADF; diff --git a/net/tcp/tcp_send_unbuffered.c b/net/tcp/tcp_send_unbuffered.c index d6422437c8..6c3688d85a 100644 --- a/net/tcp/tcp_send_unbuffered.c +++ b/net/tcp/tcp_send_unbuffered.c @@ -722,7 +722,7 @@ ssize_t psock_tcp_send(FAR struct socket *psock, /* Verify that the sockfd corresponds to valid, allocated socket */ - if (!psock || psock->s_crefs <= 0) + if (psock == NULL || psock->s_crefs <= 0) { nerr("ERROR: Invalid socket\n"); errcode = EBADF; -- GitLab From 4c6e4b2344846e6309cd322037460fb40f1db2a9 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 28 Mar 2017 14:30:46 -0600 Subject: [PATCH 250/990] Remove some garbage from wireless/Makefile --- wireless/Makefile | 8 -------- wireless/ieee802154/Make.defs | 1 + 2 files changed, 1 insertion(+), 8 deletions(-) diff --git a/wireless/Makefile b/wireless/Makefile index 008d23ff1c..f05d957943 100644 --- a/wireless/Makefile +++ b/wireless/Makefile @@ -52,14 +52,6 @@ VPATH = . include ieee802154$(DELIM)Make.defs -# Include support for various drivers. Each Make.defs file will add its -# files to the source file list, add its DEPPATH info, and will add -# the appropriate paths to the VPATH variable - -ifeq ($(CONFIG_WIRELESS_FORMAT_PCM),y) - CSRCS += pcm_decode.c -endif - AOBJS = $(ASRCS:.S=$(OBJEXT)) COBJS = $(CSRCS:.c=$(OBJEXT)) diff --git a/wireless/ieee802154/Make.defs b/wireless/ieee802154/Make.defs index 5d54b0004d..834b3da210 100644 --- a/wireless/ieee802154/Make.defs +++ b/wireless/ieee802154/Make.defs @@ -36,6 +36,7 @@ ifeq ($(CONFIG_WIRELESS_IEEE802154),y) # Include IEEE 802.15.4 support + CSRCS = # Include wireless devices build support -- GitLab From 95f7d4dca750efe60019ad945f2c0863b0bb62ab Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 28 Mar 2017 14:33:45 -0600 Subject: [PATCH 251/990] There should not be paths on C file names in wireless/ieee802154/Make.defs --- wireless/ieee802154/Make.defs | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/wireless/ieee802154/Make.defs b/wireless/ieee802154/Make.defs index 834b3da210..051bf50ee6 100644 --- a/wireless/ieee802154/Make.defs +++ b/wireless/ieee802154/Make.defs @@ -42,11 +42,11 @@ CSRCS = # Include wireless devices build support ifeq ($(CONFIG_IEEE802154_MAC),y) -CSRCS += ieee802154/mac802154.c +CSRCS += mac802154.c endif ifeq ($(CONFIG_IEEE802154_DEV),y) -CSRCS += ieee802154/radio802154_device.c +CSRCS += radio802154_device.c endif DEPPATH += --dep-path wireless/ieee802154 -- GitLab From e360492f0c63831091ecc6eb4729c39beef8c0ea Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Tue, 28 Mar 2017 16:58:18 -0400 Subject: [PATCH 252/990] wireless/ieee802154: Removes wireless path prefix from VPATH, DEPPATH --- wireless/ieee802154/Make.defs | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/wireless/ieee802154/Make.defs b/wireless/ieee802154/Make.defs index 051bf50ee6..e2f205aabc 100644 --- a/wireless/ieee802154/Make.defs +++ b/wireless/ieee802154/Make.defs @@ -49,8 +49,8 @@ ifeq ($(CONFIG_IEEE802154_DEV),y) CSRCS += radio802154_device.c endif -DEPPATH += --dep-path wireless/ieee802154 -VPATH += :wireless/ieee802154 +DEPPATH += --dep-path ieee802154 +VPATH += :ieee802154 CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)$(DELIM)wireless$(DELIM)ieee802154} endif # CONFIG_WIRELESS_IEEE802154 -- GitLab From abab1e68a8404b9bbe70eee9d25332abfb951155 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Tue, 28 Mar 2017 16:43:11 -0400 Subject: [PATCH 253/990] configs/clicker2-stm32: Fixes minor SPI configuration issues --- configs/clicker2-stm32/src/clicker2-stm32.h | 13 ++++++++++++- configs/clicker2-stm32/src/stm32_boot.c | 11 +++++++++++ configs/clicker2-stm32/src/stm32_spi.c | 13 ++++++++++++- 3 files changed, 35 insertions(+), 2 deletions(-) diff --git a/configs/clicker2-stm32/src/clicker2-stm32.h b/configs/clicker2-stm32/src/clicker2-stm32.h index 24dd9e54dc..5def0fdce8 100644 --- a/configs/clicker2-stm32/src/clicker2-stm32.h +++ b/configs/clicker2-stm32/src/clicker2-stm32.h @@ -233,6 +233,17 @@ * Public Functions ************************************************************************************/ +/**************************************************************************** + * Name: stm32_spidev_initialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the Mikroe Clicker2 STM32 + * board. + * + ****************************************************************************/ + +void weak_function stm32_spidev_initialize(void); + /************************************************************************************ * Name: stm32_bringup * @@ -254,7 +265,7 @@ int stm32_bringup(void); * * Description: * Called from stm32_boardinitialize very early in inialization to setup USB-related - * GPIO pins for the Olimex STM32 P407 board. + * GPIO pins for the Mikroe Clicker2 STM32 board. * ************************************************************************************/ diff --git a/configs/clicker2-stm32/src/stm32_boot.c b/configs/clicker2-stm32/src/stm32_boot.c index fff7bb8764..e87d316572 100644 --- a/configs/clicker2-stm32/src/stm32_boot.c +++ b/configs/clicker2-stm32/src/stm32_boot.c @@ -63,6 +63,17 @@ void stm32_boardinitialize(void) { +#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || defined(CONFIG_STM32_SPI3) + /* Configure SPI chip selects if 1) SPI is not disabled, and 2) the weak function + * stm32_spidev_initialize() has been brought into the link. + */ + + if (stm32_spidev_initialize) + { + stm32_spidev_initialize(); + } +#endif + #ifdef CONFIG_STM32_OTGFS /* Initialize USB if the 1) OTG FS controller is in the configuration and 2) * disabled, and 3) the weak function stm32_usb_configure() has been brought diff --git a/configs/clicker2-stm32/src/stm32_spi.c b/configs/clicker2-stm32/src/stm32_spi.c index 87e6e8d1d1..9780fcdb42 100644 --- a/configs/clicker2-stm32/src/stm32_spi.c +++ b/configs/clicker2-stm32/src/stm32_spi.c @@ -135,7 +135,18 @@ uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); - /* To be provided */ + + switch(devid) + { +#ifdef CONFIG_IEEE802154_MRF24J40 + case SPIDEV_IEEE802154: + /* Set the GPIO low to select and high to de-select */ + stm32_gpiowrite(GPIO_MB1_CS, !selected); + break; +#endif + default: + break; + } } uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) -- GitLab From 3809f2cc97365c844b29036febdcb4ee0b70fb32 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Tue, 28 Mar 2017 17:20:24 -0400 Subject: [PATCH 254/990] wireless/ieee802154: Removes unnecessary define --- include/nuttx/wireless/ieee802154/ieee802154_mac.h | 1 - 1 file changed, 1 deletion(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index 407360d815..1b43c3c3bb 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -95,7 +95,6 @@ /* Frame Type */ -#define IEEE802154_FC1_FTYPE 0x03 #define IEEE802154_FRAME_BEACON 0x00 #define IEEE802154_FRAME_DATA 0x01 #define IEEE802154_FRAME_ACK 0x02 -- GitLab From c3c8f8ed312aa49417d84ec8cae6311784f7282f Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 28 Mar 2017 16:14:58 -0600 Subject: [PATCH 255/990] 6loWPAN: Simplify some logic in send() if there is only an IEEE802.15.4 MAC --- net/socket/send.c | 24 +++++++++++++++++++++--- 1 file changed, 21 insertions(+), 3 deletions(-) diff --git a/net/socket/send.c b/net/socket/send.c index 20252fcdae..fd37860a1a 100644 --- a/net/socket/send.c +++ b/net/socket/send.c @@ -164,13 +164,22 @@ ssize_t psock_send(FAR struct socket *psock, FAR const void *buf, size_t len, /* Try 6loWPAN TCP packet send */ ret = psock_6lowpan_tcp_send(psock, buf, len); + +#ifdef CONFIG_NETDEV_MULTINIC if (ret < 0) -#endif { - /* Try TCP/IP packet send */ + /* UDP/IP packet send */ ret = psock_tcp_send(psock, buf, len); } + +#endif /* CONFIG_NETDEV_MULTINIC */ +#else /* CONFIG_NET_6LOWPAN */ + + /* Only TCP/IP packet send */ + + ret = psock_tcp_send(psock, buf, len); +#endif /* CONFIG_NET_6LOWPAN */ } #endif /* CONFIG_NET_TCP */ } @@ -200,13 +209,22 @@ ssize_t psock_send(FAR struct socket *psock, FAR const void *buf, size_t len, /* Try 6loWPAN UDP packet send */ ret = psock_6lowpan_udp_send(psock, buf, len); + +#ifdef CONFIG_NETDEV_MULTINIC if (ret < 0) -#endif { /* UDP/IP packet send */ ret = psock_udp_send(psock, buf, len); } + +#endif /* CONFIG_NETDEV_MULTINIC */ +#else /* CONFIG_NET_6LOWPAN */ + + /* Only UDP/IP packet send */ + + ret = psock_udp_send(psock, buf, len); +#endif /* CONFIG_NET_6LOWPAN */ } #endif /* CONFIG_NET_UDP */ } -- GitLab From ae5b5ae4319e3bd74ea7cb7aa9671afecac6e181 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 28 Mar 2017 17:26:53 -0600 Subject: [PATCH 256/990] Add Rime address macros --- net/sixlowpan/Kconfig | 3 +++ net/sixlowpan/sixlowpan.h | 14 ++++++++++++++ 2 files changed, 17 insertions(+) diff --git a/net/sixlowpan/Kconfig b/net/sixlowpan/Kconfig index 4505a7ee88..1a3882d1ad 100644 --- a/net/sixlowpan/Kconfig +++ b/net/sixlowpan/Kconfig @@ -124,6 +124,9 @@ endif # NET_6LOWPAN_COMPRESSION_HC06 config NET_6LOWPAN_RIMEADDR_SIZE int "Rime address size" default 2 + range 2 8 + ---help--- + Only the values 2 and 8 are supported config NET_SIXLOWPAN_MAXAGE int "Packet reassembly timeout" diff --git a/net/sixlowpan/sixlowpan.h b/net/sixlowpan/sixlowpan.h index 46a282b41d..3acd0f4804 100644 --- a/net/sixlowpan/sixlowpan.h +++ b/net/sixlowpan/sixlowpan.h @@ -45,10 +45,24 @@ #ifdef CONFIG_NET_6LOWPAN +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Rime addres macros */ + +#define rimeaddr_copy(dest,src) \ + memcpy(dest, src, CONFIG_NET_6LOWPAN_RIMEADDR_SIZE) + +#define rimeaddr_cmp(addr1,addr2) \ + (memcmp(addr1, addr2, CONFIG_NET_6LOWPAN_RIMEADDR_SIZE) == 0) + /**************************************************************************** * Public Types ****************************************************************************/ +/* Rime address representation */ + struct rimeaddr_s { uint8_t u8[CONFIG_NET_6LOWPAN_RIMEADDR_SIZE]; -- GitLab From 9f3b24a4a10ebd5dd5616941789bbe2ea85b6739 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Wed, 29 Mar 2017 07:08:10 -0600 Subject: [PATCH 257/990] STM32 F7: add stm32 RNG support. This is copied from stm32l4. Tested on STM32F746ZG board. --- arch/arm/src/stm32f7/Make.defs | 4 + arch/arm/src/stm32f7/chip/stm32_rng.h | 77 ++++++ arch/arm/src/stm32f7/stm32_rng.c | 362 ++++++++++++++++++++++++++ arch/arm/src/stm32l4/stm32l4_rng.c | 4 +- 4 files changed, 445 insertions(+), 2 deletions(-) create mode 100644 arch/arm/src/stm32f7/chip/stm32_rng.h create mode 100644 arch/arm/src/stm32f7/stm32_rng.c diff --git a/arch/arm/src/stm32f7/Make.defs b/arch/arm/src/stm32f7/Make.defs index d25b702d67..8baa4fbf13 100644 --- a/arch/arm/src/stm32f7/Make.defs +++ b/arch/arm/src/stm32f7/Make.defs @@ -194,3 +194,7 @@ endif ifeq ($(CONFIG_STM32F7_BBSRAM),y) CHIP_CSRCS += stm32_bbsram.c endif + +ifeq ($(CONFIG_STM32F7_RNG),y) +CHIP_CSRCS += stm32_rng.c +endif diff --git a/arch/arm/src/stm32f7/chip/stm32_rng.h b/arch/arm/src/stm32f7/chip/stm32_rng.h new file mode 100644 index 0000000000..3f5351a074 --- /dev/null +++ b/arch/arm/src/stm32f7/chip/stm32_rng.h @@ -0,0 +1,77 @@ +/************************************************************************************ + * arch/arm/src/stm32f7/chip/stm32_rng.h + * + * Copyright (C) 2012 Max Holtzberg. All rights reserved. + * Author: Max Holtzberg + * + * 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 __ARCH_ARM_STC_STM32F7_CHIP_STM32_RNG_H +#define __ARCH_ARM_STC_STM32F7_CHIP_STM32_RNG_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include "chip.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Register Offsets *****************************************************************/ + +#define STM32_RNG_CR_OFFSET 0x0000 /* RNG Control Register */ +#define STM32_RNG_SR_OFFSET 0x0004 /* RNG Status Register */ +#define STM32_RNG_DR_OFFSET 0x0008 /* RNG Data Register */ + +/* Register Addresses ***************************************************************/ + +#define STM32_RNG_CR (STM32_RNG_BASE+STM32_RNG_CR_OFFSET) +#define STM32_RNG_SR (STM32_RNG_BASE+STM32_RNG_SR_OFFSET) +#define STM32_RNG_DR (STM32_RNG_BASE+STM32_RNG_DR_OFFSET) + +/* Register Bitfield Definitions ****************************************************/ + +/* RNG Control Register */ + +#define RNG_CR_RNGEN (1 << 2) /* Bit 2: RNG enable */ +#define RNG_CR_IE (1 << 3) /* Bit 3: Interrupt enable */ + +/* RNG Status Register */ + +#define RNG_SR_DRDY (1 << 0) /* Bit 0: Data ready */ +#define RNG_SR_CECS (1 << 1) /* Bit 1: Clock error current status */ +#define RNG_SR_SECS (1 << 2) /* Bit 2: Seed error current status */ +#define RNG_SR_CEIS (1 << 5) /* Bit 5: Clock error interrupt status */ +#define RNG_SR_SEIS (1 << 6) /* Bit 6: Seed error interrupt status */ + +#endif /* __ARCH_ARM_STC_STM32F7_CHIP_STM32_RNG_H */ diff --git a/arch/arm/src/stm32f7/stm32_rng.c b/arch/arm/src/stm32f7/stm32_rng.c new file mode 100644 index 0000000000..8fb0f46685 --- /dev/null +++ b/arch/arm/src/stm32f7/stm32_rng.c @@ -0,0 +1,362 @@ +/**************************************************************************** + * arch/arm/src/stm32f7/stm32_rng.c + * + * Copyright (C) 2012 Max Holtzberg. All rights reserved. + * Author: Max Holtzberg + * mods for STL32L4 port by dev@ziggurat29.com + * + * 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 + +#include "up_arch.h" +#include "chip/stm32_rng.h" +#include "up_internal.h" + +#if defined(CONFIG_STM32F7_RNG) +#if defined(CONFIG_DEV_RANDOM) || defined(CONFIG_DEV_URANDOM_ARCH) + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static int stm32_rng_initialize(void); +static int stm32_rnginterrupt(int irq, void *context, FAR void *arg); +static void stm32_rngenable(void); +static void stm32_rngdisable(void); +static ssize_t stm32_rngread(struct file *filep, char *buffer, size_t); + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct rng_dev_s +{ + sem_t rd_devsem; /* Threads can only exclusively access the RNG */ + sem_t rd_readsem; /* To block until the buffer is filled */ + char *rd_buf; + size_t rd_buflen; + uint32_t rd_lastval; + bool rd_first; +}; + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static struct rng_dev_s g_rngdev; + +static const struct file_operations g_rngops = +{ + 0, /* open */ + 0, /* close */ + stm32_rngread, /* read */ + 0, /* write */ + 0, /* seek */ + 0 /* ioctl */ +#ifndef CONFIG_DISABLE_POLL + , 0 /* poll */ +#endif +#ifndef CONFIG_DISABLE_PSEUDOFS_OPERATIONS + , 0 /* unlink */ +#endif +}; + +/**************************************************************************** + * Private functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_rng_initialize + ****************************************************************************/ + +static int stm32_rng_initialize(void) +{ + _info("Initializing RNG\n"); + + memset(&g_rngdev, 0, sizeof(struct rng_dev_s)); + + sem_init(&g_rngdev.rd_devsem, 0, 1); + + if (irq_attach(STM32_IRQ_RNG, stm32_rnginterrupt, NULL)) + { + /* We could not attach the ISR to the interrupt */ + + _info("Could not attach IRQ.\n"); + + return -EAGAIN; + } + + return OK; +} + +/**************************************************************************** + * Name: stm32_rngenable + ****************************************************************************/ + +static void stm32_rngenable(void) +{ + uint32_t regval; + + g_rngdev.rd_first = true; + + /* Enable generation and interrupts */ + + regval = getreg32(STM32_RNG_CR); + regval |= RNG_CR_RNGEN; + regval |= RNG_CR_IE; + putreg32(regval, STM32_RNG_CR); + + up_enable_irq(STM32_IRQ_RNG); +} + +/**************************************************************************** + * Name: stm32_rngdisable + ****************************************************************************/ + +static void stm32_rngdisable(void) +{ + uint32_t regval; + + up_disable_irq(STM32_IRQ_RNG); + + regval = getreg32(STM32_RNG_CR); + regval &= ~RNG_CR_IE; + regval &= ~RNG_CR_RNGEN; + putreg32(regval, STM32_RNG_CR); +} + +/**************************************************************************** + * Name: stm32_rnginterrupt + ****************************************************************************/ + +static int stm32_rnginterrupt(int irq, void *context, FAR void *arg) +{ + uint32_t rngsr; + uint32_t data; + + rngsr = getreg32(STM32_RNG_SR); + if (rngsr & RNG_SR_CEIS) /* Check for clock error int stat */ + { + /* Clear it, we will try again. */ + + putreg32(rngsr & ~RNG_SR_CEIS, STM32_RNG_SR); + return OK; + } + + if (rngsr & RNG_SR_SEIS) /* Check for seed error in int stat */ + { + uint32_t crval; + + /* Clear seed error, then disable/enable the rng and try again. */ + + putreg32(rngsr & ~RNG_SR_SEIS, STM32_RNG_SR); + crval = getreg32(STM32_RNG_CR); + crval &= ~RNG_CR_RNGEN; + putreg32(crval, STM32_RNG_CR); + crval |= RNG_CR_RNGEN; + putreg32(crval, STM32_RNG_CR); + return OK; + } + + if (!(rngsr & RNG_SR_DRDY)) /* Data ready must be set */ + { + /* This random value is not valid, we will try again. */ + + return OK; + } + + data = getreg32(STM32_RNG_DR); + + /* As required by the FIPS PUB (Federal Information Processing Standard + * Publication) 140-2, the first random number generated after setting the + * RNGEN bit should not be used, but saved for comparison with the next + * generated random number. Each subsequent generated random number has to be + * compared with the previously generated number. The test fails if any two + * compared numbers are equal (continuous random number generator test). + */ + + if (g_rngdev.rd_first) + { + g_rngdev.rd_first = false; + g_rngdev.rd_lastval = data; + return OK; + } + + if (g_rngdev.rd_lastval == data) + { + /* Two subsequent same numbers, we will try again. */ + + return OK; + } + + /* If we get here, the random number is valid. */ + + g_rngdev.rd_lastval = data; + + if (g_rngdev.rd_buflen >= 4) + { + g_rngdev.rd_buflen -= 4; + *(uint32_t *)&g_rngdev.rd_buf[g_rngdev.rd_buflen] = data; + } + else + { + while (g_rngdev.rd_buflen > 0) + { + g_rngdev.rd_buf[--g_rngdev.rd_buflen] = (char)data; + data >>= 8; + } + } + + if (g_rngdev.rd_buflen == 0) + { + /* Buffer filled, stop further interrupts. */ + + stm32_rngdisable(); + sem_post(&g_rngdev.rd_readsem); + } + + return OK; +} + +/**************************************************************************** + * Name: stm32_rngread + ****************************************************************************/ + +static ssize_t stm32_rngread(struct file *filep, char *buffer, size_t buflen) +{ + if (sem_wait(&g_rngdev.rd_devsem) != OK) + { + return -errno; + } + else + { + /* We've got the device semaphore, proceed with reading */ + + /* Initialize the operation semaphore with 0 for blocking until the + * buffer is filled from interrupts. The readsem semaphore is used + * for signaling and, hence, should not have priority inheritance + * enabled. + */ + + sem_init(&g_rngdev.rd_readsem, 0, 0); + sem_setprotocol(&g_rngdev.rd_readsem, SEM_PRIO_NONE); + + g_rngdev.rd_buflen = buflen; + g_rngdev.rd_buf = buffer; + + /* Enable RNG with interrupts */ + + stm32_rngenable(); + + /* Wait until the buffer is filled */ + + sem_wait(&g_rngdev.rd_readsem); + + /* Done with the operation semaphore */ + + sem_destroy(&g_rngdev.rd_readsem); + + /* Free RNG via the device semaphore for next use */ + + sem_post(&g_rngdev.rd_devsem); + + return buflen; + } +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: devrandom_register + * + * Description: + * Initialize the RNG hardware and register the /dev/random driver. + * Must be called BEFORE devurandom_register. + * + * Input Parameters: + * None + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_DEV_RANDOM +void devrandom_register(void) +{ + stm32_rng_initialize(); + (void)register_driver("/dev/random", &g_rngops, 0444, NULL); +} +#endif + +/**************************************************************************** + * Name: devurandom_register + * + * Description: + * Register /dev/urandom + * + * Input Parameters: + * None + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_DEV_URANDOM_ARCH +void devurandom_register(void) +{ +#ifndef CONFIG_DEV_RANDOM + stm32_rng_initialize(); +#endif + (void)register_driver("/dev/urandom", &g_rngops, 0444, NULL); +} +#endif + +#endif /* CONFIG_DEV_RANDOM || CONFIG_DEV_URANDOM_ARCH */ +#endif /* CONFIG_STM32F7_RNG */ diff --git a/arch/arm/src/stm32l4/stm32l4_rng.c b/arch/arm/src/stm32l4/stm32l4_rng.c index dd0f782f2d..3334d86ec0 100644 --- a/arch/arm/src/stm32l4/stm32l4_rng.c +++ b/arch/arm/src/stm32l4/stm32l4_rng.c @@ -145,7 +145,7 @@ static void stm32l4_rngenable(void) up_enable_irq(STM32L4_IRQ_RNG); } -static void stm32l4_rngdisable() +static void stm32l4_rngdisable(void) { uint32_t regval; @@ -261,7 +261,7 @@ static ssize_t stm32l4_rngread(struct file *filep, char *buffer, size_t buflen) /* We've got the device semaphore, proceed with reading */ /* Initialize the operation semaphore with 0 for blocking until the - * buffer is filled from interrupts. The waitsem semaphore is used + * buffer is filled from interrupts. The readsem semaphore is used * for signaling and, hence, should not have priority inheritance * enabled. */ -- GitLab From 5577f5845839913f22936fe2c77622a38ed8eb6d Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Wed, 29 Mar 2017 07:12:19 -0600 Subject: [PATCH 258/990] STM32 RNG: Fix semaphore initial value and disable priority inheritance --- arch/arm/src/stm32/stm32_rng.c | 35 ++++++++++++++++++++++++++++------ 1 file changed, 29 insertions(+), 6 deletions(-) diff --git a/arch/arm/src/stm32/stm32_rng.c b/arch/arm/src/stm32/stm32_rng.c index ccbbd96dd7..6588814d6c 100644 --- a/arch/arm/src/stm32/stm32_rng.c +++ b/arch/arm/src/stm32/stm32_rng.c @@ -46,6 +46,7 @@ #include #include +#include #include #include @@ -97,13 +98,20 @@ static const struct file_operations g_rngops = #ifndef CONFIG_DISABLE_POLL , 0 /* poll */ #endif +#ifndef CONFIG_DISABLE_PSEUDOFS_OPERATIONS + , 0 /* unlink */ +#endif }; /**************************************************************************** * Private functions ****************************************************************************/ -static int stm32_rng_initialize() +/**************************************************************************** + * Name: stm32_rng_initialize + ****************************************************************************/ + +static int stm32_rng_initialize(void) { uint32_t regval; @@ -133,7 +141,11 @@ static int stm32_rng_initialize() return OK; } -static void stm32_enable() +/**************************************************************************** + * Name: stm32_enable + ****************************************************************************/ + +static void stm32_enable(void) { uint32_t regval; @@ -144,7 +156,11 @@ static void stm32_enable() putreg32(regval, STM32_RNG_CR); } -static void stm32_disable() +/**************************************************************************** + * Name: stm32_disable + ****************************************************************************/ + +static void stm32_disable(void) { uint32_t regval; regval = getreg32(STM32_RNG_CR); @@ -152,6 +168,10 @@ static void stm32_disable() putreg32(regval, STM32_RNG_CR); } +/**************************************************************************** + * Name: stm32_interrupt + ****************************************************************************/ + static int stm32_interrupt(int irq, void *context, FAR void *arg) { uint32_t rngsr; @@ -234,11 +254,14 @@ static ssize_t stm32_read(struct file *filep, char *buffer, size_t buflen) { /* We've got the semaphore. */ - /* Initialize semaphore with 0 for blocking until the buffer is filled from - * interrupts. + /* Initialize the operation semaphore with 0 for blocking until the + * buffer is filled from interrupts. The readsem semaphore is used + * for signaling and, hence, should not have priority inheritance + * enabled. */ - sem_init(&g_rngdev.rd_readsem, 0, 1); + sem_init(&g_rngdev.rd_readsem, 0, 0); + sem_setprotocol(&g_rngdev.rd_readsem, SEM_PRIO_NONE); g_rngdev.rd_buflen = buflen; g_rngdev.rd_buf = buffer; -- GitLab From 28e74ec058e07c8b49f6f253a7a3ab9cb568a365 Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Wed, 29 Mar 2017 07:16:27 -0600 Subject: [PATCH 259/990] Nucleo L476RG: More naming fixes. --- configs/nucleo-l476rg/src/nucleo-l476rg.h | 22 +++++++++++----------- configs/nucleo-l476rg/src/stm32_appinit.c | 10 +++++----- configs/nucleo-l476rg/src/stm32_boot.c | 10 +++++----- 3 files changed, 21 insertions(+), 21 deletions(-) diff --git a/configs/nucleo-l476rg/src/nucleo-l476rg.h b/configs/nucleo-l476rg/src/nucleo-l476rg.h index e82283b177..a6f676da54 100644 --- a/configs/nucleo-l476rg/src/nucleo-l476rg.h +++ b/configs/nucleo-l476rg/src/nucleo-l476rg.h @@ -71,7 +71,7 @@ # undef HAVE_RTC_DRIVER #endif -#if !defined(CONFIG_STM32_SDIO) || !defined(CONFIG_MMCSD) || \ +#if !defined(CONFIG_STM32L4_SDIO) || !defined(CONFIG_MMCSD) || \ !defined(CONFIG_MMCSD_SDIO) # undef HAVE_MMCSD #endif @@ -293,10 +293,10 @@ /* Global driver instances */ -#ifdef CONFIG_STM32_SPI1 +#ifdef CONFIG_STM32L4_SPI1 extern struct spi_dev_s *g_spi1; #endif -#ifdef CONFIG_STM32_SPI2 +#ifdef CONFIG_STM32L4_SPI2 extern struct spi_dev_s *g_spi2; #endif #ifdef HAVE_MMCSD @@ -308,27 +308,27 @@ extern struct sdio_dev_s *g_sdio; ************************************************************************************/ /************************************************************************************ - * Name: stm32_spiinitialize + * Name: stm32l4_spiinitialize * * Description: * Called to configure SPI chip select GPIO pins. * ************************************************************************************/ -void stm32_spiinitialize(void); +void stm32l4_spiinitialize(void); /************************************************************************************ - * Name: stm32_usbinitialize + * Name: stm32l4_usbinitialize * * Description: * Called to setup USB-related GPIO pins. * ************************************************************************************/ -void stm32_usbinitialize(void); +void stm32l4_usbinitialize(void); /************************************************************************************ - * Name: stm32_pwm_setup + * Name: stm32l4_pwm_setup * * Description: * Initialize PWM and register the PWM device. @@ -336,11 +336,11 @@ void stm32_usbinitialize(void); ************************************************************************************/ #ifdef CONFIG_PWM -int stm32_pwm_setup(void); +int stm32l4_pwm_setup(void); #endif /************************************************************************************ - * Name: stm32_adc_setup + * Name: stm32l4_adc_setup * * Description: * Initialize ADC and register the ADC driver. @@ -348,7 +348,7 @@ int stm32_pwm_setup(void); ************************************************************************************/ #ifdef CONFIG_ADC -int stm32_adc_setup(void); +int stm32l4_adc_setup(void); #endif /**************************************************************************** diff --git a/configs/nucleo-l476rg/src/stm32_appinit.c b/configs/nucleo-l476rg/src/stm32_appinit.c index 41b54976ae..ceaa3a76f5 100644 --- a/configs/nucleo-l476rg/src/stm32_appinit.c +++ b/configs/nucleo-l476rg/src/stm32_appinit.c @@ -1,5 +1,5 @@ /**************************************************************************** - * configs/nucleo-l476rg/src/stm32_appinit.c + * configs/nucleo-l476rg/src/stm32l4_appinit.c * * Copyright (C) 2016 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -199,20 +199,20 @@ int board_app_initialize(uintptr_t arg) #ifdef CONFIG_PWM /* Initialize PWM and register the PWM device. */ - ret = stm32_pwm_setup(); + ret = stm32l4_pwm_setup(); if (ret < 0) { - syslog(LOG_ERR, "ERROR: stm32_pwm_setup() failed: %d\n", ret); + syslog(LOG_ERR, "ERROR: stm32l4_pwm_setup() failed: %d\n", ret); } #endif #ifdef CONFIG_ADC /* Initialize ADC and register the ADC driver. */ - ret = stm32_adc_setup(); + ret = stm32l4_adc_setup(); if (ret < 0) { - syslog(LOG_ERR, "ERROR: stm32_adc_setup failed: %d\n", ret); + syslog(LOG_ERR, "ERROR: stm32l4_adc_setup failed: %d\n", ret); } #endif diff --git a/configs/nucleo-l476rg/src/stm32_boot.c b/configs/nucleo-l476rg/src/stm32_boot.c index 0389d18cf1..2acb52ee62 100644 --- a/configs/nucleo-l476rg/src/stm32_boot.c +++ b/configs/nucleo-l476rg/src/stm32_boot.c @@ -1,5 +1,5 @@ /************************************************************************************ - * configs/nucleo-l476rg/src/stm32_boot.c + * configs/nucleo-l476rg/src/stm32l4_boot.c * * Copyright (C) 2014-2015 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -82,19 +82,19 @@ void stm32l4_boardinitialize(void) #endif /* Configure SPI chip selects if 1) SP2 is not disabled, and 2) the weak function - * stm32_spiinitialize() has been brought into the link. + * stm32l4_spiinitialize() has been brought into the link. */ -#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || defined(CONFIG_STM32_SPI3) +#if defined(CONFIG_STM32L4_SPI1) || defined(CONFIG_STM32L4_SPI2) || defined(CONFIG_STM32L4_SPI3) stm32l4_spiinitialize(); #endif /* Initialize USB is 1) USBDEV is selected, 2) the USB controller is not - * disabled, and 3) the weak function stm32_usbinitialize() has been brought + * disabled, and 3) the weak function stm32l4_usbinitialize() has been brought * into the build. */ -#if defined(CONFIG_USBDEV) && defined(CONFIG_STM32_USB) +#if defined(CONFIG_USBDEV) && defined(CONFIG_STM32L4_USB) stm32l4_usbinitialize(); #endif } -- GitLab From eb344d7260731d850b64a201ed085496c4dce0cf Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 29 Mar 2017 07:50:40 -0600 Subject: [PATCH 260/990] Fix an assertion noted by Jussi Kivilinna. This was a consequence of the recent robust mutex changes. If robust mutexes are selected, then each mutex that a thread takes is retained in a list in threads TCB. If the thread exits and that list is not empty, then we know that the thread exitted while holding mutexes. And, in that case, each will be marked as inconsistent and the any waiter for the thread is awakened. For the case of pthread_mutex_trywait(), the mutex was not being added to the list! while not usually a fatal error, this was caught by an assertion when pthread_mutex_unlock() was called: It tried to remove the mutex from the TCB list and it was not there when, of course, it shoule be. The fix was to add pthread_mutex_trytake() which does sem_trywait() and if successful, does correctly add the mutext to the TCB list. This should eliminated the assertion. --- sched/pthread/pthread.h | 6 +- sched/pthread/pthread_mutex.c | 141 +++++++++++++++++++++++---- sched/pthread/pthread_mutextrylock.c | 111 ++++++++++----------- 3 files changed, 177 insertions(+), 81 deletions(-) diff --git a/sched/pthread/pthread.h b/sched/pthread/pthread.h index bc0238c903..b4e87d9533 100644 --- a/sched/pthread/pthread.h +++ b/sched/pthread/pthread.h @@ -112,11 +112,13 @@ int pthread_givesemaphore(sem_t *sem); #ifndef CONFIG_PTHREAD_MUTEX_UNSAFE int pthread_mutex_take(FAR struct pthread_mutex_s *mutex, bool intr); +int pthread_mutex_trytake(FAR struct pthread_mutex_s *mutex); int pthread_mutex_give(FAR struct pthread_mutex_s *mutex); void pthread_mutex_inconsistent(FAR struct pthread_tcb_s *tcb); #else -# define pthread_mutex_take(m,i) pthread_takesemaphore(&(m)->sem,(i)) -# define pthread_mutex_give(m) pthread_givesemaphore(&(m)->sem) +# define pthread_mutex_take(m,i) pthread_takesemaphore(&(m)->sem,(i)) +# define pthread_mutex_trytake(m) sem_trywait(&(m)->sem) +# define pthread_mutex_give(m) pthread_givesemaphore(&(m)->sem) #endif #ifdef CONFIG_PTHREAD_MUTEX_TYPES diff --git a/sched/pthread/pthread_mutex.c b/sched/pthread/pthread_mutex.c index 03bf35ea49..f11a5b01f6 100644 --- a/sched/pthread/pthread_mutex.c +++ b/sched/pthread/pthread_mutex.c @@ -50,6 +50,39 @@ #include "sched/sched.h" #include "pthread/pthread.h" +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: pthread_mutex_add + * + * Description: + * Add the mutex to the list of mutexes held by this thread. + * + * Parameters: + * mutex - The mux to be locked + * + * Return Value: + * None + * + ****************************************************************************/ + +static void pthread_mutex_add(FAR struct pthread_mutex_s *mutex) +{ + FAR struct pthread_tcb_s *rtcb = (FAR struct pthread_tcb_s *)this_task(); + irqstate_t flags; + + DEBUGASSERT(mutex->flink == NULL); + + /* Add the mutex to the list of mutexes held by this task */ + + flags = enter_critical_section(); + mutex->flink = rtcb->mhead; + rtcb->mhead = mutex; + leave_critical_section(flags); +} + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -58,8 +91,8 @@ * Name: pthread_mutex_take * * Description: - * Take the pthread_mutex and, if successful, add the mutex to the ist of - * mutexes held by this thread. + * Take the pthread_mutex, waiting if necessary. If successful, add the + * mutex to the list of mutexes held by this thread. * * Parameters: * mutex - The mux to be locked @@ -84,38 +117,104 @@ int pthread_mutex_take(FAR struct pthread_mutex_s *mutex, bool intr) sched_lock(); - /* Take semaphore underlying the mutex */ + /* Error out if the mutex is already in an inconsistent state. */ - ret = pthread_takesemaphore(&mutex->sem, intr); - if (ret == OK) + if ((mutex->flags & _PTHREAD_MFLAGS_INCONSISTENT) != 0) { - DEBUGASSERT(mutex->flink == NULL); - - /* Check if the holder of the mutex has terminated. In that case, - * the state of the mutex is inconsistent and we return EOWNERDEAD. - */ + ret = EOWNERDEAD; + } + else + { + /* Take semaphore underlying the mutex */ - if ((mutex->flags & _PTHREAD_MFLAGS_INCONSISTENT) != 0) + ret = pthread_takesemaphore(&mutex->sem, intr); + if (ret < OK) { - ret = EOWNERDEAD; + ret = get_errno(); } + else + { + /* Check if the holder of the mutex has terminated without + * releasing. In that case, the state of the mutex is + * inconsistent and we return EOWNERDEAD. + */ + + if ((mutex->flags & _PTHREAD_MFLAGS_INCONSISTENT) != 0) + { + ret = EOWNERDEAD; + } + + /* Add the mutex to the list of mutexes held by this task */ + + else + { + pthread_mutex_add(mutex); + } + } + } + + sched_unlock(); + } + + return ret; +} - /* Add the mutex to the list of mutexes held by this task */ +/**************************************************************************** + * Name: pthread_mutex_trytake + * + * Description: + * Try to take the pthread_mutex without waiting. If successful, add the + * mutex to the list of mutexes held by this thread. + * + * Parameters: + * mutex - The mux to be locked + * intr - false: ignore EINTR errors when locking; true tread EINTR as + * other errors by returning the errno value + * + * Return Value: + * 0 on success or an errno value on failure. + * + ****************************************************************************/ + +int pthread_mutex_trytake(FAR struct pthread_mutex_s *mutex) +{ + int ret = EINVAL; + + /* Verify input parameters */ + DEBUGASSERT(mutex != NULL); + if (mutex != NULL) + { + /* Make sure that no unexpected context switches occur */ + + sched_lock(); + + /* Error out if the mutex is already in an inconsistent state. */ + + if ((mutex->flags & _PTHREAD_MFLAGS_INCONSISTENT) != 0) + { + ret = EOWNERDEAD; + } + else + { + /* Try to take the semaphore underlying the mutex */ + + ret = sem_trywait(&mutex->sem); + if (ret < OK) + { + ret = get_errno(); + } else { - FAR struct pthread_tcb_s *rtcb = (FAR struct pthread_tcb_s *)this_task(); - irqstate_t flags; + /* Add the mutex to the list of mutexes held by this task */ - flags = enter_critical_section(); - mutex->flink = rtcb->mhead; - rtcb->mhead = mutex; - leave_critical_section(flags); + pthread_mutex_add(mutex); } } + + sched_unlock(); } - sched_unlock(); return ret; } @@ -173,7 +272,7 @@ int pthread_mutex_give(FAR struct pthread_mutex_s *mutex) mutex->flink = NULL; leave_critical_section(flags); - + /* Now release the underlying semaphore */ ret = pthread_givesemaphore(&mutex->sem); diff --git a/sched/pthread/pthread_mutextrylock.c b/sched/pthread/pthread_mutextrylock.c index 9083fd465a..f4cda697b7 100644 --- a/sched/pthread/pthread_mutextrylock.c +++ b/sched/pthread/pthread_mutextrylock.c @@ -102,7 +102,7 @@ int pthread_mutex_trylock(FAR pthread_mutex_t *mutex) /* Try to get the semaphore. */ - status = sem_trywait((FAR sem_t *)&mutex->sem); + status = pthread_mutex_trytake(mutex); if (status == OK) { /* If we successfully obtained the semaphore, then indicate @@ -120,96 +120,91 @@ int pthread_mutex_trylock(FAR pthread_mutex_t *mutex) ret = OK; } - /* sem_trywait failed */ + /* pthread_mutex_trytake failed. Did it fail because the semaphore + * was not avaialable? + */ - else + else if (status == EAGAIN) { - /* Did it fail because the semaphore was not avaialable? */ +#ifdef CONFIG_PTHREAD_MUTEX_TYPES + /* Check if recursive mutex was locked by the calling thread. */ - int errcode = get_errno(); - if (errcode == EAGAIN) + if (mutex->type == PTHREAD_MUTEX_RECURSIVE && mutex->pid == mypid) { -#ifdef CONFIG_PTHREAD_MUTEX_TYPES - /* Check if recursive mutex was locked by the calling thread. */ + /* Increment the number of locks held and return successfully. */ - if (mutex->type == PTHREAD_MUTEX_RECURSIVE && mutex->pid == mypid) + if (mutex->nlocks < INT16_MAX) { - /* Increment the number of locks held and return successfully. */ - - if (mutex->nlocks < INT16_MAX) - { - mutex->nlocks++; - ret = OK; - } - else - { - ret = EOVERFLOW; - } + mutex->nlocks++; + ret = OK; } else + { + ret = EOVERFLOW; + } + } + else #endif #ifndef CONFIG_PTHREAD_MUTEX_UNSAFE - /* The calling thread does not hold the semaphore. The correct - * behavior for the 'robust' mutex is to verify that the holder of - * the mutex is still valid. This is protection from the case - * where the holder of the mutex has exitted without unlocking it. - */ + /* The calling thread does not hold the semaphore. The correct + * behavior for the 'robust' mutex is to verify that the holder of + * the mutex is still valid. This is protection from the case + * where the holder of the mutex has exitted without unlocking it. + */ #ifdef CONFIG_PTHREAD_MUTEX_BOTH #ifdef CONFIG_PTHREAD_MUTEX_TYPES - /* Check if this NORMAL mutex is robust */ + /* Check if this NORMAL mutex is robust */ - if (mutex->pid > 0 && - ((mutex->flags & _PTHREAD_MFLAGS_ROBUST) != 0 || - mutex->type != PTHREAD_MUTEX_NORMAL) && - sched_gettcb(mutex->pid) == NULL) + if (mutex->pid > 0 && + ((mutex->flags & _PTHREAD_MFLAGS_ROBUST) != 0 || + mutex->type != PTHREAD_MUTEX_NORMAL) && + sched_gettcb(mutex->pid) == NULL) #else /* CONFIG_PTHREAD_MUTEX_TYPES */ - /* Check if this NORMAL mutex is robust */ + /* Check if this NORMAL mutex is robust */ - if (mutex->pid > 0 && - (mutex->flags & _PTHREAD_MFLAGS_ROBUST) != 0 && - sched_gettcb(mutex->pid) == NULL) + if (mutex->pid > 0 && + (mutex->flags & _PTHREAD_MFLAGS_ROBUST) != 0 && + sched_gettcb(mutex->pid) == NULL) #endif /* CONFIG_PTHREAD_MUTEX_TYPES */ #else /* CONFIG_PTHREAD_MUTEX_ROBUST */ - /* This mutex is always robust, whatever type it is. */ + /* This mutex is always robust, whatever type it is. */ - if (mutex->pid > 0 && sched_gettcb(mutex->pid) == NULL) + if (mutex->pid > 0 && sched_gettcb(mutex->pid) == NULL) #endif - { - DEBUGASSERT(mutex->pid != 0); /* < 0: available, >0 owned, ==0 error */ - DEBUGASSERT((mutex->flags & _PTHREAD_MFLAGS_INCONSISTENT) != 0); - - /* A thread holds the mutex, but there is no such thread. - * POSIX requires that the 'robust' mutex return EOWNERDEAD - * in this case. It is then the caller's responsibility to - * call pthread_mutx_consistent() fo fix the mutex. - */ - - mutex->flags |= _PTHREAD_MFLAGS_INCONSISTENT; - ret = EOWNERDEAD; - } - - /* The mutex is locked by another, active thread */ + { + DEBUGASSERT(mutex->pid != 0); /* < 0: available, >0 owned, ==0 error */ + DEBUGASSERT((mutex->flags & _PTHREAD_MFLAGS_INCONSISTENT) != 0); - else -#endif /* CONFIG_PTHREAD_MUTEX_UNSAFE */ + /* A thread holds the mutex, but there is no such thread. + * POSIX requires that the 'robust' mutex return EOWNERDEAD + * in this case. It is then the caller's responsibility to + * call pthread_mutx_consistent() fo fix the mutex. + */ - { - ret = EBUSY; - } + mutex->flags |= _PTHREAD_MFLAGS_INCONSISTENT; + ret = EOWNERDEAD; } - /* Some other, unhandled error occurred */ + /* The mutex is locked by another, active thread */ else +#endif /* CONFIG_PTHREAD_MUTEX_UNSAFE */ { - ret = errcode; + ret = EBUSY; } } + /* Some other, unhandled error occurred */ + + else + { + ret = status; + } + sched_unlock(); } -- GitLab From 5fb222180c861aa78be465967fdc4ae956dffbd8 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 29 Mar 2017 10:17:34 -0600 Subject: [PATCH 261/990] 6loWPAN: IEEE802.15.4 MAC driver will need a special form of the network device structure to manage fragmentation of the large packet into frames. --- configs/samv71-xult/netnsh/defconfig | 6 ++- include/nuttx/net/sixlowpan.h | 80 +++++++++++++++++----------- net/netdev/netdev_register.c | 2 +- net/sixlowpan/Kconfig | 8 +++ net/sixlowpan/sixlowpan_send.c | 28 +++++++--- 5 files changed, 85 insertions(+), 39 deletions(-) diff --git a/configs/samv71-xult/netnsh/defconfig b/configs/samv71-xult/netnsh/defconfig index b651274195..395fe4df82 100644 --- a/configs/samv71-xult/netnsh/defconfig +++ b/configs/samv71-xult/netnsh/defconfig @@ -96,6 +96,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -107,7 +108,7 @@ CONFIG_ARCH_CHIP_SAMV7=y # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -457,6 +458,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -1160,6 +1163,7 @@ CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index 4887d255f0..be7f9f1e36 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -50,8 +50,11 @@ ****************************************************************************/ #include + #include +#include + /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ @@ -223,51 +226,66 @@ (((a)->u16[6]) == 0) && \ (((a)->u8[14]) == 0)) -/* Maximum size of an IEEE802.15.4 frame */ +/* This maximum size of an IEEE802.15.4 frame. Certain, non-standard + * devices may exceed this value, however. + */ -#define SIXLOWPAN_MAC_MAXFRAME 127 +#define SIXLOWPAN_MAC_STDFRAME 127 /**************************************************************************** * Public Types ****************************************************************************/ -/* The header for fragments +/* The device structure for IEEE802.15.4 MAC network device differs from the + * standard Ethernet MAC device structure. The main reason for this + * difference is that fragmentation must be supported. + * + * The IEEE802.15.4 MAC does not use the d_buf packet buffer directly. + * Rather, it uses a smaller frame buffer. The packet data is provided to + * the frame buffer each time that the IEEE802.15.4 MAC needs to send + * more data. * - * NOTE: We do not define different structures for FRAG1 and FRAGN headers, - * which are different. For FRAG1, the offset field is just not used + * This is accomplished by "inheriting" the standard 'struct net_driver_s' + * and appending the frame buffer as well as other metadata needed to + * manage the fragmentation. 'struct ieee802154_driver_s' is cast + * compatible with 'struct net_driver_s' when CONFIG_NET_MULTINIC is not + * defined or when dev->d_lltype == NET_LL_IEEE802154. */ -struct sixlowpan_frag_hdr +struct ieee802154_driver_s { - uint16_t dispatch_size; - uint16_t tag; - uint8_t offset; -}; + /* This definitiona must appear first in the structure definition to + * assure cast compatibility. + */ -/* The HC1 header when HC_UDP is not used - * - * When all fields are compressed and HC_UDP is not used, we use this - * structure. If HC_UDP is used, the ttl is in another spot, and we use the - * sixlowpan_hc1_hc_udp structure - */ + struct net_driver_s i_dev; -struct sixlowpan_hc1hdr_s -{ - uint8_t dispatch; - uint8_t encoding; - uint8_t ttl; -}; + /* IEEE802.15.4 MAC-specific definitions follow. */ -/* HC1 followed by HC_UDP */ + /* The i_frame array is used to hold outgoing frame. When the + * IEEE802.15.4 device polls for new data, the outgoing frame containing + * the next fragment is placed in i_frame. + * + * The network will handle only a single outgong frame at a time. The + * IEEE802.15.4 MAC driver design may be concurrently sending and + * requesting new framesusing break-off fram buffers. That frame buffer + * management must be controlled by the IEEE802.15.4 MAC driver. + * + * Driver provied frame buffers should be 16-bit aligned. + */ -struct sixlowpan_hc1_hcudp_hdr_s -{ - uint8_t dispatch; - uint8_t hc1_encoding; - uint8_t hc_udp_encoding; - uint8_t ttl; - uint8_t ports; - uint16_t udpchksum; + FAR uint8_t *i_frame; + + /* The length of valid data in the i_frame buffer. + * + * When the network device driver calls the network input function, + * i_framelen should be set to zero. If there is frame to be sent + * by the network, i_framelen will be set to indicate the size of + * frame to be sent. The value zero means that there is no frame + * to be sent. + */ + + uint16_t i_framelen; }; /* The structure of a next header compressor. This compressor is provided diff --git a/net/netdev/netdev_register.c b/net/netdev/netdev_register.c index 9a3a01c66d..4dda608c1a 100644 --- a/net/netdev/netdev_register.c +++ b/net/netdev/netdev_register.c @@ -230,7 +230,7 @@ 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 = SIXLOWPAN_MAC_MAXFRAME; + dev->d_mtu = CONFIG_NET_6LOWPAN_FRAMELEN; #ifdef CONFIG_NET_TCP dev->d_recvwndo = CONFIG_NET_6LOWPAN_TCP_RECVWNDO; #endif diff --git a/net/sixlowpan/Kconfig b/net/sixlowpan/Kconfig index 1a3882d1ad..84cb1c6652 100644 --- a/net/sixlowpan/Kconfig +++ b/net/sixlowpan/Kconfig @@ -20,6 +20,14 @@ config NET_6LOWPAN_FRAG CONFIG_NET_6LOWPAN_FRAG specifies if 6lowpan fragmentation should be used or not. Fragmentation is on by default. +config NET_6LOWPAN_FRAMELEN + int "IEEE802.15.4 MAC Frame Length" + default 127 + range 127 999999 + ---help--- + Some wireless devices may use non-standard frame lengths. This + setting should never be smaller than 127. + choice prompt "6loWPAN Compression" default NET_6LOWPAN_COMPRESSION_HC06 diff --git a/net/sixlowpan/sixlowpan_send.c b/net/sixlowpan/sixlowpan_send.c index de33894597..b85c685f42 100644 --- a/net/sixlowpan/sixlowpan_send.c +++ b/net/sixlowpan/sixlowpan_send.c @@ -54,6 +54,7 @@ #ifdef CONFIG_NET_6LOWPAN + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -62,11 +63,20 @@ * Name: sixlowpan_send * * Description: - * Process an outgoing UDP or TCP packet. Called from UDP/TCP logic to - * determine if the the packet should be formatted for 6loWPAN output. + * Process an outgoing UDP or TCP packet. Takes an IP packet and formats + * it to be sent on an 802.15.4 network using 6lowpan. Called from common + * UDP/TCP send logic. + * + * The payload data is in the caller 'buf' and is of length 'len'. + * Compressed headers will be added and if necessary the packet is + * fragmented. The resulting packet/fragments are put in dev->d_buf and + * the first frame will be delivered to the 802.15.4 MAC. via ieee->i_frame. + * + * Input Parmeters: * * Input Parameters: - * dev - The IEEE802.15.4 MAC network driver interface. + * dev - The IEEE802.15.4 MAC network driver interface. + * raddr - The MAC address of the destination * * Returned Value: * Ok is returned on success; Othewise a negated errno value is returned. @@ -79,8 +89,10 @@ * ****************************************************************************/ -int sixlowpan_send(FAR struct net_driver_s *dev) +int sixlowpan_send(FAR struct net_driver_s *dev, net_ipv6addr_t raddr) { + FAR struct ieee802154_driver_s *ieee = (FAR struct ieee802154_driver_s *)dev; + net_lock(); /* REVISIT: To be provided */ net_unlock(); @@ -143,6 +155,7 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, conn = (FAR struct tcp_conn_s *)psock->s_conn; DEBUGASSERT(conn != NULL); +#if defined(CONFIG_NET_IPv4) && defined(CONFIG_NET_IPv6) /* Ignore if not IPv6 domain */ if (conn->domain != PF_INET6) @@ -150,6 +163,7 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, nwarn("WARNING: Not IPv6\n"); return (ssize_t)-EPROTOTYPE; } +#endif /* Route outgoing message to the correct device */ @@ -188,7 +202,7 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, * packet. */ - ret = sixlowpan_send(dev); + ret = sixlowpan_send(dev, conn->u.ipv6.raddr); if (ret < 0) { nerr("ERROR: sixlowpan_send() failed: %d\n", ret); @@ -251,6 +265,7 @@ ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, conn = (FAR struct udp_conn_s *)psock->s_conn; DEBUGASSERT(conn != NULL); +#if defined(CONFIG_NET_IPv4) && defined(CONFIG_NET_IPv6) /* Ignore if not IPv6 domain */ if (conn->domain != PF_INET6) @@ -258,6 +273,7 @@ ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, nwarn("WARNING: Not IPv6\n"); return (ssize_t)-EPROTOTYPE; } +#endif /* Route outgoing message to the correct device */ @@ -296,7 +312,7 @@ ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, * packet. */ - ret = sixlowpan_send(dev); + ret = sixlowpan_send(dev, conn->u.ipv6.raddr); if (ret < 0) { nerr("ERROR: sixlowpan_send() failed: %d\n", ret); -- GitLab From 8f67ec30a76d3a4cb4e5c201272bb7c5a814ffd4 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Wed, 29 Mar 2017 12:39:52 -0400 Subject: [PATCH 262/990] wireless/ieee802154: Removes ieee802154.h and makes other minor changes --- drivers/wireless/ieee802154/at86rf23x.c | 2 +- drivers/wireless/ieee802154/mrf24j40.c | 2 +- .../nuttx/wireless/ieee802154/ieee802154.h | 112 ----------------- .../wireless/ieee802154/ieee802154_mac.h | 118 +++++++++++++++--- .../wireless/ieee802154/ieee802154_radio.h | 9 +- wireless/ieee802154/mac802154.c | 2 +- 6 files changed, 110 insertions(+), 135 deletions(-) delete mode 100644 include/nuttx/wireless/ieee802154/ieee802154.h diff --git a/drivers/wireless/ieee802154/at86rf23x.c b/drivers/wireless/ieee802154/at86rf23x.c index 45094e99ff..7b6193c0aa 100644 --- a/drivers/wireless/ieee802154/at86rf23x.c +++ b/drivers/wireless/ieee802154/at86rf23x.c @@ -56,7 +56,7 @@ #include #include -#include + #include #include "at86rf23x.h" diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c index 300e0d50e5..9ede37739e 100644 --- a/drivers/wireless/ieee802154/mrf24j40.c +++ b/drivers/wireless/ieee802154/mrf24j40.c @@ -1099,7 +1099,7 @@ static int mrf24j40_transmit(FAR struct ieee802154_radio_s *ieee, hlen += 2 + 8; /* Destination PAN + extaddr */ } - if (!(frame_ctrl & IEEE802154_FRAMECTRL_INTRA)) + if (!(frame_ctrl & IEEE802154_FRAMECTRL_PANIDCOMP)) { hlen += 2; /* No PAN compression, source PAN is different from dest PAN */ } diff --git a/include/nuttx/wireless/ieee802154/ieee802154.h b/include/nuttx/wireless/ieee802154/ieee802154.h deleted file mode 100644 index 38410a622f..0000000000 --- a/include/nuttx/wireless/ieee802154/ieee802154.h +++ /dev/null @@ -1,112 +0,0 @@ -/**************************************************************************** - * include/nuttx/wireless/ieee802154/ieee802154.h - * - * Copyright (C) 2014-2016 Sebastien Lorquet. All rights reserved. - * Copyright (C) 2017 Verge Inc. All rights reserved. - * Author: Sebastien Lorquet - * Author: Anthony Merlino - * - * 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_WIRELESS_IEEE802154_IEEE802154_H -#define __INCLUDE_NUTTX_WIRELESS_IEEE802154_IEEE802154_H - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include -#include - -/**************************************************************************** - * Pre-Processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Public Types - ****************************************************************************/ - -struct ieee802154_packet_s -{ - uint8_t len; - uint8_t data[127]; - uint8_t lqi; - uint8_t rssi; -}; - -/* IEEE 802.15.4 Device address - * The addresses in ieee802154 have several formats: - * No address : [none] - * Short address + PAN id : PPPP/SSSS - * Extended address + PAN id : PPPP/LLLLLLLLLLLLLLLL - */ - -enum ieee802154_addr_mode_e -{ - IEEE802154_ADDRMODE_NONE = 0, - IEEE802154_ADDRMODE_SHORT = 2, - IEEE802154_ADDRMODE_EXTENDED -}; - -struct ieee802154_addr_s -{ - enum ieee802154_addr_mode_e ia_mode; /* Address mode. Short or Extended */ - uint16_t ia_panid; /* PAN identifier, can be IEEE802154_PAN_UNSPEC */ - union - { - uint16_t _ia_saddr; /* short address */ - uint8_t _ia_eaddr[8]; /* extended address */ - } ia_addr; - -#define ia_saddr ia_addr._ia_saddr -#define ia_eaddr ia_addr._ia_eaddr -}; - -#define IEEE802154_ADDRSTRLEN 22 /* (2*2+1+8*2, PPPP/EEEEEEEEEEEEEEEE) */ - -#ifdef __cplusplus -#define EXTERN extern "C" -extern "C" -{ -#else -#define EXTERN extern -#endif - -/**************************************************************************** - * Public Function Prototypes - ****************************************************************************/ - -#undef EXTERN -#ifdef __cplusplus -} -#endif - -#endif /* __INCLUDE_NUTTX_WIRELESS_IEEE802154_IEEE802154_H*/ diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index 1b43c3c3bb..10f691a9b2 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -46,7 +46,6 @@ #include #include -#include /**************************************************************************** * Pre-Processor Definitions @@ -123,23 +122,23 @@ * Seee IEEE 802.15.4/2011 5.2.1.1 page 57 */ -#define IEEE802154_FRAMECTRL_FTYPE 0x0007 /* Frame type, bits 0-2 */ -#define IEEE802154_FRAMECTRL_SEC 0x0008 /* Security Enabled, bit 3 */ -#define IEEE802154_FRAMECTRL_PEND 0x0010 /* Frame pending, bit 4 */ -#define IEEE802154_FRAMECTRL_ACKREQ 0x0020 /* Acknowledge request, bit 5 */ -#define IEEE802154_FRAMECTRL_INTRA 0x0040 /* Intra PAN, bit 6 */ -#define IEEE802154_FRAMECTRL_DADDR 0x0C00 /* Dest addressing mode, bits 10-11 */ -#define IEEE802154_FRAMECTRL_VERSION 0x3000 /* Source addressing mode, bits 12-13 */ -#define IEEE802154_FRAMECTRL_SADDR 0xC000 /* Source addressing mode, bits 14-15 */ - -#define IEEE802154_FRAMECTRL_SHIFT_FTYPE 0 /* Frame type, bits 0-2 */ -#define IEEE802154_FRAMECTRL_SHIFT_SEC 3 /* Security Enabled, bit 3 */ -#define IEEE802154_FRAMECTRL_SHIFT_PEND 4 /* Frame pending, bit 4 */ -#define IEEE802154_FRAMECTRL_SHIFT_ACKREQ 5 /* Acknowledge request, bit 5 */ -#define IEEE802154_FRAMECTRL_SHIFT_INTRA 6 /* Intra PAN, bit 6 */ -#define IEEE802154_FRAMECTRL_SHIFT_DADDR 10 /* Dest addressing mode, bits 10-11 */ -#define IEEE802154_FRAMECTRL_SHIFT_VERSION 12 /* Source addressing mode, bits 12-13 */ -#define IEEE802154_FRAMECTRL_SHIFT_SADDR 14 /* Source addressing mode, bits 14-15 */ +#define IEEE802154_FRAMECTRL_FTYPE 0x0007 /* Frame type, bits 0-2 */ +#define IEEE802154_FRAMECTRL_SEC 0x0008 /* Security Enabled, bit 3 */ +#define IEEE802154_FRAMECTRL_PEND 0x0010 /* Frame pending, bit 4 */ +#define IEEE802154_FRAMECTRL_ACKREQ 0x0020 /* Acknowledge request, bit 5 */ +#define IEEE802154_FRAMECTRL_PANIDCOMP 0x0040 /* PAN ID Compression, bit 6 */ +#define IEEE802154_FRAMECTRL_DADDR 0x0C00 /* Dest addressing mode, bits 10-11 */ +#define IEEE802154_FRAMECTRL_VERSION 0x3000 /* Source addressing mode, bits 12-13 */ +#define IEEE802154_FRAMECTRL_SADDR 0xC000 /* Source addressing mode, bits 14-15 */ + +#define IEEE802154_FRAMECTRL_SHIFT_FTYPE 0 /* Frame type, bits 0-2 */ +#define IEEE802154_FRAMECTRL_SHIFT_SEC 3 /* Security Enabled, bit 3 */ +#define IEEE802154_FRAMECTRL_SHIFT_PEND 4 /* Frame pending, bit 4 */ +#define IEEE802154_FRAMECTRL_SHIFT_ACKREQ 5 /* Acknowledge request, bit 5 */ +#define IEEE802154_FRAMECTRL_SHIFT_PANIDCOMP 6 /* PAN ID Compression, bit 6 */ +#define IEEE802154_FRAMECTRL_SHIFT_DADDR 10 /* Dest addressing mode, bits 10-11 */ +#define IEEE802154_FRAMECTRL_SHIFT_VERSION 12 /* Source addressing mode, bits 12-13 */ +#define IEEE802154_FRAMECTRL_SHIFT_SADDR 14 /* Source addressing mode, bits 14-15 */ /* IEEE 802.15.4 PHY constants */ @@ -238,6 +237,87 @@ enum IEEE802154_macSecurityMode }; +/* IEEE 802.15.4 Device address + * The addresses in ieee802154 have several formats: + * No address : [none] + * Short address + PAN id : PPPP/SSSS + * Extended address + PAN id : PPPP/LLLLLLLLLLLLLLLL + */ + +enum ieee802154_addr_mode_e +{ + IEEE802154_ADDRMODE_NONE = 0, + IEEE802154_ADDRMODE_SHORT = 2, + IEEE802154_ADDRMODE_EXTENDED +}; + +struct ieee802154_addr_s +{ + enum ieee802154_addr_mode_e ia_mode; /* Address mode. Short or Extended */ + uint16_t ia_panid; /* PAN identifier, can be IEEE802154_PAN_UNSPEC */ + union + { + uint16_t _ia_saddr; /* short address */ + uint8_t _ia_eaddr[8]; /* extended address */ + } ia_addr; + +#define ia_saddr ia_addr._ia_saddr +#define ia_eaddr ia_addr._ia_eaddr +}; + +#define IEEE802154_ADDRSTRLEN 22 /* (2*2+1+8*2, PPPP/EEEEEEEEEEEEEEEE) */ + +struct ieee802154_framecontrol_s +{ + /* Frame type + * + * Should be a value from: ieee802154_frametype_e + * + * Bits 0-1 + */ + + uint16_t frame_type : 3; + + uint16_t security_en : 1; /* Security Enabled flag, bit 3 */ + uint16_t frame_pending : 1; /* Frame Pending flag, bit 4 */ + uint16_t ack_req : 1; /* Acknowledge Request flag, bit 5 */ + uint16_t panid_comp : 1; /* PAN ID Compression flag, bit 6 */ + uint16_t reserved : 3; /* Reserved, bits 7-9 */ + + /* Destination Addressing Mode + * + * Should be a value from: ieee802154_addr_mode_e + * + * Bits 10-11 + */ + + uint16_t dest_addr_mode : 2; + + uint16_t frame_version : 2; /* Frame Version, bits 12-13 */ + + /* Source Addressing Mode + * + * Should be a value from: ieee802154_addr_mode_e + * + * Bits 14-15 + */ + + uint16_t src_addr_mode : 2; +}; + +struct ieee802154_frame_s +{ + struct ieee802154_framecontrol_s frame_control; + uint8_t seq_num; + struct ieee802154_addr_s dest_addr; + struct ieee802154_addr_s src_addr; +#ifdef CONFIG_IEEE802154_SECURITY + struct ieee802154_auxsec_s aux_sec_hdr; +#endif + void *payload; + uint16_t fcs; +}; + struct ieee802154_capability_info_s { uint8_t reserved_0 : 1; /* Reserved */ @@ -679,4 +759,4 @@ FAR struct ieee802154_mac_s * } #endif -#endif /* __INCLUDE_NUTTX_WIRELESS_IEEE802154_MRF24J40_H */ +#endif /* __INCLUDE_NUTTX_WIRELESS_IEEE802154_IEEE802154_MAC_H */ diff --git a/include/nuttx/wireless/ieee802154/ieee802154_radio.h b/include/nuttx/wireless/ieee802154/ieee802154_radio.h index f87c2010c2..0f8b7b187e 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_radio.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_radio.h @@ -47,7 +47,6 @@ #include #include #include -#include /**************************************************************************** * Pre-Processor Definitions @@ -106,6 +105,14 @@ struct ieee802154_cca_s uint8_t csth; /* Carrier sense threshold for CCA */ }; +struct ieee802154_packet_s +{ + uint8_t len; + uint8_t data[127]; + uint8_t lqi; + uint8_t rssi; +}; + struct ieee802154_radio_s; struct ieee802154_radioops_s diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index 9703a0fe97..59d5f57d79 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -77,7 +77,7 @@ struct ieee802154_privmac_s /* 0x4F */ uint32_t macMinBE : 2; /* 0x4D */ uint32_t macGTSPermit : 1; /* 0x51 */ uint32_t macPromiscuousMode : 1; - /* 0x52 */ uint32_t macRxOnWhenIdle : 1; + /* 0x52 */ uint32_t macRxOnWhenIdle : 1; uint32_t macPad : 3; /* 0x48 */ uint32_t macBeaconTxTime : 24; -- GitLab From 8df78cc74bc47d59c1e3ee382905bfbb770822b7 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Wed, 29 Mar 2017 12:51:01 -0400 Subject: [PATCH 263/990] wireless/ieee802154: Adds MAC character driver structure. Nonfunctional --- .../wireless/ieee802154/ieee802154_mac.h | 53 +- wireless/ieee802154/Kconfig | 8 + wireless/ieee802154/Make.defs | 4 + wireless/ieee802154/mac802154.c | 27 +- wireless/ieee802154/mac802154_device.c | 503 ++++++++++++++++++ 5 files changed, 565 insertions(+), 30 deletions(-) create mode 100644 wireless/ieee802154/mac802154_device.c diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index 10f691a9b2..19af457bf6 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -724,35 +724,52 @@ extern "C" ****************************************************************************/ /**************************************************************************** - * Name: mac802154_register + * Name: mac802154_create * * Description: * Create a 802.15.4 MAC device from a 802.15.4 compatible radio device. - * To create a 802.15.4 MAC, you need to pass: * - * - an instance of a radio driver in radiodev - * - a pointer to a structure that contains MAC callback routines to - * handle confirmations and indications. NULL entries indicate no - * callback. + * The returned MAC structure should be passed to either the next highest + * layer in the network stack, or registered with a mac802154dev character + * driver. In either of these scenarios, the next highest layer should + * register a set of callbacks with the MAC layer by setting the mac->cbs + * member. * - * In return you get a mac structure that has pointers to MAC operations - * and responses. - * - * This API does not create any device accessible to userspace. If you + * NOTE: This API does not create any device accessible to userspace. If you * want to call these APIs from userspace, you have to wrap your mac in a * character device via mac802154_device.c. * + * Input Parameters: + * radiodev - an instance of an IEEE 802.15.4 radio + * + * Returned Value: + * A MAC structure that has pointers to MAC operations + * and responses. + * ****************************************************************************/ -#if 0 /* REVISIT: This form is not currently used by the driver */ -FAR struct ieee802154_mac_s * - mac802154_register(FAR struct ieee802154_radio_s *radiodev, - FAR struct ieee802154_maccb_s *callbacks); -#else /* This is the form used by the driver */ FAR struct ieee802154_mac_s * - mac802154_register(FAR struct ieee802154_radio_s *radiodev, - unsigned int minor); -#endif + mac802154_create(FAR struct ieee802154_radio_s *radiodev); + +/**************************************************************************** + * Name: mac802154dev_register + * + * Description: + * Register a character driver to access the IEEE 802.15.4 MAC layer from + * user-space + * + * Input Parameters: + * mac - Pointer to the mac layer struct to be registerd. + * minor - The device minor number. The IEEE802.15.4 MAC character device + * will be registered as /dev/ieeeN where N is the minor number + * + * Returned Values: + * Zero (OK) is returned on success. Otherwise a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +int mac802154dev_register(FAR struct ieee802154_mac_s *mac, int minor); #undef EXTERN #ifdef __cplusplus diff --git a/wireless/ieee802154/Kconfig b/wireless/ieee802154/Kconfig index fa8793af3d..5470894a7d 100644 --- a/wireless/ieee802154/Kconfig +++ b/wireless/ieee802154/Kconfig @@ -21,6 +21,14 @@ config IEEE802154_MAC such as 6lowpan. It is not required to use 802.15.4 radios, but is strongly suggested to ensure exchange of valid frames. +config IEEE802154_MAC_DEV + bool "Character driver for IEEE 802.15.4 MAC layer" + default n + depends on IEEE802154_MAC + ---help--- + Enable the device driver to expose the IEEE 802.15.4 MAC layer + access to user space as IOCTLs + config IEEE802154_DEV bool "Debug character driver for ieee802.15.4 radio interfaces" default n diff --git a/wireless/ieee802154/Make.defs b/wireless/ieee802154/Make.defs index e2f205aabc..4a69b06511 100644 --- a/wireless/ieee802154/Make.defs +++ b/wireless/ieee802154/Make.defs @@ -45,6 +45,10 @@ ifeq ($(CONFIG_IEEE802154_MAC),y) CSRCS += mac802154.c endif +ifeq ($(CONFIG_IEEE802154_MAC_DEV),y) +CSRCS += mac802154_device.c +endif + ifeq ($(CONFIG_IEEE802154_DEV),y) CSRCS += radio802154_device.c endif diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index 59d5f57d79..d0a0a3ce50 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -506,29 +506,32 @@ static int mac802154_rsporphan(FAR struct ieee802154_mac_s *mac, ****************************************************************************/ /**************************************************************************** - * Name: mac802154_register + * Name: mac802154_create * * Description: * Create a 802.15.4 MAC device from a 802.15.4 compatible radio device. - * To create a 802.15.4 MAC, you need to pass: * - * - an instance of a radio driver in radiodev - * - a pointer to a structure that contains MAC callback routines to - * handle confirmations and indications. NULL entries indicate no - * callback. + * The returned MAC structure should be passed to either the next highest + * layer in the network stack, or registered with a mac802154dev character + * driver. In either of these scenarios, the next highest layer should + * register a set of callbacks with the MAC layer by setting the mac->cbs + * member. * - * In return you get a mac structure that has pointers to MAC operations - * and responses. - * - * This API does not create any device accessible to userspace. If you + * NOTE: This API does not create any device accessible to userspace. If you * want to call these APIs from userspace, you have to wrap your mac in a * character device via mac802154_device.c. * + * Input Parameters: + * radiodev - an instance of an IEEE 802.15.4 radio + * + * Returned Value: + * A MAC structure that has pointers to MAC operations + * and responses. + * ****************************************************************************/ FAR struct ieee802154_mac_s * - mac802154_register(FAR struct ieee802154_radio_s *radiodev, - unsigned int minor) + mac802154_create(FAR struct ieee802154_radio_s *radiodev) { FAR struct ieee802154_privmac_s *mac; diff --git a/wireless/ieee802154/mac802154_device.c b/wireless/ieee802154/mac802154_device.c new file mode 100644 index 0000000000..88f36ee514 --- /dev/null +++ b/wireless/ieee802154/mac802154_device.c @@ -0,0 +1,503 @@ +/**************************************************************************** + * drivers/ieee802154/mac802154_device.c + * + * Copyright (C) 2017 Verge Inc. All rights reserved. + * Author: Anthony Merlino + * + * 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 + ****************************************************************************/ + +/* Device naming ************************************************************/ + +#define DEVNAME_FMT "/dev/ieee%d" +#define DEVNAME_FMTLEN (9 + 3 + 1) + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct mac802154_devwrapper_s +{ + FAR struct ieee802154_mac_s *md_mac; /* Saved binding to the mac layer */ + sem_t md_exclsem; /* Exclusive device access */ + + /* The following is a singly linked list of open references to the + * MAC device. + */ + + FAR struct mac802154_open_s *md_open; +}; + +/* This structure describes the state of one open mac driver instance */ + +struct mac802154_open_s +{ + /* Supports a singly linked list */ + + FAR struct mac802154_open_s *md_flink; + + /* The following will be true if we are closing */ + + volatile bool md_closing; +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + + /* Semaphore helpers */ + +static inline int mac802154dev_takesem(sem_t *sem); +#define mac802154dev_givesem(s) sem_post(s); + +static int mac802154dev_open(FAR struct file *filep); +static int mac802154dev_close(FAR struct file *filep); +static ssize_t mac802154dev_read(FAR struct file *filep, FAR char *buffer, + size_t len); +static ssize_t mac802154dev_write(FAR struct file *filep, + FAR const char *buffer, size_t len); +static int mac802154dev_ioctl(FAR struct file *filep, int cmd, + unsigned long arg); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const struct file_operations mac802154dev_fops = +{ + mac802154dev_open , /* open */ + mac802154dev_close, /* close */ + mac802154dev_read , /* read */ + mac802154dev_write, /* write */ + NULL, /* seek */ + mac802154dev_ioctl /* ioctl */ +#ifndef CONFIG_DISABLE_POLL + , NULL /* poll */ +#endif +#ifndef CONFIG_DISABLE_PSEUDOFS_OPERATIONS + , NULL /* unlink */ +#endif +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: mac802154dev_semtake + * + * Description: + * Acquire the semaphore used for access serialization. + * + ****************************************************************************/ + +static inline int mac802154dev_takesem(sem_t *sem) +{ + /* Take a count from the semaphore, possibly waiting */ + + if (sem_wait(sem) < 0) + { + /* EINTR is the only error that we expect */ + + int errcode = get_errno(); + DEBUGASSERT(errcode == EINTR); + return -errcode; + } + + return OK; +} + +/**************************************************************************** + * Name: mac802154dev_open + * + * Description: + * Open the 802.15.4 MAC character device. + * + ****************************************************************************/ + +static int mac802154dev_open(FAR struct file *filep) +{ + FAR struct inode *inode; + FAR struct mac802154_devwrapper_s *dev; + FAR struct mac802154_open_s *opriv; + int ret; + + DEBUGASSERT(filep != NULL && filep->f_inode != NULL); + inode = filep->f_inode; + + dev = inode->i_private; + DEBUGASSERT(dev != NULL); + + /* Get exclusive access to the MAC driver data structure */ + + ret = mac802154dev_takesem(&dev->md_exclsem); + if (ret < 0) + { + wlerr("ERROR: mac802154dev_takesem failed: %d\n", ret); + return ret; + } + + /* Allocate a new open struct */ + + opriv = (FAR struct mac802154_open_s *)kmm_zalloc(sizeof(struct mac802154_open_s)); + if (!opriv) + { + wlerr("ERROR: Failed to allocate new open struct\n"); + ret = -ENOMEM; + goto errout_with_sem; + } + + /* Attach the open struct to the device */ + + opriv->md_flink = dev->md_open; + dev->md_open = opriv; + + /* Attach the open struct to the file structure */ + + filep->f_priv = (FAR void *)opriv; + ret = OK; + +errout_with_sem: + mac802154dev_givesem(&dev->md_exclsem); + return ret; +} + +/**************************************************************************** + * Name: mac802154dev_close + * + * Description: + * Close the 802.15.4 MAC character device. + * + ****************************************************************************/ + +static int mac802154dev_close(FAR struct file *filep) +{ + FAR struct inode *inode; + FAR struct mac802154_devwrapper_s *dev; + FAR struct mac802154_open_s *opriv; + FAR struct mac802154_open_s *curr; + FAR struct mac802154_open_s *prev; + irqstate_t flags; + bool closing; + int ret; + + DEBUGASSERT(filep && filep->f_priv && filep->f_inode); + opriv = filep->f_priv; + inode = filep->f_inode; + DEBUGASSERT(inode->i_private); + dev = (FAR struct mac802154_devwrapper_s *)inode->i_private; + + /* Handle an improbable race conditions with the following atomic test + * and set. + * + * This is actually a pretty feeble attempt to handle this. The + * improbable race condition occurs if two different threads try to + * close the joystick driver at the same time. The rule: don't do + * that! It is feeble because we do not really enforce stale pointer + * detection anyway. + */ + + flags = enter_critical_section(); + closing = opriv->md_closing; + opriv->md_closing = true; + leave_critical_section(flags); + + if (closing) + { + /* Another thread is doing the close */ + + return OK; + } + + /* Get exclusive access to the driver structure */ + + ret = mac802154dev_takesem(&dev->md_exclsem); + if (ret < 0) + { + wlerr("ERROR: mac802154_takesem failed: %d\n", ret); + return ret; + } + + /* Find the open structure in the list of open structures for the device */ + + for (prev = NULL, curr = dev->md_open; + curr && curr != opriv; + prev = curr, curr = curr->md_flink); + + DEBUGASSERT(curr); + if (!curr) + { + wlerr("ERROR: Failed to find open entry\n"); + ret = -ENOENT; + goto errout_with_exclsem; + } + + /* Remove the structure from the device */ + + if (prev) + { + prev->md_flink = opriv->md_flink; + } + else + { + dev->md_open = opriv->md_flink; + } + + /* And free the open structure */ + + kmm_free(opriv); + + ret = OK; + +errout_with_exclsem: + mac802154dev_givesem(&dev->md_exclsem); + return ret; +} + +/**************************************************************************** + * Name: mac802154dev_read + * + * Description: + * Return the last received packet. + * + ****************************************************************************/ + +static ssize_t mac802154dev_read(FAR struct file *filep, FAR char *buffer, size_t len) +{ + FAR struct inode *inode; + FAR struct mac802154_devwrapper_s *dev; + int ret; + + DEBUGASSERT(filep && filep->f_inode); + inode = filep->f_inode; + DEBUGASSERT(inode->i_private); + dev = (FAR struct mac802154_devwrapper_s *)inode->i_private; + + /* Check to make sure that the buffer is big enough to hold at least one + * packet. + */ + + if (len < sizeof(struct ieee802154_frame_s)) + { + wlerr("ERROR: buffer too small: %lu\n", (unsigned long)len); + return -EINVAL; + } + + /* Get exclusive access to the driver structure */ + + ret = mac802154dev_takesem(&dev->md_exclsem); + if (ret < 0) + { + wlerr("ERROR: mac802154dev_takesem failed: %d\n", ret); + return ret; + } + + /* TODO: Add code to read a packet and return it */ + ret = -ENOTSUP; + + mac802154dev_givesem(&dev->md_exclsem); + return ret; +} + +/**************************************************************************** + * Name: mac802154dev_write + * + * Description: + * Send a packet over the IEEE802.15.4 network. + * + ****************************************************************************/ + +static ssize_t mac802154dev_write(FAR struct file *filep, + FAR const char *buffer, size_t len) +{ + FAR struct inode *inode; + FAR struct mac802154_devwrapper_s *dev; + struct ieee802154_frame_s frame; + int ret; + + DEBUGASSERT(filep && filep->f_inode); + inode = filep->f_inode; + DEBUGASSERT(inode->i_private); + dev = (FAR struct mac802154_devwrapper_s *)inode->i_private; + + /* Check to make sure that the buffer is big enough to hold at least one + * packet. + */ + + if (len < sizeof(struct ieee802154_frame_s)) + { + wlerr("ERROR: buffer too small: %lu\n", (unsigned long)len); + return -EINVAL; + } + + DEBUGASSERT(buffer != NULL); + frame = *(FAR struct ieee802154_frame_s *)buffer; + + /* Get exclusive access to the driver structure */ + + ret = mac802154dev_takesem(&dev->md_exclsem); + if (ret < 0) + { + wlerr("ERROR: mac802154dev_takesem failed: %d\n", ret); + return ret; + } + + /* TODO: Send the frame out */ + ret = -ENOTSUP; + + mac802154dev_givesem(&dev->md_exclsem); + return ret; +} + +/**************************************************************************** + * Name: mac802154dev_ioctl + * + * Description: + * Control the MAC layer via MLME IOCTL commands. + * + ****************************************************************************/ + +static int mac802154dev_ioctl(FAR struct file *filep, int cmd, + unsigned long arg) +{ + FAR struct inode *inode; + FAR struct mac802154_devwrapper_s *dev; + FAR struct ieee802154_mac_s *mac; + int ret; + + DEBUGASSERT(filep != NULL && filep->f_priv != NULL && filep->f_inode != NULL); + inode = filep->f_inode; + DEBUGASSERT(inode->i_private); + dev = (FAR struct mac802154_devwrapper_s *)inode->i_private; + + /* Get exclusive access to the driver structure */ + + ret = mac802154dev_takesem(&dev->md_exclsem); + if (ret < 0) + { + wlerr("ERROR: mac802154dev_takesem failed: %d\n", ret); + return ret; + } + + /* Handle the ioctl command */ + + switch (cmd) + { + default: + wlerr("ERROR: Unrecognized command %ld\n", cmd); + ret = -EINVAL; + break; + } + + mac802154dev_givesem(&dev->md_exclsem); + return ret; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: mac802154dev_register + * + * Description: + * Register a character driver to access the IEEE 802.15.4 MAC layer from + * user-space + * + * Input Parameters: + * mac - Pointer to the mac layer struct to be registerd. + * minor - The device minor number. The IEEE802.15.4 MAC character device + * will be registered as /dev/ieeeN where N is the minor number + * + * Returned Values: + * Zero (OK) is returned on success. Otherwise a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +int mac802154dev_register(FAR struct ieee802154_mac_s *mac, int minor) +{ + FAR struct mac802154_devwrapper_s *dev; + char devname[DEVNAME_FMTLEN]; + int ret; + + dev = kmm_zalloc(sizeof(struct mac802154_devwrapper_s)); + if (!dev) + { + wlerr("ERROR: Failed to allocate device structure\n"); + return -ENOMEM; + } + + /* Initialize the new mac driver instance */ + + dev->md_mac = mac; + sem_init(&dev->md_exclsem, 0, 1); /* Allow the device to be opened once before blocking */ + + /* Create the character device name */ + + snprintf(devname, DEVNAME_FMTLEN, DEVNAME_FMT, minor); + + /* Register the mac character driver */ + + ret = register_driver(devname, &mac802154dev_fops, 0666, dev); + if (ret < 0) + { + wlerr("ERROR: register_driver failed: %d\n", ret); + goto errout_with_priv; + } + + return OK; + +errout_with_priv: + sem_destroy(&dev->md_exclsem); + kmm_free(dev); + return ret; +} -- GitLab From 68f2709078663a962d5febc1f5bbba53268f7908 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 29 Mar 2017 11:03:10 -0600 Subject: [PATCH 264/990] Review from last PR --- wireless/ieee802154/mac802154_device.c | 20 ++++++++++++-------- 1 file changed, 12 insertions(+), 8 deletions(-) diff --git a/wireless/ieee802154/mac802154_device.c b/wireless/ieee802154/mac802154_device.c index 88f36ee514..0478522834 100644 --- a/wireless/ieee802154/mac802154_device.c +++ b/wireless/ieee802154/mac802154_device.c @@ -117,10 +117,10 @@ static const struct file_operations mac802154dev_fops = mac802154dev_close, /* close */ mac802154dev_read , /* read */ mac802154dev_write, /* write */ - NULL, /* seek */ + NULL, /* seek */ mac802154dev_ioctl /* ioctl */ #ifndef CONFIG_DISABLE_POLL - , NULL /* poll */ + , NULL /* poll */ #endif #ifndef CONFIG_DISABLE_PSEUDOFS_OPERATIONS , NULL /* unlink */ @@ -187,7 +187,9 @@ static int mac802154dev_open(FAR struct file *filep) /* Allocate a new open struct */ - opriv = (FAR struct mac802154_open_s *)kmm_zalloc(sizeof(struct mac802154_open_s)); + opriv = (FAR struct mac802154_open_s *) + kmm_zalloc(sizeof(struct mac802154_open_s)); + if (!opriv) { wlerr("ERROR: Failed to allocate new open struct\n"); @@ -294,7 +296,6 @@ static int mac802154dev_close(FAR struct file *filep) /* And free the open structure */ kmm_free(opriv); - ret = OK; errout_with_exclsem: @@ -310,7 +311,8 @@ errout_with_exclsem: * ****************************************************************************/ -static ssize_t mac802154dev_read(FAR struct file *filep, FAR char *buffer, size_t len) +static ssize_t mac802154dev_read(FAR struct file *filep, FAR char *buffer, + size_t len) { FAR struct inode *inode; FAR struct mac802154_devwrapper_s *dev; @@ -356,7 +358,7 @@ static ssize_t mac802154dev_read(FAR struct file *filep, FAR char *buffer, size_ ****************************************************************************/ static ssize_t mac802154dev_write(FAR struct file *filep, - FAR const char *buffer, size_t len) + FAR const char *buffer, size_t len) { FAR struct inode *inode; FAR struct mac802154_devwrapper_s *dev; @@ -413,7 +415,8 @@ static int mac802154dev_ioctl(FAR struct file *filep, int cmd, FAR struct ieee802154_mac_s *mac; int ret; - DEBUGASSERT(filep != NULL && filep->f_priv != NULL && filep->f_inode != NULL); + DEBUGASSERT(filep != NULL && filep->f_priv != NULL && + filep->f_inode != NULL); inode = filep->f_inode; DEBUGASSERT(inode->i_private); dev = (FAR struct mac802154_devwrapper_s *)inode->i_private; @@ -479,7 +482,8 @@ int mac802154dev_register(FAR struct ieee802154_mac_s *mac, int minor) /* Initialize the new mac driver instance */ dev->md_mac = mac; - sem_init(&dev->md_exclsem, 0, 1); /* Allow the device to be opened once before blocking */ + sem_init(&dev->md_exclsem, 0, 1); /* Allow the device to be opened once + * before blocking */ /* Create the character device name */ -- GitLab From e7863aed731b0f5b58a80d469ac1b988ae503cb8 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Wed, 29 Mar 2017 14:09:27 -0400 Subject: [PATCH 265/990] configs/clicker2-stm32: Adds logic to create an 802.15.4 MAC and register a character driver --- configs/clicker2-stm32/src/stm32_mrf24j40.c | 37 +++++++++++---------- 1 file changed, 19 insertions(+), 18 deletions(-) diff --git a/configs/clicker2-stm32/src/stm32_mrf24j40.c b/configs/clicker2-stm32/src/stm32_mrf24j40.c index f32c9ed208..17eb70ea96 100644 --- a/configs/clicker2-stm32/src/stm32_mrf24j40.c +++ b/configs/clicker2-stm32/src/stm32_mrf24j40.c @@ -89,7 +89,6 @@ #endif #define RADIO_DEVNAME "/dev/mrf24j40" -#define MAC_DEVNAME "/dev/mrf24j40mac" /**************************************************************************** * Private Types @@ -256,39 +255,41 @@ static int stm32_mrf24j40_devsetup(FAR struct stm32_priv_s *priv) return -ENODEV; } -#if defined(CONFIG_IEEE802154_DEV) - /* Register a character driver to access the IEEE 802.15.4 radio from - * user-space - */ - - ret = radio802154dev_register(radio, RADIO_DEVNAME); - if (ret < 0) - { - wlerr("ERROR: Failed to register the radio device %s: %d\n", - RADIO_DEVNAME, ret); - return ret; - } - -#elif 0 /* defined(CONFIG_IEEE802154_MAC) */ +#if defined(CONFIG_IEEE802154_MAC) /* Create a 802.15.4 MAC device from a 802.15.4 compatible radio device. */ - mac = mac802154_register(radio, 0); - if (radio == NULL) + mac = mac802154_create(radio); + if (mac == NULL) { wlerr("ERROR: Failed to initialize IEEE802.15.4 MAC\n"); return -ENODEV; } +#endif +#if defined(CONFIG_IEEE802154_MAC_DEV) /* If want to call these APIs from userspace, you have to wrap your mac * in a character device via mac802154_device.c. */ - ret = mac802154dev_register(mac, MAC_DEVNAME); + ret = mac802154dev_register(mac, 0); + if (ret < 0) + { + wlerr("ERROR: Failed to register the MAC character driver ieee%d: %d\n", + 0, ret); + return ret; + } +#elif defined(CONFIG_IEEE802154_DEV) + /* Register a character driver to access the IEEE 802.15.4 radio from + * user-space + */ + + ret = radio802154dev_register(radio, RADIO_DEVNAME); if (ret < 0) { wlerr("ERROR: Failed to register the radio device %s: %d\n", RADIO_DEVNAME, ret); return ret; + } #endif return OK; -- GitLab From a6148cdb7cba86d89b49e7b29529f803fec53005 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 29 Mar 2017 14:28:51 -0600 Subject: [PATCH 266/990] 6loWPAN: Adding more socket send-related logic. --- include/nuttx/net/sixlowpan.h | 115 ++++++++++++++++- net/sixlowpan/Kconfig | 6 + net/sixlowpan/Make.defs | 8 +- net/sixlowpan/sixlowpan.h | 36 ++++-- net/sixlowpan/sixlowpan_globals.c | 2 + net/sixlowpan/sixlowpan_send.c | 207 ++++++++++++++++++++++++++++-- net/sixlowpan/sixlowpan_sniffer.c | 4 +- 7 files changed, 354 insertions(+), 24 deletions(-) diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index be7f9f1e36..376fbf2d9c 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -232,18 +232,91 @@ #define SIXLOWPAN_MAC_STDFRAME 127 +/* Packet buffer Definitions */ + +#define PACKETBUF_HDR_SIZE 48 + +#define PACKETBUF_ATTR_PACKET_TYPE_DATA 0 +#define PACKETBUF_ATTR_PACKET_TYPE_ACK 1 +#define PACKETBUF_ATTR_PACKET_TYPE_STREAM 2 +#define PACKETBUF_ATTR_PACKET_TYPE_STREAM_END 3 +#define PACKETBUF_ATTR_PACKET_TYPE_TIMESTAMP 4 + +/* Packet buffer attributes (indices into i_pktattr) */ + +#define PACKETBUF_ATTR_NONE 0 + +/* Scope 0 attributes: used only on the local node. */ + +#define PACKETBUF_ATTR_CHANNEL 1 +#define PACKETBUF_ATTR_NETWORK_ID 2 +#define PACKETBUF_ATTR_LINK_QUALITY 3 +#define PACKETBUF_ATTR_RSSI 4 +#define PACKETBUF_ATTR_TIMESTAMP 5 +#define PACKETBUF_ATTR_RADIO_TXPOWER 6 +#define PACKETBUF_ATTR_LISTEN_TIME 7 +#define PACKETBUF_ATTR_TRANSMIT_TIME 8 +#define PACKETBUF_ATTR_MAX_MAC_TRANSMISSIONS 9 +#define PACKETBUF_ATTR_MAC_SEQNO 10 +#define PACKETBUF_ATTR_MAC_ACK 11 + +/* Scope 1 attributes: used between two neighbors only. */ + +#define PACKETBUF_ATTR_RELIABLE 12 +#define PACKETBUF_ATTR_PACKET_ID 13 +#define PACKETBUF_ATTR_PACKET_TYPE 14 +#define PACKETBUF_ATTR_REXMIT 15 +#define PACKETBUF_ATTR_MAX_REXMIT 16 +#define PACKETBUF_ATTR_NUM_REXMIT 17 +#define PACKETBUF_ATTR_PENDING 18 + +/* Scope 2 attributes: used between end-to-end nodes. */ + +#define PACKETBUF_ATTR_HOPS 11 +#define PACKETBUF_ATTR_TTL 20 +#define PACKETBUF_ATTR_EPACKET_ID 21 +#define PACKETBUF_ATTR_EPACKET_TYPE 22 +#define PACKETBUF_ATTR_ERELIABLE 23 + +#define PACKETBUF_NUM_ATTRS 24 + + /* Addresses (indices into i_pktaddr) */ + +#define PACKETBUF_ADDR_SENDER 0 +#define PACKETBUF_ADDR_RECEIVER 1 +#define PACKETBUF_ADDR_ESENDER 2 +#define PACKETBUF_ADDR_ERECEIVER 3 + +#define PACKETBUF_NUM_ADDRS 4 + /**************************************************************************** * Public Types ****************************************************************************/ +/* Rime address representation */ + +struct rimeaddr_s +{ + uint8_t u8[CONFIG_NET_6LOWPAN_RIMEADDR_SIZE]; +}; + /* The device structure for IEEE802.15.4 MAC network device differs from the * standard Ethernet MAC device structure. The main reason for this * difference is that fragmentation must be supported. * * The IEEE802.15.4 MAC does not use the d_buf packet buffer directly. - * Rather, it uses a smaller frame buffer. The packet data is provided to - * the frame buffer each time that the IEEE802.15.4 MAC needs to send - * more data. + * Rather, it uses a smaller frame buffer, i_frame. + * + * - The packet fragment data is provided to the i_frame buffer each time + * that the IEEE802.15.4 MAC needs to send more data. The length of + * the frame is provided in i_frame. + * + * In this case, the d_buf holds the packet data yet to be sent; d_len + * holds the size of entire packet. + * + * - Received frames are provided by IEEE802.15.4 MAC to the network + * via i_frame with length i_framelen for reassembly in d_buf; d_len + * will hold the size of the reassembled packet. * * This is accomplished by "inheriting" the standard 'struct net_driver_s' * and appending the frame buffer as well as other metadata needed to @@ -286,6 +359,40 @@ struct ieee802154_driver_s */ uint16_t i_framelen; + + /* The following fields are device-specific metadata used by the 6loWPAN + * stack and should not be modified by the IEEE802.15.4 MAC network drvier. + */ + + /* A pointer to the rime buffer. + * + * We initialize it to the beginning of the rime buffer, then access + * different fields by updating the offset ieee->i_rime_hdrlen. + */ + + FAR uint8_t *i_rimeptr; + + /* i_uncomp_hdrlen is the length of the headers before compression (if HC2 + * is used this includes the UDP header in addition to the IP header). + */ + + uint8_t i_uncomp_hdrlen; + + /* i_rime_hdrlen is the total length of (the processed) 6lowpan headers + * (fragment headers, IPV6 or HC1, HC2, and HC1 and HC2 non compressed + * fields). + */ + + uint8_t i_rime_hdrlen; + + /* Next available pointer into header */ + + uint8_t i_hdrptr; + + /* Packet buffer metadata: Attributes and addresses */ + + uint16_t i_pktattrs[PACKETBUF_NUM_ATTRS]; + struct rimeaddr_s i_pktaddrs[PACKETBUF_NUM_ADDRS]; }; /* The structure of a next header compressor. This compressor is provided @@ -357,6 +464,8 @@ void sixlowpan_set_compressor(FAR struct sixlowpan_nhcompressor_s *compressor); * ****************************************************************************/ +#ifdef CONFIG_NET_6LOWPAN_SNIFFER void sixlowpan_set_sniffer(FAR struct sixlowpan_rime_sniffer_s *sniffer); +#endif #endif /* __INCLUDE_NUTTX_NET_SIXLOWOAN_H */ diff --git a/net/sixlowpan/Kconfig b/net/sixlowpan/Kconfig index 84cb1c6652..7031f21e62 100644 --- a/net/sixlowpan/Kconfig +++ b/net/sixlowpan/Kconfig @@ -169,4 +169,10 @@ config NET_6LOWPAN_TCP_RECVWNDO is slow to process incoming data, or high (32768 bytes) if the application processes data quickly. REVISIT! +config NET_6LOWPAN_SNIFFER + default n + ---help--- + Enable use use an architecture-specific sniffer to support tracing + of IP. + endif # NET_6LOWPAN diff --git a/net/sixlowpan/Make.defs b/net/sixlowpan/Make.defs index 1e58151731..8494f61f3b 100644 --- a/net/sixlowpan/Make.defs +++ b/net/sixlowpan/Make.defs @@ -39,9 +39,9 @@ ifeq ($(CONFIG_NET_6LOWPAN),y) # Include IEEE 802.15.4 file in the build -NET_CSRCS += sixlowpan_initialize.c sixlowpan_globals.c +NET_CSRCS += sixlowpan_initialize.c sixlowpan_globals.c sixlowpan_utils.c NET_CSRCS += sixlowpan_input.c sixlowpan_send.c -NET_CSRCS += sixlowpan_compressor.c sixlowpan_sniffer.c +NET_CSRCS += sixlowpan_compressor.c ifeq ($(CONFIG_NET_6LOWPAN_COMPRESSION_HC1),y) NET_CSRCS += sixlowpan_hc1.c @@ -51,6 +51,10 @@ ifeq ($(CONFIG_NET_6LOWPAN_COMPRESSION_HC06),y) NET_CSRCS += sixlowpan_hc06.c endif +ifeq ($(CONFIG_NET_6LOWPAN_SNIFFER),y) +NET_CSRCS += sixlowpan_sniffer.c +endif + # Include the sixlowpan directory in the build DEPPATH += --dep-path sixlowpan diff --git a/net/sixlowpan/sixlowpan.h b/net/sixlowpan/sixlowpan.h index 3acd0f4804..b003445fc6 100644 --- a/net/sixlowpan/sixlowpan.h +++ b/net/sixlowpan/sixlowpan.h @@ -61,13 +61,6 @@ * Public Types ****************************************************************************/ -/* Rime address representation */ - -struct rimeaddr_s -{ - uint8_t u8[CONFIG_NET_6LOWPAN_RIMEADDR_SIZE]; -}; - /**************************************************************************** * Public Data ****************************************************************************/ @@ -77,10 +70,16 @@ struct rimeaddr_s struct sixlowpan_nhcompressor_s; /* Foward reference */ extern FAR struct sixlowpan_nhcompressor_s *g_sixlowpan_compressor; +#ifdef CONFIG_NET_6LOWPAN_SNIFFER /* Rime Sniffer support for one single listener to enable trace of IP */ struct sixlowpan_rime_sniffer_s; /* Foward reference */ extern FAR struct sixlowpan_rime_sniffer_s *g_sixlowpan_sniffer; +#endif + +/* All zero rime address */ + +extern const struct rimeaddr_s g_rimeaddr_null; /**************************************************************************** * Public Types @@ -90,8 +89,10 @@ extern FAR struct sixlowpan_rime_sniffer_s *g_sixlowpan_sniffer; * Public Function Prototypes ****************************************************************************/ -struct net_driver_s; /* Forward reference */ -struct socket; /* Forward reference */ +struct net_driver_s; /* Forward reference */ +struct ieee802154_driver_s; /* Forward reference */ +struct rimeaddr_s; /* Forward reference */ +struct socket; /* Forward reference */ /**************************************************************************** * Name: sixlowpan_initialize @@ -132,6 +133,9 @@ void sixlowpan_initialize(void); * must be consistent with definition of errors reported by send() or * sendto(). * + * Assumptions: + * Called with the network locked. + * ****************************************************************************/ #ifdef CONFIG_NET_TCP @@ -157,6 +161,9 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, * must be consistent with definition of errors reported by send() or * sendto(). * + * Assumptions: + * Called with the network locked. + * ****************************************************************************/ #ifdef CONFIG_NET_UDP @@ -319,5 +326,16 @@ void sixlowpan_uncompresshdr_hc1(FAR struct net_driver_s *dev, uint16_t ip_len); #endif +/**************************************************************************** + * Name: sixlowpan_pktbuf_reset + * + * Description: + * Reset all attributes and addresses in the packet buffer metadata in the + * provided IEEE802.15.4 MAC driver structure. + * + ****************************************************************************/ + +void sixlowpan_pktbuf_reset(FAR struct ieee802154_driver_s *ieee); + #endif /* CONFIG_NET_6LOWPAN */ #endif /* _NET_SIXLOWPAN_SIXLOWPAN_H */ diff --git a/net/sixlowpan/sixlowpan_globals.c b/net/sixlowpan/sixlowpan_globals.c index 6a5729d619..ce5e06b490 100644 --- a/net/sixlowpan/sixlowpan_globals.c +++ b/net/sixlowpan/sixlowpan_globals.c @@ -53,8 +53,10 @@ FAR struct sixlowpan_nhcompressor_s *g_sixlowpan_compressor; +#ifdef CONFIG_NET_6LOWPAN_SNIFFER /* A pointer to the optional, architecture-specific sniffer */ FAR struct sixlowpan_rime_sniffer_s *g_sixlowpan_sniffer; +#endif #endif /* CONFIG_NET_6LOWPAN */ diff --git a/net/sixlowpan/sixlowpan_send.c b/net/sixlowpan/sixlowpan_send.c index b85c685f42..ce99656770 100644 --- a/net/sixlowpan/sixlowpan_send.c +++ b/net/sixlowpan/sixlowpan_send.c @@ -39,12 +39,17 @@ #include +#include #include #include #include -#include "nuttx/net/net.h" #include "nuttx/net/netdev.h" +#include "nuttx/net/ip.h" +#include "nuttx/net/tcp.h" +#include "nuttx/net/udp.h" +#include "nuttx/net/icmpv6.h" +#include "nuttx/net/sixlowpan.h" #include "netdev/netdev.h" #include "socket/socket.h" @@ -54,11 +59,133 @@ #ifdef CONFIG_NET_6LOWPAN +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/* IPv6 + TCP header */ + +struct ipv6tcp_hdr_s +{ + struct ipv6_hdr_s ipv6; + struct tcp_hdr_s tcp; +}; + +/* IPv6 + UDP header */ + +struct ipv6udp_hdr_s +{ + struct ipv6_hdr_s ipv6; + struct udp_hdr_s udp; +}; + +/* IPv6 + ICMPv6 header */ + +struct ipv6icmp_hdr_s +{ + struct ipv6_hdr_s ipv6; + struct icmpv6_iphdr_s icmp; +}; /**************************************************************************** - * Public Functions + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: sixlowpan_set_pktattrs + * + * Description: + * Setup some packet buffer attributes + * Input Parameters: + * ieee - Pointer to IEEE802.15.4 MAC driver structure. + * ipv6 - Pointer to the IPv6 header to "compress" + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void sixlowpan_set_pktattrs(FAR struct ieee802154_driver_s *ieee, + FAR const struct ipv6_hdr_s *ipv6) +{ + int attr = 0; + + /* Set protocol in NETWORK_ID */ + + ieee->i_pktattrs[PACKETBUF_ATTR_NETWORK_ID] = ipv6->proto; + + /* Assign values to the channel attribute (port or type + code) */ + + if (ipv6->proto == IP_PROTO_UDP) + { + FAR struct udp_hdr_s *udp = &((FAR struct ipv6udp_hdr_s *)ipv6)->udp; + + attr = udp->srcport; + if (udp->destport < attr) + { + attr = udp->destport; + } + } + else if (ipv6->proto == IP_PROTO_TCP) + { + FAR struct tcp_hdr_s *tcp = &((FAR struct ipv6tcp_hdr_s *)ipv6)->tcp; + + attr = tcp->srcport; + if (tcp->destport < attr) + { + attr = tcp->destport; + } + } + else if (ipv6->proto == IP_PROTO_ICMP6) + { + FAR struct icmpv6_iphdr_s *icmp = &((FAR struct ipv6icmp_hdr_s *)ipv6)->icmp; + + attr = icmp->type << 8 | icmp->code; + } + + ieee->i_pktattrs[PACKETBUF_ATTR_CHANNEL] = attr; +} + +/**************************************************************************** + * Name: sixlowpan_compress_ipv6hdr + * + * Description: + * IPv6 dispatch "compression" function. Packets "Compression" when only + * IPv6 dispatch is used + * + * There is no compression in this case, all fields are sent + * inline. We just add the IPv6 dispatch byte before the packet. + * + * 0 1 2 3 + * 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + * | IPv6 Dsp | IPv6 header and payload ... + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + * + * Input Parameters: + * ieee - Pointer to IEEE802.15.4 MAC driver structure. + * ipv6 - Pointer to the IPv6 header to "compress" + * + * Returned Value: + * None + * ****************************************************************************/ +static void sixlowpan_compress_ipv6hdr(FAR struct ieee802154_driver_s *ieee, + FAR const struct ipv6_hdr_s *ipv6) +{ + /* Indicate the IPv6 dispatch and length */ + + *ieee->i_rimeptr = SIXLOWPAN_DISPATCH_IPV6; + ieee->i_rime_hdrlen += SIXLOWPAN_IPV6_HDR_LEN; + + /* Copy the IPv6 header and adjust pointers */ + + memcpy(ieee->i_rimeptr + ieee->i_rime_hdrlen, ipv6, IPv6_HDRLEN); + ieee->i_rime_hdrlen += IPv6_HDRLEN; + ieee->i_uncomp_hdrlen += IPv6_HDRLEN; +} + /**************************************************************************** * Name: sixlowpan_send * @@ -76,6 +203,7 @@ * * Input Parameters: * dev - The IEEE802.15.4 MAC network driver interface. + * ipv6 - IPv6 plus TCP or UDP headers. * raddr - The MAC address of the destination * * Returned Value: @@ -89,13 +217,60 @@ * ****************************************************************************/ -int sixlowpan_send(FAR struct net_driver_s *dev, net_ipv6addr_t raddr) +int sixlowpan_send(FAR struct net_driver_s *dev, + FAR const struct ipv6_hdr_s *ipv6, net_ipv6addr_t raddr) { FAR struct ieee802154_driver_s *ieee = (FAR struct ieee802154_driver_s *)dev; - net_lock(); - /* REVISIT: To be provided */ - net_unlock(); + int framer_hdrlen; /* Framer header length */ + struct rimeaddr_s dest; /* The MAC address of the destination of the packet */ + uint16_t outlen; /* Number of bytes processed. */ + + /* Initialize device-specific data */ + + ieee->i_uncomp_hdrlen = 0; + ieee->i_rime_hdrlen = 0; + + /* Reset rime buffer, packet buffer metatadata */ + + dev->d_len = 0; + + sixlowpan_pktbuf_reset(ieee); + + ieee->i_rimeptr = &dev->d_buf[PACKETBUF_HDR_SIZE]; + ieee->i_pktattrs[PACKETBUF_ATTR_MAX_MAC_TRANSMISSIONS] = CONFIG_NET_6LOWPAN_MAX_MACTRANSMITS; + +#ifdef CONFIG_NET_6LOWPAN_SNIFFER + if (g_sixlowpan_sniffer != NULL) + { + /* Call the attribution when the callback comes, but set attributes here */ + + sixlowpan_set_pktattrs(ieee, ipv6); + } +#endif + + /* Set stream mode for all TCP packets, except FIN packets. */ + + if (ipv6->proto == IP_PROTO_TCP) + { + FAR const struct tcp_hdr_s *tcp = &((FAR const struct ipv6tcp_hdr_s *)ipv6)->tcp; + + if ((tcp->flags & TCP_FIN) == 0 && + (tcp->flags & TCP_CTL) != TCP_ACK) + { + ieee->i_pktattrs[PACKETBUF_ATTR_PACKET_TYPE] = PACKETBUF_ATTR_PACKET_TYPE_STREAM; + } + else if ((tcp->flags & TCP_FIN) == TCP_FIN) + { + ieee->i_pktattrs[PACKETBUF_ATTR_PACKET_TYPE] = PACKETBUF_ATTR_PACKET_TYPE_STREAM_END; + } + } + + /* The destination address will be tagged to each outbound packet. If the + * argument raddr is NULL, we are sending a broadcast packet. + */ + +#warning Missing logic return -ENOSYS; } @@ -121,6 +296,9 @@ int sixlowpan_send(FAR struct net_driver_s *dev, net_ipv6addr_t raddr) * must be consistent with definition of errors reported by send() or * sendto(). * + * Assumptions: + * Called with the network locked. + * ****************************************************************************/ #ifdef CONFIG_NET_TCP @@ -129,6 +307,7 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, { FAR struct tcp_conn_s *conn; FAR struct net_driver_s *dev; + struct ipv6tcp_hdr_s ipv6tcp; int ret; DEBUGASSERT(psock != NULL && psock->s_crefs > 0); @@ -194,6 +373,9 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, } #endif + /* Initialize the IPv6/TCP headers */ +#warning Missing logic + /* Set the socket state to sending */ psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_SEND); @@ -202,7 +384,8 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, * packet. */ - ret = sixlowpan_send(dev, conn->u.ipv6.raddr); + ret = sixlowpan_send(dev, (FAR const struct ipv6_hdr_s *)&ipv6tcp, + conn->u.ipv6.raddr); if (ret < 0) { nerr("ERROR: sixlowpan_send() failed: %d\n", ret); @@ -230,6 +413,9 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, * must be consistent with definition of errors reported by send() or * sendto(). * + * Assumptions: + * Called with the network locked. + * ****************************************************************************/ #ifdef CONFIG_NET_UDP @@ -238,6 +424,7 @@ ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, { FAR struct udp_conn_s *conn; FAR struct net_driver_s *dev; + struct ipv6udp_hdr_s ipv6udp; int ret; DEBUGASSERT(psock != NULL && psock->s_crefs > 0); @@ -304,6 +491,9 @@ ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, } #endif + /* Initialize the IPv6/UDP headers */ +#warning Missing logic + /* Set the socket state to sending */ psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_SEND); @@ -312,7 +502,8 @@ ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, * packet. */ - ret = sixlowpan_send(dev, conn->u.ipv6.raddr); + ret = sixlowpan_send(dev, (FAR const struct ipv6_hdr_s *)&ipv6udp, + conn->u.ipv6.raddr); if (ret < 0) { nerr("ERROR: sixlowpan_send() failed: %d\n", ret); diff --git a/net/sixlowpan/sixlowpan_sniffer.c b/net/sixlowpan/sixlowpan_sniffer.c index baf3acc09c..f6134a86f0 100644 --- a/net/sixlowpan/sixlowpan_sniffer.c +++ b/net/sixlowpan/sixlowpan_sniffer.c @@ -44,7 +44,7 @@ #include "sixlowpan/sixlowpan.h" -#ifdef CONFIG_NET_6LOWPAN +#ifdef CONFIG_NET_6LOWPAN_SNIFFER /**************************************************************************** * Public Functions @@ -78,4 +78,4 @@ void sixlowpan_set_sniffer(FAR struct sixlowpan_rime_sniffer_s *sniffer) net_unlock(); } -#endif /* CONFIG_NET_6LOWPAN */ +#endif /* CONFIG_NET_6LOWPAN_SNIFFER */ -- GitLab From 8083a0437e9c87bbef62eb232eac447461a74fa8 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 29 Mar 2017 15:44:24 -0600 Subject: [PATCH 267/990] 6loWPAN: Add beginning of some compression hooks to send logic. --- net/sixlowpan/sixlowpan_send.c | 38 ++++++++++++++++++++++++++++++---- 1 file changed, 34 insertions(+), 4 deletions(-) diff --git a/net/sixlowpan/sixlowpan_send.c b/net/sixlowpan/sixlowpan_send.c index ce99656770..59f26959ae 100644 --- a/net/sixlowpan/sixlowpan_send.c +++ b/net/sixlowpan/sixlowpan_send.c @@ -204,6 +204,8 @@ static void sixlowpan_compress_ipv6hdr(FAR struct ieee802154_driver_s *ieee, * Input Parameters: * dev - The IEEE802.15.4 MAC network driver interface. * ipv6 - IPv6 plus TCP or UDP headers. + * buf - Data to send + * len - Length of data to send * raddr - The MAC address of the destination * * Returned Value: @@ -217,8 +219,9 @@ static void sixlowpan_compress_ipv6hdr(FAR struct ieee802154_driver_s *ieee, * ****************************************************************************/ -int sixlowpan_send(FAR struct net_driver_s *dev, - FAR const struct ipv6_hdr_s *ipv6, net_ipv6addr_t raddr) +static int sixlowpan_send(FAR struct net_driver_s *dev, + FAR const struct ipv6_hdr_s *ipv6, FAR const void *buf, + size_t len, net_ipv6addr_t raddr) { FAR struct ieee802154_driver_s *ieee = (FAR struct ieee802154_driver_s *)dev; @@ -270,6 +273,33 @@ int sixlowpan_send(FAR struct net_driver_s *dev, * argument raddr is NULL, we are sending a broadcast packet. */ +#warning Missing logic + + ninfo("Sending packet len %d\n", len); + +#ifndef CONFIG_NET_6LOWPAN_COMPRESSION_IPv6 + if (len >= CONFIG_NET_6LOWPAN_COMPRESSION_THRESHOLD) + { + /* Try to compress the headers */ + +#if defined(CONFIG_NET_6LOWPAN_COMPRESSION_HC1) + sixlowpan_compresshdr_hc1(dev, &dest); +#elif defined(CONFIG_NET_6LOWPAN_COMPRESSION_HC06) + sixlowpan_compresshdr_hc06(dev, &dest); +#else +# error No compression specified +#endif + } + else +#endif /* !CONFIG_NET_6LOWPAN_COMPRESSION_IPv6 */ + { + /* Small.. use IPv6 dispatch (no compression) */ + + sixlowpan_compress_ipv6hdr(ieee, ipv6); + } + + ninfo("Header of len %d\n", ieee->i_rime_hdrlen); + #warning Missing logic return -ENOSYS; } @@ -385,7 +415,7 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, */ ret = sixlowpan_send(dev, (FAR const struct ipv6_hdr_s *)&ipv6tcp, - conn->u.ipv6.raddr); + buf, len, conn->u.ipv6.raddr); if (ret < 0) { nerr("ERROR: sixlowpan_send() failed: %d\n", ret); @@ -503,7 +533,7 @@ ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, */ ret = sixlowpan_send(dev, (FAR const struct ipv6_hdr_s *)&ipv6udp, - conn->u.ipv6.raddr); + buf, len, conn->u.ipv6.raddr); if (ret < 0) { nerr("ERROR: sixlowpan_send() failed: %d\n", ret); -- GitLab From c8cb2009c82e3464355cb6ac53349a4eb35488c1 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 29 Mar 2017 17:32:12 -0600 Subject: [PATCH 268/990] 6loWPAN: Forget to add a file before last commit. --- net/sixlowpan/sixlowpan.h | 27 ++--------- net/sixlowpan/sixlowpan_send.c | 3 +- net/sixlowpan/sixlowpan_utils.c | 85 +++++++++++++++++++++++++++++++++ 3 files changed, 89 insertions(+), 26 deletions(-) create mode 100644 net/sixlowpan/sixlowpan_utils.c diff --git a/net/sixlowpan/sixlowpan.h b/net/sixlowpan/sixlowpan.h index b003445fc6..c9fd5fd7bd 100644 --- a/net/sixlowpan/sixlowpan.h +++ b/net/sixlowpan/sixlowpan.h @@ -50,10 +50,13 @@ ****************************************************************************/ /* Rime addres macros */ +/* Copy a Rime address */ #define rimeaddr_copy(dest,src) \ memcpy(dest, src, CONFIG_NET_6LOWPAN_RIMEADDR_SIZE) +/* Compare two Rime addresses */ + #define rimeaddr_cmp(addr1,addr2) \ (memcmp(addr1, addr2, CONFIG_NET_6LOWPAN_RIMEADDR_SIZE) == 0) @@ -77,10 +80,6 @@ struct sixlowpan_rime_sniffer_s; /* Foward reference */ extern FAR struct sixlowpan_rime_sniffer_s *g_sixlowpan_sniffer; #endif -/* All zero rime address */ - -extern const struct rimeaddr_s g_rimeaddr_null; - /**************************************************************************** * Public Types ****************************************************************************/ @@ -171,26 +170,6 @@ ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, size_t len); #endif -/**************************************************************************** - * Name: sixlowpan_output - * - * Description: - * Process an outgoing UDP or TCP packet. Called from UDP/TCP logic to - * determine if the the packet should be formatted for 6loWPAN output. - * - * Input Parameters: - * dev - The IEEE802.15.4 MAC network driver interface. - * - * Returned Value: - * Ok is returned on success; Othewise a negated errno value is returned. - * This function is expected to fail if the driver is not an IEEE802.15.4 - * MAC network driver. In that case, the UDP/TCP will fall back to normal - * IPv4/IPv6 formatting. - * - ****************************************************************************/ - -int sixlowpan_output(FAR struct net_driver_s *dev); - /**************************************************************************** * Name: sixlowpan_hc06_initialize * diff --git a/net/sixlowpan/sixlowpan_send.c b/net/sixlowpan/sixlowpan_send.c index 59f26959ae..20b567914e 100644 --- a/net/sixlowpan/sixlowpan_send.c +++ b/net/sixlowpan/sixlowpan_send.c @@ -236,8 +236,6 @@ static int sixlowpan_send(FAR struct net_driver_s *dev, /* Reset rime buffer, packet buffer metatadata */ - dev->d_len = 0; - sixlowpan_pktbuf_reset(ieee); ieee->i_rimeptr = &dev->d_buf[PACKETBUF_HDR_SIZE]; @@ -300,6 +298,7 @@ static int sixlowpan_send(FAR struct net_driver_s *dev, ninfo("Header of len %d\n", ieee->i_rime_hdrlen); + /* Calculate frame header length. */ #warning Missing logic return -ENOSYS; } diff --git a/net/sixlowpan/sixlowpan_utils.c b/net/sixlowpan/sixlowpan_utils.c new file mode 100644 index 0000000000..077055f081 --- /dev/null +++ b/net/sixlowpan/sixlowpan_utils.c @@ -0,0 +1,85 @@ +/**************************************************************************** + * net/sixlowpan/sixlowpan_utils.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Copyright (C) 2017, Gregory Nutt, all rights reserved + * Author: Gregory Nutt + * + * Derives from logic in Contiki: + * + * Copyright (c) 2008, Swedish Institute of Computer Science. + * All rights reserved. + * Authors: Adam Dunkels + * Nicolas Tsiftes + * Niclas Finne + * Mathilde Durvy + * Julien Abeille + * Joakim Eriksson + * Joel Hoglund + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the Institute 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 INSTITUTE 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 INSTITUTE 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 "nuttx/net/sixlowpan.h" + +#include "sixlowpan/sixlowpan.h" + +#ifdef CONFIG_NET_6LOWPAN + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: sixlowpan_pktbuf_reset + * + * Description: + * Reset all attributes and addresses in the packet buffer metadata in the + * provided IEEE802.15.4 MAC driver structure. + * + ****************************************************************************/ + +void sixlowpan_pktbuf_reset(FAR struct ieee802154_driver_s *ieee) +{ + ieee->i_dev.d_len = 0; + ieee->i_rimeptr = 0; + ieee->i_hdrptr = PACKETBUF_HDR_SIZE; + + memset(ieee->i_pktattrs, 0, PACKETBUF_NUM_ATTRS * sizeof(uint16_t)); + memset(ieee->i_pktaddrs, 0, PACKETBUF_NUM_ADDRS * sizeof(struct rimeaddr_s)); +} + +#endif /* CONFIG_NET_6LOWPAN */ -- GitLab From 2e48af78e7637a3a0a710e074ef46931e62a36f0 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 29 Mar 2017 18:07:52 -0600 Subject: [PATCH 269/990] 6loWPAN: Repartition some logic --- net/sixlowpan/Make.defs | 8 + net/sixlowpan/sixlowpan.h | 188 +--------------- net/sixlowpan/sixlowpan_compressor.c | 2 +- net/sixlowpan/sixlowpan_globals.c | 2 +- net/sixlowpan/sixlowpan_hc06.c | 2 +- net/sixlowpan/sixlowpan_hc1.c | 2 +- net/sixlowpan/sixlowpan_initialize.c | 1 + net/sixlowpan/sixlowpan_input.c | 2 +- net/sixlowpan/sixlowpan_internal.h | 307 +++++++++++++++++++++++++++ net/sixlowpan/sixlowpan_send.c | 290 ++----------------------- net/sixlowpan/sixlowpan_sniffer.c | 2 +- net/sixlowpan/sixlowpan_tcpsend.c | 180 ++++++++++++++++ net/sixlowpan/sixlowpan_udpsend.c | 181 ++++++++++++++++ net/sixlowpan/sixlowpan_utils.c | 2 +- 14 files changed, 703 insertions(+), 466 deletions(-) create mode 100644 net/sixlowpan/sixlowpan_internal.h create mode 100644 net/sixlowpan/sixlowpan_tcpsend.c create mode 100644 net/sixlowpan/sixlowpan_udpsend.c diff --git a/net/sixlowpan/Make.defs b/net/sixlowpan/Make.defs index 8494f61f3b..68b1ec5ef9 100644 --- a/net/sixlowpan/Make.defs +++ b/net/sixlowpan/Make.defs @@ -43,6 +43,14 @@ NET_CSRCS += sixlowpan_initialize.c sixlowpan_globals.c sixlowpan_utils.c NET_CSRCS += sixlowpan_input.c sixlowpan_send.c NET_CSRCS += sixlowpan_compressor.c +ifeq ($(CONFIG_NET_TCP),y) +NET_CSRCS += sixlowpan_tcpsend.c +endif + +ifeq ($(CONFIG_NET_UDP),y) +NET_CSRCS += sixlowpan_udpsend.c +endif + ifeq ($(CONFIG_NET_6LOWPAN_COMPRESSION_HC1),y) NET_CSRCS += sixlowpan_hc1.c endif diff --git a/net/sixlowpan/sixlowpan.h b/net/sixlowpan/sixlowpan.h index c9fd5fd7bd..d3660cb2ce 100644 --- a/net/sixlowpan/sixlowpan.h +++ b/net/sixlowpan/sixlowpan.h @@ -1,7 +1,7 @@ /**************************************************************************** * net/sixlowpan/sixlowpan.h * - * Copyright (C) 2016 Gregory Nutt. All rights reserved. + * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -45,41 +45,6 @@ #ifdef CONFIG_NET_6LOWPAN -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/* Rime addres macros */ -/* Copy a Rime address */ - -#define rimeaddr_copy(dest,src) \ - memcpy(dest, src, CONFIG_NET_6LOWPAN_RIMEADDR_SIZE) - -/* Compare two Rime addresses */ - -#define rimeaddr_cmp(addr1,addr2) \ - (memcmp(addr1, addr2, CONFIG_NET_6LOWPAN_RIMEADDR_SIZE) == 0) - -/**************************************************************************** - * Public Types - ****************************************************************************/ - -/**************************************************************************** - * Public Data - ****************************************************************************/ - -/* A pointer to the optional, architecture-specific compressor */ - -struct sixlowpan_nhcompressor_s; /* Foward reference */ -extern FAR struct sixlowpan_nhcompressor_s *g_sixlowpan_compressor; - -#ifdef CONFIG_NET_6LOWPAN_SNIFFER -/* Rime Sniffer support for one single listener to enable trace of IP */ - -struct sixlowpan_rime_sniffer_s; /* Foward reference */ -extern FAR struct sixlowpan_rime_sniffer_s *g_sixlowpan_sniffer; -#endif - /**************************************************************************** * Public Types ****************************************************************************/ @@ -88,10 +53,7 @@ extern FAR struct sixlowpan_rime_sniffer_s *g_sixlowpan_sniffer; * Public Function Prototypes ****************************************************************************/ -struct net_driver_s; /* Forward reference */ -struct ieee802154_driver_s; /* Forward reference */ -struct rimeaddr_s; /* Forward reference */ -struct socket; /* Forward reference */ +struct socket; /* Forward reference */ /**************************************************************************** * Name: sixlowpan_initialize @@ -170,151 +132,5 @@ ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, size_t len); #endif -/**************************************************************************** - * Name: sixlowpan_hc06_initialize - * - * Description: - * sixlowpan_hc06_initialize() is called during OS initialization at power-up - * reset. It is called from the common sixlowpan_initialize() function. - * sixlowpan_hc06_initialize() configures HC06 networking data structures. - * It is called prior to platform-specific driver initialization so that - * the 6loWPAN networking subsystem is prepared to deal with network - * driver initialization actions. - * - * Input Parameters: - * None - * - * Returned Value: - * None - * - ****************************************************************************/ - -#ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 -void sixlowpan_hc06_initialize(void); -#endif - -/**************************************************************************** - * Name: sixlowpan_hc06_initialize - * - * Description: - * Compress IP/UDP header - * - * This function is called by the 6lowpan code to create a compressed - * 6lowpan packet in the packetbuf buffer from a full IPv6 packet in the - * uip_buf buffer. - * - * HC-06 (draft-ietf-6lowpan-hc, version 6) - * http://tools.ietf.org/html/draft-ietf-6lowpan-hc-06 - * - * NOTE: sixlowpan_compresshdr_hc06() does not support ISA100_UDP header - * compression - * - * Input Parameters: - * dev - A reference to the IEE802.15.4 network device state - * destaddr - L2 destination address, needed to compress IP dest - * - * Returned Value: - * None - * - ****************************************************************************/ - -#ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 -void sixlowpan_compresshdr_hc06(FAR struct net_driver_s *dev, - FAR struct rimeaddr_s *destaddr); -#endif - -/**************************************************************************** - * Name: sixlowpan_hc06_initialize - * - * Description: - * Uncompress HC06 (i.e., IPHC and LOWPAN_UDP) headers and put them in - * sixlowpan_buf - * - * This function is called by the input function when the dispatch is HC06. - * We process the packet in the rime buffer, uncompress the header fields, - * and copy the result in the sixlowpan buffer. At the end of the - * decompression, g_rime_hdrlen and g_uncompressed_hdrlen are set to the - * appropriate values - * - * Input Parmeters: - * dev - A reference to the IEE802.15.4 network device state - * iplen - Equal to 0 if the packet is not a fragment (IP length is then - * inferred from the L2 length), non 0 if the packet is a 1st - * fragment. - * - * Returned Value: - * None - * - ****************************************************************************/ - -#ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 -void sixlowpan_uncompresshdr_hc06(FAR struct net_driver_s *dev, - uint16_t iplen); -#endif - -/**************************************************************************** - * Name: sixlowpan_compresshdr_hc1 - * - * Description: - * Compress IP/UDP header using HC1 and HC_UDP - * - * This function is called by the 6lowpan code to create a compressed - * 6lowpan packet in the packetbuf buffer from a full IPv6 packet in the - * uip_buf buffer. - * - * Input Parmeters: - * dev - A reference to the IEE802.15.4 network device state - * destaddr - L2 destination address, needed to compress the IP - * destination field - * - * Returned Value: - * None - * - ****************************************************************************/ - -#ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC1 -void sixlowpan_compresshdr_hc1(FAR struct net_driver_s *dev, - FAR struct rimeaddr_s *destaddr); -#endif - -/**************************************************************************** - * Name: sixlowpan_uncompresshdr_hc1 - * - * Description: - * Uncompress HC1 (and HC_UDP) headers and put them in sixlowpan_buf - * - * This function is called by the input function when the dispatch is - * HC1. It processes the packet in the rime buffer, uncompresses the - * header fields, and copies the result in the sixlowpan buffer. At the - * end of the decompression, g_rime_hdrlen and uncompressed_hdr_len - * are set to the appropriate values - * - * Input Parameters: - * dev - A reference to the IEE802.15.4 network device state - * iplen - Equal to 0 if the packet is not a fragment (IP length is then - * inferred from the L2 length), non 0 if the packet is a 1st - * fragment. - * - * Returned Value: - * None - * - ****************************************************************************/ - -#ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC1 -void sixlowpan_uncompresshdr_hc1(FAR struct net_driver_s *dev, - uint16_t ip_len); -#endif - -/**************************************************************************** - * Name: sixlowpan_pktbuf_reset - * - * Description: - * Reset all attributes and addresses in the packet buffer metadata in the - * provided IEEE802.15.4 MAC driver structure. - * - ****************************************************************************/ - -void sixlowpan_pktbuf_reset(FAR struct ieee802154_driver_s *ieee); - #endif /* CONFIG_NET_6LOWPAN */ #endif /* _NET_SIXLOWPAN_SIXLOWPAN_H */ diff --git a/net/sixlowpan/sixlowpan_compressor.c b/net/sixlowpan/sixlowpan_compressor.c index 3457530b79..837bad7760 100644 --- a/net/sixlowpan/sixlowpan_compressor.c +++ b/net/sixlowpan/sixlowpan_compressor.c @@ -42,7 +42,7 @@ #include "nuttx/net/net.h" #include "nuttx/net/sixlowpan.h" -#include "sixlowpan/sixlowpan.h" +#include "sixlowpan/sixlowpan_internal.h" #ifdef CONFIG_NET_6LOWPAN diff --git a/net/sixlowpan/sixlowpan_globals.c b/net/sixlowpan/sixlowpan_globals.c index ce5e06b490..4be92354dd 100644 --- a/net/sixlowpan/sixlowpan_globals.c +++ b/net/sixlowpan/sixlowpan_globals.c @@ -41,7 +41,7 @@ #include "nuttx/net/sixlowpan.h" -#include "sixlowpan/sixlowpan.h" +#include "sixlowpan/sixlowpan_internal.h" #ifdef CONFIG_NET_6LOWPAN diff --git a/net/sixlowpan/sixlowpan_hc06.c b/net/sixlowpan/sixlowpan_hc06.c index 733edc900b..b270413143 100644 --- a/net/sixlowpan/sixlowpan_hc06.c +++ b/net/sixlowpan/sixlowpan_hc06.c @@ -60,7 +60,7 @@ #include #include -#include "sixlowpan/sixlowpan.h" +#include "sixlowpan/sixlowpan_internal.h" #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 diff --git a/net/sixlowpan/sixlowpan_hc1.c b/net/sixlowpan/sixlowpan_hc1.c index 3f9b93f17d..245a7465c2 100644 --- a/net/sixlowpan/sixlowpan_hc1.c +++ b/net/sixlowpan/sixlowpan_hc1.c @@ -49,7 +49,7 @@ #include #include -#include "sixlowpan/sixlowpan.h" +#include "sixlowpan/sixlowpan_internal.h" #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC1 diff --git a/net/sixlowpan/sixlowpan_initialize.c b/net/sixlowpan/sixlowpan_initialize.c index 07e10b6a37..54e32b8401 100644 --- a/net/sixlowpan/sixlowpan_initialize.c +++ b/net/sixlowpan/sixlowpan_initialize.c @@ -40,6 +40,7 @@ #include #include "sixlowpan/sixlowpan.h" +#include "sixlowpan/sixlowpan_internal.h" #ifdef CONFIG_NET_6LOWPAN diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index f28c0eafda..964d988be7 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -42,7 +42,7 @@ #include #include "nuttx/net/netdev.h" -#include "sixlowpan/sixlowpan.h" +#include "sixlowpan/sixlowpan_internal.h" #ifdef CONFIG_NET_6LOWPAN diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h new file mode 100644 index 0000000000..453d340dba --- /dev/null +++ b/net/sixlowpan/sixlowpan_internal.h @@ -0,0 +1,307 @@ +/**************************************************************************** + * net/sixlowpan/sixlowpan_internal.h + * + * 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. + * + ****************************************************************************/ + +#ifndef _NET_SIXLOWPAN_SIXLOWPAN_INTERNAL_H +#define _NET_SIXLOWPAN_SIXLOWPAN_INTERNAL_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include + +#ifdef CONFIG_NET_6LOWPAN + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Rime addres macros */ +/* Copy a Rime address */ + +#define rimeaddr_copy(dest,src) \ + memcpy(dest, src, CONFIG_NET_6LOWPAN_RIMEADDR_SIZE) + +/* Compare two Rime addresses */ + +#define rimeaddr_cmp(addr1,addr2) \ + (memcmp(addr1, addr2, CONFIG_NET_6LOWPAN_RIMEADDR_SIZE) == 0) + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* IPv6 + TCP header */ + +struct ipv6tcp_hdr_s +{ + struct ipv6_hdr_s ipv6; + struct tcp_hdr_s tcp; +}; + +/* IPv6 + UDP header */ + +struct ipv6udp_hdr_s +{ + struct ipv6_hdr_s ipv6; + struct udp_hdr_s udp; +}; + +/* IPv6 + ICMPv6 header */ + +struct ipv6icmp_hdr_s +{ + struct ipv6_hdr_s ipv6; + struct icmpv6_iphdr_s icmp; +}; + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/* A pointer to the optional, architecture-specific compressor */ + +struct sixlowpan_nhcompressor_s; /* Foward reference */ +extern FAR struct sixlowpan_nhcompressor_s *g_sixlowpan_compressor; + +#ifdef CONFIG_NET_6LOWPAN_SNIFFER +/* Rime Sniffer support for one single listener to enable trace of IP */ + +struct sixlowpan_rime_sniffer_s; /* Foward reference */ +extern FAR struct sixlowpan_rime_sniffer_s *g_sixlowpan_sniffer; +#endif + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +struct net_driver_s; /* Forward reference */ +struct ieee802154_driver_s; /* Forward reference */ +struct rimeaddr_s; /* Forward reference */ + +/**************************************************************************** + * Name: sixlowpan_send + * + * Description: + * Process an outgoing UDP or TCP packet. Takes an IP packet and formats + * it to be sent on an 802.15.4 network using 6lowpan. Called from common + * UDP/TCP send logic. + * + * The payload data is in the caller 'buf' and is of length 'len'. + * Compressed headers will be added and if necessary the packet is + * fragmented. The resulting packet/fragments are put in dev->d_buf and + * the first frame will be delivered to the 802.15.4 MAC. via ieee->i_frame. + * + * Input Parmeters: + * + * Input Parameters: + * dev - The IEEE802.15.4 MAC network driver interface. + * ipv6 - IPv6 plus TCP or UDP headers. + * buf - Data to send + * len - Length of data to send + * raddr - The MAC address of the destination + * + * Returned Value: + * Ok is returned on success; Othewise a negated errno value is returned. + * This function is expected to fail if the driver is not an IEEE802.15.4 + * MAC network driver. In that case, the UDP/TCP will fall back to normal + * IPv4/IPv6 formatting. + * + * Assumptions: + * Called with the network locked. + * + ****************************************************************************/ + +int sixlowpan_send(FAR struct net_driver_s *dev, + FAR const struct ipv6_hdr_s *ipv6, FAR const void *buf, + size_t len, FAR const struct rimeaddr_s *raddr); + +/**************************************************************************** + * Name: sixlowpan_hc06_initialize + * + * Description: + * sixlowpan_hc06_initialize() is called during OS initialization at power-up + * reset. It is called from the common sixlowpan_initialize() function. + * sixlowpan_hc06_initialize() configures HC06 networking data structures. + * It is called prior to platform-specific driver initialization so that + * the 6loWPAN networking subsystem is prepared to deal with network + * driver initialization actions. + * + * Input Parameters: + * None + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 +void sixlowpan_hc06_initialize(void); +#endif + +/**************************************************************************** + * Name: sixlowpan_hc06_initialize + * + * Description: + * Compress IP/UDP header + * + * This function is called by the 6lowpan code to create a compressed + * 6lowpan packet in the packetbuf buffer from a full IPv6 packet in the + * uip_buf buffer. + * + * HC-06 (draft-ietf-6lowpan-hc, version 6) + * http://tools.ietf.org/html/draft-ietf-6lowpan-hc-06 + * + * NOTE: sixlowpan_compresshdr_hc06() does not support ISA100_UDP header + * compression + * + * Input Parameters: + * dev - A reference to the IEE802.15.4 network device state + * destaddr - L2 destination address, needed to compress IP dest + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 +void sixlowpan_compresshdr_hc06(FAR struct net_driver_s *dev, + FAR struct rimeaddr_s *destaddr); +#endif + +/**************************************************************************** + * Name: sixlowpan_hc06_initialize + * + * Description: + * Uncompress HC06 (i.e., IPHC and LOWPAN_UDP) headers and put them in + * sixlowpan_buf + * + * This function is called by the input function when the dispatch is HC06. + * We process the packet in the rime buffer, uncompress the header fields, + * and copy the result in the sixlowpan buffer. At the end of the + * decompression, g_rime_hdrlen and g_uncompressed_hdrlen are set to the + * appropriate values + * + * Input Parmeters: + * dev - A reference to the IEE802.15.4 network device state + * iplen - Equal to 0 if the packet is not a fragment (IP length is then + * inferred from the L2 length), non 0 if the packet is a 1st + * fragment. + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 +void sixlowpan_uncompresshdr_hc06(FAR struct net_driver_s *dev, + uint16_t iplen); +#endif + +/**************************************************************************** + * Name: sixlowpan_compresshdr_hc1 + * + * Description: + * Compress IP/UDP header using HC1 and HC_UDP + * + * This function is called by the 6lowpan code to create a compressed + * 6lowpan packet in the packetbuf buffer from a full IPv6 packet in the + * uip_buf buffer. + * + * Input Parmeters: + * dev - A reference to the IEE802.15.4 network device state + * destaddr - L2 destination address, needed to compress the IP + * destination field + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC1 +void sixlowpan_compresshdr_hc1(FAR struct net_driver_s *dev, + FAR struct rimeaddr_s *destaddr); +#endif + +/**************************************************************************** + * Name: sixlowpan_uncompresshdr_hc1 + * + * Description: + * Uncompress HC1 (and HC_UDP) headers and put them in sixlowpan_buf + * + * This function is called by the input function when the dispatch is + * HC1. It processes the packet in the rime buffer, uncompresses the + * header fields, and copies the result in the sixlowpan buffer. At the + * end of the decompression, g_rime_hdrlen and uncompressed_hdr_len + * are set to the appropriate values + * + * Input Parameters: + * dev - A reference to the IEE802.15.4 network device state + * iplen - Equal to 0 if the packet is not a fragment (IP length is then + * inferred from the L2 length), non 0 if the packet is a 1st + * fragment. + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC1 +void sixlowpan_uncompresshdr_hc1(FAR struct net_driver_s *dev, + uint16_t ip_len); +#endif + +/**************************************************************************** + * Name: sixlowpan_pktbuf_reset + * + * Description: + * Reset all attributes and addresses in the packet buffer metadata in the + * provided IEEE802.15.4 MAC driver structure. + * + ****************************************************************************/ + +void sixlowpan_pktbuf_reset(FAR struct ieee802154_driver_s *ieee); + +#endif /* CONFIG_NET_6LOWPAN */ +#endif /* _NET_SIXLOWPAN_SIXLOWPAN_INTERNAL_H */ diff --git a/net/sixlowpan/sixlowpan_send.c b/net/sixlowpan/sixlowpan_send.c index 20b567914e..d204e5eeca 100644 --- a/net/sixlowpan/sixlowpan_send.c +++ b/net/sixlowpan/sixlowpan_send.c @@ -55,38 +55,10 @@ #include "socket/socket.h" #include "tcp/tcp.h" #include "udp/udp.h" -#include "sixlowpan/sixlowpan.h" +#include "sixlowpan/sixlowpan_internal.h" #ifdef CONFIG_NET_6LOWPAN -/**************************************************************************** - * Private Types - ****************************************************************************/ - -/* IPv6 + TCP header */ - -struct ipv6tcp_hdr_s -{ - struct ipv6_hdr_s ipv6; - struct tcp_hdr_s tcp; -}; - -/* IPv6 + UDP header */ - -struct ipv6udp_hdr_s -{ - struct ipv6_hdr_s ipv6; - struct udp_hdr_s udp; -}; - -/* IPv6 + ICMPv6 header */ - -struct ipv6icmp_hdr_s -{ - struct ipv6_hdr_s ipv6; - struct icmpv6_iphdr_s icmp; -}; - /**************************************************************************** * Private Functions ****************************************************************************/ @@ -186,6 +158,10 @@ static void sixlowpan_compress_ipv6hdr(FAR struct ieee802154_driver_s *ieee, ieee->i_uncomp_hdrlen += IPv6_HDRLEN; } +/**************************************************************************** + * Public Functions + ****************************************************************************/ + /**************************************************************************** * Name: sixlowpan_send * @@ -206,7 +182,7 @@ static void sixlowpan_compress_ipv6hdr(FAR struct ieee802154_driver_s *ieee, * ipv6 - IPv6 plus TCP or UDP headers. * buf - Data to send * len - Length of data to send - * raddr - The MAC address of the destination + * raddr - The IEEE802.15.4 MAC address of the destination * * Returned Value: * Ok is returned on success; Othewise a negated errno value is returned. @@ -219,9 +195,9 @@ static void sixlowpan_compress_ipv6hdr(FAR struct ieee802154_driver_s *ieee, * ****************************************************************************/ -static int sixlowpan_send(FAR struct net_driver_s *dev, - FAR const struct ipv6_hdr_s *ipv6, FAR const void *buf, - size_t len, net_ipv6addr_t raddr) +int sixlowpan_send(FAR struct net_driver_s *dev, + FAR const struct ipv6_hdr_s *ipv6, FAR const void *buf, + size_t len, FAR const struct rimeaddr_s *raddr) { FAR struct ieee802154_driver_s *ieee = (FAR struct ieee802154_driver_s *)dev; @@ -271,7 +247,14 @@ static int sixlowpan_send(FAR struct net_driver_s *dev, * argument raddr is NULL, we are sending a broadcast packet. */ -#warning Missing logic + if (raddr == NULL) + { + memset(&dest, 0, sizeof(struct rimeaddr_s)); + } + else + { + rimeaddr_copy(&dest, (FAR const struct rimeaddr_s *)raddr); + } ninfo("Sending packet len %d\n", len); @@ -303,243 +286,4 @@ static int sixlowpan_send(FAR struct net_driver_s *dev, return -ENOSYS; } -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: psock_6lowpan_tcp_send - * - * Description: - * psock_6lowpan_tcp_send() call may be used only when the TCP socket is in a - * connected state (so that the intended recipient is known). - * - * Parameters: - * psock - An instance of the internal socket structure. - * buf - Data to send - * len - Length of data to send - * - * Returned Value: - * On success, returns the number of characters sent. On error, - * -1 is returned, and errno is set appropriately. Returned error numbers - * must be consistent with definition of errors reported by send() or - * sendto(). - * - * Assumptions: - * Called with the network locked. - * - ****************************************************************************/ - -#ifdef CONFIG_NET_TCP -ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, - size_t len) -{ - FAR struct tcp_conn_s *conn; - FAR struct net_driver_s *dev; - struct ipv6tcp_hdr_s ipv6tcp; - int ret; - - DEBUGASSERT(psock != NULL && psock->s_crefs > 0); - DEBUGASSERT(psock->s_type == SOCK_STREAM); - - /* Make sure that this is a valid socket */ - - if (psock != NULL || psock->s_crefs <= 0) - { - nerr("ERROR: Invalid socket\n"); - return (ssize_t)-EBADF; - } - - /* Make sure that this is a connected TCP socket */ - - if (psock->s_type != SOCK_STREAM || !_SS_ISCONNECTED(psock->s_flags)) - { - nerr("ERROR: Not connected\n"); - return (ssize_t)-ENOTCONN; - } - - /* Get the underlying TCP connection structure */ - - conn = (FAR struct tcp_conn_s *)psock->s_conn; - DEBUGASSERT(conn != NULL); - -#if defined(CONFIG_NET_IPv4) && defined(CONFIG_NET_IPv6) - /* Ignore if not IPv6 domain */ - - if (conn->domain != PF_INET6) - { - nwarn("WARNING: Not IPv6\n"); - return (ssize_t)-EPROTOTYPE; - } -#endif - - /* Route outgoing message to the correct device */ - -#ifdef CONFIG_NETDEV_MULTINIC - dev = netdev_findby_ipv6addr(conn->u.ipv6.laddr, conn->u.ipv6.raddr); - if (dev == NULL || dev->d_lltype != NET_LL_IEEE805154) - { - nwarn("WARNING: Not routable or not IEEE802.15.4 MAC\n"); - return (ssize_t)-ENETUNREACH; - } -#else - dev = netdev_findby_ipv6addr(conn->u.ipv6.raddr); - if (dev == NULL) - { - nwarn("WARNING: Not routable\n"); - return (ssize_t)-ENETUNREACH; - } -#endif - -#ifdef CONFIG_NET_ICMPv6_NEIGHBOR - /* Make sure that the IP address mapping is in the Neighbor Table */ - - ret = icmpv6_neighbor(conn->u.ipv6.raddr); - if (ret < 0) - { - nerr("ERROR: Not reachable\n"); - return (ssize_t)-ENETUNREACH; - } -#endif - - /* Initialize the IPv6/TCP headers */ -#warning Missing logic - - /* Set the socket state to sending */ - - psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_SEND); - - /* If routable, then call sixlowpan_send() to format and send the 6loWPAN - * packet. - */ - - ret = sixlowpan_send(dev, (FAR const struct ipv6_hdr_s *)&ipv6tcp, - buf, len, conn->u.ipv6.raddr); - if (ret < 0) - { - nerr("ERROR: sixlowpan_send() failed: %d\n", ret); - } - - return ret; -} -#endif - -/**************************************************************************** - * Function: psock_6lowpan_udp_send - * - * Description: - * psock_6lowpan_udp_send() call may be used with connectionlesss UDP - * sockets. - * - * Parameters: - * psock - An instance of the internal socket structure. - * buf - Data to send - * len - Length of data to send - * - * Returned Value: - * On success, returns the number of characters sent. On error, - * -1 is returned, and errno is set appropriately. Returned error numbers - * must be consistent with definition of errors reported by send() or - * sendto(). - * - * Assumptions: - * Called with the network locked. - * - ****************************************************************************/ - -#ifdef CONFIG_NET_UDP -ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, - size_t len) -{ - FAR struct udp_conn_s *conn; - FAR struct net_driver_s *dev; - struct ipv6udp_hdr_s ipv6udp; - int ret; - - DEBUGASSERT(psock != NULL && psock->s_crefs > 0); - DEBUGASSERT(psock->s_type == SOCK_DGRAM); - - /* Make sure that this is a valid socket */ - - if (psock != NULL || psock->s_crefs <= 0) - { - nerr("ERROR: Invalid socket\n"); - return (ssize_t)-EBADF; - } - - /* Was the UDP socket connected via connect()? */ - - if (psock->s_type != SOCK_DGRAM || !_SS_ISCONNECTED(psock->s_flags)) - { - /* No, then it is not legal to call send() with this socket. */ - - return -ENOTCONN; - } - - /* Get the underlying UDP "connection" structure */ - - conn = (FAR struct udp_conn_s *)psock->s_conn; - DEBUGASSERT(conn != NULL); - -#if defined(CONFIG_NET_IPv4) && defined(CONFIG_NET_IPv6) - /* Ignore if not IPv6 domain */ - - if (conn->domain != PF_INET6) - { - nwarn("WARNING: Not IPv6\n"); - return (ssize_t)-EPROTOTYPE; - } -#endif - - /* Route outgoing message to the correct device */ - -#ifdef CONFIG_NETDEV_MULTINIC - dev = netdev_findby_ipv6addr(conn->u.ipv6.laddr, conn->u.ipv6.raddr); - if (dev == NULL || dev->d_lltype != NET_LL_IEEE805154) - { - nwarn("WARNING: Not routable or not IEEE802.15.4 MAC\n"); - return (ssize_t)-ENETUNREACH; - } -#else - dev = netdev_findby_ipv6addr(conn->u.ipv6.raddr); - if (dev == NULL) - { - nwarn("WARNING: Not routable\n"); - return (ssize_t)-ENETUNREACH; - } -#endif - -#ifdef CONFIG_NET_ICMPv6_NEIGHBOR - /* Make sure that the IP address mapping is in the Neighbor Table */ - - ret = icmpv6_neighbor(conn->u.ipv6.raddr); - if (ret < 0) - { - nerr("ERROR: Not reachable\n"); - return (ssize_t)-ENETUNREACH; - } -#endif - - /* Initialize the IPv6/UDP headers */ -#warning Missing logic - - /* Set the socket state to sending */ - - psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_SEND); - - /* If routable, then call sixlowpan_send() to format and send the 6loWPAN - * packet. - */ - - ret = sixlowpan_send(dev, (FAR const struct ipv6_hdr_s *)&ipv6udp, - buf, len, conn->u.ipv6.raddr); - if (ret < 0) - { - nerr("ERROR: sixlowpan_send() failed: %d\n", ret); - } - - return ret; -} -#endif - #endif /* CONFIG_NET_6LOWPAN */ diff --git a/net/sixlowpan/sixlowpan_sniffer.c b/net/sixlowpan/sixlowpan_sniffer.c index f6134a86f0..32a2e3121e 100644 --- a/net/sixlowpan/sixlowpan_sniffer.c +++ b/net/sixlowpan/sixlowpan_sniffer.c @@ -42,7 +42,7 @@ #include "nuttx/net/net.h" #include "nuttx/net/sixlowpan.h" -#include "sixlowpan/sixlowpan.h" +#include "sixlowpan/sixlowpan_internal.h" #ifdef CONFIG_NET_6LOWPAN_SNIFFER diff --git a/net/sixlowpan/sixlowpan_tcpsend.c b/net/sixlowpan/sixlowpan_tcpsend.c new file mode 100644 index 0000000000..9928bc3d11 --- /dev/null +++ b/net/sixlowpan/sixlowpan_tcpsend.c @@ -0,0 +1,180 @@ +/**************************************************************************** + * net/sixlowpan/sixlowpan_tcpsend.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include "nuttx/net/netdev.h" +#include "nuttx/net/tcp.h" +#include "nuttx/net/sixlowpan.h" + +#include "netdev/netdev.h" +#include "socket/socket.h" +#include "tcp/tcp.h" +#include "sixlowpan/sixlowpan_internal.h" + +#if defined(CONFIG_NET_6LOWPAN) && defined(CONFIG_NET_TCP) + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: psock_6lowpan_tcp_send + * + * Description: + * psock_6lowpan_tcp_send() call may be used only when the TCP socket is in a + * connected state (so that the intended recipient is known). + * + * Parameters: + * psock - An instance of the internal socket structure. + * buf - Data to send + * len - Length of data to send + * + * Returned Value: + * On success, returns the number of characters sent. On error, + * -1 is returned, and errno is set appropriately. Returned error numbers + * must be consistent with definition of errors reported by send() or + * sendto(). + * + * Assumptions: + * Called with the network locked. + * + ****************************************************************************/ + +ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, + size_t len) +{ + FAR struct tcp_conn_s *conn; + FAR struct net_driver_s *dev; + struct ipv6tcp_hdr_s ipv6tcp; + struct rimeaddr_s dest; + int ret; + + DEBUGASSERT(psock != NULL && psock->s_crefs > 0); + DEBUGASSERT(psock->s_type == SOCK_STREAM); + + /* Make sure that this is a valid socket */ + + if (psock != NULL || psock->s_crefs <= 0) + { + nerr("ERROR: Invalid socket\n"); + return (ssize_t)-EBADF; + } + + /* Make sure that this is a connected TCP socket */ + + if (psock->s_type != SOCK_STREAM || !_SS_ISCONNECTED(psock->s_flags)) + { + nerr("ERROR: Not connected\n"); + return (ssize_t)-ENOTCONN; + } + + /* Get the underlying TCP connection structure */ + + conn = (FAR struct tcp_conn_s *)psock->s_conn; + DEBUGASSERT(conn != NULL); + +#if defined(CONFIG_NET_IPv4) && defined(CONFIG_NET_IPv6) + /* Ignore if not IPv6 domain */ + + if (conn->domain != PF_INET6) + { + nwarn("WARNING: Not IPv6\n"); + return (ssize_t)-EPROTOTYPE; + } +#endif + + /* Route outgoing message to the correct device */ + +#ifdef CONFIG_NETDEV_MULTINIC + dev = netdev_findby_ipv6addr(conn->u.ipv6.laddr, conn->u.ipv6.raddr); + if (dev == NULL || dev->d_lltype != NET_LL_IEEE805154) + { + nwarn("WARNING: Not routable or not IEEE802.15.4 MAC\n"); + return (ssize_t)-ENETUNREACH; + } +#else + dev = netdev_findby_ipv6addr(conn->u.ipv6.raddr); + if (dev == NULL) + { + nwarn("WARNING: Not routable\n"); + return (ssize_t)-ENETUNREACH; + } +#endif + +#ifdef CONFIG_NET_ICMPv6_NEIGHBOR + /* Make sure that the IP address mapping is in the Neighbor Table */ + + ret = icmpv6_neighbor(conn->u.ipv6.raddr); + if (ret < 0) + { + nerr("ERROR: Not reachable\n"); + return (ssize_t)-ENETUNREACH; + } +#endif + + /* Initialize the IPv6/TCP headers */ +#warning Missing logic + + /* Set the socket state to sending */ + + psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_SEND); + + /* Get the Rime MAC address of the destination */ +#warning Missing logic + + /* If routable, then call sixlowpan_send() to format and send the 6loWPAN + * packet. + */ + + ret = sixlowpan_send(dev, (FAR const struct ipv6_hdr_s *)&ipv6tcp, + buf, len, &dest); + if (ret < 0) + { + nerr("ERROR: sixlowpan_send() failed: %d\n", ret); + } + + return ret; +} + +#endif /* CONFIG_NET_6LOWPAN && CONFIG_NET_TCP */ diff --git a/net/sixlowpan/sixlowpan_udpsend.c b/net/sixlowpan/sixlowpan_udpsend.c new file mode 100644 index 0000000000..9946516e00 --- /dev/null +++ b/net/sixlowpan/sixlowpan_udpsend.c @@ -0,0 +1,181 @@ +/**************************************************************************** + * net/sixlowpan/sixlowpan_udpsend.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include "nuttx/net/netdev.h" +#include "nuttx/net/udp.h" +#include "nuttx/net/sixlowpan.h" + +#include "netdev/netdev.h" +#include "socket/socket.h" +#include "udp/udp.h" +#include "sixlowpan/sixlowpan_internal.h" + +#if defined(CONFIG_NET_6LOWPAN) && defined(CONFIG_NET_UDP) + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: psock_6lowpan_udp_send + * + * Description: + * psock_6lowpan_udp_send() call may be used with connectionlesss UDP + * sockets. + * + * Parameters: + * psock - An instance of the internal socket structure. + * buf - Data to send + * len - Length of data to send + * + * Returned Value: + * On success, returns the number of characters sent. On error, + * -1 is returned, and errno is set appropriately. Returned error numbers + * must be consistent with definition of errors reported by send() or + * sendto(). + * + * Assumptions: + * Called with the network locked. + * + ****************************************************************************/ + +ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, + size_t len) +{ + FAR struct udp_conn_s *conn; + FAR struct net_driver_s *dev; + struct ipv6udp_hdr_s ipv6udp; + struct rimeaddr_s dest; + int ret; + + DEBUGASSERT(psock != NULL && psock->s_crefs > 0); + DEBUGASSERT(psock->s_type == SOCK_DGRAM); + + /* Make sure that this is a valid socket */ + + if (psock != NULL || psock->s_crefs <= 0) + { + nerr("ERROR: Invalid socket\n"); + return (ssize_t)-EBADF; + } + + /* Was the UDP socket connected via connect()? */ + + if (psock->s_type != SOCK_DGRAM || !_SS_ISCONNECTED(psock->s_flags)) + { + /* No, then it is not legal to call send() with this socket. */ + + return -ENOTCONN; + } + + /* Get the underlying UDP "connection" structure */ + + conn = (FAR struct udp_conn_s *)psock->s_conn; + DEBUGASSERT(conn != NULL); + +#if defined(CONFIG_NET_IPv4) && defined(CONFIG_NET_IPv6) + /* Ignore if not IPv6 domain */ + + if (conn->domain != PF_INET6) + { + nwarn("WARNING: Not IPv6\n"); + return (ssize_t)-EPROTOTYPE; + } +#endif + + /* Route outgoing message to the correct device */ + +#ifdef CONFIG_NETDEV_MULTINIC + dev = netdev_findby_ipv6addr(conn->u.ipv6.laddr, conn->u.ipv6.raddr); + if (dev == NULL || dev->d_lltype != NET_LL_IEEE805154) + { + nwarn("WARNING: Not routable or not IEEE802.15.4 MAC\n"); + return (ssize_t)-ENETUNREACH; + } +#else + dev = netdev_findby_ipv6addr(conn->u.ipv6.raddr); + if (dev == NULL) + { + nwarn("WARNING: Not routable\n"); + return (ssize_t)-ENETUNREACH; + } +#endif + +#ifdef CONFIG_NET_ICMPv6_NEIGHBOR + /* Make sure that the IP address mapping is in the Neighbor Table */ + + ret = icmpv6_neighbor(conn->u.ipv6.raddr); + if (ret < 0) + { + nerr("ERROR: Not reachable\n"); + return (ssize_t)-ENETUNREACH; + } +#endif + + /* Initialize the IPv6/UDP headers */ +#warning Missing logic + + /* Set the socket state to sending */ + + psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_SEND); + + /* Get the Rime MAC address of the destination */ +#warning Missing logic + + /* If routable, then call sixlowpan_send() to format and send the 6loWPAN + * packet. + */ + + ret = sixlowpan_send(dev, (FAR const struct ipv6_hdr_s *)&ipv6udp, + buf, len, &dest); + if (ret < 0) + { + nerr("ERROR: sixlowpan_send() failed: %d\n", ret); + } + + return ret; +} + +#endif /* CONFIG_NET_6LOWPAN && CONFIG_NET_UDP */ diff --git a/net/sixlowpan/sixlowpan_utils.c b/net/sixlowpan/sixlowpan_utils.c index 077055f081..5df1b3439c 100644 --- a/net/sixlowpan/sixlowpan_utils.c +++ b/net/sixlowpan/sixlowpan_utils.c @@ -55,7 +55,7 @@ #include "nuttx/net/sixlowpan.h" -#include "sixlowpan/sixlowpan.h" +#include "sixlowpan/sixlowpan_internal.h" #ifdef CONFIG_NET_6LOWPAN -- GitLab From 21545ab6434e78390bf29fdbfb4462bc12b9c645 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Thu, 30 Mar 2017 06:54:59 -0600 Subject: [PATCH 270/990] net/local: connect: Fix warning with gcc-arm-none-eabi-5-2016q1. Using compiler from gcc-arm-none-eabi-5-2016q1 toolchain: gcc version 5.3.1 20160307 (release) [ARM/embedded-5-branch revision 234589] (GNU Tools for ARM Embedded Processors) gives error: local/local_connect.c:188:7: error: '_local_semtake' is static but used in inline function 'local_stream_connect' which is not static [-Werror] this is due to compiler enforcing ISO/IEC 9899:1999 6.7.4.3: "An inline definition of a function with external linkage shall not contain a definition of a modifiable object with static storage duration, and shall not contain a reference to an identifier with internal linkage." Fix by making inlined caller to have internal linkage as well. --- net/local/local_connect.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/net/local/local_connect.c b/net/local/local_connect.c index 53dd321905..ee9a1dc2c9 100644 --- a/net/local/local_connect.c +++ b/net/local/local_connect.c @@ -121,9 +121,9 @@ static inline void _local_semtake(sem_t *sem) * ****************************************************************************/ -int inline local_stream_connect(FAR struct local_conn_s *client, - FAR struct local_conn_s *server, - bool nonblock) +static int inline local_stream_connect(FAR struct local_conn_s *client, + FAR struct local_conn_s *server, + bool nonblock) { int ret; -- GitLab From dffb8a67e3e92500651db3eca516dbcfc275311a Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Thu, 30 Mar 2017 07:38:37 -0600 Subject: [PATCH 271/990] Add entropy pool and strong random number generator Entropy pool gathers environmental noise from device drivers, user-space, etc., and returns good random numbers, suitable for cryptographic use. Based on entropy pool design from *BSDs and uses BLAKE2Xs algorithm for CSPRNG output. Patch also adds /dev/urandom support for using entropy pool RNG and new 'getrandom' system call for getting randomness without file-descriptor usage (thus avoiding file-descriptor exhaustion attacks). The 'getrandom' interface is similar as 'getentropy' and 'getrandom' available on OpenBSD and Linux respectively. --- configs/Kconfig | 21 ++ crypto/Kconfig | 31 ++ crypto/Makefile | 14 +- crypto/blake2s.c | 606 +++++++++++++++++++++++++++++++ crypto/random_pool.c | 561 ++++++++++++++++++++++++++++ drivers/Kconfig | 9 + drivers/analog/adc.c | 5 + drivers/dev_urandom.c | 72 +++- drivers/input/ads7843e.c | 3 + drivers/input/ajoystick.c | 3 + drivers/input/button_upper.c | 3 + drivers/input/djoystick.c | 3 + drivers/input/max11802.c | 3 + drivers/input/mxt.c | 3 + drivers/input/stmpe811_temp.c | 3 + drivers/input/stmpe811_tsc.c | 3 + drivers/input/tsc2007.c | 5 +- drivers/sensors/adxl345_base.c | 4 + drivers/sensors/bh1750fvi.c | 3 + drivers/sensors/bmg160.c | 5 + drivers/sensors/bmp180.c | 5 + drivers/sensors/kxtj9.c | 7 + drivers/sensors/l3gd20.c | 5 + drivers/sensors/lis331dl.c | 6 + drivers/sensors/lis3dsh.c | 5 + drivers/sensors/lis3mdl.c | 6 + drivers/sensors/lm75.c | 3 + drivers/sensors/lm92.c | 3 + drivers/sensors/lsm9ds1.c | 10 + drivers/sensors/max31855.c | 5 + drivers/sensors/max6675.c | 5 + drivers/sensors/mb7040.c | 5 + drivers/sensors/mcp9844.c | 5 + drivers/sensors/mlx90393.c | 6 + drivers/sensors/mpl115a.c | 6 + drivers/sensors/ms58xx.c | 3 + drivers/sensors/veml6070.c | 5 + drivers/sensors/xen1210.c | 7 + include/nuttx/board.h | 16 + include/nuttx/crypto/blake2s.h | 197 ++++++++++ include/nuttx/random.h | 171 +++++++++ include/string.h | 2 + include/sys/random.h | 77 ++++ include/sys/syscall.h | 15 +- libc/string/Make.defs | 1 + libc/string/lib_explicit_bzero.c | 56 +++ sched/irq/irq_dispatch.c | 9 +- syscall/syscall.csv | 1 + syscall/syscall_lookup.h | 7 + syscall/syscall_stublookup.c | 5 + 50 files changed, 2005 insertions(+), 9 deletions(-) create mode 100644 crypto/blake2s.c create mode 100644 crypto/random_pool.c create mode 100644 include/nuttx/crypto/blake2s.h create mode 100644 include/nuttx/random.h create mode 100644 include/sys/random.h create mode 100644 libc/string/lib_explicit_bzero.c diff --git a/configs/Kconfig b/configs/Kconfig index aef29eecd6..27d98e0821 100644 --- a/configs/Kconfig +++ b/configs/Kconfig @@ -2015,6 +2015,27 @@ config BOARD_RESET_ON_CRASH If selected the board_crashdump should reset the machine after saveing the state of the machine +config BOARD_ENTROPY_POOL + bool "Enable Board level storing of entropy pool structure" + default n + depends on CRYPTO_RANDOM_POOL + ---help--- + Entropy pool structure can be provided by board source. + Use for this is, for example, to allocate entropy pool + from special area of RAM which content is kept over + system reset. + +config BOARD_INITRNGSEED + bool "Enable Board level initial seeding of entropy pool RNG" + default n + depends on CRYPTO_RANDOM_POOL + ---help--- + If enabled, entropy pool random number generator will call + board_init_rndseed() upon initialization. This function + can then provide early entropy seed to the pool through + entropy injection APIs provided at 'nuttx/random.h'. +#endif + config LIB_BOARDCTL bool "Enable boardctl() interface" default n diff --git a/crypto/Kconfig b/crypto/Kconfig index 022fce7a05..0c93eaaa99 100644 --- a/crypto/Kconfig +++ b/crypto/Kconfig @@ -50,4 +50,35 @@ config CRYPTO_SW_AES implemenations. This needs to support up_aesinitialize() and aes_cypher() per include/nuttx/crypto/crypto.h. +config CRYPTO_BLAKE2S + bool "BLAKE2s hash algorithm" + default n + ---help--- + Enable the BLAKE2s hash algorithm + +config CRYPTO_RANDOM_POOL + bool "Entropy pool and strong randon number generator" + default n + select CRYPTO_BLAKE2S + ---help--- + Entropy pool gathers environmental noise from device drivers, + user-space, etc., and returns good random numbers, suitable + for cryptographic use. Based on entropy pool design from + *BSDs and uses BLAKE2Xs algorithm for CSPRNG output. + + NOTE: May not actually be cyptographically secure, if + not enough entropy is made available to the entropy pool. + +if CRYPTO_RANDOM_POOL + +config CRYPTO_RANDOM_POOL_COLLECT_IRQ_RANDOMNESS + bool "Use interrupts to feed timing randomness to entropy pool" + default y + ---help--- + Feed entropy pool with interrupt randomness from interrupt + dispatch function 'irq_dispatch'. This adds some overhead + for every interrupt handled. + +endif # CRYPTO_RANDOM_POOL + endif # CRYPTO diff --git a/crypto/Makefile b/crypto/Makefile index 23b4cf137e..56b75b6517 100644 --- a/crypto/Makefile +++ b/crypto/Makefile @@ -56,6 +56,18 @@ ifeq ($(CONFIG_CRYPTO_SW_AES),y) CRYPTO_CSRCS += aes.c endif +# BLAKE2s hash algorithm + +ifeq ($(CONFIG_CRYPTO_BLAKE2S),y) + CRYPTO_CSRCS += blake2s.c +endif + +# Entropy pool random number generator + +ifeq ($(CONFIG_CRYPTO_RANDOM_POOL),y) + CRYPTO_CSRCS += random_pool.c +endif + endif # CONFIG_CRYPTO ASRCS = $(CRYPTO_ASRCS) @@ -97,4 +109,4 @@ distclean: clean $(call DELFILE, Make.dep) $(call DELFILE, .depend) --include Make.dep \ No newline at end of file +-include Make.dep diff --git a/crypto/blake2s.c b/crypto/blake2s.c new file mode 100644 index 0000000000..a88ed045c5 --- /dev/null +++ b/crypto/blake2s.c @@ -0,0 +1,606 @@ +/**************************************************************************** + * crypto/blake2s.c + * + * This code is based on public-domain/CC0 BLAKE2 reference implementation + * by Samual Neves, at https://github.com/BLAKE2/BLAKE2/tree/master/ref + * Copyright 2012, Samuel Neves + * + * Copyright (C) 2017 Haltian Ltd. All rights reserved. + * Authors: Jussi Kivilinna + * + * 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 + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const uint32_t blake2s_IV[8] = +{ + 0x6a09e667ul, 0xbb67ae85ul, 0x3c6ef372ul, 0xa54ff53aul, 0x510e527ful, + 0x9b05688cul, 0x1f83d9abul, 0x5be0cd19ul +}; + +static const uint8_t blake2s_sigma[10][16] = +{ + { 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15 }, + { 14, 10, 4, 8, 9, 15, 13, 6, 1, 12, 0, 2, 11, 7, 5, 3 }, + { 11, 8, 12, 0, 5, 2, 15, 13, 10, 14, 3, 6, 7, 1, 9, 4 }, + { 7, 9, 3, 1, 13, 12, 11, 14, 2, 6, 5, 10, 4, 0, 15, 8 }, + { 9, 0, 5, 7, 2, 4, 10, 15, 14, 1, 11, 12, 6, 8, 3, 13 }, + { 2, 12, 6, 10, 0, 11, 8, 3, 4, 13, 7, 5, 15, 14, 1, 9 }, + { 12, 5, 1, 15, 14, 13, 4, 10, 0, 7, 6, 3, 9, 2, 8, 11 }, + { 13, 11, 7, 14, 12, 1, 3, 9, 5, 0, 15, 4, 8, 6, 2, 10 }, + { 6, 15, 14, 9, 11, 3, 0, 8, 12, 2, 13, 7, 1, 4, 10, 5 }, + { 10, 2, 8, 4, 7, 6, 1, 5, 15, 11, 9, 14, 3, 12, 13, 0 } +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static inline uint32_t rotr32(const uint32_t w, const unsigned int c) +{ + return (w >> (c & 31)) | (w << ((32 - c) & 31)); +} + +static void blake2_memcpy(FAR void *dst, FAR const void *src, size_t len) +{ +#ifdef BLAKE2_UNALIGNED + FAR uint32_alias_t *idst = dst; + FAR const uint32_alias_t *isrc = src; + FAR uint8_t *bdst; + FAR const uint8_t *bsrc; + + while (len >= sizeof(uint32_alias_t)) + { + *idst = *isrc; + idst++; + isrc++; + len -= sizeof(uint32_alias_t); + } + + bdst = (FAR uint8_t *)idst; + bsrc = (FAR const uint8_t *)isrc; + while (len) + { + *bdst = *bsrc; + bdst++; + bsrc++; + len--; + } +#else + memcpy(dst, set, len); +#endif +} + +static void blake2_memset(FAR void *dst, int set, size_t len) +{ +#ifdef BLAKE2_UNALIGNED + FAR uint32_alias_t *idst = dst; + FAR uint8_t *bdst; + uint32_t mset; + + set &= 0xff; + mset = (uint32_t)set * 0x01010101UL; + + while (len >= sizeof(uint32_alias_t)) + { + *idst = mset; + idst++; + len -= sizeof(uint32_alias_t); + } + + bdst = (FAR uint8_t *)idst; + set &= 0xff; + while (len) + { + *bdst = set; + bdst++; + len--; + } +#else + memset(dst, set, len); +#endif +} + +static inline void secure_zero_memory(FAR void *v, size_t n) +{ + explicit_bzero(v, n); +} + +/* Some helper functions, not necessarily useful */ + +static int blake2s_is_lastblock(FAR const blake2s_state *S) +{ + return S->f[0] != 0; +} + +static void blake2s_set_lastblock(FAR blake2s_state *S) +{ + S->f[0] = (uint32_t)-1; +} + +static void blake2s_increment_counter(FAR blake2s_state *S, const uint32_t inc) +{ + S->t[0] += inc; + S->t[1] += (S->t[0] < inc); +} + +static void blake2s_init0(FAR blake2s_state *S) +{ + size_t i; + + blake2_memset(S, 0, sizeof(*S) - sizeof(S->buf)); + + for (i = 0; i < 8; ++i) + S->h[i] = blake2s_IV[i]; +} + +static void blake2s_compress(FAR blake2s_state *S, + const uint8_t in[BLAKE2S_BLOCKBYTES]) +{ + uint32_t m[16]; + uint32_t v[16]; + size_t i; + unsigned int round; + + for (i = 0; i < 16; ++i) + { + m[i] = blake2_load32(in + i * sizeof(m[i])); + } + + for (i = 0; i < 8; ++i) + { + v[i] = S->h[i]; + } + + v[8] = blake2s_IV[0]; + v[9] = blake2s_IV[1]; + v[10] = blake2s_IV[2]; + v[11] = blake2s_IV[3]; + v[12] = S->t[0] ^ blake2s_IV[4]; + v[13] = S->t[1] ^ blake2s_IV[5]; + v[14] = S->f[0] ^ blake2s_IV[6]; + v[15] = S->f[1] ^ blake2s_IV[7]; + +#define G(r,i,a,b,c,d) \ + do { \ + a = a + b + m[blake2s_sigma[r][2*i+0]]; \ + d = rotr32(d ^ a, 16); \ + c = c + d; \ + b = rotr32(b ^ c, 12); \ + a = a + b + m[blake2s_sigma[r][2*i+1]]; \ + d = rotr32(d ^ a, 8); \ + c = c + d; \ + b = rotr32(b ^ c, 7); \ + } while(0) + +#define ROUND(r) \ + do { \ + G(r,0,v[ 0],v[ 4],v[ 8],v[12]); \ + G(r,1,v[ 1],v[ 5],v[ 9],v[13]); \ + G(r,2,v[ 2],v[ 6],v[10],v[14]); \ + G(r,3,v[ 3],v[ 7],v[11],v[15]); \ + G(r,4,v[ 0],v[ 5],v[10],v[15]); \ + G(r,5,v[ 1],v[ 6],v[11],v[12]); \ + G(r,6,v[ 2],v[ 7],v[ 8],v[13]); \ + G(r,7,v[ 3],v[ 4],v[ 9],v[14]); \ + } while(0) + + /* Size vs performance trade-off. With unrolling, on ARMv7-M function text + * is ~4 KiB and without ~1 KiB. Without unrolling we take ~25% performance + * hit. */ + +#if 1 + /* Smaller, slightly slower. */ + + for (round = 0; round < 10; round++) + { + ROUND(round); + } +#else + /* Larger, slightly faster. */ + + (void)(round=0); + ROUND(0); + ROUND(1); + ROUND(2); + ROUND(3); + ROUND(4); + ROUND(5); + ROUND(6); + ROUND(7); + ROUND(8); + ROUND(9); +#endif + +#undef G +#undef ROUND + + for (i = 0; i < 8; ++i) + { + S->h[i] = S->h[i] ^ v[i] ^ v[i + 8]; + } +} + +#ifdef CONFIG_BLAKE2_SELFTEST +/* BLAKE2s self-test from RFC 7693 */ + +static void selftest_seq(FAR uint8_t *out, size_t len, uint32_t seed) +{ + size_t i; + uint32_t t, a, b; + + a = 0xDEAD4BAD * seed; /* prime */ + b = 1; + /* fill the buf */ + for (i = 0; i < len; i++) + { + t = a + b; + a = b; + b = t; + out[i] = (t >> 24) & 0xFF; + } +} + +static int blake2s_selftest(void) +{ + /* Grand hash of hash results. */ + + static const uint8_t blake2s_res[32] = + { + 0x6a, 0x41, 0x1f, 0x08, 0xce, 0x25, 0xad, 0xcd, 0xfb, 0x02, 0xab, 0xa6, + 0x41, 0x45, 0x1c, 0xec, 0x53, 0xc5, 0x98, 0xb2, 0x4f, 0x4f, 0xc7, 0x87, + 0xfb, 0xdc, 0x88, 0x79, 0x7f, 0x4c, 0x1d, 0xfe + }; + + /* Parameter sets. */ + + static const size_t b2s_md_len[4] = { 16, 20, 28, 32 }; + static const size_t b2s_in_len[6] = { 0, 3, 64, 65, 255, 1024 }; + size_t i, j, outlen, inlen; + FAR uint8_t *in; + uint8_t md[32], key[32]; + blake2s_state ctx; + int ret = -1; + + in = malloc(1024); + if (!in) + { + goto out; + } + + /* 256-bit hash for testing. */ + + if (blake2s_init(&ctx, 32)) + { + goto out; + } + + for (i = 0; i < 4; i++) + { + outlen = b2s_md_len[i]; + for (j = 0; j < 6; j++) + { + inlen = b2s_in_len[j]; + + selftest_seq(in, inlen, inlen); /* unkeyed hash */ + blake2s(md, outlen, in, inlen, NULL, 0); + blake2s_update(&ctx, md, outlen); /* hash the hash */ + + selftest_seq(key, outlen, outlen); /* keyed hash */ + blake2s(md, outlen, in, inlen, key, outlen); + blake2s_update(&ctx, md, outlen); /* hash the hash */ + } + } + + /* Compute and compare the hash of hashes. */ + + blake2s_final(&ctx, md, 32); + for (i = 0; i < 32; i++) + { + if (md[i] != blake2s_res[i]) + goto out; + } + + ret = 0; + +out: + free(in); + return ret; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/* init2 xors IV with input parameter block */ + +int blake2s_init_param(FAR blake2s_state *S, FAR const blake2s_param *P) +{ + FAR const unsigned char *p = (FAR const unsigned char *)(P); + size_t i; +#ifdef CONFIG_BLAKE2_SELFTEST + static bool selftest_done = false; + int ret; + + if (!selftest_done) + { + selftest_done = true; + ret = blake2s_selftest(); + DEBUGASSERT(ret == 0); + if (ret) + return -1; + } +#endif + + blake2s_init0(S); + + /* IV XOR ParamBlock */ + + for (i = 0; i < 8; ++i) + { + S->h[i] ^= blake2_load32(&p[i * 4]); + } + + S->outlen = P->digest_length; + return 0; +} + +/* Sequential blake2s initialization */ + +int blake2s_init(FAR blake2s_state *S, size_t outlen) +{ + blake2s_param P[1]; + + /* Move interval verification here? */ + + if ((!outlen) || (outlen > BLAKE2S_OUTBYTES)) + { + return -1; + } + + P->digest_length = (uint8_t)outlen; + P->key_length = 0; + P->fanout = 1; + P->depth = 1; + blake2_store32(P->leaf_length, 0); + blake2_store32(P->node_offset, 0); + blake2_store16(P->xof_length, 0); + P->node_depth = 0; + P->inner_length = 0; + /* memset(P->reserved, 0, sizeof(P->reserved)); */ + blake2_memset(P->salt, 0, sizeof(P->salt)); + blake2_memset(P->personal, 0, sizeof(P->personal)); + return blake2s_init_param(S, P); +} + +int blake2s_init_key(FAR blake2s_state *S, size_t outlen, FAR const void *key, + size_t keylen) +{ + blake2s_param P[1]; + uint8_t block[BLAKE2S_BLOCKBYTES]; + + if ((!outlen) || (outlen > BLAKE2S_OUTBYTES)) + { + return -1; + } + + if (!key || !keylen || keylen > BLAKE2S_KEYBYTES) + { + return -1; + } + + P->digest_length = (uint8_t) outlen; + P->key_length = (uint8_t) keylen; + P->fanout = 1; + P->depth = 1; + blake2_store32(P->leaf_length, 0); + blake2_store32(P->node_offset, 0); + blake2_store16(P->xof_length, 0); + P->node_depth = 0; + P->inner_length = 0; + /* memset(P->reserved, 0, sizeof(P->reserved)); */ + blake2_memset(P->salt, 0, sizeof(P->salt)); + blake2_memset(P->personal, 0, sizeof(P->personal)); + + blake2s_init_param(S, P); + + blake2_memset(block, 0, BLAKE2S_BLOCKBYTES); + blake2_memcpy(block, key, keylen); + blake2s_update(S, block, BLAKE2S_BLOCKBYTES); + secure_zero_memory(block, BLAKE2S_BLOCKBYTES); /* Burn the key from stack */ + + return 0; +} + +int blake2s_update(FAR blake2s_state *S, FAR const void *pin, size_t inlen) +{ + FAR const unsigned char * in = FAR (const unsigned char *)pin; + size_t left, fill; + + if (inlen <= 0) + { + return 0; + } + + left = S->buflen; + fill = BLAKE2S_BLOCKBYTES - left; + if (inlen > fill) + { + S->buflen = 0; + if (fill) + { + blake2_memcpy(S->buf + left, in, fill); /* Fill buffer */ + } + + blake2s_increment_counter(S, BLAKE2S_BLOCKBYTES); + blake2s_compress(S, S->buf); /* Compress */ + in += fill; + inlen -= fill; + while (inlen > BLAKE2S_BLOCKBYTES) + { + blake2s_increment_counter(S, BLAKE2S_BLOCKBYTES); + blake2s_compress(S, in); + in += BLAKE2S_BLOCKBYTES; + inlen -= BLAKE2S_BLOCKBYTES; + } + } + + blake2_memcpy(S->buf + S->buflen, in, inlen); + S->buflen += inlen; + + return 0; +} + +int blake2s_final(FAR blake2s_state *S, FAR void *out, size_t outlen) +{ + FAR uint8_t *outbuf = out; + uint32_t tmp = 0; + size_t outwords; + size_t padding; + size_t i; + + if (out == NULL || outlen < S->outlen) + { + return -1; + } + + if (blake2s_is_lastblock(S)) + { + return -1; + } + + blake2s_increment_counter(S, (uint32_t)S->buflen); + blake2s_set_lastblock(S); + padding = BLAKE2S_BLOCKBYTES - S->buflen; + if (padding) + { + blake2_memset(S->buf + S->buflen, 0, padding); + } + blake2s_compress(S, S->buf); + + /* Output hash to out buffer */ + + outwords = outlen / sizeof(uint32_t); + outwords = (outwords < 8) ? outwords : 8; + for (i = 0; i < outwords; ++i) + { + /* Store full words */ + + blake2_store32(outbuf, S->h[i]); + outlen -= sizeof(uint32_t); + outbuf += sizeof(uint32_t); + } + + if (outwords < 8 && outlen > 0 && outlen < sizeof(uint32_t)) + { + /* Store partial word */ + + blake2_store32(&tmp, S->h[i]); + blake2_memcpy(outbuf, &tmp, outlen); + } + + return 0; +} + +int blake2s(FAR void *out, size_t outlen, FAR const void *in, size_t inlen, + FAR const void *key, size_t keylen) +{ + blake2s_state S[1]; + + /* Verify parameters */ + + if (NULL == in && inlen > 0) + { + return -1; + } + + if (NULL == out) + { + return -1; + } + + if (NULL == key && keylen > 0) + { + return -1; + } + + if (!outlen || outlen > BLAKE2S_OUTBYTES) + { + return -1; + } + + if (keylen > BLAKE2S_KEYBYTES) + { + return -1; + } + + if (keylen > 0) + { + if (blake2s_init_key(S, outlen, key, keylen) < 0) + { + return -1; + } + } + else + { + if (blake2s_init(S, outlen) < 0) + { + return -1; + } + } + + blake2s_update(S, (const uint8_t *)in, inlen); + blake2s_final(S, out, outlen); + return 0; +} diff --git a/crypto/random_pool.c b/crypto/random_pool.c new file mode 100644 index 0000000000..fed59bd727 --- /dev/null +++ b/crypto/random_pool.c @@ -0,0 +1,561 @@ +/**************************************************************************** + * crypto/random_pool.c + * + * Copyright (C) 2015-2017 Haltian Ltd. All rights reserved. + * Authors: Juha Niskanen + * Jussi Kivilinna + * + * 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 + +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +#ifndef MIN +#define MIN(a,b) ((a) < (b) ? (a) : (b)) +#endif + +#define ROTL_32(x,n) ( ((x) << (n)) | ((x) >> (32-(n))) ) +#define ROTR_32(x,n) ( ((x) >> (n)) | ((x) << (32-(n))) ) + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct blake2xs_rng_s +{ + uint32_t out_node_offset; + blake2s_param param; + blake2s_state ctx; + char out_root[BLAKE2S_OUTBYTES]; +}; + +struct rng_s +{ + sem_t rd_sem; /* Threads can only exclusively access the RNG */ + volatile uint32_t rd_addptr; + volatile uint32_t rd_newentr; + volatile uint8_t rd_rotate; + volatile uint8_t rd_prev_time; + volatile uint16_t rd_prev_irq; + bool output_initialized; + struct blake2xs_rng_s blake2xs; +}; + +enum +{ + POOL_SIZE = ENTROPY_POOL_SIZE, + POOL_MASK = (POOL_SIZE - 1), + + MIN_SEED_NEW_ENTROPY_WORDS = 128, + MAX_SEED_NEW_ENTROPY_WORDS = 1024 +}; + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static struct rng_s g_rng; + +#ifdef CONFIG_BOARD_ENTROPY_POOL +/* Entropy pool structure can be provided by board source. Use for this is, + * for example, allocate entropy pool from special area of RAM which content + * is kept over system reset. */ + +# define entropy_pool board_entropy_pool +#else +static struct entropy_pool_s entropy_pool; +#endif + +/* Polynomial from paper "The Linux Pseudorandom Number Generator Revisited" + * x^POOL_SIZE + x^104 + x^76 + x^51 + x^25 + x + 1 */ + +static const uint32_t pool_stir[] = { POOL_SIZE, 104, 76, 51, 25, 1 }; + +/* Derived from IEEE 802.3 CRC-32 */ + +static const uint32_t pool_twist[8] = +{ + 0x00000000, 0x3b6e20c8, 0x76dc4190, 0x4db26158, + 0xedb88320, 0xd6d6a3e8, 0x9b64c2b0, 0xa00ae278 +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: addentropy + * + * Description: + * + * This function adds a number of integers into the entropy pool. + * The pool is stirred with a polynomial of degree POOL_SIZE over GF(2). + * + * Code is inspired by add_entropy_words() function of OpenBSD kernel. + * + * Parameters: + * buf - Buffer of integers to be added + * n - Number of elements in buf + * inc_new - Count element as new entry + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void addentropy(FAR const uint32_t *buf, size_t n, bool inc_new) +{ + /* Compile time check for that POOL_SIZE is power of two. */ + + static char pool_size_p2_check[1 - ((POOL_SIZE & (POOL_SIZE - 1)) * 2)]; + + UNUSED(pool_size_p2_check); + + while (n-- > 0) + { + uint32_t rotate; + uint32_t w; + uint32_t i; + + rotate = g_rng.rd_rotate; + w = ROTL_32(*buf, rotate); + i = g_rng.rd_addptr = (g_rng.rd_addptr - 1) & POOL_MASK; + + /* Normal round, we add 7 bits of rotation to the pool. + * At the beginning of the pool, we add extra 7 bits + * rotation, in order for successive passes spread the + * input bits across the pool evenly. + */ + + g_rng.rd_rotate = (rotate + (i ? 7 : 14)) & 31; + + /* XOR pool contents corresponding to polynomial terms */ + + w ^= entropy_pool.pool[(i + pool_stir[1]) & POOL_MASK]; + w ^= entropy_pool.pool[(i + pool_stir[2]) & POOL_MASK]; + w ^= entropy_pool.pool[(i + pool_stir[3]) & POOL_MASK]; + w ^= entropy_pool.pool[(i + pool_stir[4]) & POOL_MASK]; + w ^= entropy_pool.pool[(i + pool_stir[5]) & POOL_MASK]; + w ^= entropy_pool.pool[i]; /* 2^POOL_SIZE */ + + entropy_pool.pool[i] = (w >> 3) ^ pool_twist[w & 7]; + buf++; + + if (inc_new) + { + g_rng.rd_newentr += 1; + } + } +} + +/**************************************************************************** + * Function: getentropy + * + * Description: + * Hash entropy pool to BLAKE2s context. This is an internal interface for + * seeding out-facing BLAKE2Xs random bit generator from entropy pool. + * + * Code is inspired by extract_entropy() function of OpenBSD kernel. + * + * Note that this function cannot fail, other than by asserting. + * + * Warning: In protected kernel builds, this interface MUST NOT be + * exported to userspace. This interface MUST NOT be used as a + * general-purpose random bit generator! + * + * Parameters: + * S - BLAKE2s instance that will absorb entropy pool + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void getentropy(FAR blake2s_state *S) +{ +#ifdef CONFIG_SCHED_CPULOAD + struct cpuload_s load; +#endif + uint32_t tmp; + + add_sw_randomness(g_rng.rd_newentr); + + /* Absorb the entropy pool */ + + blake2s_update(S, (FAR const uint32_t *)entropy_pool.pool, + sizeof(entropy_pool.pool)); + + /* Add something back so repeated calls to this function + * return different values. + */ + + tmp = sizeof(entropy_pool.pool); + tmp <<= 27; +#ifdef CONFIG_SCHED_CPULOAD + clock_cpuload(0, &load); + tmp += load.total ^ ROTL_32(load.active, 23); +#endif + add_sw_randomness(tmp); + + g_rng.rd_newentr = 0; +} + +/* The BLAKE2Xs based random number generator algorithm. + * + * BLAKE2X is a extensible-output function (XOF) variant of BLAKE2 hash + * function. One application of XOFs is use as deterministic random bit + * number generator (DRBG) as used here. BLAKE2 specification is available + * at https://blake2.net/ + * + * BLAKE2Xs here implementation is based on public-domain/CC0 BLAKE2 reference + * implementation by Samual Neves, at + * https://github.com/BLAKE2/BLAKE2/tree/master/ref + * Copyright 2012, Samuel Neves + */ + +static void rng_reseed(void) +{ + blake2s_param P = {}; + + /* Reset output node counter. */ + + g_rng.blake2xs.out_node_offset = 0; + + /* Initialize parameter block */ + + P.digest_length = BLAKE2S_OUTBYTES; + P.key_length = 0; + P.fanout = 1; + P.depth = 1; + blake2_store32(P.leaf_length, 0); + blake2_store32(P.node_offset, 0); + blake2_store16(P.xof_length, 0xffff); + P.node_depth = 0; + P.inner_length = 0; + g_rng.blake2xs.param = P; + + blake2s_init_param(&g_rng.blake2xs.ctx, &g_rng.blake2xs.param); + + /* Initialize with randomness from entropy pool */ + + getentropy(&g_rng.blake2xs.ctx); + + /* Absorb also the previous root */ + + blake2s_update(&g_rng.blake2xs.ctx, g_rng.blake2xs.out_root, + sizeof(g_rng.blake2xs.out_root)); + + /* Finalize the new root hash */ + + blake2s_final(&g_rng.blake2xs.ctx, g_rng.blake2xs.out_root, + BLAKE2S_OUTBYTES); + + explicit_bzero(&g_rng.blake2xs.ctx, sizeof(g_rng.blake2xs.ctx)); + + /* Setup parameters for output phase. */ + + g_rng.blake2xs.param.key_length = 0; + g_rng.blake2xs.param.fanout = 0; + blake2_store32(g_rng.blake2xs.param.leaf_length, BLAKE2S_OUTBYTES); + g_rng.blake2xs.param.inner_length = BLAKE2S_OUTBYTES; + g_rng.blake2xs.param.node_depth = 0; + + g_rng.output_initialized = true; +} + +static void rng_buf_internal(FAR void *bytes, size_t nbytes) +{ + if (!g_rng.output_initialized) + { + if (g_rng.rd_newentr < MIN_SEED_NEW_ENTROPY_WORDS) + { + cryptwarn("Entropy pool RNG initialized with very low entropy. " + " Consider implementing CONFIG_BOARD_INITRNGSEED!\n"); + } + + rng_reseed(); + } + else if (g_rng.rd_newentr >= MAX_SEED_NEW_ENTROPY_WORDS) + { + /* Initial entropy is low. Reseed when we have accumulated more. */ + + rng_reseed(); + } + else if (g_rng.blake2xs.out_node_offset == UINT32_MAX) + { + /* Maximum BLAKE2Xs output reached (2^32-1 output blocks, maximum 128 GiB + * bytes), reseed. */ + + rng_reseed(); + } + + /* Output phase for BLAKE2Xs. */ + + for (; nbytes > 0; ++g_rng.blake2xs.out_node_offset) + { + size_t block_size = MIN(nbytes, BLAKE2S_OUTBYTES); + + /* Initialize state */ + + g_rng.blake2xs.param.digest_length = block_size; + blake2_store32(g_rng.blake2xs.param.node_offset, + g_rng.blake2xs.out_node_offset); + blake2s_init_param(&g_rng.blake2xs.ctx, &g_rng.blake2xs.param); + + /* Process state and output random bytes */ + + blake2s_update(&g_rng.blake2xs.ctx, g_rng.blake2xs.out_root, + sizeof(g_rng.blake2xs.out_root)); + blake2s_final(&g_rng.blake2xs.ctx, bytes, block_size); + + bytes += block_size; + nbytes -= block_size; + } +} + +static void rng_init(void) +{ + crypinfo("Initializing RNG\n"); + + memset(&g_rng, 0, sizeof(struct rng_s)); + sem_init(&g_rng.rd_sem, 0, 1); + + /* We do not initialize output here because this is called + * quite early in boot and there may not be enough entropy. + * + * Board level may define CONFIG_BOARD_INITRNGSEED if it implements + * early random seeding. + */ +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: up_rngaddint + * + * Description: + * Add one integer to entropy pool, contributing a specific kind + * of entropy to pool. + * + * Parameters: + * kindof - Enumeration constant telling where val came from + * val - Integer to be added + * + * Returned Value: + * None + * + ****************************************************************************/ + +void up_rngaddint(enum rnd_source_t kindof, int val) +{ + uint32_t buf[1]; + + buf[0] = val; + + up_rngaddentropy(kindof, buf, 1); +} + +/**************************************************************************** + * Function: up_rngaddentropy + * + * Description: + * Add buffer of integers to entropy pool. + * + * Parameters: + * kindof - Enumeration constant telling where val came from + * buf - Buffer of integers to be added + * n - Number of elements in buf + * + * Returned Value: + * None + * + ****************************************************************************/ + +void up_rngaddentropy(enum rnd_source_t kindof, FAR const uint32_t *buf, + size_t n) +{ + uint32_t tbuf[1]; + struct timespec ts; + bool new_inc = true; + + if (kindof == RND_SRC_IRQ && n > 0) + { + /* Ignore interrupt randomness if previous interrupt was from same + * source. */ + + if (buf[0] == g_rng.rd_prev_irq) + { + return; + } + + g_rng.rd_prev_irq = buf[0]; + } + + /* We don't actually track what kind of entropy we receive, + * just add it all to pool. One exception is interrupt + * and timer randomness, where we limit rate of new pool entry + * counting to prevent high interrupt rate triggering RNG + * reseeding too fast. + */ + + (void)clock_gettime(CLOCK_REALTIME, &ts); + tbuf[0] = ROTL_32(ts.tv_nsec, 17) ^ ROTL_32(ts.tv_sec, 3); + tbuf[0] += ROTL_32(kindof, 27); + tbuf[0] += ROTL_32((uintptr_t)&tbuf[0], 11); + + if (kindof == RND_SRC_TIME || kindof == RND_SRC_IRQ) + { + uint8_t curr_time = ts.tv_sec * 8 + ts.tv_nsec / (NSEC_PER_SEC / 8); + + /* Allow interrupts/timers increase entropy counter at max rate + * of 8 Hz. */ + + if (g_rng.rd_prev_time == curr_time) + { + new_inc = false; + } + else + { + g_rng.rd_prev_time = curr_time; + } + } + + if (n > 0) + { + tbuf[0] ^= buf[0]; + buf++; + n--; + } + + addentropy(tbuf, 1, new_inc); + + if (n > 0) + { + addentropy(buf, n, new_inc); + } +} + +/**************************************************************************** + * Function: up_rngreseed + * + * Description: + * Force reseeding random number generator from entropy pool + * + ****************************************************************************/ + +void up_rngreseed(void) +{ + while (sem_wait(&g_rng.rd_sem) != 0) + { + assert(errno == EINTR); + } + + if (g_rng.rd_newentr >= MIN_SEED_NEW_ENTROPY_WORDS) + { + rng_reseed(); + } + + sem_post(&g_rng.rd_sem); +} + +/**************************************************************************** + * Function: up_randompool_initialize + * + * Description: + * Initialize entropy pool and random number generator + * + ****************************************************************************/ + +void up_randompool_initialize(void) +{ + rng_init(); + +#ifdef CONFIG_BOARD_INITRNGSEED + board_init_rngseed(); +#endif +} + +/**************************************************************************** + * Function: getrandom + * + * Description: + * Fill a buffer of arbitrary length with randomness. This is the + * preferred interface for getting random numbers. The traditional + * /dev/random approach is susceptible for things like the attacker + * exhausting file descriptors on purpose. + * + * Note that this function cannot fail, other than by asserting. + * + * Parameters: + * bytes - Buffer for returned random bytes + * nbytes - Number of bytes requested. + * + * Returned Value: + * None + * + ****************************************************************************/ + +void getrandom(FAR void *bytes, size_t nbytes) +{ + while (sem_wait(&g_rng.rd_sem) != 0) + { + assert(errno == EINTR); + } + + rng_buf_internal(bytes, nbytes); + sem_post(&g_rng.rd_sem); +} diff --git a/drivers/Kconfig b/drivers/Kconfig index 00adcc8f17..511d63c5f6 100644 --- a/drivers/Kconfig +++ b/drivers/Kconfig @@ -69,6 +69,15 @@ config DEV_URANDOM_CONGRUENTIAL NOTE: Not cyptographically secure +config DEV_URANDOM_RANDOM_POOL + bool "Entropy pool" + depends on CRYPTO_RANDOM_POOL + ---help--- + Use the entropy pool CPRNG output for urandom algorithm. + + NOTE: May or may not be cyptographically secure, depending upon the + quality entropy available to entropy pool. + config DEV_URANDOM_ARCH bool "Architecture-specific" depends on ARCH_HAVE_RNG diff --git a/drivers/analog/adc.c b/drivers/analog/adc.c index d81971f101..be1682e3cd 100644 --- a/drivers/analog/adc.c +++ b/drivers/analog/adc.c @@ -60,6 +60,7 @@ #include #include #include +#include #include @@ -296,6 +297,10 @@ static ssize_t adc_read(FAR struct file *filep, FAR char *buffer, size_t buflen) break; } + /* Feed ADC data to entropy pool */ + + add_sensor_randomness(msg->am_data); + /* Copy the message to the user buffer */ if (msglen == 1) diff --git a/drivers/dev_urandom.c b/drivers/dev_urandom.c index e7022cb9f5..5b59736907 100644 --- a/drivers/dev_urandom.c +++ b/drivers/dev_urandom.c @@ -49,11 +49,13 @@ #include #include #include +#include #include #include #include #include +#include #if defined(CONFIG_DEV_URANDOM) && !defined(CONFIG_DEV_URANDOM_ARCH) @@ -62,13 +64,18 @@ ****************************************************************************/ #if !defined(CONFIG_DEV_URANDOM_CONGRUENTIAL) && \ - !defined(CONFIG_DEV_URANDOM_XORSHIFT128) -# define CONFIG_DEV_URANDOM_XORSHIFT128 1 + !defined(CONFIG_DEV_URANDOM_XORSHIFT128) && \ + !defined(CONFIG_DEV_URANDOM_RANDOM_POOL) +# ifdef CONFIG_CRYPTO_RANDOM_POOL +# define CONFIG_DEV_URANDOM_RANDOM_POOL 1 +# else +# define CONFIG_DEV_URANDOM_XORSHIFT128 1 +# endif #endif #ifdef CONFIG_DEV_URANDOM_XORSHIFT128 # define PRNG() do_xorshift128() -#else /* CONFIG_DEV_URANDOM_CONGRUENTIAL */ +#elif defined(CONFIG_DEV_URANDOM_CONGRUENTIAL) # define PRNG() do_congruential() #endif @@ -158,6 +165,12 @@ static inline uint32_t do_congruential(void) static ssize_t devurand_read(FAR struct file *filep, FAR char *buffer, size_t len) { +#ifdef CONFIG_DEV_URANDOM_RANDOM_POOL + if (len) + { + getrandom(buffer, len); + } +#else size_t n; uint32_t rnd; @@ -208,6 +221,7 @@ static ssize_t devurand_read(FAR struct file *filep, FAR char *buffer, } while (--n > 0); } +#endif /* CONFIG_DEV_URANDOM_RANDOM_POOL */ return len; } @@ -228,6 +242,56 @@ static ssize_t devurand_write(FAR struct file *filep, FAR const char *buffer, memcpy(&seed, buffer, len); srand(seed); return len; +#elif defined(CONFIG_DEV_URANDOM_RANDOM_POOL) + const unsigned int alignmask = sizeof(uint32_t) - 1; + const size_t initlen = len; + uint32_t tmp = 0; + size_t currlen; + + if (!len) + { + return 0; + } + + /* Seed entropy pool with data from user. */ + + if ((uintptr_t)buffer & alignmask) + { + /* Make unaligned input aligned. */ + + currlen = min(sizeof(uint32_t) - ((uintptr_t)buffer & alignmask), len); + memcpy(&tmp, buffer, currlen); + up_rngaddint(RND_SRC_SW, tmp); + + len -= currlen; + buffer += currlen; + } + + if (len >= sizeof(uint32_t)) + { + /* Handle bulk aligned, word-sized data. */ + + DEBUGASSERT(((uintptr_t)buffer & alignmask) == 0); + currlen = len / sizeof(uint32_t); + up_rngaddentropy(RND_SRC_SW, (FAR uint32_t *)buffer, currlen); + buffer += currlen * sizeof(uint32_t); + len %= sizeof(uint32_t); + } + + if (len > 0) + { + /* Handle trailing bytes. */ + + DEBUGASSERT(len < sizeof(uint32_t)); + memcpy(&tmp, buffer, len); + up_rngaddint(RND_SRC_SW, tmp); + } + + /* Reseeding of random number generator from entropy pool. */ + + up_rngreseed(); + + return initlen; #else len = min(len, sizeof(g_prng.u)); memcpy(&g_prng.u, buffer, len); @@ -274,6 +338,8 @@ void devurandom_register(void) #ifdef CONFIG_DEV_URANDOM_CONGRUENTIAL srand(10197); +#elif defined(CONFIG_DEV_URANDOM_RANDOM_POOL) + up_randompool_initialize(); #else g_prng.state.w = 97; g_prng.state.x = 101; diff --git a/drivers/input/ads7843e.c b/drivers/input/ads7843e.c index d9c2c3b988..6e4e9395ec 100644 --- a/drivers/input/ads7843e.c +++ b/drivers/input/ads7843e.c @@ -70,6 +70,7 @@ #include #include #include +#include #include #include @@ -624,6 +625,8 @@ static void ads7843e_worker(FAR void *arg) y = ads7843e_sendcmd(priv, ADS7843_CMD_YPOSITION); #endif + add_ui_randomness((x << 16) | y); + /* Perform a thresholding operation so that the results will be more stable. * If the difference from the last sample is small, then ignore the event. * REVISIT: Should a large change in pressure also generate a event? diff --git a/drivers/input/ajoystick.c b/drivers/input/ajoystick.c index aaba021b95..6665b8fdd2 100644 --- a/drivers/input/ajoystick.c +++ b/drivers/input/ajoystick.c @@ -60,6 +60,7 @@ #include #include #include +#include #include @@ -321,6 +322,8 @@ static void ajoy_sample(FAR struct ajoy_upperhalf_s *priv) DEBUGASSERT(lower->al_buttons); sample = lower->al_buttons(lower); + add_ui_randomness(sample); + #if !defined(CONFIG_DISABLE_POLL) || !defined(CONFIG_DISABLE_SIGNALS) /* Determine which buttons have been newly pressed and which have been * newly released. diff --git a/drivers/input/button_upper.c b/drivers/input/button_upper.c index 2c03d3de3e..b4432cbad3 100644 --- a/drivers/input/button_upper.c +++ b/drivers/input/button_upper.c @@ -56,6 +56,7 @@ #include #include #include +#include #include @@ -317,6 +318,8 @@ static void btn_sample(FAR struct btn_upperhalf_s *priv) DEBUGASSERT(lower->bl_buttons); sample = lower->bl_buttons(lower); + add_ui_randomness(sample); + #if !defined(CONFIG_DISABLE_POLL) || !defined(CONFIG_DISABLE_SIGNALS) /* Determine which buttons have been newly pressed and which have been * newly released. diff --git a/drivers/input/djoystick.c b/drivers/input/djoystick.c index 1cc1b54004..bd3c9e4703 100644 --- a/drivers/input/djoystick.c +++ b/drivers/input/djoystick.c @@ -60,6 +60,7 @@ #include #include #include +#include #include @@ -321,6 +322,8 @@ static void djoy_sample(FAR struct djoy_upperhalf_s *priv) DEBUGASSERT(lower->dl_sample); sample = lower->dl_sample(lower); + add_ui_randomness(sample); + #if !defined(CONFIG_DISABLE_POLL) || !defined(CONFIG_DISABLE_SIGNALS) /* Determine which buttons have been newly pressed and which have been * newly released. diff --git a/drivers/input/max11802.c b/drivers/input/max11802.c index 82ad1f6689..7fb2087f06 100644 --- a/drivers/input/max11802.c +++ b/drivers/input/max11802.c @@ -64,6 +64,7 @@ #include #include #include +#include #include #include @@ -628,6 +629,8 @@ static void max11802_worker(FAR void *arg) } while (readycount < 2); + add_ui_randomness((x << 16) | y); + /* Continue to sample the position while the pen is down */ wd_start(priv->wdog, MAX11802_WDOG_DELAY, max11802_wdog, 1, diff --git a/drivers/input/mxt.c b/drivers/input/mxt.c index e115285171..01d11bc63b 100644 --- a/drivers/input/mxt.c +++ b/drivers/input/mxt.c @@ -64,6 +64,7 @@ #include #include #include +#include #include #include @@ -889,6 +890,8 @@ static void mxt_touch_event(FAR struct mxt_dev_s *priv, sample->pressure = pressure; sample->valid = true; + add_ui_randomness((x << 16) ^ y ^ (area << 9) ^ (pressure << 1)); + /* If this is not the first touch report, then report it as a move: * Same contact, same ID, but with a new, updated position. * The CONTACT_REPORT state means that a contacted has been detected, diff --git a/drivers/input/stmpe811_temp.c b/drivers/input/stmpe811_temp.c index 0cb5c686c7..5bbad0d455 100644 --- a/drivers/input/stmpe811_temp.c +++ b/drivers/input/stmpe811_temp.c @@ -48,6 +48,7 @@ #include #include +#include #include "stmpe811.h" @@ -139,6 +140,8 @@ uint16_t stmpe811_tempread(STMPE811_HANDLE handle) temp1 = stmpe811_getreg8(priv, STMPE811_SYS_CTRL2); temp2 = stmpe811_getreg8(priv, STMPE811_SYS_CTRL2+1); + add_sensor_randomness((temp1 << 8) | temp2); + /* Scale the temperature (where Vio is assumed to be .33) */ temp = ((uint32_t)(temp1 & 3) << 8) | temp2; diff --git a/drivers/input/stmpe811_tsc.c b/drivers/input/stmpe811_tsc.c index b58e9feebd..c49723c731 100644 --- a/drivers/input/stmpe811_tsc.c +++ b/drivers/input/stmpe811_tsc.c @@ -62,6 +62,7 @@ #include #include #include +#include #include #include @@ -534,6 +535,8 @@ static ssize_t stmpe811_read(FAR struct file *filep, FAR char *buffer, size_t le report->point[0].y = sample.y; report->point[0].pressure = sample.z; + add_ui_randomness((sample.x << 16) ^ (sample.y << 8) ^ sample.z); + /* Report the appropriate flags */ if (sample.contact == CONTACT_UP) diff --git a/drivers/input/tsc2007.c b/drivers/input/tsc2007.c index 8d49a2e070..fb82cc0557 100644 --- a/drivers/input/tsc2007.c +++ b/drivers/input/tsc2007.c @@ -68,6 +68,7 @@ #include #include #include +#include #include #include @@ -619,7 +620,7 @@ static void tsc2007_worker(FAR void *arg) * vertical or horizontal resistive network. The A/D converter converts * the voltage measured at the point where the panel is touched. A measurement * of the Y position of the pointing device is made by connecting the X+ - * input to a data converter chip, turning on the Y+ and Y– drivers, and + * input to a data converter chip, turning on the Y+ and Y- drivers, and * digitizing the voltage seen at the X+ input ..." * * "... it is recommended that whenever the host writes to the TSC2007, the @@ -698,6 +699,8 @@ static void tsc2007_worker(FAR void *arg) priv->sample.y = y; priv->sample.pressure = pressure; priv->sample.valid = true; + + add_ui_randomness((x << 16) ^ y ^ (pressure << 9)); } /* Note the availability of new measurements */ diff --git a/drivers/sensors/adxl345_base.c b/drivers/sensors/adxl345_base.c index 8a92d059eb..93ebf9cf45 100644 --- a/drivers/sensors/adxl345_base.c +++ b/drivers/sensors/adxl345_base.c @@ -48,6 +48,7 @@ #include #include +#include #include "adxl345.h" @@ -165,6 +166,9 @@ static ssize_t adxl345_read(FAR struct file *filep, FAR char *buffer, size_t len sample.data_z = adxl345_getreg8(priv, ADXL345_DATAZ1); sample.data_z = (sample.data_z << 8) | adxl345_getreg8(priv, ADXL345_DATAZ0); + add_sensor_randomness(sample.data_x); + add_sensor_randomness((sample.data_z << 16) | sample.data_y); + /* Return read sample */ buffer = (FAR char *) &sample; diff --git a/drivers/sensors/bh1750fvi.c b/drivers/sensors/bh1750fvi.c index 88ba994a38..c0c2d38de0 100644 --- a/drivers/sensors/bh1750fvi.c +++ b/drivers/sensors/bh1750fvi.c @@ -51,6 +51,7 @@ #include #include #include +#include #if defined(CONFIG_I2C) && defined(CONFIG_BH1750FVI) @@ -250,6 +251,8 @@ static ssize_t bh1750fvi_read(FAR struct file *filep, FAR char *buffer, buffer[0] = lux & 0xFF; buffer[1] = (lux & 0xFF00) >> 8; + add_sensor_randomness(lux); + return buflen; } diff --git a/drivers/sensors/bmg160.c b/drivers/sensors/bmg160.c index 03ad72a5d0..534985d133 100644 --- a/drivers/sensors/bmg160.c +++ b/drivers/sensors/bmg160.c @@ -51,6 +51,7 @@ #include #include +#include #if defined(CONFIG_SPI) && defined(CONFIG_BMG160) @@ -243,6 +244,10 @@ static void bmg160_read_measurement_data(FAR struct bmg160_dev_s *dev) /* Give back the semaphore */ sem_post(&dev->datasem); + + /* Feed sensor data to entropy pool */ + + add_sensor_randomness((x_gyr << 16) ^ (y_gyr << 8) ^ z_gyr); } /**************************************************************************** diff --git a/drivers/sensors/bmp180.c b/drivers/sensors/bmp180.c index 1a7d538c33..a0857d8e57 100644 --- a/drivers/sensors/bmp180.c +++ b/drivers/sensors/bmp180.c @@ -53,6 +53,7 @@ #include #include #include +#include #if defined(CONFIG_I2C) && defined(CONFIG_BMP180) @@ -464,6 +465,10 @@ static int bmp180_getpressure(FAR struct bmp180_dev_s *priv) bmp180_read_press_temp(priv); + /* Feed raw sensor data to entropy pool */ + + add_sensor_randomness((priv->bmp180_utemp << 16) ^ priv->bmp180_upress); + /* Calculate true temperature */ x1 = ((priv->bmp180_utemp - priv->bmp180_cal_ac6) * priv->bmp180_cal_ac5) >> 15; diff --git a/drivers/sensors/kxtj9.c b/drivers/sensors/kxtj9.c index 70ec5ec808..875a4486b4 100644 --- a/drivers/sensors/kxtj9.c +++ b/drivers/sensors/kxtj9.c @@ -51,6 +51,7 @@ #include #include #include +#include #if defined(CONFIG_I2C) && defined(CONFIG_SENSOR_KXTJ9) @@ -459,6 +460,12 @@ static int kxtj9_read_sensor_data(FAR struct kxtj9_dev_s *priv, kxtj9_reg_read(priv, INT_REL, &data, 1); sem_post(&priv->exclsem); + + /* Feed sensor data to entropy pool */ + + add_sensor_randomness((acc_data[0] << 16) ^ (acc_data[1] << 8) ^ + acc_data[2]); + return OK; } diff --git a/drivers/sensors/l3gd20.c b/drivers/sensors/l3gd20.c index d400f21308..10bcbeb77a 100644 --- a/drivers/sensors/l3gd20.c +++ b/drivers/sensors/l3gd20.c @@ -49,6 +49,7 @@ #include #include +#include #include @@ -257,6 +258,10 @@ static void l3gd20_read_measurement_data(FAR struct l3gd20_dev_s *dev) /* Give back the semaphore */ sem_post(&dev->datasem); + + /* Feed sensor data to entropy pool */ + + add_sensor_randomness((x_gyr << 16) ^ (y_gyr << 8) ^ (z_gyr << 0)); } /**************************************************************************** diff --git a/drivers/sensors/lis331dl.c b/drivers/sensors/lis331dl.c index f94a3b2ec2..deef62d705 100644 --- a/drivers/sensors/lis331dl.c +++ b/drivers/sensors/lis331dl.c @@ -48,6 +48,7 @@ #include #include #include +#include #if defined(CONFIG_I2C) && defined(CONFIG_LIS331DL) @@ -414,6 +415,11 @@ lis331dl_getreadings(FAR struct lis331dl_dev_s * dev) return NULL; } + /* Feed sensor data to entropy pool */ + + add_sensor_randomness((retval[2] << 16) ^ (retval[4] << 8) ^ + (retval[6] << 0)); + dev->a.x = retval[2]; dev->a.y = retval[4]; dev->a.z = retval[6]; diff --git a/drivers/sensors/lis3dsh.c b/drivers/sensors/lis3dsh.c index 243f89874d..80db21c3f4 100644 --- a/drivers/sensors/lis3dsh.c +++ b/drivers/sensors/lis3dsh.c @@ -48,6 +48,7 @@ #include #include +#include #include #include @@ -245,6 +246,10 @@ static void lis3dsh_read_measurement_data(FAR struct lis3dsh_dev_s *dev) /* Give back the semaphore */ sem_post(&dev->datasem); + + /* Feed sensor data to entropy pool */ + + add_sensor_randomness((x_acc << 16) ^ (y_acc << 8) ^ (z_acc << 0)); } /**************************************************************************** diff --git a/drivers/sensors/lis3mdl.c b/drivers/sensors/lis3mdl.c index cdb04e776e..64f33bae7a 100644 --- a/drivers/sensors/lis3mdl.c +++ b/drivers/sensors/lis3mdl.c @@ -47,6 +47,7 @@ #include #include +#include #include #include @@ -251,6 +252,11 @@ static void lis3mdl_read_measurement_data(FAR struct lis3mdl_dev_s *dev) /* Give back the semaphore */ sem_post(&dev->datasem); + + /* Feed sensor data to entropy pool */ + + add_sensor_randomness((x_mag << 16) ^ (y_mag << 10) ^ (z_mag << 2) ^ + temperature); } /**************************************************************************** diff --git a/drivers/sensors/lm75.c b/drivers/sensors/lm75.c index ce9445558b..6fa670e4e6 100644 --- a/drivers/sensors/lm75.c +++ b/drivers/sensors/lm75.c @@ -49,6 +49,7 @@ #include #include #include +#include #if defined(CONFIG_I2C) && defined(CONFIG_I2C_LM75) @@ -269,6 +270,8 @@ static int lm75_readtemp(FAR struct lm75_dev_s *priv, FAR b16_t *temp) return ret; } + add_sensor_randomness(temp16); + sninfo("Centigrade: %08x\n", temp16); /* Was fahrenheit requested? */ diff --git a/drivers/sensors/lm92.c b/drivers/sensors/lm92.c index c801e6633c..63ea40db38 100644 --- a/drivers/sensors/lm92.c +++ b/drivers/sensors/lm92.c @@ -51,6 +51,7 @@ #include #include #include +#include #if defined(CONFIG_I2C) && defined(CONFIG_LM92) @@ -272,6 +273,8 @@ static int lm92_readtemp(FAR struct lm92_dev_s *priv, FAR b16_t *temp) return ret; } + add_sensor_randomness(temp16); + sninfo("Centigrade: %08x\n", temp16); /* Was Fahrenheit requested? */ diff --git a/drivers/sensors/lsm9ds1.c b/drivers/sensors/lsm9ds1.c index ae69bd68c7..d54cdce379 100644 --- a/drivers/sensors/lsm9ds1.c +++ b/drivers/sensors/lsm9ds1.c @@ -50,6 +50,7 @@ #include #include #include +#include #if defined(CONFIG_I2C) && defined(CONFIG_SN_LSM9DS1) @@ -1244,6 +1245,7 @@ static ssize_t lsm9ds1_read(FAR struct file *filep, FAR char *buffer, uint8_t regaddr; uint8_t lo; uint8_t hi; + uint32_t merge = 0; /* Sanity check */ @@ -1301,6 +1303,10 @@ static ssize_t lsm9ds1_read(FAR struct file *filep, FAR char *buffer, data = ((uint16_t)hi << 8) | (uint16_t)lo; + /* Collect entropy */ + + merge += data ^ (merge >> 16); + /* The value is positive */ if (data < 0x8000) @@ -1329,6 +1335,10 @@ static ssize_t lsm9ds1_read(FAR struct file *filep, FAR char *buffer, } } + /* Feed sensor data to entropy pool */ + + add_sensor_randomness(merge); + return nsamples * samplesize; } diff --git a/drivers/sensors/max31855.c b/drivers/sensors/max31855.c index 19800a1c59..97b56f42ec 100644 --- a/drivers/sensors/max31855.c +++ b/drivers/sensors/max31855.c @@ -54,6 +54,7 @@ #include #include #include +#include #if defined(CONFIG_SPI) && defined(CONFIG_MAX31855) @@ -220,6 +221,10 @@ static ssize_t max31855_read(FAR struct file *filep, FAR char *buffer, size_t bu sninfo("Read from MAX31855 = 0x%08X\n", regval); + /* Feed sensor data to entropy pool */ + + add_sensor_randomness(regval); + /* If negative, fix signal bits */ if (regval & 0x80000000) diff --git a/drivers/sensors/max6675.c b/drivers/sensors/max6675.c index 0d205a049b..71a0e2d142 100644 --- a/drivers/sensors/max6675.c +++ b/drivers/sensors/max6675.c @@ -54,6 +54,7 @@ #include #include #include +#include #if defined(CONFIG_SPI) && defined(CONFIG_MAX6675) @@ -230,6 +231,10 @@ static ssize_t max6675_read(FAR struct file *filep, FAR char *buffer, size_t buf ret = -EINVAL; } + /* Feed sensor data to entropy pool */ + + add_sensor_randomness(regval); + /* Get the temperature */ *temp = (regval & MAX6675_TEMP_COUPLE) >> 3; diff --git a/drivers/sensors/mb7040.c b/drivers/sensors/mb7040.c index 2bdaecee0e..125825cab0 100644 --- a/drivers/sensors/mb7040.c +++ b/drivers/sensors/mb7040.c @@ -51,6 +51,7 @@ #include #include #include +#include #if defined(CONFIG_I2C) && defined(CONFIG_MB7040) @@ -323,6 +324,10 @@ static int mb7040_ioctl(FAR struct file *filep, int cmd, unsigned long arg) if (ret == OK) { *ptr = (int32_t)range; + + /* Feed sensor data to entropy pool */ + + add_sensor_randomness(range); } sninfo("range: %04x ret: %d\n", *ptr, ret); diff --git a/drivers/sensors/mcp9844.c b/drivers/sensors/mcp9844.c index 77dcee773e..f895d86152 100644 --- a/drivers/sensors/mcp9844.c +++ b/drivers/sensors/mcp9844.c @@ -50,6 +50,7 @@ #include #include #include +#include #if defined(CONFIG_I2C) && defined(CONFIG_MCP9844) @@ -274,6 +275,10 @@ static int mcp9844_ioctl(FAR struct file *filep, int cmd, unsigned long arg) if (ret == OK) { + /* Feed sensor data to entropy pool */ + + add_sensor_randomness(raw_temperature); + /* BIT15 - 13 contain information if preset temperature values * have been exceeded or undercut. BIT12 is now not any longer * needed since we do have the sign information retrieved. diff --git a/drivers/sensors/mlx90393.c b/drivers/sensors/mlx90393.c index 93a53ef871..d5b27b801e 100644 --- a/drivers/sensors/mlx90393.c +++ b/drivers/sensors/mlx90393.c @@ -50,6 +50,7 @@ #include #include +#include #if defined(CONFIG_SPI) && defined(CONFIG_MLX90393) @@ -232,6 +233,11 @@ static void mlx90393_read_measurement_data(FAR struct mlx90393_dev_s *dev) /* Give back the semaphore */ sem_post(&dev->datasem); + + /* Feed sensor data to entropy pool */ + + add_sensor_randomness((x_mag << 17) ^ (y_mag << 9) ^ (z_mag << 1) ^ + temperature); } /**************************************************************************** diff --git a/drivers/sensors/mpl115a.c b/drivers/sensors/mpl115a.c index 38763f5c71..c23df63eaf 100644 --- a/drivers/sensors/mpl115a.c +++ b/drivers/sensors/mpl115a.c @@ -50,6 +50,7 @@ #include #include #include +#include #if defined(CONFIG_SPI) && defined(CONFIG_MPL115A) @@ -227,6 +228,11 @@ static void mpl115a_read_press_temp(FAR struct mpl115a_dev_s *priv) priv->mpl115a_temperature >>= 6; /* Tadc is 10bit unsigned */ sninfo("Temperature = %d\n", priv->mpl115a_temperature); + + /* Feed sensor data to entropy pool */ + + add_sensor_randomness((priv->mpl115a_pressure << 16) ^ + priv->mpl115a_temperature); } /**************************************************************************** diff --git a/drivers/sensors/ms58xx.c b/drivers/sensors/ms58xx.c index 47f04e57ca..3efdda2713 100644 --- a/drivers/sensors/ms58xx.c +++ b/drivers/sensors/ms58xx.c @@ -53,6 +53,7 @@ #include #include #include +#include #if defined(CONFIG_I2C) && defined(CONFIG_MS58XX) @@ -725,6 +726,8 @@ static int ms58xx_measure(FAR struct ms58xx_dev_s *priv) return ret; } + add_sensor_randomness(rawpress ^ rawtemp); + diff = (int32_t)rawtemp - (int32_t)priv->c5 * ((int32_t)1 << 8); temp = (int32_t)((int64_t)2000 + (int64_t)diff * (int64_t)priv->c6 / ((int64_t)1 << 23)); diff --git a/drivers/sensors/veml6070.c b/drivers/sensors/veml6070.c index 28030ba7ce..443782458a 100644 --- a/drivers/sensors/veml6070.c +++ b/drivers/sensors/veml6070.c @@ -48,6 +48,7 @@ #include #include #include +#include #if defined(CONFIG_I2C) && defined(CONFIG_VEML6070) @@ -272,6 +273,10 @@ static ssize_t veml6070_read(FAR struct file *filep, FAR char *buffer, buffer[0] = regdata; + /* Feed sensor data to entropy pool */ + + add_sensor_randomness((buffer[1] << 16) ^ buffer[0]); + return buflen; } diff --git a/drivers/sensors/xen1210.c b/drivers/sensors/xen1210.c index 0f7bfd2b1e..a14350921c 100644 --- a/drivers/sensors/xen1210.c +++ b/drivers/sensors/xen1210.c @@ -49,6 +49,7 @@ #include #include #include +#include #include "xen1210.h" @@ -442,6 +443,12 @@ void xen1210_getdata(FAR struct xen1210_dev_s *priv) #ifdef CONFIG_XEN1210_REGDEBUG _err("%02x->%02x\n", regaddr, regval); #endif + + /* Feed sensor data to entropy pool */ + + add_sensor_randomness((priv->sample.data_x << 8) ^ + (priv->sample.data_y << 4) ^ + (priv->sample.data_z << 4)); } /**************************************************************************** diff --git a/include/nuttx/board.h b/include/nuttx/board.h index cd08aceddd..0525499021 100644 --- a/include/nuttx/board.h +++ b/include/nuttx/board.h @@ -646,4 +646,20 @@ void board_crashdump(uintptr_t currentsp, FAR void *tcb, int lineno); #endif +/**************************************************************************** + * Name: board_initrngseed + * + * Description: + * If CONFIG_BOARD_INITRNGSEED is selected then board_init_rngseed is + * called at up_randompool_initialize() to feed initial random seed + * to RNG. Implemenation of this functions should feed at least + * MIN_SEED_NEW_ENTROPY_WORDS 32-bit random words to entropy-pool using + * up_rngaddentropy() or up_rngaddint(). + * + ****************************************************************************/ + +#ifdef CONFIG_BOARD_INITRNGSEED +void board_init_rngseed(void); +#endif + #endif /* __INCLUDE_NUTTX_BOARD_H */ diff --git a/include/nuttx/crypto/blake2s.h b/include/nuttx/crypto/blake2s.h new file mode 100644 index 0000000000..fa6667fb6f --- /dev/null +++ b/include/nuttx/crypto/blake2s.h @@ -0,0 +1,197 @@ +/**************************************************************************** + * include/nuttx/crypto/blake2s.h + * + * This code is based on public-domain/CC0 BLAKE2 reference implementation + * by Samual Neves, at https://github.com/BLAKE2/BLAKE2/tree/master/ref + * Copyright 2012, Samuel Neves + * + * Copyright (C) 2017 Haltian Ltd. All rights reserved. + * Authors: Jussi Kivilinna + * + * 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_CRYPTO_BLAKE2S_H +#define __INCLUDE_NUTTX_CRYPTO_BLAKE2S_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#ifdef __cplusplus +extern "C" +{ +#endif + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +enum blake2s_constant +{ + BLAKE2S_BLOCKBYTES = 64, + BLAKE2S_OUTBYTES = 32, + BLAKE2S_KEYBYTES = 32, + BLAKE2S_SALTBYTES = 8, + BLAKE2S_PERSONALBYTES = 8 +}; + +typedef struct blake2s_state__ +{ + uint32_t h[8]; + uint32_t t[2]; + uint32_t f[2]; + size_t buflen; + size_t outlen; + uint8_t buf[BLAKE2S_BLOCKBYTES]; +} blake2s_state; + +typedef struct blake2s_param__ +{ + uint8_t digest_length; /* 1 */ + uint8_t key_length; /* 2 */ + uint8_t fanout; /* 3 */ + uint8_t depth; /* 4 */ + uint8_t leaf_length[4]; /* 8 */ + uint8_t node_offset[4]; /* 12 */ + uint8_t xof_length[2]; /* 14 */ + uint8_t node_depth; /* 15 */ + uint8_t inner_length; /* 16 */ + /* uint8_t reserved[0]; */ + uint8_t salt[BLAKE2S_SALTBYTES]; /* 24 */ + uint8_t personal[BLAKE2S_PERSONALBYTES]; /* 32 */ +} blake2s_param; + +#ifdef __GNUC__ > 3 +#define BLAKE2_UNALIGNED 1 +typedef uint32_t uint32_alias_t __attribute__((may_alias, aligned(1))); +typedef uint16_t uint16_alias_t __attribute__((may_alias, aligned(1))); +#endif + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/* Streaming API */ + +int blake2s_init(FAR blake2s_state *S, size_t outlen); +int blake2s_init_key(FAR blake2s_state *S, size_t outlen, FAR const void *key, + size_t keylen); +int blake2s_init_param(FAR blake2s_state *S, FAR const blake2s_param *P); +int blake2s_update(FAR blake2s_state *S, FAR const void *in, size_t inlen); +int blake2s_final(FAR blake2s_state *S, FAR void *out, size_t outlen); + +/* Simple API */ + +int blake2s(FAR void *out, size_t outlen, FAR const void *in, size_t inlen, + FAR const void *key, size_t keylen); + +/**************************************************************************** + * Public Inline Functions + ****************************************************************************/ + +static inline uint32_t blake2_load32(FAR const void *src) +{ +#if defined(BLAKE2_UNALIGNED) && !defined(CONFIG_ENDIAN_BIG) + return *(FAR uint32_alias_t *)src; +#elif !defined(CONFIG_ENDIAN_BIG) + FAR const uint8_t *p = (FAR const uint8_t *)src; + return ((uint32_t)(p[0]) << 24) | + ((uint32_t)(p[1]) << 16) | + ((uint32_t)(p[2]) << 8) | + ((uint32_t)(p[3]) << 0); +#else + FAR const uint8_t *p = (FAR const uint8_t *)src; + return ((uint32_t)(p[0]) << 0) | + ((uint32_t)(p[1]) << 8) | + ((uint32_t)(p[2]) << 16) | + ((uint32_t)(p[3]) << 24); +#endif +} + +static inline uint16_t blake2_load16(FAR const void *src) +{ +#if defined(BLAKE2_UNALIGNED) && !defined(CONFIG_ENDIAN_BIG) + return *(FAR uint16_alias_t *)src; +#elif !defined(CONFIG_ENDIAN_BIG) + const uint8_t *p = (FAR const uint8_t *)src; + return ((uint16_t)(p[0]) << 8) | ((uint16_t)(p[1]) << 0); +#else + const uint8_t *p = (FAR const uint8_t *)src; + return ((uint16_t)(p[0]) << 0) | ((uint16_t)(p[1]) << 8); +#endif +} + +static inline void blake2_store16(FAR void *dst, uint16_t w) +{ +#if defined(BLAKE2_UNALIGNED) && !defined(CONFIG_ENDIAN_BIG) + *(FAR uint16_alias_t *)dst = w; +#elif !defined(CONFIG_ENDIAN_BIG) + FAR uint8_t *p = (FAR uint8_t *)dst; + p[1] = (uint8_t)w; w >>= 8; + p[0] = (uint8_t)w; +#else + FAR uint8_t *p = (FAR uint8_t *)dst; + p[0] = (uint8_t)w; w >>= 8; + p[1] = (uint8_t)w; +#endif +} + +static inline void blake2_store32(FAR void *dst, uint32_t w) +{ +#if defined(BLAKE2_UNALIGNED) && !defined(CONFIG_ENDIAN_BIG) + *(FAR uint32_alias_t *)dst = w; +#elif !defined(CONFIG_ENDIAN_BIG) + FAR uint8_t *p = (FAR uint8_t *) dst; + p[0] = (uint8_t)(w >> 24); + p[1] = (uint8_t)(w >> 16); + p[2] = (uint8_t)(w >> 8); + p[3] = (uint8_t)(w >> 0); +#else + FAR uint8_t *p = (FAR uint8_t *) dst; + p[0] = (uint8_t)(w >> 0); + p[1] = (uint8_t)(w >> 8); + p[2] = (uint8_t)(w >> 16); + p[3] = (uint8_t)(w >> 24); +#endif +} + +#ifdef __cplusplus +} +#endif + +#endif /* __INCLUDE_NUTTX_CRYPTO_BLAKE2S_H */ diff --git a/include/nuttx/random.h b/include/nuttx/random.h new file mode 100644 index 0000000000..d3413e62fb --- /dev/null +++ b/include/nuttx/random.h @@ -0,0 +1,171 @@ +/**************************************************************************** + * include/nuttx/random.h + * + * Copyright (C) 2015-2017 Haltian Ltd. All rights reserved. + * Authors: Juha Niskanen + * Jussi Kivilinna + * + * 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_RANDOM_H +#define __INCLUDE_NUTTX_RANDOM_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include /* getrandom() */ + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Size of entropy pool in 32-bit integers, must be power of two */ + +#define ENTROPY_POOL_SIZE 128 + +#define add_irq_randomness(x) up_rngaddint(RND_SRC_IRQ, (x)) +#define add_sensor_randomness(x) up_rngaddint(RND_SRC_SENSOR, (x)) +#define add_time_randomness(x) up_rngaddint(RND_SRC_TIME, (x)) +#define add_hw_randomness(x) up_rngaddint(RND_SRC_HW, (x)) +#define add_sw_randomness(x) up_rngaddint(RND_SRC_SW, (x)) +#define add_ui_randomness(x) up_rngaddint(RND_SRC_UI, (x)) + +/* Allow above macros to always exist in source without ifdefs */ + +#ifndef CONFIG_CRYPTO_RANDOM_POOL +# define up_rngaddint(k, x) ((void)(k),(void)(x)) +# define up_rngaddentropy(k, buf, n) ((void)(k),(void)(buf),(void)(x)) +#endif + +/**************************************************************************** + * Public Type Definitions + ****************************************************************************/ + +/* Entropy pool structure */ + +struct entropy_pool_s +{ + volatile uint32_t pool[ENTROPY_POOL_SIZE]; +}; + +/* Randomness sources */ + +enum rnd_source_t +{ + RND_SRC_TIME = 0, + RND_SRC_IRQ, + RND_SRC_SENSOR, + RND_SRC_HW, /* unique per HW UID or coming from factory line. */ + RND_SRC_SW, /* unique per SW version. */ + RND_SRC_UI /* buttons etc. user-visible interface elements. */ +}; + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +#ifdef CONFIG_BOARD_ENTROPY_POOL +/* Entropy pool structure can be provided by board source. Use for this is, + * for example, allocate entropy pool from special area of RAM which content + * is kept over system reset. */ + +extern struct entropy_pool_s board_entropy_pool; +#endif + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +#ifdef CONFIG_CRYPTO_RANDOM_POOL + +/**************************************************************************** + * Function: up_rngaddint + * + * Description: + * Add one integer to entropy pool, contributing a specific kind + * of entropy to pool. + * + * Parameters: + * kindof - Enumeration constant telling where val came from + * val - Integer to be added + * + * Returned Value: + * None + * + ****************************************************************************/ + +void up_rngaddint(enum rnd_source_t kindof, int val); + +/**************************************************************************** + * Function: up_rngaddentropy + * + * Description: + * Add buffer of integers to entropy pool. + * + * Parameters: + * kindof - Enumeration constant telling where val came from + * buf - Buffer of integers to be added + * n - Number of elements in buf + * + * Returned Value: + * None + * + ****************************************************************************/ + +void up_rngaddentropy(enum rnd_source_t kindof, FAR const uint32_t *buf, + size_t n); + +/**************************************************************************** + * Function: up_rngreseed + * + * Description: + * Force reseeding random number generator from entropy pool + * + ****************************************************************************/ + +void up_rngreseed(void); + +/**************************************************************************** + * Function: up_randompool_initialize + * + * Description: + * Initialize entropy pool and random number generator + * + ****************************************************************************/ + +void up_randompool_initialize(void); + +#endif /* CONFIG_CRYPTO_RANDOM_POOL */ + +#endif /* __INCLUDE_NUTTX_RANDOM_H */ diff --git a/include/string.h b/include/string.h index 92df7f85b5..f3dbc2aaf6 100644 --- a/include/string.h +++ b/include/string.h @@ -93,6 +93,8 @@ FAR void *memcpy(FAR void *dest, FAR const void *src, size_t n); FAR void *memmove(FAR void *dest, FAR const void *src, size_t count); FAR void *memset(FAR void *s, int c, size_t n); +void explicit_bzero(FAR void *s, size_t n); + #undef EXTERN #if defined(__cplusplus) } diff --git a/include/sys/random.h b/include/sys/random.h new file mode 100644 index 0000000000..7856ca007e --- /dev/null +++ b/include/sys/random.h @@ -0,0 +1,77 @@ +/**************************************************************************** + * include/sys/random.h + * + * Copyright (C) 2015-2017 Haltian Ltd. All rights reserved. + * Authors: Juha Niskanen + * Jussi Kivilinna + * + * 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_SYS_RANDOM_H +#define __INCLUDE_SYS_RANDOM_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +#ifdef CONFIG_CRYPTO_RANDOM_POOL + +/**************************************************************************** + * Function: getrandom + * + * Description: + * Fill a buffer of arbitrary length with randomness. This is the + * preferred interface for getting random numbers. The traditional + * /dev/random approach is susceptible for things like the attacker + * exhausting file descriptors on purpose. + * + * Note that this function cannot fail, other than by asserting. + * + * Parameters: + * bytes - Buffer for returned random bytes + * nbytes - Number of bytes requested. + * + * Returned Value: + * None + * + ****************************************************************************/ + +void getrandom(FAR void *bytes, size_t nbytes); + +#endif /* CONFIG_CRYPTO_RANDOM_POOL */ + +#endif /* __INCLUDE_SYS_RANDOM_H */ diff --git a/include/sys/syscall.h b/include/sys/syscall.h index 56319b772d..6f1911c6c4 100644 --- a/include/sys/syscall.h +++ b/include/sys/syscall.h @@ -524,10 +524,19 @@ /* The following is defined only if CONFIG_TASK_NAME_SIZE > 0 */ #if CONFIG_TASK_NAME_SIZE > 0 -# define SYS_prctl (SYS_nnetsocket+0) -# define SYS_maxsyscall (SYS_nnetsocket+1) +# define SYS_prctl (SYS_nnetsocket+1) #else -# define SYS_maxsyscall SYS_nnetsocket +# define SYS_prctl SYS_nnetsocket +#endif + +/* The following is defined only if entropy pool random number generator + * is enabled. */ + +#ifdef CONFIG_CRYPTO_RANDOM_POOL +# define SYS_getrandom (SYS_prctl+1) +# define SYS_maxsyscall (SYS_prctl+2) +#else +# define SYS_maxsyscall SYS_prctl #endif /* Note that the reported number of system calls does *NOT* include the diff --git a/libc/string/Make.defs b/libc/string/Make.defs index 72cb8354d5..0b82b6af8d 100644 --- a/libc/string/Make.defs +++ b/libc/string/Make.defs @@ -44,6 +44,7 @@ CSRCS += lib_strerror.c lib_strlen.c lib_strnlen.c lib_strncasecmp.c CSRCS += lib_strncat.c lib_strncmp.c lib_strncpy.c lib_strndup.c CSRCS += lib_strcasestr.c lib_strpbrk.c lib_strrchr.c lib_strspn.c CSRCS += lib_strstr.c lib_strtok.c lib_strtokr.c lib_strerrorr.c +CSRCS += lib_explicit_bzero.c ifneq ($(CONFIG_LIBC_ARCH_MEMCPY),y) ifeq ($(CONFIG_MEMCPY_VIK),y) diff --git a/libc/string/lib_explicit_bzero.c b/libc/string/lib_explicit_bzero.c new file mode 100644 index 0000000000..ab862ed1a8 --- /dev/null +++ b/libc/string/lib_explicit_bzero.c @@ -0,0 +1,56 @@ +/**************************************************************************** + * libc/string/lib_explicit_bzero.c + * + * Copyright (C) 2015,2017 Haltian Ltd. All rights reserved. + * Author: Juha Niskanen + * Jussi Kivilinna + * + * 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 + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/* memset that must not be optimized away by compiler (not even with LTO). */ + +void explicit_bzero(FAR void *s, size_t n) +{ + static FAR void *(*FAR const volatile memset_v)(FAR void *, int, size_t) = + &memset; + + memset_v(s, 0, n); +} diff --git a/sched/irq/irq_dispatch.c b/sched/irq/irq_dispatch.c index b507c065b1..b311e8a2c1 100644 --- a/sched/irq/irq_dispatch.c +++ b/sched/irq/irq_dispatch.c @@ -42,6 +42,7 @@ #include #include #include +#include #include "irq/irq.h" @@ -53,7 +54,7 @@ * Name: irq_dispatch * * Description: - * This function must be called from the achitecture-specific logic in + * This function must be called from the architecture-specific logic in * order to dispatch an interrupt to the appropriate, registered handling * logic. * @@ -97,6 +98,12 @@ void irq_dispatch(int irq, FAR void *context) arg = NULL; #endif +#ifdef CONFIG_CRYPTO_RANDOM_POOL_COLLECT_IRQ_RANDOMNESS + /* Add interrupt timing randomness to entropy pool */ + + add_irq_randomness(irq); +#endif + /* Then dispatch to the interrupt handler */ vector(irq, context, arg); diff --git a/syscall/syscall.csv b/syscall/syscall.csv index 66babafb5e..1ff6948d74 100644 --- a/syscall/syscall.csv +++ b/syscall/syscall.csv @@ -30,6 +30,7 @@ "get_errno_ptr","errno.h","defined(__DIRECT_ERRNO_ACCESS)","FAR int*" "getenv","stdlib.h","!defined(CONFIG_DISABLE_ENVIRON)","FAR char*","FAR const char*" "getpid","unistd.h","","pid_t" +"getrandom","sys/random.h","defined(CONFIG_CRYPTO_RANDOM_POOL)","void","FAR void*","size_t" "getsockopt","sys/socket.h","CONFIG_NSOCKET_DESCRIPTORS > 0 && defined(CONFIG_NET)","int","int","int","int","FAR void*","FAR socklen_t*" "insmod","nuttx/module.h","defined(CONFIG_MODULE)","FAR void *","FAR const char *","FAR const char *" "ioctl","sys/ioctl.h","!defined(CONFIG_LIBC_IOCTL_VARIADIC) && (CONFIG_NSOCKET_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0)","int","int","int","unsigned long" diff --git a/syscall/syscall_lookup.h b/syscall/syscall_lookup.h index 6ed2e54e78..0719358487 100644 --- a/syscall/syscall_lookup.h +++ b/syscall/syscall_lookup.h @@ -379,6 +379,13 @@ SYSCALL_LOOKUP(up_assert, 2, STUB_up_assert) SYSCALL_LOOKUP(prctl, 5, STUB_prctl) #endif +/* The following is defined only if entropy pool random number generator + * is enabled. */ + +#ifdef CONFIG_CRYPTO_RANDOM_POOL + SYSCALL_LOOKUP(getrandom, 2, STUB_getrandom) +#endif + /**************************************************************************** * Private Functions ****************************************************************************/ diff --git a/syscall/syscall_stublookup.c b/syscall/syscall_stublookup.c index ddcffd5506..2cc52ad0a3 100644 --- a/syscall/syscall_stublookup.c +++ b/syscall/syscall_stublookup.c @@ -391,6 +391,11 @@ uintptr_t STUB_socket(int nbr, uintptr_t parm1, uintptr_t parm2, uintptr_t STUB_prctl(int nbr, uintptr_t parm1, uintptr_t parm2, uintptr_t parm3, uintptr_t parm4, uintptr_t parm5); +/* The following is defined only if entropy pool random number generator + * is enabled. */ + +uintptr_t STUB_getrandom(int nbr, uintptr_t parm1, uintptr_t parm2); + /**************************************************************************** * Public Data ****************************************************************************/ -- GitLab From 0ded0f586606bd64adb9478fc495d7d63679bb6d Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 30 Mar 2017 08:43:07 -0600 Subject: [PATCH 272/990] Update README and comments --- configs/samv71-xult/README.txt | 13 +++++++++++++ libc/string/lib_explicit_bzero.c | 1 - 2 files changed, 13 insertions(+), 1 deletion(-) diff --git a/configs/samv71-xult/README.txt b/configs/samv71-xult/README.txt index 5821d14b4f..9022351033 100644 --- a/configs/samv71-xult/README.txt +++ b/configs/samv71-xult/README.txt @@ -749,6 +749,19 @@ Selecting the GMAC peripheral CONFIG_NSH_NOMAC=n : We will get the IP address from EEPROM : Defaults should be okay for other options +SAMV71 Versions +--------------- + +WARNING: "The newer SAMV71 have 6 GMAC queues, not 5. All queues must be +configured for the GMAC to work correctly, even the queues that you are not +using (you can just configure these queues with a very small ring buffer.) + +The older uses the Cortex-M7 core r0p1 and the newer r1p1 revisions. The +SAMV71 revisions are called "rev A" (or sometimes "MRLA") and "rev B" +("MRLB"). There should be a small "A" or "B" on the chip package just below +the reference and you can also differentiate them at runtime with the +VERSION field in the CHIPID CIDR register." + Cache-Related Issues -------------------- diff --git a/libc/string/lib_explicit_bzero.c b/libc/string/lib_explicit_bzero.c index ab862ed1a8..b8d806508e 100644 --- a/libc/string/lib_explicit_bzero.c +++ b/libc/string/lib_explicit_bzero.c @@ -34,7 +34,6 @@ * ****************************************************************************/ - /**************************************************************************** * Included Files ****************************************************************************/ -- GitLab From 95cbbf552bb37ed9a4eaf20f764e3524288a3a14 Mon Sep 17 00:00:00 2001 From: Konstantin Berezenko Date: Thu, 30 Mar 2017 10:36:53 -0700 Subject: [PATCH 273/990] Change STM32 tickless to use only one timer --- arch/arm/src/stm32/Kconfig | 29 +- arch/arm/src/stm32/stm32_tickless.c | 696 ++++++++++++++++++++++++---- 2 files changed, 623 insertions(+), 102 deletions(-) diff --git a/arch/arm/src/stm32/Kconfig b/arch/arm/src/stm32/Kconfig index 97f097fc65..5ae19c927a 100644 --- a/arch/arm/src/stm32/Kconfig +++ b/arch/arm/src/stm32/Kconfig @@ -2810,31 +2810,22 @@ menu "Timer Configuration" if SCHED_TICKLESS -config STM32_ONESHOT - bool - default y - -config STM32_FREERUN - bool - default y - -config STM32_TICKLESS_ONESHOT - int "Tickless one-shot timer channel" +config STM32_TICKLESS_TIMER + int "Tickless hardware timer" default 2 range 1 14 - depends on STM32_ONESHOT ---help--- - If the Tickless OS feature is enabled, the one clock must be - assigned to provided the one-shot timer needed by the OS. + If the Tickless OS feature is enabled, then one clock must be + assigned to provided the timer needed by the OS. -config STM32_TICKLESS_FREERUN - int "Tickless free-running timer channel" - default 5 - range 1 14 - depends on STM32_FREERUN +config STM32_TICKLESS_CHANNEL + int "Tickless timer channel" + default 1 + range 1 4 ---help--- If the Tickless OS feature is enabled, the one clock must be - assigned to provided the free-running timer needed by the OS. + assigned to provided the free-running timer needed by the OS + and one channel on that clock is needed to handle intervals. endif # SCHED_TICKLESS diff --git a/arch/arm/src/stm32/stm32_tickless.c b/arch/arm/src/stm32/stm32_tickless.c index fafa9bcadf..f0baa5edee 100644 --- a/arch/arm/src/stm32/stm32_tickless.c +++ b/arch/arm/src/stm32/stm32_tickless.c @@ -2,7 +2,9 @@ * arch/arm/src/stm32/stm32_tickless.c * * Copyright (C) 2016 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Copyright (C) 2017 Ansync Labs. All rights reserved. + * Authors: Gregory Nutt + * Konstantin Berezenko * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -55,24 +57,19 @@ * ****************************************************************************/ /**************************************************************************** - * SAM34 Timer Usage - * - * This current implementation uses two timers: A one-shot timer to provide - * the timed events and a free running timer to provide the current time. - * Since timers are a limited resource, that could be an issue on some - * systems. - * - * We could do the job with a single timer if we were to keep the single - * timer in a free-running at all times. The STM32 timer/counters have - * 16-bit/32-bit counters with the capability to generate a compare interrupt - * when the timer matches a compare value but also to continue counting - * without stopping (giving another, different interrupt when the timer - * rolls over from 0xffffffff to zero). So we could potentially just set - * the compare at the number of ticks you want PLUS the current value of - * timer. Then you could have both with a single timer: An interval timer - * and a free-running counter with the same timer! - * - * Patches are welcome! + * STM32 Timer Usage + * + * This implementation uses one timer: A free running timer to provide + * the current time and a capture/compare channel for timed-events. + * The STM32 has both 16-bit and 32-bit timers so to keep things consistent + * we limit the timer counters to a 16-bit range. BASIC timers that + * are found on some STM32 chips (timers 6 and 7) are incompatible with this + * implementation because they don't have capture/compare channels. There + * are two interrupts generated from our timer, the overflow interrupt which + * drives the timing handler and the capture/compare interrupt which drives + * the interval handler. There are some low level timer control functions + * implemented here because the API of stm32_tim.c does not provide adequate + * control over capture/compare interrupts. * ****************************************************************************/ @@ -84,12 +81,15 @@ #include #include +#include +#include #include #include -#include "stm32_oneshot.h" -#include "stm32_freerun.h" +#include "up_arch.h" + +#include "stm32_tim.h" #ifdef CONFIG_SCHED_TICKLESS @@ -97,30 +97,24 @@ * Pre-processor Definitions ****************************************************************************/ -#ifndef CONFIG_STM32_ONESHOT -# error CONFIG_STM32_ONESHOT must be selected for the Tickless OS option -#endif - -#ifndef CONFIG_STM32_FREERUN -# error CONFIG_STM32_FREERUN must be selected for the Tickless OS option -#endif - -#ifndef CONFIG_STM32_TICKLESS_FREERUN -# error CONFIG_STM32_TICKLESS_FREERUN must be selected for the Tickless OS option -#endif - -#ifndef CONFIG_STM32_TICKLESS_ONESHOT -# error CONFIG_STM32_TICKLESS_ONESHOT must be selected for the Tickless OS option -#endif - /**************************************************************************** * Private Types ****************************************************************************/ struct stm32_tickless_s { - struct stm32_oneshot_s oneshot; - struct stm32_freerun_s freerun; + uint8_t timer; /* The timer/counter in use */ + uint8_t channel; /* The timer channel to use for intervals */ + FAR struct stm32_tim_dev_s *tch; /* Handle returned by stm32_tim_init() */ + uint32_t frequency; +#ifdef CONFIG_CLOCK_TIMEKEEPING + uint64_t counter_mask; +#else + uint32_t overflow; /* Timer counter overflow */ +#endif + volatile bool pending; /* True: pending task */ + uint32_t period; /* Interval period */ + uint32_t base; }; /**************************************************************************** @@ -133,11 +127,155 @@ static struct stm32_tickless_s g_tickless; * Private Functions ****************************************************************************/ +/************************************************************************************ + * Name: stm32_getreg16 + * + * Description: + * Get a 16-bit register value by offset + * + ************************************************************************************/ + +static inline uint16_t stm32_getreg16(uint8_t offset) +{ + return getreg16(g_tickless.base + offset); +} + +/************************************************************************************ + * Name: stm32_putreg16 + * + * Description: + * Put a 16-bit register value by offset + * + ************************************************************************************/ + +static inline void stm32_putreg16(uint8_t offset, uint16_t value) +{ + putreg16(value, g_tickless.base + offset); +} + +/************************************************************************************ + * Name: stm32_modifyreg16 + * + * Description: + * Modify a 16-bit register value by offset + * + ************************************************************************************/ + +static inline void stm32_modifyreg16(uint8_t offset, uint16_t clearbits, uint16_t setbits) +{ + modifyreg16(g_tickless.base + offset, clearbits, setbits); +} + +/************************************************************************************ + * Name: stm32_tickless_enableint + ************************************************************************************/ + +static inline void stm32_tickless_enableint(int channel) +{ + stm32_modifyreg16(STM32_BTIM_DIER_OFFSET, 0, 1 << channel); +} + +/************************************************************************************ + * Name: stm32_tickless_disableint + ************************************************************************************/ + +static inline void stm32_tickless_disableint(int channel) +{ + stm32_modifyreg16(STM32_BTIM_DIER_OFFSET, 1 << channel, 0); +} + +/************************************************************************************ + * Name: stm32_tickless_ackint + ************************************************************************************/ + +static inline void stm32_tickless_ackint(int channel) +{ + stm32_putreg16(STM32_BTIM_SR_OFFSET, ~(1 << channel)); +} + +/************************************************************************************ + * Name: stm32_tickless_getint + ************************************************************************************/ + +static inline uint16_t stm32_tickless_getint(void) +{ + return stm32_getreg16(STM32_BTIM_SR_OFFSET); +} + +/************************************************************************************ + * Name: stm32_tickless_setchannel + ************************************************************************************/ + +static int stm32_tickless_setchannel(uint8_t channel) +{ + uint16_t ccmr_orig = 0; + uint16_t ccmr_val = 0; + uint16_t ccmr_mask = 0xff; + uint16_t ccer_val = stm32_getreg16(STM32_GTIM_CCER_OFFSET); + uint8_t ccmr_offset = STM32_GTIM_CCMR1_OFFSET; + + /* Further we use range as 0..3; if channel=0 it will also overflow here */ + + if (--channel > 4) + { + return -EINVAL; + } + + /* Assume that channel is disabled and polarity is active high */ + + ccer_val &= ~(3 << (channel << 2)); + + /* This function is not supported on basic timers. To enable or + * disable it, simply set its clock to valid frequency or zero. + */ + +#if STM32_NBTIM > 0 + if (g_tickless.base == STM32_TIM6_BASE +#endif +#if STM32_NBTIM > 1 + || g_tickless.base == STM32_TIM7_BASE +#endif +#if STM32_NBTIM > 0 + ) + { + return -EINVAL; + } +#endif + + /* frozen mode because we don't want to change the gpio, preload register disabled */ + ccmr_val = (ATIM_CCMR_MODE_FRZN << ATIM_CCMR1_OC1M_SHIFT); + + /* Set polarity */ + + ccer_val |= ATIM_CCER_CC1P << (channel << 2); + + /* Define its position (shift) and get register offset */ + + if (channel & 1) + { + ccmr_val <<= 8; + ccmr_mask <<= 8; + } + + if (channel > 1) + { + ccmr_offset = STM32_GTIM_CCMR2_OFFSET; + } + + ccmr_orig = stm32_getreg16(ccmr_offset); + ccmr_orig &= ~ccmr_mask; + ccmr_orig |= ccmr_val; + stm32_putreg16(ccmr_offset, ccmr_orig); + stm32_putreg16(STM32_GTIM_CCER_OFFSET, ccer_val); + + return OK; +} + /**************************************************************************** - * Name: stm32_oneshot_handler + * Name: stm32_interval_handler * * Description: - * Called when the one shot timer expires + * Called when the timer counter matches the compare register * * Input Parameters: * None @@ -151,12 +289,76 @@ static struct stm32_tickless_s g_tickless; * ****************************************************************************/ -static void stm32_oneshot_handler(void *arg) +static void stm32_interval_handler(void) { tmrinfo("Expired...\n"); + + /* Disable the compare interrupt now. */ + + stm32_tickless_disableint(g_tickless.channel); + stm32_tickless_ackint(g_tickless.channel); + + g_tickless.pending = false; + sched_timer_expiration(); } + +/**************************************************************************** + * Name: stm32_timing_handler + * + * Description: + * Timer interrupt callback. When the freerun timer counter overflows, + * this interrupt will occur. We will just increment an overflow count. + * + * Input Parameters: + * None + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifndef CONFIG_CLOCK_TIMEKEEPING +static void stm32_timing_handler(void) +{ + g_tickless.overflow++; + + STM32_TIM_ACKINT(g_tickless.tch, 0); +} +#endif /* CONFIG_CLOCK_TIMEKEEPING */ + + +/**************************************************************************** + * Name: stm32_tickless_handler + * + * Description: + * Generic interrupt handler for this timer. It checks the source of the + * interrupt and fires the appropriate handler. + * + * Input Parameters: + * None + * + * Returned Value: + * None + * + ****************************************************************************/ + +static int stm32_tickless_handler(int irq, void *context, void *arg) +{ + int interrupt_flags = stm32_tickless_getint(); + +#ifndef CONFIG_CLOCK_TIMEKEEPING + if (interrupt_flags & ATIM_SR_UIF) + stm32_timing_handler(); +#endif /* CONFIG_CLOCK_TIMEKEEPING */ + + if (interrupt_flags & (1 << g_tickless.channel)) + stm32_interval_handler(); + + return OK; +} + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -188,55 +390,162 @@ static void stm32_oneshot_handler(void *arg) void arm_timer_initialize(void) { -#ifdef CONFIG_SCHED_TICKLESS_LIMIT_MAX_SLEEP - uint64_t max_delay; + switch (CONFIG_STM32_TICKLESS_TIMER) + { +#ifdef CONFIG_STM32_TIM1 + case 1: + g_tickless.base = STM32_TIM1_BASE; + break; +#endif +#ifdef CONFIG_STM32_TIM2 + case 2: + g_tickless.base = STM32_TIM2_BASE; + break; +#endif +#ifdef CONFIG_STM32_TIM3 + case 3: + g_tickless.base = STM32_TIM3_BASE; + break; +#endif +#ifdef CONFIG_STM32_TIM4 + case 4: + g_tickless.base = STM32_TIM4_BASE; + break; #endif - int ret; +#ifdef CONFIG_STM32_TIM5 + case 5: + g_tickless.base = STM32_TIM5_BASE; + break; +#endif +#ifdef CONFIG_STM32_TIM6 + case 6: - /* Initialize the one-shot timer */ + /* Basic timers not supported by this implementation */ - ret = stm32_oneshot_initialize(&g_tickless.oneshot, - CONFIG_STM32_TICKLESS_ONESHOT, - CONFIG_USEC_PER_TICK); - if (ret < 0) - { - tmrerr("ERROR: stm32_oneshot_initialize failed\n"); - PANIC(); - } + ASSERT(0); + break; +#endif +#ifdef CONFIG_STM32_TIM7 + case 7: -#ifdef CONFIG_SCHED_TICKLESS_LIMIT_MAX_SLEEP - /* Get the maximum delay of the one-shot timer in microseconds */ + /* Basic timers not supported by this implementation */ - ret = stm32_oneshot_max_delay(&g_tickless.oneshot, &max_delay); - if (ret < 0) - { - tmrerr("ERROR: stm32_oneshot_max_delay failed\n"); - PANIC(); - } + ASSERT(0); + break; +#endif +#ifdef CONFIG_STM32_TIM8 + case 8: + g_tickless.base = STM32_TIM8_BASE; + break; +#endif +#ifdef CONFIG_STM32_TIM9 + case 9: + g_tickless.base = STM32_TIM9_BASE; + break; +#endif +#ifdef CONFIG_STM32_TIM10 + case 10: + g_tickless.base = STM32_TIM10_BASE; + break; +#endif +#ifdef CONFIG_STM32_TIM11 + case 11: + g_tickless.base = STM32_TIM11_BASE; + break; +#endif +#ifdef CONFIG_STM32_TIM12 + case 12: + g_tickless.base = STM32_TIM12_BASE; + break; +#endif +#ifdef CONFIG_STM32_TIM13 + case 13: + g_tickless.base = STM32_TIM13_BASE; + break; +#endif +#ifdef CONFIG_STM32_TIM14 + case 14: + g_tickless.base = STM32_TIM14_BASE; + break; +#endif +#ifdef CONFIG_STM32_TIM15 + case 15: + g_tickless.base = STM32_TIM15_BASE; + break; +#endif +#ifdef CONFIG_STM32_TIM16 + case 16: + g_tickless.base = STM32_TIM16_BASE; + break; +#endif +#ifdef CONFIG_STM32_TIM17 + case 17: + g_tickless.base = STM32_TIM17_BASE; + break; +#endif - /* Convert this to configured clock ticks for use by the OS timer logic */ + default: + ASSERT(0); - max_delay /= CONFIG_USEC_PER_TICK; - if (max_delay > UINT32_MAX) - { - g_oneshot_maxticks = UINT32_MAX; } - else + + /* Get the TC frequency that corresponds to the requested resolution */ + + g_tickless.frequency = USEC_PER_SEC / (uint32_t)CONFIG_USEC_PER_TICK; + g_tickless.timer = CONFIG_STM32_TICKLESS_TIMER; + g_tickless.channel = CONFIG_STM32_TICKLESS_CHANNEL; + g_tickless.pending = false; + g_tickless.period = 0; + + tmrinfo("timer=%d channel=%d frequency=%d Hz\n", + g_tickless.timer, g_tickless.channel, g_tickless.frequency); + + g_tickless.tch = stm32_tim_init(g_tickless.timer); + if (!g_tickless.tch) { - g_oneshot_maxticks = max_delay; + tmrerr("ERROR: Failed to allocate TIM%d\n", g_tickless.timer); + ASSERT(0); } + + STM32_TIM_SETCLOCK(g_tickless.tch, g_tickless.frequency); + +#ifdef CONFIG_CLOCK_TIMEKEEPING + + /* Should this be changed to 0xffff because we use 16 bit timers? */ + + g_tickless.counter_mask = 0xffffffffull; +#else + g_tickless.overflow = 0; + + /* Set up to receive the callback when the counter overflow occurs */ + + STM32_TIM_SETISR(g_tickless.tch, stm32_tickless_handler, NULL, 0); #endif - /* Initialize the free-running timer */ + /* Initialize interval to zero */ - ret = stm32_freerun_initialize(&g_tickless.freerun, - CONFIG_STM32_TICKLESS_FREERUN, - CONFIG_USEC_PER_TICK); - if (ret < 0) - { - tmrerr("ERROR: stm32_freerun_initialize failed\n"); - PANIC(); - } + STM32_TIM_SETCOMPARE(g_tickless.tch, g_tickless.channel, 0); + + /* Setup compare channel for the interval timing */ + + stm32_tickless_setchannel(g_tickless.channel); + + /* Set timer period */ + + STM32_TIM_SETPERIOD(g_tickless.tch, UINT16_MAX); + + /* Initialize the counter */ + + STM32_TIM_SETMODE(g_tickless.tch, STM32_TIM_MODE_UP); + +#ifdef CONFIG_SCHED_TICKLESS_LIMIT_MAX_SLEEP + g_oneshot_maxticks = UINT16_MAX; +#endif + + /* Start the timer */ + + STM32_TIM_ACKINT(g_tickless.tch, 0); + STM32_TIM_ENABLEINT(g_tickless.tch, 0); } /**************************************************************************** @@ -276,14 +585,84 @@ void arm_timer_initialize(void) int up_timer_gettime(FAR struct timespec *ts) { - return stm32_freerun_counter(&g_tickless.freerun, ts); + uint64_t usec; + uint32_t counter; + uint32_t verify; + uint32_t overflow; + uint32_t sec; + int pending; + irqstate_t flags; + + DEBUGASSERT(g_tickless.tch && ts); + + /* Temporarily disable the overflow counter. NOTE that we have to be + * careful here because stm32_tc_getpending() will reset the pending + * interrupt status. If we do not handle the overflow here then, it will + * be lost. + */ + + flags = enter_critical_section(); + + overflow = g_tickless.overflow; + counter = STM32_TIM_GETCOUNTER(g_tickless.tch); + pending = STM32_TIM_CHECKINT(g_tickless.tch, 0); + verify = STM32_TIM_GETCOUNTER(g_tickless.tch); + + /* If an interrupt was pending before we re-enabled interrupts, + * then the overflow needs to be incremented. + */ + + if (pending) + { + STM32_TIM_ACKINT(g_tickless.tch, 0); + + /* Increment the overflow count and use the value of the + * guaranteed to be AFTER the overflow occurred. + */ + + overflow++; + counter = verify; + + /* Update tickless overflow counter. */ + + g_tickless.overflow = overflow; + } + + leave_critical_section(flags); + + tmrinfo("counter=%lu (%lu) overflow=%lu, pending=%i\n", + (unsigned long)counter, (unsigned long)verify, + (unsigned long)overflow, pending); + tmrinfo("frequency=%u\n", g_tickless.frequency); + + /* Convert the whole thing to units of microseconds. + * + * frequency = ticks / second + * seconds = ticks * frequency + * usecs = (ticks * USEC_PER_SEC) / frequency; + */ + + usec = ((((uint64_t)overflow << 16) + (uint64_t)counter) * USEC_PER_SEC) / + g_tickless.frequency; + + /* And return the value of the timer */ + + sec = (uint32_t)(usec / USEC_PER_SEC); + ts->tv_sec = sec; + ts->tv_nsec = (usec - (sec * USEC_PER_SEC)) * NSEC_PER_USEC; + + tmrinfo("usec=%llu ts=(%u, %lu)\n", + usec, (unsigned long)ts->tv_sec, (unsigned long)ts->tv_nsec); + + return OK; } #else int up_timer_getcounter(FAR uint64_t *cycles) { - return stm32_freerun_counter(&g_tickless.freerun, cycles); + *cycles = (uint64_t)STM32_TIM_GETCOUNTER(g_tickless.tch); + return OK; } #endif /* CONFIG_CLOCK_TIMEKEEPING */ @@ -306,7 +685,7 @@ int up_timer_getcounter(FAR uint64_t *cycles) void up_timer_getmask(FAR uint64_t *mask) { DEBUGASSERT(mask != NULL); - *mask = g_tickless.freerun.counter_mask; + *mask = g_tickless.counter_mask; } #endif /* CONFIG_CLOCK_TIMEKEEPING */ @@ -348,7 +727,100 @@ void up_timer_getmask(FAR uint64_t *mask) int up_timer_cancel(FAR struct timespec *ts) { - return stm32_oneshot_cancel(&g_tickless.oneshot, ts); + irqstate_t flags; + uint64_t usec; + uint64_t sec; + uint64_t nsec; + uint32_t count; + uint32_t period; + + /* Was the timer running? */ + + flags = enter_critical_section(); + if (!g_tickless.pending) + { + /* No.. Just return zero timer remaining and successful cancellation. + * This function may execute at a high rate with no timer running + * (as when pre-emption is enabled and disabled). + */ + + if (ts) + { + ts->tv_sec = 0; + ts->tv_nsec = 0; + } + leave_critical_section(flags); + return OK; + } + + /* Yes.. Get the timer counter and period registers and disable the compare interrupt. + * + */ + + tmrinfo("Cancelling...\n"); + + /* Disable the interrupt. */ + + stm32_tickless_disableint(g_tickless.channel); + + count = STM32_TIM_GETCOUNTER(g_tickless.tch); + period = g_tickless.period; + + g_tickless.pending = false; + leave_critical_section(flags); + + /* Did the caller provide us with a location to return the time + * remaining? + */ + + if (ts) + { + /* Yes.. then calculate and return the time remaining on the + * oneshot timer. + */ + + tmrinfo("period=%lu count=%lu\n", + (unsigned long)period, (unsigned long)count); + + if (count > period) + { + /* Handle rollover */ + + period += UINT16_MAX; + } + else if (count == period) + { + /* No time remaining */ + + ts->tv_sec = 0; + ts->tv_nsec = 0; + return OK; + } + + /* The total time remaining is the difference. Convert that + * to units of microseconds. + * + * frequency = ticks / second + * seconds = ticks * frequency + * usecs = (ticks * USEC_PER_SEC) / frequency; + */ + + usec = (((uint64_t)(period - count)) * USEC_PER_SEC) / + g_tickless.frequency; + + /* Return the time remaining in the correct form */ + + sec = usec / USEC_PER_SEC; + nsec = ((usec) - (sec * USEC_PER_SEC)) * NSEC_PER_USEC; + + ts->tv_sec = (time_t)sec; + ts->tv_nsec = (unsigned long)nsec; + + tmrinfo("remaining (%lu, %lu)\n", + (unsigned long)ts->tv_sec, (unsigned long)ts->tv_nsec); + } + + return OK; } /**************************************************************************** @@ -378,6 +850,64 @@ int up_timer_cancel(FAR struct timespec *ts) int up_timer_start(FAR const struct timespec *ts) { - return stm32_oneshot_start(&g_tickless.oneshot, stm32_oneshot_handler, NULL, ts); + uint64_t usec; + uint64_t period; + uint32_t count; + irqstate_t flags; + + tmrinfo("handler=%p arg=%p, ts=(%lu, %lu)\n", + handler, arg, (unsigned long)ts->tv_sec, (unsigned long)ts->tv_nsec); + DEBUGASSERT(ts); + DEBUGASSERT(g_tickless.tch); + + /* Was an interval already running? */ + + flags = enter_critical_section(); + if (g_tickless.pending) + { + /* Yes.. then cancel it */ + + tmrinfo("Already running... cancelling\n"); + (void)up_timer_cancel(NULL); + } + + /* Express the delay in microseconds */ + + usec = (uint64_t)ts->tv_sec * USEC_PER_SEC + + (uint64_t)(ts->tv_nsec / NSEC_PER_USEC); + + /* Get the timer counter frequency and determine the number of counts need + * to achieve the requested delay. + * + * frequency = ticks / second + * ticks = seconds * frequency + * = (usecs * frequency) / USEC_PER_SEC; + */ + + period = (usec * (uint64_t)g_tickless.frequency) / USEC_PER_SEC; + count = STM32_TIM_GETCOUNTER(g_tickless.tch); + + tmrinfo("usec=%llu period=%08llx\n", usec, period); + DEBUGASSERT(period <= UINT16_MAX); + + /* Set interval compare value. Rollover is fine, + * channel will trigger on the next period. (uint16_t) cast + * handles the overflow. + */ + + g_tickless.period = (uint16_t)(period + count); + + STM32_TIM_SETCOMPARE(g_tickless.tch, g_tickless.channel, g_tickless.period); + + /* Enable interrupts. We should get the callback when the interrupt + * occurs. + */ + + stm32_tickless_ackint(g_tickless.channel); + stm32_tickless_enableint(g_tickless.channel); + + g_tickless.pending = true; + leave_critical_section(flags); + return OK; } #endif /* CONFIG_SCHED_TICKLESS */ -- GitLab From 9e2b3da3e8451e1befa0f49393e3b6eaf04a89bb Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Thu, 30 Mar 2017 09:34:03 -0600 Subject: [PATCH 274/990] drivers/sensors: Add driver for ST HTS221 humidity sensor --- drivers/sensors/Kconfig | 23 + drivers/sensors/Make.defs | 4 + drivers/sensors/hts221.c | 1131 ++++++++++++++++++++++++++++++++ include/nuttx/random.h | 2 +- include/nuttx/sensors/hts221.h | 158 +++++ include/nuttx/sensors/ioctl.h | 10 + 6 files changed, 1327 insertions(+), 1 deletion(-) create mode 100644 drivers/sensors/hts221.c create mode 100644 include/nuttx/sensors/hts221.h diff --git a/drivers/sensors/Kconfig b/drivers/sensors/Kconfig index 9b3e2660b2..5871c18b81 100644 --- a/drivers/sensors/Kconfig +++ b/drivers/sensors/Kconfig @@ -32,6 +32,29 @@ config BMP180 ---help--- Enable driver support for the Bosch BMP180 barometer sensor. +config HTS221 + bool "ST HTS221 humidity sensor" + default n + select I2C + ---help--- + Enable driver support for the ST HTS221 humidity sensor. + +if HTS221 + +config DEBUG_HTS221 + bool "Debug support for the HTS221" + default n + ---help--- + Enables debug features for the HTS221 + +config HTS221_NPOLLWAITERS + int "Number of waiters to poll" + default 1 + ---help--- + Number of waiters to poll + +endif # HTS221 + config SENSORS_L3GD20 bool "ST L3GD20 Gyroscope Sensor support" default n diff --git a/drivers/sensors/Make.defs b/drivers/sensors/Make.defs index c4b14ace8f..d0bb9fa650 100644 --- a/drivers/sensors/Make.defs +++ b/drivers/sensors/Make.defs @@ -81,6 +81,10 @@ ifeq ($(CONFIG_BMP180),y) CSRCS += bmp180.c endif +ifeq ($(CONFIG_HTS221),y) + CSRCS += hts221.c +endif + ifeq ($(CONFIG_I2C_LM75),y) CSRCS += lm75.c endif diff --git a/drivers/sensors/hts221.c b/drivers/sensors/hts221.c new file mode 100644 index 0000000000..4dc9c0d2dd --- /dev/null +++ b/drivers/sensors/hts221.c @@ -0,0 +1,1131 @@ +/**************************************************************************** + * drivers/sensors/hts221.c + * + * Copyright (C) 2014 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 +#include +#include + +#include + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +#ifdef CONFIG_DEBUG_HTS221 +# define hts221_dbg(x, ...) _info(x, ##__VA_ARGS__) +#else +# define hts221_dbg(x, ...) sninfo(x, ##__VA_ARGS__) +#endif + +#define HTS221_WHO_AM_I 0x0f +#define HTS221_AV_CONF 0x10 +#define HTS221_CTRL_REG1 0x20 +#define HTS221_CTRL_REG2 0x21 +#define HTS221_CTRL_REG3 0x22 +#define HTS221_STATUS_REG 0x27 +#define HTS221_HUM_OUT_L 0x28 +#define HTS221_HUM_OUT_H 0x29 +#define HTS221_TEMP_OUT_L 0x2a +#define HTS221_TEMP_OUT_H 0x2b + +/* Calibration registers */ + +#define HTS221_CALIB_H0_RH_X2 0x30 +#define HTS221_CALIB_H1_RH_X2 0x31 +#define HTS221_CALIB_T0_DEGC_X8 0x32 +#define HTS221_CALIB_T1_DEGC_X8 0x33 +#define HTS221_CALIB_T1_T0_MSB 0x35 +#define HTS221_CALIB_H0T0_OUT_L 0x36 +#define HTS221_CALIB_H0T0_OUT_H 0x37 +#define HTS221_CALIB_H1T0_OUT_L 0x3a +#define HTS221_CALIB_H1T0_OUT_H 0x3b +#define HTS221_CALIB_T0_OUT_L 0x3c +#define HTS221_CALIB_T0_OUT_H 0x3d +#define HTS221_CALIB_T1_OUT_L 0x3e +#define HTS221_CALIB_T1_OUT_H 0x3f + +/* HTS221_CTRL_REG1 */ + +#define HTS221_CTRL_REG1_PD (1 << 7) +#define HTS221_CTRL_REG1_BDU (1 << 2) + +/* HTS221_CTRL_REG2 */ + +#define HTS221_CTRL_REG2_BOOT (1 << 7) +#define HTS221_CTRL_REG2_ONE_SHOT (1 << 0) + +/* HTS221_CTRL_REG3 */ + +#define HTS221_CTRL_REG3_DRDY_L_H (1 << 7) +#define HTS221_CTRL_REG3_PP_OD (1 << 6) +#define HTS221_CTRL_REG3_DRDY_EN (1 << 2) + +/* HTS221_STATUS_REG */ + +#define HTS221_STATUS_REG_H_DA (1 << 1) +#define HTS221_STATUS_REG_T_DA (1 << 0) + +#define HTS221_I2C_RETRIES 10 + +/**************************************************************************** +* Private Function Prototypes +*****************************************************************************/ + +static int hts221_open(FAR struct file *filep); +static int hts221_close(FAR struct file *filep); +static ssize_t hts221_read(FAR struct file *filep, FAR char *buffer, + size_t buflen); +static ssize_t hts221_write(FAR struct file *filep, FAR const char *buffer, + size_t buflen); +static int hts221_ioctl(FAR struct file *filep, int cmd, unsigned long arg); +#ifndef CONFIG_DISABLE_POLL +static int hts221_poll(FAR struct file *filep, FAR struct pollfd *fds, + bool setup); +#endif + +/**************************************************************************** +* Private Types +****************************************************************************/ + +struct hts221_dev_s +{ + struct i2c_master_s *i2c; + uint8_t addr; + hts221_config_t *config; + sem_t devsem; + volatile bool int_pending; +#ifndef CONFIG_DISABLE_POLL + struct pollfd *fds[CONFIG_HTS221_NPOLLWAITERS]; +#endif + struct + { + int16_t t0_out; + int16_t t1_out; + int16_t h0_t0_out; + int16_t h1_t0_out; + unsigned int t0_x8:10; + unsigned int t1_x8:10; + uint8_t h0_x2; + uint8_t h1_x2; + } calib; +}; + +/**************************************************************************** +* Private Data +****************************************************************************/ + +static const struct file_operations g_humidityops = +{ + hts221_open, /* open */ + hts221_close, /* close */ + hts221_read, /* read */ + hts221_write, /* write */ + NULL, /* seek */ + hts221_ioctl /* ioctl */ +#ifndef CONFIG_DISABLE_POLL + , hts221_poll /* poll */ +#endif +#ifndef CONFIG_DISABLE_PSEUDOFS_OPERATIONS + , NULL /* unlink */ +#endif +}; + +static struct hts221_dev_s *g_humid_data; + +/**************************************************************************** +* Private Functions +****************************************************************************/ + +static int hts221_do_transfer(FAR struct hts221_dev_s *dev, + FAR struct i2c_msg_s *msgv, + size_t nmsg) +{ + int ret = -EIO; + int retries; + + for (retries = 0; retries < HTS221_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 == HTS221_I2C_RETRIES - 1) + { + break; + } + + ret = up_i2creset(dev->i2c); + if (ret < 0) + { + hts221_dbg("up_i2creset failed: %d\n", ret); + return ret; + } +#endif + } + } + + hts221_dbg("xfer failed: %d\n", ret); + return ret; +} + +static int32_t hts221_write_reg8(FAR struct hts221_dev_s *dev, + const uint8_t *command) +{ + struct i2c_msg_s msgv[2] = + { + { + .addr = dev->addr, + .flags = 0, + .buffer = (FAR void *)&command[0], + .length = 1 + }, + { + .addr = dev->addr, + .flags = I2C_M_NORESTART, + .buffer = (FAR void *)&command[1], + .length = 1 + } + }; + + return hts221_do_transfer(dev, msgv, 2); +} + +static int hts221_read_reg(FAR struct hts221_dev_s *dev, + FAR const uint8_t *command, FAR uint8_t *value) +{ + struct i2c_msg_s msgv[2] = + { + { + .addr = dev->addr, + .flags = 0, + .buffer = (FAR void *)command, + .length = 1 + }, + { + .addr = dev->addr, + .flags = I2C_M_READ, + .buffer = value, + .length = 1 + } + }; + + return hts221_do_transfer(dev, msgv, 2); +} + +static int hts221_get_id(FAR struct hts221_dev_s *priv, uint8_t * value) +{ + int ret = OK; + uint8_t cmd = HTS221_WHO_AM_I; + + ret = hts221_read_reg(priv, &cmd, value); + + hts221_dbg("Who am I request: 0x%02X\n", *value); + + return ret; +} + +static int hts221_cfgr_resolution(FAR struct hts221_dev_s *priv, + FAR hts221_settings_t *settings) +{ + int ret; + uint8_t value; + const uint8_t addr = HTS221_AV_CONF; + uint8_t regval = 0; + uint8_t cmd[2] = { 0 }; + const uint8_t mask = 0x3f; + + ret = hts221_read_reg(priv, &addr, ®val); + hts221_dbg("Default resolution: 0x%02X\n", regval); + if (ret < 0) + { + return ERROR; + } + + value = (uint8_t)settings->humid_resol | + ((uint8_t)settings->temp_resol << 3); + regval &= ~mask; + cmd[0] = addr; + cmd[1] = regval | value; + hts221_dbg("New resolution: 0x%02X\n", cmd[1]); + + ret = hts221_write_reg8(priv, cmd); + + hts221_dbg("Resolution changed: temp=%d humid=%d ret=%d\n", + settings->temp_resol, settings->humid_resol, ret); + + return ret; +} + +static int hts221_config_ctrl_reg3(FAR struct hts221_dev_s *priv, + FAR hts221_settings_t *settings) +{ + int ret = OK; + uint8_t regval = 0; + uint8_t addr = HTS221_CTRL_REG3; + const uint8_t mask = 0xc4; + uint8_t data_to_write[2] = { 0 }; + + ret = hts221_read_reg(priv, &addr, ®val); + hts221_dbg("CTRL_REG3: 0x%02X\n", regval); + if (ret < 0) + { + return ERROR; + } + + regval &= ~mask; + regval |= (uint8_t)(settings->is_high_edge ? 0 : HTS221_CTRL_REG3_DRDY_L_H); + regval |= (uint8_t)(settings->is_open_drain ? HTS221_CTRL_REG3_PP_OD : 0); + regval |= (uint8_t)(settings->is_data_rdy ? HTS221_CTRL_REG3_DRDY_EN : 0); + + data_to_write[0] = addr; + data_to_write[1] = regval; + + ret = hts221_write_reg8(priv, data_to_write); + + return ret; +} + +static int hts221_config_ctrl_reg2(FAR struct hts221_dev_s *priv, + FAR hts221_settings_t *settings) +{ + int ret = OK; + uint8_t regval = 0; + uint8_t addr = HTS221_CTRL_REG2; + const uint8_t mask = 0x80; + uint8_t data_to_write[2] = { 0 }; + + ret = hts221_read_reg(priv, &addr, ®val); + hts221_dbg("CTRL_REG2: 0x%02X\n", regval); + if (ret < 0) + { + return ERROR; + } + + regval &= ~mask; + regval |= (uint8_t)(settings->is_boot ? HTS221_CTRL_REG2_BOOT : 0); + + data_to_write[0] = addr; + data_to_write[1] = regval; + + ret = hts221_write_reg8(priv, data_to_write); + + return ret; +} + +static int hts221_config_ctrl_reg1(FAR struct hts221_dev_s *priv, + FAR hts221_settings_t * settings) +{ + int ret = OK; + uint8_t regval = 0; + uint8_t addr = HTS221_CTRL_REG1; + const uint8_t mask = 0x87; + uint8_t data_to_write[2] = { 0 }; + + ret = hts221_read_reg(priv, &addr, ®val); + hts221_dbg("CTRL_REG1: 0x%02X\n", regval); + if (ret < 0) + { + return ERROR; + } + + regval &= ~mask; + regval |= (uint8_t) (settings->odr & 0xFF); + regval |= (uint8_t) (settings->is_bdu ? HTS221_CTRL_REG1_BDU : 0); + + data_to_write[0] = addr; + data_to_write[1] = regval; + + ret = hts221_write_reg8(priv, data_to_write); + + return ret; +} + +static int hts221_power_on_off(FAR struct hts221_dev_s *priv, bool on) +{ + int ret = OK; + uint8_t regval = 0; + uint8_t addr = HTS221_CTRL_REG1; + uint8_t data_to_write[2]; + + ret = hts221_read_reg(priv, &addr, ®val); + hts221_dbg("CTRL_REG1: 0x%02X\n", regval); + if (ret < 0) + { + return ret; + } + + if (on) + { + regval |= HTS221_CTRL_REG1_PD; + } + else + { + regval &= ~HTS221_CTRL_REG1_PD; + } + data_to_write[0] = addr; + data_to_write[1] = regval; + + ret = hts221_write_reg8(priv, data_to_write); + + return ret; +} + +static int hts221_config(FAR struct hts221_dev_s *priv, + FAR hts221_settings_t * cfgr) +{ + int ret = OK; + + ret = hts221_cfgr_resolution(priv, cfgr); + if (ret < 0) + { + return ERROR; + } + + ret = hts221_config_ctrl_reg3(priv, cfgr); + if (ret < 0) + { + return ERROR; + } + + ret = hts221_config_ctrl_reg2(priv, cfgr); + if (ret < 0) + { + return ERROR; + } + + ret = hts221_config_ctrl_reg1(priv, cfgr); + if (ret < 0) + { + return ERROR; + } + + return ret; +} + +static int hts221_start_conversion(FAR struct hts221_dev_s *priv) +{ + int ret; + uint8_t addr = HTS221_CTRL_REG2; + uint8_t data_to_write[2]; + + ret = hts221_power_on_off(priv, true); + if (ret < 0) + { + return ERROR; + } + + data_to_write[0] = addr; + data_to_write[1] = (uint8_t) HTS221_CTRL_REG2_ONE_SHOT; + + ret = hts221_write_reg8(priv, data_to_write); + if (ret < 0) + { + hts221_dbg("Cannot start conversion\n"); + ret = ERROR; + } + + return ret; +} + +static int hts221_check_status(FAR struct hts221_dev_s *priv, + FAR hts221_status_t * status) +{ + int ret = OK; + uint8_t addr = HTS221_STATUS_REG; + const uint8_t humid_mask = 0x02; + const uint8_t temp_mask = 0x01; + uint8_t regval = 0; + + ret = hts221_read_reg(priv, &addr, ®val); + if (ret < 0) + { + return ERROR; + } + + status->is_humid_ready = ((regval & humid_mask) ? true : false); + status->is_temp_ready = ((regval & temp_mask) ? true : false); + + return ret; +} + +static int hts221_read_raw_data(FAR struct hts221_dev_s *priv, + FAR hts221_raw_data_t * data) +{ + int ret = OK; + uint8_t addr_humid_low = HTS221_HUM_OUT_L; + uint8_t addr_humid_high = HTS221_HUM_OUT_H; + uint8_t addr_temp_low = HTS221_TEMP_OUT_L; + uint8_t addr_temp_high = HTS221_TEMP_OUT_H; + uint32_t flags; + + ret = hts221_read_reg(priv, &addr_humid_low, &data->humid_low_bits); + if (ret < 0) + { + return ERROR; + } + + ret = hts221_read_reg(priv, &addr_humid_high, &data->humid_high_bits); + if (ret < 0) + { + return ERROR; + } + + ret = hts221_read_reg(priv, &addr_temp_low, &data->temp_low_bits); + if (ret < 0) + { + return ERROR; + } + + ret = hts221_read_reg(priv, &addr_temp_high, &data->temp_high_bits); + if (ret < 0) + { + return ERROR; + } + + /* Add low-order bytes to entropy pool. */ + + add_sensor_randomness(((uint32_t)data->humid_low_bits << 8) | data->temp_low_bits); + + flags = enter_critical_section(); + priv->int_pending = false; + leave_critical_section(flags); + + hts221_dbg("Humid: 0x%02X, 0x%02X Temper: 0x%02X 0x%02X\n", + data->humid_high_bits, data->humid_low_bits, + data->temp_high_bits, data->temp_low_bits); + + return ret; +} + +static int hts221_load_calibration_data(FAR struct hts221_dev_s *priv) +{ + int ret; + uint8_t addr; + uint8_t t0_degc_x8 = 0; + uint8_t t1_degc_x8 = 0; + uint8_t t1_t0_msb = 0; + uint8_t t0_out_lsb = 0; + uint8_t t0_out_msb = 0; + uint8_t t1_out_lsb = 0; + uint8_t t1_out_msb = 0; + uint8_t h0_rh_x2 = 0; + uint8_t h1_rh_x2 = 0; + uint8_t h0t0_out_lsb = 0; + uint8_t h0t0_out_msb = 0; + uint8_t h1t0_out_lsb = 0; + uint8_t h1t0_out_msb = 0; + + addr = HTS221_CALIB_T0_DEGC_X8; + ret = hts221_read_reg(priv, &addr, &t0_degc_x8); + if (ret < 0) + { + return ret; + } + + addr = HTS221_CALIB_T1_DEGC_X8; + ret = hts221_read_reg(priv, &addr, &t1_degc_x8); + if (ret < 0) + { + return ret; + } + + addr = HTS221_CALIB_T1_T0_MSB; + ret = hts221_read_reg(priv, &addr, &t1_t0_msb); + if (ret < 0) + { + return ret; + } + + addr = HTS221_CALIB_T0_OUT_L; + ret = hts221_read_reg(priv, &addr, &t0_out_lsb); + if (ret < 0) + { + return ret; + } + + addr = HTS221_CALIB_T0_OUT_H; + ret = hts221_read_reg(priv, &addr, &t0_out_msb); + if (ret < 0) + { + return ret; + } + + addr = HTS221_CALIB_T1_OUT_L; + ret = hts221_read_reg(priv, &addr, &t1_out_lsb); + if (ret < 0) + { + return ret; + } + + addr = HTS221_CALIB_T1_OUT_H; + ret = hts221_read_reg(priv, &addr, &t1_out_msb); + if (ret < 0) + { + return ret; + } + + addr = HTS221_CALIB_H0_RH_X2; + ret = hts221_read_reg(priv, &addr, &h0_rh_x2); + if (ret < 0) + { + return ret; + } + + addr = HTS221_CALIB_H1_RH_X2; + ret = hts221_read_reg(priv, &addr, &h1_rh_x2); + if (ret < 0) + { + return ret; + } + + addr = HTS221_CALIB_H0T0_OUT_L; + ret = hts221_read_reg(priv, &addr, &h0t0_out_lsb); + if (ret < 0) + { + return ret; + } + + addr = HTS221_CALIB_H0T0_OUT_H; + ret = hts221_read_reg(priv, &addr, &h0t0_out_msb); + if (ret < 0) + { + return ret; + } + + addr = HTS221_CALIB_H1T0_OUT_L; + ret = hts221_read_reg(priv, &addr, &h1t0_out_lsb); + if (ret < 0) + { + return ret; + } + + addr = HTS221_CALIB_H1T0_OUT_H; + ret = hts221_read_reg(priv, &addr, &h1t0_out_msb); + if (ret < 0) + { + return ret; + } + + priv->calib.t0_x8 = t0_degc_x8 | ((t1_t0_msb & 0x3) << 8); + priv->calib.t1_x8 = t1_degc_x8 | ((t1_t0_msb & (0x3 << 2)) << (8 - 2)); + priv->calib.t0_out = (uint16_t) (t0_out_lsb | (t0_out_msb << 8)); + priv->calib.t1_out = (uint16_t) (t1_out_lsb | (t1_out_msb << 8)); + priv->calib.h0_x2 = h0_rh_x2; + priv->calib.h1_x2 = h1_rh_x2; + priv->calib.h0_t0_out = (uint16_t) (h0t0_out_lsb | (h0t0_out_msb << 8)); + priv->calib.h1_t0_out = (uint16_t) (h1t0_out_lsb | (h1t0_out_msb << 8)); + + hts221_dbg("calib.t0_x8: %d\n", priv->calib.t0_x8); + hts221_dbg("calib.t1_x8: %d\n", priv->calib.t1_x8); + hts221_dbg("calib.t0_out: %d\n", priv->calib.t0_out); + hts221_dbg("calib.t1_out: %d\n", priv->calib.t1_out); + hts221_dbg("calib.h0_x2: %d\n", priv->calib.h0_x2); + hts221_dbg("calib.h1_x2: %d\n", priv->calib.h1_x2); + hts221_dbg("calib.h0_t0_out: %d\n", priv->calib.h0_t0_out); + hts221_dbg("calib.h1_t0_out: %d\n", priv->calib.h1_t0_out); + + /* As calibration coefficients are unique to each sensor device, + * they are a good candidate to be added to entropy pool. + */ + + up_rngaddentropy(RND_SRC_HW, (uint32_t *)&priv->calib, + sizeof(priv->calib) / sizeof(uint32_t)); + + return OK; +} + +static int hts221_calculate_temperature(FAR struct hts221_dev_s *priv, + FAR int *temperature, + FAR hts221_raw_data_t *raw_data) +{ + int16_t t_out = (raw_data->temp_high_bits << 8) | raw_data->temp_low_bits; + int x0 = priv->calib.t0_out; + int x1 = priv->calib.t1_out; + int y0 = priv->calib.t0_x8; + int y1 = priv->calib.t1_x8; + int x = t_out; + int64_t y; + int x1_x0_diff; + + x1_x0_diff = x1 - x0; + + y = (y0 * x1_x0_diff + (y1 - y0) * (x - x0)); + y *= HTS221_TEMPERATURE_PRECISION; + y /= x1_x0_diff * 8; + + *temperature = (int)y; + + hts221_dbg("Interpolation data temper: %d\n", *temperature); + + return OK; +} + +static int hts221_calculate_humidity(FAR struct hts221_dev_s *priv, + FAR unsigned int *humidity, + FAR hts221_raw_data_t *raw_data) +{ + int16_t h_out = (raw_data->humid_high_bits << 8) | raw_data->humid_low_bits; + int x0 = priv->calib.h0_t0_out; + int x1 = priv->calib.h1_t0_out; + int y0 = priv->calib.h0_x2; + int y1 = priv->calib.h1_x2; + int x = h_out; + int64_t y; + int x1_x0_diff; + + x1_x0_diff = x1 - x0; + + y = (y0 * x1_x0_diff + (y1 - y0) * (x - x0)); + y *= HTS221_HUMIDITY_PRECISION; + y /= x1_x0_diff * 2; + + *humidity = (int)y; + + hts221_dbg("Interpolation data humidity: %d\n", *humidity); + + return OK; +} + +static int hts221_read_convert_data(FAR struct hts221_dev_s *priv, + FAR hts221_conv_data_t *data) +{ + int ret = OK; + hts221_raw_data_t raw_data; + + ret = hts221_read_raw_data(priv, &raw_data); + if (ret < 0) + { + return ERROR; + } + + ret = hts221_calculate_temperature(priv, &data->temperature, &raw_data); + if (ret < 0) + { + return ERROR; + } + + hts221_dbg("Temperature calculated\n"); + + ret = hts221_calculate_humidity(priv, &data->humidity, &raw_data); + if (ret < 0) + { + return ERROR; + } + + hts221_dbg("Humidity calculated\n"); + return ret; +} + +#ifdef CONFIG_DEBUG_HTS221 +static int hts221_dump_registers(FAR struct hts221_dev_s *priv) +{ + int ret = OK; + uint8_t av_addr = HTS221_AV_CONF; + uint8_t ctrl_reg1_addr = HTS221_CTRL_REG1; + uint8_t ctrl_reg2_addr = HTS221_CTRL_REG2; + uint8_t ctrl_reg3_addr = HTS221_CTRL_REG3; + uint8_t regval = 0; + + ret = hts221_read_reg(priv, &av_addr, ®val); + if (ret < 0) + { + return ERROR; + } + + hts221_dbg("AV_CONF_REG: 0x%02X\n", regval); + + ret = hts221_read_reg(priv, &ctrl_reg1_addr, ®val); + if (ret < 0) + { + return ERROR; + } + + hts221_dbg("CTRL_REG_1: 0x%02X\n", regval); + + ret = hts221_read_reg(priv, &ctrl_reg2_addr, ®val); + if (ret < 0) + { + return ERROR; + } + + hts221_dbg("CTRL_REG_2: 0x%02X\n", regval); + + ret = hts221_read_reg(priv, &ctrl_reg3_addr, ®val); + if (ret < 0) + { + return ERROR; + } + + hts221_dbg("CTRL_REG_3: 0x%02X\n", regval); + return ret; +} +#endif + +static int hts221_open(FAR struct file *filep) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct hts221_dev_s *priv = inode->i_private; + + while (sem_wait(&priv->devsem) != 0) + { + assert(errno == EINTR); + } + + priv->config->set_power(priv->config, true); + priv->config->irq_enable(priv->config, true); + + sem_post(&priv->devsem); + hts221_dbg("Sensor is powered on\n"); + return OK; +} + +static int hts221_close(FAR struct file *filep) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct hts221_dev_s *priv = inode->i_private; + int ret = OK; + + while (sem_wait(&priv->devsem) != 0) + { + assert(errno == EINTR); + } + + priv->config->irq_enable(priv->config, false); + ret = hts221_power_on_off(priv, false); + priv->config->set_power(priv->config, false); + + sem_post(&priv->devsem); + hts221_dbg("CLOSED\n"); + return ret; +} + +static ssize_t hts221_read(FAR struct file *filep, FAR char *buffer, + size_t buflen) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct hts221_dev_s *priv = inode->i_private; + int ret = OK; + ssize_t length = 0; + hts221_conv_data_t data; + + while (sem_wait(&priv->devsem) != 0) + { + assert(errno == EINTR); + } + + ret = hts221_read_convert_data(priv, &data); + if (ret < 0) + { + hts221_dbg("cannot read data: %d\n", ret); + } + else + { + /* This interface is mainly intended for easy debugging in nsh. */ + + length = snprintf(buffer, buflen, "%d %u\n", + data.temperature, data.humidity); + if (length > buflen) + { + length = buflen; + } + } + + sem_post(&priv->devsem); + return length; +} + +static ssize_t hts221_write(FAR struct file *filep, FAR const char *buffer, + size_t buflen) +{ + ssize_t length = 0; + return length; +} + +static int hts221_ioctl(FAR struct file *filep, int cmd, unsigned long arg) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct hts221_dev_s *priv = inode->i_private; + int32_t ret = 0; + + while (sem_wait(&priv->devsem) != 0) + { + assert(errno == EINTR); + } + + switch (cmd) + { + case SNIOC_GET_DEV_ID: + ret = hts221_get_id(priv, (FAR uint8_t *) arg); + break; + + case SNIOC_CFGR: + ret = hts221_config(priv, (FAR hts221_settings_t *) arg); + break; + + case SNIOC_START_CONVERSION: + ret = hts221_start_conversion(priv); + break; + + case SNIOC_CHECK_STATUS_REG: + ret = hts221_check_status(priv, (FAR hts221_status_t *) arg); + break; + + case SNIOC_READ_RAW_DATA: + ret = hts221_read_raw_data(priv, (FAR hts221_raw_data_t *) arg); + break; + +#ifdef CONFIG_DEBUG_HTS221 + case SNIOC_DUMP_REGS: + ret = hts221_dump_registers(priv); + break; +#endif + + case SNIOC_READ_CONVERT_DATA: + ret = hts221_read_convert_data(priv, (FAR hts221_conv_data_t *) arg); + break; + + default: + ret = -EINVAL; + break; + } + + sem_post(&priv->devsem); + return ret; +} + +#ifndef CONFIG_DISABLE_POLL +static bool hts221_sample(FAR struct hts221_dev_s *priv) +{ + int ret; + hts221_status_t status = + { + .is_humid_ready = false, + .is_temp_ready = false + }; + + ret = hts221_check_status(priv, &status); + if (ret < 0) + { + return false; + } + + return status.is_humid_ready || status.is_temp_ready; +} + +static void hts221_notify(FAR struct hts221_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_HTS221_NPOLLWAITERS; i++) + { + FAR struct pollfd *fds = priv->fds[i]; + if (fds) + { + fds->revents |= POLLIN; + hts221_dbg("Report events: %02x\n", fds->revents); + sem_post(fds->sem); + } + } +} + +static int hts221_poll(FAR struct file *filep, FAR struct pollfd *fds, + bool setup) +{ + FAR struct inode *inode; + FAR struct hts221_dev_s *priv; + int ret = OK; + int i; + uint32_t flags; + + DEBUGASSERT(filep && fds); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct hts221_dev_s *)inode->i_private; + + while (sem_wait(&priv->devsem) != 0) + { + assert(errno == 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_HTS221_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_HTS221_NPOLLWAITERS) + { + fds->priv = NULL; + ret = -EBUSY; + goto out; + } + + flags = enter_critical_section(); + if (priv->int_pending || hts221_sample(priv)) + { + hts221_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; +} +#endif /* !CONFIG_DISABLE_POLL */ + +static int hts221_int_handler(int irq, FAR void *context, FAR void *arg) +{ + if (!g_humid_data) + return OK; + + g_humid_data->int_pending = true; + hts221_dbg("Hts221 interrupt\n"); +#ifndef CONFIG_DISABLE_POLL + hts221_notify(g_humid_data); +#endif + + return OK; +} + +int hts221_register(FAR const char *devpath, FAR struct i2c_master_s *i2c, + uint8_t addr, FAR hts221_config_t *config) +{ + int ret = 0; + FAR struct hts221_dev_s *priv; + + priv = (struct hts221_dev_s *)kmm_zalloc(sizeof(struct hts221_dev_s)); + + if (!priv) + { + hts221_dbg("Memory cannot be allocated for hts221 sensor"); + return -ENOMEM; + } + + g_humid_data = priv; + priv->addr = addr; + priv->i2c = i2c; + priv->config = config; + sem_init(&priv->devsem, 0, 1); + + ret = hts221_load_calibration_data(priv); + if (ret < 0) + { + kmm_free(priv); + hts221_dbg("Cannot calibrate hts221 sensor\n"); + return -EAGAIN; + } + + ret = register_driver(devpath, &g_humidityops, 0666, priv); + + hts221_dbg("Registered with %d\n", ret); + + if (ret < 0) + { + kmm_free(priv); + hts221_dbg("Error occurred during the driver registering\n"); + return ret; + } + + if (priv->config->irq_clear) + { + priv->config->irq_clear(priv->config); + } + + priv->config->irq_attach(priv->config, hts221_int_handler); + priv->config->irq_enable(priv->config, false); + return OK; +} diff --git a/include/nuttx/random.h b/include/nuttx/random.h index d3413e62fb..4017837071 100644 --- a/include/nuttx/random.h +++ b/include/nuttx/random.h @@ -65,7 +65,7 @@ #ifndef CONFIG_CRYPTO_RANDOM_POOL # define up_rngaddint(k, x) ((void)(k),(void)(x)) -# define up_rngaddentropy(k, buf, n) ((void)(k),(void)(buf),(void)(x)) +# define up_rngaddentropy(k, buf, x) ((void)(k),(void)(buf),(void)(x)) #endif /**************************************************************************** diff --git a/include/nuttx/sensors/hts221.h b/include/nuttx/sensors/hts221.h new file mode 100644 index 0000000000..47142c3f82 --- /dev/null +++ b/include/nuttx/sensors/hts221.h @@ -0,0 +1,158 @@ +/**************************************************************************** + * include/nuttx/sensors/hts221.h + * + * Copyright (C) 2014 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_HTS221_H +#define __INCLUDE_NUTT_SENSORS_HTS221_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define HTS221_TEMPERATURE_PRECISION 100 +#define HTS221_HUMIDITY_PRECISION 10 + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* Number of temperature samples */ + +typedef enum hts221_avrg_temp_e +{ + HTS221_AVGT2 = 0, + HTS221_AVGT4, + HTS221_AVGT8, + HTS221_AVGT16, /* Default value */ + HTS221_AVGT32, + HTS221_AVGT64, + HTS221_AVGT128, + HTS221_AVGT256 +} hts221_avrg_temp_t; + +/* Number of humidity samples */ + +typedef enum hts221_avrg_humid_e +{ + HTS221_AVGH4 = 0, + HTS221_AVGH8, + HTS221_AVGH16, + HTS221_AVGH32, /* Default value */ + HTS221_AVGH64, + HTS221_AVGH128, + HTS221_AVGH256, + HTS221_AVGH512 +}hts221_avrg_humid_t; + +/* Output data rate configuration */ + +typedef enum hts221_odr_e +{ + HTS221_ODR_ONESHOT = 0, + HTS221_ODR_1HZ, + HTS221_ODR_7HZ, + HTS221_ODR_12_5HZ +} hts221_odr_t; + +/* Configuration structure */ + +typedef struct hts221_settings_s +{ + hts221_avrg_temp_t temp_resol; /* Temperature resolution. The more + * samples sensor takes, the more power + * it uses */ + hts221_avrg_humid_t humid_resol; /* Humidity resolution. The more + * samples sensor takes, the more power + * it uses */ + hts221_odr_t odr; /* Output data rate */ + bool is_bdu; /* If read operation is not faster than output + * operation, then this variable must be set to true */ + bool is_data_rdy; /* Must be set to true, if interrupt needed. + * Default is 0, disabled */ + bool is_high_edge; /* High or low interrupt signal from device. + * Default is high, 0 */ + bool is_open_drain; /* Open drain or push-pull on data-ready pin. + * Default is push-pull, 0 */ + bool is_boot; /* Refresh the content of the internal registers */ +} hts221_settings_t; + +/* Interrupt configuration data structure */ + +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, + bool enable); + 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; + +/* Raw data structure */ + +typedef struct hts221_raw_data_s +{ + uint8_t humid_low_bits; + uint8_t humid_high_bits; + uint8_t temp_low_bits; + uint8_t temp_high_bits; +} hts221_raw_data_t; + +typedef struct hts221_conv_data_s +{ + int temperature; + unsigned int humidity; +} hts221_conv_data_t; + +/* Status register data */ + +typedef struct hts221_status_s +{ + bool is_humid_ready; + bool is_temp_ready; +} hts221_status_t; + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +int hts221_register(FAR const char *devpath, FAR struct i2c_master_s *i2c, + uint8_t addr, hts221_config_t * config); + +#endif /* __INCLUDE_NUTT_SENSORS_HTS221_H */ diff --git a/include/nuttx/sensors/ioctl.h b/include/nuttx/sensors/ioctl.h index acbf31d810..231c205601 100644 --- a/include/nuttx/sensors/ioctl.h +++ b/include/nuttx/sensors/ioctl.h @@ -115,4 +115,14 @@ #define SNIOC_RESET _SNIOC(0x0028) /* Arg: None */ #define SNIOC_OVERSAMPLING _SNIOC(0x0029) /* Arg: uint16_t value */ +/* IOCTL commands unique to the HTS221 */ + +#define SNIOC_GET_DEV_ID _SNIOC(0x002a) +#define SNIOC_CFGR _SNIOC(0x002b) +#define SNIOC_START_CONVERSION _SNIOC(0x002c) +#define SNIOC_CHECK_STATUS_REG _SNIOC(0x002d) +#define SNIOC_READ_RAW_DATA _SNIOC(0x002e) +#define SNIOC_READ_CONVERT_DATA _SNIOC(0x002f) +#define SNIOC_DUMP_REGS _SNIOC(0x0030) + #endif /* __INCLUDE_NUTTX_SENSORS_IOCTL_H */ -- GitLab From 7b789f57ac507f6a20cd507cc453f6c60a626cd4 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 30 Mar 2017 12:28:40 -0600 Subject: [PATCH 275/990] Review of previous commit --- arch/arm/src/stm32/Kconfig | 4 - arch/arm/src/stm32/stm32_tickless.c | 114 ++++++++++++++++------------ 2 files changed, 66 insertions(+), 52 deletions(-) diff --git a/arch/arm/src/stm32/Kconfig b/arch/arm/src/stm32/Kconfig index 5ae19c927a..6927a3c054 100644 --- a/arch/arm/src/stm32/Kconfig +++ b/arch/arm/src/stm32/Kconfig @@ -2829,8 +2829,6 @@ config STM32_TICKLESS_CHANNEL endif # SCHED_TICKLESS -if !SCHED_TICKLESS - config STM32_ONESHOT bool "TIM one-shot wrapper" default n @@ -2845,8 +2843,6 @@ config STM32_FREERUN Enable a wrapper around the low level timer/counter functions to support a free-running timer. -endif # !SCHED_TICKLESS - config STM32_ONESHOT_MAXTIMERS int "Maximum number of oneshot timers" default 1 diff --git a/arch/arm/src/stm32/stm32_tickless.c b/arch/arm/src/stm32/stm32_tickless.c index f0baa5edee..38162ad7d7 100644 --- a/arch/arm/src/stm32/stm32_tickless.c +++ b/arch/arm/src/stm32/stm32_tickless.c @@ -161,7 +161,8 @@ static inline void stm32_putreg16(uint8_t offset, uint16_t value) * ************************************************************************************/ -static inline void stm32_modifyreg16(uint8_t offset, uint16_t clearbits, uint16_t setbits) +static inline void stm32_modifyreg16(uint8_t offset, uint16_t clearbits, + uint16_t setbits) { modifyreg16(g_tickless.base + offset, clearbits, setbits); } @@ -236,14 +237,17 @@ static int stm32_tickless_setchannel(uint8_t channel) || g_tickless.base == STM32_TIM7_BASE #endif #if STM32_NBTIM > 0 - ) + ) { return -EINVAL; } #endif - /* frozen mode because we don't want to change the gpio, preload register disabled */ - ccmr_val = (ATIM_CCMR_MODE_FRZN << ATIM_CCMR1_OC1M_SHIFT); + /* Frozen mode because we don't want to change the GPIO, preload register + * disabled. + */ + + ccmr_val = (ATIM_CCMR_MODE_FRZN << ATIM_CCMR1_OC1M_SHIFT); /* Set polarity */ @@ -251,7 +255,7 @@ static int stm32_tickless_setchannel(uint8_t channel) /* Define its position (shift) and get register offset */ - if (channel & 1) + if ((channel & 1) != 0) { ccmr_val <<= 8; ccmr_mask <<= 8; @@ -293,7 +297,7 @@ static void stm32_interval_handler(void) { tmrinfo("Expired...\n"); - /* Disable the compare interrupt now. */ + /* Disable the compare interrupt now. */ stm32_tickless_disableint(g_tickless.channel); stm32_tickless_ackint(g_tickless.channel); @@ -303,7 +307,6 @@ static void stm32_interval_handler(void) sched_timer_expiration(); } - /**************************************************************************** * Name: stm32_timing_handler * @@ -328,7 +331,6 @@ static void stm32_timing_handler(void) } #endif /* CONFIG_CLOCK_TIMEKEEPING */ - /**************************************************************************** * Name: stm32_tickless_handler * @@ -350,11 +352,15 @@ static int stm32_tickless_handler(int irq, void *context, void *arg) #ifndef CONFIG_CLOCK_TIMEKEEPING if (interrupt_flags & ATIM_SR_UIF) - stm32_timing_handler(); + { + stm32_timing_handler(); + } #endif /* CONFIG_CLOCK_TIMEKEEPING */ if (interrupt_flags & (1 << g_tickless.channel)) - stm32_interval_handler(); + { + stm32_interval_handler(); + } return OK; } @@ -395,98 +401,108 @@ void arm_timer_initialize(void) #ifdef CONFIG_STM32_TIM1 case 1: g_tickless.base = STM32_TIM1_BASE; - break; + break; #endif + #ifdef CONFIG_STM32_TIM2 case 2: g_tickless.base = STM32_TIM2_BASE; - break; + break; #endif + #ifdef CONFIG_STM32_TIM3 case 3: g_tickless.base = STM32_TIM3_BASE; - break; + break; #endif + #ifdef CONFIG_STM32_TIM4 case 4: g_tickless.base = STM32_TIM4_BASE; - break; + break; #endif #ifdef CONFIG_STM32_TIM5 case 5: g_tickless.base = STM32_TIM5_BASE; - break; + break; #endif + #ifdef CONFIG_STM32_TIM6 case 6: - /* Basic timers not supported by this implementation */ + /* Basic timers not supported by this implementation */ ASSERT(0); - break; + break; #endif + #ifdef CONFIG_STM32_TIM7 case 7: - /* Basic timers not supported by this implementation */ + /* Basic timers not supported by this implementation */ ASSERT(0); - break; + break; #endif + #ifdef CONFIG_STM32_TIM8 case 8: g_tickless.base = STM32_TIM8_BASE; - break; + break; #endif + #ifdef CONFIG_STM32_TIM9 case 9: g_tickless.base = STM32_TIM9_BASE; - break; + break; #endif #ifdef CONFIG_STM32_TIM10 case 10: g_tickless.base = STM32_TIM10_BASE; - break; + break; #endif + #ifdef CONFIG_STM32_TIM11 case 11: g_tickless.base = STM32_TIM11_BASE; - break; + break; #endif #ifdef CONFIG_STM32_TIM12 case 12: g_tickless.base = STM32_TIM12_BASE; - break; + break; #endif #ifdef CONFIG_STM32_TIM13 case 13: g_tickless.base = STM32_TIM13_BASE; - break; + break; #endif + #ifdef CONFIG_STM32_TIM14 case 14: g_tickless.base = STM32_TIM14_BASE; - break; + break; #endif #ifdef CONFIG_STM32_TIM15 case 15: g_tickless.base = STM32_TIM15_BASE; - break; + break; #endif + #ifdef CONFIG_STM32_TIM16 case 16: g_tickless.base = STM32_TIM16_BASE; - break; + break; #endif + #ifdef CONFIG_STM32_TIM17 case 17: g_tickless.base = STM32_TIM17_BASE; - break; + break; #endif default: ASSERT(0); - } /* Get the TC frequency that corresponds to the requested resolution */ @@ -749,6 +765,7 @@ int up_timer_cancel(FAR struct timespec *ts) ts->tv_sec = 0; ts->tv_nsec = 0; } + leave_critical_section(flags); return OK; } @@ -773,7 +790,7 @@ int up_timer_cancel(FAR struct timespec *ts) * remaining? */ - if (ts) + if (ts != NULL) { /* Yes.. then calculate and return the time remaining on the * oneshot timer. @@ -786,7 +803,7 @@ int up_timer_cancel(FAR struct timespec *ts) { /* Handle rollover */ - period += UINT16_MAX; + period += UINT16_MAX; } else if (count == period) { @@ -794,27 +811,27 @@ int up_timer_cancel(FAR struct timespec *ts) ts->tv_sec = 0; ts->tv_nsec = 0; - return OK; + return OK; } - /* The total time remaining is the difference. Convert that - * to units of microseconds. - * - * frequency = ticks / second - * seconds = ticks * frequency - * usecs = (ticks * USEC_PER_SEC) / frequency; - */ + /* The total time remaining is the difference. Convert that + * to units of microseconds. + * + * frequency = ticks / second + * seconds = ticks * frequency + * usecs = (ticks * USEC_PER_SEC) / frequency; + */ - usec = (((uint64_t)(period - count)) * USEC_PER_SEC) / - g_tickless.frequency; + usec = (((uint64_t)(period - count)) * USEC_PER_SEC) / + g_tickless.frequency; - /* Return the time remaining in the correct form */ + /* Return the time remaining in the correct form */ - sec = usec / USEC_PER_SEC; - nsec = ((usec) - (sec * USEC_PER_SEC)) * NSEC_PER_USEC; + sec = usec / USEC_PER_SEC; + nsec = ((usec) - (sec * USEC_PER_SEC)) * NSEC_PER_USEC; - ts->tv_sec = (time_t)sec; - ts->tv_nsec = (unsigned long)nsec; + ts->tv_sec = (time_t)sec; + ts->tv_nsec = (unsigned long)nsec; tmrinfo("remaining (%lu, %lu)\n", (unsigned long)ts->tv_sec, (unsigned long)ts->tv_nsec); @@ -897,7 +914,8 @@ int up_timer_start(FAR const struct timespec *ts) g_tickless.period = (uint16_t)(period + count); - STM32_TIM_SETCOMPARE(g_tickless.tch, g_tickless.channel, g_tickless.period); + STM32_TIM_SETCOMPARE(g_tickless.tch, g_tickless.channel, + g_tickless.period); /* Enable interrupts. We should get the callback when the interrupt * occurs. -- GitLab From c3289afa9c8d0d73ab23343403da3d231415c21c Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 30 Mar 2017 12:29:19 -0600 Subject: [PATCH 276/990] Fix error in last update to a README --- configs/samv71-xult/README.txt | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/configs/samv71-xult/README.txt b/configs/samv71-xult/README.txt index 9022351033..c963851259 100644 --- a/configs/samv71-xult/README.txt +++ b/configs/samv71-xult/README.txt @@ -752,7 +752,7 @@ Selecting the GMAC peripheral SAMV71 Versions --------------- -WARNING: "The newer SAMV71 have 6 GMAC queues, not 5. All queues must be +WARNING: The newer SAMV71 have 6 GMAC queues, not 3. All queues must be configured for the GMAC to work correctly, even the queues that you are not using (you can just configure these queues with a very small ring buffer.) @@ -760,7 +760,7 @@ The older uses the Cortex-M7 core r0p1 and the newer r1p1 revisions. The SAMV71 revisions are called "rev A" (or sometimes "MRLA") and "rev B" ("MRLB"). There should be a small "A" or "B" on the chip package just below the reference and you can also differentiate them at runtime with the -VERSION field in the CHIPID CIDR register." +VERSION field in the CHIPID CIDR register. Cache-Related Issues -------------------- -- GitLab From 2aca4d4ebd4a78a08c6bfbb85ab4aa21de42913e Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 30 Mar 2017 15:38:56 -0600 Subject: [PATCH 277/990] 6loWPAN: Add a little more send logic. --- include/nuttx/net/sixlowpan.h | 53 ++- net/sixlowpan/Kconfig | 6 +- net/sixlowpan/Make.defs | 2 +- net/sixlowpan/sixlowpan_framer.c | 606 +++++++++++++++++++++++++++++ net/sixlowpan/sixlowpan_hc06.c | 3 +- net/sixlowpan/sixlowpan_internal.h | 224 +++++++++-- net/sixlowpan/sixlowpan_send.c | 199 ++++++++-- net/sixlowpan/sixlowpan_utils.c | 32 +- 8 files changed, 1062 insertions(+), 63 deletions(-) create mode 100644 net/sixlowpan/sixlowpan_framer.c diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index 376fbf2d9c..0d403d25bb 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -323,6 +323,27 @@ struct rimeaddr_s * manage the fragmentation. 'struct ieee802154_driver_s' is cast * compatible with 'struct net_driver_s' when CONFIG_NET_MULTINIC is not * defined or when dev->d_lltype == NET_LL_IEEE802154. + * + * The IEEE802.15.4 MAC network driver has reponsibility for initializing + * this structure. In general, all fields must be set to NULL. In + * addtion: + * + * 1) i_panid must be set to identify the network. It may be set to 0xfff + * if the device is not associated. + * 2) i_dsn must be set to a random value. After that, it will be managed + * by the network. + * 3) i_nodeaddr must be set after the MAC is assigned an address. + * + * Frame Organization: + * + * Content Offset + * +----------------+ 0 + * | Frame Header | + * +----------------+ i_dataoffset + * | Data | + * +----------------+ i_framelen + * | Unused | + * +----------------+ CONFIG_NET_6LOWPAN_FRAMELEN */ struct ieee802154_driver_s @@ -344,7 +365,8 @@ struct ieee802154_driver_s * requesting new framesusing break-off fram buffers. That frame buffer * management must be controlled by the IEEE802.15.4 MAC driver. * - * Driver provied frame buffers should be 16-bit aligned. + * Driver provided frame buffers should of size CONFIG_NET_6LOWPAN_FRAMELEN + * and should be 16-bit aligned. */ FAR uint8_t *i_frame; @@ -360,6 +382,31 @@ struct ieee802154_driver_s uint16_t i_framelen; + /* i_panid. The PAN ID is 16-bit number that identifies the network. It + * must be unique to differentiate a network. All the nodes in the same + * network should have the same PAN ID. This value must be provided to + * the network from the IEEE802.15.4 MAC driver. + * + * If this value is 0xffff, the device is not associated. + */ + + uint16_t i_panid; + + /* i_node_addr. The address assigned to this node. */ + + struct rimeaddr_s i_nodeaddr; + + /* i_dsn. The sequence number in the range 0x00-0xff added to the + * transmitted data or MAC command frame. The default is a random value + * within that range. + * + * This field must be initialized to a random number by the IEEE802.15.4 + * MAC driver. It sill be subsequently incremented on each frame by the + * network logic. + */ + + uint8_t i_dsn; + /* The following fields are device-specific metadata used by the 6loWPAN * stack and should not be modified by the IEEE802.15.4 MAC network drvier. */ @@ -385,9 +432,9 @@ struct ieee802154_driver_s uint8_t i_rime_hdrlen; - /* Next available pointer into header */ + /* Offset first available byte for the payload after header region. */ - uint8_t i_hdrptr; + uint8_t i_dataoffset; /* Packet buffer metadata: Attributes and addresses */ diff --git a/net/sixlowpan/Kconfig b/net/sixlowpan/Kconfig index 7031f21e62..bbbdeb1b13 100644 --- a/net/sixlowpan/Kconfig +++ b/net/sixlowpan/Kconfig @@ -136,7 +136,7 @@ config NET_6LOWPAN_RIMEADDR_SIZE ---help--- Only the values 2 and 8 are supported -config NET_SIXLOWPAN_MAXAGE +config NET_6LOWPAN_MAXAGE int "Packet reassembly timeout" default 20 ---help--- @@ -150,11 +150,11 @@ config NET_6LOWPAN_MAX_MACTRANSMITS layer should resend packets if no link-layer ACK wasreceived. This only makes sense with the csma_driver. -config NET_SIXLOWPAN_MAXPAYLOAD +config NET_6LOWPAN_MAXPAYLOAD int "Max packet size" default 102 ---help--- - CONFIG_NET_SIXLOWPAN_MAXPAYLOAD specifies the maximum size of packets + NET_6LOWPAN_MAXPAYLOAD specifies the maximum size of packets before they get fragmented. The default is 127 bytes (the maximum size 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. diff --git a/net/sixlowpan/Make.defs b/net/sixlowpan/Make.defs index 68b1ec5ef9..e0370185e6 100644 --- a/net/sixlowpan/Make.defs +++ b/net/sixlowpan/Make.defs @@ -40,7 +40,7 @@ ifeq ($(CONFIG_NET_6LOWPAN),y) # Include IEEE 802.15.4 file in the build NET_CSRCS += sixlowpan_initialize.c sixlowpan_globals.c sixlowpan_utils.c -NET_CSRCS += sixlowpan_input.c sixlowpan_send.c +NET_CSRCS += sixlowpan_input.c sixlowpan_send.c sixlowpan_framer.c NET_CSRCS += sixlowpan_compressor.c ifeq ($(CONFIG_NET_TCP),y) diff --git a/net/sixlowpan/sixlowpan_framer.c b/net/sixlowpan/sixlowpan_framer.c new file mode 100644 index 0000000000..611e204a9f --- /dev/null +++ b/net/sixlowpan/sixlowpan_framer.c @@ -0,0 +1,606 @@ +/**************************************************************************** + * net/sixlowpan/sixlowpan_framer.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Derives from Contiki: + * + * Copyright (c) 2008, Swedish Institute of Computer Science. + * All rights reserved. + * Authors: Adam Dunkels + * Nicolas Tsiftes + * Niclas Finne + * Mathilde Durvy + * Julien Abeille + * Joakim Eriksson + * Joel Hoglund + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the Institute 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 INSTITUTE 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 INSTITUTE 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 "nuttx/net/net.h" +#include "nuttx/net/sixlowpan.h" + +#include "sixlowpan/sixlowpan_internal.h" + +#ifdef CONFIG_NET_6LOWPAN + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/* Structure that contains the lengths of the various addressing and + * security fields in the 802.15.4 header. + */ + +struct field_length_s +{ + uint8_t dest_pid_len; /**< Length (in bytes) of destination PAN ID field */ + uint8_t dest_addr_len; /**< Length (in bytes) of destination address field */ + uint8_t src_pid_len; /**< Length (in bytes) of source PAN ID field */ + uint8_t src_addr_len; /**< Length (in bytes) of source address field */ + uint8_t aux_sec_len; /**< Length (in bytes) of aux security header field */ +}; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: sixlowpan_addrlen + * + * Description: + * Return the address length associated with a 2-bit address mode + * + * Input parameters: + * addrmode - The address mode + * + * Returned Value: + * The address length associated with the address mode. + * + ****************************************************************************/ + +static inline uint8_t sixlowpan_addrlen(uint8_t addrmode) +{ + switch (addrmode) + { + case FRAME802154_SHORTADDRMODE: /* 16-bit address */ + return 2; + case FRAME802154_LONGADDRMODE: /* 64-bit address */ + return 8; + default: + return 0; + } +} + +/**************************************************************************** + * Function: sixlowpan_isbroadcast + * + * Description: + * Return the address length associated with a 2-bit address mode + * + * Input parameters: + * addrmode - The address mode + * + * Returned Value: + * The address length associated with the address mode. + * + ****************************************************************************/ + +static bool sixlowpan_isbroadcast(uint8_t mode, FAR uint8_t *addr) +{ + int i = ((mode == FRAME802154_SHORTADDRMODE) ? 2 : 8); + + while (i-- > 0) + { + if (addr[i] != 0xff) + { + return false; + } + } + + return true; +} + +/**************************************************************************** + * Function: sixlowpan_addrnull + * + * Description: + * If the output address is NULL in the Rime buf, then it is broadcast + * on the 802.15.4 network. + * + * Input parameters: + * addrmode - The address mode + * + * Returned Value: + * The address length associated with the address mode. + * + ****************************************************************************/ + +static bool sixlowpan_addrnull(FAR uint8_t *addr) +{ +#if CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 2 + int i = 2; +#else + int i = 8; +#endif + + while (i-- > 0) + { + if (addr[i] != 0x00) + { + return false; + } + } + + return true; +} + + +/**************************************************************************** + * Function: sixlowpan_fieldlengths + * + * Description: + * Return the lengths associated fields of the IEEE802.15.4 header. + * + * Input parameters: + * finfo - IEEE802.15.4 header info (input) + * flen - Field length info (output) + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void sixlowpan_fieldlengths(FAR struct frame802154_s *finfo, + FAR struct field_length_s *flen) +{ + /* Initialize to all zero */ + + memset(flen, 0, sizeof(struct field_length_s)); + + /* Determine lengths of each field based on fcf and other args */ + + if ((finfo->fcf.dest_addr_mode & 3) != 0) + { + flen->dest_pid_len = 2; + } + + if ((finfo->fcf.src_addr_mode & 3) != 0) + { + flen->src_pid_len = 2; + } + + /* Set PAN ID compression bit if src pan id matches dest pan id. */ + + if ((finfo->fcf.dest_addr_mode & 3) != 0 && + (finfo->fcf.src_addr_mode & 3) != 0 && + finfo->src_pid == finfo->dest_pid) + { + finfo->fcf.panid_compression = 1; + + /* Compressed header, only do dest pid */ + /* flen->src_pid_len = 0; */ + } + + /* Determine address lengths */ + + flen->dest_addr_len = sixlowpan_addrlen(finfo->fcf.dest_addr_mode & 3); + flen->src_addr_len = sixlowpan_addrlen(finfo->fcf.src_addr_mode & 3); + + /* Aux security header */ + +#if 0 /* TODO Aux security header not yet implemented */ + if ((finfo->fcf.security_enabled & 1) != 0) + { + switch(finfo->aux_hdr.security_control.key_id_mode) + { + case 0: + flen->aux_sec_len = 5; /* Minimum value */ + break; + + case 1: + flen->aux_sec_len = 6; + break; + + case 2: + flen->aux_sec_len = 10; + break; + + case 3: + flen->aux_sec_len = 14; + break; + + default: + break; + } + } +#endif +} + +/**************************************************************************** + * Function: sixlowpan_fieldlengths + * + * Description: + * Return the lengths associated fields of the IEEE802.15.4 header. + * + * Input parameters: + * finfo - IEEE802.15.4 header info (input) + * flen - Field length info (output) + * + * Returned Value: + * None + * + ****************************************************************************/ + +static int sixlowpan_flen_hdrlen(FAR const struct field_length_s *flen) +{ + return 3 + flen->dest_pid_len + flen->dest_addr_len + + flen->src_pid_len + flen->src_addr_len + flen->aux_sec_len; +} + +/**************************************************************************** + * Function: sixlowpan_802154_hdrlen + * + * Description: + * Calculates the length of the frame header. This function is meant to + * be called by a higher level function, that interfaces to a MAC. + * + * Input parameters: + * finfo - IEEE802.15.4 header info that specifies the frame to send. + * + * Returned Value: + * The length of the frame header. + * + ****************************************************************************/ + +static int sixlowpan_802154_hdrlen(FAR struct frame802154_s *finfo) +{ + struct field_length_s flen; + + sixlowpan_fieldlengths(finfo, &flen); + return sixlowpan_flen_hdrlen(&flen); +} + +/**************************************************************************** + * Function: sixlowpan_setup_params + * + * Description: + * Configure frame parmeters structure. + * + * Input parameters: + * ieee - A reference IEEE802.15.4 MAC network device structure. + * params - Where to put the parmeters + * dest_panid - PAN ID of the destination. May be 0xffff if the destination + * is not associated. + * + * Returned Value: + * None. + * + ****************************************************************************/ + +static void sixlowpan_setup_params(FAR struct ieee802154_driver_s *ieee, + FAR struct frame802154_s *params, + uint16_t dest_panid) +{ + bool rcvrnull; + + /* Initialize all prameters to all zero */ + + memset(¶ms, 0, sizeof(params)); + + /* Reset to an empty frame */ + + ieee->i_framelen = 0; + ieee->i_dataoffset = 0; + + /* Build the FCF (Only non-zero elements need to be initialized). */ + + params->fcf.frame_type = FRAME802154_DATAFRAME; + params->fcf.frame_pending = ieee->i_pktattrs[PACKETBUF_ATTR_PENDING]; + + /* If the output address is NULL in the Rime buf, then it is broadcast + * on the 802.15.4 network. + */ + + rcvrnull = sixlowpan_addrnull(ieee->i_pktaddrs[PACKETBUF_ADDR_RECEIVER].u8); + if (rcvrnull) + { + params->fcf.ack_required = ieee->i_pktattrs[PACKETBUF_ATTR_MAC_ACK]; + } + + /* Insert IEEE 802.15.4 (2003) version bit. */ + + params->fcf.frame_version = FRAME802154_IEEE802154_2003; + + /* Increment and set the data sequence number. */ + + if (ieee->i_pktattrs[PACKETBUF_ATTR_MAC_SEQNO] != 0) + { + params->seq = ieee->i_pktattrs[PACKETBUF_ATTR_MAC_SEQNO]; + } + else + { + params->seq = ieee->i_dsn++; + ieee->i_pktattrs[PACKETBUF_ATTR_MAC_SEQNO] = params->seq; + } + + /* Complete the addressing fields. */ + /* Set the source and destination PAN ID. */ + + params->src_pid = ieee->i_panid; + params->dest_pid = dest_panid; + + /* If the output address is NULL in the Rime buf, then it is broadcast + * on the 802.15.4 network. + */ + + if (rcvrnull) + { + /* Broadcast requires short address mode. */ + + params->fcf.dest_addr_mode = FRAME802154_SHORTADDRMODE; + params->dest_addr[0] = 0xff; + params->dest_addr[1] = 0xff; + } + else + { + /* Copy the destination address */ + + rimeaddr_copy((struct rimeaddr_s *)¶ms->dest_addr, + ieee->i_pktaddrs[PACKETBUF_ADDR_RECEIVER].u8); + + /* Use short address mode if so configured */ + +#if CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 2 + params->fcf.dest_addr_mode = FRAME802154_SHORTADDRMODE; +#else + params->fcf.dest_addr_mode = FRAME802154_LONGADDRMODE; +#endif + } + + /* Set the source address to the node address assigned to the device */ + + rimeaddr_copy((struct rimeaddr_s *)¶ms->src_addr, &ieee->i_nodeaddr.u8); + + /* Configure the payload address and length */ + + params->payload = FRAME_DATA_START(ieee); + params->payload_len = FRAME_DATA_SIZE(ieee); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: sixlowpan_hdrlen + * + * Description: + * This function is before the first frame has been sent in order to + * determine what the size of the IEEE802.15.4 header will be. No frame + * buffer is required to make this determination. + * + * Input parameters: + * ieee - A reference IEEE802.15.4 MAC network device structure. + * dest_panid - PAN ID of the destination. May be 0xffff if the destination + * is not associated. + * + * Returned Value: + * The frame header length is returnd on success; otherwise, a negated + * errno value is return on failure. + * + ****************************************************************************/ + +int sixlowpan_hdrlen(FAR struct ieee802154_driver_s *ieee, + uint16_t dest_panid) +{ + struct frame802154_s params; + + /* Set up the frame parameters */ + + sixlowpan_setup_params(ieee, ¶ms, dest_panid); + + /* Return the length of the header */ + + return sixlowpan_802154_hdrlen(¶ms); +} + +/**************************************************************************** + * Function: sixlowpan_802154_framecreate + * + * Description: + * Creates a frame for transmission over the air. This function is meant + * to be called by a higher level function, that interfaces to a MAC. + * + * Input parameters: + * finfo - Pointer to struct EEE802.15.4 header structure that specifies + * the frame to send. + * buf - Pointer to the buffer to use for the frame. + * buflen - The length of the buffer to use for the frame. + * finfo - I that specifies the frame to send. + * + * Returned Value: + * The length of the frame header or 0 if there was insufficient space in + * the buffer for the frame headers. + * + ****************************************************************************/ + +int sixlowpan_802154_framecreate(FAR struct frame802154_s *finfo, + FAR uint8_t *buf, int buflen) +{ + struct field_length_s flen; + uint8_t pos; + int hdrlen; + int i; + + sixlowpan_fieldlengths(finfo, &flen); + + hdrlen = sixlowpan_flen_hdrlen(&flen); + if (hdrlen > buflen) + { + /* Too little space for headers. */ + + return 0; + } + + /* OK, now we have field lengths. Time to actually construct + * the outgoing frame, and store it in the provided buffer + */ + + buf[0] = (finfo->fcf.frame_type & 7) | + ((finfo->fcf.security_enabled & 1) << 3) | + ((finfo->fcf.frame_pending & 1) << 4) | + ((finfo->fcf.ack_required & 1) << 5) | + ((finfo->fcf.panid_compression & 1) << 6); + buf[1] = ((finfo->fcf.dest_addr_mode & 3) << 2) | + ((finfo->fcf.frame_version & 3) << 4) | + ((finfo->fcf.src_addr_mode & 3) << 6); + + /* Sequence number */ + + buf[2] = finfo->seq; + pos = 3; + + /* Destination PAN ID */ + + if (flen.dest_pid_len == 2) + { + buf[pos++] = finfo->dest_pid & 0xff; + buf[pos++] = (finfo->dest_pid >> 8) & 0xff; + } + + /* Destination address */ + + for (i = flen.dest_addr_len; i > 0; i--) + { + buf[pos++] = finfo->dest_addr[i - 1]; + } + + /* Source PAN ID */ + + if (flen.src_pid_len == 2) + { + buf[pos++] = finfo->src_pid & 0xff; + buf[pos++] = (finfo->src_pid >> 8) & 0xff; + } + + /* Source address */ + + for (i = flen.src_addr_len; i > 0; i--) + { + buf[pos++] = finfo->src_addr[i - 1]; + } + + /* Aux header */ + +#if 0 /* TODO Aux security header not yet implemented */ + if (flen.aux_sec_len) + { + pos += flen.aux_sec_len; + } +#endif + + DEBUGASSERT(pos == hdrlen); + return (int)pos; +} + +/**************************************************************************** + * Function: sixlowpan_framecreate + * + * Description: + * This function is called after the IEEE802.15.4 MAC driver polls for + * TX data. It creates the IEEE802.15.4 header in the frame buffer. + * + * Input parameters: + * ieee - A reference IEEE802.15.4 MAC network device structure. + * dest_panid - PAN ID of the destination. May be 0xffff if the destination + * is not associated. + * + * Returned Value: + * The frame header length is returnd on success; otherwise, a negated + * errno value is return on failure. + * + ****************************************************************************/ + +int sixlowpan_framecreate(FAR struct ieee802154_driver_s *ieee, + uint16_t dest_panid) +{ + struct frame802154_s params; + int len; + int ret; + + /* Set up the frame parameters */ + + sixlowpan_setup_params(ieee, ¶ms, dest_panid); + + /* Get the length of the header */ + + len = sixlowpan_802154_hdrlen(¶ms); + + /* Allocate space for the header in the frame buffer */ + + ret = sixlowpan_frame_hdralloc(ieee, len); + if (ret < 0) + { + wlerr("ERROR: Header too large: %u\n", len); + return ret; + } + + /* Then create the frame */ + + sixlowpan_802154_framecreate(¶ms, FRAME_HDR_START(ieee), len); + + wlinfo("Frame type: %02x Data len: %d %u (%u)\n", + params.fcf.frame_type, len, FRAME_DATA_SIZE(ieee), + FRAME_SIZE(ieee)); +#if CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 2 + wlinfo("Dest address: %02x:%02x\n", + params.dest_addr[0], params.dest_addr[1]); +#else + wlinfo("Dest address: %02x:%02x:%02x:%02x:%02x:%02x:%02x:%02x\n", + params.dest_addr[0], params.dest_addr[1], params.dest_addr[2], + params.dest_addr[3], params.dest_addr[4], params.dest_addr[5], + params.dest_addr[6], params.dest_addr[7]); +#endif + + return len; +} + +#endif /* CONFIG_NET_6LOWPAN */ diff --git a/net/sixlowpan/sixlowpan_hc06.c b/net/sixlowpan/sixlowpan_hc06.c index b270413143..534cb1adbf 100644 --- a/net/sixlowpan/sixlowpan_hc06.c +++ b/net/sixlowpan/sixlowpan_hc06.c @@ -20,6 +20,7 @@ * 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 @@ -44,7 +45,7 @@ ****************************************************************************/ /* FOR HC-06 COMPLIANCE TODO: - * + * * -Add compression options to UDP, currently only supports * both ports compressed or both ports elided * -Verify TC/FL compression works diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index 453d340dba..6828c14128 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -4,9 +4,28 @@ * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * + * Parts of this file derive from Contiki: + * + * Copyright (c) 2008, Swedish Institute of Computer Science + * All rights reserved. + * + * Additional fixes for AVR contributed by: + * Colin O'Flynn coflynn@newae.com + * Eric Gnoske egnoske@gmail.com + * Blake Leverett bleverett@gmail.com + * Mike Vidales mavida404@gmail.com + * Kevin Brown kbrown3@uccs.edu + * Nate Bohlmann nate@elfwerks.com + * + * Additional fixes for MSP430 contributed by: + * Joakim Eriksson + * Niclas Finne + * Nicolas Tsiftes + * + * All rights reserved. + * * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: + * 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. @@ -14,23 +33,21 @@ * 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 + * 3. Neither the name of the copyright holders nor the names of + * 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 _NET_SIXLOWPAN_SIXLOWPAN_INTERNAL_H @@ -64,11 +81,64 @@ #define rimeaddr_cmp(addr1,addr2) \ (memcmp(addr1, addr2, CONFIG_NET_6LOWPAN_RIMEADDR_SIZE) == 0) +/* Frame buffer helpers */ + +#define FRAME_RESET(ieee) \ + do \ + { \ + (ieee)->i_dataoffset = 0; \ + (ieee)->i_framelen = 0; \ + } \ + while (0) + +#define FRAME_HDR_START(ieee) \ + ((ieee)->i_frame) +#define FRAME_HDR_SIZE(ieee) \ + ((ieee)->i_dataoffset) + +#define FRAME_DATA_START(ieee) \ + ((FAR uint8_t *)((ieee)->i_frame) + (ieee)->i_dataoffset) +#define FRAME_DATA_SIZE(ieee) \ + ((ieee)->i_framelen - (ieee)->i_dataoffset) + +#define FRAME_REMAINING(ieee) \ + (CONFIG_NET_6LOWPAN_FRAMELEN - (ieee)->i_framelen) +#define FRAME_SIZE(ieee) \ + ((ieee)->i_framelen) + +/* These are some definitions of element values used in the FCF. See the + * IEEE802.15.4 spec for details. + */ + +#define FRAME802154_BEACONFRAME 0x00 +#define FRAME802154_DATAFRAME 0x01 +#define FRAME802154_ACKFRAME 0x02 +#define FRAME802154_CMDFRAME 0x03 + +#define FRAME802154_BEACONREQ 0x07 + +#define FRAME802154_IEEERESERVED 0x00 +#define FRAME802154_NOADDR 0x00 /* Only valid for ACK or Beacon frames */ +#define FRAME802154_SHORTADDRMODE 0x02 +#define FRAME802154_LONGADDRMODE 0x03 + +#define FRAME802154_NOBEACONS 0x0f + +#define FRAME802154_BROADCASTADDR 0xffff +#define FRAME802154_BROADCASTPANDID 0xffff + +#define FRAME802154_IEEE802154_2003 0x00 +#define FRAME802154_IEEE802154_2006 0x01 + +#define FRAME802154_SECURITY_LEVEL_NONE 0 +#define FRAME802154_SECURITY_LEVEL_128 3 + /**************************************************************************** * Public Types ****************************************************************************/ -/* IPv6 + TCP header */ +/* IPv^ TCP/UDP Definitions *************************************************/ +/* IPv6 + TCP header. Cast compatible based on IPv6 protocol field. */ struct ipv6tcp_hdr_s { @@ -92,6 +162,71 @@ struct ipv6icmp_hdr_s struct icmpv6_iphdr_s icmp; }; +/* IEEE802.15.4 Frame Definitions *******************************************/ +/* The IEEE 802.15.4 frame has a number of constant/fixed fields that can be + * counted to make frame construction and max payload calculations easier. + * These include: + * + * 1. FCF - 2 bytes - Fixed + * 2. Sequence number - 1 byte - Fixed + * 3. Addressing fields - 4 - 20 bytes - Variable + * 4. Aux security header - 0 - 14 bytes - Variable + * 5. CRC - 2 bytes - Fixed +*/ + +/* Defines the bitfields of the frame control field (FCF). */ + +struct frame802154_fcf_s +{ + uint8_t frame_type; /* 3 bit. Frame type field, see 802.15.4 */ + uint8_t security_enabled; /* 1 bit. True if security is used in this frame */ + uint8_t frame_pending; /* 1 bit. True if sender has more data to send */ + uint8_t ack_required; /* 1 bit. Is an ack frame required? */ + uint8_t panid_compression; /* 1 bit. Is this a compressed header? */ + /* 3 bit. Unused bits */ + uint8_t dest_addr_mode; /* 2 bit. Destination address mode, see 802.15.4 */ + uint8_t frame_version; /* 2 bit. 802.15.4 frame version */ + uint8_t src_addr_mode; /* 2 bit. Source address mode, see 802.15.4 */ +}; + +/* 802.15.4 security control bitfield. See section 7.6.2.2.1 in 802.15.4 + * specification. + */ + +struct frame802154_scf_s +{ + uint8_t security_level; /* 3 bit. security level */ + uint8_t key_id_mode; /* 2 bit. Key identifier mode */ + uint8_t reserved; /* 3 bit. Reserved bits */ +}; + +/* 802.15.4 Aux security header */ + +struct frame802154_aux_hdr_s +{ + struct frame802154_scf_s security_control; /* Security control bitfield */ + uint32_t frame_counter; /* Frame counter, used for security */ + uint8_t key[9]; /* The key itself, or an index to the key */ +}; + +/* Parameters used by the frame802154_create() function. These parameters + * are used in the 802.15.4 frame header. See the 802.15.4 specification + * for details. + */ + +struct frame802154_s +{ + struct frame802154_fcf_s fcf; /* Frame control field */ + uint8_t seq; /* Sequence number */ + uint16_t dest_pid; /* Destination PAN ID */ + uint8_t dest_addr[8]; /* Destination address */ + uint16_t src_pid; /* Source PAN ID */ + uint8_t src_addr[8]; /* Source address */ + struct frame802154_aux_hdr_s aux_hdr; /* Aux security header */ + uint8_t *payload; /* Pointer to 802.15.4 frame payload */ + uint8_t payload_len; /* Length of payload field */ +}; + /**************************************************************************** * Public Data ****************************************************************************/ @@ -157,6 +292,49 @@ int sixlowpan_send(FAR struct net_driver_s *dev, FAR const struct ipv6_hdr_s *ipv6, FAR const void *buf, size_t len, FAR const struct rimeaddr_s *raddr); +/**************************************************************************** + * Function: sixlowpan_hdrlen + * + * Description: + * This function is before the first frame has been sent in order to + * determine what the size of the IEEE802.15.4 header will be. No frame + * buffer is required to make this determination. + * + * Input parameters: + * ieee - A reference IEEE802.15.4 MAC network device structure. + * dest_panid - PAN ID of the destination. May be 0xffff if the destination + * is not associated. + * + * Returned Value: + * The frame header length is returnd on success; otherwise, a negated + * errno value is return on failure. + * + ****************************************************************************/ + +int sixlowpan_hdrlen(FAR struct ieee802154_driver_s *ieee, + uint16_t dest_panid); + +/**************************************************************************** + * Function: sixlowpan_framecreate + * + * Description: + * This function is called after the IEEE802.15.4 MAC driver polls for + * TX data. It creates the IEEE802.15.4 header in the frame buffer. + * + * Input parameters: + * ieee - A reference IEEE802.15.4 MAC network device structure. + * dest_panid - PAN ID of the destination. May be 0xffff if the destination + * is not associated. + * + * Returned Value: + * The frame header length is returnd on success; otherwise, a negated + * errno value is return on failure. + * + ****************************************************************************/ + +int sixlowpan_framecreate(FAR struct ieee802154_driver_s *ieee, + uint16_t dest_panid); + /**************************************************************************** * Name: sixlowpan_hc06_initialize * @@ -293,15 +471,15 @@ void sixlowpan_uncompresshdr_hc1(FAR struct net_driver_s *dev, #endif /**************************************************************************** - * Name: sixlowpan_pktbuf_reset + * Name: sixlowpan_frame_hdralloc * * Description: - * Reset all attributes and addresses in the packet buffer metadata in the - * provided IEEE802.15.4 MAC driver structure. + * Allocate space for a header within the frame buffer (i_frame). * ****************************************************************************/ -void sixlowpan_pktbuf_reset(FAR struct ieee802154_driver_s *ieee); +int sixlowpan_frame_hdralloc(FAR struct ieee802154_driver_s *ieee, + int size); #endif /* CONFIG_NET_6LOWPAN */ #endif /* _NET_SIXLOWPAN_SIXLOWPAN_INTERNAL_H */ diff --git a/net/sixlowpan/sixlowpan_send.c b/net/sixlowpan/sixlowpan_send.c index d204e5eeca..9a7b0095cd 100644 --- a/net/sixlowpan/sixlowpan_send.c +++ b/net/sixlowpan/sixlowpan_send.c @@ -4,6 +4,18 @@ * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * + * Parts of this file derive from Contiki: + * + * Copyright (c) 2008, Swedish Institute of Computer Science. + * All rights reserved. + * Authors: Adam Dunkels + * Nicolas Tsiftes + * Niclas Finne + * Mathilde Durvy + * Julien Abeille + * Joakim Eriksson + * Joel Hoglund + * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: @@ -11,25 +23,23 @@ * 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 + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the Institute 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. + * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE 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 INSTITUTE 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. * ****************************************************************************/ @@ -68,6 +78,7 @@ * * Description: * Setup some packet buffer attributes + * * Input Parameters: * ieee - Pointer to IEEE802.15.4 MAC driver structure. * ipv6 - Pointer to the IPv6 header to "compress" @@ -158,6 +169,42 @@ static void sixlowpan_compress_ipv6hdr(FAR struct ieee802154_driver_s *ieee, ieee->i_uncomp_hdrlen += IPv6_HDRLEN; } +/**************************************************************************** + * Name: sixlowpan_send_frame + * + * Description: + * Send one frame when the IEEE802.15.4 MAC device next polls. + * + * Input Parameters: + * ieee - Pointer to IEEE802.15.4 MAC driver structure. + * ipv6 - Pointer to the IPv6 header to "compress" + * + * Returned Value: + * None + * + ****************************************************************************/ + +static int sixlowpan_send_frame(FAR struct ieee802154_driver_s *ieee) +{ + /* Prepare the frame */ +#warning Missing logic + /* Set up for the TX poll */ + /* When polled, then we need to call sixlowpan_framecreate() to create the + * frame and copy the payload data into the frame. + */ +#if 0 /* Just some notes of what needs to be done in interrupt handler */ + framer_hdrlen = sixlowpan_createframe(ieee, ieee->i_panid); + memcpy(ieee->i_rimeptr + ieee->i_rime_hdrlen, (uint8_t *)ipv6 + ieee->i_uncomp_hdrlen, len - ieee->i_uncomp_hdrlen); + dev->i_framelen = len - ieee->i_uncomp_hdrlen + ieee->i_rime_hdrlen; +#endif +#warning Missing logic + /* Notify the IEEE802.14.5 MAC driver that we have data to be sent */ +#warning Missing logic + /* Wait for the transfer to complete */ +#warning Missing logic + return -ENOSYS; +} + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -203,29 +250,49 @@ int sixlowpan_send(FAR struct net_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; /* Number of bytes processed. */ + uint16_t outlen = 0; /* Number of bytes processed. */ /* Initialize device-specific data */ + FRAME_RESET(ieee); ieee->i_uncomp_hdrlen = 0; ieee->i_rime_hdrlen = 0; + /* REVISIT: Do I need this rimeptr? */ + ieee->i_rimeptr = &dev->d_buf[PACKETBUF_HDR_SIZE]; /* Reset rime buffer, packet buffer metatadata */ - sixlowpan_pktbuf_reset(ieee); + memset(ieee->i_pktattrs, 0, PACKETBUF_NUM_ATTRS * sizeof(uint16_t)); + memset(ieee->i_pktaddrs, 0, PACKETBUF_NUM_ADDRS * sizeof(struct rimeaddr_s)); - ieee->i_rimeptr = &dev->d_buf[PACKETBUF_HDR_SIZE]; - ieee->i_pktattrs[PACKETBUF_ATTR_MAX_MAC_TRANSMISSIONS] = CONFIG_NET_6LOWPAN_MAX_MACTRANSMITS; + ieee->i_pktattrs[PACKETBUF_ATTR_MAX_MAC_TRANSMISSIONS] = + CONFIG_NET_6LOWPAN_MAX_MACTRANSMITS; #ifdef CONFIG_NET_6LOWPAN_SNIFFER if (g_sixlowpan_sniffer != NULL) { + /* Reset rime buffer, packet buffer metatadata */ + + memset(ieee->i_pktattrs, 0, PACKETBUF_NUM_ATTRS * sizeof(uint16_t)); + memset(ieee->i_pktaddrs, 0, PACKETBUF_NUM_ADDRS * sizeof(struct rimeaddr_s)); + + ieee->i_pktattrs[PACKETBUF_ATTR_MAX_MAC_TRANSMISSIONS] = + CONFIG_NET_6LOWPAN_MAX_MACTRANSMITS; + /* Call the attribution when the callback comes, but set attributes here */ sixlowpan_set_pktattrs(ieee, ipv6); } #endif + /* Reset rime buffer, packet buffer metatadata */ + + memset(ieee->i_pktattrs, 0, PACKETBUF_NUM_ATTRS * sizeof(uint16_t)); + memset(ieee->i_pktaddrs, 0, PACKETBUF_NUM_ADDRS * sizeof(struct rimeaddr_s)); + + ieee->i_pktattrs[PACKETBUF_ATTR_MAX_MAC_TRANSMISSIONS] = + CONFIG_NET_6LOWPAN_MAX_MACTRANSMITS; + /* Set stream mode for all TCP packets, except FIN packets. */ if (ipv6->proto == IP_PROTO_TCP) @@ -281,8 +348,94 @@ int sixlowpan_send(FAR struct net_driver_s *dev, ninfo("Header of len %d\n", ieee->i_rime_hdrlen); - /* Calculate frame header length. */ -#warning Missing logic + rimeaddr_copy(&ieee->i_pktaddrs[PACKETBUF_ADDR_RECEIVER], &dest); + + /* Pre-calculate frame header length. */ + + framer_hdrlen = sixlowpan_hdrlen(ieee, ieee->i_panid); + 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; + } + + /* Check if we need to fragment the packet into several frames */ + + if ((int)len - (int)ieee->i_uncomp_hdrlen > + (int)CONFIG_NET_6LOWPAN_MAXPAYLOAD - framer_hdrlen - + (int)ieee->i_rime_hdrlen) + { +#if CONFIG_NET_6LOWPAN_FRAG + /* 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 + * IPv6/HC1/HC06/HC_UDP dispatchs/headers. + * The following fragments contain only the fragn dispatch. + */ + + ninfo("Fragmentation sending packet len %d\n", len); + + /* Create 1st Fragment */ +# warning Missing logic + + /* Move HC1/HC06/IPv6 header */ +# warning Missing logic + + /* FRAG1 dispatch + header + * Note that the length is in units of 8 bytes + */ +# warning Missing logic + + /* 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 + + /* Create following fragments + * Datagram tag is already in the buffer, we need to set the + * FRAGN dispatch and for each fragment, the offset + */ +# warning Missing logic + + while (outlen < len) + { + /* Copy payload and send */ +# 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); + + /* Check tx result. */ +# warning Missing logic + } + + return -ENOSYS; +#else + nerr("ERROR: Packet too large: %d\n", len); + nerr(" Cannot to be sent without fragmentation support\n"); + nerr(" dropping packet\n"); + + return -E2BIG; +#endif + } + else + { + /* The packet does not need to be fragmented just copy the "payload" + * and send in one frame. + */ + + return sixlowpan_send_frame(ieee); + } + return -ENOSYS; } diff --git a/net/sixlowpan/sixlowpan_utils.c b/net/sixlowpan/sixlowpan_utils.c index 5df1b3439c..a12394407f 100644 --- a/net/sixlowpan/sixlowpan_utils.c +++ b/net/sixlowpan/sixlowpan_utils.c @@ -44,6 +44,17 @@ * SUCH DAMAGE. * ****************************************************************************/ +/* Frame Organization: + * + * Content Offset + * +----------------+ 0 + * | Frame Header | + * +----------------+ i_dataoffset + * | Data | + * +----------------+ i_framelen + * | Unused | + * +----------------+ CONFIG_NET_6LOWPAN_FRAMELEN + */ /**************************************************************************** * Included Files @@ -52,6 +63,7 @@ #include #include +#include #include "nuttx/net/sixlowpan.h" @@ -64,22 +76,24 @@ ****************************************************************************/ /**************************************************************************** - * Name: sixlowpan_pktbuf_reset + * Name: sixlowpan_frame_hdralloc * * Description: - * Reset all attributes and addresses in the packet buffer metadata in the - * provided IEEE802.15.4 MAC driver structure. + * Allocate space for a header within the packet buffer (dev->d_buf). * ****************************************************************************/ -void sixlowpan_pktbuf_reset(FAR struct ieee802154_driver_s *ieee) +int sixlowpan_frame_hdralloc(FAR struct ieee802154_driver_s *ieee, + int size) { - ieee->i_dev.d_len = 0; - ieee->i_rimeptr = 0; - ieee->i_hdrptr = PACKETBUF_HDR_SIZE; + if (size <= FRAME_REMAINING(ieee)) + { + ieee->i_dataoffset += size; + ieee->i_framelen += size; + return OK; + } - memset(ieee->i_pktattrs, 0, PACKETBUF_NUM_ATTRS * sizeof(uint16_t)); - memset(ieee->i_pktaddrs, 0, PACKETBUF_NUM_ADDRS * sizeof(struct rimeaddr_s)); + return -ENOMEM; } #endif /* CONFIG_NET_6LOWPAN */ -- GitLab From 9aabb44118fe207458cd965b64259e2e11b2acb2 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 30 Mar 2017 16:30:04 -0600 Subject: [PATCH 278/990] 6loWPAN: Add some comments, move a function --- include/nuttx/net/sixlowpan.h | 27 ++++++++++++++++++-------- net/sixlowpan/sixlowpan_framer.c | 29 ---------------------------- net/sixlowpan/sixlowpan_input.c | 33 ++++++++++++++++++++++++++++++++ net/sixlowpan/sixlowpan_utils.c | 17 ++++++++-------- 4 files changed, 61 insertions(+), 45 deletions(-) diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index 0d403d25bb..be3bfa7636 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -333,17 +333,28 @@ struct rimeaddr_s * 2) i_dsn must be set to a random value. After that, it will be managed * by the network. * 3) i_nodeaddr must be set after the MAC is assigned an address. + * 4) On network TX poll operations, the IEEE802.15.4 MAC needs to provide + * the i_frame buffer with size greater than or equal to + * CONFIG_NET_6LOWPAN_FRAMELEN. No dev.d_buf need be provided in this + * case. The entire is TX is performed using only the i_frame buffer. + * 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. * * Frame Organization: * - * Content Offset - * +----------------+ 0 - * | Frame Header | - * +----------------+ i_dataoffset - * | Data | - * +----------------+ i_framelen - * | Unused | - * +----------------+ CONFIG_NET_6LOWPAN_FRAMELEN + * Content Offset + * +------------------+ 0 + * | Frame Header | + * +------------------+ i_dataoffset + * | Procotol Headers | + * | Data Payload | + * +------------------+ i_framelen + * | Unused | + * +------------------+ CONFIG_NET_6LOWPAN_FRAMELEN */ struct ieee802154_driver_s diff --git a/net/sixlowpan/sixlowpan_framer.c b/net/sixlowpan/sixlowpan_framer.c index 611e204a9f..2b528dea10 100644 --- a/net/sixlowpan/sixlowpan_framer.c +++ b/net/sixlowpan/sixlowpan_framer.c @@ -109,35 +109,6 @@ static inline uint8_t sixlowpan_addrlen(uint8_t addrmode) } } -/**************************************************************************** - * Function: sixlowpan_isbroadcast - * - * Description: - * Return the address length associated with a 2-bit address mode - * - * Input parameters: - * addrmode - The address mode - * - * Returned Value: - * The address length associated with the address mode. - * - ****************************************************************************/ - -static bool sixlowpan_isbroadcast(uint8_t mode, FAR uint8_t *addr) -{ - int i = ((mode == FRAME802154_SHORTADDRMODE) ? 2 : 8); - - while (i-- > 0) - { - if (addr[i] != 0xff) - { - return false; - } - } - - return true; -} - /**************************************************************************** * Function: sixlowpan_addrnull * diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index 964d988be7..ce520f8e5e 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -46,6 +46,39 @@ #ifdef CONFIG_NET_6LOWPAN +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: sixlowpan_isbroadcast + * + * Description: + * Return the address length associated with a 2-bit address mode + * + * Input parameters: + * addrmode - The address mode + * + * Returned Value: + * The address length associated with the address mode. + * + ****************************************************************************/ + +static bool sixlowpan_isbroadcast(uint8_t mode, FAR uint8_t *addr) +{ + int i = ((mode == FRAME802154_SHORTADDRMODE) ? 2 : 8); + + while (i-- > 0) + { + if (addr[i] != 0xff) + { + return false; + } + } + + return true; +} + /**************************************************************************** * Public Functions ****************************************************************************/ diff --git a/net/sixlowpan/sixlowpan_utils.c b/net/sixlowpan/sixlowpan_utils.c index a12394407f..f00eaeae4c 100644 --- a/net/sixlowpan/sixlowpan_utils.c +++ b/net/sixlowpan/sixlowpan_utils.c @@ -46,14 +46,15 @@ ****************************************************************************/ /* Frame Organization: * - * Content Offset - * +----------------+ 0 - * | Frame Header | - * +----------------+ i_dataoffset - * | Data | - * +----------------+ i_framelen - * | Unused | - * +----------------+ CONFIG_NET_6LOWPAN_FRAMELEN + * Content Offset + * +------------------+ 0 + * | Frame Header | + * +------------------+ i_dataoffset + * | Procotol Headers | + * | Data Payload | + * +------------------+ i_framelen + * | Unused | + * +------------------+ CONFIG_NET_6LOWPAN_FRAMELEN */ /**************************************************************************** -- GitLab From 1a12682f23d8967b5d0b36026ad713c64558244d Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 30 Mar 2017 17:18:18 -0600 Subject: [PATCH 279/990] 6loWPAN: Fix some MTU-related craziness. --- include/nuttx/net/netconfig.h | 46 +++++++++++++++++++++++++++++++---- include/nuttx/net/sixlowpan.h | 9 ++++--- net/netdev/netdev_register.c | 4 +-- net/sixlowpan/Kconfig | 25 ++++++++++++++++--- 4 files changed, 70 insertions(+), 14 deletions(-) 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/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 -- GitLab From c5d55c62f480d21d4c666a2be889189aaeb343d4 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 30 Mar 2017 20:13:59 -0600 Subject: [PATCH 280/990] 6loWPAN: Pre-format frames in an IOB change before sending. --- net/sixlowpan/sixlowpan_send.c | 93 ++++++++++++++++++++++++++++------ 1 file changed, 77 insertions(+), 16 deletions(-) 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 */ -- GitLab From 916bd8a48fc86a76c23b6c3b7e676d96d35a24b3 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 31 Mar 2017 05:31:35 -0600 Subject: [PATCH 281/990] HTS221 driver: Modify to use new interrupt parameter passing hooks. --- drivers/sensors/hts221.c | 14 ++++++-------- include/nuttx/sensors/hts221.h | 7 ++++--- 2 files changed, 10 insertions(+), 11 deletions(-) diff --git a/drivers/sensors/hts221.c b/drivers/sensors/hts221.c index 4dc9c0d2dd..7ce201ecac 100644 --- a/drivers/sensors/hts221.c +++ b/drivers/sensors/hts221.c @@ -174,8 +174,6 @@ static const struct file_operations g_humidityops = #endif }; -static struct hts221_dev_s *g_humid_data; - /**************************************************************************** * Private Functions ****************************************************************************/ @@ -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; + + DEBUGASSERT(priv != NULL); - g_humid_data->int_pending = true; + 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/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; -- GitLab From b5b148fef8c185190f440ec494d4397a05c8ddf7 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Fri, 31 Mar 2017 05:53:43 -0600 Subject: [PATCH 282/990] drivers/sensors: Add driver for ST LPS25H pressure sensor --- drivers/sensors/Kconfig | 31 +- drivers/sensors/Make.defs | 6 +- drivers/sensors/hts221.c | 32 +- drivers/sensors/lps25h.c | 793 +++++++++++++++++++++++++++++++++ include/nuttx/sensors/ioctl.h | 8 + include/nuttx/sensors/lps25h.h | 105 +++++ 6 files changed, 951 insertions(+), 24 deletions(-) create mode 100644 drivers/sensors/lps25h.c create mode 100644 include/nuttx/sensors/lps25h.h 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 7ce201ecac..59c5790ad5 100644 --- a/drivers/sensors/hts221.c +++ b/drivers/sensors/hts221.c @@ -178,7 +178,7 @@ static const struct file_operations g_humidityops = * 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) { @@ -187,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; @@ -201,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); @@ -215,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; @@ -360,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; @@ -418,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; @@ -475,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; @@ -496,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; diff --git a/drivers/sensors/lps25h.c b/drivers/sensors/lps25h.c new file mode 100644 index 0000000000..e46b1c7c0a --- /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 */ + 0, /* 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/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 */ -- GitLab From 5e8ed2dd4e3521be411c052a77eb75a582a6d856 Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Fri, 31 Mar 2017 06:00:32 -0600 Subject: [PATCH 283/990] crypto/random_pool: fix typo in debug print, change 'crypinfo' to 'cryptinfo' --- crypto/random_pool.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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); -- GitLab From 9d13a2463f3f655a786686066c6c4577422055a5 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Fri, 31 Mar 2017 06:35:36 -0600 Subject: [PATCH 284/990] drivers/usbmisc: Add driver for Fairchild FUSB301 USB type-C controller. From Harri Luhtala . Tested with earlier version of NuttX; with current version checked that it compiles. --- drivers/Kconfig | 10 + drivers/Makefile | 1 + drivers/sensors/lps25h.c | 2 +- drivers/usbmisc/Kconfig | 29 ++ drivers/usbmisc/Make.defs | 49 +++ drivers/usbmisc/fusb301.c | 855 ++++++++++++++++++++++++++++++++++++ include/nuttx/fs/ioctl.h | 7 + include/nuttx/usb/fusb301.h | 243 ++++++++++ 8 files changed, 1195 insertions(+), 1 deletion(-) create mode 100644 drivers/usbmisc/Kconfig create mode 100644 drivers/usbmisc/Make.defs create mode 100644 drivers/usbmisc/fusb301.c create mode 100644 include/nuttx/usb/fusb301.h 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/lps25h.c b/drivers/sensors/lps25h.c index e46b1c7c0a..3ebba98285 100644 --- a/drivers/sensors/lps25h.c +++ b/drivers/sensors/lps25h.c @@ -220,7 +220,7 @@ static const struct file_operations g_lps25hops = lps25h_close, /* close */ lps25h_read, /* read */ lps25h_write, /* write */ - 0, /* seek */ + NULL, /* seek */ lps25h_ioctl /* ioctl */ #ifndef CONFIG_DISABLE_POLL , NULL /* poll */ 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 5582ccd0fe..9b000ceb05 100644 --- a/include/nuttx/fs/ioctl.h +++ b/include/nuttx/fs/ioctl.h @@ -86,6 +86,7 @@ #define _SPIBASE (0x2100) /* SPI driver commands */ #define _GPIOBASE (0x2200) /* GPIO driver commands */ #define _CLIOCBASE (0x2300) /* Contactless modules ioctl commands */ +#define _USBCBASE (0x2400) /* USB-C controller ioctl commands */ /* boardctl() commands share the same number space */ @@ -401,6 +402,12 @@ #define _CLIOCVALID(c) (_IOC_TYPE(c)==_CLIOCBASE) #define _CLIOC(nr) _IOC(_CLIOCBASE,nr) +/* 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) + /* boardctl() command definitions *******************************************/ #define _BOARDIOCVALID(c) (_IOC_TYPE(c)==_BOARDBASE) 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 */ -- GitLab From 0427d6c726cc50aad4c10e3699464407f93023a0 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 31 Mar 2017 07:54:58 -0600 Subject: [PATCH 285/990] 6loWPAN: Replace frame buffer with a list of IOBs. --- include/nuttx/fs/ioctl.h | 8 +- include/nuttx/net/sixlowpan.h | 170 ++++++++++++++++++++--------- net/sixlowpan/sixlowpan_framer.c | 32 +++--- net/sixlowpan/sixlowpan_internal.h | 42 +++---- net/sixlowpan/sixlowpan_send.c | 15 ++- net/sixlowpan/sixlowpan_utils.c | 12 +- 6 files changed, 178 insertions(+), 101 deletions(-) diff --git a/include/nuttx/fs/ioctl.h b/include/nuttx/fs/ioctl.h index 9b000ceb05..86aaefae18 100644 --- a/include/nuttx/fs/ioctl.h +++ b/include/nuttx/fs/ioctl.h @@ -372,19 +372,19 @@ #define _LOOPIOCVALID(c) (_IOC_TYPE(c)==_LOOPBASE) #define _LOOPIOC(nr) _IOC(_LOOPBASE,nr) -/* Modem driver ioctl definitions ********************************************/ +/* Modem driver ioctl definitions *******************************************/ /* see nuttx/include/modem/ioctl.h */ #define _MODEMIOCVALID(c) (_IOC_TYPE(c)==_MODEMBASE) #define _MODEMIOC(nr) _IOC(_MODEMBASE,nr) -/* I2C driver ioctl definitions **********************************************/ +/* I2C driver ioctl definitions *********************************************/ /* see nuttx/include/i2c/i2c_master.h */ #define _I2CIOCVALID(c) (_IOC_TYPE(c)==_I2CBASE) #define _I2CIOC(nr) _IOC(_I2CBASE,nr) -/* SPI driver ioctl definitions **********************************************/ +/* SPI driver ioctl definitions *********************************************/ /* see nuttx/include/spi/spi_transfer.h */ #define _SPIIOCVALID(c) (_IOC_TYPE(c)==_SPIBASE) @@ -396,7 +396,7 @@ #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) diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index 7463763bff..66c84ac58f 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -53,6 +53,7 @@ #include +#include #include /**************************************************************************** @@ -280,7 +281,7 @@ #define PACKETBUF_NUM_ATTRS 24 - /* Addresses (indices into i_pktaddr) */ +/* Addresses (indices into i_pktaddr) */ #define PACKETBUF_ADDR_SENDER 0 #define PACKETBUF_ADDR_RECEIVER 1 @@ -289,6 +290,62 @@ #define PACKETBUF_NUM_ADDRS 4 +/* Frame buffer helper macros. + * + * The IEEE802.15.4 MAC driver structures includes a list of IOB + * structures, i_framelist, containing frames to be sent by the driver or + * that were received by the driver. The IOB structure is defined in + * include/nuttx/net/iob.h. The length of data in the IOB is provided by + * the io_len field of the IOB structure. + * + * NOTE that IOBs must be configured such that CONFIG_IOB_BUFSIZE >= + * CONFIG_NET_6LOWPAN_FRAMELEN + * + * 1. On a TX poll, the IEEE802.15.4 MAC driver should provide its driver + * structure with i_framelist set to NULL. At the conclusion of the + * poll, if there are frames to be sent, they will have been added to + * the i_framelist. The non-empty frame list is the indication that + * there is data to be sent. + * + * The IEEE802.15.4 may use the FRAME_IOB_EMPTY() macro to determine + * if there there frames to be sent. If so, it should remove each + * frame from the frame list using the FRAME_IOB_REMOVE() macro and send + * it. That macro will return NULL when all of the frames have been + * sent. + * + * After sending each frame, the driver must return the IOB to the pool + * of free IOBs using the FROM_IOB_FREE() macro. + */ + + +#define FRAME_IOB_EMPTY(ieee) ((ieee)->framelist == NULL) +#define FRAME_IOB_REMOVE(ieee, iob) \ + do \ + { \ + (iob) = (ieee)->i_framelist; \ + (ieee)->i_framelist = (iob)->io_flink; \ + (iob)->io_flink = NULL; \ + } \ + while (0) +#define FRAME_IOB_FREE(iob) iob_free(iob) + +/* 2. When receiving data, the IEEE802.15.4 MAC driver should receive the + * frame data directly into the payload area of an IOB structure. That + * IOB structure may be obtained using the FRAME_IOB_ALLOC() macro. The + * single frame should be added to the frame list using FRAME_IOB_ADD() + * (it will be a list of length one) . The MAC driver should then inform + * the network of the by calling sixlowpan_input(). + */ + +#define FRAME_IOB_ALLOC() iob_alloc(false) +#define FRAME_IOB_ADD(ieee, iob) \ + do \ + { \ + (iob)->io_flink = (ieee)->i_framelist; \ + (ieee)->i_framelist = (iob); \ + } \ + while (0) + /**************************************************************************** * Public Types ****************************************************************************/ @@ -305,18 +362,20 @@ struct rimeaddr_s * difference is that fragmentation must be supported. * * The IEEE802.15.4 MAC does not use the d_buf packet buffer directly. - * Rather, it uses a smaller frame buffer, i_frame. + * Rather, it uses a list smaller frame buffers, i_framelist. * - * - The packet fragment data is provided to the i_frame buffer each time - * that the IEEE802.15.4 MAC needs to send more data. The length of - * the frame is provided in i_frame. + * - The packet fragment data is provided to an IOB in the i_framelist + * buffer each time that the IEEE802.15.4 MAC needs to send more data. + * The length of the frame is provided in the io_len field of the IOB. * - * In this case, the d_buf holds the packet data yet to be sent; d_len - * holds the size of entire packet. + * In this case, the d_buf is not used at all and, if fact, may be + * NULL. * * - Received frames are provided by IEEE802.15.4 MAC to the network - * via i_frame with length i_framelen for reassembly in d_buf; d_len - * will hold the size of the reassembled packet. + * via and IOB in i_framelist with length io_len for reassembly in + * d_buf; d_len will hold the size of the reassembled packet. + * + * In this case, a d_buf of size CONFIG_NET_6LOWPAN_MTU must be provided. * * This is accomplished by "inheriting" the standard 'struct net_driver_s' * and appending the frame buffer as well as other metadata needed to @@ -328,26 +387,49 @@ struct rimeaddr_s * this structure. In general, all fields must be set to NULL. In * addtion: * - * 1) i_panid must be set to identify the network. It may be set to 0xfff + * 1. i_panid must be set to identify the network. It may be set to 0xfff * if the device is not associated. - * 2) i_dsn must be set to a random value. After that, it will be managed + * + * 2. i_dsn must be set to a random value. After that, it will be managed * by the network. - * 3) i_nodeaddr must be set after the MAC is assigned an address. - * 4) On network TX poll operations, the IEEE802.15.4 MAC needs to provide - * the i_frame buffer with size greater than or equal to - * CONFIG_NET_6LOWPAN_FRAMELEN. No dev.d_buf need be provided in this - * case. The entire is TX is performed using only the i_frame buffer. - * 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 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: + * + * 3. i_nodeaddr must be set after the MAC is assigned an address. + * + * 4. On a TX poll, the IEEE802.15.4 MAC driver should provide its driver + * structure with i_framelist set to NULL. At the conclusion of the + * poll, if there are frames to be sent, they will have been added to + * the i_framelist. The non-empty frame list at the conclusion of the + * TX poll is the indication that is data to be sent. + * + * The IEEE802.15.4 may use the FRAME_IOB_EMPTY() macro to determine + * if there there frames to be sent. If so, it should remove each + * frame from the frame list using the FRAME_IOB_REMOVE() macro and send + * it. That macro will return NULL when all of the frames have been + * sent. + * + * After sending each frame, the driver must return the IOB to the pool + * of free IOBs using the FROM_IOB_FREE() macro. + * + * 5. When receiving data both buffers must be provided: + * + * The IEEE802.15.4 MAC driver should receive the frame data directly + * into the payload area of an IOB structure. That IOB structure may be + * obtained using the FRAME_IOB_ALLOC() macro. The single frame should + * be added to the frame list using FRAME_IOB_ADD() (it will be a list of + * length one). + * + * The larger dev.d_buf must have a size 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. + * + * The MAC driver should then inform the network of the by calling + * sixlowpan_input(). + * + * Frame Organization. The IOB data is retained in the io_data[] field of the + * IOB structure like: * * Content Offset * +------------------+ 0 @@ -355,7 +437,7 @@ struct rimeaddr_s * +------------------+ i_dataoffset * | Procotol Headers | * | Data Payload | - * +------------------+ i_framelen + * +------------------+ io_len * | Unused | * +------------------+ CONFIG_NET_6LOWPAN_FRAMELEN */ @@ -370,31 +452,21 @@ struct ieee802154_driver_s /* IEEE802.15.4 MAC-specific definitions follow. */ - /* The i_frame array is used to hold outgoing frame. When the - * IEEE802.15.4 device polls for new data, the outgoing frame containing - * the next fragment is placed in i_frame. - * - * The network will handle only a single outgong frame at a time. The - * IEEE802.15.4 MAC driver design may be concurrently sending and - * requesting new framesusing break-off fram buffers. That frame buffer - * management must be controlled by the IEEE802.15.4 MAC driver. + /* The i_framelist is used to hold a outgoing frames contained in IOB + * structures. When the IEEE802.15.4 device polls for new TX data, the + * outgoing frame(s) containing the packet fragments are placed in IOBs + * and queued in i_framelist. * - * Driver provided frame buffers should of size CONFIG_NET_6LOWPAN_FRAMELEN - * and should be 16-bit aligned. - */ - - FAR uint8_t *i_frame; - - /* The length of valid data in the i_frame buffer. + * The i_framelist is similary used to hold incoming frames in IOB + * structures. The IEEE802.15.4 MAC driver must receive frames in an IOB, + * place the IOB in the i_framelist, and call sixlowpan_input(). * - * When the network device driver calls the network input function, - * i_framelen should be set to zero. If there is frame to be sent - * by the network, i_framelen will be set to indicate the size of - * frame to be sent. The value zero means that there is no frame - * to be sent. + * The IEEE802.15.4 MAC driver design may be concurrently sending and + * requesting new frames using lists of IOBs. That IOB frame buffer + * management must be managed by the IEEE802.15.4 MAC driver. */ - uint16_t i_framelen; + FAR struct iob_s *i_framelist; /* i_panid. The PAN ID is 16-bit number that identifies the network. It * must be unique to differentiate a network. All the nodes in the same diff --git a/net/sixlowpan/sixlowpan_framer.c b/net/sixlowpan/sixlowpan_framer.c index 2b528dea10..3c753f3530 100644 --- a/net/sixlowpan/sixlowpan_framer.c +++ b/net/sixlowpan/sixlowpan_framer.c @@ -277,9 +277,10 @@ static int sixlowpan_802154_hdrlen(FAR struct frame802154_s *finfo) * * Input parameters: * ieee - A reference IEEE802.15.4 MAC network device structure. - * params - Where to put the parmeters + * iob - The IOB in which to create the frame. * dest_panid - PAN ID of the destination. May be 0xffff if the destination * is not associated. + * params - Where to put the parmeters * * Returned Value: * None. @@ -287,8 +288,8 @@ static int sixlowpan_802154_hdrlen(FAR struct frame802154_s *finfo) ****************************************************************************/ static void sixlowpan_setup_params(FAR struct ieee802154_driver_s *ieee, - FAR struct frame802154_s *params, - uint16_t dest_panid) + FAR struct iob_s *iob, uint16_t dest_panid, + FAR struct frame802154_s *params) { bool rcvrnull; @@ -298,7 +299,6 @@ static void sixlowpan_setup_params(FAR struct ieee802154_driver_s *ieee, /* Reset to an empty frame */ - ieee->i_framelen = 0; ieee->i_dataoffset = 0; /* Build the FCF (Only non-zero elements need to be initialized). */ @@ -370,10 +370,13 @@ static void sixlowpan_setup_params(FAR struct ieee802154_driver_s *ieee, rimeaddr_copy((struct rimeaddr_s *)¶ms->src_addr, &ieee->i_nodeaddr.u8); - /* Configure the payload address and length */ + /* Configure the (optional) payload address and length */ - params->payload = FRAME_DATA_START(ieee); - params->payload_len = FRAME_DATA_SIZE(ieee); + if (iob != NULL) + { + params->payload = FRAME_DATA_START(ieee, iob); + params->payload_len = FRAME_DATA_SIZE(ieee, iob); + } } /**************************************************************************** @@ -406,7 +409,7 @@ int sixlowpan_hdrlen(FAR struct ieee802154_driver_s *ieee, /* Set up the frame parameters */ - sixlowpan_setup_params(ieee, ¶ms, dest_panid); + sixlowpan_setup_params(ieee, NULL, dest_panid, ¶ms); /* Return the length of the header */ @@ -521,6 +524,7 @@ int sixlowpan_802154_framecreate(FAR struct frame802154_s *finfo, * * Input parameters: * ieee - A reference IEEE802.15.4 MAC network device structure. + * iob - The IOB in which to create the frame. * dest_panid - PAN ID of the destination. May be 0xffff if the destination * is not associated. * @@ -531,7 +535,7 @@ int sixlowpan_802154_framecreate(FAR struct frame802154_s *finfo, ****************************************************************************/ int sixlowpan_framecreate(FAR struct ieee802154_driver_s *ieee, - uint16_t dest_panid) + FAR struct iob_s *iob, uint16_t dest_panid) { struct frame802154_s params; int len; @@ -539,7 +543,7 @@ int sixlowpan_framecreate(FAR struct ieee802154_driver_s *ieee, /* Set up the frame parameters */ - sixlowpan_setup_params(ieee, ¶ms, dest_panid); + sixlowpan_setup_params(ieee, iob, dest_panid, ¶ms); /* Get the length of the header */ @@ -547,7 +551,7 @@ int sixlowpan_framecreate(FAR struct ieee802154_driver_s *ieee, /* Allocate space for the header in the frame buffer */ - ret = sixlowpan_frame_hdralloc(ieee, len); + ret = sixlowpan_frame_hdralloc(ieee, iob, len); if (ret < 0) { wlerr("ERROR: Header too large: %u\n", len); @@ -556,11 +560,11 @@ int sixlowpan_framecreate(FAR struct ieee802154_driver_s *ieee, /* Then create the frame */ - sixlowpan_802154_framecreate(¶ms, FRAME_HDR_START(ieee), len); + sixlowpan_802154_framecreate(¶ms, FRAME_HDR_START(ieee, iob), len); wlinfo("Frame type: %02x Data len: %d %u (%u)\n", - params.fcf.frame_type, len, FRAME_DATA_SIZE(ieee), - FRAME_SIZE(ieee)); + params.fcf.frame_type, len, FRAME_DATA_SIZE(ieee, iob), + FRAME_SIZE(ieee, iob)); #if CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 2 wlinfo("Dest address: %02x:%02x\n", params.dest_addr[0], params.dest_addr[1]); diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index 6828c14128..a1166aed35 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -87,24 +87,23 @@ do \ { \ (ieee)->i_dataoffset = 0; \ - (ieee)->i_framelen = 0; \ } \ while (0) -#define FRAME_HDR_START(ieee) \ - ((ieee)->i_frame) -#define FRAME_HDR_SIZE(ieee) \ +#define FRAME_HDR_START(ieee,iob) \ + ((iob)->io_data) +#define FRAME_HDR_SIZE(ieee,iob) \ ((ieee)->i_dataoffset) -#define FRAME_DATA_START(ieee) \ - ((FAR uint8_t *)((ieee)->i_frame) + (ieee)->i_dataoffset) -#define FRAME_DATA_SIZE(ieee) \ - ((ieee)->i_framelen - (ieee)->i_dataoffset) +#define FRAME_DATA_START(ieee,iob) \ + ((FAR uint8_t *)((iob)->io_data) + (ieee)->i_dataoffset) +#define FRAME_DATA_SIZE(ieee,iob) \ + ((iob)->io_len - (ieee)->i_dataoffset) -#define FRAME_REMAINING(ieee) \ - (CONFIG_NET_6LOWPAN_FRAMELEN - (ieee)->i_framelen) -#define FRAME_SIZE(ieee) \ - ((ieee)->i_framelen) +#define FRAME_REMAINING(ieee,iob) \ + (CONFIG_NET_6LOWPAN_FRAMELEN - (iob)->io_len) +#define FRAME_SIZE(ieee,iob) \ + ((iob)->io_len) /* These are some definitions of element values used in the FCF. See the * IEEE802.15.4 spec for details. @@ -254,6 +253,7 @@ extern FAR struct sixlowpan_rime_sniffer_s *g_sixlowpan_sniffer; struct net_driver_s; /* Forward reference */ struct ieee802154_driver_s; /* Forward reference */ struct rimeaddr_s; /* Forward reference */ +struct iob_s; /* Forward reference */ /**************************************************************************** * Name: sixlowpan_send @@ -263,12 +263,11 @@ struct rimeaddr_s; /* Forward reference */ * it to be sent on an 802.15.4 network using 6lowpan. Called from common * UDP/TCP send logic. * - * The payload data is in the caller 'buf' and is of length 'len'. - * Compressed headers will be added and if necessary the packet is - * fragmented. The resulting packet/fragments are put in dev->d_buf and - * the first frame will be delivered to the 802.15.4 MAC. via ieee->i_frame. - * - * Input Parmeters: + * The payload data is in the caller 'buf' and is of length 'len'. + * Compressed headers will be added and if necessary the packet is + * fragmented. The resulting packet/fragments are put in ieee->i_framelist + * and the entire list of frames will be delivered to the 802.15.4 MAC via + * ieee->i_framelist. * * Input Parameters: * dev - The IEEE802.15.4 MAC network driver interface. @@ -323,6 +322,7 @@ int sixlowpan_hdrlen(FAR struct ieee802154_driver_s *ieee, * * Input parameters: * ieee - A reference IEEE802.15.4 MAC network device structure. + * iob - The IOB in which to create the frame. * dest_panid - PAN ID of the destination. May be 0xffff if the destination * is not associated. * @@ -333,7 +333,7 @@ int sixlowpan_hdrlen(FAR struct ieee802154_driver_s *ieee, ****************************************************************************/ int sixlowpan_framecreate(FAR struct ieee802154_driver_s *ieee, - uint16_t dest_panid); + FAR struct iob_s *iob, uint16_t dest_panid); /**************************************************************************** * Name: sixlowpan_hc06_initialize @@ -474,12 +474,12 @@ void sixlowpan_uncompresshdr_hc1(FAR struct net_driver_s *dev, * Name: sixlowpan_frame_hdralloc * * Description: - * Allocate space for a header within the frame buffer (i_frame). + * Allocate space for a header within the frame buffer (IOB). * ****************************************************************************/ int sixlowpan_frame_hdralloc(FAR struct ieee802154_driver_s *ieee, - int size); + FAR struct iob_s *iob, int size); #endif /* CONFIG_NET_6LOWPAN */ #endif /* _NET_SIXLOWPAN_SIXLOWPAN_INTERNAL_H */ diff --git a/net/sixlowpan/sixlowpan_send.c b/net/sixlowpan/sixlowpan_send.c index ad72cce383..1b8ab0e07d 100644 --- a/net/sixlowpan/sixlowpan_send.c +++ b/net/sixlowpan/sixlowpan_send.c @@ -218,7 +218,7 @@ static int sixlowpan_send_frame(FAR struct ieee802154_driver_s *ieee, #if 0 /* Just some notes of what needs to be done in interrupt handler */ framer_hdrlen = sixlowpan_createframe(ieee, ieee->i_panid); memcpy(ieee->i_rimeptr + ieee->i_rime_hdrlen, (uint8_t *)ipv6 + ieee->i_uncomp_hdrlen, len - ieee->i_uncomp_hdrlen); - dev->i_framelen = len - ieee->i_uncomp_hdrlen + ieee->i_rime_hdrlen; + iob->io_len = len - ieee->i_uncomp_hdrlen + ieee->i_rime_hdrlen; #endif #warning Missing logic /* Notify the IEEE802.14.5 MAC driver that we have data to be sent */ @@ -240,12 +240,11 @@ static int sixlowpan_send_frame(FAR struct ieee802154_driver_s *ieee, * it to be sent on an 802.15.4 network using 6lowpan. Called from common * UDP/TCP send logic. * - * The payload data is in the caller 'buf' and is of length 'len'. - * Compressed headers will be added and if necessary the packet is - * fragmented. The resulting packet/fragments are put in dev->d_buf and - * the first frame will be delivered to the 802.15.4 MAC. via ieee->i_frame. - * - * Input Parmeters: + * The payload data is in the caller 'buf' and is of length 'len'. + * Compressed headers will be added and if necessary the packet is + * fragmented. The resulting packet/fragments are put in ieee->i_framelist + * and the entire list of frames will be delivered to the 802.15.4 MAC via + * ieee->i_framelist. * * Input Parameters: * dev - The IEEE802.15.4 MAC network driver interface. @@ -380,7 +379,7 @@ int sixlowpan_send(FAR struct net_driver_s *dev, { /* Failed to determine the size of the header failed. */ - nerr("ERROR: sixlowpan_framecreate() failed: %d\n", framer_hdrlen); + nerr("ERROR: sixlowpan_hdrlen() failed: %d\n", framer_hdrlen); return framer_hdrlen; } diff --git a/net/sixlowpan/sixlowpan_utils.c b/net/sixlowpan/sixlowpan_utils.c index f00eaeae4c..946fc91971 100644 --- a/net/sixlowpan/sixlowpan_utils.c +++ b/net/sixlowpan/sixlowpan_utils.c @@ -44,7 +44,9 @@ * SUCH DAMAGE. * ****************************************************************************/ -/* Frame Organization: + +/* Frame Organization. The IOB data is retained in the io_data[] field of the + * IOB structure like: * * Content Offset * +------------------+ 0 @@ -52,7 +54,7 @@ * +------------------+ i_dataoffset * | Procotol Headers | * | Data Payload | - * +------------------+ i_framelen + * +------------------+ io_len * | Unused | * +------------------+ CONFIG_NET_6LOWPAN_FRAMELEN */ @@ -85,12 +87,12 @@ ****************************************************************************/ int sixlowpan_frame_hdralloc(FAR struct ieee802154_driver_s *ieee, - int size) + FAR struct iob_s *iob, int size) { - if (size <= FRAME_REMAINING(ieee)) + if (size <= FRAME_REMAINING(ieee, iob)) { ieee->i_dataoffset += size; - ieee->i_framelen += size; + iob->io_len += size; return OK; } -- GitLab From c999519bf298c8f2811252fca36318a36e25ff06 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 31 Mar 2017 08:27:39 -0600 Subject: [PATCH 286/990] 6loWPAN: A little more IOB-related logic. --- net/sixlowpan/sixlowpan_send.c | 57 ++++++++++++++++++++++++++++------ 1 file changed, 48 insertions(+), 9 deletions(-) diff --git a/net/sixlowpan/sixlowpan_send.c b/net/sixlowpan/sixlowpan_send.c index 1b8ab0e07d..c8f2846beb 100644 --- a/net/sixlowpan/sixlowpan_send.c +++ b/net/sixlowpan/sixlowpan_send.c @@ -390,12 +390,12 @@ 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 + /* ieee->i_framelist will hold the generated frames; frames will be * added at qtail. */ - FAR struct iob_s *qhead; FAR struct iob_s *qtail; + int verify; /* 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. @@ -411,8 +411,19 @@ int sixlowpan_send(FAR struct net_driver_s *dev, iob = iob_alloc(false); DEBUGASSERT(iob != NULL); + /* Initialize the IOB */ + + iob->io_flink = NULL; + iob->io_len = 0; + iob->io_offset = 0; + iob->io_pktlen = 0; + /* Create 1st Fragment */ -# warning Missing logic + /* Add the frame header. */ + + verify = sixlowpan_hdrlen(ieee, ieee->i_panid); + DEBUGASSERT(vreify == framer_hdrlen); + UNUSED(verify); /* Move HC1/HC06/IPv6 header */ # warning Missing logic @@ -433,9 +444,12 @@ int sixlowpan_send(FAR struct net_driver_s *dev, /* Add the first frame to the IOB queue */ - qhead = iob; - qtail = iob; - iob->io_flink = NULL; + ieee->i_framelist = iob; + qtail = iob; + + /* Keep track of the total amount of data queue */ + + iob->io_pktlen = iob->io_len; /* Create following fragments * Datagram tag is already in the buffer, we need to set the @@ -452,6 +466,13 @@ int sixlowpan_send(FAR struct net_driver_s *dev, iob = iob_alloc(false); DEBUGASSERT(iob != NULL); + /* Initialize the IOB */ + + iob->io_flink = NULL; + iob->io_len = 0; + iob->io_offset = 0; + iob->io_pktlen = 0; + /* Copy payload */ # warning Missing logic @@ -461,7 +482,10 @@ int sixlowpan_send(FAR struct net_driver_s *dev, /* Add the next frame to the tail of the IOB queue */ qtail->io_flink = iob; - iob->io_flink = NULL; + + /* Keep track of the total amount of data queue */ + + ieee->i_framelist->io_pktlen += iob->io_len; /* Check tx result. */ # warning Missing logic @@ -469,7 +493,7 @@ int sixlowpan_send(FAR struct net_driver_s *dev, /* Send the list of frames */ - return sixlowpan_send_frame(ieee, qhead); + return sixlowpan_send_frame(ieee, ieee->i_framelist); #else nerr("ERROR: Packet too large: %d\n", len); nerr(" Cannot to be sent without fragmentation support\n"); @@ -489,12 +513,27 @@ int sixlowpan_send(FAR struct net_driver_s *dev, iob = iob_alloc(false); DEBUGASSERT(iob != NULL); + /* Initialize the IOB */ + + iob->io_flink = NULL; + iob->io_len = 0; + iob->io_offset = 0; + iob->io_pktlen = 0; + /* Format the single frame */ # warning Missing logic /* Send the single frame */ +# warning Missing logic + + /* Add the first frame to the IOB queue */ + + ieee->i_framelist = iob; + + /* Keep track of the total amount of data queue */ + + iob->io_pktlen = iob->io_len; - iob->io_flink = NULL; return sixlowpan_send_frame(ieee, iob); } } -- GitLab From cd3c9634c8510b27f473b1c648d1b7aa70d73396 Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Fri, 31 Mar 2017 08:58:14 -0600 Subject: [PATCH 287/990] Add user-space networking stack API (usrsock) User-space networking stack API allows user-space daemon to provide TCP/IP stack implementation for NuttX network. Main use for this is to allow use and seamless integration of HW-provided TCP/IP stacks to NuttX. For example, user-space daemon can translate /dev/usrsock API requests to HW TCP/IP API requests while rest of the user-space can access standard socket API, with socket descriptors that can be used with NuttX system calls. --- include/nuttx/net/netconfig.h | 14 +- include/nuttx/net/usrsock.h | 233 ++++++ net/Kconfig | 18 + net/Makefile | 1 + net/README.txt | 34 +- net/devif/devif.h | 9 +- net/devif/devif_poll.c | 14 +- net/devif/ipv4_input.c | 6 +- net/devif/ipv6_input.c | 6 +- net/net_initialize.c | 11 +- net/socket/Make.defs | 5 +- net/socket/accept.c | 17 + net/socket/bind.c | 24 + net/socket/connect.c | 54 +- net/socket/getsockname.c | 38 +- net/socket/getsockopt.c | 51 ++ net/socket/listen.c | 13 + net/socket/net_clone.c | 14 +- net/socket/net_close.c | 63 +- net/socket/net_monitor.c | 4 + net/socket/net_poll.c | 13 +- net/socket/net_sendfile.c | 19 + net/socket/net_vfcntl.c | 27 +- net/socket/recvfrom.c | 99 ++- net/socket/send.c | 34 +- net/socket/sendto.c | 27 +- net/socket/setsockopt.c | 36 + net/socket/socket.c | 58 +- net/socket/socket.h | 9 +- net/tcp/Kconfig | 13 +- net/tcp/Make.defs | 2 + net/tcp/tcp.h | 7 +- net/udp/Kconfig | 11 +- net/udp/Make.defs | 2 + net/udp/udp.h | 7 +- net/usrsock/Kconfig | 39 + net/usrsock/Make.defs | 51 ++ net/usrsock/usrsock.h | 553 +++++++++++++ net/usrsock/usrsock_bind.c | 221 +++++ net/usrsock/usrsock_close.c | 205 +++++ net/usrsock/usrsock_conn.c | 347 ++++++++ net/usrsock/usrsock_connect.c | 257 ++++++ net/usrsock/usrsock_dev.c | 1271 +++++++++++++++++++++++++++++ net/usrsock/usrsock_event.c | 136 +++ net/usrsock/usrsock_getsockname.c | 265 ++++++ net/usrsock/usrsock_getsockopt.c | 275 +++++++ net/usrsock/usrsock_poll.c | 388 +++++++++ net/usrsock/usrsock_recvfrom.c | 485 +++++++++++ net/usrsock/usrsock_sendto.c | 426 ++++++++++ net/usrsock/usrsock_setsockopt.c | 230 ++++++ net/usrsock/usrsock_socket.c | 265 ++++++ 51 files changed, 6283 insertions(+), 124 deletions(-) create mode 100644 include/nuttx/net/usrsock.h create mode 100644 net/usrsock/Kconfig create mode 100644 net/usrsock/Make.defs create mode 100644 net/usrsock/usrsock.h create mode 100644 net/usrsock/usrsock_bind.c create mode 100644 net/usrsock/usrsock_close.c create mode 100644 net/usrsock/usrsock_conn.c create mode 100644 net/usrsock/usrsock_connect.c create mode 100644 net/usrsock/usrsock_dev.c create mode 100644 net/usrsock/usrsock_event.c create mode 100644 net/usrsock/usrsock_getsockname.c create mode 100644 net/usrsock/usrsock_getsockopt.c create mode 100644 net/usrsock/usrsock_poll.c create mode 100644 net/usrsock/usrsock_recvfrom.c create mode 100644 net/usrsock/usrsock_sendto.c create mode 100644 net/usrsock/usrsock_setsockopt.c create mode 100644 net/usrsock/usrsock_socket.c diff --git a/include/nuttx/net/netconfig.h b/include/nuttx/net/netconfig.h index 3456132901..1e79580ee3 100644 --- a/include/nuttx/net/netconfig.h +++ b/include/nuttx/net/netconfig.h @@ -97,7 +97,7 @@ * * - Maximum Transfer Unit (MTU) * - TCP Receive Window size (See TCP configuration options below) - * + * * A better solution would be to support device-by-device MTU and receive * window sizes. This minimum support is require to support the optimal * SLIP MTU of 296 bytes and the standard Ethernet MTU of 1500 @@ -547,6 +547,18 @@ # define CONFIG_NET_ARP_MAXAGE 120 #endif +/* Usrsock configuration options */ + +/* The maximum amount of concurrent usrsock connections, Default: 6 */ + +#ifndef CONFIG_NET_USRSOCK_CONNS +# ifdef CONFIG_NET_USRSOCK +# define CONFIG_NET_USRSOCK_CONNS 6 +# else +# define CONFIG_NET_USRSOCK_CONNS 0 +# endif +#endif + /* General configuration options */ /* Delay after receive to catch a following packet. No delay should be diff --git a/include/nuttx/net/usrsock.h b/include/nuttx/net/usrsock.h new file mode 100644 index 0000000000..3ca990d44e --- /dev/null +++ b/include/nuttx/net/usrsock.h @@ -0,0 +1,233 @@ +/**************************************************************************** + * include/nuttx/net/usrsock.h + * + * Copyright (C) 2015, 2017 Haltian Ltd. All rights reserved. + * Author: Jussi Kivilinna + * + * 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_NET_USRSOCK_H +#define __INCLUDE_NUTTX_NET_USRSOCK_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Event message flags */ + +#define USRSOCK_EVENT_ABORT (1 << 0) +#define USRSOCK_EVENT_SENDTO_READY (1 << 1) +#define USRSOCK_EVENT_RECVFROM_AVAIL (1 << 2) +#define USRSOCK_EVENT_REMOTE_CLOSED (1 << 3) + +/* Response message flags */ + +#define USRSOCK_MESSAGE_FLAG_REQ_IN_PROGRESS (1 << 0) +#define USRSOCK_MESSAGE_FLAG_EVENT (1 << 1) + +#define USRSOCK_MESSAGE_IS_EVENT(flags) \ + (!!((flags) & USRSOCK_MESSAGE_FLAG_EVENT)) +#define USRSOCK_MESSAGE_IS_REQ_RESPONSE(flags) \ + (!USRSOCK_MESSAGE_IS_EVENT(flags)) + +#define USRSOCK_MESSAGE_REQ_IN_PROGRESS(flags) \ + (!!((flags) & USRSOCK_MESSAGE_FLAG_REQ_IN_PROGRESS)) +#define USRSOCK_MESSAGE_REQ_COMPLETED(flags) \ + (!USRSOCK_MESSAGE_REQ_IN_PROGRESS(flags)) + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* Request types */ + +enum usrsock_request_types_e +{ + USRSOCK_REQUEST_SOCKET = 0, + USRSOCK_REQUEST_CLOSE, + USRSOCK_REQUEST_CONNECT, + USRSOCK_REQUEST_SENDTO, + USRSOCK_REQUEST_RECVFROM, + USRSOCK_REQUEST_SETSOCKOPT, + USRSOCK_REQUEST_GETSOCKOPT, + USRSOCK_REQUEST_GETSOCKNAME, + USRSOCK_REQUEST_BIND, + USRSOCK_REQUEST__MAX +}; + +/* Response/event message types */ + +enum usrsock_message_types_e +{ + USRSOCK_MESSAGE_RESPONSE_ACK = 0, + USRSOCK_MESSAGE_RESPONSE_DATA_ACK, + USRSOCK_MESSAGE_SOCKET_EVENT, +}; + +/* Request structures (kernel => /dev/usrsock => daemon) */ + +begin_packed_struct struct usrsock_request_common_s +{ + int8_t reqid; + uint8_t xid; +} end_packed_struct; + +begin_packed_struct struct usrsock_request_socket_s +{ + struct usrsock_request_common_s head; + + int16_t domain; + int16_t type; + int16_t protocol; +} end_packed_struct; + +begin_packed_struct struct usrsock_request_close_s +{ + struct usrsock_request_common_s head; + + int16_t usockid; +} end_packed_struct; + +begin_packed_struct struct usrsock_request_bind_s +{ + struct usrsock_request_common_s head; + + int16_t usockid; + uint16_t addrlen; +} end_packed_struct; + +begin_packed_struct struct usrsock_request_connect_s +{ + struct usrsock_request_common_s head; + + int16_t usockid; + uint16_t addrlen; +} end_packed_struct; + +begin_packed_struct struct usrsock_request_sendto_s +{ + struct usrsock_request_common_s head; + + int16_t usockid; + uint16_t addrlen; + uint16_t buflen; +} end_packed_struct; + +begin_packed_struct struct usrsock_request_recvfrom_s +{ + struct usrsock_request_common_s head; + + int16_t usockid; + uint16_t max_buflen; + uint16_t max_addrlen; +} end_packed_struct; + +begin_packed_struct struct usrsock_request_setsockopt_s +{ + struct usrsock_request_common_s head; + + int16_t usockid; + int16_t level; + int16_t option; + uint16_t valuelen; +} end_packed_struct; + +begin_packed_struct struct usrsock_request_getsockopt_s +{ + struct usrsock_request_common_s head; + + int16_t usockid; + int16_t level; + int16_t option; + uint16_t max_valuelen; +} end_packed_struct; + +begin_packed_struct struct usrsock_request_getsockname_s +{ + struct usrsock_request_common_s head; + + int16_t usockid; + uint16_t max_addrlen; +} end_packed_struct; + +/* Response/event message structures (kernel <= /dev/usrsock <= daemon) */ + +begin_packed_struct struct usrsock_message_common_s +{ + int8_t msgid; + int8_t flags; +} end_packed_struct; + +/* Request acknowledgment/completion message */ + +begin_packed_struct struct usrsock_message_req_ack_s +{ + struct usrsock_message_common_s head; + + uint8_t xid; + int32_t result; +} end_packed_struct; + +/* Request acknowledgment/completion message */ + +begin_packed_struct struct usrsock_message_datareq_ack_s +{ + struct usrsock_message_req_ack_s reqack; + + /* head.result => positive buflen, negative error-code. */ + + uint16_t valuelen; /* length of value returned after buffer */ + uint16_t valuelen_nontrunc; /* actual non-truncated length of value at + * daemon-sïde. */ +} end_packed_struct; + +/* Socket event message */ + +begin_packed_struct struct usrsock_message_socket_event_s +{ + struct usrsock_message_common_s head; + + int16_t usockid; + uint16_t events; +} end_packed_struct; + +#endif /* __INCLUDE_NUTTX_NET_USRSOCK_H */ diff --git a/net/Kconfig b/net/Kconfig index 2741c67816..f15c9b5d7a 100644 --- a/net/Kconfig +++ b/net/Kconfig @@ -236,6 +236,23 @@ config TUN_LPWORK endchoice # Work queue endif # NET_TUN +config NET_USRSOCK + bool "User-space networking stack API" + default n + ---help--- + Enable or disable user-space networking stack support. + + User-space networking stack API allows user-space daemon to + provide TCP/IP stack implementation for NuttX network. + + Main use for this is to allow use and integration of + HW-provided TCP/IP stacks for NuttX. + + For example, user-space daemon can translate /dev/usrsock API + requests to HW TCP/IP API requests while rest of the user-space + can access standard socket API, with socket descriptors that + can be used with NuttX system calls. + endmenu # Data link support source "net/netdev/Kconfig" @@ -271,6 +288,7 @@ source "net/arp/Kconfig" source "net/loopback/Kconfig" source "net/iob/Kconfig" source "net/procfs/Kconfig" +source "net/usrsock/Kconfig" source "net/utils/Kconfig" config NET_STATISTICS diff --git a/net/Makefile b/net/Makefile index 6898bad40e..cd6979a414 100644 --- a/net/Makefile +++ b/net/Makefile @@ -72,6 +72,7 @@ include devif/Make.defs include loopback/Make.defs include route/Make.defs include procfs/Make.defs +include usrsock/Make.defs include utils/Make.defs endif diff --git a/net/README.txt b/net/README.txt index 0f93c07581..e87a0889b5 100644 --- a/net/README.txt +++ b/net/README.txt @@ -22,21 +22,25 @@ Directory Structure +- route - Routing table support +- tcp - Transmission Control Protocol +- udp - User Datagram Protocol + +- usrsock - User socket API for user-space networking stack `- utils - Miscellaneous utility functions - +----------------------------------------------------------------+ - | Application layer | - +----------------------------------------------------------------+ - +----------------------------------------------------------------+ - | Socket layer (socket/) | - +----------------------------------------------------------------+ - +------------++--------------------------------------------------+ - | Network || Protocol stacks (arp, ipv6, icmp, pkt, tcp, udp) | - | Device |+--------------------------------------------------+ - | Interface |+------------------------------------++------------+ - | (netdev/) || Network Device Interface (devif/) || Utilities | - +------------++------------------------------------++------------+ - +----------------------------------------------------------------+ - | Network Device Drivers | - +----------------------------------------------------------------+ + +-------------------------------------------------------------------++------------------------+ + | Application layer || usrsock daemon | + +-------------------------------------------------------------------++------------------------+ + +-------------------------------------------------------------------++----------------+ +-----+ + | Socket layer (socket/) || /dev/usrsock | | | + +-------------------------------------------------------------------++----------------+ | | + +------------++--------------------------------------------------++-------------------+ | | + | Network || Protocol stacks (arp, ipv6, icmp, pkt, tcp, udp) || usrsock/ | | | + | Device |+--------------------------------------------------++-------------------+ | | + | Interface |+------------------------------------++---------------------------------+ | | + | (netdev/) || Network Device Interface (devif/) || Utilities | | | + +------------++------------------------------------++---------------------------------+ | | + +----------------------------------------------------------------+ | | + | Network Device Drivers | | HAL | + +----------------------------------------------------------------+ +-----+ + +----------------------------------------------------------------+ +--------------------------+ + | Networking Hardware | | Hardware TCP/IP Stack | + +----------------------------------------------------------------+ +--------------------------+ \ No newline at end of file diff --git a/net/devif/devif.h b/net/devif/devif.h index bca0987896..e15f6317b8 100644 --- a/net/devif/devif.h +++ b/net/devif/devif.h @@ -234,12 +234,17 @@ */ struct net_driver_s; /* Forward reference */ + +typedef CODE uint16_t (*devif_callback_event_t)(FAR struct net_driver_s *dev, + FAR void *pvconn, + FAR void *pvpriv, + uint16_t flags); + struct devif_callback_s { FAR struct devif_callback_s *nxtconn; FAR struct devif_callback_s *nxtdev; - uint16_t (*event)(FAR struct net_driver_s *dev, FAR void *pvconn, - FAR void *pvpriv, uint16_t flags); + FAR devif_callback_event_t event; FAR void *priv; uint16_t flags; }; diff --git a/net/devif/devif_poll.c b/net/devif/devif_poll.c index 928b779fb3..4a5d325d43 100644 --- a/net/devif/devif_poll.c +++ b/net/devif/devif_poll.c @@ -186,7 +186,7 @@ static inline int devif_poll_igmp(FAR struct net_driver_s *dev, * ****************************************************************************/ -#ifdef CONFIG_NET_UDP +#ifdef NET_UDP_HAVE_STACK static int devif_poll_udp_connections(FAR struct net_driver_s *dev, devif_poll_callback_t callback) { @@ -208,7 +208,7 @@ static int devif_poll_udp_connections(FAR struct net_driver_s *dev, return bstop; } -#endif /* CONFIG_NET_UDP */ +#endif /* NET_UDP_HAVE_STACK */ /**************************************************************************** * Function: devif_poll_tcp_connections @@ -222,7 +222,7 @@ static int devif_poll_udp_connections(FAR struct net_driver_s *dev, * ****************************************************************************/ -#ifdef CONFIG_NET_TCP +#ifdef NET_TCP_HAVE_STACK static inline int devif_poll_tcp_connections(FAR struct net_driver_s *dev, devif_poll_callback_t callback) { @@ -261,7 +261,7 @@ static inline int devif_poll_tcp_connections(FAR struct net_driver_s *dev, * ****************************************************************************/ -#ifdef CONFIG_NET_TCP +#ifdef NET_TCP_HAVE_STACK static inline int devif_poll_tcp_timer(FAR struct net_driver_s *dev, devif_poll_callback_t callback, int hsec) @@ -349,7 +349,7 @@ int devif_poll(FAR struct net_driver_s *dev, devif_poll_callback_t callback) if (!bstop) #endif -#ifdef CONFIG_NET_TCP +#ifdef NET_TCP_HAVE_STACK { /* Traverse all of the active TCP connections and perform the poll * action. @@ -360,7 +360,7 @@ int devif_poll(FAR struct net_driver_s *dev, devif_poll_callback_t callback) if (!bstop) #endif -#ifdef CONFIG_NET_UDP +#ifdef NET_UDP_HAVE_STACK { /* Traverse all of the allocated UDP connections and perform * the poll action @@ -467,7 +467,7 @@ int devif_timer(FAR struct net_driver_s *dev, devif_poll_callback_t callback) neighbor_periodic(hsec); #endif -#ifdef CONFIG_NET_TCP +#ifdef NET_TCP_HAVE_STACK /* Traverse all of the active TCP connections and perform the * timer action. */ diff --git a/net/devif/ipv4_input.c b/net/devif/ipv4_input.c index 5a773b1ef8..faa23ad547 100644 --- a/net/devif/ipv4_input.c +++ b/net/devif/ipv4_input.c @@ -391,7 +391,7 @@ int ipv4_input(FAR struct net_driver_s *dev) #endif /* CONFIG_NET_TCP_REASSEMBLY */ } -#if defined(CONFIG_NET_BROADCAST) && defined(CONFIG_NET_UDP) +#if defined(CONFIG_NET_BROADCAST) && defined(NET_UDP_HAVE_STACK) /* If IP broadcast support is configured, we check for a broadcast * UDP packet, which may be destined to us (even if there is no IP * address yet assigned to the device as is the case when we are @@ -459,13 +459,13 @@ int ipv4_input(FAR struct net_driver_s *dev) switch (pbuf->proto) { -#ifdef CONFIG_NET_TCP +#ifdef NET_TCP_HAVE_STACK case IP_PROTO_TCP: /* TCP input */ tcp_ipv4_input(dev); break; #endif -#ifdef CONFIG_NET_UDP +#ifdef NET_UDP_HAVE_STACK case IP_PROTO_UDP: /* UDP input */ udp_ipv4_input(dev); break; diff --git a/net/devif/ipv6_input.c b/net/devif/ipv6_input.c index 0816630679..149f06d33d 100644 --- a/net/devif/ipv6_input.c +++ b/net/devif/ipv6_input.c @@ -197,7 +197,7 @@ int ipv6_input(FAR struct net_driver_s *dev) * negotiating over DHCP for an address). */ -#if defined(CONFIG_NET_BROADCAST) && defined(CONFIG_NET_UDP) +#if defined(CONFIG_NET_BROADCAST) && defined(NET_UDP_HAVE_STACK) if (ipv6->proto == IP_PROTO_UDP && net_ipv6addr_cmp(ipv6->destipaddr, g_ipv6_alloneaddr)) { @@ -253,13 +253,13 @@ int ipv6_input(FAR struct net_driver_s *dev) switch (ipv6->proto) { -#ifdef CONFIG_NET_TCP +#ifdef NET_TCP_HAVE_STACK case IP_PROTO_TCP: /* TCP input */ tcp_ipv6_input(dev); break; #endif -#ifdef CONFIG_NET_UDP +#ifdef NET_UDP_HAVE_STACK case IP_PROTO_UDP: /* UDP input */ udp_ipv6_input(dev); break; diff --git a/net/net_initialize.c b/net/net_initialize.c index 988faf6b54..3edbd6849b 100644 --- a/net/net_initialize.c +++ b/net/net_initialize.c @@ -57,6 +57,7 @@ #include "local/local.h" #include "igmp/igmp.h" #include "route/route.h" +#include "usrsock/usrsock.h" #include "utils/utils.h" /**************************************************************************** @@ -130,7 +131,7 @@ void net_setup(void) local_initialize(); #endif -#ifdef CONFIG_NET_TCP +#ifdef NET_TCP_HAVE_STACK /* Initialize the listening port structures */ tcp_listen_initialize(); @@ -146,7 +147,7 @@ void net_setup(void) #endif #endif /* CONFIG_NET_TCP */ -#ifdef CONFIG_NET_UDP +#ifdef NET_UDP_HAVE_STACK /* Initialize the UDP connection structures */ udp_initialize(); @@ -163,6 +164,12 @@ void net_setup(void) net_initroute(); #endif + +#ifdef CONFIG_NET_USRSOCK + /* Initialize the user-space socket API */ + + usrsock_initialize(); +#endif } /**************************************************************************** diff --git a/net/socket/Make.defs b/net/socket/Make.defs index cfb6233bd1..6f433cd97a 100644 --- a/net/socket/Make.defs +++ b/net/socket/Make.defs @@ -42,7 +42,10 @@ SOCK_CSRCS += net_dupsd2.c net_clone.c net_poll.c net_vfcntl.c # TCP/IP support ifeq ($(CONFIG_NET_TCP),y) -SOCK_CSRCS += listen.c accept.c net_monitor.c +SOCK_CSRCS += listen.c accept.c +ifneq ($(CONFIG_NET_TCP_NO_STACK),y) +SOCK_CSRCS += net_monitor.c +endif # Local Unix domain support diff --git a/net/socket/accept.c b/net/socket/accept.c index 4bf35dc7f2..ec7385b4f2 100644 --- a/net/socket/accept.c +++ b/net/socket/accept.c @@ -54,6 +54,7 @@ #include "tcp/tcp.h" #include "local/local.h" #include "socket/socket.h" +#include "usrsock/usrsock.h" /**************************************************************************** * Public Functions @@ -129,7 +130,9 @@ int psock_accept(FAR struct socket *psock, FAR struct sockaddr *addr, FAR socklen_t *addrlen, FAR struct socket *newsock) { int errcode; +#ifdef NET_TCP_HAVE_STACK int ret; +#endif DEBUGASSERT(psock != NULL); @@ -141,6 +144,13 @@ int psock_accept(FAR struct socket *psock, FAR struct sockaddr *addr, if (psock->s_type != SOCK_STREAM) { +#ifdef CONFIG_NET_USRSOCK + if (psock->s_type == SOCK_USRSOCK_TYPE) + { +#warning "Missing logic" + } +#endif + errcode = EOPNOTSUPP; goto errout; } @@ -238,6 +248,7 @@ int psock_accept(FAR struct socket *psock, FAR struct sockaddr *addr, else #endif { +#ifdef NET_TCP_HAVE_STACK /* Perform the local accept operation (with the network locked) */ net_lock(); @@ -267,6 +278,10 @@ int psock_accept(FAR struct socket *psock, FAR struct sockaddr *addr, } net_unlock(); +#else + errcode = EOPNOTSUPP; + goto errout; +#endif /* NET_TCP_HAVE_STACK */ } #endif /* CONFIG_NET_TCP */ @@ -278,8 +293,10 @@ int psock_accept(FAR struct socket *psock, FAR struct sockaddr *addr, leave_cancellation_point(); return OK; +#ifdef NET_TCP_HAVE_STACK errout_after_accept: psock_close(newsock); +#endif errout: set_errno(errcode); diff --git a/net/socket/bind.c b/net/socket/bind.c index 1197460ce7..8ffc1274e8 100644 --- a/net/socket/bind.c +++ b/net/socket/bind.c @@ -46,6 +46,7 @@ #include #include #include +#include #ifdef CONFIG_NET_PKT # include @@ -60,6 +61,7 @@ #include "udp/udp.h" #include "pkt/pkt.h" #include "local/local.h" +#include "usrsock/usrsock.h" /**************************************************************************** * Private Functions @@ -212,6 +214,20 @@ int psock_bind(FAR struct socket *psock, const struct sockaddr *addr, switch (psock->s_type) { +#ifdef CONFIG_NET_USRSOCK + case SOCK_USRSOCK_TYPE: + { + FAR struct usrsock_conn_s *conn = psock->s_conn; + + DEBUGASSERT(conn); + + /* Perform the usrsock bind operation */ + + ret = usrsock_bind(conn, addr, addrlen); + } + break; +#endif + #ifdef CONFIG_NET_PKT case SOCK_RAW: ret = pkt_bind(psock->s_conn, lladdr); @@ -243,9 +259,13 @@ int psock_bind(FAR struct socket *psock, const struct sockaddr *addr, else #endif { +#ifdef NET_TCP_HAVE_STACK /* Bind the TCP/IP connection structure */ ret = tcp_bind(psock->s_conn, addr); +#else + ret = -ENOSYS; +#endif } #endif /* CONFIG_NET_TCP */ @@ -284,9 +304,13 @@ int psock_bind(FAR struct socket *psock, const struct sockaddr *addr, else #endif { +#ifdef NET_UDP_HAVE_STACK /* Bind the UDPP/IP connection structure */ ret = udp_bind(psock->s_conn, addr); +#else + ret = -ENOSYS; +#endif } #endif /* CONFIG_NET_UDP */ diff --git a/net/socket/connect.c b/net/socket/connect.c index 6a0140ea55..d8b2eb46e1 100644 --- a/net/socket/connect.c +++ b/net/socket/connect.c @@ -62,12 +62,13 @@ #include "udp/udp.h" #include "local/local.h" #include "socket/socket.h" +#include "usrsock/usrsock.h" /**************************************************************************** * Private Types ****************************************************************************/ -#ifdef CONFIG_NET_TCP +#ifdef NET_TCP_HAVE_STACK struct tcp_connect_s { FAR struct tcp_conn_s *tc_conn; /* Reference to TCP connection structure */ @@ -82,7 +83,7 @@ struct tcp_connect_s * Private Function Prototypes ****************************************************************************/ -#ifdef CONFIG_NET_TCP +#ifdef NET_TCP_HAVE_STACK static inline int psock_setup_callbacks(FAR struct socket *psock, FAR struct tcp_connect_s *pstate); static void psock_teardown_callbacks(FAR struct tcp_connect_s *pstate, @@ -92,7 +93,7 @@ static uint16_t psock_connect_interrupt(FAR struct net_driver_s *dev, uint16_t flags); static inline int psock_tcp_connect(FAR struct socket *psock, FAR const struct sockaddr *addr); -#endif /* CONFIG_NET_TCP */ +#endif /* NET_TCP_HAVE_STACK */ /**************************************************************************** * Private Functions @@ -101,7 +102,7 @@ static inline int psock_tcp_connect(FAR struct socket *psock, * Name: psock_setup_callbacks ****************************************************************************/ -#ifdef CONFIG_NET_TCP +#ifdef NET_TCP_HAVE_STACK static inline int psock_setup_callbacks(FAR struct socket *psock, FAR struct tcp_connect_s *pstate) { @@ -137,13 +138,13 @@ static inline int psock_setup_callbacks(FAR struct socket *psock, return ret; } -#endif /* CONFIG_NET_TCP */ +#endif /* NET_TCP_HAVE_STACK */ /**************************************************************************** * Name: psock_teardown_callbacks ****************************************************************************/ -#ifdef CONFIG_NET_TCP +#ifdef NET_TCP_HAVE_STACK static void psock_teardown_callbacks(FAR struct tcp_connect_s *pstate, int status) { @@ -165,7 +166,7 @@ static void psock_teardown_callbacks(FAR struct tcp_connect_s *pstate, net_stopmonitor(conn); } } -#endif /* CONFIG_NET_TCP */ +#endif /* NET_TCP_HAVE_STACK */ /**************************************************************************** * Name: psock_connect_interrupt @@ -187,7 +188,7 @@ static void psock_teardown_callbacks(FAR struct tcp_connect_s *pstate, * ****************************************************************************/ -#ifdef CONFIG_NET_TCP +#ifdef NET_TCP_HAVE_STACK static uint16_t psock_connect_interrupt(FAR struct net_driver_s *dev, FAR void *pvconn, FAR void *pvpriv, uint16_t flags) @@ -322,7 +323,7 @@ static uint16_t psock_connect_interrupt(FAR struct net_driver_s *dev, return flags; } -#endif /* CONFIG_NET_TCP */ +#endif /* NET_TCP_HAVE_STACK */ /**************************************************************************** * Name: psock_tcp_connect @@ -342,7 +343,7 @@ static uint16_t psock_connect_interrupt(FAR struct net_driver_s *dev, * ****************************************************************************/ -#ifdef CONFIG_NET_TCP +#ifdef NET_TCP_HAVE_STACK static inline int psock_tcp_connect(FAR struct socket *psock, FAR const struct sockaddr *addr) { @@ -434,7 +435,7 @@ static inline int psock_tcp_connect(FAR struct socket *psock, net_unlock(); return ret; } -#endif /* CONFIG_NET_TCP */ +#endif /* NET_TCP_HAVE_STACK */ /**************************************************************************** * Public Functions @@ -512,7 +513,8 @@ int psock_connect(FAR struct socket *psock, FAR const struct sockaddr *addr, socklen_t addrlen) { FAR const struct sockaddr_in *inaddr = (FAR const struct sockaddr_in *)addr; -#if defined(CONFIG_NET_TCP) || defined(CONFIG_NET_UDP) || defined(CONFIG_NET_LOCAL) +#if defined(CONFIG_NET_TCP) || defined(CONFIG_NET_UDP) || \ + defined(CONFIG_NET_LOCAL) || defined(CONFIG_NET_USRSOCK) int ret; #endif int errcode; @@ -570,6 +572,13 @@ int psock_connect(FAR struct socket *psock, FAR const struct sockaddr *addr, #endif default: +#ifdef CONFIG_NET_USRSOCK + if (psock->s_type == SOCK_USRSOCK_TYPE) + { + break; + } +#endif + DEBUGPANIC(); errcode = EAFNOSUPPORT; goto errout; @@ -608,9 +617,13 @@ int psock_connect(FAR struct socket *psock, FAR const struct sockaddr *addr, else #endif { +#ifdef NET_TCP_HAVE_STACK /* Connect the TCP/IP socket */ ret = psock_tcp_connect(psock, addr); +#else + ret = -ENOSYS; +#endif } #endif /* CONFIG_NET_TCP */ @@ -642,6 +655,7 @@ int psock_connect(FAR struct socket *psock, FAR const struct sockaddr *addr, else #endif { +#ifdef NET_UDP_HAVE_STACK ret = udp_connect(psock->s_conn, addr); if (ret < 0 || addr == NULL) { @@ -651,6 +665,9 @@ int psock_connect(FAR struct socket *psock, FAR const struct sockaddr *addr, { psock->s_flags |= _SF_CONNECTED; } +#else + ret = -ENOSYS; +#endif } #endif /* CONFIG_NET_UDP */ @@ -663,6 +680,19 @@ int psock_connect(FAR struct socket *psock, FAR const struct sockaddr *addr, break; #endif /* CONFIG_NET_UDP || CONFIG_NET_LOCAL_DGRAM */ +#ifdef CONFIG_NET_USRSOCK + case SOCK_USRSOCK_TYPE: + { + ret = usrsock_connect(psock, addr, addrlen); + if (ret < 0) + { + errcode = -ret; + goto errout; + } + } + break; +#endif /* CONFIG_NET_USRSOCK */ + default: errcode = EBADF; goto errout; diff --git a/net/socket/getsockname.c b/net/socket/getsockname.c index 7bf87c29d1..703136e0d9 100644 --- a/net/socket/getsockname.c +++ b/net/socket/getsockname.c @@ -44,6 +44,7 @@ #include #include +#include #include #include @@ -54,6 +55,7 @@ #include "tcp/tcp.h" #include "udp/udp.h" #include "socket/socket.h" +#include "usrsock/usrsock.h" #ifdef CONFIG_NET @@ -92,7 +94,7 @@ int ipv4_getsockname(FAR struct socket *psock, FAR struct sockaddr *addr, FAR socklen_t *addrlen) { FAR struct net_driver_s *dev; -#if defined(CONFIG_NET_TCP) || defined(CONFIG_NET_UDP) +#if defined(NET_TCP_HAVE_STACK) || defined(NET_UDP_HAVE_STACK) FAR struct sockaddr_in *outaddr = (FAR struct sockaddr_in *)addr; #endif #ifdef CONFIG_NETDEV_MULTINIC @@ -116,7 +118,7 @@ int ipv4_getsockname(FAR struct socket *psock, FAR struct sockaddr *addr, switch (psock->s_type) { -#ifdef CONFIG_NET_TCP +#ifdef NET_TCP_HAVE_STACK case SOCK_STREAM: { FAR struct tcp_conn_s *tcp_conn = (FAR struct tcp_conn_s *)psock->s_conn; @@ -129,7 +131,7 @@ int ipv4_getsockname(FAR struct socket *psock, FAR struct sockaddr *addr, break; #endif -#ifdef CONFIG_NET_UDP +#ifdef NET_UDP_HAVE_STACK case SOCK_DGRAM: { FAR struct udp_conn_s *udp_conn = (FAR struct udp_conn_s *)psock->s_conn; @@ -171,7 +173,7 @@ int ipv4_getsockname(FAR struct socket *psock, FAR struct sockaddr *addr, /* Set the address family and the IP address */ -#if defined(CONFIG_NET_TCP) || defined(CONFIG_NET_UDP) +#if defined(NET_TCP_HAVE_STACK) || defined(NET_UDP_HAVE_STACK) outaddr->sin_family = AF_INET; outaddr->sin_addr.s_addr = dev->d_ipaddr; *addrlen = sizeof(struct sockaddr_in); @@ -215,7 +217,7 @@ int ipv6_getsockname(FAR struct socket *psock, FAR struct sockaddr *addr, FAR socklen_t *addrlen) { FAR struct net_driver_s *dev; -#if defined(CONFIG_NET_TCP) || defined(CONFIG_NET_UDP) +#if defined(NET_TCP_HAVE_STACK) || defined(NET_UDP_HAVE_STACK) FAR struct sockaddr_in6 *outaddr = (FAR struct sockaddr_in6 *)addr; #endif #ifdef CONFIG_NETDEV_MULTINIC @@ -239,7 +241,7 @@ int ipv6_getsockname(FAR struct socket *psock, FAR struct sockaddr *addr, switch (psock->s_type) { -#ifdef CONFIG_NET_TCP +#ifdef NET_TCP_HAVE_STACK case SOCK_STREAM: { FAR struct tcp_conn_s *tcp_conn = (FAR struct tcp_conn_s *)psock->s_conn; @@ -252,7 +254,7 @@ int ipv6_getsockname(FAR struct socket *psock, FAR struct sockaddr *addr, break; #endif -#ifdef CONFIG_NET_UDP +#ifdef NET_UDP_HAVE_STACK case SOCK_DGRAM: { FAR struct udp_conn_s *udp_conn = (FAR struct udp_conn_s *)psock->s_conn; @@ -294,7 +296,7 @@ int ipv6_getsockname(FAR struct socket *psock, FAR struct sockaddr *addr, /* Set the address family and the IP address */ -#if defined(CONFIG_NET_TCP) || defined(CONFIG_NET_UDP) +#if defined(NET_TCP_HAVE_STACK) || defined(NET_UDP_HAVE_STACK) outaddr->sin6_family = AF_INET6; memcpy(outaddr->sin6_addr.in6_u.u6_addr8, dev->d_ipv6addr, 16); *addrlen = sizeof(struct sockaddr_in6); @@ -371,6 +373,26 @@ int getsockname(int sockfd, FAR struct sockaddr *addr, FAR socklen_t *addrlen) } #endif +#ifdef CONFIG_NET_USRSOCK + if (psock->s_type == SOCK_USRSOCK_TYPE) + { + FAR struct usrsock_conn_s *conn = psock->s_conn; + + DEBUGASSERT(conn); + + /* Handle usrsock getsockname */ + + ret = usrsock_getsockname(conn, addr, addrlen); + if (ret < 0) + { + errcode = -ret; + goto errout; + } + + return OK; + } +#endif + /* Handle by address domain */ switch (psock->s_domain) diff --git a/net/socket/getsockopt.c b/net/socket/getsockopt.c index 5072f02067..ab15d511aa 100644 --- a/net/socket/getsockopt.c +++ b/net/socket/getsockopt.c @@ -43,9 +43,12 @@ #include #include #include +#include +#include #include #include "socket/socket.h" +#include "usrsock/usrsock.h" #include "utils/utils.h" /**************************************************************************** @@ -106,6 +109,40 @@ int psock_getsockopt(FAR struct socket *psock, int level, int option, goto errout; } +#ifdef CONFIG_NET_USRSOCK + if (psock->s_type == SOCK_USRSOCK_TYPE) + { + FAR struct usrsock_conn_s *conn = psock->s_conn; + int ret; + + DEBUGASSERT(conn); + + /* Some of the socket options are handled from this function. */ + + switch (option) + { + case SO_TYPE: /* Type can be read from NuttX psock structure. */ + case SO_RCVTIMEO: /* Rx timeouts can be handled at NuttX side, thus + * simplify daemon implementation. */ + case SO_SNDTIMEO: /* Rx timeouts can be handled at NuttX side, thus + * simplify daemon implementation. */ + break; + + default: /* Other options are passed to usrsock daemon. */ + { + ret = usrsock_getsockopt(conn, level, option, value, value_len); + if (ret < 0) + { + errcode = -ret; + goto errout; + } + + return OK; + } + } + } +#endif + /* Process the option */ switch (option) @@ -159,6 +196,20 @@ int psock_getsockopt(FAR struct socket *psock, int level, int option, goto errout; } +#ifdef CONFIG_NET_USRSOCK + if (psock->s_type == SOCK_USRSOCK_TYPE) + { + FAR struct usrsock_conn_s *conn = psock->s_conn; + + /* Return the actual socket type */ + + *(int*)value = conn->type; + *value_len = sizeof(int); + + break; + } +#endif + /* Return the socket type */ *(FAR int *)value = psock->s_type; diff --git a/net/socket/listen.c b/net/socket/listen.c index 0d91ccb586..3b0189d019 100644 --- a/net/socket/listen.c +++ b/net/socket/listen.c @@ -48,6 +48,7 @@ #include "tcp/tcp.h" #include "local/local.h" #include "socket/socket.h" +#include "usrsock/usrsock.h" /**************************************************************************** * Public Functions @@ -92,6 +93,13 @@ int psock_listen(FAR struct socket *psock, int backlog) if (psock->s_type != SOCK_STREAM || !psock->s_conn) { +#ifdef CONFIG_NET_USRSOCK + if (psock->s_type == SOCK_USRSOCK_TYPE) + { +#warning "Missing logic" + } +#endif + errcode = EOPNOTSUPP; goto errout; } @@ -118,6 +126,7 @@ int psock_listen(FAR struct socket *psock, int backlog) else #endif { +#ifdef NET_TCP_HAVE_STACK FAR struct tcp_conn_s *conn = (FAR struct tcp_conn_s *)psock->s_conn; @@ -143,6 +152,10 @@ int psock_listen(FAR struct socket *psock, int backlog) */ tcp_listen(conn); +#else + errcode = EOPNOTSUPP; + goto errout; +#endif /* NET_TCP_HAVE_STACK */ } #endif /* CONFIG_NET_TCP */ diff --git a/net/socket/net_clone.c b/net/socket/net_clone.c index 5398c614fd..83a7c5150c 100644 --- a/net/socket/net_clone.c +++ b/net/socket/net_clone.c @@ -51,6 +51,7 @@ #include "tcp/tcp.h" #include "udp/udp.h" #include "socket/socket.h" +#include "usrsock/usrsock.h" /**************************************************************************** * Public Functions @@ -96,7 +97,7 @@ int net_clone(FAR struct socket *psock1, FAR struct socket *psock2) DEBUGASSERT(psock2->s_conn); psock2->s_crefs = 1; /* One reference on the new socket itself */ -#ifdef CONFIG_NET_TCP +#ifdef NET_TCP_HAVE_STACK if (psock2->s_type == SOCK_STREAM) { FAR struct tcp_conn_s *conn = psock2->s_conn; @@ -105,7 +106,7 @@ int net_clone(FAR struct socket *psock1, FAR struct socket *psock2) } else #endif -#ifdef CONFIG_NET_UDP +#ifdef NET_UDP_HAVE_STACK if (psock2->s_type == SOCK_DGRAM) { FAR struct udp_conn_s *conn = psock2->s_conn; @@ -113,6 +114,15 @@ int net_clone(FAR struct socket *psock1, FAR struct socket *psock2) conn->crefs++; } else +#endif +#ifdef CONFIG_NET_USRSOCK + if (psock2->s_type == SOCK_USRSOCK_TYPE) + { + FAR struct usrsock_conn_s *conn = psock2->s_conn; + DEBUGASSERT(conn->crefs > 0 && conn->crefs < 255); + conn->crefs++; + } + else #endif { nerr("ERROR: Unsupported type: %d\n", psock2->s_type); diff --git a/net/socket/net_close.c b/net/socket/net_close.c index ba0fb85dc1..6bbc01b725 100644 --- a/net/socket/net_close.c +++ b/net/socket/net_close.c @@ -67,12 +67,13 @@ #include "pkt/pkt.h" #include "local/local.h" #include "socket/socket.h" +#include "usrsock/usrsock.h" /**************************************************************************** * Private Types ****************************************************************************/ -#ifdef CONFIG_NET_TCP +#ifdef NET_TCP_HAVE_STACK struct tcp_close_s { FAR struct devif_callback_s *cl_cb; /* Reference to TCP callback instance */ @@ -106,7 +107,7 @@ struct tcp_close_s * ****************************************************************************/ -#if defined(CONFIG_NET_TCP) && defined(CONFIG_NET_SOLINGER) +#if defined(NET_TCP_HAVE_STACK) && defined(CONFIG_NET_SOLINGER) static inline int close_timeout(FAR struct tcp_close_s *pstate) { FAR struct socket *psock = 0; @@ -132,7 +133,7 @@ static inline int close_timeout(FAR struct tcp_close_s *pstate) return FALSE; } -#endif /* CONFIG_NET_SOCKOPTS && CONFIG_NET_SOLINGER */ +#endif /* NET_TCP_HAVE_STACK && CONFIG_NET_SOLINGER */ /**************************************************************************** * Function: netclose_interrupt @@ -151,7 +152,7 @@ static inline int close_timeout(FAR struct tcp_close_s *pstate) * ****************************************************************************/ -#ifdef CONFIG_NET_TCP +#ifdef NET_TCP_HAVE_STACK static uint16_t netclose_interrupt(FAR struct net_driver_s *dev, FAR void *pvconn, FAR void *pvpriv, uint16_t flags) @@ -256,7 +257,7 @@ end_wait: return 0; #endif } -#endif /* CONFIG_NET_TCP */ +#endif /* NET_TCP_HAVE_STACK */ /**************************************************************************** * Function: netclose_txnotify @@ -274,7 +275,7 @@ end_wait: * ****************************************************************************/ -#ifdef CONFIG_NET_TCP +#ifdef NET_TCP_HAVE_STACK static inline void netclose_txnotify(FAR struct socket *psock, FAR struct tcp_conn_s *conn) { @@ -313,7 +314,7 @@ static inline void netclose_txnotify(FAR struct socket *psock, } #endif /* CONFIG_NET_IPv6 */ } -#endif /* CONFIG_NET_TCP */ +#endif /* NET_TCP_HAVE_STACK */ /**************************************************************************** * Function: netclose_disconnect @@ -332,7 +333,7 @@ static inline void netclose_txnotify(FAR struct socket *psock, * ****************************************************************************/ -#ifdef CONFIG_NET_TCP +#ifdef NET_TCP_HAVE_STACK static inline int netclose_disconnect(FAR struct socket *psock) { struct tcp_close_s state; @@ -451,7 +452,7 @@ static inline int netclose_disconnect(FAR struct socket *psock) net_unlock(); return ret; } -#endif /* CONFIG_NET_TCP */ +#endif /* NET_TCP_HAVE_STACK */ /**************************************************************************** * Function: local_close @@ -557,6 +558,7 @@ int psock_close(FAR struct socket *psock) else #endif { +#ifdef NET_TCP_HAVE_STACK FAR struct tcp_conn_s *conn = psock->s_conn; /* Is this the last reference to the connection structure @@ -592,6 +594,7 @@ int psock_close(FAR struct socket *psock) conn->crefs--; } +#endif /* NET_TCP_HAVE_STACK */ } #endif /* CONFIG_NET_TCP || CONFIG_NET_LOCAL_STREAM */ } @@ -617,6 +620,7 @@ int psock_close(FAR struct socket *psock) else #endif { +#ifdef NET_UDP_HAVE_STACK FAR struct udp_conn_s *conn = psock->s_conn; /* Is this the last reference to the connection structure @@ -636,6 +640,7 @@ int psock_close(FAR struct socket *psock) conn->crefs--; } +#endif /* NET_UDP_HAVE_STACK */ } #endif /* CONFIG_NET_UDP || CONFIG_NET_LOCAL_DGRAM */ } @@ -668,6 +673,44 @@ int psock_close(FAR struct socket *psock) break; #endif +#ifdef CONFIG_NET_USRSOCK + case SOCK_USRSOCK_TYPE: + { + FAR struct usrsock_conn_s *conn = psock->s_conn; + + /* Is this the last reference to the connection structure (there + * could be more if the socket was dup'ed). + */ + + if (conn->crefs <= 1) + { + /* Yes... inform user-space daemon of socket close. */ + + errcode = usrsock_close(conn); + + /* Free the connection structure */ + + conn->crefs = 0; + usrsock_free(psock->s_conn); + + if (errcode < 0) + { + /* Return with error code, but free resources. */ + + errcode = -errcode; + goto errout_with_psock; + } + } + else + { + /* No.. Just decrement the reference count */ + + conn->crefs--; + } + } + break; +#endif + default: errcode = EBADF; goto errout; @@ -679,7 +722,7 @@ int psock_close(FAR struct socket *psock) sock_release(psock); return OK; -#ifdef CONFIG_NET_TCP +#if defined(NET_TCP_HAVE_STACK) || defined(CONFIG_NET_USRSOCK) errout_with_psock: sock_release(psock); #endif diff --git a/net/socket/net_monitor.c b/net/socket/net_monitor.c index cee6a13cd9..d44a6fe515 100644 --- a/net/socket/net_monitor.c +++ b/net/socket/net_monitor.c @@ -50,6 +50,8 @@ #include "tcp/tcp.h" #include "socket/socket.h" +#ifdef NET_TCP_HAVE_STACK + /**************************************************************************** * Private Function Prototypes ****************************************************************************/ @@ -345,4 +347,6 @@ void net_lostconnection(FAR struct socket *psock, uint16_t flags) net_unlock(); } +#endif /* NET_TCP_HAVE_STACK */ + #endif /* CONFIG_NET && CONFIG_NET_TCP */ diff --git a/net/socket/net_poll.c b/net/socket/net_poll.c index e534e9d022..0fe2b23db1 100644 --- a/net/socket/net_poll.c +++ b/net/socket/net_poll.c @@ -45,6 +45,7 @@ #include "udp/udp.h" #include "local/local.h" #include "socket/socket.h" +#include "usrsock/usrsock.h" #if defined(CONFIG_NET) && !defined(CONFIG_DISABLE_POLL) @@ -57,7 +58,8 @@ */ #undef HAVE_NET_POLL -#if defined(HAVE_TCP_POLL) || defined(HAVE_UDP_POLL) || defined(HAVE_LOCAL_POLL) +#if defined(HAVE_TCP_POLL) || defined(HAVE_UDP_POLL) || \ + defined(HAVE_LOCAL_POLL) || defined(CONFIG_NET_USRSOCK) # define HAVE_NET_POLL 1 #endif @@ -233,6 +235,15 @@ int psock_poll(FAR struct socket *psock, FAR struct pollfd *fds, bool setup) #else int ret; +#ifdef CONFIG_NET_USRSOCK + if (psock->s_type == SOCK_USRSOCK_TYPE) + { + /* Perform usrsock setup/teardown. */ + + return usrsock_poll(psock, fds, setup); + } +#endif + /* Check if we are setting up or tearing down the poll */ if (setup) diff --git a/net/socket/net_sendfile.c b/net/socket/net_sendfile.c index 617bce5397..81f527abe7 100644 --- a/net/socket/net_sendfile.c +++ b/net/socket/net_sendfile.c @@ -72,6 +72,8 @@ #include "tcp/tcp.h" #include "socket/socket.h" +#ifdef NET_TCP_HAVE_STACK + /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ @@ -615,6 +617,21 @@ ssize_t net_sendfile(int outfd, struct file *infile, off_t *offset, goto errout; } +#ifdef CONFIG_NET_USRSOCK + /* If this is a usrsock socket, use generic sendfile implementation. */ + + if (psock->s_type == SOCK_USRSOCK_TYPE) + { + int infd; + + list = sched_getfiles(); + DEBUGASSERT(list != NULL); + + infd = infile - list->fl_files; + return lib_sendfile(outfd, infd, offset, count); + } +#endif /* CONFIG_NET_USRSOCK */ + /* If this is an un-connected socket, then return ENOTCONN */ if (psock->s_type != SOCK_STREAM || !_SS_ISCONNECTED(psock->s_flags)) @@ -776,4 +793,6 @@ errout: } } +#endif /* NET_TCP_HAVE_STACK */ + #endif /* CONFIG_NET && CONFIG_NET_TCP */ diff --git a/net/socket/net_vfcntl.c b/net/socket/net_vfcntl.c index b260edb5b0..79df78379b 100644 --- a/net/socket/net_vfcntl.c +++ b/net/socket/net_vfcntl.c @@ -49,6 +49,7 @@ #include #include #include "socket/socket.h" +#include "usrsock/usrsock.h" #if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0 @@ -164,6 +165,13 @@ int net_vfcntl(int sockfd, int cmd, va_list ap) ret |= O_NONBLOCK; } #endif /* CONFIG_NET_LOCAL || CONFIG_NET_TCP_READAHEAD || CONFIG_NET_UDP_READAHEAD */ + +#ifdef CONFIG_NET_USRSOCK + if (psock->s_type == SOCK_USRSOCK_TYPE && _SS_ISNONBLOCK(psock->s_flags)) + { + ret |= O_NONBLOCK; + } +#endif } break; @@ -178,7 +186,7 @@ int net_vfcntl(int sockfd, int cmd, va_list ap) { #if defined(CONFIG_NET_LOCAL) || defined(CONFIG_NET_TCP_READAHEAD) || \ - defined(CONFIG_NET_UDP_READAHEAD) + defined(CONFIG_NET_UDP_READAHEAD) || defined(CONFIG_NET_USRSOCK) /* Non-blocking is the only configurable option. And it applies * only Unix domain sockets and to read operations on TCP/IP * and UDP/IP sockets when read-ahead is enabled. @@ -213,7 +221,22 @@ int net_vfcntl(int sockfd, int cmd, va_list ap) } else #endif -#endif /* CONFIG_NET_LOCAL || CONFIG_NET_TCP_READAHEAD || CONFIG_NET_UDP_READAHEAD */ +#if defined(CONFIG_NET_USRSOCK) + if (psock->s_type == SOCK_USRSOCK_TYPE) /* usrsock socket */ + { + if ((mode & O_NONBLOCK) != 0) + { + psock->s_flags |= _SF_NONBLOCK; + } + else + { + psock->s_flags &= ~_SF_NONBLOCK; + } + } + else +#endif +#endif /* CONFIG_NET_LOCAL || CONFIG_NET_TCP_READAHEAD || + CONFIG_NET_UDP_READAHEAD || CONFIG_NET_USRSOCK */ { nerr("ERROR: Non-blocking not supported for this socket\n"); } diff --git a/net/socket/recvfrom.c b/net/socket/recvfrom.c index 64789b0672..fc713375cb 100644 --- a/net/socket/recvfrom.c +++ b/net/socket/recvfrom.c @@ -72,6 +72,7 @@ #include "pkt/pkt.h" #include "local/local.h" #include "socket/socket.h" +#include "usrsock/usrsock.h" /**************************************************************************** * Pre-processor Definitions @@ -90,7 +91,8 @@ * Private Types ****************************************************************************/ -#if defined(CONFIG_NET_UDP) || defined(CONFIG_NET_TCP) || defined(CONFIG_NET_PKT) +#if defined(NET_UDP_HAVE_STACK) || defined(NET_TCP_HAVE_STACK) \ + || defined(CONFIG_NET_PKT) struct recvfrom_s { FAR struct socket *rf_sock; /* The parent socket structure */ @@ -106,7 +108,7 @@ struct recvfrom_s ssize_t rf_recvlen; /* The received length */ int rf_result; /* Success:OK, failure:negated errno */ }; -#endif /* CONFIG_NET_UDP || CONFIG_NET_TCP */ +#endif /* NET_UDP_HAVE_STACK || NET_TCP_HAVE_STACK */ /**************************************************************************** * Private Functions @@ -129,7 +131,8 @@ struct recvfrom_s * ****************************************************************************/ -#if defined(CONFIG_NET_UDP) || defined(CONFIG_NET_TCP) || defined(CONFIG_NET_PKT) +#if defined(NET_UDP_HAVE_STACK) || defined(NET_TCP_HAVE_STACK) \ + || defined(CONFIG_NET_PKT) static inline void recvfrom_add_recvlen(FAR struct recvfrom_s *pstate, size_t recvlen) @@ -143,7 +146,7 @@ static inline void recvfrom_add_recvlen(FAR struct recvfrom_s *pstate, pstate->rf_buffer += recvlen; pstate->rf_buflen -= recvlen; } -#endif /* CONFIG_NET_UDP || CONFIG_NET_TCP || CONFIG_NET_PKT */ +#endif /* NET_UDP_HAVE_STACK || NET_TCP_HAVE_STACK || CONFIG_NET_PKT */ /**************************************************************************** * Function: recvfrom_newdata @@ -163,7 +166,7 @@ static inline void recvfrom_add_recvlen(FAR struct recvfrom_s *pstate, * ****************************************************************************/ -#if defined(CONFIG_NET_UDP) || defined(CONFIG_NET_TCP) +#if defined(NET_UDP_HAVE_STACK) || defined(NET_TCP_HAVE_STACK) static size_t recvfrom_newdata(FAR struct net_driver_s *dev, FAR struct recvfrom_s *pstate) { @@ -191,7 +194,7 @@ static size_t recvfrom_newdata(FAR struct net_driver_s *dev, return recvlen; } -#endif /* CONFIG_NET_UDP || CONFIG_NET_TCP */ +#endif /* NET_UDP_HAVE_STACK || NET_TCP_HAVE_STACK */ /**************************************************************************** * Function: recvfrom_newpktdata @@ -255,7 +258,7 @@ static void recvfrom_newpktdata(FAR struct net_driver_s *dev, * ****************************************************************************/ -#ifdef CONFIG_NET_TCP +#ifdef NET_TCP_HAVE_STACK static inline void recvfrom_newtcpdata(FAR struct net_driver_s *dev, FAR struct recvfrom_s *pstate) { @@ -307,7 +310,7 @@ static inline void recvfrom_newtcpdata(FAR struct net_driver_s *dev, dev->d_len = 0; } -#endif /* CONFIG_NET_TCP */ +#endif /* NET_TCP_HAVE_STACK */ /**************************************************************************** * Function: recvfrom_newudpdata @@ -327,7 +330,7 @@ static inline void recvfrom_newtcpdata(FAR struct net_driver_s *dev, * ****************************************************************************/ -#ifdef CONFIG_NET_UDP +#ifdef NET_UDP_HAVE_STACK static inline void recvfrom_newudpdata(FAR struct net_driver_s *dev, FAR struct recvfrom_s *pstate) { @@ -339,7 +342,7 @@ static inline void recvfrom_newudpdata(FAR struct net_driver_s *dev, dev->d_len = 0; } -#endif /* CONFIG_NET_TCP */ +#endif /* NET_UDP_HAVE_STACK */ /**************************************************************************** * Function: recvfrom_tcpreadahead @@ -359,7 +362,7 @@ static inline void recvfrom_newudpdata(FAR struct net_driver_s *dev, * ****************************************************************************/ -#if defined(CONFIG_NET_TCP) && defined(CONFIG_NET_TCP_READAHEAD) +#if defined(NET_TCP_HAVE_STACK) && defined(CONFIG_NET_TCP_READAHEAD) static inline void recvfrom_tcpreadahead(struct recvfrom_s *pstate) { FAR struct tcp_conn_s *conn = (FAR struct tcp_conn_s *)pstate->rf_sock->s_conn; @@ -419,9 +422,9 @@ static inline void recvfrom_tcpreadahead(struct recvfrom_s *pstate) } } } -#endif /* CONFIG_NET_UDP || CONFIG_NET_TCP */ +#endif /* NET_TCP_HAVE_STACK && CONFIG_NET_TCP_READAHEAD */ -#if defined(CONFIG_NET_UDP) && defined(CONFIG_NET_UDP_READAHEAD) +#if defined(NET_UDP_HAVE_STACK) && defined(CONFIG_NET_UDP_READAHEAD) static inline void recvfrom_udpreadahead(struct recvfrom_s *pstate) { @@ -526,7 +529,7 @@ out: * ****************************************************************************/ -#if defined(CONFIG_NET_UDP) || defined(CONFIG_NET_TCP) +#if defined(NET_UDP_HAVE_STACK) || defined(NET_TCP_HAVE_STACK) #ifdef CONFIG_NET_SOCKOPTS static int recvfrom_timeout(struct recvfrom_s *pstate) { @@ -581,7 +584,7 @@ static int recvfrom_timeout(struct recvfrom_s *pstate) return FALSE; } #endif /* CONFIG_NET_SOCKOPTS */ -#endif /* CONFIG_NET_UDP || CONFIG_NET_TCP */ +#endif /* NET_UDP_HAVE_STACK || NET_TCP_HAVE_STACK */ /**************************************************************************** * Function: recvfrom_pktsender @@ -684,7 +687,7 @@ static uint16_t recvfrom_pktinterrupt(FAR struct net_driver_s *dev, * ****************************************************************************/ -#ifdef CONFIG_NET_TCP +#ifdef NET_TCP_HAVE_STACK static inline void recvfrom_tcpsender(FAR struct net_driver_s *dev, FAR struct recvfrom_s *pstate) { @@ -735,7 +738,7 @@ static inline void recvfrom_tcpsender(FAR struct net_driver_s *dev, } #endif /* CONFIG_NET_IPv4 */ } -#endif /* CONFIG_NET_TCP */ +#endif /* NET_TCP_HAVE_STACK */ /**************************************************************************** * Function: recvfrom_tcpinterrupt @@ -757,7 +760,7 @@ static inline void recvfrom_tcpsender(FAR struct net_driver_s *dev, * ****************************************************************************/ -#ifdef CONFIG_NET_TCP +#ifdef NET_TCP_HAVE_STACK static uint16_t recvfrom_tcpinterrupt(FAR struct net_driver_s *dev, FAR void *pvconn, FAR void *pvpriv, uint16_t flags) @@ -958,7 +961,7 @@ static uint16_t recvfrom_tcpinterrupt(FAR struct net_driver_s *dev, return flags; } -#endif /* CONFIG_NET_TCP */ +#endif /* NET_TCP_HAVE_STACK */ /**************************************************************************** * Function: recvfrom_udpsender @@ -978,7 +981,7 @@ static uint16_t recvfrom_tcpinterrupt(FAR struct net_driver_s *dev, * ****************************************************************************/ -#ifdef CONFIG_NET_UDP +#ifdef NET_UDP_HAVE_STACK static inline void recvfrom_udpsender(struct net_driver_s *dev, struct recvfrom_s *pstate) { /* Get the family from the packet type, IP address from the IP header, and @@ -1059,7 +1062,7 @@ static inline void recvfrom_udpsender(struct net_driver_s *dev, struct recvfrom_ } #endif /* CONFIG_NET_IPv4 */ } -#endif /* CONFIG_NET_UDP */ +#endif /* NET_UDP_HAVE_STACK */ /**************************************************************************** * Function: recvfrom_udp_terminate @@ -1076,7 +1079,7 @@ static inline void recvfrom_udpsender(struct net_driver_s *dev, struct recvfrom_ * ****************************************************************************/ -#ifdef CONFIG_NET_UDP +#ifdef NET_UDP_HAVE_STACK static void recvfrom_udp_terminate(FAR struct recvfrom_s *pstate, int result) { /* Don't allow any further UDP call backs. */ @@ -1095,7 +1098,7 @@ static void recvfrom_udp_terminate(FAR struct recvfrom_s *pstate, int result) sem_post(&pstate->rf_sem); } -#endif /* CONFIG_NET_UDP */ +#endif /* NET_UDP_HAVE_STACK */ /**************************************************************************** * Function: recvfrom_udp_interrupt @@ -1117,7 +1120,7 @@ static void recvfrom_udp_terminate(FAR struct recvfrom_s *pstate, int result) * ****************************************************************************/ -#ifdef CONFIG_NET_UDP +#ifdef NET_UDP_HAVE_STACK static uint16_t recvfrom_udp_interrupt(FAR struct net_driver_s *dev, FAR void *pvconn, FAR void *pvpriv, uint16_t flags) @@ -1189,7 +1192,7 @@ static uint16_t recvfrom_udp_interrupt(FAR struct net_driver_s *dev, return flags; } -#endif /* CONFIG_NET_UDP */ +#endif /* NET_UDP_HAVE_STACK */ /**************************************************************************** * Function: recvfrom_init @@ -1210,7 +1213,8 @@ static uint16_t recvfrom_udp_interrupt(FAR struct net_driver_s *dev, * ****************************************************************************/ -#if defined(CONFIG_NET_UDP) || defined(CONFIG_NET_TCP) || defined(CONFIG_NET_PKT) +#if defined(NET_UDP_HAVE_STACK) || defined(NET_TCP_HAVE_STACK) \ + || defined(CONFIG_NET_PKT) static void recvfrom_init(FAR struct socket *psock, FAR void *buf, size_t len, FAR struct sockaddr *infrom, FAR socklen_t *fromlen, @@ -1246,7 +1250,7 @@ static void recvfrom_init(FAR struct socket *psock, FAR void *buf, #define recvfrom_uninit(s) sem_destroy(&(s)->rf_sem) -#endif /* CONFIG_NET_UDP || CONFIG_NET_TCP */ +#endif /* NET_UDP_HAVE_STACK || NET_TCP_HAVE_STACK */ /**************************************************************************** * Function: recvfrom_result @@ -1265,7 +1269,8 @@ static void recvfrom_init(FAR struct socket *psock, FAR void *buf, * ****************************************************************************/ -#if defined(CONFIG_NET_UDP) || defined(CONFIG_NET_TCP) || defined(CONFIG_NET_PKT) +#if defined(NET_UDP_HAVE_STACK) || defined(NET_TCP_HAVE_STACK) \ + || defined(CONFIG_NET_PKT) static ssize_t recvfrom_result(int result, struct recvfrom_s *pstate) { int save_errno = get_errno(); /* In case something we do changes it */ @@ -1294,7 +1299,7 @@ static ssize_t recvfrom_result(int result, struct recvfrom_s *pstate) return pstate->rf_recvlen; } -#endif /* CONFIG_NET_UDP || CONFIG_NET_TCP */ +#endif /* NET_UDP_HAVE_STACK || NET_TCP_HAVE_STACK */ /**************************************************************************** * Function: recvfromo_pkt_rxnotify @@ -1334,7 +1339,7 @@ static void recvfromo_pkt_rxnotify(FAR struct pkt_conn_s *conn) * ****************************************************************************/ -#ifdef CONFIG_NET_UDP +#ifdef NET_UDP_HAVE_STACK static inline void recvfrom_udp_rxnotify(FAR struct socket *psock, FAR struct udp_conn_s *conn) { @@ -1373,7 +1378,7 @@ static inline void recvfrom_udp_rxnotify(FAR struct socket *psock, } #endif /* CONFIG_NET_IPv6 */ } -#endif /* CONFIG_NET_UDP */ +#endif /* NET_UDP_HAVE_STACK */ /**************************************************************************** * Function: pkt_recvfrom @@ -1489,7 +1494,7 @@ errout_with_state: * ****************************************************************************/ -#ifdef CONFIG_NET_UDP +#ifdef NET_UDP_HAVE_STACK static ssize_t udp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len, FAR struct sockaddr *from, FAR socklen_t *fromlen) { @@ -1607,7 +1612,7 @@ errout_with_state: recvfrom_uninit(&state); return ret; } -#endif /* CONFIG_NET_UDP */ +#endif /* NET_UDP_HAVE_STACK */ /**************************************************************************** * Function: tcp_recvfrom @@ -1629,7 +1634,7 @@ errout_with_state: * ****************************************************************************/ -#ifdef CONFIG_NET_TCP +#ifdef NET_TCP_HAVE_STACK static ssize_t tcp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len, FAR struct sockaddr *from, FAR socklen_t *fromlen) { @@ -1785,7 +1790,7 @@ static ssize_t tcp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len, recvfrom_uninit(&state); return (ssize_t)ret; } -#endif /* CONFIG_NET_TCP */ +#endif /* NET_TCP_HAVE_STACK */ /**************************************************************************** * Public Functions @@ -1880,6 +1885,22 @@ ssize_t psock_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len, goto errout; } +#ifdef CONFIG_NET_USRSOCK + if (psock->s_type == SOCK_USRSOCK_TYPE) + { + /* Perform the usrsock recvfrom operation */ + + ret = usrsock_recvfrom(psock, buf, len, from, fromlen); + if (ret < 0) + { + errcode = -ret; + goto errout; + } + + return ret; + } +#endif + /* If a 'from' address has been provided, verify that it is large * enough to hold this address family. */ @@ -1964,7 +1985,11 @@ ssize_t psock_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len, else #endif { +#ifdef NET_TCP_HAVE_STACK ret = tcp_recvfrom(psock, buf, len, from, fromlen); +#else + ret = -ENOSYS; +#endif } #endif /* CONFIG_NET_TCP */ } @@ -1989,7 +2014,11 @@ ssize_t psock_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len, else #endif { +#ifdef NET_UDP_HAVE_STACK ret = udp_recvfrom(psock, buf, len, from, fromlen); +#else + ret = -ENOSYS; +#endif } #endif /* CONFIG_NET_UDP */ } diff --git a/net/socket/send.c b/net/socket/send.c index fd37860a1a..fb50549e86 100644 --- a/net/socket/send.c +++ b/net/socket/send.c @@ -51,6 +51,7 @@ #include "sixlowpan/sixlowpan.h" #include "local/local.h" #include "socket/socket.h" +#include "usrsock/usrsock.h" /**************************************************************************** * Public Functions @@ -168,9 +169,14 @@ ssize_t psock_send(FAR struct socket *psock, FAR const void *buf, size_t len, #ifdef CONFIG_NETDEV_MULTINIC if (ret < 0) { - /* UDP/IP packet send */ + /* TCP/IP packet send */ ret = psock_tcp_send(psock, buf, len); +#ifdef NET_TCP_HAVE_STACK + ret = psock_tcp_send(psock, buf, len); +#else + ret = -ENOSYS; +#endif } #endif /* CONFIG_NETDEV_MULTINIC */ @@ -178,7 +184,11 @@ ssize_t psock_send(FAR struct socket *psock, FAR const void *buf, size_t len, /* Only TCP/IP packet send */ +#ifdef NET_TCP_HAVE_STACK ret = psock_tcp_send(psock, buf, len); +#else + ret = -ENOSYS; +#endif #endif /* CONFIG_NET_6LOWPAN */ } #endif /* CONFIG_NET_TCP */ @@ -216,6 +226,11 @@ ssize_t psock_send(FAR struct socket *psock, FAR const void *buf, size_t len, /* UDP/IP packet send */ ret = psock_udp_send(psock, buf, len); +#ifdef NET_UDP_HAVE_STACK + ret = psock_udp_send(psock, buf, len); +#else + ret = -ENOSYS; +#endif } #endif /* CONFIG_NETDEV_MULTINIC */ @@ -223,7 +238,11 @@ ssize_t psock_send(FAR struct socket *psock, FAR const void *buf, size_t len, /* Only UDP/IP packet send */ +#ifdef NET_UDP_HAVE_STACK ret = psock_udp_send(psock, buf, len); +#else + ret = -ENOSYS; +#endif #endif /* CONFIG_NET_6LOWPAN */ } #endif /* CONFIG_NET_UDP */ @@ -231,6 +250,14 @@ ssize_t psock_send(FAR struct socket *psock, FAR const void *buf, size_t len, break; #endif /* CONFIG_NET_UDP */ +#ifdef CONFIG_NET_USRSOCK + case SOCK_USRSOCK_TYPE: + { + ret = usrsock_sendto(psock, buf, len, NULL, 0); + } + break; +#endif /*CONFIG_NET_USRSOCK*/ + default: { /* EDESTADDRREQ. Signifies that the socket is not connection-mode @@ -243,6 +270,11 @@ ssize_t psock_send(FAR struct socket *psock, FAR const void *buf, size_t len, } leave_cancellation_point(); + if (ret < 0) + { + set_errno(-ret); + ret = ERROR; + } return ret; } diff --git a/net/socket/sendto.c b/net/socket/sendto.c index db51b73c79..eba84f5cea 100644 --- a/net/socket/sendto.c +++ b/net/socket/sendto.c @@ -51,6 +51,7 @@ #include "udp/udp.h" #include "local/local.h" #include "socket/socket.h" +#include "usrsock/usrsock.h" /**************************************************************************** * Public Functions @@ -126,7 +127,8 @@ ssize_t psock_sendto(FAR struct socket *psock, FAR const void *buf, socklen_t tolen) { socklen_t minlen; -#if defined(CONFIG_NET_UDP) || defined(CONFIG_NET_LOCAL_DGRAM) +#if defined(CONFIG_NET_UDP) || defined(CONFIG_NET_LOCAL_DGRAM) || \ + defined(CONFIG_NET_USRSOCK) ssize_t nsent; #endif int errcode; @@ -137,7 +139,8 @@ ssize_t psock_sendto(FAR struct socket *psock, FAR const void *buf, if (!to || !tolen) { -#if defined(CONFIG_NET_TCP) || defined(CONFIG_NET_LOCAL_STREAM) +#if defined(CONFIG_NET_TCP) || defined(CONFIG_NET_LOCAL_STREAM) || \ + defined(CONFIG_NET_USRSOCK) return psock_send(psock, buf, len, flags); #else nerr("ERROR: No 'to' address\n"); @@ -146,6 +149,22 @@ ssize_t psock_sendto(FAR struct socket *psock, FAR const void *buf, #endif } +#ifdef CONFIG_NET_USRSOCK + if (psock->s_type == SOCK_USRSOCK_TYPE) + { + /* Perform the usrsock sendto operation */ + + nsent = usrsock_sendto(psock, buf, len, to, tolen); + if (nsent < 0) + { + errcode = -nsent; + goto errout; + } + + return nsent; + } +#endif + /* Verify that a valid address has been provided */ switch (to->sa_family) @@ -218,7 +237,11 @@ ssize_t psock_sendto(FAR struct socket *psock, FAR const void *buf, else #endif { +#ifdef NET_UDP_HAVE_STACK nsent = psock_udp_sendto(psock, buf, len, flags, to, tolen); +#else + nsent = -ENOSYS; +#endif } #endif /* CONFIG_NET_UDP */ diff --git a/net/socket/setsockopt.c b/net/socket/setsockopt.c index cdcd8d2e85..fd41045f3e 100644 --- a/net/socket/setsockopt.c +++ b/net/socket/setsockopt.c @@ -45,11 +45,14 @@ #include #include #include +#include +#include #include #include #include "socket/socket.h" +#include "usrsock/usrsock.h" #include "utils/utils.h" /**************************************************************************** @@ -115,6 +118,39 @@ int psock_setsockopt(FAR struct socket *psock, int level, int option, goto errout; } +#ifdef CONFIG_NET_USRSOCK + if (psock->s_type == SOCK_USRSOCK_TYPE) + { + FAR struct usrsock_conn_s *conn = psock->s_conn; + int ret; + + DEBUGASSERT(conn); + + /* Some of the socket options are handled from this function. */ + + switch (option) + { + case SO_RCVTIMEO: /* Rx timeouts can be handled at NuttX side, thus + * simplify daemon implementation. */ + case SO_SNDTIMEO: /* Rx timeouts can be handled at NuttX side, thus + * simplify daemon implementation. */ + break; + + default: /* Other options are passed to usrsock daemon. */ + { + ret = usrsock_setsockopt(conn, level, option, value, value_len); + if (ret < 0) + { + errcode = -ret; + goto errout; + } + + return OK; + } + } + } +#endif + /* Process the option */ switch (option) diff --git a/net/socket/socket.c b/net/socket/socket.c index 56f6ddfe9c..04d595a831 100644 --- a/net/socket/socket.c +++ b/net/socket/socket.c @@ -52,6 +52,7 @@ #include "udp/udp.h" #include "pkt/pkt.h" #include "local/local.h" +#include "usrsock/usrsock.h" /**************************************************************************** * Private Functions @@ -65,7 +66,7 @@ * ****************************************************************************/ -#ifdef CONFIG_NET_TCP +#ifdef NET_TCP_HAVE_STACK static int psock_tcp_alloc(FAR struct socket *psock) { /* Allocate the TCP connection structure */ @@ -90,7 +91,7 @@ static int psock_tcp_alloc(FAR struct socket *psock) psock->s_conn = conn; return OK; } -#endif /* CONFIG_NET_TCP */ +#endif /* NET_TCP_HAVE_STACK */ /**************************************************************************** * Name: psock_udp_alloc @@ -100,7 +101,7 @@ static int psock_tcp_alloc(FAR struct socket *psock) * ****************************************************************************/ -#ifdef CONFIG_NET_UDP +#ifdef NET_UDP_HAVE_STACK static int psock_udp_alloc(FAR struct socket *psock) { /* Allocate the UDP connection structure */ @@ -125,7 +126,7 @@ static int psock_udp_alloc(FAR struct socket *psock) psock->s_conn = conn; return OK; } -#endif /* CONFIG_NET_UDP */ +#endif /* NET_UDP_HAVE_STACK */ /**************************************************************************** * Name: psock_pkt_alloc @@ -250,6 +251,47 @@ int psock_socket(int domain, int type, int protocol, FAR struct socket *psock) int ret; int errcode; +#ifdef CONFIG_NET_USRSOCK + switch (domain) + { + default: + break; + + case PF_INET: + case PF_INET6: + { +#ifndef CONFIG_NET_USRSOCK_UDP + if (type == SOCK_DGRAM) + break; +#endif +#ifndef CONFIG_NET_USRSOCK_TCP + if (type == SOCK_STREAM) + break; +#endif + psock->s_type = 0; + psock->s_conn = NULL; + + ret = usrsock_socket(domain, type, protocol, psock); + if (ret >= 0) + { + /* Successfully handled and opened by usrsock daemon. */ + + return OK; + } + else if (ret == -ENETDOWN) + { + /* Net down means that usrsock daemon is not running. + * Attempt to open socket with kernel networking stack. */ + } + else + { + errcode = -ret; + goto errout; + } + } + } +#endif /* CONFIG_NET_USRSOCK */ + /* Only PF_INET, PF_INET6 or PF_PACKET domains supported */ switch (domain) @@ -400,9 +442,13 @@ int psock_socket(int domain, int type, int protocol, FAR struct socket *psock) if (ipdomain) #endif { +#ifdef NET_TCP_HAVE_STACK /* Allocate and attach the TCP connection structure */ ret = psock_tcp_alloc(psock); +#else + ret = -ENETDOWN; +#endif } #endif /* CONFIG_NET_TCP */ @@ -438,9 +484,13 @@ int psock_socket(int domain, int type, int protocol, FAR struct socket *psock) if (ipdomain) #endif { +#ifdef NET_UDP_HAVE_STACK /* Allocate and attach the UDP connection structure */ ret = psock_udp_alloc(psock); +#else + ret = -ENETDOWN; +#endif } #endif /* CONFIG_NET_UDP */ diff --git a/net/socket/socket.h b/net/socket/socket.h index e9bfa161db..4141cf7477 100644 --- a/net/socket/socket.h +++ b/net/socket/socket.h @@ -49,6 +49,7 @@ #include #include +#include "tcp/tcp.h" /**************************************************************************** * Pre-processor Definitions @@ -152,7 +153,7 @@ extern "C" * Public Function Prototypes ****************************************************************************/ -#ifdef CONFIG_NET_TCP +#ifdef NET_TCP_HAVE_STACK struct tcp_conn_s; /* Forward reference */ #endif @@ -243,7 +244,7 @@ FAR struct socket *sockfd_socket(int sockfd); * ****************************************************************************/ -#ifdef CONFIG_NET_TCP +#ifdef NET_TCP_HAVE_STACK int net_startmonitor(FAR struct socket *psock); #endif @@ -265,7 +266,7 @@ int net_startmonitor(FAR struct socket *psock); * ****************************************************************************/ -#ifdef CONFIG_NET_TCP +#ifdef NET_TCP_HAVE_STACK void net_stopmonitor(FAR struct tcp_conn_s *conn); #endif @@ -287,7 +288,7 @@ void net_stopmonitor(FAR struct tcp_conn_s *conn); * ****************************************************************************/ -#ifdef CONFIG_NET_TCP +#ifdef NET_TCP_HAVE_STACK void net_lostconnection(FAR struct socket *psock, uint16_t flags); #endif diff --git a/net/tcp/Kconfig b/net/tcp/Kconfig index 59fa04d018..8ac6aab128 100644 --- a/net/tcp/Kconfig +++ b/net/tcp/Kconfig @@ -9,9 +9,16 @@ config NET_TCP bool "TCP/IP Networking" default n ---help--- - TCP support on or off + Enable or disable TCP networking support. -if NET_TCP +config NET_TCP_NO_STACK + bool "Disable TCP/IP Stack" + default n + select NET_TCP + ---help--- + Build without TCP/IP stack even if TCP networking support enabled. + +if NET_TCP && !NET_TCP_NO_STACK config NET_TCPURGDATA bool "Urgent data" @@ -184,5 +191,5 @@ config NET_SENDFILE Support larger, higher performance sendfile() for transferring files out a TCP connection. -endif # NET_TCP +endif # NET_TCP && !NET_TCP_NO_STACK endmenu # TCP/IP Networking diff --git a/net/tcp/Make.defs b/net/tcp/Make.defs index 520e601f4c..29b6167a65 100644 --- a/net/tcp/Make.defs +++ b/net/tcp/Make.defs @@ -36,6 +36,7 @@ # TCP/IP source files ifeq ($(CONFIG_NET_TCP),y) +ifneq ($(CONFIG_NET_TCP_NO_STACK),y) # Socket layer @@ -73,4 +74,5 @@ endif DEPPATH += --dep-path tcp VPATH += :tcp +endif # !CONFIG_NET_TCP_NO_STACK endif # CONFIG_NET_TCP diff --git a/net/tcp/tcp.h b/net/tcp/tcp.h index c53475d75a..f2a5115e53 100644 --- a/net/tcp/tcp.h +++ b/net/tcp/tcp.h @@ -48,11 +48,14 @@ #include #include -#ifdef CONFIG_NET_TCP +#if defined(CONFIG_NET_TCP) && !defined(CONFIG_NET_TCP_NO_STACK) /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ + +#define NET_TCP_HAVE_STACK 1 + /* Conditions for support TCP poll/select operations */ #if !defined(CONFIG_DISABLE_POLL) && CONFIG_NSOCKET_DESCRIPTORS > 0 && \ @@ -1306,5 +1309,5 @@ int tcp_pollteardown(FAR struct socket *psock, FAR struct pollfd *fds); } #endif -#endif /* CONFIG_NET_TCP */ +#endif /* CONFIG_NET_TCP && !CONFIG_NET_TCP_NO_STACK */ #endif /* _NET_TCP_TCP_H */ diff --git a/net/udp/Kconfig b/net/udp/Kconfig index a32f34534d..2c8e85d70b 100644 --- a/net/udp/Kconfig +++ b/net/udp/Kconfig @@ -12,7 +12,14 @@ config NET_UDP ---help--- Enable or disable UDP networking support. -if NET_UDP +config NET_UDP_NO_STACK + bool "Disable UDP/IP Stack" + default n + select NET_UDP + ---help--- + Build without UDP/IP stack even if UDP networking support enabled. + +if NET_UDP && !NET_UDP_NO_STACK config NET_UDP_CHECKSUMS bool "UDP checksums" @@ -55,5 +62,5 @@ config NET_UDP_READAHEAD default y select NET_IOB -endif # NET_UDP +endif # NET_UDP && !NET_UDP_NO_STACK endmenu # UDP Networking diff --git a/net/udp/Make.defs b/net/udp/Make.defs index 76c72b33ab..4b3992911d 100644 --- a/net/udp/Make.defs +++ b/net/udp/Make.defs @@ -36,6 +36,7 @@ # UDP source files ifeq ($(CONFIG_NET_UDP),y) +ifneq ($(CONFIG_NET_UDP_NO_STACK),y) # Socket layer @@ -57,4 +58,5 @@ NET_CSRCS += udp_callback.c udp_ipselect.c DEPPATH += --dep-path udp VPATH += :udp +endif # !CONFIG_NET_UDP_NO_STACK endif # CONFIG_NET_UDP diff --git a/net/udp/udp.h b/net/udp/udp.h index f8584bff0b..1aac4a8328 100644 --- a/net/udp/udp.h +++ b/net/udp/udp.h @@ -51,11 +51,14 @@ # include #endif -#ifdef CONFIG_NET_UDP +#if defined(CONFIG_NET_UDP) && !defined(CONFIG_NET_UDP_NO_STACK) /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ + +#define NET_UDP_HAVE_STACK 1 + /* Conditions for support UDP poll/select operations */ #if !defined(CONFIG_DISABLE_POLL) && CONFIG_NSOCKET_DESCRIPTORS > 0 && \ @@ -510,5 +513,5 @@ int udp_pollteardown(FAR struct socket *psock, FAR struct pollfd *fds); } #endif -#endif /* CONFIG_NET_UDP */ +#endif /* CONFIG_NET_UDP && !CONFIG_NET_UDP_NO_STACK */ #endif /* __NET_UDP_UDP_H */ diff --git a/net/usrsock/Kconfig b/net/usrsock/Kconfig new file mode 100644 index 0000000000..677200cb67 --- /dev/null +++ b/net/usrsock/Kconfig @@ -0,0 +1,39 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# + +menu "User-space networking stack API" + +config NET_USRSOCK + bool "User-space networking stack API" + default n + depends on NET + ---help--- + Enable or disable user-space networking stack support. + +if NET_USRSOCK + +config NET_USRSOCK_CONNS + int "Number of usrsock connections" + default 6 + ---help--- + Maximum number of usrsock connections (all tasks). + + Note: Usrsock daemon can impose additional restrictions for + maximum number of concurrent connections supported. + +config NET_USRSOCK_UDP + bool "User-space daemon provides UDP sockets" + default n + select NET_UDP + ---help--- + +config NET_USRSOCK_TCP + bool "User-space daemon provides TCP sockets" + default n + select NET_TCP + ---help--- + +endif # NET_USRSOCK +endmenu # User-space networking stack API diff --git a/net/usrsock/Make.defs b/net/usrsock/Make.defs new file mode 100644 index 0000000000..2aa069b077 --- /dev/null +++ b/net/usrsock/Make.defs @@ -0,0 +1,51 @@ +############################################################################ +# net/usrsock/Make.defs +# +# Copyright (C) 2015, 2017 Haltian Ltd. All rights reserved. +# Author: Jussi Kivilinna +# +# 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. +# +############################################################################ + +# User Socket source files + +ifeq ($(CONFIG_NET_USRSOCK),y) + +NET_CSRCS += usrsock_close.c usrsock_conn.c usrsock_bind.c usrsock_connect.c +NET_CSRCS += usrsock_dev.c +NET_CSRCS += usrsock_event.c usrsock_getsockname.c usrsock_getsockopt.c +NET_CSRCS += usrsock_poll.c usrsock_recvfrom.c usrsock_sendto.c +NET_CSRCS += usrsock_setsockopt.c usrsock_socket.c + +# Include User Socket build support + +DEPPATH += --dep-path usrsock +VPATH += :usrsock + +endif # CONFIG_NET_USRSOCK diff --git a/net/usrsock/usrsock.h b/net/usrsock/usrsock.h new file mode 100644 index 0000000000..55d92187e2 --- /dev/null +++ b/net/usrsock/usrsock.h @@ -0,0 +1,553 @@ +/**************************************************************************** + * net/usrsock/usrsock.h + * + * Copyright (C) 2015, 2017 Haltian Ltd. All rights reserved. + * Author: Jussi Kivilinna + * + * 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 __NET_USRSOCK_USRSOCK_H +#define __NET_USRSOCK_USRSOCK_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#ifdef CONFIG_NET_USRSOCK + +#include +#include +#include + +#include "devif/devif.h" +#include "socket/socket.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#ifndef ARRAY_SIZE +# define ARRAY_SIZE(x) (sizeof(x) / sizeof((x)[0])) +#endif + +/* Internal socket type/domain for marking usrsock sockets */ + +#define SOCK_USRSOCK_TYPE 0x7f +#define PF_USRSOCK_DOMAIN 0x7f + +/* Internal event flags */ + +#define USRSOCK_EVENT_REQ_COMPLETE (1 << 14) +#define USRSOCK_EVENT_CONNECT_RESP (1 << 15) +#define USRSOCK_EVENT_INTERNAL_MASK 0xf000U + +/**************************************************************************** + * Public Type Definitions + ****************************************************************************/ + +struct usrsockdev_s; + +enum usrsock_conn_state_e +{ + USRSOCK_CONN_STATE_UNINITIALIZED = 0, + USRSOCK_CONN_STATE_ABORTED, + USRSOCK_CONN_STATE_READY, + USRSOCK_CONN_STATE_CONNECTING, +}; + +struct iovec +{ + FAR void *iov_base; /* Starting address */ + size_t iov_len; /* Number of bytes to transfer */ +}; + +struct usrsock_conn_s +{ + dq_entry_t node; /* Supports a doubly linked list */ + uint8_t crefs; /* Reference counts on this instance */ + + enum usrsock_conn_state_e state; /* State of kernel<->daemon link for conn */ + bool connected; /* Socket has been connected */ + int8_t type; /* Socket type (SOCK_STREAM, etc) */ + int16_t usockid; /* Connection number used for kernel<->daemon */ + uint16_t flags; /* Socket state flags */ + struct usrsockdev_s *dev; /* Device node used for this conn */ + + struct + { + uint8_t xid; /* Expected message exchange id */ + bool inprogress; /* Request was received but daemon is still processing */ + uint16_t valuelen; /* Length of value from daemon */ + uint16_t valuelen_nontrunc; /* Actual length of value at daemon */ + int result; /* Result for request */ + + struct + { + FAR struct iovec *iov; /* Data request input buffers */ + int iovcnt; /* Number of input buffers */ + size_t total; /* Total length of buffers */ + size_t pos; /* Writer position on input buffer */ + } datain; + } resp; + + /* Defines the list of usrsock callbacks */ + + FAR struct devif_callback_s *list; +}; + +struct usrsock_reqstate_s +{ + FAR struct usrsock_conn_s *conn; /* Reference to connection structure */ + FAR struct devif_callback_s *cb; /* Reference to callback instance */ + sem_t recvsem; /* Semaphore signals recv completion */ + int result; /* OK on success, otherwise a negated errno. */ + bool completed; +}; + +struct usrsock_data_reqstate_s +{ + struct usrsock_reqstate_s reqstate; + uint16_t valuelen; + uint16_t valuelen_nontrunc; +}; + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +#ifdef __cplusplus +# define EXTERN extern "C" +extern "C" +{ +#else +# define EXTERN extern +#endif + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Name: usrsock_initialize() + * + * Description: + * Initialize the User Socket connection structures. Called once and only + * from the networking layer. + * + ****************************************************************************/ + +void usrsock_initialize(void); + +/**************************************************************************** + * Name: usrsock_alloc() + * + * Description: + * Allocate a new, uninitialized usrsock connection structure. This is + * normally something done by the implementation of the socket() API + * + ****************************************************************************/ + +FAR struct usrsock_conn_s *usrsock_alloc(void); + +/**************************************************************************** + * Name: usrsock_free() + * + * Description: + * Free a usrsock connection structure that is no longer in use. This should + * be done by the implementation of close(). + * + ****************************************************************************/ + +void usrsock_free(FAR struct usrsock_conn_s *conn); + +/**************************************************************************** + * Name: usrsock_nextconn() + * + * Description: + * Traverse the list of allocated usrsock connections + * + * Assumptions: + * This function is called from usrsock device logic. + * + ****************************************************************************/ + +FAR struct usrsock_conn_s *usrsock_nextconn(FAR struct usrsock_conn_s *conn); + +/**************************************************************************** + * Name: usrsock_connidx() + ****************************************************************************/ + +int usrsock_connidx(FAR struct usrsock_conn_s *conn); + +/**************************************************************************** + * Name: usrsock_active() + * + * Description: + * Find a connection structure that is the appropriate + * connection for usrsock + * + * Assumptions: + * + ****************************************************************************/ + +FAR struct usrsock_conn_s *usrsock_active(int16_t usockid); + +/**************************************************************************** + * Name: usrsock_setup_request_callback() + ****************************************************************************/ + +int usrsock_setup_request_callback(FAR struct usrsock_conn_s *conn, + FAR struct usrsock_reqstate_s *pstate, + FAR devif_callback_event_t event, + uint16_t flags); + +/**************************************************************************** + * Name: usrsock_setup_data_request_callback() + ****************************************************************************/ + +int usrsock_setup_data_request_callback(FAR struct usrsock_conn_s *conn, + FAR struct usrsock_data_reqstate_s *pstate, + FAR devif_callback_event_t event, + uint16_t flags); + +/**************************************************************************** + * Name: usrsock_teardown_request_callback() + ****************************************************************************/ + +void usrsock_teardown_request_callback(FAR struct usrsock_reqstate_s *pstate); + +/**************************************************************************** + * Name: usrsock_teardown_data_request_callback() + ****************************************************************************/ + +#define usrsock_teardown_data_request_callback(datastate) \ + usrsock_teardown_request_callback(&(datastate)->reqstate) + +/**************************************************************************** + * Name: usrsock_event + * + * Description: + * Handler for received connection events + * + ****************************************************************************/ + +int usrsock_event(FAR struct usrsock_conn_s *conn, uint16_t events); + +/**************************************************************************** + * Name: usrsockdev_do_request + ****************************************************************************/ + +int usrsockdev_do_request(FAR struct usrsock_conn_s *conn, + FAR struct iovec *iov, unsigned int iovcnt); + +/**************************************************************************** + * Name: usrsockdev_register + * + * Description: + * Register /dev/usrsock + * + ****************************************************************************/ + +void usrsockdev_register(void); + +/**************************************************************************** + * Name: usrsock_socket + * + * Description: + * socket() creates an endpoint for communication and returns a socket + * structure. + * + * Input Parameters: + * domain (see sys/socket.h) + * type (see sys/socket.h) + * protocol (see sys/socket.h) + * psock A pointer to a user allocated socket structure to be initialized. + * + * Returned Value: + * 0 on success; negative error-code on error + * + * EACCES + * Permission to create a socket of the specified type and/or protocol + * is denied. + * EAFNOSUPPORT + * The implementation does not support the specified address family. + * EINVAL + * Unknown protocol, or protocol family not available. + * EMFILE + * Process file table overflow. + * ENFILE + * The system limit on the total number of open files has been reached. + * ENOBUFS or ENOMEM + * Insufficient memory is available. The socket cannot be created until + * sufficient resources are freed. + * EPROTONOSUPPORT + * The protocol type or the specified protocol is not supported within + * this domain. + * + * Assumptions: + * + ****************************************************************************/ + +int usrsock_socket(int domain, int type, int protocol, FAR struct socket *psock); + +/**************************************************************************** + * Name: usrsock_close + * + * Description: + * Performs the close operation on a usrsock connection instance + * + * Input Parameters: + * conn usrsock connection instance + * + * Returned Value: + * 0 on success; -1 on error with errno set appropriately. + * + * Assumptions: + * + ****************************************************************************/ + +int usrsock_close(FAR struct usrsock_conn_s *conn); + +/**************************************************************************** + * Name: usrsock_bind + * + * Description: + * usrsock_bind() gives the socket 'conn' the local address 'addr'. 'addr' + * is 'addrlen' bytes long. Traditionally, this is called "assigning a name + * to a socket." When a socket is created with socket, it exists in a name + * space (address family) but has no name assigned. + * + * Input Parameters: + * conn usrsock socket connection structure + * addr Socket local address + * addrlen Length of 'addr' + * + * Returned Value: + * 0 on success; -1 on error with errno set appropriately + * + * EACCES + * The address is protected, and the user is not the superuser. + * EADDRINUSE + * The given address is already in use. + * EINVAL + * The socket is already bound to an address. + * ENOTSOCK + * psock is a descriptor for a file, not a socket. + * + * Assumptions: + * + ****************************************************************************/ + +int usrsock_bind(FAR struct usrsock_conn_s *conn, + FAR const struct sockaddr *addr, + socklen_t addrlen); + +/**************************************************************************** + * Name: usrsock_connect + * + * Description: + * Perform a usrsock connection + * + * Input Parameters: + * psock A reference to the socket structure of the socket to be connected + * addr The address of the remote server to connect to + * addrlen Length of address buffer + * + * Returned Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +int usrsock_connect(FAR struct socket *psock, + FAR const struct sockaddr *addr, socklen_t addrlen); + +/**************************************************************************** + * Name: usrsock_poll + * + * Description: + * The standard poll() operation redirects operations on socket descriptors + * to this function. + * + * Input Parameters: + * psock - An instance of the internal socket structure. + * fds - The structure describing the events to be monitored. + * setup - true: Setup up the poll; false: Teardown the poll + * + * Returned Value: + * 0: Success; Negated errno on failure + * + ****************************************************************************/ + +#ifndef CONFIG_DISABLE_POLL +int usrsock_poll(FAR struct socket *psock, FAR struct pollfd *fds, bool setup); +#endif + +/**************************************************************************** + * Name: usrsock_sendto + * + * Description: + * If sendto() is used on a connection-mode (SOCK_STREAM, SOCK_SEQPACKET) + * socket, the parameters to and 'tolen' are ignored (and the error EISCONN + * may be returned when they are not NULL and 0), and the error ENOTCONN is + * returned when the socket was not actually connected. + * + * Input Parameters: + * psock A reference to the socket structure of the socket to be connected + * buf Data to send + * len Length of data to send + * to Address of recipient + * tolen The length of the address structure + * + * Returned Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +ssize_t usrsock_sendto(FAR struct socket *psock, FAR const void *buf, + size_t len, FAR const struct sockaddr *to, + socklen_t tolen); + +/**************************************************************************** + * Name: usrsock_recvfrom + * + * Description: + * recvfrom() receives messages from a socket, and may be used to receive + * data on a socket whether or not it is connection-oriented. + * + * If from is not NULL, and the underlying protocol provides the source + * address, this source address is filled in. The argument fromlen + * initialized to the size of the buffer associated with from, and modified + * on return to indicate the actual size of the address stored there. + * + * Input Parameters: + * psock A pointer to a NuttX-specific, internal socket structure + * buf Buffer to receive data + * len Length of buffer + * flags Receive flags + * from Address of source (may be NULL) + * fromlen The length of the address structure + * + ****************************************************************************/ + +ssize_t usrsock_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len, + FAR struct sockaddr *from, FAR socklen_t *fromlen); + +/**************************************************************************** + * Name: usrsock_getsockopt + * + * Description: + * getsockopt() retrieve thse value for the option specified by the + * 'option' argument for the socket specified by the 'psock' argument. If + * the size of the option value is greater than 'value_len', the value + * stored in the object pointed to by the 'value' argument will be silently + * truncated. Otherwise, the length pointed to by the 'value_len' argument + * will be modified to indicate the actual length of the'value'. + * + * The 'level' argument specifies the protocol level of the option. To + * retrieve options at the socket level, specify the level argument as + * SOL_SOCKET. + * + * See a complete list of values for the 'option' argument. + * + * Input Parameters: + * conn usrsock socket connection structure + * level Protocol level to set the option + * option identifies the option to get + * value Points to the argument value + * value_len The length of the argument value + * + ****************************************************************************/ + +int usrsock_getsockopt(FAR struct usrsock_conn_s *conn, int level, int option, + FAR void *value, FAR socklen_t *value_len); + +/**************************************************************************** + * Name: usrsock_setsockopt + * + * Description: + * psock_setsockopt() sets the option specified by the 'option' argument, + * at the protocol level specified by the 'level' argument, to the value + * pointed to by the 'value' argument for the socket on the 'psock' argument. + * + * The 'level' argument specifies the protocol level of the option. To set + * options at the socket level, specify the level argument as SOL_SOCKET. + * + * See a complete list of values for the 'option' argument. + * + * Input Parameters: + * conn usrsock socket connection structure + * level Protocol level to set the option + * option identifies the option to set + * value Points to the argument value + * value_len The length of the argument value + * + ****************************************************************************/ + +int usrsock_setsockopt(FAR struct usrsock_conn_s *conn, int level, int option, + FAR const void *value, FAR socklen_t value_len); + +/**************************************************************************** + * Name: usrsock_getsockname + * + * Description: + * The getsockname() function retrieves the locally-bound name of the + * specified socket, stores this address in the sockaddr structure pointed + * to by the 'addr' argument, and stores the length of this address in the + * object pointed to by the 'addrlen' argument. + * + * If the actual length of the address is greater than the length of the + * supplied sockaddr structure, the stored address will be truncated. + * + * If the socket has not been bound to a local name, the value stored in + * the object pointed to by address is unspecified. + * + * Input Parameters: + * conn usrsock socket connection structure + * addr sockaddr structure to receive data [out] + * addrlen Length of sockaddr structure [in/out] + * + ****************************************************************************/ + +int usrsock_getsockname(FAR struct usrsock_conn_s *conn, + FAR struct sockaddr *addr, FAR socklen_t *addrlen); + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* CONFIG_NET_USRSOCK */ +#endif /* __NET_USRSOCK_USRSOCK_H */ diff --git a/net/usrsock/usrsock_bind.c b/net/usrsock/usrsock_bind.c new file mode 100644 index 0000000000..8ce21f0762 --- /dev/null +++ b/net/usrsock/usrsock_bind.c @@ -0,0 +1,221 @@ +/**************************************************************************** + * net/usrsock/usrsock_bind.c + * + * Copyright (C) 2015-2017 Haltian Ltd. All rights reserved. + * Author: Jussi Kivilinna + * + * 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 +#if defined(CONFIG_NET) && defined(CONFIG_NET_USRSOCK) + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include + +#include "socket/socket.h" +#include "usrsock/usrsock.h" + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static uint16_t bind_event(FAR struct net_driver_s *dev, FAR void *pvconn, + FAR void *pvpriv, uint16_t flags) +{ + FAR struct usrsock_reqstate_s *pstate = pvpriv; + FAR struct usrsock_conn_s *conn = pvconn; + + if (flags & USRSOCK_EVENT_ABORT) + { + ninfo("socket aborted.\n"); + + pstate->result = -ECONNABORTED; + + /* Stop further callbacks */ + + pstate->cb->flags = 0; + pstate->cb->priv = NULL; + pstate->cb->event = NULL; + + /* Wake up the waiting thread */ + + sem_post(&pstate->recvsem); + } + else if (flags & USRSOCK_EVENT_REQ_COMPLETE) + { + ninfo("request completed.\n"); + + pstate->result = conn->resp.result; + + /* Stop further callbacks */ + + pstate->cb->flags = 0; + pstate->cb->priv = NULL; + pstate->cb->event = NULL; + + /* Wake up the waiting thread */ + + sem_post(&pstate->recvsem); + } + + return flags; +} + +/**************************************************************************** + * Name: do_bind_request + ****************************************************************************/ + +static int do_bind_request(FAR struct usrsock_conn_s *conn, + FAR const struct sockaddr *addr, + socklen_t addrlen) +{ + struct usrsock_request_bind_s req = {}; + struct iovec bufs[2]; + + /* Prepare request for daemon to read. */ + + req.head.reqid = USRSOCK_REQUEST_BIND; + req.usockid = conn->usockid; + req.addrlen = addrlen; + + bufs[0].iov_base = (FAR void *)&req; + bufs[0].iov_len = sizeof(req); + bufs[1].iov_base = (FAR void *)addr; + bufs[1].iov_len = req.addrlen; + + return usrsockdev_do_request(conn, bufs, ARRAY_SIZE(bufs)); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: usrsock_bind + * + * Description: + * usrsock_bind() gives the socket 'conn' the local address 'addr'. 'addr' + * is 'addrlen' bytes long. Traditionally, this is called "assigning a name + * to a socket." When a socket is created with socket, it exists in a name + * space (address family) but has no name assigned. + * + * Parameters: + * conn usrsock socket connection structure + * addr Socket local address + * addrlen Length of 'addr' + * + * Returned Value: + * 0 on success; -1 on error with errno set appropriately + * + * EACCES + * The address is protected, and the user is not the superuser. + * EADDRINUSE + * The given address is already in use. + * EINVAL + * The socket is already bound to an address. + * ENOTSOCK + * psock is a descriptor for a file, not a socket. + * + * Assumptions: + * + ****************************************************************************/ + +int usrsock_bind(FAR struct usrsock_conn_s *conn, + FAR const struct sockaddr *addr, + socklen_t addrlen) +{ + struct usrsock_reqstate_s state = {}; + ssize_t ret; + + DEBUGASSERT(conn); + + net_lock(); + + if (conn->state == USRSOCK_CONN_STATE_UNINITIALIZED || + conn->state == USRSOCK_CONN_STATE_ABORTED) + { + /* Invalid state or closed by daemon. */ + + ninfo("usockid=%d; connect() with uninitialized usrsock.\n", + conn->usockid); + + ret = (conn->state == USRSOCK_CONN_STATE_ABORTED) ? -EPIPE : -ECONNRESET; + goto errout_unlock; + } + + /* Set up event callback for usrsock. */ + + ret = usrsock_setup_request_callback(conn, &state, bind_event, + USRSOCK_EVENT_ABORT | + USRSOCK_EVENT_REQ_COMPLETE); + if (ret < 0) + { + nwarn("usrsock_setup_request_callback failed: %d\n", ret); + goto errout_unlock; + } + + /* Request user-space daemon to close socket. */ + + ret = do_bind_request(conn, addr, addrlen); + if (ret >= 0) + { + /* Wait for completion of request. */ + + while (net_lockedwait(&state.recvsem) != OK) + { + DEBUGASSERT(*get_errno_ptr() == EINTR); + } + + ret = state.result; + } + + usrsock_teardown_request_callback(&state); + +errout_unlock: + net_unlock(); + return ret; +} + +#endif /* CONFIG_NET && CONFIG_NET_USRSOCK */ diff --git a/net/usrsock/usrsock_close.c b/net/usrsock/usrsock_close.c new file mode 100644 index 0000000000..bb6f052732 --- /dev/null +++ b/net/usrsock/usrsock_close.c @@ -0,0 +1,205 @@ +/**************************************************************************** + * net/usrsock/usrsock_close.c + * + * Copyright (C) 2015, 2017 Haltian Ltd. All rights reserved. + * Author: Jussi Kivilinna + * + * 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 +#if defined(CONFIG_NET) && defined(CONFIG_NET_USRSOCK) + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include + +#include "usrsock/usrsock.h" + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static uint16_t close_event(FAR struct net_driver_s *dev, FAR void *pvconn, + FAR void *pvpriv, uint16_t flags) +{ + FAR struct usrsock_reqstate_s *pstate = pvpriv; + FAR struct usrsock_conn_s *conn = pvconn; + + if (flags & USRSOCK_EVENT_ABORT) + { + ninfo("socket aborted.\n"); + + conn->state = USRSOCK_CONN_STATE_ABORTED; + pstate->result = -ECONNABORTED; + + /* Stop further callbacks */ + + pstate->cb->flags = 0; + pstate->cb->priv = NULL; + pstate->cb->event = NULL; + + /* Wake up the waiting thread */ + + sem_post(&pstate->recvsem); + } + else if (flags & USRSOCK_EVENT_REQ_COMPLETE) + { + ninfo("request completed.\n"); + + pstate->result = conn->resp.result; + + /* Stop further callbacks */ + + pstate->cb->flags = 0; + pstate->cb->priv = NULL; + pstate->cb->event = NULL; + + /* Wake up the waiting thread */ + + sem_post(&pstate->recvsem); + } + + return flags; +} + +/**************************************************************************** + * Name: do_close_request + ****************************************************************************/ + +static int do_close_request(FAR struct usrsock_conn_s *conn) +{ + struct usrsock_request_close_s req = {}; + struct iovec bufs[1]; + + /* Prepare request for daemon to read. */ + + req.head.reqid = USRSOCK_REQUEST_CLOSE; + req.usockid = conn->usockid; + + bufs[0].iov_base = (FAR void *)&req; + bufs[0].iov_len = sizeof(req); + + return usrsockdev_do_request(conn, bufs, ARRAY_SIZE(bufs)); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: usrsock_close + * + * Description: + * + ****************************************************************************/ + +int usrsock_close(FAR struct usrsock_conn_s *conn) +{ + struct usrsock_reqstate_s state = {}; + int ret; + + net_lock(); + + if (conn->state == USRSOCK_CONN_STATE_UNINITIALIZED || + conn->state == USRSOCK_CONN_STATE_ABORTED) + { + /* Already closed? */ + + ninfo("usockid=%d; already closed.\n", conn->usockid); + + ret = OK; + goto close_out; + } + + /* Set up event callback for usrsock. */ + + ret = usrsock_setup_request_callback(conn, &state, close_event, + USRSOCK_EVENT_ABORT | + USRSOCK_EVENT_REQ_COMPLETE); + if (ret < 0) + { + nwarn("usrsock_setup_request_callback failed: %d\n", ret); + goto errout; + } + + /* Request user-space daemon to close socket. */ + + ret = do_close_request(conn); + if (ret < 0) + { + ret = OK; /* Error? return OK for close. */ + } + else + { + /* Wait for completion of request. */ + + while (net_lockedwait(&state.recvsem) != OK) + { + DEBUGASSERT(*get_errno_ptr() == EINTR); + } + + ret = state.result; + if (ret < 0) + { + /* TODO: Error handling for close? Mark closed anyway? There is not + * much we can do if this happens. + */ + ninfo("user-space daemon reported error %d for usockid=%d\n", + state.result, conn->usockid); + + ret = OK; + } + } + + usrsock_teardown_request_callback(&state); + +close_out: + conn->state = USRSOCK_CONN_STATE_UNINITIALIZED; + conn->usockid = -1; + +errout: + net_unlock(); + return ret; +} + +#endif /* CONFIG_NET && CONFIG_NET_USRSOCK */ diff --git a/net/usrsock/usrsock_conn.c b/net/usrsock/usrsock_conn.c new file mode 100644 index 0000000000..0b02276246 --- /dev/null +++ b/net/usrsock/usrsock_conn.c @@ -0,0 +1,347 @@ +/**************************************************************************** + * net/usrsock/usrsock_conn.c + * + * Copyright (C) 2015, 2017 Haltian Ltd. All rights reserved. + * Author: Jussi Kivilinna + * + * 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 +#if defined(CONFIG_NET) && defined(CONFIG_NET_USRSOCK) + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include + +#include "usrsock/usrsock.h" + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* The array containing all usrsock connections. */ + +struct usrsock_conn_s g_usrsock_connections[CONFIG_NET_USRSOCK_CONNS]; + +/* A list of all free usrsock connections */ + +static dq_queue_t g_free_usrsock_connections; +static sem_t g_free_sem; + +/* A list of all allocated usrsock connections */ + +static dq_queue_t g_active_usrsock_connections; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: _usrsock_semtake() and _usrsock_semgive() + * + * Description: + * Take/give semaphore + * + ****************************************************************************/ + +static void _usrsock_semtake(FAR sem_t *sem) +{ + /* Take the semaphore (perhaps waiting) */ + + while (net_lockedwait(sem) != 0) + { + /* The only case that an error should occur here is if + * the wait was awakened by a signal. + */ + + DEBUGASSERT(*get_errno_ptr() == EINTR); + } +} + +static void _usrsock_semgive(FAR sem_t *sem) +{ + (void)sem_post(sem); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: usrsock_alloc() + * + * Description: + * Allocate a new, uninitialized usrsock connection structure. This is + * normally something done by the implementation of the socket() API + * + ****************************************************************************/ + +FAR struct usrsock_conn_s *usrsock_alloc(void) +{ + FAR struct usrsock_conn_s *conn; + + /* The free list is only accessed from user, non-interrupt level and + * is protected by a semaphore (that behaves like a mutex). + */ + + _usrsock_semtake(&g_free_sem); + conn = (FAR struct usrsock_conn_s *)dq_remfirst(&g_free_usrsock_connections); + if (conn) + { + /* Make sure that the connection is marked as uninitialized */ + + memset(conn, 0, sizeof(*conn)); + conn->dev = NULL; + conn->usockid = -1; + conn->state = USRSOCK_CONN_STATE_UNINITIALIZED; + conn->list = NULL; + conn->connected = false; + + /* Enqueue the connection into the active list */ + + dq_addlast(&conn->node, &g_active_usrsock_connections); + } + + _usrsock_semgive(&g_free_sem); + return conn; +} + +/**************************************************************************** + * Name: usrsock_free() + * + * Description: + * Free a usrsock connection structure that is no longer in use. This should + * be done by the implementation of close(). + * + ****************************************************************************/ + +void usrsock_free(FAR struct usrsock_conn_s *conn) +{ + /* The free list is only accessed from user, non-interrupt level and + * is protected by a semaphore (that behaves like a mutex). + */ + + DEBUGASSERT(conn->crefs == 0); + + _usrsock_semtake(&g_free_sem); + + /* Remove the connection from the active list */ + + dq_rem(&conn->node, &g_active_usrsock_connections); + + /* Reset structure */ + + memset(conn, 0, sizeof(*conn)); + conn->dev = NULL; + conn->usockid = -1; + conn->state = USRSOCK_CONN_STATE_UNINITIALIZED; + conn->list = NULL; + + /* Free the connection */ + + dq_addlast(&conn->node, &g_free_usrsock_connections); + _usrsock_semgive(&g_free_sem); +} + +/**************************************************************************** + * Name: usrsock_nextconn() + * + * Description: + * Traverse the list of allocated usrsock connections + * + * Assumptions: + * This function is called from usrsock device logic. + * + ****************************************************************************/ + +FAR struct usrsock_conn_s *usrsock_nextconn(FAR struct usrsock_conn_s *conn) +{ + if (!conn) + { + return (FAR struct usrsock_conn_s *)g_active_usrsock_connections.head; + } + else + { + return (FAR struct usrsock_conn_s *)conn->node.flink; + } +} + +/**************************************************************************** + * Name: usrsock_connidx() + ****************************************************************************/ + +int usrsock_connidx(FAR struct usrsock_conn_s *conn) +{ + int idx = conn - g_usrsock_connections; + + DEBUGASSERT(idx >= 0); + DEBUGASSERT(idx < ARRAY_SIZE(g_usrsock_connections)); + + return idx; +} + +/**************************************************************************** + * Name: usrsock_active() + * + * Description: + * Find a connection structure that is the appropriate + * connection for usrsock + * + * Assumptions: + * + ****************************************************************************/ + +FAR struct usrsock_conn_s *usrsock_active(int16_t usockid) +{ + FAR struct usrsock_conn_s *conn = NULL; + + while ((conn = usrsock_nextconn(conn)) != NULL) + { + if (conn->usockid == usockid) + return conn; + } + + return NULL; +} + +/**************************************************************************** + * Name: usrsock_setup_request_callback() + ****************************************************************************/ + +int usrsock_setup_request_callback(FAR struct usrsock_conn_s *conn, + FAR struct usrsock_reqstate_s *pstate, + FAR devif_callback_event_t event, + uint16_t flags) +{ + int ret = -EBUSY; + + (void)sem_init(&pstate->recvsem, 0, 0); + pstate->conn = conn; + pstate->result = -EAGAIN; + pstate->completed = false; + + /* Set up the callback in the connection */ + + pstate->cb = devif_callback_alloc(NULL, &conn->list); + if (pstate->cb) + { + /* Set up the connection "interrupt" handler */ + + pstate->cb->flags = flags; + pstate->cb->priv = (FAR void *)pstate; + pstate->cb->event = event; + + ret = OK; + } + + return ret; +} + +/**************************************************************************** + * Name: usrsock_setup_data_request_callback() + ****************************************************************************/ + +int usrsock_setup_data_request_callback(FAR struct usrsock_conn_s *conn, + FAR struct usrsock_data_reqstate_s *pstate, + FAR devif_callback_event_t event, + uint16_t flags) +{ + pstate->valuelen = 0; + pstate->valuelen_nontrunc = 0; + return usrsock_setup_request_callback(conn, &pstate->reqstate, event, flags); +} + +/**************************************************************************** + * Name: usrsock_teardown_request_callback() + ****************************************************************************/ + +void usrsock_teardown_request_callback(FAR struct usrsock_reqstate_s *pstate) +{ + FAR struct usrsock_conn_s *conn = pstate->conn; + + /* Make sure that no further events are processed */ + + devif_conn_callback_free(NULL, pstate->cb, &conn->list); + + pstate->cb = NULL; +} + +/**************************************************************************** + * Name: usrsock_initialize() + * + * Description: + * Initialize the User Socket connection structures. Called once and only + * from the networking layer. + * + ****************************************************************************/ + +void usrsock_initialize(void) +{ + int i; + + /* Initialize the queues */ + + dq_init(&g_free_usrsock_connections); + dq_init(&g_active_usrsock_connections); + sem_init(&g_free_sem, 0, 1); + + for (i = 0; i < CONFIG_NET_USRSOCK_CONNS; i++) + { + FAR struct usrsock_conn_s *conn = &g_usrsock_connections[i]; + + /* Mark the connection closed and move it to the free list */ + + memset(conn, 0, sizeof(*conn)); + conn->dev = NULL; + conn->usockid = -1; + conn->state = USRSOCK_CONN_STATE_UNINITIALIZED; + conn->list = NULL; + conn->flags = 0; + dq_addlast(&conn->node, &g_free_usrsock_connections); + } + + /* Register /dev/usrsock character device. */ + + usrsockdev_register(); +} + +#endif /* CONFIG_NET && CONFIG_NET_USRSOCK */ diff --git a/net/usrsock/usrsock_connect.c b/net/usrsock/usrsock_connect.c new file mode 100644 index 0000000000..45ed8c1dd6 --- /dev/null +++ b/net/usrsock/usrsock_connect.c @@ -0,0 +1,257 @@ +/**************************************************************************** + * net/usrsock/usrsock_connect.c + * + * Copyright (C) 2015, 2017 Haltian Ltd. All rights reserved. + * Author: Jussi Kivilinna + * + * 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 +#if defined(CONFIG_NET) && defined(CONFIG_NET_USRSOCK) + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include + +#include "socket/socket.h" +#include "usrsock/usrsock.h" + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static uint16_t connect_event(FAR struct net_driver_s *dev, FAR void *pvconn, + FAR void *pvpriv, uint16_t flags) +{ + FAR struct usrsock_reqstate_s *pstate = pvpriv; + FAR struct usrsock_conn_s *conn = pvconn; + + if (flags & USRSOCK_EVENT_ABORT) + { + ninfo("socket aborted.\n"); + + pstate->result = -ECONNABORTED; + + /* Stop further callbacks */ + + pstate->cb->flags = 0; + pstate->cb->priv = NULL; + pstate->cb->event = NULL; + + /* Wake up the waiting thread */ + + sem_post(&pstate->recvsem); + } + else if (flags & USRSOCK_EVENT_REQ_COMPLETE) + { + ninfo("request completed.\n"); + + pstate->result = conn->resp.result; + + /* Stop further callbacks */ + + pstate->cb->flags = 0; + pstate->cb->priv = NULL; + pstate->cb->event = NULL; + + /* Wake up the waiting thread */ + + sem_post(&pstate->recvsem); + } + + return flags; +} + +/**************************************************************************** + * Name: do_connect_request + ****************************************************************************/ + +static int do_connect_request(FAR struct usrsock_conn_s *conn, + FAR const struct sockaddr *addr, + socklen_t addrlen) +{ + struct usrsock_request_connect_s req = {}; + struct iovec bufs[2]; + + if (addrlen > UINT16_MAX) + { + addrlen = UINT16_MAX; + } + + /* Prepare request for daemon to read. */ + + req.head.reqid = USRSOCK_REQUEST_CONNECT; + req.usockid = conn->usockid; + req.addrlen = addrlen; + + bufs[0].iov_base = (FAR void *)&req; + bufs[0].iov_len = sizeof(req); + bufs[1].iov_base = (FAR void *)addr; + bufs[1].iov_len = addrlen; + + return usrsockdev_do_request(conn, bufs, ARRAY_SIZE(bufs)); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: usrsock_connect + * + * Description: + * Perform a usrsock connection + * + * Parameters: + * psock - A reference to the socket structure of the socket to be connected + * addr The address of the remote server to connect to + * addrlen Length of address buffer + * + * Returned Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +int usrsock_connect(FAR struct socket *psock, + FAR const struct sockaddr *addr, socklen_t addrlen) +{ + FAR struct usrsock_conn_s *conn = psock->s_conn; + struct usrsock_reqstate_s state = {}; + int ret; + + DEBUGASSERT(conn); + + net_lock(); + + if (conn->state == USRSOCK_CONN_STATE_UNINITIALIZED || + conn->state == USRSOCK_CONN_STATE_ABORTED) + { + /* Invalid state or closed by daemon. */ + + ninfo("usockid=%d; connect() with uninitialized usrsock.\n", + conn->usockid); + + ret = (conn->state == USRSOCK_CONN_STATE_ABORTED) ? -EPIPE : -ECONNREFUSED; + goto errout_unlock; + } + + if (conn->connected && + (conn->type == SOCK_STREAM || conn->type == SOCK_SEQPACKET)) + { + /* Already connected. */ + + ret = -EISCONN; + goto errout_unlock; + } + + if (conn->state == USRSOCK_CONN_STATE_CONNECTING) + { + /* Already connecting. */ + + ninfo("usockid=%d; socket already connecting.\n", + conn->usockid); + + ret = -EALREADY; + goto errout_unlock; + } + + /* Set up event callback for usrsock. */ + + ret = usrsock_setup_request_callback(conn, &state, connect_event, + USRSOCK_EVENT_ABORT | + USRSOCK_EVENT_REQ_COMPLETE); + if (ret < 0) + { + nwarn("usrsock_setup_request_callback failed: %d\n", ret); + + goto errout_unlock; + } + + /* Mark conn as connecting one. */ + + conn->state = USRSOCK_CONN_STATE_CONNECTING; + + /* Send request. */ + + ret = do_connect_request(conn, addr, addrlen); + if (ret < 0) + { + goto errout_teardown; + } + + /* Do not block on waiting for request completion if nonblocking socket. */ + + if (!conn->resp.inprogress || !_SS_ISNONBLOCK(psock->s_flags)) + { + /* Wait for completion of request (or signal). */ + + if (net_lockedwait(&state.recvsem) != OK) + { + DEBUGASSERT(*get_errno_ptr() == EINTR); + + /* Wait interrupted, exit early. */ + + ret = -EINTR; + goto errout_teardown; + } + + ret = state.result; + } + else + { + /* Request not completed and socket is non-blocking. */ + + ret = -EINPROGRESS; + } + +errout_teardown: + usrsock_teardown_request_callback(&state); +errout_unlock: + net_unlock(); + return ret; +} + +#endif /* CONFIG_NET && CONFIG_NET_USRSOCK */ diff --git a/net/usrsock/usrsock_dev.c b/net/usrsock/usrsock_dev.c new file mode 100644 index 0000000000..11b915e0d8 --- /dev/null +++ b/net/usrsock/usrsock_dev.c @@ -0,0 +1,1271 @@ +/**************************************************************************** + * net/usrsock/usrsock_dev.c + * + * Copyright (C) 2015-2017 Haltian Ltd. All rights reserved. + * Author: Jussi Kivilinna + * + * 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 +#if defined(CONFIG_NET) && defined(CONFIG_NET_USRSOCK) + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include + +#include "devif/devif.h" +#include "usrsock/usrsock.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +#ifndef CONFIG_NET_USRSOCKDEV_NPOLLWAITERS +# define CONFIG_NET_USRSOCKDEV_NPOLLWAITERS 1 +#endif + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct usrsockdev_s +{ + sem_t devsem; /* Lock for device node */ + uint8_t ocount; /* The number of times the device has been opened */ + + struct + { + FAR const struct iovec *iov; /* Pending request buffers */ + int iovcnt; /* Number of request buffers */ + size_t pos; /* Reader position on request buffer */ + sem_t sem; /* Request semaphore (only one outstanding + * request) */ + sem_t acksem; /* Request acknowledgment notification */ + uint8_t ack_xid; /* Exchange id for which waiting ack */ + uint16_t nbusy; /* Number of requests blocked from different + threads */ + } req; + + FAR struct usrsock_conn_s *datain_conn; /* Connection instance to receive + * data buffers. */ + +#ifndef CONFIG_DISABLE_POLL + struct pollfd *pollfds[CONFIG_NET_USRSOCKDEV_NPOLLWAITERS]; +#endif +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* Character driver methods */ + +static ssize_t usrsockdev_read(FAR struct file *filep, FAR char *buffer, + size_t len); + +static ssize_t usrsockdev_write(FAR struct file *filep, + FAR const char *buffer, size_t len); + +static off_t usrsockdev_seek(FAR struct file *filep, off_t offset, + int whence); + +static int usrsockdev_open(FAR struct file *filep); + +static int usrsockdev_close(FAR struct file *filep); + +#ifndef CONFIG_DISABLE_POLL +static int usrsockdev_poll(FAR struct file *filep, FAR struct pollfd *fds, + bool setup); +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const struct file_operations g_usrsockdevops = +{ + usrsockdev_open, /* open */ + usrsockdev_close, /* close */ + usrsockdev_read, /* read */ + usrsockdev_write, /* write */ + usrsockdev_seek, /* seek */ + NULL /* ioctl */ +#ifndef CONFIG_DISABLE_POLL + , usrsockdev_poll /* poll */ +#endif +#ifndef CONFIG_DISABLE_PSEUDOFS_OPERATIONS + , NULL /* unlink */ +#endif +}; + +static struct usrsockdev_s g_usrsockdev; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: iovec_do() - copy to/from iovec from/to buffer. + ****************************************************************************/ + +static ssize_t iovec_do(FAR void *srcdst, size_t srcdstlen, + FAR struct iovec *iov, int iovcnt, size_t pos, + bool from_iov) +{ + ssize_t total; + size_t srclen; + FAR uint8_t *ioout = srcdst; + FAR uint8_t *iovbuf; + + /* Rewind to correct position. */ + + while (pos > 0 && iovcnt > 0) + { + if (iov->iov_len <= pos) + { + pos -= iov->iov_len; + iov++; + iovcnt--; + } + else + { + break; + } + } + + if (iovcnt == 0) + { + /* Position beyond iovec. */ + + return -1; + } + + iovbuf = iov->iov_base; + srclen = iov->iov_len; + iovbuf += pos; + srclen -= pos; + iov++; + iovcnt--; + total = 0; + + while ((srclen > 0 || iovcnt > 0) && srcdstlen > 0) + { + size_t clen = srclen; + + if (srclen == 0) + { + /* Skip empty iovec. */ + + iovbuf = iov->iov_base; + srclen = iov->iov_len; + iov++; + iovcnt--; + + continue; + } + + if (clen > srcdstlen) + { + clen = srcdstlen; + } + + if (from_iov) + { + memmove(ioout, iovbuf, clen); + } + else + { + memmove(iovbuf, ioout, clen); + } + + ioout += clen; + srcdstlen -= clen; + iovbuf += clen; + srclen -= clen; + total += clen; + + if (srclen == 0) + { + if (iovcnt == 0) + { + break; + } + + iovbuf = iov->iov_base; + srclen = iov->iov_len; + iov++; + iovcnt--; + } + } + + return total; +} + +/**************************************************************************** + * Name: iovec_get() - copy from iovec to buffer. + ****************************************************************************/ + +static ssize_t iovec_get(FAR void *dst, size_t dstlen, + FAR const struct iovec *iov, int iovcnt, size_t pos) +{ + return iovec_do(dst, dstlen, (FAR struct iovec *)iov, iovcnt, pos, true); +} + +/**************************************************************************** + * Name: iovec_put() - copy to iovec from buffer. + ****************************************************************************/ + +static ssize_t iovec_put(FAR struct iovec *iov, int iovcnt, size_t pos, + FAR const void *src, size_t srclen) +{ + return iovec_do((FAR void *)src, srclen, iov, iovcnt, pos, false); +} + +/**************************************************************************** + * Name: usrsockdev_get_xid() + ****************************************************************************/ + +static uint8_t usrsockdev_get_xid(FAR struct usrsock_conn_s *conn) +{ + int conn_idx; + +#if CONFIG_NET_USRSOCK_CONNS > 255 +# error "CONFIG_NET_USRSOCK_CONNS too large (over 255)" +#endif + + /* Each connection can one only one request/response pending. So map + * connection structure index to xid value. */ + + conn_idx = usrsock_connidx(conn); + + DEBUGASSERT(1 <= conn_idx + 1); + DEBUGASSERT(conn_idx + 1 <= UINT8_MAX); + + return conn_idx + 1; +} + +/**************************************************************************** + * Name: usrsockdev_semtake() and usrsockdev_semgive() + * + * Description: + * Take/give semaphore + * + ****************************************************************************/ + +static void usrsockdev_semtake(FAR sem_t *sem) +{ + /* Take the semaphore (perhaps waiting) */ + + while (sem_wait(sem) != 0) + { + /* The only case that an error should occur here is if + * the wait was awakened by a signal. + */ + + DEBUGASSERT(*get_errno_ptr() == EINTR); + } +} + +static void usrsockdev_semgive(FAR sem_t *sem) +{ + (void)sem_post(sem); +} + +/**************************************************************************** + * Name: usrsockdev_is_opened + ****************************************************************************/ + +static bool usrsockdev_is_opened(FAR struct usrsockdev_s *dev) +{ + bool ret = true; + + if (dev->ocount == 0) + { + ret = false; /* No usrsock daemon running. */ + } + + return ret; +} + +/**************************************************************************** + * Name: usrsockdev_pollnotify + ****************************************************************************/ + +static void usrsockdev_pollnotify(FAR struct usrsockdev_s *dev, pollevent_t eventset) +{ +#ifndef CONFIG_DISABLE_POLL + int i; + for (i = 0; i < ARRAY_SIZE(dev->pollfds); i++) + { + struct pollfd *fds = dev->pollfds[i]; + if (fds) + { + fds->revents |= (fds->events & eventset); + if (fds->revents != 0) + { + ninfo("Report events: %02x\n", fds->revents); + sem_post(fds->sem); + } + } + } +#endif +} + +/**************************************************************************** + * Name: usrsockdev_read + ****************************************************************************/ + +static ssize_t usrsockdev_read(FAR struct file *filep, FAR char *buffer, + size_t len) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct usrsockdev_s *dev; + + if (len == 0) + { + return 0; + } + + if (buffer == NULL) + { + return -EINVAL; + } + + DEBUGASSERT(inode); + + dev = inode->i_private; + + DEBUGASSERT(dev); + + usrsockdev_semtake(&dev->devsem); + net_lock(); + + /* Is request available? */ + + if (dev->req.iov) + { + ssize_t rlen; + + /* Copy request to user-space. */ + + rlen = iovec_get(buffer, len, dev->req.iov, dev->req.iovcnt, + dev->req.pos); + if (rlen < 0) + { + /* Tried reading beyond buffer. */ + + len = 0; + } + else + { + dev->req.pos += rlen; + len = rlen; + } + } + else + { + len = 0; + } + + net_unlock(); + usrsockdev_semgive(&dev->devsem); + + return len; +} + +/**************************************************************************** + * Name: usrsockdev_seek + ****************************************************************************/ + +static off_t usrsockdev_seek(FAR struct file *filep, off_t offset, int whence) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct usrsockdev_s *dev; + off_t pos; + + if (whence != SEEK_CUR && whence != SEEK_SET) + { + return -EINVAL; + } + + DEBUGASSERT(inode); + + dev = inode->i_private; + + DEBUGASSERT(dev); + + usrsockdev_semtake(&dev->devsem); + net_lock(); + + /* Is request available? */ + + if (dev->req.iov) + { + ssize_t rlen; + + if (whence == SEEK_CUR) + { + pos = dev->req.pos + offset; + } + else if (whence == SEEK_SET) + { + pos = offset; + } + + /* Copy request to user-space. */ + + rlen = iovec_get(NULL, 0, dev->req.iov, dev->req.iovcnt, pos); + if (rlen < 0) + { + /* Tried seek beyond buffer. */ + + pos = -EINVAL; + } + else + { + dev->req.pos = pos; + } + } + else + { + pos = 0; + } + + net_unlock(); + usrsockdev_semgive(&dev->devsem); + + return pos; +} + +/**************************************************************************** + * Name: usrsockdev_handle_event + ****************************************************************************/ + +static ssize_t usrsockdev_handle_event(FAR struct usrsockdev_s *dev, + FAR const void *buffer, + size_t len) +{ + FAR const struct usrsock_message_common_s *common = buffer; + + switch (common->msgid) + { + case USRSOCK_MESSAGE_SOCKET_EVENT: + { + FAR const struct usrsock_message_socket_event_s *hdr = buffer; + FAR struct usrsock_conn_s *conn; + int ret; + + if (len < sizeof(*hdr)) + { + nwarn("message too short, %d < %d.\n", len, sizeof(*hdr)); + + return -EINVAL; + } + + /* Get corresponding usrsock connection. */ + + conn = usrsock_active(hdr->usockid); + if (!conn) + { + nwarn("no active connection for usockid=%d.\n", hdr->usockid); + + return -ENOENT; + } + +#ifdef CONFIG_DEV_RANDOM + /* Add randomness. */ + + add_sw_randomness((hdr->events << 16) - hdr->usockid); +#endif + + /* Handle event. */ + + ret = usrsock_event(conn, hdr->events & ~USRSOCK_EVENT_INTERNAL_MASK); + if (ret < 0) + { + return ret; + } + + len = sizeof(*hdr); + } + break; + + default: + nwarn("Unknown event type: %d\n", common->msgid); + return -EINVAL; + } + + return len; +} + +/**************************************************************************** + * Name: usrsockdev_handle_response + ****************************************************************************/ + +static ssize_t usrsockdev_handle_response(FAR struct usrsockdev_s *dev, + FAR struct usrsock_conn_s *conn, + FAR const void *buffer) +{ + FAR const struct usrsock_message_req_ack_s *hdr = buffer; + + if (USRSOCK_MESSAGE_REQ_IN_PROGRESS(hdr->head.flags)) + { + /* In-progress response is acknowledgment that response was + * received. */ + + conn->resp.inprogress = true; + } + else + { + conn->resp.inprogress = false; + conn->resp.xid = 0; + + /* Get result for common request. */ + + conn->resp.result = hdr->result; + + /* Done with request/response. */ + + (void)usrsock_event(conn, USRSOCK_EVENT_REQ_COMPLETE); + } + + return sizeof(*hdr); +} + +/**************************************************************************** + * Name: usrsockdev_handle_datareq_response + ****************************************************************************/ + +static ssize_t +usrsockdev_handle_datareq_response(FAR struct usrsockdev_s *dev, + FAR struct usrsock_conn_s *conn, + FAR const void *buffer) +{ + FAR const struct usrsock_message_datareq_ack_s *datahdr = buffer; + FAR const struct usrsock_message_req_ack_s *hdr = &datahdr->reqack; + int num_inbufs, iovpos; + ssize_t ret; + + if (USRSOCK_MESSAGE_REQ_IN_PROGRESS(hdr->head.flags)) + { + if (datahdr->reqack.result > 0) + { + ninfo("error: request in progress, and result > 0.\n"); + ret = -EINVAL; + goto unlock_out; + } + else if (datahdr->valuelen > 0) + { + ninfo("error: request in progress, and valuelen > 0.\n"); + ret = -EINVAL; + goto unlock_out; + } + + /* In-progress response is acknowledgment that response was + * received. */ + + conn->resp.inprogress = true; + + ret = sizeof(*datahdr); + goto unlock_out; + } + + conn->resp.inprogress = false; + conn->resp.xid = 0; + + /* Prepare to read buffers. */ + + conn->resp.result = hdr->result; + conn->resp.valuelen = datahdr->valuelen; + conn->resp.valuelen_nontrunc = datahdr->valuelen_nontrunc; + + if (conn->resp.result < 0) + { + /* Error, valuelen must be zero. */ + + if (datahdr->valuelen > 0 || datahdr->valuelen_nontrunc > 0) + { + nerr("error: response result negative, and valuelen or valuelen_nontrunc non-zero.\n"); + + ret = -EINVAL; + goto unlock_out; + } + + /* Done with request/response. */ + + (void)usrsock_event(conn, USRSOCK_EVENT_REQ_COMPLETE); + + ret = sizeof(*datahdr); + goto unlock_out; + } + + /* Check that number of buffers match available. */ + + num_inbufs = (hdr->result > 0) + 1; + + if (conn->resp.datain.iovcnt < num_inbufs) + { + nwarn("not enough recv buffers (need: %d, have: %d).\n", num_inbufs, + conn->resp.datain.iovcnt); + + ret = -EINVAL; + goto unlock_out; + } + + /* Adjust length of receiving buffers. */ + + conn->resp.datain.total = 0; + iovpos = 0; + + /* Value buffer is always the first */ + + if (conn->resp.datain.iov[iovpos].iov_len < datahdr->valuelen) + { + nwarn("%dth buffer not large enough (need: %d, have: %d).\n", + iovpos, + datahdr->valuelen, + conn->resp.datain.iov[iovpos].iov_len); + + ret = -EINVAL; + goto unlock_out; + } + + /* Adjust read size. */ + + conn->resp.datain.iov[iovpos].iov_len = datahdr->valuelen; + conn->resp.datain.total += conn->resp.datain.iov[iovpos].iov_len; + iovpos++; + + if (hdr->result > 0) + { + /* Value buffer is always the first */ + + if (conn->resp.datain.iov[iovpos].iov_len < hdr->result) + { + nwarn("%dth buffer not large enough (need: %d, have: %d).\n", + iovpos, + hdr->result, + conn->resp.datain.iov[iovpos].iov_len); + + ret = -EINVAL; + goto unlock_out; + } + + /* Adjust read size. */ + + conn->resp.datain.iov[iovpos].iov_len = hdr->result; + conn->resp.datain.total += conn->resp.datain.iov[iovpos].iov_len; + iovpos++; + } + + DEBUGASSERT(num_inbufs == iovpos); + + conn->resp.datain.iovcnt = num_inbufs; + + /* Next written buffers are redirected to data buffers. */ + + dev->datain_conn = conn; + ret = sizeof(*datahdr); + +unlock_out: + return ret; +} + +/**************************************************************************** + * Name: usrsockdev_handle_req_response + ****************************************************************************/ + +static ssize_t usrsockdev_handle_req_response(FAR struct usrsockdev_s *dev, + FAR const void *buffer, + size_t len) +{ + FAR const struct usrsock_message_req_ack_s *hdr = buffer; + FAR struct usrsock_conn_s *conn; + unsigned int hdrlen; + ssize_t ret; + ssize_t (* handle_response)(FAR struct usrsockdev_s *dev, + FAR struct usrsock_conn_s *conn, + FAR const void *buffer); + + switch (hdr->head.msgid) + { + case USRSOCK_MESSAGE_RESPONSE_ACK: + hdrlen = sizeof(struct usrsock_message_req_ack_s); + handle_response = &usrsockdev_handle_response; + break; + + case USRSOCK_MESSAGE_RESPONSE_DATA_ACK: + hdrlen = sizeof(struct usrsock_message_datareq_ack_s); + handle_response = &usrsockdev_handle_datareq_response; + break; + + default: + nwarn("unknown message type: %d, flags: %d, xid: %02x, result: %d\n", + hdr->head.msgid, hdr->head.flags, hdr->xid, hdr->result); + return -EINVAL; + } + + if (len < hdrlen) + { + nwarn("message too short, %d < %d.\n", len, hdrlen); + + return -EINVAL; + } + + net_lock(); + + /* Get corresponding usrsock connection for this transfer */ + + conn = usrsock_nextconn(NULL); + while (conn) + { + if (conn->resp.xid == hdr->xid) + break; + + conn = usrsock_nextconn(conn); + } + + if (!conn) + { + /* No connection waiting for this message. */ + + nwarn("Could find connection waiting for response with xid=%d\n", + hdr->xid); + + ret = -EINVAL; + goto unlock_out; + } + + if (dev->req.ack_xid == hdr->xid && dev->req.iov) + { + /* Signal that request was received and read by daemon and acknowledgment + * response was received. */ + + dev->req.iov = NULL; + + sem_post(&dev->req.acksem); + } + + ret = handle_response(dev, conn, buffer); + +unlock_out: + net_unlock(); + return ret; +} + +/**************************************************************************** + * Name: usrsockdev_handle_message + ****************************************************************************/ + +static ssize_t usrsockdev_handle_message(FAR struct usrsockdev_s *dev, + FAR const void *buffer, + size_t len) +{ + FAR const struct usrsock_message_common_s *common = buffer; + + if (USRSOCK_MESSAGE_IS_EVENT(common->flags)) + { + return usrsockdev_handle_event(dev, buffer, len); + } + + if (USRSOCK_MESSAGE_IS_REQ_RESPONSE(common->flags)) + { + return usrsockdev_handle_req_response(dev, buffer, len); + } + + return -EINVAL; +} + +/**************************************************************************** + * Name: usrsockdev_write + ****************************************************************************/ + +static ssize_t usrsockdev_write(FAR struct file *filep, FAR const char *buffer, + size_t len) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct usrsock_conn_s *conn; + FAR struct usrsockdev_s *dev; + size_t origlen = len; + ssize_t ret = 0; + + if (len == 0) + { + return 0; + } + + if (buffer == NULL) + { + return -EINVAL; + } + + DEBUGASSERT(inode); + + dev = inode->i_private; + + DEBUGASSERT(dev); + + usrsockdev_semtake(&dev->devsem); + + if (!dev->datain_conn) + { + /* Start of message, buffer length should be at least size of common + * message header. */ + + if (len < sizeof(struct usrsock_message_common_s)) + { + nwarn("message too short, %d < %d.\n", len, + sizeof(struct usrsock_message_common_s)); + + ret = -EINVAL; + goto errout; + } + + /* Handle message. */ + + ret = usrsockdev_handle_message(dev, buffer, len); + if (ret >= 0) + { + buffer += ret; + len -= ret; + ret = origlen - len; + } + } + + /* Data input handling. */ + + if (dev->datain_conn) + { + conn = dev->datain_conn; + + /* Copy data from user-space. */ + + ret = iovec_put(conn->resp.datain.iov, conn->resp.datain.iovcnt, + conn->resp.datain.pos, buffer, len); + if (ret < 0) + { + /* Tried writing beyond buffer. */ + + ret = -EINVAL; + conn->resp.result = -EINVAL; + conn->resp.datain.pos = + conn->resp.datain.total; + } + else + { + conn->resp.datain.pos += ret; + buffer += ret; + len -= ret; + ret = origlen - len; + } + + if (conn->resp.datain.pos == conn->resp.datain.total) + { + dev->datain_conn = NULL; + + /* Done with data response. */ + + (void)usrsock_event(conn, USRSOCK_EVENT_REQ_COMPLETE); + } + } + +errout: + usrsockdev_semgive(&dev->devsem); + return ret; +} + +/**************************************************************************** + * Name: usrsockdev_open + ****************************************************************************/ + +static int usrsockdev_open(FAR struct file *filep) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct usrsockdev_s *dev; + int ret, tmp; + + DEBUGASSERT(inode); + + dev = inode->i_private; + + DEBUGASSERT(dev); + + usrsockdev_semtake(&dev->devsem); + + ninfo("opening /usr/usrsock\n"); + + /* Increment the count of references to the device. */ + + tmp = dev->ocount + 1; + if (tmp > 1) + { + /* Only one reference is allowed. */ + + nwarn("failed to open\n"); + + ret = -EPERM; + } + else + { + dev->ocount = tmp; + ret = OK; + } + + usrsockdev_semgive(&dev->devsem); + + return ret; +} + +/**************************************************************************** + * Name: usrsockdev_close + ****************************************************************************/ + +static int usrsockdev_close(FAR struct file *filep) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct usrsockdev_s *dev; + FAR struct usrsock_conn_s *conn; + struct timespec abstime; + int ret; + + DEBUGASSERT(inode); + + dev = inode->i_private; + + DEBUGASSERT(dev); + + usrsockdev_semtake(&dev->devsem); + + ninfo("closing /dev/usrsock\n"); + + /* Set active usrsock sockets to aborted state. */ + + conn = usrsock_nextconn(NULL); + while (conn) + { + net_lock(); + + conn->resp.inprogress = false; + conn->resp.xid = 0; + usrsock_event(conn, USRSOCK_EVENT_ABORT); + + net_unlock(); + + conn = usrsock_nextconn(conn); + } + + net_lock(); + + /* Decrement the references to the driver. */ + + dev->ocount--; + DEBUGASSERT(dev->ocount == 0); + ret = OK; + + do + { + /* Give other threads short time window to complete recently completed + * requests. + */ + + DEBUGVERIFY(clock_gettime(CLOCK_REALTIME, &abstime)); + + abstime.tv_sec += 0; + abstime.tv_nsec += 10 * NSEC_PER_MSEC; + if (abstime.tv_nsec >= NSEC_PER_SEC) + { + abstime.tv_sec++; + abstime.tv_nsec -= NSEC_PER_SEC; + } + + ret = net_timedwait(&dev->req.sem, &abstime); + if (ret < 0) + { + ret = *get_errno_ptr(); + + if (ret != ETIMEDOUT && ret != EINTR) + { + ninfo("net_timedwait errno: %d\n", ret); + DEBUGASSERT(false); + } + } + else + { + usrsockdev_semgive(&dev->req.sem); + } + + /* Wake-up pending requests. */ + + if (dev->req.nbusy == 0) + { + break; + } + + dev->req.iov = NULL; + sem_post(&dev->req.acksem); + } + while (true); + + net_unlock(); + + /* Check if request line is active */ + + if (dev->req.iov != NULL) + { + dev->req.iov = NULL; + } + + usrsockdev_semgive(&dev->devsem); + + return ret; +} + +/**************************************************************************** + * Name: pipecommon_poll + ****************************************************************************/ + +#ifndef CONFIG_DISABLE_POLL +static int usrsockdev_poll(FAR struct file *filep, FAR struct pollfd *fds, + bool setup) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct usrsockdev_s *dev; + pollevent_t eventset; + int ret = OK; + int i; + + DEBUGASSERT(inode); + + dev = inode->i_private; + + DEBUGASSERT(dev); + + /* Some sanity checking */ + + if (!dev || !fds) + { + return -ENODEV; + } + + /* Are we setting up the poll? Or tearing it down? */ + + usrsockdev_semtake(&dev->devsem); + net_lock(); + if (setup) + { + /* This is a request to set up the poll. Find an available + * slot for the poll structure reference + */ + + for (i = 0; i < ARRAY_SIZE(dev->pollfds); i++) + { + /* Find an available slot */ + + if (!dev->pollfds[i]) + { + /* Bind the poll structure and this slot */ + + dev->pollfds[i] = fds; + fds->priv = &dev->pollfds[i]; + break; + } + } + + if (i >= ARRAY_SIZE(dev->pollfds)) + { + fds->priv = NULL; + ret = -EBUSY; + goto errout; + } + + /* Should immediately notify on any of the requested events? */ + + eventset = 0; + + /* Notify the POLLIN event if pending request. */ + + if (dev->req.iov != NULL && + !(iovec_get(NULL, 0, dev->req.iov, + dev->req.iovcnt, dev->req.pos) < 0)) + { + eventset |= POLLIN; + } + + if (eventset) + { + usrsockdev_pollnotify(dev, eventset); + } + } + else + { + /* This is a request to tear down the poll. */ + + FAR struct pollfd **slot = (FAR struct pollfd **)fds->priv; + + if (!slot) + { + ret = -EIO; + goto errout; + } + + /* Remove all memory of the poll setup */ + + *slot = NULL; + fds->priv = NULL; + } + +errout: + net_unlock(); + usrsockdev_semgive(&dev->devsem); + return ret; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: usrsockdev_do_request + ****************************************************************************/ + +int usrsockdev_do_request(FAR struct usrsock_conn_s *conn, + FAR struct iovec *iov, unsigned int iovcnt) +{ + FAR struct usrsockdev_s *dev = conn->dev; + FAR struct usrsock_request_common_s *req_head = iov[0].iov_base; + + if (!dev) + { + /* Setup conn for new usrsock device. */ + + DEBUGASSERT(req_head->reqid == USRSOCK_REQUEST_SOCKET); + dev = &g_usrsockdev; + conn->dev = dev; + } + + if (!usrsockdev_is_opened(dev)) + { + ninfo("usockid=%d; daemon has closed /usr/usrsock.\n", conn->usockid); + + return -ENETDOWN; + } + + /* Get exchange id. */ + + req_head->xid = usrsockdev_get_xid(conn); + + /* Prepare connection for response. */ + + conn->resp.xid = req_head->xid; + conn->resp.result = -EACCES; + + ++dev->req.nbusy; /* net_lock held. */ + + /* Set outstanding request for daemon to handle. */ + + while (net_lockedwait(&dev->req.sem) != OK) + { + DEBUGASSERT(*get_errno_ptr() == EINTR); + } + + if (usrsockdev_is_opened(dev)) + { + DEBUGASSERT(dev->req.iov == NULL); + dev->req.ack_xid = req_head->xid; + dev->req.iov = iov; + dev->req.pos = 0; + dev->req.iovcnt = iovcnt; + + /* Notify daemon of new request. */ + + usrsockdev_pollnotify(dev, POLLIN); + + /* Wait ack for request. */ + + while (net_lockedwait(&dev->req.acksem) != OK) + { + DEBUGASSERT(*get_errno_ptr() == EINTR); + } + } + else + { + ninfo("usockid=%d; daemon abruptly closed /usr/usrsock.\n", conn->usockid); + } + + /* Free request line for next command. */ + + usrsockdev_semgive(&dev->req.sem); + + --dev->req.nbusy; /* net_lock held. */ + + return OK; +} + +/**************************************************************************** + * Name: usrsockdev_register + * + * Description: + * Register /dev/usrsock + * + ****************************************************************************/ + +void usrsockdev_register(void) +{ + /* Initialize device private structure. */ + + g_usrsockdev.ocount = 0; + g_usrsockdev.req.nbusy = 0; + sem_init(&g_usrsockdev.devsem, 0, 1); + sem_init(&g_usrsockdev.req.sem, 0, 1); + sem_init(&g_usrsockdev.req.acksem, 0, 0); + + (void)register_driver("/dev/usrsock", &g_usrsockdevops, 0666, &g_usrsockdev); +} + +#endif /* CONFIG_NET && CONFIG_NET_USRSOCK */ diff --git a/net/usrsock/usrsock_event.c b/net/usrsock/usrsock_event.c new file mode 100644 index 0000000000..d16fb04fc9 --- /dev/null +++ b/net/usrsock/usrsock_event.c @@ -0,0 +1,136 @@ +/**************************************************************************** + * net/usrsock/usrsock_event.c + * + * Copyright (C) 2015, 2017 Haltian Ltd. All rights reserved. + * Author: Jussi Kivilinna + * + * 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 +#if defined(CONFIG_NET) && defined(CONFIG_NET_USRSOCK) + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include + +#include "devif/devif.h" +#include "usrsock/usrsock.h" + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: usrsock_event + * + * Description: + * Handler for received connection events + * + ****************************************************************************/ + +int usrsock_event(FAR struct usrsock_conn_s *conn, uint16_t events) +{ + ninfo("events: %04X\n", events); + + if (!events) + { + return OK; + } + + net_lock(); + + /* Generic state updates. */ + + if (events & USRSOCK_EVENT_REQ_COMPLETE) + { + if (conn->state == USRSOCK_CONN_STATE_CONNECTING) + { + conn->state = USRSOCK_CONN_STATE_READY; + events |= USRSOCK_EVENT_CONNECT_RESP; + + if (conn->resp.result == 0) + { + conn->connected = true; + } + } + } + + if (events & USRSOCK_EVENT_ABORT) + { + conn->state = USRSOCK_CONN_STATE_ABORTED; + } + + if (events & USRSOCK_EVENT_REMOTE_CLOSED) + { + /* After reception of remote close event, clear input/output flags. */ + + conn->flags &= ~(USRSOCK_EVENT_SENDTO_READY | + USRSOCK_EVENT_RECVFROM_AVAIL); + + conn->flags |= USRSOCK_EVENT_REMOTE_CLOSED; + } + + if ((conn->state == USRSOCK_CONN_STATE_READY || + conn->state == USRSOCK_CONN_STATE_CONNECTING) && + !(conn->flags & USRSOCK_EVENT_REMOTE_CLOSED)) + { + if (events & USRSOCK_EVENT_SENDTO_READY) + { + conn->flags |= USRSOCK_EVENT_SENDTO_READY; + } + + if (events & USRSOCK_EVENT_RECVFROM_AVAIL) + { + conn->flags |= USRSOCK_EVENT_RECVFROM_AVAIL; + } + } + + /* Send events to callbacks */ + + (void)devif_conn_event(NULL, conn, events, conn->list); + net_unlock(); + + return OK; +} + +#endif /* CONFIG_NET && CONFIG_NET_USRSOCK */ diff --git a/net/usrsock/usrsock_getsockname.c b/net/usrsock/usrsock_getsockname.c new file mode 100644 index 0000000000..5049ab8d21 --- /dev/null +++ b/net/usrsock/usrsock_getsockname.c @@ -0,0 +1,265 @@ +/**************************************************************************** + * net/usrsock/usrsock_getsockname.c + * + * Copyright (C) 2015, 2017 Haltian Ltd. All rights reserved. + * Author: Jussi Kivilinna + * + * 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 +#if defined(CONFIG_NET) && defined(CONFIG_NET_USRSOCK) + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include + +#include "socket/socket.h" +#include "usrsock/usrsock.h" + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static uint16_t getsockname_event(FAR struct net_driver_s *dev, + FAR void *pvconn, + FAR void *pvpriv, uint16_t flags) +{ + FAR struct usrsock_data_reqstate_s *pstate = pvpriv; + FAR struct usrsock_conn_s *conn = pvconn; + + if (flags & USRSOCK_EVENT_ABORT) + { + ninfo("socket aborted.\n"); + + pstate->reqstate.result = -ECONNABORTED; + pstate->valuelen = 0; + + /* Stop further callbacks */ + + pstate->reqstate.cb->flags = 0; + pstate->reqstate.cb->priv = NULL; + pstate->reqstate.cb->event = NULL; + + /* Wake up the waiting thread */ + + sem_post(&pstate->reqstate.recvsem); + } + else if (flags & USRSOCK_EVENT_REQ_COMPLETE) + { + ninfo("request completed.\n"); + + pstate->reqstate.result = conn->resp.result; + if (pstate->reqstate.result < 0) + { + pstate->valuelen = 0; + pstate->valuelen_nontrunc = 0; + } + else + { + pstate->valuelen = conn->resp.valuelen; + pstate->valuelen_nontrunc = conn->resp.valuelen_nontrunc; + } + + /* Stop further callbacks */ + + pstate->reqstate.cb->flags = 0; + pstate->reqstate.cb->priv = NULL; + pstate->reqstate.cb->event = NULL; + + /* Wake up the waiting thread */ + + sem_post(&pstate->reqstate.recvsem); + } + + return flags; +} + +/**************************************************************************** + * Name: do_getsockopt_request + ****************************************************************************/ + +static int do_getsockname_request(FAR struct usrsock_conn_s *conn, + socklen_t addrlen) +{ + struct usrsock_request_getsockname_s req = {}; + struct iovec bufs[1]; + + if (addrlen > UINT16_MAX) + { + addrlen = UINT16_MAX; + } + + /* Prepare request for daemon to read. */ + + req.head.reqid = USRSOCK_REQUEST_GETSOCKNAME; + req.usockid = conn->usockid; + req.max_addrlen = addrlen; + + bufs[0].iov_base = (FAR void *)&req; + bufs[0].iov_len = sizeof(req); + + return usrsockdev_do_request(conn, bufs, ARRAY_SIZE(bufs)); +} + +/**************************************************************************** + * Name: setup_conn_getsockopt + ****************************************************************************/ + +static void setup_conn_getsockname(FAR struct usrsock_conn_s *conn, + FAR struct iovec *iov, + unsigned int iovcnt) +{ + unsigned int i; + + conn->resp.datain.iov = iov; + conn->resp.datain.pos = 0; + conn->resp.datain.total = 0; + conn->resp.datain.iovcnt = iovcnt; + + for (i = 0; i < iovcnt; i++) + { + conn->resp.datain.total += iov[i].iov_len; + } +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: usrsock_getsockname + * + * Description: + * The getsockname() function retrieves the locally-bound name of the + * specified socket, stores this address in the sockaddr structure pointed + * to by the 'addr' argument, and stores the length of this address in the + * object pointed to by the 'addrlen' argument. + * + * If the actual length of the address is greater than the length of the + * supplied sockaddr structure, the stored address will be truncated. + * + * If the socket has not been bound to a local name, the value stored in + * the object pointed to by address is unspecified. + * + * Parameters: + * conn usrsock socket connection structure + * addr sockaddr structure to receive data [out] + * addrlen Length of sockaddr structure [in/out] + * + ****************************************************************************/ + +int usrsock_getsockname(FAR struct usrsock_conn_s *conn, + FAR struct sockaddr *addr, FAR socklen_t *addrlen) +{ + struct usrsock_data_reqstate_s state = {}; + struct iovec inbufs[1]; + ssize_t ret; + socklen_t outaddrlen = 0; + + net_lock(); + + if (conn->state == USRSOCK_CONN_STATE_UNINITIALIZED || + conn->state == USRSOCK_CONN_STATE_ABORTED) + { + /* Invalid state or closed by daemon. */ + + ninfo("usockid=%d; connect() with uninitialized usrsock.\n", + conn->usockid); + + ret = (conn->state == USRSOCK_CONN_STATE_ABORTED) ? -EPIPE : -ECONNRESET; + goto errout_unlock; + } + + /* Set up event callback for usrsock. */ + + ret = usrsock_setup_data_request_callback( + conn, &state, getsockname_event, + USRSOCK_EVENT_ABORT | USRSOCK_EVENT_REQ_COMPLETE); + if (ret < 0) + { + nwarn("usrsock_setup_request_callback failed: %d\n", ret); + goto errout_unlock; + } + + inbufs[0].iov_base = (FAR void *)addr; + inbufs[0].iov_len = *addrlen; + + setup_conn_getsockname(conn, inbufs, ARRAY_SIZE(inbufs)); + + /* Request user-space daemon to close socket. */ + + ret = do_getsockname_request(conn, *addrlen); + if (ret >= 0) + { + /* Wait for completion of request. */ + + while (net_lockedwait(&state.reqstate.recvsem) != OK) + { + DEBUGASSERT(*get_errno_ptr() == EINTR); + } + + ret = state.reqstate.result; + + DEBUGASSERT(state.valuelen <= *addrlen); + DEBUGASSERT(state.valuelen <= state.valuelen_nontrunc); + + if (ret >= 0) + { + /* Store length of data that was written to 'value' buffer. */ + + outaddrlen = state.valuelen_nontrunc; + } + } + + setup_conn_getsockname(conn, NULL, 0); + usrsock_teardown_data_request_callback(&state); + +errout_unlock: + net_unlock(); + + *addrlen = outaddrlen; + return ret; +} + +#endif /* CONFIG_NET && CONFIG_NET_USRSOCK */ diff --git a/net/usrsock/usrsock_getsockopt.c b/net/usrsock/usrsock_getsockopt.c new file mode 100644 index 0000000000..f4a8ccb0d4 --- /dev/null +++ b/net/usrsock/usrsock_getsockopt.c @@ -0,0 +1,275 @@ +/**************************************************************************** + * net/usrsock/usrsock_getsockopt.c + * + * Copyright (C) 2015, 2017 Haltian Ltd. All rights reserved. + * Author: Jussi Kivilinna + * + * 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 +#if defined(CONFIG_NET) && defined(CONFIG_NET_USRSOCK) && \ + defined(CONFIG_NET_SOCKOPTS) + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include + +#include "socket/socket.h" +#include "usrsock/usrsock.h" + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static uint16_t getsockopt_event(FAR struct net_driver_s *dev, FAR void *pvconn, + FAR void *pvpriv, uint16_t flags) +{ + FAR struct usrsock_data_reqstate_s *pstate = pvpriv; + FAR struct usrsock_conn_s *conn = pvconn; + + if (flags & USRSOCK_EVENT_ABORT) + { + ninfo("socket aborted.\n"); + + pstate->reqstate.result = -ECONNABORTED; + pstate->valuelen = 0; + + /* Stop further callbacks */ + + pstate->reqstate.cb->flags = 0; + pstate->reqstate.cb->priv = NULL; + pstate->reqstate.cb->event = NULL; + + /* Wake up the waiting thread */ + + sem_post(&pstate->reqstate.recvsem); + } + else if (flags & USRSOCK_EVENT_REQ_COMPLETE) + { + ninfo("request completed.\n"); + + pstate->reqstate.result = conn->resp.result; + if (pstate->reqstate.result < 0) + { + pstate->valuelen = 0; + } + else + { + pstate->valuelen = conn->resp.valuelen; + } + + /* Stop further callbacks */ + + pstate->reqstate.cb->flags = 0; + pstate->reqstate.cb->priv = NULL; + pstate->reqstate.cb->event = NULL; + + /* Wake up the waiting thread */ + + sem_post(&pstate->reqstate.recvsem); + } + + return flags; +} + +/**************************************************************************** + * Name: do_getsockopt_request + ****************************************************************************/ + +static int do_getsockopt_request(FAR struct usrsock_conn_s *conn, int level, + int option, socklen_t value_len) +{ + struct usrsock_request_getsockopt_s req = {}; + struct iovec bufs[1]; + + if (level < INT16_MIN || level > INT16_MAX) + { + return -EINVAL; + } + + if (option < INT16_MIN || option > INT16_MAX) + { + return -EINVAL; + } + + if (value_len > UINT16_MAX) + { + value_len = UINT16_MAX; + } + + /* Prepare request for daemon to read. */ + + req.head.reqid = USRSOCK_REQUEST_GETSOCKOPT; + req.usockid = conn->usockid; + req.level = level; + req.option = option; + req.max_valuelen = value_len; + + bufs[0].iov_base = (FAR void *)&req; + bufs[0].iov_len = sizeof(req); + + return usrsockdev_do_request(conn, bufs, ARRAY_SIZE(bufs)); +} + +/**************************************************************************** + * Name: setup_conn_getsockopt + ****************************************************************************/ + +static void setup_conn_getsockopt(FAR struct usrsock_conn_s *conn, + FAR struct iovec *iov, unsigned int iovcnt) +{ + unsigned int i; + + conn->resp.datain.iov = iov; + conn->resp.datain.pos = 0; + conn->resp.datain.total = 0; + conn->resp.datain.iovcnt = iovcnt; + + for (i = 0; i < iovcnt; i++) + { + conn->resp.datain.total += iov[i].iov_len; + } +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: usrsock_getsockopt + * + * Description: + * getsockopt() retrieve thse value for the option specified by the + * 'option' argument for the socket specified by the 'psock' argument. If + * the size of the option value is greater than 'value_len', the value + * stored in the object pointed to by the 'value' argument will be silently + * truncated. Otherwise, the length pointed to by the 'value_len' argument + * will be modified to indicate the actual length of the'value'. + * + * The 'level' argument specifies the protocol level of the option. To + * retrieve options at the socket level, specify the level argument as + * SOL_SOCKET. + * + * See a complete list of values for the 'option' argument. + * + * Parameters: + * conn usrsock socket connection structure + * level Protocol level to set the option + * option identifies the option to get + * value Points to the argument value + * value_len The length of the argument value + * + ****************************************************************************/ + +int usrsock_getsockopt(FAR struct usrsock_conn_s *conn, int level, int option, + FAR void *value, FAR socklen_t *value_len) +{ + struct usrsock_data_reqstate_s state = {}; + struct iovec inbufs[1]; + ssize_t ret; + + net_lock(); + + if (conn->state == USRSOCK_CONN_STATE_UNINITIALIZED || + conn->state == USRSOCK_CONN_STATE_ABORTED) + { + /* Invalid state or closed by daemon. */ + + ninfo("usockid=%d; connect() with uninitialized usrsock.\n", + conn->usockid); + + ret = (conn->state == USRSOCK_CONN_STATE_ABORTED) ? -EPIPE : -ECONNRESET; + goto errout_unlock; + } + + /* Set up event callback for usrsock. */ + + ret = usrsock_setup_data_request_callback( + conn, &state, getsockopt_event, + USRSOCK_EVENT_ABORT | USRSOCK_EVENT_REQ_COMPLETE); + if (ret < 0) + { + nwarn("usrsock_setup_request_callback failed: %d\n", ret); + goto errout_unlock; + } + + inbufs[0].iov_base = (FAR void *)value; + inbufs[0].iov_len = *value_len; + + setup_conn_getsockopt(conn, inbufs, ARRAY_SIZE(inbufs)); + + /* Request user-space daemon to close socket. */ + + ret = do_getsockopt_request(conn, level, option, *value_len); + if (ret >= 0) + { + /* Wait for completion of request. */ + + while (net_lockedwait(&state.reqstate.recvsem) != OK) + { + DEBUGASSERT(*get_errno_ptr() == EINTR); + } + + ret = state.reqstate.result; + + DEBUGASSERT(state.valuelen <= *value_len); + + if (ret >= 0) + { + /* Store length of data that was written to 'value' buffer. */ + + *value_len = state.valuelen; + } + } + + setup_conn_getsockopt(conn, NULL, 0); + usrsock_teardown_data_request_callback(&state); + +errout_unlock: + net_unlock(); + + return ret; +} + +#endif /* CONFIG_NET && CONFIG_NET_USRSOCK && CONFIG_NET_SOCKOPTS */ diff --git a/net/usrsock/usrsock_poll.c b/net/usrsock/usrsock_poll.c new file mode 100644 index 0000000000..41860f4d7f --- /dev/null +++ b/net/usrsock/usrsock_poll.c @@ -0,0 +1,388 @@ +/**************************************************************************** + * net/usrsock/usrsock_poll.c + * + * Copyright (C) 2015, 2017 Haltian Ltd. All rights reserved. + * Author: Jussi Kivilinna + * + * 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 +#if defined(CONFIG_NET) && defined(CONFIG_NET_USRSOCK) && \ + !defined(CONFIG_DISABLE_POLL) + +#include +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include + +#include "socket/socket.h" +#include "usrsock/usrsock.h" + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +struct usrsock_poll_s +{ + FAR struct socket *psock; /* Needed to handle loss of connection */ + struct pollfd *fds; /* Needed to handle poll events */ + FAR struct devif_callback_s *cb; /* Needed to teardown the poll */ +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static uint16_t poll_event(FAR struct net_driver_s *dev, FAR void *pvconn, + FAR void *pvpriv, uint16_t flags) +{ + FAR struct usrsock_poll_s *info = (FAR struct usrsock_poll_s *)pvpriv; + FAR struct usrsock_conn_s *conn = pvconn; + pollevent_t eventset = 0; + + DEBUGASSERT(!info || (info->psock && info->fds)); + + if (!info) + return flags; + + if (flags & USRSOCK_EVENT_ABORT) + { + ninfo("socket aborted.\n"); + + /* Socket forcefully terminated. */ + + eventset |= (POLLERR | POLLHUP); + } + else if ((flags & USRSOCK_EVENT_CONNECT_RESP) && !conn->connected) + { + ninfo("socket connect failed.\n"); + + /* Non-blocking connect failed. */ + + eventset |= (POLLERR | POLLHUP); + } + else if (flags & USRSOCK_EVENT_REMOTE_CLOSED) + { + ninfo("remote closed.\n"); + + /* Remote closed. */ + + eventset |= (POLLHUP | POLLIN); + } + else + { + /* Check data events. */ + + if (flags & USRSOCK_EVENT_RECVFROM_AVAIL) + { + ninfo("socket recv avail.\n"); + + eventset |= POLLIN; + } + + if (flags & USRSOCK_EVENT_SENDTO_READY) + { + ninfo("socket send ready.\n"); + + eventset |= POLLOUT; + } + } + + /* Filter I/O events depending on requested events. */ + + eventset &= (~(POLLOUT | POLLIN) | info->fds->events); + + /* POLLOUT and PULLHUP are mutually exclusive. */ + + if ((eventset & POLLOUT) && (eventset & POLLHUP)) + { + eventset &= ~POLLOUT; + } + + /* Awaken the caller of poll() is requested event occurred. */ + + if (eventset) + { + info->fds->revents |= eventset; + sem_post(info->fds->sem); + } + + return flags; +} + +/**************************************************************************** + * Function: usrsock_poll + * + * Description: + * Setup to monitor events on an usrsock socket + * + * Input Parameters: + * psock - An instance of the internal socket structure. + * fds - The structure describing the events to be monitored. + * + * Returned Value: + * 0: Success; Negated errno on failure + * + ****************************************************************************/ + +static int usrsock_pollsetup(FAR struct socket *psock, FAR struct pollfd *fds) +{ + FAR struct usrsock_conn_s *conn = psock->s_conn; + FAR struct usrsock_poll_s *info; + FAR struct devif_callback_s *cb; + int ret = OK; + + /* Sanity check */ + +#ifdef CONFIG_DEBUG + if (!conn || !fds) + { + return -EINVAL; + } +#endif + + /* Allocate a container to hold the poll information */ + + info = (FAR struct usrsock_poll_s *)kmm_malloc(sizeof(struct usrsock_poll_s)); + if (!info) + { + return -ENOMEM; + } + + net_lock(); + + /* Allocate a usrsock callback structure */ + + cb = devif_callback_alloc(NULL, &conn->list); + if (!cb) + { + ret = -EBUSY; + kmm_free(info); /* fds->priv not set, so we need to free info here. */ + goto errout_unlock; + } + + /* Initialize the poll info container */ + + info->psock = psock; + info->fds = fds; + info->cb = cb; + + /* Initialize the callback structure. Save the reference to the info + * structure as callback private data so that it will be available during + * callback processing. + */ + + cb->flags = USRSOCK_EVENT_ABORT | USRSOCK_EVENT_CONNECT_RESP | + USRSOCK_EVENT_SENDTO_READY | USRSOCK_EVENT_RECVFROM_AVAIL | + USRSOCK_EVENT_REMOTE_CLOSED; + cb->priv = (FAR void *)info; + cb->event = poll_event; + + /* Save the reference in the poll info structure as fds private as well + * for use during poll teardown as well. + */ + + fds->priv = (FAR void *)info; + + /* Check if socket is in error state */ + + if (conn->state == USRSOCK_CONN_STATE_UNINITIALIZED || + conn->state == USRSOCK_CONN_STATE_ABORTED) + { + ninfo("socket %s.\n", + conn->state == USRSOCK_CONN_STATE_UNINITIALIZED ? + "uninitialized" : "aborted"); + + fds->revents |= (POLLERR | POLLHUP); + } + + /* Stream sockets need to be connected or connecting (or listening). */ + + else if ((conn->type == SOCK_STREAM || conn->type == SOCK_SEQPACKET) && + !(conn->connected || conn->state == USRSOCK_CONN_STATE_CONNECTING)) + { + ninfo("stream socket not connected and not connecting.\n"); + + fds->revents |= (POLLOUT | POLLIN | POLLHUP); + } + else if (conn->flags & USRSOCK_EVENT_REMOTE_CLOSED) + { + ninfo("socket remote closed.\n"); + + /* Remote closed. */ + + fds->revents |= (POLLHUP | POLLIN); + } + else + { + /* Check if daemon has room for send data or has data to receive. */ + + if (conn->flags & USRSOCK_EVENT_SENDTO_READY) + { + ninfo("socket send ready.\n"); + + fds->revents |= (POLLOUT & fds->events); + } + + if (conn->flags & USRSOCK_EVENT_RECVFROM_AVAIL) + { + ninfo("socket recv avail.\n"); + + fds->revents |= (POLLIN & fds->events); + } + } + + /* Filter I/O events depending on requested events. */ + + fds->revents &= (~(POLLOUT | POLLIN) | info->fds->events); + + /* POLLOUT and PULLHUP are mutually exclusive. */ + + if ((fds->revents & POLLOUT) && (fds->revents & POLLHUP)) + { + fds->revents &= ~POLLOUT; + } + + /* Check if any requested events are already in effect */ + + if (fds->revents != 0) + { + /* Yes.. then signal the poll logic */ + + sem_post(fds->sem); + } + +errout_unlock: + net_unlock(); + return ret; +} + +/**************************************************************************** + * Function: usrsock_pollteardown + * + * Description: + * Teardown monitoring of events on an usrsock socket + * + * Input Parameters: + * psock - An instance of the internal socket structure. + * fds - The structure describing the events to be stopped being monitored. + * + * Returned Value: + * 0: Success; Negated errno on failure + * + ****************************************************************************/ + +static int usrsock_pollteardown(FAR struct socket *psock, + FAR struct pollfd *fds) +{ + FAR struct usrsock_conn_s *conn = psock->s_conn; + FAR struct usrsock_poll_s *info; + + /* Sanity check */ + +#ifdef CONFIG_DEBUG + if (!conn || !fds->priv) + { + return -EINVAL; + } +#endif + + /* Recover the socket descriptor poll state info from the poll structure */ + + info = (FAR struct usrsock_poll_s *)fds->priv; + DEBUGASSERT(info && info->fds && info->cb); + if (info) + { + /* Release the callback */ + + net_lock(); + devif_conn_callback_free(NULL, info->cb, &conn->list); + net_unlock(); + + /* Release the poll/select data slot */ + + info->fds->priv = NULL; + + /* Then free the poll info container */ + + kmm_free(info); + } + + return OK; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: usrsock_poll + * + * Description: + * The standard poll() operation redirects operations on socket descriptors + * to this function. + * + * Input Parameters: + * psock - An instance of the internal socket structure. + * fds - The structure describing the events to be monitored. + * setup - true: Setup up the poll; false: Teardown the poll + * + * Returned Value: + * 0: Success; Negated errno on failure + * + ****************************************************************************/ + +int usrsock_poll(FAR struct socket *psock, FAR struct pollfd *fds, bool setup) +{ + if (setup) + { + return usrsock_pollsetup(psock, fds); + } + else + { + return usrsock_pollteardown(psock, fds); + } +} + +#endif /* CONFIG_NET && CONFIG_NET_USRSOCK && !CONFIG_DISABLE_POLL */ diff --git a/net/usrsock/usrsock_recvfrom.c b/net/usrsock/usrsock_recvfrom.c new file mode 100644 index 0000000000..d97cba5c3a --- /dev/null +++ b/net/usrsock/usrsock_recvfrom.c @@ -0,0 +1,485 @@ +/**************************************************************************** + * net/usrsock/usrsock_recvfrom.c + * + * Copyright (C) 2015, 2017 Haltian Ltd. All rights reserved. + * Author: Jussi Kivilinna + * + * 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 +#if defined(CONFIG_NET) && defined(CONFIG_NET_USRSOCK) + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include + +#include "socket/socket.h" +#include "usrsock/usrsock.h" + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static uint16_t recvfrom_event(FAR struct net_driver_s *dev, FAR void *pvconn, + FAR void *pvpriv, uint16_t flags) +{ + FAR struct usrsock_data_reqstate_s *pstate = pvpriv; + FAR struct usrsock_conn_s *conn = pvconn; + + if (flags & USRSOCK_EVENT_ABORT) + { + ninfo("socket aborted.\n"); + + pstate->reqstate.result = -ECONNABORTED; + pstate->valuelen = 0; + pstate->valuelen_nontrunc = 0; + + /* Stop further callbacks */ + + pstate->reqstate.cb->flags = 0; + pstate->reqstate.cb->priv = NULL; + pstate->reqstate.cb->event = NULL; + + /* Wake up the waiting thread */ + + sem_post(&pstate->reqstate.recvsem); + } + else if (flags & USRSOCK_EVENT_REQ_COMPLETE) + { + ninfo("request completed.\n"); + + pstate->reqstate.result = conn->resp.result; + if (pstate->reqstate.result < 0) + { + pstate->valuelen = 0; + pstate->valuelen_nontrunc = 0; + } + else + { + pstate->valuelen = conn->resp.valuelen; + pstate->valuelen_nontrunc = conn->resp.valuelen_nontrunc; + } + + if (pstate->reqstate.result >= 0 || + pstate->reqstate.result == -EAGAIN) + { + /* After reception of data, mark input not ready. Daemon will + * send event to restore this flag. */ + + conn->flags &= ~USRSOCK_EVENT_RECVFROM_AVAIL; + } + + /* Stop further callbacks */ + + pstate->reqstate.cb->flags = 0; + pstate->reqstate.cb->priv = NULL; + pstate->reqstate.cb->event = NULL; + + /* Wake up the waiting thread */ + + sem_post(&pstate->reqstate.recvsem); + } + else if (flags & USRSOCK_EVENT_REMOTE_CLOSED) + { + ninfo("remote closed.\n"); + + pstate->reqstate.result = -EPIPE; + + /* Stop further callbacks */ + + pstate->reqstate.cb->flags = 0; + pstate->reqstate.cb->priv = NULL; + pstate->reqstate.cb->event = NULL; + + /* Wake up the waiting thread */ + + sem_post(&pstate->reqstate.recvsem); + } + else if (flags & USRSOCK_EVENT_RECVFROM_AVAIL) + { + ninfo("recvfrom avail.\n"); + + flags &= ~USRSOCK_EVENT_RECVFROM_AVAIL; + + /* Stop further callbacks */ + + pstate->reqstate.cb->flags = 0; + pstate->reqstate.cb->priv = NULL; + pstate->reqstate.cb->event = NULL; + + /* Wake up the waiting thread */ + + sem_post(&pstate->reqstate.recvsem); + } + + return flags; +} + +/**************************************************************************** + * Name: do_recvfrom_request + ****************************************************************************/ + +static int do_recvfrom_request(FAR struct usrsock_conn_s *conn, size_t buflen, + socklen_t addrlen) +{ + struct usrsock_request_recvfrom_s req = {}; + struct iovec bufs[1]; + + if (addrlen > UINT16_MAX) + { + addrlen = UINT16_MAX; + } + + if (buflen > UINT16_MAX) + { + buflen = UINT16_MAX; + } + + /* Prepare request for daemon to read. */ + + req.head.reqid = USRSOCK_REQUEST_RECVFROM; + req.usockid = conn->usockid; + req.max_addrlen = addrlen; + req.max_buflen = buflen; + + bufs[0].iov_base = (FAR void *)&req; + bufs[0].iov_len = sizeof(req); + + return usrsockdev_do_request(conn, bufs, ARRAY_SIZE(bufs)); +} + +/**************************************************************************** + * Name: setup_conn_recvfrom + ****************************************************************************/ + +static void setup_conn_recvfrom(FAR struct usrsock_conn_s *conn, + FAR struct iovec *iov, unsigned int iovcnt) +{ + unsigned int i; + + conn->resp.datain.iov = iov; + conn->resp.datain.pos = 0; + conn->resp.datain.total = 0; + conn->resp.datain.iovcnt = iovcnt; + + for (i = 0; i < iovcnt; i++) + { + conn->resp.datain.total += iov[i].iov_len; + } +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: usrsock_recvfrom + * + * Description: + * recvfrom() receives messages from a socket, and may be used to receive + * data on a socket whether or not it is connection-oriented. + * + * If from is not NULL, and the underlying protocol provides the source + * address, this source address is filled in. The argument fromlen + * initialized to the size of the buffer associated with from, and modified + * on return to indicate the actual size of the address stored there. + * + * Parameters: + * psock A pointer to a NuttX-specific, internal socket structure + * buf Buffer to receive data + * len Length of buffer + * from Address of source (may be NULL) + * fromlen The length of the address structure + * + ****************************************************************************/ + +ssize_t usrsock_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len, + FAR struct sockaddr *from, FAR socklen_t *fromlen) +{ + FAR struct usrsock_conn_s *conn = psock->s_conn; + struct usrsock_data_reqstate_s state = {}; + struct iovec inbufs[2]; + socklen_t addrlen = 0; + socklen_t outaddrlen = 0; + ssize_t ret; +#ifdef CONFIG_NET_SOCKOPTS + struct timespec abstime; +#endif + struct timespec *ptimeo = NULL; + + DEBUGASSERT(conn); + + if (fromlen) + { + if (*fromlen > 0 && from == NULL) + { + return -EINVAL; + } + + addrlen = *fromlen; + } + + net_lock(); + + if (conn->state == USRSOCK_CONN_STATE_UNINITIALIZED || + conn->state == USRSOCK_CONN_STATE_ABORTED) + { + /* Invalid state or closed by daemon. */ + + ninfo("usockid=%d; connect() with uninitialized usrsock.\n", + conn->usockid); + + ret = (conn->state == USRSOCK_CONN_STATE_ABORTED) ? -EPIPE : -ECONNRESET; + goto errout_unlock; + } + + if (conn->type == SOCK_STREAM || conn->type == SOCK_SEQPACKET) + { + if (!conn->connected) + { + if (conn->state == USRSOCK_CONN_STATE_CONNECTING) + { + /* Connecting. */ + + ninfo("usockid=%d; socket still connecting.\n", + conn->usockid); + + ret = -EAGAIN; + goto errout_unlock; + } + else + { + /* Not connected. */ + + ninfo("usockid=%d; socket not connected.\n", + conn->usockid); + + ret = -ENOTCONN; + goto errout_unlock; + } + } + } + + if (conn->state == USRSOCK_CONN_STATE_CONNECTING) + { + /* Non-blocking connecting. */ + + ninfo("usockid=%d; socket still connecting.\n", + conn->usockid); + + ret = -EAGAIN; + goto errout_unlock; + } + +#ifdef CONFIG_NET_SOCKOPTS + if (psock->s_rcvtimeo != 0) + { + DEBUGVERIFY(clock_gettime(CLOCK_REALTIME, &abstime)); + + /* Prepare timeout value for recvfrom. */ + + abstime.tv_sec += psock->s_rcvtimeo / DSEC_PER_SEC; + abstime.tv_nsec += (psock->s_rcvtimeo % DSEC_PER_SEC) * NSEC_PER_DSEC; + if (abstime.tv_nsec >= NSEC_PER_SEC) + { + abstime.tv_sec++; + abstime.tv_nsec -= NSEC_PER_SEC; + } + + ptimeo = &abstime; + } +#endif + + do + { + /* Check if remote end has closed connection. */ + + if (conn->flags & USRSOCK_EVENT_REMOTE_CLOSED) + { + ninfo("usockid=%d; remote closed (EOF).\n", conn->usockid); + + ret = 0; + goto errout_unlock; + } + + /* Check if need to wait for receive data to become available. */ + + if (!(conn->flags & USRSOCK_EVENT_RECVFROM_AVAIL)) + { + if (_SS_ISNONBLOCK(psock->s_flags)) + { + /* Nothing to receive from daemon side. */ + + ret = -EAGAIN; + goto errout_unlock; + } + + /* Wait recv to become avail. */ + + ret = usrsock_setup_data_request_callback( + conn, &state, recvfrom_event, + USRSOCK_EVENT_ABORT | USRSOCK_EVENT_RECVFROM_AVAIL | + USRSOCK_EVENT_REMOTE_CLOSED); + if (ret < 0) + { + nwarn("usrsock_setup_request_callback failed: %d\n", ret); + goto errout_unlock; + } + + /* Wait for receive-avail (or abort, or timeout, or signal). */ + + ret = 0; + if (net_timedwait(&state.reqstate.recvsem, ptimeo) != OK) + { + ret = *get_errno_ptr(); + + if (ret == ETIMEDOUT) + { + ninfo("recvfrom timedout\n"); + + ret = -EAGAIN; + } + else if (ret == EINTR) + { + ninfo("recvfrom interrupted\n"); + + ret = -EINTR; + } + else + { + nerr("net_timedwait errno: %d\n", ret); + DEBUGASSERT(false); + } + } + + usrsock_teardown_data_request_callback(&state); + + /* Did wait timeout or got signal? */ + + if (ret != 0) + { + goto errout_unlock; + } + + /* Was socket aborted? */ + + if (conn->state == USRSOCK_CONN_STATE_ABORTED) + { + ret = -EPIPE; + goto errout_unlock; + } + + /* Did remote disconnect? */ + + if (conn->flags & USRSOCK_EVENT_REMOTE_CLOSED) + { + ret = 0; + goto errout_unlock; + } + + DEBUGASSERT(conn->flags & USRSOCK_EVENT_RECVFROM_AVAIL); + } + + /* Set up event callback for usrsock. */ + + ret = usrsock_setup_data_request_callback( + conn, &state, recvfrom_event, + USRSOCK_EVENT_ABORT | USRSOCK_EVENT_REQ_COMPLETE); + if (ret < 0) + { + nwarn("usrsock_setup_request_callback failed: %d\n", ret); + goto errout_unlock; + } + + inbufs[0].iov_base = (FAR void *)from; + inbufs[0].iov_len = addrlen; + inbufs[1].iov_base = (FAR void *)buf; + inbufs[1].iov_len = len; + + setup_conn_recvfrom(conn, inbufs, ARRAY_SIZE(inbufs)); + + /* Request user-space daemon to close socket. */ + + ret = do_recvfrom_request(conn, len, addrlen); + if (ret >= 0) + { + /* Wait for completion of request. */ + + while (net_lockedwait(&state.reqstate.recvsem) != OK) + { + DEBUGASSERT(*get_errno_ptr() == EINTR); + } + + ret = state.reqstate.result; + + DEBUGASSERT(ret <= (ssize_t)len); + DEBUGASSERT(state.valuelen <= addrlen); + DEBUGASSERT(state.valuelen <= state.valuelen_nontrunc); + + if (ret >= 0) + { + /* Store length of 'from' address that was available at + * daemon-side. */ + + outaddrlen = state.valuelen_nontrunc; + } + } + + setup_conn_recvfrom(conn, NULL, 0); + usrsock_teardown_data_request_callback(&state); + } + while (ret == -EAGAIN); + +errout_unlock: + net_unlock(); + + if (fromlen) + { + *fromlen = outaddrlen; + } + + return ret; +} + +#endif /* CONFIG_NET && CONFIG_NET_USRSOCK */ diff --git a/net/usrsock/usrsock_sendto.c b/net/usrsock/usrsock_sendto.c new file mode 100644 index 0000000000..dc747d451c --- /dev/null +++ b/net/usrsock/usrsock_sendto.c @@ -0,0 +1,426 @@ +/**************************************************************************** + * net/usrsock/usrsock_sendto.c + * + * Copyright (C) 2015, 2017 Haltian Ltd. All rights reserved. + * Author: Jussi Kivilinna + * + * 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 +#if defined(CONFIG_NET) && defined(CONFIG_NET_USRSOCK) + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include + +#include "socket/socket.h" +#include "usrsock/usrsock.h" + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static uint16_t sendto_event(FAR struct net_driver_s *dev, FAR void *pvconn, + FAR void *pvpriv, uint16_t flags) +{ + FAR struct usrsock_reqstate_s *pstate = pvpriv; + FAR struct usrsock_conn_s *conn = pvconn; + + if (flags & USRSOCK_EVENT_ABORT) + { + ninfo("socket aborted.\n"); + + pstate->result = -ECONNABORTED; + + /* Stop further callbacks */ + + pstate->cb->flags = 0; + pstate->cb->priv = NULL; + pstate->cb->event = NULL; + + /* Wake up the waiting thread */ + + sem_post(&pstate->recvsem); + } + else if (flags & USRSOCK_EVENT_REQ_COMPLETE) + { + ninfo("request completed.\n"); + + pstate->result = conn->resp.result; + + if (pstate->result >= 0 || pstate->result == -EAGAIN) + { + /* After reception of data, mark input not ready. Daemon will + * send event to restore this flag. */ + + conn->flags &= ~USRSOCK_EVENT_SENDTO_READY; + } + + /* Stop further callbacks */ + + pstate->cb->flags = 0; + pstate->cb->priv = NULL; + pstate->cb->event = NULL; + + /* Wake up the waiting thread */ + + sem_post(&pstate->recvsem); + } + else if (flags & USRSOCK_EVENT_REMOTE_CLOSED) + { + ninfo("remote closed.\n"); + + pstate->result = -EPIPE; + + /* Stop further callbacks */ + + pstate->cb->flags = 0; + pstate->cb->priv = NULL; + pstate->cb->event = NULL; + + /* Wake up the waiting thread */ + + sem_post(&pstate->recvsem); + } + else if (flags & USRSOCK_EVENT_SENDTO_READY) + { + ninfo("sendto ready.\n"); + + /* Do not let other waiters to claim new data. */ + + flags &= ~USRSOCK_EVENT_SENDTO_READY; + + /* Stop further callbacks */ + + pstate->cb->flags = 0; + pstate->cb->priv = NULL; + pstate->cb->event = NULL; + + /* Wake up the waiting thread */ + + sem_post(&pstate->recvsem); + } + + return flags; +} + +/**************************************************************************** + * Name: do_sendto_request + ****************************************************************************/ + +static int do_sendto_request(FAR struct usrsock_conn_s *conn, + FAR const void *buf, size_t buflen, + FAR const struct sockaddr *addr, + socklen_t addrlen) +{ + struct usrsock_request_sendto_s req = {}; + struct iovec bufs[3]; + + if (addrlen > UINT16_MAX) + { + addrlen = UINT16_MAX; + } + + if (buflen > UINT16_MAX) + { + buflen = UINT16_MAX; + } + + /* Prepare request for daemon to read. */ + + req.head.reqid = USRSOCK_REQUEST_SENDTO; + req.usockid = conn->usockid; + req.addrlen = addrlen; + req.buflen = buflen; + + bufs[0].iov_base = (FAR void *)&req; + bufs[0].iov_len = sizeof(req); + bufs[1].iov_base = (FAR void *)addr; + bufs[1].iov_len = addrlen; + bufs[2].iov_base = (FAR void *)buf; + bufs[2].iov_len = buflen; + + return usrsockdev_do_request(conn, bufs, ARRAY_SIZE(bufs)); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: usrsock_sendto + * + * Description: + * If sendto() is used on a connection-mode (SOCK_STREAM, SOCK_SEQPACKET) + * socket, the parameters to and 'tolen' are ignored (and the error EISCONN + * may be returned when they are not NULL and 0), and the error ENOTCONN is + * returned when the socket was not actually connected. + * + * Parameters: + * psock A pointer to a NuttX-specific, internal socket structure + * buf Data to send + * len Length of data to send + * flags Send flags + * to Address of recipient + * tolen The length of the address structure + * + ****************************************************************************/ + +ssize_t usrsock_sendto(FAR struct socket *psock, FAR const void *buf, + size_t len, FAR const struct sockaddr *to, + socklen_t tolen) +{ + FAR struct usrsock_conn_s *conn = psock->s_conn; + struct usrsock_reqstate_s state = {}; + ssize_t ret; +#ifdef CONFIG_NET_SOCKOPTS + struct timespec abstime; +#endif + struct timespec *ptimeo = NULL; + + DEBUGASSERT(conn); + + net_lock(); + + if (conn->state == USRSOCK_CONN_STATE_UNINITIALIZED || + conn->state == USRSOCK_CONN_STATE_ABORTED) + { + /* Invalid state or closed by daemon. */ + + ninfo("usockid=%d; connect() with uninitialized usrsock.\n", + conn->usockid); + + ret = (conn->state == USRSOCK_CONN_STATE_ABORTED) ? -EPIPE : -ECONNRESET; + goto errout_unlock; + } + + if (conn->type == SOCK_STREAM || conn->type == SOCK_SEQPACKET) + { + if (!conn->connected) + { + if (conn->state == USRSOCK_CONN_STATE_CONNECTING) + { + /* Connecting. */ + + ninfo("usockid=%d; socket still connecting.\n", + conn->usockid); + + ret = -EAGAIN; + goto errout_unlock; + } + else + { + /* Not connected. */ + + ret = -ENOTCONN; + goto errout_unlock; + } + } + + if (to || tolen) + { + /* Address provided for connection-mode socket */ + + ret = -EISCONN; + goto errout_unlock; + } + } + + if (conn->state == USRSOCK_CONN_STATE_CONNECTING) + { + /* Non-blocking connecting. */ + + ninfo("usockid=%d; socket still connecting.\n", conn->usockid); + + ret = -EAGAIN; + goto errout_unlock; + } + +#ifdef CONFIG_NET_SOCKOPTS + if (psock->s_sndtimeo != 0) + { + DEBUGVERIFY(clock_gettime(CLOCK_REALTIME, &abstime)); + + /* Prepare timeout value for sendto. */ + + abstime.tv_sec += psock->s_sndtimeo / DSEC_PER_SEC; + abstime.tv_nsec += (psock->s_sndtimeo % DSEC_PER_SEC) * NSEC_PER_DSEC; + if (abstime.tv_nsec >= NSEC_PER_SEC) + { + abstime.tv_sec++; + abstime.tv_nsec -= NSEC_PER_SEC; + } + + ptimeo = &abstime; + } +#endif + + do + { + /* Check if remote end has closed connection. */ + + if (conn->flags & USRSOCK_EVENT_REMOTE_CLOSED) + { + ninfo("usockid=%d; remote closed.\n", conn->usockid); + + ret = -EPIPE; + goto errout_unlock; + } + + /* Check if need to wait for send to become ready. */ + + if (!(conn->flags & USRSOCK_EVENT_SENDTO_READY)) + { + if (_SS_ISNONBLOCK(psock->s_flags)) + { + /* Send busy at daemon side. */ + + ret = -EAGAIN; + goto errout_unlock; + } + + /* Wait send to become ready. */ + + ret = usrsock_setup_request_callback(conn, &state, sendto_event, + USRSOCK_EVENT_ABORT | + USRSOCK_EVENT_SENDTO_READY | + USRSOCK_EVENT_REMOTE_CLOSED); + if (ret < 0) + { + nwarn("usrsock_setup_request_callback failed: %d\n", ret); + goto errout_unlock; + } + + /* Wait for send-ready (or abort, or timeout, or signal). */ + + ret = 0; + if (net_timedwait(&state.recvsem, ptimeo) != OK) + { + ret = *get_errno_ptr(); + + if (ret == ETIMEDOUT) + { + ninfo("sendto timedout\n"); + + ret = -EAGAIN; + } + else if (ret == EINTR) + { + ninfo("sendto interrupted\n"); + + ret = -EINTR; + } + else + { + nerr("net_timedwait errno: %d\n", ret); + DEBUGASSERT(false); + } + } + + usrsock_teardown_request_callback(&state); + + /* Did wait timeout or got signal? */ + + if (ret != 0) + { + goto errout_unlock; + } + + /* Was socket aborted? */ + + if (conn->state == USRSOCK_CONN_STATE_ABORTED) + { + ret = -EPIPE; + goto errout_unlock; + } + + /* Did remote disconnect? */ + + if (conn->flags & USRSOCK_EVENT_REMOTE_CLOSED) + { + ret = -EPIPE; + goto errout_unlock; + } + + DEBUGASSERT(conn->flags & USRSOCK_EVENT_SENDTO_READY); + } + + /* Set up event callback for usrsock. */ + + ret = usrsock_setup_request_callback(conn, &state, sendto_event, + USRSOCK_EVENT_ABORT | + USRSOCK_EVENT_REQ_COMPLETE); + if (ret < 0) + { + nwarn("usrsock_setup_request_callback failed: %d\n", ret); + goto errout_unlock; + } + + /* Request user-space daemon to close socket. */ + + ret = do_sendto_request(conn, buf, len, to, tolen); + if (ret >= 0) + { + /* Wait for completion of request. */ + + while (net_lockedwait(&state.recvsem) != OK) + { + DEBUGASSERT(*get_errno_ptr() == EINTR); + } + + ret = state.result; + + DEBUGASSERT(ret <= (ssize_t)len); + } + + usrsock_teardown_request_callback(&state); + } + while (ret == -EAGAIN); + +errout_unlock: + net_unlock(); + return ret; +} + +#endif /* CONFIG_NET && CONFIG_NET_USRSOCK */ diff --git a/net/usrsock/usrsock_setsockopt.c b/net/usrsock/usrsock_setsockopt.c new file mode 100644 index 0000000000..5795fdee94 --- /dev/null +++ b/net/usrsock/usrsock_setsockopt.c @@ -0,0 +1,230 @@ +/**************************************************************************** + * net/usrsock/usrsock_setsockopt.c + * + * Copyright (C) 2015, 2017 Haltian Ltd. All rights reserved. + * Author: Jussi Kivilinna + * + * 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 +#if defined(CONFIG_NET) && defined(CONFIG_NET_USRSOCK) && \ + defined(CONFIG_NET_SOCKOPTS) + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include + +#include "socket/socket.h" +#include "usrsock/usrsock.h" + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static uint16_t setsockopt_event(FAR struct net_driver_s *dev, FAR void *pvconn, + FAR void *pvpriv, uint16_t flags) +{ + FAR struct usrsock_reqstate_s *pstate = pvpriv; + FAR struct usrsock_conn_s *conn = pvconn; + + if (flags & USRSOCK_EVENT_ABORT) + { + ninfo("socket aborted.\n"); + + pstate->result = -ECONNABORTED; + + /* Stop further callbacks */ + + pstate->cb->flags = 0; + pstate->cb->priv = NULL; + pstate->cb->event = NULL; + + /* Wake up the waiting thread */ + + sem_post(&pstate->recvsem); + } + else if (flags & USRSOCK_EVENT_REQ_COMPLETE) + { + ninfo("request completed.\n"); + + pstate->result = conn->resp.result; + + /* Stop further callbacks */ + + pstate->cb->flags = 0; + pstate->cb->priv = NULL; + pstate->cb->event = NULL; + + /* Wake up the waiting thread */ + + sem_post(&pstate->recvsem); + } + + return flags; +} + +/**************************************************************************** + * Name: do_setsockopt_request + ****************************************************************************/ + +static int do_setsockopt_request(FAR struct usrsock_conn_s *conn, + int level, int option, FAR const void *value, + socklen_t value_len) +{ + struct usrsock_request_setsockopt_s req = {}; + struct iovec bufs[2]; + + if (level < INT16_MIN || level > INT16_MAX) + { + return -EINVAL; + } + + if (option < INT16_MIN || option > INT16_MAX) + { + return -EINVAL; + } + + if (value_len > UINT16_MAX) + { + value_len = UINT16_MAX; + } + + /* Prepare request for daemon to read. */ + + req.head.reqid = USRSOCK_REQUEST_SETSOCKOPT; + req.usockid = conn->usockid; + req.level = level; + req.option = option; + req.valuelen = value_len; + + bufs[0].iov_base = (FAR void *)&req; + bufs[0].iov_len = sizeof(req); + bufs[1].iov_base = (FAR void *)value; + bufs[1].iov_len = req.valuelen; + + return usrsockdev_do_request(conn, bufs, ARRAY_SIZE(bufs)); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: usrsock_setsockopt + * + * Description: + * psock_setsockopt() sets the option specified by the 'option' argument, + * at the protocol level specified by the 'level' argument, to the value + * pointed to by the 'value' argument for the socket on the 'psock' argument. + * + * The 'level' argument specifies the protocol level of the option. To set + * options at the socket level, specify the level argument as SOL_SOCKET. + * + * See a complete list of values for the 'option' argument. + * + * Parameters: + * conn usrsock socket connection structure + * level Protocol level to set the option + * option identifies the option to set + * value Points to the argument value + * value_len The length of the argument value + * + ****************************************************************************/ + +int usrsock_setsockopt(FAR struct usrsock_conn_s *conn, int level, int option, + FAR const void *value, FAR socklen_t value_len) +{ + struct usrsock_reqstate_s state = {}; + ssize_t ret; + + DEBUGASSERT(conn); + + net_lock(); + + if (conn->state == USRSOCK_CONN_STATE_UNINITIALIZED || + conn->state == USRSOCK_CONN_STATE_ABORTED) + { + /* Invalid state or closed by daemon. */ + + ninfo("usockid=%d; connect() with uninitialized usrsock.\n", + conn->usockid); + + ret = (conn->state == USRSOCK_CONN_STATE_ABORTED) ? -EPIPE : -ECONNRESET; + goto errout_unlock; + } + + /* Set up event callback for usrsock. */ + + ret = usrsock_setup_request_callback(conn, &state, setsockopt_event, + USRSOCK_EVENT_ABORT | + USRSOCK_EVENT_REQ_COMPLETE); + if (ret < 0) + { + nwarn("usrsock_setup_request_callback failed: %d\n", ret); + goto errout_unlock; + } + + /* Request user-space daemon to close socket. */ + + ret = do_setsockopt_request(conn, level, option, value, value_len); + if (ret >= 0) + { + /* Wait for completion of request. */ + + while (net_lockedwait(&state.recvsem) != OK) + { + DEBUGASSERT(*get_errno_ptr() == EINTR); + } + + ret = state.result; + } + + usrsock_teardown_request_callback(&state); + +errout_unlock: + net_unlock(); + return ret; +} + +#endif /* CONFIG_NET && CONFIG_NET_USRSOCK && CONFIG_NET_SOCKOPTS */ diff --git a/net/usrsock/usrsock_socket.c b/net/usrsock/usrsock_socket.c new file mode 100644 index 0000000000..71764befea --- /dev/null +++ b/net/usrsock/usrsock_socket.c @@ -0,0 +1,265 @@ +/**************************************************************************** + * net/usrsock/usrsock_socket.c + * + * Copyright (C) 2015, 2017 Haltian Ltd. All rights reserved. + * Author: Jussi Kivilinna + * + * 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 +#if defined(CONFIG_NET) && defined(CONFIG_NET_USRSOCK) + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include + +#include "devif/devif.h" +#include "usrsock/usrsock.h" + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static uint16_t socket_event(FAR struct net_driver_s *dev, FAR void *pvconn, + FAR void *pvpriv, uint16_t flags) +{ + FAR struct usrsock_reqstate_s *pstate = pvpriv; + FAR struct usrsock_conn_s *conn = pvconn; + + if (flags & USRSOCK_EVENT_ABORT) + { + ninfo("socket aborted.\n"); + + pstate->result = -ENETDOWN; + + /* Stop further callbacks */ + + pstate->cb->flags = 0; + pstate->cb->priv = NULL; + pstate->cb->event = NULL; + + /* Wake up the waiting thread */ + + sem_post(&pstate->recvsem); + } + else if (flags & USRSOCK_EVENT_REQ_COMPLETE) + { + ninfo("request completed.\n"); + + pstate->result = conn->resp.result; + if (pstate->result >= 0) + { + /* We might start getting events for this socket right after + * returning to daemon, so setup 'conn' already here. */ + + conn->state = USRSOCK_CONN_STATE_READY; + conn->usockid = pstate->result; + } + + /* Stop further callbacks */ + + pstate->cb->flags = 0; + pstate->cb->priv = NULL; + pstate->cb->event = NULL; + + /* Wake up the waiting thread */ + + sem_post(&pstate->recvsem); + } + + return flags; +} + +/**************************************************************************** + * Name: do_socket_request + ****************************************************************************/ + +static int do_socket_request(FAR struct usrsock_conn_s *conn, int domain, + int type, int protocol) +{ + struct usrsock_request_socket_s req = {}; + struct iovec bufs[1]; + + /* Prepare request for daemon to read. */ + + req.head.reqid = USRSOCK_REQUEST_SOCKET; + req.domain = domain; + req.type = type; + req.protocol = protocol; + + if (req.domain != domain) + { + return -EINVAL; + } + + if (req.type != type) + { + return -EINVAL; + } + + if (req.protocol != protocol) + { + return -EINVAL; + } + + bufs[0].iov_base = (FAR void *)&req; + bufs[0].iov_len = sizeof(req); + + return usrsockdev_do_request(conn, bufs, ARRAY_SIZE(bufs)); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: usrsock_socket + * + * Description: + * socket() creates an endpoint for communication and returns a socket + * structure. + * + * Parameters: + * domain (see sys/socket.h) + * type (see sys/socket.h) + * protocol (see sys/socket.h) + * psock A pointer to a user allocated socket structure to be initialized. + * + * Returned Value: + * 0 on success; negative error-code on error + * + * EACCES + * Permission to create a socket of the specified type and/or protocol + * is denied. + * EAFNOSUPPORT + * The implementation does not support the specified address family. + * EINVAL + * Unknown protocol, or protocol family not available. + * EMFILE + * Process file table overflow. + * ENFILE + * The system limit on the total number of open files has been reached. + * ENOBUFS or ENOMEM + * Insufficient memory is available. The socket cannot be created until + * sufficient resources are freed. + * EPROTONOSUPPORT + * The protocol type or the specified protocol is not supported within + * this domain. + * + * Assumptions: + * + ****************************************************************************/ + +int usrsock_socket(int domain, int type, int protocol, FAR struct socket *psock) +{ + struct usrsock_reqstate_s state = {}; + FAR struct usrsock_conn_s *conn; + int err; + + /* Allocate the usrsock socket connection structure and save in the new + * socket instance. + */ + + conn = usrsock_alloc(); + if (!conn) + { + /* Failed to reserve a connection structure */ + + return -ENOMEM; + } + + net_lock(); + + /* Set up event callback for usrsock. */ + + err = usrsock_setup_request_callback(conn, &state, socket_event, + USRSOCK_EVENT_ABORT | + USRSOCK_EVENT_REQ_COMPLETE); + if (err < 0) + { + goto errout_free_conn; + } + + /* Request user-space daemon for new socket. */ + + err = do_socket_request(conn, domain, type, protocol); + if (err < 0) + { + goto errout_teardown_callback; + } + + /* Wait for completion of request. */ + + while (net_lockedwait(&state.recvsem) != OK) + { + DEBUGASSERT(*get_errno_ptr() == EINTR); + } + + if (state.result < 0) + { + err = state.result; + goto errout_teardown_callback; + } + + psock->s_type = SOCK_USRSOCK_TYPE; + psock->s_domain = PF_USRSOCK_DOMAIN; + conn->type = type; + psock->s_conn = conn; + conn->crefs = 1; + + usrsock_teardown_request_callback(&state); + + net_unlock(); + + return OK; + +errout_teardown_callback: + usrsock_teardown_request_callback(&state); +errout_free_conn: + usrsock_free(conn); + net_unlock(); + + return err; +} + +#endif /* CONFIG_NET && CONFIG_NET_USRSOCK */ -- GitLab From 44f1326046a864a13e2a08a1a8ebd1d49018661a Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 31 Mar 2017 10:04:29 -0600 Subject: [PATCH 288/990] 6loWPAN: Repartition device-specific vs. global data -- again. --- include/nuttx/net/sixlowpan.h | 104 ------------------------ net/sixlowpan/sixlowpan_compressor.c | 1 - net/sixlowpan/sixlowpan_framer.c | 27 +++---- net/sixlowpan/sixlowpan_globals.c | 39 ++++++++- net/sixlowpan/sixlowpan_hc06.c | 1 - net/sixlowpan/sixlowpan_internal.h | 117 +++++++++++++++++++++++---- net/sixlowpan/sixlowpan_send.c | 64 +++++++-------- net/sixlowpan/sixlowpan_sniffer.c | 1 - net/sixlowpan/sixlowpan_tcpsend.c | 2 - net/sixlowpan/sixlowpan_udpsend.c | 2 - net/sixlowpan/sixlowpan_utils.c | 15 ++-- 11 files changed, 190 insertions(+), 183 deletions(-) diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index 66c84ac58f..b9b995cdae 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -233,63 +233,6 @@ #define SIXLOWPAN_MAC_STDFRAME 127 -/* Packet buffer Definitions */ - -#define PACKETBUF_HDR_SIZE 48 - -#define PACKETBUF_ATTR_PACKET_TYPE_DATA 0 -#define PACKETBUF_ATTR_PACKET_TYPE_ACK 1 -#define PACKETBUF_ATTR_PACKET_TYPE_STREAM 2 -#define PACKETBUF_ATTR_PACKET_TYPE_STREAM_END 3 -#define PACKETBUF_ATTR_PACKET_TYPE_TIMESTAMP 4 - -/* Packet buffer attributes (indices into i_pktattr) */ - -#define PACKETBUF_ATTR_NONE 0 - -/* Scope 0 attributes: used only on the local node. */ - -#define PACKETBUF_ATTR_CHANNEL 1 -#define PACKETBUF_ATTR_NETWORK_ID 2 -#define PACKETBUF_ATTR_LINK_QUALITY 3 -#define PACKETBUF_ATTR_RSSI 4 -#define PACKETBUF_ATTR_TIMESTAMP 5 -#define PACKETBUF_ATTR_RADIO_TXPOWER 6 -#define PACKETBUF_ATTR_LISTEN_TIME 7 -#define PACKETBUF_ATTR_TRANSMIT_TIME 8 -#define PACKETBUF_ATTR_MAX_MAC_TRANSMISSIONS 9 -#define PACKETBUF_ATTR_MAC_SEQNO 10 -#define PACKETBUF_ATTR_MAC_ACK 11 - -/* Scope 1 attributes: used between two neighbors only. */ - -#define PACKETBUF_ATTR_RELIABLE 12 -#define PACKETBUF_ATTR_PACKET_ID 13 -#define PACKETBUF_ATTR_PACKET_TYPE 14 -#define PACKETBUF_ATTR_REXMIT 15 -#define PACKETBUF_ATTR_MAX_REXMIT 16 -#define PACKETBUF_ATTR_NUM_REXMIT 17 -#define PACKETBUF_ATTR_PENDING 18 - -/* Scope 2 attributes: used between end-to-end nodes. */ - -#define PACKETBUF_ATTR_HOPS 11 -#define PACKETBUF_ATTR_TTL 20 -#define PACKETBUF_ATTR_EPACKET_ID 21 -#define PACKETBUF_ATTR_EPACKET_TYPE 22 -#define PACKETBUF_ATTR_ERELIABLE 23 - -#define PACKETBUF_NUM_ATTRS 24 - -/* Addresses (indices into i_pktaddr) */ - -#define PACKETBUF_ADDR_SENDER 0 -#define PACKETBUF_ADDR_RECEIVER 1 -#define PACKETBUF_ADDR_ESENDER 2 -#define PACKETBUF_ADDR_ERECEIVER 3 - -#define PACKETBUF_NUM_ADDRS 4 - /* Frame buffer helper macros. * * The IEEE802.15.4 MAC driver structures includes a list of IOB @@ -427,19 +370,6 @@ struct rimeaddr_s * * The MAC driver should then inform the network of the by calling * sixlowpan_input(). - * - * Frame Organization. The IOB data is retained in the io_data[] field of the - * IOB structure like: - * - * Content Offset - * +------------------+ 0 - * | Frame Header | - * +------------------+ i_dataoffset - * | Procotol Headers | - * | Data Payload | - * +------------------+ io_len - * | Unused | - * +------------------+ CONFIG_NET_6LOWPAN_FRAMELEN */ struct ieee802154_driver_s @@ -492,40 +422,6 @@ struct ieee802154_driver_s */ uint8_t i_dsn; - - /* The following fields are device-specific metadata used by the 6loWPAN - * stack and should not be modified by the IEEE802.15.4 MAC network drvier. - */ - - /* A pointer to the rime buffer. - * - * We initialize it to the beginning of the rime buffer, then access - * different fields by updating the offset ieee->i_rime_hdrlen. - */ - - FAR uint8_t *i_rimeptr; - - /* i_uncomp_hdrlen is the length of the headers before compression (if HC2 - * is used this includes the UDP header in addition to the IP header). - */ - - uint8_t i_uncomp_hdrlen; - - /* i_rime_hdrlen is the total length of (the processed) 6lowpan headers - * (fragment headers, IPV6 or HC1, HC2, and HC1 and HC2 non compressed - * fields). - */ - - uint8_t i_rime_hdrlen; - - /* Offset first available byte for the payload after header region. */ - - uint8_t i_dataoffset; - - /* Packet buffer metadata: Attributes and addresses */ - - uint16_t i_pktattrs[PACKETBUF_NUM_ATTRS]; - struct rimeaddr_s i_pktaddrs[PACKETBUF_NUM_ADDRS]; }; /* The structure of a next header compressor. This compressor is provided diff --git a/net/sixlowpan/sixlowpan_compressor.c b/net/sixlowpan/sixlowpan_compressor.c index 837bad7760..7450e408e2 100644 --- a/net/sixlowpan/sixlowpan_compressor.c +++ b/net/sixlowpan/sixlowpan_compressor.c @@ -40,7 +40,6 @@ #include #include "nuttx/net/net.h" -#include "nuttx/net/sixlowpan.h" #include "sixlowpan/sixlowpan_internal.h" diff --git a/net/sixlowpan/sixlowpan_framer.c b/net/sixlowpan/sixlowpan_framer.c index 3c753f3530..ab5fc06fe3 100644 --- a/net/sixlowpan/sixlowpan_framer.c +++ b/net/sixlowpan/sixlowpan_framer.c @@ -55,7 +55,6 @@ #include #include "nuttx/net/net.h" -#include "nuttx/net/sixlowpan.h" #include "sixlowpan/sixlowpan_internal.h" @@ -299,21 +298,21 @@ static void sixlowpan_setup_params(FAR struct ieee802154_driver_s *ieee, /* Reset to an empty frame */ - ieee->i_dataoffset = 0; + FRAME_RESET(); /* Build the FCF (Only non-zero elements need to be initialized). */ params->fcf.frame_type = FRAME802154_DATAFRAME; - params->fcf.frame_pending = ieee->i_pktattrs[PACKETBUF_ATTR_PENDING]; + params->fcf.frame_pending = g_pktattrs[PACKETBUF_ATTR_PENDING]; /* If the output address is NULL in the Rime buf, then it is broadcast * on the 802.15.4 network. */ - rcvrnull = sixlowpan_addrnull(ieee->i_pktaddrs[PACKETBUF_ADDR_RECEIVER].u8); + rcvrnull = sixlowpan_addrnull(g_pktaddrs[PACKETBUF_ADDR_RECEIVER].u8); if (rcvrnull) { - params->fcf.ack_required = ieee->i_pktattrs[PACKETBUF_ATTR_MAC_ACK]; + params->fcf.ack_required = g_pktattrs[PACKETBUF_ATTR_MAC_ACK]; } /* Insert IEEE 802.15.4 (2003) version bit. */ @@ -322,14 +321,14 @@ static void sixlowpan_setup_params(FAR struct ieee802154_driver_s *ieee, /* Increment and set the data sequence number. */ - if (ieee->i_pktattrs[PACKETBUF_ATTR_MAC_SEQNO] != 0) + if (g_pktattrs[PACKETBUF_ATTR_MAC_SEQNO] != 0) { - params->seq = ieee->i_pktattrs[PACKETBUF_ATTR_MAC_SEQNO]; + params->seq = g_pktattrs[PACKETBUF_ATTR_MAC_SEQNO]; } else { params->seq = ieee->i_dsn++; - ieee->i_pktattrs[PACKETBUF_ATTR_MAC_SEQNO] = params->seq; + g_pktattrs[PACKETBUF_ATTR_MAC_SEQNO] = params->seq; } /* Complete the addressing fields. */ @@ -355,7 +354,7 @@ static void sixlowpan_setup_params(FAR struct ieee802154_driver_s *ieee, /* Copy the destination address */ rimeaddr_copy((struct rimeaddr_s *)¶ms->dest_addr, - ieee->i_pktaddrs[PACKETBUF_ADDR_RECEIVER].u8); + g_pktaddrs[PACKETBUF_ADDR_RECEIVER].u8); /* Use short address mode if so configured */ @@ -374,8 +373,8 @@ static void sixlowpan_setup_params(FAR struct ieee802154_driver_s *ieee, if (iob != NULL) { - params->payload = FRAME_DATA_START(ieee, iob); - params->payload_len = FRAME_DATA_SIZE(ieee, iob); + params->payload = FRAME_DATA_START(iob); + params->payload_len = FRAME_DATA_SIZE(iob); } } @@ -551,7 +550,7 @@ int sixlowpan_framecreate(FAR struct ieee802154_driver_s *ieee, /* Allocate space for the header in the frame buffer */ - ret = sixlowpan_frame_hdralloc(ieee, iob, len); + ret = sixlowpan_frame_hdralloc(iob, len); if (ret < 0) { wlerr("ERROR: Header too large: %u\n", len); @@ -560,10 +559,10 @@ int sixlowpan_framecreate(FAR struct ieee802154_driver_s *ieee, /* Then create the frame */ - sixlowpan_802154_framecreate(¶ms, FRAME_HDR_START(ieee, iob), len); + sixlowpan_802154_framecreate(¶ms, FRAME_HDR_START(iob), len); wlinfo("Frame type: %02x Data len: %d %u (%u)\n", - params.fcf.frame_type, len, FRAME_DATA_SIZE(ieee, iob), + params.fcf.frame_type, len, FRAME_DATA_SIZE(iob), FRAME_SIZE(ieee, iob)); #if CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 2 wlinfo("Dest address: %02x:%02x\n", diff --git a/net/sixlowpan/sixlowpan_globals.c b/net/sixlowpan/sixlowpan_globals.c index 4be92354dd..1c7c378df0 100644 --- a/net/sixlowpan/sixlowpan_globals.c +++ b/net/sixlowpan/sixlowpan_globals.c @@ -39,8 +39,6 @@ #include -#include "nuttx/net/sixlowpan.h" - #include "sixlowpan/sixlowpan_internal.h" #ifdef CONFIG_NET_6LOWPAN @@ -59,4 +57,41 @@ FAR struct sixlowpan_nhcompressor_s *g_sixlowpan_compressor; FAR struct sixlowpan_rime_sniffer_s *g_sixlowpan_sniffer; #endif +/* The following data values are used to hold intermediate settings while + * processing IEEE802.15.4 frames. These globals are shared with incoming + * and outgoing frame processing and possibly with mutliple IEEE802.15.4 MAC + * devices. The network lock provides exclusive use of these globals + * during that processing + */ + +/* A pointer to the rime buffer. + * + * We initialize it to the beginning of the rime buffer, then access + * different fields by updating the offset ieee->g_rime_hdrlen. + */ + +FAR uint8_t *g_rimeptr; + +/* g_uncomp_hdrlen is the length of the headers before compression (if HC2 + * is used this includes the UDP header in addition to the IP header). + */ + +uint8_t g_uncomp_hdrlen; + +/* g_rime_hdrlen is the total length of (the processed) 6lowpan headers + * (fragment headers, IPV6 or HC1, HC2, and HC1 and HC2 non compressed + * fields). + */ + +uint8_t g_rime_hdrlen; + +/* Offset first available byte for the payload after header region. */ + +uint8_t g_dataoffset; + +/* Packet buffer metadata: Attributes and addresses */ + +uint16_t g_pktattrs[PACKETBUF_NUM_ATTRS]; +struct rimeaddr_s g_pktaddrs[PACKETBUF_NUM_ADDRS]; + #endif /* CONFIG_NET_6LOWPAN */ diff --git a/net/sixlowpan/sixlowpan_hc06.c b/net/sixlowpan/sixlowpan_hc06.c index 534cb1adbf..e8d0cf3d89 100644 --- a/net/sixlowpan/sixlowpan_hc06.c +++ b/net/sixlowpan/sixlowpan_hc06.c @@ -59,7 +59,6 @@ #include #include -#include #include "sixlowpan/sixlowpan_internal.h" diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index a1166aed35..05240dafdf 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -63,6 +63,7 @@ #include #include #include +#include #ifdef CONFIG_NET_6LOWPAN @@ -83,25 +84,20 @@ /* Frame buffer helpers */ -#define FRAME_RESET(ieee) \ +#define FRAME_RESET() \ do \ { \ - (ieee)->i_dataoffset = 0; \ + g_dataoffset = 0; \ } \ while (0) -#define FRAME_HDR_START(ieee,iob) \ - ((iob)->io_data) -#define FRAME_HDR_SIZE(ieee,iob) \ - ((ieee)->i_dataoffset) +#define FRAME_HDR_START(iob) ((iob)->io_data) +#define FRAME_HDR_SIZE(iob) g_dataoffset -#define FRAME_DATA_START(ieee,iob) \ - ((FAR uint8_t *)((iob)->io_data) + (ieee)->i_dataoffset) -#define FRAME_DATA_SIZE(ieee,iob) \ - ((iob)->io_len - (ieee)->i_dataoffset) +#define FRAME_DATA_START(iob) ((FAR uint8_t *)((iob)->io_data) + g_dataoffset) +#define FRAME_DATA_SIZE(iob) ((iob)->io_len - g_dataoffset) -#define FRAME_REMAINING(ieee,iob) \ - (CONFIG_NET_6LOWPAN_FRAMELEN - (iob)->io_len) +#define FRAME_REMAINING(iob) (CONFIG_NET_6LOWPAN_FRAMELEN - (iob)->io_len) #define FRAME_SIZE(ieee,iob) \ ((iob)->io_len) @@ -132,6 +128,63 @@ #define FRAME802154_SECURITY_LEVEL_NONE 0 #define FRAME802154_SECURITY_LEVEL_128 3 +/* Packet buffer Definitions */ + +#define PACKETBUF_HDR_SIZE 48 + +#define PACKETBUF_ATTR_PACKET_TYPE_DATA 0 +#define PACKETBUF_ATTR_PACKET_TYPE_ACK 1 +#define PACKETBUF_ATTR_PACKET_TYPE_STREAM 2 +#define PACKETBUF_ATTR_PACKET_TYPE_STREAM_END 3 +#define PACKETBUF_ATTR_PACKET_TYPE_TIMESTAMP 4 + +/* Packet buffer attributes (indices into i_pktattr) */ + +#define PACKETBUF_ATTR_NONE 0 + +/* Scope 0 attributes: used only on the local node. */ + +#define PACKETBUF_ATTR_CHANNEL 1 +#define PACKETBUF_ATTR_NETWORK_ID 2 +#define PACKETBUF_ATTR_LINK_QUALITY 3 +#define PACKETBUF_ATTR_RSSI 4 +#define PACKETBUF_ATTR_TIMESTAMP 5 +#define PACKETBUF_ATTR_RADIO_TXPOWER 6 +#define PACKETBUF_ATTR_LISTEN_TIME 7 +#define PACKETBUF_ATTR_TRANSMIT_TIME 8 +#define PACKETBUF_ATTR_MAX_MAC_TRANSMISSIONS 9 +#define PACKETBUF_ATTR_MAC_SEQNO 10 +#define PACKETBUF_ATTR_MAC_ACK 11 + +/* Scope 1 attributes: used between two neighbors only. */ + +#define PACKETBUF_ATTR_RELIABLE 12 +#define PACKETBUF_ATTR_PACKET_ID 13 +#define PACKETBUF_ATTR_PACKET_TYPE 14 +#define PACKETBUF_ATTR_REXMIT 15 +#define PACKETBUF_ATTR_MAX_REXMIT 16 +#define PACKETBUF_ATTR_NUM_REXMIT 17 +#define PACKETBUF_ATTR_PENDING 18 + +/* Scope 2 attributes: used between end-to-end nodes. */ + +#define PACKETBUF_ATTR_HOPS 11 +#define PACKETBUF_ATTR_TTL 20 +#define PACKETBUF_ATTR_EPACKET_ID 21 +#define PACKETBUF_ATTR_EPACKET_TYPE 22 +#define PACKETBUF_ATTR_ERELIABLE 23 + +#define PACKETBUF_NUM_ATTRS 24 + +/* Addresses (indices into i_pktaddr) */ + +#define PACKETBUF_ADDR_SENDER 0 +#define PACKETBUF_ADDR_RECEIVER 1 +#define PACKETBUF_ADDR_ESENDER 2 +#define PACKETBUF_ADDR_ERECEIVER 3 + +#define PACKETBUF_NUM_ADDRS 4 + /**************************************************************************** * Public Types ****************************************************************************/ @@ -242,6 +295,43 @@ struct sixlowpan_rime_sniffer_s; /* Foward reference */ extern FAR struct sixlowpan_rime_sniffer_s *g_sixlowpan_sniffer; #endif +/* The following data values are used to hold intermediate settings while + * processing IEEE802.15.4 frames. These globals are shared with incoming + * and outgoing frame processing and possibly with mutliple IEEE802.15.4 MAC + * devices. The network lock provides exclusive use of these globals + * during that processing + */ + +/* A pointer to the rime buffer. + * + * We initialize it to the beginning of the rime buffer, then access + * different fields by updating the offset ieee->g_rime_hdrlen. + */ + +extern FAR uint8_t *g_rimeptr; + +/* g_uncomp_hdrlen is the length of the headers before compression (if HC2 + * is used this includes the UDP header in addition to the IP header). + */ + +extern uint8_t g_uncomp_hdrlen; + +/* g_rime_hdrlen is the total length of (the processed) 6lowpan headers + * (fragment headers, IPV6 or HC1, HC2, and HC1 and HC2 non compressed + * fields). + */ + +extern uint8_t g_rime_hdrlen; + +/* Offset first available byte for the payload after header region. */ + +uint8_t g_dataoffset; + +/* Packet buffer metadata: Attributes and addresses */ + +extern uint16_t g_pktattrs[PACKETBUF_NUM_ATTRS]; +extern struct rimeaddr_s g_pktaddrs[PACKETBUF_NUM_ADDRS]; + /**************************************************************************** * Public Types ****************************************************************************/ @@ -478,8 +568,7 @@ void sixlowpan_uncompresshdr_hc1(FAR struct net_driver_s *dev, * ****************************************************************************/ -int sixlowpan_frame_hdralloc(FAR struct ieee802154_driver_s *ieee, - FAR struct iob_s *iob, int size); +int sixlowpan_frame_hdralloc(FAR struct iob_s *iob, int size); #endif /* CONFIG_NET_6LOWPAN */ #endif /* _NET_SIXLOWPAN_SIXLOWPAN_INTERNAL_H */ diff --git a/net/sixlowpan/sixlowpan_send.c b/net/sixlowpan/sixlowpan_send.c index c8f2846beb..cf9c8d751b 100644 --- a/net/sixlowpan/sixlowpan_send.c +++ b/net/sixlowpan/sixlowpan_send.c @@ -57,10 +57,6 @@ #include "nuttx/net/iob.h" #include "nuttx/net/netdev.h" #include "nuttx/net/ip.h" -#include "nuttx/net/tcp.h" -#include "nuttx/net/udp.h" -#include "nuttx/net/icmpv6.h" -#include "nuttx/net/sixlowpan.h" #include "iob/iob.h" #include "netdev/netdev.h" @@ -117,7 +113,7 @@ static void sixlowpan_set_pktattrs(FAR struct ieee802154_driver_s *ieee, /* Set protocol in NETWORK_ID */ - ieee->i_pktattrs[PACKETBUF_ATTR_NETWORK_ID] = ipv6->proto; + g_pktattrs[PACKETBUF_ATTR_NETWORK_ID] = ipv6->proto; /* Assign values to the channel attribute (port or type + code) */ @@ -148,7 +144,7 @@ static void sixlowpan_set_pktattrs(FAR struct ieee802154_driver_s *ieee, attr = icmp->type << 8 | icmp->code; } - ieee->i_pktattrs[PACKETBUF_ATTR_CHANNEL] = attr; + g_pktattrs[PACKETBUF_ATTR_CHANNEL] = attr; } /**************************************************************************** @@ -181,14 +177,14 @@ static void sixlowpan_compress_ipv6hdr(FAR struct ieee802154_driver_s *ieee, { /* Indicate the IPv6 dispatch and length */ - *ieee->i_rimeptr = SIXLOWPAN_DISPATCH_IPV6; - ieee->i_rime_hdrlen += SIXLOWPAN_IPV6_HDR_LEN; + *g_rimeptr = SIXLOWPAN_DISPATCH_IPV6; + g_rime_hdrlen += SIXLOWPAN_IPV6_HDR_LEN; /* Copy the IPv6 header and adjust pointers */ - memcpy(ieee->i_rimeptr + ieee->i_rime_hdrlen, ipv6, IPv6_HDRLEN); - ieee->i_rime_hdrlen += IPv6_HDRLEN; - ieee->i_uncomp_hdrlen += IPv6_HDRLEN; + memcpy(g_rimeptr + g_rime_hdrlen, ipv6, IPv6_HDRLEN); + g_rime_hdrlen += IPv6_HDRLEN; + g_uncomp_hdrlen += IPv6_HDRLEN; } /**************************************************************************** @@ -217,8 +213,8 @@ static int sixlowpan_send_frame(FAR struct ieee802154_driver_s *ieee, */ #if 0 /* Just some notes of what needs to be done in interrupt handler */ framer_hdrlen = sixlowpan_createframe(ieee, ieee->i_panid); - memcpy(ieee->i_rimeptr + ieee->i_rime_hdrlen, (uint8_t *)ipv6 + ieee->i_uncomp_hdrlen, len - ieee->i_uncomp_hdrlen); - iob->io_len = len - ieee->i_uncomp_hdrlen + ieee->i_rime_hdrlen; + memcpy(g_rimeptr + g_rime_hdrlen, (uint8_t *)ipv6 + g_uncomp_hdrlen, len - g_uncomp_hdrlen); + iob->io_len = len - g_uncomp_hdrlen + g_rime_hdrlen; #endif #warning Missing logic /* Notify the IEEE802.14.5 MAC driver that we have data to be sent */ @@ -274,20 +270,22 @@ int sixlowpan_send(FAR struct net_driver_s *dev, struct rimeaddr_s dest; uint16_t outlen = 0; - /* Initialize device-specific data */ + /* Initialize global data. Locking the network guarantees that we have + * exclusive use of the global values for intermediate calculations. + */ - FRAME_RESET(ieee); - ieee->i_uncomp_hdrlen = 0; - ieee->i_rime_hdrlen = 0; + FRAME_RESET(); + g_uncomp_hdrlen = 0; + g_rime_hdrlen = 0; /* REVISIT: Do I need this rimeptr? */ - ieee->i_rimeptr = &dev->d_buf[PACKETBUF_HDR_SIZE]; + g_rimeptr = &dev->d_buf[PACKETBUF_HDR_SIZE]; /* Reset rime buffer, packet buffer metatadata */ - memset(ieee->i_pktattrs, 0, PACKETBUF_NUM_ATTRS * sizeof(uint16_t)); - memset(ieee->i_pktaddrs, 0, PACKETBUF_NUM_ADDRS * sizeof(struct rimeaddr_s)); + memset(g_pktattrs, 0, PACKETBUF_NUM_ATTRS * sizeof(uint16_t)); + memset(g_pktaddrs, 0, PACKETBUF_NUM_ADDRS * sizeof(struct rimeaddr_s)); - ieee->i_pktattrs[PACKETBUF_ATTR_MAX_MAC_TRANSMISSIONS] = + g_pktattrs[PACKETBUF_ATTR_MAX_MAC_TRANSMISSIONS] = CONFIG_NET_6LOWPAN_MAX_MACTRANSMITS; #ifdef CONFIG_NET_6LOWPAN_SNIFFER @@ -295,10 +293,10 @@ int sixlowpan_send(FAR struct net_driver_s *dev, { /* Reset rime buffer, packet buffer metatadata */ - memset(ieee->i_pktattrs, 0, PACKETBUF_NUM_ATTRS * sizeof(uint16_t)); - memset(ieee->i_pktaddrs, 0, PACKETBUF_NUM_ADDRS * sizeof(struct rimeaddr_s)); + memset(g_pktattrs, 0, PACKETBUF_NUM_ATTRS * sizeof(uint16_t)); + memset(g_pktaddrs, 0, PACKETBUF_NUM_ADDRS * sizeof(struct rimeaddr_s)); - ieee->i_pktattrs[PACKETBUF_ATTR_MAX_MAC_TRANSMISSIONS] = + g_pktattrs[PACKETBUF_ATTR_MAX_MAC_TRANSMISSIONS] = CONFIG_NET_6LOWPAN_MAX_MACTRANSMITS; /* Call the attribution when the callback comes, but set attributes here */ @@ -309,10 +307,10 @@ int sixlowpan_send(FAR struct net_driver_s *dev, /* Reset rime buffer, packet buffer metatadata */ - memset(ieee->i_pktattrs, 0, PACKETBUF_NUM_ATTRS * sizeof(uint16_t)); - memset(ieee->i_pktaddrs, 0, PACKETBUF_NUM_ADDRS * sizeof(struct rimeaddr_s)); + memset(g_pktattrs, 0, PACKETBUF_NUM_ATTRS * sizeof(uint16_t)); + memset(g_pktaddrs, 0, PACKETBUF_NUM_ADDRS * sizeof(struct rimeaddr_s)); - ieee->i_pktattrs[PACKETBUF_ATTR_MAX_MAC_TRANSMISSIONS] = + g_pktattrs[PACKETBUF_ATTR_MAX_MAC_TRANSMISSIONS] = CONFIG_NET_6LOWPAN_MAX_MACTRANSMITS; /* Set stream mode for all TCP packets, except FIN packets. */ @@ -324,11 +322,11 @@ int sixlowpan_send(FAR struct net_driver_s *dev, if ((tcp->flags & TCP_FIN) == 0 && (tcp->flags & TCP_CTL) != TCP_ACK) { - ieee->i_pktattrs[PACKETBUF_ATTR_PACKET_TYPE] = PACKETBUF_ATTR_PACKET_TYPE_STREAM; + g_pktattrs[PACKETBUF_ATTR_PACKET_TYPE] = PACKETBUF_ATTR_PACKET_TYPE_STREAM; } else if ((tcp->flags & TCP_FIN) == TCP_FIN) { - ieee->i_pktattrs[PACKETBUF_ATTR_PACKET_TYPE] = PACKETBUF_ATTR_PACKET_TYPE_STREAM_END; + g_pktattrs[PACKETBUF_ATTR_PACKET_TYPE] = PACKETBUF_ATTR_PACKET_TYPE_STREAM_END; } } @@ -368,9 +366,9 @@ int sixlowpan_send(FAR struct net_driver_s *dev, sixlowpan_compress_ipv6hdr(ieee, ipv6); } - ninfo("Header of len %d\n", ieee->i_rime_hdrlen); + ninfo("Header of len %d\n", g_rime_hdrlen); - rimeaddr_copy(&ieee->i_pktaddrs[PACKETBUF_ADDR_RECEIVER], &dest); + rimeaddr_copy(&g_pktaddrs[PACKETBUF_ADDR_RECEIVER], &dest); /* Pre-calculate frame header length. */ @@ -385,9 +383,9 @@ int sixlowpan_send(FAR struct net_driver_s *dev, /* Check if we need to fragment the packet into several frames */ - if ((int)len - (int)ieee->i_uncomp_hdrlen > + if ((int)len - (int)g_uncomp_hdrlen > (int)CONFIG_NET_6LOWPAN_MAXPAYLOAD - framer_hdrlen - - (int)ieee->i_rime_hdrlen) + (int)g_rime_hdrlen) { #if CONFIG_NET_6LOWPAN_FRAG /* ieee->i_framelist will hold the generated frames; frames will be diff --git a/net/sixlowpan/sixlowpan_sniffer.c b/net/sixlowpan/sixlowpan_sniffer.c index 32a2e3121e..eb8a77e3f7 100644 --- a/net/sixlowpan/sixlowpan_sniffer.c +++ b/net/sixlowpan/sixlowpan_sniffer.c @@ -40,7 +40,6 @@ #include #include "nuttx/net/net.h" -#include "nuttx/net/sixlowpan.h" #include "sixlowpan/sixlowpan_internal.h" diff --git a/net/sixlowpan/sixlowpan_tcpsend.c b/net/sixlowpan/sixlowpan_tcpsend.c index 9928bc3d11..092ec2f071 100644 --- a/net/sixlowpan/sixlowpan_tcpsend.c +++ b/net/sixlowpan/sixlowpan_tcpsend.c @@ -44,8 +44,6 @@ #include #include "nuttx/net/netdev.h" -#include "nuttx/net/tcp.h" -#include "nuttx/net/sixlowpan.h" #include "netdev/netdev.h" #include "socket/socket.h" diff --git a/net/sixlowpan/sixlowpan_udpsend.c b/net/sixlowpan/sixlowpan_udpsend.c index 9946516e00..e6972badad 100644 --- a/net/sixlowpan/sixlowpan_udpsend.c +++ b/net/sixlowpan/sixlowpan_udpsend.c @@ -44,8 +44,6 @@ #include #include "nuttx/net/netdev.h" -#include "nuttx/net/udp.h" -#include "nuttx/net/sixlowpan.h" #include "netdev/netdev.h" #include "socket/socket.h" diff --git a/net/sixlowpan/sixlowpan_utils.c b/net/sixlowpan/sixlowpan_utils.c index 946fc91971..f6ad77c68b 100644 --- a/net/sixlowpan/sixlowpan_utils.c +++ b/net/sixlowpan/sixlowpan_utils.c @@ -51,10 +51,10 @@ * Content Offset * +------------------+ 0 * | Frame Header | - * +------------------+ i_dataoffset + * +------------------+ g_dataoffset * | Procotol Headers | * | Data Payload | - * +------------------+ io_len + * +------------------+ iob->io_len * | Unused | * +------------------+ CONFIG_NET_6LOWPAN_FRAMELEN */ @@ -68,8 +68,6 @@ #include #include -#include "nuttx/net/sixlowpan.h" - #include "sixlowpan/sixlowpan_internal.h" #ifdef CONFIG_NET_6LOWPAN @@ -86,13 +84,12 @@ * ****************************************************************************/ -int sixlowpan_frame_hdralloc(FAR struct ieee802154_driver_s *ieee, - FAR struct iob_s *iob, int size) +int sixlowpan_frame_hdralloc(FAR struct iob_s *iob, int size) { - if (size <= FRAME_REMAINING(ieee, iob)) + if (size <= FRAME_REMAINING(iob)) { - ieee->i_dataoffset += size; - iob->io_len += size; + g_dataoffset += size; + iob->io_len += size; return OK; } -- GitLab From 41912ed98cd2a564f43dab4331b7b565d788a691 Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Fri, 31 Mar 2017 10:13:40 -0600 Subject: [PATCH 289/990] STM32F7: add support for LSE RTC and enable RTC subseconds --- arch/arm/src/stm32f7/Kconfig | 2 +- arch/arm/src/stm32f7/Make.defs | 4 ++ arch/arm/src/stm32f7/stm32_exti_pwr.c | 2 +- arch/arm/src/stm32f7/stm32_lse.c | 86 +++++++++++++++++++++++++++ arch/arm/src/stm32f7/stm32_lsi.c | 2 +- arch/arm/src/stm32f7/stm32_rtc.c | 76 ++++++++++++++--------- 6 files changed, 141 insertions(+), 31 deletions(-) create mode 100644 arch/arm/src/stm32f7/stm32_lse.c diff --git a/arch/arm/src/stm32f7/Kconfig b/arch/arm/src/stm32f7/Kconfig index ff7dfe80cf..e727aef24a 100644 --- a/arch/arm/src/stm32f7/Kconfig +++ b/arch/arm/src/stm32f7/Kconfig @@ -1823,7 +1823,7 @@ config STM32F7_HAVE_RTC_COUNTER config STM32F7_HAVE_RTC_SUBSECONDS bool - default n + default y config RTC_MAGIC_REG int "The BKP register used to store/check the Magic value to determine if RTC is set already" diff --git a/arch/arm/src/stm32f7/Make.defs b/arch/arm/src/stm32f7/Make.defs index 8baa4fbf13..06a190f463 100644 --- a/arch/arm/src/stm32f7/Make.defs +++ b/arch/arm/src/stm32f7/Make.defs @@ -149,6 +149,10 @@ ifeq ($(filter y,$(CONFIG_STM32F7_IWDG) $(CONFIG_STM32F7_RTC_LSICLOCK)),y) CHIP_CSRCS += stm32_lsi.c endif +ifeq ($(CONFIG_STM32F7_RTC_LSECLOCK),y) +CHIP_CSRCS += stm32_lse.c +endif + ifeq ($(CONFIG_STM32F7_I2C),y) CHIP_CSRCS += stm32_i2c.c endif diff --git a/arch/arm/src/stm32f7/stm32_exti_pwr.c b/arch/arm/src/stm32f7/stm32_exti_pwr.c index 09d064e930..3c4f2d07a3 100644 --- a/arch/arm/src/stm32f7/stm32_exti_pwr.c +++ b/arch/arm/src/stm32f7/stm32_exti_pwr.c @@ -129,7 +129,7 @@ static int stm32_exti_pvd_isr(int irq, void *context, void *arg) ****************************************************************************/ int stm32_exti_pvd(bool risingedge, bool fallingedge, bool event, - xcpt_t func, void *arg); + xcpt_t func, void *arg) { /* Get the previous GPIO IRQ handler; Save the new IRQ handler. */ diff --git a/arch/arm/src/stm32f7/stm32_lse.c b/arch/arm/src/stm32f7/stm32_lse.c new file mode 100644 index 0000000000..162630060b --- /dev/null +++ b/arch/arm/src/stm32f7/stm32_lse.c @@ -0,0 +1,86 @@ +/**************************************************************************** + * arch/arm/src/stm32f7/stm32_lse.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * David Sidrane + * + * 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 "up_arch.h" + +#include "stm32_rcc.h" +#include "stm32_pwr.h" + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_rcc_enablelse + * + * Description: + * Enable the External Low-Speed (LSE) oscillator. + * + ****************************************************************************/ + +void stm32_rcc_enablelse(void) +{ + uint32_t regval; + + /* The LSE is in the RTC domain and write access is denied to this domain + * after reset, you have to enable write access using DBP bit in the PWR CR + * register before to configuring the LSE. + */ + + stm32_pwr_enablebkp(true); + + /* Enable the External Low-Speed (LSE) oscillator by setting the LSEON bit + * the RCC BDCR register. + */ + + regval = getreg32(STM32_RCC_BDCR); + regval |= RCC_BDCR_LSEON; + putreg32(regval,STM32_RCC_BDCR); + + /* Wait for the LSE clock to be ready */ + + while (((regval = getreg32(STM32_RCC_BDCR)) & RCC_BDCR_LSERDY) == 0); + + /* Disable backup domain access if it was disabled on entry */ + + stm32_pwr_enablebkp(false); +} diff --git a/arch/arm/src/stm32f7/stm32_lsi.c b/arch/arm/src/stm32f7/stm32_lsi.c index 46e9616372..636662721b 100644 --- a/arch/arm/src/stm32f7/stm32_lsi.c +++ b/arch/arm/src/stm32f7/stm32_lsi.c @@ -1,5 +1,5 @@ /**************************************************************************** - * arch/arm/src/stm32f/stm32_lsi.c + * arch/arm/src/stm32f7/stm32_lsi.c * * Copyright (C) 2012, 2015-2016 Gregory Nutt. All rights reserved. * Authors: Gregory Nutt diff --git a/arch/arm/src/stm32f7/stm32_rtc.c b/arch/arm/src/stm32f7/stm32_rtc.c index 8a21ec41fe..2840fac8a5 100644 --- a/arch/arm/src/stm32f7/stm32_rtc.c +++ b/arch/arm/src/stm32f7/stm32_rtc.c @@ -196,7 +196,7 @@ static void rtc_dumpregs(FAR const char *msg) rtcinfo(" TSDR: %08x\n", getreg32(STM32_RTC_TSDR)); rtcinfo(" TSSSR: %08x\n", getreg32(STM32_RTC_TSSSR)); rtcinfo(" CALR: %08x\n", getreg32(STM32_RTC_CALR)); - rtcinfo(" TAFCR: %08x\n", getreg32(STM32_RTC_TAFCR)); + rtcinfo(" TAMPCR: %08x\n", getreg32(STM32_RTC_TAMPCR)); rtcinfo("ALRMASSR: %08x\n", getreg32(STM32_RTC_ALRMASSR)); rtcinfo("ALRMBSSR: %08x\n", getreg32(STM32_RTC_ALRMBSSR)); rtcinfo("MAGICREG: %08x\n", getreg32(RTC_MAGIC_REG)); @@ -227,7 +227,8 @@ static void rtc_dumpregs(FAR const char *msg) ****************************************************************************/ #ifdef CONFIG_DEBUG_RTC_INFO -static void rtc_dumptime(FAR const struct tm *tp, FAR const char *msg) +static void rtc_dumptime(FAR const struct tm *tp, FAR const uint32_t *usecs, + FAR const char *msg) { rtcinfo("%s:\n", msg); rtcinfo(" tm_sec: %08x\n", tp->tm_sec); @@ -236,9 +237,14 @@ static void rtc_dumptime(FAR const struct tm *tp, FAR const char *msg) rtcinfo(" tm_mday: %08x\n", tp->tm_mday); rtcinfo(" tm_mon: %08x\n", tp->tm_mon); rtcinfo(" tm_year: %08x\n", tp->tm_year); + + if (usecs != NULL) + { + rtcinfo(" usecs: %08x\n", (unsigned int)*usecs); + } } #else -# define rtc_dumptime(tp, msg) +# define rtc_dumptime(tp, usecs, msg) #endif /**************************************************************************** @@ -1069,34 +1075,48 @@ int up_rtc_initialize(void) * ****************************************************************************/ -#ifdef CONFIG_STM32_HAVE_RTC_SUBSECONDS +#ifdef CONFIG_STM32F7_HAVE_RTC_SUBSECONDS int stm32_rtc_getdatetime_with_subseconds(FAR struct tm *tp, FAR long *nsec) #else int up_rtc_getdatetime(FAR struct tm *tp) #endif { -#ifdef CONFIG_STM32_HAVE_RTC_SUBSECONDS - uint32_t ssr; -#endif uint32_t dr; uint32_t tr; uint32_t tmp; +#ifdef CONFIG_STM32F7_HAVE_RTC_SUBSECONDS + uint32_t ssr; + uint32_t prediv_s; + uint32_t usecs; +#endif /* Sample the data time registers. There is a race condition here... If * we sample the time just before midnight on December 31, the date could - * be wrong because the day rolled over while were sampling. + * be wrong because the day rolled over while were sampling. Thus loop for + * checking overflow here is needed. There is a race condition with + * subseconds too. If we sample TR register just before second rolling + * and subseconds are read at wrong second, we get wrong time. */ do { dr = getreg32(STM32_RTC_DR); tr = getreg32(STM32_RTC_TR); -#ifdef CONFIG_STM32_HAVE_RTC_SUBSECONDS +#ifdef CONFIG_STM32F7_HAVE_RTC_SUBSECONDS ssr = getreg32(STM32_RTC_SSR); + tmp = getreg32(STM32_RTC_TR); + if (tmp != tr) + { + continue; + } #endif tmp = getreg32(STM32_RTC_DR); + if (tmp == dr) + { + break; + } } - while (tmp != dr); + while (1); rtc_dumpregs("Reading Time"); @@ -1141,31 +1161,31 @@ int up_rtc_getdatetime(FAR struct tm *tp) tp->tm_isdst = 0 #endif -#ifdef CONFIG_STM32_HAVE_RTC_SUBSECONDS +#ifdef CONFIG_STM32F7_HAVE_RTC_SUBSECONDS /* Return RTC sub-seconds if no configured and if a non-NULL value * of nsec has been provided to receive the sub-second value. */ - if (nsec) - { - uint32_t prediv_s; - uint32_t usecs; + prediv_s = getreg32(STM32_RTC_PRER) & RTC_PRER_PREDIV_S_MASK; + prediv_s >>= RTC_PRER_PREDIV_S_SHIFT; - prediv_s = getreg32(STM32_RTC_PRER) & RTC_PRER_PREDIV_S_MASK; - prediv_s >>= RTC_PRER_PREDIV_S_SHIFT; + ssr &= RTC_SSR_MASK; - ssr &= RTC_SSR_MASK; - - /* Maximum prediv_s is 0x7fff, thus we can multiply by 100000 and - * still fit 32-bit unsigned integer. - */ + /* Maximum prediv_s is 0x7fff, thus we can multiply by 100000 and + * still fit 32-bit unsigned integer. + */ - usecs = (((prediv_s - ssr) * 100000) / (prediv_s + 1)) * 10; + usecs = (((prediv_s - ssr) * 100000) / (prediv_s + 1)) * 10; + if (nsec != NULL) + { *nsec = usecs * 1000; } -#endif /* CONFIG_STM32_HAVE_RTC_SUBSECONDS */ - rtc_dumptime((FAR const struct tm *)tp, "Returning"); + rtc_dumptime((FAR const struct tm *)tp, &usecs, "Returning"); +#else /* CONFIG_STM32_HAVE_RTC_SUBSECONDS */ + rtc_dumptime((FAR const struct tm *)tp, NULL, "Returning"); +#endif + return OK; } @@ -1192,7 +1212,7 @@ int up_rtc_getdatetime(FAR struct tm *tp) * ****************************************************************************/ -#ifdef CONFIG_STM32_HAVE_RTC_SUBSECONDS +#ifdef CONFIG_STM32F7_HAVE_RTC_SUBSECONDS int up_rtc_getdatetime(FAR struct tm *tp) { return stm32_rtc_getdatetime_with_subseconds(tp, NULL); @@ -1221,7 +1241,7 @@ int stm32_rtc_setdatetime(FAR const struct tm *tp) uint32_t dr; int ret; - rtc_dumptime(tp, "Setting time"); + rtc_dumptime(tp, NULL, "Setting time"); /* Then write the broken out values to the RTC */ @@ -1337,7 +1357,7 @@ int stm32_rtc_setalarm(FAR struct alm_setalarm_s *alminfo) /* REVISIT: Should test that the time is in the future */ - rtc_dumptime(&alminfo->as_time, "New alarm time"); + rtc_dumptime(&alminfo->as_time, NULL, "New alarm time"); /* Break out the values to the HW alarm register format. The values in * all STM32 fields match the fields of struct tm in this case. Notice -- GitLab From 755b05ff3092196d8f0bb539fe4e2e358d647f85 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 31 Mar 2017 10:45:39 -0600 Subject: [PATCH 290/990] TCP/IPv6: Fix a compile issue when IPv6, but not IPv4 is enabled. --- net/socket/connect.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/net/socket/connect.c b/net/socket/connect.c index d8b2eb46e1..dd3ee97e09 100644 --- a/net/socket/connect.c +++ b/net/socket/connect.c @@ -300,7 +300,7 @@ static uint16_t psock_connect_interrupt(FAR struct net_driver_s *dev, else #endif { - pstate->tc_conn->mss = TCP_IPv4_INITIAL_MSS(dev); + pstate->tc_conn->mss = TCP_IPv6_INITIAL_MSS(dev); } #endif /* CONFIG_NET_IPv6 */ -- GitLab From ad89c88eb31dddf234c1bf14b3d9a6dc411aef0f Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 31 Mar 2017 10:47:12 -0600 Subject: [PATCH 291/990] net/: Fix MULTINIC/MULTILINK selection when 6loWPAN selected. --- net/Kconfig | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/net/Kconfig b/net/Kconfig index f15c9b5d7a..d36e3a9be1 100644 --- a/net/Kconfig +++ b/net/Kconfig @@ -125,8 +125,8 @@ config NET_ETHERNET bool "Ethernet support" default y if !NET_SLIP default n if NET_SLIP - select NETDEV_MULTINIC if NET_LOOPBACK || NET_SLIP || NET_TUN - select NET_MULTILINK if NET_LOOPBACK || NET_SLIP || NET_TUN + select NETDEV_MULTINIC if NET_6LOWPAN || NET_LOOPBACK || NET_SLIP || NET_TUN + select NET_MULTILINK if NET_6LOWPAN || NET_LOOPBACK || NET_SLIP || NET_TUN ---help--- If NET_SLIP is not selected, then Ethernet will be used (there is no need to define anything special in the configuration file to use @@ -135,16 +135,16 @@ config NET_ETHERNET config NET_LOOPBACK bool "Local loopback" default n - select NETDEV_MULTINIC if NET_ETHERNET || NET_SLIP || NET_TUN - select NET_MULTILINK if NET_ETHERNET || NET_SLIP || NET_TUN + select NETDEV_MULTINIC if NET_ETHERNET || NET_6LOWPAN || NET_SLIP || NET_TUN + select NET_MULTILINK if NET_ETHERNET || NET_6LOWPAN || NET_SLIP || NET_TUN ---help--- Add support for the local network loopback device, lo. config NET_SLIP bool "SLIP support" default n - select NETDEV_MULTINIC if NET_ETHERNET || NET_LOOPBACK || NET_TUN - select NET_MULTILINK if NET_ETHERNET || NET_LOOPBACK || NET_TUN + select NETDEV_MULTINIC if NET_ETHERNET || NET_6LOWPAN || NET_LOOPBACK || NET_TUN + select NET_MULTILINK if NET_ETHERNET || NET_6LOWPAN || NET_LOOPBACK || NET_TUN ---help--- Enables building of the SLIP driver. SLIP requires at least one IP protocol selected. @@ -190,8 +190,8 @@ endif # NET_SLIP config NET_TUN bool "TUN Virtual Network Device support" default n - select NETDEV_MULTINIC if NET_ETHERNET || NET_LOOPBACK || NET_SLIP - select NET_MULTILINK if NET_ETHERNET || NET_LOOPBACK || NET_SLIP + select NETDEV_MULTINIC if NET_ETHERNET || NET_6LOWPAN || NET_LOOPBACK || NET_SLIP + select NET_MULTILINK if NET_ETHERNET || NET_6LOWPAN || NET_LOOPBACK || NET_SLIP select ARCH_HAVE_NETDEV_STATISTICS if NET_TUN -- GitLab From a771ec65d60400264a43423f893bf9d2456d7e2d Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 31 Mar 2017 10:47:40 -0600 Subject: [PATCH 292/990] 6loWPAN: Fix a spelling error in macro name. --- include/nuttx/net/net.h | 2 +- net/sixlowpan/sixlowpan_tcpsend.c | 2 +- net/sixlowpan/sixlowpan_udpsend.c | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/include/nuttx/net/net.h b/include/nuttx/net/net.h index 337e0a6366..d99c2f584a 100644 --- a/include/nuttx/net/net.h +++ b/include/nuttx/net/net.h @@ -79,7 +79,7 @@ enum net_lltype_e NET_LL_SLIP, /* Serial Line Internet Protocol (SLIP) */ NET_LL_TUN, /* TUN Virtual Network Device */ NET_LL_IEEE80211, /* IEEE 802.11 */ - NET_LL_IEEE805154 /* IEEE 802.15.4 MAC */ + NET_LL_IEEE802154 /* IEEE 802.15.4 MAC */ }; /* This defines a bitmap big enough for one bit for each socket option */ diff --git a/net/sixlowpan/sixlowpan_tcpsend.c b/net/sixlowpan/sixlowpan_tcpsend.c index 092ec2f071..b515933053 100644 --- a/net/sixlowpan/sixlowpan_tcpsend.c +++ b/net/sixlowpan/sixlowpan_tcpsend.c @@ -126,7 +126,7 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, #ifdef CONFIG_NETDEV_MULTINIC dev = netdev_findby_ipv6addr(conn->u.ipv6.laddr, conn->u.ipv6.raddr); - if (dev == NULL || dev->d_lltype != NET_LL_IEEE805154) + if (dev == NULL || dev->d_lltype != NET_LL_IEEE802154) { nwarn("WARNING: Not routable or not IEEE802.15.4 MAC\n"); return (ssize_t)-ENETUNREACH; diff --git a/net/sixlowpan/sixlowpan_udpsend.c b/net/sixlowpan/sixlowpan_udpsend.c index e6972badad..be128918ca 100644 --- a/net/sixlowpan/sixlowpan_udpsend.c +++ b/net/sixlowpan/sixlowpan_udpsend.c @@ -127,7 +127,7 @@ ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, #ifdef CONFIG_NETDEV_MULTINIC dev = netdev_findby_ipv6addr(conn->u.ipv6.laddr, conn->u.ipv6.raddr); - if (dev == NULL || dev->d_lltype != NET_LL_IEEE805154) + if (dev == NULL || dev->d_lltype != NET_LL_IEEE802154) { nwarn("WARNING: Not routable or not IEEE802.15.4 MAC\n"); return (ssize_t)-ENETUNREACH; -- GitLab From eb446d526186687b68acf81da498978a1c9d17d2 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 31 Mar 2017 11:15:16 -0600 Subject: [PATCH 293/990] net/: Permit net/neighbor to build when IPv6 is defined, but not Ethernet. Needs more work to support 6loWPAN. Also included, some minor configuration updates for 6loWPAN. --- net/Kconfig | 13 +++++++++++-- net/neighbor/Make.defs | 11 ++++++++++- .../{neighbor_out.c => neighbor_ethernet_out.c} | 4 ++-- net/sixlowpan/Kconfig | 8 -------- 4 files changed, 23 insertions(+), 13 deletions(-) rename net/neighbor/{neighbor_out.c => neighbor_ethernet_out.c} (98%) diff --git a/net/Kconfig b/net/Kconfig index d36e3a9be1..21ef8b3e7a 100644 --- a/net/Kconfig +++ b/net/Kconfig @@ -123,8 +123,7 @@ config NET_USER_DEVFMT config NET_ETHERNET bool "Ethernet support" - default y if !NET_SLIP - default n if NET_SLIP + default y select NETDEV_MULTINIC if NET_6LOWPAN || NET_LOOPBACK || NET_SLIP || NET_TUN select NET_MULTILINK if NET_6LOWPAN || NET_LOOPBACK || NET_SLIP || NET_TUN ---help--- @@ -132,6 +131,16 @@ config NET_ETHERNET no need to define anything special in the configuration file to use Ethernet -- it is the default). +menuconfig NET_6LOWPAN + bool "IEEE 802.15.4 6LoWPAN support" + default n + select NETDEV_MULTINIC if NET_ETHERNET || NET_LOOPBACK || NET_SLIP || NET_TUN + select NET_MULTILINK if NET_ETHERNET || NET_LOOPBACK || NET_SLIP || NET_TUN + depends on EXPERIMENTAL && NET_IPv6 + ---help--- + Enable support for IEEE 802.15.4 Low power Wireless Personal Area + Networking (6LoWPAN). + config NET_LOOPBACK bool "Local loopback" default n diff --git a/net/neighbor/Make.defs b/net/neighbor/Make.defs index cf13cbb732..7f6b56244e 100644 --- a/net/neighbor/Make.defs +++ b/net/neighbor/Make.defs @@ -39,7 +39,16 @@ ifeq ($(CONFIG_NET_IPv6),y) NET_CSRCS += neighbor_initialize.c neighbor_add.c neighbor_lookup.c NET_CSRCS += neighbor_update.c neighbor_periodic.c neighbor_findentry.c -NET_CSRCS += neighbor_out.c + +# Link layer specific support + +ifeq ($(CONFIG_NET_ETHERNET),y) +NET_CSRCS += neighbor_ethernet_out.c +endif + +ifeq ($(CONFIG_NET_6LOWPAN),y) +# NET_CSRCS += neighbor_6lowpan_out.c +endif # Include utility build support diff --git a/net/neighbor/neighbor_out.c b/net/neighbor/neighbor_ethernet_out.c similarity index 98% rename from net/neighbor/neighbor_out.c rename to net/neighbor/neighbor_ethernet_out.c index 4725a90ea2..ddd9a3a5ff 100644 --- a/net/neighbor/neighbor_out.c +++ b/net/neighbor/neighbor_ethernet_out.c @@ -1,7 +1,7 @@ /**************************************************************************** - * net/neighbor/neighbor_out.c + * net/neighbor/neighbor_ethernet_out.c * - * Copyright (C) 2015 Gregory Nutt. All rights reserved. + * Copyright (C) 2015, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without diff --git a/net/sixlowpan/Kconfig b/net/sixlowpan/Kconfig index 406a5e8d34..4b4c6ad9eb 100644 --- a/net/sixlowpan/Kconfig +++ b/net/sixlowpan/Kconfig @@ -3,14 +3,6 @@ # see the file kconfig-language.txt in the NuttX tools repository. # -menuconfig NET_6LOWPAN - bool "IEEE 802.15.4 6LoWPAN support" - default n - depends on EXPERIMENTAL && NET_IPv6 - ---help--- - Enable support for IEEE 802.15.4 Low power Wireless Personal Area - Networking (6LoWPAN). - if NET_6LOWPAN config NET_6LOWPAN_FRAG -- GitLab From 85e1d1583541a450ee8f7dea745a649fe363e63a Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 31 Mar 2017 12:06:21 -0600 Subject: [PATCH 294/990] 6loWPAN: Fix more configuration related issues detected by addition of 6loWPAN --- README.txt | 6 +- include/nuttx/net/netconfig.h | 115 ++++++++++++++++++++++++++---- net/sixlowpan/sixlowpan_tcpsend.c | 8 +++ net/sixlowpan/sixlowpan_udpsend.c | 8 +++ 4 files changed, 120 insertions(+), 17 deletions(-) diff --git a/README.txt b/README.txt index 59648d01f4..5d3721f4c5 100644 --- a/README.txt +++ b/README.txt @@ -464,9 +464,9 @@ Notes about Header Files Certain header files, such as setjmp.h, stdarg.h, and math.h, may still be needed from your toolchain and your compiler may not, however, be able - to find these if you compile NuttX without using standard header file. - If that is the case, one solution is to copy those header file from - your toolchain into the NuttX include directory. + to find these if you compile NuttX without using standard header files + (ie., with -nostdinc). If that is the case, one solution is to copy + those header file from your toolchain into the NuttX include directory. Duplicated Header Files. diff --git a/include/nuttx/net/netconfig.h b/include/nuttx/net/netconfig.h index 1e79580ee3..77689ae32c 100644 --- a/include/nuttx/net/netconfig.h +++ b/include/nuttx/net/netconfig.h @@ -226,6 +226,12 @@ # define MIN_NET_DEV_MTU CONFIG_NET_6LOWPAN_MTU # define MAX_NET_DEV_MTU CONFIG_NET_6LOWPAN_MTU +/* For the IEEE802.15.4 MAC device, we will use the packet MTU + * (which is probably much larger than the IEEE802.15.4 fram size) + */ + +# define NET_LO_MTU MAX_NET_DEV_MTU + #else /* Perhaps only Unix domain sockets or the loopback device */ @@ -418,24 +424,105 @@ * the minimum MSS for that case. */ -#define TCP_MSS(d,h) (NET_DEV_MTU(d) - NET_LL_HDRLEN(d) - TCP_HDRLEN - (h)) -#define LO_TCP_MSS(h) (NET_LO_MTU - (h)) +#define TCP_MSS(d,h) (NET_DEV_MTU(d) - NET_LL_HDRLEN(d) - TCP_HDRLEN - (h)) +#define LO_TCP_MSS(h) (NET_LO_MTU - (h)) -/* If Ethernet is supported, then it will have the smaller MSS */ +/* Get the smallest and largest */ -#if defined(CONFIG_NET_SLIP) -# define SLIP_TCP_MSS(h) (CONFIG_NET_SLIP_MTU - (h)) -# define __MIN_TCP_MSS(h) SLIP_TCP_MSS(h) -#elif defined(CONFIG_NET_LOOPBACK) -# define LO_TCP_MSS(h) (NET_LO_MTU - (h)) -# define __MIN_TCP_MSS(h) LO_TCP_MSS(h) +#ifdef CONFIG_NET_ETHERNET +# define ETH_TCP_MSS(h) (CONFIG_NET_ETH_MTU - ETH_HDRLEN - (h)) +# ifndef CONFIG_NET_MULTILINK +# define __MIN_TCP_MSS(h) ETH_TCP_MSS(h) +# define __MAX_TCP_MSS(h) ETH_TCP_MSS(h) +# endif #endif -#ifdef CONFIG_NET_ETHERNET -# define ETH_TCP_MSS(h) (CONFIG_NET_ETH_MTU - ETH_HDRLEN - (h)) -# undef __MIN_TCP_MSS -# define __MIN_TCP_MSS(h) ETH_TCP_MSS(h) -# define __MAX_TCP_MSS(h) ETH_TCP_MSS(h) +#ifdef CONFIG_NET_6LOWPAN +# define IEEE802154_TCP_MSS(h) CONFIG_NET_6LOWPAN_MAXPAYLOAD +# ifndef CONFIG_NET_MULTILINK +# define __MIN_TCP_MSS(h) IEEE802154_TCP_MSS(h) +# define __MAX_TCP_MSS(h) IEEE802154_TCP_MSS(h) +# endif +#endif + +#ifdef CONFIG_NET_LOOPBACK +# define LO_TCP_MSS(h) (NET_LO_MTU - (h)) +# ifndef CONFIG_NET_MULTILINK +# define __MIN_TCP_MSS(h) LO_TCP_MSS(h) +# define __MAX_TCP_MSS(h) LO_TCP_MSS(h) +# endif +#endif + +#ifdef CONFIG_NET_SLIP +# define SLIP_TCP_MSS(h) (CONFIG_NET_SLIP_MTU - (h)) +# ifndef CONFIG_NET_MULTILINK +# define __MIN_TCP_MSS(h) SLIP_TCP_MSS(h) +# define __MAX_TCP_MSS(h) SLIP_TCP_MSS(h) +# endif +#endif + +#ifdef CONFIG_NET_MULTILINK +# undef __LAST_MIN_TCP_MSS +# undef __LAST_MAX_TCP_MSS + +# ifdef CONFIG_NET_ETHERNET +# ifdef __LAST_MIN_TCP_MSS +# define __MIN_TCP_MSS(h) MIN(ETH_TCP_MSS(h),__LAST_MIN_TCP_MSS(h)) +# define __MAX_TCP_MSS(h) MAX(ETH_TCP_MSS(h),__LAST_MAX_TCP_MSS(h)) +# else +# define __MIN_TCP_MSS(h) ETH_TCP_MSS(h) +# define __MAX_TCP_MSS(h) ETH_TCP_MSS(h) +# endif +# undef __LAST_MIN_TCP_MSS +# undef __LAST_MAX_TCP_MSS +# define __LAST_MIN_TCP_MSS(h) __MIN_TCP_MSS(h) +# define __LAST_MAX_TCP_MSS(h) __MAX_TCP_MSS(h) +# endif + +# ifdef CONFIG_NET_6LOWPAN +# ifdef __LAST_MIN_TCP_MSS +# define __MIN_TCP_MSS(h) MIN(IEEE802154_TCP_MSS(h),__LAST_MIN_TCP_MSS(h)) +# define __MAX_TCP_MSS(h) MAX(IEEE802154_TCP_MSS(h),__LAST_MAX_TCP_MSS(h)) +# else +# define __MIN_TCP_MSS(h) IEEE802154_TCP_MSS(h) +# define __MAX_TCP_MSS(h) IEEE802154_TCP_MSS(h) +# endif +# undef __LAST_MIN_TCP_MSS +# undef __LAST_MAX_TCP_MSS +# define __LAST_MIN_TCP_MSS(h) __MIN_TCP_MSS(h) +# define __LAST_MAX_TCP_MSS(h) __MAX_TCP_MSS(h) +# endif + +# ifdef CONFIG_NET_LOOPBACK +# ifdef __LAST_MIN_TCP_MSS +# define __MIN_TCP_MSS(h) MIN(LO_TCP_MSS(h),__LAST_MIN_TCP_MSS(h)) +# define __MAX_TCP_MSS(h) MAX(LO_TCP_MSS(h),__LAST_MAX_TCP_MSS(h)) +# else +# define __MIN_TCP_MSS(h) LO_TCP_MSS(h) +# define __MAX_TCP_MSS(h) LO_TCP_MSS(h) +# endif +# undef __LAST_MIN_TCP_MSS +# undef __LAST_MAX_TCP_MSS +# define __LAST_MIN_TCP_MSS(h) __MIN_TCP_MSS(h) +# define __LAST_MAX_TCP_MSS(h) __MAX_TCP_MSS(h) +# endif + +# ifdef CONFIG_NET_SLIP +# ifdef __LAST_MIN_TCP_MSS +# define __MIN_TCP_MSS(h) MIN(SLIP_TCP_MSS(h),__LAST_MIN_TCP_MSS(h)) +# define __MAX_TCP_MSS(h) MAX(SLIP_TCP_MSS(h),__LAST_MAX_TCP_MSS(h)) +# else +# define __MIN_TCP_MSS(h) SLIP_TCP_MSS(h) +# define __MAX_TCP_MSS(h) SLIP_TCP_MSS(h) +# endif +# undef __LAST_MIN_TCP_MSS +# undef __LAST_MAX_TCP_MSS +# define __LAST_MIN_TCP_MSS(h) __MIN_TCP_MSS(h) +# define __LAST_MAX_TCP_MSS(h) __MAX_TCP_MSS(h) +# endif + +# undef __LAST_MIN_TCP_MSS +# undef __LAST_MAX_TCP_MSS #endif /* If SLIP is supported, then it will have the larger MSS */ diff --git a/net/sixlowpan/sixlowpan_tcpsend.c b/net/sixlowpan/sixlowpan_tcpsend.c index b515933053..4e9f01d237 100644 --- a/net/sixlowpan/sixlowpan_tcpsend.c +++ b/net/sixlowpan/sixlowpan_tcpsend.c @@ -126,14 +126,22 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, #ifdef CONFIG_NETDEV_MULTINIC dev = netdev_findby_ipv6addr(conn->u.ipv6.laddr, conn->u.ipv6.raddr); +#ifdef CONFIG_NETDEV_MULTILINK if (dev == NULL || dev->d_lltype != NET_LL_IEEE802154) +#else + if (dev == NULL) +#endif { nwarn("WARNING: Not routable or not IEEE802.15.4 MAC\n"); return (ssize_t)-ENETUNREACH; } #else dev = netdev_findby_ipv6addr(conn->u.ipv6.raddr); +#ifdef CONFIG_NETDEV_MULTILINK + if (dev == NULL || dev->d_lltype != NET_LL_IEEE802154) +#else if (dev == NULL) +#endif { nwarn("WARNING: Not routable\n"); return (ssize_t)-ENETUNREACH; diff --git a/net/sixlowpan/sixlowpan_udpsend.c b/net/sixlowpan/sixlowpan_udpsend.c index be128918ca..7f55810180 100644 --- a/net/sixlowpan/sixlowpan_udpsend.c +++ b/net/sixlowpan/sixlowpan_udpsend.c @@ -127,14 +127,22 @@ ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, #ifdef CONFIG_NETDEV_MULTINIC dev = netdev_findby_ipv6addr(conn->u.ipv6.laddr, conn->u.ipv6.raddr); +#ifdef CONFIG_NETDEV_MULTILINK if (dev == NULL || dev->d_lltype != NET_LL_IEEE802154) +#else + if (dev == NULL) +#endif { nwarn("WARNING: Not routable or not IEEE802.15.4 MAC\n"); return (ssize_t)-ENETUNREACH; } #else dev = netdev_findby_ipv6addr(conn->u.ipv6.raddr); +#ifdef CONFIG_NETDEV_MULTILINK + if (dev == NULL || dev->d_lltype != NET_LL_IEEE802154) +#else if (dev == NULL) +#endif { nwarn("WARNING: Not routable\n"); return (ssize_t)-ENETUNREACH; -- GitLab From 732f0855c607da4d9551bb33e75647fbcac380ad Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 31 Mar 2017 15:09:07 -0600 Subject: [PATCH 295/990] 6loWPAN: Fleshes out framwork for IEEE802.15.4 send. But still has some gaping holes. --- include/nuttx/net/sixlowpan.h | 8 +- net/devif/devif.h | 4 +- net/sixlowpan/sixlowpan_globals.c | 9 + net/sixlowpan/sixlowpan_internal.h | 103 +++++-- net/sixlowpan/sixlowpan_send.c | 455 ++++++++++++++++++++++++----- net/sixlowpan/sixlowpan_tcpsend.c | 9 +- net/sixlowpan/sixlowpan_udpsend.c | 9 +- net/tcp/tcp_send_unbuffered.c | 12 +- 8 files changed, 510 insertions(+), 99 deletions(-) diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index b9b995cdae..1fbfee79b4 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -99,7 +99,6 @@ #define SIXLOWPAN_IPHC_TTL_255 0x03 #define SIXLOWPAN_IPHC_TTL_I 0x00 - /* Values of fields within the IPHC encoding second byte */ #define SIXLOWPAN_IPHC_CID 0x80 @@ -422,6 +421,13 @@ struct ieee802154_driver_s */ uint8_t i_dsn; + + /* i_dgramtag. Datagram tag to be put in the header of the set of + * fragments. It is used by the recipient to match fragments of the + * same payload. + */ + + uint16_t i_dgramtag; }; /* The structure of a next header compressor. This compressor is provided diff --git a/net/devif/devif.h b/net/devif/devif.h index e15f6317b8..28135f4d30 100644 --- a/net/devif/devif.h +++ b/net/devif/devif.h @@ -1,7 +1,7 @@ /**************************************************************************** * net/devif/devif.h * - * Copyright (C) 2007-2009, 2013-2016 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009, 2013-2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * This logic was leveraged from uIP which also has a BSD-style license: @@ -170,11 +170,13 @@ #define TCP_NEWDATA (1 << 1) #define UDP_NEWDATA TCP_NEWDATA #define PKT_NEWDATA TCP_NEWDATA +#define WPAN_NEWDATA TCP_NEWDATA #define TCP_SNDACK (1 << 2) #define TCP_REXMIT (1 << 3) #define TCP_POLL (1 << 4) #define UDP_POLL TCP_POLL #define PKT_POLL TCP_POLL +#define WPAN_POLL TCP_POLL #define TCP_BACKLOG (1 << 5) #define TCP_CLOSE (1 << 6) #define TCP_ABORT (1 << 7) diff --git a/net/sixlowpan/sixlowpan_globals.c b/net/sixlowpan/sixlowpan_globals.c index 1c7c378df0..b62c3e110f 100644 --- a/net/sixlowpan/sixlowpan_globals.c +++ b/net/sixlowpan/sixlowpan_globals.c @@ -72,6 +72,15 @@ FAR struct sixlowpan_rime_sniffer_s *g_sixlowpan_sniffer; FAR uint8_t *g_rimeptr; +/* The length of the payload in the Rime buffer. + * + * The payload is what comes after the compressed or uncompressed headers + * (can be the IP payload if the IP header only is compressed or the UDP + * payload if the UDP header is also compressed) + */ + +uint8_t g_rime_payloadlen; + /* g_uncomp_hdrlen is the length of the headers before compression (if HC2 * is used this includes the UDP header in addition to the IP header). */ diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index 05240dafdf..3bf65fc09c 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -82,24 +82,45 @@ #define rimeaddr_cmp(addr1,addr2) \ (memcmp(addr1, addr2, CONFIG_NET_6LOWPAN_RIMEADDR_SIZE) == 0) -/* Frame buffer helpers */ +/* Pointers in the Rime buffer */ + +/* Fragment header. + * + * The fragment header is used when the payload is too large to fit in a + * single IEEE 802.15.4 frame. The fragment header contains three fields: + * Datagram size, datagram tag and datagram offset. + * + * 1. Datagram size describes the total (un-fragmented) payload. + * 2. Datagram tag identifies the set of fragments and is used to match + * fragments of the same payload. + * 3. Datagram offset identifies the fragment’s offset within the un- + * fragmented payload. + * + * The fragment header length is 4 bytes for the first header and 5 + * bytes for all subsequent headers. + */ -#define FRAME_RESET() \ - do \ - { \ - g_dataoffset = 0; \ - } \ - while (0) +#define RIME_FRAG_PTR g_rimeptr +#define RIME_FRAG_DISPATCH_SIZE 0 /* 16 bit */ +#define RIME_FRAG_TAG 2 /* 16 bit */ +#define RIME_FRAG_OFFSET 4 /* 8 bit */ -#define FRAME_HDR_START(iob) ((iob)->io_data) -#define FRAME_HDR_SIZE(iob) g_dataoffset +/* Define the Rime buffer as a byte array */ -#define FRAME_DATA_START(iob) ((FAR uint8_t *)((iob)->io_data) + g_dataoffset) -#define FRAME_DATA_SIZE(iob) ((iob)->io_len - g_dataoffset) +#define RIME_IPHC_BUF (g_rimeptr + g_rime_hdrlen) -#define FRAME_REMAINING(iob) (CONFIG_NET_6LOWPAN_FRAMELEN - (iob)->io_len) -#define FRAME_SIZE(ieee,iob) \ - ((iob)->io_len) +#define RIME_HC1_PTR (g_rimeptr + g_rime_hdrlen) +#define RIME_HC1_DISPATCH 0 /* 8 bit */ +#define RIME_HC1_ENCODING 1 /* 8 bit */ +#define RIME_HC1_TTL 2 /* 8 bit */ + +#define RIME_HC1_HC_UDP_PTR (g_rimeptr + g_rime_hdrlen) +#define RIME_HC1_HC_UDP_DISPATCH 0 /* 8 bit */ +#define RIME_HC1_HC_UDP_HC1_ENCODING 1 /* 8 bit */ +#define RIME_HC1_HC_UDP_UDP_ENCODING 2 /* 8 bit */ +#define RIME_HC1_HC_UDP_TTL 3 /* 8 bit */ +#define RIME_HC1_HC_UDP_PORTS 4 /* 8 bit */ +#define RIME_HC1_HC_UDP_CHKSUM 5 /* 16 bit */ /* These are some definitions of element values used in the FCF. See the * IEEE802.15.4 spec for details. @@ -185,6 +206,37 @@ #define PACKETBUF_NUM_ADDRS 4 +/* Frame buffer helpers *****************************************************/ + +#define FRAME_RESET() \ + do \ + { \ + g_dataoffset = 0; \ + } \ + while (0) + +#define FRAME_HDR_START(iob) ((iob)->io_data) +#define FRAME_HDR_SIZE(iob) g_dataoffset + +#define FRAME_DATA_START(iob) ((FAR uint8_t *)((iob)->io_data) + g_dataoffset) +#define FRAME_DATA_SIZE(iob) ((iob)->io_len - g_dataoffset) + +#define FRAME_REMAINING(iob) (CONFIG_NET_6LOWPAN_FRAMELEN - (iob)->io_len) +#define FRAME_SIZE(ieee,iob) \ + ((iob)->io_len) + +/* General helper macros ****************************************************/ + +#define GETINT16(ptr,index) \ + ((((uint16_t)((ptr)[index]) << 8)) | ((uint16_t)(((ptr)[(index) + 1])))) +#define PUTINT16(ptr,index,value) \ + do \ + { \ + (ptr)[index] = ((uint16_t)(value) >> 8) & 0xff; \ + (ptr)[index + 1] = (uint16_t)(value) & 0xff; \ + } \ + while(0) + /**************************************************************************** * Public Types ****************************************************************************/ @@ -310,6 +362,15 @@ extern FAR struct sixlowpan_rime_sniffer_s *g_sixlowpan_sniffer; extern FAR uint8_t *g_rimeptr; +/* The length of the payload in the Rime buffer. + * + * The payload is what comes after the compressed or uncompressed headers + * (can be the IP payload if the IP header only is compressed or the UDP + * payload if the UDP header is also compressed) + */ + +extern uint8_t g_rime_payloadlen; + /* g_uncomp_hdrlen is the length of the headers before compression (if HC2 * is used this includes the UDP header in addition to the IP header). */ @@ -360,11 +421,12 @@ struct iob_s; /* Forward reference */ * ieee->i_framelist. * * Input Parameters: - * dev - The IEEE802.15.4 MAC network driver interface. - * ipv6 - IPv6 plus TCP or UDP headers. - * buf - Data to send - * len - Length of data to send - * raddr - The MAC address of the destination + * dev - The IEEE802.15.4 MAC network driver interface. + * ipv6 - IPv6 plus TCP or UDP headers. + * buf - Data to send + * len - Length of data to send + * raddr - The MAC address of the destination + * timeout - Send timeout in deciseconds * * Returned Value: * Ok is returned on success; Othewise a negated errno value is returned. @@ -379,7 +441,8 @@ struct iob_s; /* Forward reference */ int sixlowpan_send(FAR struct net_driver_s *dev, FAR const struct ipv6_hdr_s *ipv6, FAR const void *buf, - size_t len, FAR const struct rimeaddr_s *raddr); + size_t len, FAR const struct rimeaddr_s *raddr, + uint16_t timeout); /**************************************************************************** * Function: sixlowpan_hdrlen diff --git a/net/sixlowpan/sixlowpan_send.c b/net/sixlowpan/sixlowpan_send.c index cf9c8d751b..69bf3b8392 100644 --- a/net/sixlowpan/sixlowpan_send.c +++ b/net/sixlowpan/sixlowpan_send.c @@ -54,13 +54,15 @@ #include #include -#include "nuttx/net/iob.h" +#include "nuttx/semaphore.h" +#include "nuttx/net/net.h" #include "nuttx/net/netdev.h" +#include "nuttx/net/iob.h" #include "nuttx/net/ip.h" #include "iob/iob.h" #include "netdev/netdev.h" -#include "socket/socket.h" +#include "devif/devif.h" #include "tcp/tcp.h" #include "udp/udp.h" #include "sixlowpan/sixlowpan_internal.h" @@ -87,6 +89,30 @@ # error Not enough IOBs to hold one full IEEE802.14.5 packet #endif +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/* This is the state data provided to the send interrupt logic. No actions + * can be taken until the until we receive the TX poll, then we can call + * sixlowpan_queue_frames() with this data strurcture. + */ + +struct sixlowpan_send_s +{ + FAR struct devif_callback_s *s_cb; /* Reference to callback instance */ + sem_t s_waitsem; /* Supports waiting for driver events */ + int s_result; /* The result of the transfer */ +#ifdef CONFIG_NET_SOCKOPTS + uint16_t s_timeout; /* Send timeout in deciseconds */ + systime_t s_time; /* Last send time for determining timeout */ +#endif + FAR const struct ipv6_hdr_s *s_destip; /* Destination IP address */ + FAR const struct rimeaddr_s *s_destmac; /* Destination MAC address */ + FAR const void *s_buf; /* Data to send */ + size_t s_len; /* Length of data in buf */ +}; + /**************************************************************************** * Private Functions ****************************************************************************/ @@ -106,6 +132,7 @@ * ****************************************************************************/ +/* REVISIT: This is use in input function, but only for sniffer on output */ static void sixlowpan_set_pktattrs(FAR struct ieee802154_driver_s *ieee, FAR const struct ipv6_hdr_s *ipv6) { @@ -206,16 +233,6 @@ static int sixlowpan_send_frame(FAR struct ieee802154_driver_s *ieee, FAR struct iob_s *iobq) { /* Prepare the frame */ -#warning Missing logic - /* Set up for the TX poll */ - /* When polled, then we need to call sixlowpan_framecreate() to create the - * frame and copy the payload data into the frame. - */ -#if 0 /* Just some notes of what needs to be done in interrupt handler */ - framer_hdrlen = sixlowpan_createframe(ieee, ieee->i_panid); - memcpy(g_rimeptr + g_rime_hdrlen, (uint8_t *)ipv6 + g_uncomp_hdrlen, len - g_uncomp_hdrlen); - iob->io_len = len - g_uncomp_hdrlen + g_rime_hdrlen; -#endif #warning Missing logic /* Notify the IEEE802.14.5 MAC driver that we have data to be sent */ #warning Missing logic @@ -225,29 +242,22 @@ static int sixlowpan_send_frame(FAR struct ieee802154_driver_s *ieee, } /**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: sixlowpan_send + * Name: sixlowpan_queue_frames * * Description: - * Process an outgoing UDP or TCP packet. Takes an IP packet and formats - * it to be sent on an 802.15.4 network using 6lowpan. Called from common - * UDP/TCP send logic. + * Process an outgoing UDP or TCP packet. This function is called from + * send interrupt logic when a TX poll is received. It formates the + * list of frames to be sent by the IEEE802.15.4 MAC driver. * - * The payload data is in the caller 'buf' and is of length 'len'. + * The payload data is in the caller 's_buf' and is of length 's_len'. * Compressed headers will be added and if necessary the packet is * fragmented. The resulting packet/fragments are put in ieee->i_framelist * and the entire list of frames will be delivered to the 802.15.4 MAC via * ieee->i_framelist. * * Input Parameters: - * dev - The IEEE802.15.4 MAC network driver interface. - * ipv6 - IPv6 plus TCP or UDP headers. - * buf - Data to send - * len - Length of data to send - * raddr - The IEEE802.15.4 MAC address of the destination + * dev - The structure of the network driver that caused the interrupt + * sinfo - Send state information * * Returned Value: * Ok is returned on success; Othewise a negated errno value is returned. @@ -260,9 +270,8 @@ static int sixlowpan_send_frame(FAR struct ieee802154_driver_s *ieee, * ****************************************************************************/ -int sixlowpan_send(FAR struct net_driver_s *dev, - FAR const struct ipv6_hdr_s *ipv6, FAR const void *buf, - size_t len, FAR const struct rimeaddr_s *raddr) +int sixlowpan_queue_frames(FAR struct net_driver_s *dev, + FAR struct sixlowpan_send_s *sinfo) { FAR struct ieee802154_driver_s *ieee = (FAR struct ieee802154_driver_s *)dev; FAR struct iob_s *iob; @@ -301,7 +310,7 @@ int sixlowpan_send(FAR struct net_driver_s *dev, /* Call the attribution when the callback comes, but set attributes here */ - sixlowpan_set_pktattrs(ieee, ipv6); + sixlowpan_set_pktattrs(ieee, sinfo->s_destip); } #endif @@ -315,9 +324,9 @@ int sixlowpan_send(FAR struct net_driver_s *dev, /* Set stream mode for all TCP packets, except FIN packets. */ - if (ipv6->proto == IP_PROTO_TCP) + if (sinfo->s_destip->proto == IP_PROTO_TCP) { - FAR const struct tcp_hdr_s *tcp = &((FAR const struct ipv6tcp_hdr_s *)ipv6)->tcp; + FAR const struct tcp_hdr_s *tcp = &((FAR const struct ipv6tcp_hdr_s *)sinfo->s_destip)->tcp; if ((tcp->flags & TCP_FIN) == 0 && (tcp->flags & TCP_CTL) != TCP_ACK) @@ -331,22 +340,22 @@ int sixlowpan_send(FAR struct net_driver_s *dev, } /* The destination address will be tagged to each outbound packet. If the - * argument raddr is NULL, we are sending a broadcast packet. + * argument destmac is NULL, we are sending a broadcast packet. */ - if (raddr == NULL) + if (sinfo->s_destmac == NULL) { memset(&dest, 0, sizeof(struct rimeaddr_s)); } else { - rimeaddr_copy(&dest, (FAR const struct rimeaddr_s *)raddr); + rimeaddr_copy(&dest, (FAR const struct rimeaddr_s *)sinfo->s_destmac); } - ninfo("Sending packet len %d\n", len); + ninfo("Sending packet len %d\n", sinfo->s_len); #ifndef CONFIG_NET_6LOWPAN_COMPRESSION_IPv6 - if (len >= CONFIG_NET_6LOWPAN_COMPRESSION_THRESHOLD) + if (sinfo->s_len >= CONFIG_NET_6LOWPAN_COMPRESSION_THRESHOLD) { /* Try to compress the headers */ @@ -363,7 +372,7 @@ int sixlowpan_send(FAR struct net_driver_s *dev, { /* Small.. use IPv6 dispatch (no compression) */ - sixlowpan_compress_ipv6hdr(ieee, ipv6); + sixlowpan_compress_ipv6hdr(ieee, sinfo->s_destip); } ninfo("Header of len %d\n", g_rime_hdrlen); @@ -383,7 +392,7 @@ int sixlowpan_send(FAR struct net_driver_s *dev, /* Check if we need to fragment the packet into several frames */ - if ((int)len - (int)g_uncomp_hdrlen > + if ((int)sinfo->s_len - (int)g_uncomp_hdrlen > (int)CONFIG_NET_6LOWPAN_MAXPAYLOAD - framer_hdrlen - (int)g_rime_hdrlen) { @@ -402,7 +411,7 @@ int sixlowpan_send(FAR struct net_driver_s *dev, * The following fragments contain only the fragn dispatch. */ - ninfo("Fragmentation sending packet len %d\n", len); + ninfo("Fragmentation sending packet len %d\n", sinfo->s_len); /* Allocate an IOB to hold the first fragment, waiting if necessary. */ @@ -417,28 +426,52 @@ int sixlowpan_send(FAR struct net_driver_s *dev, iob->io_pktlen = 0; /* Create 1st Fragment */ - /* Add the frame header. */ + /* Add the frame header */ - verify = sixlowpan_hdrlen(ieee, ieee->i_panid); + verify = sixlowpan_framecreate(ieee, iob, ieee->i_panid); DEBUGASSERT(vreify == framer_hdrlen); UNUSED(verify); /* Move HC1/HC06/IPv6 header */ -# warning Missing logic - /* FRAG1 dispatch + header - * Note that the length is in units of 8 bytes + memmove(g_rimeptr + SIXLOWPAN_FRAG1_HDR_LEN, g_rimeptr, g_rime_hdrlen); + + /* Setup up the fragment header. + * + * The fragment header contains three fields: Datagram size, datagram + * tag and datagram offset: + * + * 1. Datagram size describes the total (un-fragmented) payload. + * 2. Datagram tag identifies the set of fragments and is used to + * match fragments of the same payload. + * 3. Datagram offset identifies the fragment’s offset within the un- + * fragmented payload. + * + * The fragment header length is 4 bytes for the first header and 5 + * bytes for all subsequent headers. */ -# warning Missing logic - /* Copy payload and send */ -# warning Missing logic + PUTINT16(RIME_FRAG_PTR, RIME_FRAG_DISPATCH_SIZE, + ((SIXLOWPAN_DISPATCH_FRAG1 << 8) | sinfo->s_len)); + PUTINT16(RIME_FRAG_PTR, RIME_FRAG_TAG, ieee->i_dgramtag); + ieee->i_dgramtag++; + + /* Copy payload and enqueue */ + + g_rime_hdrlen += SIXLOWPAN_FRAG1_HDR_LEN; + g_rime_payloadlen = + (CONFIG_NET_6LOWPAN_MAXPAYLOAD - framer_hdrlen - g_rime_hdrlen) & 0xf8; - /* Check TX result. */ -# warning Missing logic + memcpy(g_rimeptr + g_rime_hdrlen, + (uint8_t *) sinfo->s_destip + g_uncomp_hdrlen, g_rime_payloadlen); + iob->io_len += g_rime_payloadlen + g_rime_hdrlen; /* Set outlen to what we already sent from the IP payload */ -# warning Missing logic + + outlen = g_rime_payloadlen + g_uncomp_hdrlen; + + ninfo("First fragment: len %d, tag %d\n", + g_rime_payloadlen, ieee->i_dgramtag); /* Add the first frame to the IOB queue */ @@ -449,13 +482,11 @@ int sixlowpan_send(FAR struct net_driver_s *dev, iob->io_pktlen = iob->io_len; - /* Create following fragments - * Datagram tag is already in the buffer, we need to set the - * FRAGN dispatch and for each fragment, the offset - */ -# warning Missing logic + /* Create following fragments */ - while (outlen < len) + g_rime_hdrlen = SIXLOWPAN_FRAGN_HDR_LEN; + + while (outlen < sinfo->s_len) { /* Allocate an IOB to hold the next fragment, waiting if * necessary. @@ -471,11 +502,47 @@ int sixlowpan_send(FAR struct net_driver_s *dev, iob->io_offset = 0; iob->io_pktlen = 0; - /* Copy payload */ -# warning Missing logic + /* Add the frame header */ + + verify = sixlowpan_framecreate(ieee, iob, ieee->i_panid); + DEBUGASSERT(vreify == framer_hdrlen); + UNUSED(verify); + + /* Move HC1/HC06/IPv6 header */ + + memmove(g_rimeptr + SIXLOWPAN_FRAGN_HDR_LEN, g_rimeptr, g_rime_hdrlen); + + /* Setup up the fragment header */ + + PUTINT16(RIME_FRAG_PTR, RIME_FRAG_DISPATCH_SIZE, + ((SIXLOWPAN_DISPATCH_FRAGN << 8) | sinfo->s_len)); + PUTINT16(RIME_FRAG_PTR, RIME_FRAG_TAG, ieee->i_dgramtag); + RIME_FRAG_PTR[RIME_FRAG_OFFSET] = outlen >> 3; + + /* Copy payload and enqueue */ + + if (sinfo->s_len - outlen < g_rime_payloadlen) + { + /* Last fragment */ + + g_rime_payloadlen = sinfo->s_len - outlen; + } + else + { + g_rime_payloadlen = + (CONFIG_NET_6LOWPAN_MAXPAYLOAD - framer_hdrlen - g_rime_hdrlen) & 0xf8; + } + + memcpy(g_rimeptr + g_rime_hdrlen, (FAR uint8_t *) sinfo->s_destip + outlen, + g_rime_payloadlen); + iob->io_len = g_rime_payloadlen + g_rime_hdrlen; + + /* Set outlen to what we already sent from the IP payload */ + + outlen += (g_rime_payloadlen + g_uncomp_hdrlen); ninfo("sixlowpan output: fragment offset %d, len %d, tag %d\n", - outlen >> 3, g_rime_payloadlen, g_mytag); + outlen >> 3, g_rime_payloadlen, ieee->i_dgramtag); /* Add the next frame to the tail of the IOB queue */ @@ -484,16 +551,13 @@ int sixlowpan_send(FAR struct net_driver_s *dev, /* Keep track of the total amount of data queue */ ieee->i_framelist->io_pktlen += iob->io_len; - - /* Check tx result. */ -# warning Missing logic } /* Send the list of frames */ return sixlowpan_send_frame(ieee, ieee->i_framelist); #else - nerr("ERROR: Packet too large: %d\n", len); + nerr("ERROR: Packet too large: %d\n", sinfo->s_len); nerr(" Cannot to be sent without fragmentation support\n"); nerr(" dropping packet\n"); @@ -502,6 +566,8 @@ int sixlowpan_send(FAR struct net_driver_s *dev, } else { + int verify; + /* The packet does not need to be fragmented just copy the "payload" * and send in one frame. */ @@ -518,11 +584,17 @@ int sixlowpan_send(FAR struct net_driver_s *dev, iob->io_offset = 0; iob->io_pktlen = 0; - /* Format the single frame */ -# warning Missing logic + /* Add the frame header */ - /* Send the single frame */ -# warning Missing logic + verify = sixlowpan_framecreate(ieee, iob, ieee->i_panid); + DEBUGASSERT(vreify == framer_hdrlen); + UNUSED(verify); + + /* Copy the payload and queue */ + + memcpy(g_rimeptr + g_rime_hdrlen, (uint8_t *)sinfo->s_destip + g_uncomp_hdrlen, + sinfo->s_len - g_uncomp_hdrlen); + iob->io_len = sinfo->s_len - g_uncomp_hdrlen + g_rime_hdrlen; /* Add the first frame to the IOB queue */ @@ -535,5 +607,252 @@ int sixlowpan_send(FAR struct net_driver_s *dev, return sixlowpan_send_frame(ieee, iob); } } +/**************************************************************************** + * Function: send_timeout + * + * Description: + * Check for send timeout. + * + * Input Parameters: + * sinfo - Send state structure reference + * + * Returned Value: + * TRUE:timeout FALSE:no timeout + * + * Assumptions: + * The network is locked + * + ****************************************************************************/ + +#ifdef CONFIG_NET_SOCKOPTS +static inline int send_timeout(FAR struct sixlowpan_send_s *sinfo) +{ + /* Check for a timeout. Zero means none and, in that case, we will let + * the send wait forever. + */ + + if (sinfo->s_timeout != 0) + { + /* Check if the configured timeout has elapsed */ + /* REVISIT: I would need a psock to do this */ + + //return net_timeo(sinfo->s_time, psock->s_sndtimeo); +#warning Missing logic + } + + /* No timeout */ + + return FALSE; +} +#endif /* CONFIG_NET_SOCKOPTS */ + +/**************************************************************************** + * Function: tcpsend_interrupt + * + * Description: + * This function is called from the interrupt level to perform the actual + * send operation when polled by the lower, device interfacing layer. + * + * Parameters: + * dev - The structure of the network driver that caused the interrupt + * conn - The connection structure associated with the socket + * flags - Set of events describing why the callback was invoked + * + * Returned Value: + * None + * + * Assumptions: + * The network is locked. + * + ****************************************************************************/ + +static uint16_t send_interrupt(FAR struct net_driver_s *dev, + FAR void *pvconn, + FAR void *pvpriv, uint16_t flags) +{ + FAR struct sixlowpan_send_s *sinfo = (FAR struct sixlowpan_send_s *)pvpriv; + + ninfo("flags: %04x: %d\n", flags); + + /* Check if the IEEE802.15.4 went down */ + + if ((flags & NETDEV_DOWN) != 0) + { + ninfo("Device is down\n"); + sinfo->s_result = -ENOTCONN; + goto end_wait; + } + + /* Check for a poll for TX data. */ + + if ((flags & WPAN_NEWDATA) == 0) + { + DEBUGASSERT((flags & WPAN_POLL) != 0); + + /* Transfer the frame listto the IEEE802.15.4 MAC device */ + + sinfo->s_result = sixlowpan_queue_frames(dev, sinfo); + flags &= ~WPAN_POLL; + goto end_wait; + } + +#ifdef CONFIG_NET_SOCKOPTS + /* All data has been sent and we are just waiting for ACK or re-transmit + * indications to complete the send. Check for a timeout. + */ + + if (send_timeout(sinfo)) + { + /* Yes.. report the timeout */ + + nwarn("WARNING: SEND timeout\n"); + sinfo->s_result = -ETIMEDOUT; + goto end_wait; + } +#endif /* CONFIG_NET_SOCKOPTS */ + + /* Continue waiting */ + + return flags; + +end_wait: + /* Do not allow any further callbacks */ + + sinfo->s_cb->flags = 0; + sinfo->s_cb->priv = NULL; + sinfo->s_cb->event = NULL; + + /* Wake up the waiting thread */ + + sem_post(&sinfo->s_waitsem); + return flags; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: sixlowpan_send + * + * Description: + * Process an outgoing UDP or TCP packet. Takes an IP packet and formats + * it to be sent on an 802.15.4 network using 6lowpan. Called from common + * UDP/TCP send logic. + * + * The payload data is in the caller 'buf' and is of length 'len'. + * Compressed headers will be added and if necessary the packet is + * fragmented. The resulting packet/fragments are put in ieee->i_framelist + * and the entire list of frames will be delivered to the 802.15.4 MAC via + * ieee->i_framelist. + * + * Input Parameters: + * dev - The IEEE802.15.4 MAC network driver interface. + * ipv6 - IPv6 plus TCP or UDP headers. + * buf - Data to send + * len - Length of data to send + * raddr - The IEEE802.15.4 MAC address of the destination + * timeout - Send timeout in deciseconds + * + * Returned Value: + * Ok is returned on success; Othewise a negated errno value is returned. + * This function is expected to fail if the driver is not an IEEE802.15.4 + * MAC network driver. In that case, the UDP/TCP will fall back to normal + * IPv4/IPv6 formatting. + * + * Assumptions: + * Called with the network locked. + * + ****************************************************************************/ + +int sixlowpan_send(FAR struct net_driver_s *dev, + FAR const struct ipv6_hdr_s *ipv6, FAR const void *buf, + size_t len, FAR const struct rimeaddr_s *raddr, + uint16_t timeout) +{ + struct sixlowpan_send_s sinfo; + + /* Initialize the send state structure */ + + sem_init(&sinfo.s_waitsem, 0, 0); + (void)sem_setprotocol(&sinfo.s_waitsem, SEM_PRIO_NONE); + + sinfo.s_result = -EBUSY; + sinfo.s_destip = ipv6; + sinfo.s_destmac = raddr; + sinfo.s_buf = buf; + sinfo.s_len = len; + +#ifdef CONFIG_NET_SOCKOPTS + sinfo.s_timeout = timeout; + sinfo.s_time = clock_systimer(); +#endif + + /* Set the socket state to sending */ + /* REVISIT: We would need a psock to do this. Already done by caller. */ + + //psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_SEND); +#warning Missing logic + + net_lock(); + if (len > 0) + { + /* Allocate resources to receive a callback */ + /* REVISIT: Need a psock instance to get the second argument + * to devif_conn_callback_alloc(). + */ + + sinfo.s_cb = devif_callback_alloc(dev, NULL); + if (sinfo.s_cb != NULL) + { + int ret; + + /* Set up the callback in the connection */ + + sinfo.s_cb->flags = (NETDEV_DOWN | WPAN_POLL); + sinfo.s_cb->priv = (FAR void *)&sinfo; + sinfo.s_cb->event = send_interrupt; + + /* Notify the the IEEE802.15.4 MAC that we have data to send. */ + /* REVISIT: Need a psock instance for the arguments to + * send_txnotify(). + */ + + // send_txnotify(psock, conn); +#warning Missing logic + + /* Wait for the send to complete or an error to occur: NOTES: (1) + * net_lockedwait will also terminate if a signal is received, (2) interrupts + * may be disabled! They will be re-enabled while the task sleeps and + * automatically re-enabled when the task restarts. + */ + + ret = net_lockedwait(&sinfo.s_waitsem); + if (ret < 0) + { + sinfo.s_result = -get_errno(); + } + + /* Make sure that no further interrupts are processed */ + /* REVISIT: Need a psock instance to get the arguments + * to devif_conn_callback_free(). + */ + + //devif_conn_callback_free(conn, sinfo.s_cb, NULL); +#warning Missing logic + } + } + + sem_destroy(&sinfo.s_waitsem); + net_unlock(); + + /* Set the socket state to idle */ + /* REVISIT: Again, need a psock instance */ + + // psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_IDLE); +#warning Missing logic + + return (sinfo.s_result < 0 ? sinfo.s_result : len); +} #endif /* CONFIG_NET_6LOWPAN */ diff --git a/net/sixlowpan/sixlowpan_tcpsend.c b/net/sixlowpan/sixlowpan_tcpsend.c index 4e9f01d237..c84e04e388 100644 --- a/net/sixlowpan/sixlowpan_tcpsend.c +++ b/net/sixlowpan/sixlowpan_tcpsend.c @@ -86,6 +86,7 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, FAR struct net_driver_s *dev; struct ipv6tcp_hdr_s ipv6tcp; struct rimeaddr_s dest; + uint16_t timeout; int ret; DEBUGASSERT(psock != NULL && psock->s_crefs > 0); @@ -173,8 +174,14 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, * packet. */ +#ifdef CONFIG_NET_SOCKOPTS + timeout = psock->s_sndtimeo; +#else + timeout = 0; +#endif + ret = sixlowpan_send(dev, (FAR const struct ipv6_hdr_s *)&ipv6tcp, - buf, len, &dest); + buf, len, &dest, timeout); if (ret < 0) { nerr("ERROR: sixlowpan_send() failed: %d\n", ret); diff --git a/net/sixlowpan/sixlowpan_udpsend.c b/net/sixlowpan/sixlowpan_udpsend.c index 7f55810180..5f76245f76 100644 --- a/net/sixlowpan/sixlowpan_udpsend.c +++ b/net/sixlowpan/sixlowpan_udpsend.c @@ -86,6 +86,7 @@ ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, FAR struct net_driver_s *dev; struct ipv6udp_hdr_s ipv6udp; struct rimeaddr_s dest; + uint16_t timeout; int ret; DEBUGASSERT(psock != NULL && psock->s_crefs > 0); @@ -174,8 +175,14 @@ ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, * packet. */ +#ifdef CONFIG_NET_SOCKOPTS + timeout = psock->s_sndtimeo; +#else + timeout = 0; +#endif + ret = sixlowpan_send(dev, (FAR const struct ipv6_hdr_s *)&ipv6udp, - buf, len, &dest); + buf, len, &dest, timeout); if (ret < 0) { nerr("ERROR: sixlowpan_send() failed: %d\n", ret); diff --git a/net/tcp/tcp_send_unbuffered.c b/net/tcp/tcp_send_unbuffered.c index 6c3688d85a..5a2ccc98c4 100644 --- a/net/tcp/tcp_send_unbuffered.c +++ b/net/tcp/tcp_send_unbuffered.c @@ -129,7 +129,7 @@ struct send_s * TRUE:timeout FALSE:no timeout * * Assumptions: - * Running at the interrupt level + * The network is locked. * ****************************************************************************/ @@ -139,7 +139,7 @@ static inline int send_timeout(FAR struct send_s *pstate) FAR struct socket *psock; /* Check for a timeout configured via setsockopts(SO_SNDTIMEO). - * If none... we well let the send wait forever. + * If none... we will let the send wait forever. */ psock = pstate->snd_sock; @@ -173,7 +173,7 @@ static inline int send_timeout(FAR struct send_s *pstate) * None * * Assumptions: - * Running at the interrupt level + * The network is locked. * ****************************************************************************/ @@ -224,7 +224,7 @@ static inline void tcpsend_ipselect(FAR struct net_driver_s *dev, * None * * Assumptions: - * Running at the interrupt level + * The network is locked. * ****************************************************************************/ @@ -278,7 +278,7 @@ static inline bool psock_send_addrchck(FAR struct tcp_conn_s *conn) * None * * Assumptions: - * Running at the interrupt level + * The network is locked. * ****************************************************************************/ @@ -708,8 +708,6 @@ static inline void send_txnotify(FAR struct socket *psock, * In this case the process will also receive a SIGPIPE unless * MSG_NOSIGNAL is set. * - * Assumptions: - * ****************************************************************************/ ssize_t psock_tcp_send(FAR struct socket *psock, -- GitLab From 503f3e5477e4cdaf939a289815ff398539f4b95f Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 31 Mar 2017 15:54:12 -0600 Subject: [PATCH 296/990] net/: Struggling with MSS definitions. --- include/nuttx/net/netconfig.h | 136 +++++++++++++++++++++++++--------- 1 file changed, 100 insertions(+), 36 deletions(-) diff --git a/include/nuttx/net/netconfig.h b/include/nuttx/net/netconfig.h index 77689ae32c..0e912a5352 100644 --- a/include/nuttx/net/netconfig.h +++ b/include/nuttx/net/netconfig.h @@ -295,47 +295,113 @@ #endif /* The UDP maximum packet size. This is should not be to set to more - * than NET_DEV_MTU(d) - NET_LL_HDRLEN(dev) - IPv4UDP_HDRLEN. + * than NET_DEV_MTU(d) - NET_LL_HDRLEN(dev) - IPv*_HDRLEN. + * + * REVISIT: It is unclear to me if the UDP_HDRLEN should subtracted + * or not. */ -#define UDP_MSS(d,h) (NET_DEV_MTU(d) - NET_LL_HDRLEN(d) - (h)) - -/* If Ethernet is supported, then it will have the smaller MSS */ +#define UDP_MSS(d,h) (NET_DEV_MTU(d) - NET_LL_HDRLEN(d) (h)) -#if defined(CONFIG_NET_SLIP) -# define SLIP_UDP_MSS(h) (CONFIG_NET_SLIP_MTU - (h)) -# define __MIN_UDP_MSS(h) SLIP_UDP_MSS(h) -#elif defined(CONFIG_NET_LOOPBACK) -# define LO_UDP_MSS(h) (NET_LO_MTU - (h)) -# define __MIN_UDP_MSS(h) LO_UDP_MSS(h) +#ifdef CONFIG_NET_ETHERNET +# define ETH_UDP_MSS(h) (CONFIG_NET_ETH_MTU - ETH_HDRLEN - (h)) +# ifndef CONFIG_NET_MULTILINK +# define __MIN_UDP_MSS(h) ETH_UDP_MSS(h) +# define __MAX_UDP_MSS(h) ETH_UDP_MSS(h) +# endif #endif -#ifdef CONFIG_NET_ETHERNET -# define ETH_UDP_MSS(h) (CONFIG_NET_ETH_MTU - ETH_HDRLEN - (h)) -# undef __MIN_UDP_MSS -# define __MIN_UDP_MSS(h) ETH_UDP_MSS(h) -# define __MAX_UDP_MSS(h) ETH_UDP_MSS(h) +#ifdef CONFIG_NET_6LOWPAN +# define IEEE802154_UDP_MSS(h) (CONFIG_NET_6LOWPAN_MAXPAYLOAD - (h)) +# ifndef CONFIG_NET_MULTILINK +# define __MIN_UDP_MSS(h) IEEE802154_UDP_MSS(h) +# define __MAX_UDP_MSS(h) IEEE802154_UDP_MSS(h) +# endif #endif -/* If SLIP is supported, then it will have the larger MSS */ +#ifdef CONFIG_NET_LOOPBACK +# define LO_UDP_MSS(h) (NET_LO_MTU - (h)) +# ifndef CONFIG_NET_MULTILINK +# define __MIN_UDP_MSS(h) LO_UDP_MSS(h) +# define __MAX_UDP_MSS(h) LO_UDP_MSS(h) +# endif +#endif #ifdef CONFIG_NET_SLIP -# undef __MAX_UDP_MSS -# define __MAX_UDP_MSS(h) SLIP_UDP_MSS(h) +# define SLIP_UDP_MSS(h) (CONFIG_NET_SLIP_MTU - (h)) +# ifndef CONFIG_NET_MULTILINK +# define __MIN_UDP_MSS(h) SLIP_UDP_MSS(h) +# define __MAX_UDP_MSS(h) SLIP_UDP_MSS(h) +# endif #endif -/* If IPv4 is supported, it will have the larger MSS */ +#ifdef CONFIG_NET_MULTILINK +# undef __LAST_MIN_UDP_MSS +# undef __LAST_MAX_UDP_MSS -#ifdef CONFIG_NET_IPv6 -# define UDP_IPv6_MSS(d) UDP_MSS(d,IPv6_HDRLEN) -# define ETH_IPv6_UDP_MSS ETH_UDP_MSS(IPv6_HDRLEN) -# define SLIP_IPv6_UDP_MSS SLIP_UDP_MSS(IPv6_HDRLEN) +# ifdef CONFIG_NET_ETHERNET +# ifdef __LAST_MIN_UDP_MSS +# define __MIN_UDP_MSS(h) MIN(ETH_UDP_MSS(h),__LAST_MIN_UDP_MSS(h)) +# define __MAX_UDP_MSS(h) MAX(ETH_UDP_MSS(h),__LAST_MAX_UDP_MSS(h)) +# else +# define __MIN_UDP_MSS(h) ETH_UDP_MSS(h) +# define __MAX_UDP_MSS(h) ETH_UDP_MSS(h) +# endif +# undef __LAST_MIN_UDP_MSS +# undef __LAST_MAX_UDP_MSS +# define __LAST_MIN_UDP_MSS(h) __MIN_UDP_MSS(h) +# define __LAST_MAX_UDP_MSS(h) __MAX_UDP_MSS(h) +# endif -# define MAX_IPv6_UDP_MSS __MAX_UDP_MSS(IPv6_HDRLEN) -# define MAX_UDP_MSS __MAX_UDP_MSS(IPv6_HDRLEN) +# ifdef CONFIG_NET_6LOWPAN +# ifdef __LAST_MIN_UDP_MSS +# define __MIN_UDP_MSS(h) MIN(IEEE802154_UDP_MSS(h),__LAST_MIN_UDP_MSS(h)) +# define __MAX_UDP_MSS(h) MAX(IEEE802154_UDP_MSS(h),__LAST_MAX_UDP_MSS(h)) +# else +# define __MIN_UDP_MSS(h) IEEE802154_UDP_MSS(h) +# define __MAX_UDP_MSS(h) IEEE802154_UDP_MSS(h) +# endif +# undef __LAST_MIN_UDP_MSS +# undef __LAST_MAX_UDP_MSS +# define __LAST_MIN_UDP_MSS(h) __MIN_UDP_MSS(h) +# define __LAST_MAX_UDP_MSS(h) __MAX_UDP_MSS(h) +# endif + +# ifdef CONFIG_NET_LOOPBACK +# ifdef __LAST_MIN_UDP_MSS +# define __MIN_UDP_MSS(h) MIN(LO_UDP_MSS(h),__LAST_MIN_UDP_MSS(h)) +# define __MAX_UDP_MSS(h) MAX(LO_UDP_MSS(h),__LAST_MAX_UDP_MSS(h)) +# else +# define __MIN_UDP_MSS(h) LO_UDP_MSS(h) +# define __MAX_UDP_MSS(h) LO_UDP_MSS(h) +# endif +# undef __LAST_MIN_UDP_MSS +# undef __LAST_MAX_UDP_MSS +# define __LAST_MIN_UDP_MSS(h) __MIN_UDP_MSS(h) +# define __LAST_MAX_UDP_MSS(h) __MAX_UDP_MSS(h) +# endif + +# ifdef CONFIG_NET_SLIP +# ifdef __LAST_MIN_UDP_MSS +# define __MIN_UDP_MSS(h) MIN(SLIP_UDP_MSS(h),__LAST_MIN_UDP_MSS(h)) +# define __MAX_UDP_MSS(h) MAX(SLIP_UDP_MSS(h),__LAST_MAX_UDP_MSS(h)) +# else +# define __MIN_UDP_MSS(h) SLIP_UDP_MSS(h) +# define __MAX_UDP_MSS(h) SLIP_UDP_MSS(h) +# endif +# undef __LAST_MIN_UDP_MSS +# undef __LAST_MAX_UDP_MSS +# define __LAST_MIN_UDP_MSS(h) __MIN_UDP_MSS(h) +# define __LAST_MAX_UDP_MSS(h) __MAX_UDP_MSS(h) +# endif + +# undef __LAST_MIN_UDP_MSS +# undef __LAST_MAX_UDP_MSS #endif -#ifdef CONFIG_NET_IPv4 +/* NOTE: MSS calcuation excludes the UDP_HDRLEN. */ + + #ifdef CONFIG_NET_IPv4 # define UDP_IPv4_MSS(d) UDP_MSS(d,IPv4_HDRLEN) # define ETH_IPv4_UDP_MSS ETH_UDP_MSS(IPv4_HDRLEN) # define SLIP_IPv4_UDP_MSS SLIP_UDP_MSS(IPv4_HDRLEN) @@ -422,12 +488,15 @@ * link layer protocols (CONFIG_NET_MULTILINK), each network device * may support a different UDP MSS value. Here we arbitrarily select * the minimum MSS for that case. + * + * REVISIT: It is unclear to me if the TCP_HDRLEN should subtracted + * or not. */ -#define TCP_MSS(d,h) (NET_DEV_MTU(d) - NET_LL_HDRLEN(d) - TCP_HDRLEN - (h)) +#define TCP_MSS(d,h) (NET_DEV_MTU(d) - NET_LL_HDRLEN(d) - (h)) #define LO_TCP_MSS(h) (NET_LO_MTU - (h)) -/* Get the smallest and largest */ +/* Get the smallest and largest MSS */ #ifdef CONFIG_NET_ETHERNET # define ETH_TCP_MSS(h) (CONFIG_NET_ETH_MTU - ETH_HDRLEN - (h)) @@ -525,14 +594,9 @@ # undef __LAST_MAX_TCP_MSS #endif -/* If SLIP is supported, then it will have the larger MSS */ - -#ifdef CONFIG_NET_SLIP -# undef __MAX_TCP_MSS -# define __MAX_TCP_MSS(h) SLIP_TCP_MSS(h) -#endif - -/* If IPv4 is support, it will have the larger MSS */ +/* If IPv4 is supported, it will have the larger MSS. + * NOTE: MSS calcuation excludes the TCP_HDRLEN. + */ #ifdef CONFIG_NET_IPv6 # define TCP_IPv6_MSS(d) TCP_MSS(d,IPv6_HDRLEN) -- GitLab From cccbb6c693f68c51127c4a004e6d47efbd31fd94 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 31 Mar 2017 16:33:21 -0600 Subject: [PATCH 297/990] 6loWPAN: Clean up some send logic; remove sniffer. --- include/nuttx/net/sixlowpan.h | 28 ----- net/sixlowpan/Kconfig | 6 - net/sixlowpan/Make.defs | 4 - net/sixlowpan/sixlowpan_globals.c | 6 - net/sixlowpan/sixlowpan_input.c | 56 +++++++++ net/sixlowpan/sixlowpan_internal.h | 7 -- net/sixlowpan/sixlowpan_send.c | 182 ++++------------------------- net/sixlowpan/sixlowpan_sniffer.c | 80 ------------- net/sixlowpan/sixlowpan_tcpsend.c | 3 + net/sixlowpan/sixlowpan_udpsend.c | 3 + net/socket/net_timeo.c | 1 + 11 files changed, 85 insertions(+), 291 deletions(-) delete mode 100644 net/sixlowpan/sixlowpan_sniffer.c diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index 1fbfee79b4..db4bbd1d02 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -454,14 +454,6 @@ struct sixlowpan_nhcompressor_s FAR uint8_t *uncompressed_len); }; -/* RIME sniffer callbacks */ - -struct sixlowpan_rime_sniffer_s -{ - CODE void (*input)(void); - CODE void (*output)(int mac_status); -}; - /**************************************************************************** * Public Function Prototypes ****************************************************************************/ @@ -483,24 +475,4 @@ struct sixlowpan_rime_sniffer_s void sixlowpan_set_compressor(FAR struct sixlowpan_nhcompressor_s *compressor); -/**************************************************************************** - * Function: sixlowpan_set_sniffer - * - * Description: - * Configure to use an architecture-specific sniffer to enable tracing of - * IP. - * - * Input parameters: - * sniffer - A reference to the new sniffer to be used. This may - * be a NULL value to disable the sniffer. - * - * Returned Value: - * None - * - ****************************************************************************/ - -#ifdef CONFIG_NET_6LOWPAN_SNIFFER -void sixlowpan_set_sniffer(FAR struct sixlowpan_rime_sniffer_s *sniffer); -#endif - #endif /* __INCLUDE_NUTTX_NET_SIXLOWOAN_H */ diff --git a/net/sixlowpan/Kconfig b/net/sixlowpan/Kconfig index 4b4c6ad9eb..4d0be0b660 100644 --- a/net/sixlowpan/Kconfig +++ b/net/sixlowpan/Kconfig @@ -178,10 +178,4 @@ config NET_6LOWPAN_TCP_RECVWNDO the application is slow to process incoming data, or high (32768 bytes) if the application processes data quickly. -config NET_6LOWPAN_SNIFFER - default n - ---help--- - Enable use use an architecture-specific sniffer to support tracing - of IP. - endif # NET_6LOWPAN diff --git a/net/sixlowpan/Make.defs b/net/sixlowpan/Make.defs index e0370185e6..becc0a7edd 100644 --- a/net/sixlowpan/Make.defs +++ b/net/sixlowpan/Make.defs @@ -59,10 +59,6 @@ ifeq ($(CONFIG_NET_6LOWPAN_COMPRESSION_HC06),y) NET_CSRCS += sixlowpan_hc06.c endif -ifeq ($(CONFIG_NET_6LOWPAN_SNIFFER),y) -NET_CSRCS += sixlowpan_sniffer.c -endif - # Include the sixlowpan directory in the build DEPPATH += --dep-path sixlowpan diff --git a/net/sixlowpan/sixlowpan_globals.c b/net/sixlowpan/sixlowpan_globals.c index b62c3e110f..6b0f5bcf74 100644 --- a/net/sixlowpan/sixlowpan_globals.c +++ b/net/sixlowpan/sixlowpan_globals.c @@ -51,12 +51,6 @@ FAR struct sixlowpan_nhcompressor_s *g_sixlowpan_compressor; -#ifdef CONFIG_NET_6LOWPAN_SNIFFER -/* A pointer to the optional, architecture-specific sniffer */ - -FAR struct sixlowpan_rime_sniffer_s *g_sixlowpan_sniffer; -#endif - /* The following data values are used to hold intermediate settings while * processing IEEE802.15.4 frames. These globals are shared with incoming * and outgoing frame processing and possibly with mutliple IEEE802.15.4 MAC diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index ce520f8e5e..466069f2d5 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -79,6 +79,62 @@ static bool sixlowpan_isbroadcast(uint8_t mode, FAR uint8_t *addr) return true; } +/**************************************************************************** + * Name: sixlowpan_set_pktattrs + * + * Description: + * Setup some packet buffer attributes + * + * Input Parameters: + * ieee - Pointer to IEEE802.15.4 MAC driver structure. + * ipv6 - Pointer to the IPv6 header to "compress" + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void sixlowpan_set_pktattrs(FAR struct ieee802154_driver_s *ieee, + FAR const struct ipv6_hdr_s *ipv6) +{ + int attr = 0; + + /* Set protocol in NETWORK_ID */ + + g_pktattrs[PACKETBUF_ATTR_NETWORK_ID] = ipv6->proto; + + /* Assign values to the channel attribute (port or type + code) */ + + if (ipv6->proto == IP_PROTO_UDP) + { + FAR struct udp_hdr_s *udp = &((FAR struct ipv6udp_hdr_s *)ipv6)->udp; + + attr = udp->srcport; + if (udp->destport < attr) + { + attr = udp->destport; + } + } + else if (ipv6->proto == IP_PROTO_TCP) + { + FAR struct tcp_hdr_s *tcp = &((FAR struct ipv6tcp_hdr_s *)ipv6)->tcp; + + attr = tcp->srcport; + if (tcp->destport < attr) + { + attr = tcp->destport; + } + } + else if (ipv6->proto == IP_PROTO_ICMP6) + { + FAR struct icmpv6_iphdr_s *icmp = &((FAR struct ipv6icmp_hdr_s *)ipv6)->icmp; + + attr = icmp->type << 8 | icmp->code; + } + + g_pktattrs[PACKETBUF_ATTR_CHANNEL] = attr; +} + /**************************************************************************** * Public Functions ****************************************************************************/ diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index 3bf65fc09c..d96c4213b7 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -340,13 +340,6 @@ struct frame802154_s struct sixlowpan_nhcompressor_s; /* Foward reference */ extern FAR struct sixlowpan_nhcompressor_s *g_sixlowpan_compressor; -#ifdef CONFIG_NET_6LOWPAN_SNIFFER -/* Rime Sniffer support for one single listener to enable trace of IP */ - -struct sixlowpan_rime_sniffer_s; /* Foward reference */ -extern FAR struct sixlowpan_rime_sniffer_s *g_sixlowpan_sniffer; -#endif - /* The following data values are used to hold intermediate settings while * processing IEEE802.15.4 frames. These globals are shared with incoming * and outgoing frame processing and possibly with mutliple IEEE802.15.4 MAC diff --git a/net/sixlowpan/sixlowpan_send.c b/net/sixlowpan/sixlowpan_send.c index 69bf3b8392..12420a2574 100644 --- a/net/sixlowpan/sixlowpan_send.c +++ b/net/sixlowpan/sixlowpan_send.c @@ -103,10 +103,8 @@ struct sixlowpan_send_s FAR struct devif_callback_s *s_cb; /* Reference to callback instance */ sem_t s_waitsem; /* Supports waiting for driver events */ int s_result; /* The result of the transfer */ -#ifdef CONFIG_NET_SOCKOPTS uint16_t s_timeout; /* Send timeout in deciseconds */ systime_t s_time; /* Last send time for determining timeout */ -#endif FAR const struct ipv6_hdr_s *s_destip; /* Destination IP address */ FAR const struct rimeaddr_s *s_destmac; /* Destination MAC address */ FAR const void *s_buf; /* Data to send */ @@ -117,63 +115,6 @@ struct sixlowpan_send_s * Private Functions ****************************************************************************/ -/**************************************************************************** - * Name: sixlowpan_set_pktattrs - * - * Description: - * Setup some packet buffer attributes - * - * Input Parameters: - * ieee - Pointer to IEEE802.15.4 MAC driver structure. - * ipv6 - Pointer to the IPv6 header to "compress" - * - * Returned Value: - * None - * - ****************************************************************************/ - -/* REVISIT: This is use in input function, but only for sniffer on output */ -static void sixlowpan_set_pktattrs(FAR struct ieee802154_driver_s *ieee, - FAR const struct ipv6_hdr_s *ipv6) -{ - int attr = 0; - - /* Set protocol in NETWORK_ID */ - - g_pktattrs[PACKETBUF_ATTR_NETWORK_ID] = ipv6->proto; - - /* Assign values to the channel attribute (port or type + code) */ - - if (ipv6->proto == IP_PROTO_UDP) - { - FAR struct udp_hdr_s *udp = &((FAR struct ipv6udp_hdr_s *)ipv6)->udp; - - attr = udp->srcport; - if (udp->destport < attr) - { - attr = udp->destport; - } - } - else if (ipv6->proto == IP_PROTO_TCP) - { - FAR struct tcp_hdr_s *tcp = &((FAR struct ipv6tcp_hdr_s *)ipv6)->tcp; - - attr = tcp->srcport; - if (tcp->destport < attr) - { - attr = tcp->destport; - } - } - else if (ipv6->proto == IP_PROTO_ICMP6) - { - FAR struct icmpv6_iphdr_s *icmp = &((FAR struct ipv6icmp_hdr_s *)ipv6)->icmp; - - attr = icmp->type << 8 | icmp->code; - } - - g_pktattrs[PACKETBUF_ATTR_CHANNEL] = attr; -} - /**************************************************************************** * Name: sixlowpan_compress_ipv6hdr * @@ -214,33 +155,6 @@ static void sixlowpan_compress_ipv6hdr(FAR struct ieee802154_driver_s *ieee, g_uncomp_hdrlen += IPv6_HDRLEN; } -/**************************************************************************** - * Name: sixlowpan_send_frame - * - * Description: - * Send one frame when the IEEE802.15.4 MAC device next polls. - * - * Input Parameters: - * ieee - Pointer to IEEE802.15.4 MAC driver structure. - * iobq - The list of frames to send. - * - * Returned Value: - * Zero (OK) on success; otherwise a negated errno value is returned. - * - ****************************************************************************/ - -static int sixlowpan_send_frame(FAR struct ieee802154_driver_s *ieee, - FAR struct iob_s *iobq) -{ - /* Prepare the frame */ -#warning Missing logic - /* Notify the IEEE802.14.5 MAC driver that we have data to be sent */ -#warning Missing logic - /* Wait for the transfer to complete */ -#warning Missing logic - return -ENOSYS; -} - /**************************************************************************** * Name: sixlowpan_queue_frames * @@ -297,31 +211,6 @@ int sixlowpan_queue_frames(FAR struct net_driver_s *dev, g_pktattrs[PACKETBUF_ATTR_MAX_MAC_TRANSMISSIONS] = CONFIG_NET_6LOWPAN_MAX_MACTRANSMITS; -#ifdef CONFIG_NET_6LOWPAN_SNIFFER - if (g_sixlowpan_sniffer != NULL) - { - /* Reset rime buffer, packet buffer metatadata */ - - memset(g_pktattrs, 0, PACKETBUF_NUM_ATTRS * sizeof(uint16_t)); - memset(g_pktaddrs, 0, PACKETBUF_NUM_ADDRS * sizeof(struct rimeaddr_s)); - - g_pktattrs[PACKETBUF_ATTR_MAX_MAC_TRANSMISSIONS] = - CONFIG_NET_6LOWPAN_MAX_MACTRANSMITS; - - /* Call the attribution when the callback comes, but set attributes here */ - - sixlowpan_set_pktattrs(ieee, sinfo->s_destip); - } -#endif - - /* Reset rime buffer, packet buffer metatadata */ - - memset(g_pktattrs, 0, PACKETBUF_NUM_ATTRS * sizeof(uint16_t)); - memset(g_pktaddrs, 0, PACKETBUF_NUM_ADDRS * sizeof(struct rimeaddr_s)); - - g_pktattrs[PACKETBUF_ATTR_MAX_MAC_TRANSMISSIONS] = - CONFIG_NET_6LOWPAN_MAX_MACTRANSMITS; - /* Set stream mode for all TCP packets, except FIN packets. */ if (sinfo->s_destip->proto == IP_PROTO_TCP) @@ -552,10 +441,6 @@ int sixlowpan_queue_frames(FAR struct net_driver_s *dev, ieee->i_framelist->io_pktlen += iob->io_len; } - - /* Send the list of frames */ - - return sixlowpan_send_frame(ieee, ieee->i_framelist); #else nerr("ERROR: Packet too large: %d\n", sinfo->s_len); nerr(" Cannot to be sent without fragmentation support\n"); @@ -603,10 +488,11 @@ int sixlowpan_queue_frames(FAR struct net_driver_s *dev, /* Keep track of the total amount of data queue */ iob->io_pktlen = iob->io_len; - - return sixlowpan_send_frame(ieee, iob); } + + return OK; } + /**************************************************************************** * Function: send_timeout * @@ -624,8 +510,7 @@ int sixlowpan_queue_frames(FAR struct net_driver_s *dev, * ****************************************************************************/ -#ifdef CONFIG_NET_SOCKOPTS -static inline int send_timeout(FAR struct sixlowpan_send_s *sinfo) +static inline bool send_timeout(FAR struct sixlowpan_send_s *sinfo) { /* Check for a timeout. Zero means none and, in that case, we will let * the send wait forever. @@ -634,17 +519,20 @@ static inline int send_timeout(FAR struct sixlowpan_send_s *sinfo) if (sinfo->s_timeout != 0) { /* Check if the configured timeout has elapsed */ - /* REVISIT: I would need a psock to do this */ - //return net_timeo(sinfo->s_time, psock->s_sndtimeo); -#warning Missing logic + systime_t timeo_ticks = DSEC2TICK(sinfo->s_timeout); + systime_t elapsed = clock_systimer() - sinfo->s_time; + + if (elapsed >= timeo_ticks) + { + return true; + } } /* No timeout */ - return FALSE; + return false; } -#endif /* CONFIG_NET_SOCKOPTS */ /**************************************************************************** * Function: tcpsend_interrupt @@ -696,10 +584,7 @@ static uint16_t send_interrupt(FAR struct net_driver_s *dev, goto end_wait; } -#ifdef CONFIG_NET_SOCKOPTS - /* All data has been sent and we are just waiting for ACK or re-transmit - * indications to complete the send. Check for a timeout. - */ + /* Check for a timeout. */ if (send_timeout(sinfo)) { @@ -709,7 +594,6 @@ static uint16_t send_interrupt(FAR struct net_driver_s *dev, sinfo->s_result = -ETIMEDOUT; goto end_wait; } -#endif /* CONFIG_NET_SOCKOPTS */ /* Continue waiting */ @@ -778,28 +662,20 @@ int sixlowpan_send(FAR struct net_driver_s *dev, (void)sem_setprotocol(&sinfo.s_waitsem, SEM_PRIO_NONE); sinfo.s_result = -EBUSY; + sinfo.s_timeout = timeout; + sinfo.s_time = clock_systimer(); sinfo.s_destip = ipv6; sinfo.s_destmac = raddr; sinfo.s_buf = buf; sinfo.s_len = len; -#ifdef CONFIG_NET_SOCKOPTS - sinfo.s_timeout = timeout; - sinfo.s_time = clock_systimer(); -#endif - - /* Set the socket state to sending */ - /* REVISIT: We would need a psock to do this. Already done by caller. */ - - //psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_SEND); -#warning Missing logic - net_lock(); if (len > 0) { - /* Allocate resources to receive a callback */ - /* REVISIT: Need a psock instance to get the second argument - * to devif_conn_callback_alloc(). + /* Allocate resources to receive a callback. + * + * The second parameter is NULL meaning that we can get only + * device related events, no connect-related events. */ sinfo.s_cb = devif_callback_alloc(dev, NULL); @@ -814,12 +690,8 @@ int sixlowpan_send(FAR struct net_driver_s *dev, sinfo.s_cb->event = send_interrupt; /* Notify the the IEEE802.15.4 MAC that we have data to send. */ - /* REVISIT: Need a psock instance for the arguments to - * send_txnotify(). - */ - // send_txnotify(psock, conn); -#warning Missing logic + netdev_txnotify_dev(dev); /* Wait for the send to complete or an error to occur: NOTES: (1) * net_lockedwait will also terminate if a signal is received, (2) interrupts @@ -834,25 +706,15 @@ int sixlowpan_send(FAR struct net_driver_s *dev, } /* Make sure that no further interrupts are processed */ - /* REVISIT: Need a psock instance to get the arguments - * to devif_conn_callback_free(). - */ - //devif_conn_callback_free(conn, sinfo.s_cb, NULL); -#warning Missing logic + devif_dev_callback_free(dev, sinfo.s_cb); } } sem_destroy(&sinfo.s_waitsem); net_unlock(); - /* Set the socket state to idle */ - /* REVISIT: Again, need a psock instance */ - - // psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_IDLE); -#warning Missing logic - - return (sinfo.s_result < 0 ? sinfo.s_result : len); + return (sinfo.s_result < 0 ? sinfo.s_result : len); } #endif /* CONFIG_NET_6LOWPAN */ diff --git a/net/sixlowpan/sixlowpan_sniffer.c b/net/sixlowpan/sixlowpan_sniffer.c deleted file mode 100644 index eb8a77e3f7..0000000000 --- a/net/sixlowpan/sixlowpan_sniffer.c +++ /dev/null @@ -1,80 +0,0 @@ -/**************************************************************************** - * net/sixlowpan/sixlowpan_sniffer.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include "nuttx/net/net.h" - -#include "sixlowpan/sixlowpan_internal.h" - -#ifdef CONFIG_NET_6LOWPAN_SNIFFER - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: sixlowpan_set_sniffer - * - * Description: - * Configure to use an architecture-specific sniffer to enable tracing of - * IP. - * - * Input parameters: - * sniffer - A reference to the new sniffer to be used. This may - * be a NULL value to disable the sniffer. - * - * Returned Value: - * None - * - ****************************************************************************/ - -void sixlowpan_set_sniffer(FAR struct sixlowpan_rime_sniffer_s *sniffer) -{ - /* Make sure that the sniffer is not in use */ - - net_lock(); - - /* Then instantiate the new sniffer */ - - g_sixlowpan_sniffer = sniffer; - net_unlock(); -} - -#endif /* CONFIG_NET_6LOWPAN_SNIFFER */ diff --git a/net/sixlowpan/sixlowpan_tcpsend.c b/net/sixlowpan/sixlowpan_tcpsend.c index c84e04e388..7089b19b27 100644 --- a/net/sixlowpan/sixlowpan_tcpsend.c +++ b/net/sixlowpan/sixlowpan_tcpsend.c @@ -187,6 +187,9 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, nerr("ERROR: sixlowpan_send() failed: %d\n", ret); } + /* Set the socket state to idle */ + + psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_IDLE); return ret; } diff --git a/net/sixlowpan/sixlowpan_udpsend.c b/net/sixlowpan/sixlowpan_udpsend.c index 5f76245f76..18f9ea8ac1 100644 --- a/net/sixlowpan/sixlowpan_udpsend.c +++ b/net/sixlowpan/sixlowpan_udpsend.c @@ -188,6 +188,9 @@ ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, nerr("ERROR: sixlowpan_send() failed: %d\n", ret); } + /* Set the socket state to idle */ + + psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_IDLE); return ret; } diff --git a/net/socket/net_timeo.c b/net/socket/net_timeo.c index 47099d205d..81b7123a31 100644 --- a/net/socket/net_timeo.c +++ b/net/socket/net_timeo.c @@ -78,6 +78,7 @@ int net_timeo(systime_t start_time, socktimeo_t timeo) { return TRUE; } + return FALSE; } -- GitLab From fbb6cfc79c76f698f0b13963292928059b6dbd9f Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Fri, 31 Mar 2017 12:07:40 -1000 Subject: [PATCH 298/990] stm32f7:Serial fix for dropped data 1) Revert the inherited dma bug from the stm32 see https://bitbucket.org/nuttx/nuttx/commits/df9ae3c13fc2fff2c21ebdb098c520b11f43280d for details. 2) Most all CR1-CR3 settings can not be configured while UE is true. Threfore we make all operation atomic and disable UE and restore it's originalstate on exit. --- arch/arm/src/stm32f7/stm32_serial.c | 217 +++++++++------------------- 1 file changed, 66 insertions(+), 151 deletions(-) diff --git a/arch/arm/src/stm32f7/stm32_serial.c b/arch/arm/src/stm32f7/stm32_serial.c index 77138526dd..b839aad8f4 100644 --- a/arch/arm/src/stm32f7/stm32_serial.c +++ b/arch/arm/src/stm32f7/stm32_serial.c @@ -1,8 +1,9 @@ /**************************************************************************** * arch/arm/src/stm32f7/stm32_serial.c * - * Copyright (C) 2015-2016 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Copyright (C) 2015-2017 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * David Sidrane * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -189,16 +190,6 @@ CONFIG_USART_DMAPRIO | \ DMA_SCR_PBURST_SINGLE | \ DMA_SCR_MBURST_SINGLE) -# ifdef CONFIG_SERIAL_IFLOWCONTROL -# define SERIAL_DMA_IFLOW_CONTROL_WORD \ - (DMA_SCR_DIR_P2M | \ - DMA_SCR_MINC | \ - DMA_SCR_PSIZE_8BITS | \ - DMA_SCR_MSIZE_8BITS | \ - CONFIG_USART_DMAPRIO | \ - DMA_SCR_PBURST_SINGLE | \ - DMA_SCR_MBURST_SINGLE) -# endif #endif /* SERIAL_HAVE_DMA */ /* Power management definitions */ @@ -286,8 +277,7 @@ struct up_dev_s #ifdef SERIAL_HAVE_DMA DMA_HANDLE rxdma; /* currently-open receive DMA stream */ bool rxenable; /* DMA-based reception en/disable */ - uint16_t rxdmain; /* Next byte in the DMA where hardware will write */ - uint16_t rxdmaout; /* Next byte in the DMA buffer to be read */ + uint32_t rxdmanext; /* Next byte in the DMA buffer to be read */ char *const rxfifo; /* Receive DMA buffer */ #endif @@ -1139,7 +1129,22 @@ static void up_set_format(struct uart_dev_s *dev) uint32_t regval; uint32_t usartdiv8; uint32_t cr1; + uint32_t cr1_ue; uint32_t brr; + irqstate_t flags; + + flags = enter_critical_section(); + + /* Get the original state of UE */ + + cr1 = up_serialin(priv, STM32_USART_CR1_OFFSET); + cr1_ue = cr1 & USART_CR1_UE; + cr1 &= ~USART_CR1_UE; + + /* Disable UE as the format bits and baud rate registers can not be + * updated while UE = 1 */ + + up_serialout(priv, STM32_USART_CR1_OFFSET, cr1); /* In case of oversampling by 8, the equation is: * @@ -1159,7 +1164,6 @@ static void up_set_format(struct uart_dev_s *dev) /* Use oversamply by 8 only if the divisor is small. But what is small? */ - cr1 = up_serialin(priv, STM32_USART_CR1_OFFSET); if (usartdiv8 > 100) { /* Use usartdiv16 */ @@ -1188,30 +1192,44 @@ static void up_set_format(struct uart_dev_s *dev) /* Configure parity mode */ - regval = up_serialin(priv, STM32_USART_CR1_OFFSET); - regval &= ~(USART_CR1_PCE | USART_CR1_PS | USART_CR1_M0); + cr1 &= ~(USART_CR1_PCE | USART_CR1_PS | USART_CR1_M0 | USART_CR1_M1); if (priv->parity == 1) /* Odd parity */ { - regval |= (USART_CR1_PCE | USART_CR1_PS); + cr1 |= (USART_CR1_PCE | USART_CR1_PS); } else if (priv->parity == 2) /* Even parity */ { - regval |= USART_CR1_PCE; + cr1 |= USART_CR1_PCE; } - /* Configure word length (Default: 8-bits) */ + /* Configure word length (parity uses one of configured bits) + * + * Default: 1 start, 8 data (no parity), n stop, OR + * 1 start, 7 data + parity, n stop + */ - if (priv->bits == 7) + if (priv->bits == 9 || (priv->bits == 8 && priv->parity != 0)) { - regval |= USART_CR1_M1; + /* Select: 1 start, 8 data + parity, n stop, OR + * 1 start, 9 data (no parity), n stop. + */ + + cr1 |= USART_CR1_M0; } - else if (priv->bits == 9) + else if (priv->bits == 7 && priv->parity == 0) { - regval |= USART_CR1_M0; + /* Select: 1 start, 7 data (no parity), n stop, OR + */ + + cr1 |= USART_CR1_M1; } - up_serialout(priv, STM32_USART_CR1_OFFSET, regval); + /* Else Select: 1 start, 7 data + parity, n stop, OR + * 1 start, 8 data (no parity), n stop. + */ + + up_serialout(priv, STM32_USART_CR1_OFFSET, cr1); /* Configure STOP bits */ @@ -1230,7 +1248,8 @@ static void up_set_format(struct uart_dev_s *dev) regval = up_serialin(priv, STM32_USART_CR3_OFFSET); regval &= ~(USART_CR3_CTSE | USART_CR3_RTSE); -#if defined(CONFIG_SERIAL_IFLOWCONTROL) && !defined(CONFIG_STM32F7_FLOWCONTROL_BROKEN) +#if defined(CONFIG_SERIAL_IFLOWCONTROL) && \ + !defined(CONFIG_STM32F7_FLOWCONTROL_BROKEN) if (priv->iflow && (priv->rts_gpio != 0)) { regval |= USART_CR3_RTSE; @@ -1245,6 +1264,8 @@ static void up_set_format(struct uart_dev_s *dev) #endif up_serialout(priv, STM32_USART_CR3_OFFSET, regval); + up_serialout(priv, STM32_USART_CR1_OFFSET, cr1 | cr1_ue); + leave_critical_section(flags); } #endif /* CONFIG_SUPPRESS_UART_CONFIG */ @@ -1473,35 +1494,19 @@ static int up_dma_setup(struct uart_dev_s *dev) priv->rxdma = stm32_dmachannel(priv->rxdma_channel); -#ifdef CONFIG_SERIAL_IFLOWCONTROL - if (priv->iflow) - { - /* Configure for non-circular DMA reception into the RX FIFO */ + /* Configure for circular DMA reception into the RX FIFO */ - stm32_dmasetup(priv->rxdma, - priv->usartbase + STM32_USART_RDR_OFFSET, - (uint32_t)priv->rxfifo, - RXDMA_BUFFER_SIZE, - SERIAL_DMA_IFLOW_CONTROL_WORD); - } - else -#endif - { - /* Configure for circular DMA reception into the RX FIFO */ - - stm32_dmasetup(priv->rxdma, - priv->usartbase + STM32_USART_RDR_OFFSET, - (uint32_t)priv->rxfifo, - RXDMA_BUFFER_SIZE, - SERIAL_DMA_CONTROL_WORD); - } + stm32_dmasetup(priv->rxdma, + priv->usartbase + STM32_USART_RDR_OFFSET, + (uint32_t)priv->rxfifo, + RXDMA_BUFFER_SIZE, + SERIAL_DMA_CONTROL_WORD); /* Reset our DMA shadow pointer to match the address just * programmed above. */ - priv->rxdmaout = 0; - priv->rxdmain = 0; + priv->rxdmanext = 0; /* Enable receive DMA for the UART */ @@ -1509,26 +1514,12 @@ static int up_dma_setup(struct uart_dev_s *dev) regval |= USART_CR3_DMAR; up_serialout(priv, STM32_USART_CR3_OFFSET, regval); -#ifdef CONFIG_SERIAL_IFLOWCONTROL - if (priv->iflow) - { - /* Start the DMA channel, and arrange for callbacks at the full point - * in the FIFO. After buffer gets full, hardware flow-control kicks - * in and DMA transfer is stopped. - */ + /* Start the DMA channel, and arrange for callbacks at the half and + * full points in the FIFO. This ensures that we have half a FIFO + * worth of time to claim bytes before they are overwritten. + */ - stm32_dmastart(priv->rxdma, up_dma_rxcallback, (void *)priv, false); - } - else -#endif - { - /* Start the DMA channel, and arrange for callbacks at the half and - * full points in the FIFO. This ensures that we have half a FIFO - * worth of time to claim bytes before they are overwritten. - */ - - stm32_dmastart(priv->rxdma, up_dma_rxcallback, (void *)priv, true); - } + stm32_dmastart(priv->rxdma, up_dma_rxcallback, (void *)priv, true); return OK; } @@ -2226,49 +2217,27 @@ static bool up_rxflowcontrol(struct uart_dev_s *dev, static int up_dma_receive(struct uart_dev_s *dev, unsigned int *status) { struct up_dev_s *priv = (struct up_dev_s *)dev->priv; - uint32_t rxdmain; int c = 0; /* If additional bytes have been added to the DMA buffer, then we will need * to invalidate the DMA buffer before reading the byte. */ - rxdmain = up_dma_nextrx(priv); - if (rxdmain != priv->rxdmain) + if (up_dma_nextrx(priv) != priv->rxdmanext) { /* Invalidate the DMA buffer */ arch_invalidate_dcache((uintptr_t)priv->rxfifo, (uintptr_t)priv->rxfifo + RXDMA_BUFFER_SIZE - 1); - /* Since DMA is ongoing, there are lots of race conditions here. We - * just have to hope that the rxdmaout stays well ahead of rxdmain. - */ - - priv->rxdmain = rxdmain; - } + /* Now read from the DMA buffer */ - /* Now check if there are any bytes to read from the DMA buffer */ - - if (rxdmain != priv->rxdmaout) - { - c = priv->rxfifo[priv->rxdmaout]; + c = priv->rxfifo[priv->rxdmanext]; - priv->rxdmaout++; - if (priv->rxdmaout == RXDMA_BUFFER_SIZE) + priv->rxdmanext++; + if (priv->rxdmanext == RXDMA_BUFFER_SIZE) { -#ifdef CONFIG_SERIAL_IFLOWCONTROL - if (priv->iflow) - { - /* RX DMA buffer full. RX paused, RTS line pulled up to prevent - * more input data from other end. - */ - } - else -#endif - { - priv->rxdmaout = 0; - } + priv->rxdmanext = 0; } } @@ -2276,41 +2245,6 @@ static int up_dma_receive(struct uart_dev_s *dev, unsigned int *status) } #endif -/**************************************************************************** - * Name: up_dma_reenable - * - * Description: - * Call to re-enable RX DMA. - * - ****************************************************************************/ - -#if defined(SERIAL_HAVE_DMA) && defined(CONFIG_SERIAL_IFLOWCONTROL) -static void up_dma_reenable(struct up_dev_s *priv) -{ - /* Configure for non-circular DMA reception into the RX FIFO */ - - stm32_dmasetup(priv->rxdma, - priv->usartbase + STM32_USART_RDR_OFFSET, - (uint32_t)priv->rxfifo, - RXDMA_BUFFER_SIZE, - SERIAL_DMA_IFLOW_CONTROL_WORD); - - /* Reset our DMA shadow pointer to match the address just programmed - * above. - */ - - priv->rxdmaout = 0; - priv->rxdmain = 0; - - /* Start the DMA channel, and arrange for callbacks at the full point in - * the FIFO. After buffer gets full, hardware flow-control kicks in and - * DMA transfer is stopped. - */ - - stm32_dmastart(priv->rxdma, up_dma_rxcallback, (void *)priv, false); -} -#endif - /**************************************************************************** * Name: up_dma_rxint * @@ -2333,15 +2267,6 @@ static void up_dma_rxint(struct uart_dev_s *dev, bool enable) */ priv->rxenable = enable; - -#ifdef CONFIG_SERIAL_IFLOWCONTROL - if (priv->iflow && priv->rxenable && (priv->rxdmaout == RXDMA_BUFFER_SIZE)) - { - /* Re-enable RX DMA. */ - - up_dma_reenable(priv); - } -#endif } #endif @@ -2362,7 +2287,7 @@ static bool up_dma_rxavailable(struct uart_dev_s *dev) * do not match, then there are bytes to be received. */ - return (up_dma_nextrx(priv) != priv->rxdmaout); + return (up_dma_nextrx(priv) != priv->rxdmanext); } #endif @@ -2486,16 +2411,6 @@ static void up_dma_rxcallback(DMA_HANDLE handle, uint8_t status, void *arg) if (priv->rxenable && up_dma_rxavailable(&priv->dev)) { uart_recvchars(&priv->dev); - -#ifdef CONFIG_SERIAL_IFLOWCONTROL - if (priv->iflow && priv->rxenable && - (priv->rxdmaout == RXDMA_BUFFER_SIZE)) - { - /* Re-enable RX DMA. */ - - up_dma_reenable(priv); - } -#endif } } #endif -- GitLab From 97fa617c89811d16a0dd82d842f7d16a73508f52 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Fri, 31 Mar 2017 12:20:32 -1000 Subject: [PATCH 299/990] stm32f7:stm32_sdmmc removed stray semicolon --- arch/arm/src/stm32f7/stm32_sdmmc.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/arch/arm/src/stm32f7/stm32_sdmmc.c b/arch/arm/src/stm32f7/stm32_sdmmc.c index 2249dc87c3..9225312bd1 100644 --- a/arch/arm/src/stm32f7/stm32_sdmmc.c +++ b/arch/arm/src/stm32f7/stm32_sdmmc.c @@ -1510,7 +1510,7 @@ static int stm32_sdmmc_rdyinterrupt(int irq, void *context, void *arg) * ****************************************************************************/ -static int stm32_sdmmc_interrupt(int irq, void *context, void *arg); +static int stm32_sdmmc_interrupt(int irq, void *context, void *arg) { struct stm32_dev_s *priv =(struct stm32_dev_s *)arg; uint32_t enabled; -- GitLab From 52ead055fda1b20760b93797857ef8283f3624fb Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 1 Apr 2017 09:07:16 -0600 Subject: [PATCH 300/990] 6loWPAN: Beginning of IEEE802.15.4 frame input logic. --- drivers/net/skeleton.c | 2 +- include/nuttx/net/netdev.h | 3 +- include/nuttx/net/sixlowpan.h | 62 +++- net/sixlowpan/Make.defs | 4 +- net/sixlowpan/sixlowpan_framelist.c | 473 +++++++++++++++++++++++++++ net/sixlowpan/sixlowpan_framer.c | 6 +- net/sixlowpan/sixlowpan_hc06.c | 10 +- net/sixlowpan/sixlowpan_hc1.c | 8 +- net/sixlowpan/sixlowpan_input.c | 244 ++++++++++++-- net/sixlowpan/sixlowpan_internal.h | 53 ++- net/sixlowpan/sixlowpan_send.c | 479 ++-------------------------- net/sixlowpan/sixlowpan_tcpsend.c | 4 +- net/sixlowpan/sixlowpan_udpsend.c | 4 +- 13 files changed, 849 insertions(+), 503 deletions(-) create mode 100644 net/sixlowpan/sixlowpan_framelist.c diff --git a/drivers/net/skeleton.c b/drivers/net/skeleton.c index b33c46e6e0..d354ab8130 100644 --- a/drivers/net/skeleton.c +++ b/drivers/net/skeleton.c @@ -437,8 +437,8 @@ static void skel_receive(FAR struct skel_driver_s *priv) skel_transmit(priv); } } -#endif else +#endif { NETDEV_RXDROPPED(&priv->sk_dev); } diff --git a/include/nuttx/net/netdev.h b/include/nuttx/net/netdev.h index 72bddc067c..12b71840d7 100644 --- a/include/nuttx/net/netdev.h +++ b/include/nuttx/net/netdev.h @@ -419,7 +419,8 @@ int ipv6_input(FAR struct net_driver_s *dev); #endif #ifdef CONFIG_NET_6LOWPAN -int sixlowpan_input(FAR struct net_driver_s *dev); +struct ieee802154_driver_s; /* See sixlowpan.h */ +int sixlowpan_input(FAR struct ieee802154_driver_s *ieee); #endif /**************************************************************************** diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index db4bbd1d02..f31c453c43 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -260,7 +260,7 @@ */ -#define FRAME_IOB_EMPTY(ieee) ((ieee)->framelist == NULL) +#define FRAME_IOB_EMPTY(ieee) ((ieee)->i_framelist == NULL) #define FRAME_IOB_REMOVE(ieee, iob) \ do \ { \ @@ -369,6 +369,11 @@ struct rimeaddr_s * * The MAC driver should then inform the network of the by calling * sixlowpan_input(). + * + * Normally, the network will free the IOB and will nullify the frame + * list. But ss a complexity, the result of receiving a frame may be + * that the network may respond provide an outgoing frames in the + * frame list. */ struct ieee802154_driver_s @@ -458,6 +463,61 @@ struct sixlowpan_nhcompressor_s * Public Function Prototypes ****************************************************************************/ +/**************************************************************************** + * Name: sixlowpan_input + * + * Description: + * Process an incoming 6loWPAN frame. + * + * This function is called when the device driver has received a 6loWPAN + * frame from the network. The frame from the device driver must be + * provided in a IOB present in the i_framelist: The frame data is in the + * IOB io_data[] buffer and the length of the frame is in the IOB io_len + * field. Only a single IOB is expected in the i_framelist. This incoming + * data will be processed one frame at a time. + * + * An non-NULL d_buf of size CONFIG_NET_6LOWPAN_MTU must also be provided. + * The frame will be decompressed and placed in the d_buf. Fragmented + * packets will also be reassembled in the d_buf as they are received + * (meaning for the driver, that two packet buffers are required: One for + * reassembly of RX packets and one used for TX polling). + * + * After each frame is processed into d_buf, the IOB is removed and + * deallocated. i_framelist will be nullified. If reassembly is + * incomplete, this function will return to called with i_framelist + * equal to NULL. The partially reassembled packet must be preserved by + * the IEEE802.15.4 MAC and provided again when the next frame is + * received. + * + * When the packet in the d_buf is fully reassembled, it will be provided + * to the network as with any other received packet. d_len will be set + * the the length of the uncompressed, reassembled packet. + * + * After the network processes the packet, d_len will be set to zero. + * Network logic may also decide to send a response to the packet. In + * that case, the outgoing network packet will be placed in d_buf the + * d_buf and d_len will be set to a non-zero value. That case is handled + * by this function. + * + * If that case occurs, the packet will be converted to a list of + * compressed and possibly fragmented frames in i_framelist as with other + * TX operations. + * + * So from the standpoint of the IEEE802.15.4 MAC driver, there are two + * possible results: (1) i_framelist is NULL meaning that the frame + * was fully processed and freed, or (2) i_framelist is non-NULL meaning + * that there are outgoing frame(s) to be sent. + * + * Input Parameters: + * ieee - The IEEE802.15.4 MAC network driver interface. + * + * Returned Value: + * Ok is returned on success; Othewise a negated errno value is returned. + * + ****************************************************************************/ + +int sixlowpan_input(FAR struct ieee802154_driver_s *ieee); + /**************************************************************************** * Function: sixlowpan_set_compressor * diff --git a/net/sixlowpan/Make.defs b/net/sixlowpan/Make.defs index becc0a7edd..09fc742d39 100644 --- a/net/sixlowpan/Make.defs +++ b/net/sixlowpan/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # net/sixlowpan/Make.defs # -# Copyright (C) 2016 Gregory Nutt. All rights reserved. +# Copyright (C) 2017 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -41,7 +41,7 @@ ifeq ($(CONFIG_NET_6LOWPAN),y) NET_CSRCS += sixlowpan_initialize.c sixlowpan_globals.c sixlowpan_utils.c NET_CSRCS += sixlowpan_input.c sixlowpan_send.c sixlowpan_framer.c -NET_CSRCS += sixlowpan_compressor.c +NET_CSRCS += sixlowpan_framelist.c sixlowpan_compressor.c ifeq ($(CONFIG_NET_TCP),y) NET_CSRCS += sixlowpan_tcpsend.c diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c new file mode 100644 index 0000000000..35750b3ce7 --- /dev/null +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -0,0 +1,473 @@ +/**************************************************************************** + * net/sixlowpan/sixlowpan_framelist.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Parts of this file derive from Contiki: + * + * Copyright (c) 2008, Swedish Institute of Computer Science. + * All rights reserved. + * Authors: Adam Dunkels + * Nicolas Tsiftes + * Niclas Finne + * Mathilde Durvy + * Julien Abeille + * Joakim Eriksson + * Joel Hoglund + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the Institute 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 INSTITUTE 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 INSTITUTE 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 "sixlowpan/sixlowpan_internal.h" + +#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 + ****************************************************************************/ + +/**************************************************************************** + * Name: sixlowpan_compress_ipv6hdr + * + * Description: + * IPv6 dispatch "compression" function. Packets "Compression" when only + * IPv6 dispatch is used + * + * There is no compression in this case, all fields are sent + * inline. We just add the IPv6 dispatch byte before the packet. + * + * 0 1 2 3 + * 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + * | IPv6 Dsp | IPv6 header and payload ... + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + * + * Input Parameters: + * ieee - Pointer to IEEE802.15.4 MAC driver structure. + * ipv6 - Pointer to the IPv6 header to "compress" + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void sixlowpan_compress_ipv6hdr(FAR struct ieee802154_driver_s *ieee, + FAR const struct ipv6_hdr_s *ipv6) +{ + /* Indicate the IPv6 dispatch and length */ + + *g_rimeptr = SIXLOWPAN_DISPATCH_IPV6; + g_rime_hdrlen += SIXLOWPAN_IPV6_HDR_LEN; + + /* Copy the IPv6 header and adjust pointers */ + + memcpy(g_rimeptr + g_rime_hdrlen, ipv6, IPv6_HDRLEN); + g_rime_hdrlen += IPv6_HDRLEN; + g_uncomp_hdrlen += IPv6_HDRLEN; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: sixlowpan_queue_frames + * + * Description: + * Process an outgoing UDP or TCP packet. This function is called from + * send interrupt logic when a TX poll is received. It formates the + * list of frames to be sent by the IEEE802.15.4 MAC driver. + * + * The payload data is in the caller 's_buf' and is of length 's_len'. + * Compressed headers will be added and if necessary the packet is + * fragmented. The resulting packet/fragments are put in ieee->i_framelist + * and the entire list of frames will be delivered to the 802.15.4 MAC via + * ieee->i_framelist. + * + * Input Parameters: + * ieee - The IEEE802.15.4 MAC driver instance + * ipv6hdr - IPv6 header followed by TCP or UDP header. + * buf - Data to send + * len - Length of data to send + * destmac - The IEEE802.15.4 MAC address of the destination + * + * Returned Value: + * Ok is returned on success; Othewise a negated errno value is returned. + * This function is expected to fail if the driver is not an IEEE802.15.4 + * MAC network driver. In that case, the UDP/TCP will fall back to normal + * IPv4/IPv6 formatting. + * + * Assumptions: + * Called with the network locked. + * + ****************************************************************************/ + +int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, + FAR const struct ipv6_hdr_s *destip, + FAR const void *buf, size_t len, + FAR const struct rimeaddr_s *destmac) +{ + FAR struct iob_s *iob; + int framer_hdrlen; + struct rimeaddr_s dest; + uint16_t outlen = 0; + + /* Initialize global data. Locking the network guarantees that we have + * exclusive use of the global values for intermediate calculations. + */ + + FRAME_RESET(); + g_uncomp_hdrlen = 0; + g_rime_hdrlen = 0; + /* REVISIT: Do I need this rimeptr? */ + g_rimeptr = &ieee->i_dev.d_buf[PACKETBUF_HDR_SIZE]; + + /* Reset rime buffer, packet buffer metatadata */ + + memset(g_pktattrs, 0, PACKETBUF_NUM_ATTRS * sizeof(uint16_t)); + memset(g_pktaddrs, 0, PACKETBUF_NUM_ADDRS * sizeof(struct rimeaddr_s)); + + g_pktattrs[PACKETBUF_ATTR_MAX_MAC_TRANSMISSIONS] = + CONFIG_NET_6LOWPAN_MAX_MACTRANSMITS; + + /* Set stream mode for all TCP packets, except FIN packets. */ + + if (destip->proto == IP_PROTO_TCP) + { + FAR const struct tcp_hdr_s *tcp = + &((FAR const struct ipv6tcp_hdr_s *)destip)->tcp; + + if ((tcp->flags & TCP_FIN) == 0 && + (tcp->flags & TCP_CTL) != TCP_ACK) + { + g_pktattrs[PACKETBUF_ATTR_PACKET_TYPE] = PACKETBUF_ATTR_PACKET_TYPE_STREAM; + } + else if ((tcp->flags & TCP_FIN) == TCP_FIN) + { + g_pktattrs[PACKETBUF_ATTR_PACKET_TYPE] = PACKETBUF_ATTR_PACKET_TYPE_STREAM_END; + } + } + + /* The destination address will be tagged to each outbound packet. If the + * argument destmac is NULL, we are sending a broadcast packet. + */ + + if (destmac == NULL) + { + memset(&dest, 0, sizeof(struct rimeaddr_s)); + } + else + { + rimeaddr_copy(&dest, (FAR const struct rimeaddr_s *)destmac); + } + + ninfo("Sending packet len %d\n", len); + +#ifndef CONFIG_NET_6LOWPAN_COMPRESSION_IPv6 + if (len >= CONFIG_NET_6LOWPAN_COMPRESSION_THRESHOLD) + { + /* Try to compress the headers */ + +#if defined(CONFIG_NET_6LOWPAN_COMPRESSION_HC1) + sixlowpan_compresshdr_hc1(ieee, &dest); +#elif defined(CONFIG_NET_6LOWPAN_COMPRESSION_HC06) + sixlowpan_compresshdr_hc06(ieee, &dest); +#else +# error No compression specified +#endif + } + else +#endif /* !CONFIG_NET_6LOWPAN_COMPRESSION_IPv6 */ + { + /* Small.. use IPv6 dispatch (no compression) */ + + sixlowpan_compress_ipv6hdr(ieee, destip); + } + + ninfo("Header of len %d\n", g_rime_hdrlen); + + rimeaddr_copy(&g_pktaddrs[PACKETBUF_ADDR_RECEIVER], &dest); + + /* Pre-calculate frame header length. */ + + framer_hdrlen = sixlowpan_hdrlen(ieee, ieee->i_panid); + if (framer_hdrlen < 0) + { + /* Failed to determine the size of the header failed. */ + + nerr("ERROR: sixlowpan_hdrlen() failed: %d\n", framer_hdrlen); + return framer_hdrlen; + } + + /* Check if we need to fragment the packet into several frames */ + + if ((int)len - (int)g_uncomp_hdrlen > + (int)CONFIG_NET_6LOWPAN_MAXPAYLOAD - framer_hdrlen - + (int)g_rime_hdrlen) + { +#if CONFIG_NET_6LOWPAN_FRAG + /* ieee->i_framelist will hold the generated frames; frames will be + * added at qtail. + */ + + FAR struct iob_s *qtail; + int verify; + + /* 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 + * IPv6/HC1/HC06/HC_UDP dispatchs/headers. + * The following fragments contain only the fragn dispatch. + */ + + 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); + + /* Initialize the IOB */ + + iob->io_flink = NULL; + iob->io_len = 0; + iob->io_offset = 0; + iob->io_pktlen = 0; + + /* Create 1st Fragment */ + /* Add the frame header */ + + verify = sixlowpan_framecreate(ieee, iob, ieee->i_panid); + DEBUGASSERT(verify == framer_hdrlen); + UNUSED(verify); + + /* Move HC1/HC06/IPv6 header */ + + memmove(g_rimeptr + SIXLOWPAN_FRAG1_HDR_LEN, g_rimeptr, g_rime_hdrlen); + + /* Setup up the fragment header. + * + * The fragment header contains three fields: Datagram size, datagram + * tag and datagram offset: + * + * 1. Datagram size describes the total (un-fragmented) payload. + * 2. Datagram tag identifies the set of fragments and is used to + * match fragments of the same payload. + * 3. Datagram offset identifies the fragment’s offset within the un- + * fragmented payload. + * + * The fragment header length is 4 bytes for the first header and 5 + * bytes for all subsequent headers. + */ + + PUTINT16(RIME_FRAG_PTR, RIME_FRAG_DISPATCH_SIZE, + ((SIXLOWPAN_DISPATCH_FRAG1 << 8) | len)); + PUTINT16(RIME_FRAG_PTR, RIME_FRAG_TAG, ieee->i_dgramtag); + ieee->i_dgramtag++; + + /* Copy payload and enqueue */ + + g_rime_hdrlen += SIXLOWPAN_FRAG1_HDR_LEN; + g_rime_payloadlen = + (CONFIG_NET_6LOWPAN_MAXPAYLOAD - framer_hdrlen - g_rime_hdrlen) & 0xf8; + + memcpy(g_rimeptr + g_rime_hdrlen, + (FAR uint8_t *)destip + g_uncomp_hdrlen, g_rime_payloadlen); + iob->io_len += g_rime_payloadlen + g_rime_hdrlen; + + /* Set outlen to what we already sent from the IP payload */ + + outlen = g_rime_payloadlen + g_uncomp_hdrlen; + + ninfo("First fragment: len %d, tag %d\n", + g_rime_payloadlen, ieee->i_dgramtag); + + /* Add the first frame to the IOB queue */ + + ieee->i_framelist = iob; + qtail = iob; + + /* Keep track of the total amount of data queue */ + + iob->io_pktlen = iob->io_len; + + /* Create following fragments */ + + g_rime_hdrlen = SIXLOWPAN_FRAGN_HDR_LEN; + + while (outlen < len) + { + /* Allocate an IOB to hold the next fragment, waiting if + * necessary. + */ + + iob = iob_alloc(false); + DEBUGASSERT(iob != NULL); + + /* Initialize the IOB */ + + iob->io_flink = NULL; + iob->io_len = 0; + iob->io_offset = 0; + iob->io_pktlen = 0; + + /* Add the frame header */ + + verify = sixlowpan_framecreate(ieee, iob, ieee->i_panid); + DEBUGASSERT(vreify == framer_hdrlen); + UNUSED(verify); + + /* Move HC1/HC06/IPv6 header */ + + memmove(g_rimeptr + SIXLOWPAN_FRAGN_HDR_LEN, g_rimeptr, g_rime_hdrlen); + + /* Setup up the fragment header */ + + PUTINT16(RIME_FRAG_PTR, RIME_FRAG_DISPATCH_SIZE, + ((SIXLOWPAN_DISPATCH_FRAGN << 8) | len)); + PUTINT16(RIME_FRAG_PTR, RIME_FRAG_TAG, ieee->i_dgramtag); + RIME_FRAG_PTR[RIME_FRAG_OFFSET] = outlen >> 3; + + /* Copy payload and enqueue */ + + if (len - outlen < g_rime_payloadlen) + { + /* Last fragment */ + + g_rime_payloadlen = len - outlen; + } + else + { + g_rime_payloadlen = + (CONFIG_NET_6LOWPAN_MAXPAYLOAD - framer_hdrlen - g_rime_hdrlen) & 0xf8; + } + + memcpy(g_rimeptr + g_rime_hdrlen, (FAR uint8_t *)destip + outlen, + g_rime_payloadlen); + iob->io_len = g_rime_payloadlen + g_rime_hdrlen; + + /* Set outlen to what we already sent from the IP payload */ + + outlen += (g_rime_payloadlen + g_uncomp_hdrlen); + + ninfo("sixlowpan output: fragment offset %d, len %d, tag %d\n", + outlen >> 3, g_rime_payloadlen, ieee->i_dgramtag); + + /* Add the next frame to the tail of the IOB queue */ + + qtail->io_flink = iob; + + /* Keep track of the total amount of data queue */ + + ieee->i_framelist->io_pktlen += iob->io_len; + } +#else + nerr("ERROR: Packet too large: %d\n", len); + nerr(" Cannot to be sent without fragmentation support\n"); + nerr(" dropping packet\n"); + + return -E2BIG; +#endif + } + else + { + int verify; + + /* The packet does not need to be fragmented just copy the "payload" + * and send in one frame. + */ + + /* Allocate an IOB to hold the frame, waiting if necessary. */ + + iob = iob_alloc(false); + DEBUGASSERT(iob != NULL); + + /* Initialize the IOB */ + + iob->io_flink = NULL; + iob->io_len = 0; + iob->io_offset = 0; + iob->io_pktlen = 0; + + /* Add the frame header */ + + verify = sixlowpan_framecreate(ieee, iob, ieee->i_panid); + DEBUGASSERT(vreify == framer_hdrlen); + UNUSED(verify); + + /* Copy the payload and queue */ + + memcpy(g_rimeptr + g_rime_hdrlen, (FAR uint8_t *)destip + g_uncomp_hdrlen, + len - g_uncomp_hdrlen); + iob->io_len = len - g_uncomp_hdrlen + g_rime_hdrlen; + + /* Add the first frame to the IOB queue */ + + ieee->i_framelist = iob; + + /* Keep track of the total amount of data queue */ + + iob->io_pktlen = iob->io_len; + } + + return OK; +} + +#endif /* CONFIG_NET_6LOWPAN */ diff --git a/net/sixlowpan/sixlowpan_framer.c b/net/sixlowpan/sixlowpan_framer.c index ab5fc06fe3..d0efa291d4 100644 --- a/net/sixlowpan/sixlowpan_framer.c +++ b/net/sixlowpan/sixlowpan_framer.c @@ -518,8 +518,10 @@ int sixlowpan_802154_framecreate(FAR struct frame802154_s *finfo, * Function: sixlowpan_framecreate * * Description: - * This function is called after the IEEE802.15.4 MAC driver polls for - * TX data. It creates the IEEE802.15.4 header in the frame buffer. + * This function is called after eiether (1) the IEEE802.15.4 MAC driver + * polls for TX data or (2) after the IEEE802.15.4 MAC driver provides an + * in frame and the network responds with an outgoing packet. It creates + * the IEEE802.15.4 header in the frame buffer. * * Input parameters: * ieee - A reference IEEE802.15.4 MAC network device structure. diff --git a/net/sixlowpan/sixlowpan_hc06.c b/net/sixlowpan/sixlowpan_hc06.c index e8d0cf3d89..e0ca657c03 100644 --- a/net/sixlowpan/sixlowpan_hc06.c +++ b/net/sixlowpan/sixlowpan_hc06.c @@ -168,7 +168,7 @@ void sixlowpan_hc06_initialize(void) } /**************************************************************************** - * Name: sixlowpan_hc06_initialize + * Name: sixlowpan_compresshdr_hc06 * * Description: * Compress IP/UDP header @@ -202,7 +202,7 @@ void sixlowpan_hc06_initialize(void) * compress the IID. * * Input Parameters: - * dev - A reference to the IEE802.15.4 network device state + * ieee - A reference to the IEE802.15.4 network device state * destaddr - L2 destination address, needed to compress IP dest * * Returned Value: @@ -210,7 +210,7 @@ void sixlowpan_hc06_initialize(void) * ****************************************************************************/ -void sixlowpan_compresshdr_hc06(FAR struct net_driver_s *dev, +void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, FAR struct rimeaddr_s *destaddr) { /* REVISIT: To be provided */ @@ -230,7 +230,7 @@ void sixlowpan_compresshdr_hc06(FAR struct net_driver_s *dev, * appropriate values * * Input Parmeters: - * dev - A reference to the IEE802.15.4 network device state + * ieee - A reference to the IEE802.15.4 network device state * iplen - Equal to 0 if the packet is not a fragment (IP length is then * inferred from the L2 length), non 0 if the packet is a 1st * fragment. @@ -240,7 +240,7 @@ void sixlowpan_compresshdr_hc06(FAR struct net_driver_s *dev, * ****************************************************************************/ -void sixlowpan_uncompresshdr_hc06(FAR struct net_driver_s *dev, +void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, uint16_t iplen) { /* REVISIT: To be provided */ diff --git a/net/sixlowpan/sixlowpan_hc1.c b/net/sixlowpan/sixlowpan_hc1.c index 245a7465c2..268f0bad3e 100644 --- a/net/sixlowpan/sixlowpan_hc1.c +++ b/net/sixlowpan/sixlowpan_hc1.c @@ -102,7 +102,7 @@ * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ * * Input Parmeters: - * dev - A reference to the IEE802.15.4 network device state + * ieee - A reference to the IEE802.15.4 network device state * destaddr - L2 destination address, needed to compress the IP * destination field * @@ -111,7 +111,7 @@ * ****************************************************************************/ -void sixlowpan_compresshdr_hc1(FAR struct net_driver_s *dev, +void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, FAR struct rimeaddr_s *destaddr) { /* REVISIT: To be provided */ @@ -130,7 +130,7 @@ void sixlowpan_compresshdr_hc1(FAR struct net_driver_s *dev, * are set to the appropriate values * * Input Parameters: - * dev - A reference to the IEE802.15.4 network device state + * ieee - A reference to the IEE802.15.4 network device state * iplen - Equal to 0 if the packet is not a fragment (IP length is then * inferred from the L2 length), non 0 if the packet is a 1st * fragment. @@ -140,7 +140,7 @@ void sixlowpan_compresshdr_hc1(FAR struct net_driver_s *dev, * ****************************************************************************/ -void sixlowpan_uncompresshdr_hc1(FAR struct net_driver_s *dev, +void sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, uint16_t iplen) { /* REVISIT: To be provided */ diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index 466069f2d5..151d205f85 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -1,35 +1,45 @@ /**************************************************************************** * net/sixlowpan/sixlowpan_input.c + * 6lowpan implementation (RFC4944 and draft-ietf-6lowpan-hc-06) * - * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Copyright (C) 2017, Gregory Nutt, all rights reserved * Author: Gregory Nutt * + * Derives in large part from Contiki: + * + * Copyright (c) 2008, Swedish Institute of Computer Science. + * All rights reserved. + * Authors: Adam Dunkels + * Nicolas Tsiftes + * Niclas Finne + * Mathilde Durvy + * Julien Abeille + * Joakim Eriksson + * Joel Hoglund + * * 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 + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the Institute 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. + * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE 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 INSTITUTE 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. * ****************************************************************************/ @@ -39,13 +49,31 @@ #include +#include #include +#include #include "nuttx/net/netdev.h" +#include "nuttx/net/ip.h" +#include "nuttx/net/sixlowpan.h" + +#ifdef CONFIG_NET_PKT +# include "pkt/pkt.h" +#endif + #include "sixlowpan/sixlowpan_internal.h" #ifdef CONFIG_NET_6LOWPAN +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Success return values from sixlowpan_frame_process */ + +#define INPUT_PARTIAL 0 /* Frame processed successful, packet incomplete */ +#define INPUT_COMPLETE 1 /* Frame processed successful, packet complete */ + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -135,6 +163,73 @@ static void sixlowpan_set_pktattrs(FAR struct ieee802154_driver_s *ieee, g_pktattrs[PACKETBUF_ATTR_CHANNEL] = attr; } +/**************************************************************************** + * Name: sixlowpan_frame_process + * + * Description: + * Process an incoming 6loWPAN frame in 'iob'. + * + * If its a FRAG1 or a non-fragmented frame we first uncompress the IP + * header. The 6loWPAN payload and possibly the uncompressed IP header + * are then copied into d_buf. An indication is returned if the packet + * in d_buf is complete (i.e., non-fragmented frame or and the last + * FRAGN frame). + * + * NOTE: We do not check for overlapping sixlowpan fragments (that is a + * SHALL in the RFC 4944 and should never happen) + * + * Input Parameters: + * ieee - The IEEE802.15.4 MAC network driver interface. + * iob - The IOB containing the frame. + * + * Returned Value: + * Ok is returned on success; Othewise a negated errno value is returned. + * + ****************************************************************************/ + +static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, + FAR struct iob_s *iob) +{ + /* REVISIT: To be provided */ + return -ENOSYS; +} + +/**************************************************************************** + * Function: sixlowpan_dispatch + * + * Description: + * Inject the packet in d_buf into the network for normal packet processing. + * + * Parameters: + * ieee - The IEEE802.15.4 MAC network driver interface. + * + * Returned Value: + * None + * + ****************************************************************************/ + +static int sixlowpan_dispatch(FAR struct ieee802154_driver_s *ieee) +{ +#ifdef CONFIG_NET_PKT + /* When packet sockets are enabled, feed the frame into the packet tap */ + + ninfo("Packet tap\n"); + pkt_input(&ieee->i_dev); +#endif + + /* We only accept IPv6 packets. */ + + ninfo("Iv6 packet dispatch\n"); + NETDEV_RXIPV6(&ieee->i_dev); + + /* Give the IPv6 packet to the network layer. NOTE: If there is a + * problem with IPv6 header, it will be silently dropped and d_len will + * be set to zero. Oddly, ipv6_input() will return OK in this case. + */ + + return ipv6_input(&ieee->i_dev); +} + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -143,30 +238,117 @@ static void sixlowpan_set_pktattrs(FAR struct ieee802154_driver_s *ieee, * Name: sixlowpan_input * * Description: - * Process an incoming IP packet. + * Process an incoming 6loWPAN frame. * * This function is called when the device driver has received a 6loWPAN - * packet from the network. The packet from the device driver must be - * present in the d_buf buffer, and the length of the packet should be - * placed in the d_len field. + * frame from the network. The frame from the device driver must be + * provided in a IOB present in the i_framelist: The frame data is in the + * IOB io_data[] buffer and the length of the frame is in the IOB io_len + * field. Only a single IOB is expected in the i_framelist. This incoming + * data will be processed one frame at a time. + * + * An non-NULL d_buf of size CONFIG_NET_6LOWPAN_MTU must also be provided. + * The frame will be decompressed and placed in the d_buf. Fragmented + * packets will also be reassembled in the d_buf as they are received + * (meaning for the driver, that two packet buffers are required: One for + * reassembly of RX packets and one used for TX polling). * - * When the function returns, there may be an outbound packet placed - * in the d_buf packet buffer. If so, the d_len field is set to - * the length of the packet. If no packet is to be sent out, the - * d_len field is set to 0. + * After each frame is processed into d_buf, the IOB is removed and + * deallocated. i_framelist will be nullified. If reassembly is + * incomplete, this function will return to called with i_framelist + * equal to NULL. The partially reassembled packet must be preserved by + * the IEEE802.15.4 MAC and provided again when the next frame is + * received. + * + * When the packet in the d_buf is fully reassembled, it will be provided + * to the network as with any other received packet. d_len will be set + * the the length of the uncompressed, reassembled packet. + * + * After the network processes the packet, d_len will be set to zero. + * Network logic may also decide to send a response to the packet. In + * that case, the outgoing network packet will be placed in d_buf the + * d_buf and d_len will be set to a non-zero value. That case is handled + * by this function. + * + * If that case occurs, the packet will be converted to a list of + * compressed and possibly fragmented frames in i_framelist as with other + * TX operations. + * + * So from the standpoint of the IEEE802.15.4 MAC driver, there are two + * possible results: (1) i_framelist is NULL meaning that the frame + * was fully processed and freed, or (2) i_framelist is non-NULL meaning + * that there are outgoing frame(s) to be sent. * * Input Parameters: - * dev - The IEEE802.15.4 MAC network driver interface. + * ieee - The IEEE802.15.4 MAC network driver interface. * * Returned Value: * Ok is returned on success; Othewise a negated errno value is returned. * ****************************************************************************/ -int sixlowpan_input(FAR struct net_driver_s *dev) +int sixlowpan_input(FAR struct ieee802154_driver_s *ieee) { - /* REVISIT: To be provided */ - return -ENOSYS; + int ret = -EINVAL; + + DEBUGASSERT(ieee != NULL && !FRAME_IOB_EMPTY(ieee)); + + /* Verify that an IOB is provided in the device structure */ + + while (!FRAME_IOB_EMPTY(ieee)) + { + FAR struct iob_s *iob; + + /* Remove the IOB containing the frame from the device structure */ + + FRAME_IOB_REMOVE(ieee, iob); + DEBUGASSERT(iob != NULL); + + /* Process the frame, decompressing it into the packet buffer */ + + ret = sixlowpan_frame_process(ieee, iob); + + /* Was the frame successfully processed? Is the packet in d_buf fully + * reassembled? + */ + + if (ret == INPUT_COMPLETE) + { + /* Inject the uncompressed, reassembled packet into the network */ + + ret = sixlowpan_dispatch(ieee); + if (ret >= 0) + { + /* Check if this resulted in a request to send an outgoing + * packet. + */ + + if (ieee->i_dev.d_len > 0) + { + FAR struct ipv6_hdr_s *ipv6hdr; + struct rimeaddr_s destmac; + + /* The IPv6 header followed by TCP or UDP headers should + * lie at the beginning of d_buf since there is no link + * layer protocol header. + */ + + ipv6hdr = (FAR struct ipv6_hdr_s *)(ieee->i_dev.d_buf); + + /* Get the Rime MAC address of the destination */ +#warning Missing logic + + /* Convert the outgoing packet into a frame list. */ + + ret = sixlowpan_queue_frames(ieee, ipv6hdr, ieee->i_dev.d_buf, + ieee->i_dev.d_len, &destmac); + ieee->i_dev.d_len = 0; + } + } + } + } + + return ret; } #endif /* CONFIG_NET_6LOWPAN */ diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index d96c4213b7..644880398f 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -481,6 +481,43 @@ int sixlowpan_hdrlen(FAR struct ieee802154_driver_s *ieee, int sixlowpan_framecreate(FAR struct ieee802154_driver_s *ieee, FAR struct iob_s *iob, uint16_t dest_panid); +/**************************************************************************** + * Name: sixlowpan_queue_frames + * + * Description: + * Process an outgoing UDP or TCP packet. This function is called from + * send interrupt logic when a TX poll is received. It formates the + * list of frames to be sent by the IEEE802.15.4 MAC driver. + * + * The payload data is in the caller 's_buf' and is of length 's_len'. + * Compressed headers will be added and if necessary the packet is + * fragmented. The resulting packet/fragments are put in ieee->i_framelist + * and the entire list of frames will be delivered to the 802.15.4 MAC via + * ieee->i_framelist. + * + * Input Parameters: + * ieee - The IEEE802.15.4 MAC driver instance + * ipv6hdr - IPv6 header followed by TCP or UDP header. + * buf - Data to send + * len - Length of data to send + * destmac - The IEEE802.15.4 MAC address of the destination + * + * Returned Value: + * Ok is returned on success; Othewise a negated errno value is returned. + * This function is expected to fail if the driver is not an IEEE802.15.4 + * MAC network driver. In that case, the UDP/TCP will fall back to normal + * IPv4/IPv6 formatting. + * + * Assumptions: + * Called with the network locked. + * + ****************************************************************************/ + +int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, + FAR const struct ipv6_hdr_s *ipv6hdr, + FAR const void *buf, size_t len, + FAR const struct rimeaddr_s *destmac); + /**************************************************************************** * Name: sixlowpan_hc06_initialize * @@ -521,7 +558,7 @@ void sixlowpan_hc06_initialize(void); * compression * * Input Parameters: - * dev - A reference to the IEE802.15.4 network device state + * ieee - A reference to the IEE802.15.4 network device state * destaddr - L2 destination address, needed to compress IP dest * * Returned Value: @@ -530,7 +567,7 @@ void sixlowpan_hc06_initialize(void); ****************************************************************************/ #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 -void sixlowpan_compresshdr_hc06(FAR struct net_driver_s *dev, +void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *dev, FAR struct rimeaddr_s *destaddr); #endif @@ -548,7 +585,7 @@ void sixlowpan_compresshdr_hc06(FAR struct net_driver_s *dev, * appropriate values * * Input Parmeters: - * dev - A reference to the IEE802.15.4 network device state + * ieee - A reference to the IEE802.15.4 network device state * iplen - Equal to 0 if the packet is not a fragment (IP length is then * inferred from the L2 length), non 0 if the packet is a 1st * fragment. @@ -559,7 +596,7 @@ void sixlowpan_compresshdr_hc06(FAR struct net_driver_s *dev, ****************************************************************************/ #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 -void sixlowpan_uncompresshdr_hc06(FAR struct net_driver_s *dev, +void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, uint16_t iplen); #endif @@ -574,7 +611,7 @@ void sixlowpan_uncompresshdr_hc06(FAR struct net_driver_s *dev, * uip_buf buffer. * * Input Parmeters: - * dev - A reference to the IEE802.15.4 network device state + * ieee - A reference to the IEE802.15.4 network device state * destaddr - L2 destination address, needed to compress the IP * destination field * @@ -584,7 +621,7 @@ void sixlowpan_uncompresshdr_hc06(FAR struct net_driver_s *dev, ****************************************************************************/ #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC1 -void sixlowpan_compresshdr_hc1(FAR struct net_driver_s *dev, +void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, FAR struct rimeaddr_s *destaddr); #endif @@ -601,7 +638,7 @@ void sixlowpan_compresshdr_hc1(FAR struct net_driver_s *dev, * are set to the appropriate values * * Input Parameters: - * dev - A reference to the IEE802.15.4 network device state + * ieee - A reference to the IEE802.15.4 network device state * iplen - Equal to 0 if the packet is not a fragment (IP length is then * inferred from the L2 length), non 0 if the packet is a 1st * fragment. @@ -612,7 +649,7 @@ void sixlowpan_compresshdr_hc1(FAR struct net_driver_s *dev, ****************************************************************************/ #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC1 -void sixlowpan_uncompresshdr_hc1(FAR struct net_driver_s *dev, +void sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, uint16_t ip_len); #endif diff --git a/net/sixlowpan/sixlowpan_send.c b/net/sixlowpan/sixlowpan_send.c index 12420a2574..cff92eecee 100644 --- a/net/sixlowpan/sixlowpan_send.c +++ b/net/sixlowpan/sixlowpan_send.c @@ -4,18 +4,6 @@ * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * - * Parts of this file derive from Contiki: - * - * Copyright (c) 2008, Swedish Institute of Computer Science. - * All rights reserved. - * Authors: Adam Dunkels - * Nicolas Tsiftes - * Niclas Finne - * Mathilde Durvy - * Julien Abeille - * Joakim Eriksson - * Joel Hoglund - * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: @@ -23,23 +11,25 @@ * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in the - * documentation and/or other materials provided with the distribution. - * 3. Neither the name of the Institute nor the names of its contributors - * may be used to endorse or promote products derived from this software + * 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 INSTITUTE 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 INSTITUTE 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. + * 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. * ****************************************************************************/ @@ -49,46 +39,21 @@ #include -#include -#include +#include #include #include -#include "nuttx/semaphore.h" -#include "nuttx/net/net.h" -#include "nuttx/net/netdev.h" -#include "nuttx/net/iob.h" -#include "nuttx/net/ip.h" +#include +#include +#include -#include "iob/iob.h" #include "netdev/netdev.h" #include "devif/devif.h" -#include "tcp/tcp.h" -#include "udp/udp.h" + #include "sixlowpan/sixlowpan_internal.h" #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 Types ****************************************************************************/ @@ -105,7 +70,7 @@ struct sixlowpan_send_s int s_result; /* The result of the transfer */ uint16_t s_timeout; /* Send timeout in deciseconds */ systime_t s_time; /* Last send time for determining timeout */ - FAR const struct ipv6_hdr_s *s_destip; /* Destination IP address */ + FAR const struct ipv6_hdr_s *s_ipv6hdr; /* IPv6 header, followed by UDP or TCP header. */ FAR const struct rimeaddr_s *s_destmac; /* Destination MAC address */ FAR const void *s_buf; /* Data to send */ size_t s_len; /* Length of data in buf */ @@ -115,384 +80,6 @@ struct sixlowpan_send_s * Private Functions ****************************************************************************/ -/**************************************************************************** - * Name: sixlowpan_compress_ipv6hdr - * - * Description: - * IPv6 dispatch "compression" function. Packets "Compression" when only - * IPv6 dispatch is used - * - * There is no compression in this case, all fields are sent - * inline. We just add the IPv6 dispatch byte before the packet. - * - * 0 1 2 3 - * 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 - * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ - * | IPv6 Dsp | IPv6 header and payload ... - * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ - * - * Input Parameters: - * ieee - Pointer to IEEE802.15.4 MAC driver structure. - * ipv6 - Pointer to the IPv6 header to "compress" - * - * Returned Value: - * None - * - ****************************************************************************/ - -static void sixlowpan_compress_ipv6hdr(FAR struct ieee802154_driver_s *ieee, - FAR const struct ipv6_hdr_s *ipv6) -{ - /* Indicate the IPv6 dispatch and length */ - - *g_rimeptr = SIXLOWPAN_DISPATCH_IPV6; - g_rime_hdrlen += SIXLOWPAN_IPV6_HDR_LEN; - - /* Copy the IPv6 header and adjust pointers */ - - memcpy(g_rimeptr + g_rime_hdrlen, ipv6, IPv6_HDRLEN); - g_rime_hdrlen += IPv6_HDRLEN; - g_uncomp_hdrlen += IPv6_HDRLEN; -} - -/**************************************************************************** - * Name: sixlowpan_queue_frames - * - * Description: - * Process an outgoing UDP or TCP packet. This function is called from - * send interrupt logic when a TX poll is received. It formates the - * list of frames to be sent by the IEEE802.15.4 MAC driver. - * - * The payload data is in the caller 's_buf' and is of length 's_len'. - * Compressed headers will be added and if necessary the packet is - * fragmented. The resulting packet/fragments are put in ieee->i_framelist - * and the entire list of frames will be delivered to the 802.15.4 MAC via - * ieee->i_framelist. - * - * Input Parameters: - * dev - The structure of the network driver that caused the interrupt - * sinfo - Send state information - * - * Returned Value: - * Ok is returned on success; Othewise a negated errno value is returned. - * This function is expected to fail if the driver is not an IEEE802.15.4 - * MAC network driver. In that case, the UDP/TCP will fall back to normal - * IPv4/IPv6 formatting. - * - * Assumptions: - * Called with the network locked. - * - ****************************************************************************/ - -int sixlowpan_queue_frames(FAR struct net_driver_s *dev, - FAR struct sixlowpan_send_s *sinfo) -{ - FAR struct ieee802154_driver_s *ieee = (FAR struct ieee802154_driver_s *)dev; - FAR struct iob_s *iob; - int framer_hdrlen; - struct rimeaddr_s dest; - uint16_t outlen = 0; - - /* Initialize global data. Locking the network guarantees that we have - * exclusive use of the global values for intermediate calculations. - */ - - FRAME_RESET(); - g_uncomp_hdrlen = 0; - g_rime_hdrlen = 0; - /* REVISIT: Do I need this rimeptr? */ - g_rimeptr = &dev->d_buf[PACKETBUF_HDR_SIZE]; - - /* Reset rime buffer, packet buffer metatadata */ - - memset(g_pktattrs, 0, PACKETBUF_NUM_ATTRS * sizeof(uint16_t)); - memset(g_pktaddrs, 0, PACKETBUF_NUM_ADDRS * sizeof(struct rimeaddr_s)); - - g_pktattrs[PACKETBUF_ATTR_MAX_MAC_TRANSMISSIONS] = - CONFIG_NET_6LOWPAN_MAX_MACTRANSMITS; - - /* Set stream mode for all TCP packets, except FIN packets. */ - - if (sinfo->s_destip->proto == IP_PROTO_TCP) - { - FAR const struct tcp_hdr_s *tcp = &((FAR const struct ipv6tcp_hdr_s *)sinfo->s_destip)->tcp; - - if ((tcp->flags & TCP_FIN) == 0 && - (tcp->flags & TCP_CTL) != TCP_ACK) - { - g_pktattrs[PACKETBUF_ATTR_PACKET_TYPE] = PACKETBUF_ATTR_PACKET_TYPE_STREAM; - } - else if ((tcp->flags & TCP_FIN) == TCP_FIN) - { - g_pktattrs[PACKETBUF_ATTR_PACKET_TYPE] = PACKETBUF_ATTR_PACKET_TYPE_STREAM_END; - } - } - - /* The destination address will be tagged to each outbound packet. If the - * argument destmac is NULL, we are sending a broadcast packet. - */ - - if (sinfo->s_destmac == NULL) - { - memset(&dest, 0, sizeof(struct rimeaddr_s)); - } - else - { - rimeaddr_copy(&dest, (FAR const struct rimeaddr_s *)sinfo->s_destmac); - } - - ninfo("Sending packet len %d\n", sinfo->s_len); - -#ifndef CONFIG_NET_6LOWPAN_COMPRESSION_IPv6 - if (sinfo->s_len >= CONFIG_NET_6LOWPAN_COMPRESSION_THRESHOLD) - { - /* Try to compress the headers */ - -#if defined(CONFIG_NET_6LOWPAN_COMPRESSION_HC1) - sixlowpan_compresshdr_hc1(dev, &dest); -#elif defined(CONFIG_NET_6LOWPAN_COMPRESSION_HC06) - sixlowpan_compresshdr_hc06(dev, &dest); -#else -# error No compression specified -#endif - } - else -#endif /* !CONFIG_NET_6LOWPAN_COMPRESSION_IPv6 */ - { - /* Small.. use IPv6 dispatch (no compression) */ - - sixlowpan_compress_ipv6hdr(ieee, sinfo->s_destip); - } - - ninfo("Header of len %d\n", g_rime_hdrlen); - - rimeaddr_copy(&g_pktaddrs[PACKETBUF_ADDR_RECEIVER], &dest); - - /* Pre-calculate frame header length. */ - - framer_hdrlen = sixlowpan_hdrlen(ieee, ieee->i_panid); - if (framer_hdrlen < 0) - { - /* Failed to determine the size of the header failed. */ - - nerr("ERROR: sixlowpan_hdrlen() failed: %d\n", framer_hdrlen); - return framer_hdrlen; - } - - /* Check if we need to fragment the packet into several frames */ - - if ((int)sinfo->s_len - (int)g_uncomp_hdrlen > - (int)CONFIG_NET_6LOWPAN_MAXPAYLOAD - framer_hdrlen - - (int)g_rime_hdrlen) - { -#if CONFIG_NET_6LOWPAN_FRAG - /* ieee->i_framelist will hold the generated frames; frames will be - * added at qtail. - */ - - FAR struct iob_s *qtail; - int verify; - - /* 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 - * IPv6/HC1/HC06/HC_UDP dispatchs/headers. - * The following fragments contain only the fragn dispatch. - */ - - ninfo("Fragmentation sending packet len %d\n", sinfo->s_len); - - /* Allocate an IOB to hold the first fragment, waiting if necessary. */ - - iob = iob_alloc(false); - DEBUGASSERT(iob != NULL); - - /* Initialize the IOB */ - - iob->io_flink = NULL; - iob->io_len = 0; - iob->io_offset = 0; - iob->io_pktlen = 0; - - /* Create 1st Fragment */ - /* Add the frame header */ - - verify = sixlowpan_framecreate(ieee, iob, ieee->i_panid); - DEBUGASSERT(vreify == framer_hdrlen); - UNUSED(verify); - - /* Move HC1/HC06/IPv6 header */ - - memmove(g_rimeptr + SIXLOWPAN_FRAG1_HDR_LEN, g_rimeptr, g_rime_hdrlen); - - /* Setup up the fragment header. - * - * The fragment header contains three fields: Datagram size, datagram - * tag and datagram offset: - * - * 1. Datagram size describes the total (un-fragmented) payload. - * 2. Datagram tag identifies the set of fragments and is used to - * match fragments of the same payload. - * 3. Datagram offset identifies the fragment’s offset within the un- - * fragmented payload. - * - * The fragment header length is 4 bytes for the first header and 5 - * bytes for all subsequent headers. - */ - - PUTINT16(RIME_FRAG_PTR, RIME_FRAG_DISPATCH_SIZE, - ((SIXLOWPAN_DISPATCH_FRAG1 << 8) | sinfo->s_len)); - PUTINT16(RIME_FRAG_PTR, RIME_FRAG_TAG, ieee->i_dgramtag); - ieee->i_dgramtag++; - - /* Copy payload and enqueue */ - - g_rime_hdrlen += SIXLOWPAN_FRAG1_HDR_LEN; - g_rime_payloadlen = - (CONFIG_NET_6LOWPAN_MAXPAYLOAD - framer_hdrlen - g_rime_hdrlen) & 0xf8; - - memcpy(g_rimeptr + g_rime_hdrlen, - (uint8_t *) sinfo->s_destip + g_uncomp_hdrlen, g_rime_payloadlen); - iob->io_len += g_rime_payloadlen + g_rime_hdrlen; - - /* Set outlen to what we already sent from the IP payload */ - - outlen = g_rime_payloadlen + g_uncomp_hdrlen; - - ninfo("First fragment: len %d, tag %d\n", - g_rime_payloadlen, ieee->i_dgramtag); - - /* Add the first frame to the IOB queue */ - - ieee->i_framelist = iob; - qtail = iob; - - /* Keep track of the total amount of data queue */ - - iob->io_pktlen = iob->io_len; - - /* Create following fragments */ - - g_rime_hdrlen = SIXLOWPAN_FRAGN_HDR_LEN; - - while (outlen < sinfo->s_len) - { - /* Allocate an IOB to hold the next fragment, waiting if - * necessary. - */ - - iob = iob_alloc(false); - DEBUGASSERT(iob != NULL); - - /* Initialize the IOB */ - - iob->io_flink = NULL; - iob->io_len = 0; - iob->io_offset = 0; - iob->io_pktlen = 0; - - /* Add the frame header */ - - verify = sixlowpan_framecreate(ieee, iob, ieee->i_panid); - DEBUGASSERT(vreify == framer_hdrlen); - UNUSED(verify); - - /* Move HC1/HC06/IPv6 header */ - - memmove(g_rimeptr + SIXLOWPAN_FRAGN_HDR_LEN, g_rimeptr, g_rime_hdrlen); - - /* Setup up the fragment header */ - - PUTINT16(RIME_FRAG_PTR, RIME_FRAG_DISPATCH_SIZE, - ((SIXLOWPAN_DISPATCH_FRAGN << 8) | sinfo->s_len)); - PUTINT16(RIME_FRAG_PTR, RIME_FRAG_TAG, ieee->i_dgramtag); - RIME_FRAG_PTR[RIME_FRAG_OFFSET] = outlen >> 3; - - /* Copy payload and enqueue */ - - if (sinfo->s_len - outlen < g_rime_payloadlen) - { - /* Last fragment */ - - g_rime_payloadlen = sinfo->s_len - outlen; - } - else - { - g_rime_payloadlen = - (CONFIG_NET_6LOWPAN_MAXPAYLOAD - framer_hdrlen - g_rime_hdrlen) & 0xf8; - } - - memcpy(g_rimeptr + g_rime_hdrlen, (FAR uint8_t *) sinfo->s_destip + outlen, - g_rime_payloadlen); - iob->io_len = g_rime_payloadlen + g_rime_hdrlen; - - /* Set outlen to what we already sent from the IP payload */ - - outlen += (g_rime_payloadlen + g_uncomp_hdrlen); - - ninfo("sixlowpan output: fragment offset %d, len %d, tag %d\n", - outlen >> 3, g_rime_payloadlen, ieee->i_dgramtag); - - /* Add the next frame to the tail of the IOB queue */ - - qtail->io_flink = iob; - - /* Keep track of the total amount of data queue */ - - ieee->i_framelist->io_pktlen += iob->io_len; - } -#else - nerr("ERROR: Packet too large: %d\n", sinfo->s_len); - nerr(" Cannot to be sent without fragmentation support\n"); - nerr(" dropping packet\n"); - - return -E2BIG; -#endif - } - else - { - int verify; - - /* The packet does not need to be fragmented just copy the "payload" - * and send in one frame. - */ - - /* Allocate an IOB to hold the frame, waiting if necessary. */ - - iob = iob_alloc(false); - DEBUGASSERT(iob != NULL); - - /* Initialize the IOB */ - - iob->io_flink = NULL; - iob->io_len = 0; - iob->io_offset = 0; - iob->io_pktlen = 0; - - /* Add the frame header */ - - verify = sixlowpan_framecreate(ieee, iob, ieee->i_panid); - DEBUGASSERT(vreify == framer_hdrlen); - UNUSED(verify); - - /* Copy the payload and queue */ - - memcpy(g_rimeptr + g_rime_hdrlen, (uint8_t *)sinfo->s_destip + g_uncomp_hdrlen, - sinfo->s_len - g_uncomp_hdrlen); - iob->io_len = sinfo->s_len - g_uncomp_hdrlen + g_rime_hdrlen; - - /* Add the first frame to the IOB queue */ - - ieee->i_framelist = iob; - - /* Keep track of the total amount of data queue */ - - iob->io_pktlen = iob->io_len; - } - - return OK; -} - /**************************************************************************** * Function: send_timeout * @@ -535,7 +122,7 @@ static inline bool send_timeout(FAR struct sixlowpan_send_s *sinfo) } /**************************************************************************** - * Function: tcpsend_interrupt + * Function: send_interrupt * * Description: * This function is called from the interrupt level to perform the actual @@ -579,7 +166,11 @@ static uint16_t send_interrupt(FAR struct net_driver_s *dev, /* Transfer the frame listto the IEEE802.15.4 MAC device */ - sinfo->s_result = sixlowpan_queue_frames(dev, sinfo); + sinfo->s_result = + sixlowpan_queue_frames((FAR struct ieee802154_driver_s *)dev, + sinfo->s_ipv6hdr, sinfo->s_buf, sinfo->s_len, + sinfo->s_destmac); + flags &= ~WPAN_POLL; goto end_wait; } @@ -632,10 +223,10 @@ end_wait: * * Input Parameters: * dev - The IEEE802.15.4 MAC network driver interface. - * ipv6 - IPv6 plus TCP or UDP headers. + * ipv6hdr - IPv6 header followed by TCP or UDP header. * buf - Data to send * len - Length of data to send - * raddr - The IEEE802.15.4 MAC address of the destination + * destmac - The IEEE802.15.4 MAC address of the destination * timeout - Send timeout in deciseconds * * Returned Value: @@ -650,8 +241,8 @@ end_wait: ****************************************************************************/ int sixlowpan_send(FAR struct net_driver_s *dev, - FAR const struct ipv6_hdr_s *ipv6, FAR const void *buf, - size_t len, FAR const struct rimeaddr_s *raddr, + FAR const struct ipv6_hdr_s *ipv6hdr, FAR const void *buf, + size_t len, FAR const struct rimeaddr_s *destmac, uint16_t timeout) { struct sixlowpan_send_s sinfo; @@ -664,8 +255,8 @@ int sixlowpan_send(FAR struct net_driver_s *dev, sinfo.s_result = -EBUSY; sinfo.s_timeout = timeout; sinfo.s_time = clock_systimer(); - sinfo.s_destip = ipv6; - sinfo.s_destmac = raddr; + sinfo.s_ipv6hdr = ipv6hdr; + sinfo.s_destmac = destmac; sinfo.s_buf = buf; sinfo.s_len = len; diff --git a/net/sixlowpan/sixlowpan_tcpsend.c b/net/sixlowpan/sixlowpan_tcpsend.c index 7089b19b27..ba11700ab4 100644 --- a/net/sixlowpan/sixlowpan_tcpsend.c +++ b/net/sixlowpan/sixlowpan_tcpsend.c @@ -85,7 +85,7 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, FAR struct tcp_conn_s *conn; FAR struct net_driver_s *dev; struct ipv6tcp_hdr_s ipv6tcp; - struct rimeaddr_s dest; + struct rimeaddr_s destmac; uint16_t timeout; int ret; @@ -181,7 +181,7 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, #endif ret = sixlowpan_send(dev, (FAR const struct ipv6_hdr_s *)&ipv6tcp, - buf, len, &dest, timeout); + buf, len, &destmac, timeout); if (ret < 0) { nerr("ERROR: sixlowpan_send() failed: %d\n", ret); diff --git a/net/sixlowpan/sixlowpan_udpsend.c b/net/sixlowpan/sixlowpan_udpsend.c index 18f9ea8ac1..3b17d00767 100644 --- a/net/sixlowpan/sixlowpan_udpsend.c +++ b/net/sixlowpan/sixlowpan_udpsend.c @@ -85,7 +85,7 @@ ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, FAR struct udp_conn_s *conn; FAR struct net_driver_s *dev; struct ipv6udp_hdr_s ipv6udp; - struct rimeaddr_s dest; + struct rimeaddr_s destmac; uint16_t timeout; int ret; @@ -182,7 +182,7 @@ ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, #endif ret = sixlowpan_send(dev, (FAR const struct ipv6_hdr_s *)&ipv6udp, - buf, len, &dest, timeout); + buf, len, &destmac, timeout); if (ret < 0) { nerr("ERROR: sixlowpan_send() failed: %d\n", ret); -- GitLab From 7a4af75fcf577097d8292babc549cd38ef8de903 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 1 Apr 2017 12:34:08 -0600 Subject: [PATCH 301/990] 6lowWPAN: Add frame decompression logic to IEEE802.15.4 input --- include/nuttx/net/sixlowpan.h | 44 +++- net/sixlowpan/Kconfig | 3 +- net/sixlowpan/sixlowpan_input.c | 371 +++++++++++++++++++++++++++++++- net/sixlowpan/sixlowpan_send.c | 13 ++ 4 files changed, 426 insertions(+), 5 deletions(-) diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index f31c453c43..9cfa3e0973 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -53,6 +53,7 @@ #include +#include #include #include @@ -71,9 +72,13 @@ #define SIXLOWPAN_DISPATCH_IPV6 0x41 /* 01000001 = 65 */ #define SIXLOWPAN_DISPATCH_HC1 0x42 /* 01000010 = 66 */ -#define SIXLOWPAN_DISPATCH_IPHC 0x60 /* 011xxxxx = ... */ + +#define SIXLOWPAN_DISPATCH_IPHC 0x60 /* 011xxxxx */ +#define SIXLOWPAN_DISPATCH_IPHC_MASK 0xe0 /* 11100000 */ + #define SIXLOWPAN_DISPATCH_FRAG1 0xc0 /* 11000xxx */ #define SIXLOWPAN_DISPATCH_FRAGN 0xe0 /* 11100xxx */ +#define SIXLOWPAN_DISPATCH_FRAG_MASK 0xf1 /* 11111000 */ /* HC1 encoding */ @@ -402,6 +407,7 @@ struct ieee802154_driver_s FAR struct iob_s *i_framelist; + /* Driver Configuration ***************************************************/ /* i_panid. The PAN ID is 16-bit number that identifies the network. It * must be unique to differentiate a network. All the nodes in the same * network should have the same PAN ID. This value must be provided to @@ -433,6 +439,42 @@ struct ieee802154_driver_s */ uint16_t i_dgramtag; + +#if CONFIG_NET_6LOWPAN_FRAG + /* Fragmentation Support *************************************************/ + /* Fragementation is handled frame by frame and requires that certain + * state information be retained from frame to frame. + */ + + /* i_pktlen. The total length of the IPv6 packet to be re-assembled in + * d_buf. + */ + + uint16_t i_pktlen; + + /* The current accumulated length of the packet being received in d_buf. + * Included IPv6 and protocol headers. + */ + + uint16_t i_accumlen; + + /* i_reasstag. Each frame in the reassembly has a tag. That tag must + * match the reassembly tag in the fragments being merged. + */ + + uint16_t i_reasstag; + + /* The source MAC address of the fragments being merged */ + + struct rimeaddr_s i_fragsrc; + + /* That time at which reassembly was started. If the elapsed time + * exceeds CONFIG_NET_6LOWPAN_MAXAGE, then the reassembly will + * be cancelled. + */ + + systime_t i_time; +#endif /* CONFIG_NET_6LOWPAN_FRAG */ }; /* The structure of a next header compressor. This compressor is provided diff --git a/net/sixlowpan/Kconfig b/net/sixlowpan/Kconfig index 4d0be0b660..49f4756a02 100644 --- a/net/sixlowpan/Kconfig +++ b/net/sixlowpan/Kconfig @@ -132,7 +132,8 @@ config NET_6LOWPAN_MAXAGE int "Packet reassembly timeout" default 20 ---help--- - Timeout for packet reassembly at the 6lowpan layer (should be < 60s) + Timeout for packet reassembly at the 6lowpan layer in units of + seconds (should be < 60s) config NET_6LOWPAN_MAX_MACTRANSMITS int "Max MAC transmissions" diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index 151d205f85..18e499f0d5 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -1,6 +1,6 @@ /**************************************************************************** * net/sixlowpan/sixlowpan_input.c - * 6lowpan implementation (RFC4944 and draft-ietf-6lowpan-hc-06) + * 6loWPAN implementation (RFC4944 and draft-ietf-6loWPAN-hc-06) * * Copyright (C) 2017, Gregory Nutt, all rights reserved * Author: Gregory Nutt @@ -49,10 +49,15 @@ #include +#include #include #include #include +#if CONFIG_NET_6LOWPAN_FRAG +# include "nuttx/clock.h" +#endif + #include "nuttx/net/netdev.h" #include "nuttx/net/ip.h" #include "nuttx/net/sixlowpan.h" @@ -74,6 +79,14 @@ #define INPUT_PARTIAL 0 /* Frame processed successful, packet incomplete */ #define INPUT_COMPLETE 1 /* Frame processed successful, packet complete */ +/* Re-assembly timeout in clock ticks */ + +#define NET_6LOWPAN_TIMEOUT SEC2TICK(CONFIG_NET_6LOWPAN_MAXAGE) + +/* Buffer access helpers */ + +#define IPv6BUF(dev) ((FAR struct ipv6_hdr_s *)((dev)->d_buf)) + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -185,13 +198,365 @@ static void sixlowpan_set_pktattrs(FAR struct ieee802154_driver_s *ieee, * Returned Value: * Ok is returned on success; Othewise a negated errno value is returned. * + * Assumptions: + * Network is locked + * ****************************************************************************/ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, FAR struct iob_s *iob) { - /* REVISIT: To be provided */ - return -ENOSYS; + FAR uint8_t *hc1 = RIME_HC1_PTR; + + uint16_t fragsize = 0; /* Size of the IP packet (read from fragment) */ + uint8_t fragoffset = 0; /* Offset of the fragment in the IP packet */ + bool isfrag = false; + int reqsize; /* Required buffer size */ + +#if CONFIG_NET_6LOWPAN_FRAG + bool isfirstfrag = false; + bool islastfrag = false; + uint16_t fragtag = 0; /* Tag of the fragment */ + systime_t elapsed; /* Elapsed time */ +#endif /* CONFIG_NET_6LOWPAN_FRAG */ + + /* Initialize global data. Locking the network guarantees that we have + * exclusive use of the global values for intermediate calculations. + */ + + g_uncomp_hdrlen = 0; + g_rime_hdrlen = 0; + + /* The MAC puts the 15.4 payload inside the RIME data buffer */ + + g_rimeptr = &iob->io_data[PACKETBUF_HDR_SIZE]; + +#if CONFIG_NET_6LOWPAN_FRAG + /* If reassembly timed out, cancel it */ + + elapsed = clock_systimer() - ieee->i_time; + if (elapsed > NET_6LOWPAN_TIMEOUT) + { + nwarn("WARNING: Reassembly timed out\n"); + ieee->i_pktlen = 0; + ieee->i_accumlen = 0; + } + + /* Since we don't support the mesh and broadcast header, the first header + * we look for is the fragmentation header + */ + + switch ((GETINT16(RIME_FRAG_PTR, RIME_FRAG_DISPATCH_SIZE) & 0xf800) >> 8) + { + /* First fragment of new reassembly */ + + case SIXLOWPAN_DISPATCH_FRAG1: + { + /* Set up for the reassembly */ + + fragoffset = 0; + fragsize = GETINT16(RIME_FRAG_PTR, RIME_FRAG_DISPATCH_SIZE) & 0x07ff; + fragtag = GETINT16(RIME_FRAG_PTR, RIME_FRAG_TAG); + + ninfo("FRAG1: size %d, tag %d, offset %d\n", + fragsize, fragtag, fragoffset); + + g_rime_hdrlen += SIXLOWPAN_FRAG1_HDR_LEN; + + /* Indicate the first fragment of the reassembly */ + + isfirstfrag = true; + isfrag = true; + } + break; + + case SIXLOWPAN_DISPATCH_FRAGN: + { + /* Set offset, tag, size. Offset is in units of 8 bytes. */ + + fragoffset = RIME_FRAG_PTR[RIME_FRAG_OFFSET]; + fragtag = GETINT16(RIME_FRAG_PTR, RIME_FRAG_TAG); + fragsize = GETINT16(RIME_FRAG_PTR, RIME_FRAG_DISPATCH_SIZE) & 0x07ff; + + ninfo("FRAGN: size %d, tag %d, offset %d\n", + fragsize, fragtag, fragoffset); + + g_rime_hdrlen += SIXLOWPAN_FRAGN_HDR_LEN; + + ninfo("islastfrag?: i_accumlen %d g_rime_payloadlen %d fragsize %d\n", + ieee->i_accumlen, iob->io_len - g_rime_hdrlen, fragsize); + + /* Indicate that this frame is a another fragment for reassembly */ + + isfrag = true; + + /* Check if it is the last fragement to be processed. + * + * If this is the last fragment, we may shave off any extrenous + * bytes at the end. We must be liberal in what we accept. + */ + + if (ieee->i_accumlen + iob->io_len - g_rime_hdrlen >= fragsize) + { + islastfrag = true; + } + } + break; + + /* Not a fragment */ + + default: + break; + } + + /* Check if we are currently reassembling a packet */ + + if (ieee->i_accumlen > 0) + { + /* In this case what we expect is that the next frame will hold the + * next FRAGN of the sequence. We have to handle a few exeptional + * cases that we need to handle: + * + * 1. If we are currently reassembling a packet, but have just received + * the first fragment of another packet. We can either ignore it and + * hope to receive the rest of the under-reassembly packet fragments, + * or we can discard the previous packet altogether, and start + * reassembling the new packet. Here we discard the previous packet, + * and start reassembling the new packet. + * 2. The new frame is not a fragment. We should be able to handle this + * case, but we cannot because that would require two packet buffers. + * It could be handled with a more extensive design. + * 3. The fragment came from a different sender. What would this mean? + * + */ + + if (!isfrag) + { + /* Discard the partially assembled packet */ + + nwarn("WARNING: Non-fragment frame received during reassembly\n"); + ieee->i_pktlen = 0; + ieee->i_accumlen = 0; + } + + /* It is a fragment of some kind. Drop any zero length fragments */ + + else if (fragsize == 0) + { + nwarn("WARNING: Dropping zero-length 6loWPAN fragment\n"); + return OK; + } + + /* A non-zero, first fragement received while we are in the middle of + * rassembly. Discard the partially assembled packet and start over. + */ + + else if (isfirstfrag) + { + nwarn("WARNING: First fragment frame received during reassembly\n"); + ieee->i_pktlen = 0; + ieee->i_accumlen = 0; + } + + /* Verify that this fragment is part of that reassembly sequence */ + + else if (fragsize != ieee->i_pktlen || ieee->i_reasstag != fragtag || + !rimeaddr_cmp(&ieee->i_fragsrc, &g_pktaddrs[PACKETBUF_ADDR_SENDER])) + { + /* The packet is a fragment that does not belong to the packet + * being reassembled or the packet is not a fragment. + */ + + nwarn("WARNING: Dropping 6loWPAN packet that is not a fragment of " + "the packet currently being reassembled\n"); + return OK; + } + + /* Looks good. We are currently processing a reassembling sequence and + * we recieved a valid FRAGN fragment. Skip the header compression + * dispatch logic. + */ + + goto copypayload; + } + + /* There is no reassembly in progress. Check if we received a fragment */ + + else if (isfrag) + { + /* Another case that we have to handle is if a FRAGN fragment of a + * reassembly is received, but we are not currently reassembling a + * packet. I think we have no choice but to drop the packet in this + * case. + */ + + if (!isfirstfrag) + { + nwarn("WARNING: FRAGN 6loWPAN fragment while not reassembling\n"); + return OK; + } + + /* Start reassembly if we received a non-zero length, first fragment */ + + if (fragsize > 0) + { + /* Drop the packet if it cannot fit into the d_buf */ + + if (fragsize > CONFIG_NET_6LOWPAN_MTU) + { + nwarn("WARNING: Reassembled packet size exeeds CONFIG_NET_6LOWPAN_MTU\n"); + return OK; + } + + /* Set up for the reassembly */ + + ieee->i_pktlen = fragsize; + ieee->i_reasstag = fragtag; + ieee->i_time = clock_systimer(); + + ninfo("Starting reassembly: i_pktlen %d, i_pktlen %d\n", + ieee->i_pktlen, ieee->i_reasstag); + + rimeaddr_copy(&ieee->i_fragsrc, &g_pktaddrs[PACKETBUF_ADDR_SENDER]); + } + } +#endif /* CONFIG_NET_6LOWPAN_FRAG */ + + /* Process next dispatch and headers */ + +#ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 + if ((hc1[RIME_HC1_DISPATCH] & SIXLOWPAN_DISPATCH_IPHC_MASK) == SIXLOWPAN_DISPATCH_IPHC) + { + ninfo("IPHC Dispatch\n"); + sixlowpan_uncompresshdr_hc06(ieee, fragsize); + } + else +#endif /* CONFIG_NET_6LOWPAN_COMPRESSION_HC06 */ + +#ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC1 + if (hc1[RIME_HC1_DISPATCH] == SIXLOWPAN_DISPATCH_HC1) + { + ninfo("HC1 Dispatch\n"); + sixlowpan_uncompresshdr_hc1(ieee, fragsize); + } + else +#endif /* CONFIG_NET_6LOWPAN_COMPRESSION_HC1 */ + if (hc1[RIME_HC1_DISPATCH] == SIXLOWPAN_DISPATCH_IPV6) + { + ninfo("IPV6 Dispatch\n"); + g_rime_hdrlen += SIXLOWPAN_IPV6_HDR_LEN; + + /* Put uncompressed IP header in d_buf. */ + + memcpy(ieee->i_dev.d_buf, g_rimeptr + g_rime_hdrlen, IPv6_HDRLEN); + + /* Update g_uncomp_hdrlen and g_rime_hdrlen. */ + + g_rime_hdrlen += IPv6_HDRLEN; + g_uncomp_hdrlen += IPv6_HDRLEN; + } + else + { + /* Unknown or unsupported header */ + + nwarn("WARNING unknown dispatch: %u\n", hc1[RIME_HC1_DISPATCH]); + return OK; + } + +#if CONFIG_NET_6LOWPAN_FRAG +copypayload: +#endif /* CONFIG_NET_6LOWPAN_FRAG */ + + /* Copy "payload" from the rime buffer to the d_buf. If this frame is a + * first fragment or not part of a fragmented packet, we have already + * copied the compressed headers, g_uncomp_hdrlen and g_rime_hdrlen are + * non-zerio, fragoffset is. + */ + + if (ieee->i_dev.d_len < g_rime_hdrlen) + { + ninfo("SIXLOWPAN: packet dropped due to header > total packet\n"); + return OK; + } + + g_rime_payloadlen = ieee->i_dev.d_len - g_rime_hdrlen; + + /* Sanity-check size of incoming packet to avoid buffer overflow */ + + reqsize = g_uncomp_hdrlen + (uint16_t) (fragoffset << 3) + g_rime_payloadlen; + if (reqsize > CONFIG_NET_6LOWPAN_MTU) + { + ninfo("Required buffer size: %d+%d+%d=%d Available: %d\n", + g_uncomp_hdrlen, (int)(fragoffset << 3), g_rime_payloadlen, + reqsize, CONFIG_NET_6LOWPAN_MTU); + return OK; + } + + memcpy((FAR uint8_t *)ieee->i_dev.d_buf + g_uncomp_hdrlen + + (int)(fragoffset << 3), g_rimeptr + g_rime_hdrlen, + g_rime_payloadlen); + +#if CONFIG_NET_6LOWPAN_FRAG + /* Update ieee->i_accumlen if the frame is a fragment, ieee->i_pktlen + * otherwise. + */ + + if (isfrag) + { + /* Add the size of the header only for the first fragment. */ + + if (isfirstfrag) + { + ieee->i_accumlen += g_uncomp_hdrlen; + } + + /* For the last fragment, we are OK if there is extraneous bytes at the + * end of the packet. + */ + + if (islastfrag) + { + ieee->i_accumlen = fragsize; + } + else + { + ieee->i_accumlen += g_rime_payloadlen; + } + + ninfo("i_accumlen %d, g_rime_payloadlen %d\n", + ieee->i_accumlen, g_rime_payloadlen); + } + else +#endif /* CONFIG_NET_6LOWPAN_FRAG */ + { + ieee->i_pktlen = g_rime_payloadlen + g_uncomp_hdrlen; + } + +#if CONFIG_NET_6LOWPAN_FRAG + /* If we have a full IP packet in sixlowpan_buf, deliver it to + * the IP stack + */ + + ninfo("sixlowpan_init i_accumlen %d, ieee->i_pktlen %d\n", + ieee->i_accumlen, ieee->i_pktlen); + + if (ieee->i_accumlen == 0 || ieee->i_accumlen == ieee->i_pktlen) + { + FAR struct ipv6_hdr_s *ipv6 = IPv6BUF(&ieee->i_dev); + + ninfo("IP packet ready (length %d)\n", ieee->i_pktlen); + + /* REVISIT -- clearly wrong. */ + memcpy((FAR uint8_t *)ipv6, (FAR uint8_t *)ipv6, ieee->i_pktlen); + + ieee->i_pktlen = 0; + ieee->i_accumlen = 0; + + } +#endif /* CONFIG_NET_6LOWPAN_FRAG */ + + ninfodumpbuffer("IPv6 header", IPv6BUF(ieee->i_dev), IPv6_HDRLEN) + return OK; } /**************************************************************************** diff --git a/net/sixlowpan/sixlowpan_send.c b/net/sixlowpan/sixlowpan_send.c index cff92eecee..f8076449b9 100644 --- a/net/sixlowpan/sixlowpan_send.c +++ b/net/sixlowpan/sixlowpan_send.c @@ -54,6 +54,17 @@ #ifdef CONFIG_NET_6LOWPAN +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* These are temporary stubs. Something like this would be needed to + * monitor the health of a IPv6 neighbor. + */ + +#define neighbor_reachable(dev) +#define neighbor_notreachable(dev) + /**************************************************************************** * Private Types ****************************************************************************/ @@ -172,6 +183,7 @@ static uint16_t send_interrupt(FAR struct net_driver_s *dev, sinfo->s_destmac); flags &= ~WPAN_POLL; + neighbor_reachable(dev); goto end_wait; } @@ -183,6 +195,7 @@ static uint16_t send_interrupt(FAR struct net_driver_s *dev, nwarn("WARNING: SEND timeout\n"); sinfo->s_result = -ETIMEDOUT; + neighbor_notreachable(dev); goto end_wait; } -- GitLab From 64afba55dda7b20c0ec037615a1e27f46a81474e Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 1 Apr 2017 13:42:00 -0600 Subject: [PATCH 302/990] 6loWPAN: Add a little bit of HC1 compression logic. --- net/sixlowpan/sixlowpan_hc1.c | 132 ++++++++++++++++++++++++++++- net/sixlowpan/sixlowpan_input.c | 8 +- net/sixlowpan/sixlowpan_internal.h | 22 +++++ net/sixlowpan/sixlowpan_tcpsend.c | 7 +- net/sixlowpan/sixlowpan_udpsend.c | 7 +- net/sixlowpan/sixlowpan_utils.c | 59 +++++++++++++ 6 files changed, 225 insertions(+), 10 deletions(-) diff --git a/net/sixlowpan/sixlowpan_hc1.c b/net/sixlowpan/sixlowpan_hc1.c index 268f0bad3e..1285144703 100644 --- a/net/sixlowpan/sixlowpan_hc1.c +++ b/net/sixlowpan/sixlowpan_hc1.c @@ -53,6 +53,17 @@ #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC1 +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Buffer access helpers */ + +#define IPv6BUF(dev) \ + ((FAR struct ipv6_hdr_s *)((dev)->d_buf)) +#define UDPIPv6BUF(dev) \ + ((FAR struct udp_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev) + IPv6_HDRLEN]) + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -136,14 +147,127 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, * fragment. * * Returned Value: - * None + * Zero (OK) is returned on success, on failure a negater errno value is + * returned. * ****************************************************************************/ -void sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, - uint16_t iplen) +int sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, + uint16_t iplen) { -/* REVISIT: To be provided */ + FAR struct ipv6_hdr_s *ipv6 = IPv6BUF(&ieee->i_dev); + FAR uint8_t *hc1 = RIME_HC1_PTR; + + /* Format the IPv6 header in the device d_buf */ + /* Set version, traffic clase, and flow label */ + + ipv6->vtc = 0x60; /* Bits 0-3: version, bits 4-7: traffic class (MS) */ + ipv6->tcf = 0; /* Bits 0-3: traffic class (LS), 4-bits: flow label (MS) */ + ipv6->flow = 0; /* 16-bit flow label (LS) */ + + /* Use stateless auto-configuration to set source and destination IP + * addresses. + */ + + sixlowpan_ipfromrime(&g_pktaddrs[PACKETBUF_ADDR_SENDER], + &ipv6->srcipaddr); + sixlowpan_ipfromrime(&g_pktaddrs[PACKETBUF_ADDR_RECEIVER], + &ipv6->destipaddr); + g_uncomp_hdrlen += IPv6_HDRLEN; + + /* len[], proto, and ttl depend on the encoding */ + + switch (hc1[RIME_HC1_ENCODING] & 0x06) + { + case SIXLOWPAN_HC1_NH_ICMP6: + ipv6->proto = IP_PROTO_ICMP6; + ipv6->ttl = hc1[RIME_HC1_TTL]; + g_rime_hdrlen += SIXLOWPAN_HC1_HDR_LEN; + break; + +#if CONFIG_NET_TCP + case SIXLOWPAN_HC1_NH_TCP: + ipv6->proto = IP_PROTO_TCP; + ipv6->ttl = hc1[RIME_HC1_TTL]; + g_rime_hdrlen += SIXLOWPAN_HC1_HDR_LEN; + break; +#endif /* CONFIG_NET_TCP */ + +#if CONFIG_NET_UDP + case SIXLOWPAN_HC1_NH_UDP: + { + FAR struct udp_hdr_s *udp = UDPIPv6BUF(&ieee->i_dev); + FAR uint8_t *hcudp = RIME_HC1_HC_UDP_PTR; + + ipv6->proto = IP_PROTO_UDP; + if ((hcudp[RIME_HC1_HC_UDP_HC1_ENCODING] & 0x01) != 0) + { + /* UDP header is compressed with HC_UDP */ + + if (hcudp[RIME_HC1_HC_UDP_UDP_ENCODING] != + SIXLOWPAN_HC_UDP_ALL_C) + { + nwarn("WARNING: sixlowpan (uncompress_hdr), packet not supported"); + return -EOPNOTSUPP; + } + + /* IP TTL */ + + ipv6->ttl = hcudp[RIME_HC1_HC_UDP_TTL]; + + /* UDP ports, len, checksum */ + + udp->srcport = + htons(SIXLOWPAN_UDP_PORT_MIN + (hcudp[RIME_HC1_HC_UDP_PORTS] >> 4)); + udp->destport = + htons(SIXLOWPAN_UDP_PORT_MIN + (hcudp[RIME_HC1_HC_UDP_PORTS] & 0x0F)); + + memcpy(&udp->udpchksum, &hcudp[RIME_HC1_HC_UDP_CHKSUM], 2); + + g_uncomp_hdrlen += UIP_UDPH_LEN; + g_rime_hdrlen += SIXLOWPAN_HC1_HC_UDP_HDR_LEN; + } + else + { + g_rime_hdrlen += SIXLOWPAN_HC1_HDR_LEN; + } + } + break; +#endif /* CONFIG_NET_UDP */ + + default: + return -EPROTONOSUPPORT; + } + + /* IP length field. */ + + if (iplen == 0) + { + /* This is not a fragmented packet */ + + ipv6->len[0] = 0; + ipv6->len[1] = ieee->i_dev.d_len - g_rime_hdrlen + /* REVISIT */ + g_uncomp_hdrlen - IPv6_HDRLEN; + } + else + { + /* This is a 1st fragment */ + + ipv6->len[0] = (iplen - IPv6_HDRLEN) >> 8; + ipv6->len[1] = (iplen - IPv6_HDRLEN) & 0x00FF; + } + + /* length field in UDP header */ + +#if CONFIG_NET_UDP + if (ipv6->proto == IP_PROTO_UDP) + { + FAR struct udp_hdr_s *udp = UDPIPv6BUF(&ieee->i_dev); + memcpy(&udp->udplen, &ipv6->len[0], 2); + } +#endif + + return; } #endif /* CONFIG_NET_6LOWPAN_COMPRESSION_HC1 */ diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index 18e499f0d5..882af91708 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -700,8 +700,12 @@ int sixlowpan_input(FAR struct ieee802154_driver_s *ieee) ipv6hdr = (FAR struct ipv6_hdr_s *)(ieee->i_dev.d_buf); - /* Get the Rime MAC address of the destination */ -#warning Missing logic + /* Get the Rime MAC address of the destination. This + * assumes an encoding of the MAC address in the IPv6 + * address. + */ + + sixlowpan_rimefromip(ipv6hdr->destipaddr, &destmac); /* Convert the outgoing packet into a frame list. */ diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index 644880398f..1ec75b57f8 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -663,5 +663,27 @@ void sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, int sixlowpan_frame_hdralloc(FAR struct iob_s *iob, int size); +/**************************************************************************** + * Name: sixlowpan_ipfromrime and sixlowpan_rimefromip + * + * Description: + * sixlowpan_ipfromrime: Use stateless auto-configuration to create an IP + * address from a rime address. + * + * sixlowpan_rimefromip: Assume stateless auto-configuration to extrate + * the rime address from an IP address + * + * 128 112 96 80 64 48 32 16 + * ---- ---- ---- ---- ---- ---- ---- ---- + * fe80 0000 0000 0000 xxxx xxxx 0000 0000 2-byte Rime address (VALID?) + * fe80 0000 0000 0000 xxxx xxxx xxxx xxxx 8-byte Rime address + * + ****************************************************************************/ + +void sixlowpan_ipfromrime(FAR const struct rimeaddr_s *rime, + net_ipv6addr_t ipaddr); +void sixlowpan_rimefromip(const net_ipv6addr_t ipaddr, + FAR struct rimeaddr_s *rime); + #endif /* CONFIG_NET_6LOWPAN */ #endif /* _NET_SIXLOWPAN_SIXLOWPAN_INTERNAL_H */ diff --git a/net/sixlowpan/sixlowpan_tcpsend.c b/net/sixlowpan/sixlowpan_tcpsend.c index ba11700ab4..ae581b150a 100644 --- a/net/sixlowpan/sixlowpan_tcpsend.c +++ b/net/sixlowpan/sixlowpan_tcpsend.c @@ -167,8 +167,11 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_SEND); - /* Get the Rime MAC address of the destination */ -#warning Missing logic + /* Get the Rime MAC address of the destination This assumes an encoding + * of the MAC address in the IPv6 address. + */ + + sixlowpan_rimefromip(conn->u.ipv6.raddr, &destmac); /* If routable, then call sixlowpan_send() to format and send the 6loWPAN * packet. diff --git a/net/sixlowpan/sixlowpan_udpsend.c b/net/sixlowpan/sixlowpan_udpsend.c index 3b17d00767..c0c3148b90 100644 --- a/net/sixlowpan/sixlowpan_udpsend.c +++ b/net/sixlowpan/sixlowpan_udpsend.c @@ -168,8 +168,11 @@ ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_SEND); - /* Get the Rime MAC address of the destination */ -#warning Missing logic + /* Get the Rime MAC address of the destination This assumes an encoding + * of the MAC address in the IPv6 address. + */ + + sixlowpan_rimefromip(conn->u.ipv6.raddr, &destmac); /* If routable, then call sixlowpan_send() to format and send the 6loWPAN * packet. diff --git a/net/sixlowpan/sixlowpan_utils.c b/net/sixlowpan/sixlowpan_utils.c index f6ad77c68b..77612c82c1 100644 --- a/net/sixlowpan/sixlowpan_utils.c +++ b/net/sixlowpan/sixlowpan_utils.c @@ -66,8 +66,11 @@ #include #include +#include #include +#include + #include "sixlowpan/sixlowpan_internal.h" #ifdef CONFIG_NET_6LOWPAN @@ -96,4 +99,60 @@ int sixlowpan_frame_hdralloc(FAR struct iob_s *iob, int size) return -ENOMEM; } +/**************************************************************************** + * Name: sixlowpan_ipfromrime + * + * Description: + * Use stateless auto-configuration to create an IP address from a rime + * address: + * + * 128 112 96 80 64 48 32 16 + * ---- ---- ---- ---- ---- ---- ---- ---- + * fe80 0000 0000 0000 xxxx xxxx 0000 0000 2-byte Rime address (VALID?) + * fe80 0000 0000 0000 xxxx xxxx xxxx xxxx 8-byte Rime address + * + ****************************************************************************/ + +void sixlowpan_ipfromrime(FAR const struct rimeaddr_s *rime, + net_ipv6addr_t ipaddr) +{ + memset(ipaddr, 0, sizeof(net_ipv6addr_t)); + ipaddr[0] = 0xfe80; + + /* We consider only links with IEEE EUI-64 identifier or IEEE 48-bit MAC + * addresses. NOTE: that CONFIG_NET_6LOWPAN_RIMEADDR_SIZE may be 2 or + * 8. In the case of 2, we treat the address like an 8 byte address with + * the lower bytes set to zero. + * + * REVISIT: This is just a guess so that I can continue making forward + * progress. What is the correct policy? + */ + + memcpy(&ipaddr[4], rime, CONFIG_NET_6LOWPAN_RIMEADDR_SIZE); +} + +/**************************************************************************** + * Name: sixlowpan_rimefromip + * + * Description: + * Assume stateless auto-configuration to extrate the rime address from + * an IP address: + * + * 128 112 96 80 64 48 32 16 + * ---- ---- ---- ---- ---- ---- ---- ---- + * fe80 0000 0000 0000 xxxx xxxx 0000 0000 2-byte Rime address (VALID?) + * fe80 0000 0000 0000 xxxx xxxx xxxx xxxx 8-byte Rime address + * + ****************************************************************************/ + +void sixlowpan_rimefromip(const net_ipv6addr_t ipaddr, + FAR struct rimeaddr_s *rime) +{ + /* REVISIT: See notes about 2 byte addresses in sixlowpan_ipfromrime() */ + + DEBUGASSERT(ipaddr[0] == 0xfe80); + + memcpy(rime, &ipaddr[4], CONFIG_NET_6LOWPAN_RIMEADDR_SIZE); +} + #endif /* CONFIG_NET_6LOWPAN */ -- GitLab From 5af0909275f6e55ef27a31b421e669c7c42cf06f Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 1 Apr 2017 15:05:38 -0600 Subject: [PATCH 303/990] 6loWPAN: A little HC1 compression logic. --- net/sixlowpan/sixlowpan_hc06.c | 5 +- net/sixlowpan/sixlowpan_hc1.c | 106 ++++++++++++++++++++++++++++- net/sixlowpan/sixlowpan_internal.h | 40 ++++++++--- net/sixlowpan/sixlowpan_utils.c | 39 +++++++++-- 4 files changed, 171 insertions(+), 19 deletions(-) diff --git a/net/sixlowpan/sixlowpan_hc06.c b/net/sixlowpan/sixlowpan_hc06.c index e0ca657c03..d6668978d9 100644 --- a/net/sixlowpan/sixlowpan_hc06.c +++ b/net/sixlowpan/sixlowpan_hc06.c @@ -203,7 +203,10 @@ void sixlowpan_hc06_initialize(void) * * Input Parameters: * ieee - A reference to the IEE802.15.4 network device state - * destaddr - L2 destination address, needed to compress IP dest + * ipv6 - The IPv6 header to be compressed + * destaddr - L2 destination address, needed to compress the IP + * destination field + * iob - The IOB into which the compressed header should be saved. * * Returned Value: * None diff --git a/net/sixlowpan/sixlowpan_hc1.c b/net/sixlowpan/sixlowpan_hc1.c index 1285144703..3078896921 100644 --- a/net/sixlowpan/sixlowpan_hc1.c +++ b/net/sixlowpan/sixlowpan_hc1.c @@ -114,8 +114,10 @@ * * Input Parmeters: * ieee - A reference to the IEE802.15.4 network device state + * ipv6 - The IPv6 header to be compressed * destaddr - L2 destination address, needed to compress the IP * destination field + * iob - The IOB into which the compressed header should be saved. * * Returned Value: * None @@ -123,9 +125,109 @@ ****************************************************************************/ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, - FAR struct rimeaddr_s *destaddr) + FAR const struct ipv6_hdr_s *ipv6, + FAR const struct rimeaddr_s *destaddr, + FAR struct iob_s *iob) { -/* REVISIT: To be provided */ + FAR uint8_t *hc1 = RIME_HC1_PTR; + + /* Check if all the assumptions for full compression are valid */ + + if (ipv6->vtc != 0x60 || ipv6->tcflow != 0 || ipv6->flow != 0 || + !sixlowpan_islinklocal(&ipv6->srcipaddr) || + !sixlowpan_ismacbased(&ipv6->srcipaddr, &ieee->i_rimeaddr) || + !sixlowpan_islinklocal(&ipv6->destipaddr) || + !sixlowpan_ismacbased(&ipv6->destipaddr, destaddr) || + (ipv6->proto != IP_PROTO_ICMP6 && ipv6->proto != IP_PROTO_UDP && + ipv6->proto != IP_PROTO_TCP)) + { + /* IPV6 DISPATCH + * Something cannot be compressed, use IPV6 DISPATCH, + * compress nothing, copy IPv6 header in rime buffer + */ + + *g_rimeptr = SIXLOWPAN_DISPATCH_IPV6; + g_rime_hdrlen += SIXLOWPAN_IPV6_HDR_LEN; + memcpy(g_rimeptr + g_rime_hdrlen, ipv6, IPv6_HDRLEN); + g_rime_hdrlen += IPv6_HDRLEN; + g_uncomp_hdrlen += IPv6_HDRLEN; + } + else + { + /* HC1 DISPATCH maximum compresssion: + * All fields in the IP header but Hop Limit are elided. If next + * header is UDP, we compress UDP header using HC2 + */ + + hc1[RIME_HC1_DISPATCH] = SIXLOWPAN_DISPATCH_HC1; + g_uncomp_hdrlen += IPv6_HDRLEN; + switch (ipv6->proto) + { + case IP_PROTO_ICMP6: + /* HC1 encoding and ttl */ + + hc1[RIME_HC1_ENCODING] = 0xfc; + hc1[RIME_HC1_TTL] = ipv6->ttl; + g_rime_hdrlen += SIXLOWPAN_HC1_HDR_LEN; + break; + +#if CONFIG_NET_TCP + case IP_PROTO_TCP: + /* HC1 encoding and ttl */ + + hc1[RIME_HC1_ENCODING] = 0xfe; + hc1[RIME_HC1_TTL] = ipv6->ttl; + g_rime_hdrlen += SIXLOWPAN_HC1_HDR_LEN; + break; +#endif /* CONFIG_NET_TCP */ + +#if CONFIG_NET_UDP + case IP_PROTO_UDP: + FAR struct udp_hdr_s *udp = UDPIPv6BUF(dev); + + /* Try to compress UDP header (we do only full compression). This + * is feasible if both src and dest ports are between + * SIXLOWPAN_UDP_PORT_MIN and SIXLOWPAN_UDP_PORT_MIN + 15 + */ + + ninfo("local/remote port %u/%u\n", udp->srcport, udp->destport); + + if (htons(udp->srcport) >= SIXLOWPAN_UDP_PORT_MIN && + htons(udp->srcport) < SIXLOWPAN_UDP_PORT_MAX && + htons(udp->destport) >= SIXLOWPAN_UDP_PORT_MIN && + htons(udp->destport) < SIXLOWPAN_UDP_PORT_MAX) + { + FAR uint8_t *hcudp = RIME_HC1_HC_UDP_PTR; + + /* HC1 encoding */ + + hcudp[RIME_HC1_HC_UDP_HC1_ENCODING] = 0xfb; + + /* HC_UDP encoding, ttl, src and dest ports, checksum */ + + hcudp[RIME_HC1_HC_UDP_UDP_ENCODING] = 0xe0; + hcudp[RIME_HC1_HC_UDP_TTL] = ipv6->ttl; + hcudp[RIME_HC1_HC_UDP_PORTS] = + (uint8_t)((htons(udp->srcport) - SIXLOWPAN_UDP_PORT_MIN) << 4) + + (uint8_t)((htons(udp->destport) - SIXLOWPAN_UDP_PORT_MIN)); + + memcpy(&hcudp[RIME_HC1_HC_UDP_CHKSUM], &udp->udpchksum, 2); + + g_rime_hdrlen += SIXLOWPAN_HC1_HC_UDP_HDR_LEN; + g_uncomp_hdrlen += UIP_UDPH_LEN; + } + else + { + /* HC1 encoding and ttl */ + + hc1[RIME_HC1_ENCODING] = 0xfa; + hc1[RIME_HC1_TTL] = ipv6->ttl; + g_rime_hdrlen += SIXLOWPAN_HC1_HDR_LEN; + } + break; +#endif /* CONFIG_NET_UDP */ + } + } } /**************************************************************************** diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index 1ec75b57f8..bd8929cbb5 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -228,7 +228,7 @@ /* General helper macros ****************************************************/ #define GETINT16(ptr,index) \ - ((((uint16_t)((ptr)[index]) << 8)) | ((uint16_t)(((ptr)[(index) + 1])))) + ((((uint16_t)((ptr)[index])) << 8) | ((uint16_t)(((ptr)[(index) + 1])))) #define PUTINT16(ptr,index,value) \ do \ { \ @@ -396,6 +396,7 @@ extern struct rimeaddr_s g_pktaddrs[PACKETBUF_NUM_ADDRS]; struct net_driver_s; /* Forward reference */ struct ieee802154_driver_s; /* Forward reference */ +struct ipv6_hdr_s; /* Forward reference */ struct rimeaddr_s; /* Forward reference */ struct iob_s; /* Forward reference */ @@ -559,7 +560,10 @@ void sixlowpan_hc06_initialize(void); * * Input Parameters: * ieee - A reference to the IEE802.15.4 network device state - * destaddr - L2 destination address, needed to compress IP dest + * ipv6 - The IPv6 header to be compressed + * destaddr - L2 destination address, needed to compress the IP + * destination field + * iob - The IOB into which the compressed header should be saved. * * Returned Value: * None @@ -567,8 +571,10 @@ void sixlowpan_hc06_initialize(void); ****************************************************************************/ #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 -void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *dev, - FAR struct rimeaddr_s *destaddr); +void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, + FAR const struct ipv6_hdr_s *ipv6, + FAR const struct rimeaddr_s *destaddr, + FAR struct iob_s *iob); #endif /**************************************************************************** @@ -612,8 +618,10 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, * * Input Parmeters: * ieee - A reference to the IEE802.15.4 network device state + * ipv6 - The IPv6 header to be compressed * destaddr - L2 destination address, needed to compress the IP * destination field + * iob - The IOB into which the compressed header should be saved. * * Returned Value: * None @@ -622,7 +630,9 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC1 void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, - FAR struct rimeaddr_s *destaddr); + FAR const struct ipv6_hdr_s *ipv6, + FAR const struct rimeaddr_s *destaddr, + FAR struct iob_s *iob); #endif /**************************************************************************** @@ -664,26 +674,34 @@ void sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, int sixlowpan_frame_hdralloc(FAR struct iob_s *iob, int size); /**************************************************************************** - * Name: sixlowpan_ipfromrime and sixlowpan_rimefromip + * Name: sixlowpan_islinklocal, sixlowpan_ipfromrime, sixlowpan_rimefromip, + * and sixlowpan_ismacbased * * Description: - * sixlowpan_ipfromrime: Use stateless auto-configuration to create an IP - * address from a rime address. + * sixlowpan_ipfromrime: Create a link local IPv6 address from a rime + * address. * - * sixlowpan_rimefromip: Assume stateless auto-configuration to extrate - * the rime address from an IP address + * sixlowpan_rimefromip: Extract the rime address from a link local IPv6 + * address. + * + * sixlowpan_islinklocal and sixlowpan_ismacbased will return true for + * address created in this fashion. * * 128 112 96 80 64 48 32 16 * ---- ---- ---- ---- ---- ---- ---- ---- - * fe80 0000 0000 0000 xxxx xxxx 0000 0000 2-byte Rime address (VALID?) + * fe80 0000 0000 0000 xxxx 0000 0000 0000 2-byte Rime address (VALID?) * fe80 0000 0000 0000 xxxx xxxx xxxx xxxx 8-byte Rime address * ****************************************************************************/ +#define sixlowpan_islinklocal(ipaddr) ((ipaddr)[0] = NTOHS(0xfe80)) + void sixlowpan_ipfromrime(FAR const struct rimeaddr_s *rime, net_ipv6addr_t ipaddr); void sixlowpan_rimefromip(const net_ipv6addr_t ipaddr, FAR struct rimeaddr_s *rime); +bool sixlowpan_ismacbased(const net_ipv6addr_t ipaddr, + FAR const struct rimeaddr_s *rime); #endif /* CONFIG_NET_6LOWPAN */ #endif /* _NET_SIXLOWPAN_SIXLOWPAN_INTERNAL_H */ diff --git a/net/sixlowpan/sixlowpan_utils.c b/net/sixlowpan/sixlowpan_utils.c index 77612c82c1..fae33fe207 100644 --- a/net/sixlowpan/sixlowpan_utils.c +++ b/net/sixlowpan/sixlowpan_utils.c @@ -103,8 +103,7 @@ int sixlowpan_frame_hdralloc(FAR struct iob_s *iob, int size) * Name: sixlowpan_ipfromrime * * Description: - * Use stateless auto-configuration to create an IP address from a rime - * address: + * Create a link local IPv6 address from a rime address: * * 128 112 96 80 64 48 32 16 * ---- ---- ---- ---- ---- ---- ---- ---- @@ -129,18 +128,18 @@ void sixlowpan_ipfromrime(FAR const struct rimeaddr_s *rime, */ memcpy(&ipaddr[4], rime, CONFIG_NET_6LOWPAN_RIMEADDR_SIZE); + ipaddr[4] ^= 0x0200; } /**************************************************************************** * Name: sixlowpan_rimefromip * * Description: - * Assume stateless auto-configuration to extrate the rime address from - * an IP address: + * Extract the rime address from a link local IPv6 address: * * 128 112 96 80 64 48 32 16 * ---- ---- ---- ---- ---- ---- ---- ---- - * fe80 0000 0000 0000 xxxx xxxx 0000 0000 2-byte Rime address (VALID?) + * fe80 0000 0000 0000 xxxx 0000 0000 0000 2-byte Rime address (VALID?) * fe80 0000 0000 0000 xxxx xxxx xxxx xxxx 8-byte Rime address * ****************************************************************************/ @@ -153,6 +152,36 @@ void sixlowpan_rimefromip(const net_ipv6addr_t ipaddr, DEBUGASSERT(ipaddr[0] == 0xfe80); memcpy(rime, &ipaddr[4], CONFIG_NET_6LOWPAN_RIMEADDR_SIZE); + rime->u8[0] ^= 0x02; +} + +/**************************************************************************** + * Name: sixlowpan_ismacbased + * + * Description: + * Extract the rime address from a link local IPv6 address: + * + * 128 112 96 80 64 48 32 16 + * ---- ---- ---- ---- ---- ---- ---- ---- + * fe80 0000 0000 0000 xxxx 0000 0000 0000 2-byte Rime address (VALID?) + * fe80 0000 0000 0000 xxxx xxxx xxxx xxxx 8-byte Rime address + * + ****************************************************************************/ + +bool sixlowpan_ismacbased(const net_ipv6addr_t ipaddr, + FAR const struct rimeaddr_s *rime) +{ + FAR const uint8_t *rimeptr = rime->u8; + +#if CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 2 + return ((ipaddr[4] == (GETINT16(rimeptr, 0) ^ 0x0200)) && + ipaddr[5] == 0 && ipaddr[6] == 0 && ipaddr[7] == 0); +#else /* CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 8 */ + return ((ipaddr[4] == (GETINT16(rimeptr, 0) ^ 0x0200)) && + ipaddr[5] == GETINT16(rimeptr, 2) && + ipaddr[6] == GETINT16(rimeptr, 4) && + ipaddr[7] == GETINT16(rimeptr, 6)); +#endif } #endif /* CONFIG_NET_6LOWPAN */ -- GitLab From 6464ebbc7f1d15b54b5a657cc078d44668c62f6d Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 1 Apr 2017 18:23:21 -0600 Subject: [PATCH 304/990] Networking: Fix bad macro logic of recent commit. Macros were not being evaluating in the order and time that I thought. --- include/nuttx/net/netconfig.h | 169 ++++++++++++++-------------------- 1 file changed, 69 insertions(+), 100 deletions(-) diff --git a/include/nuttx/net/netconfig.h b/include/nuttx/net/netconfig.h index 0e912a5352..b320e0b98f 100644 --- a/include/nuttx/net/netconfig.h +++ b/include/nuttx/net/netconfig.h @@ -336,67 +336,51 @@ #endif #ifdef CONFIG_NET_MULTILINK -# undef __LAST_MIN_UDP_MSS -# undef __LAST_MAX_UDP_MSS - # ifdef CONFIG_NET_ETHERNET -# ifdef __LAST_MIN_UDP_MSS -# define __MIN_UDP_MSS(h) MIN(ETH_UDP_MSS(h),__LAST_MIN_UDP_MSS(h)) -# define __MAX_UDP_MSS(h) MAX(ETH_UDP_MSS(h),__LAST_MAX_UDP_MSS(h)) -# else -# define __MIN_UDP_MSS(h) ETH_UDP_MSS(h) -# define __MAX_UDP_MSS(h) ETH_UDP_MSS(h) -# endif -# undef __LAST_MIN_UDP_MSS -# undef __LAST_MAX_UDP_MSS -# define __LAST_MIN_UDP_MSS(h) __MIN_UDP_MSS(h) -# define __LAST_MAX_UDP_MSS(h) __MAX_UDP_MSS(h) +# define __MIN_UDP_MSS(h) ETH_UDP_MSS(h) +# define __MAX_UDP_MSS(h) ETH_UDP_MSS(h) +# define __ETH_MIN_UDP_MSS(h) ETH_UDP_MSS(h) +# define __ETH_MAX_UDP_MSS(h) ETH_UDP_MSS(h) +# else +# define __ETH_MIN_UDP_MSS(h) INT_MAX +# define __ETH_MAX_UDP_MSS(h) 0 # endif # ifdef CONFIG_NET_6LOWPAN -# ifdef __LAST_MIN_UDP_MSS -# define __MIN_UDP_MSS(h) MIN(IEEE802154_UDP_MSS(h),__LAST_MIN_UDP_MSS(h)) -# define __MAX_UDP_MSS(h) MAX(IEEE802154_UDP_MSS(h),__LAST_MAX_UDP_MSS(h)) -# else -# define __MIN_UDP_MSS(h) IEEE802154_UDP_MSS(h) -# define __MAX_UDP_MSS(h) IEEE802154_UDP_MSS(h) -# endif -# undef __LAST_MIN_UDP_MSS -# undef __LAST_MAX_UDP_MSS -# define __LAST_MIN_UDP_MSS(h) __MIN_UDP_MSS(h) -# define __LAST_MAX_UDP_MSS(h) __MAX_UDP_MSS(h) +# undef __MIN_UDP_MSS +# undef __MIN_UDP_MSS +# define __MIN_UDP_MSS(h) MIN(IEEE802154_UDP_MSS(h),__ETH_MIN_UDP_MSS(h)) +# define __MAX_UDP_MSS(h) MAX(IEEE802154_UDP_MSS(h),__ETH_MAX_UDP_MSS(h)) +# define __6LOWPAN_MIN_UDP_MSS(h) MIN(IEEE802154_UDP_MSS(h),__ETH_MIN_UDP_MSS(h)) +# define __6LOWPAN_MAX_UDP_MSS(h) MAX(IEEE802154_UDP_MSS(h),__ETH_MAX_UDP_MSS(h)) +# else +# define __6LOWPAN_MIN_UDP_MSS(h) __ETH_MIN_UDP_MSS(h) +# define __6LOWPAN_MAX_UDP_MSS(h) __ETH_MAX_UDP_MSS(h) # endif # ifdef CONFIG_NET_LOOPBACK -# ifdef __LAST_MIN_UDP_MSS -# define __MIN_UDP_MSS(h) MIN(LO_UDP_MSS(h),__LAST_MIN_UDP_MSS(h)) -# define __MAX_UDP_MSS(h) MAX(LO_UDP_MSS(h),__LAST_MAX_UDP_MSS(h)) -# else -# define __MIN_UDP_MSS(h) LO_UDP_MSS(h) -# define __MAX_UDP_MSS(h) LO_UDP_MSS(h) -# endif -# undef __LAST_MIN_UDP_MSS -# undef __LAST_MAX_UDP_MSS -# define __LAST_MIN_UDP_MSS(h) __MIN_UDP_MSS(h) -# define __LAST_MAX_UDP_MSS(h) __MAX_UDP_MSS(h) +# undef __MIN_UDP_MSS +# undef __MIN_UDP_MSS +# define __MIN_UDP_MSS(h) MIN(LO_UDP_MSS(h),__6LOWPAN_MIN_UDP_MSS(h)) +# define __MAX_UDP_MSS(h) MAX(LO_UDP_MSS(h),__6LOWPAN_MAX_UDP_MSS(h)) +# define __LOOP_MIN_UDP_MSS(h) MIN(LO_UDP_MSS(h),__6LOWPAN_MIN_UDP_MSS(h)) +# define __LOOP_MAX_UDP_MSS(h) MAX(LO_UDP_MSS(h),__6LOWPAN_MAX_UDP_MSS(h)) +# else +# define __LOOP_MIN_UDP_MSS(h) __6LOWPAN_MIN_UDP_MSS(h) +# define __LOOP_MAX_UDP_MSS(h) __6LOWPAN_MAX_UDP_MSS(h) # endif # ifdef CONFIG_NET_SLIP -# ifdef __LAST_MIN_UDP_MSS -# define __MIN_UDP_MSS(h) MIN(SLIP_UDP_MSS(h),__LAST_MIN_UDP_MSS(h)) -# define __MAX_UDP_MSS(h) MAX(SLIP_UDP_MSS(h),__LAST_MAX_UDP_MSS(h)) -# else -# define __MIN_UDP_MSS(h) SLIP_UDP_MSS(h) -# define __MAX_UDP_MSS(h) SLIP_UDP_MSS(h) -# endif -# undef __LAST_MIN_UDP_MSS -# undef __LAST_MAX_UDP_MSS -# define __LAST_MIN_UDP_MSS(h) __MIN_UDP_MSS(h) -# define __LAST_MAX_UDP_MSS(h) __MAX_UDP_MSS(h) +# undef __MIN_UDP_MSS +# undef __MIN_UDP_MSS +# define __MIN_UDP_MSS(h) MIN(SLIP_UDP_MSS(h),__LOOP_MIN_UDP_MSS(h)) +# define __MAX_UDP_MSS(h) MAX(SLIP_UDP_MSS(h),__LOOP_MAX_UDP_MSS(h)) +# define __SLIP_MIN_UDP_MSS(h) MIN(SLIP_UDP_MSS(h),__LOOP_MIN_UDP_MSS(h)) +# define __SLIP_MAX_UDP_MSS(h) MAX(SLIP_UDP_MSS(h),__LOOP_MAX_UDP_MSS(h)) +# else +# define __SLIP_MIN_UDP_MSS(h) __LOOP_MIN_UDP_MSS(h) +# define __SLIP_MAX_UDP_MSS(h) __LOOP_MAX_UDP_MSS(h) # endif - -# undef __LAST_MIN_UDP_MSS -# undef __LAST_MAX_UDP_MSS #endif /* NOTE: MSS calcuation excludes the UDP_HDRLEN. */ @@ -531,67 +515,52 @@ #endif #ifdef CONFIG_NET_MULTILINK -# undef __LAST_MIN_TCP_MSS -# undef __LAST_MAX_TCP_MSS # ifdef CONFIG_NET_ETHERNET -# ifdef __LAST_MIN_TCP_MSS -# define __MIN_TCP_MSS(h) MIN(ETH_TCP_MSS(h),__LAST_MIN_TCP_MSS(h)) -# define __MAX_TCP_MSS(h) MAX(ETH_TCP_MSS(h),__LAST_MAX_TCP_MSS(h)) -# else -# define __MIN_TCP_MSS(h) ETH_TCP_MSS(h) -# define __MAX_TCP_MSS(h) ETH_TCP_MSS(h) -# endif -# undef __LAST_MIN_TCP_MSS -# undef __LAST_MAX_TCP_MSS -# define __LAST_MIN_TCP_MSS(h) __MIN_TCP_MSS(h) -# define __LAST_MAX_TCP_MSS(h) __MAX_TCP_MSS(h) +# define __MIN_TCP_MSS(h) ETH_TCP_MSS(h) +# define __MAX_TCP_MSS(h) ETH_TCP_MSS(h) +# define __ETH_MIN_TCP_MSS(h) ETH_TCP_MSS(h) +# define __ETH_MAX_TCP_MSS(h) ETH_TCP_MSS(h) +# else +# define __ETH_MIN_TCP_MSS(h) INT_MAX +# define __ETH_MAX_TCP_MSS(h) 0 # endif # ifdef CONFIG_NET_6LOWPAN -# ifdef __LAST_MIN_TCP_MSS -# define __MIN_TCP_MSS(h) MIN(IEEE802154_TCP_MSS(h),__LAST_MIN_TCP_MSS(h)) -# define __MAX_TCP_MSS(h) MAX(IEEE802154_TCP_MSS(h),__LAST_MAX_TCP_MSS(h)) -# else -# define __MIN_TCP_MSS(h) IEEE802154_TCP_MSS(h) -# define __MAX_TCP_MSS(h) IEEE802154_TCP_MSS(h) -# endif -# undef __LAST_MIN_TCP_MSS -# undef __LAST_MAX_TCP_MSS -# define __LAST_MIN_TCP_MSS(h) __MIN_TCP_MSS(h) -# define __LAST_MAX_TCP_MSS(h) __MAX_TCP_MSS(h) +# undef __MIN_TCP_MSS +# undef __MAX_TCP_MSS +# define __MIN_TCP_MSS(h) MIN(IEEE802154_TCP_MSS(h),__ETH_MIN_TCP_MSS(h)) +# define __MAX_TCP_MSS(h) MAX(IEEE802154_TCP_MSS(h),__ETH_MAX_TCP_MSS(h)) +# define __6LOWPAN_MIN_TCP_MSS(h) MIN(IEEE802154_TCP_MSS(h),__ETH_MIN_TCP_MSS(h)) +# define __6LOWPAN_MAX_TCP_MSS(h) MAX(IEEE802154_TCP_MSS(h),__ETH_MAX_TCP_MSS(h)) +# else +# define __6LOWPAN_MIN_TCP_MSS(h) __ETH_MIN_TCP_MSS(h) +# define __6LOWPAN_MAX_TCP_MSS(h) __ETH_MAX_TCP_MSS(h) # endif # ifdef CONFIG_NET_LOOPBACK -# ifdef __LAST_MIN_TCP_MSS -# define __MIN_TCP_MSS(h) MIN(LO_TCP_MSS(h),__LAST_MIN_TCP_MSS(h)) -# define __MAX_TCP_MSS(h) MAX(LO_TCP_MSS(h),__LAST_MAX_TCP_MSS(h)) -# else -# define __MIN_TCP_MSS(h) LO_TCP_MSS(h) -# define __MAX_TCP_MSS(h) LO_TCP_MSS(h) -# endif -# undef __LAST_MIN_TCP_MSS -# undef __LAST_MAX_TCP_MSS -# define __LAST_MIN_TCP_MSS(h) __MIN_TCP_MSS(h) -# define __LAST_MAX_TCP_MSS(h) __MAX_TCP_MSS(h) +# undef __MIN_TCP_MSS +# undef __MAX_TCP_MSS +# define __MIN_TCP_MSS(h) MIN(LO_TCP_MSS(h),__6LOWPAN_MIN_TCP_MSS(h)) +# define __MAX_TCP_MSS(h) MAX(LO_TCP_MSS(h),__6LOWPAN_MAX_TCP_MSS(h)) +# define __LOOP_MIN_TCP_MSS(h) MIN(LO_TCP_MSS(h),__6LOWPAN_MIN_TCP_MSS(h)) +# define __LOOP_MAX_TCP_MSS(h) MAX(LO_TCP_MSS(h),__6LOWPAN_MAX_TCP_MSS(h)) +# else +# define __LOOP_MIN_TCP_MSS(h) _6LOWPAN_MIN_TCP_MSS(h) +# define __LOOP_MAX_TCP_MSS(h) __6LOWPAN_MAX_TCP_MSS(h) # endif # ifdef CONFIG_NET_SLIP -# ifdef __LAST_MIN_TCP_MSS -# define __MIN_TCP_MSS(h) MIN(SLIP_TCP_MSS(h),__LAST_MIN_TCP_MSS(h)) -# define __MAX_TCP_MSS(h) MAX(SLIP_TCP_MSS(h),__LAST_MAX_TCP_MSS(h)) -# else -# define __MIN_TCP_MSS(h) SLIP_TCP_MSS(h) -# define __MAX_TCP_MSS(h) SLIP_TCP_MSS(h) -# endif -# undef __LAST_MIN_TCP_MSS -# undef __LAST_MAX_TCP_MSS -# define __LAST_MIN_TCP_MSS(h) __MIN_TCP_MSS(h) -# define __LAST_MAX_TCP_MSS(h) __MAX_TCP_MSS(h) -# endif - -# undef __LAST_MIN_TCP_MSS -# undef __LAST_MAX_TCP_MSS +# undef __MIN_TCP_MSS +# undef __MAX_TCP_MSS +# define __MIN_TCP_MSS(h) MIN(SLIP_TCP_MSS(h),__LOOP_MIN_TCP_MSS(h)) +# define __MAX_TCP_MSS(h) MAX(SLIP_TCP_MSS(h),__LOOP_MAX_TCP_MSS(h)) +# define __SLIP_MIN_TCP_MSS(h) MIN(SLIP_TCP_MSS(h),__LOOP_MIN_TCP_MSS(h)) +# define __SLIP_MAX_TCP_MSS(h) MAX(SLIP_TCP_MSS(h),__LOOP_MAX_TCP_MSS(h)) +# else +# define __SLIP_MIN_TCP_MSS(h) __LOOP_MIN_TCP_MSS(h) +# define __SLIP_MAX_TCP_MSS(h) __LOOP_MAX_TCP_MSS(h) +# endif #endif /* If IPv4 is supported, it will have the larger MSS. -- GitLab From 5a56d3cce729279884b2a46ef33bad3eba9c4ae6 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 1 Apr 2017 18:24:21 -0600 Subject: [PATCH 305/990] 6loWPAN: Change ordering of some operations so that the IOB is available at the time that headr compression is perfomed. --- net/sixlowpan/sixlowpan_framelist.c | 67 +++++++++++---------------- net/sixlowpan/sixlowpan_hc06.c | 8 ++-- net/sixlowpan/sixlowpan_hc1.c | 72 ++++++++++++++--------------- net/sixlowpan/sixlowpan_internal.h | 20 ++++---- 4 files changed, 78 insertions(+), 89 deletions(-) diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c index 35750b3ce7..62582bed1c 100644 --- a/net/sixlowpan/sixlowpan_framelist.c +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -100,8 +100,8 @@ * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ * * Input Parameters: - * ieee - Pointer to IEEE802.15.4 MAC driver structure. - * ipv6 - Pointer to the IPv6 header to "compress" + * ieee - Pointer to IEEE802.15.4 MAC driver structure. + * destip - Pointer to the IPv6 header to "compress" * * Returned Value: * None @@ -109,7 +109,7 @@ ****************************************************************************/ static void sixlowpan_compress_ipv6hdr(FAR struct ieee802154_driver_s *ieee, - FAR const struct ipv6_hdr_s *ipv6) + FAR const struct ipv6_hdr_s *destip) { /* Indicate the IPv6 dispatch and length */ @@ -118,7 +118,7 @@ static void sixlowpan_compress_ipv6hdr(FAR struct ieee802154_driver_s *ieee, /* Copy the IPv6 header and adjust pointers */ - memcpy(g_rimeptr + g_rime_hdrlen, ipv6, IPv6_HDRLEN); + memcpy(g_rimeptr + g_rime_hdrlen, destip, IPv6_HDRLEN); g_rime_hdrlen += IPv6_HDRLEN; g_uncomp_hdrlen += IPv6_HDRLEN; } @@ -161,12 +161,12 @@ static void sixlowpan_compress_ipv6hdr(FAR struct ieee802154_driver_s *ieee, int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, FAR const struct ipv6_hdr_s *destip, - FAR const void *buf, size_t len, + FAR const void *buf, size_t len, FAR const struct rimeaddr_s *destmac) { FAR struct iob_s *iob; int framer_hdrlen; - struct rimeaddr_s dest; + struct rimeaddr_s bcastmac; uint16_t outlen = 0; /* Initialize global data. Locking the network guarantees that we have @@ -211,13 +211,24 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, if (destmac == NULL) { - memset(&dest, 0, sizeof(struct rimeaddr_s)); - } - else - { - rimeaddr_copy(&dest, (FAR const struct rimeaddr_s *)destmac); + memset(&bcastmac, 0, sizeof(struct rimeaddr_s)); + destmac = &bcastmac; } + /* Pre-allocate the IOB to hold frame or the first fragment, waiting if + * necessary. + */ + + iob = iob_alloc(false); + DEBUGASSERT(iob != NULL); + + /* Initialize the IOB */ + + iob->io_flink = NULL; + iob->io_len = 0; + iob->io_offset = 0; + iob->io_pktlen = 0; + ninfo("Sending packet len %d\n", len); #ifndef CONFIG_NET_6LOWPAN_COMPRESSION_IPv6 @@ -226,9 +237,9 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, /* Try to compress the headers */ #if defined(CONFIG_NET_6LOWPAN_COMPRESSION_HC1) - sixlowpan_compresshdr_hc1(ieee, &dest); + sixlowpan_compresshdr_hc1(ieee, destip, destmac, iob); #elif defined(CONFIG_NET_6LOWPAN_COMPRESSION_HC06) - sixlowpan_compresshdr_hc06(ieee, &dest); + sixlowpan_compresshdr_hc06(ieee, destip, destmac, iob); #else # error No compression specified #endif @@ -243,7 +254,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, ninfo("Header of len %d\n", g_rime_hdrlen); - rimeaddr_copy(&g_pktaddrs[PACKETBUF_ADDR_RECEIVER], &dest); + rimeaddr_copy(&g_pktaddrs[PACKETBUF_ADDR_RECEIVER], destmac); /* Pre-calculate frame header length. */ @@ -279,20 +290,8 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, 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); - - /* Initialize the IOB */ - - iob->io_flink = NULL; - iob->io_len = 0; - iob->io_offset = 0; - iob->io_pktlen = 0; - /* Create 1st Fragment */ - /* Add the frame header */ + /* Add the frame header using the pre-allocated IOB. */ verify = sixlowpan_framecreate(ieee, iob, ieee->i_panid); DEBUGASSERT(verify == framer_hdrlen); @@ -434,19 +433,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, * and send in one frame. */ - /* Allocate an IOB to hold the frame, waiting if necessary. */ - - iob = iob_alloc(false); - DEBUGASSERT(iob != NULL); - - /* Initialize the IOB */ - - iob->io_flink = NULL; - iob->io_len = 0; - iob->io_offset = 0; - iob->io_pktlen = 0; - - /* Add the frame header */ + /* Add the frame header to the prealloated IOB. */ verify = sixlowpan_framecreate(ieee, iob, ieee->i_panid); DEBUGASSERT(vreify == framer_hdrlen); diff --git a/net/sixlowpan/sixlowpan_hc06.c b/net/sixlowpan/sixlowpan_hc06.c index d6668978d9..4293d68c48 100644 --- a/net/sixlowpan/sixlowpan_hc06.c +++ b/net/sixlowpan/sixlowpan_hc06.c @@ -203,8 +203,8 @@ void sixlowpan_hc06_initialize(void) * * Input Parameters: * ieee - A reference to the IEE802.15.4 network device state - * ipv6 - The IPv6 header to be compressed - * destaddr - L2 destination address, needed to compress the IP + * destip - The IPv6 header to be compressed + * destmac - L2 destination address, needed to compress the IP * destination field * iob - The IOB into which the compressed header should be saved. * @@ -214,7 +214,9 @@ void sixlowpan_hc06_initialize(void) ****************************************************************************/ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, - FAR struct rimeaddr_s *destaddr) + FAR const struct ipv6_hdr_s *destip, + FAR const struct rimeaddr_s *destmac, + FAR struct iob_s *iob) { /* REVISIT: To be provided */ } diff --git a/net/sixlowpan/sixlowpan_hc1.c b/net/sixlowpan/sixlowpan_hc1.c index 3078896921..c3b5be0899 100644 --- a/net/sixlowpan/sixlowpan_hc1.c +++ b/net/sixlowpan/sixlowpan_hc1.c @@ -114,8 +114,8 @@ * * Input Parmeters: * ieee - A reference to the IEE802.15.4 network device state - * ipv6 - The IPv6 header to be compressed - * destaddr - L2 destination address, needed to compress the IP + * destip - The IPv6 header to be compressed + * destmac - L2 destination address, needed to compress the IP * destination field * iob - The IOB into which the compressed header should be saved. * @@ -125,21 +125,21 @@ ****************************************************************************/ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, - FAR const struct ipv6_hdr_s *ipv6, - FAR const struct rimeaddr_s *destaddr, + FAR const struct ipv6_hdr_s *destip, + FAR const struct rimeaddr_s *destmac, FAR struct iob_s *iob) { FAR uint8_t *hc1 = RIME_HC1_PTR; /* Check if all the assumptions for full compression are valid */ - if (ipv6->vtc != 0x60 || ipv6->tcflow != 0 || ipv6->flow != 0 || - !sixlowpan_islinklocal(&ipv6->srcipaddr) || - !sixlowpan_ismacbased(&ipv6->srcipaddr, &ieee->i_rimeaddr) || - !sixlowpan_islinklocal(&ipv6->destipaddr) || - !sixlowpan_ismacbased(&ipv6->destipaddr, destaddr) || - (ipv6->proto != IP_PROTO_ICMP6 && ipv6->proto != IP_PROTO_UDP && - ipv6->proto != IP_PROTO_TCP)) + if (destip->vtc != 0x60 || destip->tcflow != 0 || destip->flow != 0 || + !sixlowpan_islinklocal(&destip->srcipaddr) || + !sixlowpan_ismacbased(&destip->srcipaddr, &ieee->i_rimeaddr) || + !sixlowpan_islinklocal(&destip->destipaddr) || + !sixlowpan_ismacbased(&destip->destipaddr, destmac) || + (destip->proto != IP_PROTO_ICMP6 && destip->proto != IP_PROTO_UDP && + destip->proto != IP_PROTO_TCP)) { /* IPV6 DISPATCH * Something cannot be compressed, use IPV6 DISPATCH, @@ -148,7 +148,7 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, *g_rimeptr = SIXLOWPAN_DISPATCH_IPV6; g_rime_hdrlen += SIXLOWPAN_IPV6_HDR_LEN; - memcpy(g_rimeptr + g_rime_hdrlen, ipv6, IPv6_HDRLEN); + memcpy(g_rimeptr + g_rime_hdrlen, destip, IPv6_HDRLEN); g_rime_hdrlen += IPv6_HDRLEN; g_uncomp_hdrlen += IPv6_HDRLEN; } @@ -161,13 +161,13 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, hc1[RIME_HC1_DISPATCH] = SIXLOWPAN_DISPATCH_HC1; g_uncomp_hdrlen += IPv6_HDRLEN; - switch (ipv6->proto) + switch (destip->proto) { case IP_PROTO_ICMP6: /* HC1 encoding and ttl */ hc1[RIME_HC1_ENCODING] = 0xfc; - hc1[RIME_HC1_TTL] = ipv6->ttl; + hc1[RIME_HC1_TTL] = destip->ttl; g_rime_hdrlen += SIXLOWPAN_HC1_HDR_LEN; break; @@ -176,7 +176,7 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, /* HC1 encoding and ttl */ hc1[RIME_HC1_ENCODING] = 0xfe; - hc1[RIME_HC1_TTL] = ipv6->ttl; + hc1[RIME_HC1_TTL] = destip->ttl; g_rime_hdrlen += SIXLOWPAN_HC1_HDR_LEN; break; #endif /* CONFIG_NET_TCP */ @@ -206,7 +206,7 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, /* HC_UDP encoding, ttl, src and dest ports, checksum */ hcudp[RIME_HC1_HC_UDP_UDP_ENCODING] = 0xe0; - hcudp[RIME_HC1_HC_UDP_TTL] = ipv6->ttl; + hcudp[RIME_HC1_HC_UDP_TTL] = destip->ttl; hcudp[RIME_HC1_HC_UDP_PORTS] = (uint8_t)((htons(udp->srcport) - SIXLOWPAN_UDP_PORT_MIN) << 4) + (uint8_t)((htons(udp->destport) - SIXLOWPAN_UDP_PORT_MIN)); @@ -221,7 +221,7 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, /* HC1 encoding and ttl */ hc1[RIME_HC1_ENCODING] = 0xfa; - hc1[RIME_HC1_TTL] = ipv6->ttl; + hc1[RIME_HC1_TTL] = destip->ttl; g_rime_hdrlen += SIXLOWPAN_HC1_HDR_LEN; } break; @@ -257,24 +257,24 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, int sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, uint16_t iplen) { - FAR struct ipv6_hdr_s *ipv6 = IPv6BUF(&ieee->i_dev); + FAR struct ipv6_hdr_s *destip = IPv6BUF(&ieee->i_dev); FAR uint8_t *hc1 = RIME_HC1_PTR; /* Format the IPv6 header in the device d_buf */ /* Set version, traffic clase, and flow label */ - ipv6->vtc = 0x60; /* Bits 0-3: version, bits 4-7: traffic class (MS) */ - ipv6->tcf = 0; /* Bits 0-3: traffic class (LS), 4-bits: flow label (MS) */ - ipv6->flow = 0; /* 16-bit flow label (LS) */ + destip->vtc = 0x60; /* Bits 0-3: version, bits 4-7: traffic class (MS) */ + destip->tcf = 0; /* Bits 0-3: traffic class (LS), 4-bits: flow label (MS) */ + destip->flow = 0; /* 16-bit flow label (LS) */ /* Use stateless auto-configuration to set source and destination IP * addresses. */ sixlowpan_ipfromrime(&g_pktaddrs[PACKETBUF_ADDR_SENDER], - &ipv6->srcipaddr); + &destip->srcipaddr); sixlowpan_ipfromrime(&g_pktaddrs[PACKETBUF_ADDR_RECEIVER], - &ipv6->destipaddr); + &destip->destipaddr); g_uncomp_hdrlen += IPv6_HDRLEN; /* len[], proto, and ttl depend on the encoding */ @@ -282,15 +282,15 @@ int sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, switch (hc1[RIME_HC1_ENCODING] & 0x06) { case SIXLOWPAN_HC1_NH_ICMP6: - ipv6->proto = IP_PROTO_ICMP6; - ipv6->ttl = hc1[RIME_HC1_TTL]; + destip->proto = IP_PROTO_ICMP6; + destip->ttl = hc1[RIME_HC1_TTL]; g_rime_hdrlen += SIXLOWPAN_HC1_HDR_LEN; break; #if CONFIG_NET_TCP case SIXLOWPAN_HC1_NH_TCP: - ipv6->proto = IP_PROTO_TCP; - ipv6->ttl = hc1[RIME_HC1_TTL]; + destip->proto = IP_PROTO_TCP; + destip->ttl = hc1[RIME_HC1_TTL]; g_rime_hdrlen += SIXLOWPAN_HC1_HDR_LEN; break; #endif /* CONFIG_NET_TCP */ @@ -301,7 +301,7 @@ int sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, FAR struct udp_hdr_s *udp = UDPIPv6BUF(&ieee->i_dev); FAR uint8_t *hcudp = RIME_HC1_HC_UDP_PTR; - ipv6->proto = IP_PROTO_UDP; + destip->proto = IP_PROTO_UDP; if ((hcudp[RIME_HC1_HC_UDP_HC1_ENCODING] & 0x01) != 0) { /* UDP header is compressed with HC_UDP */ @@ -315,7 +315,7 @@ int sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, /* IP TTL */ - ipv6->ttl = hcudp[RIME_HC1_HC_UDP_TTL]; + destip->ttl = hcudp[RIME_HC1_HC_UDP_TTL]; /* UDP ports, len, checksum */ @@ -347,25 +347,25 @@ int sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, { /* This is not a fragmented packet */ - ipv6->len[0] = 0; - ipv6->len[1] = ieee->i_dev.d_len - g_rime_hdrlen + /* REVISIT */ - g_uncomp_hdrlen - IPv6_HDRLEN; + destip->len[0] = 0; + destip->len[1] = ieee->i_dev.d_len - g_rime_hdrlen + /* REVISIT */ + g_uncomp_hdrlen - IPv6_HDRLEN; } else { /* This is a 1st fragment */ - ipv6->len[0] = (iplen - IPv6_HDRLEN) >> 8; - ipv6->len[1] = (iplen - IPv6_HDRLEN) & 0x00FF; + destip->len[0] = (iplen - IPv6_HDRLEN) >> 8; + destip->len[1] = (iplen - IPv6_HDRLEN) & 0x00FF; } /* length field in UDP header */ #if CONFIG_NET_UDP - if (ipv6->proto == IP_PROTO_UDP) + if (destip->proto == IP_PROTO_UDP) { FAR struct udp_hdr_s *udp = UDPIPv6BUF(&ieee->i_dev); - memcpy(&udp->udplen, &ipv6->len[0], 2); + memcpy(&udp->udplen, &destip->len[0], 2); } #endif diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index bd8929cbb5..514c5dae6e 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -416,7 +416,7 @@ struct iob_s; /* Forward reference */ * * Input Parameters: * dev - The IEEE802.15.4 MAC network driver interface. - * ipv6 - IPv6 plus TCP or UDP headers. + * destip - IPv6 plus TCP or UDP headers. * buf - Data to send * len - Length of data to send * raddr - The MAC address of the destination @@ -434,7 +434,7 @@ struct iob_s; /* Forward reference */ ****************************************************************************/ int sixlowpan_send(FAR struct net_driver_s *dev, - FAR const struct ipv6_hdr_s *ipv6, FAR const void *buf, + FAR const struct ipv6_hdr_s *destip, FAR const void *buf, size_t len, FAR const struct rimeaddr_s *raddr, uint16_t timeout); @@ -560,8 +560,8 @@ void sixlowpan_hc06_initialize(void); * * Input Parameters: * ieee - A reference to the IEE802.15.4 network device state - * ipv6 - The IPv6 header to be compressed - * destaddr - L2 destination address, needed to compress the IP + * destip - The IPv6 header to be compressed + * destmac - L2 destination address, needed to compress the IP * destination field * iob - The IOB into which the compressed header should be saved. * @@ -572,8 +572,8 @@ void sixlowpan_hc06_initialize(void); #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, - FAR const struct ipv6_hdr_s *ipv6, - FAR const struct rimeaddr_s *destaddr, + FAR const struct ipv6_hdr_s *destip, + FAR const struct rimeaddr_s *destmac, FAR struct iob_s *iob); #endif @@ -618,8 +618,8 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, * * Input Parmeters: * ieee - A reference to the IEE802.15.4 network device state - * ipv6 - The IPv6 header to be compressed - * destaddr - L2 destination address, needed to compress the IP + * destip - The IPv6 header to be compressed + * destmac - L2 destination address, needed to compress the IP * destination field * iob - The IOB into which the compressed header should be saved. * @@ -630,8 +630,8 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC1 void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, - FAR const struct ipv6_hdr_s *ipv6, - FAR const struct rimeaddr_s *destaddr, + FAR const struct ipv6_hdr_s *destip, + FAR const struct rimeaddr_s *destmac, FAR struct iob_s *iob); #endif -- GitLab From d16fc98c74fe273f3bca1b58f654e561649ec88f Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 2 Apr 2017 08:08:35 -0600 Subject: [PATCH 306/990] 6loWPAN: Add HC06 decompression logic; Remove outboard compressor hooks. --- include/nuttx/net/ip.h | 11 + include/nuttx/net/sixlowpan.h | 41 -- net/sixlowpan/Make.defs | 2 +- net/sixlowpan/sixlowpan_compressor.c | 79 ---- net/sixlowpan/sixlowpan_globals.c | 4 - net/sixlowpan/sixlowpan_hc06.c | 547 ++++++++++++++++++++++++++- net/sixlowpan/sixlowpan_internal.h | 9 +- 7 files changed, 554 insertions(+), 139 deletions(-) delete mode 100644 net/sixlowpan/sixlowpan_compressor.c diff --git a/include/nuttx/net/ip.h b/include/nuttx/net/ip.h index 6a07edd585..8a9c842244 100644 --- a/include/nuttx/net/ip.h +++ b/include/nuttx/net/ip.h @@ -526,6 +526,17 @@ bool net_ipv6addr_maskcmp(const net_ipv6addr_t addr1, const net_ipv6addr_t mask); #endif +/**************************************************************************** + * Function: net_ipv6addr_prefixcmp + * + * Description: + * Compare two IPv6 address prefixes. + * + ****************************************************************************/ + +#define net_ipv6addr_prefixcmp(addr1, addr2, length) \ + (memcmp(addr1, addr2, length >> 3) == 0) + /**************************************************************************** * Function: net_ipaddr_mask * diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index 9cfa3e0973..21fac9b2ca 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -477,30 +477,6 @@ struct ieee802154_driver_s #endif /* CONFIG_NET_6LOWPAN_FRAG */ }; -/* The structure of a next header compressor. This compressor is provided - * by architecture-specific logic outside of the network stack. - * - * TODO: needs more parameters when compressing extension headers, etc. - */ - -struct sixlowpan_nhcompressor_s -{ - CODE int (*is_compressable)(uint8_t next_header); - - /* Compress next header (TCP/UDP, etc) - ptr points to next header to - * compress. - */ - - CODE int (*compress)(FAR uint8_t *compressed, FAR uint8_t *uncompressed_len); - - /* Uncompress next header (TCP/UDP, etc) - ptr points to next header to - * uncompress. - */ - - CODE int (*uncompress)(FAR uint8_t *compressed, FAR uint8_t *lowpanbuf, - FAR uint8_t *uncompressed_len); -}; - /**************************************************************************** * Public Function Prototypes ****************************************************************************/ @@ -560,21 +536,4 @@ struct sixlowpan_nhcompressor_s int sixlowpan_input(FAR struct ieee802154_driver_s *ieee); -/**************************************************************************** - * Function: sixlowpan_set_compressor - * - * Description: - * Configure to use the architecture-specific compressor. - * - * Input parameters: - * compressor - A reference to the new compressor to be used. This may - * be a NULL value to disable the compressor. - * - * Returned Value: - * None - * - ****************************************************************************/ - -void sixlowpan_set_compressor(FAR struct sixlowpan_nhcompressor_s *compressor); - #endif /* __INCLUDE_NUTTX_NET_SIXLOWOAN_H */ diff --git a/net/sixlowpan/Make.defs b/net/sixlowpan/Make.defs index 09fc742d39..d1faae0eac 100644 --- a/net/sixlowpan/Make.defs +++ b/net/sixlowpan/Make.defs @@ -41,7 +41,7 @@ ifeq ($(CONFIG_NET_6LOWPAN),y) NET_CSRCS += sixlowpan_initialize.c sixlowpan_globals.c sixlowpan_utils.c NET_CSRCS += sixlowpan_input.c sixlowpan_send.c sixlowpan_framer.c -NET_CSRCS += sixlowpan_framelist.c sixlowpan_compressor.c +NET_CSRCS += sixlowpan_framelist.c ifeq ($(CONFIG_NET_TCP),y) NET_CSRCS += sixlowpan_tcpsend.c diff --git a/net/sixlowpan/sixlowpan_compressor.c b/net/sixlowpan/sixlowpan_compressor.c deleted file mode 100644 index 7450e408e2..0000000000 --- a/net/sixlowpan/sixlowpan_compressor.c +++ /dev/null @@ -1,79 +0,0 @@ -/**************************************************************************** - * net/sixlowpan/sixlowpan_compressor.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include "nuttx/net/net.h" - -#include "sixlowpan/sixlowpan_internal.h" - -#ifdef CONFIG_NET_6LOWPAN - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Function: sixlowpan_set_compressor - * - * Description: - * Configure to use the architecture-specific compressor. - * - * Input parameters: - * compressor - A reference to the new compressor to be used. This may - * be a NULL value to disable the compressor. - * - * Returned Value: - * None - * - ****************************************************************************/ - -void sixlowpan_set_compressor(FAR struct sixlowpan_nhcompressor_s *compressor) -{ - /* Make sure that the compressor is not in use */ - - net_lock(); - - /* Then instantiate the new compressor */ - - g_sixlowpan_compressor = compressor; - net_unlock(); -} - -#endif /* CONFIG_NET_6LOWPAN */ diff --git a/net/sixlowpan/sixlowpan_globals.c b/net/sixlowpan/sixlowpan_globals.c index 6b0f5bcf74..2f9843022f 100644 --- a/net/sixlowpan/sixlowpan_globals.c +++ b/net/sixlowpan/sixlowpan_globals.c @@ -47,10 +47,6 @@ * Public Data ****************************************************************************/ -/* A pointer to the optional, architecture-specific compressor */ - -FAR struct sixlowpan_nhcompressor_s *g_sixlowpan_compressor; - /* The following data values are used to hold intermediate settings while * processing IEEE802.15.4 frames. These globals are shared with incoming * and outgoing frame processing and possibly with mutliple IEEE802.15.4 MAC diff --git a/net/sixlowpan/sixlowpan_hc06.c b/net/sixlowpan/sixlowpan_hc06.c index 4293d68c48..7e151f2c37 100644 --- a/net/sixlowpan/sixlowpan_hc06.c +++ b/net/sixlowpan/sixlowpan_hc06.c @@ -58,12 +58,26 @@ #include +#include +#include + #include +#include #include "sixlowpan/sixlowpan_internal.h" #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define IPv6BUF(ieee) \ + ((FAR struct ipv6_hdr_s *)&(ieee)->i_dev.d_buf) +#define UDPIPv6BUF(ieee) \ + ((FAR struct udp_hdr_s *)&(ieee)->i_dev.d_buf[IPv6_HDRLEN]) + /**************************************************************************** * Private Types ****************************************************************************/ @@ -83,7 +97,12 @@ struct sixlowpan_addrcontext_s * Private Data ****************************************************************************/ -/* HC06 specific variables */ +/* HC06 specific variables **************************************************/ +/* Use of global variables simplifies the logic and is safe in the multi- + * device environment because access is serialized via the network lock. + * + * But note that state may NOT be preserved from packet-to-packet. + */ #if CONFIG_NET_6LOWPAN_MAXADDRCONTEXT > 0 /* Addresses contexts for IPHC. */ @@ -92,6 +111,180 @@ static struct sixlowpan_addrcontext_s g_hc06_addrcontexts[CONFIG_NET_6LOWPAN_MAXADDRCONTEXT]; #endif +/* Pointer to the byte where to write next inline field. */ + +static FAR uint8_t *g_hc06ptr; + +/* Constant Data ************************************************************/ +/* Uncompression of linklocal + * + * 0 -> 16 bytes from packet + * 1 -> 2 bytes from prefix - bunch of zeroes and 8 from packet + * 2 -> 2 bytes from prefix - 0000::00ff:fe00:XXXX from packet + * 3 -> 2 bytes from prefix - infer 8 bytes from lladdr + * + * NOTE: => the uncompress function does change 0xf to 0x10 + * NOTE: 0x00 => no-autoconfig => unspecified + */ + +static const uint8_t g_unc_llconf[] = { 0x0f, 0x28, 0x22, 0x20 }; + +/* Uncompression of ctx-based + * + * 0 -> 0 bits from packet [unspecified / reserved] + * 1 -> 8 bytes from prefix - bunch of zeroes and 8 from packet + * 2 -> 8 bytes from prefix - 0000::00ff:fe00:XXXX + 2 from packet + * 3 -> 8 bytes from prefix - infer 8 bytes from lladdr + */ + +static const uint8_t g_unc_ctxconf[] = { 0x00, 0x88, 0x82, 0x80 }; + +/* Uncompression of ctx-based + * + * 0 -> 0 bits from packet + * 1 -> 2 bytes from prefix - bunch of zeroes 5 from packet + * 2 -> 2 bytes from prefix - zeroes + 3 from packet + * 3 -> 2 bytes from prefix - infer 1 bytes from lladdr + */ + +static const uint8_t g_unc_mxconf[] = { 0x0f, 0x25, 0x23, 0x21 }; + +/* Link local prefix */ + +static const uint8_t g_llprefix[] = { 0xfe, 0x80 }; + +/* TTL uncompression values */ + +static const uint8_t g_ttl_values[] = { 0, 1, 64, 255 }; + + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: find_addrcontext_bynumber + * + * Description: + * Find the address context with the given number. + * + ****************************************************************************/ + +static FAR struct sixlowpan_addrcontext_s * + find_addrcontext_bynumber(uint8_t number) +{ + /* Remove code to avoid warnings and save flash if no address context is + * used. + */ + +#if CONFIG_NET_6LOWPAN_MAXADDRCONTEXT > 0 + int i; + + for (i = 0; i < CONFIG_NET_6LOWPAN_MAXADDRCONTEXT; i++) + { + if ((g_hc06_addrcontexts[i].used == 1) && + g_hc06_addrcontexts[i].number == number) + { + return &g_hc06_addrcontexts[i]; + } + } +#endif /* CONFIG_NET_6LOWPAN_MAXADDRCONTEXT > 0 */ + + return NULL; +} + +/**************************************************************************** + * Name: find_addrcontext_bynumber + * + * Description: + * Find the address context corresponding to the prefix ipaddr. + * + ****************************************************************************/ + +static FAR struct sixlowpan_addrcontext_s * + find_addrcontext_byprefix(FAR net_ipv6addr_t *ipaddr) +{ +#if CONFIG_NET_6LOWPAN_MAXADDRCONTEXT > 0 + int i; + + /* Remove code to avoid warnings and save flash if no address context is used */ + + for (i = 0; i < CONFIG_NET_6LOWPAN_MAXADDRCONTEXT; i++) + { + if ((g_hc06_addrcontexts[i].used == 1) && + net_ipv6addr_prefixcmp(&g_hc06_addrcontexts[i].prefix, ipaddr, 64)) + { + return &g_hc06_addrcontexts[i]; + } + } +#endif /* CONFIG_NET_6LOWPAN_MAXADDRCONTEXT > 0 */ + + return NULL; +} + +/**************************************************************************** + * Name: uncompress_addr + * + * Description: + * Uncompress addresses based on a prefix and a postfix with zeroes in + * between. If the postfix is zero in length it will use the link address + * to configure the IP address (autoconf style). + * + * prefpost takes a byte where the first nibble specify prefix count + * and the second postfix count (NOTE: 15/0xf => 16 bytes copy). + * + ****************************************************************************/ + +static void uncompress_addr(FAR net_ipv6addr_t ipaddr, uint8_t const prefix[], + uint8_t prefpost, FAR struct rimeaddr_s *macaddr) +{ + uint8_t prefcount = prefpost >> 4; + uint8_t postcount = prefpost & 0x0f; + + /* Full nibble 15 => 16 */ + + prefcount = prefcount == 15 ? 16 : prefcount; + postcount = postcount == 15 ? 16 : postcount; + + if (prefcount > 0) + { + memcpy(ipaddr, prefix, prefcount); + } + + if (prefcount + postcount < 16) + { + FAR uint8_t *iptr = (FAR uint8_t *)&ipaddr[0]; + + memset(&iptr[prefcount], 0, 16 - (prefcount + postcount)); + } + + if (postcount > 0) + { + FAR uint8_t *iptr = (FAR uint8_t *)&ipaddr[0]; + + memcpy(&iptr[16 - postcount], g_hc06ptr, postcount); + if (postcount == 2 && prefcount < 11) + { + /* 16 bits uncompression => 0000:00ff:fe00:XXXX */ + + iptr[11] = 0xff; + iptr[12] = 0xfe; + } + + g_hc06ptr += postcount; + } + else if (prefcount > 0) + { + /* No IID based configuration if no prefix and no data => unspec */ + + sixlowpan_ipfromrime(macaddr, ipaddr); + } + + ninfo("Uncompressing %d + %d => %04x:%04x:%04x:%04x:%04x:%04x:%04x:%04x\n", + prefcount, postcount, ipaddr[0], ipaddr[2], ipaddr[3], ipaddr[5], + ipaddr[5], ipaddr[6], ipaddr[7]); +} + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -197,9 +390,9 @@ void sixlowpan_hc06_initialize(void) * | L4 data ... | * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ * - * NOTE: The g_addr_context number 00 is reserved for the link local prefix. - * For unicast addresses, if we cannot compress the prefix, we neither - * compress the IID. + * NOTE: The address context number 00 is reserved for the link local + * prefix. For unicast addresses, if we cannot compress the prefix, we + * neither compress the IID. * * Input Parameters: * ieee - A reference to the IEE802.15.4 network device state @@ -237,7 +430,7 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, * Input Parmeters: * ieee - A reference to the IEE802.15.4 network device state * iplen - Equal to 0 if the packet is not a fragment (IP length is then - * inferred from the L2 length), non 0 if the packet is a 1st + * inferred from the L2 length), non 0 if the packet is a first * fragment. * * Returned Value: @@ -248,8 +441,348 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, uint16_t iplen) { - /* REVISIT: To be provided */ -} + FAR struct ipv6_hdr_s *ipv6 = IPv6BUF(ieee); + FAR uint8_t *iphc = RIME_IPHC_BUF; + uint8_t iphc0; + uint8_t iphc1; + uint8_t tmp; + + /* At least two byte will be used for the encoding */ + + g_hc06ptr = g_rimeptr + g_rime_hdrlen + 2; + + iphc0 = iphc[0]; + iphc1 = iphc[1]; + + /* Another if the CID flag is set */ + + if (iphc1 & SIXLOWPAN_IPHC_CID) + { + ninfo("IPHC: CID flag set - increase header with one\n"); + g_hc06ptr++; + } + + /* Traffic class and flow label */ + + if ((iphc0 & SIXLOWPAN_IPHC_FL_C) == 0) + { + /* Flow label are carried inline */ + + if ((iphc0 & SIXLOWPAN_IPHC_TC_C) == 0) + { + /* Traffic class is carried inline */ + + memcpy(&ipv6->tcf, g_hc06ptr + 1, 3); + tmp = *g_hc06ptr; + g_hc06ptr += 4; + + /* hc06 format of tc is ECN | DSCP , original is DSCP | ECN */ + /* set version, pick highest DSCP bits and set in vtc */ + + ipv6->vtc = 0x60 | ((tmp >> 2) & 0x0f); + /* ECN rolled down two steps + lowest DSCP bits at top two bits */ + + ipv6->tcf = ((tmp >> 2) & 0x30) | (tmp << 6) | (ipv6->tcf & 0x0f); + } + else + { + /* Traffic class is compressed (set version and no TC) */ + + ipv6->vtc = 0x60; + + /* Highest flow label bits + ECN bits */ + + ipv6->tcf = (*g_hc06ptr & 0x0f) | ((*g_hc06ptr >> 2) & 0x30); + memcpy(&ipv6->flow, g_hc06ptr + 1, 2); + g_hc06ptr += 3; + } + } + else + { + /* Version is always 6! */ + /* Version and flow label are compressed */ + + if ((iphc0 & SIXLOWPAN_IPHC_TC_C) == 0) + { + /* Traffic class is inline */ + + ipv6->vtc = 0x60 | ((*g_hc06ptr >> 2) & 0x0f); + ipv6->tcf = ((*g_hc06ptr << 6) & 0xC0) | ((*g_hc06ptr >> 2) & 0x30); + ipv6->flow = 0; + g_hc06ptr += 1; + } + else + { + /* Traffic class is compressed */ + + ipv6->vtc = 0x60; + ipv6->tcf = 0; + ipv6->flow = 0; + } + } + + /* Next Header */ + + if ((iphc0 & SIXLOWPAN_IPHC_NH_C) == 0) + { + /* Next header is carried inline */ + + ipv6->proto = *g_hc06ptr; + ninfo("IPHC: next header inline: %d\n", ipv6->proto); + g_hc06ptr += 1; + } + + /* Hop limit */ + + if ((iphc0 & 0x03) != SIXLOWPAN_IPHC_TTL_I) + { + ipv6->ttl = g_ttl_values[iphc0 & 0x03]; + } + else + { + ipv6->ttl = *g_hc06ptr; + g_hc06ptr += 1; + } + + /* Put the source address compression mode SAM in the tmp var */ + + tmp = ((iphc1 & SIXLOWPAN_IPHC_SAM_11) >> SIXLOWPAN_IPHC_SAM_BIT) & 0x03; + + /* Address context based compression */ + + if (iphc1 & SIXLOWPAN_IPHC_SAC) + { + FAR struct sixlowpan_addrcontext_s *addrcontext; + uint8_t sci = (iphc1 & SIXLOWPAN_IPHC_CID) ? iphc[2] >> 4 : 0; + + /* Source address - check address context != NULL only if SAM bits are != 0 */ + + if (tmp != 0) + { + addrcontext = find_addrcontext_bynumber(sci); + if (addrcontext == NULL) + { + ninfo("sixlowpan uncompress_hdr: error address context not found\n"); + return; + } + } + + /* If tmp == 0 we do not have a Address context and therefore no prefix */ + + uncompress_addr(ipv6->srcipaddr, + tmp != 0 ? addrcontext->prefix : NULL, g_unc_ctxconf[tmp], + (FAR struct rimeaddr_s *)&g_pktaddrs[PACKETBUF_ADDR_SENDER]); + } + else + { + /* No compression and link local */ + + uncompress_addr(ipv6->srcipaddr, g_llprefix, g_unc_llconf[tmp], + (FAR struct rimeaddr_s *)&g_pktaddrs[PACKETBUF_ADDR_SENDER]); + } + + /* Destination address */ + /* put the destination address compression mode into tmp */ + + tmp = ((iphc1 & SIXLOWPAN_IPHC_DAM_11) >> SIXLOWPAN_IPHC_DAM_BIT) & 0x03; + + /* Multicast compression */ + + if (iphc1 & SIXLOWPAN_IPHC_M) + { + /* Address context based multicast compression */ + + if (iphc1 & SIXLOWPAN_IPHC_DAC) + { + /* TODO: implement this */ + } + else + { + /* non-address context based multicast compression + * + * DAM_00: 128 bits + * DAM_01: 48 bits FFXX::00XX:XXXX:XXXX + * DAM_10: 32 bits FFXX::00XX:XXXX + * DAM_11: 8 bits FF02::00XX + */ + + uint8_t prefix[] = { 0xff, 0x02 }; + if (tmp > 0 && tmp < 3) + { + prefix[1] = *g_hc06ptr; + g_hc06ptr++; + } + + uncompress_addr(ipv6->destipaddr, prefix, g_unc_mxconf[tmp], NULL); + } + } + else + { + /* no multicast */ + /* Context based */ + + if (iphc1 & SIXLOWPAN_IPHC_DAC) + { + FAR struct sixlowpan_addrcontext_s *addrcontext; + uint8_t dci = (iphc1 & SIXLOWPAN_IPHC_CID) ? iphc[2] & 0x0f : 0; + + addrcontext = find_addrcontext_bynumber(dci); + + /* All valid cases below need the address context! */ + + if (addrcontext == NULL) + { + ninfo("sixlowpan uncompress_hdr: error address context not found\n"); + return; + } + + uncompress_addr(ipv6->destipaddr, addrcontext->prefix, g_unc_ctxconf[tmp], + (FAR struct rimeaddr_s *)&g_pktaddrs[PACKETBUF_ADDR_RECEIVER]); + } + else + { + /* Not address context based => link local M = 0, DAC = 0 - same as SAC */ + + uncompress_addr(ipv6->destipaddr, g_llprefix, g_unc_llconf[tmp], + (FAR struct rimeaddr_s *)&g_pktaddrs[PACKETBUF_ADDR_RECEIVER]); + } + } + + g_uncomp_hdrlen += IPv6_HDRLEN; + + /* Next header processing - continued */ + + if ((iphc0 & SIXLOWPAN_IPHC_NH_C)) + { + FAR struct udp_hdr_s *udp = UDPIPv6BUF(ieee); + + /* The next header is compressed, NHC is following */ + + if ((*g_hc06ptr & SIXLOWPAN_NHC_UDP_MASK) == SIXLOWPAN_NHC_UDP_ID) + { + uint8_t checksum_compressed; + + ipv6->proto = IP_PROTO_UDP; + checksum_compressed = *g_hc06ptr & SIXLOWPAN_NHC_UDP_CHECKSUMC; + + ninfo("IPHC: Incoming header value: %i\n", *g_hc06ptr); + + switch (*g_hc06ptr & SIXLOWPAN_NHC_UDP_CS_P_11) + { + case SIXLOWPAN_NHC_UDP_CS_P_00: + /* 1 byte for NHC, 4 byte for ports, 2 bytes chksum */ + + memcpy(&udp->srcport, g_hc06ptr + 1, 2); + memcpy(&udp->destport, g_hc06ptr + 3, 2); + + ninfo("IPHC: Uncompressed UDP ports (ptr+5): %x, %x\n", + htons(udp->srcport), + htons(udp->destport)); + + g_hc06ptr += 5; + break; + + case SIXLOWPAN_NHC_UDP_CS_P_01: + /* 1 byte for NHC + source 16bit inline, dest = 0xF0 + 8 bit + * inline + */ + + ninfo("IPHC: Decompressing destination\n"); + + memcpy(&udp->srcport, g_hc06ptr + 1, 2); + udp->destport = + htons(SIXLOWPAN_UDP_8_BIT_PORT_MIN + (*(g_hc06ptr + 3))); + + ninfo("IPHC: Uncompressed UDP ports (ptr+4): %x, %x\n", + htons(udp->srcport), + htons(udp->destport)); + + g_hc06ptr += 4; + break; + + case SIXLOWPAN_NHC_UDP_CS_P_10: + /* 1 byte for NHC + source = 0xF0 + 8bit inline, dest = 16 bit + * inline + */ + + ninfo("IPHC: Decompressing source\n"); + + udp->srcport = + htons(SIXLOWPAN_UDP_8_BIT_PORT_MIN + (*(g_hc06ptr + 1))); + memcpy(&udp->destport, g_hc06ptr + 2, 2); + + ninfo("IPHC: Uncompressed UDP ports (ptr+4): %x, %x\n", + htons(udp->srcport), + htons(udp->destport)); + + g_hc06ptr += 4; + break; + + case SIXLOWPAN_NHC_UDP_CS_P_11: + /* 1 byte for NHC, 1 byte for ports */ + + udp->srcport = + htons(SIXLOWPAN_UDP_4_BIT_PORT_MIN + + (*(g_hc06ptr + 1) >> 4)); + udp->destport = + htons(SIXLOWPAN_UDP_4_BIT_PORT_MIN + + ((*(g_hc06ptr + 1)) & 0x0F)); + ninfo("IPHC: Uncompressed UDP ports (ptr+2): %x, %x\n", + htons(udp->srcport), + htons(udp->destport)); + + g_hc06ptr += 2; + break; + + default: + nerr("ERROR: Error unsupported UDP compression\n"); + return; + } + + if (!checksum_compressed) + { + /* Has_checksum, default */ + + memcpy(&udp->udpchksum, g_hc06ptr, 2); + g_hc06ptr += 2; + ninfo("IPHC: sixlowpan uncompress_hdr: checksum included\n"); + } + else + { + nwarn("WARNING: checksum *NOT* included\n"); + } + + g_uncomp_hdrlen += UDP_HDRLEN; + } + } + + g_rime_hdrlen = g_hc06ptr - g_rimeptr; + + /* IP length field. */ + + if (iplen == 0) + { + /* This is not a fragmented packet */ + + ipv6->len[0] = 0; + ipv6->len[1] = ieee->i_dev.d_len - g_rime_hdrlen + g_uncomp_hdrlen - IPv6_HDRLEN; + } + else + { + /* This is a first fragment */ + + ipv6->len[0] = (iplen - IPv6_HDRLEN) >> 8; + ipv6->len[1] = (iplen - IPv6_HDRLEN) & 0x00ff; + } + + /* Length field in UDP header */ + + if (ipv6->proto == IP_PROTO_UDP) + { + FAR struct udp_hdr_s *udp = UDPIPv6BUF(ieee); + memcpy(&udp->udplen, &ipv6->len[0], 2); + } +} #endif /* CONFIG_NET_6LOWPAN_COMPRESSION_HC06 */ diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index 514c5dae6e..4b56f57aa5 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -335,11 +335,6 @@ struct frame802154_s * Public Data ****************************************************************************/ -/* A pointer to the optional, architecture-specific compressor */ - -struct sixlowpan_nhcompressor_s; /* Foward reference */ -extern FAR struct sixlowpan_nhcompressor_s *g_sixlowpan_compressor; - /* The following data values are used to hold intermediate settings while * processing IEEE802.15.4 frames. These globals are shared with incoming * and outgoing frame processing and possibly with mutliple IEEE802.15.4 MAC @@ -593,7 +588,7 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, * Input Parmeters: * ieee - A reference to the IEE802.15.4 network device state * iplen - Equal to 0 if the packet is not a fragment (IP length is then - * inferred from the L2 length), non 0 if the packet is a 1st + * inferred from the L2 length), non 0 if the packet is a first * fragment. * * Returned Value: @@ -650,7 +645,7 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, * Input Parameters: * ieee - A reference to the IEE802.15.4 network device state * iplen - Equal to 0 if the packet is not a fragment (IP length is then - * inferred from the L2 length), non 0 if the packet is a 1st + * inferred from the L2 length), non 0 if the packet is a first * fragment. * * Returned Value: -- GitLab From ec3c40d99d811089347f059c05b0cd1e3e80c62f Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 2 Apr 2017 10:06:31 -0600 Subject: [PATCH 307/990] 6loWPAN: Finishes port of Contiki HC06 compression logic --- include/nuttx/net/ip.h | 74 ++++- include/nuttx/net/sixlowpan.h | 71 ----- net/sixlowpan/sixlowpan_hc06.c | 461 ++++++++++++++++++++++++++--- net/sixlowpan/sixlowpan_hc1.c | 76 ++--- net/sixlowpan/sixlowpan_internal.h | 84 +++++- 5 files changed, 610 insertions(+), 156 deletions(-) diff --git a/include/nuttx/net/ip.h b/include/nuttx/net/ip.h index 8a9c842244..c7b606078b 100644 --- a/include/nuttx/net/ip.h +++ b/include/nuttx/net/ip.h @@ -483,7 +483,7 @@ EXTERN const net_ipv6addr_t g_ipv6_llnetmask; /* Netmask for local link addres #endif /**************************************************************************** - * Function: net_ipv4addr_maskcmp and net_ipv6addr_maskcmp + * Name: net_ipv4addr_maskcmp and net_ipv6addr_maskcmp * * Description: * Compare two IP addresses under a netmask. The mask is used to mask @@ -527,7 +527,7 @@ bool net_ipv6addr_maskcmp(const net_ipv6addr_t addr1, #endif /**************************************************************************** - * Function: net_ipv6addr_prefixcmp + * Name: net_ipv6addr_prefixcmp * * Description: * Compare two IPv6 address prefixes. @@ -538,7 +538,75 @@ bool net_ipv6addr_maskcmp(const net_ipv6addr_t addr1, (memcmp(addr1, addr2, length >> 3) == 0) /**************************************************************************** - * Function: net_ipaddr_mask + * Name: net_is_addr_loopback + * + * Description: + * Is Ithe Pv6 address a the loopback address? + * + ****************************************************************************/ + +#define net_is_addr_loopback(a) \ + ((a)[0] == 0 && (a)[1] == 0 && (a)[2] == 0 && (a)[3] == 0 && \ + (a)[4] == 0 && (a)[5] == 0 && (a)[6] == 0 && (a)[7] == 0x0001) + +/**************************************************************************** + * Name: net_is_addr_unspecified + * + * Description: + * Is Ithe Pv6 address the unspecified address? + * + ****************************************************************************/ + +#define net_is_addr_unspecified(a) \ + ((a)[0] == 0 && (a)[1] == 0 && (a)[2] == 0 && (a)[3] == 0 && \ + (a)[4] == 0 && (a)[5] == 0 && (a)[6] == 0 && (a)[7] == 0) + +/**************************************************************************** + * Name: net_is_addr_mcast + * + * Description: + * s address a multicast address? see RFC 3513. + * + ****************************************************************************/ + +#define net_is_addr_mcast(a) (((a)[0] & 0xff00) == 0xff00) + +/**************************************************************************** + * Name: net_is_addr_linklocal_allnodes_mcast + * + * Description: + * Is IPv6 address a the link local all-nodes multicast address? + * + ****************************************************************************/ + +#define net_is_addr_linklocal_allnodes_mcast(a) \ + ((a)[0] == 0xff02 && (a)[1] == 0 && (a)[2] == 0 && (a)[3] == 0 && \ + (a)[4] == 0 && (a)[5] == 0 && (a)[6] == 0 && (a)[7] == 0x0001) + +/**************************************************************************** + * Name: net_is_addr_linklocal_allrouters_mcast + * + * Description: + * Is IPv6 address a the link local all-routers multicast address? + * + ****************************************************************************/ + +#define net_is_addr_linklocal_allrouters_mcast(a) \ + ((a)[0] == 0xff02 && (a)[1] == 0 && (a)[2] == 0 && (a)[3] == 0 && \ + (a)[4] == 0 && (a)[5] == 0 && (a)[6] == 0 && (a)[7] == 0x0002) + +/**************************************************************************** + * Name: net_is_addr_linklocal + * + * Description: + * Checks whether the address a is link local. + * + ****************************************************************************/ + +#define net_is_addr_linklocal(a) ((a)[0] == 0xfe80) + +/**************************************************************************** + * Name: net_ipaddr_mask * * Description: * Mask out the network part of an IP address, given the address and diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index 21fac9b2ca..ebeb34933a 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -160,77 +160,6 @@ #define SIXLOWPAN_FRAG1_HDR_LEN 4 #define SIXLOWPAN_FRAGN_HDR_LEN 5 -/* Address compressibility test macros */ - -/* Check whether we can compress the IID in address 'a' to 16 bits. This is - * used for unicast addresses only, and is true if the address is on the - * format ::0000:00ff:fe00:XXXX - * - * NOTE: we currently assume 64-bits prefixes - */ - -#define SIXLOWPAN_IS_IID_16BIT_COMPRESSABLE(a) \ - ((((a)->u16[4]) == 0) && \ - // (((a)->u8[10]) == 0)&& \ - (((a)->u8[11]) == 0xff)&& \ - (((a)->u8[12]) == 0xfe)&& \ - (((a)->u8[13]) == 0)) - -/* Check whether the 9-bit group-id of the compressed multicast address is - * known. It is true if the 9-bit group is the all nodes or all routers - * group. Parameter 'a' is typed uint8_t * - */ - -#define SIXLOWPAN_IS_MCASTADDR_DECOMPRESSABLE(a) \ - (((*a & 0x01) == 0) && \ - ((*(a + 1) == 0x01) || (*(a + 1) == 0x02))) - -/* Check whether the 112-bit group-id of the multicast address is mappable - * to a 9-bit group-id. It is true if the group is the all nodes or all - * routers group. - */ - -#define SIXLOWPAN_IS_MCASTADDR_COMPRESSABLE(a) \ - ((((a)->u16[1]) == 0) && \ - (((a)->u16[2]) == 0) && \ - (((a)->u16[3]) == 0) && \ - (((a)->u16[4]) == 0) && \ - (((a)->u16[5]) == 0) && \ - (((a)->u16[6]) == 0) && \ - (((a)->u8[14]) == 0) && \ - ((((a)->u8[15]) == 1) || (((a)->u8[15]) == 2))) - -/* FFXX::00XX:XXXX:XXXX */ - -#define SIXLOWPAN_IS_MCASTADDR_COMPRESSABLE48(a) \ - ((((a)->u16[1]) == 0) && \ - (((a)->u16[2]) == 0) && \ - (((a)->u16[3]) == 0) && \ - (((a)->u16[4]) == 0) && \ - (((a)->u8[10]) == 0)) - -/* FFXX::00XX:XXXX */ - -#define SIXLOWPAN_IS_MCASTADDR_COMPRESSABLE32(a) \ - ((((a)->u16[1]) == 0) && \ - (((a)->u16[2]) == 0) && \ - (((a)->u16[3]) == 0) && \ - (((a)->u16[4]) == 0) && \ - (((a)->u16[5]) == 0) && \ - (((a)->u8[12]) == 0)) - -/* FF02::00XX */ - -#define SIXLOWPAN_IS_MCASTADDR_COMPRESSABLE8(a) \ - ((((a)->u8[1]) == 2) && \ - (((a)->u16[1]) == 0) && \ - (((a)->u16[2]) == 0) && \ - (((a)->u16[3]) == 0) && \ - (((a)->u16[4]) == 0) && \ - (((a)->u16[5]) == 0) && \ - (((a)->u16[6]) == 0) && \ - (((a)->u8[14]) == 0)) - /* This maximum size of an IEEE802.15.4 frame. Certain, non-standard * devices may exceed this value, however. */ diff --git a/net/sixlowpan/sixlowpan_hc06.c b/net/sixlowpan/sixlowpan_hc06.c index 7e151f2c37..270c6f6885 100644 --- a/net/sixlowpan/sixlowpan_hc06.c +++ b/net/sixlowpan/sixlowpan_hc06.c @@ -121,7 +121,7 @@ static FAR uint8_t *g_hc06ptr; * 0 -> 16 bytes from packet * 1 -> 2 bytes from prefix - bunch of zeroes and 8 from packet * 2 -> 2 bytes from prefix - 0000::00ff:fe00:XXXX from packet - * 3 -> 2 bytes from prefix - infer 8 bytes from lladdr + * 3 -> 2 bytes from prefix - infer 8 bytes from MAC address * * NOTE: => the uncompress function does change 0xf to 0x10 * NOTE: 0x00 => no-autoconfig => unspecified @@ -134,7 +134,7 @@ static const uint8_t g_unc_llconf[] = { 0x0f, 0x28, 0x22, 0x20 }; * 0 -> 0 bits from packet [unspecified / reserved] * 1 -> 8 bytes from prefix - bunch of zeroes and 8 from packet * 2 -> 8 bytes from prefix - 0000::00ff:fe00:XXXX + 2 from packet - * 3 -> 8 bytes from prefix - infer 8 bytes from lladdr + * 3 -> 8 bytes from prefix - infer 8 bytes from MAC address */ static const uint8_t g_unc_ctxconf[] = { 0x00, 0x88, 0x82, 0x80 }; @@ -144,7 +144,7 @@ static const uint8_t g_unc_ctxconf[] = { 0x00, 0x88, 0x82, 0x80 }; * 0 -> 0 bits from packet * 1 -> 2 bytes from prefix - bunch of zeroes 5 from packet * 2 -> 2 bytes from prefix - zeroes + 3 from packet - * 3 -> 2 bytes from prefix - infer 1 bytes from lladdr + * 3 -> 2 bytes from prefix - infer 1 bytes from MAC address */ static const uint8_t g_unc_mxconf[] = { 0x0f, 0x25, 0x23, 0x21 }; @@ -202,7 +202,7 @@ static FAR struct sixlowpan_addrcontext_s * ****************************************************************************/ static FAR struct sixlowpan_addrcontext_s * - find_addrcontext_byprefix(FAR net_ipv6addr_t *ipaddr) + find_addrcontext_byprefix(FAR const net_ipv6addr_t ipaddr) { #if CONFIG_NET_6LOWPAN_MAXADDRCONTEXT > 0 int i; @@ -222,6 +222,45 @@ static FAR struct sixlowpan_addrcontext_s * return NULL; } +/**************************************************************************** + * Name: uncompress_addr + * + * Description: + * Uncompress addresses based on a prefix and a postfix with zeroes in + * between. If the postfix is zero in length it will use the link address + * to configure the IP address (autoconf style). + * + * prefpost takes a byte where the first nibble specify prefix count + * and the second postfix count (NOTE: 15/0xf => 16 bytes copy). + * + ****************************************************************************/ + +static uint8_t compress_addr_64(FAR const net_ipv6addr_t ipaddr, + FAR const struct rimeaddr_s *macaddr, + uint8_t bitpos) +{ + if (sixlowpan_ismacbased(ipaddr, macaddr)) + { + return 3 << bitpos; /* 0-bits */ + } + else if (SIXLOWPAN_IS_IID_16BIT_COMPRESSABLE(ipaddr)) + { + /* Compress IID to 16 bits xxxx::0000:00ff:fe00:XXXX */ + + memcpy(g_hc06ptr, &ipaddr[7], 2); + g_hc06ptr += 2; + return 2 << bitpos; /* 16-bits */ + } + else + { + /* Do not compress IID => xxxx::IID */ + + memcpy(g_hc06ptr, &ipaddr[4], 8); + g_hc06ptr += 8; + return 1 << bitpos; /* 64-bits */ + } +} + /**************************************************************************** * Name: uncompress_addr * @@ -367,8 +406,7 @@ void sixlowpan_hc06_initialize(void) * Compress IP/UDP header * * This function is called by the 6lowpan code to create a compressed - * 6lowpan packet in the packetbuf buffer from a full IPv6 packet in the - * uip_buf buffer. + * 6lowpan packet in the frame buffer from a full IPv6 packet. * * HC-06 (draft-ietf-6lowpan-hc, version 6) * http://tools.ietf.org/html/draft-ietf-6lowpan-hc-06 @@ -395,11 +433,11 @@ void sixlowpan_hc06_initialize(void) * neither compress the IID. * * Input Parameters: - * ieee - A reference to the IEE802.15.4 network device state - * destip - The IPv6 header to be compressed - * destmac - L2 destination address, needed to compress the IP - * destination field - * iob - The IOB into which the compressed header should be saved. + * ieee - A reference to the IEE802.15.4 network device state + * ipv6 - The IPv6 header to be compressed + * destmac - L2 destination address, needed to compress the IP + * destination field + * iob - The IOB into which the compressed header should be saved. * * Returned Value: * None @@ -407,11 +445,370 @@ void sixlowpan_hc06_initialize(void) ****************************************************************************/ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, - FAR const struct ipv6_hdr_s *destip, + FAR const struct ipv6_hdr_s *ipv6, FAR const struct rimeaddr_s *destmac, FAR struct iob_s *iob) { - /* REVISIT: To be provided */ + FAR uint8_t *iphc = RIME_IPHC_BUF; + FAR struct sixlowpan_addrcontext_s *addrcontext; + uint8_t iphc0; + uint8_t iphc1; + uint8_t tmp; + + ninfodumpbuffer("IPv6 before compression", ipv6, sizeof(ipv6_hdr_s)); + + g_hc06ptr = g_rimeptr + 2; + + /* As we copy some bit-length fields, in the IPHC encoding bytes, + * we sometimes use |= + * If the field is 0, and the current bit value in memory is 1, + * this does not work. We therefore reset the IPHC encoding here + */ + + iphc0 = SIXLOWPAN_DISPATCH_IPHC; + iphc1 = 0; + iphc[2] = 0; /* Might not be used - but needs to be cleared */ + + /* Address handling needs to be made first since it might cause an extra + * byte with [ SCI | DCI ] + */ + + /* Check if dest address context exists (for allocating third byte) + * + * TODO: fix this so that it remembers the looked up values for avoiding two + * lookups - or set the lookup values immediately + */ + + if (find_addrcontext_byprefix(ipv6->destipaddr) != NULL || + find_addrcontext_byprefix(ipv6->srcipaddr) != NULL) + { + /* set address context flag and increase g_hc06ptr */ + + ninfo("Decompressing dest or src ipaddr. Setting CID\n"); + iphc1 |= SIXLOWPAN_IPHC_CID; + g_hc06ptr++; + } + + /* Traffic class, flow label + * + * If flow label is 0, compress it. If traffic class is 0, compress it + * We have to process both in the same time as the offset of traffic class + * depends on the presence of version and flow label + */ + + /* hc06 format of tc is ECN | DSCP , original is DSCP | ECN */ + + tmp = (ipv6->vtc << 4) | (ipv6->tcf >> 4); + tmp = ((tmp & 0x03) << 6) | (tmp >> 2); + + if (((ipv6->tcf & 0x0f) == 0) && (ipv6->flow == 0)) + { + /* Flow label can be compressed */ + + iphc0 |= SIXLOWPAN_IPHC_FL_C; + if (((ipv6->vtc & 0x0f) == 0) && ((ipv6->tcf & 0xf0) == 0)) + { + /* Compress (elide) all */ + + iphc0 |= SIXLOWPAN_IPHC_TC_C; + } + else + { + /* Sompress only the flow label */ + + *g_hc06ptr = tmp; + g_hc06ptr += 1; + } + } + else + { + /* Flow label cannot be compressed */ + + if (((ipv6->vtc & 0x0f) == 0) && ((ipv6->tcf & 0xF0) == 0)) + { + /* Compress only traffic class */ + + iphc0 |= SIXLOWPAN_IPHC_TC_C; + *g_hc06ptr = (tmp & 0xc0) | (ipv6->tcf & 0x0f); + memcpy(g_hc06ptr + 1, &ipv6->flow, 2); + g_hc06ptr += 3; + } + else + { + /* Compress nothing */ + + memcpy(g_hc06ptr, &ipv6->vtc, 4); + + /* But replace the top byte with the new ECN | DSCP format */ + + *g_hc06ptr = tmp; + g_hc06ptr += 4; + } + } + + /* Note that the payload length is always compressed */ + + /* Next header. We compress it if UDP */ + +#if CONFIG_NET_UDP || UIP_CONF_ROUTER + if (ipv6->proto == IP_PROTO_UDP) + { + iphc0 |= SIXLOWPAN_IPHC_NH_C; + } +#endif /* CONFIG_NET_UDP */ + + if ((iphc0 & SIXLOWPAN_IPHC_NH_C) == 0) + { + *g_hc06ptr = ipv6->proto; + g_hc06ptr += 1; + } + + /* Hop limit + * + * if 1: compress, encoding is 01 + * if 64: compress, encoding is 10 + * if 255: compress, encoding is 11 + * else do not compress + */ + + switch (ipv6->ttl) + { + case 1: + iphc0 |= SIXLOWPAN_IPHC_TTL_1; + break; + + case 64: + iphc0 |= SIXLOWPAN_IPHC_TTL_64; + break; + + case 255: + iphc0 |= SIXLOWPAN_IPHC_TTL_255; + break; + + default: + *g_hc06ptr = ipv6->ttl; + g_hc06ptr += 1; + break; + } + + /* Source address - cannot be multicast */ + + if (net_is_addr_unspecified(ipv6->srcipaddr)) + { + ninfo("Compressing unspecified. Setting SAC\n"); + + iphc1 |= SIXLOWPAN_IPHC_SAC; + iphc1 |= SIXLOWPAN_IPHC_SAM_00; + } + else if ((addrcontext = find_addrcontext_byprefix(ipv6->srcipaddr)) != NULL) + { + /* Elide the prefix - indicate by CID and set address context + SAC */ + + ninfo("Compressing src with address context. Setting CID and SAC context: %d\n", + addrcontext->number); + + iphc1 |= SIXLOWPAN_IPHC_CID | SIXLOWPAN_IPHC_SAC; + iphc[2] |= addrcontext->number << 4; + + /* Compession compare with this nodes address (source) */ + + iphc1 |= compress_addr_64(ipv6->srcipaddr, &ieee->i_nodeaddr, + SIXLOWPAN_IPHC_SAM_BIT); + + /* No address context found for this address */ + } + else if (net_is_addr_linklocal(ipv6->srcipaddr) && + ipv6->destipaddr[1] == 0 && ipv6->destipaddr[2] == 0 && + ipv6->destipaddr[3] == 0) + { + iphc1 |= compress_addr_64(ipv6->srcipaddr, &ieee->i_nodeaddr, + SIXLOWPAN_IPHC_SAM_BIT); + } + else + { + /* Send the full address => SAC = 0, SAM = 00 */ + + iphc1 |= SIXLOWPAN_IPHC_SAM_00; /* 128-bits */ + memcpy(g_hc06ptr, ipv6->srcipaddr, 16); + g_hc06ptr += 16; + } + + /* Destination address */ + + if (net_is_addr_mcast(ipv6->destipaddr)) + { + /* Address is multicast, try to compress */ + + iphc1 |= SIXLOWPAN_IPHC_M; + if (SIXLOWPAN_IS_MCASTADDR_COMPRESSABLE8(ipv6->destipaddr)) + { + iphc1 |= SIXLOWPAN_IPHC_DAM_11; + + /* Use last byte */ + + *g_hc06ptr = ipv6->destipaddr[7] & 0x00ff; + g_hc06ptr += 1; + } + else if (SIXLOWPAN_IS_MCASTADDR_COMPRESSABLE32(ipv6->destipaddr)) + { + FAR uint8_t *iptr = (FAR uint8_t *)ipv6->destipaddr; + + iphc1 |= SIXLOWPAN_IPHC_DAM_10; + + /* Second byte + the last three */ + + *g_hc06ptr = iptr[1]; + memcpy(g_hc06ptr + 1, &iptr[13], 3); + g_hc06ptr += 4; + } + else if (SIXLOWPAN_IS_MCASTADDR_COMPRESSABLE48(ipv6->destipaddr)) + { + FAR uint8_t *iptr = (FAR uint8_t *)ipv6->destipaddr; + + iphc1 |= SIXLOWPAN_IPHC_DAM_01; + + /* Second byte + the last five */ + + *g_hc06ptr = iptr[1]; + memcpy(g_hc06ptr + 1, &iptr[11], 5); + g_hc06ptr += 6; + } + else + { + iphc1 |= SIXLOWPAN_IPHC_DAM_00; + + /* Full address */ + + memcpy(g_hc06ptr, ipv6->destipaddr, 16); + g_hc06ptr += 16; + } + } + else + { + /* Address is unicast, try to compress */ + + if ((addrcontext = find_addrcontext_byprefix(ipv6->destipaddr)) != NULL) + { + /* Elide the prefix */ + + iphc1 |= SIXLOWPAN_IPHC_DAC; + iphc[2] |= addrcontext->number; + + /* Compession compare with link adress (destination) */ + + iphc1 |= compress_addr_64(ipv6->destipaddr, destmac, + SIXLOWPAN_IPHC_DAM_BIT); + + /* No address context found for this address */ + } + else if (net_is_addr_linklocal(ipv6->destipaddr) && + ipv6->destipaddr[1] == 0 && ipv6->destipaddr[2] == 0 && + ipv6->destipaddr[3] == 0) + { + iphc1 |= compress_addr_64(ipv6->destipaddr, destmac, + SIXLOWPAN_IPHC_DAM_BIT); + } + else + { + /* Send the full address */ + + iphc1 |= SIXLOWPAN_IPHC_DAM_00; /* 128-bits */ + memcpy(g_hc06ptr, ipv6->destipaddr, 16); + g_hc06ptr += 16; + } + } + + g_uncomp_hdrlen = IPv6_HDRLEN; + +#if CONFIG_NET_UDP + /* UDP header compression */ + + if (ipv6->proto == IP_PROTO_UDP) + { + FAR struct udp_hdr_s *udp = UDPIPv6BUF(ieee); + + ninfo("Uncompressed UDP ports on send side: %x, %x\n", + ntohs(udp->srcport), ntohs(udp->destport)); + + /* Mask out the last 4 bits can be used as a mask */ + + if (((ntohs(udp->srcport) & 0xfff0) == SIXLOWPAN_UDP_4_BIT_PORT_MIN) && + ((ntohs(udp->destport) & 0xfff0) == SIXLOWPAN_UDP_4_BIT_PORT_MIN)) + { + /* We can compress 12 bits of both source and dest */ + + *g_hc06ptr = SIXLOWPAN_NHC_UDP_CS_P_11; + + ninfo("Remove 12b of both source & dest with prefix 0xfob\n"); + + *(g_hc06ptr + 1) = + (uint8_t)((ntohs(udp->srcport) - SIXLOWPAN_UDP_4_BIT_PORT_MIN) << 4) + + (uint8_t)((ntohs(udp->destport) - SIXLOWPAN_UDP_4_BIT_PORT_MIN)); + + g_hc06ptr += 2; + } + else if ((ntohs(udp->destport) & 0xff00) == + SIXLOWPAN_UDP_8_BIT_PORT_MIN) + { + /* We can compress 8 bits of dest, leave source. */ + + *g_hc06ptr = SIXLOWPAN_NHC_UDP_CS_P_01; + + ninfo("Leave source, remove 8 bits of dest with prefix 0xF0\n"); + + memcpy(g_hc06ptr + 1, &udp->srcport, 2); + *(g_hc06ptr + 3) = + (uint8_t) ((ntohs(udp->destport) - + SIXLOWPAN_UDP_8_BIT_PORT_MIN)); + g_hc06ptr += 4; + } + else if ((ntohs(udp->srcport) & 0xff00) == + SIXLOWPAN_UDP_8_BIT_PORT_MIN) + { + /* We can compress 8 bits of src, leave dest. Copy compressed port */ + + *g_hc06ptr = SIXLOWPAN_NHC_UDP_CS_P_10; + + ninfo("Remove 8 bits of source with prefix 0xF0, leave dest. hch: %u\n", + *g_hc06ptr); + + *(g_hc06ptr + 1) = + (uint8_t)((ntohs(udp->srcport) - SIXLOWPAN_UDP_8_BIT_PORT_MIN)); + + memcpy(g_hc06ptr + 2, &udp->destport, 2); + g_hc06ptr += 4; + } + else + { + /* we cannot compress. Copy uncompressed ports, full checksum */ + + *g_hc06ptr = SIXLOWPAN_NHC_UDP_CS_P_00; + + nwarn("WARNING: Cannot compress headers\n"); + + memcpy(g_hc06ptr + 1, &udp->srcport, 4); + g_hc06ptr += 5; + } + + /* Always inline the checksum */ + + if (1) + { + memcpy(g_hc06ptr, &udp->udpchksum, 2); + g_hc06ptr += 2; + } + + g_uncomp_hdrlen += UDP_HDRLEN; + } +#endif /* CONFIG_NET_UDP */ + + /* Before the g_rime_hdrlen operation */ + + iphc[0] = iphc0; + iphc[1] = iphc1; + + g_rime_hdrlen = g_hc06ptr - g_rimeptr; + return; } /**************************************************************************** @@ -529,7 +926,7 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, /* Next header is carried inline */ ipv6->proto = *g_hc06ptr; - ninfo("IPHC: next header inline: %d\n", ipv6->proto); + ninfo("Next header inline: %d\n", ipv6->proto); g_hc06ptr += 1; } @@ -563,7 +960,7 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, addrcontext = find_addrcontext_bynumber(sci); if (addrcontext == NULL) { - ninfo("sixlowpan uncompress_hdr: error address context not found\n"); + nerr("ERROR: Address context not found\n"); return; } } @@ -633,7 +1030,7 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, if (addrcontext == NULL) { - ninfo("sixlowpan uncompress_hdr: error address context not found\n"); + ninfo("ERROR: Address context not found\n"); return; } @@ -666,7 +1063,7 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, ipv6->proto = IP_PROTO_UDP; checksum_compressed = *g_hc06ptr & SIXLOWPAN_NHC_UDP_CHECKSUMC; - ninfo("IPHC: Incoming header value: %i\n", *g_hc06ptr); + ninfo("Incoming header value: %i\n", *g_hc06ptr); switch (*g_hc06ptr & SIXLOWPAN_NHC_UDP_CS_P_11) { @@ -676,9 +1073,8 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, memcpy(&udp->srcport, g_hc06ptr + 1, 2); memcpy(&udp->destport, g_hc06ptr + 3, 2); - ninfo("IPHC: Uncompressed UDP ports (ptr+5): %x, %x\n", - htons(udp->srcport), - htons(udp->destport)); + ninfo("Uncompressed UDP ports (ptr+5): %x, %x\n", + htons(udp->srcport), htons(udp->destport)); g_hc06ptr += 5; break; @@ -688,15 +1084,14 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, * inline */ - ninfo("IPHC: Decompressing destination\n"); + ninfo("Decompressing destination\n"); memcpy(&udp->srcport, g_hc06ptr + 1, 2); udp->destport = htons(SIXLOWPAN_UDP_8_BIT_PORT_MIN + (*(g_hc06ptr + 3))); - ninfo("IPHC: Uncompressed UDP ports (ptr+4): %x, %x\n", - htons(udp->srcport), - htons(udp->destport)); + ninfo("Uncompressed UDP ports (ptr+4): %x, %x\n", + htons(udp->srcport), htons(udp->destport)); g_hc06ptr += 4; break; @@ -706,15 +1101,14 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, * inline */ - ninfo("IPHC: Decompressing source\n"); + ninfo("Decompressing source\n"); udp->srcport = htons(SIXLOWPAN_UDP_8_BIT_PORT_MIN + (*(g_hc06ptr + 1))); memcpy(&udp->destport, g_hc06ptr + 2, 2); - ninfo("IPHC: Uncompressed UDP ports (ptr+4): %x, %x\n", - htons(udp->srcport), - htons(udp->destport)); + ninfo("Uncompressed UDP ports (ptr+4): %x, %x\n", + htons(udp->srcport), htons(udp->destport)); g_hc06ptr += 4; break; @@ -727,10 +1121,10 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, (*(g_hc06ptr + 1) >> 4)); udp->destport = htons(SIXLOWPAN_UDP_4_BIT_PORT_MIN + - ((*(g_hc06ptr + 1)) & 0x0F)); - ninfo("IPHC: Uncompressed UDP ports (ptr+2): %x, %x\n", - htons(udp->srcport), - htons(udp->destport)); + ((*(g_hc06ptr + 1)) & 0x0f)); + + ninfo("Uncompressed UDP ports (ptr+2): %x, %x\n", + htons(udp->srcport), htons(udp->destport)); g_hc06ptr += 2; break; @@ -746,7 +1140,8 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, memcpy(&udp->udpchksum, g_hc06ptr, 2); g_hc06ptr += 2; - ninfo("IPHC: sixlowpan uncompress_hdr: checksum included\n"); + + ninfo("Checksum included\n"); } else { diff --git a/net/sixlowpan/sixlowpan_hc1.c b/net/sixlowpan/sixlowpan_hc1.c index c3b5be0899..fd45280ea0 100644 --- a/net/sixlowpan/sixlowpan_hc1.c +++ b/net/sixlowpan/sixlowpan_hc1.c @@ -113,11 +113,11 @@ * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ * * Input Parmeters: - * ieee - A reference to the IEE802.15.4 network device state - * destip - The IPv6 header to be compressed - * destmac - L2 destination address, needed to compress the IP - * destination field - * iob - The IOB into which the compressed header should be saved. + * ieee - A reference to the IEE802.15.4 network device state + * ipv6 - The IPv6 header to be compressed + * destmac - L2 destination address, needed to compress the IP + * destination field + * iob - The IOB into which the compressed header should be saved. * * Returned Value: * None @@ -125,7 +125,7 @@ ****************************************************************************/ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, - FAR const struct ipv6_hdr_s *destip, + FAR const struct ipv6_hdr_s *ipv6, FAR const struct rimeaddr_s *destmac, FAR struct iob_s *iob) { @@ -133,13 +133,13 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, /* Check if all the assumptions for full compression are valid */ - if (destip->vtc != 0x60 || destip->tcflow != 0 || destip->flow != 0 || - !sixlowpan_islinklocal(&destip->srcipaddr) || - !sixlowpan_ismacbased(&destip->srcipaddr, &ieee->i_rimeaddr) || - !sixlowpan_islinklocal(&destip->destipaddr) || - !sixlowpan_ismacbased(&destip->destipaddr, destmac) || - (destip->proto != IP_PROTO_ICMP6 && destip->proto != IP_PROTO_UDP && - destip->proto != IP_PROTO_TCP)) + if (ipv6->vtc != 0x60 || ipv6->tcflow != 0 || ipv6->flow != 0 || + !sixlowpan_islinklocal(&ipv6->srcipaddr) || + !sixlowpan_ismacbased(&ipv6->srcipaddr, &ieee->i_rimeaddr) || + !sixlowpan_islinklocal(&ipv6->destipaddr) || + !sixlowpan_ismacbased(&ipv6->destipaddr, destmac) || + (ipv6->proto != IP_PROTO_ICMP6 && ipv6->proto != IP_PROTO_UDP && + ipv6->proto != IP_PROTO_TCP)) { /* IPV6 DISPATCH * Something cannot be compressed, use IPV6 DISPATCH, @@ -148,7 +148,7 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, *g_rimeptr = SIXLOWPAN_DISPATCH_IPV6; g_rime_hdrlen += SIXLOWPAN_IPV6_HDR_LEN; - memcpy(g_rimeptr + g_rime_hdrlen, destip, IPv6_HDRLEN); + memcpy(g_rimeptr + g_rime_hdrlen, ipv6, IPv6_HDRLEN); g_rime_hdrlen += IPv6_HDRLEN; g_uncomp_hdrlen += IPv6_HDRLEN; } @@ -161,13 +161,13 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, hc1[RIME_HC1_DISPATCH] = SIXLOWPAN_DISPATCH_HC1; g_uncomp_hdrlen += IPv6_HDRLEN; - switch (destip->proto) + switch (ipv6->proto) { case IP_PROTO_ICMP6: /* HC1 encoding and ttl */ hc1[RIME_HC1_ENCODING] = 0xfc; - hc1[RIME_HC1_TTL] = destip->ttl; + hc1[RIME_HC1_TTL] = ipv6->ttl; g_rime_hdrlen += SIXLOWPAN_HC1_HDR_LEN; break; @@ -176,7 +176,7 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, /* HC1 encoding and ttl */ hc1[RIME_HC1_ENCODING] = 0xfe; - hc1[RIME_HC1_TTL] = destip->ttl; + hc1[RIME_HC1_TTL] = ipv6->ttl; g_rime_hdrlen += SIXLOWPAN_HC1_HDR_LEN; break; #endif /* CONFIG_NET_TCP */ @@ -206,7 +206,7 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, /* HC_UDP encoding, ttl, src and dest ports, checksum */ hcudp[RIME_HC1_HC_UDP_UDP_ENCODING] = 0xe0; - hcudp[RIME_HC1_HC_UDP_TTL] = destip->ttl; + hcudp[RIME_HC1_HC_UDP_TTL] = ipv6->ttl; hcudp[RIME_HC1_HC_UDP_PORTS] = (uint8_t)((htons(udp->srcport) - SIXLOWPAN_UDP_PORT_MIN) << 4) + (uint8_t)((htons(udp->destport) - SIXLOWPAN_UDP_PORT_MIN)); @@ -221,7 +221,7 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, /* HC1 encoding and ttl */ hc1[RIME_HC1_ENCODING] = 0xfa; - hc1[RIME_HC1_TTL] = destip->ttl; + hc1[RIME_HC1_TTL] = ipv6->ttl; g_rime_hdrlen += SIXLOWPAN_HC1_HDR_LEN; } break; @@ -257,24 +257,24 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, int sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, uint16_t iplen) { - FAR struct ipv6_hdr_s *destip = IPv6BUF(&ieee->i_dev); + FAR struct ipv6_hdr_s *ipv6 = IPv6BUF(&ieee->i_dev); FAR uint8_t *hc1 = RIME_HC1_PTR; /* Format the IPv6 header in the device d_buf */ /* Set version, traffic clase, and flow label */ - destip->vtc = 0x60; /* Bits 0-3: version, bits 4-7: traffic class (MS) */ - destip->tcf = 0; /* Bits 0-3: traffic class (LS), 4-bits: flow label (MS) */ - destip->flow = 0; /* 16-bit flow label (LS) */ + ipv6->vtc = 0x60; /* Bits 0-3: version, bits 4-7: traffic class (MS) */ + ipv6->tcf = 0; /* Bits 0-3: traffic class (LS), 4-bits: flow label (MS) */ + ipv6->flow = 0; /* 16-bit flow label (LS) */ /* Use stateless auto-configuration to set source and destination IP * addresses. */ sixlowpan_ipfromrime(&g_pktaddrs[PACKETBUF_ADDR_SENDER], - &destip->srcipaddr); + &ipv6->srcipaddr); sixlowpan_ipfromrime(&g_pktaddrs[PACKETBUF_ADDR_RECEIVER], - &destip->destipaddr); + &ipv6->destipaddr); g_uncomp_hdrlen += IPv6_HDRLEN; /* len[], proto, and ttl depend on the encoding */ @@ -282,15 +282,15 @@ int sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, switch (hc1[RIME_HC1_ENCODING] & 0x06) { case SIXLOWPAN_HC1_NH_ICMP6: - destip->proto = IP_PROTO_ICMP6; - destip->ttl = hc1[RIME_HC1_TTL]; + ipv6->proto = IP_PROTO_ICMP6; + ipv6->ttl = hc1[RIME_HC1_TTL]; g_rime_hdrlen += SIXLOWPAN_HC1_HDR_LEN; break; #if CONFIG_NET_TCP case SIXLOWPAN_HC1_NH_TCP: - destip->proto = IP_PROTO_TCP; - destip->ttl = hc1[RIME_HC1_TTL]; + ipv6->proto = IP_PROTO_TCP; + ipv6->ttl = hc1[RIME_HC1_TTL]; g_rime_hdrlen += SIXLOWPAN_HC1_HDR_LEN; break; #endif /* CONFIG_NET_TCP */ @@ -301,7 +301,7 @@ int sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, FAR struct udp_hdr_s *udp = UDPIPv6BUF(&ieee->i_dev); FAR uint8_t *hcudp = RIME_HC1_HC_UDP_PTR; - destip->proto = IP_PROTO_UDP; + ipv6->proto = IP_PROTO_UDP; if ((hcudp[RIME_HC1_HC_UDP_HC1_ENCODING] & 0x01) != 0) { /* UDP header is compressed with HC_UDP */ @@ -315,7 +315,7 @@ int sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, /* IP TTL */ - destip->ttl = hcudp[RIME_HC1_HC_UDP_TTL]; + ipv6->ttl = hcudp[RIME_HC1_HC_UDP_TTL]; /* UDP ports, len, checksum */ @@ -347,25 +347,25 @@ int sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, { /* This is not a fragmented packet */ - destip->len[0] = 0; - destip->len[1] = ieee->i_dev.d_len - g_rime_hdrlen + /* REVISIT */ - g_uncomp_hdrlen - IPv6_HDRLEN; + ipv6->len[0] = 0; + ipv6->len[1] = ieee->i_dev.d_len - g_rime_hdrlen + /* REVISIT */ + g_uncomp_hdrlen - IPv6_HDRLEN; } else { /* This is a 1st fragment */ - destip->len[0] = (iplen - IPv6_HDRLEN) >> 8; - destip->len[1] = (iplen - IPv6_HDRLEN) & 0x00FF; + ipv6->len[0] = (iplen - IPv6_HDRLEN) >> 8; + ipv6->len[1] = (iplen - IPv6_HDRLEN) & 0x00FF; } /* length field in UDP header */ #if CONFIG_NET_UDP - if (destip->proto == IP_PROTO_UDP) + if (ipv6->proto == IP_PROTO_UDP) { FAR struct udp_hdr_s *udp = UDPIPv6BUF(&ieee->i_dev); - memcpy(&udp->udplen, &destip->len[0], 2); + memcpy(&udp->udplen, &ipv6->len[0], 2); } #endif diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index 4b56f57aa5..dff37cf6f8 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -89,7 +89,7 @@ * The fragment header is used when the payload is too large to fit in a * single IEEE 802.15.4 frame. The fragment header contains three fields: * Datagram size, datagram tag and datagram offset. - * + * * 1. Datagram size describes the total (un-fragmented) payload. * 2. Datagram tag identifies the set of fragments and is used to match * fragments of the same payload. @@ -225,6 +225,68 @@ #define FRAME_SIZE(ieee,iob) \ ((iob)->io_len) +/* Address compressibility test macros **************************************/ + +/* Check whether we can compress the IID in address 'a' to 16 bits. This is + * used for unicast addresses only, and is true if the address is on the + * format ::0000:00ff:fe00:XXXX + * + * NOTE: we currently assume 64-bits prefixes + */ + +/* Check whether we can compress the IID in address 'a' to 16 bits. This is + * used for unicast addresses only, and is true if the address is on the + * format ::0000:00ff:fe00:XXXX. + * + * NOTE: we currently assume 64-bits prefixes. Big-endian, network order is + * assumed. + */ + +#define SIXLOWPAN_IS_IID_16BIT_COMPRESSABLE(a) \ + ((((a)[4]) == 0x0000) && (((a)[5]) == 0x00ff) && (((a)[6]) == 0xfe00)) + +/* Check whether the 9-bit group-id of the compressed multicast address is + * known. It is true if the 9-bit group is the all nodes or all routers + * group. Parameter 'a' is typed uint8_t * + */ + +#define SIXLOWPAN_IS_MCASTADDR_DECOMPRESSABLE(a) \ + (((*a & 0x01) == 0) && \ + ((*(a + 1) == 0x01) || (*(a + 1) == 0x02))) + +/* Check whether the 112-bit group-id of the multicast address is mappable + * to a 9-bit group-id. It is true if the group is the all nodes or all + * routers group: + * + * XXXX:0000:0000:0000:0000:0000:0000:0001 All nodes address + * XXXX:0000:0000:0000:0000:0000:0000:0002 All routers address + */ + +#define SIXLOWPAN_IS_MCASTADDR_COMPRESSABLE(a) \ + ((a)[1] == 0 && (a)[2] == 0 && (a)[3] == 0 && \ + (a)[4] == 0 && (a)[5] == 0 && (a)[6] == 0 && \ + ((a)[7] == 0x0001 || (a)[7] == 0x0002)) + +/* FFXX:0000:0000:0000:0000:00XX:XXXX:XXXX */ + +#define SIXLOWPAN_IS_MCASTADDR_COMPRESSABLE48(a) \ + ((a)[1] == 0 && (a)[2] == 0 && (a)[3] == 0 && \ + (a)[4] == 0 && (((a)[5] & 0xff00) == 0)) + +/* FFXX:0000:0000:0000:0000:0000:00XX:XXXX */ + +#define SIXLOWPAN_IS_MCASTADDR_COMPRESSABLE32(a) \ + ((a)[1] == 0 && (a)[2] == 0 && (a)[3] == 0 && \ + (a)[4] == 0 && (a)[5] == 0 && ((a)[6] & 0xff00) == 0) + +/* FF02:0000:0000:0000:0000:0000:0000:00XX */ + +#define SIXLOWPAN_IS_MCASTADDR_COMPRESSABLE8(a) \ + ((((a)[0] & 0x00ff) == 0x0002) && \ + (a)[1] == 0 && (a)[2] == 0 && (a)[3] == 0 && \ + (a)[4] == 0 && (a)[5] == 0 && (a)[6] == 0 && \ + (((a)[7] & 0xff00) == 0x0000)) + /* General helper macros ****************************************************/ #define GETINT16(ptr,index) \ @@ -538,7 +600,7 @@ void sixlowpan_hc06_initialize(void); #endif /**************************************************************************** - * Name: sixlowpan_hc06_initialize + * Name: sixlowpan_compresshdr_hc06 * * Description: * Compress IP/UDP header @@ -555,7 +617,7 @@ void sixlowpan_hc06_initialize(void); * * Input Parameters: * ieee - A reference to the IEE802.15.4 network device state - * destip - The IPv6 header to be compressed + * ipv6 - The IPv6 header to be compressed * destmac - L2 destination address, needed to compress the IP * destination field * iob - The IOB into which the compressed header should be saved. @@ -567,13 +629,13 @@ void sixlowpan_hc06_initialize(void); #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, - FAR const struct ipv6_hdr_s *destip, + FAR const struct ipv6_hdr_s *ipv6, FAR const struct rimeaddr_s *destmac, FAR struct iob_s *iob); #endif /**************************************************************************** - * Name: sixlowpan_hc06_initialize + * Name: sixlowpan_uncompresshdr_hc06 * * Description: * Uncompress HC06 (i.e., IPHC and LOWPAN_UDP) headers and put them in @@ -612,11 +674,11 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, * uip_buf buffer. * * Input Parmeters: - * ieee - A reference to the IEE802.15.4 network device state - * destip - The IPv6 header to be compressed + * ieee - A reference to the IEE802.15.4 network device state + * ipv6 - The IPv6 header to be compressed * destmac - L2 destination address, needed to compress the IP - * destination field - * iob - The IOB into which the compressed header should be saved. + * destination field + * iob - The IOB into which the compressed header should be saved. * * Returned Value: * None @@ -625,7 +687,7 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC1 void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, - FAR const struct ipv6_hdr_s *destip, + FAR const struct ipv6_hdr_s *ipv6, FAR const struct rimeaddr_s *destmac, FAR struct iob_s *iob); #endif @@ -673,7 +735,7 @@ int sixlowpan_frame_hdralloc(FAR struct iob_s *iob, int size); * and sixlowpan_ismacbased * * Description: - * sixlowpan_ipfromrime: Create a link local IPv6 address from a rime + * sixlowpan_ipfromrime: Create a link local IPv6 address from a rime * address. * * sixlowpan_rimefromip: Extract the rime address from a link local IPv6 -- GitLab From 76406af71b0c9b63b924c5c0725a29f522eead6f Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 2 Apr 2017 11:15:46 -0600 Subject: [PATCH 308/990] 6loWPAN: Add support for sendto() --- net/devif/ipv6_input.c | 37 ++++++++- net/sixlowpan/sixlowpan.h | 37 ++++++++- net/sixlowpan/sixlowpan_udpsend.c | 134 ++++++++++++++++++++++++------ net/socket/send.c | 42 +++------- net/socket/sendto.c | 18 +++- net/tcp/tcp_input.c | 2 +- 6 files changed, 210 insertions(+), 60 deletions(-) diff --git a/net/devif/ipv6_input.c b/net/devif/ipv6_input.c index 149f06d33d..e1940bf4f0 100644 --- a/net/devif/ipv6_input.c +++ b/net/devif/ipv6_input.c @@ -255,12 +255,45 @@ int ipv6_input(FAR struct net_driver_s *dev) { #ifdef NET_TCP_HAVE_STACK case IP_PROTO_TCP: /* TCP input */ + /* Forward the IPv6 TCP packet */ + tcp_ipv6_input(dev); - break; + +#ifdef CONFIG_NET_6LOWPAN + /* TCP output comes through two different mechansims. Either from: + * + * 1. TCP socket output. For the case of TCP output to an + * IEEE802.15.4, the TCP output is caught in the socket + * send()/sendto() logic and and redirected to 6loWPAN logic. + * 2. TCP output from the TCP state machine. That will pass + * here and can be detected if d_len > 0. It will be redirected + * to 6loWPAN logic here. + */ + +#ifdef CONFIG_NET_MULTILINK + /* Handle the case where multiple link layer protocols are supported */ + + if (dev->d_len > 0 && dev->d_lltype == CONFIG_NET_6LOWPAN) +#else + if (dev->d_len > 0) #endif + { + /* Let 6loWPAN handle the TCP output */ + + sixlowpan_tcp_send(dev); + + /* Drop the packet in the d_buf */ + + goto drop; + } +#endif /* CONFIG_NET_6LOWPAN */ + break; +#endif /* NET_TCP_HAVE_STACK */ #ifdef NET_UDP_HAVE_STACK case IP_PROTO_UDP: /* UDP input */ + /* Forward the IPv6 UDP packet */ + udp_ipv6_input(dev); break; #endif @@ -269,6 +302,8 @@ int ipv6_input(FAR struct net_driver_s *dev) #ifdef CONFIG_NET_ICMPv6 case IP_PROTO_ICMP6: /* ICMP6 input */ + /* Forward the ICMPv6 packet */ + icmpv6_input(dev); break; #endif diff --git a/net/sixlowpan/sixlowpan.h b/net/sixlowpan/sixlowpan.h index d3660cb2ce..62a9074acf 100644 --- a/net/sixlowpan/sixlowpan.h +++ b/net/sixlowpan/sixlowpan.h @@ -53,7 +53,8 @@ * Public Function Prototypes ****************************************************************************/ -struct socket; /* Forward reference */ +struct socket; /* Forward reference */ +struct sockaddr; /* Forward reference */ /**************************************************************************** * Name: sixlowpan_initialize @@ -132,5 +133,39 @@ ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, size_t len); #endif +/**************************************************************************** + * Function: psock_6lowpan_udp_sendto + * + * Description: + * If sendto() is used on a connection-mode (SOCK_STREAM, SOCK_SEQPACKET) + * socket, the parameters to and 'tolen' are ignored (and the error EISCONN + * may be returned when they are not NULL and 0), and the error ENOTCONN is + * returned when the socket was not actually connected. + * + * Parameters: + * psock A pointer to a NuttX-specific, internal socket structure + * buf Data to send + * len Length of data to send + * flags Send flags + * to Address of recipient + * tolen The length of the address structure + * + * Returned Value: + * On success, returns the number of characters sent. On error, + * -1 is returned, and errno is set appropriately. Returned error + * number must be consistent with definition of errors reported by + * sendto(). + * + * Assumptions: + * Called with the network locked. + * + ****************************************************************************/ + +ssize_t psock_6lowpan_udp_sendto(FAR struct socket *psock, + FAR const void *buf, + size_t len, int flags, + FAR const struct sockaddr *to, + socklen_t tolen); + #endif /* CONFIG_NET_6LOWPAN */ #endif /* _NET_SIXLOWPAN_SIXLOWPAN_H */ diff --git a/net/sixlowpan/sixlowpan_udpsend.c b/net/sixlowpan/sixlowpan_udpsend.c index c0c3148b90..ae16a23355 100644 --- a/net/sixlowpan/sixlowpan_udpsend.c +++ b/net/sixlowpan/sixlowpan_udpsend.c @@ -39,6 +39,8 @@ #include +#include +#include #include #include #include @@ -57,21 +59,26 @@ ****************************************************************************/ /**************************************************************************** - * Function: psock_6lowpan_udp_send + * Function: psock_6lowpan_udp_sendto * * Description: - * psock_6lowpan_udp_send() call may be used with connectionlesss UDP - * sockets. + * If sendto() is used on a connection-mode (SOCK_STREAM, SOCK_SEQPACKET) + * socket, the parameters to and 'tolen' are ignored (and the error EISCONN + * may be returned when they are not NULL and 0), and the error ENOTCONN is + * returned when the socket was not actually connected. * * Parameters: - * psock - An instance of the internal socket structure. - * buf - Data to send - * len - Length of data to send + * psock A pointer to a NuttX-specific, internal socket structure + * buf Data to send + * len Length of data to send + * flags Send flags + * to Address of recipient + * tolen The length of the address structure * * Returned Value: * On success, returns the number of characters sent. On error, - * -1 is returned, and errno is set appropriately. Returned error numbers - * must be consistent with definition of errors reported by send() or + * -1 is returned, and errno is set appropriately. Returned error + * number must be consistent with definition of errors reported by * sendto(). * * Assumptions: @@ -79,9 +86,13 @@ * ****************************************************************************/ -ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, - size_t len) +ssize_t psock_6lowpan_udp_sendto(FAR struct socket *psock, + FAR const void *buf, + size_t len, int flags, + FAR const struct sockaddr *to, + socklen_t tolen) { + FAR struct sockaddr_in6 *to6 = (FAR struct sockaddr_in6 *)to; FAR struct udp_conn_s *conn; FAR struct net_driver_s *dev; struct ipv6udp_hdr_s ipv6udp; @@ -89,24 +100,28 @@ ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, uint16_t timeout; int ret; - DEBUGASSERT(psock != NULL && psock->s_crefs > 0); + DEBUGASSERT(psock != NULL && psock->s_crefs > 0 && to != NULL); DEBUGASSERT(psock->s_type == SOCK_DGRAM); - /* Make sure that this is a valid socket */ + if (psock == NULL || to == NULL) + { + return (ssize_t)-EINVAL; + } - if (psock != NULL || psock->s_crefs <= 0) + /* Make sure that this is a datagram valid socket */ + + if (psock->s_crefs <= 0 || psock->s_type != SOCK_DGRAM) { nerr("ERROR: Invalid socket\n"); return (ssize_t)-EBADF; } - /* Was the UDP socket connected via connect()? */ + /* Make sure that the destination address is valid */ - if (psock->s_type != SOCK_DGRAM || !_SS_ISCONNECTED(psock->s_flags)) + if (to6->sin6_family != AF_INET6 || tolen < sizeof(struct sockaddr_in6)) { - /* No, then it is not legal to call send() with this socket. */ - - return -ENOTCONN; + nerr("ERROR: Invalid destination address\n"); + return (ssize_t)-EAFNOSUPPORT; } /* Get the underlying UDP "connection" structure */ @@ -114,7 +129,6 @@ ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, conn = (FAR struct udp_conn_s *)psock->s_conn; DEBUGASSERT(conn != NULL); -#if defined(CONFIG_NET_IPv4) && defined(CONFIG_NET_IPv6) /* Ignore if not IPv6 domain */ if (conn->domain != PF_INET6) @@ -122,12 +136,12 @@ ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, nwarn("WARNING: Not IPv6\n"); return (ssize_t)-EPROTOTYPE; } -#endif /* Route outgoing message to the correct device */ #ifdef CONFIG_NETDEV_MULTINIC - dev = netdev_findby_ipv6addr(conn->u.ipv6.laddr, conn->u.ipv6.raddr); + dev = netdev_findby_ipv6addr(conn->u.ipv6.laddr, + to6->sin6_addr.in6_u.u6_addr16); #ifdef CONFIG_NETDEV_MULTILINK if (dev == NULL || dev->d_lltype != NET_LL_IEEE802154) #else @@ -138,7 +152,7 @@ ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, return (ssize_t)-ENETUNREACH; } #else - dev = netdev_findby_ipv6addr(conn->u.ipv6.raddr); + dev = netdev_findby_ipv6addr(to6->sin6_addr.in6_u.u6_addr16); #ifdef CONFIG_NETDEV_MULTILINK if (dev == NULL || dev->d_lltype != NET_LL_IEEE802154) #else @@ -153,7 +167,7 @@ ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, #ifdef CONFIG_NET_ICMPv6_NEIGHBOR /* Make sure that the IP address mapping is in the Neighbor Table */ - ret = icmpv6_neighbor(conn->u.ipv6.raddr); + ret = icmpv6_neighbor(to6->sin6_addr.in6_u.u6_addr16); if (ret < 0) { nerr("ERROR: Not reachable\n"); @@ -172,7 +186,7 @@ ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, * of the MAC address in the IPv6 address. */ - sixlowpan_rimefromip(conn->u.ipv6.raddr, &destmac); + sixlowpan_rimefromip(to6->sin6_addr.in6_u.u6_addr16, &destmac); /* If routable, then call sixlowpan_send() to format and send the 6loWPAN * packet. @@ -197,4 +211,76 @@ ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, return ret; } +/**************************************************************************** + * Function: psock_6lowpan_udp_send + * + * Description: + * psock_6lowpan_udp_send() call may be used with connectionlesss UDP + * sockets. + * + * Parameters: + * psock - An instance of the internal socket structure. + * buf - Data to send + * len - Length of data to send + * + * Returned Value: + * On success, returns the number of characters sent. On error, + * -1 is returned, and errno is set appropriately. Returned error numbers + * must be consistent with definition of errors reported by send(). + * + * Assumptions: + * Called with the network locked. + * + ****************************************************************************/ + +ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, + size_t len) +{ + FAR struct udp_conn_s *conn; + struct sockaddr_in6 to; + + DEBUGASSERT(psock != NULL && psock->s_crefs > 0); + DEBUGASSERT(psock->s_type == SOCK_DGRAM); + + /* Make sure that this is a valid socket */ + + if (psock != NULL || psock->s_crefs <= 0) + { + nerr("ERROR: Invalid socket\n"); + return (ssize_t)-EBADF; + } + + /* Was the UDP socket connected via connect()? */ + + if (psock->s_type != SOCK_DGRAM || !_SS_ISCONNECTED(psock->s_flags)) + { + /* No, then it is not legal to call send() with this socket. */ + + return -ENOTCONN; + } + + /* Get the underlying UDP "connection" structure */ + + conn = (FAR struct udp_conn_s *)psock->s_conn; + DEBUGASSERT(conn != NULL); + + /* Ignore if not IPv6 domain */ + + if (conn->domain != PF_INET6) + { + nwarn("WARNING: Not IPv6\n"); + return (ssize_t)-EPROTOTYPE; + } + + /* Create the 'to' address */ + + to.sin6_family = AF_INET6; + to.sin6_port = conn->rport; /* Already network order */ + memcpy(to.sin6_addr.in6_u.u6_addr16, conn->u.ipv6.raddr, 16); + + return psock_6lowpan_udp_sendto(psock, buf, len, 0, + (FAR const struct sockaddr *)&to, + sizeof(struct sockaddr_in6)); +} + #endif /* CONFIG_NET_6LOWPAN && CONFIG_NET_UDP */ diff --git a/net/socket/send.c b/net/socket/send.c index fb50549e86..2e805b4eaf 100644 --- a/net/socket/send.c +++ b/net/socket/send.c @@ -1,7 +1,7 @@ /**************************************************************************** * net/socket/send.c * - * Copyright (C) 2007-2014, 2016 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2014, 2016-2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -166,29 +166,18 @@ ssize_t psock_send(FAR struct socket *psock, FAR const void *buf, size_t len, ret = psock_6lowpan_tcp_send(psock, buf, len); -#ifdef CONFIG_NETDEV_MULTINIC +#if defined(CONFIG_NETDEV_MULTINIC) && defined(NET_TCP_HAVE_STACK) if (ret < 0) { /* TCP/IP packet send */ ret = psock_tcp_send(psock, buf, len); -#ifdef NET_TCP_HAVE_STACK - ret = psock_tcp_send(psock, buf, len); -#else - ret = -ENOSYS; -#endif } - -#endif /* CONFIG_NETDEV_MULTINIC */ -#else /* CONFIG_NET_6LOWPAN */ - - /* Only TCP/IP packet send */ - -#ifdef NET_TCP_HAVE_STACK - ret = psock_tcp_send(psock, buf, len); +#endif /* CONFIG_NETDEV_MULTINIC && NET_TCP_HAVE_STACK */ +#elif defined(NET_TCP_HAVE_STACK) + nsent = psock_tcp_send(psock, buf, len, flags, to, tolen); #else - ret = -ENOSYS; -#endif + nsent = -ENOSYS; #endif /* CONFIG_NET_6LOWPAN */ } #endif /* CONFIG_NET_TCP */ @@ -215,34 +204,25 @@ ssize_t psock_send(FAR struct socket *psock, FAR const void *buf, size_t len, else #endif { -#ifdef CONFIG_NET_6LOWPAN +#if defined(CONFIG_NET_6LOWPAN) /* Try 6loWPAN UDP packet send */ ret = psock_6lowpan_udp_send(psock, buf, len); -#ifdef CONFIG_NETDEV_MULTINIC +#if defined(CONFIG_NETDEV_MULTINIC) && defined(NET_UDP_HAVE_STACK) if (ret < 0) { /* UDP/IP packet send */ ret = psock_udp_send(psock, buf, len); -#ifdef NET_UDP_HAVE_STACK - ret = psock_udp_send(psock, buf, len); -#else - ret = -ENOSYS; -#endif } - -#endif /* CONFIG_NETDEV_MULTINIC */ -#else /* CONFIG_NET_6LOWPAN */ - +#endif /* CONFIG_NETDEV_MULTINIC && NET_UDP_HAVE_STACK */ +#elif defined(NET_UDP_HAVE_STACK) /* Only UDP/IP packet send */ - -#ifdef NET_UDP_HAVE_STACK + ret = psock_udp_send(psock, buf, len); #else ret = -ENOSYS; -#endif #endif /* CONFIG_NET_6LOWPAN */ } #endif /* CONFIG_NET_UDP */ diff --git a/net/socket/sendto.c b/net/socket/sendto.c index eba84f5cea..4c2798cd6c 100644 --- a/net/socket/sendto.c +++ b/net/socket/sendto.c @@ -49,6 +49,7 @@ #include #include "udp/udp.h" +#include "sixlowpan/sixlowpan.h" #include "local/local.h" #include "socket/socket.h" #include "usrsock/usrsock.h" @@ -237,11 +238,24 @@ ssize_t psock_sendto(FAR struct socket *psock, FAR const void *buf, else #endif { -#ifdef NET_UDP_HAVE_STACK +#if defined(CONFIG_NET_6LOWPAN) + /* Try 6loWPAN UDP packet sendto() */ + + nsent = psock_6lowpan_udp_sendto(psock, buf, len, flags, to, tolen); + +#if defined(CONFIG_NETDEV_MULTINIC) && defined(NET_UDP_HAVE_STACK) + if (nsent < 0) + { + /* UDP/IP packet sendto */ + + nsent = psock_udp_sendto(psock, buf, len, flags, to, tolen); + } +#endif /* CONFIG_NETDEV_MULTINIC && NET_UDP_HAVE_STACK */ +#elif defined(NET_UDP_HAVE_STACK) nsent = psock_udp_sendto(psock, buf, len, flags, to, tolen); #else nsent = -ENOSYS; -#endif +#endif /* CONFIG_NET_6LOWPAN */ } #endif /* CONFIG_NET_UDP */ diff --git a/net/tcp/tcp_input.c b/net/tcp/tcp_input.c index 184dfebb01..1918bd3492 100644 --- a/net/tcp/tcp_input.c +++ b/net/tcp/tcp_input.c @@ -2,7 +2,7 @@ * net/tcp/tcp_input.c * Handling incoming TCP input * - * Copyright (C) 2007-2014 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2014, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Adapted for NuttX from logic in uIP which also has a BSD-like license: -- GitLab From 663c48c329aa488c42d4fd9b47e46ca537267771 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 2 Apr 2017 12:01:04 -0600 Subject: [PATCH 309/990] 6loWPAN: Hook 6loWPAN output into path of output from TCP state machine. --- net/devif/ipv6_input.c | 1 + net/sixlowpan/sixlowpan.h | 32 +++++++- net/sixlowpan/sixlowpan_input.c | 128 ++++++++++-------------------- net/sixlowpan/sixlowpan_tcpsend.c | 84 +++++++++++++++++++- 4 files changed, 155 insertions(+), 90 deletions(-) diff --git a/net/devif/ipv6_input.c b/net/devif/ipv6_input.c index e1940bf4f0..d55b0739ad 100644 --- a/net/devif/ipv6_input.c +++ b/net/devif/ipv6_input.c @@ -95,6 +95,7 @@ #include "neighbor/neighbor.h" #include "tcp/tcp.h" #include "udp/udp.h" +#include "sixlowpan/sixlowpan.h" #include "pkt/pkt.h" #include "icmpv6/icmpv6.h" diff --git a/net/sixlowpan/sixlowpan.h b/net/sixlowpan/sixlowpan.h index 62a9074acf..c9f54154b5 100644 --- a/net/sixlowpan/sixlowpan.h +++ b/net/sixlowpan/sixlowpan.h @@ -53,8 +53,9 @@ * Public Function Prototypes ****************************************************************************/ -struct socket; /* Forward reference */ -struct sockaddr; /* Forward reference */ +struct net_driver_s; /* Forward reference */ +struct socket; /* Forward reference */ +struct sockaddr; /* Forward reference */ /**************************************************************************** * Name: sixlowpan_initialize @@ -105,6 +106,33 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, size_t len); #endif +/**************************************************************************** + * Function: sixlowpan_tcp_send + * + * Description: + * TCP output comes through two different mechansims. Either from: + * + * 1. TCP socket output. For the case of TCP output to an + * IEEE802.15.4, the TCP output is caught in the socket + * send()/sendto() logic and and redirected to psock_6lowpan_tcp_send(). + * 2. TCP output from the TCP state machine. That will occur + * during TCP packet processing by the TCP state meachine. It + * is detected there when ipv6_tcp_input() returns with d_len > 0. This + * will be redirected here. + * + * Parameters: + * dev - An instance of nework device state structure + * + * Returned Value: + * None + * + * Assumptions: + * Called with the network locked. + * + ****************************************************************************/ + +void sixlowpan_tcp_send(FAR struct net_driver_s *dev); + /**************************************************************************** * Function: psock_6lowpan_udp_send * diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index 882af91708..b89af933d8 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -91,91 +91,6 @@ * Public Functions ****************************************************************************/ -/**************************************************************************** - * Function: sixlowpan_isbroadcast - * - * Description: - * Return the address length associated with a 2-bit address mode - * - * Input parameters: - * addrmode - The address mode - * - * Returned Value: - * The address length associated with the address mode. - * - ****************************************************************************/ - -static bool sixlowpan_isbroadcast(uint8_t mode, FAR uint8_t *addr) -{ - int i = ((mode == FRAME802154_SHORTADDRMODE) ? 2 : 8); - - while (i-- > 0) - { - if (addr[i] != 0xff) - { - return false; - } - } - - return true; -} - -/**************************************************************************** - * Name: sixlowpan_set_pktattrs - * - * Description: - * Setup some packet buffer attributes - * - * Input Parameters: - * ieee - Pointer to IEEE802.15.4 MAC driver structure. - * ipv6 - Pointer to the IPv6 header to "compress" - * - * Returned Value: - * None - * - ****************************************************************************/ - -static void sixlowpan_set_pktattrs(FAR struct ieee802154_driver_s *ieee, - FAR const struct ipv6_hdr_s *ipv6) -{ - int attr = 0; - - /* Set protocol in NETWORK_ID */ - - g_pktattrs[PACKETBUF_ATTR_NETWORK_ID] = ipv6->proto; - - /* Assign values to the channel attribute (port or type + code) */ - - if (ipv6->proto == IP_PROTO_UDP) - { - FAR struct udp_hdr_s *udp = &((FAR struct ipv6udp_hdr_s *)ipv6)->udp; - - attr = udp->srcport; - if (udp->destport < attr) - { - attr = udp->destport; - } - } - else if (ipv6->proto == IP_PROTO_TCP) - { - FAR struct tcp_hdr_s *tcp = &((FAR struct ipv6tcp_hdr_s *)ipv6)->tcp; - - attr = tcp->srcport; - if (tcp->destport < attr) - { - attr = tcp->destport; - } - } - else if (ipv6->proto == IP_PROTO_ICMP6) - { - FAR struct icmpv6_iphdr_s *icmp = &((FAR struct ipv6icmp_hdr_s *)ipv6)->icmp; - - attr = icmp->type << 8 | icmp->code; - } - - g_pktattrs[PACKETBUF_ATTR_CHANNEL] = attr; -} - /**************************************************************************** * Name: sixlowpan_frame_process * @@ -691,7 +606,10 @@ int sixlowpan_input(FAR struct ieee802154_driver_s *ieee) if (ieee->i_dev.d_len > 0) { FAR struct ipv6_hdr_s *ipv6hdr; + FAR uint8_t *buffer; struct rimeaddr_s destmac; + size_t hdrlen; + size_t buflen; /* The IPv6 header followed by TCP or UDP headers should * lie at the beginning of d_buf since there is no link @@ -707,10 +625,46 @@ int sixlowpan_input(FAR struct ieee802154_driver_s *ieee) sixlowpan_rimefromip(ipv6hdr->destipaddr, &destmac); + /* The data payload should follow the IPv6 header plus + * the protocol header. + */ + + if (ipv6hdr->proto != IP_PROTO_TCP) + { + hdrlen = IPv6_HDRLEN + TCP_HDRLEN; + } + else if (ipv6hdr->proto != IP_PROTO_UDP) + { + hdrlen = IPv6_HDRLEN + UDP_HDRLEN; + } + else if (ipv6hdr->proto != IP_PROTO_ICMP6) + { + hdrlen = IPv6_HDRLEN + ICMPv6_HDRLEN; + } + else + { + nwarn("WARNING: Unsupported protoype: %u\n", + ipv6hdr->proto); + ret = -EPROTO; + goto drop; + } + + if (hdrlen < ieee->i_dev.d_len) + { + nwarn("WARNING: Packet to small: Have %u need >%u\n", + ieee->i_dev.d_len, hdrlen); + ret = -ENOBUFS; + goto drop; + } + /* Convert the outgoing packet into a frame list. */ - ret = sixlowpan_queue_frames(ieee, ipv6hdr, ieee->i_dev.d_buf, - ieee->i_dev.d_len, &destmac); + buffer = ieee->i_dev.d_buf + hdrlen; + buflen = ieee->i_dev.d_len - hdrlen; + + ret = sixlowpan_queue_frames(ieee, ipv6hdr, buffer, buflen, + &destmac); +drop: ieee->i_dev.d_len = 0; } } diff --git a/net/sixlowpan/sixlowpan_tcpsend.c b/net/sixlowpan/sixlowpan_tcpsend.c index ae581b150a..bc3e84f934 100644 --- a/net/sixlowpan/sixlowpan_tcpsend.c +++ b/net/sixlowpan/sixlowpan_tcpsend.c @@ -113,7 +113,7 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, conn = (FAR struct tcp_conn_s *)psock->s_conn; DEBUGASSERT(conn != NULL); -#if defined(CONFIG_NET_IPv4) && defined(CONFIG_NET_IPv6) +#ifdef CONFIG_NET_IPv4 /* Ignore if not IPv6 domain */ if (conn->domain != PF_INET6) @@ -196,4 +196,86 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, return ret; } +/**************************************************************************** + * Function: sixlowpan_tcp_send + * + * Description: + * TCP output comes through two different mechansims. Either from: + * + * 1. TCP socket output. For the case of TCP output to an + * IEEE802.15.4, the TCP output is caught in the socket + * send()/sendto() logic and and redirected to psock_6lowpan_tcp_send(). + * 2. TCP output from the TCP state machine. That will occur + * during TCP packet processing by the TCP state meachine. It + * is detected there when ipv6_tcp_input() returns with d_len > 0. This + * will be redirected here. + * + * Parameters: + * dev - An instance of nework device state structure + * + * Returned Value: + * None + * + * Assumptions: + * Called with the network locked. + * + ****************************************************************************/ + +void sixlowpan_tcp_send(FAR struct net_driver_s *dev) +{ + DEBUGASSERT(dev != NULL && dev->d_len > 0); + + /* Double check */ + + if (dev != NULL && dev->d_len > 0) + { + FAR struct ipv6_hdr_s *ipv6hdr; + + /* The IPv6 header followed by a TCP headers should lie at the + * beginning of d_buf since there is no link layer protocol header + * and the TCP state machine should only response with TCP packets. + */ + + ipv6hdr = (FAR struct ipv6_hdr_s *)(dev->d_buf); + + /* The TCP data payload should follow the IPv6 header plus the + * protocol header. + */ + + if (ipv6hdr->proto != IP_PROTO_TCP) + { + nwarn("WARNING: Expected TCP protoype: %u\n", ipv6hdr->proto); + } + else + { + size_t hdrlen; + + hdrlen = IPv6_HDRLEN + TCP_HDRLEN; + if (hdrlen < dev->d_len) + { + nwarn("WARNING: Packet to small: Have %u need >%u\n", + dev->d_len, hdrlen); + } + else + { + struct rimeaddr_s destmac; + + /* Get the Rime MAC address of the destination. This assumes + * an encoding of the MAC address in the IPv6 address. + */ + + sixlowpan_rimefromip(ipv6hdr->destipaddr, &destmac); + + /* Convert the outgoing packet into a frame list. */ + + (void)sixlowpan_queue_frames( + (FAR struct ieee802154_driver_s *)dev, ipv6hdr, + dev->d_buf + hdrlen, dev->d_len - hdrlen, &destmac); + } + } + } + + dev->d_len = 0; +} + #endif /* CONFIG_NET_6LOWPAN && CONFIG_NET_TCP */ -- GitLab From fb42844788a3deb13cfc4ee5668af3bac4fb9f4a Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 2 Apr 2017 12:32:20 -0600 Subject: [PATCH 310/990] STM32: Fix a comment --- arch/arm/src/stm32/stm32_eth.c | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/arch/arm/src/stm32/stm32_eth.c b/arch/arm/src/stm32/stm32_eth.c index 7703a9a745..b17077fd54 100644 --- a/arch/arm/src/stm32/stm32_eth.c +++ b/arch/arm/src/stm32/stm32_eth.c @@ -90,9 +90,7 @@ # error "Logic to support multiple Ethernet interfaces is incomplete" #endif -/* If processing is not done at the interrupt level, then work queue support - * is required. - */ +/* Work queue support is required. */ #if !defined(CONFIG_SCHED_WORKQUEUE) # error Work queue support is required -- GitLab From 6e2f8f3aa34d15e30231e923dc927d8ac4005649 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 2 Apr 2017 13:27:53 -0600 Subject: [PATCH 311/990] 6loWPAN: Add logic to fill in UDP/TCP headers. Still missing some checksum logic. --- net/sixlowpan/sixlowpan_internal.h | 12 ++--- net/sixlowpan/sixlowpan_tcpsend.c | 82 ++++++++++++++++++++++++++++-- net/sixlowpan/sixlowpan_udpsend.c | 73 +++++++++++++++++++++++--- 3 files changed, 149 insertions(+), 18 deletions(-) diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index dff37cf6f8..c6a83480d9 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -465,7 +465,7 @@ struct iob_s; /* Forward reference */ * it to be sent on an 802.15.4 network using 6lowpan. Called from common * UDP/TCP send logic. * - * The payload data is in the caller 'buf' and is of length 'len'. + * The payload data is in the caller 'buf' and is of length 'buflen'. * Compressed headers will be added and if necessary the packet is * fragmented. The resulting packet/fragments are put in ieee->i_framelist * and the entire list of frames will be delivered to the 802.15.4 MAC via @@ -473,9 +473,9 @@ struct iob_s; /* Forward reference */ * * Input Parameters: * dev - The IEEE802.15.4 MAC network driver interface. - * destip - IPv6 plus TCP or UDP headers. + * destip - IPv6 plus TCP or UDP headers. * buf - Data to send - * len - Length of data to send + * buflen - Length of data to send * raddr - The MAC address of the destination * timeout - Send timeout in deciseconds * @@ -492,7 +492,7 @@ struct iob_s; /* Forward reference */ int sixlowpan_send(FAR struct net_driver_s *dev, FAR const struct ipv6_hdr_s *destip, FAR const void *buf, - size_t len, FAR const struct rimeaddr_s *raddr, + size_t buflen, FAR const struct rimeaddr_s *raddr, uint16_t timeout); /**************************************************************************** @@ -557,7 +557,7 @@ int sixlowpan_framecreate(FAR struct ieee802154_driver_s *ieee, * ieee - The IEEE802.15.4 MAC driver instance * ipv6hdr - IPv6 header followed by TCP or UDP header. * buf - Data to send - * len - Length of data to send + * buflen - Length of data to send * destmac - The IEEE802.15.4 MAC address of the destination * * Returned Value: @@ -573,7 +573,7 @@ int sixlowpan_framecreate(FAR struct ieee802154_driver_s *ieee, int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, FAR const struct ipv6_hdr_s *ipv6hdr, - FAR const void *buf, size_t len, + FAR const void *buf, size_t buflen, FAR const struct rimeaddr_s *destmac); /**************************************************************************** diff --git a/net/sixlowpan/sixlowpan_tcpsend.c b/net/sixlowpan/sixlowpan_tcpsend.c index bc3e84f934..a7a1a90f3b 100644 --- a/net/sixlowpan/sixlowpan_tcpsend.c +++ b/net/sixlowpan/sixlowpan_tcpsend.c @@ -39,11 +39,13 @@ #include +#include #include #include #include #include "nuttx/net/netdev.h" +#include "nuttx/net/netstats.h" #include "netdev/netdev.h" #include "socket/socket.h" @@ -66,7 +68,7 @@ * Parameters: * psock - An instance of the internal socket structure. * buf - Data to send - * len - Length of data to send + * bulen - Length of data to send * * Returned Value: * On success, returns the number of characters sent. On error, @@ -80,13 +82,14 @@ ****************************************************************************/ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, - size_t len) + size_t buflen) { FAR struct tcp_conn_s *conn; FAR struct net_driver_s *dev; struct ipv6tcp_hdr_s ipv6tcp; struct rimeaddr_s destmac; uint16_t timeout; + uint16_t iplen; int ret; DEBUGASSERT(psock != NULL && psock->s_crefs > 0); @@ -161,8 +164,79 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, #endif /* Initialize the IPv6/TCP headers */ -#warning Missing logic + /* Initialize the IPv6/UDP headers */ + + ipv6tcp.ipv6.vtc = 0x60; + ipv6tcp.ipv6.tcf = 0x00; + ipv6tcp.ipv6.flow = 0x00; + ipv6tcp.ipv6.proto = IP_PROTO_TCP; + ipv6tcp.ipv6.ttl = IP_TTL; + + /* The IPv6 header length field does not include the size of IPv6 IP + * header. + */ + + iplen = buflen + TCP_HDRLEN; + ipv6tcp.ipv6.len[0] = (iplen >> 8); + ipv6tcp.ipv6.len[1] = (iplen & 0xff); + + /* Copy the source and destination addresses */ + + net_ipv6addr_hdrcopy(ipv6tcp.ipv6.srcipaddr, conn->u.ipv6.laddr); + net_ipv6addr_hdrcopy(ipv6tcp.ipv6.destipaddr, conn->u.ipv6.raddr); + + ninfo("IPv6 length: %d\n", ((int)ipv6->len[0] << 8) + ipv6->len[1]); + +#ifdef CONFIG_NET_STATISTICS + g_netstats.ipv6.sent++; +#endif + + /* Initialize the TCP header */ + + ipv6tcp.tcp.srcport = conn->lport; /* Local port */ + ipv6tcp.tcp.destport = conn->rport; /* Connected remote port */ + + memcpy(ipv6tcp.tcp.ackno, conn->rcvseq, 4); /* ACK number */ + memcpy(ipv6tcp.tcp.seqno, conn->sndseq, 4); /* Sequence number */ + + ipv6tcp.tcp.tcpoffset = (TCP_HDRLEN / 4) << 4; /* No optdata */ + ipv6tcp.tcp.urgp[0] = 0; /* No urgent data */ + ipv6tcp.tcp.urgp[1] = 0; + + /* Set the TCP window */ + + if (conn->tcpstateflags & TCP_STOPPED) + { + /* If the connection has issued TCP_STOPPED, we advertise a zero + * window so that the remote host will stop sending data. + */ + + ipv6tcp.tcp.wnd[0] = 0; + ipv6tcp.tcp.wnd[1] = 0; + } + else + { + ipv6tcp.tcp.wnd[0] = ((NET_DEV_RCVWNDO(dev)) >> 8); + ipv6tcp.tcp.wnd[1] = ((NET_DEV_RCVWNDO(dev)) & 0xff); + } + + /* Calculate TCP checksum. */ + + ipv6tcp.tcp.tcpchksum = 0; +#if 0 + /* REVISIT: Current checksum logic expects the IPv6 header, the UDP header, and + * the payload data to be in contiguous memory. + */ + + ipv6tcp.tcp.tcpchksum = ~tcp_ipv6_chksum(dev); +#endif + + ninfo("Outgoing TCP packet length: %d bytes\n", iplen + IOPv6_HDRLEN); + +#ifdef CONFIG_NET_STATISTICS + g_netstats.tcp.sent++; +#endif /* Set the socket state to sending */ psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_SEND); @@ -184,7 +258,7 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, #endif ret = sixlowpan_send(dev, (FAR const struct ipv6_hdr_s *)&ipv6tcp, - buf, len, &destmac, timeout); + buf, buflen, &destmac, timeout); if (ret < 0) { nerr("ERROR: sixlowpan_send() failed: %d\n", ret); diff --git a/net/sixlowpan/sixlowpan_udpsend.c b/net/sixlowpan/sixlowpan_udpsend.c index ae16a23355..49932514c8 100644 --- a/net/sixlowpan/sixlowpan_udpsend.c +++ b/net/sixlowpan/sixlowpan_udpsend.c @@ -46,6 +46,7 @@ #include #include "nuttx/net/netdev.h" +#include "nuttx/net/netstats.h" #include "netdev/netdev.h" #include "socket/socket.h" @@ -70,7 +71,7 @@ * Parameters: * psock A pointer to a NuttX-specific, internal socket structure * buf Data to send - * len Length of data to send + * buflen Length of data to send * flags Send flags * to Address of recipient * tolen The length of the address structure @@ -88,7 +89,7 @@ ssize_t psock_6lowpan_udp_sendto(FAR struct socket *psock, FAR const void *buf, - size_t len, int flags, + size_t buflen, int flags, FAR const struct sockaddr *to, socklen_t tolen) { @@ -97,6 +98,7 @@ ssize_t psock_6lowpan_udp_sendto(FAR struct socket *psock, FAR struct net_driver_s *dev; struct ipv6udp_hdr_s ipv6udp; struct rimeaddr_s destmac; + uint16_t iplen; uint16_t timeout; int ret; @@ -176,7 +178,62 @@ ssize_t psock_6lowpan_udp_sendto(FAR struct socket *psock, #endif /* Initialize the IPv6/UDP headers */ + + ipv6udp.ipv6.vtc = 0x60; + ipv6udp.ipv6.tcf = 0x00; + ipv6udp.ipv6.flow = 0x00; + ipv6udp.ipv6.proto = IP_PROTO_UDP; + ipv6udp.ipv6.ttl = conn->ttl; + + /* The IPv6 header length field does not include the size of IPv6 IP + * header. + */ + + iplen = buflen + UDP_HDRLEN; + ipv6udp.ipv6.len[0] = (iplen >> 8); + ipv6udp.ipv6.len[1] = (iplen & 0xff); + + /* Copy the source and destination addresses */ + + net_ipv6addr_hdrcopy(ipv6udp.ipv6.srcipaddr, to6->sin6_addr.in6_u.u6_addr16); + net_ipv6addr_hdrcopy(ipv6udp.ipv6.destipaddr, conn->u.ipv6.raddr); + + ninfo("IPv6 length: %d\n", ((int)ipv6->len[0] << 8) + ipv6->len[1]); + +#ifdef CONFIG_NET_STATISTICS + g_netstats.ipv6.sent++; +#endif + + /* Initialize the UDP header */ + + ipv6udp.udp.srcport = conn->lport; + ipv6udp.udp.destport = to6->sin6_port; + ipv6udp.udp.udplen = htons(iplen); + ipv6udp.udp.udpchksum = 0; + + ipv6udp.udp.udpchksum = 0; + #warning Missing logic +#if 0 /* REVISIT */ +#ifdef CONFIG_NET_UDP_CHECKSUMS + /* Calculate UDP checksum. */ + /* REVISIT: Current checksum logic expects the IPv6 header, the UDP header, and + * the payload data to be in contiguous memory. + */ + + ipv6udp.udp.udpchksum = ~udp_ipv6_chksum(dev); + if (ipv6udp.udp.udpchksum == 0) + { + ipv6udp.udp.udpchksum = 0xffff; + } +#endif /* CONFIG_NET_UDP_CHECKSUMS */ +#endif /* REVISIT */ + + ninfo("Outgoing UDP packet length: %d\n", iplen + IPv6_HDRLEN); + +#ifdef CONFIG_NET_STATISTICS + g_netstats.udp.sent++; +#endif /* Set the socket state to sending */ @@ -199,7 +256,7 @@ ssize_t psock_6lowpan_udp_sendto(FAR struct socket *psock, #endif ret = sixlowpan_send(dev, (FAR const struct ipv6_hdr_s *)&ipv6udp, - buf, len, &destmac, timeout); + buf, buflen, &destmac, timeout); if (ret < 0) { nerr("ERROR: sixlowpan_send() failed: %d\n", ret); @@ -219,9 +276,9 @@ ssize_t psock_6lowpan_udp_sendto(FAR struct socket *psock, * sockets. * * Parameters: - * psock - An instance of the internal socket structure. - * buf - Data to send - * len - Length of data to send + * psock - An instance of the internal socket structure. + * buf - Data to send + * buflen - Length of data to send * * Returned Value: * On success, returns the number of characters sent. On error, @@ -234,7 +291,7 @@ ssize_t psock_6lowpan_udp_sendto(FAR struct socket *psock, ****************************************************************************/ ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, - size_t len) + size_t buflen) { FAR struct udp_conn_s *conn; struct sockaddr_in6 to; @@ -278,7 +335,7 @@ ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, to.sin6_port = conn->rport; /* Already network order */ memcpy(to.sin6_addr.in6_u.u6_addr16, conn->u.ipv6.raddr, 16); - return psock_6lowpan_udp_sendto(psock, buf, len, 0, + return psock_6lowpan_udp_sendto(psock, buf, buflen, 0, (FAR const struct sockaddr *)&to, sizeof(struct sockaddr_in6)); } -- GitLab From 392c90b0202ec23d0edfa96fd982afd45fbb9c52 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 2 Apr 2017 14:30:01 -0600 Subject: [PATCH 312/990] 6loWPAN: Fix last checksum issues. Contiki 6loWPAN port is now complete (but completely untested) --- net/sixlowpan/sixlowpan_tcpsend.c | 72 ++++++- net/sixlowpan/sixlowpan_udpsend.c | 77 ++++++-- net/utils/Make.defs | 24 ++- net/utils/net_chksum.c | 309 ++---------------------------- net/utils/utils.h | 93 +++++++++ 5 files changed, 262 insertions(+), 313 deletions(-) diff --git a/net/sixlowpan/sixlowpan_tcpsend.c b/net/sixlowpan/sixlowpan_tcpsend.c index a7a1a90f3b..2b0ce15cb3 100644 --- a/net/sixlowpan/sixlowpan_tcpsend.c +++ b/net/sixlowpan/sixlowpan_tcpsend.c @@ -50,10 +50,73 @@ #include "netdev/netdev.h" #include "socket/socket.h" #include "tcp/tcp.h" +#include "utils/utils.h" #include "sixlowpan/sixlowpan_internal.h" #if defined(CONFIG_NET_6LOWPAN) && defined(CONFIG_NET_TCP) +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: sixlowpan_tcp_chksum + * + * Description: + * Perform the checksum calcaultion over the IPv6, protocol headers, and + * data payload as necessary. + * + * Input Parameters: + * ipv6tcp - A reference to a structure containing the IPv6 and TCP headers. + * buf - The beginning of the payload data + * buflen - The length of the payload data. + * + * Returned Value: + * The calculated checksum + * + ****************************************************************************/ + +static uint16_t sixlowpan_tcp_chksum(FAR struct ipv6tcp_hdr_s *ipv6tcp, + FAR const uint8_t *buf, uint16_t buflen) +{ + uint16_t upperlen; + uint16_t sum; + + /* The length reported in the IPv6 header is the length of the payload + * that follows the header. + */ + + upperlen = ((uint16_t)ipv6tcp->ipv6.len[0] << 8) + ipv6tcp->ipv6.len[1]; + + /* Verify some minimal assumptions */ + + if (upperlen > CONFIG_NET_6LOWPAN_MTU) + { + return 0; + } + + /* The checksum is calculated starting with a pseudo-header of IPv6 header + * fields according to the IPv6 standard, which consists of the source + * and destination addresses, the packet length and the next header field. + */ + + sum = upperlen + ipv6tcp->ipv6.proto; + + /* Sum IP source and destination addresses. */ + + sum = chksum(sum, (FAR uint8_t *)ipv6tcp->ipv6.srcipaddr, + 2 * sizeof(net_ipv6addr_t)); + + /* Sum the TCP header */ + + sum = chksum(sum, (FAR uint8_t *)&ipv6tcp->tcp, TCP_HDRLEN); + + /* Sum payload data. */ + + sum = chksum(sum, buf, buflen); + return (sum == 0) ? 0xffff : htons(sum); +} + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -224,19 +287,14 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, /* Calculate TCP checksum. */ ipv6tcp.tcp.tcpchksum = 0; -#if 0 - /* REVISIT: Current checksum logic expects the IPv6 header, the UDP header, and - * the payload data to be in contiguous memory. - */ - - ipv6tcp.tcp.tcpchksum = ~tcp_ipv6_chksum(dev); -#endif + ipv6tcp.tcp.tcpchksum = ~sixlowpan_tcp_chksum(&ipv6tcp, buf, buflen); ninfo("Outgoing TCP packet length: %d bytes\n", iplen + IOPv6_HDRLEN); #ifdef CONFIG_NET_STATISTICS g_netstats.tcp.sent++; #endif + /* Set the socket state to sending */ psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_SEND); diff --git a/net/sixlowpan/sixlowpan_udpsend.c b/net/sixlowpan/sixlowpan_udpsend.c index 49932514c8..61fbe3b237 100644 --- a/net/sixlowpan/sixlowpan_udpsend.c +++ b/net/sixlowpan/sixlowpan_udpsend.c @@ -51,10 +51,75 @@ #include "netdev/netdev.h" #include "socket/socket.h" #include "udp/udp.h" +#include "utils/utils.h" #include "sixlowpan/sixlowpan_internal.h" #if defined(CONFIG_NET_6LOWPAN) && defined(CONFIG_NET_UDP) +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: sixlowpan_udp_chksum + * + * Description: + * Perform the checksum calcaultion over the IPv6, protocol headers, and + * data payload as necessary. + * + * Input Parameters: + * ipv6udp - A reference to a structure containing the IPv6 and UDP headers. + * buf - The beginning of the payload data + * buflen - The length of the payload data. + * + * Returned Value: + * The calculated checksum + * + ****************************************************************************/ + +#ifdef CONFIG_NET_UDP_CHECKSUMS +static uint16_t sixlowpan_udp_chksum(FAR struct ipv6udp_hdr_s *ipv6udp, + FAR const uint8_t *buf, uint16_t buflen) +{ + uint16_t upperlen; + uint16_t sum; + + /* The length reported in the IPv6 header is the length of the payload + * that follows the header. + */ + + upperlen = ((uint16_t)ipv6udp->ipv6.len[0] << 8) + ipv6udp->ipv6.len[1]; + + /* Verify some minimal assumptions */ + + if (upperlen > CONFIG_NET_6LOWPAN_MTU) + { + return 0; + } + + /* The checksum is calculated starting with a pseudo-header of IPv6 header + * fields according to the IPv6 standard, which consists of the source + * and destination addresses, the packet length and the next header field. + */ + + sum = upperlen + ipv6udp->ipv6.proto; + + /* Sum IP source and destination addresses. */ + + sum = chksum(sum, (FAR uint8_t *)ipv6udp->ipv6.srcipaddr, + 2 * sizeof(net_ipv6addr_t)); + + /* Sum the UDP header */ + + sum = chksum(sum, (FAR uint8_t *)&ipv6udp->udp, UDP_HDRLEN); + + /* Sum payload data. */ + + sum = chksum(sum, buf, buflen); + return (sum == 0) ? 0xffff : htons(sum); +} +#endif + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -211,23 +276,13 @@ ssize_t psock_6lowpan_udp_sendto(FAR struct socket *psock, ipv6udp.udp.udplen = htons(iplen); ipv6udp.udp.udpchksum = 0; - ipv6udp.udp.udpchksum = 0; - -#warning Missing logic -#if 0 /* REVISIT */ #ifdef CONFIG_NET_UDP_CHECKSUMS - /* Calculate UDP checksum. */ - /* REVISIT: Current checksum logic expects the IPv6 header, the UDP header, and - * the payload data to be in contiguous memory. - */ - - ipv6udp.udp.udpchksum = ~udp_ipv6_chksum(dev); + ipv6udp.udp.udpchksum = ~sixlowpan_udp_chksum(ipv6udp, buf, buflen); if (ipv6udp.udp.udpchksum == 0) { ipv6udp.udp.udpchksum = 0xffff; } #endif /* CONFIG_NET_UDP_CHECKSUMS */ -#endif /* REVISIT */ ninfo("Outgoing UDP packet length: %d\n", iplen + IPv6_HDRLEN); diff --git a/net/utils/Make.defs b/net/utils/Make.defs index 270b80bbbe..daad84805e 100644 --- a/net/utils/Make.defs +++ b/net/utils/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # net/utils/Make.defs # -# Copyright (C) 2014 Gregory Nutt. All rights reserved. +# Copyright (C) 2014, 2017 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -36,7 +36,7 @@ # Common utilities NET_CSRCS += net_dsec2tick.c net_dsec2timeval.c net_timeval2dsec.c -NET_CSRCS += net_chksum.c net_lock.c +NET_CSRCS += net_chksum.c net_ipchksum.c net_incr32.c net_lock.c # IPv6 utilities @@ -44,6 +44,26 @@ ifeq ($(CONFIG_NET_IPv6),y) NET_CSRCS += net_ipv6_maskcmp.c net_ipv6_mask2pref.c net_ipv6_pref2mask.c endif +# TCP utilities + +ifeq ($(CONFIG_NET_TCP),y) +NET_CSRCS += net_tcpchksum.c +endif + +# UDP utilities + +ifeq ($(CONFIG_NET_UDP),y) +NET_CSRCS += net_udpchksum.c +endif + +# ICMP utilities + +ifeq ($(CONFIG_NET_ICMP),y) +NET_CSRCS += net_icmpchksum.c +else ifeq ($(CONFIG_NET_ICMPv6),y) +NET_CSRCS += net_icmpchksum.c +endif + # Include utility build support DEPPATH += --dep-path utils diff --git a/net/utils/net_chksum.c b/net/utils/net_chksum.c index 9f4055c756..6527238775 100644 --- a/net/utils/net_chksum.c +++ b/net/utils/net_chksum.c @@ -56,19 +56,31 @@ #define IPv4BUF ((struct ipv4_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)]) #define IPv6BUF ((struct ipv6_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)]) -#define ICMPBUF ((struct icmp_iphdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)]) -#define ICMPv6BUF ((struct icmp_ipv6hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)]) /**************************************************************************** - * Private Functions + * Public Functions ****************************************************************************/ /**************************************************************************** * Name: chksum + * + * Description: + * Calculate the raw change some over the memory region described by + * data and len. + * + * Input Parameters: + * sum - Partial calculations carried over from a previous call to chksum(). + * This should be zero on the first time that check sum is called. + * data - Beginning of the data to include in the checksum. + * len - Length of the data to include in the checksum. + * + * Returned Value: + * The updated checksum value. + * ****************************************************************************/ #ifndef CONFIG_NET_ARCH_CHKSUM -static uint16_t chksum(uint16_t sum, FAR const uint8_t *data, uint16_t len) +uint16_t chksum(uint16_t sum, FAR const uint8_t *data, uint16_t len) { FAR const uint8_t *dataptr; FAR const uint8_t *last_byte; @@ -107,158 +119,6 @@ static uint16_t chksum(uint16_t sum, FAR const uint8_t *data, uint16_t len) } #endif /* CONFIG_NET_ARCH_CHKSUM */ -/**************************************************************************** - * Name: ipv4_upperlayer_chksum - ****************************************************************************/ - -#if !defined(CONFIG_NET_ARCH_CHKSUM) && defined(CONFIG_NET_IPv4) -static uint16_t ipv4_upperlayer_chksum(FAR struct net_driver_s *dev, - uint8_t proto) -{ - FAR struct ipv4_hdr_s *ipv4 = IPv4BUF; - uint16_t upperlen; - uint16_t sum; - - /* The length reported in the IPv4 header is the length of both the IPv4 - * header and the payload that follows the header. We need to subtract - * the size of the IPv4 header to get the size of the payload. - */ - - upperlen = (((uint16_t)(ipv4->len[0]) << 8) + ipv4->len[1]) - IPv4_HDRLEN; - - /* Verify some minimal assumptions */ - - if (upperlen > NET_DEV_MTU(dev)) - { - return 0; - } - - /* First sum pseudo-header. */ - /* IP protocol and length fields. This addition cannot carry. */ - - sum = upperlen + proto; - - /* Sum IP source and destination addresses. */ - - sum = chksum(sum, (FAR uint8_t *)&ipv4->srcipaddr, 2 * sizeof(in_addr_t)); - - /* Sum IP payload data. */ - - sum = chksum(sum, &dev->d_buf[IPv4_HDRLEN + NET_LL_HDRLEN(dev)], upperlen); - return (sum == 0) ? 0xffff : htons(sum); -} -#endif /* CONFIG_NET_ARCH_CHKSUM */ - -/**************************************************************************** - * Name: ipv6_upperlayer_chksum - ****************************************************************************/ - -#if !defined(CONFIG_NET_ARCH_CHKSUM) && defined(CONFIG_NET_IPv6) -static uint16_t ipv6_upperlayer_chksum(FAR struct net_driver_s *dev, - uint8_t proto) -{ - FAR struct ipv6_hdr_s *ipv6 = IPv6BUF; - uint16_t upperlen; - uint16_t sum; - - /* The length reported in the IPv6 header is the length of the payload - * that follows the header. - */ - - upperlen = ((uint16_t)ipv6->len[0] << 8) + ipv6->len[1]; - - /* Verify some minimal assumptions */ - - if (upperlen > NET_DEV_MTU(dev)) - { - return 0; - } - - /* The checksum is calculated starting with a pseudo-header of IPv6 header - * fields according to the IPv6 standard, which consists of the source - * and destination addresses, the packet length and the next header field. - */ - - sum = upperlen + proto; - - /* Sum IP source and destination addresses. */ - - sum = chksum(sum, (FAR uint8_t *)&ipv6->srcipaddr, 2 * sizeof(net_ipv6addr_t)); - - /* Sum IP payload data. */ - - sum = chksum(sum, &dev->d_buf[IPv6_HDRLEN + NET_LL_HDRLEN(dev)], upperlen); - return (sum == 0) ? 0xffff : htons(sum); -} -#endif /* CONFIG_NET_ARCH_CHKSUM */ - -/**************************************************************************** - * Name: net_carry32 - * - * Description: - * Calculate the Internet checksum over a buffer. - * - ****************************************************************************/ - -#ifndef CONFIG_NET_ARCH_INCR32 -static inline void net_carry32(FAR uint8_t *sum, uint16_t op16) -{ - if (sum[2] < (op16 >> 8)) - { - ++sum[1]; - if (sum[1] == 0) - { - ++sum[0]; - } - } - - if (sum[3] < (op16 & 0xff)) - { - ++sum[2]; - if (sum[2] == 0) - { - ++sum[1]; - if (sum[1] == 0) - { - ++sum[0]; - } - } - } -} -#endif /* CONFIG_NET_ARCH_INCR32 */ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: net_incr32 - * - * Description: - * - * Carry out a 32-bit addition. - * - * By defining CONFIG_NET_ARCH_INCR32, the architecture can replace - * net_incr32 with hardware assisted solutions. - * - * Input Parameters: - * op32 - A pointer to a 4-byte array representing a 32-bit integer in - * network byte order (big endian). This value may not be word - * aligned. The value pointed to by op32 is modified in place - * - * op16 - A 16-bit integer in host byte order. - * - ****************************************************************************/ - -#ifndef CONFIG_NET_ARCH_INCR32 -void net_incr32(FAR uint8_t *op32, uint16_t op16) -{ - op32[3] += (op16 & 0xff); - op32[2] += (op16 >> 8); - net_carry32(op32, op16); -} -#endif /* CONFIG_NET_ARCH_INCR32 */ - /**************************************************************************** * Name: net_chksum * @@ -291,141 +151,4 @@ uint16_t net_chksum(FAR uint16_t *data, uint16_t len) } #endif /* CONFIG_NET_ARCH_CHKSUM */ -/**************************************************************************** - * Name: ipv4_chksum - * - * Description: - * Calculate the IPv4 header checksum of the packet header in d_buf. - * - * The IPv4 header checksum is the Internet checksum of the 20 bytes of - * the IPv4 header. - * - * If CONFIG_NET_ARCH_CHKSUM is defined, then this function must be - * provided by architecture-specific logic. - * - * Returned Value: - * The IPv4 header checksum of the IPv4 header in the d_buf buffer. - * - ****************************************************************************/ - -#if defined(CONFIG_NET_IPv4) && !defined(CONFIG_NET_ARCH_CHKSUM) -uint16_t ipv4_chksum(FAR struct net_driver_s *dev) -{ - uint16_t sum; - - sum = chksum(0, &dev->d_buf[NET_LL_HDRLEN(dev)], IPv4_HDRLEN); - return (sum == 0) ? 0xffff : htons(sum); -} -#endif /* CONFIG_NET_ARCH_CHKSUM */ - -/**************************************************************************** - * Name: tcp_chksum, tcp_ipv4_chksum, and tcp_ipv6_chksum - * - * Description: - * Calculate the TCP checksum of the packet in d_buf and d_appdata. - * - * The TCP checksum is the Internet checksum of data contents of the - * TCP segment, and a pseudo-header as defined in RFC793. - * - * Note: The d_appdata pointer that points to the packet data may - * point anywhere in memory, so it is not possible to simply calculate - * the Internet checksum of the contents of the d_buf buffer. - * - * Returned Value: - * The TCP checksum of the TCP segment in d_buf and pointed to by - * d_appdata. - * - ****************************************************************************/ - -#ifndef CONFIG_NET_ARCH_CHKSUM -#ifdef CONFIG_NET_IPv4 -uint16_t tcp_ipv4_chksum(FAR struct net_driver_s *dev) -{ - return ipv4_upperlayer_chksum(dev, IP_PROTO_TCP); -} -#endif /* CONFIG_NET_IPv4 */ - -#ifdef CONFIG_NET_IPv6 -uint16_t tcp_ipv6_chksum(FAR struct net_driver_s *dev) -{ - return ipv6_upperlayer_chksum(dev, IP_PROTO_TCP); -} -#endif /* CONFIG_NET_IPv6 */ -#endif /* !CONFIG_NET_ARCH_CHKSUM */ - -#if defined(CONFIG_NET_IPv4) && defined(CONFIG_NET_IPv6) -uint16_t tcp_chksum(FAR struct net_driver_s *dev) -{ - if (IFF_IS_IPv6(dev->d_flags)) - { - return tcp_ipv6_chksum(dev); - } - else - { - return tcp_ipv4_chksum(dev); - } -} -#endif - -/**************************************************************************** - * Name: udp_ipv4_chksum - * - * Description: - * Calculate the UDP/IPv4 checksum of the packet in d_buf and d_appdata. - * - ****************************************************************************/ - -#if defined(CONFIG_NET_UDP_CHECKSUMS) && defined(CONFIG_NET_IPv4) -uint16_t udp_ipv4_chksum(FAR struct net_driver_s *dev) -{ - return ipv4_upperlayer_chksum(dev, IP_PROTO_UDP); -} -#endif - -/**************************************************************************** - * Name: udp_ipv6_chksum - * - * Description: - * Calculate the UDP/IPv6 checksum of the packet in d_buf and d_appdata. - * - ****************************************************************************/ - -#if defined(CONFIG_NET_UDP_CHECKSUMS) && defined(CONFIG_NET_IPv6) -uint16_t udp_ipv6_chksum(FAR struct net_driver_s *dev) -{ - return ipv6_upperlayer_chksum(dev, IP_PROTO_UDP); -} -#endif - -/**************************************************************************** - * Name: icmp_chksum - * - * Description: - * Calculate the checksum of the ICMP message - * - ****************************************************************************/ - -#if defined(CONFIG_NET_ICMP) && defined(CONFIG_NET_ICMP_PING) -uint16_t icmp_chksum(FAR struct net_driver_s *dev, int len) -{ - FAR struct icmp_iphdr_s *icmp = ICMPBUF; - return net_chksum((FAR uint16_t *)&icmp->type, len); -} -#endif /* CONFIG_NET_ICMP && CONFIG_NET_ICMP_PING */ - -/**************************************************************************** - * Name: icmpv6_chksum - * - * Description: - * Calculate the checksum of the ICMPv6 message - * - ****************************************************************************/ - -#ifdef CONFIG_NET_ICMPv6 -uint16_t icmpv6_chksum(FAR struct net_driver_s *dev) -{ - return ipv6_upperlayer_chksum(dev, IP_PROTO_ICMP6); -} -#endif - #endif /* CONFIG_NET */ diff --git a/net/utils/utils.h b/net/utils/utils.h index 6e33b72a83..ffeca8c3f6 100644 --- a/net/utils/utils.h +++ b/net/utils/utils.h @@ -191,6 +191,99 @@ uint8_t net_ipv6_mask2pref(FAR const uint16_t *mask); void net_ipv6_pref2mask(uint8_t preflen, net_ipv6addr_t mask); #endif +/**************************************************************************** + * Name: chksum + * + * Description: + * Calculate the raw change some over the memory region described by + * data and len. + * + * Input Parameters: + * sum - Partial calculations carried over from a previous call to chksum(). + * This should be zero on the first time that check sum is called. + * data - Beginning of the data to include in the checksum. + * len - Length of the data to include in the checksum. + * + * Returned Value: + * The updated checksum value. + * + ****************************************************************************/ + +#ifndef CONFIG_NET_ARCH_CHKSUM +uint16_t chksum(uint16_t sum, FAR const uint8_t *data, uint16_t len); +#endif + +/**************************************************************************** + * Name: net_chksum + * + * Description: + * Calculate the Internet checksum over a buffer. + * + * The Internet checksum is the one's complement of the one's complement + * sum of all 16-bit words in the buffer. + * + * See RFC1071. + * + * If CONFIG_NET_ARCH_CHKSUM is defined, then this function must be + * provided by architecture-specific logic. + * + * Input Parameters: + * + * buf - A pointer to the buffer over which the checksum is to be computed. + * + * len - The length of the buffer over which the checksum is to be computed. + * + * Returned Value: + * The Internet checksum of the buffer. + * + ****************************************************************************/ + +#ifndef CONFIG_NET_ARCH_CHKSUM +uint16_t net_chksum(FAR uint16_t *data, uint16_t len); +#endif + +/**************************************************************************** + * Name: ipv4_upperlayer_chksum + * + * Description: + * Perform the checksum calcaultion over the IPv4, protocol headers, and + * data payload as necessary. + * + * Input Parameters: + * dev - The network driver instance. The packet data is in the d_buf + * of the device. + * proto - The protocol being supported + * + * Returned Value: + * The calculated checksum + * + ****************************************************************************/ + +#if !defined(CONFIG_NET_ARCH_CHKSUM) && defined(CONFIG_NET_IPv4) +uint16_t ipv4_upperlayer_chksum(FAR struct net_driver_s *dev, uint8_t proto); +#endif + +/**************************************************************************** + * Name: ipv6_upperlayer_chksum + * + * Description: + * Perform the checksum calcaultion over the IPv6, protocol headers, and + * data payload as necessary. + * + * Input Parameters: + * dev - The network driver instance. The packet data is in the d_buf + * of the device. + * proto - The protocol being supported + * + * Returned Value: + * The calculated checksum + * + ****************************************************************************/ + +#if !defined(CONFIG_NET_ARCH_CHKSUM) && defined(CONFIG_NET_IPv6) +uint16_t ipv6_upperlayer_chksum(FAR struct net_driver_s *dev, uint8_t proto); +#endif + /**************************************************************************** * Name: tcp_chksum, tcp_ipv4_chksum, and tcp_ipv6_chksum * -- GitLab From 3367312401d0a4ff7c2d32d931154cfb2ccab241 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 2 Apr 2017 14:45:14 -0600 Subject: [PATCH 313/990] 6loWPAN: Forgot to add files with last commit. --- net/utils/net_icmpchksum.c | 94 ++++++++++++++++++ net/utils/net_incr32.c | 121 ++++++++++++++++++++++ net/utils/net_ipchksum.c | 199 +++++++++++++++++++++++++++++++++++++ net/utils/net_tcpchksum.c | 104 +++++++++++++++++++ net/utils/net_udpchksum.c | 85 ++++++++++++++++ 5 files changed, 603 insertions(+) create mode 100644 net/utils/net_icmpchksum.c create mode 100644 net/utils/net_incr32.c create mode 100644 net/utils/net_ipchksum.c create mode 100644 net/utils/net_tcpchksum.c create mode 100644 net/utils/net_udpchksum.c diff --git a/net/utils/net_icmpchksum.c b/net/utils/net_icmpchksum.c new file mode 100644 index 0000000000..c9d24148bd --- /dev/null +++ b/net/utils/net_icmpchksum.c @@ -0,0 +1,94 @@ +/**************************************************************************** + * net/utils/net_icmpchksum.c + * + * Copyright (C) 2007-2010, 2012, 2014-2015 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#ifdef CONFIG_NET + +#include +#include + +#include +#include +#include + +#include "utils/utils.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define ICMPBUF ((struct icmp_iphdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)]) +#define ICMPv6BUF ((struct icmp_ipv6hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)]) + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: icmp_chksum + * + * Description: + * Calculate the checksum of the ICMP message + * + ****************************************************************************/ + +#if defined(CONFIG_NET_ICMP) && defined(CONFIG_NET_ICMP_PING) +uint16_t icmp_chksum(FAR struct net_driver_s *dev, int len) +{ + FAR struct icmp_iphdr_s *icmp = ICMPBUF; + return net_chksum((FAR uint16_t *)&icmp->type, len); +} +#endif /* CONFIG_NET_ICMP && CONFIG_NET_ICMP_PING */ + +/**************************************************************************** + * Name: icmpv6_chksum + * + * Description: + * Calculate the checksum of the ICMPv6 message + * + ****************************************************************************/ + +#ifdef CONFIG_NET_ICMPv6 +uint16_t icmpv6_chksum(FAR struct net_driver_s *dev) +{ + return ipv6_upperlayer_chksum(dev, IP_PROTO_ICMP6); +} +#endif + +#endif /* CONFIG_NET */ diff --git a/net/utils/net_incr32.c b/net/utils/net_incr32.c new file mode 100644 index 0000000000..b80acb6f8d --- /dev/null +++ b/net/utils/net_incr32.c @@ -0,0 +1,121 @@ +/**************************************************************************** + * net/utils/net_incr32.c + * + * Copyright (C) 2007-2010, 2012, 2014-2015, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include +#include +#include +#include + +#include "utils/utils.h" + +#ifndef CONFIG_NET_ARCH_INCR32 + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: net_carry32 + * + * Description: + * Calculate the Internet checksum over a buffer. + * + ****************************************************************************/ + +static inline void net_carry32(FAR uint8_t *sum, uint16_t op16) +{ + if (sum[2] < (op16 >> 8)) + { + ++sum[1]; + if (sum[1] == 0) + { + ++sum[0]; + } + } + + if (sum[3] < (op16 & 0xff)) + { + ++sum[2]; + if (sum[2] == 0) + { + ++sum[1]; + if (sum[1] == 0) + { + ++sum[0]; + } + } + } +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: net_incr32 + * + * Description: + * + * Carry out a 32-bit addition. + * + * By defining CONFIG_NET_ARCH_INCR32, the architecture can replace + * net_incr32 with hardware assisted solutions. + * + * Input Parameters: + * op32 - A pointer to a 4-byte array representing a 32-bit integer in + * network byte order (big endian). This value may not be word + * aligned. The value pointed to by op32 is modified in place + * + * op16 - A 16-bit integer in host byte order. + * + ****************************************************************************/ + +void net_incr32(FAR uint8_t *op32, uint16_t op16) +{ + op32[3] += (op16 & 0xff); + op32[2] += (op16 >> 8); + net_carry32(op32, op16); +} + +#endif /* CONFIG_NET_ARCH_INCR32 */ diff --git a/net/utils/net_ipchksum.c b/net/utils/net_ipchksum.c new file mode 100644 index 0000000000..2006033599 --- /dev/null +++ b/net/utils/net_ipchksum.c @@ -0,0 +1,199 @@ +/**************************************************************************** + * net/utils/net_ipchksum.c + * + * Copyright (C) 2007-2010, 2012, 2014-2015, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include +#include +#include + +#include "utils/utils.h" + +#ifdef CONFIG_NET + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define IPv4BUF ((struct ipv4_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)]) +#define IPv6BUF ((struct ipv6_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)]) + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: ipv4_upperlayer_chksum + * + * Description: + * Perform the checksum calcaultion over the IPv4, protocol headers, and + * data payload as necessary. + * + * Input Parameters: + * dev - The network driver instance. The packet data is in the d_buf + * of the device. + * proto - The protocol being supported + * + * Returned Value: + * The calculated checksum + * + ****************************************************************************/ + +#if !defined(CONFIG_NET_ARCH_CHKSUM) && defined(CONFIG_NET_IPv4) +uint16_t ipv4_upperlayer_chksum(FAR struct net_driver_s *dev, uint8_t proto) +{ + FAR struct ipv4_hdr_s *ipv4 = IPv4BUF; + uint16_t upperlen; + uint16_t sum; + + /* The length reported in the IPv4 header is the length of both the IPv4 + * header and the payload that follows the header. We need to subtract + * the size of the IPv4 header to get the size of the payload. + */ + + upperlen = (((uint16_t)(ipv4->len[0]) << 8) + ipv4->len[1]) - IPv4_HDRLEN; + + /* Verify some minimal assumptions */ + + if (upperlen > NET_DEV_MTU(dev)) + { + return 0; + } + + /* First sum pseudo-header. */ + /* IP protocol and length fields. This addition cannot carry. */ + + sum = upperlen + proto; + + /* Sum IP source and destination addresses. */ + + sum = chksum(sum, (FAR uint8_t *)&ipv4->srcipaddr, 2 * sizeof(in_addr_t)); + + /* Sum IP payload data. */ + + sum = chksum(sum, &dev->d_buf[IPv4_HDRLEN + NET_LL_HDRLEN(dev)], upperlen); + return (sum == 0) ? 0xffff : htons(sum); +} +#endif /* CONFIG_NET_ARCH_CHKSUM */ + +/**************************************************************************** + * Name: ipv6_upperlayer_chksum + * + * Description: + * Perform the checksum calcaultion over the IPv6, protocol headers, and + * data payload as necessary. + * + * Input Parameters: + * dev - The network driver instance. The packet data is in the d_buf + * of the device. + * proto - The protocol being supported + * + * Returned Value: + * The calculated checksum + * + ****************************************************************************/ + +#if !defined(CONFIG_NET_ARCH_CHKSUM) && defined(CONFIG_NET_IPv6) +uint16_t ipv6_upperlayer_chksum(FAR struct net_driver_s *dev, uint8_t proto) +{ + FAR struct ipv6_hdr_s *ipv6 = IPv6BUF; + uint16_t upperlen; + uint16_t sum; + + /* The length reported in the IPv6 header is the length of the payload + * that follows the header. + */ + + upperlen = ((uint16_t)ipv6->len[0] << 8) + ipv6->len[1]; + + /* Verify some minimal assumptions */ + + if (upperlen > NET_DEV_MTU(dev)) + { + return 0; + } + + /* The checksum is calculated starting with a pseudo-header of IPv6 header + * fields according to the IPv6 standard, which consists of the source + * and destination addresses, the packet length and the next header field. + */ + + sum = upperlen + proto; + + /* Sum IP source and destination addresses. */ + + sum = chksum(sum, (FAR uint8_t *)&ipv6->srcipaddr, 2 * sizeof(net_ipv6addr_t)); + + /* Sum IP payload data. */ + + sum = chksum(sum, &dev->d_buf[IPv6_HDRLEN + NET_LL_HDRLEN(dev)], upperlen); + return (sum == 0) ? 0xffff : htons(sum); +} +#endif /* CONFIG_NET_ARCH_CHKSUM */ + +/**************************************************************************** + * Name: ipv4_chksum + * + * Description: + * Calculate the IPv4 header checksum of the packet header in d_buf. + * + * The IPv4 header checksum is the Internet checksum of the 20 bytes of + * the IPv4 header. + * + * If CONFIG_NET_ARCH_CHKSUM is defined, then this function must be + * provided by architecture-specific logic. + * + * Returned Value: + * The IPv4 header checksum of the IPv4 header in the d_buf buffer. + * + ****************************************************************************/ + +#if defined(CONFIG_NET_IPv4) && !defined(CONFIG_NET_ARCH_CHKSUM) +uint16_t ipv4_chksum(FAR struct net_driver_s *dev) +{ + uint16_t sum; + + sum = chksum(0, &dev->d_buf[NET_LL_HDRLEN(dev)], IPv4_HDRLEN); + return (sum == 0) ? 0xffff : htons(sum); +} +#endif /* CONFIG_NET_ARCH_CHKSUM */ + +#endif /* CONFIG_NET */ diff --git a/net/utils/net_tcpchksum.c b/net/utils/net_tcpchksum.c new file mode 100644 index 0000000000..b52226c6e1 --- /dev/null +++ b/net/utils/net_tcpchksum.c @@ -0,0 +1,104 @@ +/**************************************************************************** + * net/utils/net_tcpchksum.c + * + * Copyright (C) 2007-2010, 2012, 2014-2015, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include +#include + +#include "utils/utils.h" + +#ifdef CONFIG_NET_TCP + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: tcp_chksum, tcp_ipv4_chksum, and tcp_ipv6_chksum + * + * Description: + * Calculate the TCP checksum of the packet in d_buf and d_appdata. + * + * The TCP checksum is the Internet checksum of data contents of the + * TCP segment, and a pseudo-header as defined in RFC793. + * + * Note: The d_appdata pointer that points to the packet data may + * point anywhere in memory, so it is not possible to simply calculate + * the Internet checksum of the contents of the d_buf buffer. + * + * Returned Value: + * The TCP checksum of the TCP segment in d_buf and pointed to by + * d_appdata. + * + ****************************************************************************/ + +#ifndef CONFIG_NET_ARCH_CHKSUM +#ifdef CONFIG_NET_IPv4 +uint16_t tcp_ipv4_chksum(FAR struct net_driver_s *dev) +{ + return ipv4_upperlayer_chksum(dev, IP_PROTO_TCP); +} +#endif /* CONFIG_NET_IPv4 */ + +#ifdef CONFIG_NET_IPv6 +uint16_t tcp_ipv6_chksum(FAR struct net_driver_s *dev) +{ + return ipv6_upperlayer_chksum(dev, IP_PROTO_TCP); +} +#endif /* CONFIG_NET_IPv6 */ +#endif /* !CONFIG_NET_ARCH_CHKSUM */ + +#if defined(CONFIG_NET_IPv4) && defined(CONFIG_NET_IPv6) +uint16_t tcp_chksum(FAR struct net_driver_s *dev) +{ + if (IFF_IS_IPv6(dev->d_flags)) + { + return tcp_ipv6_chksum(dev); + } + else + { + return tcp_ipv4_chksum(dev); + } +} +#endif + +#endif /* CONFIG_NET_TCP */ diff --git a/net/utils/net_udpchksum.c b/net/utils/net_udpchksum.c new file mode 100644 index 0000000000..3f3eca11ab --- /dev/null +++ b/net/utils/net_udpchksum.c @@ -0,0 +1,85 @@ +/**************************************************************************** + * net/utils/net_udpchksum.c + * + * Copyright (C) 2007-2010, 2012, 2014-2015, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include +#include + +#include "utils/utils.h" + +#ifdef CONFIG_NET_UDP + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: udp_ipv4_chksum + * + * Description: + * Calculate the UDP/IPv4 checksum of the packet in d_buf and d_appdata. + * + ****************************************************************************/ + +#if defined(CONFIG_NET_UDP_CHECKSUMS) && defined(CONFIG_NET_IPv4) +uint16_t udp_ipv4_chksum(FAR struct net_driver_s *dev) +{ + return ipv4_upperlayer_chksum(dev, IP_PROTO_UDP); +} +#endif + +/**************************************************************************** + * Name: udp_ipv6_chksum + * + * Description: + * Calculate the UDP/IPv6 checksum of the packet in d_buf and d_appdata. + * + ****************************************************************************/ + +#if defined(CONFIG_NET_UDP_CHECKSUMS) && defined(CONFIG_NET_IPv6) +uint16_t udp_ipv6_chksum(FAR struct net_driver_s *dev) +{ + return ipv6_upperlayer_chksum(dev, IP_PROTO_UDP); +} +#endif + +#endif /* CONFIG_NET_UDP */ -- GitLab From 86dc312ae4ba21f15b0a4d9eec5ba027f7dda3b2 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 2 Apr 2017 16:29:02 -0600 Subject: [PATCH 314/990] iee802154 loopback: Eliminate dependency on CONFIG_NET_LOOPBACK --- wireless/ieee802154/Kconfig | 31 ++ wireless/ieee802154/Make.defs | 4 + wireless/ieee802154/mac802154_loopback.c | 585 +++++++++++++++++++++++ 3 files changed, 620 insertions(+) create mode 100644 wireless/ieee802154/mac802154_loopback.c diff --git a/wireless/ieee802154/Kconfig b/wireless/ieee802154/Kconfig index 5470894a7d..d030f5bd39 100644 --- a/wireless/ieee802154/Kconfig +++ b/wireless/ieee802154/Kconfig @@ -37,4 +37,35 @@ config IEEE802154_DEV Enables a device driver to expose ieee802.15.4 radio controls to user space as IOCTLs. +config IEEE802154_LOOPBACK + bool "IEEE802154 6loWPAN Loopback" + default n + depends on NET_6LOWPAN && NET_IPv6 + select ARCH_HAVE_NETDEV_STATISTICS + ---help--- + Add support for the IEEE802154 6loWPAN Loopback test device. + +if IEEE802154_LOOPBACK + +choice + prompt "Work queue" + default IEEE802154_LOOPBACK_LPWORK if SCHED_LPWORK + default IEEE802154_LOOPBACK_HPWORK if !SCHED_LPWORK && SCHED_HPWORK + depends on SCHED_WORKQUEUE + ---help--- + Work queue support is required to use the loopback driver. If the + low priority work queue is available, then it should be used by the + loopback driver. + +config IEEE802154_LOOPBACK_HPWORK + bool "High priority" + depends on SCHED_HPWORK + +config IEEE802154_LOOPBACK_LPWORK + bool "Low priority" + depends on SCHED_LPWORK + +endchoice # Work queue +endif # IEEE802154_LOOPBACK + endif # IEEE802154 diff --git a/wireless/ieee802154/Make.defs b/wireless/ieee802154/Make.defs index 4a69b06511..bb2531e3e7 100644 --- a/wireless/ieee802154/Make.defs +++ b/wireless/ieee802154/Make.defs @@ -53,6 +53,10 @@ ifeq ($(CONFIG_IEEE802154_DEV),y) CSRCS += radio802154_device.c endif +ifeq ($(CONFIG_IEEE802154_LOOPBACK),y) +CSRCS += mac802154_loopback.c +endif + DEPPATH += --dep-path ieee802154 VPATH += :ieee802154 CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)$(DELIM)wireless$(DELIM)ieee802154} diff --git a/wireless/ieee802154/mac802154_loopback.c b/wireless/ieee802154/mac802154_loopback.c new file mode 100644 index 0000000000..5bbd6f5beb --- /dev/null +++ b/wireless/ieee802154/mac802154_loopback.c @@ -0,0 +1,585 @@ +/**************************************************************************** + * wireless/iee802154/mac802154_loopback.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include +#include + +#ifndef CONFIG_NET_LOOPBACK +# include +#endif + +#ifdef CONFIG_IEEE802154_LOOPBACK + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* We need to have the work queue to handle SPI interrupts */ + +#if !defined(CONFIG_SCHED_WORKQUEUE) +# error Worker thread support is required (CONFIG_SCHED_WORKQUEUE) +#else +# if defined(CONFIG_IEEE802154_LOOPBACK_HPWORK) +# define LPBKWORK HPWORK +# elif defined(CONFIG_IEEE802154_LOOPBACK_LPWORK) +# define LPBKWORK LPWORK +# else +# error Neither CONFIG_IEEE802154_LOOPBACK_HPWORK nor CONFIG_IEEE802154_LOOPBACK_LPWORK defined +# endif +#endif + +/* TX poll delay = 1 seconds. CLK_TCK is the number of clock ticks per second */ + +#define LO_WDDELAY (1*CLK_TCK) + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/* The lo_driver_s encapsulates all state information for a single hardware + * interface + */ + +struct lo_driver_s +{ + bool lo_bifup; /* true:ifup false:ifdown */ + bool lo_txdone; /* One RX packet was looped back */ + WDOG_ID lo_polldog; /* TX poll timer */ + struct work_s lo_work; /* For deferring poll work to the work queue */ + + /* This holds the information visible to the NuttX network */ + + struct ieee802154_driver_s lo_ieee; /* Interface understood by the network */ +}; + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static struct lo_driver_s g_loopback; +static uint8_t g_iobuffer[CONFIG_NET_6LOWPAN_MTU + CONFIG_NET_GUARDSIZE]; + +#ifndef CONFIG_NET_LOOPBACK +static const net_ipv6addr_t g_lo_ipv6addr = +{ + HTONS(0), HTONS(0), HTONS(0), HTONS(0), + HTONS(0), HTONS(0), HTONS(0), HTONS(1) +}; +#endif + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* Polling logic */ + +static int lo_txpoll(FAR struct net_driver_s *dev); +static void lo_poll_work(FAR void *arg); +static void lo_poll_expiry(int argc, wdparm_t arg, ...); + +/* NuttX callback functions */ + +static int lo_ifup(FAR struct net_driver_s *dev); +static int lo_ifdown(FAR struct net_driver_s *dev); +static void lo_txavail_work(FAR void *arg); +static int lo_txavail(FAR struct net_driver_s *dev); +#if defined(CONFIG_NET_IGMP) || defined(CONFIG_NET_ICMPv6) +static int lo_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac); +#ifdef CONFIG_NET_IGMP +static int lo_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac); +#endif +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: lo_txpoll + * + * Description: + * Check if the network has any outgoing packets ready to send. This is + * a callback from devif_poll() or devif_timer(). devif_poll() will be + * called only during normal TX polling. + * + * Parameters: + * dev - Reference to the NuttX driver state structure + * + * Returned Value: + * OK on success; a negated errno on failure + * + * Assumptions: + * May or may not be called from an interrupt handler. In either case, + * the network is locked. + * + ****************************************************************************/ + +static int lo_txpoll(FAR struct net_driver_s *dev) +{ + FAR struct lo_driver_s *priv = (FAR struct lo_driver_s *)dev->d_private; + FAR struct iob_s *head; + FAR struct iob_s *tail; + FAR struct iob_s *iob; + int ret; + + /* Remove the queued IOBs from driver structure */ + + head = priv->lo_ieee.i_framelist; + + /* Find the tail of the IOB queue */ + + for (tail = NULL, iob = head; + iob != NULL; + tail = iob, iob = iob->io_flink); + + /* Loop while there frames to be sent, i.e., while the IOB list is not + * emtpy. Sending, of course, just means relaying back through the network + * for this driver. + */ + + while (!FRAME_IOB_EMPTY(&priv->lo_ieee)) + { + /* Remove the IOB from the queue */ + + FRAME_IOB_REMOVE(&priv->lo_ieee, iob); + + /* Is the queue now empty? */ + + if (FRAME_IOB_EMPTY(&priv->lo_ieee)) + { + tail = NULL; + } + + /* Return the next frame to the network */ + + iob->io_flink = NULL; + priv->lo_ieee.i_framelist = iob; + + ninfo("Send frame %p to the network. Length=%u\n", iob, iob->io_len); + ret = sixlowpan_input(&priv->lo_ieee); + if (ret < 0) + { + nerr("ERROR: sixlowpan_input returned %d\n", ret); + } + + /* What if the network responds with more frames to send? */ + + if (priv->lo_ieee.i_framelist != NULL) + { + /* Append the new list to the tail of the queue */ + + iob = priv->lo_ieee.i_framelist; + priv->lo_ieee.i_framelist = NULL; + + if (tail == NULL) + { + head = iob; + } + else + { + tail->io_flink = iob; + } + + /* Find the new tail of the IOB queue */ + + for (tail = iob, iob = iob->io_flink; + iob != NULL; + tail = iob, iob = iob->io_flink); + } + + priv->lo_txdone = true; + } + + return 0; +} + +/**************************************************************************** + * Function: lo_poll_work + * + * Description: + * Perform periodic polling from the worker thread + * + * Parameters: + * arg - The argument passed when work_queue() as called. + * + * Returned Value: + * OK on success + * + * Assumptions: + * The network is locked + * + ****************************************************************************/ + +static void lo_poll_work(FAR void *arg) +{ + FAR struct lo_driver_s *priv = (FAR struct lo_driver_s *)arg; + + /* Perform the poll */ + + net_lock(); + priv->lo_txdone = false; + (void)devif_timer(&priv->lo_ieee.i_dev, lo_txpoll); + + /* Was something received and looped back? */ + + while (priv->lo_txdone) + { + /* Yes, poll again for more TX data */ + + priv->lo_txdone = false; + (void)devif_poll(&priv->lo_ieee.i_dev, lo_txpoll); + } + + /* Setup the watchdog poll timer again */ + + (void)wd_start(priv->lo_polldog, LO_WDDELAY, lo_poll_expiry, 1, priv); + net_unlock(); +} + +/**************************************************************************** + * Function: lo_poll_expiry + * + * Description: + * Periodic timer handler. Called from the timer interrupt handler. + * + * Parameters: + * argc - The number of available arguments + * arg - The first argument + * + * Returned Value: + * None + * + * Assumptions: + * The network is locked. + * + ****************************************************************************/ + +static void lo_poll_expiry(int argc, wdparm_t arg, ...) +{ + FAR struct lo_driver_s *priv = (FAR struct lo_driver_s *)arg; + + /* Schedule to perform the interrupt processing on the worker thread. */ + + work_queue(LPBKWORK, &priv->lo_work, lo_poll_work, priv, 0); +} + +/**************************************************************************** + * Function: lo_ifup + * + * Description: + * NuttX Callback: Bring up the Ethernet interface when an IP address is + * provided + * + * Parameters: + * dev - Reference to the NuttX driver state structure + * + * Returned Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +static int lo_ifup(FAR struct net_driver_s *dev) +{ + FAR struct lo_driver_s *priv = (FAR struct lo_driver_s *)dev->d_private; + +#if CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 2 + ninfo("Bringing up: Rime %02x:%02x PANID=%04x\n", + dev->d_ipv6addr[0], dev->d_ipv6addr[1], priv->lo_ieee.i_panid); +#elif CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 8 + ninfo("Bringing up: Rime %02x:%02x:%02x:%02x:%02x:%02x:%02x:%02x PANID=%04x\n", + dev->d_ipv6addr[0], dev->d_ipv6addr[1], dev->d_ipv6addr[2], + dev->d_ipv6addr[3], dev->d_ipv6addr[4], dev->d_ipv6addr[5], + dev->d_ipv6addr[6], dev->d_ipv6addr[7], priv->lo_ieee.i_panid); +#endif + + /* Set and activate a timer process */ + + (void)wd_start(priv->lo_polldog, LO_WDDELAY, lo_poll_expiry, + 1, (wdparm_t)priv); + + priv->lo_bifup = true; + return OK; +} + +/**************************************************************************** + * Function: lo_ifdown + * + * Description: + * NuttX Callback: Stop the interface. + * + * Parameters: + * dev - Reference to the NuttX driver state structure + * + * Returned Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +static int lo_ifdown(FAR struct net_driver_s *dev) +{ + FAR struct lo_driver_s *priv = (FAR struct lo_driver_s *)dev->d_private; + + /* Cancel the TX poll timer and TX timeout timers */ + + wd_cancel(priv->lo_polldog); + + /* Mark the device "down" */ + + priv->lo_bifup = false; + return OK; +} + +/**************************************************************************** + * Function: lo_txavail_work + * + * Description: + * Perform an out-of-cycle poll on the worker thread. + * + * Parameters: + * arg - Reference to the NuttX driver state structure (cast to void*) + * + * Returned Value: + * None + * + * Assumptions: + * Called on the higher priority worker thread. + * + ****************************************************************************/ + +static void lo_txavail_work(FAR void *arg) +{ + FAR struct lo_driver_s *priv = (FAR struct lo_driver_s *)arg; + + /* Ignore the notification if the interface is not yet up */ + + net_lock(); + if (priv->lo_bifup) + { + do + { + /* If so, then poll the network for new XMIT data */ + + priv->lo_txdone = false; + (void)devif_poll(&priv->lo_ieee.i_dev, lo_txpoll); + } + while (priv->lo_txdone); + } + + net_unlock(); +} + +/**************************************************************************** + * Function: lo_txavail + * + * Description: + * Driver callback invoked when new TX data is available. This is a + * stimulus perform an out-of-cycle poll and, thereby, reduce the TX + * latency. + * + * Parameters: + * dev - Reference to the NuttX driver state structure + * + * Returned Value: + * None + * + * Assumptions: + * Called in normal user mode + * + ****************************************************************************/ + +static int lo_txavail(FAR struct net_driver_s *dev) +{ + FAR struct lo_driver_s *priv = (FAR struct lo_driver_s *)dev->d_private; + + /* Is our single work structure available? It may not be if there are + * pending interrupt actions and we will have to ignore the Tx + * availability action. + */ + + if (work_available(&priv->lo_work)) + { + /* Schedule to serialize the poll on the worker thread. */ + + work_queue(LPBKWORK, &priv->lo_work, lo_txavail_work, priv, 0); + } + + return OK; +} + +/**************************************************************************** + * Function: lo_addmac + * + * Description: + * NuttX Callback: Add the specified MAC address to the hardware multicast + * address filtering + * + * Parameters: + * dev - Reference to the NuttX driver state structure + * mac - The MAC address to be added + * + * Returned Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +#if defined(CONFIG_NET_IGMP) || defined(CONFIG_NET_ICMPv6) +static int lo_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) +{ + /* There is no multicast support in the loopback driver */ + + return OK; +} +#endif + +/**************************************************************************** + * Function: lo_rmmac + * + * Description: + * NuttX Callback: Remove the specified MAC address from the hardware multicast + * address filtering + * + * Parameters: + * dev - Reference to the NuttX driver state structure + * mac - The MAC address to be removed + * + * Returned Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +#ifdef CONFIG_NET_IGMP +static int lo_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) +{ + /* There is no multicast support in the loopback driver */ + + return OK; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: localhost_initialize + * + * Description: + * Initialize the Ethernet controller and driver + * + * Parameters: + * intf - In the case where there are multiple EMACs, this value + * identifies which EMAC is to be initialized. + * + * Returned Value: + * OK on success; Negated errno on failure. + * + * Assumptions: + * + ****************************************************************************/ + +int localhost_initialize(void) +{ + FAR struct lo_driver_s *priv; + FAR struct net_driver_s *dev; + + /* Get the interface structure associated with this interface number. */ + + priv = &g_loopback; + + /* Initialize the driver structure */ + + memset(priv, 0, sizeof(struct lo_driver_s)); + + dev = &priv->lo_ieee.i_dev; + dev->d_ifup = lo_ifup; /* I/F up (new IP address) callback */ + dev->d_ifdown = lo_ifdown; /* I/F down callback */ + dev->d_txavail = lo_txavail; /* New TX data callback */ +#ifdef CONFIG_NET_IGMP + dev->d_addmac = lo_addmac; /* Add multicast MAC address */ + dev->d_rmmac = lo_rmmac; /* Remove multicast MAC address */ +#endif + dev->d_buf = g_iobuffer; /* Attach the IO buffer */ + dev->d_private = (FAR void *)priv; /* Used to recover private state from dev */ + + /* Create a watchdog for timing polling for and timing of transmissions */ + + priv->lo_polldog = wd_create(); /* Create periodic poll timer */ + + /* Register the loopabck device with the OS so that socket IOCTLs can b + * performed. + */ + + (void)netdev_register(&priv->lo_ieee.i_dev, NET_LL_IEEE802154); + + /* Set the local loopback IP address */ + + net_ipv6addr_copy(dev->d_ipv6addr, g_lo_ipv6addr); + net_ipv6addr_copy(dev->d_ipv6draddr, g_lo_ipv6addr); + net_ipv6addr_copy(dev->d_ipv6netmask, g_ipv6_alloneaddr); + + /* Put the network in the UP state */ + + dev->d_flags = IFF_UP; + return lo_ifup(&priv->lo_ieee.i_dev); +} + +#endif /* CONFIG_IEEE802154_LOOPBACK */ -- GitLab From 1b6630ee7557687f7717b52a0d938c72a3e047a8 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 2 Apr 2017 17:46:22 -0600 Subject: [PATCH 315/990] 6loWPAN: Fix compile errors and warnings when building the complete 6loWPAN configuration. --- arch/sim/Kconfig | 9 +++++++++ arch/sim/src/Makefile | 8 +++++--- arch/sim/src/up_idle.c | 2 +- arch/sim/src/up_initialize.c | 2 +- arch/sim/src/up_netdriver.c | 12 ++++++++---- configs/sim/nettest/defconfig | 14 +++++++++++++- configs/sim/udgram/defconfig | 14 +++++++++++++- configs/sim/ustream/defconfig | 14 +++++++++++++- include/nuttx/net/netconfig.h | 12 ++++++------ libc/netdb/lib_dnscache.c | 4 ++-- libc/netdb/lib_dnsinit.c | 1 + net/sixlowpan/sixlowpan_framelist.c | 4 ++-- net/sixlowpan/sixlowpan_send.c | 1 + net/tcp/tcp_devpoll.c | 1 + net/tcp/tcp_timer.c | 1 + 15 files changed, 77 insertions(+), 22 deletions(-) diff --git a/arch/sim/Kconfig b/arch/sim/Kconfig index 5168c7796e..5bf4695154 100644 --- a/arch/sim/Kconfig +++ b/arch/sim/Kconfig @@ -100,10 +100,19 @@ config SIM_WALLTIME correct for the system timer tick rate. With this definition in the configuration, sleep() behavior is more or less normal. +config SIM_NETDEV + bool "Simulated Network Device" + default y + depends on NET + ---help--- + Build in support for a simulated network device using a TAP device on Linux or + WPCAP on Windows. + if HOST_LINUX choice prompt "Simulation Network Type" default SIM_NET_HOST_ROUTE + depends on SIM_NETDEV config SIM_NET_HOST_ROUTE bool "Use local host route" diff --git a/arch/sim/src/Makefile b/arch/sim/src/Makefile index 540c1c6fc8..5668604ce5 100644 --- a/arch/sim/src/Makefile +++ b/arch/sim/src/Makefile @@ -119,6 +119,7 @@ ifeq ($(CONFIG_ARCH_ROMGETC),y) CSRCS += up_romgetc.c endif +ifeq ($(CONFIG_SIM_NETDEV),y) ifeq ($(CONFIG_NET_ETHERNET),y) CSRCS += up_netdriver.c HOSTCFLAGS += -DNETDEV_BUFSIZE=$(CONFIG_NET_ETH_MTU) @@ -131,11 +132,12 @@ endif ifeq ($(CONFIG_SIM_NET_HOST_ROUTE),y) HOSTCFLAGS += -DCONFIG_SIM_NET_HOST_ROUTE endif -else +else # HOSTOS != Cygwin HOSTSRCS += up_wpcap.c up_netdev.c DRVLIB = /lib/w32api/libws2_32.a /lib/w32api/libiphlpapi.a -endif -endif +endif # HOSTOS != Cygwin +endif # CONFIG_NET_ETHERNET +endif # CONFIG_SIM_NETDEV ifeq ($(CONFIG_SMP),y) HOSTCFLAGS += -DCONFIG_SMP=1 -DCONFIG_SMP_NCPUS=$(CONFIG_SMP_NCPUS) diff --git a/arch/sim/src/up_idle.c b/arch/sim/src/up_idle.c index 1912bf755c..05067a7c7c 100644 --- a/arch/sim/src/up_idle.c +++ b/arch/sim/src/up_idle.c @@ -142,7 +142,7 @@ void up_idle(void) } #endif -#ifdef CONFIG_NET_ETHERNET +#if defined(CONFIG_NET_ETHERNET) && defined(CONFIG_SIM_NETDEV) /* Run the network if enabled */ netdriver_loop(); diff --git a/arch/sim/src/up_initialize.c b/arch/sim/src/up_initialize.c index ada5bb33ba..fa8468196e 100644 --- a/arch/sim/src/up_initialize.c +++ b/arch/sim/src/up_initialize.c @@ -270,7 +270,7 @@ void up_initialize(void) up_registerblockdevice(); /* Our FAT ramdisk at /dev/ram0 */ #endif -#ifdef CONFIG_NET_ETHERNET +#if defined(CONFIG_NET_ETHERNET) && defined(CONFIG_SIM_NETDEV) netdriver_init(); /* Our "real" network driver */ #endif diff --git a/arch/sim/src/up_netdriver.c b/arch/sim/src/up_netdriver.c index d9c12ae339..bb37ec9fcc 100644 --- a/arch/sim/src/up_netdriver.c +++ b/arch/sim/src/up_netdriver.c @@ -209,7 +209,7 @@ void netdriver_loop(void) { pkt_input(&g_sim_dev); } -#endif +#endif /* CONFIG_NET_PKT */ /* We only accept IP packets of the configured type and ARP packets */ @@ -253,7 +253,7 @@ void netdriver_loop(void) } } else -#endif +#endif /* CONFIG_NET_IPv4 */ #ifdef CONFIG_NET_IPv6 if (eth->type == HTONS(ETHTYPE_IP6) && is_ours) { @@ -283,7 +283,7 @@ void netdriver_loop(void) { neighbor_out(&g_sim_dev); } -#endif +#endif /* CONFIG_NET_IPv6 */ /* And send the packet */ @@ -291,7 +291,7 @@ void netdriver_loop(void) } } else -#endif +#endif/* CONFIG_NET_IPv6 */ #ifdef CONFIG_NET_ARP if (eth->type == htons(ETHTYPE_ARP)) { @@ -307,7 +307,11 @@ void netdriver_loop(void) netdev_send(g_sim_dev.d_buf, g_sim_dev.d_len); } } + else #endif + { + nwarn("WARNING: Unsupported Ethernet type %u\n", eth->type) + } } } diff --git a/configs/sim/nettest/defconfig b/configs/sim/nettest/defconfig index 14b60be76e..2c94b1e3a6 100644 --- a/configs/sim/nettest/defconfig +++ b/configs/sim/nettest/defconfig @@ -77,6 +77,7 @@ CONFIG_HOST_X86_64=y CONFIG_SIM_X8664_SYSTEMV=y # CONFIG_SIM_X8664_MICROSOFT is not set # CONFIG_SIM_WALLTIME is not set +CONFIG_SIM_NETDEV=y CONFIG_SIM_NET_HOST_ROUTE=y # CONFIG_SIM_NET_BRIDGE is not set # CONFIG_SIM_FRAMEBUFFER is not set @@ -203,6 +204,8 @@ CONFIG_MAX_TASKS=64 # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -368,6 +371,7 @@ CONFIG_SERIAL_CONSOLE=y # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -408,10 +412,12 @@ CONFIG_NET_GUARDSIZE=2 CONFIG_NET_ETHERNET=y # CONFIG_NET_LOOPBACK is not set # CONFIG_NET_TUN is not set +# CONFIG_NET_USRSOCK is not set # # Network Device Operations # +# CONFIG_NETDEV_IOCTL is not set # CONFIG_NETDEV_PHY_IOCTL is not set # @@ -442,6 +448,7 @@ CONFIG_NET_SOCKOPTS=y # TCP/IP Networking # CONFIG_NET_TCP=y +# CONFIG_NET_TCP_NO_STACK is not set # CONFIG_NET_TCPURGDATA is not set CONFIG_NET_TCP_CONNS=40 CONFIG_NET_MAX_LISTENPORTS=40 @@ -456,6 +463,7 @@ CONFIG_NET_TCP_RECVDELAY=0 # UDP Networking # # CONFIG_NET_UDP is not set +# CONFIG_NET_UDP_NO_STACK is not set # # ICMP Networking Support @@ -484,6 +492,10 @@ CONFIG_NET_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 + +# +# User-space networking stack API +# # CONFIG_NET_ARCH_INCR32 is not set # CONFIG_NET_ARCH_CHKSUM is not set CONFIG_NET_STATISTICS=y @@ -717,7 +729,6 @@ CONFIG_EXAMPLES_NETTEST_IPADDR=0xc0a80080 CONFIG_EXAMPLES_NETTEST_DRIPADDR=0xc0a80001 CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 CONFIG_EXAMPLES_NETTEST_CLIENTIP=0xc0a8006a -# CONFIG_EXAMPLES_NRF24L01TERM is not set # CONFIG_EXAMPLES_NSH is not set # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -748,6 +759,7 @@ CONFIG_EXAMPLES_NETTEST_CLIENTIP=0xc0a8006a # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set # CONFIG_EXAMPLES_WGET is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities diff --git a/configs/sim/udgram/defconfig b/configs/sim/udgram/defconfig index 87e97419c1..aacb9eb00e 100644 --- a/configs/sim/udgram/defconfig +++ b/configs/sim/udgram/defconfig @@ -77,6 +77,7 @@ CONFIG_HOST_X86_64=y CONFIG_SIM_X8664_SYSTEMV=y # CONFIG_SIM_X8664_MICROSOFT is not set CONFIG_SIM_WALLTIME=y +CONFIG_SIM_NETDEV=y CONFIG_SIM_NET_HOST_ROUTE=y # CONFIG_SIM_NET_BRIDGE is not set # CONFIG_SIM_FRAMEBUFFER is not set @@ -210,6 +211,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -380,6 +383,7 @@ CONFIG_SERIAL_CONSOLE=y # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -418,10 +422,12 @@ CONFIG_NET_GUARDSIZE=2 # CONFIG_NET_ETHERNET is not set # CONFIG_NET_LOOPBACK is not set # CONFIG_NET_TUN is not set +# CONFIG_NET_USRSOCK is not set # # Network Device Operations # +# CONFIG_NETDEV_IOCTL is not set # CONFIG_NETDEV_PHY_IOCTL is not set # @@ -453,11 +459,13 @@ CONFIG_NET_LOCAL_DGRAM=y # TCP/IP Networking # # CONFIG_NET_TCP is not set +# CONFIG_NET_TCP_NO_STACK is not set # # UDP Networking # # CONFIG_NET_UDP is not set +# CONFIG_NET_UDP_NO_STACK is not set # # IGMPv2 Client Support @@ -472,6 +480,10 @@ CONFIG_NET_LOCAL_DGRAM=y # Network I/O Buffer Support # # CONFIG_NET_IOB is not set + +# +# User-space networking stack API +# # CONFIG_NET_ARCH_INCR32 is not set # CONFIG_NET_ARCH_CHKSUM is not set # CONFIG_NET_STATISTICS is not set @@ -715,7 +727,6 @@ CONFIG_EXAMPLES_HELLO_STACKSIZE=2048 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -760,6 +771,7 @@ CONFIG_EXAMPLES_UDGRAM_CLIENT_PRIORITY=100 # CONFIG_EXAMPLES_USTREAM is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities diff --git a/configs/sim/ustream/defconfig b/configs/sim/ustream/defconfig index 3b4cf6bdd2..43bb73515d 100644 --- a/configs/sim/ustream/defconfig +++ b/configs/sim/ustream/defconfig @@ -77,6 +77,7 @@ CONFIG_HOST_X86_64=y CONFIG_SIM_X8664_SYSTEMV=y # CONFIG_SIM_X8664_MICROSOFT is not set CONFIG_SIM_WALLTIME=y +CONFIG_SIM_NETDEV=y CONFIG_SIM_NET_HOST_ROUTE=y # CONFIG_SIM_NET_BRIDGE is not set # CONFIG_SIM_FRAMEBUFFER is not set @@ -210,6 +211,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -380,6 +383,7 @@ CONFIG_SERIAL_CONSOLE=y # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -418,10 +422,12 @@ CONFIG_NET_GUARDSIZE=2 # CONFIG_NET_ETHERNET is not set # CONFIG_NET_LOOPBACK is not set # CONFIG_NET_TUN is not set +# CONFIG_NET_USRSOCK is not set # # Network Device Operations # +# CONFIG_NETDEV_IOCTL is not set # CONFIG_NETDEV_PHY_IOCTL is not set # @@ -453,11 +459,13 @@ CONFIG_NET_LOCAL_STREAM=y # TCP/IP Networking # # CONFIG_NET_TCP is not set +# CONFIG_NET_TCP_NO_STACK is not set # # UDP Networking # # CONFIG_NET_UDP is not set +# CONFIG_NET_UDP_NO_STACK is not set # # IGMPv2 Client Support @@ -472,6 +480,10 @@ CONFIG_NET_LOCAL_STREAM=y # Network I/O Buffer Support # # CONFIG_NET_IOB is not set + +# +# User-space networking stack API +# # CONFIG_NET_ARCH_INCR32 is not set # CONFIG_NET_ARCH_CHKSUM is not set # CONFIG_NET_STATISTICS is not set @@ -715,7 +727,6 @@ CONFIG_EXAMPLES_HELLO_STACKSIZE=2048 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -755,6 +766,7 @@ CONFIG_EXAMPLES_USTREAM_ADDR="/dev/fifo" # CONFIG_EXAMPLES_USTREAM_USE_POLL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities diff --git a/include/nuttx/net/netconfig.h b/include/nuttx/net/netconfig.h index b320e0b98f..9bbd0e9929 100644 --- a/include/nuttx/net/netconfig.h +++ b/include/nuttx/net/netconfig.h @@ -158,19 +158,19 @@ # endif # ifdef CONFIG_NET_SLIP -# define _MIN_SLIP_MTU MIN(_MIN_LO_MTU,CONFIG_NET_6LOWPAN_MTU) -# define _MAX_SLIP_MTU MAX(_MAX_LO_MTU,CONFIG_NET_6LOWPAN_MTU) +# define _MIN_SLIP_MTU MIN(_MIN_LO_MTU,CONFIG_NET_SLIP_MTU) +# define _MAX_SLIP_MTU MAX(_MAX_LO_MTU,CONFIG_NET_SLIP_MTU) # else # define _MIN_SLIP_MTU _MIN_LO_MTU # define _MAX_SLIP_MTU _MAX_LO_MTU # endif # 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) +# define _MIN_6LOWPAN_MTU MIN(_MIN_SLIP_MTU,CONFIG_NET_6LOWPAN_MTU) +# define _MAX_6LOWPAN_MTU MAX(_MAX_SLIP_MTU,CONFIG_NET_6LOWPAN_MTU) # else -# define _MIN_6LOWPAN_MTU _MIN_LO_MTU -# define _MAX_6LOWPAN_MTU _MAX_LO_MTU +# define _MIN_6LOWPAN_MTU _MIN_SLIP_MTU +# define _MAX_6LOWPAN_MTU _MAX_SLIP_MTU # endif # define MIN_NET_DEV_MTU _MIN_6LOWPAN_MTU diff --git a/libc/netdb/lib_dnscache.c b/libc/netdb/lib_dnscache.c index 5a95dc9b1b..30cfdcd577 100644 --- a/libc/netdb/lib_dnscache.c +++ b/libc/netdb/lib_dnscache.c @@ -268,8 +268,8 @@ int dns_find_answer(FAR const char *hostname, FAR struct sockaddr *addr, /* We have a match. Return the resolved host address */ #ifdef CONFIG_NET_IPv4 - if (entry->addr.addr.sa_family == AF_INET) #ifdef CONFIG_NET_IPv6 + if (entry->addr.addr.sa_family == AF_INET) #endif { inlen = sizeof(struct sockaddr_in); @@ -277,8 +277,8 @@ int dns_find_answer(FAR const char *hostname, FAR struct sockaddr *addr, #endif #ifdef CONFIG_NET_IPv6 - else #ifdef CONFIG_NET_IPv4 + else #endif { inlen = sizeof(struct sockaddr_in6); diff --git a/libc/netdb/lib_dnsinit.c b/libc/netdb/lib_dnsinit.c index 04b490a167..b6e0f8d0e0 100644 --- a/libc/netdb/lib_dnsinit.c +++ b/libc/netdb/lib_dnsinit.c @@ -39,6 +39,7 @@ #include +#include #include #include #include diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c index 62582bed1c..f206a3fe9f 100644 --- a/net/sixlowpan/sixlowpan_framelist.c +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -370,7 +370,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, /* Add the frame header */ verify = sixlowpan_framecreate(ieee, iob, ieee->i_panid); - DEBUGASSERT(vreify == framer_hdrlen); + DEBUGASSERT(verify == framer_hdrlen); UNUSED(verify); /* Move HC1/HC06/IPv6 header */ @@ -436,7 +436,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, /* Add the frame header to the prealloated IOB. */ verify = sixlowpan_framecreate(ieee, iob, ieee->i_panid); - DEBUGASSERT(vreify == framer_hdrlen); + DEBUGASSERT(verify == framer_hdrlen); UNUSED(verify); /* Copy the payload and queue */ diff --git a/net/sixlowpan/sixlowpan_send.c b/net/sixlowpan/sixlowpan_send.c index f8076449b9..98cc577f5f 100644 --- a/net/sixlowpan/sixlowpan_send.c +++ b/net/sixlowpan/sixlowpan_send.c @@ -40,6 +40,7 @@ #include #include +#include #include #include diff --git a/net/tcp/tcp_devpoll.c b/net/tcp/tcp_devpoll.c index 6a7f16c513..d292d46473 100644 --- a/net/tcp/tcp_devpoll.c +++ b/net/tcp/tcp_devpoll.c @@ -46,6 +46,7 @@ #if defined(CONFIG_NET) && defined(CONFIG_NET_TCP) #include +#include #include #include diff --git a/net/tcp/tcp_timer.c b/net/tcp/tcp_timer.c index eeabb0910c..245e849ec6 100644 --- a/net/tcp/tcp_timer.c +++ b/net/tcp/tcp_timer.c @@ -46,6 +46,7 @@ #if defined(CONFIG_NET) && defined(CONFIG_NET_TCP) #include +#include #include #include -- GitLab From dfe6a672c1ddeafc934dabc3cc7134fa5bbe8dc8 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Mon, 3 Apr 2017 07:28:22 -0600 Subject: [PATCH 316/990] drivers/sensors: Add driver for ST LIS2DH accelerometer. From Timo Voutilainen et al. --- drivers/sensors/Kconfig | 33 +- drivers/sensors/Make.defs | 4 + drivers/sensors/lis2dh.c | 2033 ++++++++++++++++++++++++++++++++ include/nuttx/sensors/ioctl.h | 10 + include/nuttx/sensors/lis2dh.h | 441 +++++++ 5 files changed, 2519 insertions(+), 2 deletions(-) create mode 100644 drivers/sensors/lis2dh.c create mode 100644 include/nuttx/sensors/lis2dh.h diff --git a/drivers/sensors/Kconfig b/drivers/sensors/Kconfig index 969f5e1010..b5fc76cb41 100644 --- a/drivers/sensors/Kconfig +++ b/drivers/sensors/Kconfig @@ -75,12 +75,41 @@ config SENSOR_KXTJ9_I2C_BUS_SPEED endif # SENSOR_KXTJ9 +config LIS2DH + bool "STMicro LIS2DH device support" + default n + select I2C + ---help--- + Enable driver support for the STMicro LIS2DH accelerometer + +if LIS2DH + +config DEBUG_LIS2DH + bool "Debug support for the LIS2DH" + default n + ---help--- + Enables debug features for the LIS2DH + +config LIS2DH_NPOLLWAITERS + int "Number of waiters to poll" + default 2 + ---help--- + Maximum number of threads that can be waiting on poll() + +config LIS2DH_DRIVER_SELFTEST + bool "Enable selftest in LIS2DH driver" + default n + ---help--- + Enable selftest in LIS2DH driver + +endif # LIS2DH + config LIS3DSH - bool "STMicro LIS3DSH 3-Axis acclerometer support" + bool "STMicro LIS3DSH 3-Axis accelerometer support" default n select SPI ---help--- - Enable driver support for the STMicro LIS3DSH 3-Axis acclerometer. + Enable driver support for the STMicro LIS3DSH 3-Axis accelerometer. config LIS331DL bool "STMicro LIS331DL device support" diff --git a/drivers/sensors/Make.defs b/drivers/sensors/Make.defs index b676c4aa8e..7a5d5a0bba 100644 --- a/drivers/sensors/Make.defs +++ b/drivers/sensors/Make.defs @@ -53,6 +53,10 @@ ifeq ($(CONFIG_SENSOR_KXTJ9),y) CSRCS += kxtj9.c endif +ifeq ($(CONFIG_LIS2DH),y) + CSRCS += lis2dh.c +endif + ifeq ($(CONFIG_LIS3DSH),y) CSRCS += lis3dsh.c endif diff --git a/drivers/sensors/lis2dh.c b/drivers/sensors/lis2dh.c new file mode 100644 index 0000000000..003baa390a --- /dev/null +++ b/drivers/sensors/lis2dh.c @@ -0,0 +1,2033 @@ +/**************************************************************************** + * drivers/sensors/lis2dh.c + * LIS2DH accelerometer driver + * + * Copyright (C) 2014-2017 Haltian Ltd. All rights reserved. + * Authors: Timo Voutilainen + * Jussi Kivilinna + * 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 + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#ifdef CONFIG_DEBUG_LIS2DH +# define lis2dh_dbg(x, ...) _info(x, ##__VA_ARGS__) +#else +# define lis2dh_dbg(x, ...) sninfo(x, ##__VA_ARGS__) +#endif + +#ifdef CONFIG_LIS2DH_DRIVER_SELFTEST +# define LSB_AT_10BIT_RESOLUTION 4 +# define LSB_AT_12BIT_RESOLUTION 1 +# define SELFTEST_BUF_SIZE 5 +# define SELFTEST_MAX_READ_ATTEMPTS 200 +# define SELFTEST_ABS_DIFF_MIN_10BIT 17 +# define SELFTEST_ABS_DIFF_MAX_10_BIT 360 +# define SELFTEST_ABS_DIFF_MIN_12BIT (LSB_AT_10BIT_RESOLUTION * SELFTEST_ABS_DIFF_MIN_10BIT) +# define SELFTEST_ABS_DIFF_MAX_12BIT (LSB_AT_10BIT_RESOLUTION * SELFTEST_ABS_DIFF_MAX_10_BIT) +# define SELFTEST_0 0 +# define SELFTEST_1 1 +#endif + +/* Miscellaneous macros */ + +#define LIS2DH_I2C_RETRIES 10 +#define LIS2DH_COUNT_INTS + +/**************************************************************************** + * Private Data Types + ****************************************************************************/ + +enum interrupts +{ + LIS2DH_INT1 = 1, + LIS2DH_INT2 = 2 +}; + +struct lis2dh_dev_s +{ + FAR struct i2c_master_s *i2c; /* I2C interface */ + uint8_t addr; /* I2C address */ + FAR struct lis2dh_config_s *config; /* Platform specific configuration */ + struct lis2dh_setup *setup; /* User defined device operation mode setup */ + struct lis2dh_vector_s vector_data; /* Latest read data read from lis2dh */ + int scale; /* Full scale in milliG */ + sem_t devsem; /* Manages exclusive access to this structure */ + bool fifo_used; /* LIS2DH configured to use FIFO */ + bool fifo_stopped;/* FIFO got full and has stopped. */ +#ifdef LIS2DH_COUNT_INTS + volatile int16_t int_pending; /* Interrupt received but data not read, yet */ +#else + volatile bool int_pending; /* Interrupt received but data not read, yet */ +#endif +#ifndef CONFIG_DISABLE_POLL + struct pollfd *fds[CONFIG_LIS2DH_NPOLLWAITERS]; +#endif +}; + +/**************************************************************************** + * Private Function prototypes + ****************************************************************************/ + +static int lis2dh_open(FAR struct file *filep); +static int lis2dh_close(FAR struct file *filep); +static ssize_t lis2dh_read(FAR struct file *, FAR char *, size_t); +static ssize_t lis2dh_write(FAR struct file *filep, + FAR const char *buffer, size_t buflen); +static int lis2dh_ioctl(FAR struct file *filep, int cmd, + unsigned long arg); +static int lis2dh_access(FAR struct lis2dh_dev_s *dev, + uint8_t subaddr, FAR uint8_t *buf, int length); +static int lis2dh_get_reading(FAR struct lis2dh_dev_s *dev, + FAR struct lis2dh_vector_s *res, bool force_read); +static int lis2dh_powerdown(FAR struct lis2dh_dev_s dev); +static int lis2dh_reboot(FAR struct lis2dh_dev_s *dev); +static int lis2dh_poll(FAR struct file *filep, + FAR struct pollfd *fds, bool setup); +static void lis2dh_notify(FAR struct lis2dh_dev_s *priv); +static int lis2dh_int_handler(int irq, FAR void *context, + FAR void *arg); +static int lis2dh_setup(FAR struct lis2dh_dev_s *dev, + FAR struct lis2dh_setup *new_setup); +static inline int16_t lis2dh_raw_to_mg(uint8_t raw_hibyte, + uint8_t raw_lobyte, int scale); +static int lis2dh_read_temp(FAR struct lis2dh_dev_s *dev, + FAR int16_t *temper); +static int lis2dh_clear_interrupts(FAR struct lis2dh_dev_s *priv, + uint8_t interrupts); +static unsigned int lis2dh_get_fifo_readings(FAR struct lis2dh_dev_s *priv, + FAR struct lis2dh_result *res, unsigned int readcount, + FAR int *perr); +#ifdef CONFIG_LIS2DH_DRIVER_SELFTEST +static int lis2dh_handle_selftest(FAR struct lis2dh_dev_s *priv); +static int16_t lis2dh_raw_convert_to_12bit(uint8_t raw_hibyte, + uint8_t raw_lobyte); +static FAR const struct lis2dh_vector_s * + lis2dh_get_raw_readings(FAR struct lis2dh_dev_s *dev, + FAR int *err); +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const struct file_operations g_lis2dhops = +{ + lis2dh_open, /* open */ + lis2dh_close, /* close */ + lis2dh_read, /* read */ + lis2dh_write, /* write */ + NULL, /* seek */ + lis2dh_ioctl /* ioctl */ +#ifndef CONFIG_DISABLE_POLL + , lis2dh_poll /* poll */ +#endif +#ifndef CONFIG_DISABLE_PSEUDOFS_OPERATIONS + , NULL /* unlink */ +#endif +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static int lis2dh_who_am_i(FAR struct lis2dh_dev_s *dev, uint8_t *id) +{ + int ret; + + ret = lis2dh_access(dev, ST_LIS2DH_WHOAMI_REG, id, 1); + if (ret < 0) + { + lis2dh_dbg("Cannot read who am i value\n"); + return -EIO; + } + + return ret; +} + +/**************************************************************************** + * Name: lis2dh_open + * + * Description: + * This function is called whenever the LIS2DH device is opened. + * + ****************************************************************************/ + +static int lis2dh_open(FAR struct file *filep) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct lis2dh_dev_s *priv = inode->i_private; + uint8_t regval; + int ret = OK; + + /* Probe device */ + + if (lis2dh_access(priv, ST_LIS2DH_WHOAMI_REG, ®val, 1) > 0) + { + /* Check chip identification, in the future several more compatible parts + * may be added here. + */ + + if (regval == ST_LIS2DH_WHOAMI_VALUE) + { + priv->config->irq_enable(priv->config, true); + /* Normal exit point */ + ret = lis2dh_clear_interrupts(priv, LIS2DH_INT1 | LIS2DH_INT2); + return ret; + } + + /* Otherwise, we mark an invalid device found at given address */ + + ret = -ENODEV; + } + else + { + /* No response at given address is marked as */ + + ret = -EFAULT; + } + + /* Error exit */ + + return ret; +} + +/**************************************************************************** + * Name: lis2dh_close + * + * Description: + * This routine is called when the LIS2DH device is closed. + * + ****************************************************************************/ + +static int lis2dh_close(FAR struct file *filep) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct lis2dh_dev_s *priv = inode->i_private; + + priv->config->irq_enable(priv->config, false); + return lis2dh_powerdown(priv); +} + +/**************************************************************************** + * Name: lis2dh_fifo_start + * + * Description: + * This function restarts FIFO reading. + * + ****************************************************************************/ + +static int lis2dh_fifo_start(FAR struct lis2dh_dev_s *priv) +{ + uint8_t buf; + int err = OK; + + buf = 0x00 | priv->setup->trigger_selection | + priv->setup->fifo_trigger_threshold; + if (lis2dh_access(priv, ST_LIS2DH_FIFO_CTRL_REG, &buf, -1) != 1) + { + lis2dh_dbg("lis2dh: Failed to write FIFO control register\n"); + err = -EIO; + } + else + { + buf = priv->setup->fifo_mode | priv->setup->trigger_selection | + priv->setup->fifo_trigger_threshold; + if (lis2dh_access(priv, ST_LIS2DH_FIFO_CTRL_REG, &buf, -1) != 1) + { + lis2dh_dbg("lis2dh: Failed to write FIFO control register\n"); + err = -EIO; + } + else + { + priv->fifo_stopped = false; + + lis2dh_dbg("lis2dh: FIFO restarted\n"); + } + } + + return err; +} + +/**************************************************************************** + * Name: lis2dh_read + * + * Description: + * This routine is called when the LIS2DH device is read. + * + ****************************************************************************/ + +static ssize_t lis2dh_read(FAR struct file *filep, FAR char *buffer, + size_t buflen) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct lis2dh_dev_s *priv = inode->i_private; + FAR struct lis2dh_result *ptr; + int readcount = (buflen - sizeof(struct lis2dh_res_header)) / sizeof(struct lis2dh_vector_s); + uint8_t buf; + uint8_t int1_src = 0; + uint8_t int2_src = 0; + irqstate_t flags; + int err; + + if (buflen < sizeof(struct lis2dh_result) || + (buflen - sizeof(struct lis2dh_res_header)) % sizeof(struct lis2dh_vector_s) != 0) + { + lis2dh_dbg("lis2dh: Illegal amount of bytes to read: %d\n", buflen); + return -EINVAL; + } + + flags = enter_critical_section(); +#ifdef LIS2DH_COUNT_INTS + if (priv->int_pending > 0) + { + priv->int_pending--; + } + + DEBUGASSERT(priv->int_pending >= 0 && priv->int_pending < 10); +#else + priv->int_pending = false; +#endif + leave_critical_section(flags); + + /* Set pointer to first measurement data */ + + ptr = (FAR struct lis2dh_result *)buffer; + + err = sem_wait(&priv->devsem); + if (err < 0) + { + return -EINTR; + } + + ptr->header.meas_count = 0; + + if (!priv->fifo_used) + { + /* FIFO not used, read only one sample. */ + + if (readcount > 0) + { + err = lis2dh_get_reading(priv, &ptr->measurements[0], true); + if (err < 0) + { + lis2dh_dbg("lis2dh: Failed to read xyz\n"); + } + else + { + ptr->header.meas_count = 1; + } + } + } + else /* FIFO modes */ + { + uint8_t fifo_mode = priv->setup->fifo_mode & ST_LIS2DH_FIFOCR_MODE_MASK; + bool fifo_empty = false; + uint8_t fifo_num_samples; + + ptr->header.meas_count = 0; + + do + { + /* Check if FIFO needs to be restarted after being read empty. + * We need to read SRC_REG before reading measurement, as reading + * sample from FIFO clears OVRN_FIFO flag. + */ + + if (lis2dh_access(priv, ST_LIS2DH_FIFO_SRC_REG, &buf, 1) != 1) + { + lis2dh_dbg("lis2dh: Failed to read FIFO source register\n"); + return -EIO; + } + + if (fifo_mode != LIS2DH_STREAM_MODE) + { + /* FIFO is full and has stopped. */ + + priv->fifo_stopped |= !!(buf & ST_LIS2DH_FIFOSR_OVRN_FIFO); + } + + if (buf & ST_LIS2DH_FIFOSR_OVRN_FIFO) + { + lis2dh_dbg("lis2dh: FIFO overrun\n"); + } + + if (buf & ST_LIS2DH_FIFOSR_EMPTY) + { + lis2dh_dbg("lis2dh: FIFO empty\n"); + + fifo_empty = true; + + if (fifo_mode != LIS2DH_STREAM_MODE) + { + priv->fifo_stopped = true; + } + + /* FIFO is empty, skip reading. */ + + break; + } + + /* How many samples available in FIFO? */ + + fifo_num_samples = (buf & ST_LIS2DH_FIFOSR_NUM_SAMP_MASK) + 1; + + if (fifo_num_samples > readcount) + { + fifo_num_samples = readcount; + } + + ptr->header.meas_count += + lis2dh_get_fifo_readings(priv, ptr, fifo_num_samples, &err); + } + while (!fifo_empty && ptr->header.meas_count < readcount); + + if (!fifo_empty && fifo_mode != LIS2DH_TRIGGER_MODE) + { + /* FIFO was not read empty, more data available. */ + + flags = enter_critical_section(); + +#ifdef LIS2DH_COUNT_INTS + priv->int_pending++; +#else + priv->int_pending = true; +#endif + +#ifndef CONFIG_DISABLE_POLL + lis2dh_notify(priv); +#endif + + leave_critical_section(flags); + } + else if (fifo_mode != LIS2DH_STREAM_MODE && priv->fifo_stopped) + { + /* FIFO is empty and has stopped by overrun event. Reset FIFO for + * further reading. + */ + + err = lis2dh_fifo_start(priv); + } + } + + /* Make sure interrupt will get cleared (by reading this register) in case of + * latched configuration. + */ + + buf = 0; + if (lis2dh_access(priv, ST_LIS2DH_INT1_SRC_REG, &buf, 1) != 1) + { + lis2dh_dbg("lis2dh: Failed to read INT1_SRC_REG\n"); + err = -EIO; + } + if (buf & ST_LIS2DH_INT_SR_ACTIVE) + { + /* Interrupt has happened */ + + int1_src = buf; + ptr->header.int1_occurred = true; + } + else + { + ptr->header.int1_occurred = false; + } + + /* Make sure interrupt will get cleared (by reading this register) in case of + * latched configuration. + */ + + buf = 0; + if (lis2dh_access(priv, ST_LIS2DH_INT2_SRC_REG, &buf, 1) != 1) + { + lis2dh_dbg("lis2dh: Failed to read INT2_SRC_REG\n"); + err = -EIO; + } + if (buf & ST_LIS2DH_INT_SR_ACTIVE) + { + /* Interrupt has happened */ + + int2_src = buf; + ptr->header.int2_occurred = true; + } + else + { + ptr->header.int2_occurred = false; + } + ptr->header.int1_source = int1_src; + ptr->header.int2_source = int2_src; + + sem_post(&priv->devsem); + + /* 'err' was just for debugging, we do return partial reads here. */ + + return sizeof(ptr->header) + + ptr->header.meas_count * sizeof(struct lis2dh_vector_s); +} + +/**************************************************************************** + * Name: lis2dh_write + * Description: + * This routine is called when the LIS2DH device is written to. + ****************************************************************************/ + +static ssize_t lis2dh_write(FAR struct file *filep, FAR const char *buffer, + size_t buflen) +{ + DEBUGASSERT(filep != NULL && buffer != NULL && buflen > 0); + + return -ENOSYS; +} + +/**************************************************************************** + * Name: lis2dh_ioctl + * + * Description: + * This routine is called when ioctl function call + * for the LIS2DH device is done. + * + ****************************************************************************/ + +static int lis2dh_ioctl(FAR struct file *filep, int cmd, unsigned long arg) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct lis2dh_dev_s *priv = inode->i_private; + int ret; + uint8_t buf; + + DEBUGASSERT(filep != NULL); + + ret = sem_wait(&priv->devsem); + if (ret < 0) + { + return -EINTR; + } + + ret = OK; + switch (cmd) + { + case SNIOC_WRITESETUP: + { + /* Write to the configuration registers. Arg: uint8_t value */ + + ret = lis2dh_setup(priv, (struct lis2dh_setup *)arg); + lis2dh_dbg("lis2dh: conf: %02x ret: %d\n", *(uint8_t*)arg, ret); + + /* Make sure interrupt will get cleared (by reading this register) in + * case of latched configuration. + */ + + lis2dh_clear_interrupts(priv, LIS2DH_INT1 | LIS2DH_INT2); + } + break; + + case SNIOC_WRITE_INT1THRESHOLD: + { + buf = (uint8_t)arg; + + if (lis2dh_access(priv, ST_LIS2DH_INT1_THS_REG, &buf, -1) != 1) + { + lis2dh_dbg("lis2dh: Failed to write INT1_THS_REG\n"); + ret = -EIO; + } + + lis2dh_clear_interrupts(priv, LIS2DH_INT2); + } + break; + + case SNIOC_WRITE_INT2THRESHOLD: + { + buf = (uint8_t)arg; + + if (lis2dh_access(priv, ST_LIS2DH_INT2_THS_REG, &buf, -1) != 1) + { + lis2dh_dbg("lis2dh: Failed to write INT2_THS_REG\n"); + ret = -EIO; + } + + lis2dh_clear_interrupts(priv, LIS2DH_INT2); + } + break; + + case SNIOC_RESET_HPFILTER: + { + /* Read reference register to reset/recalib DC offset for HP filter */ + + if (lis2dh_access(priv, ST_LIS2DH_REFERENCE_REG, &buf, 1) != 1) + { + lis2dh_dbg("lis2dh: Failed to write reference register\n"); + ret = -EIO; + } + + lis2dh_clear_interrupts(priv, LIS2DH_INT2); + } + break; + + case SNIOC_START_SELFTEST: +#ifdef CONFIG_LIS2DH_DRIVER_SELFTEST + { + priv->config->irq_enable(priv->config, false); + lis2dh_clear_interrupts(priv, LIS2DH_INT1 | LIS2DH_INT2); + ret = lis2dh_handle_selftest(priv); + priv->config->irq_enable(priv->config, true); + } +#else + { + ret = -EINVAL; + } +#endif + break; + + case SNIOC_READ_TEMP: + { + ret = lis2dh_read_temp(priv, (int16_t *)arg); + } + break; + + case SNIOC_WHO_AM_I: + { + ret = lis2dh_who_am_i(priv, (uint8_t *)arg); + } + break; + + default: + { + lis2dh_dbg("lis2dh: Unrecognized cmd: %d\n", cmd); + ret = -ENOTTY; + } + break; + } + + sem_post(&priv->devsem); + return ret; +} + +/**************************************************************************** + * Name: lis2dh_poll + * + * Description: + * This routine is called during LIS2DH device poll + * + ****************************************************************************/ + +#ifndef CONFIG_DISABLE_POLL +static int lis2dh_poll(FAR struct file *filep, FAR struct pollfd *fds, + bool setup) +{ + FAR struct inode *inode; + FAR struct lis2dh_dev_s *priv; + int ret = OK; + int i; + + DEBUGASSERT(filep && fds); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct lis2dh_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_LIS2DH_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_LIS2DH_NPOLLWAITERS) + { + fds->priv = NULL; + ret = -EBUSY; + goto out; + } + + if (priv->int_pending) + { + lis2dh_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: + sem_post(&priv->devsem); + return ret; +} + +static void lis2dh_notify(FAR struct lis2dh_dev_s *priv) +{ + DEBUGASSERT(priv != NULL); + + int i; + + /* If there are threads waiting on poll() for LIS2DH 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_LIS2DH_NPOLLWAITERS; i++) + { + struct pollfd *fds = priv->fds[i]; + if (fds) + { + fds->revents |= POLLIN; + lis2dh_dbg("lis2dh: Report events: %02x\n", fds->revents); + sem_post(fds->sem); + } + } +} +#endif /* !CONFIG_DISABLE_POLL */ + +/**************************************************************************** + * Name: lis2dh_callback + * + * Description: + * lis2dh interrupt handler + * + ****************************************************************************/ + +static int lis2dh_int_handler(int irq, FAR void *context, FAR void *arg) +{ + FAR struct lis2dh_dev_s *priv = (FAR struct lis2dh_dev_s *)arg; + irqstate_t flags; + + DEBUGASSERT(priv != NULL); + + flags = enter_critical_section(); + +#ifdef LIS2DH_COUNT_INTS + priv->int_pending++; +#else + priv->int_pending = true; +#endif + +#ifndef CONFIG_DISABLE_POLL + lis2dh_notify(priv); +#endif + + leave_critical_section(flags); + + return OK; +} + +#ifdef CONFIG_LIS2DH_DRIVER_SELFTEST +/**************************************************************************** + * Name: lis2dh_clear_registers + * + * Description: + * Clear lis2dh registers + * + * Input Parameters: + * priv - pointer to LIS2DH Private Structure + * + * Returned Value: + * Returns OK in case of success, otherwise ERROR + * + ****************************************************************************/ + +static int lis2dh_clear_registers(FAR struct lis2dh_dev_s *priv) +{ + uint8_t i, buf = 0; + + DEBUGASSERT(priv); + + for (i = ST_LIS2DH_TEMP_CFG_REG; i <= ST_LIS2DH_ACT_DUR_REG; i++) + { + /* Skip read only registers */ + + if ((i <= 0x1e) || (i >= 0x27 && i <= 0x2d) || (i == 0x2f) || (i == 0x31)) + { + continue; + } + + if (lis2dh_access(priv, i, &buf, -1) != 1) + { + lis2dh_dbg("lis2dh: Failed to clear register 0x%02x\n", i); + return ERROR; + } + } + + return OK; +} + +/**************************************************************************** + * Name: lis2dh_write_register + * + * Description: + * Clear lis2dh registers + * + * Input Parameters: + * priv - pointer to LIS2DH Private Structure + * reg - target register + * value - value to write + * + * Returned Value: + * Returns OK in case of success, otherwise ERROR + * + ****************************************************************************/ + +static int lis2dh_write_register(FAR struct lis2dh_dev_s *priv, uint8_t reg, + uint8_t value) +{ + DEBUGASSERT(priv); + + if (lis2dh_access(priv, reg, &value, -1) != 1) + { + lis2dh_dbg("lis2dh: Failed to write %d to register 0x%02x\n", + value, reg); + return ERROR; + } + return OK; +} + +/**************************************************************************** + * Name: lis2dh_read_register + * + * Description: + * read lis2dh register + * + * Input Parameters: + * priv - pointer to LIS2DH Private Structure + * reg - register to read + * + * Returned Value: + * Returns positive register value in case of success, otherwise ERROR ( < 0) + ****************************************************************************/ + +static int lis2dh_read_register(FAR struct lis2dh_dev_s *priv, uint8_t reg) +{ + uint8_t buf; + + DEBUGASSERT(priv); + + if (lis2dh_access(priv, reg, &buf, sizeof(buf)) == sizeof(buf)) + { + return buf; + } + + return ERROR; +} + +/**************************************************************************** + * Name: lis2dh_handle_selftest + * + * Description: + * Handle selftest. Note, that after running selftest lis2dh is left in + * shutdown mode without valid setup. Therefore SNIOC_WRITESETUP must be + * sent again to proceed with normal operations. + * + ****************************************************************************/ + +static int lis2dh_handle_selftest(FAR struct lis2dh_dev_s *priv) +{ + const struct lis2dh_vector_s *results; + uint8_t i; + uint8_t j; + uint8_t buf; + int16_t avg_x_no_st = 0; + int16_t avg_y_no_st = 0; + int16_t avg_z_no_st = 0; + int16_t avg_x_with_st = 0; + int16_t avg_y_with_st = 0; + int16_t avg_z_with_st = 0; + int16_t abs_st_x_value; + int16_t abs_st_y_value; + int16_t abs_st_z_value; + int ret = OK; + int err = OK; + + DEBUGASSERT(priv); + + lis2dh_powerdown(priv); + + if (lis2dh_clear_registers(priv) != OK) + { + ret = -EIO; + goto out; + } + + /* Set the control register (23h) to ±2g FS, normal mode with BDU (Block + * Data Update) and HR (High Resolution) bits enabled. + */ + + if (lis2dh_write_register(priv, ST_LIS2DH_CTRL_REG4, 0x88) != OK) + { + lis2dh_dbg("lis2dh: Failed to write CTRL4 REG for selftest\n"); + ret = -EIO; + goto out; + } + + /* Set the control register (20h) to 50Hz ODR (Output Data Rate) with + * X/Y/Z axis enabled. + */ + + if (lis2dh_write_register(priv, ST_LIS2DH_CTRL_REG1, 0x47) != OK) + { + lis2dh_dbg("lis2dh: Failed to write CTRL1 REG for selftest\n"); + ret = -EIO; + goto out; + } + + /* Dummy reads so that values have stabilized */ + + for (i = 0; i < 20; i++) + { + if (lis2dh_get_raw_readings(priv, &err) == NULL) + { + ret = -EIO; + goto out; + } + } + + for (i = 0; i < SELFTEST_BUF_SIZE; i++) + { + results = lis2dh_get_raw_readings(priv, &err); + if (results == NULL) + { + ret = -EIO; + goto out; + } + + avg_x_no_st += results->x; + avg_y_no_st += results->y; + avg_z_no_st += results->z; + } + + avg_x_no_st = avg_x_no_st / SELFTEST_BUF_SIZE; + avg_y_no_st = avg_y_no_st / SELFTEST_BUF_SIZE; + avg_z_no_st = avg_z_no_st / SELFTEST_BUF_SIZE; + + for (i = SELFTEST_0; i <= SELFTEST_1; i++) + { + avg_x_with_st = 0; + avg_y_with_st = 0; + avg_z_with_st = 0; + + /* Enable self-test 0 or 1 at +/-2g FS with BDU and HR bits enabled. */ + + buf = (i == SELFTEST_0) ? 0x8a : 0x8c; + + if (lis2dh_write_register(priv, ST_LIS2DH_CTRL_REG4, buf) != OK) + { + lis2dh_dbg("lis2dh: Failed to write CTRL4 REG for selftest\n"); + ret = -EIO; + goto out; + } + + /* Dummy reads so that values have stabilized */ + + for (i = 0; i < 10; i++) + { + if (lis2dh_get_raw_readings(priv, &err) == NULL) + { + ret = -EIO; + goto out; + } + } + + for (j = 0; j < SELFTEST_BUF_SIZE; j++) + { + results = lis2dh_get_raw_readings(priv, &err); + if (results == NULL) + { + ret = -EIO; + goto out; + } + + avg_x_with_st += results->x; + avg_y_with_st += results->y; + avg_z_with_st += results->z; + } + + avg_x_with_st = avg_x_with_st / SELFTEST_BUF_SIZE; + avg_y_with_st = avg_y_with_st / SELFTEST_BUF_SIZE; + avg_z_with_st = avg_z_with_st / SELFTEST_BUF_SIZE; + + abs_st_x_value = abs(avg_x_with_st - avg_x_no_st); + abs_st_y_value = abs(avg_y_with_st - avg_y_no_st); + abs_st_z_value = abs(avg_z_with_st - avg_z_no_st); + + dbg ("ST %d, ABSX: %d, ABSY: %d, ABSZ: %d\n", + i, abs_st_x_value, abs_st_y_value, abs_st_z_value); + + if (abs_st_x_value < SELFTEST_ABS_DIFF_MIN_12BIT || + abs_st_x_value > SELFTEST_ABS_DIFF_MAX_12BIT || + abs_st_y_value < SELFTEST_ABS_DIFF_MIN_12BIT || + abs_st_y_value > SELFTEST_ABS_DIFF_MAX_12BIT || + abs_st_z_value < SELFTEST_ABS_DIFF_MIN_12BIT || + abs_st_z_value > SELFTEST_ABS_DIFF_MAX_12BIT) + { + dbg("Selftest %d fail! Limits (%d <= value <= %d). " + "Results: x: %d, y: %d, z: %d ", + i, + SELFTEST_ABS_DIFF_MIN_12BIT, SELFTEST_ABS_DIFF_MAX_12BIT, + abs_st_x_value, abs_st_y_value, abs_st_z_value); + ret = -ERANGE; + goto out; + } + } + + /* Verify INT1 and INT2 lines */ + + if (lis2dh_clear_registers(priv) != OK) + { + ret = -EIO; + goto out; + } + + /* Both INT lines should be low */ + + if (priv->config->read_int1_pin() != 0) + { + dbg("INT1 line is HIGH - expected LOW\n"); + ret = -ENXIO; + goto out; + } + + if (priv->config->read_int2_pin) + { + if (priv->config->read_int2_pin() != 0) + { + dbg("INT2 line is HIGH - expected LOW\n"); + ret = -ENODEV; + goto out; + } + } + + /* 400Hz ODR all axes enabled + FIFO overrun & DATA READY on INT1 + FIFO enabled and INT1 & INT2 latched + FIFO mode, INT1 , THS 0 + OR combination, all events enabled */ + + if ((lis2dh_write_register(priv, ST_LIS2DH_CTRL_REG1, 0x77) != OK) || + (lis2dh_write_register(priv, ST_LIS2DH_CTRL_REG3, 0x12) != OK) || + (lis2dh_write_register(priv, ST_LIS2DH_CTRL_REG5, 0x4a) != OK) || + (lis2dh_write_register(priv, ST_LIS2DH_FIFO_CTRL_REG, 0x40) != OK) || + (lis2dh_write_register(priv, ST_LIS2DH_INT1_CFG_REG, 0x3f) != OK)) + { + dbg("Writing registers for INT line check failed\n"); + ret = -EIO; + goto out; + } + + /* Clear INT1 & INT2 */ + + if ((lis2dh_read_register(priv, ST_LIS2DH_INT1_SRC_REG) == ERROR) || + (lis2dh_read_register(priv, ST_LIS2DH_INT2_SRC_REG) == ERROR)) + { + dbg("Failed to clear INT1 / INT2 registers\n"); + ret = -EIO; + goto out; + } + + usleep(20000); + + /* Now INT1 should have been latched high and INT2 should be still low */ + + if (priv->config->read_int1_pin() != 1) + { + dbg("INT1 line is LOW - expected HIGH\n"); + ret = -ENXIO; + goto out; + } + + if (priv->config->read_int2_pin) + { + if (priv->config->read_int2_pin() != 0) + { + dbg("INT2 line is HIGH - expected LOW\n"); + ret = -ENODEV; + goto out; + } + + /* Enable interupt 1 on INT2 pin */ + + if (lis2dh_write_register(priv, ST_LIS2DH_CTRL_REG6, 0x40) != OK) + { + dbg("Failed to enable interrupt 1 on INT2 pin"); + ret = -EIO; + goto out; + } + + usleep(20000); + + if (priv->config->read_int2_pin() != 1) + { + dbg("INT2 line is LOW - expected HIGH\n"); + ret = -ENODEV; + goto out; + } + } + +out: + (void)lis2dh_clear_registers(priv); + lis2dh_powerdown(priv); + + return ret; +} + +/**************************************************************************** + * Name: lis2dh_raw_to_mg + * + * Description: + * Convert raw acceleration value to mg + * + * Input Parameters: + * raw_hibyte - Hi byte of raw data + * raw_lobyte - Lo byte of raw data + * + * Returned Value: + * Returns acceleration value in mg + ****************************************************************************/ + +static int16_t lis2dh_raw_convert_to_12bit(uint8_t raw_hibyte, + uint8_t raw_lobyte) +{ + int16_t value; + + value = (raw_hibyte << 8) | raw_lobyte; + value = value >> 4; + + value &= 0xfff; + if (value & 0x800) + { + value = ~value; + value &= 0xfff; + value += 1; + value = -value; + } + + return value; +} + +/**************************************************************************** + * Name: lis2dh_data_available + * + * Description: + * Check if new data is available to read + * + * Input Parameters: + * dev - pointer to LIS2DH Private Structure + * + * Returned Value: + * Return true if new data is available. Otherwise returns false + * + ****************************************************************************/ + +static bool lis2dh_data_available(FAR struct lis2dh_dev_s *dev) +{ + uint8_t retval; + + DEBUGASSERT(dev); + + if (lis2dh_access(dev, ST_LIS2DH_STATUS_REG, &retval, + sizeof(retval)) == sizeof(retval)) + { + return ((retval & ST_LIS2DH_SR_ZYXDA) != 0); + } + return false; +} + +/**************************************************************************** + * Name: lis2dh_get_raw_readings + * + * Description: + * Read X, Y, Z - acceleration values from chip + * + * Input Parameters: + * dev - pointer to LIS2DH Private Structure + * + * Returned Value: + * Returns acceleration vectors (High resolution = 12bit values) on + * success, NULL otherwise. + * + ****************************************************************************/ + +static FAR const struct lis2dh_vector_s * + lis2dh_get_raw_readings(FAR struct lis2dh_dev_s *dev, int *err) +{ + uint8_t retval[6]; + uint8_t retries_left = SELFTEST_MAX_READ_ATTEMPTS; + + DEBUGASSERT(dev); + + *err = 0; + + while (--retries_left > 0) + { + usleep(20000); + if (lis2dh_data_available(dev)) + { + if (lis2dh_access(dev, ST_LIS2DH_OUT_X_L_REG, retval, + sizeof(retval)) == sizeof(retval)) + { + dev->vector_data.x = lis2dh_raw_convert_to_12bit(retval[1], retval[0]); + dev->vector_data.y = lis2dh_raw_convert_to_12bit(retval[3], retval[2]); + dev->vector_data.z = lis2dh_raw_convert_to_12bit(retval[5], retval[4]); + return &dev->vector_data; + } + + return NULL; + } + } + + return NULL; +} +#endif /* CONFIG_LIS2DH_DRIVER_SELFTEST */ + +/**************************************************************************** + * Name: lis2dh_clear_interrupts + * + * Description: + * Clear interrupts from LIS2DH chip + * + ****************************************************************************/ + +static int lis2dh_clear_interrupts(FAR struct lis2dh_dev_s *priv, + uint8_t interrupts) +{ + uint8_t buf; + int ret = OK; + + if (interrupts & LIS2DH_INT1) + { + /* Make sure interrupt will get cleared (by reading this register) in + * case of latched configuration. + */ + + if (lis2dh_access(priv, ST_LIS2DH_INT1_SRC_REG, &buf, 1) != 1) + { + lis2dh_dbg("lis2dh: Failed to read INT1_SRC_REG\n"); + ret = -EIO; + } + } + + if (interrupts & LIS2DH_INT2) + { + /* Make sure interrupt will get cleared (by reading this register) in + * case of latched configuration. + */ + + if (lis2dh_access(priv, ST_LIS2DH_INT2_SRC_REG, &buf, 1) != 1) + { + lis2dh_dbg("lis2dh: Failed to read INT2_SRC_REG\n"); + ret = -EIO; + } + } + + return ret; +} + +/**************************************************************************** + * Name: lis2dh_get_reading + * + * Description: + * Read X, Y, Z - acceleration value from chip + * + * Input Parameters: + * dev - pointer to LIS2DH Private Structure + * force_read - Read even if new data is not available (old data) + * + * Returned Value: + * Returns OK if success, negative error code otherwise + * + ****************************************************************************/ + +static int lis2dh_get_reading(FAR struct lis2dh_dev_s *dev, + FAR struct lis2dh_vector_s *res, + bool force_read) +{ + int scale = dev->scale; + uint8_t retval[7]; + int16_t x; + int16_t y; + int16_t z; + + if (lis2dh_access(dev, ST_LIS2DH_STATUS_REG, retval, 7) == 7) + { + /* If result is not yet ready, return NULL */ + + if (!force_read && !(retval[0] & ST_LIS2DH_SR_ZYXDA)) + { + lis2dh_dbg("lis2dh: Results were not ready\n"); + return -EAGAIN; + } + + /* Add something to entropy pool. */ + + add_sensor_randomness((((uint32_t)retval[6] << 25) | + ((uint32_t)retval[6] >> 7)) ^ + ((uint32_t)retval[5] << 20) ^ + ((uint32_t)retval[4] << 15) ^ + ((uint32_t)retval[3] << 10) ^ + ((uint32_t)retval[2] << 5) ^ + ((uint32_t)retval[1] << 0)); + + x = lis2dh_raw_to_mg(retval[2], retval[1], scale); + y = lis2dh_raw_to_mg(retval[4], retval[3], scale); + z = lis2dh_raw_to_mg(retval[6], retval[5], scale); + + if (dev->setup->xy_axis_fixup) + { + res->x = y; + res->y = -x; + } + else + { + res->x = x; + res->y = y; + } + + res->z = z; + return OK; + } + + return -EIO; +} + +/**************************************************************************** + * Name: lis2dh_get_fifo_readings + * + * Description: + * Bulk read from FIFO + * + ****************************************************************************/ + +static unsigned int lis2dh_get_fifo_readings(FAR struct lis2dh_dev_s *priv, + FAR struct lis2dh_result *res, + unsigned int readcount, + FAR int *perr) +{ + int scale = priv->scale; + union + { + uint8_t raw[6]; + struct lis2dh_vector_s sample; + } *buf = (void *)&res->measurements[res->header.meas_count]; + bool xy_axis_fixup = priv->setup->xy_axis_fixup; + size_t buflen = readcount * 6; + int16_t x; + int16_t y; + int16_t z; + unsigned int i; + + if (readcount == 0) + { + return 0; + } + + if (lis2dh_access(priv, ST_LIS2DH_OUT_X_L_REG, (void *)buf, buflen) != buflen) + { + lis2dh_dbg("lis2dh: Failed to read FIFO (%d bytes, %d samples)\n", + buflen, readcount); + *perr = -EIO; + return 0; + } + + /* Add something to entropy pool. */ + + up_rngaddentropy(RND_SRC_SENSOR, (void *)buf, buflen / 4); + + /* Convert raw values to mG */ + + for (i = 0; i < readcount; i++) + { + x = lis2dh_raw_to_mg(buf[i].raw[1], buf[i].raw[0], scale); + y = lis2dh_raw_to_mg(buf[i].raw[3], buf[i].raw[2], scale); + z = lis2dh_raw_to_mg(buf[i].raw[5], buf[i].raw[4], scale); + + if (xy_axis_fixup) + { + buf[i].sample.x = y; + buf[i].sample.y = -x; + } + else + { + buf[i].sample.x = x; + buf[i].sample.y = y; + } + + buf[i].sample.z = z; + } + + return readcount; +} + +/**************************************************************************** + * Name: lis2dh_raw_to_mg + * + * Description: + * Convert raw acceleration value to mg + * + * Input Parameters: + * raw_hibyte - Hi byte of raw data + * raw_lobyte - Lo byte of raw data + * scale - full scale in milliG + * + * Returned Value: + * Returns acceleration value in mg + * + ****************************************************************************/ + +static inline int16_t lis2dh_raw_to_mg(uint8_t raw_hibyte, uint8_t raw_lobyte, + int scale) +{ + int16_t value; + + /* Value is signed integer, range INT16_MIN..INT16_MAX. */ + + value = (raw_hibyte << 8) | raw_lobyte; + + /* Scale to mg, INT16_MIN..INT16_MAX => -scale..scale */ + + return (int32_t)value * scale / INT16_MAX; +} + +/**************************************************************************** + * Name: lis2dh_read_temp + * + * Description: + * + * Input Parameters: + * + * Returned Value: + * + ****************************************************************************/ + +static int lis2dh_read_temp(FAR struct lis2dh_dev_s *dev, FAR int16_t *temper) +{ + int ret; + uint8_t buf[2] = { 0 }; + + ret = lis2dh_access(dev, ST_LIS2DH_OUT_TEMP_L_REG, buf, 2); + if (ret < 0) + { + lis2dh_dbg("Cannot read temperature\n"); + return -EIO; + } + + *temper = buf[0] | ((int16_t)buf[1] << 8); + + return OK; +} + +/**************************************************************************** + * LIS2DH Access with range check + * + * Description: + * Read or write data via I2C + * + * Input Parameters: + * dev LIS2DH Private Structure + * subaddr LIS2DH Sub Address + * buf Pointer to buffer, either for read or write access + * length When >0 it denotes read access, when <0 it denotes write access + * of -length + * + * Returned Value: + * Returns actual length of data on success or negated errno. + * + ****************************************************************************/ + +static int lis2dh_access(FAR struct lis2dh_dev_s *dev, uint8_t subaddr, + FAR uint8_t *buf, int length) +{ + uint16_t flags = 0; + int retval; + int retries; + + DEBUGASSERT(dev != NULL && buf != NULL && length != 0); + + if (length > 0) + { + flags = I2C_M_READ; + } + else + { + flags = I2C_M_NORESTART; + length = -length; + } + + /* Check valid address ranges and set auto address increment flag */ + + if (subaddr == ST_LIS2DH_STATUS_AUX_REG) + { + if (length > 1) + { + length = 1; + } + } + else if (subaddr >= ST_LIS2DH_OUT_TEMP_L_REG && subaddr < 0x10) + { + if (length > (0x10 - subaddr)) + { + length = 0x10 - subaddr; + } + } + + else if (subaddr >= ST_LIS2DH_TEMP_CFG_REG && subaddr <= ST_LIS2DH_ACT_DUR_REG) + { + if (subaddr == ST_LIS2DH_OUT_X_L_REG) + { + /* FIFO bulk read, length maximum 6*32 = 192 bytes. */ + if (length > 6 * 32) + { + length = 6 * 32; + } + } + else + { + if (length > (ST_LIS2DH_ACT_DUR_REG + 1 - subaddr)) + { + length = ST_LIS2DH_ACT_DUR_REG + 1 - subaddr; + } + } + } + else + { + return -EFAULT; + } + + if (length > 1) + { + subaddr |= 0x80; + } + + for (retries = 0; retries < LIS2DH_I2C_RETRIES; retries++) + { + /* Create message and send */ + + struct i2c_msg_s msgv[2] = + { + { + .addr = dev->addr, + .flags = 0, + .buffer = &subaddr, + .length = 1 + }, + { + .addr = dev->addr, + .flags = flags, + .buffer = buf, + .length = length + } + }; + + retval = I2C_TRANSFER(dev->i2c, msgv, 2); + if (retval == OK) + { + return length; + } + else + { + /* Some error. Try to reset I2C bus and keep trying. */ +#ifdef CONFIG_I2C_RESET + int ret = up_i2creset(dev->i2c); + if (ret < 0) + { + lis2dh_dbg("up_i2creset failed: %d\n", ret); + return ret; + } +#endif + continue; + } + } + + lis2dh_dbg("failed, error: %d\n", retval); + return retval; +} + +/**************************************************************************** + * Name: lis2dh_reboot + * + * Description: + * + * Input Parameters: + * + * Returned Value: + * + ****************************************************************************/ + +static int lis2dh_reboot(FAR struct lis2dh_dev_s *dev) +{ + struct timespec start, curr; + int32_t diff_msec; + uint8_t value; + + (void)clock_gettime(CLOCK_MONOTONIC, &start); + + /* Reboot to reset chip. */ + + value = ST_LIS2DH_CR5_BOOT; + if (lis2dh_access(dev, ST_LIS2DH_CTRL_REG5, &value, -1) != 1) + { + return -EIO; + } + + /* Reboot is completed when reboot bit is cleared. */ + + do + { + value = 0; + if (lis2dh_access(dev, ST_LIS2DH_CTRL_REG5, &value, 1) != 1) + { + return -EIO; + } + + if (!(value & ST_LIS2DH_CR5_BOOT)) + { + break; + } + + (void)clock_gettime(CLOCK_MONOTONIC, &curr); + + diff_msec = (curr.tv_sec - start.tv_sec) * 1000; + diff_msec += (curr.tv_nsec - start.tv_nsec) / (1000 * 1000); + + if (diff_msec > 100) + { + return -ETIMEDOUT; + } + + usleep(1); + } + while (true); + + /* Reboot completed, chip is now in power-down state. */ + + return OK; +} + +/**************************************************************************** + * Name: lis2dh_powerdown + * + * Description: + * + * Input Parameters: + * + * Returned Value: + * + ****************************************************************************/ + +static int lis2dh_powerdown(FAR struct lis2dh_dev_s * dev) +{ + uint8_t buf = 0; + int ret = OK; + + if (lis2dh_access(dev, ST_LIS2DH_CTRL_REG1, &buf, -1) != 1) + { + lis2dh_dbg("Failed to clear CTRL_REG1\n"); + ret = -EIO; + } + + return ret; +} + +/**************************************************************************** + * LIS2DH Setup + * + * Description: + * Apply new register setup + * + * Input Parameters: + * dev - pointer to LIS2DH Private Structure + * new_setup - pointer to new setup data to be configured + * + * Returned Value: + * Returns OK on success, ERROR otherwise. + * + ****************************************************************************/ + +static int lis2dh_setup(FAR struct lis2dh_dev_s * dev, + FAR struct lis2dh_setup *new_setup) +{ + uint8_t value; + + dev->setup = new_setup; + + /* Clear old configuration. On first boot after power-loss, reboot bit does + * not get cleared, and lis2dh_reboot() times out. Anyway, chip accepts + * new configuration and functions correctly. */ + + (void)lis2dh_reboot(dev); + + /* TEMP_CFG_REG */ + + value = dev->setup->temp_enable ? (0x3 << 6): 0; + if (lis2dh_access(dev, ST_LIS2DH_TEMP_CFG_REG, &value, -1) != 1) + { + goto error; + } + + /* CTRL_REG2 */ + + value = dev->setup->hpmode | dev->setup->hpcf | dev->setup->fds | + dev->setup->hpclick | dev->setup->hpis2 | dev->setup->hpis1; + if (lis2dh_access(dev, ST_LIS2DH_CTRL_REG2, &value, -1) != 1) + { + goto error; + } + + /* CTRL_REG3 */ + + value = dev->setup->int1_click_enable | dev->setup->int1_aoi_enable | + dev->setup->int2_aoi_enable | dev->setup->int1_drdy_enable | + dev->setup->int2_drdy_enable | dev->setup->int_wtm_enable | + dev->setup->int_overrun_enable; + if (lis2dh_access(dev, ST_LIS2DH_CTRL_REG3, &value, -1) != 1) + { + goto error; + } + + /* CTRL_REG4 */ + + value = dev->setup->bdu | dev->setup->endian | dev->setup->fullscale | + dev->setup->high_resolution_enable | dev->setup->selftest | + dev->setup->spi_mode; + if (lis2dh_access(dev, ST_LIS2DH_CTRL_REG4, &value, -1) != 1) + { + goto error; + } + + /* CTRL_REG5 */ + + value = dev->setup->reboot | dev->setup->fifo_enable | dev->setup->int1_latch | + dev->setup->int1_4d_enable | dev->setup->int2_latch | + dev->setup->int2_4d_enable; + if (lis2dh_access(dev, ST_LIS2DH_CTRL_REG5, &value, -1) != 1) + { + goto error; + } + + /* CTRL_REG6 */ + + value = dev->setup->int2_click_enable | dev->setup->int_enable | + dev->setup->boot_int1_enable | dev->setup->high_low_active; + if (lis2dh_access(dev, ST_LIS2DH_CTRL_REG6, &value, -1) != 1) + { + goto error; + } + + /* REFERENCE */ + + value = dev->setup->reference; + if (lis2dh_access(dev, ST_LIS2DH_REFERENCE_REG, &value, -1) != 1) + { + goto error; + } + + /* FIFO_CTRL_REG */ + + value = dev->setup->fifo_mode | dev->setup->trigger_selection | + dev->setup->fifo_trigger_threshold; + if (lis2dh_access(dev, ST_LIS2DH_FIFO_CTRL_REG, &value, -1) != 1) + { + goto error; + } + + /* INT1_CFG */ + + value = dev->setup->int1_interrupt_mode | dev->setup->int1_enable_6d | dev->setup->int1_int_z_high_enable | + dev->setup->int1_int_z_low_enable | dev->setup->int1_int_y_high_enable | + dev->setup->int1_int_y_low_enable | dev->setup->int1_int_x_high_enable | + dev->setup->int1_int_x_low_enable; + if (lis2dh_access(dev, ST_LIS2DH_INT1_CFG_REG, &value, -1) != 1) + { + goto error; + } + + /* INT1_THS */ + + value = dev->setup->int1_int_threshold; + if (lis2dh_access(dev, ST_LIS2DH_INT1_THS_REG, &value, -1) != 1) + { + goto error; + } + + /* INT1_DURATION */ + + value = dev->setup->int1_int_duration; + if (lis2dh_access(dev, ST_LIS2DH_INT1_DUR_REG, &value, -1) != 1) + { + goto error; + } + + /* INT2_CFG */ + + value = dev->setup->int2_interrupt_mode | dev->setup->int2_enable_6d | dev->setup->int2_int_z_high_enable | + dev->setup->int2_int_z_low_enable | dev->setup->int2_int_y_high_enable | + dev->setup->int2_int_y_low_enable | dev->setup->int2_int_x_high_enable | + dev->setup->int2_int_x_low_enable; + if (lis2dh_access(dev, ST_LIS2DH_INT2_CFG_REG, &value, -1) != 1) + { + goto error; + } + + /* INT2_THS */ + + value = dev->setup->int2_int_threshold; + if (lis2dh_access(dev, ST_LIS2DH_INT2_THS_REG, &value, -1) != 1) + { + goto error; + } + + /* INT2_DURATION */ + + value = dev->setup->int2_int_duration; + if (lis2dh_access(dev, ST_LIS2DH_INT2_DUR_REG, &value, -1) != 1) + { + goto error; + } + + /* CLICK_CFG */ + + value = dev->setup->z_double_click_enable | dev->setup->z_single_click_enable | + dev->setup->y_double_click_enable | dev->setup->y_single_click_enable | + dev->setup->x_double_click_enable | dev->setup->x_single_click_enable; + if (lis2dh_access(dev, ST_LIS2DH_CLICK_CFG_REG, &value, -1) != 1) + { + goto error; + } + + /* CLICK_THS */ + + value = dev->setup->click_threshold; + if (lis2dh_access(dev, ST_LIS2DH_CLICK_THS_REG, &value, -1) != 1) + { + goto error; + } + + /* TIME_LIMIT */ + + value = dev->setup->click_time_limit; + if (lis2dh_access(dev, ST_LIS2DH_TIME_LIMIT_REG, &value, -1) != 1) + { + goto error; + } + + /* TIME_LATENCY */ + + value = dev->setup->click_time_latency; + if (lis2dh_access(dev, ST_LIS2DH_TIME_LATENCY_REG, &value, -1) != 1) + { + goto error; + } + + /* TIME_WINDOW */ + + value = dev->setup->click_time_window; + if (lis2dh_access(dev, ST_LIS2DH_TIME_WINDOW_REG, &value, -1) != 1) + { + goto error; + } + + /* CTRL_REG1 */ + + value = dev->setup->data_rate | dev->setup->low_power_mode_enable | + dev->setup->zen | dev->setup->yen | dev->setup->xen; + if (lis2dh_access(dev, ST_LIS2DH_CTRL_REG1, &value, -1) != 1) + { + goto error; + } + + switch (dev->setup->fullscale & 0x30) + { + default: + case ST_LIS2DH_CR4_FULL_SCALE_2G: + dev->scale = 2000; + break; + + case ST_LIS2DH_CR4_FULL_SCALE_4G: + dev->scale = 4000; + break; + + case ST_LIS2DH_CR4_FULL_SCALE_8G: + dev->scale = 8000; + break; + + case ST_LIS2DH_CR4_FULL_SCALE_16G: + dev->scale = 16000; + break; + } + + if (dev->setup->fifo_enable) + { + dev->fifo_used = true; + + if (lis2dh_fifo_start(dev) < 0) + { + goto error; + } + } + else + { + dev->fifo_used = false; + } + + return OK; + +error: + + /* Setup failed - power down */ + + lis2dh_powerdown(dev); + return -EIO; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lis2dh_register + * + * Description: + * Register the LIS2DH character device as 'devpath' + * + * Input Parameters: + * devpath - The full path to the driver to register. E.g., "/dev/acc0" + * i2c - An instance of the I2C interface to use to communicate with LIS2DH + * addr - The I2C address of the LIS2DH. The base I2C address of the LIS2DH + * is 0x18. Bit 0 can be controlled via SA0 pad - when connected to + * voltage supply the address is 0x19. + * config - Pointer to LIS2DH configuration + * + * Returned Value: + * Zero (OK) on success; a negated errno value on failure. + * + ****************************************************************************/ + +int lis2dh_register(FAR const char *devpath, FAR struct i2c_master_s *i2c, + uint8_t addr, FAR struct lis2dh_config_s *config) +{ + FAR struct lis2dh_dev_s *priv; + int ret; + + DEBUGASSERT(devpath != NULL && i2c != NULL && config != NULL); + + priv = (FAR struct lis2dh_dev_s *)kmm_zalloc(sizeof(struct lis2dh_dev_s)); + if (!priv) + { + lis2dh_dbg("lis2dh: Failed to allocate instance\n"); + return -ENOMEM; + } + + sem_init(&priv->devsem, 0, 1); + + priv->fifo_used = false; +#ifdef LIS2DH_COUNT_INTS + priv->int_pending = 0; +#else + priv->int_pending = false; +#endif + + priv->i2c = i2c; + priv->addr = addr; + priv->config = config; + + ret = register_driver(devpath, &g_lis2dhops, 0666, priv); + if (ret < 0) + { + lis2dh_dbg("lis2dh: Failed to register driver: %d\n", ret); + goto errout_with_priv; + } + + if (priv->config->irq_clear) + { + priv->config->irq_clear(config); + } + priv->config->irq_attach(config, lis2dh_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/sensors/ioctl.h b/include/nuttx/sensors/ioctl.h index 3cef5a8997..18b414773f 100644 --- a/include/nuttx/sensors/ioctl.h +++ b/include/nuttx/sensors/ioctl.h @@ -133,4 +133,14 @@ #define SNIOC_PRESSURE_OUT _SNIOC(0x0034) #define SNIOC_SENSOR_OFF _SNIOC(0x0035) +/* IOCTL commands unique to the LIS2DH */ + +#define SNIOC_WRITESETUP _SNIOC(0x0036) /* Arg: uint8_t value */ +#define SNIOC_WRITE_INT1THRESHOLD _SNIOC(0x0037) /* Arg: uint8_t value */ +#define SNIOC_WRITE_INT2THRESHOLD _SNIOC(0x0038) /* Arg: uint8_t value */ +#define SNIOC_RESET_HPFILTER _SNIOC(0x0039) /* Arg: uint8_t value */ +#define SNIOC_START_SELFTEST _SNIOC(0x003a) /* Arg: uint8_t value */ +#define SNIOC_WHO_AM_I _SNIOC(0x003b) +#define SNIOC_READ_TEMP _SNIOC(0x003c) /* Arg: int16_t value */ + #endif /* __INCLUDE_NUTTX_SENSORS_IOCTL_H */ diff --git a/include/nuttx/sensors/lis2dh.h b/include/nuttx/sensors/lis2dh.h new file mode 100644 index 0000000000..f9fdd839ca --- /dev/null +++ b/include/nuttx/sensors/lis2dh.h @@ -0,0 +1,441 @@ +/**************************************************************************** + * include/nuttx/sensors/lis2dh.h + * LIS2DH accelerometer driver + * + * Copyright (C) 2014-2017 Haltian Ltd. All rights reserved. + * Authors: Timo Voutilainen + * + * 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_LIS2DH_H +#define __INCLUDE_NUTTX_SENSORS_LIS2DH_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Pre-Processor Declarations + ****************************************************************************/ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +#define ST_LIS2DH_WHOAMI_VALUE 0x33 /* Valid WHOAMI register value */ + +/* LIS2DH Internal Registers **********************************************/ + +#define ST_LIS2DH_WHOAMI_REG 0x0f /* WHOAMI register */ + +#define ST_LIS2DH_STATUS_AUX_REG 0x07 /* Temperature status */ +#define ST_LIS2DH_OUT_TEMP_L_REG 0x0c /* Temperature data */ +#define ST_LIS2DH_OUT_TEMP_H_REG 0x0d /* Temperature data */ + +#define ST_LIS2DH_TEMP_CFG_REG 0x1f + +#define ST_LIS2DH_CTRL_REG1 0x20 + +/* CR1 ODR 4 MSBs (XXXX---) */ + +#define ST_LIS2DH_CR1_ODR_PWR_DWN 0x00 +#define ST_LIS2DH_CR1_ODR_1HZ 0x10 /* HR / Normal / Low Power */ +#define ST_LIS2DH_CR1_ODR_10HZ 0x20 /* HR / Normal / Low Power */ +#define ST_LIS2DH_CR1_ODR_25HZ 0x30 /* HR / Normal / Low Power */ +#define ST_LIS2DH_CR1_ODR_50HZ 0x40 /* HR / Normal / Low Power */ +#define ST_LIS2DH_CR1_ODR_100HZ 0x50 /* HR / Normal / Low Power */ +#define ST_LIS2DH_CR1_ODR_200HZ 0x60 /* HR / Normal / Low Power */ +#define ST_LIS2DH_CR1_ODR_400HZ 0x70 /* HR / Normal / Low Power */ +#define ST_LIS2DH_CR1_ODR_1620HZ 0x80 /* Low Power */ +#define ST_LIS2DH_CR1_ODR_1344_5376HZ 0x90 /* HR / Normal: 1344Hz, Low power: 5376Hz*/ +#define ST_LIS2DH_CR1_LOWP_ENABLE 0x08 /* Low power mode enable */ +#define ST_LIS2DH_CR1_ZEN 0x04 /* Z-Axis Enable */ +#define ST_LIS2DH_CR1_YEN 0x02 /* Y-Axis Enable */ +#define ST_LIS2DH_CR1_XEN 0x01 /* X-Axis Enable */ + +#define ST_LIS2DH_CTRL_REG2 0x21 + +/* HPM1 .... HP FILT_MODE (XX------) */ + +#define ST_LIS2DH_CR2_HPFILT_M_NORM 0x00 /* Normal mode (reset reading REFERENCE/DATACAPTURE (26h) register) */ +#define ST_LIS2DH_CR2_HPFILT_M_REFSIG 0x40 /* Reference signal for filtering */ +#define ST_LIS2DH_CR2_HPFILT_M_NORM2 0x80 /* Normal mode */ +#define ST_LIS2DH_CR2_HPFILT_M_AUTOR 0xc0 /* Autoreset on interrupt event */ +#define ST_LIS2DH_CR2_FDS 0x08 + +/* HPIS1 HPFILT ENABLE for INT1 (-------X) */ + +#define ST_LIS2DH_CR2_HPENABLED_INT1 0x01 /* HP filter enabled for INT1 */ + +/* HPIS2 HPFILT ENABLE for INT2 (------X-) */ + +#define ST_LIS2DH_CR2_HPENABLED_INT2 0x02 /* HP filter enabled for INT2 */ + +#define ST_LIS2DH_CTRL_REG3 0x22 + +/* I1_AOI1 ENABLE for INT2 (-X------) */ + +#define ST_LIS2DH_CR3_I1_AOI1_ENABLED 0x40 /* AOI1 interrupt on INT1 pin.*/ +#define ST_LIS2DH_CR3_I1_AOI2_ENABLED 0x20 /* AOI2 interrupt on INT1 pin.*/ + +#define ST_LIS2DH_CTRL_REG4 0x23 + +/* BDU ... Block Data Update (X-------) */ + +#define ST_LIS2DH_CR4_BDU_CONT 0x00 /* Continuous update (Default) */ +#define ST_LIS2DH_CR4_BDU_UPD_ON_READ 0x80 /* Output registers not updated until MSB and LSB have been read */ +#define ST_LIS2DH_CR4_FULL_SCALE_2G 0x0 +#define ST_LIS2DH_CR4_FULL_SCALE_4G 0x10 +#define ST_LIS2DH_CR4_FULL_SCALE_8G 0x20 +#define ST_LIS2DH_CR4_FULL_SCALE_16G 0x30 + +/* HR .. Operation mode selector (----X---) */ + +#define ST_LIS2DH_CR4_HR_ENABLED 0x08 /* See section 2.6.3 in datasheet */ + +#define ST_LIS2DH_CTRL_REG5 0x24 +#define ST_LIS2DH_CR5_BOOT 0x80 +#define ST_LIS2DH_CR5_FIFO_EN 0x40 +#define ST_LIS2DH_CR5_LIR_INT1 0x08 +#define ST_LIS2DH_CR5_D4D_INT1 0x04 +#define ST_LIS2DH_CR5_LIR_INT2 0x02 +#define ST_LIS2DH_CR5_D4D_INT2 0x01 + +#define ST_LIS2DH_CTRL_REG6 0x25 +#define ST_LIS2DH_REFERENCE_REG 0x26 + +#define ST_LIS2DH_STATUS_REG 0x27 /* Status Register */ +#define ST_LIS2DH_SR_ZYXOR 0x80 /* OR'ed X,Y and Z data over-run */ +#define ST_LIS2DH_SR_ZOR 0x40 /* individual data over-run ... */ +#define ST_LIS2DH_SR_YOR 0x20 +#define ST_LIS2DH_SR_XOR 0x10 +#define ST_LIS2DH_SR_ZYXDA 0x08 /* OR'ed X,Y and Z data available */ +#define ST_LIS2DH_SR_ZDA 0x04 /* individual data available ... */ +#define ST_LIS2DH_SR_YDA 0x02 +#define ST_LIS2DH_SR_XDA 0x01 + +#define ST_LIS2DH_OUT_X_L_REG 0x28 +#define ST_LIS2DH_OUT_X_H_REG 0x29 +#define ST_LIS2DH_OUT_Y_L_REG 0x2a +#define ST_LIS2DH_OUT_Y_H_REG 0x2b +#define ST_LIS2DH_OUT_Z_L_REG 0x2c +#define ST_LIS2DH_OUT_Z_H_REG 0x2d + +#define ST_LIS2DH_FIFO_CTRL_REG 0x2e +#define ST_LIS2DH_FIFOCR_THRESHOLD_MASK 0x1f +#define ST_LIS2DH_FIFOCR_THRESHOLD(x) ((x) & ST_LIS2DH_FIFOCR_THRESHOLD_MASK) +#define ST_LIS2DH_FIFOCR_INT1 0x00 +#define ST_LIS2DH_FIFOCR_INT2 0x20 +#define ST_LIS2DH_FIFOCR_MODE_MASK 0xc0 + +#define ST_LIS2DH_FIFO_SRC_REG 0x2f +#define ST_LIS2DH_FIFOSR_NUM_SAMP_MASK 0x1f +#define ST_LIS2DH_FIFOSR_EMPTY 0x20 +#define ST_LIS2DH_FIFOSR_OVRN_FIFO 0x40 +#define ST_LIS2DH_FIFOSR_WTM 0x80 + +#define ST_LIS2DH_INT1_CFG_REG 0x30 +#define ST_LIS2DH_INT_CFG_AOI 0x80 +#define ST_LIS2DH_INT_CFG_6D 0x40 +#define ST_LIS2DH_INT_CFG_ZHIE 0x20 +#define ST_LIS2DH_INT_CFG_ZLIE 0x10 +#define ST_LIS2DH_INT_CFG_YHIE 0x08 +#define ST_LIS2DH_INT_CFG_YLIE 0x04 +#define ST_LIS2DH_INT_CFG_XHIE 0x02 +#define ST_LIS2DH_INT_CFG_XLIE 0x01 + +#define ST_LIS2DH_INT1_SRC_REG 0x31 +#define ST_LIS2DH_INT_SR_XLOW 0x01 +#define ST_LIS2DH_INT_SR_XHIGH 0x02 +#define ST_LIS2DH_INT_SR_YLOW 0x04 +#define ST_LIS2DH_INT_SR_YHIGH 0x08 +#define ST_LIS2DH_INT_SR_ZLOW 0x10 +#define ST_LIS2DH_INT_SR_ZHIGH 0x20 +#define ST_LIS2DH_INT_SR_ACTIVE 0x40 + +#define ST_LIS2DH_INT1_THS_REG 0x32 /* 7-bit value for threshold */ + +#define ST_LIS2DH_INT1_DUR_REG 0x33 /* 7-bit value for duration */ + +#define ST_LIS2DH_INT2_CFG_REG 0x34 + +#define ST_LIS2DH_INT2_SRC_REG 0x35 + +#define ST_LIS2DH_INT2_THS_REG 0x36 /* 7-bit value for threshold */ + +#define ST_LIS2DH_INT2_DUR_REG 0x37 /* 7-bit value for duration */ + +#define ST_LIS2DH_CLICK_CFG_REG 0x38 + +#define ST_LIS2DH_CLICK_SRC_REG 0x39 + +#define ST_LIS2DH_CLICK_THS_REG 0x3a + +#define ST_LIS2DH_TIME_LIMIT_REG 0x3b + +#define ST_LIS2DH_TIME_LATENCY_REG 0x3c + +#define ST_LIS2DH_TIME_WINDOW_REG 0x3d + +#define ST_LIS2DH_ACT_DUR_REG 0x3f + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +enum lis2dh_ouput_data_rate +{ + LIS2DH_ODR_POWER_DOWN = 0x00, + LIS2DH_ODR_1HZ = 0x10, + LIS2DH_ODR_10HZ = 0x20, + LIS2DH_ODR_25HZ = 0x30, + LIS2DH_ODR_50HZ = 0x40, + LIS2DH_ODR_100HZ = 0x50, + LIS2DH_ODR_200HZ = 0x60, + LIS2DH_ODR_400HZ = 0x70, + LIS2DH_ODR_1620HZ = 0x80, + LIS2DH_ODR_5376HZ = 0x90, +}; + +enum lis2dh_high_pass_filter_mode +{ + LIS2DH_REFERENCE_SIGNAL = 0x40, + LIS2DH_NORMAL_MODE = 0x80, + LIS2DH_AUTORESET_ON_INTERRUPT = 0xc0, +}; + +enum lis2dh_scale_range +{ + LIS2DH_RANGE_2G = 0x00, + LIS2DH_RANGE_4G = 0x10, + LIS2DH_RANGE_8G = 0x20, + LIS2DH_RANGE_16G = 0x30, +}; + +enum lis2dh_self_test +{ + LIS2DH_NORMAL = 0x00, + LIS2DH_SELF_TEST0 = 0x02, + LIS2DH_SELF_TEST1 = 0x04, +}; + +enum lis2dh_fifo_mode +{ + LIS2DH_BYPASS_MODE = 0x00, + LIS2DH_FIFO_MODE = 0x40, + LIS2DH_STREAM_MODE = 0x80, + LIS2DH_TRIGGER_MODE = 0xc0, +}; + +enum lis2dh_interrupt_mode +{ + LIS2DH_OR_COMBINATION = 0x00, + LIS2DH_6D_MOVEMENT = 0x40, + LIS2DH_AND_COMBINATION = 0x80, + LIS2DH_6D_POSITION = 0xc0, +}; + +struct lis2dh_vector_s +{ + int16_t x, y, z; +} packed_struct; + +struct lis2dh_res_header +{ + uint8_t meas_count; + bool int1_occurred; + uint8_t int1_source; + bool int2_occurred; + uint8_t int2_source; +} packed_struct; + +struct lis2dh_result +{ + struct lis2dh_res_header header; + struct lis2dh_vector_s measurements[0]; +} packed_struct; + +struct lis2dh_setup +{ + bool temp_enable:1; + bool xy_axis_fixup:1; + + uint8_t data_rate; + uint8_t low_power_mode_enable; + uint8_t zen; + uint8_t yen; + uint8_t xen; + + uint8_t hpmode; + uint8_t hpcf; + uint8_t fds; + uint8_t hpclick; + uint8_t hpis2; + uint8_t hpis1; + + uint8_t int1_click_enable; + uint8_t int1_aoi_enable; + uint8_t int2_aoi_enable; + uint8_t int1_drdy_enable; + uint8_t int2_drdy_enable; + uint8_t int_wtm_enable; + uint8_t int_overrun_enable; + + uint8_t bdu; + uint8_t endian; + uint8_t fullscale; + uint8_t high_resolution_enable; + uint8_t selftest; + uint8_t spi_mode; + + uint8_t reboot; + uint8_t fifo_enable; + uint8_t int1_latch; + uint8_t int1_4d_enable; + uint8_t int2_latch; + uint8_t int2_4d_enable; + + uint8_t int2_click_enable; + uint8_t int_enable; + uint8_t boot_int1_enable; + uint8_t high_low_active; + + uint8_t reference; + + uint8_t fifo_mode; + uint8_t trigger_selection; + uint8_t fifo_trigger_threshold; + + uint8_t int1_interrupt_mode; + uint8_t int1_enable_6d; + uint8_t int1_int_z_high_enable; + uint8_t int1_int_z_low_enable; + uint8_t int1_int_y_high_enable; + uint8_t int1_int_y_low_enable; + uint8_t int1_int_x_high_enable; + uint8_t int1_int_x_low_enable; + uint8_t int1_int_threshold; + uint8_t int1_int_duration; + + uint8_t int2_interrupt_mode; + uint8_t int2_enable_6d; + uint8_t int2_int_z_high_enable; + uint8_t int2_int_z_low_enable; + uint8_t int2_int_y_high_enable; + uint8_t int2_int_y_low_enable; + uint8_t int2_int_x_high_enable; + uint8_t int2_int_x_low_enable; + uint8_t int2_int_threshold; + uint8_t int2_int_duration; + + uint8_t z_double_click_enable; + uint8_t z_single_click_enable; + uint8_t y_double_click_enable; + uint8_t y_single_click_enable; + uint8_t x_double_click_enable; + uint8_t x_single_click_enable; + + uint8_t click_threshold; + uint8_t click_time_limit; + uint8_t click_time_latency; + uint8_t click_time_window; +}; + +struct lis2dh_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 lis2dh driver from differences in GPIO + * interrupt handling by varying boards and MCUs. + * + * irq_attach - Attach the lis2dh interrupt handler to the GPIO interrupt + * irq_enable - Enable or disable the GPIO interrupt + * clear_irq - Acknowledge/clear any pending GPIO interrupt + * + */ + + CODE int (*irq_attach)(FAR struct lis2dh_config_s *state, xcpt_t isr, FAR void *arg); + CODE void (*irq_enable)(FAR const struct lis2dh_config_s *state, bool enable); + CODE void (*irq_clear)(FAR const struct lis2dh_config_s *state); + CODE bool (*read_int1_pin)(void); + CODE bool (*read_int2_pin)(void); +}; + +struct lis2dh_raw_data_s +{ + uint16_t out_x; + uint16_t out_y; + uint16_t out_z; +} packed_struct; + +typedef struct lis2dh_raw_data_s lis2dh_raw_data_t; + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Name: lis2dh_register + * + * Description: + * Register the LIS2DH character device as 'devpath' + * + * Input Parameters: + * devpath - The full path to the driver to register. E.g., "/dev/acc0" + * i2c - An instance of the I2C interface to use to communicate with LIS2DH + * addr - The I2C address of the LIS2DH. The base I2C address of the LIS2DH + * is 0x18. Bit 0 can be controlled via SA0 pad - when connected to + * voltage supply the address is 0x19. + * config - Pointer to LIS2DH configuration + * + * Returned Value: + * Zero (OK) on success; a negated errno value on failure. + * + ****************************************************************************/ + +int lis2dh_register(FAR const char *devpath, FAR struct i2c_master_s *i2c, + uint8_t addr, FAR struct lis2dh_config_s *config); + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __INCLUDE_NUTTX_SENSORS_LIS2DH_H */ -- GitLab From ae1265c01e9205885b4bcf60cb0896a0a7248406 Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Mon, 3 Apr 2017 07:36:29 -0600 Subject: [PATCH 317/990] net/socket/send: fix building without CONFIG_NET_6LOWPAN --- net/socket/send.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/net/socket/send.c b/net/socket/send.c index 2e805b4eaf..340e4caa62 100644 --- a/net/socket/send.c +++ b/net/socket/send.c @@ -124,7 +124,7 @@ ssize_t psock_send(FAR struct socket *psock, FAR const void *buf, size_t len, int flags) { - int ret; + ssize_t ret; /* Treat as a cancellation point */ @@ -175,9 +175,9 @@ ssize_t psock_send(FAR struct socket *psock, FAR const void *buf, size_t len, } #endif /* CONFIG_NETDEV_MULTINIC && NET_TCP_HAVE_STACK */ #elif defined(NET_TCP_HAVE_STACK) - nsent = psock_tcp_send(psock, buf, len, flags, to, tolen); + ret = psock_tcp_send(psock, buf, len); #else - nsent = -ENOSYS; + ret = -ENOSYS; #endif /* CONFIG_NET_6LOWPAN */ } #endif /* CONFIG_NET_TCP */ @@ -219,7 +219,7 @@ ssize_t psock_send(FAR struct socket *psock, FAR const void *buf, size_t len, #endif /* CONFIG_NETDEV_MULTINIC && NET_UDP_HAVE_STACK */ #elif defined(NET_UDP_HAVE_STACK) /* Only UDP/IP packet send */ - + ret = psock_udp_send(psock, buf, len); #else ret = -ENOSYS; -- GitLab From ee4a8336ceb8b74a0d0283c10cfee45f48586f61 Mon Sep 17 00:00:00 2001 From: Kivilinna Date: Mon, 3 Apr 2017 07:38:23 -0600 Subject: [PATCH 318/990] net/socket/accept: fix building with CONFIG_NET_LOCAL_STREAM --- net/socket/accept.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/net/socket/accept.c b/net/socket/accept.c index ec7385b4f2..b4db581dba 100644 --- a/net/socket/accept.c +++ b/net/socket/accept.c @@ -130,7 +130,7 @@ int psock_accept(FAR struct socket *psock, FAR struct sockaddr *addr, FAR socklen_t *addrlen, FAR struct socket *newsock) { int errcode; -#ifdef NET_TCP_HAVE_STACK +#if defined(NET_TCP_HAVE_STACK) || defined(CONFIG_NET_LOCAL_STREAM) int ret; #endif -- GitLab From 3a6bd901e4d72c9cef7ffb474d2373883bcb6042 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Mon, 3 Apr 2017 07:45:09 -0600 Subject: [PATCH 319/990] stm32: fix IWDG and WWDG debug mode stop for STM32L15XX --- arch/arm/src/stm32/stm32_iwdg.c | 12 ++++++------ arch/arm/src/stm32/stm32_wwdg.c | 10 +++++----- 2 files changed, 11 insertions(+), 11 deletions(-) diff --git a/arch/arm/src/stm32/stm32_iwdg.c b/arch/arm/src/stm32/stm32_iwdg.c index 1cdf8e47bc..64495b71ab 100644 --- a/arch/arm/src/stm32/stm32_iwdg.c +++ b/arch/arm/src/stm32/stm32_iwdg.c @@ -634,8 +634,8 @@ static int stm32_settimeout(FAR struct watchdog_lowerhalf_s *lower, * Name: stm32_iwdginitialize * * Description: - * Initialize the IWDG watchdog time. The watchdog timer is initialized and - * registers as 'devpath. The initial state of the watchdog time is + * Initialize the IWDG watchdog timer. The watchdog timer is initialized and + * registers as 'devpath'. The initial state of the watchdog timer is * disabled. * * Input Parameters: @@ -665,7 +665,7 @@ void stm32_iwdginitialize(FAR const char *devpath, uint32_t lsifreq) priv->started = false; /* Make sure that the LSI oscillator is enabled. NOTE: The LSI oscillator - * is enabled here but is not disabled by this file (because this file does + * is enabled here but is not disabled by this file, because this file does * not know the global usage of the oscillator. Any clock management * logic (say, as part of a power management scheme) needs handle other * LSI controls outside of this file. @@ -685,9 +685,9 @@ void stm32_iwdginitialize(FAR const char *devpath, uint32_t lsifreq) (void)watchdog_register(devpath, (FAR struct watchdog_lowerhalf_s *)priv); - /* When the microcontroller enters debug mode (Cortex™-M4F core halted), + /* When the microcontroller enters debug mode (Cortex-M4F core halted), * the IWDG counter either continues to work normally or stops, depending - * on DBG_WIDG_STOP configuration bit in DBG module. + * on DBG_IWDG_STOP configuration bit in DBG module. */ #if defined(CONFIG_STM32_JTAG_FULL_ENABLE) || \ @@ -695,7 +695,7 @@ void stm32_iwdginitialize(FAR const char *devpath, uint32_t lsifreq) defined(CONFIG_STM32_JTAG_SW_ENABLE) { #if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F30XX) || \ - defined(CONFIG_STM32_STM32F40XX) + defined(CONFIG_STM32_STM32F40XX) || defined(CONFIG_STM32_STM32L15XX) uint32_t cr = getreg32(STM32_DBGMCU_APB1_FZ); cr |= DBGMCU_APB1_IWDGSTOP; putreg32(cr, STM32_DBGMCU_APB1_FZ); diff --git a/arch/arm/src/stm32/stm32_wwdg.c b/arch/arm/src/stm32/stm32_wwdg.c index a299de8c99..c0cb34f1f7 100644 --- a/arch/arm/src/stm32/stm32_wwdg.c +++ b/arch/arm/src/stm32/stm32_wwdg.c @@ -734,8 +734,8 @@ static int stm32_ioctl(FAR struct watchdog_lowerhalf_s *lower, int cmd, * Name: stm32_wwdginitialize * * Description: - * Initialize the WWDG watchdog time. The watchdog timer is initialized and - * registers as 'devpath. The initial state of the watchdog time is + * Initialize the WWDG watchdog timer. The watchdog timer is initialized and + * registers as 'devpath'. The initial state of the watchdog timer is * disabled. * * Input Parameters: @@ -753,7 +753,7 @@ void stm32_wwdginitialize(FAR const char *devpath) wdinfo("Entry: devpath=%s\n", devpath); - /* NOTE we assume that clocking to the IWDG has already been provided by + /* NOTE we assume that clocking to the WWDG has already been provided by * the RCC initialization logic. */ @@ -780,7 +780,7 @@ void stm32_wwdginitialize(FAR const char *devpath) (void)watchdog_register(devpath, (FAR struct watchdog_lowerhalf_s *)priv); - /* When the microcontroller enters debug mode (Cortex�-M4F core halted), + /* When the microcontroller enters debug mode (Cortex-M core halted), * the WWDG counter either continues to work normally or stops, depending * on DBG_WWDG_STOP configuration bit in DBG module. */ @@ -790,7 +790,7 @@ void stm32_wwdginitialize(FAR const char *devpath) defined(CONFIG_STM32_JTAG_SW_ENABLE) { #if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F30XX) || \ - defined(CONFIG_STM32_STM32F40XX) + defined(CONFIG_STM32_STM32F40XX) || defined(CONFIG_STM32_STM32L15XX) uint32_t cr = getreg32(STM32_DBGMCU_APB1_FZ); cr |= DBGMCU_APB1_WWDGSTOP; putreg32(cr, STM32_DBGMCU_APB1_FZ); -- GitLab From e320e5c100415d42eed309e1148d1ede0b9d5752 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Mon, 3 Apr 2017 07:59:11 -0600 Subject: [PATCH 320/990] STM32: add STM32L162VE to chip.h --- arch/arm/include/stm32/chip.h | 60 +++++++++++++++++++++++++++++++---- 1 file changed, 54 insertions(+), 6 deletions(-) diff --git a/arch/arm/include/stm32/chip.h b/arch/arm/include/stm32/chip.h index 0844c5a09f..df921df4b8 100644 --- a/arch/arm/include/stm32/chip.h +++ b/arch/arm/include/stm32/chip.h @@ -64,12 +64,16 @@ * STM32L15XCX -- 48-pins * STM32L15XRX -- 64-pins * STM32L15XVX -- 100-pins + * STM32L15XZX -- 144-pins * * STM32L15XX6 -- 32KB FLASH, 10KB SRAM, 4KB EEPROM * STM32L15XX8 -- 64KB FLASH, 10KB SRAM, 4KB EEPROM * STM32L15XXB -- 128KB FLASH, 16KB SRAM, 4KB EEPROM * * STM32L15XXC -- 256KB FLASH, 32KB SRAM, 8KB EEPROM (medium+ density) + * + * STM32L16XXD -- 384KB FLASH, 48KB SRAM, 12KB EEPROM (high density) + * STM32L16XXE -- 512KB FLASH, 80KB SRAM, 16KB EEPROM (high density) */ #if defined(CONFIG_ARCH_CHIP_STM32L151C6) || defined(CONFIG_ARCH_CHIP_STM32L151C8) || \ @@ -320,7 +324,7 @@ #elif defined(CONFIG_ARCH_CHIP_STM32L152RC) # define CONFIG_STM32_STM32L15XX 1 /* STM32L151xx and STM32L152xx family */ -# define CONFIG_STM32_ENERGYLITE 1 /* STM32L EnergyLite vamily */ +# define CONFIG_STM32_ENERGYLITE 1 /* STM32L EnergyLite family */ # undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */ # undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes * and STM32L15xxx */ @@ -331,6 +335,7 @@ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ # undef CONFIG_STM32_STM32F30XX /* STM32F30xxx family */ +# undef CONFIG_STM32_STM32F33XX /* STM32F33xxx family */ # undef CONFIG_STM32_STM32F40XX /* STM32F405xx and STM32407xx families */ # define STM32_NFSMC 0 /* No FSMC */ # define STM32_NATIM 0 /* No advanced timers */ @@ -358,17 +363,18 @@ #elif defined(CONFIG_ARCH_CHIP_STM32L162ZD) # define CONFIG_STM32_STM32L15XX 1 /* STM32L151xx and STM32L152xx family */ -# define CONFIG_STM32_ENERGYLITE 1 /* STM32L EnergyLite vamily */ +# define CONFIG_STM32_ENERGYLITE 1 /* STM32L EnergyLite family */ # undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */ # undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes * and STM32L15xxx */ # undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ # undef CONFIG_STM32_MEDIUMPLUSDENSITY /* STM32L15xxC w/ 32/256 Kbytes */ -# define CONFIG_STM32_HIGHDENSITY 1 /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes, STM32L16x w/ 48/384 Kbytes. */ +# define CONFIG_STM32_HIGHDENSITY 1 /* STM32L16xD w/ 48/384 Kbytes. */ # undef CONFIG_STM32_VALUELINE /* STM32F100x */ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ # undef CONFIG_STM32_STM32F30XX /* STM32F30xxx family */ +# undef CONFIG_STM32_STM32F33XX /* STM32F33xxx family */ # undef CONFIG_STM32_STM32F40XX /* STM32F405xx and STM32407xx families */ # define STM32_NFSMC 1 /* FSMC */ # define STM32_NATIM 0 /* No advanced timers */ @@ -395,6 +401,48 @@ # define STM32_NRNG 0 /* No random number generator (RNG) */ # define STM32_NDCMI 0 /* No digital camera interface (DCMI) */ +#elif defined(CONFIG_ARCH_CHIP_STM32L162VE) +# define CONFIG_STM32_STM32L15XX 1 /* STM32L151xx and STM32L152xx family */ +# define CONFIG_STM32_ENERGYLITE 1 /* STM32L EnergyLite family */ +# undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes + * and STM32L15xxx */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# undef CONFIG_STM32_MEDIUMPLUSDENSITY /* STM32L15xxC w/ 32/256 Kbytes */ +# define CONFIG_STM32_HIGHDENSITY 1 /* STM32L16xE w/ 80/512 Kbytes. */ +# undef CONFIG_STM32_VALUELINE /* STM32F100x */ +# undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ +# undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ +# undef CONFIG_STM32_STM32F30XX /* STM32F30xxx family */ +# undef CONFIG_STM32_STM32F33XX /* STM32F33xxx family */ +# undef CONFIG_STM32_STM32F40XX /* STM32F405xx and STM32407xx families */ +# define STM32_NFSMC 0 /* No FSMC */ +# define STM32_NATIM 0 /* No advanced timers */ +# define STM32_NGTIM 4 /* 16-bit general timers TIM2-4 with DMA + * 32-bit general timer TIM5 with DMA */ +# define STM32_NGTIMNDMA 3 /* 16-bit general timers TIM9-11 without DMA */ +# define STM32_NBTIM 2 /* 2 basic timers: TIM6, TIM7 with DMA */ +# define STM32_NDMA 2 /* DMA1, 12-channels */ +# define STM32_NSPI 3 /* SPI1-3 */ +# define STM32_NI2S 2 /* I2S1-2, overlapping with SPI2-3 */ +# define STM32_NUSART 5 /* USART1-3, UART4-5 */ +# define STM32_NI2C 2 /* I2C1-2 */ +# define STM32_NCAN 0 /* No CAN */ +# define STM32_NSDIO 0 /* No SDIO */ +# define STM32_NLCD 1 /* LCD 4x44, 8x40*/ +# define STM32_NUSBOTG 1 /* USB OTG FS/HS (only USB 2.0 device) */ +# define STM32_NGPIO 83 /* GPIOA-G,H */ + +# define STM32_NADC 1 /* ADC1, up to 40-channels (medium+ and high density). See for more information RM0038 Reference manual */ +# define STM32_NDAC 1 /* DAC 1, 2 channels. See for more information RM0038 Reference manual */ + /* (2) Comparators */ +# define STM32_NCAPSENSE 23 /* Capacitive sensing channels */ +# define STM32_NCRC 1 /* CRC */ +# define STM32_NETHERNET 0 /* No ethernet */ +# define STM32_NRNG 0 /* No random number generator (RNG) */ +# define STM32_NDCMI 0 /* No digital camera interface (DCMI) */ + + /* STM32 F100 Value Line ************************************************************/ #elif defined(CONFIG_ARCH_CHIP_STM32F100C8) || defined(CONFIG_ARCH_CHIP_STM32F100CB) \ @@ -562,7 +610,7 @@ #elif defined(CONFIG_ARCH_CHIP_STM32F102CB) # undef CONFIG_STM32_STM32L15XX /* STM32L151xx and STM32L152xx family */ -# undef CONFIG_STM32_ENERGYLITE /* STM32L EnergyLite vamily */ +# undef CONFIG_STM32_ENERGYLITE /* STM32L EnergyLite family */ # define CONFIG_STM32_STM32F10XX 1 /* STM32F10xx family */ # undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ # define CONFIG_STM32_MEDIUMDENSITY 1 /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ @@ -1129,7 +1177,7 @@ #elif defined(CONFIG_ARCH_CHIP_STM32F302K6) || defined(CONFIG_ARCH_CHIP_STM32F302K8) # undef CONFIG_STM32_STM32L15XX /* STM32L151xx and STM32L152xx family */ -# undef CONFIG_STM32_ENERGYLITE /* STM32L EnergyLite vamily */ +# undef CONFIG_STM32_ENERGYLITE /* STM32L EnergyLite family */ # undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */ # undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ # undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ @@ -1668,7 +1716,7 @@ #elif defined(CONFIG_ARCH_CHIP_STM32F373C8) || defined(CONFIG_ARCH_CHIP_STM32F373CB) || defined(CONFIG_ARCH_CHIP_STM32F373CC) # undef CONFIG_STM32_STM32L15XX /* STM32L151xx and STM32L152xx family */ -# undef CONFIG_STM32_ENERGYLITE /* STM32L EnergyLite vamily */ +# undef CONFIG_STM32_ENERGYLITE /* STM32L EnergyLite family */ # undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */ # undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ # undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ -- GitLab From 04346ebaf2a8e1d4f68a4247f274f18bb6f7967a Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 2 Apr 2017 16:29:02 -0600 Subject: [PATCH 321/990] iee802154 loopback: Eliminate dependency on CONFIG_NET_LOOPBACK --- wireless/ieee802154/Kconfig | 31 ++ wireless/ieee802154/Make.defs | 8 +- wireless/ieee802154/mac802154_loopback.c | 585 +++++++++++++++++++++++ 3 files changed, 622 insertions(+), 2 deletions(-) create mode 100644 wireless/ieee802154/mac802154_loopback.c diff --git a/wireless/ieee802154/Kconfig b/wireless/ieee802154/Kconfig index 1b443ff979..92872fcb9f 100644 --- a/wireless/ieee802154/Kconfig +++ b/wireless/ieee802154/Kconfig @@ -12,4 +12,35 @@ config WIRELESS_IEEE802154 if IEEE802154 +config IEEE802154_LOOPBACK + bool "IEEE802154 6loWPAN Loopback" + default n + depends on NET_6LOWPAN && NET_IPv6 + select ARCH_HAVE_NETDEV_STATISTICS + ---help--- + Add support for the IEEE802154 6loWPAN Loopback test device. + +if IEEE802154_LOOPBACK + +choice + prompt "Work queue" + default IEEE802154_LOOPBACK_LPWORK if SCHED_LPWORK + default IEEE802154_LOOPBACK_HPWORK if !SCHED_LPWORK && SCHED_HPWORK + depends on SCHED_WORKQUEUE + ---help--- + Work queue support is required to use the loopback driver. If the + low priority work queue is available, then it should be used by the + loopback driver. + +config IEEE802154_LOOPBACK_HPWORK + bool "High priority" + depends on SCHED_HPWORK + +config IEEE802154_LOOPBACK_LPWORK + bool "Low priority" + depends on SCHED_LPWORK + +endchoice # Work queue +endif # IEEE802154_LOOPBACK + endif # IEEE802154 diff --git a/wireless/ieee802154/Make.defs b/wireless/ieee802154/Make.defs index 200d948dd7..2f5f19967f 100644 --- a/wireless/ieee802154/Make.defs +++ b/wireless/ieee802154/Make.defs @@ -39,8 +39,12 @@ ifeq ($(CONFIG_WIRELESS_IEEE802154),y) # Include wireless devices build support -DEPPATH += --dep-path wireless/ieee802154 -VPATH += :wireless/ieee802154 +ifeq ($(CONFIG_IEEE802154_LOOPBACK),y) +CSRCS += mac802154_loopback.c +endif + +DEPPATH += --dep-path ieee802154 +VPATH += :ieee802154 CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)$(DELIM)wireless$(DELIM)ieee802154} endif # CONFIG_WIRELESS_IEEE802154 diff --git a/wireless/ieee802154/mac802154_loopback.c b/wireless/ieee802154/mac802154_loopback.c new file mode 100644 index 0000000000..5bbd6f5beb --- /dev/null +++ b/wireless/ieee802154/mac802154_loopback.c @@ -0,0 +1,585 @@ +/**************************************************************************** + * wireless/iee802154/mac802154_loopback.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include +#include + +#ifndef CONFIG_NET_LOOPBACK +# include +#endif + +#ifdef CONFIG_IEEE802154_LOOPBACK + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* We need to have the work queue to handle SPI interrupts */ + +#if !defined(CONFIG_SCHED_WORKQUEUE) +# error Worker thread support is required (CONFIG_SCHED_WORKQUEUE) +#else +# if defined(CONFIG_IEEE802154_LOOPBACK_HPWORK) +# define LPBKWORK HPWORK +# elif defined(CONFIG_IEEE802154_LOOPBACK_LPWORK) +# define LPBKWORK LPWORK +# else +# error Neither CONFIG_IEEE802154_LOOPBACK_HPWORK nor CONFIG_IEEE802154_LOOPBACK_LPWORK defined +# endif +#endif + +/* TX poll delay = 1 seconds. CLK_TCK is the number of clock ticks per second */ + +#define LO_WDDELAY (1*CLK_TCK) + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/* The lo_driver_s encapsulates all state information for a single hardware + * interface + */ + +struct lo_driver_s +{ + bool lo_bifup; /* true:ifup false:ifdown */ + bool lo_txdone; /* One RX packet was looped back */ + WDOG_ID lo_polldog; /* TX poll timer */ + struct work_s lo_work; /* For deferring poll work to the work queue */ + + /* This holds the information visible to the NuttX network */ + + struct ieee802154_driver_s lo_ieee; /* Interface understood by the network */ +}; + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static struct lo_driver_s g_loopback; +static uint8_t g_iobuffer[CONFIG_NET_6LOWPAN_MTU + CONFIG_NET_GUARDSIZE]; + +#ifndef CONFIG_NET_LOOPBACK +static const net_ipv6addr_t g_lo_ipv6addr = +{ + HTONS(0), HTONS(0), HTONS(0), HTONS(0), + HTONS(0), HTONS(0), HTONS(0), HTONS(1) +}; +#endif + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* Polling logic */ + +static int lo_txpoll(FAR struct net_driver_s *dev); +static void lo_poll_work(FAR void *arg); +static void lo_poll_expiry(int argc, wdparm_t arg, ...); + +/* NuttX callback functions */ + +static int lo_ifup(FAR struct net_driver_s *dev); +static int lo_ifdown(FAR struct net_driver_s *dev); +static void lo_txavail_work(FAR void *arg); +static int lo_txavail(FAR struct net_driver_s *dev); +#if defined(CONFIG_NET_IGMP) || defined(CONFIG_NET_ICMPv6) +static int lo_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac); +#ifdef CONFIG_NET_IGMP +static int lo_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac); +#endif +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: lo_txpoll + * + * Description: + * Check if the network has any outgoing packets ready to send. This is + * a callback from devif_poll() or devif_timer(). devif_poll() will be + * called only during normal TX polling. + * + * Parameters: + * dev - Reference to the NuttX driver state structure + * + * Returned Value: + * OK on success; a negated errno on failure + * + * Assumptions: + * May or may not be called from an interrupt handler. In either case, + * the network is locked. + * + ****************************************************************************/ + +static int lo_txpoll(FAR struct net_driver_s *dev) +{ + FAR struct lo_driver_s *priv = (FAR struct lo_driver_s *)dev->d_private; + FAR struct iob_s *head; + FAR struct iob_s *tail; + FAR struct iob_s *iob; + int ret; + + /* Remove the queued IOBs from driver structure */ + + head = priv->lo_ieee.i_framelist; + + /* Find the tail of the IOB queue */ + + for (tail = NULL, iob = head; + iob != NULL; + tail = iob, iob = iob->io_flink); + + /* Loop while there frames to be sent, i.e., while the IOB list is not + * emtpy. Sending, of course, just means relaying back through the network + * for this driver. + */ + + while (!FRAME_IOB_EMPTY(&priv->lo_ieee)) + { + /* Remove the IOB from the queue */ + + FRAME_IOB_REMOVE(&priv->lo_ieee, iob); + + /* Is the queue now empty? */ + + if (FRAME_IOB_EMPTY(&priv->lo_ieee)) + { + tail = NULL; + } + + /* Return the next frame to the network */ + + iob->io_flink = NULL; + priv->lo_ieee.i_framelist = iob; + + ninfo("Send frame %p to the network. Length=%u\n", iob, iob->io_len); + ret = sixlowpan_input(&priv->lo_ieee); + if (ret < 0) + { + nerr("ERROR: sixlowpan_input returned %d\n", ret); + } + + /* What if the network responds with more frames to send? */ + + if (priv->lo_ieee.i_framelist != NULL) + { + /* Append the new list to the tail of the queue */ + + iob = priv->lo_ieee.i_framelist; + priv->lo_ieee.i_framelist = NULL; + + if (tail == NULL) + { + head = iob; + } + else + { + tail->io_flink = iob; + } + + /* Find the new tail of the IOB queue */ + + for (tail = iob, iob = iob->io_flink; + iob != NULL; + tail = iob, iob = iob->io_flink); + } + + priv->lo_txdone = true; + } + + return 0; +} + +/**************************************************************************** + * Function: lo_poll_work + * + * Description: + * Perform periodic polling from the worker thread + * + * Parameters: + * arg - The argument passed when work_queue() as called. + * + * Returned Value: + * OK on success + * + * Assumptions: + * The network is locked + * + ****************************************************************************/ + +static void lo_poll_work(FAR void *arg) +{ + FAR struct lo_driver_s *priv = (FAR struct lo_driver_s *)arg; + + /* Perform the poll */ + + net_lock(); + priv->lo_txdone = false; + (void)devif_timer(&priv->lo_ieee.i_dev, lo_txpoll); + + /* Was something received and looped back? */ + + while (priv->lo_txdone) + { + /* Yes, poll again for more TX data */ + + priv->lo_txdone = false; + (void)devif_poll(&priv->lo_ieee.i_dev, lo_txpoll); + } + + /* Setup the watchdog poll timer again */ + + (void)wd_start(priv->lo_polldog, LO_WDDELAY, lo_poll_expiry, 1, priv); + net_unlock(); +} + +/**************************************************************************** + * Function: lo_poll_expiry + * + * Description: + * Periodic timer handler. Called from the timer interrupt handler. + * + * Parameters: + * argc - The number of available arguments + * arg - The first argument + * + * Returned Value: + * None + * + * Assumptions: + * The network is locked. + * + ****************************************************************************/ + +static void lo_poll_expiry(int argc, wdparm_t arg, ...) +{ + FAR struct lo_driver_s *priv = (FAR struct lo_driver_s *)arg; + + /* Schedule to perform the interrupt processing on the worker thread. */ + + work_queue(LPBKWORK, &priv->lo_work, lo_poll_work, priv, 0); +} + +/**************************************************************************** + * Function: lo_ifup + * + * Description: + * NuttX Callback: Bring up the Ethernet interface when an IP address is + * provided + * + * Parameters: + * dev - Reference to the NuttX driver state structure + * + * Returned Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +static int lo_ifup(FAR struct net_driver_s *dev) +{ + FAR struct lo_driver_s *priv = (FAR struct lo_driver_s *)dev->d_private; + +#if CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 2 + ninfo("Bringing up: Rime %02x:%02x PANID=%04x\n", + dev->d_ipv6addr[0], dev->d_ipv6addr[1], priv->lo_ieee.i_panid); +#elif CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 8 + ninfo("Bringing up: Rime %02x:%02x:%02x:%02x:%02x:%02x:%02x:%02x PANID=%04x\n", + dev->d_ipv6addr[0], dev->d_ipv6addr[1], dev->d_ipv6addr[2], + dev->d_ipv6addr[3], dev->d_ipv6addr[4], dev->d_ipv6addr[5], + dev->d_ipv6addr[6], dev->d_ipv6addr[7], priv->lo_ieee.i_panid); +#endif + + /* Set and activate a timer process */ + + (void)wd_start(priv->lo_polldog, LO_WDDELAY, lo_poll_expiry, + 1, (wdparm_t)priv); + + priv->lo_bifup = true; + return OK; +} + +/**************************************************************************** + * Function: lo_ifdown + * + * Description: + * NuttX Callback: Stop the interface. + * + * Parameters: + * dev - Reference to the NuttX driver state structure + * + * Returned Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +static int lo_ifdown(FAR struct net_driver_s *dev) +{ + FAR struct lo_driver_s *priv = (FAR struct lo_driver_s *)dev->d_private; + + /* Cancel the TX poll timer and TX timeout timers */ + + wd_cancel(priv->lo_polldog); + + /* Mark the device "down" */ + + priv->lo_bifup = false; + return OK; +} + +/**************************************************************************** + * Function: lo_txavail_work + * + * Description: + * Perform an out-of-cycle poll on the worker thread. + * + * Parameters: + * arg - Reference to the NuttX driver state structure (cast to void*) + * + * Returned Value: + * None + * + * Assumptions: + * Called on the higher priority worker thread. + * + ****************************************************************************/ + +static void lo_txavail_work(FAR void *arg) +{ + FAR struct lo_driver_s *priv = (FAR struct lo_driver_s *)arg; + + /* Ignore the notification if the interface is not yet up */ + + net_lock(); + if (priv->lo_bifup) + { + do + { + /* If so, then poll the network for new XMIT data */ + + priv->lo_txdone = false; + (void)devif_poll(&priv->lo_ieee.i_dev, lo_txpoll); + } + while (priv->lo_txdone); + } + + net_unlock(); +} + +/**************************************************************************** + * Function: lo_txavail + * + * Description: + * Driver callback invoked when new TX data is available. This is a + * stimulus perform an out-of-cycle poll and, thereby, reduce the TX + * latency. + * + * Parameters: + * dev - Reference to the NuttX driver state structure + * + * Returned Value: + * None + * + * Assumptions: + * Called in normal user mode + * + ****************************************************************************/ + +static int lo_txavail(FAR struct net_driver_s *dev) +{ + FAR struct lo_driver_s *priv = (FAR struct lo_driver_s *)dev->d_private; + + /* Is our single work structure available? It may not be if there are + * pending interrupt actions and we will have to ignore the Tx + * availability action. + */ + + if (work_available(&priv->lo_work)) + { + /* Schedule to serialize the poll on the worker thread. */ + + work_queue(LPBKWORK, &priv->lo_work, lo_txavail_work, priv, 0); + } + + return OK; +} + +/**************************************************************************** + * Function: lo_addmac + * + * Description: + * NuttX Callback: Add the specified MAC address to the hardware multicast + * address filtering + * + * Parameters: + * dev - Reference to the NuttX driver state structure + * mac - The MAC address to be added + * + * Returned Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +#if defined(CONFIG_NET_IGMP) || defined(CONFIG_NET_ICMPv6) +static int lo_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) +{ + /* There is no multicast support in the loopback driver */ + + return OK; +} +#endif + +/**************************************************************************** + * Function: lo_rmmac + * + * Description: + * NuttX Callback: Remove the specified MAC address from the hardware multicast + * address filtering + * + * Parameters: + * dev - Reference to the NuttX driver state structure + * mac - The MAC address to be removed + * + * Returned Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +#ifdef CONFIG_NET_IGMP +static int lo_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) +{ + /* There is no multicast support in the loopback driver */ + + return OK; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: localhost_initialize + * + * Description: + * Initialize the Ethernet controller and driver + * + * Parameters: + * intf - In the case where there are multiple EMACs, this value + * identifies which EMAC is to be initialized. + * + * Returned Value: + * OK on success; Negated errno on failure. + * + * Assumptions: + * + ****************************************************************************/ + +int localhost_initialize(void) +{ + FAR struct lo_driver_s *priv; + FAR struct net_driver_s *dev; + + /* Get the interface structure associated with this interface number. */ + + priv = &g_loopback; + + /* Initialize the driver structure */ + + memset(priv, 0, sizeof(struct lo_driver_s)); + + dev = &priv->lo_ieee.i_dev; + dev->d_ifup = lo_ifup; /* I/F up (new IP address) callback */ + dev->d_ifdown = lo_ifdown; /* I/F down callback */ + dev->d_txavail = lo_txavail; /* New TX data callback */ +#ifdef CONFIG_NET_IGMP + dev->d_addmac = lo_addmac; /* Add multicast MAC address */ + dev->d_rmmac = lo_rmmac; /* Remove multicast MAC address */ +#endif + dev->d_buf = g_iobuffer; /* Attach the IO buffer */ + dev->d_private = (FAR void *)priv; /* Used to recover private state from dev */ + + /* Create a watchdog for timing polling for and timing of transmissions */ + + priv->lo_polldog = wd_create(); /* Create periodic poll timer */ + + /* Register the loopabck device with the OS so that socket IOCTLs can b + * performed. + */ + + (void)netdev_register(&priv->lo_ieee.i_dev, NET_LL_IEEE802154); + + /* Set the local loopback IP address */ + + net_ipv6addr_copy(dev->d_ipv6addr, g_lo_ipv6addr); + net_ipv6addr_copy(dev->d_ipv6draddr, g_lo_ipv6addr); + net_ipv6addr_copy(dev->d_ipv6netmask, g_ipv6_alloneaddr); + + /* Put the network in the UP state */ + + dev->d_flags = IFF_UP; + return lo_ifup(&priv->lo_ieee.i_dev); +} + +#endif /* CONFIG_IEEE802154_LOOPBACK */ -- GitLab From 068ac948e14e168d666f8e76ea01b0e0a2e626eb Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 3 Apr 2017 08:46:16 -0600 Subject: [PATCH 322/990] sim: Add a configuration for testing 6loWPAN. --- configs/sim/README.txt | 6 + configs/sim/sixlowpan/Make.defs | 128 ++++ configs/sim/sixlowpan/defconfig | 1173 +++++++++++++++++++++++++++++++ configs/sim/sixlowpan/setenv.sh | 45 ++ wireless/ieee802154/Kconfig | 4 +- 5 files changed, 1354 insertions(+), 2 deletions(-) create mode 100644 configs/sim/sixlowpan/Make.defs create mode 100644 configs/sim/sixlowpan/defconfig create mode 100644 configs/sim/sixlowpan/setenv.sh diff --git a/configs/sim/README.txt b/configs/sim/README.txt index e3712b11f9..7fa886b5bd 100644 --- a/configs/sim/README.txt +++ b/configs/sim/README.txt @@ -807,6 +807,12 @@ pashello Configures to use apps/examples/pashello. +sixlowpan + + This configuration was intended only for unit-level testing of the + 6loWPAN stack. It enables networking with 6loWPAN support and uses + only a IEEE802.15.4 MAC loopback network device to supported testing. + touchscreen This configuration uses the simple touchscreen test at diff --git a/configs/sim/sixlowpan/Make.defs b/configs/sim/sixlowpan/Make.defs new file mode 100644 index 0000000000..f2a7938575 --- /dev/null +++ b/configs/sim/sixlowpan/Make.defs @@ -0,0 +1,128 @@ +############################################################################ +# configs/sim/sixlowpan/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. +# +############################################################################ + +include ${TOPDIR}/.config +include ${TOPDIR}/tools/Config.mk + +HOSTOS = ${shell uname -o 2>/dev/null || echo "Other"} + +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + ARCHOPTIMIZATION = -g +endif + +ifneq ($(CONFIG_DEBUG_NOOPT),y) + ARCHOPTIMIZATION += -O2 +endif + +ARCHCPUFLAGS = -fno-builtin +ARCHCPUFLAGSXX = -fno-builtin -fno-exceptions -fcheck-new -fno-rtti +ARCHPICFLAGS = -fpic +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow -Wundef +ARCHWARNINGSXX = -Wall -Wshadow -Wundef +ARCHDEFINES = +ARCHINCLUDES = -I. -isystem $(TOPDIR)/include +ARCHINCLUDESXX = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx +ARCHSCRIPT = + +ifeq ($(CONFIG_SIM_M32),y) + ARCHCPUFLAGS += -m32 + ARCHCPUFLAGSXX += -m32 +endif + +CROSSDEV = +CC = $(CROSSDEV)gcc +CXX = $(CROSSDEV)g++ +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(CROSSDEV)ar rcs +NM = $(CROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump + +CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CXXFLAGS = $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGSXX) $(ARCHINCLUDESXX) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + + +# ELF module definitions + +CELFFLAGS = $(CFLAGS) +CXXELFFLAGS = $(CXXFLAGS) + +LDELFFLAGS = -r -e main +ifeq ($(WINTOOL),y) + LDELFFLAGS += -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/gnu-elf.ld}" +else + LDELFFLAGS += -T $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/gnu-elf.ld +endif + + +ASMEXT = .S +OBJEXT = .o +LIBEXT = .a + +ifeq ($(HOSTOS),Cygwin) + EXEEXT = .exe +else + EXEEXT = +endif + +LDLINKFLAGS = $(ARCHSCRIPT) # Link flags used with $(LD) +CCLINKFLAGS = $(ARCHSCRIPT) # Link flags used with $(CC) +LDFLAGS = $(ARCHSCRIPT) # For backward compatibility, same as CCLINKFLAGS + +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + LDLINKFLAGS += -g + CCLINKFLAGS += -g + LDFLAGS += -g +endif + +ifeq ($(CONFIG_SIM_M32),y) + LDLINKFLAGS += -melf_i386 + CCLINKFLAGS += -m32 + LDFLAGS += -m32 +endif + + +MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT) + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGS) $(HOSTINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +HOSTLDFLAGS = diff --git a/configs/sim/sixlowpan/defconfig b/configs/sim/sixlowpan/defconfig new file mode 100644 index 0000000000..dbf6981155 --- /dev/null +++ b/configs/sim/sixlowpan/defconfig @@ -0,0 +1,1173 @@ +# +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# + +# +# Build Setup +# +CONFIG_EXPERIMENTAL=y +# CONFIG_DEFAULT_SMALL is not set +# CONFIG_HOST_LINUX is not set +# CONFIG_HOST_OSX is not set +CONFIG_HOST_WINDOWS=y +# CONFIG_HOST_OTHER is not set +CONFIG_TOOLCHAIN_WINDOWS=y +# CONFIG_WINDOWS_NATIVE is not set +CONFIG_WINDOWS_CYGWIN=y +# CONFIG_WINDOWS_UBUNTU is not set +# CONFIG_WINDOWS_MSYS is not set +# CONFIG_WINDOWS_OTHER is not set + +# +# Build Configuration +# +# CONFIG_APPS_DIR="../apps" +CONFIG_BUILD_FLAT=y +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +# CONFIG_INTELHEX_BINARY is not set +# CONFIG_MOTOROLA_SREC is not set +CONFIG_RAW_BINARY=y +# CONFIG_UBOOT_UIMAGE is not set + +# +# Customize Header Files +# +# CONFIG_ARCH_STDINT_H is not set +# CONFIG_ARCH_STDBOOL_H is not set +# CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_FLOAT_H is not set +# CONFIG_ARCH_STDARG_H is not set +# CONFIG_ARCH_DEBUG_H is not set + +# +# Debug Options +# +CONFIG_DEBUG_ALERT=y +# CONFIG_DEBUG_FEATURES is not set +# CONFIG_ARCH_HAVE_STACKCHECK is not set +# CONFIG_ARCH_HAVE_HEAPCHECK is not set +CONFIG_DEBUG_SYMBOLS=y +# CONFIG_ARCH_HAVE_CUSTOMOPT is not set +CONFIG_DEBUG_NOOPT=y +# CONFIG_DEBUG_FULLOPT is not set + +# +# System Type +# +# CONFIG_ARCH_ARM is not set +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_MISOC is not set +# CONFIG_ARCH_RENESAS is not set +# CONFIG_ARCH_RISCV is not set +CONFIG_ARCH_SIM=y +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_XTENSA is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="sim" + +# +# Simulation Configuration Options +# +CONFIG_HOST_X86_64=y +# CONFIG_HOST_X86 is not set +# CONFIG_SIM_M32 is not set +# CONFIG_SIM_CYGWIN_DECORATED is not set +# CONFIG_SIM_X8664_SYSTEMV is not set +CONFIG_SIM_X8664_MICROSOFT=y +# CONFIG_SIM_WALLTIME is not set +# CONFIG_SIM_NETDEV is not set +# CONFIG_SIM_FRAMEBUFFER is not set +# CONFIG_SIM_SPIFLASH is not set +# CONFIG_SIM_QSPIFLASH is not set + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_VECNOTIRQ is not set +# CONFIG_ARCH_DMA is not set +# CONFIG_ARCH_HAVE_IRQPRIO is not set +# CONFIG_ARCH_L2CACHE is not set +# CONFIG_ARCH_HAVE_COHERENT_DCACHE is not set +# CONFIG_ARCH_HAVE_ADDRENV is not set +# CONFIG_ARCH_NEED_ADDRENV_MAPPING is not set +CONFIG_ARCH_HAVE_MULTICPU=y +# CONFIG_ARCH_HAVE_VFORK is not set +# CONFIG_ARCH_HAVE_MMU is not set +# CONFIG_ARCH_HAVE_MPU is not set +# CONFIG_ARCH_NAND_HWECC is not set +# CONFIG_ARCH_HAVE_EXTCLK is not set +CONFIG_ARCH_HAVE_POWEROFF=y +# CONFIG_ARCH_HAVE_RESET is not set +CONFIG_ARCH_STACKDUMP=y +# CONFIG_ENDIAN_BIG is not set +# CONFIG_ARCH_IDLE_CUSTOM is not set +# CONFIG_ARCH_HAVE_RAMFUNCS is not set +# CONFIG_ARCH_HAVE_RAMVECTORS is not set +# CONFIG_ARCH_MINIMAL_VECTORTABLE is not set + +# +# Board Settings +# +CONFIG_BOARD_LOOPSPERMSEC=51262 +# CONFIG_ARCH_CALIBRATION is not set + +# +# Interrupt options +# +# CONFIG_ARCH_HAVE_INTERRUPTSTACK is not set +# CONFIG_ARCH_HAVE_HIPRI_INTERRUPT is not set + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Boot Memory Configuration +# +CONFIG_RAM_START=0x20400000 +CONFIG_RAM_SIZE=393216 +# CONFIG_ARCH_HAVE_SDRAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_SIM=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="sim" + +# +# Common Board Options +# + +# +# Board-Specific Options +# +# CONFIG_BOARD_CRASHDUMP is not set +CONFIG_LIB_BOARDCTL=y +# CONFIG_BOARDCTL_POWEROFF is not set +# CONFIG_BOARDCTL_UNIQUEID is not set +# CONFIG_BOARDCTL_TSCTEST is not set +# CONFIG_BOARDCTL_GRAPHICS is not set +# CONFIG_BOARDCTL_IOCTL is not set + +# +# RTOS Features +# +CONFIG_DISABLE_OS_API=y +# CONFIG_DISABLE_POSIX_TIMERS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_DISABLE_SIGNALS is not set +# CONFIG_DISABLE_MQUEUE is not set +# CONFIG_DISABLE_ENVIRON is not set + +# +# Clocks and Timers +# +CONFIG_ARCH_HAVE_TICKLESS=y +# CONFIG_SCHED_TICKLESS is not set +CONFIG_USEC_PER_TICK=10000 +# CONFIG_SYSTEM_TIME64 is not set +# CONFIG_CLOCK_MONOTONIC is not set +# CONFIG_ARCH_HAVE_TIMEKEEPING is not set +# CONFIG_JULIAN_TIME is not set +CONFIG_START_YEAR=2014 +CONFIG_START_MONTH=3 +CONFIG_START_DAY=10 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=32 +CONFIG_WDOG_INTRESERVE=4 +CONFIG_PREALLOC_TIMERS=4 + +# +# Tasks and Scheduling +# +# CONFIG_SPINLOCK is not set +# CONFIG_SMP is not set +# CONFIG_INIT_NONE is not set +CONFIG_INIT_ENTRYPOINT=y +# CONFIG_INIT_FILEPATH is not set +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_RR_INTERVAL=200 +# CONFIG_SCHED_SPORADIC is not set +CONFIG_TASK_NAME_SIZE=31 +CONFIG_MAX_TASKS=16 +# CONFIG_SCHED_HAVE_PARENT is not set +CONFIG_SCHED_WAITPID=y + +# +# Pthread Options +# +# CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set +CONFIG_NPTHREAD_KEYS=4 +# CONFIG_PTHREAD_CLEANUP is not set +# CONFIG_CANCELLATION_POINTS is not set + +# +# Performance Monitoring +# +# CONFIG_SCHED_CPULOAD is not set +# CONFIG_SCHED_INSTRUMENTATION is not set + +# +# Files and I/O +# +CONFIG_DEV_CONSOLE=y +# CONFIG_FDCLONE_DISABLE is not set +# CONFIG_FDCLONE_STDIO is not set +CONFIG_SDCLONE_DISABLE=y +CONFIG_NFILE_DESCRIPTORS=8 +CONFIG_NFILE_STREAMS=8 +CONFIG_NAME_MAX=32 +# CONFIG_PRIORITY_INHERITANCE is not set + +# +# RTOS hooks +# +# CONFIG_BOARD_INITIALIZE is not set +# CONFIG_SCHED_STARTHOOK is not set +# CONFIG_SCHED_ATEXIT is not set +# CONFIG_SCHED_ONEXIT is not set +# CONFIG_SIG_EVTHREAD is not set + +# +# Signal Numbers +# +CONFIG_SIG_SIGUSR1=1 +CONFIG_SIG_SIGUSR2=2 +CONFIG_SIG_SIGALARM=3 +CONFIG_SIG_SIGCONDTIMEDOUT=16 +CONFIG_SIG_SIGWORK=17 + +# +# POSIX Message Queue Options +# +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_MQ_MAXMSGSIZE=32 +# CONFIG_MODULE is not set + +# +# Work queue support +# +CONFIG_SCHED_WORKQUEUE=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=224 +CONFIG_SCHED_HPWORKPERIOD=50000 +CONFIG_SCHED_HPWORKSTACKSIZE=4096 +# CONFIG_SCHED_LPWORK is not set + +# +# Stack and heap information +# +CONFIG_IDLETHREAD_STACKSIZE=4096 +CONFIG_USERMAIN_STACKSIZE=8192 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=4096 +# CONFIG_LIB_SYSCALL is not set + +# +# Device Drivers +# +CONFIG_DISABLE_POLL=y +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_DEV_URANDOM is not set +# CONFIG_DEV_LOOP is not set + +# +# Buffering +# +# CONFIG_DRVR_WRITEBUFFER is not set +# CONFIG_DRVR_READAHEAD is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_ARCH_HAVE_PWM_PULSECOUNT is not set +# CONFIG_ARCH_HAVE_PWM_MULTICHAN is not set +# CONFIG_PWM is not set +# CONFIG_ARCH_HAVE_I2CRESET is not set +CONFIG_I2C=y +# CONFIG_I2C_SLAVE is not set +# CONFIG_I2C_POLLED is not set +# CONFIG_I2C_TRACE is not set +CONFIG_I2C_DRIVER=y +# CONFIG_ARCH_HAVE_SPI_CRCGENERATION is not set +# CONFIG_ARCH_HAVE_SPI_CS_CONTROL is not set +# CONFIG_ARCH_HAVE_SPI_BITORDER is not set +CONFIG_SPI=y +# CONFIG_SPI_SLAVE is not set +CONFIG_SPI_EXCHANGE=y +# CONFIG_SPI_CMDDATA is not set +# CONFIG_SPI_CALLBACK is not set +# CONFIG_SPI_HWFEATURES is not set +# CONFIG_SPI_CS_DELAY_CONTROL is not set +# CONFIG_SPI_DRIVER is not set +# CONFIG_SPI_BITBANG is not set +# CONFIG_I2S is not set + +# +# Timer Driver Support +# +# CONFIG_TIMER is not set +# CONFIG_ONESHOT is not set +# CONFIG_RTC is not set +# CONFIG_WATCHDOG is not set +# CONFIG_TIMERS_CS2100CP is not set +# CONFIG_ANALOG is not set +# CONFIG_AUDIO_DEVICES is not set +# CONFIG_VIDEO_DEVICES is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set + +# +# IO Expander/GPIO Support +# +# CONFIG_IOEXPANDER is not set +# CONFIG_DEV_GPIO is not set + +# +# LCD Driver Support +# +# CONFIG_LCD is not set +# CONFIG_SLCD is not set + +# +# LED Support +# +# CONFIG_RGBLED is not set +# CONFIG_PCA9635PW is not set +# CONFIG_NCP5623C is not set +CONFIG_MMCSD=y +CONFIG_MMCSD_NSLOTS=1 +# CONFIG_MMCSD_READONLY is not set +CONFIG_MMCSD_MULTIBLOCK_DISABLE=y +# CONFIG_MMCSD_MMCSUPPORT is not set +CONFIG_MMCSD_HAVECARDDETECT=y +# CONFIG_MMCSD_SPI is not set +# CONFIG_ARCH_HAVE_SDIO is not set +# CONFIG_SDIO_DMA is not set +# CONFIG_ARCH_HAVE_SDIOWAIT_WRCOMPLETE is not set +# CONFIG_MODEM is not set +CONFIG_MTD=y + +# +# MTD Configuration +# +# CONFIG_MTD_PARTITION is not set +# CONFIG_MTD_SECT512 is not set +# CONFIG_MTD_BYTE_WRITE is not set +# CONFIG_MTD_PROGMEM is not set +CONFIG_MTD_CONFIG=y +# CONFIG_MTD_CONFIG_RAM_CONSOLIDATE is not set +CONFIG_MTD_CONFIG_ERASEDVALUE=0xff + +# +# MTD Device Drivers +# +# CONFIG_MTD_NAND is not set +# CONFIG_RAMMTD is not set +# CONFIG_FILEMTD is not set +CONFIG_MTD_AT24XX=y +# CONFIG_AT24XX_MULTI is not set +CONFIG_AT24XX_SIZE=2 +CONFIG_AT24XX_ADDR=0x57 +CONFIG_AT24XX_EXTENDED=y +CONFIG_AT24XX_EXTSIZE=160 +CONFIG_AT24XX_FREQUENCY=100000 +CONFIG_MTD_AT25=y +CONFIG_AT25_SPIMODE=0 +CONFIG_AT25_SPIFREQUENCY=20000000 +# CONFIG_MTD_AT45DB is not set +# CONFIG_MTD_IS25XP is not set +# CONFIG_MTD_M25P is not set +# CONFIG_MTD_MX25L is not set +# CONFIG_MTD_S25FL1 is not set +# CONFIG_MTD_N25QXXX is not set +# CONFIG_MTD_SMART is not set +# CONFIG_MTD_RAMTRON is not set +# CONFIG_MTD_SST25 is not set +# CONFIG_MTD_SST25XX is not set +# CONFIG_MTD_SST26 is not set +# CONFIG_MTD_SST39FV is not set +# CONFIG_MTD_W25 is not set +# CONFIG_EEPROM is not set +CONFIG_NETDEVICES=y + +# +# General Ethernet MAC Driver Options +# +# CONFIG_NETDEV_LOOPBACK is not set +CONFIG_NETDEV_TELNET=y +CONFIG_TELNET_RXBUFFER_SIZE=256 +CONFIG_TELNET_TXBUFFER_SIZE=256 +CONFIG_NETDEV_MULTINIC=y +CONFIG_ARCH_HAVE_NETDEV_STATISTICS=y +CONFIG_NETDEV_STATISTICS=y +# CONFIG_NETDEV_LATEINIT is not set + +# +# External Ethernet MAC Device Support +# +# CONFIG_NET_DM90x0 is not set +# CONFIG_NET_CS89x0 is not set +# CONFIG_ENC28J60 is not set +# CONFIG_ENCX24J600 is not set +# CONFIG_NET_SLIP is not set +# CONFIG_NET_FTMAC100 is not set +# CONFIG_PIPES is not set +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +CONFIG_SERIAL=y +# CONFIG_DEV_LOWCONSOLE is not set +# CONFIG_SERIAL_REMOVABLE is not set +CONFIG_SERIAL_CONSOLE=y +# CONFIG_16550_UART is not set +# CONFIG_UART_SERIALDRIVER is not set +# CONFIG_UART0_SERIALDRIVER is not set +# CONFIG_UART1_SERIALDRIVER is not set +# CONFIG_UART2_SERIALDRIVER is not set +# CONFIG_UART3_SERIALDRIVER is not set +# CONFIG_UART4_SERIALDRIVER is not set +# CONFIG_UART5_SERIALDRIVER is not set +# CONFIG_UART6_SERIALDRIVER is not set +# CONFIG_UART7_SERIALDRIVER is not set +# CONFIG_UART8_SERIALDRIVER is not set +# CONFIG_SCI0_SERIALDRIVER is not set +# CONFIG_SCI1_SERIALDRIVER is not set +# CONFIG_USART0_SERIALDRIVER is not set +# CONFIG_USART1_SERIALDRIVER is not set +# CONFIG_USART2_SERIALDRIVER is not set +# CONFIG_USART3_SERIALDRIVER is not set +# CONFIG_USART4_SERIALDRIVER is not set +# CONFIG_USART5_SERIALDRIVER is not set +# CONFIG_USART6_SERIALDRIVER is not set +# CONFIG_USART7_SERIALDRIVER is not set +# CONFIG_USART8_SERIALDRIVER is not set +# CONFIG_OTHER_UART_SERIALDRIVER is not set +# CONFIG_MCU_SERIAL is not set +CONFIG_STANDARD_SERIAL=y +# CONFIG_SERIAL_IFLOWCONTROL is not set +# CONFIG_SERIAL_OFLOWCONTROL is not set +# CONFIG_SERIAL_DMA is not set +# CONFIG_ARCH_HAVE_SERIAL_TERMIOS is not set +# CONFIG_PSEUDOTERM is not set +# CONFIG_USBDEV is not set +# CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set +# CONFIG_HAVE_USBTRACE is not set +# CONFIG_DRIVERS_WIRELESS is not set +# CONFIG_DRIVERS_CONTACTLESS is not set + +# +# System Logging +# +# CONFIG_ARCH_SYSLOG is not set +# CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_INTBUFFER is not set +# CONFIG_SYSLOG_TIMESTAMP is not set +CONFIG_SYSLOG_SERIAL_CONSOLE=y +# CONFIG_SYSLOG_CHAR is not set +CONFIG_SYSLOG_CONSOLE=y +# CONFIG_SYSLOG_NONE is not set +# CONFIG_SYSLOG_FILE is not set +# CONFIG_SYSLOG_CHARDEV is not set + +# +# Networking Support +# +CONFIG_ARCH_HAVE_NET=y +# CONFIG_ARCH_HAVE_PHY is not set +CONFIG_NET=y +# CONFIG_NET_PROMISCUOUS is not set + +# +# Driver buffer configuration +# +CONFIG_NET_ETH_MTU=590 +CONFIG_NET_ETH_TCP_RECVWNDO=536 +CONFIG_NET_GUARDSIZE=2 + +# +# Data link support +# +CONFIG_NET_MULTILINK=y +# CONFIG_NET_USER_DEVFMT is not set +CONFIG_NET_ETHERNET=y +CONFIG_NET_6LOWPAN=y +# CONFIG_NET_LOOPBACK is not set +# CONFIG_NET_TUN is not set +# CONFIG_NET_USRSOCK is not set + +# +# Network Device Operations +# +CONFIG_NETDEV_IOCTL=y +CONFIG_NETDEV_PHY_IOCTL=y + +# +# Internet Protocol Selection +# +# CONFIG_NET_IPv4 is not set +CONFIG_NET_IPv6=y +CONFIG_NET_IPv6_NCONF_ENTRIES=8 +CONFIG_NET_6LOWPAN_FRAG=y +CONFIG_NET_6LOWPAN_FRAMELEN=127 +# CONFIG_NET_6LOWPAN_COMPRESSION_IPv6 is not set +# CONFIG_NET_6LOWPAN_COMPRESSION_HC1 is not set +CONFIG_NET_6LOWPAN_COMPRESSION_HC06=y +CONFIG_NET_6LOWPAN_COMPRESSION_THRESHOLD=63 +CONFIG_NET_6LOWPAN_MAXADDRCONTEXT=1 +CONFIG_NET_6LOWPAN_MAXADDRCONTEXT_PREFIX_0_0=0xaa +CONFIG_NET_6LOWPAN_MAXADDRCONTEXT_PREFIX_0_1=0xaa +# CONFIG_NET_6LOWPAN_MAXADDRCONTEXT_PREINIT_1 is not set +CONFIG_NET_6LOWPAN_RIMEADDR_SIZE=2 +CONFIG_NET_6LOWPAN_MAXAGE=20 +CONFIG_NET_6LOWPAN_MAX_MACTRANSMITS=4 +CONFIG_NET_6LOWPAN_MAXPAYLOAD=102 +CONFIG_NET_6LOWPAN_MTU=1294 +CONFIG_NET_6LOWPAN_TCP_RECVWNDO=102 + +# +# Socket Support +# +CONFIG_NSOCKET_DESCRIPTORS=8 +CONFIG_NET_NACTIVESOCKETS=16 +CONFIG_NET_SOCKOPTS=y +# CONFIG_NET_SOLINGER is not set + +# +# Raw Socket Support +# +# CONFIG_NET_PKT is not set + +# +# Unix Domain Socket Support +# +# CONFIG_NET_LOCAL is not set + +# +# TCP/IP Networking +# +CONFIG_NET_TCP=y +# CONFIG_NET_TCP_NO_STACK is not set +# CONFIG_NET_TCPURGDATA is not set +# CONFIG_NET_TCP_REASSEMBLY is not set +CONFIG_NET_TCP_CONNS=8 +CONFIG_NET_MAX_LISTENPORTS=20 +CONFIG_NET_TCP_READAHEAD=y +CONFIG_NET_TCP_WRITE_BUFFERS=y +CONFIG_NET_TCP_NWRBCHAINS=8 +CONFIG_NET_TCP_RECVDELAY=0 +CONFIG_NET_TCPBACKLOG=y +# CONFIG_NET_SENDFILE is not set + +# +# UDP Networking +# +CONFIG_NET_UDP=y +# CONFIG_NET_UDP_NO_STACK is not set +# CONFIG_NET_UDP_CHECKSUMS is not set +CONFIG_NET_UDP_CONNS=8 +CONFIG_NET_BROADCAST=y +# CONFIG_NET_RXAVAIL is not set +CONFIG_NET_UDP_READAHEAD=y + +# +# ICMPv6 Networking Support +# +# CONFIG_NET_ICMPv6 is not set + +# +# IGMPv2 Client Support +# +# CONFIG_NET_IGMP is not set + +# +# ARP Configuration +# + +# +# Network I/O Buffer Support +# +CONFIG_NET_IOB=y +CONFIG_IOB_NBUFFERS=36 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 +CONFIG_IOB_THROTTLE=8 + +# +# User-space networking stack API +# +# CONFIG_NET_ARCH_INCR32 is not set +# CONFIG_NET_ARCH_CHKSUM is not set +CONFIG_NET_STATISTICS=y + +# +# Routing Table Configuration +# +# CONFIG_NET_ROUTE is not set +CONFIG_NET_HOSTNAME="SAMV71-XULT" + +# +# Crypto API +# +# CONFIG_CRYPTO is not set + +# +# File Systems +# + +# +# File system configuration +# +# CONFIG_DISABLE_MOUNTPOINT is not set +# CONFIG_FS_AUTOMOUNTER is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_PSEUDOFS_SOFTLINKS is not set +CONFIG_FS_READABLE=y +CONFIG_FS_WRITABLE=y +# CONFIG_FS_NAMED_SEMAPHORES is not set +CONFIG_FS_MQUEUE_MPATH="/var/mqueue" +# CONFIG_FS_RAMMAP is not set +CONFIG_FS_FAT=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_MAXFNAME=32 +# CONFIG_FS_FATTIME is not set +# CONFIG_FAT_FORCE_INDIRECT is not set +# CONFIG_FAT_DMAMEMORY is not set +# CONFIG_FAT_DIRECT_RETRY is not set +# CONFIG_FS_NXFFS is not set +# CONFIG_FS_ROMFS is not set +# CONFIG_FS_TMPFS is not set +# CONFIG_FS_SMARTFS is not set +# CONFIG_FS_BINFS is not set +CONFIG_FS_PROCFS=y +# CONFIG_FS_PROCFS_REGISTER is not set + +# +# Exclude individual procfs entries +# +# CONFIG_FS_PROCFS_EXCLUDE_PROCESS is not set +# CONFIG_FS_PROCFS_EXCLUDE_UPTIME is not set +# CONFIG_FS_PROCFS_EXCLUDE_MOUNTS is not set +# CONFIG_FS_PROCFS_EXCLUDE_NET is not set +# CONFIG_FS_PROCFS_EXCLUDE_MTD is not set +# CONFIG_FS_UNIONFS is not set +# CONFIG_FS_HOSTFS is not set + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=1 +# CONFIG_ARCH_HAVE_HEAP2 is not set +# CONFIG_GRAN is not set + +# +# Audio Support +# +# CONFIG_AUDIO is not set + +# +# Wireless Support +# +CONFIG_WIRELESS=y +CONFIG_WIRELESS_IEEE802154=y +CONFIG_IEEE802154_LOOPBACK=y +CONFIG_IEEE802154_LOOPBACK_HPWORK=y + +# +# Binary Loader +# +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_BINFMT_EXEPATH is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +CONFIG_BUILTIN=y +# CONFIG_PIC is not set +# CONFIG_SYMTAB_ORDEREDBYNAME is not set + +# +# Library Routines +# + +# +# Standard C Library Options +# + +# +# Standard C I/O +# +# CONFIG_STDIO_DISABLE_BUFFERING is not set +CONFIG_STDIO_BUFFER_SIZE=64 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +# CONFIG_NOPRINTF_FIELDWIDTH is not set +# CONFIG_LIBC_FLOATINGPOINT is not set +CONFIG_LIBC_LONG_LONG=y +# CONFIG_LIBC_SCANSET is not set +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_MEMCPY_VIK is not set +# CONFIG_LIBM is not set + +# +# Architecture-Specific Support +# +CONFIG_ARCH_LOWPUTC=y +# CONFIG_ARCH_ROMGETC is not set +# CONFIG_LIBC_ARCH_MEMCPY is not set +# CONFIG_LIBC_ARCH_MEMCMP is not set +# CONFIG_LIBC_ARCH_MEMMOVE is not set +# CONFIG_LIBC_ARCH_MEMSET is not set +# CONFIG_LIBC_ARCH_STRCHR is not set +# CONFIG_LIBC_ARCH_STRCMP is not set +# CONFIG_LIBC_ARCH_STRCPY is not set +# CONFIG_LIBC_ARCH_STRNCPY is not set +# CONFIG_LIBC_ARCH_STRLEN is not set +# CONFIG_LIBC_ARCH_STRNLEN is not set +# CONFIG_LIBC_ARCH_ELF is not set + +# +# stdlib Options +# +CONFIG_LIB_RAND_ORDER=1 +CONFIG_LIB_HOMEDIR="/" +CONFIG_LIBC_TMPDIR="/tmp" +CONFIG_LIBC_MAX_TMPFILE=32 + +# +# Program Execution Options +# +# CONFIG_LIBC_EXECFUNCS is not set +CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=2048 +CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=4096 + +# +# errno Decode Support +# +# CONFIG_LIBC_STRERROR is not set +# CONFIG_LIBC_PERROR_STDOUT is not set + +# +# memcpy/memset Options +# +# CONFIG_MEMSET_OPTSPEED is not set +# CONFIG_LIBC_DLLFCN is not set +# CONFIG_LIBC_MODLIB is not set +# CONFIG_LIBC_WCHAR is not set +# CONFIG_LIBC_LOCALE is not set + +# +# Time/Time Zone Support +# +# CONFIG_LIBC_LOCALTIME is not set +# CONFIG_TIME_EXTENDED is not set +CONFIG_ARCH_HAVE_TLS=y + +# +# Thread Local Storage (TLS) +# +# CONFIG_TLS is not set + +# +# Network-Related Options +# +# CONFIG_LIBC_IPv4_ADDRCONV is not set +CONFIG_LIBC_NETDB=y + +# +# NETDB Support +# +# CONFIG_NETDB_HOSTFILE is not set +CONFIG_NETDB_DNSCLIENT=y +CONFIG_NETDB_DNSCLIENT_ENTRIES=8 +CONFIG_NETDB_DNSCLIENT_NAMESIZE=32 +CONFIG_NETDB_DNSCLIENT_LIFESEC=3600 +CONFIG_NETDB_DNSCLIENT_MAXRESPONSE=96 +# CONFIG_NETDB_RESOLVCONF is not set +# CONFIG_NETDB_DNSSERVER_NOADDR is not set +CONFIG_NETDB_DNSSERVER_IPv6=y +CONFIG_NETDB_DNSSERVER_IPv6ADDR_1=0xfc00 +CONFIG_NETDB_DNSSERVER_IPv6ADDR_2=0x0000 +CONFIG_NETDB_DNSSERVER_IPv6ADDR_3=0x0000 +CONFIG_NETDB_DNSSERVER_IPv6ADDR_4=0x0000 +CONFIG_NETDB_DNSSERVER_IPv6ADDR_5=0x0000 +CONFIG_NETDB_DNSSERVER_IPv6ADDR_6=0x0000 +CONFIG_NETDB_DNSSERVER_IPv6ADDR_7=0x0000 +CONFIG_NETDB_DNSSERVER_IPv6ADDR_8=0x0001 +# CONFIG_LIBC_IOCTL_VARIADIC is not set +CONFIG_LIB_SENDFILE_BUFSIZE=512 + +# +# Non-standard Library Support +# +# CONFIG_LIB_CRC64_FAST is not set +# CONFIG_LIB_KBDCODEC is not set +# CONFIG_LIB_SLCDCODEC is not set +# CONFIG_LIB_HEX2BIN is not set + +# +# Basic CXX Support +# +# CONFIG_C99_BOOL8 is not set +# CONFIG_HAVE_CXX is not set + +# +# Application Configuration +# + +# +# Built-In Applications +# +CONFIG_BUILTIN_PROXY_STACKSIZE=2048 + +# +# CAN Utilities +# + +# +# Examples +# +# CONFIG_EXAMPLES_CCTYPE is not set +# CONFIG_EXAMPLES_CHAT is not set +# CONFIG_EXAMPLES_CONFIGDATA is not set +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_DISCOVER is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FSTEST is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HIDKBD is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_JSON is not set +# CONFIG_EXAMPLES_KEYPADTEST is not set +# CONFIG_EXAMPLES_MEDIA is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MODBUS is not set +# CONFIG_EXAMPLES_MOUNT is not set +CONFIG_EXAMPLES_NETTEST=y +# CONFIG_EXAMPLES_NETTEST_SERVER is not set +# CONFIG_EXAMPLES_NETTEST_PERFORMANCE is not set +CONFIG_EXAMPLES_NETTEST_IPv6=y +# CONFIG_EXAMPLES_NETTEST_INIT is not set + +# +# Target IPv6 address +# + +# +# Client IPv6 address +# +CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_1=0xfc00 +CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_2=0x0000 +CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_3=0x0000 +CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_4=0x0000 +CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_5=0x0000 +CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_6=0x0000 +CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_7=0x0000 +CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_8=0x0001 +CONFIG_EXAMPLES_NSH=y +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NXLINES is not set +# CONFIG_EXAMPLES_NXTERM is not set +# CONFIG_EXAMPLES_NXTEXT is not set +# CONFIG_EXAMPLES_OSTEST is not set +# CONFIG_EXAMPLES_PCA9635 is not set +# CONFIG_EXAMPLES_POSIXSPAWN is not set +# CONFIG_EXAMPLES_PPPD is not set +# CONFIG_EXAMPLES_RFID_READUID is not set +# CONFIG_EXAMPLES_RGBLED is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERIALBLASTER is not set +# CONFIG_EXAMPLES_SERIALRX is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_SLCD is not set +# CONFIG_EXAMPLES_SMART is not set +# CONFIG_EXAMPLES_SMART_TEST is not set +# CONFIG_EXAMPLES_SMP is not set +# CONFIG_EXAMPLES_STAT is not set +# CONFIG_EXAMPLES_TCPECHO is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_UDP is not set +# CONFIG_EXAMPLES_UDPBLASTER is not set +# CONFIG_EXAMPLES_USBSERIAL is not set +# CONFIG_EXAMPLES_WATCHDOG is not set +# CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set + +# +# File System Utilities +# +# CONFIG_FSUTILS_FLASH_ERASEALL is not set +# CONFIG_FSUTILS_INIFILE is not set +# CONFIG_FSUTILS_PASSWD is not set + +# +# GPS Utilities +# +# CONFIG_GPSUTILS_MINMEA_LIB is not set + +# +# Graphics Support +# +# CONFIG_TIFF is not set +# CONFIG_GRAPHICS_TRAVELER is not set + +# +# Interpreters +# +# CONFIG_INTERPRETERS_BAS is not set +# CONFIG_INTERPRETERS_FICL is not set +# CONFIG_INTERPRETERS_MICROPYTHON is not set +# CONFIG_INTERPRETERS_MINIBASIC is not set +# CONFIG_INTERPRETERS_PCODE is not set + +# +# FreeModBus +# +# CONFIG_MODBUS is not set + +# +# Network Utilities +# +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_DISCOVER is not set +# CONFIG_NETUTILS_ESP8266 is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_JSON is not set +CONFIG_NETUTILS_NETLIB=y +# CONFIG_NETUTILS_NTPCLIENT is not set +# CONFIG_NETUTILS_PPPD is not set +# CONFIG_NETUTILS_SMTP is not set +# CONFIG_NETUTILS_TELNETD is not set +# CONFIG_NETUTILS_TFTPC is not set +# CONFIG_NETUTILS_WEBCLIENT is not set +# CONFIG_NETUTILS_WEBSERVER is not set +# CONFIG_NETUTILS_XMLRPC is not set + +# +# NSH Library +# +CONFIG_NSH_LIBRARY=y +# CONFIG_NSH_MOTD is not set + +# +# Command Line Configuration +# +CONFIG_NSH_READLINE=y +# CONFIG_NSH_CLE is not set +CONFIG_NSH_LINELEN=64 +# CONFIG_NSH_DISABLE_SEMICOLON is not set +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_MAXARGUMENTS=6 +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_NESTDEPTH=3 +# CONFIG_NSH_DISABLEBG is not set +CONFIG_NSH_BUILTIN_APPS=y + +# +# Disable Individual commands +# +# CONFIG_NSH_DISABLE_ADDROUTE is not set +# CONFIG_NSH_DISABLE_BASENAME is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_CMP is not set +CONFIG_NSH_DISABLE_DATE=y +# CONFIG_NSH_DISABLE_DD is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_DELROUTE is not set +# CONFIG_NSH_DISABLE_DIRNAME is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_HEXDUMP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +# CONFIG_NSH_DISABLE_IFUPDOWN is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOSETUP is not set +CONFIG_NSH_DISABLE_LOSMART=y +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MB is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MKRD is not set +# CONFIG_NSH_DISABLE_MH is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_MW is not set +# CONFIG_NSH_DISABLE_NSLOOKUP is not set +CONFIG_NSH_DISABLE_PRINTF=y +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PUT is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SH is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNAME is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +# CONFIG_NSH_DISABLE_WGET is not set +# CONFIG_NSH_DISABLE_XD is not set +CONFIG_NSH_MMCSDMINOR=0 +CONFIG_NSH_MMCSDSLOTNO=0 + +# +# Configure Command Options +# +# CONFIG_NSH_CMDOPT_DF_H is not set +# CONFIG_NSH_CMDOPT_DD_STATS is not set +CONFIG_NSH_CODECS_BUFSIZE=128 +CONFIG_NSH_CMDOPT_HEXDUMP=y +CONFIG_NSH_PROC_MOUNTPOINT="/proc" +CONFIG_NSH_FILEIOSIZE=512 + +# +# Scripting Support +# +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_LOOPS is not set + +# +# Console Configuration +# +CONFIG_NSH_CONSOLE=y +# CONFIG_NSH_ALTCONDEV is not set +CONFIG_NSH_ARCHINIT=y + +# +# Networking Configuration +# +CONFIG_NSH_NETINIT=y +# CONFIG_NSH_NETINIT_THREAD is not set + +# +# IP Address Configuration +# + +# +# Target IPv6 address +# +CONFIG_NSH_IPv6ADDR_1=0xfe80 +CONFIG_NSH_IPv6ADDR_2=0x0000 +CONFIG_NSH_IPv6ADDR_3=0x0000 +CONFIG_NSH_IPv6ADDR_4=0x0000 +CONFIG_NSH_IPv6ADDR_5=0xabcd +CONFIG_NSH_IPv6ADDR_6=0x0000 +CONFIG_NSH_IPv6ADDR_7=0x0000 +CONFIG_NSH_IPv6ADDR_8=0x0000 + +# +# Router IPv6 address +# +CONFIG_NSH_DRIPv6ADDR_1=0xfe80 +CONFIG_NSH_DRIPv6ADDR_2=0x0000 +CONFIG_NSH_DRIPv6ADDR_3=0x0000 +CONFIG_NSH_DRIPv6ADDR_4=0x0000 +CONFIG_NSH_DRIPv6ADDR_5=0x1234 +CONFIG_NSH_DRIPv6ADDR_6=0x0000 +CONFIG_NSH_DRIPv6ADDR_7=0x0000 +CONFIG_NSH_DRIPv6ADDR_8=0x0000 + +# +# IPv6 Network mask +# +CONFIG_NSH_IPv6NETMASK_1=0xffff +CONFIG_NSH_IPv6NETMASK_2=0xffff +CONFIG_NSH_IPv6NETMASK_3=0xffff +CONFIG_NSH_IPv6NETMASK_4=0xffff +CONFIG_NSH_IPv6NETMASK_5=0xffff +CONFIG_NSH_IPv6NETMASK_6=0x0000 +CONFIG_NSH_IPv6NETMASK_7=0x0000 +CONFIG_NSH_IPv6NETMASK_8=0x0000 +# CONFIG_NSH_DNS is not set +CONFIG_NSH_NOMAC=y +CONFIG_NSH_SWMAC=y +CONFIG_NSH_MACADDR=0xabcd +CONFIG_NSH_MAX_ROUNDTRIP=20 +# CONFIG_NSH_LOGIN is not set +# CONFIG_NSH_CONSOLE_LOGIN is not set + +# +# NxWidgets/NxWM +# + +# +# Platform-specific Support +# +# CONFIG_PLATFORM_CONFIGDATA is not set + +# +# System Libraries and NSH Add-Ons +# +# CONFIG_SYSTEM_CLE is not set +# CONFIG_SYSTEM_CUTERM is not set +# CONFIG_SYSTEM_FLASH_ERASEALL is not set +# CONFIG_SYSTEM_FREE is not set +# CONFIG_SYSTEM_HEX2BIN is not set +# CONFIG_SYSTEM_HEXED is not set +CONFIG_SYSTEM_I2CTOOL=y +CONFIG_I2CTOOL_MINBUS=0 +CONFIG_I2CTOOL_MAXBUS=0 +CONFIG_I2CTOOL_MINADDR=0x03 +CONFIG_I2CTOOL_MAXADDR=0x77 +CONFIG_I2CTOOL_MAXREGADDR=0xff +CONFIG_I2CTOOL_DEFFREQ=400000 +# CONFIG_SYSTEM_INSTALL is not set +# CONFIG_SYSTEM_MDIO is not set +# CONFIG_SYSTEM_NETDB is not set +# CONFIG_SYSTEM_RAMTEST is not set +CONFIG_READLINE_HAVE_EXTMATCH=y +CONFIG_SYSTEM_READLINE=y +CONFIG_READLINE_ECHO=y +# CONFIG_READLINE_TABCOMPLETION is not set +# CONFIG_READLINE_CMD_HISTORY is not set +# CONFIG_SYSTEM_SUDOKU is not set +# CONFIG_SYSTEM_SYSTEM is not set +# CONFIG_SYSTEM_TEE is not set +# CONFIG_SYSTEM_UBLOXMODEM is not set +# CONFIG_SYSTEM_VI is not set +# CONFIG_SYSTEM_ZMODEM is not set diff --git a/configs/sim/sixlowpan/setenv.sh b/configs/sim/sixlowpan/setenv.sh new file mode 100644 index 0000000000..65065ccc9b --- /dev/null +++ b/configs/sim/sixlowpan/setenv.sh @@ -0,0 +1,45 @@ +#!/bin/bash +# sim/sixlowpan/setenv.sh +# +# 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. +# + +if [ "$(basename $0)" = "setenv.sh" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +fi + +if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi + +#export NUTTX_BIN= +#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG} + +echo "PATH : ${PATH}" diff --git a/wireless/ieee802154/Kconfig b/wireless/ieee802154/Kconfig index 92872fcb9f..228779a5d4 100644 --- a/wireless/ieee802154/Kconfig +++ b/wireless/ieee802154/Kconfig @@ -10,7 +10,7 @@ config WIRELESS_IEEE802154 ---help--- Enables support for the IEEE 802.14.5 Wireless library. -if IEEE802154 +if WIRELESS_IEEE802154 config IEEE802154_LOOPBACK bool "IEEE802154 6loWPAN Loopback" @@ -43,4 +43,4 @@ config IEEE802154_LOOPBACK_LPWORK endchoice # Work queue endif # IEEE802154_LOOPBACK -endif # IEEE802154 +endif # WIRELESS_IEEE802154 -- GitLab From e9d831ac60befca21dbf7780f0ca43b54c95d196 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 3 Apr 2017 09:15:00 -0600 Subject: [PATCH 323/990] wireless/ieee802154: Add initialization logic for loopback driver; configs/sim: Add configuration for testing 6loWPAN; net/sixlowpan: Fix for compilation with debug output enabled. --- configs/sim/src/sim_boot.c | 16 ---- configs/sim/src/sim_bringup.c | 11 +++ .../wireless/ieee802154/ieee802154_loopback.h | 73 +++++++++++++++++++ net/sixlowpan/sixlowpan_hc06.c | 2 +- net/sixlowpan/sixlowpan_input.c | 3 +- net/sixlowpan/sixlowpan_tcpsend.c | 5 +- net/sixlowpan/sixlowpan_udpsend.c | 3 +- wireless/ieee802154/mac802154_loopback.c | 30 ++------ 8 files changed, 98 insertions(+), 45 deletions(-) create mode 100644 include/nuttx/wireless/ieee802154/ieee802154_loopback.h diff --git a/configs/sim/src/sim_boot.c b/configs/sim/src/sim_boot.c index 826ca47f90..6e0be20777 100644 --- a/configs/sim/src/sim_boot.c +++ b/configs/sim/src/sim_boot.c @@ -42,22 +42,6 @@ #include "sim.h" -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Types - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - /**************************************************************************** * Public Functions ****************************************************************************/ diff --git a/configs/sim/src/sim_bringup.c b/configs/sim/src/sim_bringup.c index 8f0d85c078..8dd0f75bdd 100644 --- a/configs/sim/src/sim_bringup.c +++ b/configs/sim/src/sim_bringup.c @@ -47,6 +47,7 @@ #include #include #include +#include #include "up_internal.h" #include "sim.h" @@ -139,5 +140,15 @@ int sim_bringup(void) } #endif +#ifdef CONFIG_IEEE802154_LOOPBACK + /* Initialize and register the IEEE802.15.4 MAC network loop device */ + + ret = ieee8021514_loopback(); + if (ret < 0) + { + _err("ERROR: ieee8021514_loopback() failed: %d\n", ret); + } +#endif + return OK; } diff --git a/include/nuttx/wireless/ieee802154/ieee802154_loopback.h b/include/nuttx/wireless/ieee802154/ieee802154_loopback.h new file mode 100644 index 0000000000..d1952df24f --- /dev/null +++ b/include/nuttx/wireless/ieee802154/ieee802154_loopback.h @@ -0,0 +1,73 @@ +/**************************************************************************** + * include/nuttx/net/ieee802154.h + * + * Copyright (C) 2016 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Includes some definitions that a compatible with the LGPL GNU C Library + * header file of the same name. + * + * 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_WIRELESS_IEEE802154_IEEE802154_LOOPBACK_H +#define __INCLUDE_NUTTX_WIRELESS_IEEE802154_IEEE802154_LOOPBACK_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#ifdef CONFIG_IEEE802154_LOOPBACK + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Function: ieee8021514_loopback + * + * Description: + * Initialize and register the Ieee802.15.4 MAC loopback network driver. + * + * Parameters: + * None + * + * Returned Value: + * OK on success; Negated errno on failure. + * + * Assumptions: + * + ****************************************************************************/ + +int ieee8021514_loopback(void); + +#endif /* CONFIG_IEEE802154_LOOPBACK */ +#endif /* __INCLUDE_NUTTX_WIRELESS_IEEE802154_IEEE802154_LOOPBACK_H */ diff --git a/net/sixlowpan/sixlowpan_hc06.c b/net/sixlowpan/sixlowpan_hc06.c index 270c6f6885..d23a392e05 100644 --- a/net/sixlowpan/sixlowpan_hc06.c +++ b/net/sixlowpan/sixlowpan_hc06.c @@ -455,7 +455,7 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, uint8_t iphc1; uint8_t tmp; - ninfodumpbuffer("IPv6 before compression", ipv6, sizeof(ipv6_hdr_s)); + ninfodumpbuffer("IPv6 before compression", ipv6, sizeof(struct ipv6_hdr_s)); g_hc06ptr = g_rimeptr + 2; diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index b89af933d8..5ee8b49017 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -470,7 +470,8 @@ copypayload: } #endif /* CONFIG_NET_6LOWPAN_FRAG */ - ninfodumpbuffer("IPv6 header", IPv6BUF(ieee->i_dev), IPv6_HDRLEN) + ninfodumpbuffer("IPv6 header", (FAR const uint8_t *)IPv6BUF(&ieee->i_dev), + IPv6_HDRLEN); return OK; } diff --git a/net/sixlowpan/sixlowpan_tcpsend.c b/net/sixlowpan/sixlowpan_tcpsend.c index 2b0ce15cb3..3fd541999d 100644 --- a/net/sixlowpan/sixlowpan_tcpsend.c +++ b/net/sixlowpan/sixlowpan_tcpsend.c @@ -249,7 +249,8 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, net_ipv6addr_hdrcopy(ipv6tcp.ipv6.srcipaddr, conn->u.ipv6.laddr); net_ipv6addr_hdrcopy(ipv6tcp.ipv6.destipaddr, conn->u.ipv6.raddr); - ninfo("IPv6 length: %d\n", ((int)ipv6->len[0] << 8) + ipv6->len[1]); + ninfo("IPv6 length: %d\n", + ((int)ipv6tcp.ipv6.len[0] << 8) + ipv6tcp.ipv6.len[1]); #ifdef CONFIG_NET_STATISTICS g_netstats.ipv6.sent++; @@ -289,7 +290,7 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, ipv6tcp.tcp.tcpchksum = 0; ipv6tcp.tcp.tcpchksum = ~sixlowpan_tcp_chksum(&ipv6tcp, buf, buflen); - ninfo("Outgoing TCP packet length: %d bytes\n", iplen + IOPv6_HDRLEN); + ninfo("Outgoing TCP packet length: %d bytes\n", iplen + IPv6_HDRLEN); #ifdef CONFIG_NET_STATISTICS g_netstats.tcp.sent++; diff --git a/net/sixlowpan/sixlowpan_udpsend.c b/net/sixlowpan/sixlowpan_udpsend.c index 61fbe3b237..53c7ead6ce 100644 --- a/net/sixlowpan/sixlowpan_udpsend.c +++ b/net/sixlowpan/sixlowpan_udpsend.c @@ -263,7 +263,8 @@ ssize_t psock_6lowpan_udp_sendto(FAR struct socket *psock, net_ipv6addr_hdrcopy(ipv6udp.ipv6.srcipaddr, to6->sin6_addr.in6_u.u6_addr16); net_ipv6addr_hdrcopy(ipv6udp.ipv6.destipaddr, conn->u.ipv6.raddr); - ninfo("IPv6 length: %d\n", ((int)ipv6->len[0] << 8) + ipv6->len[1]); + ninfo("IPv6 length: %d\n", + ((int)ipv6udp.ipv6.len[0] << 8) + ipv6udp.ipv6.len[1]); #ifdef CONFIG_NET_STATISTICS g_netstats.ipv6.sent++; diff --git a/wireless/ieee802154/mac802154_loopback.c b/wireless/ieee802154/mac802154_loopback.c index 5bbd6f5beb..595c085e8f 100644 --- a/wireless/ieee802154/mac802154_loopback.c +++ b/wireless/ieee802154/mac802154_loopback.c @@ -53,11 +53,8 @@ #include #include #include -#include - -#ifndef CONFIG_NET_LOOPBACK -# include -#endif +#include +#include #ifdef CONFIG_IEEE802154_LOOPBACK @@ -110,14 +107,6 @@ struct lo_driver_s static struct lo_driver_s g_loopback; static uint8_t g_iobuffer[CONFIG_NET_6LOWPAN_MTU + CONFIG_NET_GUARDSIZE]; -#ifndef CONFIG_NET_LOOPBACK -static const net_ipv6addr_t g_lo_ipv6addr = -{ - HTONS(0), HTONS(0), HTONS(0), HTONS(0), - HTONS(0), HTONS(0), HTONS(0), HTONS(1) -}; -#endif - /**************************************************************************** * Private Function Prototypes ****************************************************************************/ @@ -520,14 +509,13 @@ static int lo_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) ****************************************************************************/ /**************************************************************************** - * Function: localhost_initialize + * Function: ieee8021514_loopback * * Description: - * Initialize the Ethernet controller and driver + * Initialize and register the Ieee802.15.4 MAC loopback network driver. * * Parameters: - * intf - In the case where there are multiple EMACs, this value - * identifies which EMAC is to be initialized. + * None * * Returned Value: * OK on success; Negated errno on failure. @@ -536,7 +524,7 @@ static int lo_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) * ****************************************************************************/ -int localhost_initialize(void) +int ieee8021514_loopback(void) { FAR struct lo_driver_s *priv; FAR struct net_driver_s *dev; @@ -570,12 +558,6 @@ int localhost_initialize(void) (void)netdev_register(&priv->lo_ieee.i_dev, NET_LL_IEEE802154); - /* Set the local loopback IP address */ - - net_ipv6addr_copy(dev->d_ipv6addr, g_lo_ipv6addr); - net_ipv6addr_copy(dev->d_ipv6draddr, g_lo_ipv6addr); - net_ipv6addr_copy(dev->d_ipv6netmask, g_ipv6_alloneaddr); - /* Put the network in the UP state */ dev->d_flags = IFF_UP; -- GitLab From 2c06f8ab789d3dd8959315a85fc762515bdae0ff Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 3 Apr 2017 12:01:04 -0600 Subject: [PATCH 324/990] 6loWPAN: Updates/fixes from early testing with the IEEE802.15.4 loopback driver. --- configs/sim/sixlowpan/defconfig | 23 +++----- net/devif/devif_poll.c | 74 ++++++++++++++++++++++++ net/devif/ipv6_input.c | 23 +++++--- net/sixlowpan/sixlowpan.h | 13 +++-- net/sixlowpan/sixlowpan_tcpsend.c | 17 ++++-- wireless/ieee802154/mac802154_loopback.c | 65 +++++++++++++++++++-- 6 files changed, 177 insertions(+), 38 deletions(-) diff --git a/configs/sim/sixlowpan/defconfig b/configs/sim/sixlowpan/defconfig index dbf6981155..d3c4c9d54c 100644 --- a/configs/sim/sixlowpan/defconfig +++ b/configs/sim/sixlowpan/defconfig @@ -159,7 +159,7 @@ CONFIG_ARCH_BOARD="sim" # # CONFIG_BOARD_CRASHDUMP is not set CONFIG_LIB_BOARDCTL=y -# CONFIG_BOARDCTL_POWEROFF is not set +CONFIG_BOARDCTL_POWEROFF=y # CONFIG_BOARDCTL_UNIQUEID is not set # CONFIG_BOARDCTL_TSCTEST is not set # CONFIG_BOARDCTL_GRAPHICS is not set @@ -873,26 +873,17 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=2048 # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set CONFIG_EXAMPLES_NETTEST=y -# CONFIG_EXAMPLES_NETTEST_SERVER is not set +CONFIG_EXAMPLES_NETTEST_STACKSIZE=4096 +CONFIG_EXAMPLES_NETTEST_PRIORITY=100 +CONFIG_EXAMPLES_NETTEST_LOOPBACK=y +CONFIG_EXAMPLES_NETTEST_SERVER_STACKSIZE=4096 +CONFIG_EXAMPLES_NETTEST_SERVER_PRIORITY=100 # CONFIG_EXAMPLES_NETTEST_PERFORMANCE is not set CONFIG_EXAMPLES_NETTEST_IPv6=y -# CONFIG_EXAMPLES_NETTEST_INIT is not set # # Target IPv6 address # - -# -# Client IPv6 address -# -CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_1=0xfc00 -CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_2=0x0000 -CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_3=0x0000 -CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_4=0x0000 -CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_5=0x0000 -CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_6=0x0000 -CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_7=0x0000 -CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_8=0x0001 CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -1034,6 +1025,7 @@ CONFIG_NSH_DISABLE_LOSMART=y # CONFIG_NSH_DISABLE_MV is not set # CONFIG_NSH_DISABLE_MW is not set # CONFIG_NSH_DISABLE_NSLOOKUP is not set +# CONFIG_NSH_DISABLE_POWEROFF is not set CONFIG_NSH_DISABLE_PRINTF=y # CONFIG_NSH_DISABLE_PS is not set # CONFIG_NSH_DISABLE_PUT is not set @@ -1042,6 +1034,7 @@ CONFIG_NSH_DISABLE_PRINTF=y # CONFIG_NSH_DISABLE_RMDIR is not set # CONFIG_NSH_DISABLE_SET is not set # CONFIG_NSH_DISABLE_SH is not set +CONFIG_NSH_DISABLE_SHUTDOWN=y # CONFIG_NSH_DISABLE_SLEEP is not set # CONFIG_NSH_DISABLE_TIME is not set # CONFIG_NSH_DISABLE_TEST is not set diff --git a/net/devif/devif_poll.c b/net/devif/devif_poll.c index 4a5d325d43..bde0cabb7a 100644 --- a/net/devif/devif_poll.c +++ b/net/devif/devif_poll.c @@ -45,6 +45,7 @@ #include #include #include +#include #include "devif/devif.h" #include "arp/arp.h" @@ -55,6 +56,7 @@ #include "icmp/icmp.h" #include "icmpv6/icmpv6.h" #include "igmp/igmp.h" +#include "sixlowpan/sixlowpan.h" /**************************************************************************** * Public Data @@ -68,6 +70,50 @@ systime_t g_polltime; * Private Functions ****************************************************************************/ +/**************************************************************************** + * Function: devif_packet_conversion + * + * Description: + * TCP output comes through three different mechansims. Either from: + * + * 1. TCP socket output. For the case of TCP output to an + * IEEE802.15.4, the TCP output is caught in the socket + * send()/sendto() logic and and redirected to 6loWPAN logic. + * 2. TCP output from the TCP state machine. That will occur + * during TCP packet processing by the TCP state meachine. + * 3. TCP output resulting from TX or timer polling + * + * Cases 2 is handled here. Logic here detected if (1) an attempt + * to return with d_len > 0 and (2) that the device is an + * IEEE802.15.4 MAC network driver. Under those conditions, 6loWPAN + * logic will be called to create the IEEE80215.4 frames. + * + * Assumptions: + * The network is locked. + * + ****************************************************************************/ + +#ifdef CONFIG_NET_6LOWPAN +static inline void devif_packet_conversion(FAR struct net_driver_s *dev) +{ +#ifdef CONFIG_NET_MULTILINK + /* Handle the case where multiple link layer protocols are supported */ + + if (dev->d_len > 0 && dev->d_lltype == NET_LL_IEEE802154) +#else + if (dev->d_len > 0) +#endif + { + /* Let 6loWPAN convert output into the IEEE802.15.4 frames */ + + sixlowpan_tcp_send(dev); + dev->d_len = 0; + } +} +#else +# define devif_packet_conversion(dev) +#endif /* CONFIG_NET_6LOWPAN */ + /**************************************************************************** * Function: devif_poll_pkt_connections * @@ -95,6 +141,10 @@ static int devif_poll_pkt_connections(FAR struct net_driver_s *dev, pkt_poll(dev, pkt_conn); + /* Perform any necessary conversions on outgoing packets */ + + devif_packet_conversion(dev); + /* Call back into the driver */ bstop = callback(dev); @@ -120,6 +170,10 @@ static inline int devif_poll_icmp(FAR struct net_driver_s *dev, icmp_poll(dev); + /* Perform any necessary conversions on outgoing packets */ + + devif_packet_conversion(dev); + /* Call back into the driver */ return callback(dev); @@ -142,6 +196,10 @@ static inline int devif_poll_icmpv6(FAR struct net_driver_s *dev, icmpv6_poll(dev); + /* Perform any necessary conversions on outgoing packets */ + + devif_packet_conversion(dev); + /* Call back into the driver */ return callback(dev); @@ -168,6 +226,10 @@ static inline int devif_poll_igmp(FAR struct net_driver_s *dev, igmp_poll(dev); + /* Perform any necessary conversions on outgoing packets */ + + devif_packet_conversion(dev); + /* Call back into the driver */ return callback(dev); @@ -201,6 +263,10 @@ static int devif_poll_udp_connections(FAR struct net_driver_s *dev, udp_poll(dev, conn); + /* Perform any necessary conversions on outgoing packets */ + + devif_packet_conversion(dev); + /* Call back into the driver */ bstop = callback(dev); @@ -237,6 +303,10 @@ static inline int devif_poll_tcp_connections(FAR struct net_driver_s *dev, tcp_poll(dev, conn); + /* Perform any necessary conversions on outgoing packets */ + + devif_packet_conversion(dev); + /* Call back into the driver */ bstop = callback(dev); @@ -277,6 +347,10 @@ static inline int devif_poll_tcp_timer(FAR struct net_driver_s *dev, tcp_timer(dev, conn, hsec); + /* Perform any necessary conversions on outgoing packets */ + + devif_packet_conversion(dev); + /* Call back into the driver */ bstop = callback(dev); diff --git a/net/devif/ipv6_input.c b/net/devif/ipv6_input.c index d55b0739ad..24be107a47 100644 --- a/net/devif/ipv6_input.c +++ b/net/devif/ipv6_input.c @@ -261,24 +261,29 @@ int ipv6_input(FAR struct net_driver_s *dev) tcp_ipv6_input(dev); #ifdef CONFIG_NET_6LOWPAN - /* TCP output comes through two different mechansims. Either from: + /* TCP output comes through three different mechansims. Either from: * * 1. TCP socket output. For the case of TCP output to an * IEEE802.15.4, the TCP output is caught in the socket * send()/sendto() logic and and redirected to 6loWPAN logic. - * 2. TCP output from the TCP state machine. That will pass - * here and can be detected if d_len > 0. It will be redirected - * to 6loWPAN logic here. + * 2. TCP output from the TCP state machine. That will occur + * during TCP packet processing by the TCP state meachine. + * 3. TCP output resulting from TX or timer polling + * + * Cases 2 is handled here. Logic here detected if (1) an attempt + * to return with d_len > 0 and (2) that the device is an + * IEEE802.15.4 MAC network driver. Under those conditions, 6loWPAN + * logic will be called to create the IEEE80215.4 frames. */ #ifdef CONFIG_NET_MULTILINK - /* Handle the case where multiple link layer protocols are supported */ + /* Handle the case where multiple link layer protocols are supported */ - if (dev->d_len > 0 && dev->d_lltype == CONFIG_NET_6LOWPAN) + if (dev->d_len > 0 && dev->d_lltype == CONFIG_NET_6LOWPAN) #else - if (dev->d_len > 0) + if (dev->d_len > 0) #endif - { + { /* Let 6loWPAN handle the TCP output */ sixlowpan_tcp_send(dev); @@ -286,7 +291,7 @@ int ipv6_input(FAR struct net_driver_s *dev) /* Drop the packet in the d_buf */ goto drop; - } + } #endif /* CONFIG_NET_6LOWPAN */ break; #endif /* NET_TCP_HAVE_STACK */ diff --git a/net/sixlowpan/sixlowpan.h b/net/sixlowpan/sixlowpan.h index c9f54154b5..05ce9496c9 100644 --- a/net/sixlowpan/sixlowpan.h +++ b/net/sixlowpan/sixlowpan.h @@ -110,15 +110,20 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, * Function: sixlowpan_tcp_send * * Description: - * TCP output comes through two different mechansims. Either from: + * TCP output comes through three different mechansims. Either from: * * 1. TCP socket output. For the case of TCP output to an * IEEE802.15.4, the TCP output is caught in the socket * send()/sendto() logic and and redirected to psock_6lowpan_tcp_send(). * 2. TCP output from the TCP state machine. That will occur - * during TCP packet processing by the TCP state meachine. It - * is detected there when ipv6_tcp_input() returns with d_len > 0. This - * will be redirected here. + * during TCP packet processing by the TCP state meachine. + * 3. TCP output resulting from TX or timer polling + * + * Cases 2 and 3 will be handled here. Logic in ipv6_tcp_input(), + * devif_poll(), and devif_timer() detect if (1) an attempt to return with + * d_len > 0 and (2) that the device is an IEEE802.15.4 MAC network + * driver. Under those conditions, this function will be called to create + * the IEEE80215.4 frames. * * Parameters: * dev - An instance of nework device state structure diff --git a/net/sixlowpan/sixlowpan_tcpsend.c b/net/sixlowpan/sixlowpan_tcpsend.c index 3fd541999d..933a7f6361 100644 --- a/net/sixlowpan/sixlowpan_tcpsend.c +++ b/net/sixlowpan/sixlowpan_tcpsend.c @@ -155,6 +155,8 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, uint16_t iplen; int ret; + ninfo("buflen %lu\n", (unsigned long)buflen); + DEBUGASSERT(psock != NULL && psock->s_crefs > 0); DEBUGASSERT(psock->s_type == SOCK_STREAM); @@ -333,15 +335,20 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, * Function: sixlowpan_tcp_send * * Description: - * TCP output comes through two different mechansims. Either from: + * TCP output comes through three different mechansims. Either from: * * 1. TCP socket output. For the case of TCP output to an * IEEE802.15.4, the TCP output is caught in the socket * send()/sendto() logic and and redirected to psock_6lowpan_tcp_send(). * 2. TCP output from the TCP state machine. That will occur - * during TCP packet processing by the TCP state meachine. It - * is detected there when ipv6_tcp_input() returns with d_len > 0. This - * will be redirected here. + * during TCP packet processing by the TCP state meachine. + * 3. TCP output resulting from TX or timer polling + * + * Cases 2 and 3 will be handled here. Logic in ipv6_tcp_input(), + * devif_poll(), and devif_timer() detect if (1) an attempt to return with + * d_len > 0 and (2) that the device is an IEEE802.15.4 MAC network + * driver. Under those conditions, this function will be called to create + * the IEEE80215.4 frames. * * Parameters: * dev - An instance of nework device state structure @@ -360,6 +367,8 @@ void sixlowpan_tcp_send(FAR struct net_driver_s *dev) /* Double check */ + ninfo("d_len %u\n", dev->d_len); + if (dev != NULL && dev->d_len > 0) { FAR struct ipv6_hdr_s *ipv6hdr; diff --git a/wireless/ieee802154/mac802154_loopback.c b/wireless/ieee802154/mac802154_loopback.c index 595c085e8f..1f8dc4e8c3 100644 --- a/wireless/ieee802154/mac802154_loopback.c +++ b/wireless/ieee802154/mac802154_loopback.c @@ -162,6 +162,22 @@ static int lo_txpoll(FAR struct net_driver_s *dev) FAR struct iob_s *iob; int ret; + if (dev->d_len > 0 || priv->lo_ieee.i_framelist != NULL) + { + ninfo("d_len: %u i_framelist: %p\n", + dev->d_len, priv->lo_ieee.i_framelist); + + /* The only two valid settings are: + * + * 1. Nothing to send: + * dev->d_len == 0 && priv->lo_ieee.i_framelist == NULL + * 2. Outgoing packet has been converted to IEEE802.15.4 frames: + * dev->d_len == 0 && priv->lo_ieee.i_framelist != NULL + */ + + DEBUGASSERT(dev->d_len == 0 && priv->lo_ieee.i_framelist != NULL); + } + /* Remove the queued IOBs from driver structure */ head = priv->lo_ieee.i_framelist; @@ -298,6 +314,11 @@ static void lo_poll_expiry(int argc, wdparm_t arg, ...) { FAR struct lo_driver_s *priv = (FAR struct lo_driver_s *)arg; + if (!work_available(&priv->lo_work)) + { + nwarn("WARNING: lo_work NOT available\n"); + } + /* Schedule to perform the interrupt processing on the worker thread. */ work_queue(LPBKWORK, &priv->lo_work, lo_poll_work, priv, 0); @@ -324,14 +345,22 @@ static int lo_ifup(FAR struct net_driver_s *dev) { FAR struct lo_driver_s *priv = (FAR struct lo_driver_s *)dev->d_private; -#if CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 2 - ninfo("Bringing up: Rime %02x:%02x PANID=%04x\n", - dev->d_ipv6addr[0], dev->d_ipv6addr[1], priv->lo_ieee.i_panid); -#elif CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 8 - ninfo("Bringing up: Rime %02x:%02x:%02x:%02x:%02x:%02x:%02x:%02x PANID=%04x\n", + ninfo("Bringing up: IPv6 %04x:%04x:%04x:%04x:%04x:%04x:%04x:%04x\n", dev->d_ipv6addr[0], dev->d_ipv6addr[1], dev->d_ipv6addr[2], dev->d_ipv6addr[3], dev->d_ipv6addr[4], dev->d_ipv6addr[5], - dev->d_ipv6addr[6], dev->d_ipv6addr[7], priv->lo_ieee.i_panid); + dev->d_ipv6addr[6], dev->d_ipv6addr[7]); + +#if CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 2 + ninfo(" Node: %02x:%02x PANID=%04x\n", + priv->lo_ieee.i_nodeaddr.u8[0], priv->lo_ieee.i_nodeaddr.u8[1], + priv->lo_ieee.i_panid); +#else /* CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 8 */ + ninfo(" Node: %02x:%02x:%02x:%02x:%02x:%02x:%02x:%02x PANID=%04x\n", + priv->lo_ieee.i_nodeaddr.u8[0], priv->lo_ieee.i_nodeaddr.u8[1], + priv->lo_ieee.i_nodeaddr.u8[2], priv->lo_ieee.i_nodeaddr.u8[3], + priv->lo_ieee.i_nodeaddr.u8[4], priv->lo_ieee.i_nodeaddr.u8[5], + priv->lo_ieee.i_nodeaddr.u8[6], priv->lo_ieee.i_nodeaddr.u8[7], + priv->lo_ieee.i_panid); #endif /* Set and activate a timer process */ @@ -363,6 +392,8 @@ static int lo_ifdown(FAR struct net_driver_s *dev) { FAR struct lo_driver_s *priv = (FAR struct lo_driver_s *)dev->d_private; + ninfo("IP up: %u\n", priv->lo_bifup); + /* Cancel the TX poll timer and TX timeout timers */ wd_cancel(priv->lo_polldog); @@ -394,6 +425,8 @@ static void lo_txavail_work(FAR void *arg) { FAR struct lo_driver_s *priv = (FAR struct lo_driver_s *)arg; + ninfo("IP up: %u\n", priv->lo_bifup); + /* Ignore the notification if the interface is not yet up */ net_lock(); @@ -435,6 +468,8 @@ static int lo_txavail(FAR struct net_driver_s *dev) { FAR struct lo_driver_s *priv = (FAR struct lo_driver_s *)dev->d_private; + ninfo("Available: %u\n", work_available(&priv->lo_work)); + /* Is our single work structure available? It may not be if there are * pending interrupt actions and we will have to ignore the Tx * availability action. @@ -471,6 +506,14 @@ static int lo_txavail(FAR struct net_driver_s *dev) #if defined(CONFIG_NET_IGMP) || defined(CONFIG_NET_ICMPv6) static int lo_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) { +#if CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 2 + ninfo("MAC: %02x:%02x\n", + mac[0], mac[1]); +#else /* CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 8 */ + ninfo("MAC: %02x:%02x:%02x:%02x:%02x:%02x:%02x:%02x\n", + mac[0], mac[1], mac[2], mac[3], mac[4], mac[5], mac[6], mac[7]); +#endif + /* There is no multicast support in the loopback driver */ return OK; @@ -498,6 +541,14 @@ static int lo_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) #ifdef CONFIG_NET_IGMP static int lo_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) { +#if CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 2 + ninfo("MAC: %02x:%02x\n", + mac[0], mac[1]); +#else /* CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 8 */ + ninfo("MAC: %02x:%02x:%02x:%02x:%02x:%02x:%02x:%02x\n", + mac[0], mac[1], mac[2], mac[3], mac[4], mac[5], mac[6], mac[7]); +#endif + /* There is no multicast support in the loopback driver */ return OK; @@ -529,6 +580,8 @@ int ieee8021514_loopback(void) FAR struct lo_driver_s *priv; FAR struct net_driver_s *dev; + ninfo("Initializing\n"); + /* Get the interface structure associated with this interface number. */ priv = &g_loopback; -- GitLab From 7cb34d969de6a62461ee8b7d29ad4a405c0b143c Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 3 Apr 2017 15:25:36 -0600 Subject: [PATCH 325/990] 6loWPAN: More fixes from early debug. --- configs/sim/sixlowpan/defconfig | 19 ++++++--- include/nuttx/net/ip.h | 14 +++---- net/devif/devif_poll.c | 64 +++++++++++++++++++++++++----- net/procfs/netdev_statistics.c | 50 ++++++++++++++++++++++- net/sixlowpan/sixlowpan_hc06.c | 3 +- net/sixlowpan/sixlowpan_internal.h | 13 +++--- net/sixlowpan/sixlowpan_tcpsend.c | 4 +- net/sixlowpan/sixlowpan_utils.c | 8 ++-- net/tcp/tcp_finddev.c | 1 - 9 files changed, 138 insertions(+), 38 deletions(-) diff --git a/configs/sim/sixlowpan/defconfig b/configs/sim/sixlowpan/defconfig index d3c4c9d54c..adf330024f 100644 --- a/configs/sim/sixlowpan/defconfig +++ b/configs/sim/sixlowpan/defconfig @@ -500,16 +500,14 @@ CONFIG_NET=y # # Driver buffer configuration # -CONFIG_NET_ETH_MTU=590 -CONFIG_NET_ETH_TCP_RECVWNDO=536 CONFIG_NET_GUARDSIZE=2 # # Data link support # -CONFIG_NET_MULTILINK=y +# CONFIG_NET_MULTILINK is not set # CONFIG_NET_USER_DEVFMT is not set -CONFIG_NET_ETHERNET=y +# CONFIG_NET_ETHERNET is not set CONFIG_NET_6LOWPAN=y # CONFIG_NET_LOOPBACK is not set # CONFIG_NET_TUN is not set @@ -884,6 +882,17 @@ CONFIG_EXAMPLES_NETTEST_IPv6=y # # Target IPv6 address # +# +# Client IPv6 address +# +CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_1=0xfe80 +CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_2=0x0000 +CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_3=0x0000 +CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_4=0x0000 +CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_5=0x1234 +CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_6=0x0000 +CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_7=0x0000 +CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_8=0x0000 CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -1112,7 +1121,7 @@ CONFIG_NSH_IPv6NETMASK_1=0xffff CONFIG_NSH_IPv6NETMASK_2=0xffff CONFIG_NSH_IPv6NETMASK_3=0xffff CONFIG_NSH_IPv6NETMASK_4=0xffff -CONFIG_NSH_IPv6NETMASK_5=0xffff +CONFIG_NSH_IPv6NETMASK_5=0x0000 CONFIG_NSH_IPv6NETMASK_6=0x0000 CONFIG_NSH_IPv6NETMASK_7=0x0000 CONFIG_NSH_IPv6NETMASK_8=0x0000 diff --git a/include/nuttx/net/ip.h b/include/nuttx/net/ip.h index c7b606078b..84df352074 100644 --- a/include/nuttx/net/ip.h +++ b/include/nuttx/net/ip.h @@ -547,7 +547,7 @@ bool net_ipv6addr_maskcmp(const net_ipv6addr_t addr1, #define net_is_addr_loopback(a) \ ((a)[0] == 0 && (a)[1] == 0 && (a)[2] == 0 && (a)[3] == 0 && \ - (a)[4] == 0 && (a)[5] == 0 && (a)[6] == 0 && (a)[7] == 0x0001) + (a)[4] == 0 && (a)[5] == 0 && (a)[6] == 0 && (a)[7] == HTONS(0x0001)) /**************************************************************************** * Name: net_is_addr_unspecified @@ -569,7 +569,7 @@ bool net_ipv6addr_maskcmp(const net_ipv6addr_t addr1, * ****************************************************************************/ -#define net_is_addr_mcast(a) (((a)[0] & 0xff00) == 0xff00) +#define net_is_addr_mcast(a) (((a)[0] & HTONS(0xff00)) == HTONS(0xff00)) /**************************************************************************** * Name: net_is_addr_linklocal_allnodes_mcast @@ -580,8 +580,8 @@ bool net_ipv6addr_maskcmp(const net_ipv6addr_t addr1, ****************************************************************************/ #define net_is_addr_linklocal_allnodes_mcast(a) \ - ((a)[0] == 0xff02 && (a)[1] == 0 && (a)[2] == 0 && (a)[3] == 0 && \ - (a)[4] == 0 && (a)[5] == 0 && (a)[6] == 0 && (a)[7] == 0x0001) + ((a)[0] == HTONS(0xff02) && (a)[1] == 0 && (a)[2] == 0 && (a)[3] == 0 && \ + (a)[4] == 0 && (a)[5] == 0 && (a)[6] == 0 && (a)[7] == HTONS(0x0001)) /**************************************************************************** * Name: net_is_addr_linklocal_allrouters_mcast @@ -592,8 +592,8 @@ bool net_ipv6addr_maskcmp(const net_ipv6addr_t addr1, ****************************************************************************/ #define net_is_addr_linklocal_allrouters_mcast(a) \ - ((a)[0] == 0xff02 && (a)[1] == 0 && (a)[2] == 0 && (a)[3] == 0 && \ - (a)[4] == 0 && (a)[5] == 0 && (a)[6] == 0 && (a)[7] == 0x0002) + ((a)[0] == HTONS(0xff02) && (a)[1] == 0 && (a)[2] == 0 && (a)[3] == 0 && \ + (a)[4] == 0 && (a)[5] == 0 && (a)[6] == 0 && (a)[7] == HTOS(0x0002)) /**************************************************************************** * Name: net_is_addr_linklocal @@ -603,7 +603,7 @@ bool net_ipv6addr_maskcmp(const net_ipv6addr_t addr1, * ****************************************************************************/ -#define net_is_addr_linklocal(a) ((a)[0] == 0xfe80) +#define net_is_addr_linklocal(a) ((a)[0] == HTONS(0xfe80)) /**************************************************************************** * Name: net_ipaddr_mask diff --git a/net/devif/devif_poll.c b/net/devif/devif_poll.c index bde0cabb7a..235c58bcf2 100644 --- a/net/devif/devif_poll.c +++ b/net/devif/devif_poll.c @@ -58,6 +58,20 @@ #include "igmp/igmp.h" #include "sixlowpan/sixlowpan.h" +/**************************************************************************** + * Private Types + ****************************************************************************/ + +enum devif_packet_type +{ + DEVIF_PKT = 0, + DEVIF_ICMP, + DEVIF_IGMP, + DEVIF_TCP, + DEVIF_UDP, + DEVIF_ICMP6 +}; + /**************************************************************************** * Public Data ****************************************************************************/ @@ -74,6 +88,9 @@ systime_t g_polltime; * Function: devif_packet_conversion * * Description: + * Generic output conversion hook. Only needed for IEEE802.15.4 for now + * is a point where support for other conversions may be provided. + * * TCP output comes through three different mechansims. Either from: * * 1. TCP socket output. For the case of TCP output to an @@ -94,7 +111,8 @@ systime_t g_polltime; ****************************************************************************/ #ifdef CONFIG_NET_6LOWPAN -static inline void devif_packet_conversion(FAR struct net_driver_s *dev) +static void devif_packet_conversion(FAR struct net_driver_s *dev, + enum devif_packet_type pkttype) { #ifdef CONFIG_NET_MULTILINK /* Handle the case where multiple link layer protocols are supported */ @@ -104,14 +122,38 @@ static inline void devif_packet_conversion(FAR struct net_driver_s *dev) if (dev->d_len > 0) #endif { - /* Let 6loWPAN convert output into the IEEE802.15.4 frames */ + if (pkttype == DEVIF_TCP) + { + FAR struct ipv6_hdr_s *ipv6 = (FAR struct ipv6_hdr_s *)dev->d_buf; + + /* This packet came from a response to TCP polling and is directed + * to an IEEE802.15.4 device using 6loWPAN. Verify that the outgoing + * packet is IPv6 with TCP protocol. + */ + + if (ipv6->vtc == IPv6_VERSION && ipv6->proto == IP_PROTO_TCP) + { + /* Let 6loWPAN convert IPv6 TCP output into IEEE802.15.4 frames. */ + + sixlowpan_tcp_send(dev); + } + else + { + nerr("ERROR: IPv6 version or protocol error. Packet dropped\n"); + nerr(" IP version: %02x proocol: %u\n", + ipv6->vtc, ipv6->proto); + } + } + else + { + nerr("ERROR: Non-TCP packet dropped. Packet type: %u\n", pkttype); + } - sixlowpan_tcp_send(dev); dev->d_len = 0; } } #else -# define devif_packet_conversion(dev) +# define devif_packet_conversion(dev,pkttype) #endif /* CONFIG_NET_6LOWPAN */ /**************************************************************************** @@ -143,7 +185,7 @@ static int devif_poll_pkt_connections(FAR struct net_driver_s *dev, /* Perform any necessary conversions on outgoing packets */ - devif_packet_conversion(dev); + devif_packet_conversion(dev, DEVIF_PKT); /* Call back into the driver */ @@ -172,7 +214,7 @@ static inline int devif_poll_icmp(FAR struct net_driver_s *dev, /* Perform any necessary conversions on outgoing packets */ - devif_packet_conversion(dev); + devif_packet_conversion(dev, DEVIF_ICMP); /* Call back into the driver */ @@ -198,7 +240,7 @@ static inline int devif_poll_icmpv6(FAR struct net_driver_s *dev, /* Perform any necessary conversions on outgoing packets */ - devif_packet_conversion(dev); + devif_packet_conversion(dev, DEVIF_ICMP6); /* Call back into the driver */ @@ -228,7 +270,7 @@ static inline int devif_poll_igmp(FAR struct net_driver_s *dev, /* Perform any necessary conversions on outgoing packets */ - devif_packet_conversion(dev); + devif_packet_conversion(dev, DEVIF_IGMP); /* Call back into the driver */ @@ -265,7 +307,7 @@ static int devif_poll_udp_connections(FAR struct net_driver_s *dev, /* Perform any necessary conversions on outgoing packets */ - devif_packet_conversion(dev); + devif_packet_conversion(dev, DEVIF_UDP); /* Call back into the driver */ @@ -305,7 +347,7 @@ static inline int devif_poll_tcp_connections(FAR struct net_driver_s *dev, /* Perform any necessary conversions on outgoing packets */ - devif_packet_conversion(dev); + devif_packet_conversion(dev, DEVIF_TCP); /* Call back into the driver */ @@ -349,7 +391,7 @@ static inline int devif_poll_tcp_timer(FAR struct net_driver_s *dev, /* Perform any necessary conversions on outgoing packets */ - devif_packet_conversion(dev); + devif_packet_conversion(dev, DEVIF_TCP); /* Call back into the driver */ diff --git a/net/procfs/netdev_statistics.c b/net/procfs/netdev_statistics.c index 80154c91fa..d7673507b7 100644 --- a/net/procfs/netdev_statistics.c +++ b/net/procfs/netdev_statistics.c @@ -1,7 +1,7 @@ /**************************************************************************** * net/procfs/netdev_statistics.c * - * Copyright (C) 2015 Gregory Nutt. All rights reserved. + * Copyright (C) 2015, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -47,6 +47,7 @@ #include #include +#include #include "netdev/netdev.h" #include "utils/utils.h" @@ -106,6 +107,9 @@ static const linegen_t g_linegen[] = static int netprocfs_linklayer(FAR struct netprocfs_file_s *netfile) { FAR struct net_driver_s *dev; +#ifdef CONFIG_NET_6LOWPAN + FAR struct ieee802154_driver_s *ieee; +#endif FAR const char *status; int len = 0; @@ -142,6 +146,30 @@ static int netprocfs_linklayer(FAR struct netprocfs_file_s *netfile) break; #endif +#ifdef CONFIG_NET_6LOWPAN + case NET_LL_IEEE802154: + { + ieee = (FAR struct ieee802154_driver_s *)dev; + +#if CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 2 + len += snprintf(&netfile->line[len], NET_LINELEN - len, + "%s\tLink encap:6loWPAN HWaddr %02x:%02x", + dev->d_ifname, + ieee->i_nodeaddr.u8[0], ieee->i_nodeaddr.u8[1]); +#else /* CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 8 */ + len += snprintf(&netfile->line[len], NET_LINELEN - len, + "%s\tLink encap:6loWPAN HWaddr " + "%02x:%02x:%02x:%02x:%02x:%02x:%02x:%02x", + dev->d_ifname, + ieee->i_nodeaddr.u8[0], ieee->i_nodeaddr.u8[1], + ieee->i_nodeaddr.u8[2], ieee->i_nodeaddr.u8[3], + ieee->i_nodeaddr.u8[4], ieee->i_nodeaddr.u8[5], + ieee->i_nodeaddr.u8[6], ieee->i_nodeaddr.u8[7]); +#endif + } + break; +#endif + #ifdef CONFIG_NET_LOOPBACK case NET_LL_LOOPBACK: len += snprintf(&netfile->line[len], NET_LINELEN - len, @@ -184,6 +212,26 @@ static int netprocfs_linklayer(FAR struct netprocfs_file_s *netfile) "%s\tLink encap:Ethernet HWaddr %s at %s\n", dev->d_ifname, ether_ntoa(&dev->d_mac), status); +#elif defined(CONFIG_NET_6LOWPAN) + ieee = (FAR struct ieee802154_driver_s *)dev; + +#if CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 2 + len += snprintf(&netfile->line[len], NET_LINELEN - len, + "%s\tLink encap:6loWPAN HWaddr %02x:%02x at %s", + dev->d_ifname, + ieee->i_nodeaddr.u8[0], ieee->i_nodeaddr.u8[1], + status); +#else /* CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 8 */ + len += snprintf(&netfile->line[len], NET_LINELEN - len, + "%s\tLink encap:6loWPAN HWaddr " + "%02x:%02x:%02x:%02x:%02x:%02x:%02x:%02x at %s", + dev->d_ifname, + ieee->i_nodeaddr.u8[0], ieee->i_nodeaddr.u8[1], + ieee->i_nodeaddr.u8[2], ieee->i_nodeaddr.u8[3], + ieee->i_nodeaddr.u8[4], ieee->i_nodeaddr.u8[5], + ieee->i_nodeaddr.u8[6], ieee->i_nodeaddr.u8[7], + status); +#endif #elif defined(CONFIG_NET_LOOPBACK) len += snprintf(&netfile->line[len], NET_LINELEN - len, "%s\tLink encap:Local Loopback at %s\n", diff --git a/net/sixlowpan/sixlowpan_hc06.c b/net/sixlowpan/sixlowpan_hc06.c index d23a392e05..5caee4b838 100644 --- a/net/sixlowpan/sixlowpan_hc06.c +++ b/net/sixlowpan/sixlowpan_hc06.c @@ -455,7 +455,8 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, uint8_t iphc1; uint8_t tmp; - ninfodumpbuffer("IPv6 before compression", ipv6, sizeof(struct ipv6_hdr_s)); + ninfodumpbuffer("IPv6 before compression", (FAR const uint8_t *)ipv6, + sizeof(struct ipv6_hdr_s)); g_hc06ptr = g_rimeptr + 2; diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index c6a83480d9..4e8fc75d77 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -243,7 +243,8 @@ */ #define SIXLOWPAN_IS_IID_16BIT_COMPRESSABLE(a) \ - ((((a)[4]) == 0x0000) && (((a)[5]) == 0x00ff) && (((a)[6]) == 0xfe00)) + ((((a)[4]) == 0x0000) && (((a)[5]) == HTONS(0x00ff)) && \ + (((a)[6]) == 0xfe00)) /* Check whether the 9-bit group-id of the compressed multicast address is * known. It is true if the 9-bit group is the all nodes or all routers @@ -265,27 +266,27 @@ #define SIXLOWPAN_IS_MCASTADDR_COMPRESSABLE(a) \ ((a)[1] == 0 && (a)[2] == 0 && (a)[3] == 0 && \ (a)[4] == 0 && (a)[5] == 0 && (a)[6] == 0 && \ - ((a)[7] == 0x0001 || (a)[7] == 0x0002)) + ((a)[7] == HTONS(0x0001) || (a)[7] == HTONS(0x0002))) /* FFXX:0000:0000:0000:0000:00XX:XXXX:XXXX */ #define SIXLOWPAN_IS_MCASTADDR_COMPRESSABLE48(a) \ ((a)[1] == 0 && (a)[2] == 0 && (a)[3] == 0 && \ - (a)[4] == 0 && (((a)[5] & 0xff00) == 0)) + (a)[4] == 0 && (((a)[5] & HTONS(0xff00)) == 0)) /* FFXX:0000:0000:0000:0000:0000:00XX:XXXX */ #define SIXLOWPAN_IS_MCASTADDR_COMPRESSABLE32(a) \ ((a)[1] == 0 && (a)[2] == 0 && (a)[3] == 0 && \ - (a)[4] == 0 && (a)[5] == 0 && ((a)[6] & 0xff00) == 0) + (a)[4] == 0 && (a)[5] == 0 && ((a)[6] & HTONS(0xff00)) == 0) /* FF02:0000:0000:0000:0000:0000:0000:00XX */ #define SIXLOWPAN_IS_MCASTADDR_COMPRESSABLE8(a) \ - ((((a)[0] & 0x00ff) == 0x0002) && \ + ((((a)[0] & HTONS(0x00ff)) == HTONS(0x0002)) && \ (a)[1] == 0 && (a)[2] == 0 && (a)[3] == 0 && \ (a)[4] == 0 && (a)[5] == 0 && (a)[6] == 0 && \ - (((a)[7] & 0xff00) == 0x0000)) + (((a)[7] & HTONS(0xff00)) == 0x0000)) /* General helper macros ****************************************************/ diff --git a/net/sixlowpan/sixlowpan_tcpsend.c b/net/sixlowpan/sixlowpan_tcpsend.c index 933a7f6361..7beceee5c5 100644 --- a/net/sixlowpan/sixlowpan_tcpsend.c +++ b/net/sixlowpan/sixlowpan_tcpsend.c @@ -393,10 +393,10 @@ void sixlowpan_tcp_send(FAR struct net_driver_s *dev) size_t hdrlen; hdrlen = IPv6_HDRLEN + TCP_HDRLEN; - if (hdrlen < dev->d_len) + if (hdrlen > dev->d_len) { nwarn("WARNING: Packet to small: Have %u need >%u\n", - dev->d_len, hdrlen); + dev->d_len, hdrlen); } else { diff --git a/net/sixlowpan/sixlowpan_utils.c b/net/sixlowpan/sixlowpan_utils.c index fae33fe207..7dd4e9e35c 100644 --- a/net/sixlowpan/sixlowpan_utils.c +++ b/net/sixlowpan/sixlowpan_utils.c @@ -116,7 +116,7 @@ void sixlowpan_ipfromrime(FAR const struct rimeaddr_s *rime, net_ipv6addr_t ipaddr) { memset(ipaddr, 0, sizeof(net_ipv6addr_t)); - ipaddr[0] = 0xfe80; + ipaddr[0] = HTONS(0xfe80); /* We consider only links with IEEE EUI-64 identifier or IEEE 48-bit MAC * addresses. NOTE: that CONFIG_NET_6LOWPAN_RIMEADDR_SIZE may be 2 or @@ -128,7 +128,7 @@ void sixlowpan_ipfromrime(FAR const struct rimeaddr_s *rime, */ memcpy(&ipaddr[4], rime, CONFIG_NET_6LOWPAN_RIMEADDR_SIZE); - ipaddr[4] ^= 0x0200; + ipaddr[4] ^= HTONS(0x0200); } /**************************************************************************** @@ -174,10 +174,10 @@ bool sixlowpan_ismacbased(const net_ipv6addr_t ipaddr, FAR const uint8_t *rimeptr = rime->u8; #if CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 2 - return ((ipaddr[4] == (GETINT16(rimeptr, 0) ^ 0x0200)) && + return ((ipaddr[4] == htons((GETINT16(rimeptr, 0) ^ 0x0200))) && ipaddr[5] == 0 && ipaddr[6] == 0 && ipaddr[7] == 0); #else /* CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 8 */ - return ((ipaddr[4] == (GETINT16(rimeptr, 0) ^ 0x0200)) && + return ((ipaddr[4] == htons((GETINT16(rimeptr, 0) ^ 0x0200))) && ipaddr[5] == GETINT16(rimeptr, 2) && ipaddr[6] == GETINT16(rimeptr, 4) && ipaddr[7] == GETINT16(rimeptr, 6)); diff --git a/net/tcp/tcp_finddev.c b/net/tcp/tcp_finddev.c index ef6ae8f0d2..e3cf0b3288 100644 --- a/net/tcp/tcp_finddev.c +++ b/net/tcp/tcp_finddev.c @@ -250,7 +250,6 @@ int tcp_local_ipv6_device(FAR struct tcp_conn_s *conn) #else return tcp_find_ipv6_device(conn, NULL); #endif - } #endif /* CONFIG_NET_IPv6 */ -- GitLab From cd643394131720b569a888921b02eb1cc10a0fb4 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 3 Apr 2017 15:31:18 -0600 Subject: [PATCH 326/990] Still try to recover from bad merge. --- wireless/ieee802154/Kconfig | 8 -------- 1 file changed, 8 deletions(-) diff --git a/wireless/ieee802154/Kconfig b/wireless/ieee802154/Kconfig index 90d20d07d6..b46aada66d 100644 --- a/wireless/ieee802154/Kconfig +++ b/wireless/ieee802154/Kconfig @@ -45,14 +45,6 @@ config IEEE802154_LOOPBACK ---help--- Add support for the IEEE802154 6loWPAN Loopback test device. -config IEEE802154_LOOPBACK - bool "IEEE802154 6loWPAN Loopback" - default n - depends on NET_6LOWPAN && NET_IPv6 - select ARCH_HAVE_NETDEV_STATISTICS - ---help--- - Add support for the IEEE802154 6loWPAN Loopback test device. - if IEEE802154_LOOPBACK choice -- GitLab From cc9445624fd8e8b262ba5a528bb8c6e461e2f803 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 3 Apr 2017 16:17:10 -0600 Subject: [PATCH 327/990] 6loWPAN: Correct a couple of tiny but fatal bugs. --- net/sixlowpan/sixlowpan_framer.c | 2 +- net/sixlowpan/sixlowpan_utils.c | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/net/sixlowpan/sixlowpan_framer.c b/net/sixlowpan/sixlowpan_framer.c index d0efa291d4..ad502ebbc9 100644 --- a/net/sixlowpan/sixlowpan_framer.c +++ b/net/sixlowpan/sixlowpan_framer.c @@ -294,7 +294,7 @@ static void sixlowpan_setup_params(FAR struct ieee802154_driver_s *ieee, /* Initialize all prameters to all zero */ - memset(¶ms, 0, sizeof(params)); + memset(params, 0, sizeof(params)); /* Reset to an empty frame */ diff --git a/net/sixlowpan/sixlowpan_utils.c b/net/sixlowpan/sixlowpan_utils.c index 7dd4e9e35c..1ec8eec2b6 100644 --- a/net/sixlowpan/sixlowpan_utils.c +++ b/net/sixlowpan/sixlowpan_utils.c @@ -149,7 +149,7 @@ void sixlowpan_rimefromip(const net_ipv6addr_t ipaddr, { /* REVISIT: See notes about 2 byte addresses in sixlowpan_ipfromrime() */ - DEBUGASSERT(ipaddr[0] == 0xfe80); + DEBUGASSERT(ipaddr[0] == HTONS(0xfe80)); memcpy(rime, &ipaddr[4], CONFIG_NET_6LOWPAN_RIMEADDR_SIZE); rime->u8[0] ^= 0x02; -- GitLab From db48f0319298f6dac57af26f7752b49793efb41a Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 3 Apr 2017 17:04:56 -0600 Subject: [PATCH 328/990] 6loWPAN: Fix some compilation problems with HC1 compression is enabled. --- net/sixlowpan/Kconfig | 11 ++++ net/sixlowpan/sixlowpan_hc1.c | 97 ++++++++++++++++-------------- net/sixlowpan/sixlowpan_internal.h | 6 +- 3 files changed, 65 insertions(+), 49 deletions(-) diff --git a/net/sixlowpan/Kconfig b/net/sixlowpan/Kconfig index 49f4756a02..09bb010c9f 100644 --- a/net/sixlowpan/Kconfig +++ b/net/sixlowpan/Kconfig @@ -51,6 +51,17 @@ config NET_6LOWPAN_COMPRESSION_THRESHOLD CONFIG_NET_6LOWPAN_COMPRESSION_THRESHOLD sets a lower threshold for when packets should not be compressed. +config NET_6LOWPAN_MINPORT + hex "Minimum port nubmer" + default 0x5471 + depends on NET_6LOWPAN_COMPRESSION_HC1 + ---help--- + HC1 compression of UDP headersis feasible only if both src and dest + ports are between CONFIG_NET_6LOWPAN_MINPORT and + CONFIG_NET_6LOWPAN_MINPORT + 15, inclusive. + + All nodes must agree on the value of CONFIG_NET_6LOWPAN_MINPORT + if NET_6LOWPAN_COMPRESSION_HC06 config NET_6LOWPAN_MAXADDRCONTEXT diff --git a/net/sixlowpan/sixlowpan_hc1.c b/net/sixlowpan/sixlowpan_hc1.c index fd45280ea0..ae65fd4bdc 100644 --- a/net/sixlowpan/sixlowpan_hc1.c +++ b/net/sixlowpan/sixlowpan_hc1.c @@ -48,6 +48,10 @@ #include +#include +#include +#include + #include #include "sixlowpan/sixlowpan_internal.h" @@ -59,10 +63,8 @@ /* Buffer access helpers */ -#define IPv6BUF(dev) \ - ((FAR struct ipv6_hdr_s *)((dev)->d_buf)) -#define UDPIPv6BUF(dev) \ - ((FAR struct udp_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev) + IPv6_HDRLEN]) +#define IPv6BUF(dev) ((FAR struct ipv6_hdr_s *)((dev)->d_buf)) +#define UDPIPv6BUF(dev) ((FAR struct udp_hdr_s *)&(dev)->d_buf[IPv6_HDRLEN]) /**************************************************************************** * Public Functions @@ -133,11 +135,11 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, /* Check if all the assumptions for full compression are valid */ - if (ipv6->vtc != 0x60 || ipv6->tcflow != 0 || ipv6->flow != 0 || - !sixlowpan_islinklocal(&ipv6->srcipaddr) || - !sixlowpan_ismacbased(&ipv6->srcipaddr, &ieee->i_rimeaddr) || - !sixlowpan_islinklocal(&ipv6->destipaddr) || - !sixlowpan_ismacbased(&ipv6->destipaddr, destmac) || + if (ipv6->vtc != 0x60 || ipv6->tcf != 0 || ipv6->flow != 0 || + !sixlowpan_islinklocal(ipv6->srcipaddr) || + !sixlowpan_ismacbased(ipv6->srcipaddr, &ieee->i_nodeaddr) || + !sixlowpan_islinklocal(ipv6->destipaddr) || + !sixlowpan_ismacbased(ipv6->destipaddr, destmac) || (ipv6->proto != IP_PROTO_ICMP6 && ipv6->proto != IP_PROTO_UDP && ipv6->proto != IP_PROTO_TCP)) { @@ -183,47 +185,50 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, #if CONFIG_NET_UDP case IP_PROTO_UDP: - FAR struct udp_hdr_s *udp = UDPIPv6BUF(dev); + { + FAR struct udp_hdr_s *udp = UDPIPv6BUF(&ieee->i_dev); - /* Try to compress UDP header (we do only full compression). This - * is feasible if both src and dest ports are between - * SIXLOWPAN_UDP_PORT_MIN and SIXLOWPAN_UDP_PORT_MIN + 15 - */ + /* Try to compress UDP header (we do only full compression). + * This is feasible if both src and dest ports are between + * CONFIG_NET_6LOWPAN_MINPORT and CONFIG_NET_6LOWPAN_MINPORT + + * 15 + */ - ninfo("local/remote port %u/%u\n", udp->srcport, udp->destport); + ninfo("local/remote port %u/%u\n", udp->srcport, udp->destport); - if (htons(udp->srcport) >= SIXLOWPAN_UDP_PORT_MIN && - htons(udp->srcport) < SIXLOWPAN_UDP_PORT_MAX && - htons(udp->destport) >= SIXLOWPAN_UDP_PORT_MIN && - htons(udp->destport) < SIXLOWPAN_UDP_PORT_MAX) - { - FAR uint8_t *hcudp = RIME_HC1_HC_UDP_PTR; + if (htons(udp->srcport) >= CONFIG_NET_6LOWPAN_MINPORT && + htons(udp->srcport) < (CONFIG_NET_6LOWPAN_MINPORT + 16) && + htons(udp->destport) >= CONFIG_NET_6LOWPAN_MINPORT && + htons(udp->destport) < (CONFIG_NET_6LOWPAN_MINPORT + 16)) + { + FAR uint8_t *hcudp = RIME_HC1_HC_UDP_PTR; - /* HC1 encoding */ + /* HC1 encoding */ - hcudp[RIME_HC1_HC_UDP_HC1_ENCODING] = 0xfb; + hcudp[RIME_HC1_HC_UDP_HC1_ENCODING] = 0xfb; - /* HC_UDP encoding, ttl, src and dest ports, checksum */ + /* HC_UDP encoding, ttl, src and dest ports, checksum */ - hcudp[RIME_HC1_HC_UDP_UDP_ENCODING] = 0xe0; - hcudp[RIME_HC1_HC_UDP_TTL] = ipv6->ttl; - hcudp[RIME_HC1_HC_UDP_PORTS] = - (uint8_t)((htons(udp->srcport) - SIXLOWPAN_UDP_PORT_MIN) << 4) + - (uint8_t)((htons(udp->destport) - SIXLOWPAN_UDP_PORT_MIN)); + hcudp[RIME_HC1_HC_UDP_UDP_ENCODING] = 0xe0; + hcudp[RIME_HC1_HC_UDP_TTL] = ipv6->ttl; + hcudp[RIME_HC1_HC_UDP_PORTS] = + (uint8_t)((htons(udp->srcport) - CONFIG_NET_6LOWPAN_MINPORT) << 4) + + (uint8_t)((htons(udp->destport) - CONFIG_NET_6LOWPAN_MINPORT)); - memcpy(&hcudp[RIME_HC1_HC_UDP_CHKSUM], &udp->udpchksum, 2); + memcpy(&hcudp[RIME_HC1_HC_UDP_CHKSUM], &udp->udpchksum, 2); - g_rime_hdrlen += SIXLOWPAN_HC1_HC_UDP_HDR_LEN; - g_uncomp_hdrlen += UIP_UDPH_LEN; - } - else - { - /* HC1 encoding and ttl */ + g_rime_hdrlen += SIXLOWPAN_HC1_HC_UDP_HDR_LEN; + g_uncomp_hdrlen += UDP_HDRLEN; + } + else + { + /* HC1 encoding and ttl */ - hc1[RIME_HC1_ENCODING] = 0xfa; - hc1[RIME_HC1_TTL] = ipv6->ttl; - g_rime_hdrlen += SIXLOWPAN_HC1_HDR_LEN; - } + hc1[RIME_HC1_ENCODING] = 0xfa; + hc1[RIME_HC1_TTL] = ipv6->ttl; + g_rime_hdrlen += SIXLOWPAN_HC1_HDR_LEN; + } + } break; #endif /* CONFIG_NET_UDP */ } @@ -272,9 +277,9 @@ int sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, */ sixlowpan_ipfromrime(&g_pktaddrs[PACKETBUF_ADDR_SENDER], - &ipv6->srcipaddr); + ipv6->srcipaddr); sixlowpan_ipfromrime(&g_pktaddrs[PACKETBUF_ADDR_RECEIVER], - &ipv6->destipaddr); + ipv6->destipaddr); g_uncomp_hdrlen += IPv6_HDRLEN; /* len[], proto, and ttl depend on the encoding */ @@ -320,13 +325,13 @@ int sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, /* UDP ports, len, checksum */ udp->srcport = - htons(SIXLOWPAN_UDP_PORT_MIN + (hcudp[RIME_HC1_HC_UDP_PORTS] >> 4)); + htons(CONFIG_NET_6LOWPAN_MINPORT + (hcudp[RIME_HC1_HC_UDP_PORTS] >> 4)); udp->destport = - htons(SIXLOWPAN_UDP_PORT_MIN + (hcudp[RIME_HC1_HC_UDP_PORTS] & 0x0F)); + htons(CONFIG_NET_6LOWPAN_MINPORT + (hcudp[RIME_HC1_HC_UDP_PORTS] & 0x0F)); memcpy(&udp->udpchksum, &hcudp[RIME_HC1_HC_UDP_CHKSUM], 2); - g_uncomp_hdrlen += UIP_UDPH_LEN; + g_uncomp_hdrlen += UDP_HDRLEN; g_rime_hdrlen += SIXLOWPAN_HC1_HC_UDP_HDR_LEN; } else @@ -369,7 +374,7 @@ int sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, } #endif - return; + return OK; } #endif /* CONFIG_NET_6LOWPAN_COMPRESSION_HC1 */ diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index 4e8fc75d77..5bb88f63c6 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -717,8 +717,8 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, ****************************************************************************/ #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC1 -void sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, - uint16_t ip_len); +int sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, + uint16_t ip_len); #endif /**************************************************************************** @@ -752,7 +752,7 @@ int sixlowpan_frame_hdralloc(FAR struct iob_s *iob, int size); * ****************************************************************************/ -#define sixlowpan_islinklocal(ipaddr) ((ipaddr)[0] = NTOHS(0xfe80)) +#define sixlowpan_islinklocal(ipaddr) ((ipaddr)[0] == NTOHS(0xfe80)) void sixlowpan_ipfromrime(FAR const struct rimeaddr_s *rime, net_ipv6addr_t ipaddr); -- GitLab From 730b674b0139b07099e815c0a6047150cd66dd01 Mon Sep 17 00:00:00 2001 From: no1wudi <757509347@qq.com> Date: Tue, 4 Apr 2017 11:50:58 +0800 Subject: [PATCH 329/990] STM32:add I2C3 SDA pin mapping for STM32F411 --- arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h b/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h index 82fb74a448..0bd2e39549 100644 --- a/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h +++ b/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h @@ -424,6 +424,9 @@ #define GPIO_I2C3_SCL_2 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTH|GPIO_PIN7) #define GPIO_I2C3_SDA_1 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTC|GPIO_PIN9) #define GPIO_I2C3_SDA_2 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTH|GPIO_PIN8) +#if defined(CONFIG_STM32_STM32F411) +# define GPIO_I2C3_SDA_3 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTB|GPIO_PIN4) +#endif #define GPIO_I2C3_SMBA_1 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN9) #define GPIO_I2C3_SMBA_2 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN9) #if defined(CONFIG_STM32_STM32F446) -- GitLab From 8fbd8b9e6fd8bdfa449e9386a767d4f245da8109 Mon Sep 17 00:00:00 2001 From: no1wudi <757509347@qq.com> Date: Tue, 4 Apr 2017 11:57:45 +0800 Subject: [PATCH 330/990] STM32:add I2C3 SDA pin mapping for STM32F411 --- arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h | 1 + 1 file changed, 1 insertion(+) diff --git a/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h b/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h index 0bd2e39549..d44c664edb 100644 --- a/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h +++ b/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h @@ -426,6 +426,7 @@ #define GPIO_I2C3_SDA_2 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTH|GPIO_PIN8) #if defined(CONFIG_STM32_STM32F411) # define GPIO_I2C3_SDA_3 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTB|GPIO_PIN4) +# define GPIO_I2C3_SDA_4 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_OPENDRAIN|GPIO_PORTB|GPIO_PIN8) #endif #define GPIO_I2C3_SMBA_1 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN9) #define GPIO_I2C3_SMBA_2 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN9) -- GitLab From 88fd66760367578510f11d5fb7a37dfb36a2133d Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 4 Apr 2017 07:22:59 -0600 Subject: [PATCH 331/990] 6loWPAN: Fix a pointer initialization problem. --- net/sixlowpan/sixlowpan_framelist.c | 63 ++++++++++++++------------- net/sixlowpan/sixlowpan_globals.c | 12 +----- net/sixlowpan/sixlowpan_hc06.c | 36 +++++++++------- net/sixlowpan/sixlowpan_hc1.c | 67 +++++++++++++++-------------- net/sixlowpan/sixlowpan_input.c | 51 +++++++++++----------- net/sixlowpan/sixlowpan_internal.h | 40 ++++++++--------- 6 files changed, 137 insertions(+), 132 deletions(-) diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c index f206a3fe9f..ee5a8a2cf7 100644 --- a/net/sixlowpan/sixlowpan_framelist.c +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -102,6 +102,7 @@ * Input Parameters: * ieee - Pointer to IEEE802.15.4 MAC driver structure. * destip - Pointer to the IPv6 header to "compress" + * fptr - Pointer to the beginning of the frame under construction * * Returned Value: * None @@ -109,17 +110,18 @@ ****************************************************************************/ static void sixlowpan_compress_ipv6hdr(FAR struct ieee802154_driver_s *ieee, - FAR const struct ipv6_hdr_s *destip) + FAR const struct ipv6_hdr_s *destip, + FAR uint8_t *fptr) { /* Indicate the IPv6 dispatch and length */ - *g_rimeptr = SIXLOWPAN_DISPATCH_IPV6; - g_rime_hdrlen += SIXLOWPAN_IPV6_HDR_LEN; + *fptr = SIXLOWPAN_DISPATCH_IPV6; + g_frame_hdrlen += SIXLOWPAN_IPV6_HDR_LEN; /* Copy the IPv6 header and adjust pointers */ - memcpy(g_rimeptr + g_rime_hdrlen, destip, IPv6_HDRLEN); - g_rime_hdrlen += IPv6_HDRLEN; + memcpy(fptr + g_frame_hdrlen, destip, IPv6_HDRLEN); + g_frame_hdrlen += IPv6_HDRLEN; g_uncomp_hdrlen += IPv6_HDRLEN; } @@ -165,6 +167,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, FAR const struct rimeaddr_s *destmac) { FAR struct iob_s *iob; + FAR uint8_t *fptr; int framer_hdrlen; struct rimeaddr_s bcastmac; uint16_t outlen = 0; @@ -175,9 +178,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, FRAME_RESET(); g_uncomp_hdrlen = 0; - g_rime_hdrlen = 0; - /* REVISIT: Do I need this rimeptr? */ - g_rimeptr = &ieee->i_dev.d_buf[PACKETBUF_HDR_SIZE]; + g_frame_hdrlen = 0; /* Reset rime buffer, packet buffer metatadata */ @@ -228,6 +229,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, iob->io_len = 0; iob->io_offset = 0; iob->io_pktlen = 0; + fptr = iob->io_data; ninfo("Sending packet len %d\n", len); @@ -237,9 +239,9 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, /* Try to compress the headers */ #if defined(CONFIG_NET_6LOWPAN_COMPRESSION_HC1) - sixlowpan_compresshdr_hc1(ieee, destip, destmac, iob); + sixlowpan_compresshdr_hc1(ieee, destip, destmac, fptr); #elif defined(CONFIG_NET_6LOWPAN_COMPRESSION_HC06) - sixlowpan_compresshdr_hc06(ieee, destip, destmac, iob); + sixlowpan_compresshdr_hc06(ieee, destip, destmac, fptr); #else # error No compression specified #endif @@ -249,10 +251,10 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, { /* Small.. use IPv6 dispatch (no compression) */ - sixlowpan_compress_ipv6hdr(ieee, destip); + sixlowpan_compress_ipv6hdr(ieee, destip, fptr); } - ninfo("Header of len %d\n", g_rime_hdrlen); + ninfo("Header of len %d\n", g_frame_hdrlen); rimeaddr_copy(&g_pktaddrs[PACKETBUF_ADDR_RECEIVER], destmac); @@ -271,7 +273,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, if ((int)len - (int)g_uncomp_hdrlen > (int)CONFIG_NET_6LOWPAN_MAXPAYLOAD - framer_hdrlen - - (int)g_rime_hdrlen) + (int)g_frame_hdrlen) { #if CONFIG_NET_6LOWPAN_FRAG /* ieee->i_framelist will hold the generated frames; frames will be @@ -299,7 +301,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, /* Move HC1/HC06/IPv6 header */ - memmove(g_rimeptr + SIXLOWPAN_FRAG1_HDR_LEN, g_rimeptr, g_rime_hdrlen); + memmove(fptr + SIXLOWPAN_FRAG1_HDR_LEN, fptr, g_frame_hdrlen); /* Setup up the fragment header. * @@ -316,20 +318,20 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, * bytes for all subsequent headers. */ - PUTINT16(RIME_FRAG_PTR, RIME_FRAG_DISPATCH_SIZE, + PUTINT16(fptr, RIME_FRAG_DISPATCH_SIZE, ((SIXLOWPAN_DISPATCH_FRAG1 << 8) | len)); - PUTINT16(RIME_FRAG_PTR, RIME_FRAG_TAG, ieee->i_dgramtag); + PUTINT16(fptr, RIME_FRAG_TAG, ieee->i_dgramtag); ieee->i_dgramtag++; /* Copy payload and enqueue */ - g_rime_hdrlen += SIXLOWPAN_FRAG1_HDR_LEN; + g_frame_hdrlen += SIXLOWPAN_FRAG1_HDR_LEN; g_rime_payloadlen = - (CONFIG_NET_6LOWPAN_MAXPAYLOAD - framer_hdrlen - g_rime_hdrlen) & 0xf8; + (CONFIG_NET_6LOWPAN_MAXPAYLOAD - framer_hdrlen - g_frame_hdrlen) & 0xf8; - memcpy(g_rimeptr + g_rime_hdrlen, + memcpy(fptr + g_frame_hdrlen, (FAR uint8_t *)destip + g_uncomp_hdrlen, g_rime_payloadlen); - iob->io_len += g_rime_payloadlen + g_rime_hdrlen; + iob->io_len += g_rime_payloadlen + g_frame_hdrlen; /* Set outlen to what we already sent from the IP payload */ @@ -349,7 +351,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, /* Create following fragments */ - g_rime_hdrlen = SIXLOWPAN_FRAGN_HDR_LEN; + g_frame_hdrlen = SIXLOWPAN_FRAGN_HDR_LEN; while (outlen < len) { @@ -366,6 +368,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, iob->io_len = 0; iob->io_offset = 0; iob->io_pktlen = 0; + fptr = iob->io_data; /* Add the frame header */ @@ -375,14 +378,14 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, /* Move HC1/HC06/IPv6 header */ - memmove(g_rimeptr + SIXLOWPAN_FRAGN_HDR_LEN, g_rimeptr, g_rime_hdrlen); + memmove(fptr + SIXLOWPAN_FRAGN_HDR_LEN, fptr, g_frame_hdrlen); /* Setup up the fragment header */ - PUTINT16(RIME_FRAG_PTR, RIME_FRAG_DISPATCH_SIZE, + PUTINT16(fptr, RIME_FRAG_DISPATCH_SIZE, ((SIXLOWPAN_DISPATCH_FRAGN << 8) | len)); - PUTINT16(RIME_FRAG_PTR, RIME_FRAG_TAG, ieee->i_dgramtag); - RIME_FRAG_PTR[RIME_FRAG_OFFSET] = outlen >> 3; + PUTINT16(fptr, RIME_FRAG_TAG, ieee->i_dgramtag); + fptr[RIME_FRAG_OFFSET] = outlen >> 3; /* Copy payload and enqueue */ @@ -395,12 +398,12 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, else { g_rime_payloadlen = - (CONFIG_NET_6LOWPAN_MAXPAYLOAD - framer_hdrlen - g_rime_hdrlen) & 0xf8; + (CONFIG_NET_6LOWPAN_MAXPAYLOAD - framer_hdrlen - g_frame_hdrlen) & 0xf8; } - memcpy(g_rimeptr + g_rime_hdrlen, (FAR uint8_t *)destip + outlen, + memcpy(fptr + g_frame_hdrlen, (FAR uint8_t *)destip + outlen, g_rime_payloadlen); - iob->io_len = g_rime_payloadlen + g_rime_hdrlen; + iob->io_len = g_rime_payloadlen + g_frame_hdrlen; /* Set outlen to what we already sent from the IP payload */ @@ -441,9 +444,9 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, /* Copy the payload and queue */ - memcpy(g_rimeptr + g_rime_hdrlen, (FAR uint8_t *)destip + g_uncomp_hdrlen, + memcpy(fptr + g_frame_hdrlen, (FAR uint8_t *)destip + g_uncomp_hdrlen, len - g_uncomp_hdrlen); - iob->io_len = len - g_uncomp_hdrlen + g_rime_hdrlen; + iob->io_len = len - g_uncomp_hdrlen + g_frame_hdrlen; /* Add the first frame to the IOB queue */ diff --git a/net/sixlowpan/sixlowpan_globals.c b/net/sixlowpan/sixlowpan_globals.c index 2f9843022f..274ef47fa7 100644 --- a/net/sixlowpan/sixlowpan_globals.c +++ b/net/sixlowpan/sixlowpan_globals.c @@ -54,14 +54,6 @@ * during that processing */ -/* A pointer to the rime buffer. - * - * We initialize it to the beginning of the rime buffer, then access - * different fields by updating the offset ieee->g_rime_hdrlen. - */ - -FAR uint8_t *g_rimeptr; - /* The length of the payload in the Rime buffer. * * The payload is what comes after the compressed or uncompressed headers @@ -77,12 +69,12 @@ uint8_t g_rime_payloadlen; uint8_t g_uncomp_hdrlen; -/* g_rime_hdrlen is the total length of (the processed) 6lowpan headers +/* g_frame_hdrlen is the total length of (the processed) 6lowpan headers * (fragment headers, IPV6 or HC1, HC2, and HC1 and HC2 non compressed * fields). */ -uint8_t g_rime_hdrlen; +uint8_t g_frame_hdrlen; /* Offset first available byte for the payload after header region. */ diff --git a/net/sixlowpan/sixlowpan_hc06.c b/net/sixlowpan/sixlowpan_hc06.c index 5caee4b838..a713e32807 100644 --- a/net/sixlowpan/sixlowpan_hc06.c +++ b/net/sixlowpan/sixlowpan_hc06.c @@ -437,7 +437,7 @@ void sixlowpan_hc06_initialize(void) * ipv6 - The IPv6 header to be compressed * destmac - L2 destination address, needed to compress the IP * destination field - * iob - The IOB into which the compressed header should be saved. + * fptr - Pointer to frame data payload. * * Returned Value: * None @@ -447,9 +447,9 @@ void sixlowpan_hc06_initialize(void) void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, FAR const struct ipv6_hdr_s *ipv6, FAR const struct rimeaddr_s *destmac, - FAR struct iob_s *iob) + FAR uint8_t *fptr) { - FAR uint8_t *iphc = RIME_IPHC_BUF; + FAR uint8_t *iphc = fptr + g_frame_hdrlen; FAR struct sixlowpan_addrcontext_s *addrcontext; uint8_t iphc0; uint8_t iphc1; @@ -458,7 +458,7 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, ninfodumpbuffer("IPv6 before compression", (FAR const uint8_t *)ipv6, sizeof(struct ipv6_hdr_s)); - g_hc06ptr = g_rimeptr + 2; + g_hc06ptr = fptr + 2; /* As we copy some bit-length fields, in the IPHC encoding bytes, * we sometimes use |= @@ -803,12 +803,12 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, } #endif /* CONFIG_NET_UDP */ - /* Before the g_rime_hdrlen operation */ + /* Before the g_frame_hdrlen operation */ iphc[0] = iphc0; iphc[1] = iphc1; - g_rime_hdrlen = g_hc06ptr - g_rimeptr; + g_frame_hdrlen = g_hc06ptr - fptr; return; } @@ -822,14 +822,16 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, * This function is called by the input function when the dispatch is HC06. * We process the packet in the rime buffer, uncompress the header fields, * and copy the result in the sixlowpan buffer. At the end of the - * decompression, g_rime_hdrlen and g_uncompressed_hdrlen are set to the + * decompression, g_frame_hdrlen and g_uncompressed_hdrlen are set to the * appropriate values * * Input Parmeters: - * ieee - A reference to the IEE802.15.4 network device state - * iplen - Equal to 0 if the packet is not a fragment (IP length is then - * inferred from the L2 length), non 0 if the packet is a first - * fragment. + * ieee - A reference to the IEE802.15.4 network device state + * iplen - Equal to 0 if the packet is not a fragment (IP length is then + * inferred from the L2 length), non 0 if the packet is a first + * fragment. + * iob - Pointer to the IOB containing the received frame. + * payptr - Pointer to the frame data payload. * * Returned Value: * None @@ -837,17 +839,18 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, ****************************************************************************/ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, - uint16_t iplen) + uint16_t iplen, FAR struct iob_s *iob, + FAR char *payptr) { FAR struct ipv6_hdr_s *ipv6 = IPv6BUF(ieee); - FAR uint8_t *iphc = RIME_IPHC_BUF; + FAR uint8_t *iphc = payptr + g_frame_hdrlen; uint8_t iphc0; uint8_t iphc1; uint8_t tmp; /* At least two byte will be used for the encoding */ - g_hc06ptr = g_rimeptr + g_rime_hdrlen + 2; + g_hc06ptr = payptr + g_frame_hdrlen + 2; iphc0 = iphc[0]; iphc1 = iphc[1]; @@ -1153,7 +1156,7 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, } } - g_rime_hdrlen = g_hc06ptr - g_rimeptr; + g_frame_hdrlen = g_hc06ptr - payptr; /* IP length field. */ @@ -1162,7 +1165,8 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, /* This is not a fragmented packet */ ipv6->len[0] = 0; - ipv6->len[1] = ieee->i_dev.d_len - g_rime_hdrlen + g_uncomp_hdrlen - IPv6_HDRLEN; + ipv6->len[1] = iob->io_len - g_frame_hdrlen + g_uncomp_hdrlen - + IPv6_HDRLEN; } else { diff --git a/net/sixlowpan/sixlowpan_hc1.c b/net/sixlowpan/sixlowpan_hc1.c index ae65fd4bdc..67fa142cf7 100644 --- a/net/sixlowpan/sixlowpan_hc1.c +++ b/net/sixlowpan/sixlowpan_hc1.c @@ -119,7 +119,7 @@ * ipv6 - The IPv6 header to be compressed * destmac - L2 destination address, needed to compress the IP * destination field - * iob - The IOB into which the compressed header should be saved. + * fptr - Pointer to frame data payload. * * Returned Value: * None @@ -129,9 +129,9 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, FAR const struct ipv6_hdr_s *ipv6, FAR const struct rimeaddr_s *destmac, - FAR struct iob_s *iob) + FAR uint8_t *fptr) { - FAR uint8_t *hc1 = RIME_HC1_PTR; + FAR uint8_t *hc1 = fptr + g_frame_hdrlen; /* Check if all the assumptions for full compression are valid */ @@ -148,10 +148,10 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, * compress nothing, copy IPv6 header in rime buffer */ - *g_rimeptr = SIXLOWPAN_DISPATCH_IPV6; - g_rime_hdrlen += SIXLOWPAN_IPV6_HDR_LEN; - memcpy(g_rimeptr + g_rime_hdrlen, ipv6, IPv6_HDRLEN); - g_rime_hdrlen += IPv6_HDRLEN; + *fptr = SIXLOWPAN_DISPATCH_IPV6; + g_frame_hdrlen += SIXLOWPAN_IPV6_HDR_LEN; + memcpy(fptr + g_frame_hdrlen, ipv6, IPv6_HDRLEN); + g_frame_hdrlen += IPv6_HDRLEN; g_uncomp_hdrlen += IPv6_HDRLEN; } else @@ -170,7 +170,7 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, hc1[RIME_HC1_ENCODING] = 0xfc; hc1[RIME_HC1_TTL] = ipv6->ttl; - g_rime_hdrlen += SIXLOWPAN_HC1_HDR_LEN; + g_frame_hdrlen += SIXLOWPAN_HC1_HDR_LEN; break; #if CONFIG_NET_TCP @@ -179,7 +179,7 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, hc1[RIME_HC1_ENCODING] = 0xfe; hc1[RIME_HC1_TTL] = ipv6->ttl; - g_rime_hdrlen += SIXLOWPAN_HC1_HDR_LEN; + g_frame_hdrlen += SIXLOWPAN_HC1_HDR_LEN; break; #endif /* CONFIG_NET_TCP */ @@ -201,7 +201,7 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, htons(udp->destport) >= CONFIG_NET_6LOWPAN_MINPORT && htons(udp->destport) < (CONFIG_NET_6LOWPAN_MINPORT + 16)) { - FAR uint8_t *hcudp = RIME_HC1_HC_UDP_PTR; + FAR uint8_t *hcudp = fptr + g_frame_hdrlen; /* HC1 encoding */ @@ -217,7 +217,7 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, memcpy(&hcudp[RIME_HC1_HC_UDP_CHKSUM], &udp->udpchksum, 2); - g_rime_hdrlen += SIXLOWPAN_HC1_HC_UDP_HDR_LEN; + g_frame_hdrlen += SIXLOWPAN_HC1_HC_UDP_HDR_LEN; g_uncomp_hdrlen += UDP_HDRLEN; } else @@ -226,7 +226,7 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, hc1[RIME_HC1_ENCODING] = 0xfa; hc1[RIME_HC1_TTL] = ipv6->ttl; - g_rime_hdrlen += SIXLOWPAN_HC1_HDR_LEN; + g_frame_hdrlen += SIXLOWPAN_HC1_HDR_LEN; } } break; @@ -244,14 +244,16 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, * This function is called by the input function when the dispatch is * HC1. It processes the packet in the rime buffer, uncompresses the * header fields, and copies the result in the sixlowpan buffer. At the - * end of the decompression, g_rime_hdrlen and uncompressed_hdr_len + * end of the decompression, g_frame_hdrlen and uncompressed_hdr_len * are set to the appropriate values * * Input Parameters: - * ieee - A reference to the IEE802.15.4 network device state - * iplen - Equal to 0 if the packet is not a fragment (IP length is then - * inferred from the L2 length), non 0 if the packet is a 1st - * fragment. + * ieee - A reference to the IEE802.15.4 network device state + * iplen - Equal to 0 if the packet is not a fragment (IP length is then + * inferred from the L2 length), non 0 if the packet is a 1st + * fragment. + * iob - Pointer to the IOB containing the received frame. + * payptr - Pointer to the frame data payload. * * Returned Value: * Zero (OK) is returned on success, on failure a negater errno value is @@ -260,10 +262,11 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, ****************************************************************************/ int sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, - uint16_t iplen) + uint16_t iplen, FAR struct iob_s *iob, + FAR uint8_t *payptr) { FAR struct ipv6_hdr_s *ipv6 = IPv6BUF(&ieee->i_dev); - FAR uint8_t *hc1 = RIME_HC1_PTR; + FAR uint8_t *hc1 = payptr + g_frame_hdrlen; /* Format the IPv6 header in the device d_buf */ /* Set version, traffic clase, and flow label */ @@ -287,16 +290,16 @@ int sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, switch (hc1[RIME_HC1_ENCODING] & 0x06) { case SIXLOWPAN_HC1_NH_ICMP6: - ipv6->proto = IP_PROTO_ICMP6; - ipv6->ttl = hc1[RIME_HC1_TTL]; - g_rime_hdrlen += SIXLOWPAN_HC1_HDR_LEN; + ipv6->proto = IP_PROTO_ICMP6; + ipv6->ttl = hc1[RIME_HC1_TTL]; + g_frame_hdrlen += SIXLOWPAN_HC1_HDR_LEN; break; #if CONFIG_NET_TCP case SIXLOWPAN_HC1_NH_TCP: - ipv6->proto = IP_PROTO_TCP; - ipv6->ttl = hc1[RIME_HC1_TTL]; - g_rime_hdrlen += SIXLOWPAN_HC1_HDR_LEN; + ipv6->proto = IP_PROTO_TCP; + ipv6->ttl = hc1[RIME_HC1_TTL]; + g_frame_hdrlen += SIXLOWPAN_HC1_HDR_LEN; break; #endif /* CONFIG_NET_TCP */ @@ -304,7 +307,7 @@ int sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, case SIXLOWPAN_HC1_NH_UDP: { FAR struct udp_hdr_s *udp = UDPIPv6BUF(&ieee->i_dev); - FAR uint8_t *hcudp = RIME_HC1_HC_UDP_PTR; + FAR uint8_t *hcudp = payptr + g_frame_hdrlen; ipv6->proto = IP_PROTO_UDP; if ((hcudp[RIME_HC1_HC_UDP_HC1_ENCODING] & 0x01) != 0) @@ -332,11 +335,11 @@ int sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, memcpy(&udp->udpchksum, &hcudp[RIME_HC1_HC_UDP_CHKSUM], 2); g_uncomp_hdrlen += UDP_HDRLEN; - g_rime_hdrlen += SIXLOWPAN_HC1_HC_UDP_HDR_LEN; + g_frame_hdrlen += SIXLOWPAN_HC1_HC_UDP_HDR_LEN; } else { - g_rime_hdrlen += SIXLOWPAN_HC1_HDR_LEN; + g_frame_hdrlen += SIXLOWPAN_HC1_HDR_LEN; } } break; @@ -353,8 +356,8 @@ int sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, /* This is not a fragmented packet */ ipv6->len[0] = 0; - ipv6->len[1] = ieee->i_dev.d_len - g_rime_hdrlen + /* REVISIT */ - g_uncomp_hdrlen - IPv6_HDRLEN; + ipv6->len[1] = iob->io_len - g_frame_hdrlen + g_uncomp_hdrlen - + IPv6_HDRLEN; } else { @@ -364,9 +367,9 @@ int sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, ipv6->len[1] = (iplen - IPv6_HDRLEN) & 0x00FF; } - /* length field in UDP header */ - #if CONFIG_NET_UDP + /* Length field in UDP header */ + if (ipv6->proto == IP_PROTO_UDP) { FAR struct udp_hdr_s *udp = UDPIPv6BUF(&ieee->i_dev); diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index 5ee8b49017..093da4bf30 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -121,7 +121,8 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, FAR struct iob_s *iob) { - FAR uint8_t *hc1 = RIME_HC1_PTR; + FAR uint8_t *payptr; /* Pointer to the frame payload */ + FAR uint8_t *hc1; /* Convenience pointer to HC1 data */ uint16_t fragsize = 0; /* Size of the IP packet (read from fragment) */ uint8_t fragoffset = 0; /* Offset of the fragment in the IP packet */ @@ -140,11 +141,11 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, */ g_uncomp_hdrlen = 0; - g_rime_hdrlen = 0; + g_frame_hdrlen = 0; /* The MAC puts the 15.4 payload inside the RIME data buffer */ - g_rimeptr = &iob->io_data[PACKETBUF_HDR_SIZE]; + payptr = &iob->io_data[PACKETBUF_HDR_SIZE]; #if CONFIG_NET_6LOWPAN_FRAG /* If reassembly timed out, cancel it */ @@ -161,7 +162,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, * we look for is the fragmentation header */ - switch ((GETINT16(RIME_FRAG_PTR, RIME_FRAG_DISPATCH_SIZE) & 0xf800) >> 8) + switch ((GETINT16(payptr, RIME_FRAG_DISPATCH_SIZE) & 0xf800) >> 8) { /* First fragment of new reassembly */ @@ -170,13 +171,13 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, /* Set up for the reassembly */ fragoffset = 0; - fragsize = GETINT16(RIME_FRAG_PTR, RIME_FRAG_DISPATCH_SIZE) & 0x07ff; - fragtag = GETINT16(RIME_FRAG_PTR, RIME_FRAG_TAG); + fragsize = GETINT16(payptr, RIME_FRAG_DISPATCH_SIZE) & 0x07ff; + fragtag = GETINT16(payptr, RIME_FRAG_TAG); ninfo("FRAG1: size %d, tag %d, offset %d\n", fragsize, fragtag, fragoffset); - g_rime_hdrlen += SIXLOWPAN_FRAG1_HDR_LEN; + g_frame_hdrlen += SIXLOWPAN_FRAG1_HDR_LEN; /* Indicate the first fragment of the reassembly */ @@ -189,17 +190,17 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, { /* Set offset, tag, size. Offset is in units of 8 bytes. */ - fragoffset = RIME_FRAG_PTR[RIME_FRAG_OFFSET]; - fragtag = GETINT16(RIME_FRAG_PTR, RIME_FRAG_TAG); - fragsize = GETINT16(RIME_FRAG_PTR, RIME_FRAG_DISPATCH_SIZE) & 0x07ff; + fragoffset = payptr[RIME_FRAG_OFFSET]; + fragtag = GETINT16(payptr, RIME_FRAG_TAG); + fragsize = GETINT16(payptr, RIME_FRAG_DISPATCH_SIZE) & 0x07ff; ninfo("FRAGN: size %d, tag %d, offset %d\n", fragsize, fragtag, fragoffset); - g_rime_hdrlen += SIXLOWPAN_FRAGN_HDR_LEN; + g_frame_hdrlen += SIXLOWPAN_FRAGN_HDR_LEN; ninfo("islastfrag?: i_accumlen %d g_rime_payloadlen %d fragsize %d\n", - ieee->i_accumlen, iob->io_len - g_rime_hdrlen, fragsize); + ieee->i_accumlen, iob->io_len - g_frame_hdrlen, fragsize); /* Indicate that this frame is a another fragment for reassembly */ @@ -211,7 +212,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, * bytes at the end. We must be liberal in what we accept. */ - if (ieee->i_accumlen + iob->io_len - g_rime_hdrlen >= fragsize) + if (ieee->i_accumlen + iob->io_len - g_frame_hdrlen >= fragsize) { islastfrag = true; } @@ -339,11 +340,13 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, /* Process next dispatch and headers */ -#ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 + hc1 = payptr + g_frame_hdrlen; + + #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 if ((hc1[RIME_HC1_DISPATCH] & SIXLOWPAN_DISPATCH_IPHC_MASK) == SIXLOWPAN_DISPATCH_IPHC) { ninfo("IPHC Dispatch\n"); - sixlowpan_uncompresshdr_hc06(ieee, fragsize); + sixlowpan_uncompresshdr_hc06(ieee, fragsize, iob, payptr); } else #endif /* CONFIG_NET_6LOWPAN_COMPRESSION_HC06 */ @@ -352,22 +355,22 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, if (hc1[RIME_HC1_DISPATCH] == SIXLOWPAN_DISPATCH_HC1) { ninfo("HC1 Dispatch\n"); - sixlowpan_uncompresshdr_hc1(ieee, fragsize); + sixlowpan_uncompresshdr_hc1(ieee, fragsize, iob, payptr); } else #endif /* CONFIG_NET_6LOWPAN_COMPRESSION_HC1 */ if (hc1[RIME_HC1_DISPATCH] == SIXLOWPAN_DISPATCH_IPV6) { ninfo("IPV6 Dispatch\n"); - g_rime_hdrlen += SIXLOWPAN_IPV6_HDR_LEN; + g_frame_hdrlen += SIXLOWPAN_IPV6_HDR_LEN; /* Put uncompressed IP header in d_buf. */ - memcpy(ieee->i_dev.d_buf, g_rimeptr + g_rime_hdrlen, IPv6_HDRLEN); + memcpy(ieee->i_dev.d_buf, payptr + g_frame_hdrlen, IPv6_HDRLEN); - /* Update g_uncomp_hdrlen and g_rime_hdrlen. */ + /* Update g_uncomp_hdrlen and g_frame_hdrlen. */ - g_rime_hdrlen += IPv6_HDRLEN; + g_frame_hdrlen += IPv6_HDRLEN; g_uncomp_hdrlen += IPv6_HDRLEN; } else @@ -384,17 +387,17 @@ copypayload: /* Copy "payload" from the rime buffer to the d_buf. If this frame is a * first fragment or not part of a fragmented packet, we have already - * copied the compressed headers, g_uncomp_hdrlen and g_rime_hdrlen are + * copied the compressed headers, g_uncomp_hdrlen and g_frame_hdrlen are * non-zerio, fragoffset is. */ - if (ieee->i_dev.d_len < g_rime_hdrlen) + if (ieee->i_dev.d_len < g_frame_hdrlen) { ninfo("SIXLOWPAN: packet dropped due to header > total packet\n"); return OK; } - g_rime_payloadlen = ieee->i_dev.d_len - g_rime_hdrlen; + g_rime_payloadlen = ieee->i_dev.d_len - g_frame_hdrlen; /* Sanity-check size of incoming packet to avoid buffer overflow */ @@ -408,7 +411,7 @@ copypayload: } memcpy((FAR uint8_t *)ieee->i_dev.d_buf + g_uncomp_hdrlen + - (int)(fragoffset << 3), g_rimeptr + g_rime_hdrlen, + (int)(fragoffset << 3), payptr + g_frame_hdrlen, g_rime_payloadlen); #if CONFIG_NET_6LOWPAN_FRAG diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index 5bb88f63c6..726acc9eea 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -100,21 +100,16 @@ * bytes for all subsequent headers. */ -#define RIME_FRAG_PTR g_rimeptr #define RIME_FRAG_DISPATCH_SIZE 0 /* 16 bit */ #define RIME_FRAG_TAG 2 /* 16 bit */ #define RIME_FRAG_OFFSET 4 /* 8 bit */ /* Define the Rime buffer as a byte array */ -#define RIME_IPHC_BUF (g_rimeptr + g_rime_hdrlen) - -#define RIME_HC1_PTR (g_rimeptr + g_rime_hdrlen) #define RIME_HC1_DISPATCH 0 /* 8 bit */ #define RIME_HC1_ENCODING 1 /* 8 bit */ #define RIME_HC1_TTL 2 /* 8 bit */ -#define RIME_HC1_HC_UDP_PTR (g_rimeptr + g_rime_hdrlen) #define RIME_HC1_HC_UDP_DISPATCH 0 /* 8 bit */ #define RIME_HC1_HC_UDP_HC1_ENCODING 1 /* 8 bit */ #define RIME_HC1_HC_UDP_UDP_ENCODING 2 /* 8 bit */ @@ -408,7 +403,7 @@ struct frame802154_s /* A pointer to the rime buffer. * * We initialize it to the beginning of the rime buffer, then access - * different fields by updating the offset ieee->g_rime_hdrlen. + * different fields by updating the offset ieee->g_frame_hdrlen. */ extern FAR uint8_t *g_rimeptr; @@ -428,12 +423,12 @@ extern uint8_t g_rime_payloadlen; extern uint8_t g_uncomp_hdrlen; -/* g_rime_hdrlen is the total length of (the processed) 6lowpan headers +/* g_frame_hdrlen is the total length of (the processed) 6lowpan headers * (fragment headers, IPV6 or HC1, HC2, and HC1 and HC2 non compressed * fields). */ -extern uint8_t g_rime_hdrlen; +extern uint8_t g_frame_hdrlen; /* Offset first available byte for the payload after header region. */ @@ -621,7 +616,7 @@ void sixlowpan_hc06_initialize(void); * ipv6 - The IPv6 header to be compressed * destmac - L2 destination address, needed to compress the IP * destination field - * iob - The IOB into which the compressed header should be saved. + * fptr - Pointer to frame data payload. * * Returned Value: * None @@ -632,7 +627,7 @@ void sixlowpan_hc06_initialize(void); void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, FAR const struct ipv6_hdr_s *ipv6, FAR const struct rimeaddr_s *destmac, - FAR struct iob_s *iob); + FAR uint8_t *fptr); #endif /**************************************************************************** @@ -645,14 +640,16 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, * This function is called by the input function when the dispatch is HC06. * We process the packet in the rime buffer, uncompress the header fields, * and copy the result in the sixlowpan buffer. At the end of the - * decompression, g_rime_hdrlen and g_uncompressed_hdrlen are set to the + * decompression, g_frame_hdrlen and g_uncompressed_hdrlen are set to the * appropriate values * * Input Parmeters: - * ieee - A reference to the IEE802.15.4 network device state - * iplen - Equal to 0 if the packet is not a fragment (IP length is then - * inferred from the L2 length), non 0 if the packet is a first - * fragment. + * ieee - A reference to the IEE802.15.4 network device state + * iplen - Equal to 0 if the packet is not a fragment (IP length is then + * inferred from the L2 length), non 0 if the packet is a first + * fragment. + * iob - Pointer to the IOB containing the received frame. + * payptr - Pointer to the frame data payload. * * Returned Value: * None @@ -661,7 +658,8 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, - uint16_t iplen); + uint16_t iplen, FAR struct iob_s *iob, + FAR uint8_t *payptr); #endif /**************************************************************************** @@ -679,7 +677,6 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, * ipv6 - The IPv6 header to be compressed * destmac - L2 destination address, needed to compress the IP * destination field - * iob - The IOB into which the compressed header should be saved. * * Returned Value: * None @@ -690,7 +687,7 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, FAR const struct ipv6_hdr_s *ipv6, FAR const struct rimeaddr_s *destmac, - FAR struct iob_s *iob); + FAR uint8_t *fptr); #endif /**************************************************************************** @@ -702,7 +699,7 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, * This function is called by the input function when the dispatch is * HC1. It processes the packet in the rime buffer, uncompresses the * header fields, and copies the result in the sixlowpan buffer. At the - * end of the decompression, g_rime_hdrlen and uncompressed_hdr_len + * end of the decompression, g_frame_hdrlen and uncompressed_hdr_len * are set to the appropriate values * * Input Parameters: @@ -710,6 +707,8 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, * iplen - Equal to 0 if the packet is not a fragment (IP length is then * inferred from the L2 length), non 0 if the packet is a first * fragment. + * iob - Pointer to the IOB containing the received frame. + * payptr - Pointer to the frame data payload. * * Returned Value: * None @@ -718,7 +717,8 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC1 int sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, - uint16_t ip_len); + uint16_t ip_len, FAR struct iob_s *iob, + FAR uint8_t *payptr); #endif /**************************************************************************** -- GitLab From 73056863ba9bca131a7743d6dd68e867c1a089bf Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Tue, 4 Apr 2017 07:27:19 -0600 Subject: [PATCH 332/990] Fix building without CONFIG_NET_6LOWPAN --- include/nuttx/net/sixlowpan.h | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index ebeb34933a..9f051857e4 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -42,8 +42,8 @@ * ****************************************************************************/ -#ifndef __INCLUDE_NUTTX_NET_SIXLOWOAN_H -#define __INCLUDE_NUTTX_NET_SIXLOWOAN_H +#ifndef __INCLUDE_NUTTX_NET_SIXLOWPAN_H +#define __INCLUDE_NUTTX_NET_SIXLOWPAN_H /**************************************************************************** * Included Files @@ -57,6 +57,8 @@ #include #include +#ifdef CONFIG_NET_6LOWPAN + /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ @@ -465,4 +467,5 @@ struct ieee802154_driver_s int sixlowpan_input(FAR struct ieee802154_driver_s *ieee); -#endif /* __INCLUDE_NUTTX_NET_SIXLOWOAN_H */ +#endif /* CONFIG_NET_6LOWPAN */ +#endif /* __INCLUDE_NUTTX_NET_SIXLOWPAN_H */ -- GitLab From d64d4e02b46fe3773e47da6fe1df1849444ed3bb Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Tue, 4 Apr 2017 07:29:23 -0600 Subject: [PATCH 333/990] sensors: lis2dh: fix hardfault when reading from unconfigured sensor --- drivers/sensors/lis2dh.c | 27 +++++++++++++++++---------- include/nuttx/sensors/lis2dh.h | 8 ++++++-- 2 files changed, 23 insertions(+), 12 deletions(-) diff --git a/drivers/sensors/lis2dh.c b/drivers/sensors/lis2dh.c index 003baa390a..b24aa782e3 100644 --- a/drivers/sensors/lis2dh.c +++ b/drivers/sensors/lis2dh.c @@ -129,7 +129,7 @@ static int lis2dh_access(FAR struct lis2dh_dev_s *dev, uint8_t subaddr, FAR uint8_t *buf, int length); static int lis2dh_get_reading(FAR struct lis2dh_dev_s *dev, FAR struct lis2dh_vector_s *res, bool force_read); -static int lis2dh_powerdown(FAR struct lis2dh_dev_s dev); +static int lis2dh_powerdown(FAR struct lis2dh_dev_s *dev); static int lis2dh_reboot(FAR struct lis2dh_dev_s *dev); static int lis2dh_poll(FAR struct file *filep, FAR struct pollfd *fds, bool setup); @@ -326,6 +326,20 @@ static ssize_t lis2dh_read(FAR struct file *filep, FAR char *buffer, return -EINVAL; } + err = sem_wait(&priv->devsem); + if (err < 0) + { + return -EINTR; + } + + /* Do not allow read() if no SNIOC_WRITESETUP first. */ + + if (!priv->setup) + { + lis2dh_dbg("lis2dh: Read from unconfigured device\n"); + return -EINVAL; + } + flags = enter_critical_section(); #ifdef LIS2DH_COUNT_INTS if (priv->int_pending > 0) @@ -342,13 +356,6 @@ static ssize_t lis2dh_read(FAR struct file *filep, FAR char *buffer, /* Set pointer to first measurement data */ ptr = (FAR struct lis2dh_result *)buffer; - - err = sem_wait(&priv->devsem); - if (err < 0) - { - return -EINTR; - } - ptr->header.meas_count = 0; if (!priv->fifo_used) @@ -421,9 +428,9 @@ static ssize_t lis2dh_read(FAR struct file *filep, FAR char *buffer, fifo_num_samples = (buf & ST_LIS2DH_FIFOSR_NUM_SAMP_MASK) + 1; - if (fifo_num_samples > readcount) + if (fifo_num_samples > (readcount - ptr->header.meas_count)) { - fifo_num_samples = readcount; + fifo_num_samples = (readcount - ptr->header.meas_count); } ptr->header.meas_count += diff --git a/include/nuttx/sensors/lis2dh.h b/include/nuttx/sensors/lis2dh.h index f9fdd839ca..bede2795c2 100644 --- a/include/nuttx/sensors/lis2dh.h +++ b/include/nuttx/sensors/lis2dh.h @@ -109,8 +109,12 @@ extern "C" /* I1_AOI1 ENABLE for INT2 (-X------) */ -#define ST_LIS2DH_CR3_I1_AOI1_ENABLED 0x40 /* AOI1 interrupt on INT1 pin.*/ -#define ST_LIS2DH_CR3_I1_AOI2_ENABLED 0x20 /* AOI2 interrupt on INT1 pin.*/ +#define ST_LIS2DH_CR3_I1_AOI1_ENABLED 0x40 /* AOI1 interrupt on INT1 pin. */ +#define ST_LIS2DH_CR3_I1_AOI2_ENABLED 0x20 /* AOI2 interrupt on INT1 pin. */ +#define ST_LIS2DH_CR3_I1_DRDY1 0x10 /* DRDY1 interrupt on INT1 pin. */ +#define ST_LIS2DH_CR3_I1_DRDY2 0x08 /* DRDY2 interrupt on INT1 pin. */ +#define ST_LIS2DH_CR3_I1_WTM 0x04 /* FIFO Watermark interrupt on INT1 pin. */ +#define ST_LIS2DH_CR3_I1_OVERRUN 0x02 /* FIFO Overrun interrupt on INT1 pin. */ #define ST_LIS2DH_CTRL_REG4 0x23 -- GitLab From 9a29b9a327854d472356b4957d9140251b246d5a Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Tue, 4 Apr 2017 07:34:24 -0600 Subject: [PATCH 334/990] stm32: stm32_flash: add EEPROM writing for STM32L15XX --- arch/arm/src/stm32/chip/stm32_flash.h | 145 +++++++++++---- arch/arm/src/stm32/stm32_flash.c | 246 ++++++++++++++++++++++++-- arch/arm/src/stm32/stm32_flash.h | 56 ++++++ 3 files changed, 399 insertions(+), 48 deletions(-) diff --git a/arch/arm/src/stm32/chip/stm32_flash.h b/arch/arm/src/stm32/chip/stm32_flash.h index 6bc1085bd1..13c966c05c 100644 --- a/arch/arm/src/stm32/chip/stm32_flash.h +++ b/arch/arm/src/stm32/chip/stm32_flash.h @@ -59,16 +59,33 @@ #if defined(CONFIG_STM32_FLASH_CONFIG_DEFAULT) # if defined(CONFIG_STM32_STM32L15XX) +# if defined(CONFIG_STM32_HIGHDENSITY) -/* The STM32 L15xx/L16xx can support up to 384KB of FLASH. (In reality, supported - * L15xx parts have no more than 128KB). The program memory block is divided into - * 96 sectors of 4 Kbytes each, and each sector is further split up into 16 pages of - * 256 bytes each. The sector is the write protection granularity. In total, the +/* Different STM32L1xxx MCU version are now called by different 'categories' instead + * of 'densities'. Cat.5 MCU can have up to 512KB of FLASH. STM32L1xxx also have + * data EEPROM, up to 16KB. + */ + +# define STM32_FLASH_NPAGES 2048 +# define STM32_FLASH_PAGESIZE 256 +# else + +/* The STM32 (< Cat.5) L15xx/L16xx can support up to 384KB of FLASH. (In reality, most + * supported L15xx parts have no more than 128KB). The program memory block is divided + * into 96 sectors of 4 Kbytes each, and each sector is further split up into 16 pages + * of 256 bytes each. The sector is the write protection granularity. In total, the * program memory block contains 1536 pages. */ -# define STM32_FLASH_NPAGES 1536 -# define STM32_FLASH_PAGESIZE 256 +# define STM32_FLASH_NPAGES 1536 +# define STM32_FLASH_PAGESIZE 256 +# endif + + /* Maximum EEPROM size on Cat.5 MCU. TODO: this should be in chip config. */ + +# ifndef STM32_EEPROM_SIZE +# define STM32_EEPROM_SIZE (16 * 1024) +# endif # elif defined(CONFIG_STM32_LOWDENSITY) # define STM32_FLASH_NPAGES 32 @@ -201,27 +218,40 @@ # elif defined(CONFIG_STM32_FLASH_CONFIG_I) # endif # endif -#endif +#endif /* !defined(CONFIG_STM32_FLASH_CONFIG_DEFAULT) */ #ifdef STM32_FLASH_PAGESIZE # define STM32_FLASH_SIZE (STM32_FLASH_NPAGES * STM32_FLASH_PAGESIZE) -#endif /* def STM32_FLASH_PAGESIZE */ +#endif /* Register Offsets *****************************************************************/ -#define STM32_FLASH_ACR_OFFSET 0x0000 -#define STM32_FLASH_KEYR_OFFSET 0x0004 -#define STM32_FLASH_OPTKEYR_OFFSET 0x0008 -#define STM32_FLASH_SR_OFFSET 0x000c -#define STM32_FLASH_CR_OFFSET 0x0010 - -#if defined(CONFIG_STM32_STM32F10XX) || defined(CONFIG_STM32_STM32F30XX) || \ - defined(CONFIG_STM32_STM32F33XX) || defined(CONFIG_STM32_STM32F37XX) -# define STM32_FLASH_AR_OFFSET 0x0014 -# define STM32_FLASH_OBR_OFFSET 0x001c -# define STM32_FLASH_WRPR_OFFSET 0x0020 -#elif defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX) -# define STM32_FLASH_OPTCR_OFFSET 0x0014 +#define STM32_FLASH_ACR_OFFSET 0x0000 +#if defined(CONFIG_STM32_STM32L15XX) +# define STM32_FLASH_PECR_OFFSET 0x0004 +# define STM32_FLASH_PDKEYR_OFFSET 0x0008 +# define STM32_FLASH_PEKEYR_OFFSET 0x000c +# define STM32_FLASH_PRGKEYR_OFFSET 0x0010 +# define STM32_FLASH_OPTKEYR_OFFSET 0x0014 +# define STM32_FLASH_SR_OFFSET 0x0018 +# define STM32_FLASH_OBR_OFFSET 0x001c +# define STM32_FLASH_WRPR1_OFFSET 0x0020 +# define STM32_FLASH_WRPR2_OFFSET 0x0080 +# define STM32_FLASH_WRPR3_OFFSET 0x0084 +# define STM32_FLASH_WRPR4_OFFSET 0x0088 +#else +# define STM32_FLASH_KEYR_OFFSET 0x0004 +# define STM32_FLASH_OPTKEYR_OFFSET 0x0008 +# define STM32_FLASH_SR_OFFSET 0x000c +# define STM32_FLASH_CR_OFFSET 0x0010 +# if defined(CONFIG_STM32_STM32F10XX) || defined(CONFIG_STM32_STM32F30XX) || \ + defined(CONFIG_STM32_STM32F33XX) || defined(CONFIG_STM32_STM32F37XX) +# define STM32_FLASH_AR_OFFSET 0x0014 +# define STM32_FLASH_OBR_OFFSET 0x001c +# define STM32_FLASH_WRPR_OFFSET 0x0020 +# elif defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX) +# define STM32_FLASH_OPTCR_OFFSET 0x0014 +# endif #endif #if defined(CONFIG_STM32_STM32F427) || defined(CONFIG_STM32_STM32F429) @@ -230,22 +260,36 @@ /* Register Addresses ***************************************************************/ -#define STM32_FLASH_ACR (STM32_FLASHIF_BASE+STM32_FLASH_ACR_OFFSET) -#define STM32_FLASH_KEYR (STM32_FLASHIF_BASE+STM32_FLASH_KEYR_OFFSET) -#define STM32_FLASH_OPTKEYR (STM32_FLASHIF_BASE+STM32_FLASH_OPTKEYR_OFFSET) -#define STM32_FLASH_SR (STM32_FLASHIF_BASE+STM32_FLASH_SR_OFFSET) -#define STM32_FLASH_CR (STM32_FLASHIF_BASE+STM32_FLASH_CR_OFFSET) +#define STM32_FLASH_ACR (STM32_FLASHIF_BASE+STM32_FLASH_ACR_OFFSET) +#if defined(CONFIG_STM32_STM32L15XX) +# define STM32_FLASH_PECR (STM32_FLASHIF_BASE+STM32_FLASH_PECR_OFFSET) +# define STM32_FLASH_PDKEYR (STM32_FLASHIF_BASE+STM32_FLASH_PDKEYR_OFFSET) +# define STM32_FLASH_PEKEYR (STM32_FLASHIF_BASE+STM32_FLASH_PEKEYR_OFFSET) +# define STM32_FLASH_PRGKEYR (STM32_FLASHIF_BASE+STM32_FLASH_PRGKEYR_OFFSET) +# define STM32_FLASH_OPTKEYR (STM32_FLASHIF_BASE+STM32_FLASH_OPTKEYR_OFFSET) +# define STM32_FLASH_SR (STM32_FLASHIF_BASE+STM32_FLASH_SR_OFFSET) +# define STM32_FLASH_OBR (STM32_FLASHIF_BASE+STM32_FLASH_OBR_OFFSET) +# define STM32_FLASH_WRPR1 (STM32_FLASHIF_BASE+STM32_FLASH_WRPR1_OFFSET) +# define STM32_FLASH_WRPR2 (STM32_FLASHIF_BASE+STM32_FLASH_WRPR2_OFFSET) +# define STM32_FLASH_WRPR3 (STM32_FLASHIF_BASE+STM32_FLASH_WRPR3_OFFSET) +# define STM32_FLASH_WRPR4 (STM32_FLASHIF_BASE+STM32_FLASH_WRPR4_OFFSET) +#else +# define STM32_FLASH_KEYR (STM32_FLASHIF_BASE+STM32_FLASH_KEYR_OFFSET) +# define STM32_FLASH_OPTKEYR (STM32_FLASHIF_BASE+STM32_FLASH_OPTKEYR_OFFSET) +# define STM32_FLASH_SR (STM32_FLASHIF_BASE+STM32_FLASH_SR_OFFSET) +# define STM32_FLASH_CR (STM32_FLASHIF_BASE+STM32_FLASH_CR_OFFSET) -#if defined(CONFIG_STM32_STM32F10XX) || defined(CONFIG_STM32_STM32F30XX) || \ - defined(CONFIG_STM32_STM32F33XX) || defined(CONFIG_STM32_STM32F37XX) -# define STM32_FLASH_AR (STM32_FLASHIF_BASE+STM32_FLASH_AR_OFFSET) -# define STM32_FLASH_OBR (STM32_FLASHIF_BASE+STM32_FLASH_OBR_OFFSET) -# define STM32_FLASH_WRPR (STM32_FLASHIF_BASE+STM32_FLASH_WRPR_OFFSET) -#elif defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX) -# define STM32_FLASH_OPTCR (STM32_FLASHIF_BASE+STM32_FLASH_OPTCR_OFFSET) -#endif -#if defined(CONFIG_STM32_STM32F427) || defined(CONFIG_STM32_STM32F429) -# define STM32_FLASH_OPTCR1 (STM32_FLASHIF_BASE+STM32_FLASH_OPTCR1_OFFSET) +# if defined(CONFIG_STM32_STM32F10XX) || defined(CONFIG_STM32_STM32F30XX) || \ + defined(CONFIG_STM32_STM32F33XX) || defined(CONFIG_STM32_STM32F37XX) +# define STM32_FLASH_AR (STM32_FLASHIF_BASE+STM32_FLASH_AR_OFFSET) +# define STM32_FLASH_OBR (STM32_FLASHIF_BASE+STM32_FLASH_OBR_OFFSET) +# define STM32_FLASH_WRPR (STM32_FLASHIF_BASE+STM32_FLASH_WRPR_OFFSET) +# elif defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX) +# define STM32_FLASH_OPTCR (STM32_FLASHIF_BASE+STM32_FLASH_OPTCR_OFFSET) +# endif +# if defined(CONFIG_STM32_STM32F427) || defined(CONFIG_STM32_STM32F429) +# define STM32_FLASH_OPTCR1 (STM32_FLASHIF_BASE+STM32_FLASH_OPTCR1_OFFSET) +# endif #endif /* Register Bitfield Definitions ****************************************************/ @@ -303,6 +347,34 @@ # define FLASH_SR_PGPERR (1 << 6) /* Bit 6: Programming parallelism error */ # define FLASH_SR_PGSERR (1 << 7) /* Bit 7: Programming sequence error */ # define FLASH_SR_BSY (1 << 16) /* Bit 16: Busy */ +#elif defined(CONFIG_STM32_STM32L15XX) +# define FLASH_SR_BSY (1 << 0) /* Bit 0: Busy */ +# define FLASH_SR_EOP (1 << 1) /* Bit 1: End of operation */ +# define FLASH_SR_ENDHV (1 << 2) /* Bit 2: End of high voltage */ +# define FLASH_SR_READY (1 << 3) /* Bit 3: Flash memory module ready after low power mode */ +# define FLASH_SR_WRPERR (1 << 8) /* Bit 8: Write protection error */ +# define FLASH_SR_PGAERR (1 << 9) /* Bit 9: Programming alignment error */ +# define FLASH_SR_SIZERR (1 << 10) /* Bit 10: Size error */ +# define FLASH_SR_OPTVERR (1 << 11) /* Bit 11: Option validity error */ +# define FLASH_SR_OPTVERRUSR (1 << 12) /* Bit 12: Option UserValidity Error */ +# define FLASH_SR_RDERR (1 << 13) /* Bit 13: Read protected error */ +#endif + +/* Program/Erase Control Register (PECR) */ + +#if defined(CONFIG_STM32_STM32L15XX) +# define FLASH_PECR_PELOCK (1 << 0) /* Bit 0: PECR and data EEPROM lock */ +# define FLASH_PECR_PRGLOCK (1 << 1) /* Bit 1: Program memory lock */ +# define FLASH_PECR_OPTLOCK (1 << 2) /* Bit 2: Option bytes block lock */ +# define FLASH_PECR_PROG (1 << 3) /* Bit 3: Program memory selection */ +# define FLASH_PECR_DATA (1 << 4) /* Bit 4: Data EEPROM selection */ +# define FLASH_PECR_FTDW (1 << 8) /* Bit 8: Fixed time data write for Byte, Half Word and Word programming */ +# define FLASH_PECR_ERASE (1 << 9) /* Bit 9: Page or Double Word erase mode */ +# define FLASH_PECR_FPRG (1 << 10) /* Bit 10: Half Page/Double Word programming mode */ +# define FLASH_PECR_PARALLBANK (1 << 15) /* Bit 15: Parallel bank mode */ +# define FLASH_PECR_EOPIE (1 << 16) /* Bit 16: End of programming interrupt enable */ +# define FLASH_PECR_ERRIE (1 << 17) /* Bit 17: Error interrupt enable */ +# define FLASH_PECR_OBL_LAUNCH (1 << 18) /* Bit 18: Launch the option byte loading */ #endif /* Flash Control Register (CR) */ @@ -380,7 +452,6 @@ # define FLASH_OPTCR1_BFB2_SHIFT (4) /* Bits 4: Dual-bank Boot option byte */ # define FLASH_OPTCR1_BFB2_MASK (1 << FLASH_OPTCR_NWRP_SHIFT) - #endif #if defined(CONFIG_STM32_STM32F446) diff --git a/arch/arm/src/stm32/stm32_flash.c b/arch/arm/src/stm32/stm32_flash.c index fb1e1cac22..1dae18724c 100644 --- a/arch/arm/src/stm32/stm32_flash.c +++ b/arch/arm/src/stm32/stm32_flash.c @@ -59,10 +59,10 @@ #include "up_arch.h" -/* Only for the STM32F[1|3|4]0xx family for now */ +/* Only for the STM32F[1|3|4]0xx family and STM32L15xx (EEPROM only) for now */ #if defined(CONFIG_STM32_STM32F10XX) || defined(CONFIG_STM32_STM32F30XX) || \ - defined (CONFIG_STM32_STM32F40XX) + defined (CONFIG_STM32_STM32F40XX) || defined(CONFIG_STM32_STM32L15XX) #if defined(CONFIG_STM32_FLASH_CONFIG_DEFAULT) && \ (defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)) @@ -73,15 +73,25 @@ * Pre-processor Definitions ************************************************************************************/ -#define FLASH_KEY1 0x45670123 -#define FLASH_KEY2 0xCDEF89AB +#if defined(CONFIG_STM32_STM32L15XX) +# define FLASH_KEY1 0x8C9DAEBF +# define FLASH_KEY2 0x13141516 +#else +# define FLASH_KEY1 0x45670123 +# define FLASH_KEY2 0xCDEF89AB +#endif #if defined(CONFIG_STM32_STM32F10XX) || defined(CONFIG_STM32_STM32F30XX) -#define FLASH_CR_PAGE_ERASE FLASH_CR_PER -#define FLASH_SR_WRITE_PROTECTION_ERROR FLASH_SR_WRPRT_ERR +# define FLASH_CR_PAGE_ERASE FLASH_CR_PER +# define FLASH_SR_WRITE_PROTECTION_ERROR FLASH_SR_WRPRT_ERR #elif defined(CONFIG_STM32_STM32F40XX) -#define FLASH_CR_PAGE_ERASE FLASH_CR_SER -#define FLASH_SR_WRITE_PROTECTION_ERROR FLASH_SR_WRPERR +# define FLASH_CR_PAGE_ERASE FLASH_CR_SER +# define FLASH_SR_WRITE_PROTECTION_ERROR FLASH_SR_WRPERR +#endif + +#if defined(CONFIG_STM32_STM32L15XX) +# define EEPROM_KEY1 0x89ABCDEF +# define EEPROM_KEY2 0x02030405 #endif /************************************************************************************ @@ -107,6 +117,8 @@ static inline void sem_unlock(void) sem_post(&g_sem); } +#if !defined(CONFIG_STM32_STM32L15XX) + static void flash_unlock(void) { while (getreg32(STM32_FLASH_SR) & FLASH_SR_BSY) @@ -128,6 +140,8 @@ static void flash_lock(void) modifyreg32(STM32_FLASH_CR, 0, FLASH_CR_LOCK); } +#endif /* !defined(CONFIG_STM32_STM32L15XX) */ + #if defined(CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW) static void data_cache_disable(void) { @@ -146,6 +160,183 @@ static void data_cache_enable(void) } #endif /* defined(CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW) */ +#if defined(CONFIG_STM32_STM32L15XX) + +static void stm32_eeprom_unlock(void) +{ + while (getreg32(STM32_FLASH_SR) & FLASH_SR_BSY) + { + up_waste(); + } + + if (getreg32(STM32_FLASH_PECR) & FLASH_PECR_PELOCK) + { + /* Unlock sequence */ + + putreg32(EEPROM_KEY1, STM32_FLASH_PEKEYR); + putreg32(EEPROM_KEY2, STM32_FLASH_PEKEYR); + } +} + +static void stm32_eeprom_lock(void) +{ + modifyreg32(STM32_FLASH_PECR, 0, FLASH_PECR_PELOCK); +} + +static void flash_unlock(void) +{ + if (getreg32(STM32_FLASH_PECR) & FLASH_PECR_PRGLOCK) + { + stm32_eeprom_unlock(); + + /* Unlock sequence */ + + putreg32(FLASH_KEY1, STM32_FLASH_PRGKEYR); + putreg32(FLASH_KEY2, STM32_FLASH_PRGKEYR); + } +} + +static void flash_lock(void) +{ + modifyreg32(STM32_FLASH_PECR, 0, FLASH_PECR_PRGLOCK); + stm32_eeprom_lock(); +} + +static ssize_t stm32_eeprom_erase_write(size_t addr, const void *buf, + size_t buflen) +{ + const char *cbuf = buf; + size_t i; + + if (buflen == 0) + { + return 0; + } + + /* Check for valid address range */ + + if (addr >= STM32_EEPROM_BASE) + { + addr -= STM32_EEPROM_BASE; + } + + if (addr >= STM32_EEPROM_SIZE) + { + return -EINVAL; + } + + /* TODO: Voltage range must be range 1 or 2. Erase/program not allowed in + * range 3. + */ + + stm32_eeprom_unlock(); + + /* Clear pending status flags. */ + + putreg32(FLASH_SR_WRPERR | FLASH_SR_PGAERR | + FLASH_SR_SIZERR | FLASH_SR_OPTVERR | + FLASH_SR_OPTVERRUSR | FLASH_SR_RDERR, STM32_FLASH_SR); + + /* Enable automatic erasing (by disabling 'fixed time' programming). */ + + modifyreg32(STM32_FLASH_PECR, FLASH_PECR_FTDW, 0); + + /* Write buffer to EEPROM data memory. */ + + addr += STM32_EEPROM_BASE; + i = 0; + while (i < buflen) + { + uint32_t writeval; + size_t left = buflen - i; + + if ((addr & 0x03) == 0x00 && left >= 4) + { + /* Read/erase/write word */ + + writeval = cbuf ? *(uint32_t *)cbuf : 0; + putreg32(writeval, addr); + } + else if ((addr & 0x01) == 0x00 && left >= 2) + { + /* Read/erase/write half-word */ + + writeval = cbuf ? *(uint16_t *)cbuf : 0; + putreg16(writeval, addr); + } + else + { + /* Read/erase/write byte */ + + writeval = cbuf ? *(uint8_t *)cbuf : 0; + putreg8(writeval, addr); + } + + /* ... and wait to complete. */ + + while (getreg32(STM32_FLASH_SR) & FLASH_SR_BSY) + { + up_waste(); + } + + /* Verify */ + + /* We do not check Options Byte invalid flags FLASH_SR_OPTVERR + * and FLASH_SR_OPTVERRUSR for EEPROM erase/write. They are unrelated + * and STM32L standard library does not check for these either. + */ + + if (getreg32(STM32_FLASH_SR) & (FLASH_SR_WRPERR | FLASH_SR_PGAERR | + FLASH_SR_SIZERR | FLASH_SR_RDERR)) + { + stm32_eeprom_lock(); + return -EROFS; + } + + if ((addr & 0x03) == 0x00 && left >= 4) + { + if (getreg32(addr) != writeval) + { + stm32_eeprom_lock(); + return -EIO; + } + + addr += 4; + i += 4; + cbuf += !!(cbuf) * 4; + } + else if ((addr & 0x01) == 0x00 && left >= 2) + { + if (getreg16(addr) != writeval) + { + stm32_eeprom_lock(); + return -EIO; + } + + addr += 2; + i += 2; + cbuf += !!(cbuf) * 2; + } + else + { + if (getreg8(addr) != writeval) + { + stm32_eeprom_lock(); + return -EIO; + } + + addr += 1; + i += 1; + cbuf += !!(cbuf) * 1; + } + } + + stm32_eeprom_lock(); + return buflen; +} + +#endif /* defined(CONFIG_STM32_STM32L15XX) */ + /************************************************************************************ * Public Functions ************************************************************************************/ @@ -164,6 +355,35 @@ void stm32_flash_lock(void) sem_unlock(); } +#if defined(CONFIG_STM32_STM32L15XX) + +size_t stm32_eeprom_size(void) +{ + return STM32_EEPROM_SIZE; +} + +size_t stm32_eeprom_getaddress(void) +{ + return STM32_EEPROM_BASE; +} + +ssize_t stm32_eeprom_write(size_t addr, const void *buf, size_t buflen) +{ + if (!buf) + { + return -EINVAL; + } + + return stm32_eeprom_erase_write(addr, buf, buflen); +} + +ssize_t stm32_eeprom_erase(size_t addr, size_t eraselen) +{ + return stm32_eeprom_erase_write(addr, NULL, eraselen); +} + +#endif /* defined(CONFIG_STM32_STM32L15XX) */ + #if defined(CONFIG_STM32_STM32F10XX) || defined(CONFIG_STM32_STM32F30XX) size_t up_progmem_pagesize(size_t page) { @@ -260,6 +480,8 @@ size_t up_progmem_getaddress(size_t page) #endif /* def CONFIG_STM32_STM32F40XX */ +#if !defined(CONFIG_STM32_STM32L15XX) + size_t up_progmem_npages(void) { return STM32_FLASH_NPAGES; @@ -271,14 +493,14 @@ bool up_progmem_isuniform(void) return true; #else return false; -#endif /* def STM32_FLASH_PAGESIZE */ +#endif } ssize_t up_progmem_erasepage(size_t page) { #if defined(CONFIG_STM32_STM32F10XX) || defined(CONFIG_STM32_STM32F30XX) size_t page_address; -#endif /* defined(CONFIG_STM32_STM32F10XX) || defined(CONFIG_STM32_STM32F30XX) */ +#endif if (page >= STM32_FLASH_NPAGES) { @@ -438,5 +660,7 @@ ssize_t up_progmem_write(size_t addr, const void *buf, size_t count) return written; } +#endif /* !defined(CONFIG_STM32_STM32L15XX) */ + #endif /* defined(CONFIG_STM32_STM32F10XX) || defined(CONFIG_STM32_STM32F30XX) || \ - defined (CONFIG_STM32_STM32F40XX) */ + defined(CONFIG_STM32_STM32F40XX) || defined(CONFIG_STM32_STM32L15XX) */ diff --git a/arch/arm/src/stm32/stm32_flash.h b/arch/arm/src/stm32/stm32_flash.h index 10c5cc189e..6da1b0b703 100644 --- a/arch/arm/src/stm32/stm32_flash.h +++ b/arch/arm/src/stm32/stm32_flash.h @@ -46,4 +46,60 @@ #include "chip.h" #include "chip/stm32_flash.h" +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_eeprom_size + * + * Description: + * Get EEPROM data memory size + * + * Returns: + * Length of EEPROM memory region + * + ************************************************************************************/ + +size_t stm32_eeprom_size(void); + +/************************************************************************************ + * Name: stm32_eeprom_getaddress + * + * Description: + * Get EEPROM data memory address + * + * Returns: + * Address of EEPROM memory region + * + ************************************************************************************/ + +size_t stm32_eeprom_getaddress(void); + +/************************************************************************************ + * Name: stm32_eeprom_write + * + * Description: + * Write buffer to EEPROM data memory address + * + * Returns: + * Number of written bytes or error code. + * + ************************************************************************************/ + +ssize_t stm32_eeprom_write(size_t addr, const void *buf, size_t buflen); + +/************************************************************************************ + * Name: stm32_eeprom_erase + * + * Description: + * Erase memory on EEPROM data memory address + * + * Returns: + * Number of erased bytes or error code. + * + ************************************************************************************/ + +ssize_t stm32_eeprom_erase(size_t addr, size_t eraselen); + #endif /* __ARCH_ARM_SRC_STM32_STM32_FLASH_H */ -- GitLab From a6ae7d4ae3d378680f3bb325f6aedd3c7b9aac71 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 4 Apr 2017 09:08:48 -0600 Subject: [PATCH 335/990] 6loWPAN: Fix an error in how reassembly timeouts work. --- net/sixlowpan/sixlowpan_framelist.c | 43 +++++++++++++++-------------- net/sixlowpan/sixlowpan_input.c | 37 +++++++++++++------------ net/sixlowpan/sixlowpan_internal.h | 7 +++-- net/sixlowpan/sixlowpan_tcpsend.c | 37 +++++++++---------------- 4 files changed, 59 insertions(+), 65 deletions(-) diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c index ee5a8a2cf7..0c6519e8fe 100644 --- a/net/sixlowpan/sixlowpan_framelist.c +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -134,10 +134,10 @@ static void sixlowpan_compress_ipv6hdr(FAR struct ieee802154_driver_s *ieee, * * Description: * Process an outgoing UDP or TCP packet. This function is called from - * send interrupt logic when a TX poll is received. It formates the + * send interrupt logic when a TX poll is received. It formats the * list of frames to be sent by the IEEE802.15.4 MAC driver. * - * The payload data is in the caller 's_buf' and is of length 's_len'. + * The payload data is in the caller 'buf' and is of length 'buflen'. * Compressed headers will be added and if necessary the packet is * fragmented. The resulting packet/fragments are put in ieee->i_framelist * and the entire list of frames will be delivered to the 802.15.4 MAC via @@ -146,8 +146,9 @@ static void sixlowpan_compress_ipv6hdr(FAR struct ieee802154_driver_s *ieee, * Input Parameters: * ieee - The IEEE802.15.4 MAC driver instance * ipv6hdr - IPv6 header followed by TCP or UDP header. - * buf - Data to send - * len - Length of data to send + * buf - Beginning of the packet packet to send (with IPv6 + protocol + * headers) + * buflen - Length of data to send (include IPv6 and protocol headers) * destmac - The IEEE802.15.4 MAC address of the destination * * Returned Value: @@ -163,7 +164,7 @@ static void sixlowpan_compress_ipv6hdr(FAR struct ieee802154_driver_s *ieee, int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, FAR const struct ipv6_hdr_s *destip, - FAR const void *buf, size_t len, + FAR const void *buf, size_t buflen, FAR const struct rimeaddr_s *destmac) { FAR struct iob_s *iob; @@ -231,10 +232,10 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, iob->io_pktlen = 0; fptr = iob->io_data; - ninfo("Sending packet len %d\n", len); + ninfo("Sending packet length %d\n", buflen); #ifndef CONFIG_NET_6LOWPAN_COMPRESSION_IPv6 - if (len >= CONFIG_NET_6LOWPAN_COMPRESSION_THRESHOLD) + if (buflen >= CONFIG_NET_6LOWPAN_COMPRESSION_THRESHOLD) { /* Try to compress the headers */ @@ -254,7 +255,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, sixlowpan_compress_ipv6hdr(ieee, destip, fptr); } - ninfo("Header of len %d\n", g_frame_hdrlen); + ninfo("Header of length %d\n", g_frame_hdrlen); rimeaddr_copy(&g_pktaddrs[PACKETBUF_ADDR_RECEIVER], destmac); @@ -271,7 +272,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, /* Check if we need to fragment the packet into several frames */ - if ((int)len - (int)g_uncomp_hdrlen > + if ((int)buflen - (int)g_uncomp_hdrlen > (int)CONFIG_NET_6LOWPAN_MAXPAYLOAD - framer_hdrlen - (int)g_frame_hdrlen) { @@ -290,7 +291,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, * The following fragments contain only the fragn dispatch. */ - ninfo("Fragmentation sending packet len %d\n", len); + ninfo("Fragmentation sending packet length %d\n", buflen); /* Create 1st Fragment */ /* Add the frame header using the pre-allocated IOB. */ @@ -319,7 +320,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, */ PUTINT16(fptr, RIME_FRAG_DISPATCH_SIZE, - ((SIXLOWPAN_DISPATCH_FRAG1 << 8) | len)); + ((SIXLOWPAN_DISPATCH_FRAG1 << 8) | buflen)); PUTINT16(fptr, RIME_FRAG_TAG, ieee->i_dgramtag); ieee->i_dgramtag++; @@ -337,7 +338,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, outlen = g_rime_payloadlen + g_uncomp_hdrlen; - ninfo("First fragment: len %d, tag %d\n", + ninfo("First fragment: length %d, tag %d\n", g_rime_payloadlen, ieee->i_dgramtag); /* Add the first frame to the IOB queue */ @@ -353,7 +354,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, g_frame_hdrlen = SIXLOWPAN_FRAGN_HDR_LEN; - while (outlen < len) + while (outlen < buflen) { /* Allocate an IOB to hold the next fragment, waiting if * necessary. @@ -383,17 +384,17 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, /* Setup up the fragment header */ PUTINT16(fptr, RIME_FRAG_DISPATCH_SIZE, - ((SIXLOWPAN_DISPATCH_FRAGN << 8) | len)); + ((SIXLOWPAN_DISPATCH_FRAGN << 8) | buflen)); PUTINT16(fptr, RIME_FRAG_TAG, ieee->i_dgramtag); fptr[RIME_FRAG_OFFSET] = outlen >> 3; /* Copy payload and enqueue */ - if (len - outlen < g_rime_payloadlen) + if (buflen - outlen < g_rime_payloadlen) { /* Last fragment */ - g_rime_payloadlen = len - outlen; + g_rime_payloadlen = buflen - outlen; } else { @@ -409,7 +410,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, outlen += (g_rime_payloadlen + g_uncomp_hdrlen); - ninfo("sixlowpan output: fragment offset %d, len %d, tag %d\n", + ninfo("sixlowpan output: fragment offset %d, length %d, tag %d\n", outlen >> 3, g_rime_payloadlen, ieee->i_dgramtag); /* Add the next frame to the tail of the IOB queue */ @@ -421,7 +422,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, ieee->i_framelist->io_pktlen += iob->io_len; } #else - nerr("ERROR: Packet too large: %d\n", len); + nerr("ERROR: Packet too large: %d\n", buflen); nerr(" Cannot to be sent without fragmentation support\n"); nerr(" dropping packet\n"); @@ -436,7 +437,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, * and send in one frame. */ - /* Add the frame header to the prealloated IOB. */ + /* Add the frame header to the preallocated IOB. */ verify = sixlowpan_framecreate(ieee, iob, ieee->i_panid); DEBUGASSERT(verify == framer_hdrlen); @@ -445,8 +446,8 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, /* Copy the payload and queue */ memcpy(fptr + g_frame_hdrlen, (FAR uint8_t *)destip + g_uncomp_hdrlen, - len - g_uncomp_hdrlen); - iob->io_len = len - g_uncomp_hdrlen + g_frame_hdrlen; + buflen - g_uncomp_hdrlen); + iob->io_len = buflen - g_uncomp_hdrlen + g_frame_hdrlen; /* Add the first frame to the IOB queue */ diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index 093da4bf30..a098e69dc1 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -148,16 +148,6 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, payptr = &iob->io_data[PACKETBUF_HDR_SIZE]; #if CONFIG_NET_6LOWPAN_FRAG - /* If reassembly timed out, cancel it */ - - elapsed = clock_systimer() - ieee->i_time; - if (elapsed > NET_6LOWPAN_TIMEOUT) - { - nwarn("WARNING: Reassembly timed out\n"); - ieee->i_pktlen = 0; - ieee->i_accumlen = 0; - } - /* Since we don't support the mesh and broadcast header, the first header * we look for is the fragmentation header */ @@ -229,6 +219,16 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, if (ieee->i_accumlen > 0) { + /* If reassembly timed out, cancel it */ + + elapsed = clock_systimer() - ieee->i_time; + if (elapsed > NET_6LOWPAN_TIMEOUT) + { + nwarn("WARNING: Reassembly timed out\n"); + ieee->i_pktlen = 0; + ieee->i_accumlen = 0; + } + /* In this case what we expect is that the next frame will hold the * next FRAGN of the sequence. We have to handle a few exeptional * cases that we need to handle: @@ -246,7 +246,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, * */ - if (!isfrag) + else if (!isfrag) { /* Discard the partially assembled packet */ @@ -287,13 +287,15 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, "the packet currently being reassembled\n"); return OK; } + else + { + /* Looks good. We are currently processing a reassembling sequence + * and we recieved a valid FRAGN fragment. Skip the header + * compression dispatch logic. + */ - /* Looks good. We are currently processing a reassembling sequence and - * we recieved a valid FRAGN fragment. Skip the header compression - * dispatch logic. - */ - - goto copypayload; + goto copypayload; + } } /* There is no reassembly in progress. Check if we received a fragment */ @@ -359,6 +361,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, } else #endif /* CONFIG_NET_6LOWPAN_COMPRESSION_HC1 */ + if (hc1[RIME_HC1_DISPATCH] == SIXLOWPAN_DISPATCH_IPV6) { ninfo("IPV6 Dispatch\n"); diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index 726acc9eea..4a8b4ea0a9 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -543,7 +543,7 @@ int sixlowpan_framecreate(FAR struct ieee802154_driver_s *ieee, * send interrupt logic when a TX poll is received. It formates the * list of frames to be sent by the IEEE802.15.4 MAC driver. * - * The payload data is in the caller 's_buf' and is of length 's_len'. + * The payload data is in the caller 'buf' and is of length 'buflen'. * Compressed headers will be added and if necessary the packet is * fragmented. The resulting packet/fragments are put in ieee->i_framelist * and the entire list of frames will be delivered to the 802.15.4 MAC via @@ -552,8 +552,9 @@ int sixlowpan_framecreate(FAR struct ieee802154_driver_s *ieee, * Input Parameters: * ieee - The IEEE802.15.4 MAC driver instance * ipv6hdr - IPv6 header followed by TCP or UDP header. - * buf - Data to send - * buflen - Length of data to send + * buf - Beginning of the packet packet to send (with IPv6 + protocol + * headers) + * buflen - Length of data to send (include IPv6 and protocol headers) * destmac - The IEEE802.15.4 MAC address of the destination * * Returned Value: diff --git a/net/sixlowpan/sixlowpan_tcpsend.c b/net/sixlowpan/sixlowpan_tcpsend.c index 7beceee5c5..c075a3b827 100644 --- a/net/sixlowpan/sixlowpan_tcpsend.c +++ b/net/sixlowpan/sixlowpan_tcpsend.c @@ -390,30 +390,19 @@ void sixlowpan_tcp_send(FAR struct net_driver_s *dev) } else { - size_t hdrlen; - - hdrlen = IPv6_HDRLEN + TCP_HDRLEN; - if (hdrlen > dev->d_len) - { - nwarn("WARNING: Packet to small: Have %u need >%u\n", - dev->d_len, hdrlen); - } - else - { - struct rimeaddr_s destmac; - - /* Get the Rime MAC address of the destination. This assumes - * an encoding of the MAC address in the IPv6 address. - */ - - sixlowpan_rimefromip(ipv6hdr->destipaddr, &destmac); - - /* Convert the outgoing packet into a frame list. */ - - (void)sixlowpan_queue_frames( - (FAR struct ieee802154_driver_s *)dev, ipv6hdr, - dev->d_buf + hdrlen, dev->d_len - hdrlen, &destmac); - } + struct rimeaddr_s destmac; + + /* Get the Rime MAC address of the destination. This assumes an + * encoding of the MAC address in the IPv6 address. + */ + + sixlowpan_rimefromip(ipv6hdr->destipaddr, &destmac); + + /* Convert the outgoing packet into a frame list. */ + + (void)sixlowpan_queue_frames( + (FAR struct ieee802154_driver_s *)dev, ipv6hdr, + dev->d_buf, dev->d_len, &destmac); } } -- GitLab From 1f394a61b3cce387ff6020a4d07f6da71729320c Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 4 Apr 2017 12:31:22 -0600 Subject: [PATCH 336/990] 6loWPAN: Add option to dump buffers. Fix some issues with calculation of the IEEE802.15.4 header size. --- net/Kconfig | 2 +- net/sixlowpan/Kconfig | 14 +++- net/sixlowpan/sixlowpan_framelist.c | 13 +++- net/sixlowpan/sixlowpan_framer.c | 26 +++---- net/sixlowpan/sixlowpan_hc06.c | 5 +- net/sixlowpan/sixlowpan_hc1.c | 31 ++++---- net/sixlowpan/sixlowpan_input.c | 114 ++++++++++++++++++++++++++-- net/sixlowpan/sixlowpan_internal.h | 63 ++++++++++----- net/sixlowpan/sixlowpan_tcpsend.c | 11 +++ net/sixlowpan/sixlowpan_udpsend.c | 8 ++ 10 files changed, 228 insertions(+), 59 deletions(-) diff --git a/net/Kconfig b/net/Kconfig index 21ef8b3e7a..da5eab15d2 100644 --- a/net/Kconfig +++ b/net/Kconfig @@ -131,7 +131,7 @@ config NET_ETHERNET no need to define anything special in the configuration file to use Ethernet -- it is the default). -menuconfig NET_6LOWPAN +config NET_6LOWPAN bool "IEEE 802.15.4 6LoWPAN support" default n select NETDEV_MULTINIC if NET_ETHERNET || NET_LOOPBACK || NET_SLIP || NET_TUN diff --git a/net/sixlowpan/Kconfig b/net/sixlowpan/Kconfig index 09bb010c9f..d7635cf362 100644 --- a/net/sixlowpan/Kconfig +++ b/net/sixlowpan/Kconfig @@ -3,7 +3,8 @@ # see the file kconfig-language.txt in the NuttX tools repository. # -if NET_6LOWPAN +menu "6LoWPAN Configuration" + depends on NET_6LOWPAN config NET_6LOWPAN_FRAG bool "6loWPAN Fragmentation" @@ -190,4 +191,13 @@ config NET_6LOWPAN_TCP_RECVWNDO the application is slow to process incoming data, or high (32768 bytes) if the application processes data quickly. -endif # NET_6LOWPAN +config NET_6LOWPAN_DUMPBUFFER + bool "Enable dumping of buffer data" + default n + depends on DEBUG_NET_INFO + ---help--- + Enable dumping of all packet and frame buffers coming into and out + of the 6loWPAN logic. This will generate a large volume of data if + selected. + +endmenu # 6LoWPAN Configuration diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c index 0c6519e8fe..7275f21ac3 100644 --- a/net/sixlowpan/sixlowpan_framelist.c +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -261,12 +261,12 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, /* Pre-calculate frame header length. */ - framer_hdrlen = sixlowpan_hdrlen(ieee, ieee->i_panid); + framer_hdrlen = sixlowpan_send_hdrlen(ieee, ieee->i_panid); if (framer_hdrlen < 0) { /* Failed to determine the size of the header failed. */ - nerr("ERROR: sixlowpan_hdrlen() failed: %d\n", framer_hdrlen); + nerr("ERROR: sixlowpan_send_hdrlen() failed: %d\n", framer_hdrlen); return framer_hdrlen; } @@ -340,6 +340,8 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, ninfo("First fragment: length %d, tag %d\n", g_rime_payloadlen, ieee->i_dgramtag); + sixlowpan_dumpbuffer("Outgoing frame", + (FAR const uint8_t *)iob->io_data, iob->io_len); /* Add the first frame to the IOB queue */ @@ -412,6 +414,9 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, ninfo("sixlowpan output: fragment offset %d, length %d, tag %d\n", outlen >> 3, g_rime_payloadlen, ieee->i_dgramtag); + sixlowpan_dumpbuffer("Outgoing frame", + (FAR const uint8_t *)iob->io_data, + iob->io_len); /* Add the next frame to the tail of the IOB queue */ @@ -449,6 +454,10 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, buflen - g_uncomp_hdrlen); iob->io_len = buflen - g_uncomp_hdrlen + g_frame_hdrlen; + ninfo("Non-fragmented: length %d\n", iob->io_len); + sixlowpan_dumpbuffer("Outgoing frame", + (FAR const uint8_t *)iob->io_data, iob->io_len); + /* Add the first frame to the IOB queue */ ieee->i_framelist = iob; diff --git a/net/sixlowpan/sixlowpan_framer.c b/net/sixlowpan/sixlowpan_framer.c index ad502ebbc9..1adad943ab 100644 --- a/net/sixlowpan/sixlowpan_framer.c +++ b/net/sixlowpan/sixlowpan_framer.c @@ -383,7 +383,7 @@ static void sixlowpan_setup_params(FAR struct ieee802154_driver_s *ieee, ****************************************************************************/ /**************************************************************************** - * Function: sixlowpan_hdrlen + * Function: sixlowpan_send_hdrlen * * Description: * This function is before the first frame has been sent in order to @@ -401,7 +401,7 @@ static void sixlowpan_setup_params(FAR struct ieee802154_driver_s *ieee, * ****************************************************************************/ -int sixlowpan_hdrlen(FAR struct ieee802154_driver_s *ieee, +int sixlowpan_send_hdrlen(FAR struct ieee802154_driver_s *ieee, uint16_t dest_panid) { struct frame802154_s params; @@ -453,18 +453,18 @@ int sixlowpan_802154_framecreate(FAR struct frame802154_s *finfo, return 0; } - /* OK, now we have field lengths. Time to actually construct - * the outgoing frame, and store it in the provided buffer + /* OK, now we have field lengths. Time to actually construct the outgoing + * frame, and store it in the provided buffer */ - buf[0] = (finfo->fcf.frame_type & 7) | - ((finfo->fcf.security_enabled & 1) << 3) | - ((finfo->fcf.frame_pending & 1) << 4) | - ((finfo->fcf.ack_required & 1) << 5) | - ((finfo->fcf.panid_compression & 1) << 6); - buf[1] = ((finfo->fcf.dest_addr_mode & 3) << 2) | - ((finfo->fcf.frame_version & 3) << 4) | - ((finfo->fcf.src_addr_mode & 3) << 6); + buf[0] = ((finfo->fcf.frame_type & 7) << FRAME802154_FRAMETYPE_SHIFT) | + ((finfo->fcf.security_enabled & 1) << FRAME802154_SECENABLED_SHIFT) | + ((finfo->fcf.frame_pending & 1) << FRAME802154_FRAMEPENDING_SHIFT) | + ((finfo->fcf.ack_required & 1) << FRAME802154_ACKREQUEST_SHIFT) | + ((finfo->fcf.panid_compression & 1) << FRAME802154_PANIDCOMP_SHIFT); + buf[1] = ((finfo->fcf.dest_addr_mode & 3) << FRAME802154_DSTADDR_SHIFT) | + ((finfo->fcf.frame_version & 3) << FRAME802154_VERSION_SHIFT) | + ((finfo->fcf.src_addr_mode & 3) << FRAME802154_SRCADDR_SHIFT); /* Sequence number */ @@ -483,7 +483,7 @@ int sixlowpan_802154_framecreate(FAR struct frame802154_s *finfo, for (i = flen.dest_addr_len; i > 0; i--) { - buf[pos++] = finfo->dest_addr[i - 1]; + buf[pos++] = finfo->dest_addr[i - 1]; } /* Source PAN ID */ diff --git a/net/sixlowpan/sixlowpan_hc06.c b/net/sixlowpan/sixlowpan_hc06.c index a713e32807..f5d8396e91 100644 --- a/net/sixlowpan/sixlowpan_hc06.c +++ b/net/sixlowpan/sixlowpan_hc06.c @@ -455,8 +455,9 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, uint8_t iphc1; uint8_t tmp; - ninfodumpbuffer("IPv6 before compression", (FAR const uint8_t *)ipv6, - sizeof(struct ipv6_hdr_s)); + sixlowpan_dumpbuffer("IPv6 before compression", + (FAR const uint8_t *)ipv6, + sizeof(struct ipv6_hdr_s)); g_hc06ptr = fptr + 2; diff --git a/net/sixlowpan/sixlowpan_hc1.c b/net/sixlowpan/sixlowpan_hc1.c index 67fa142cf7..a7040d5bcb 100644 --- a/net/sixlowpan/sixlowpan_hc1.c +++ b/net/sixlowpan/sixlowpan_hc1.c @@ -119,7 +119,7 @@ * ipv6 - The IPv6 header to be compressed * destmac - L2 destination address, needed to compress the IP * destination field - * fptr - Pointer to frame data payload. + * fptr - Pointer to frame to be compressed. * * Returned Value: * None @@ -144,15 +144,18 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, ipv6->proto != IP_PROTO_TCP)) { /* IPV6 DISPATCH - * Something cannot be compressed, use IPV6 DISPATCH, - * compress nothing, copy IPv6 header in rime buffer + * Something cannot be compressed, use IPV6 DISPATCH, compress + * nothing, copy IPv6 header in rime buffer */ - *fptr = SIXLOWPAN_DISPATCH_IPV6; - g_frame_hdrlen += SIXLOWPAN_IPV6_HDR_LEN; - memcpy(fptr + g_frame_hdrlen, ipv6, IPv6_HDRLEN); - g_frame_hdrlen += IPv6_HDRLEN; - g_uncomp_hdrlen += IPv6_HDRLEN; + /* IPv6 dispatch header (1 byte) */ + + hc1[RIME_HC1_DISPATCH] = SIXLOWPAN_DISPATCH_IPV6; + g_frame_hdrlen += SIXLOWPAN_IPV6_HDR_LEN; + + memcpy(fptr + g_frame_hdrlen, ipv6, IPv6_HDRLEN); + g_frame_hdrlen += IPv6_HDRLEN; + g_uncomp_hdrlen += IPv6_HDRLEN; } else { @@ -169,8 +172,8 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, /* HC1 encoding and ttl */ hc1[RIME_HC1_ENCODING] = 0xfc; - hc1[RIME_HC1_TTL] = ipv6->ttl; - g_frame_hdrlen += SIXLOWPAN_HC1_HDR_LEN; + hc1[RIME_HC1_TTL] = ipv6->ttl; + g_frame_hdrlen += SIXLOWPAN_HC1_HDR_LEN; break; #if CONFIG_NET_TCP @@ -178,8 +181,8 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, /* HC1 encoding and ttl */ hc1[RIME_HC1_ENCODING] = 0xfe; - hc1[RIME_HC1_TTL] = ipv6->ttl; - g_frame_hdrlen += SIXLOWPAN_HC1_HDR_LEN; + hc1[RIME_HC1_TTL] = ipv6->ttl; + g_frame_hdrlen += SIXLOWPAN_HC1_HDR_LEN; break; #endif /* CONFIG_NET_TCP */ @@ -217,8 +220,8 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, memcpy(&hcudp[RIME_HC1_HC_UDP_CHKSUM], &udp->udpchksum, 2); - g_frame_hdrlen += SIXLOWPAN_HC1_HC_UDP_HDR_LEN; - g_uncomp_hdrlen += UDP_HDRLEN; + g_frame_hdrlen += SIXLOWPAN_HC1_HC_UDP_HDR_LEN; + g_uncomp_hdrlen += UDP_HDRLEN; } else { diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index a098e69dc1..5d0eaa5869 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -87,6 +87,94 @@ #define IPv6BUF(dev) ((FAR struct ipv6_hdr_s *)((dev)->d_buf)) +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: sixlowpan_recv_hdrlen + * + * Description: + * Get the length of the IEEE802.15.4 header on the received frame. + * + * Input Parameters: + * ieee - The IEEE802.15.4 MAC network driver interface. + * iob - The IOB containing the frame. + * + * Returned Value: + * Ok is returned on success; Othewise a negated errno value is returned. + * + * Assumptions: + * Network is locked + * + ****************************************************************************/ + +int sixlowpan_recv_hdrlen(FAR const uint8_t *fptr) +{ + uint16_t hdrlen; + uint8_t addrmode; + + /* Minimum header: 2 byte FCF + 1 byte sequence number */ + + hdrlen = 3; + + /* Account for destination address size */ + + addrmode = (fptr[1] & FRAME802154_DSTADDR_MASK) >> FRAME802154_DSTADDR_SHIFT; + if (addrmode == FRAME802154_SHORTADDRMODE) + { + /* 2 byte dest PAN + 2 byte dest short address */ + + hdrlen += 4; + } + else if (addrmode == FRAME802154_LONGADDRMODE) + { + /* 2 byte dest PAN + 6 byte dest long address */ + + hdrlen += 10; + } + else if (addrmode != FRAME802154_NOADDR) + { + nwarn("WARNING: Unrecognized address mode\n"); + + return -ENOSYS; + } + else if ((fptr[0] & (1 << FRAME802154_PANIDCOMP_SHIFT)) != 0) + { + nwarn("WARNING: PAN compression, but no destination address\n"); + + return -EINVAL; + } + + /* Account for source address size */ + + addrmode = (fptr[1] & FRAME802154_SRCADDR_MASK) >> FRAME802154_SRCADDR_SHIFT; + if (addrmode == FRAME802154_NOADDR) + { + return hdrlen; + } + else + { + if ((fptr[0] & (1 << FRAME802154_PANIDCOMP_SHIFT)) == 0) + { + hdrlen += 2; + } + + /* Add the length of the source address */ + + if (addrmode == FRAME802154_SHORTADDRMODE) + { + return hdrlen + 2; + } + else if (addrmode == FRAME802154_LONGADDRMODE) + { + return hdrlen + 8; + } + } + + return 0; +} + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -128,6 +216,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, uint8_t fragoffset = 0; /* Offset of the fragment in the IP packet */ bool isfrag = false; int reqsize; /* Required buffer size */ + int hdrsize; /* Size of the IEEE802.15.4 header */ #if CONFIG_NET_6LOWPAN_FRAG bool isfirstfrag = false; @@ -141,11 +230,18 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, */ g_uncomp_hdrlen = 0; - g_frame_hdrlen = 0; + g_frame_hdrlen = 0; - /* The MAC puts the 15.4 payload inside the RIME data buffer */ + /* Get a pointer to the payload following the IEEE802.15.4 frame header. */ - payptr = &iob->io_data[PACKETBUF_HDR_SIZE]; + hdrsize = sixlowpan_recv_hdrlen(iob->io_data); + if (hdrsize < 0) + { + nwarn("Invalid IEEE802.15.2 header: %d\n", hdrsize); + return hdrsize; + } + + payptr = &iob->io_data[hdrsize]; #if CONFIG_NET_6LOWPAN_FRAG /* Since we don't support the mesh and broadcast header, the first header @@ -476,8 +572,9 @@ copypayload: } #endif /* CONFIG_NET_6LOWPAN_FRAG */ - ninfodumpbuffer("IPv6 header", (FAR const uint8_t *)IPv6BUF(&ieee->i_dev), - IPv6_HDRLEN); + sixlowpan_dumpbuffer("IPv6 header", + (FAR const uint8_t *)IPv6BUF(&ieee->i_dev), + IPv6_HDRLEN); return OK; } @@ -497,6 +594,10 @@ copypayload: static int sixlowpan_dispatch(FAR struct ieee802154_driver_s *ieee) { + sixlowpan_dumpbuffer("Incoming packet", + (FAR const uint8_t *)IPv6BUF(&ieee->i_dev), + ieee->i_dev.d_len); + #ifdef CONFIG_NET_PKT /* When packet sockets are enabled, feed the frame into the packet tap */ @@ -591,6 +692,9 @@ int sixlowpan_input(FAR struct ieee802154_driver_s *ieee) FRAME_IOB_REMOVE(ieee, iob); DEBUGASSERT(iob != NULL); + sixlowpan_dumpbuffer("Incoming frame", + (FAR const uint8_t *)iob->io_data, iob->io_len); + /* Process the frame, decompressing it into the packet buffer */ ret = sixlowpan_frame_process(ieee, iob); diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index 4a8b4ea0a9..1a4f28056e 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -121,33 +121,47 @@ * IEEE802.15.4 spec for details. */ -#define FRAME802154_BEACONFRAME 0x00 -#define FRAME802154_DATAFRAME 0x01 -#define FRAME802154_ACKFRAME 0x02 -#define FRAME802154_CMDFRAME 0x03 - -#define FRAME802154_BEACONREQ 0x07 - -#define FRAME802154_IEEERESERVED 0x00 -#define FRAME802154_NOADDR 0x00 /* Only valid for ACK or Beacon frames */ -#define FRAME802154_SHORTADDRMODE 0x02 -#define FRAME802154_LONGADDRMODE 0x03 +#define FRAME802154_FRAMETYPE_SHIFT (0) /* Bits 0-2: Frame type */ +#define FRAME802154_FRAMETYPE_MASK (7 << FRAME802154_FRAMETYPE_SHIFT) +#define FRAME802154_SECENABLED_SHIFT (3) /* Bit 3: Security enabled */ +#define FRAME802154_FRAMEPENDING_SHIFT (4) /* Bit 4: Frame pending */ +#define FRAME802154_ACKREQUEST_SHIFT (5) /* Bit 5: ACK request */ +#define FRAME802154_PANIDCOMP_SHIFT (6) /* Bit 6: PANID compression */ + /* Bits 7-9: Reserved */ +#define FRAME802154_DSTADDR_SHIFT (2) /* Bits 10-11: Dest address mode */ +#define FRAME802154_DSTADDR_MASK (3 << FRAME802154_DSTADDR_SHIFT) +#define FRAME802154_VERSION_SHIFT (4) /* Bit 12-13: Frame version */ +#define FRAME802154_VERSION_MASK (3 << FRAME802154_VERSION_SHIFT) +#define FRAME802154_SRCADDR_SHIFT (6) /* Bits 14-15: Source address mode */ +#define FRAME802154_SRCADDR_MASK (3 << FRAME802154_SRCADDR_SHIFT) + +/* Unshifted values for use in struct frame802154_fcf_s */ + +#define FRAME802154_BEACONFRAME (0) +#define FRAME802154_DATAFRAME (1) +#define FRAME802154_ACKFRAME (2) +#define FRAME802154_CMDFRAME (3) + +#define FRAME802154_BEACONREQ (7) + +#define FRAME802154_IEEERESERVED (0) +#define FRAME802154_NOADDR (0) /* Only valid for ACK or Beacon frames */ +#define FRAME802154_SHORTADDRMODE (2) +#define FRAME802154_LONGADDRMODE (3) #define FRAME802154_NOBEACONS 0x0f #define FRAME802154_BROADCASTADDR 0xffff #define FRAME802154_BROADCASTPANDID 0xffff -#define FRAME802154_IEEE802154_2003 0x00 -#define FRAME802154_IEEE802154_2006 0x01 +#define FRAME802154_IEEE802154_2003 (0) +#define FRAME802154_IEEE802154_2006 (1) -#define FRAME802154_SECURITY_LEVEL_NONE 0 -#define FRAME802154_SECURITY_LEVEL_128 3 +#define FRAME802154_SECURITY_LEVEL_NONE (0) +#define FRAME802154_SECURITY_LEVEL_128 (3) /* Packet buffer Definitions */ -#define PACKETBUF_HDR_SIZE 48 - #define PACKETBUF_ATTR_PACKET_TYPE_DATA 0 #define PACKETBUF_ATTR_PACKET_TYPE_ACK 1 #define PACKETBUF_ATTR_PACKET_TYPE_STREAM 2 @@ -295,6 +309,14 @@ } \ while(0) +/* Debug ********************************************************************/ + +#ifdef CONFIG_NET_6LOWPAN_DUMPBUFFER +# define sixlowpan_dumpbuffer(m,b,s) ninfodumpbuffer(m,b,s) +#else +# define sixlowpan_dumpbuffer(m,b,s) +#endif + /**************************************************************************** * Public Types ****************************************************************************/ @@ -492,7 +514,7 @@ int sixlowpan_send(FAR struct net_driver_s *dev, uint16_t timeout); /**************************************************************************** - * Function: sixlowpan_hdrlen + * Function: sixlowpan_send_hdrlen * * Description: * This function is before the first frame has been sent in order to @@ -510,7 +532,7 @@ int sixlowpan_send(FAR struct net_driver_s *dev, * ****************************************************************************/ -int sixlowpan_hdrlen(FAR struct ieee802154_driver_s *ieee, +int sixlowpan_send_hdrlen(FAR struct ieee802154_driver_s *ieee, uint16_t dest_panid); /**************************************************************************** @@ -617,7 +639,7 @@ void sixlowpan_hc06_initialize(void); * ipv6 - The IPv6 header to be compressed * destmac - L2 destination address, needed to compress the IP * destination field - * fptr - Pointer to frame data payload. + * fptr - Pointer to frame to be compressed. * * Returned Value: * None @@ -678,6 +700,7 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, * ipv6 - The IPv6 header to be compressed * destmac - L2 destination address, needed to compress the IP * destination field + * fptr - Pointer to frame to be compressed. * * Returned Value: * None diff --git a/net/sixlowpan/sixlowpan_tcpsend.c b/net/sixlowpan/sixlowpan_tcpsend.c index c075a3b827..1ad8068a31 100644 --- a/net/sixlowpan/sixlowpan_tcpsend.c +++ b/net/sixlowpan/sixlowpan_tcpsend.c @@ -55,6 +55,14 @@ #if defined(CONFIG_NET_6LOWPAN) && defined(CONFIG_NET_TCP) +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Buffer access helpers */ + +#define IPv6BUF(dev) ((FAR struct ipv6_hdr_s *)((dev)->d_buf)) + /**************************************************************************** * Private Functions ****************************************************************************/ @@ -156,6 +164,7 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, int ret; ninfo("buflen %lu\n", (unsigned long)buflen); + sixlowpan_dumpbuffer("Outgoing TCP payload", buf, buflen); DEBUGASSERT(psock != NULL && psock->s_crefs > 0); DEBUGASSERT(psock->s_type == SOCK_STREAM); @@ -368,6 +377,8 @@ void sixlowpan_tcp_send(FAR struct net_driver_s *dev) /* Double check */ ninfo("d_len %u\n", dev->d_len); + sixlowpan_dumpbuffer("Outgoing TCP packet", + (FAR const uint8_t *)IPv6BUF(dev), dev->d_len); if (dev != NULL && dev->d_len > 0) { diff --git a/net/sixlowpan/sixlowpan_udpsend.c b/net/sixlowpan/sixlowpan_udpsend.c index 53c7ead6ce..717df424a2 100644 --- a/net/sixlowpan/sixlowpan_udpsend.c +++ b/net/sixlowpan/sixlowpan_udpsend.c @@ -167,9 +167,13 @@ ssize_t psock_6lowpan_udp_sendto(FAR struct socket *psock, uint16_t timeout; int ret; + ninfo("buflen %lu\n", (unsigned long)buflen); + DEBUGASSERT(psock != NULL && psock->s_crefs > 0 && to != NULL); DEBUGASSERT(psock->s_type == SOCK_DGRAM); + sixlowpan_dumpbuffer("Outgoing UDP payload", buf, buflen); + if (psock == NULL || to == NULL) { return (ssize_t)-EINVAL; @@ -352,9 +356,13 @@ ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf, FAR struct udp_conn_s *conn; struct sockaddr_in6 to; + ninfo("buflen %lu\n", (unsigned long)buflen); + DEBUGASSERT(psock != NULL && psock->s_crefs > 0); DEBUGASSERT(psock->s_type == SOCK_DGRAM); + sixlowpan_dumpbuffer("Outgoing UDP payload", buf, buflen); + /* Make sure that this is a valid socket */ if (psock != NULL || psock->s_crefs <= 0) -- GitLab From fdf706a3a9ca41880aa6c88d202ec064cba3b8cf Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 4 Apr 2017 13:52:02 -0600 Subject: [PATCH 337/990] 6loWPAN: Additional fixes related to buffer offsets primarily. --- net/sixlowpan/sixlowpan_framelist.c | 24 +++++++++++++----------- net/sixlowpan/sixlowpan_input.c | 19 ++++++++++--------- 2 files changed, 23 insertions(+), 20 deletions(-) diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c index 7275f21ac3..f1e1250b55 100644 --- a/net/sixlowpan/sixlowpan_framelist.c +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -234,6 +234,19 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, ninfo("Sending packet length %d\n", buflen); + /* Pre-calculate frame header length. */ + + framer_hdrlen = sixlowpan_send_hdrlen(ieee, ieee->i_panid); + if (framer_hdrlen < 0) + { + /* Failed to determine the size of the header failed. */ + + nerr("ERROR: sixlowpan_send_hdrlen() failed: %d\n", framer_hdrlen); + return framer_hdrlen; + } + + g_frame_hdrlen = framer_hdrlen; + #ifndef CONFIG_NET_6LOWPAN_COMPRESSION_IPv6 if (buflen >= CONFIG_NET_6LOWPAN_COMPRESSION_THRESHOLD) { @@ -259,17 +272,6 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, rimeaddr_copy(&g_pktaddrs[PACKETBUF_ADDR_RECEIVER], destmac); - /* Pre-calculate frame header length. */ - - framer_hdrlen = sixlowpan_send_hdrlen(ieee, ieee->i_panid); - if (framer_hdrlen < 0) - { - /* Failed to determine the size of the header failed. */ - - nerr("ERROR: sixlowpan_send_hdrlen() failed: %d\n", framer_hdrlen); - return framer_hdrlen; - } - /* Check if we need to fragment the packet into several frames */ if ((int)buflen - (int)g_uncomp_hdrlen > diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index 5d0eaa5869..616a464ea9 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -461,7 +461,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, if (hc1[RIME_HC1_DISPATCH] == SIXLOWPAN_DISPATCH_IPV6) { ninfo("IPV6 Dispatch\n"); - g_frame_hdrlen += SIXLOWPAN_IPV6_HDR_LEN; + g_frame_hdrlen += SIXLOWPAN_IPV6_HDR_LEN; /* Put uncompressed IP header in d_buf. */ @@ -469,7 +469,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, /* Update g_uncomp_hdrlen and g_frame_hdrlen. */ - g_frame_hdrlen += IPv6_HDRLEN; + g_frame_hdrlen += IPv6_HDRLEN; g_uncomp_hdrlen += IPv6_HDRLEN; } else @@ -484,19 +484,20 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, copypayload: #endif /* CONFIG_NET_6LOWPAN_FRAG */ - /* Copy "payload" from the rime buffer to the d_buf. If this frame is a - * first fragment or not part of a fragmented packet, we have already - * copied the compressed headers, g_uncomp_hdrlen and g_frame_hdrlen are - * non-zerio, fragoffset is. + /* Copy "payload" from the rime buffer to the IEEE802.15.4 MAC drivers + * d_buf. If this frame is a first fragment or not part of a fragmented + * packet, we have already copied the compressed headers, g_uncomp_hdrlen + * and g_frame_hdrlen are non-zerio, fragoffset is. */ - if (ieee->i_dev.d_len < g_frame_hdrlen) + if (g_frame_hdrlen > CONFIG_NET_6LOWPAN_MTU) { - ninfo("SIXLOWPAN: packet dropped due to header > total packet\n"); + nwarn("WARNING: Packet dropped due to header (%u) > packet buffer (%u)\n", + g_frame_hdrlen, CONFIG_NET_6LOWPAN_MTU); return OK; } - g_rime_payloadlen = ieee->i_dev.d_len - g_frame_hdrlen; + g_rime_payloadlen = iob->io_len - g_frame_hdrlen; /* Sanity-check size of incoming packet to avoid buffer overflow */ -- GitLab From 34da085b40fff342d0daf8614057ae681575f88f Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 4 Apr 2017 14:27:21 -0600 Subject: [PATCH 338/990] 6loWPAN: Yet another fix related to buffer offsets primarily. --- net/sixlowpan/sixlowpan_framelist.c | 10 +++++----- net/sixlowpan/sixlowpan_input.c | 2 +- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c index f1e1250b55..58f4ba624e 100644 --- a/net/sixlowpan/sixlowpan_framelist.c +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -115,14 +115,14 @@ static void sixlowpan_compress_ipv6hdr(FAR struct ieee802154_driver_s *ieee, { /* Indicate the IPv6 dispatch and length */ - *fptr = SIXLOWPAN_DISPATCH_IPV6; - g_frame_hdrlen += SIXLOWPAN_IPV6_HDR_LEN; + fptr[g_frame_hdrlen] = SIXLOWPAN_DISPATCH_IPV6; + g_frame_hdrlen += SIXLOWPAN_IPV6_HDR_LEN; /* Copy the IPv6 header and adjust pointers */ - memcpy(fptr + g_frame_hdrlen, destip, IPv6_HDRLEN); - g_frame_hdrlen += IPv6_HDRLEN; - g_uncomp_hdrlen += IPv6_HDRLEN; + memcpy(&fptr[g_frame_hdrlen] , destip, IPv6_HDRLEN); + g_frame_hdrlen += IPv6_HDRLEN; + g_uncomp_hdrlen += IPv6_HDRLEN; } /**************************************************************************** diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index 616a464ea9..ffc85bdfcf 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -440,7 +440,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, hc1 = payptr + g_frame_hdrlen; - #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 +#ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 if ((hc1[RIME_HC1_DISPATCH] & SIXLOWPAN_DISPATCH_IPHC_MASK) == SIXLOWPAN_DISPATCH_IPHC) { ninfo("IPHC Dispatch\n"); -- GitLab From ca2c18c023c7daaf101d2e0fa4637118f8cbaf27 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 4 Apr 2017 16:12:16 -0600 Subject: [PATCH 339/990] 6loWPAN: Fix return value and other issues in sixlowpan_frame_process --- include/nuttx/net/sixlowpan.h | 6 +++--- net/sixlowpan/Kconfig | 2 +- net/sixlowpan/sixlowpan_input.c | 30 +++++++++++++----------------- 3 files changed, 17 insertions(+), 21 deletions(-) diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index 9f051857e4..43a1a9660e 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -66,9 +66,9 @@ /* Min and Max compressible UDP ports - HC06 */ #define SIXLOWPAN_UDP_4_BIT_PORT_MIN 0xf0b0 -#define SIXLOWPAN_UDP_4_BIT_PORT_MAX 0xf0bf /* F0B0 + 15 */ -#define SIXLOWPAN_UDP_8_BIT_PORT_MIN 0xF000 -#define SIXLOWPAN_UDP_8_BIT_PORT_MAX 0xf0ff /* F000 + 255 */ +#define SIXLOWPAN_UDP_4_BIT_PORT_MAX 0xf0bf /* f0b0 + 15 */ +#define SIXLOWPAN_UDP_8_BIT_PORT_MIN 0xf000 +#define SIXLOWPAN_UDP_8_BIT_PORT_MAX 0xf0ff /* f000 + 255 */ /* 6lowpan dispatches */ diff --git a/net/sixlowpan/Kconfig b/net/sixlowpan/Kconfig index d7635cf362..02d17a42f1 100644 --- a/net/sixlowpan/Kconfig +++ b/net/sixlowpan/Kconfig @@ -54,7 +54,7 @@ config NET_6LOWPAN_COMPRESSION_THRESHOLD config NET_6LOWPAN_MINPORT hex "Minimum port nubmer" - default 0x5471 + default 0xf0b0 depends on NET_6LOWPAN_COMPRESSION_HC1 ---help--- HC1 compression of UDP headersis feasible only if both src and dest diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index ffc85bdfcf..2018cc1376 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -356,7 +356,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, else if (fragsize == 0) { nwarn("WARNING: Dropping zero-length 6loWPAN fragment\n"); - return OK; + return INPUT_PARTIAL; } /* A non-zero, first fragement received while we are in the middle of @@ -381,7 +381,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, nwarn("WARNING: Dropping 6loWPAN packet that is not a fragment of " "the packet currently being reassembled\n"); - return OK; + return INPUT_PARTIAL; } else { @@ -507,7 +507,7 @@ copypayload: ninfo("Required buffer size: %d+%d+%d=%d Available: %d\n", g_uncomp_hdrlen, (int)(fragoffset << 3), g_rime_payloadlen, reqsize, CONFIG_NET_6LOWPAN_MTU); - return OK; + return -ENOMEM; } memcpy((FAR uint8_t *)ieee->i_dev.d_buf + g_uncomp_hdrlen + @@ -545,12 +545,10 @@ copypayload: ieee->i_accumlen, g_rime_payloadlen); } else -#endif /* CONFIG_NET_6LOWPAN_FRAG */ { ieee->i_pktlen = g_rime_payloadlen + g_uncomp_hdrlen; } -#if CONFIG_NET_6LOWPAN_FRAG /* If we have a full IP packet in sixlowpan_buf, deliver it to * the IP stack */ @@ -560,23 +558,21 @@ copypayload: if (ieee->i_accumlen == 0 || ieee->i_accumlen == ieee->i_pktlen) { - FAR struct ipv6_hdr_s *ipv6 = IPv6BUF(&ieee->i_dev); - ninfo("IP packet ready (length %d)\n", ieee->i_pktlen); - /* REVISIT -- clearly wrong. */ - memcpy((FAR uint8_t *)ipv6, (FAR uint8_t *)ipv6, ieee->i_pktlen); + ieee->i_dev.d_len = ieee->i_pktlen; + ieee->i_pktlen = 0; + ieee->i_accumlen = 0; + return INPUT_COMPLETE; + } - ieee->i_pktlen = 0; - ieee->i_accumlen = 0; + return INPUT_PARTIAL; +#else + /* Deliver the packet to the IP stack */ - } + ieee->i_dev.d_len = g_rime_payloadlen + g_uncomp_hdrlen; + return INPUT_COMPLETE; #endif /* CONFIG_NET_6LOWPAN_FRAG */ - - sixlowpan_dumpbuffer("IPv6 header", - (FAR const uint8_t *)IPv6BUF(&ieee->i_dev), - IPv6_HDRLEN); - return OK; } /**************************************************************************** -- GitLab From 38eed0a847ddf9c85ebc6e4b8163de338fc76871 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 4 Apr 2017 17:06:17 -0600 Subject: [PATCH 340/990] 6loWPAN: Various fixes for building with different configurations; Some minimal testing of HC06 --- include/nuttx/net/sixlowpan.h | 12 ++++++------ net/sixlowpan/sixlowpan_framelist.c | 5 ++++- net/sixlowpan/sixlowpan_hc06.c | 8 ++++---- net/sixlowpan/sixlowpan_input.c | 14 +++++++------- net/sixlowpan/sixlowpan_internal.h | 2 +- 5 files changed, 22 insertions(+), 19 deletions(-) diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index 43a1a9660e..5f73d9cdb1 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -364,6 +364,12 @@ struct ieee802154_driver_s uint8_t i_dsn; +#if CONFIG_NET_6LOWPAN_FRAG + /* Fragmentation Support *************************************************/ + /* Fragmentation is handled frame by frame and requires that certain + * state information be retained from frame to frame. + */ + /* i_dgramtag. Datagram tag to be put in the header of the set of * fragments. It is used by the recipient to match fragments of the * same payload. @@ -371,12 +377,6 @@ struct ieee802154_driver_s uint16_t i_dgramtag; -#if CONFIG_NET_6LOWPAN_FRAG - /* Fragmentation Support *************************************************/ - /* Fragementation is handled frame by frame and requires that certain - * state information be retained from frame to frame. - */ - /* i_pktlen. The total length of the IPv6 packet to be re-assembled in * d_buf. */ diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c index 58f4ba624e..11a98274ad 100644 --- a/net/sixlowpan/sixlowpan_framelist.c +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -51,6 +51,7 @@ #include #include +#include #include #include @@ -171,7 +172,9 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, FAR uint8_t *fptr; int framer_hdrlen; struct rimeaddr_s bcastmac; +#ifdef CONFIG_NET_6LOWPAN_FRAG uint16_t outlen = 0; +#endif /* Initialize global data. Locking the network guarantees that we have * exclusive use of the global values for intermediate calculations. @@ -278,7 +281,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, (int)CONFIG_NET_6LOWPAN_MAXPAYLOAD - framer_hdrlen - (int)g_frame_hdrlen) { -#if CONFIG_NET_6LOWPAN_FRAG +#ifdef CONFIG_NET_6LOWPAN_FRAG /* ieee->i_framelist will hold the generated frames; frames will be * added at qtail. */ diff --git a/net/sixlowpan/sixlowpan_hc06.c b/net/sixlowpan/sixlowpan_hc06.c index f5d8396e91..98df1c1bd3 100644 --- a/net/sixlowpan/sixlowpan_hc06.c +++ b/net/sixlowpan/sixlowpan_hc06.c @@ -18,7 +18,7 @@ * Joel Hoglund * * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions + * modification, are permitted provided that the following c/onditions * are met: * * 1. Redistributions of source code must retain the above copyright @@ -74,9 +74,9 @@ ****************************************************************************/ #define IPv6BUF(ieee) \ - ((FAR struct ipv6_hdr_s *)&(ieee)->i_dev.d_buf) + ((FAR struct ipv6_hdr_s *)((ieee)->i_dev.d_buf)) #define UDPIPv6BUF(ieee) \ - ((FAR struct udp_hdr_s *)&(ieee)->i_dev.d_buf[IPv6_HDRLEN]) + ((FAR struct udp_hdr_s *)&((ieee)->i_dev.d_buf[IPv6_HDRLEN])) /**************************************************************************** * Private Types @@ -841,7 +841,7 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, uint16_t iplen, FAR struct iob_s *iob, - FAR char *payptr) + FAR uint8_t *payptr) { FAR struct ipv6_hdr_s *ipv6 = IPv6BUF(ieee); FAR uint8_t *iphc = payptr + g_frame_hdrlen; diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index 2018cc1376..c279920e41 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -54,7 +54,7 @@ #include #include -#if CONFIG_NET_6LOWPAN_FRAG +#ifdef CONFIG_NET_6LOWPAN_FRAG # include "nuttx/clock.h" #endif @@ -214,11 +214,11 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, uint16_t fragsize = 0; /* Size of the IP packet (read from fragment) */ uint8_t fragoffset = 0; /* Offset of the fragment in the IP packet */ - bool isfrag = false; int reqsize; /* Required buffer size */ int hdrsize; /* Size of the IEEE802.15.4 header */ -#if CONFIG_NET_6LOWPAN_FRAG +#ifdef CONFIG_NET_6LOWPAN_FRAG + bool isfrag = false; bool isfirstfrag = false; bool islastfrag = false; uint16_t fragtag = 0; /* Tag of the fragment */ @@ -243,7 +243,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, payptr = &iob->io_data[hdrsize]; -#if CONFIG_NET_6LOWPAN_FRAG +#ifdef CONFIG_NET_6LOWPAN_FRAG /* Since we don't support the mesh and broadcast header, the first header * we look for is the fragmentation header */ @@ -285,7 +285,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, g_frame_hdrlen += SIXLOWPAN_FRAGN_HDR_LEN; - ninfo("islastfrag?: i_accumlen %d g_rime_payloadlen %d fragsize %d\n", + ninfo("FRAGN: i_accumlen %d g_rime_payloadlen %d fragsize %d\n", ieee->i_accumlen, iob->io_len - g_frame_hdrlen, fragsize); /* Indicate that this frame is a another fragment for reassembly */ @@ -480,7 +480,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, return OK; } -#if CONFIG_NET_6LOWPAN_FRAG +#ifdef CONFIG_NET_6LOWPAN_FRAG copypayload: #endif /* CONFIG_NET_6LOWPAN_FRAG */ @@ -514,7 +514,7 @@ copypayload: (int)(fragoffset << 3), payptr + g_frame_hdrlen, g_rime_payloadlen); -#if CONFIG_NET_6LOWPAN_FRAG +#ifdef CONFIG_NET_6LOWPAN_FRAG /* Update ieee->i_accumlen if the frame is a fragment, ieee->i_pktlen * otherwise. */ diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index 1a4f28056e..4a221f4fa9 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -454,7 +454,7 @@ extern uint8_t g_frame_hdrlen; /* Offset first available byte for the payload after header region. */ -uint8_t g_dataoffset; +extern uint8_t g_dataoffset; /* Packet buffer metadata: Attributes and addresses */ -- GitLab From 64a43627a20b96b7e2dfff269c9edf01d41f86bb Mon Sep 17 00:00:00 2001 From: Hidetaka Takano Date: Wed, 5 Apr 2017 19:53:54 +0900 Subject: [PATCH 341/990] Fixed gconfig target. --- Makefile.unix | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Makefile.unix b/Makefile.unix index 220740c5bd..d816947a38 100644 --- a/Makefile.unix +++ b/Makefile.unix @@ -498,7 +498,7 @@ do_qconfig: dirlinks apps_preconfig qconfig: do_qconfig clean_context -gconfig: dirlinks apps_preconfig +do_gconfig: dirlinks apps_preconfig $(Q) APPSDIR=${CONFIG_APPS_DIR} kconfig-gconf Kconfig gconfig: do_gconfig clean_context -- GitLab From bff341fdfcbaed6cf884647ead12b5a7d8d8b867 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Wed, 5 Apr 2017 07:15:19 -0600 Subject: [PATCH 342/990] stm32: stm32l15xx_rcc: add support for using MSI as system clock --- arch/arm/src/stm32/stm32l15xxx_rcc.c | 17 +++++++++++------ 1 file changed, 11 insertions(+), 6 deletions(-) diff --git a/arch/arm/src/stm32/stm32l15xxx_rcc.c b/arch/arm/src/stm32/stm32l15xxx_rcc.c index 51a163d99a..fce96fa6e6 100644 --- a/arch/arm/src/stm32/stm32l15xxx_rcc.c +++ b/arch/arm/src/stm32/stm32l15xxx_rcc.c @@ -579,12 +579,11 @@ static void stm32_stdclockconfig(void) #endif - /* Enable the source clock for the PLL (via HSE or HSI), HSE, and HSI. - * NOTE that only PLL, HSE, or HSI are supported for the system clock - * in this implementation - */ + /* Enable the source clock for the PLL (via HSE or HSI), HSE, and HSI. */ + +#if (STM32_SYSCLK_SW == RCC_CFGR_SW_HSE) || \ + ((STM32_SYSCLK_SW == RCC_CFGR_SW_PLL) && (STM32_CFGR_PLLSRC == RCC_CFGR_PLLSRC)) -#if (STM32_CFGR_PLLSRC == RCC_CFGR_PLLSRC) || (STM32_SYSCLK_SW == RCC_CFGR_SW_HSE) /* The PLL is using the HSE, or the HSE is the system clock. In either * case, we need to enable HSE clocking. */ @@ -599,7 +598,9 @@ static void stm32_stdclockconfig(void) return; } -#elif (STM32_CFGR_PLLSRC == 0) || (STM32_SYSCLK_SW == RCC_CFGR_SW_HSI) +#elif (STM32_SYSCLK_SW == RCC_CFGR_SW_HSI) || \ + ((STM32_SYSCLK_SW == RCC_CFGR_SW_PLL) && STM32_CFGR_PLLSRC == 0) + /* The PLL is using the HSI, or the HSI is the system clock. In either * case, we need to enable HSI clocking. */ @@ -616,6 +617,8 @@ static void stm32_stdclockconfig(void) #endif +#if (STM32_SYSCLK_SW != RCC_CFGR_SW_MSI) + /* Increasing the CPU frequency (in the same voltage range): * * After reset, the used clock is the MSI (2 MHz) with 0 WS configured in the @@ -651,6 +654,8 @@ static void stm32_stdclockconfig(void) regval |= FLASH_ACR_PRFTEN; putreg32(regval, STM32_FLASH_ACR); +#endif /* STM32_SYSCLK_SW != RCC_CFGR_SW_MSI */ + /* Set the HCLK source/divider */ regval = getreg32(STM32_RCC_CFGR); -- GitLab From 3e6b92d5fadbd01c4d62e44d0f5aa1d30a11de7b Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Wed, 5 Apr 2017 07:20:31 -0600 Subject: [PATCH 343/990] tm32: stm32l15xxx_rcc: configure medium performance voltage range and zero wait-state when allowed by SYSCLK setting Zero wait-state for flash can be configured when: Range 1 and SYSCLK <= 16 Mhz Range 2 and SYSCLK <= 8 Mhz Range 3 and SYSCLK <= 4.2 Mhz Medium performance voltage range (1.5V) can be configured when SYSCLK is up to 16 Mhz and PLLVCO up to 48 Mhz. --- arch/arm/src/stm32/stm32l15xxx_rcc.c | 43 ++++++++++++++++++++++++++-- 1 file changed, 40 insertions(+), 3 deletions(-) diff --git a/arch/arm/src/stm32/stm32l15xxx_rcc.c b/arch/arm/src/stm32/stm32l15xxx_rcc.c index fce96fa6e6..2624fade10 100644 --- a/arch/arm/src/stm32/stm32l15xxx_rcc.c +++ b/arch/arm/src/stm32/stm32l15xxx_rcc.c @@ -524,6 +524,8 @@ static void stm32_stdclockconfig(void) #if defined(CONFIG_RTC_HSECLOCK) || defined(CONFIG_LCD_HSECLOCK) uint16_t pwrcr; #endif + uint32_t pwr_vos; + bool flash_1ws; /* Enable PWR clock from APB1 to give access to PWR_CR register */ @@ -537,12 +539,39 @@ static void stm32_stdclockconfig(void) * Range 1: PLLVCO up to 96MHz in range 1 (1.8V) * Range 2: PLLVCO up to 48MHz in range 2 (1.5V) (default) * Range 3: PLLVCO up to 24MHz in range 3 (1.2V) + * + * Range 1: SYSCLK up to 32Mhz + * Range 2: SYSCLK up to 16Mhz + * Range 3: SYSCLK up to 4.2Mhz + * + * Range 1: Flash 1WS if SYSCLK > 16Mhz + * Range 2: Flash 1WS if SYSCLK > 8Mhz + * Range 3: Flash 1WS if SYSCLK > 2.1Mhz */ -#if STM32_PLL_FREQUENCY > 48000000 - stm32_pwr_setvos(PWR_CR_VOS_SCALE_1); + pwr_vos = PWR_CR_VOS_SCALE_2; + flash_1ws = false; + +#ifdef STM32_PLL_FREQUENCY + if (STM32_PLL_FREQUENCY > 48000000) + { + pwr_vos = PWR_CR_VOS_SCALE_1; + } #endif + if (STM32_SYSCLK_FREQUENCY > 16000000) + { + pwr_vos = PWR_CR_VOS_SCALE_1; + } + + if ((pwr_vos == PWR_CR_VOS_SCALE_1 && STM32_SYSCLK_FREQUENCY > 16000000) || + (pwr_vos == PWR_CR_VOS_SCALE_2 && STM32_SYSCLK_FREQUENCY > 8000000)) + { + flash_1ws = true; + } + + stm32_pwr_setvos(pwr_vos); + #if defined(CONFIG_RTC_HSECLOCK) || defined(CONFIG_LCD_HSECLOCK) /* If RTC / LCD selects HSE as clock source, the RTC prescaler * needs to be set before HSEON bit is set. @@ -646,7 +675,15 @@ static void stm32_stdclockconfig(void) regval |= FLASH_ACR_ACC64; /* 64-bit access mode */ putreg32(regval, STM32_FLASH_ACR); - regval |= FLASH_ACR_LATENCY; /* One wait state */ + if (flash_1ws) + { + regval |= FLASH_ACR_LATENCY; /* One wait state */ + } + else + { + regval &= ~FLASH_ACR_LATENCY; /* Zero wait state */ + } + putreg32(regval, STM32_FLASH_ACR); /* Enable FLASH prefetch */ -- GitLab From 3b21545480b53ca401491ac19ffd197f5258b659 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 5 Apr 2017 08:40:30 -0600 Subject: [PATCH 344/990] sixlowpan: Minor reorganization to removed some unused global varialbes and structure fields. --- net/sixlowpan/sixlowpan_framelist.c | 1 - net/sixlowpan/sixlowpan_framer.c | 45 +++++++---------------------- net/sixlowpan/sixlowpan_globals.c | 4 --- net/sixlowpan/sixlowpan_internal.h | 35 ---------------------- net/sixlowpan/sixlowpan_utils.c | 34 ---------------------- 5 files changed, 11 insertions(+), 108 deletions(-) diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c index 11a98274ad..bd4dd2e8eb 100644 --- a/net/sixlowpan/sixlowpan_framelist.c +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -180,7 +180,6 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, * exclusive use of the global values for intermediate calculations. */ - FRAME_RESET(); g_uncomp_hdrlen = 0; g_frame_hdrlen = 0; diff --git a/net/sixlowpan/sixlowpan_framer.c b/net/sixlowpan/sixlowpan_framer.c index 1adad943ab..b0953db648 100644 --- a/net/sixlowpan/sixlowpan_framer.c +++ b/net/sixlowpan/sixlowpan_framer.c @@ -287,7 +287,7 @@ static int sixlowpan_802154_hdrlen(FAR struct frame802154_s *finfo) ****************************************************************************/ static void sixlowpan_setup_params(FAR struct ieee802154_driver_s *ieee, - FAR struct iob_s *iob, uint16_t dest_panid, + uint16_t dest_panid, FAR struct frame802154_s *params) { bool rcvrnull; @@ -296,10 +296,6 @@ static void sixlowpan_setup_params(FAR struct ieee802154_driver_s *ieee, memset(params, 0, sizeof(params)); - /* Reset to an empty frame */ - - FRAME_RESET(); - /* Build the FCF (Only non-zero elements need to be initialized). */ params->fcf.frame_type = FRAME802154_DATAFRAME; @@ -368,14 +364,6 @@ static void sixlowpan_setup_params(FAR struct ieee802154_driver_s *ieee, /* Set the source address to the node address assigned to the device */ rimeaddr_copy((struct rimeaddr_s *)¶ms->src_addr, &ieee->i_nodeaddr.u8); - - /* Configure the (optional) payload address and length */ - - if (iob != NULL) - { - params->payload = FRAME_DATA_START(iob); - params->payload_len = FRAME_DATA_SIZE(iob); - } } /**************************************************************************** @@ -402,13 +390,13 @@ static void sixlowpan_setup_params(FAR struct ieee802154_driver_s *ieee, ****************************************************************************/ int sixlowpan_send_hdrlen(FAR struct ieee802154_driver_s *ieee, - uint16_t dest_panid) + uint16_t dest_panid) { struct frame802154_s params; /* Set up the frame parameters */ - sixlowpan_setup_params(ieee, NULL, dest_panid, ¶ms); + sixlowpan_setup_params(ieee, dest_panid, ¶ms); /* Return the length of the header */ @@ -427,7 +415,7 @@ int sixlowpan_send_hdrlen(FAR struct ieee802154_driver_s *ieee, * the frame to send. * buf - Pointer to the buffer to use for the frame. * buflen - The length of the buffer to use for the frame. - * finfo - I that specifies the frame to send. + * finfo - Specifies the frame to send. * * Returned Value: * The length of the frame header or 0 if there was insufficient space in @@ -539,33 +527,22 @@ int sixlowpan_framecreate(FAR struct ieee802154_driver_s *ieee, FAR struct iob_s *iob, uint16_t dest_panid) { struct frame802154_s params; - int len; - int ret; + int hdrlen; /* Set up the frame parameters */ - sixlowpan_setup_params(ieee, iob, dest_panid, ¶ms); + sixlowpan_setup_params(ieee, dest_panid, ¶ms); /* Get the length of the header */ - len = sixlowpan_802154_hdrlen(¶ms); - - /* Allocate space for the header in the frame buffer */ - - ret = sixlowpan_frame_hdralloc(iob, len); - if (ret < 0) - { - wlerr("ERROR: Header too large: %u\n", len); - return ret; - } + hdrlen = sixlowpan_802154_hdrlen(¶ms); /* Then create the frame */ - sixlowpan_802154_framecreate(¶ms, FRAME_HDR_START(iob), len); + sixlowpan_802154_framecreate(¶ms, iob->io_data, hdrlen); - wlinfo("Frame type: %02x Data len: %d %u (%u)\n", - params.fcf.frame_type, len, FRAME_DATA_SIZE(iob), - FRAME_SIZE(ieee, iob)); + wlinfo("Frame type: %02x hdrlen: %d\n", + params.fcf.frame_type, hdrlen); #if CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 2 wlinfo("Dest address: %02x:%02x\n", params.dest_addr[0], params.dest_addr[1]); @@ -576,7 +553,7 @@ int sixlowpan_framecreate(FAR struct ieee802154_driver_s *ieee, params.dest_addr[6], params.dest_addr[7]); #endif - return len; + return hdrlen; } #endif /* CONFIG_NET_6LOWPAN */ diff --git a/net/sixlowpan/sixlowpan_globals.c b/net/sixlowpan/sixlowpan_globals.c index 274ef47fa7..8f48ade9f2 100644 --- a/net/sixlowpan/sixlowpan_globals.c +++ b/net/sixlowpan/sixlowpan_globals.c @@ -76,10 +76,6 @@ uint8_t g_uncomp_hdrlen; uint8_t g_frame_hdrlen; -/* Offset first available byte for the payload after header region. */ - -uint8_t g_dataoffset; - /* Packet buffer metadata: Attributes and addresses */ uint16_t g_pktattrs[PACKETBUF_NUM_ATTRS]; diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index 4a221f4fa9..8f3e52dfd3 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -215,25 +215,6 @@ #define PACKETBUF_NUM_ADDRS 4 -/* Frame buffer helpers *****************************************************/ - -#define FRAME_RESET() \ - do \ - { \ - g_dataoffset = 0; \ - } \ - while (0) - -#define FRAME_HDR_START(iob) ((iob)->io_data) -#define FRAME_HDR_SIZE(iob) g_dataoffset - -#define FRAME_DATA_START(iob) ((FAR uint8_t *)((iob)->io_data) + g_dataoffset) -#define FRAME_DATA_SIZE(iob) ((iob)->io_len - g_dataoffset) - -#define FRAME_REMAINING(iob) (CONFIG_NET_6LOWPAN_FRAMELEN - (iob)->io_len) -#define FRAME_SIZE(ieee,iob) \ - ((iob)->io_len) - /* Address compressibility test macros **************************************/ /* Check whether we can compress the IID in address 'a' to 16 bits. This is @@ -407,8 +388,6 @@ struct frame802154_s uint16_t src_pid; /* Source PAN ID */ uint8_t src_addr[8]; /* Source address */ struct frame802154_aux_hdr_s aux_hdr; /* Aux security header */ - uint8_t *payload; /* Pointer to 802.15.4 frame payload */ - uint8_t payload_len; /* Length of payload field */ }; /**************************************************************************** @@ -452,10 +431,6 @@ extern uint8_t g_uncomp_hdrlen; extern uint8_t g_frame_hdrlen; -/* Offset first available byte for the payload after header region. */ - -extern uint8_t g_dataoffset; - /* Packet buffer metadata: Attributes and addresses */ extern uint16_t g_pktattrs[PACKETBUF_NUM_ATTRS]; @@ -745,16 +720,6 @@ int sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, FAR uint8_t *payptr); #endif -/**************************************************************************** - * Name: sixlowpan_frame_hdralloc - * - * Description: - * Allocate space for a header within the frame buffer (IOB). - * - ****************************************************************************/ - -int sixlowpan_frame_hdralloc(FAR struct iob_s *iob, int size); - /**************************************************************************** * Name: sixlowpan_islinklocal, sixlowpan_ipfromrime, sixlowpan_rimefromip, * and sixlowpan_ismacbased diff --git a/net/sixlowpan/sixlowpan_utils.c b/net/sixlowpan/sixlowpan_utils.c index 1ec8eec2b6..3dcf757bfa 100644 --- a/net/sixlowpan/sixlowpan_utils.c +++ b/net/sixlowpan/sixlowpan_utils.c @@ -45,20 +45,6 @@ * ****************************************************************************/ -/* Frame Organization. The IOB data is retained in the io_data[] field of the - * IOB structure like: - * - * Content Offset - * +------------------+ 0 - * | Frame Header | - * +------------------+ g_dataoffset - * | Procotol Headers | - * | Data Payload | - * +------------------+ iob->io_len - * | Unused | - * +------------------+ CONFIG_NET_6LOWPAN_FRAMELEN - */ - /**************************************************************************** * Included Files ****************************************************************************/ @@ -79,26 +65,6 @@ * Public Functions ****************************************************************************/ -/**************************************************************************** - * Name: sixlowpan_frame_hdralloc - * - * Description: - * Allocate space for a header within the packet buffer (dev->d_buf). - * - ****************************************************************************/ - -int sixlowpan_frame_hdralloc(FAR struct iob_s *iob, int size) -{ - if (size <= FRAME_REMAINING(iob)) - { - g_dataoffset += size; - iob->io_len += size; - return OK; - } - - return -ENOMEM; -} - /**************************************************************************** * Name: sixlowpan_ipfromrime * -- GitLab From e61fd2d45b730dc15432afa67f64071f00439485 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 5 Apr 2017 09:14:28 -0600 Subject: [PATCH 345/990] 6loWPAN input: Fix a counting error. Input packet sizes were being calculated a little too big. --- net/sixlowpan/sixlowpan_input.c | 29 +++++++++++++++-------------- 1 file changed, 15 insertions(+), 14 deletions(-) diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index c279920e41..03a78f3684 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -225,13 +225,6 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, systime_t elapsed; /* Elapsed time */ #endif /* CONFIG_NET_6LOWPAN_FRAG */ - /* Initialize global data. Locking the network guarantees that we have - * exclusive use of the global values for intermediate calculations. - */ - - g_uncomp_hdrlen = 0; - g_frame_hdrlen = 0; - /* Get a pointer to the payload following the IEEE802.15.4 frame header. */ hdrsize = sixlowpan_recv_hdrlen(iob->io_data); @@ -241,6 +234,15 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, return hdrsize; } + /* Initialize global data. Locking the network guarantees that we have + * exclusive use of the global values for intermediate calculations. + */ + + g_uncomp_hdrlen = 0; + g_frame_hdrlen = hdrsize; + + /* Payload starts after the IEEE802.15.4 header */ + payptr = &iob->io_data[hdrsize]; #ifdef CONFIG_NET_6LOWPAN_FRAG @@ -438,7 +440,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, /* Process next dispatch and headers */ - hc1 = payptr + g_frame_hdrlen; + hc1 = &iob->io_data[g_frame_hdrlen]; #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 if ((hc1[RIME_HC1_DISPATCH] & SIXLOWPAN_DISPATCH_IPHC_MASK) == SIXLOWPAN_DISPATCH_IPHC) @@ -484,21 +486,20 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, copypayload: #endif /* CONFIG_NET_6LOWPAN_FRAG */ - /* Copy "payload" from the rime buffer to the IEEE802.15.4 MAC drivers + /* Copy "payload" from the rime buffer to the IEEE802.15.4 MAC driver's * d_buf. If this frame is a first fragment or not part of a fragmented * packet, we have already copied the compressed headers, g_uncomp_hdrlen * and g_frame_hdrlen are non-zerio, fragoffset is. */ - if (g_frame_hdrlen > CONFIG_NET_6LOWPAN_MTU) + g_rime_payloadlen = iob->io_len - g_frame_hdrlen; + if (g_rime_payloadlen > CONFIG_NET_6LOWPAN_MTU) { - nwarn("WARNING: Packet dropped due to header (%u) > packet buffer (%u)\n", - g_frame_hdrlen, CONFIG_NET_6LOWPAN_MTU); + nwarn("WARNING: Packet dropped due to payload (%u) > packet buffer (%u)\n", + g_rime_payloadlen, CONFIG_NET_6LOWPAN_MTU); return OK; } - g_rime_payloadlen = iob->io_len - g_frame_hdrlen; - /* Sanity-check size of incoming packet to avoid buffer overflow */ reqsize = g_uncomp_hdrlen + (uint16_t) (fragoffset << 3) + g_rime_payloadlen; -- GitLab From cb70ce7d3c927e4168a87dcde98db5b0d9423dea Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 5 Apr 2017 12:11:09 -0600 Subject: [PATCH 346/990] 6loWPAN: Correct some IPv6 addresses and operations on IPv6 addresses. --- configs/sim/sixlowpan/defconfig | 30 +++++++++++++++--------------- drivers/input/button_upper.c | 4 ++-- net/sixlowpan/sixlowpan_hc06.c | 24 ++++++++++++++++-------- net/sixlowpan/sixlowpan_utils.c | 32 +++++++++++++++++++------------- 4 files changed, 52 insertions(+), 38 deletions(-) diff --git a/configs/sim/sixlowpan/defconfig b/configs/sim/sixlowpan/defconfig index adf330024f..a71e704bfe 100644 --- a/configs/sim/sixlowpan/defconfig +++ b/configs/sim/sixlowpan/defconfig @@ -889,10 +889,10 @@ CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_1=0xfe80 CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_2=0x0000 CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_3=0x0000 CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_4=0x0000 -CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_5=0x1234 -CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_6=0x0000 -CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_7=0x0000 -CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_8=0x0000 +CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_5=0x0000 +CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_6=0x00ff +CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_7=0xfe00 +CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_8=0x3234 CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -1097,10 +1097,10 @@ CONFIG_NSH_IPv6ADDR_1=0xfe80 CONFIG_NSH_IPv6ADDR_2=0x0000 CONFIG_NSH_IPv6ADDR_3=0x0000 CONFIG_NSH_IPv6ADDR_4=0x0000 -CONFIG_NSH_IPv6ADDR_5=0xabcd -CONFIG_NSH_IPv6ADDR_6=0x0000 -CONFIG_NSH_IPv6ADDR_7=0x0000 -CONFIG_NSH_IPv6ADDR_8=0x0000 +CONFIG_NSH_IPv6ADDR_5=0x0000 +CONFIG_NSH_IPv6ADDR_6=0x00ff +CONFIG_NSH_IPv6ADDR_7=0xfe00 +CONFIG_NSH_IPv6ADDR_8=0x8bcd # # Router IPv6 address @@ -1109,10 +1109,10 @@ CONFIG_NSH_DRIPv6ADDR_1=0xfe80 CONFIG_NSH_DRIPv6ADDR_2=0x0000 CONFIG_NSH_DRIPv6ADDR_3=0x0000 CONFIG_NSH_DRIPv6ADDR_4=0x0000 -CONFIG_NSH_DRIPv6ADDR_5=0x1234 -CONFIG_NSH_DRIPv6ADDR_6=0x0000 -CONFIG_NSH_DRIPv6ADDR_7=0x0000 -CONFIG_NSH_DRIPv6ADDR_8=0x0000 +CONFIG_NSH_DRIPv6ADDR_5=0x0000 +CONFIG_NSH_DRIPv6ADDR_6=0x00ff +CONFIG_NSH_DRIPv6ADDR_7=0xfe00 +CONFIG_NSH_DRIPv6ADDR_8=0x3234 # # IPv6 Network mask @@ -1121,9 +1121,9 @@ CONFIG_NSH_IPv6NETMASK_1=0xffff CONFIG_NSH_IPv6NETMASK_2=0xffff CONFIG_NSH_IPv6NETMASK_3=0xffff CONFIG_NSH_IPv6NETMASK_4=0xffff -CONFIG_NSH_IPv6NETMASK_5=0x0000 -CONFIG_NSH_IPv6NETMASK_6=0x0000 -CONFIG_NSH_IPv6NETMASK_7=0x0000 +CONFIG_NSH_IPv6NETMASK_5=0xffff +CONFIG_NSH_IPv6NETMASK_6=0xffff +CONFIG_NSH_IPv6NETMASK_7=0xffff CONFIG_NSH_IPv6NETMASK_8=0x0000 # CONFIG_NSH_DNS is not set CONFIG_NSH_NOMAC=y diff --git a/drivers/input/button_upper.c b/drivers/input/button_upper.c index b4432cbad3..f5486752fc 100644 --- a/drivers/input/button_upper.c +++ b/drivers/input/button_upper.c @@ -158,8 +158,8 @@ static const struct file_operations btn_fops = btn_open, /* open */ btn_close, /* close */ btn_read, /* read */ - 0, /* write */ - 0, /* seek */ + NULL, /* write */ + NULL, /* seek */ btn_ioctl /* ioctl */ #ifndef CONFIG_DISABLE_POLL , btn_poll /* poll */ diff --git a/net/sixlowpan/sixlowpan_hc06.c b/net/sixlowpan/sixlowpan_hc06.c index 98df1c1bd3..0b9d5153b0 100644 --- a/net/sixlowpan/sixlowpan_hc06.c +++ b/net/sixlowpan/sixlowpan_hc06.c @@ -239,13 +239,16 @@ static uint8_t compress_addr_64(FAR const net_ipv6addr_t ipaddr, FAR const struct rimeaddr_s *macaddr, uint8_t bitpos) { + ninfo("ipaddr=%p macaddr=%p bitpos=%u g_hc06ptr=%p\n", + ipaddr, macaddr, bitpos, g_hc06ptr); + if (sixlowpan_ismacbased(ipaddr, macaddr)) { return 3 << bitpos; /* 0-bits */ } else if (SIXLOWPAN_IS_IID_16BIT_COMPRESSABLE(ipaddr)) { - /* Compress IID to 16 bits xxxx::0000:00ff:fe00:XXXX */ + /* Compress IID to 16 bits: xxxx:xxxx:xxxx:xxxx:0000:00ff:fe00:XXXX */ memcpy(g_hc06ptr, &ipaddr[7], 2); g_hc06ptr += 2; @@ -253,7 +256,7 @@ static uint8_t compress_addr_64(FAR const net_ipv6addr_t ipaddr, } else { - /* Do not compress IID => xxxx::IID */ + /* Do not compress IID: xxxx:xxxx:xxxx:xxxx:IID:IID:IID:IID */ memcpy(g_hc06ptr, &ipaddr[4], 8); g_hc06ptr += 8; @@ -455,11 +458,9 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, uint8_t iphc1; uint8_t tmp; - sixlowpan_dumpbuffer("IPv6 before compression", - (FAR const uint8_t *)ipv6, - sizeof(struct ipv6_hdr_s)); - g_hc06ptr = fptr + 2; + ninfo("fptr=%p g_frame_hdrlen=%u iphc=%p g_hc06ptr=%p\n", + fptr, g_frame_hdrlen, iphc, g_hc06ptr); /* As we copy some bit-length fields, in the IPHC encoding bytes, * we sometimes use |= @@ -516,7 +517,7 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, } else { - /* Sompress only the flow label */ + /* Compress only the flow label */ *g_hc06ptr = tmp; g_hc06ptr += 1; @@ -810,6 +811,10 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, iphc[1] = iphc1; g_frame_hdrlen = g_hc06ptr - fptr; + + ninfo("fptr=%p g_frame_hdrlen=%u iphc=%02x:%02x:%02x g_hc06ptr=%p\n", + fptr, g_frame_hdrlen, iphc[0], iphc[1], iphc[2], g_hc06ptr); + return; } @@ -856,11 +861,14 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, iphc0 = iphc[0]; iphc1 = iphc[1]; + ninfo("payptr=%p g_frame_hdrlen=%u iphc[%p]=%02x:%02x:%02x g_hc06ptr=%p\n", + payptr, g_frame_hdrlen, iphc, iphc[0], iphc[1], iphc[2], g_hc06ptr); + /* Another if the CID flag is set */ if (iphc1 & SIXLOWPAN_IPHC_CID) { - ninfo("IPHC: CID flag set - increase header with one\n"); + ninfo("IPHC: CID flag set. Increase header by one\n"); g_hc06ptr++; } diff --git a/net/sixlowpan/sixlowpan_utils.c b/net/sixlowpan/sixlowpan_utils.c index 3dcf757bfa..c7cf3887a0 100644 --- a/net/sixlowpan/sixlowpan_utils.c +++ b/net/sixlowpan/sixlowpan_utils.c @@ -73,7 +73,7 @@ * * 128 112 96 80 64 48 32 16 * ---- ---- ---- ---- ---- ---- ---- ---- - * fe80 0000 0000 0000 xxxx xxxx 0000 0000 2-byte Rime address (VALID?) + * fe80 0000 0000 0000 0000 00ff fe00 xxxx 2-byte Rime address * fe80 0000 0000 0000 xxxx xxxx xxxx xxxx 8-byte Rime address * ****************************************************************************/ @@ -81,20 +81,22 @@ void sixlowpan_ipfromrime(FAR const struct rimeaddr_s *rime, net_ipv6addr_t ipaddr) { - memset(ipaddr, 0, sizeof(net_ipv6addr_t)); - ipaddr[0] = HTONS(0xfe80); - /* We consider only links with IEEE EUI-64 identifier or IEEE 48-bit MAC - * addresses. NOTE: that CONFIG_NET_6LOWPAN_RIMEADDR_SIZE may be 2 or - * 8. In the case of 2, we treat the address like an 8 byte address with - * the lower bytes set to zero. - * - * REVISIT: This is just a guess so that I can continue making forward - * progress. What is the correct policy? + * addresses. */ + memset(ipaddr, 0, sizeof(net_ipv6addr_t)); + ipaddr[0] = HTONS(0xfe80); + +#if CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 2 + ipaddr[5] = HTONS(0x00ff); + ipaddr[6] = HTONS(0xfe00); + memcpy(&ipaddr[7], rime, CONFIG_NET_6LOWPAN_RIMEADDR_SIZE); + ipaddr[7] ^= HTONS(0x0200); +#else memcpy(&ipaddr[4], rime, CONFIG_NET_6LOWPAN_RIMEADDR_SIZE); ipaddr[4] ^= HTONS(0x0200); +#endif } /**************************************************************************** @@ -105,7 +107,7 @@ void sixlowpan_ipfromrime(FAR const struct rimeaddr_s *rime, * * 128 112 96 80 64 48 32 16 * ---- ---- ---- ---- ---- ---- ---- ---- - * fe80 0000 0000 0000 xxxx 0000 0000 0000 2-byte Rime address (VALID?) + * fe80 0000 0000 0000 0000 00ff fe00 xxxx 2-byte Rime address * fe80 0000 0000 0000 xxxx xxxx xxxx xxxx 8-byte Rime address * ****************************************************************************/ @@ -117,7 +119,11 @@ void sixlowpan_rimefromip(const net_ipv6addr_t ipaddr, DEBUGASSERT(ipaddr[0] == HTONS(0xfe80)); +#if CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 2 + memcpy(rime, &ipaddr[7], CONFIG_NET_6LOWPAN_RIMEADDR_SIZE); +#else memcpy(rime, &ipaddr[4], CONFIG_NET_6LOWPAN_RIMEADDR_SIZE); +#endif rime->u8[0] ^= 0x02; } @@ -125,11 +131,11 @@ void sixlowpan_rimefromip(const net_ipv6addr_t ipaddr, * Name: sixlowpan_ismacbased * * Description: - * Extract the rime address from a link local IPv6 address: + * Check if the MAC address is encoded in the IP address: * * 128 112 96 80 64 48 32 16 * ---- ---- ---- ---- ---- ---- ---- ---- - * fe80 0000 0000 0000 xxxx 0000 0000 0000 2-byte Rime address (VALID?) + * fe80 0000 0000 0000 0000 00ff fe00 xxxx 2-byte Rime address * fe80 0000 0000 0000 xxxx xxxx xxxx xxxx 8-byte Rime address * ****************************************************************************/ -- GitLab From aada26f90397c5ef0e743b3c2fc17b322f2f82f9 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Wed, 5 Apr 2017 15:03:47 -0400 Subject: [PATCH 347/990] wireless/ieee802154: Defines more data types/macros. Some renaming and cleanup --- .../wireless/ieee802154/ieee802154_mac.h | 456 +++++++++++++----- wireless/ieee802154/mac802154.c | 167 +++---- 2 files changed, 417 insertions(+), 206 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index 19af457bf6..13191bfa40 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -2,7 +2,13 @@ * include/nuttx/wireless/ieee802154/ieee802154_mac.h * * Copyright (C) 2016 Sebastien Lorquet. All rights reserved. + * Copyright (C) 2017 Verge Inc. All rights reserved. + * * Author: Sebastien Lorquet + * Author: Anthony Merlino + * + * The naming and comments for various fields are taken directly + * from the IEEE 802.15.4 2011 standard. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -142,29 +148,40 @@ /* IEEE 802.15.4 PHY constants */ -#define IEEE802154_aMaxPHYPacketSize 127 -#define IEEE802154_aTurnaroundTime 12 /*symbol periods*/ +#define IEEE802154_MAX_PHY_PACKET_SIZE 127 +#define IEEE802154_TURN_AROUND_TIME 12 /*symbol periods*/ /* IEEE 802.15.4 MAC constants */ -#define IEEE802154_aBaseSlotDuration 60 -#define IEEE802154_aNumSuperframeSlots 16 -#define IEEE802154_aBaseSuperframeDuration (IEEE802154_aBaseSlotDuration * IEEE802154_aNumSuperframeSlots) -#define IEEE802154_aMaxBE 5 -#define IEEE802154_aMaxBeaconOverhead 75 -#define IEEE802154_aMaxBeaconPayloadLength (IEEE802154_aMaxPHYPacketSize - IEEE802154_aMaxBeaconOverhead) -#define IEEE802154_aGTSDescPersistenceTime 4 -#define IEEE802154_aMaxFrameOverhead 25 -#define IEEE802154_aMaxFrameResponseTime 1220 -#define IEEE802154_aMaxFrameRetries 3 -#define IEEE802154_aMaxLostBeacons 4 -#define IEEE802154_aMaxMACFrameSize (IEEE802154_aMaxPHYPacketSize - IEEE802154_aMaxFrameOverhead) -#define IEEE802154_aMaxSIFSFrameSize 18 -#define IEEE802154_aMinCAPLength 440 -#define IEEE802154_aMinLIFSPeriod 40 -#define IEEE802154_aMinSIFSPeriod 12 -#define IEEE802154_aResponseWaitTime (32 * IEEE802154_aBaseSuperframeDuration) -#define IEEE802154_aUnitBackoffPeriod 20 +#define IEEE802154_BASE_SLOT_DURATION 60 +#define IEEE802154_NUM_SUPERFRAME_SLOTS 16 + +#define IEEE802154_BASE_SUPERFRAME_DURATION \ + (IEEE802154_BASE_SLOT_DURATION * IEEE802154_NUM_SUPERFRAME_SLOTS) + +#define IEEE802154_GTS_DESC_PERSISTENCE_TIME 4 +#define IEEE802154_MAX_BEACON_OVERHEAD 75 + +#define IEEE802154_MAX_BEACON_PAYLOAD_LENGTH \ + (IEEE802154_MAX_PHY_PACKET_SIZE - IEEE802154_MAX_BEACON_OVERHEAD) + +#define IEEE802154_MAX_LOST_BEACONS 4 +#define IEEE802514_MIN_MPDU_OVERHEAD 9 +#define IEEE802154_MAX_MPDU_UNSEC_OVERHEAD 25 + +#define IEEE802154_MAX_SAFE_MAC_PAYLOAD_SIZE \ + (IEEE802154_MAX_PHY_PACKET_SIZE - IEEE802154_MAX_MPDU_UNSEC_OVERHEAD) + +#define IEEE802154_MAX_MAC_PAYLOAD_SIZE \ + (IEEE802154_MAX_PHY_PACKET_SIZE - IEEE802154_MIN_MPDU_OVERHEAD) + +#define IEEE802154_MAX_SIFS_FRAME_SIZE 18 +#define IEEE802154_MIN_CAP_LENGTH 440 +#define IEEE802154_UNIT_BACKOFF_PERIOD 20 + +/* IEEE 802.15.4 MAC PIB Attribut Defaults */ + +// TODO: Add macros /**************************************************************************** * Public Types @@ -200,41 +217,100 @@ enum ieee802154_status_e /* IEEE 802.15.4 PHY/MAC PIB attributes IDs */ -enum +enum ieee802154_pib_attr_e { - IEEE802154_phyCurrentChannel = 0x00, - IEEE802154_phyChannelsSupported, - IEEE802154_phyTransmitPower, - IEEE802154_phyCCAMode, - IEEE802154_macAckWaitDuration = 0x40, - IEEE802154_macAssociationPermit, - IEEE802154_macAutoRequest, - IEEE802154_macBattLifeExt, - IEEE802154_macBattLifeExtPeriods, - IEEE802154_macBeaconPayload, - IEEE802154_macBeaconPayloadLength, - IEEE802154_macBeaconOrder, - IEEE802154_macBeaconTxTime, - IEEE802154_macBSN, - IEEE802154_macCoordExtendedAddress, - IEEE802154_macCoordShortAddress, - IEEE802154_macDSN, - IEEE802154_macGTSPermit, - IEEE802154_macMaxCSMABackoffs, - IEEE802154_macMinBE, - IEEE802154_macPANId, - IEEE802154_macPromiscuousMode, - IEEE802154_macRxOnWhenIdle, - IEEE802154_macShortAddress, - IEEE802154_macSuperframeOrder, - IEEE802154_macTransactionPersistenceTime, - IEEE802154_macACLEntryDescriptorSet = 0x70, - IEEE802154_macACLEntryDescriptorSetSize, - IEEE802154_macDefaultSecurity, - IEEE802154_macDefaultSecurityMaterialLength, - IEEE802154_macDefaultSecurityMaterial, - IEEE802154_macDefaultSecuritySuite, - IEEE802154_macSecurityMode + /* PHY PIB Attributes */ + + IEEE802154_PIB_PHY_CURRENT_CHANNEL = 0x00, + IEEE802154_PIB_PHY_CHANNELS_SUPPORTED, + IEEE802154_PIB_PHY_TX_POWER_TOLERANCE, + IEEE802154_PIB_PHY_TX_POWER, + IEEE802154_PIB_PHY_CCA_MODE, + IEEE802154_PIB_PHY_CURRENT_PAGE, + IEEE802154_PIB_PHY_MAX_FRAME_DURATION, + IEEE802154_PIB_PHY_SHR_DURATION, + IEEE802154_PIB_PHY_SYM_PER_OCTET, + IEEE802154_PIB_PHY_PREAMBLE_SYM_LEN, + IEEE802154_PIB_PHY_UWB_DATARATES_SUP, + IEEE802154_PIB_PHY_CSS_LOW_DATARATE_SUP, + IEEE802154_PIB_PHY_UWB_COU_PULSES_SUP, + IEEE802154_PIB_PHY_UWB_CS_PULSES_SUP, + IEEE802154_PIB_PHY_UWB_LCP_PULSES_SUP, + IEEE802154_PIB_PHY_UWB_CURR_PULSE_SHAPE, + IEEE802154_PIB_PHY_UWB_COU_PULSE, + IEEE802154_PIB_PHY_UWB_CS_PULSE, + IEEE802154_PIB_PHY_UWB_LCP_WEIGHT1, + IEEE802154_PIB_PHY_UWB_LCP_WEIGHT2, + IEEE802154_PIB_PHY_UWB_LCP_WEIGHT3, + IEEE802154_PIB_PHY_UWB_LCP_WEIGHT4, + IEEE802154_PIB_PHY_UWB_LCP_DELAY2, + IEEE802154_PIB_PHY_UWB_LCP_DELAY3, + IEEE802154_PIB_PHY_UWB_LCP_DELAY4, + IEEE802154_PIB_PHY_RANGING, + IEEE802154_PIB_PHY_RANGING_CRYSTAL_OFFSET, + IEEE802154_PIB_PHY_RANGING_DPS, + IEEE802154_PIB_PHY_CURRENT_CODE, + IEEE802154_PIB_PHY_NATIVE_PRF, + IEEE802154_PIB_PHY_UWB_SCAN_BINS_PER_CHAN, + IEEE802154_PIB_PHY_UWB_INS_PREAMBLE_INTERVAL, + IEEE802154_PIB_PHY_UWB_TX_RMARKER, + IEEE802154_PIB_PHY_UWB_RX_RMARKER, + IEEE802154_PIB_PHY_RFRAME_PROC_TIME, + IEEE802154_PIB_PHY_CCA_DURATION, + + /* MAC PIB Attributes */ + + IEEE802154_PIB_MAC_EXTENDED_ADDR = 0x40, + IEEE802154_PIB_MAC_ACK_WAIT_DUR, + IEEE802154_PIB_MAC_ASSOCIATED_PANCOORD, + IEEE802154_PIB_MAC_ASSOCIATION_PERMIT, + IEEE802154_PIB_MAC_AUTO_REQUEST, + IEEE802154_PIB_MAC_BATT_LIFE_EXT, + IEEE802154_PIB_MAC_BATT_LIFE_EXT_PERIODS, + IEEE802154_PIB_MAC_BEACON_PAYLOAD, + IEEE802154_PIB_MAC_BEACON_PAYLOAD_LEN, + IEEE802154_PIB_MAC_BEACON_ORDER, + IEEE802154_PIB_MAC_BEACON_TX_TIME, + IEEE802154_PIB_MAC_BSN, + IEEE802154_PIB_MAC_COORD_EXT_ADDR, + IEEE802154_PIB_MAC_COORD_SHORT_ADDR, + IEEE802154_PIB_MAC_DSN, + IEEE802154_PIB_MAC_GTS_PERMIT, + IEEE802154_PIB_MAC_MAX_BE, + IEEE802154_PIB_MAC_MAX_CSMA_BACKOFFS, + IEEE802154_PIB_MAC_FRAME_TOTAL_WAIT_TIME, + IEEE802154_PIB_MAC_MAX_FRAME_RETRIES, + IEEE802154_PIB_MAC_MIN_BE, + IEEE802154_PIB_MAC_LIFS_PERIOD, + IEEE802154_PIB_MAC_SIFS_PERIOD, + IEEE802154_PIB_MAC_PAN_ID, + IEEE802154_PIB_MAC_PROMISCUOUS_MODE, + IEEE802154_PIB_MAC_RANGING_SUPPORT, + IEEE802154_PIB_MAC_RESPONSE_WAIT_TIME, + IEEE802154_PIB_MAC_RX_ON_WHEN_IDLE, + IEEE802154_PIB_MAC_SECURITY_ENABLED, + IEEE802154_PIB_MAC_SHORT_ADDRESS, + IEEE802154_PIB_MAC_SUPERFRAME_ORDER, + IEEE802154_PIB_MAC_SYNC_SYMBOL_OFFSET, + IEEE802154_PIB_MAC_TIMESTAMP_SUPPORT, + IEEE802154_PIB_MAC_TRANSACTION_PERSIST_TIME, + IEEE802154_PIB_MAC_TX_CTRL_ACTIVE_DUR, + IEEE802154_PIB_MAC_TX_CTRL_PAUSE_DUR, + IEEE802154_PIB_MAC_TX_TOTAL_DUR, + + /* MAC Security Attributes */ + + IEEE802154_PIB_MAC_KEY_TABLE = 0x70, + IEEE802154_PIB_MAC_DEV_TABLE, + IEEE802154_PIB_MAC_SEC_LVL_TABLE, + IEEE802154_PIB_MAC_FRAME_COUNTER, + IEEE802154_PIB_MAC_AUTOREQ_SEC_LVL, + IEEE802154_PIB_MAC_AUTOREQ_KEY_ID_MODE, + IEEE802154_PIB_MAC_AUTOREQ_KEY_SOURCE, + IEEE802154_PIB_MAC_AUTOREQ_KEY_INDEX, + IEEE802154_PIB_MAC_DEFAULT_KEY_SRC, + IEEE802154_PIB_MAC_PANCOORD_EXT_ADDR, + IEEE802154_PIB_MAC_PANCOORD_SHORT_ADDR, }; /* IEEE 802.15.4 Device address @@ -253,12 +329,15 @@ enum ieee802154_addr_mode_e struct ieee802154_addr_s { - enum ieee802154_addr_mode_e ia_mode; /* Address mode. Short or Extended */ - uint16_t ia_panid; /* PAN identifier, can be IEEE802154_PAN_UNSPEC */ + /* Address mode. Short or Extended */ + + enum ieee802154_addr_mode_e ia_mode; + + uint16_t ia_panid; /* PAN identifier, can be IEEE802154_PAN_UNSPEC */ union { - uint16_t _ia_saddr; /* short address */ - uint8_t _ia_eaddr[8]; /* extended address */ + uint16_t _ia_saddr; /* short address */ + uint8_t _ia_eaddr[8]; /* extended address */ } ia_addr; #define ia_saddr ia_addr._ia_saddr @@ -305,6 +384,42 @@ struct ieee802154_framecontrol_s uint16_t src_addr_mode : 2; }; +#ifdef CONFIG_IEEE802154_SECURITY +struct ieee802154_security_s +{ + uint8_t level; /* Security level to be used */ + uint8_t key_id_mode; /* Mode used to identify the key to be used */ + uint8_t key_source[8]; /* Originator of the key to be used */ + uint8_t key_index; /* Index of the key to be used */ +}; +#endif + +#ifdef CONFIG_IEEE802154_UWB +enum ieee802154_uwbprf_e +{ + IEEE802154_UWBPRF_OFF = 0, + IEEE802154_UWBPRF_4M, + IEEE802154_UWBPRF_16M, + IEEE802154_UWBPRF_64M +}; + +enum ieee802154_uwb_datarate_e +{ + IEEE802154_UWB_DATARATE_0 = 0, + IEEE802154_UWB_DATARATE_16, + IEEE802154_UWB_DATARATE_64, + IEEE802154_UWB_DATARATE_1024, + IEEE802154_UWB_DATARATE_4096 +}; +#endif + +enum ieee802154_ranging_e +{ + IEEE802154_NON_RANGING = 0, + IEEE802154_ALL_RANGING, + IEEE802154_PHY_HEADER_ONLY +}; + struct ieee802154_frame_s { struct ieee802154_framecontrol_s frame_control; @@ -318,6 +433,99 @@ struct ieee802154_frame_s uint16_t fcs; }; +struct ieee802154_data_req_s +{ + enum ieee802154_addr_mode_e src_addr_mode; /* Source Address Mode */ + struct ieee802154_addr_s dest__addr; /* Destination Address */ + + /* Number of bytes contained in the MAC Service Data Unit (MSDU) + * to be transmitted by the MAC sublayer enitity + * Note: This could be a uint8_t but if anyone ever wants to use + * non-standard frame lengths, they may want a length larger than + * a uint8_t */ + + uint16_t msdu_length; + + + uint8_t msdu_handle; /* Handle assoc. with MSDU */ + struct { + uint8_t ack_tx : 1; /* Acknowledge TX? */ + uint8_t gts_tx : 1; /* 1=GTS used for TX, 0=CAP used for TX */ + uint8_t indirect_tx : 1; /* Should indirect transmission be used? */ + }; + +#ifdef CONFIG_IEEE802154_SECURITY + /* Security information if enabled */ + + struct ieee802154_security_s security; +#endif + +#ifdef CONFIG_IEEE802154_UWB + /* The UWB Pulse Repetion Frequency to be used for the transmission */ + + enum ieee802154_uwbprf_e uwb_prf; + + /* The UWB preamble symbol repititions + * Should be one of: + * 0, 16, 64, 1024, 4096 */ + + uint16_t uwb_presym_rep; + + /* The UWB Data Rate to be used for the transmission */ + + enum ieee802154_uwb_datarate_e data_rate; +#endif + + enum ieee802154_ranging_e ranging; + + /* The MAC service data unit array that is to be transmitted + * This must be at the end of the struct to allow the array + * to continue and make the struct "variable length" */ + + uint8_t msdu[1]; +}; +#define SIZEOF_IEEE802154_DATA_REQ_S(n) \ + (sizeof(struct ieee802154_data_req_s) + (n)) + +struct ieee802154_data_conf_s +{ + uint8_t msdu_handle; /* Handle assoc. with MSDU */ + + /* The time, in symbols, at which the data were transmitted */ + + uint32_t timestamp; + + enum ieee802154_status_e status; /* The status of the MSDU transmission */ + +#ifdef CONFIG_IEEE802154_RANGING + bool rng_rcvd; /* Ranging indicated by MSDU */ + + /* A count of the time units corresponding to an RMARKER at the antenna at + * the beginning of the ranging exchange */ + + uint32_t rng_counter_start; + + /* A count of the time units corresponding to an RMARKER at the antenna at + * end of the ranging exchange */ + + uint32_t rng_counter_stop; + + /* A count of the time units in a message exchange over which the tracking + * offset was measured */ + + uint34_t rng_tracking_interval; + + /* A count of the time units slipped or advanced by the radio tracking + * system over the course of the entire tracking interval */ + + uint32_t rng_offset; + + /* The Figure of Merit (FoM) characterizing the ranging measurement */ + + uint8_t rng_fom; +#endif +}; + struct ieee802154_capability_info_s { uint8_t reserved_0 : 1; /* Reserved */ @@ -331,16 +539,6 @@ struct ieee802154_capability_info_s * 0=otherwise */ }; -#ifdef CONFIG_IEEE802154_SECURITY -struct ieee802154_security_s -{ - uint8_t level; /* Security level to be used */ - uint8_t key_id_mode; /* Mode used to identify the key to be used */ - uint8_t key_source[8]; /* Originator of the key to be used */ - uint8_t key_index; /* Index of the key to be used */ -}; -#endif - struct ieee802154_superframe_spec_s { uint16_t beacon_order : 4; /* Transmission interval of beacon */ @@ -367,7 +565,7 @@ struct ieee802154_pan_desc_s uint8_t gts_permit; /* 0=No GTS requests allowed * 1=GTS request allowed */ - uint8_t link_quality; /* LQI at which beacon was received */ + uint8_t lqi; /* Link Quality Indication of the beacon */ uint32_t timestamp; /* Time at which the beacon frame was received * in symbols */ }; @@ -390,7 +588,7 @@ struct ieee802154_pend_addr_s /* Primitive Semantics */ -struct ieee802154_assoc_request_s +struct ieee802154_assoc_req_s { uint8_t channel; /* Channel number to attempt association */ uint8_t channel_page; /* Channel page to attempt association */ @@ -410,7 +608,7 @@ struct ieee802154_assoc_request_s #endif }; -struct ieee802154_assoc_indication_s +struct ieee802154_assoc_ind_s { /* Address of device requesting association. Always in extended mode */ @@ -427,7 +625,7 @@ struct ieee802154_assoc_indication_s #endif }; -struct ieee802154_assoc_response_s +struct ieee802154_assoc_rsp_s { /* Address of device requesting association. Always in extended mode */ @@ -444,7 +642,7 @@ struct ieee802154_assoc_response_s #endif }; -struct ieee802154_assoc_confirm_s +struct ieee802154_assoc_conf_s { /* Associated device address ALWAYS passed in short address mode. The * address will be IEEE802154_SADDR_UNSPEC if association was unsuccessful */ @@ -462,7 +660,7 @@ struct ieee802154_assoc_confirm_s #endif }; -struct ieee802154_disassoc_request_s +struct ieee802154_disassoc_req_s { /* Address of device to send disassociation notification */ @@ -481,7 +679,7 @@ struct ieee802154_disassoc_request_s #endif }; -struct ieee802154_disassoc_indication_s +struct ieee802154_disassoc_ind_s { /* Address of device requesting disassociation. Always extended mode */ @@ -498,7 +696,7 @@ struct ieee802154_disassoc_indication_s #endif }; -struct ieee802154_disassoc_confirm_s +struct ieee802154_disassoc_conf_s { /* Status of the disassociation attempt */ @@ -509,7 +707,7 @@ struct ieee802154_disassoc_confirm_s struct ieee802154_addr_s dev_addr; }; -struct ieee802154_beaconnotify_indication_s +struct ieee802154_beaconnotify_ind_s { uint8_t bsn; /* Beacon sequence number */ @@ -526,8 +724,11 @@ struct ieee802154_beaconnotify_indication_s /* Beacon payload */ - uint8_t sdu[IEEE802154_aMaxBeaconPayloadLength]; + uint8_t sdu[IEEE802154_MAX_BEACON_PAYLOAD_LENGTH]; }; +#define SIZEOF_IEEE802154_BEACONNOTIFY_IND_S(n) \ + (sizeof(struct ieee802154_beaconnotify_ind_s) \ + - IEEE802154_MAX_BEACON_PAYLOAD_LENGTH + (n)) /* Operations */ @@ -539,8 +740,8 @@ struct ieee802154_macops_s /* Transmit a data frame */ - CODE int (*req_data)(FAR struct ieee802154_mac_s *mac, uint8_t handle, - FAR uint8_t *buf, int len); + CODE int (*req_data)(FAR struct ieee802154_mac_s *mac, + FAR struct ieee802154_data_req_s *req); /* Cancel transmission of a data frame */ @@ -549,16 +750,17 @@ struct ieee802154_macops_s /* Start association with coordinator */ CODE int (*req_associate)(FAR struct ieee802154_mac_s *mac, - uint16_t panid, FAR uint8_t *coordeadr); + FAR struct ieee802154_assoc_req_s *req); /* Start disassociation with coordinator */ CODE int (*req_disassociate)(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *eadr, uint8_t reason); + FAR struct ieee802154_disassoc_req_s *req); /* Read the PIB */ - CODE int (*req_get)(FAR struct ieee802154_mac_s *mac, int attribute); + CODE int (*req_get)(FAR struct ieee802154_mac_s *mac, + enum ieee802154_pib_attr_e attr); /* Allocate or deallocate a GTS */ @@ -612,94 +814,98 @@ struct ieee802154_macops_s struct ieee802154_maccb_s { + /* Context arg for handling callback */ + + FAR void *cb_context; + /* Asynchronous confirmations to requests */ /* Data frame was received by remote device */ - CODE int (*conf_data)(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *buf, int len); + CODE void (*conf_data)(FAR struct ieee802154_mac_s *mac, + FAR struct ieee802154_data_conf_s *conf); /* Data frame was purged */ - CODE int (*conf_purge)(FAR struct ieee802154_mac_s *mac, uint8_t handle, - int status); + CODE void (*conf_purge)(FAR struct ieee802154_mac_s *mac, uint8_t handle, + int status); /* Association request completed */ - CODE int (*conf_associate)(FAR struct ieee802154_mac_s *mac, - uint16_t saddr, int status); + CODE void (*conf_associate)(FAR struct ieee802154_mac_s *mac, + uint16_t saddr, int status); /* Disassociation request completed */ - CODE int (*conf_disassociate)(FAR struct ieee802154_mac_s *mac, - int status); + CODE void (*conf_disassociate)(FAR struct ieee802154_mac_s *mac, + int status); - /* PIB data returned */ + /* PIvoata returned */ - CODE int (*conf_get)(FAR struct ieee802154_mac_s *mac, int status, - int attribute, FAR uint8_t *value, - int valuelen); + CODE void (*conf_get)(FAR struct ieee802154_mac_s *mac, int status, + int attribute, FAR uint8_t *value, + int valuelen); - /* GTS management completed */ + /* GTvoanagement completed */ - CODE int (*conf_gts)(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *characteristics, int status); + CODE void (*conf_gts)(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *characteristics, int status); - /* MAC reset completed */ + /* MAveset completed */ - CODE int (*conf_reset)(FAR struct ieee802154_mac_s *mac, int status); + CODE void (*conf_reset)(FAR struct ieee802154_mac_s *mac, int status); - CODE int (*conf_rxenable)(FAR struct ieee802154_mac_s *mac, int status); + CODE void (*conf_rxenable)(FAR struct ieee802154_mac_s *mac, int status); - CODE int (*conf_scan)(FAR struct ieee802154_mac_s *mac, int status, - uint8_t type, uint32_t unscanned, int rsltsize, - FAR uint8_t *edlist, FAR uint8_t *pandescs); + CODE void (*conf_scan)(FAR struct ieee802154_mac_s *mac, int status, + uint8_t type, uint32_t unscanned, int rsltsize, + FAR uint8_t *edlist, FAR uint8_t *pandescs); - CODE int (*conf_set)(FAR struct ieee802154_mac_s *mac, int status, - int attribute); + CODE void (*conf_set)(FAR struct ieee802154_mac_s *mac, int status, + int attribute); - CODE int (*conf_start)(FAR struct ieee802154_mac_s *mac, int status); + CODE void (*conf_start)(FAR struct ieee802154_mac_s *mac, int status); - CODE int (*conf_poll)(FAR struct ieee802154_mac_s *mac, int status); + CODE void (*conf_poll)(FAR struct ieee802154_mac_s *mac, int status); /* Asynchronous event indications, replied to synchronously with responses */ /* Data frame received */ - CODE int (*ind_data)(FAR struct ieee802154_mac_s *mac, FAR uint8_t *buf, - int len); + CODE void (*ind_data)(FAR struct ieee802154_mac_s *mac, FAR uint8_t *buf, + int len); /* Association request received */ - CODE int (*ind_associate)(FAR struct ieee802154_mac_s *mac, - uint16_t clipanid, FAR uint8_t *clieaddr); + CODE void (*ind_associate)(FAR struct ieee802154_mac_s *mac, + uint16_t clipanid, FAR uint8_t *clieaddr); /* Disassociation request received */ - CODE int (*ind_disassociate)(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *eadr, uint8_t reason); + CODE void (*ind_disassociate)(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *eadr, uint8_t reason); /* Beacon notification */ - CODE int (*ind_beaconnotify)(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *bsn, FAR struct ieee802154_pan_desc_s *pandesc, - FAR uint8_t *sdu, int sdulen); + CODE void (*ind_beaconnotify)(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *bsn, FAR struct ieee802154_pan_desc_s *pandesc, + FAR uint8_t *sdu, int sdulen); /* GTS management request received */ - CODE int (*ind_gts)(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *devaddr, FAR uint8_t *characteristics); + CODE void (*ind_gts)(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *devaddr, FAR uint8_t *characteristics); /* Orphan device detected */ - CODE int (*ind_orphan)(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *orphanaddr); + CODE void (*ind_orphan)(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *orphanaddr); - CODE int (*ind_commstatus)(FAR struct ieee802154_mac_s *mac, - uint16_t panid, FAR uint8_t *src, - FAR uint8_t *dst, int status); + CODE void (*ind_commstatus)(FAR struct ieee802154_mac_s *mac, + uint16_t panid, FAR uint8_t *src, + FAR uint8_t *dst, int status); - CODE int (*ind_syncloss)(FAR struct ieee802154_mac_s *mac, int reason); + CODE void (*ind_syncloss)(FAR struct ieee802154_mac_s *mac, int reason); }; struct ieee802154_radio_s; /* Forware reference */ diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index d0a0a3ce50..8e4a3b8055 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -81,7 +81,7 @@ struct ieee802154_privmac_s uint32_t macPad : 3; /* 0x48 */ uint32_t macBeaconTxTime : 24; - /* 0x45 */ uint8_t macBeaconPayload[IEEE802154_aMaxBeaconPayloadLength]; + /* 0x45 */ uint8_t macBeaconPayload[IEEE802154_MAX_BEACON_PAYLOAD_LENGTH]; /* 0x46 */ uint8_t macBeaconPayloadLength; /* 0x49 */ uint8_t macBSN; /* 0x4A */ uint8_t macCoordExtendedAddress[8]; @@ -106,36 +106,41 @@ struct ieee802154_privmac_s * Private Function Prototypes ****************************************************************************/ -static int mac802154_reqdata(FAR struct ieee802154_mac_s *mac, - uint8_t handle, FAR uint8_t *buf, int len); -static int mac802154_reqpurge(FAR struct ieee802154_mac_s *mac, - uint8_t handle); -static int mac802154_reqassociate(FAR struct ieee802154_mac_s *mac, - uint16_t panid, FAR uint8_t *coordeadr); -static int mac802154_reqdisassociate(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *eadr, uint8_t reason); -static int mac802154_reqget(FAR struct ieee802154_mac_s *mac, - int attribute); -static int mac802154_reqgts(FAR struct ieee802154_mac_s *mac, +/* MAC Data Service (MCPS) functions */ + +static int mac802154_req_data(FAR struct ieee802154_mac_s *mac, + FAR struct ieee802154_data_req_s *req); +static int mac802154_req_purge(FAR struct ieee802154_mac_s *mac, + uint8_t handle); + +/* MAC Sublayer Management Entity (MLME) functions */ + +static int mac802154_req_associate(FAR struct ieee802154_mac_s *mac, + FAR struct ieee802154_assoc_req_s *req); +static int mac802154_req_disassociate(FAR struct ieee802154_mac_s *mac, + FAR struct ieee802154_disassoc_req_s *req); +static int mac802154_req_get(FAR struct ieee802154_mac_s *mac, + enum ieee802154_pib_attr_e attr); +static int mac802154_req_gts(FAR struct ieee802154_mac_s *mac, FAR uint8_t *characteristics); -static int mac802154_reqreset(FAR struct ieee802154_mac_s *mac, +static int mac802154_req_reset(FAR struct ieee802154_mac_s *mac, bool setdefaults); -static int mac802154_reqrxenable(FAR struct ieee802154_mac_s *mac, +static int mac802154_req_rxenable(FAR struct ieee802154_mac_s *mac, bool deferrable, int ontime, int duration); -static int mac802154_reqscan(FAR struct ieee802154_mac_s *mac, +static int mac802154_req_scan(FAR struct ieee802154_mac_s *mac, uint8_t type, uint32_t channels, int duration); -static int mac802154_reqset(FAR struct ieee802154_mac_s *mac, +static int mac802154_req_set(FAR struct ieee802154_mac_s *mac, int attribute, FAR uint8_t *value, int valuelen); -static int mac802154_reqstart(FAR struct ieee802154_mac_s *mac, +static int mac802154_req_start(FAR struct ieee802154_mac_s *mac, uint16_t panid, int channel, uint8_t bo, uint8_t fo, bool coord, bool batext, bool realign); -static int mac802154_reqsync(FAR struct ieee802154_mac_s *mac, +static int mac802154_req_sync(FAR struct ieee802154_mac_s *mac, int channel, bool track); -static int mac802154_reqpoll(FAR struct ieee802154_mac_s *mac, +static int mac802154_req_poll(FAR struct ieee802154_mac_s *mac, FAR uint8_t *coordaddr); -static int mac802154_rspassociate(FAR struct ieee802154_mac_s *mac, +static int mac802154_rsp_associate(FAR struct ieee802154_mac_s *mac, uint8_t eadr, uint16_t saddr, int status); -static int mac802154_rsporphan(FAR struct ieee802154_mac_s *mac, +static int mac802154_rsp_orphan(FAR struct ieee802154_mac_s *mac, FAR uint8_t *orphanaddr, uint16_t saddr, bool associated); @@ -145,21 +150,21 @@ static int mac802154_rsporphan(FAR struct ieee802154_mac_s *mac, static const struct ieee802154_macops_s mac802154ops = { - .req_data = mac802154_reqdata, - .req_purge = mac802154_reqpurge, - .req_associate = mac802154_reqassociate, - .req_disassociate = mac802154_reqdisassociate, - .req_get = mac802154_reqget, - .req_gts = mac802154_reqgts, - .req_reset = mac802154_reqreset, - .req_rxenable = mac802154_reqrxenable, - .req_scan = mac802154_reqscan, - .req_set = mac802154_reqset, - .req_start = mac802154_reqstart, - .req_sync = mac802154_reqsync, - .req_poll = mac802154_reqpoll, - .rsp_associate = mac802154_rspassociate, - .rsp_orphan = mac802154_rsporphan, + .req_data = mac802154_req_data, + .req_purge = mac802154_req_purge, + .req_associate = mac802154_req_associate, + .req_disassociate = mac802154_req_disassociate, + .req_get = mac802154_req_get, + .req_gts = mac802154_req_gts, + .req_reset = mac802154_req_reset, + .req_rxenable = mac802154_req_rxenable, + .req_scan = mac802154_req_scan, + .req_set = mac802154_req_set, + .req_start = mac802154_req_start, + .req_sync = mac802154_req_sync, + .req_poll = mac802154_req_poll, + .rsp_associate = mac802154_rsp_associate, + .rsp_orphan = mac802154_rsp_orphan, }; /**************************************************************************** @@ -244,8 +249,8 @@ static int mac802154_applymib(FAR struct ieee802154_privmac_s *priv) * ****************************************************************************/ -static int mac802154_reqdata(FAR struct ieee802154_mac_s *mac, - uint8_t handle, FAR uint8_t *buf, int len) +static int mac802154_req_data(FAR struct ieee802154_mac_s *mac, + FAR struct ieee802154_data_req_s *req) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; @@ -261,7 +266,7 @@ static int mac802154_reqdata(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -static int mac802154_reqpurge(FAR struct ieee802154_mac_s *mac, +static int mac802154_req_purge(FAR struct ieee802154_mac_s *mac, uint8_t handle) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; @@ -269,7 +274,7 @@ static int mac802154_reqpurge(FAR struct ieee802154_mac_s *mac, } /**************************************************************************** - * Name: mac802154_reqassociate + * Name: mac802154_req_associate * * Description: * The MLME-ASSOCIATE.request primitive allows a device to request an @@ -278,15 +283,15 @@ static int mac802154_reqpurge(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -static int mac802154_reqassociate(FAR struct ieee802154_mac_s *mac, - uint16_t panid, FAR uint8_t *coordeadr) +static int mac802154_req_associate(FAR struct ieee802154_mac_s *mac, + FAR struct ieee802154_assoc_req_s *req) { FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } /**************************************************************************** - * Name: mac802154_reqdisassociate + * Name: mac802154_req_disassociate * * Description: * The MLME-DISASSOCIATE.request primitive is used by an associated device to @@ -297,15 +302,15 @@ static int mac802154_reqassociate(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -static int mac802154_reqdisassociate(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *eadr, uint8_t reason) +static int mac802154_req_disassociate(FAR struct ieee802154_mac_s *mac, + FAR struct ieee802154_disassoc_req_s *req) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } /**************************************************************************** - * Name: mac802154_reqget + * Name: mac802154_req_get * * Description: * The MLME-GET.request primitive requests information about a given PIB @@ -314,15 +319,15 @@ static int mac802154_reqdisassociate(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -static int mac802154_reqget(FAR struct ieee802154_mac_s *mac, - int attribute) +static int mac802154_req_get(FAR struct ieee802154_mac_s *mac, + enum ieee802154_pib_attr_e attr) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } /**************************************************************************** - * Name: mac802154_reqgts + * Name: mac802154_req_gts * * Description: * The MLME-GTS.request primitive allows a device to send a request to the PAN @@ -332,15 +337,15 @@ static int mac802154_reqget(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -static int mac802154_reqgts(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *characteristics) +static int mac802154_req_gts(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *characteristics) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } /**************************************************************************** - * Name: mac802154_reqreset + * Name: mac802154_req_reset * * Description: * The MLME-RESET.request primitive allows the next higher layer to request @@ -349,15 +354,15 @@ static int mac802154_reqgts(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -static int mac802154_reqreset(FAR struct ieee802154_mac_s *mac, - bool setdefaults) +static int mac802154_req_reset(FAR struct ieee802154_mac_s *mac, + bool setdefaults) { FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; return -ENOTTY; } /**************************************************************************** - * Name: mac802154_reqrxenable + * Name: mac802154_req_rxenable * * Description: * The MLME-RX-ENABLE.request primitive allows the next higher layer to @@ -367,15 +372,15 @@ static int mac802154_reqreset(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -static int mac802154_reqrxenable(FAR struct ieee802154_mac_s *mac, - bool deferrable, int ontime, int duration) +static int mac802154_req_rxenable(FAR struct ieee802154_mac_s *mac, + bool deferrable, int ontime, int duration) { FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } /**************************************************************************** - * Name: mac802154_reqscan + * Name: mac802154_req_scan * * Description: * The MLME-SCAN.request primitive is used to initiate a channel scan over a @@ -389,15 +394,15 @@ static int mac802154_reqrxenable(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -static int mac802154_reqscan(FAR struct ieee802154_mac_s *mac, - uint8_t type, uint32_t channels, int duration) +static int mac802154_req_scan(FAR struct ieee802154_mac_s *mac, + uint8_t type, uint32_t channels, int duration) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } /**************************************************************************** - * Name: mac802154_reqset + * Name: mac802154_req_set * * Description: * The MLME-SET.request primitive attempts to write the given value to the @@ -406,15 +411,15 @@ static int mac802154_reqscan(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -static int mac802154_reqset(FAR struct ieee802154_mac_s *mac, - int attribute, FAR uint8_t *value, int valuelen) +static int mac802154_req_set(FAR struct ieee802154_mac_s *mac, + int attribute, FAR uint8_t *value, int valuelen) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } /**************************************************************************** - * Name: mac802154_reqstart + * Name: mac802154_req_start * * Description: * The MLME-START.request primitive makes a request for the device to start @@ -423,17 +428,17 @@ static int mac802154_reqset(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -static int mac802154_reqstart(FAR struct ieee802154_mac_s *mac, - uint16_t panid, int channel, uint8_t bo, - uint8_t fo, bool coord, bool batext, - bool realign) +static int mac802154_req_start(FAR struct ieee802154_mac_s *mac, + uint16_t panid, int channel, uint8_t bo, + uint8_t fo, bool coord, bool batext, + bool realign) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } /**************************************************************************** - * Name: mac802154_reqsync + * Name: mac802154_req_sync * * Description: * The MLME-SYNC.request primitive requests to synchronize with the @@ -443,15 +448,15 @@ static int mac802154_reqstart(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -static int mac802154_reqsync(FAR struct ieee802154_mac_s *mac, - int channel, bool track) +static int mac802154_req_sync(FAR struct ieee802154_mac_s *mac, + int channel, bool track) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } /**************************************************************************** - * Name: mac802154_reqpoll + * Name: mac802154_req_poll * * Description: * The MLME-POLL.request primitive prompts the device to request data from the @@ -461,15 +466,15 @@ static int mac802154_reqsync(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -static int mac802154_reqpoll(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *coordaddr) +static int mac802154_req_poll(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *coordaddr) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } /**************************************************************************** - * Name: mac802154_rspassociate + * Name: mac802154_rsp_associate * * Description: * The MLME-ASSOCIATE.response primitive is used to initiate a response to an @@ -477,15 +482,15 @@ static int mac802154_reqpoll(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -static int mac802154_rspassociate(FAR struct ieee802154_mac_s *mac, - uint8_t eadr, uint16_t saddr, int status) +static int mac802154_rsp_associate(FAR struct ieee802154_mac_s *mac, + uint8_t eadr, uint16_t saddr, int status) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } /**************************************************************************** - * Name: mac802154_rsporphan + * Name: mac802154_rsp_orphan * * Description: * The MLME-ORPHAN.response primitive allows the next higher layer of a @@ -493,9 +498,9 @@ static int mac802154_rspassociate(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -static int mac802154_rsporphan(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *orphanaddr, uint16_t saddr, - bool associated) +static int mac802154_rsp_orphan(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *orphanaddr, uint16_t saddr, + bool associated) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; -- GitLab From b7c55660cbaf579bcd56e5a1f8701ed9ee2b9a7d Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 5 Apr 2017 13:04:22 -0600 Subject: [PATCH 348/990] 6loWPAN: Correct more address manipulations. --- configs/sim/sixlowpan/defconfig | 6 +++--- net/sixlowpan/sixlowpan_utils.c | 24 ++++++++++++------------ 2 files changed, 15 insertions(+), 15 deletions(-) diff --git a/configs/sim/sixlowpan/defconfig b/configs/sim/sixlowpan/defconfig index a71e704bfe..8a5d9f766d 100644 --- a/configs/sim/sixlowpan/defconfig +++ b/configs/sim/sixlowpan/defconfig @@ -892,7 +892,7 @@ CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_4=0x0000 CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_5=0x0000 CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_6=0x00ff CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_7=0xfe00 -CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_8=0x3234 +CONFIG_EXAMPLES_NETTEST_CLIENTIPv6ADDR_8=0x1034 CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -1100,7 +1100,7 @@ CONFIG_NSH_IPv6ADDR_4=0x0000 CONFIG_NSH_IPv6ADDR_5=0x0000 CONFIG_NSH_IPv6ADDR_6=0x00ff CONFIG_NSH_IPv6ADDR_7=0xfe00 -CONFIG_NSH_IPv6ADDR_8=0x8bcd +CONFIG_NSH_IPv6ADDR_8=0xa9cd # # Router IPv6 address @@ -1112,7 +1112,7 @@ CONFIG_NSH_DRIPv6ADDR_4=0x0000 CONFIG_NSH_DRIPv6ADDR_5=0x0000 CONFIG_NSH_DRIPv6ADDR_6=0x00ff CONFIG_NSH_DRIPv6ADDR_7=0xfe00 -CONFIG_NSH_DRIPv6ADDR_8=0x3234 +CONFIG_NSH_DRIPv6ADDR_8=0x1034 # # IPv6 Network mask diff --git a/net/sixlowpan/sixlowpan_utils.c b/net/sixlowpan/sixlowpan_utils.c index c7cf3887a0..fc322ec38e 100644 --- a/net/sixlowpan/sixlowpan_utils.c +++ b/net/sixlowpan/sixlowpan_utils.c @@ -73,8 +73,8 @@ * * 128 112 96 80 64 48 32 16 * ---- ---- ---- ---- ---- ---- ---- ---- - * fe80 0000 0000 0000 0000 00ff fe00 xxxx 2-byte Rime address - * fe80 0000 0000 0000 xxxx xxxx xxxx xxxx 8-byte Rime address + * fe80 0000 0000 0000 0000 00ff fe00 xxxx 2-byte Rime address IEEE 48-bit MAC + * fe80 0000 0000 0000 xxxx xxxx xxxx xxxx 8-byte Rime address IEEE EUI-64 * ****************************************************************************/ @@ -107,8 +107,8 @@ void sixlowpan_ipfromrime(FAR const struct rimeaddr_s *rime, * * 128 112 96 80 64 48 32 16 * ---- ---- ---- ---- ---- ---- ---- ---- - * fe80 0000 0000 0000 0000 00ff fe00 xxxx 2-byte Rime address - * fe80 0000 0000 0000 xxxx xxxx xxxx xxxx 8-byte Rime address + * fe80 0000 0000 0000 0000 00ff fe00 xxxx 2-byte Rime address IEEE 48-bit MAC + * fe80 0000 0000 0000 xxxx xxxx xxxx xxxx 8-byte Rime address IEEE EUI-64 * ****************************************************************************/ @@ -135,8 +135,8 @@ void sixlowpan_rimefromip(const net_ipv6addr_t ipaddr, * * 128 112 96 80 64 48 32 16 * ---- ---- ---- ---- ---- ---- ---- ---- - * fe80 0000 0000 0000 0000 00ff fe00 xxxx 2-byte Rime address - * fe80 0000 0000 0000 xxxx xxxx xxxx xxxx 8-byte Rime address + * fe80 0000 0000 0000 0000 00ff fe00 xxxx 2-byte Rime address IEEE 48-bit MAC + * fe80 0000 0000 0000 xxxx xxxx xxxx xxxx 8-byte Rime address IEEE EUI-64 * ****************************************************************************/ @@ -146,13 +146,13 @@ bool sixlowpan_ismacbased(const net_ipv6addr_t ipaddr, FAR const uint8_t *rimeptr = rime->u8; #if CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 2 - return ((ipaddr[4] == htons((GETINT16(rimeptr, 0) ^ 0x0200))) && - ipaddr[5] == 0 && ipaddr[6] == 0 && ipaddr[7] == 0); + return (ipaddr[5] == HTONS(0x00ff) && ipaddr[6] == HTONS(0xfe00) && + ipaddr[7] == htons((GETINT16(rimeptr, 0) ^ 0x0200))); #else /* CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 8 */ - return ((ipaddr[4] == htons((GETINT16(rimeptr, 0) ^ 0x0200))) && - ipaddr[5] == GETINT16(rimeptr, 2) && - ipaddr[6] == GETINT16(rimeptr, 4) && - ipaddr[7] == GETINT16(rimeptr, 6)); + return (ipaddr[4] == htons((GETINT16(rimeptr, 0) ^ 0x0200)) && + ipaddr[5] == GETINT16(rimeptr, 2) && + ipaddr[6] == GETINT16(rimeptr, 4) && + ipaddr[7] == GETINT16(rimeptr, 6)); #endif } -- GitLab From 2ecca492ad5fefa712fe0a2ee5599dcea7c020f6 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Wed, 5 Apr 2017 15:07:58 -0400 Subject: [PATCH 349/990] wireless/ieee802154: WIP for MAC char driver write functionality --- wireless/ieee802154/mac802154_device.c | 82 ++++++++++++++++++++++++-- 1 file changed, 77 insertions(+), 5 deletions(-) diff --git a/wireless/ieee802154/mac802154_device.c b/wireless/ieee802154/mac802154_device.c index 0478522834..d89e9c9b45 100644 --- a/wireless/ieee802154/mac802154_device.c +++ b/wireless/ieee802154/mac802154_device.c @@ -74,6 +74,8 @@ struct mac802154_devwrapper_s */ FAR struct mac802154_open_s *md_open; + + FAR struct mac802154dev_dwait_s *md_dwait; }; /* This structure describes the state of one open mac driver instance */ @@ -89,6 +91,17 @@ struct mac802154_open_s volatile bool md_closing; }; +struct mac802154dev_dwait_s +{ + uint8_t mw_handle; /* The msdu handle identifying the frame */ + sem_t mw_sem; /* The semaphore used to signal the completion */ + int status; /* The success/error of the transaction */ + + /* Supports a singly linked list */ + + FAR struct mac802154dev_dwait_s *mw_flink; +}; + /**************************************************************************** * Private Function Prototypes ****************************************************************************/ @@ -362,7 +375,8 @@ static ssize_t mac802154dev_write(FAR struct file *filep, { FAR struct inode *inode; FAR struct mac802154_devwrapper_s *dev; - struct ieee802154_frame_s frame; + FAR struct ieee802154_data_req_s *req; + struct mac802154dev_dwait_s dwait; int ret; DEBUGASSERT(filep && filep->f_inode); @@ -391,12 +405,37 @@ static ssize_t mac802154dev_write(FAR struct file *filep, wlerr("ERROR: mac802154dev_takesem failed: %d\n", ret); return ret; } - - /* TODO: Send the frame out */ - ret = -ENOTSUP; + + /* Setup the wait struct */ + + dwait.mw_handle = req->msdu_handle; + + /* Link the wait struct */ + + dwait.mw_flink = dev->md_dwait; + dev->md_wait = &dwait; + + /* Pass the request to the MAC layer */ + + ret = dev->md_mac->ops.req_data(dev->md_mac, req); mac802154dev_givesem(&dev->md_exclsem); - return ret; + + if (ret < 0) + { + wlerr("ERROR: req_data failed %d\n", ret); + return ret; + } + + /* Wait for the DATA.confirm callback to be called for our handle */ + + sem_wait(dwait.mw_sem); + + /* The unlinking of the wait struct happens inside the callback. This + * is more efficient since it will already have to find the struct in + * the list in order to perform the sem_post. */ + + return dwait.status; } /**************************************************************************** @@ -444,6 +483,39 @@ static int mac802154dev_ioctl(FAR struct file *filep, int cmd, return ret; } +void mac802154dev_conf_data(FAR struct ieee802154_mac_s *mac, + FAR struct ieee802154_data_conf_s *conf) +{ + FAR struct mac802154_devwrapper_s *dev; + FAR struct mac802154dev_dwait_s *curr; + FAR struct mac802154dev_dwait_s *prev; + int ret; + + /* Get the dev from the callback context. This should have been set when the + * char driver was registered */ + + dev = mac->cbs.cb_context; + + /* Get exclusive access to the driver structure */ + + ret = mac802154dev_takesem(&dev->md_exclsem); + if (ret < 0) + { + wlerr("ERROR: mac802154dev_takesem failed: %d\n", ret); + return ret; + } + + /* Search to see if there is a dwait pending for this transaction */ + + for (prev = NULL, curr = dev->md_dwait; + curr && curr->mw_handle != conf->msdu_handle; + prev = curr, curr = curr->mw_flink); + + + +} + + /**************************************************************************** * Public Functions ****************************************************************************/ -- GitLab From 9893b7243b340decf78ec3391f2f2beafdc63b9b Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 5 Apr 2017 13:28:35 -0600 Subject: [PATCH 350/990] Trivial changes from review of last PR. --- .../wireless/ieee802154/ieee802154_mac.h | 26 +++++++++++++------ wireless/ieee802154/mac802154_device.c | 12 ++++----- 2 files changed, 23 insertions(+), 15 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index 13191bfa40..1299fe9856 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -448,7 +448,8 @@ struct ieee802154_data_req_s uint8_t msdu_handle; /* Handle assoc. with MSDU */ - struct { + struct + { uint8_t ack_tx : 1; /* Acknowledge TX? */ uint8_t gts_tx : 1; /* 1=GTS used for TX, 0=CAP used for TX */ uint8_t indirect_tx : 1; /* Should indirect transmission be used? */ @@ -467,7 +468,8 @@ struct ieee802154_data_req_s /* The UWB preamble symbol repititions * Should be one of: - * 0, 16, 64, 1024, 4096 */ + * 0, 16, 64, 1024, 4096 + */ uint16_t uwb_presym_rep; @@ -480,10 +482,12 @@ struct ieee802154_data_req_s /* The MAC service data unit array that is to be transmitted * This must be at the end of the struct to allow the array - * to continue and make the struct "variable length" */ + * to continue and make the struct "variable length" + */ uint8_t msdu[1]; }; + #define SIZEOF_IEEE802154_DATA_REQ_S(n) \ (sizeof(struct ieee802154_data_req_s) + (n)) @@ -501,22 +505,26 @@ struct ieee802154_data_conf_s bool rng_rcvd; /* Ranging indicated by MSDU */ /* A count of the time units corresponding to an RMARKER at the antenna at - * the beginning of the ranging exchange */ + * the beginning of the ranging exchange + */ uint32_t rng_counter_start; /* A count of the time units corresponding to an RMARKER at the antenna at - * end of the ranging exchange */ + * end of the ranging exchange + */ uint32_t rng_counter_stop; /* A count of the time units in a message exchange over which the tracking - * offset was measured */ + * offset was measured + */ uint34_t rng_tracking_interval; /* A count of the time units slipped or advanced by the radio tracking - * system over the course of the entire tracking interval */ + * system over the course of the entire tracking interval + */ uint32_t rng_offset; @@ -645,7 +653,8 @@ struct ieee802154_assoc_rsp_s struct ieee802154_assoc_conf_s { /* Associated device address ALWAYS passed in short address mode. The - * address will be IEEE802154_SADDR_UNSPEC if association was unsuccessful */ + * address will be IEEE802154_SADDR_UNSPEC if association was unsuccessful. + */ struct ieee802154_addr_s dev_addr; @@ -726,6 +735,7 @@ struct ieee802154_beaconnotify_ind_s uint8_t sdu[IEEE802154_MAX_BEACON_PAYLOAD_LENGTH]; }; + #define SIZEOF_IEEE802154_BEACONNOTIFY_IND_S(n) \ (sizeof(struct ieee802154_beaconnotify_ind_s) \ - IEEE802154_MAX_BEACON_PAYLOAD_LENGTH + (n)) diff --git a/wireless/ieee802154/mac802154_device.c b/wireless/ieee802154/mac802154_device.c index d89e9c9b45..d2bc248980 100644 --- a/wireless/ieee802154/mac802154_device.c +++ b/wireless/ieee802154/mac802154_device.c @@ -433,7 +433,8 @@ static ssize_t mac802154dev_write(FAR struct file *filep, /* The unlinking of the wait struct happens inside the callback. This * is more efficient since it will already have to find the struct in - * the list in order to perform the sem_post. */ + * the list in order to perform the sem_post. + */ return dwait.status; } @@ -491,8 +492,9 @@ void mac802154dev_conf_data(FAR struct ieee802154_mac_s *mac, FAR struct mac802154dev_dwait_s *prev; int ret; - /* Get the dev from the callback context. This should have been set when the - * char driver was registered */ + /* Get the dev from the callback context. This should have been set when + * the char driver was registered. + */ dev = mac->cbs.cb_context; @@ -510,12 +512,8 @@ void mac802154dev_conf_data(FAR struct ieee802154_mac_s *mac, for (prev = NULL, curr = dev->md_dwait; curr && curr->mw_handle != conf->msdu_handle; prev = curr, curr = curr->mw_flink); - - - } - /**************************************************************************** * Public Functions ****************************************************************************/ -- GitLab From e5c4a28c3ad7b70c8a79aadcffe36ce1b46594a6 Mon Sep 17 00:00:00 2001 From: Simon Piriou Date: Sun, 26 Mar 2017 17:42:53 +0200 Subject: [PATCH 351/990] photon: wlan support --- arch/arm/src/stm32/stm32_sdio.c | 26 +- config_wlan | 7 +- configs/photon/scripts/photon_dfu.ld | 10 + configs/photon/src/Makefile | 1 + configs/photon/src/stm32_wlan.c | 10 +- configs/photon/src/stm32_wlan_firmware.c | 17650 ++++++++++++++++ drivers/wireless/ieee80211/Kconfig | 5 + drivers/wireless/ieee80211/Make.defs | 5 + .../wireless/ieee80211/bcm43362_constants.h | 164 + drivers/wireless/ieee80211/bcmf_chip_43362.c | 28 + drivers/wireless/ieee80211/bcmf_chip_43362.h | 8 + drivers/wireless/ieee80211/bcmf_core.c | 390 + drivers/wireless/ieee80211/bcmf_core.h | 83 + drivers/wireless/ieee80211/bcmf_driver.h | 54 + drivers/wireless/ieee80211/bcmf_sdio.c | 399 +- drivers/wireless/ieee80211/bcmf_sdio.h | 21 + drivers/wireless/ieee80211/bcmf_sdio_core.h | 214 + drivers/wireless/ieee80211/bcmf_sdio_regs.h | 167 + drivers/wireless/ieee80211/chip_constants.h | 421 - drivers/wireless/ieee80211/mmc_sdio.c | 19 +- include/nuttx/wireless/ieee80211/bcmf_board.h | 16 + include/nuttx/wireless/ieee80211/mmc_sdio.h | 2 + 22 files changed, 19022 insertions(+), 678 deletions(-) create mode 100644 configs/photon/src/stm32_wlan_firmware.c create mode 100644 drivers/wireless/ieee80211/bcm43362_constants.h create mode 100644 drivers/wireless/ieee80211/bcmf_chip_43362.c create mode 100644 drivers/wireless/ieee80211/bcmf_chip_43362.h create mode 100644 drivers/wireless/ieee80211/bcmf_core.c create mode 100644 drivers/wireless/ieee80211/bcmf_core.h create mode 100644 drivers/wireless/ieee80211/bcmf_driver.h create mode 100644 drivers/wireless/ieee80211/bcmf_sdio.h create mode 100644 drivers/wireless/ieee80211/bcmf_sdio_core.h create mode 100644 drivers/wireless/ieee80211/bcmf_sdio_regs.h delete mode 100644 drivers/wireless/ieee80211/chip_constants.h diff --git a/arch/arm/src/stm32/stm32_sdio.c b/arch/arm/src/stm32/stm32_sdio.c index 7a7cfae725..d3a8884447 100644 --- a/arch/arm/src/stm32/stm32_sdio.c +++ b/arch/arm/src/stm32/stm32_sdio.c @@ -186,7 +186,8 @@ /* Big DTIMER setting */ -#define SDIO_DTIMER_DATATIMEOUT (0x000fffff) +// #define SDIO_DTIMER_DATATIMEOUT (0x000fffff) +#define SDIO_DTIMER_DATATIMEOUT (0xffffffff) /* DMA channel/stream configuration register settings. The following * must be selected. The DMA driver will select the remaining fields. @@ -300,7 +301,7 @@ # endif #endif -#define STM32_SDIO_USE_DEFAULT_BLOCK_SIZE ((uint8_t)-1) +#define STM32_SDIO_USE_DEFAULT_BLOCKSIZE ((uint8_t)-1) /**************************************************************************** * Private Types @@ -468,8 +469,6 @@ static int stm32_recvlong(FAR struct sdio_dev_s *dev, uint32_t cmd, uint32_t rlong[4]); static int stm32_recvshort(FAR struct sdio_dev_s *dev, uint32_t cmd, uint32_t *rshort); -static int stm32_recvnotimpl(FAR struct sdio_dev_s *dev, uint32_t cmd, - uint32_t *rnotimpl); /* EVENT handler */ @@ -1027,8 +1026,11 @@ static void stm32_dataconfig(uint32_t timeout, uint32_t dlen, uint32_t dctrl) regval = getreg32(STM32_SDIO_DCTRL); regval &= ~(SDIO_DCTRL_DTDIR | SDIO_DCTRL_DTMODE | SDIO_DCTRL_DBLOCKSIZE_MASK); dctrl &= (SDIO_DCTRL_DTDIR | SDIO_DCTRL_DTMODE | SDIO_DCTRL_DBLOCKSIZE_MASK); - regval |= (dctrl | SDIO_DCTRL_DTEN); + regval |= (dctrl | SDIO_DCTRL_DTEN | SDIO_DCTRL_SDIOEN); putreg32(regval, STM32_SDIO_DCTRL); + + struct stm32_dev_s *priv = &g_sdiodev; + // mcinfo("data cfg: %08x %08x %08x (bs=%d)\n", timeout, dlen, regval, 1<block_size); } /**************************************************************************** @@ -1868,7 +1870,7 @@ static int stm32_sendcmd(FAR struct sdio_dev_s *dev, uint32_t cmd, uint32_t arg) cmdidx = (cmd & MMCSD_CMDIDX_MASK) >> MMCSD_CMDIDX_SHIFT; regval |= cmdidx | SDIO_CMD_CPSMEN; - mcinfo("cmd: %08x arg: %08x regval: %08x\n", cmd, arg, regval); + // mcinfo("cmd: %08x arg: %08x regval: %08x\n", cmd, arg, regval); /* Write the SDIO CMD */ @@ -2260,7 +2262,7 @@ static int stm32_recvshortcrc(FAR struct sdio_dev_s *dev, uint32_t cmd, uint32_t putreg32(SDIO_RESPDONE_ICR | SDIO_CMDDONE_ICR, STM32_SDIO_ICR); *rshort = getreg32(STM32_SDIO_RESP1); - mcinfo("data: %08x %08x\n", *rshort, respcmd); + // mcinfo("data: %08x %08x\n", *rshort, respcmd); return ret; } @@ -2361,20 +2363,12 @@ static int stm32_recvshort(FAR struct sdio_dev_s *dev, uint32_t cmd, uint32_t *r if (rshort) { *rshort = getreg32(STM32_SDIO_RESP1); - mcinfo("data: %08x\n", *rshort); + // mcinfo("data: %08x\n", *rshort); } return ret; } -/* MMC responses not supported */ - -static int stm32_recvnotimpl(FAR struct sdio_dev_s *dev, uint32_t cmd, uint32_t *rnotimpl) -{ - putreg32(SDIO_RESPDONE_ICR | SDIO_CMDDONE_ICR, STM32_SDIO_ICR); - return -ENOSYS; -} - /**************************************************************************** * Name: stm32_waitenable * diff --git a/config_wlan b/config_wlan index 9e025fe2d9..9eaf60fd64 100644 --- a/config_wlan +++ b/config_wlan @@ -822,8 +822,12 @@ CONFIG_MMCSD_NSLOTS=1 CONFIG_ARCH_HAVE_SDIO=y # CONFIG_SDIO_DMA is not set CONFIG_ARCH_HAVE_SDIOWAIT_WRCOMPLETE=y -# CONFIG_MMCSD_SDIO is not set +CONFIG_MMCSD_SDIO=y CONFIG_SDIO_PREFLIGHT=y +# CONFIG_SDIO_MUXBUS is not set +# CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE is not set +# CONFIG_SDIO_WIDTH_D1_ONLY is not set +CONFIG_SDIO_BLOCKSETUP=y # CONFIG_MODEM is not set # CONFIG_MTD is not set # CONFIG_EEPROM is not set @@ -891,6 +895,7 @@ CONFIG_DRIVERS_WIRELESS=y # CONFIG_DRIVERS_IEEE802154 is not set CONFIG_DRIVERS_IEEE80211=y CONFIG_IEEE80211_BROADCOM_FULLMAC=y +CONFIG_IEEE80211_BROADCOM_BCM43362=y CONFIG_IEEE80211_BROADCOM_FULLMAC_SDIO=y # CONFIG_WL_NRF24L01 is not set # CONFIG_DRIVERS_CONTACTLESS is not set diff --git a/configs/photon/scripts/photon_dfu.ld b/configs/photon/scripts/photon_dfu.ld index e59f501210..7571d7fe90 100644 --- a/configs/photon/scripts/photon_dfu.ld +++ b/configs/photon/scripts/photon_dfu.ld @@ -61,6 +61,16 @@ SECTIONS *(.text .text.*) *(.fixup) *(.gnu.warning) + + . = ALIGN(0x4); + wlan_firmware_image_location = .; + *(.wlan_firmware_image .wlan_firmware_image.*) + wlan_firmware_image_end = .; + . = ALIGN(0x4); + wlan_nvram_image_location = .; + *(.wlan_nvram_image .wlan_nvram_image.*) + wlan_nvram_image_end = .; + *(.rodata .rodata.*) *(.gnu.linkonce.t.*) *(.glue_7) diff --git a/configs/photon/src/Makefile b/configs/photon/src/Makefile index 5d9501759c..b40c6f71aa 100644 --- a/configs/photon/src/Makefile +++ b/configs/photon/src/Makefile @@ -55,6 +55,7 @@ endif ifeq ($(CONFIG_PHOTON_WLAN),y) CSRCS += stm32_wlan.c +CSRCS += stm32_wlan_firmware.c endif ifeq ($(CONFIG_STM32_OTGHS),y) diff --git a/configs/photon/src/stm32_wlan.c b/configs/photon/src/stm32_wlan.c index fdc6f4ed03..1a18981a6f 100644 --- a/configs/photon/src/stm32_wlan.c +++ b/configs/photon/src/stm32_wlan.c @@ -99,20 +99,18 @@ void bcmf_board_initialize(int minor) * Name: bcmf_board_setup_oob_irq ****************************************************************************/ -void bcmf_board_setup_oob_irq(int minor) +void bcmf_board_setup_oob_irq(int minor, xcpt_t func, void *arg) { if (minor != SDIO_WLAN0_MINOR) { return; } - /* Configure reset pin */ + /* Configure interrupt pin */ - stm32_configgpio(GPIO_WLAN0_RESET); + stm32_configgpio(GPIO_WLAN0_OOB_INT); - /* Put wlan chip in reset state */ - - bcmf_board_reset(minor, true); + stm32_gpiosetevent(GPIO_WLAN0_OOB_INT, true, false, false, func, arg); } /**************************************************************************** diff --git a/configs/photon/src/stm32_wlan_firmware.c b/configs/photon/src/stm32_wlan_firmware.c new file mode 100644 index 0000000000..d550643d97 --- /dev/null +++ b/configs/photon/src/stm32_wlan_firmware.c @@ -0,0 +1,17650 @@ +/* + * Copyright (c) 2015 Broadcom + * 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 of Broadcom nor the names of other contributors to this + * software may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * 4. This software may not be used as a standalone product, and may only be used as + * incorporated in your product or device that incorporates Broadcom wireless connectivity + * products and solely for the purpose of enabling the functionalities of such Broadcom products. + * + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + * ANY WARRANTIES OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + * WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT, ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER 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. + */ + +/** @file + * + * BCM43362 NVRAM variables for WM-N-BM-09 USI SiP + * + */ + +#include + +/** + * Character array of NVRAM image + */ + +const char __attribute__((section(".wlan_nvram_image"))) bcmf_nvram_image[] = + "manfid=0x2d0" "\x00" + "prodid=0x492" "\x00" + "vendid=0x14e4" "\x00" + "devid=0x4343" "\x00" + "boardtype=0x0636" "\x00" + "boardrev=0x1201" "\x00" + "boardnum=777" "\x00" + "xtalfreq=26000" "\x00" + "boardflags=0xa00" "\x00" + "sromrev=3" "\x00" + "wl0id=0x431b" "\x00" + "macaddr=02:0A:F7:e0:ae:ce" "\x00" + "aa2g=3" "\x00" + "ag0=2" "\x00" + "maxp2ga0=74" "\x00" + "ofdm2gpo=0x44111111" "\x00" + "mcs2gpo0=0x4444" "\x00" + "mcs2gpo1=0x6444" "\x00" + "pa0maxpwr=80" "\x00" + "pa0b0=5264" "\x00" /*PA params*/ + "pa0b1=64897" "\x00" + "pa0b2=65359" "\x00" + "pa0itssit=62" "\x00" + "pa1itssit=62" "\x00" + "temp_based_dutycy_en=1" "\x00" + "tx_duty_cycle_ofdm=100" "\x00" + "tx_duty_cycle_cck=100" "\x00" + "tx_ofdm_temp_0=115" "\x00" + "tx_cck_temp_0=115" "\x00" + "tx_ofdm_dutycy_0=40" "\x00" + "tx_cck_dutycy_0=40" "\x00" + "tx_ofdm_temp_1=255" "\x00" + "tx_cck_temp_1=255" "\x00" + "tx_ofdm_dutycy_1=40" "\x00" + "tx_cck_dutycy_1=40" "\x00" + "tx_tone_power_index=40" "\x00" + "tx_tone_power_index.fab.3=48" "\x00" + "cckPwrOffset=0" "\x00" + "ccode=0" "\x00" + "rssismf2g=0xa" "\x00" + "rssismc2g=0x3" "\x00" + "rssisav2g=0x7" "\x00" + "triso2g=0" "\x00" + "noise_cal_enable_2g=0" "\x00" + "noise_cal_po_2g=0" "\x00" + "noise_cal_po_2g.fab.3=-2" "\x00" + "swctrlmap_2g=0x0a030a03,0x0c050c05,0x0c050c05,0x0,0x1ff" "\x00" + "temp_add=29767" "\x00" + "temp_mult=425" "\x00" + "temp_q=10" "\x00" + "initxidx2g=45" "\x00" + "tssitime=1" "\x00" + "rfreg033=0x19" "\x00" + "rfreg033_cck=0x1f" "\x00" + "cckPwrIdxCorr=-8" "\x00" + "spuravoid_enable2g=1" "\x00" + "edonthd=-70" "\x00" + "edoffthd=-76" "\x00" + "\x00\x00"; + +const unsigned int bcmf_nvram_image_len = sizeof(bcmf_nvram_image); + +const uint8_t +__attribute__((section(".wlan_firmware_image"))) bcmf_firmware_image[] = { + 0x00, 0x00, 0x00, 0x00, 0xcd, 0xc2, 0x00, 0x00, 0x91, 0xc1, 0x00, 0x00, + 0x91, 0xc1, 0x00, 0x00, 0x91, 0xc1, 0x00, 0x00, 0x91, 0xc1, 0x00, 0x00, + 0x91, 0xc1, 0x00, 0x00, 0x91, 0xc1, 0x00, 0x00, 0x91, 0xc1, 0x00, 0x00, + 0x91, 0xc1, 0x00, 0x00, 0x91, 0xc1, 0x00, 0x00, 0x91, 0xc1, 0x00, 0x00, + 0x91, 0xc1, 0x00, 0x00, 0x91, 0xc1, 0x00, 0x00, 0x91, 0xc1, 0x00, 0x00, + 0x91, 0xc1, 0x00, 0x00, 0x91, 0xc1, 0x00, 0x00, 0x91, 0xc1, 0x00, 0x00, + 0x91, 0xc1, 0x00, 0x00, 0x91, 0xc1, 0x00, 0x00, 0x91, 0xc1, 0x00, 0x00, + 0x91, 0xc1, 0x00, 0x00, 0x91, 0xc1, 0x00, 0x00, 0x91, 0xc1, 0x00, 0x00, + 0x91, 0xc1, 0x00, 0x00, 0x91, 0xc1, 0x00, 0x00, 0x91, 0xc1, 0x00, 0x00, + 0x91, 0xc1, 0x00, 0x00, 0x91, 0xc1, 0x00, 0x00, 0x91, 0xc1, 0x00, 0x00, + 0x91, 0xc1, 0x00, 0x00, 0x91, 0xc1, 0x00, 0x00, 0x00, 0x48, 0x00, 0x47, + 0xcd, 0xc2, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0xd1, 0x1e, 0x80, 0x00, 0xb5, 0x22, 0x80, 0x00, + 0xbd, 0x24, 0x80, 0x00, 0x49, 0x1f, 0x80, 0x00, 0xf9, 0x21, 0x80, 0x00, + 0xe5, 0xf7, 0x00, 0x00, 0xf1, 0x20, 0x80, 0x00, 0xd1, 0x20, 0x80, 0x00, + 0x59, 0x48, 0x80, 0x00, 0x69, 0x48, 0x80, 0x00, 0x15, 0x64, 0x80, 0x00, + 0xe1, 0x62, 0x80, 0x00, 0x29, 0x62, 0x80, 0x00, 0x3d, 0x65, 0x80, 0x00, + 0x8d, 0x62, 0x80, 0x00, 0xc5, 0x62, 0x80, 0x00, 0x59, 0x63, 0x80, 0x00, + 0x5d, 0x65, 0x80, 0x00, 0x7d, 0x63, 0x80, 0x00, 0x9d, 0x63, 0x80, 0x00, + 0x0d, 0x66, 0x80, 0x00, 0xa9, 0x61, 0x80, 0x00, 0x61, 0x61, 0x80, 0x00, + 0x75, 0x60, 0x80, 0x00, 0x95, 0x60, 0x80, 0x00, 0xdd, 0x63, 0x80, 0x00, + 0x9d, 0x65, 0x80, 0x00, 0x29, 0x66, 0x80, 0x00, 0xfd, 0x61, 0x80, 0x00, + 0xb9, 0x65, 0x80, 0x00, 0x1d, 0x61, 0x80, 0x00, 0xf1, 0x65, 0x80, 0x00, + 0x9d, 0x66, 0x80, 0x00, 0x6d, 0x65, 0x80, 0x00, 0x91, 0x6c, 0x80, 0x00, + 0xcd, 0x6b, 0x80, 0x00, 0x31, 0x6c, 0x80, 0x00, 0x8d, 0x6b, 0x80, 0x00, + 0x55, 0x6c, 0x80, 0x00, 0xad, 0x6a, 0x80, 0x00, 0xc1, 0x6a, 0x80, 0x00, + 0xd5, 0x6a, 0x80, 0x00, 0x49, 0x6b, 0x80, 0x00, 0x1d, 0x6a, 0x80, 0x00, + 0xfd, 0x6a, 0x80, 0x00, 0xad, 0x68, 0x80, 0x00, 0xc1, 0x69, 0x80, 0x00, + 0xd1, 0x68, 0x80, 0x00, 0x35, 0x6b, 0x80, 0x00, 0xb1, 0x69, 0x80, 0x00, + 0xa1, 0xc9, 0x00, 0x00, 0xd1, 0x66, 0x80, 0x00, 0xe1, 0x67, 0x80, 0x00, + 0x8d, 0x67, 0x80, 0x00, 0xcd, 0x67, 0x80, 0x00, 0x9d, 0x68, 0x80, 0x00, + 0xed, 0x67, 0x80, 0x00, 0xbd, 0x67, 0x80, 0x00, 0xa1, 0x67, 0x80, 0x00, + 0xed, 0x66, 0x80, 0x00, 0x09, 0x67, 0x80, 0x00, 0x61, 0x67, 0x80, 0x00, + 0x4d, 0x48, 0x80, 0x00, 0x1d, 0x48, 0x80, 0x00, 0x85, 0x98, 0x80, 0x00, + 0xdd, 0x96, 0x80, 0x00, 0x51, 0x94, 0x80, 0x00, 0xb1, 0x9b, 0x80, 0x00, + 0x39, 0x94, 0x80, 0x00, 0x05, 0x98, 0x80, 0x00, 0x19, 0x98, 0x80, 0x00, + 0x2d, 0x98, 0x80, 0x00, 0xc5, 0x9b, 0x80, 0x00, 0xd1, 0x9a, 0x80, 0x00, + 0x89, 0x9d, 0x80, 0x00, 0xd1, 0x93, 0x80, 0x00, 0xd9, 0x91, 0x80, 0x00, + 0xed, 0x9a, 0x80, 0x00, 0x01, 0x29, 0x00, 0x00, 0x79, 0xf7, 0x00, 0x00, + 0x51, 0x29, 0x00, 0x00, 0x55, 0xf7, 0x00, 0x00, 0x51, 0x9b, 0x80, 0x00, + 0x79, 0x29, 0x00, 0x00, 0x49, 0xa9, 0x80, 0x00, 0x99, 0x98, 0x80, 0x00, + 0xb1, 0x29, 0x00, 0x00, 0x31, 0xa8, 0x80, 0x00, 0x05, 0xa7, 0x80, 0x00, + 0x21, 0xa2, 0x80, 0x00, 0xbd, 0x93, 0x80, 0x00, 0xdd, 0x93, 0x80, 0x00, + 0x19, 0x9e, 0x80, 0x00, 0x7d, 0x93, 0x80, 0x00, 0x45, 0x98, 0x80, 0x00, + 0xe5, 0x9b, 0x80, 0x00, 0x6d, 0xa6, 0x80, 0x00, 0xc1, 0x9c, 0x80, 0x00, + 0xc5, 0x9f, 0x80, 0x00, 0xa1, 0x9d, 0x80, 0x00, 0xad, 0x2a, 0x00, 0x00, + 0xa1, 0xf7, 0x00, 0x00, 0xb5, 0xf7, 0x00, 0x00, 0x29, 0xaa, 0x80, 0x00, + 0xb9, 0xa9, 0x80, 0x00, 0x75, 0xaa, 0x80, 0x00, 0xe1, 0xa9, 0x80, 0x00, + 0x39, 0xaa, 0x80, 0x00, 0x8d, 0xaa, 0x80, 0x00, 0x5d, 0xaa, 0x80, 0x00, + 0x0d, 0xaa, 0x80, 0x00, 0xc5, 0xa9, 0x80, 0x00, 0x9d, 0xa9, 0x80, 0x00, + 0xa9, 0x0c, 0x80, 0x00, 0x85, 0x0d, 0x80, 0x00, 0xc1, 0x06, 0x80, 0x00, + 0x29, 0x08, 0x80, 0x00, 0x69, 0x46, 0x80, 0x00, 0x4d, 0x46, 0x80, 0x00, + 0xd9, 0x44, 0x80, 0x00, 0x41, 0x46, 0x80, 0x00, 0x21, 0x44, 0x80, 0x00, + 0xf5, 0x43, 0x80, 0x00, 0x15, 0x44, 0x80, 0x00, 0xe1, 0x43, 0x80, 0x00, + 0xe1, 0x42, 0x80, 0x00, 0x85, 0x46, 0x80, 0x00, 0x75, 0x44, 0x80, 0x00, + 0x2d, 0x44, 0x80, 0x00, 0xa9, 0x42, 0x80, 0x00, 0xf9, 0x42, 0x80, 0x00, + 0xcd, 0x43, 0x80, 0x00, 0xb9, 0x45, 0x80, 0x00, 0xf5, 0x44, 0x80, 0x00, + 0x39, 0x45, 0x80, 0x00, 0x09, 0x00, 0x80, 0x00, 0x3d, 0x00, 0x80, 0x00, + 0x49, 0x01, 0x80, 0x00, 0xd1, 0x04, 0x80, 0x00, 0x0d, 0x04, 0x80, 0x00, + 0x91, 0x03, 0x80, 0x00, 0x4d, 0x03, 0x80, 0x00, 0xe5, 0x03, 0x80, 0x00, + 0x35, 0x03, 0x80, 0x00, 0x65, 0x03, 0x80, 0x00, 0x29, 0x02, 0x80, 0x00, + 0xcd, 0x02, 0x80, 0x00, 0x51, 0x02, 0x80, 0x00, 0x85, 0x02, 0x80, 0x00, + 0xf5, 0x02, 0x80, 0x00, 0x95, 0x06, 0x80, 0x00, 0x39, 0x06, 0x80, 0x00, + 0x81, 0x05, 0x80, 0x00, 0x05, 0x06, 0x80, 0x00, 0xfd, 0x04, 0x80, 0x00, + 0x69, 0x0f, 0x80, 0x00, 0x25, 0x16, 0x80, 0x00, 0x15, 0x16, 0x80, 0x00, + 0x45, 0x13, 0x80, 0x00, 0x15, 0x13, 0x80, 0x00, 0x25, 0x13, 0x80, 0x00, + 0x09, 0x13, 0x80, 0x00, 0x35, 0x13, 0x80, 0x00, 0x0d, 0x1e, 0x80, 0x00, + 0xf9, 0x1d, 0x80, 0x00, 0x29, 0x1d, 0x80, 0x00, 0x1d, 0x1c, 0x80, 0x00, + 0x39, 0x1c, 0x80, 0x00, 0x31, 0x16, 0x80, 0x00, 0x59, 0x13, 0x80, 0x00, + 0x65, 0x0e, 0x80, 0x00, 0x95, 0x13, 0x80, 0x00, 0xb9, 0x1c, 0x80, 0x00, + 0x73, 0x28, 0x00, 0x00, 0x7d, 0x0c, 0x02, 0x00, 0x75, 0x1d, 0x80, 0x00, + 0xbd, 0x04, 0x01, 0x00, 0x3d, 0x1d, 0x80, 0x00, 0x0d, 0x1b, 0x80, 0x00, + 0xe9, 0x10, 0x80, 0x00, 0x79, 0x0f, 0x80, 0x00, 0xa9, 0x16, 0x80, 0x00, + 0x31, 0x14, 0x80, 0x00, 0x2d, 0x11, 0x80, 0x00, 0xa5, 0x1e, 0x80, 0x00, + 0xb1, 0x1e, 0x80, 0x00, 0xbd, 0x1e, 0x80, 0x00, 0x69, 0x2b, 0x80, 0x00, + 0xad, 0x28, 0x80, 0x00, 0x11, 0x29, 0x80, 0x00, 0x89, 0x2b, 0x80, 0x00, + 0xfd, 0x2b, 0x80, 0x00, 0xe1, 0x28, 0x80, 0x00, 0x65, 0x28, 0x80, 0x00, + 0xb5, 0x2c, 0x80, 0x00, 0x91, 0x2c, 0x80, 0x00, 0x1d, 0x2b, 0x80, 0x00, + 0x75, 0x2d, 0x80, 0x00, 0x25, 0x2c, 0x80, 0x00, 0x4d, 0x30, 0x80, 0x00, + 0xdd, 0x2d, 0x80, 0x00, 0x59, 0x27, 0x80, 0x00, 0x31, 0x31, 0x80, 0x00, + 0x01, 0xf7, 0x00, 0x00, 0x8d, 0x26, 0x80, 0x00, 0xc5, 0x26, 0x80, 0x00, + 0xe5, 0x24, 0x80, 0x00, 0xfd, 0x26, 0x80, 0x00, 0x21, 0x25, 0x80, 0x00, + 0xb1, 0x2a, 0x80, 0x00, 0x65, 0x25, 0x80, 0x00, 0x25, 0x28, 0x80, 0x00, + 0x61, 0x29, 0x80, 0x00, 0x41, 0x29, 0x80, 0x00, 0xd9, 0x29, 0x80, 0x00, + 0x9d, 0x29, 0x80, 0x00, 0x81, 0x29, 0x80, 0x00, 0x89, 0x30, 0x80, 0x00, + 0x4d, 0x2e, 0x80, 0x00, 0xb1, 0x2b, 0x80, 0x00, 0x31, 0x2c, 0x80, 0x00, + 0xe1, 0x2c, 0x80, 0x00, 0x61, 0x32, 0x80, 0x00, 0x2d, 0x32, 0x80, 0x00, + 0xc9, 0x33, 0x80, 0x00, 0x4d, 0x36, 0x80, 0x00, 0x69, 0x3a, 0x80, 0x00, + 0xb5, 0x35, 0x80, 0x00, 0xf9, 0x34, 0x80, 0x00, 0xa9, 0x34, 0x80, 0x00, + 0x3d, 0x33, 0x80, 0x00, 0x9d, 0x33, 0x80, 0x00, 0x01, 0x34, 0x80, 0x00, + 0x35, 0x36, 0x80, 0x00, 0x31, 0x38, 0x80, 0x00, 0x35, 0x3a, 0x80, 0x00, + 0x21, 0x3a, 0x80, 0x00, 0xad, 0x32, 0x80, 0x00, 0x0d, 0x33, 0x80, 0x00, + 0xdd, 0x32, 0x80, 0x00, 0x95, 0x3a, 0x80, 0x00, 0xd9, 0x37, 0x80, 0x00, + 0x99, 0x36, 0x80, 0x00, 0x19, 0x37, 0x80, 0x00, 0x59, 0x38, 0x80, 0x00, + 0x49, 0x38, 0x80, 0x00, 0x19, 0x39, 0x80, 0x00, 0x31, 0x3d, 0x80, 0x00, + 0xd5, 0x3a, 0x80, 0x00, 0xc9, 0x3c, 0x80, 0x00, 0xe1, 0x3b, 0x80, 0x00, + 0x51, 0x3d, 0x80, 0x00, 0xd9, 0x3d, 0x80, 0x00, 0xad, 0x3e, 0x80, 0x00, + 0x59, 0x3f, 0x80, 0x00, 0x99, 0x41, 0x80, 0x00, 0x41, 0x47, 0x80, 0x00, + 0xcd, 0x5b, 0x80, 0x00, 0x89, 0x53, 0x80, 0x00, 0x2d, 0x4d, 0x80, 0x00, + 0xa9, 0x4c, 0x80, 0x00, 0xe1, 0x4d, 0x80, 0x00, 0xe9, 0x4f, 0x80, 0x00, + 0xb1, 0x4f, 0x80, 0x00, 0xc9, 0x4e, 0x80, 0x00, 0x8d, 0x4e, 0x80, 0x00, + 0xf1, 0x51, 0x80, 0x00, 0x5d, 0x52, 0x80, 0x00, 0xd1, 0x51, 0x80, 0x00, + 0x2d, 0x52, 0x80, 0x00, 0x01, 0x52, 0x80, 0x00, 0xc9, 0x4f, 0x80, 0x00, + 0x59, 0x4c, 0x80, 0x00, 0x6d, 0x4c, 0x80, 0x00, 0x45, 0x5b, 0x80, 0x00, + 0x39, 0x56, 0x80, 0x00, 0x15, 0x5a, 0x80, 0x00, 0xc9, 0x58, 0x80, 0x00, + 0x31, 0x5a, 0x80, 0x00, 0x81, 0x57, 0x80, 0x00, 0xf9, 0x59, 0x80, 0x00, + 0x1d, 0x56, 0x80, 0x00, 0xad, 0x55, 0x80, 0x00, 0x91, 0x55, 0x80, 0x00, + 0x4d, 0x5a, 0x80, 0x00, 0x2d, 0x55, 0x80, 0x00, 0x71, 0x4b, 0x80, 0x00, + 0x71, 0x54, 0x80, 0x00, 0x09, 0x54, 0x80, 0x00, 0xf5, 0x4d, 0x80, 0x00, + 0x1d, 0x4c, 0x80, 0x00, 0xf9, 0x4b, 0x80, 0x00, 0x09, 0x4c, 0x80, 0x00, + 0x11, 0x4e, 0x80, 0x00, 0x15, 0x58, 0x80, 0x00, 0x0d, 0x03, 0x01, 0x00, + 0x2d, 0x50, 0x80, 0x00, 0xe5, 0x58, 0x80, 0x00, 0x55, 0x56, 0x80, 0x00, + 0x7d, 0x5a, 0x80, 0x00, 0x05, 0x4f, 0x80, 0x00, 0x35, 0x4e, 0x80, 0x00, + 0xd9, 0x55, 0x80, 0x00, 0x51, 0x58, 0x80, 0x00, 0x9d, 0x57, 0x80, 0x00, + 0x59, 0x51, 0x80, 0x00, 0x61, 0x4d, 0x80, 0x00, 0xb1, 0x48, 0x80, 0x00, + 0x5d, 0x5b, 0x80, 0x00, 0x81, 0x52, 0x80, 0x00, 0x49, 0x4c, 0x80, 0x00, + 0x51, 0xfe, 0x00, 0x00, 0xf1, 0x5b, 0x80, 0x00, 0xe5, 0x5c, 0x80, 0x00, + 0xe1, 0x5f, 0x80, 0x00, 0xa5, 0x5e, 0x80, 0x00, 0x7d, 0x5e, 0x80, 0x00, + 0x8d, 0x5c, 0x80, 0x00, 0x01, 0x5c, 0x80, 0x00, 0xa1, 0x5f, 0x80, 0x00, + 0x89, 0x5d, 0x80, 0x00, 0x05, 0x60, 0x80, 0x00, 0x39, 0x5d, 0x80, 0x00, + 0xd1, 0x5e, 0x80, 0x00, 0x49, 0x5e, 0x80, 0x00, 0xed, 0x6c, 0x80, 0x00, + 0x65, 0x6d, 0x80, 0x00, 0xdd, 0x6d, 0x80, 0x00, 0x0d, 0x6d, 0x80, 0x00, + 0x29, 0x6d, 0x80, 0x00, 0x89, 0x6d, 0x80, 0x00, 0xf9, 0x6c, 0x80, 0x00, + 0xd9, 0x6c, 0x80, 0x00, 0x3d, 0x6e, 0x80, 0x00, 0x61, 0x6f, 0x80, 0x00, + 0x75, 0x6e, 0x80, 0x00, 0x05, 0x6e, 0x80, 0x00, 0xa9, 0x74, 0x80, 0x00, + 0x55, 0x75, 0x80, 0x00, 0xd5, 0x74, 0x80, 0x00, 0x05, 0x74, 0x80, 0x00, + 0xd1, 0x7c, 0x80, 0x00, 0x45, 0x7d, 0x80, 0x00, 0x75, 0x7c, 0x80, 0x00, + 0x11, 0x7e, 0x80, 0x00, 0x89, 0x7e, 0x80, 0x00, 0xe9, 0x7e, 0x80, 0x00, + 0x91, 0x7d, 0x80, 0x00, 0x3d, 0x7e, 0x80, 0x00, 0x51, 0x7f, 0x80, 0x00, + 0xa5, 0x81, 0x80, 0x00, 0x65, 0x84, 0x80, 0x00, 0x41, 0x84, 0x80, 0x00, + 0x8d, 0x83, 0x80, 0x00, 0x65, 0x83, 0x80, 0x00, 0x35, 0x85, 0x80, 0x00, + 0xe5, 0x84, 0x80, 0x00, 0x9d, 0x84, 0x80, 0x00, 0x21, 0x85, 0x80, 0x00, + 0x75, 0x84, 0x80, 0x00, 0xbd, 0x83, 0x80, 0x00, 0x5d, 0x85, 0x80, 0x00, + 0xbd, 0x85, 0x80, 0x00, 0x15, 0x8f, 0x80, 0x00, 0x91, 0x8d, 0x80, 0x00, + 0xd5, 0x89, 0x80, 0x00, 0x19, 0x86, 0x80, 0x00, 0x19, 0xab, 0x80, 0x00, + 0x5d, 0xac, 0x80, 0x00, 0xa1, 0xaa, 0x80, 0x00, 0xb5, 0xab, 0x80, 0x00, + 0x5d, 0xab, 0x80, 0x00, 0xfd, 0xb0, 0x80, 0x00, 0x7d, 0xb1, 0x80, 0x00, + 0x65, 0xb0, 0x80, 0x00, 0x6d, 0xae, 0x80, 0x00, 0x85, 0xae, 0x80, 0x00, + 0xed, 0xad, 0x80, 0x00, 0x41, 0xaf, 0x80, 0x00, 0x1d, 0xae, 0x80, 0x00, + 0x31, 0xb1, 0x80, 0x00, 0x3d, 0xb1, 0x80, 0x00, 0xb9, 0xae, 0x80, 0x00, + 0xf5, 0xb1, 0x80, 0x00, 0x79, 0xb0, 0x80, 0x00, 0xfd, 0xad, 0x80, 0x00, + 0x09, 0xb1, 0x80, 0x00, 0x8d, 0xb0, 0x80, 0x00, 0x49, 0xb1, 0x80, 0x00, + 0x69, 0xb1, 0x80, 0x00, 0x4d, 0xae, 0x80, 0x00, 0x3d, 0xae, 0x80, 0x00, + 0x95, 0xae, 0x80, 0x00, 0x29, 0xb3, 0x80, 0x00, 0xc9, 0xae, 0x80, 0x00, + 0xcd, 0xaf, 0x80, 0x00, 0xe5, 0xaf, 0x80, 0x00, 0x25, 0xb0, 0x80, 0x00, + 0x8d, 0xaf, 0x80, 0x00, 0xb5, 0xb2, 0x80, 0x00, 0xfd, 0xb2, 0x80, 0x00, + 0x19, 0xb3, 0x80, 0x00, 0xed, 0xb0, 0x80, 0x00, 0x5d, 0xae, 0x80, 0x00, + 0x2d, 0xae, 0x80, 0x00, 0x29, 0xb2, 0x80, 0x00, 0xa9, 0xb0, 0x80, 0x00, + 0xa1, 0xb1, 0x80, 0x00, 0x05, 0xb2, 0x80, 0x00, 0x39, 0xb2, 0x80, 0x00, + 0xa9, 0xae, 0x80, 0x00, 0x7d, 0xaf, 0x80, 0x00, 0xad, 0xb3, 0x80, 0x00, + 0xa9, 0xbd, 0x80, 0x00, 0x9d, 0xc1, 0x80, 0x00, 0x25, 0xc7, 0x80, 0x00, + 0xdd, 0xc8, 0x80, 0x00, 0x65, 0xca, 0x80, 0x00, 0xe1, 0xcb, 0x80, 0x00, + 0xdd, 0xce, 0x80, 0x00, 0x19, 0xce, 0x80, 0x00, 0x99, 0xce, 0x80, 0x00, + 0x15, 0xcf, 0x80, 0x00, 0xc1, 0x2d, 0x00, 0x00, 0x0d, 0xd8, 0x80, 0x00, + 0xdd, 0xd7, 0x80, 0x00, 0x91, 0xd7, 0x80, 0x00, 0x2d, 0x04, 0x01, 0x00, + 0xb1, 0x2c, 0x00, 0x00, 0x69, 0xd8, 0x80, 0x00, 0x7d, 0xcf, 0x80, 0x00, + 0x45, 0xd9, 0x80, 0x00, 0xf5, 0x03, 0x01, 0x00, 0x99, 0xd1, 0x80, 0x00, + 0x49, 0x03, 0x01, 0x00, 0xf9, 0xe0, 0x80, 0x00, 0x71, 0xf5, 0x80, 0x00, + 0xab, 0x2f, 0x00, 0x00, 0xd1, 0xde, 0x80, 0x00, 0x33, 0xf1, 0x00, 0x00, + 0x09, 0xea, 0x80, 0x00, 0xa1, 0xe4, 0x80, 0x00, 0xf1, 0xf1, 0x00, 0x00, + 0xe1, 0xec, 0x80, 0x00, 0x11, 0xe3, 0x80, 0x00, 0x39, 0xea, 0x80, 0x00, + 0x39, 0xe3, 0x80, 0x00, 0x99, 0xe3, 0x80, 0x00, 0x29, 0xdf, 0x80, 0x00, + 0xeb, 0xf0, 0x00, 0x00, 0x99, 0xf0, 0x00, 0x00, 0x29, 0xf0, 0x00, 0x00, + 0x5d, 0xef, 0x00, 0x00, 0x27, 0xef, 0x00, 0x00, 0xbd, 0xeb, 0x80, 0x00, + 0xb9, 0x2e, 0x00, 0x00, 0x31, 0x2f, 0x00, 0x00, 0x45, 0xf0, 0x00, 0x00, + 0x93, 0xef, 0x00, 0x00, 0xff, 0xf0, 0x00, 0x00, 0xe1, 0xe1, 0x80, 0x00, + 0xa9, 0xe9, 0x80, 0x00, 0x69, 0xf1, 0x00, 0x00, 0x75, 0xf1, 0x00, 0x00, + 0xed, 0xf5, 0x80, 0x00, 0xd9, 0x00, 0x81, 0x00, 0x9d, 0xf6, 0x80, 0x00, + 0xc5, 0xf7, 0x80, 0x00, 0x85, 0xff, 0x80, 0x00, 0x45, 0x01, 0x81, 0x00, + 0xd5, 0x02, 0x81, 0x00, 0x4d, 0x03, 0x81, 0x00, 0xe5, 0x00, 0x81, 0x00, + 0x7d, 0xf6, 0x80, 0x00, 0x81, 0xf7, 0x80, 0x00, 0xd5, 0xf5, 0x80, 0x00, + 0x51, 0xf9, 0x80, 0x00, 0x31, 0xfb, 0x80, 0x00, 0xf1, 0xf6, 0x80, 0x00, + 0xf9, 0xf5, 0x80, 0x00, 0x41, 0xff, 0x80, 0x00, 0xd9, 0xf9, 0x80, 0x00, + 0xdd, 0xfc, 0x80, 0x00, 0xa9, 0xf7, 0x80, 0x00, 0xc9, 0x2f, 0x00, 0x00, + 0x59, 0xfb, 0x80, 0x00, 0x8d, 0xf7, 0x80, 0x00, 0xa5, 0xf9, 0x80, 0x00, + 0x9d, 0x04, 0x01, 0x00, 0x29, 0xf6, 0x80, 0x00, 0xa1, 0xf8, 0x80, 0x00, + 0x5d, 0xf7, 0x80, 0x00, 0x65, 0xf6, 0x80, 0x00, 0x95, 0xfd, 0x80, 0x00, + 0x09, 0x31, 0x00, 0x00, 0xf5, 0x02, 0x81, 0x00, 0x2d, 0x02, 0x81, 0x00, + 0x89, 0x01, 0x81, 0x00, 0x05, 0x01, 0x81, 0x00, 0x21, 0x32, 0x00, 0x00, + 0x99, 0xff, 0x80, 0x00, 0x19, 0xf7, 0x80, 0x00, 0x89, 0xf6, 0x80, 0x00, + 0xc1, 0xf6, 0x80, 0x00, 0x79, 0x04, 0x01, 0x00, 0x85, 0xf5, 0x80, 0x00, + 0x05, 0xf7, 0x80, 0x00, 0xdd, 0xf6, 0x80, 0x00, 0xb1, 0xf6, 0x80, 0x00, + 0xad, 0x6a, 0x81, 0x00, 0xbd, 0x6a, 0x81, 0x00, 0xdd, 0x2f, 0x81, 0x00, + 0xe1, 0x57, 0x81, 0x00, 0xf5, 0x6d, 0x82, 0x00, 0xa9, 0x8d, 0x82, 0x00, + 0x09, 0x25, 0x82, 0x00, 0x19, 0x6e, 0x82, 0x00, 0x01, 0xaa, 0x81, 0x00, + 0x5d, 0x60, 0x82, 0x00, 0xa5, 0x37, 0x82, 0x00, 0xed, 0x69, 0x81, 0x00, + 0x79, 0x59, 0x82, 0x00, 0xe5, 0x58, 0x82, 0x00, 0x1d, 0x59, 0x82, 0x00, + 0xfd, 0x6d, 0x81, 0x00, 0x49, 0x3a, 0x81, 0x00, 0x41, 0xbc, 0x82, 0x00, + 0xe9, 0x5a, 0x82, 0x00, 0xcd, 0x60, 0x81, 0x00, 0xd5, 0x96, 0x81, 0x00, + 0x1d, 0x61, 0x81, 0x00, 0x29, 0x61, 0x81, 0x00, 0x89, 0xbf, 0x81, 0x00, + 0x1d, 0xab, 0x81, 0x00, 0xa9, 0x32, 0x82, 0x00, 0x67, 0x36, 0x00, 0x00, + 0x25, 0x69, 0x81, 0x00, 0x05, 0xa6, 0x81, 0x00, 0x21, 0xad, 0x82, 0x00, + 0x29, 0x58, 0x81, 0x00, 0xbd, 0x3e, 0x81, 0x00, 0xa5, 0x40, 0x81, 0x00, + 0x35, 0x95, 0x81, 0x00, 0x59, 0x9b, 0x81, 0x00, 0x3d, 0x36, 0x82, 0x00, + 0x1d, 0x45, 0x82, 0x00, 0x09, 0x28, 0x81, 0x00, 0x99, 0xa0, 0x81, 0x00, + 0xd1, 0x28, 0x81, 0x00, 0xe9, 0x3b, 0x81, 0x00, 0x8d, 0x28, 0x81, 0x00, + 0x41, 0x6e, 0x82, 0x00, 0x85, 0x9b, 0x81, 0x00, 0x29, 0x5d, 0x81, 0x00, + 0x6d, 0x39, 0x82, 0x00, 0xfd, 0x39, 0x82, 0x00, 0x25, 0x3a, 0x82, 0x00, + 0x95, 0x69, 0x81, 0x00, 0xc9, 0x7a, 0x81, 0x00, 0x91, 0x57, 0x81, 0x00, + 0x5d, 0x57, 0x81, 0x00, 0x75, 0x30, 0x82, 0x00, 0x85, 0x2f, 0x82, 0x00, + 0x35, 0x57, 0x81, 0x00, 0xd1, 0x2f, 0x82, 0x00, 0x21, 0x57, 0x81, 0x00, + 0x49, 0x57, 0x81, 0x00, 0xf5, 0x28, 0x81, 0x00, 0x95, 0xa8, 0x82, 0x00, + 0x2d, 0xa2, 0x82, 0x00, 0x89, 0xd3, 0x81, 0x00, 0xd5, 0x6b, 0x81, 0x00, + 0x59, 0x59, 0x81, 0x00, 0x75, 0x59, 0x81, 0x00, 0xf5, 0x5a, 0x82, 0x00, + 0x05, 0xad, 0x81, 0x00, 0xf1, 0xd2, 0x81, 0x00, 0x39, 0x37, 0x81, 0x00, + 0xed, 0x71, 0x81, 0x00, 0xc5, 0x96, 0x81, 0x00, 0x89, 0x57, 0x82, 0x00, + 0x91, 0x61, 0x82, 0x00, 0xcd, 0x61, 0x82, 0x00, 0xa9, 0x58, 0x81, 0x00, + 0x1d, 0x27, 0x82, 0x00, 0x45, 0x43, 0x82, 0x00, 0x01, 0x44, 0x82, 0x00, + 0x15, 0x6a, 0x81, 0x00, 0x61, 0x4a, 0x81, 0x00, 0xed, 0x4e, 0x81, 0x00, + 0x71, 0x22, 0x82, 0x00, 0x05, 0x5a, 0x81, 0x00, 0x4d, 0x8a, 0x81, 0x00, + 0x75, 0x49, 0x81, 0x00, 0x71, 0x24, 0x82, 0x00, 0xb1, 0x49, 0x81, 0x00, + 0xb1, 0x44, 0x81, 0x00, 0x75, 0xac, 0x82, 0x00, 0x29, 0x2b, 0x82, 0x00, + 0x59, 0x52, 0x81, 0x00, 0xe1, 0x2a, 0x82, 0x00, 0xb5, 0x29, 0x82, 0x00, + 0x71, 0xa7, 0x81, 0x00, 0x35, 0xa7, 0x81, 0x00, 0x01, 0xd4, 0x81, 0x00, + 0xf5, 0xbe, 0x81, 0x00, 0x55, 0xb4, 0x81, 0x00, 0xd1, 0x6a, 0x82, 0x00, + 0xd1, 0x9c, 0x81, 0x00, 0x9d, 0x9c, 0x81, 0x00, 0x95, 0x9b, 0x81, 0x00, + 0xb5, 0x9d, 0x81, 0x00, 0x45, 0x9d, 0x81, 0x00, 0xc5, 0x9d, 0x81, 0x00, + 0x61, 0x70, 0x82, 0x00, 0x09, 0x35, 0x81, 0x00, 0xa1, 0xab, 0x82, 0x00, + 0x8d, 0xab, 0x82, 0x00, 0x75, 0xab, 0x82, 0x00, 0xf1, 0x93, 0x81, 0x00, + 0x99, 0x68, 0x81, 0x00, 0x15, 0xd7, 0x81, 0x00, 0x71, 0xc1, 0x82, 0x00, + 0x7d, 0x2b, 0x81, 0x00, 0xe9, 0x2f, 0x81, 0x00, 0x0d, 0xb6, 0x81, 0x00, + 0x25, 0xbd, 0x82, 0x00, 0x8d, 0x4f, 0x81, 0x00, 0x0d, 0x50, 0x81, 0x00, + 0x85, 0x43, 0x82, 0x00, 0x31, 0xd7, 0x81, 0x00, 0xb1, 0xbd, 0x82, 0x00, + 0x95, 0xc1, 0x82, 0x00, 0x5d, 0xb3, 0x82, 0x00, 0x5f, 0x08, 0x01, 0x00, + 0x8d, 0xd1, 0x81, 0x00, 0xa9, 0x36, 0x81, 0x00, 0xe9, 0xbc, 0x82, 0x00, + 0x29, 0x37, 0x81, 0x00, 0xe9, 0x36, 0x81, 0x00, 0xa1, 0xd6, 0x81, 0x00, + 0xa5, 0x3b, 0x81, 0x00, 0x6d, 0xab, 0x81, 0x00, 0x41, 0xb0, 0x81, 0x00, + 0xd9, 0xf2, 0x00, 0x00, 0x8f, 0xf2, 0x00, 0x00, 0x41, 0xbd, 0x82, 0x00, + 0x95, 0xbe, 0x82, 0x00, 0xcd, 0x2e, 0x82, 0x00, 0x9d, 0x6b, 0x81, 0x00, + 0xcd, 0x45, 0x82, 0x00, 0x45, 0x39, 0x81, 0x00, 0x35, 0x3b, 0x81, 0x00, + 0xbd, 0x3a, 0x81, 0x00, 0xf1, 0xd5, 0x81, 0x00, 0x41, 0x9f, 0x81, 0x00, + 0x11, 0x9f, 0x81, 0x00, 0x71, 0xa4, 0x82, 0x00, 0xad, 0xd5, 0x81, 0x00, + 0xc1, 0x30, 0x81, 0x00, 0xa1, 0x39, 0x82, 0x00, 0x4d, 0x61, 0x81, 0x00, + 0x99, 0x5b, 0x81, 0x00, 0xa5, 0x72, 0x81, 0x00, 0x89, 0xda, 0x81, 0x00, + 0x61, 0xbf, 0x81, 0x00, 0x61, 0x57, 0x82, 0x00, 0x81, 0x21, 0x82, 0x00, + 0xa9, 0x21, 0x82, 0x00, 0xd1, 0xad, 0x82, 0x00, 0x09, 0xbc, 0x82, 0x00, + 0xb5, 0xa1, 0x81, 0x00, 0x9d, 0xca, 0x81, 0x00, 0xb9, 0x2f, 0x82, 0x00, + 0xd9, 0xbb, 0x82, 0x00, 0x11, 0x30, 0x82, 0x00, 0x7d, 0xad, 0x82, 0x00, + 0xcd, 0xa4, 0x81, 0x00, 0x99, 0xa4, 0x81, 0x00, 0xcd, 0xab, 0x82, 0x00, + 0x15, 0xab, 0x82, 0x00, 0xc1, 0xaa, 0x82, 0x00, 0xb9, 0x98, 0x81, 0x00, + 0x81, 0xa5, 0x81, 0x00, 0xd9, 0xd0, 0x81, 0x00, 0xa9, 0xcf, 0x81, 0x00, + 0xe9, 0x3b, 0x82, 0x00, 0xed, 0xcf, 0x81, 0x00, 0x65, 0xd1, 0x81, 0x00, + 0x79, 0xd1, 0x81, 0x00, 0x51, 0xd0, 0x81, 0x00, 0x65, 0xd0, 0x81, 0x00, + 0xe5, 0x21, 0x82, 0x00, 0x11, 0x22, 0x82, 0x00, 0xbb, 0x52, 0x00, 0x00, + 0x19, 0x53, 0x00, 0x00, 0xfd, 0x9c, 0x81, 0x00, 0x91, 0x45, 0x82, 0x00, + 0x55, 0xae, 0x82, 0x00, 0x41, 0xb4, 0x81, 0x00, 0x95, 0xbd, 0x81, 0x00, + 0xf1, 0x8a, 0x82, 0x00, 0x09, 0x8b, 0x82, 0x00, 0x79, 0xd9, 0x81, 0x00, + 0x7d, 0x61, 0x82, 0x00, 0xcd, 0xa4, 0x82, 0x00, 0x41, 0x91, 0x81, 0x00, + 0xa1, 0x3f, 0x82, 0x00, 0x35, 0x94, 0x82, 0x00, 0x49, 0x94, 0x82, 0x00, + 0x89, 0x89, 0x82, 0x00, 0x5d, 0xc1, 0x82, 0x00, 0xf1, 0xc1, 0x82, 0x00, + 0xd1, 0x3b, 0x82, 0x00, 0xd5, 0x95, 0x82, 0x00, 0xe5, 0x60, 0x81, 0x00, + 0x09, 0x20, 0x82, 0x00, 0x39, 0xf7, 0x00, 0x00, 0xbd, 0x3b, 0x82, 0x00, + 0x75, 0xa1, 0x82, 0x00, 0x25, 0xa5, 0x82, 0x00, 0x25, 0x3b, 0x82, 0x00, + 0xe9, 0x3a, 0x82, 0x00, 0x75, 0x3a, 0x82, 0x00, 0xf1, 0x30, 0x82, 0x00, + 0xb1, 0x30, 0x82, 0x00, 0x71, 0xd7, 0x81, 0x00, 0x45, 0x99, 0x82, 0x00, + 0x91, 0xd7, 0x81, 0x00, 0x89, 0x94, 0x82, 0x00, 0xdd, 0xc1, 0x82, 0x00, + 0xa9, 0x6a, 0x82, 0x00, 0x25, 0x6b, 0x82, 0x00, 0xc9, 0x44, 0x81, 0x00, + 0x29, 0x45, 0x81, 0x00, 0x59, 0x6b, 0x81, 0x00, 0x59, 0x49, 0x81, 0x00, + 0xed, 0xaa, 0x81, 0x00, 0x69, 0x61, 0x82, 0x00, 0xad, 0x24, 0x82, 0x00, + 0x05, 0x36, 0x81, 0x00, 0xd5, 0x35, 0x81, 0x00, 0x79, 0xd0, 0x81, 0x00, + 0xa5, 0xd0, 0x81, 0x00, 0x71, 0x5c, 0x81, 0x00, 0xe1, 0xad, 0x81, 0x00, + 0xed, 0xd0, 0x81, 0x00, 0x49, 0xc9, 0x81, 0x00, 0x4d, 0xd8, 0x81, 0x00, + 0x89, 0x3d, 0x82, 0x00, 0x49, 0x20, 0x82, 0x00, 0x65, 0x96, 0x82, 0x00, + 0xf9, 0x25, 0x82, 0x00, 0x89, 0xcf, 0x81, 0x00, 0x85, 0x6a, 0x82, 0x00, + 0x15, 0x93, 0x82, 0x00, 0x2d, 0x5d, 0x82, 0x00, 0xe9, 0xca, 0x81, 0x00, + 0x6d, 0x40, 0x82, 0x00, 0x61, 0x30, 0x82, 0x00, 0x15, 0x48, 0x82, 0x00, + 0x31, 0x3c, 0x81, 0x00, 0x61, 0xd6, 0x81, 0x00, 0x11, 0x4e, 0x81, 0x00, + 0x91, 0x33, 0x00, 0x00, 0x41, 0xa1, 0x81, 0x00, 0x15, 0xa6, 0x81, 0x00, + 0x09, 0x99, 0x82, 0x00, 0xe5, 0xc9, 0x81, 0x00, 0xb1, 0xd7, 0x81, 0x00, + 0x35, 0xc0, 0x82, 0x00, 0x29, 0x4a, 0x81, 0x00, 0x41, 0xad, 0x81, 0x00, + 0xed, 0xbe, 0x82, 0x00, 0x2d, 0xbe, 0x82, 0x00, 0x05, 0xbe, 0x82, 0x00, + 0x79, 0xbe, 0x82, 0x00, 0x55, 0x32, 0x81, 0x00, 0xa5, 0x95, 0x81, 0x00, + 0xb1, 0x59, 0x81, 0x00, 0xe5, 0x47, 0x81, 0x00, 0x91, 0x52, 0x81, 0x00, + 0x15, 0x63, 0x81, 0x00, 0x95, 0x64, 0x81, 0x00, 0x8d, 0x66, 0x81, 0x00, + 0x59, 0x2c, 0x81, 0x00, 0x39, 0x2c, 0x81, 0x00, 0x21, 0x2e, 0x81, 0x00, + 0x65, 0x35, 0x82, 0x00, 0xd5, 0x57, 0x82, 0x00, 0x35, 0x2b, 0x82, 0x00, + 0x99, 0x60, 0x82, 0x00, 0x01, 0x61, 0x82, 0x00, 0x1d, 0x40, 0x82, 0x00, + 0x1d, 0x20, 0x82, 0x00, 0x1d, 0xd8, 0x81, 0x00, 0xa9, 0xac, 0x82, 0x00, + 0xf1, 0xab, 0x82, 0x00, 0xf5, 0x2b, 0x82, 0x00, 0x41, 0xae, 0x82, 0x00, + 0xf9, 0x02, 0x01, 0x00, 0x35, 0x6a, 0x81, 0x00, 0x09, 0xae, 0x82, 0x00, + 0x69, 0x6d, 0x82, 0x00, 0x09, 0x8c, 0x81, 0x00, 0xd5, 0x8b, 0x81, 0x00, + 0x11, 0x6f, 0x81, 0x00, 0x81, 0x90, 0x81, 0x00, 0x29, 0x6c, 0x82, 0x00, + 0xdd, 0xa1, 0x81, 0x00, 0xe9, 0x2b, 0x81, 0x00, 0x55, 0x2f, 0x82, 0x00, + 0x39, 0x8c, 0x81, 0x00, 0xa5, 0x5a, 0x82, 0x00, 0x35, 0x5c, 0x82, 0x00, + 0x45, 0xbb, 0x82, 0x00, 0x91, 0xbe, 0x81, 0x00, 0x2d, 0x6e, 0x81, 0x00, + 0x11, 0x5c, 0x82, 0x00, 0x25, 0x8a, 0x81, 0x00, 0x4d, 0x93, 0x81, 0x00, + 0x89, 0x38, 0x82, 0x00, 0xd5, 0x37, 0x82, 0x00, 0x55, 0x5a, 0x81, 0x00, + 0x01, 0x38, 0x82, 0x00, 0x8d, 0x03, 0x81, 0x00, 0xe9, 0x20, 0x82, 0x00, + 0xe1, 0x3e, 0x82, 0x00, 0x91, 0x45, 0x81, 0x00, 0x2d, 0x6d, 0x81, 0x00, + 0x0d, 0x58, 0x82, 0x00, 0x21, 0x47, 0x82, 0x00, 0xfd, 0xce, 0x81, 0x00, + 0x11, 0xca, 0x81, 0x00, 0x59, 0x36, 0x82, 0x00, 0x9f, 0x4b, 0x00, 0x00, + 0x25, 0xcb, 0x81, 0x00, 0x91, 0x2e, 0x81, 0x00, 0x2d, 0x2f, 0x81, 0x00, + 0xb9, 0x3a, 0x82, 0x00, 0x8d, 0xf2, 0x00, 0x00, 0xdd, 0xa9, 0x81, 0x00, + 0x31, 0xd4, 0x81, 0x00, 0xd1, 0xb3, 0x82, 0x00, 0xad, 0xa9, 0x81, 0x00, + 0xd5, 0x38, 0x82, 0x00, 0x8d, 0xd8, 0x81, 0x00, 0x55, 0x5e, 0x82, 0x00, + 0x71, 0x9a, 0x81, 0x00, 0x15, 0x41, 0x82, 0x00, 0x35, 0xda, 0x81, 0x00, + 0x19, 0x25, 0x82, 0x00, 0x69, 0x26, 0x82, 0x00, 0x35, 0x35, 0x81, 0x00, + 0x41, 0x08, 0x01, 0x00, 0x3d, 0x71, 0x81, 0x00, 0x01, 0x2d, 0x81, 0x00, + 0x09, 0xa2, 0x82, 0x00, 0x0d, 0x23, 0x82, 0x00, 0xfd, 0x71, 0x81, 0x00, + 0xd9, 0x60, 0x82, 0x00, 0x51, 0x72, 0x81, 0x00, 0x41, 0x61, 0x82, 0x00, + 0x45, 0x28, 0x81, 0x00, 0xc1, 0x23, 0x82, 0x00, 0x8d, 0x6c, 0x81, 0x00, + 0x6d, 0x23, 0x82, 0x00, 0x95, 0x47, 0x81, 0x00, 0xb9, 0xd9, 0x81, 0x00, + 0xb5, 0x34, 0x81, 0x00, 0x75, 0xc9, 0x81, 0x00, 0xf1, 0x34, 0x81, 0x00, + 0x2d, 0xbf, 0x81, 0x00, 0x59, 0xaf, 0x82, 0x00, 0xd9, 0x3c, 0x81, 0x00, + 0x49, 0x4f, 0x81, 0x00, 0xe5, 0xab, 0x81, 0x00, 0x35, 0xfd, 0x00, 0x00, + 0x79, 0x31, 0x81, 0x00, 0x05, 0x95, 0x82, 0x00, 0x61, 0x4c, 0x00, 0x00, + 0xdd, 0x93, 0x82, 0x00, 0xa5, 0x66, 0x82, 0x00, 0x0d, 0xc8, 0x81, 0x00, + 0x09, 0x5e, 0x81, 0x00, 0x7d, 0x75, 0x81, 0x00, 0x15, 0x62, 0x81, 0x00, + 0x91, 0x59, 0x81, 0x00, 0x51, 0x4f, 0x00, 0x00, 0x11, 0x49, 0x81, 0x00, + 0xc1, 0x48, 0x81, 0x00, 0xb9, 0xbf, 0x81, 0x00, 0xa5, 0x45, 0x82, 0x00, + 0xf5, 0x59, 0x82, 0x00, 0xf1, 0xa9, 0x82, 0x00, 0x41, 0xa6, 0x82, 0x00, + 0x39, 0x58, 0x82, 0x00, 0xbd, 0x42, 0x82, 0x00, 0xbd, 0xa7, 0x82, 0x00, + 0x4d, 0x22, 0x82, 0x00, 0x71, 0xa7, 0x82, 0x00, 0xa5, 0xa7, 0x82, 0x00, + 0xe1, 0x5c, 0x81, 0x00, 0xed, 0x41, 0x82, 0x00, 0xd1, 0xa7, 0x82, 0x00, + 0xd1, 0x68, 0x81, 0x00, 0xb5, 0xcc, 0x81, 0x00, 0x15, 0xaf, 0x82, 0x00, + 0x95, 0x41, 0x81, 0x00, 0xe1, 0xc8, 0x81, 0x00, 0x89, 0xaa, 0x81, 0x00, + 0xe9, 0x96, 0x81, 0x00, 0x7d, 0x2f, 0x81, 0x00, 0x39, 0x39, 0x00, 0x00, + 0x49, 0x42, 0x82, 0x00, 0x59, 0x44, 0x82, 0x00, 0xfd, 0x07, 0x01, 0x00, + 0x31, 0x31, 0x82, 0x00, 0x61, 0x49, 0x82, 0x00, 0x4d, 0x49, 0x82, 0x00, + 0x0d, 0xa5, 0x81, 0x00, 0x09, 0x5e, 0x82, 0x00, 0x25, 0x3e, 0x82, 0x00, + 0xcd, 0xcd, 0x81, 0x00, 0x29, 0xb3, 0x82, 0x00, 0x21, 0x51, 0x81, 0x00, + 0x45, 0xb1, 0x82, 0x00, 0xa9, 0x1d, 0x82, 0x00, 0x79, 0xbc, 0x82, 0x00, + 0xd1, 0x56, 0x81, 0x00, 0x59, 0x9d, 0x81, 0x00, 0x99, 0x9d, 0x81, 0x00, + 0x19, 0x1c, 0x82, 0x00, 0x51, 0x3f, 0x82, 0x00, 0x1d, 0x30, 0x81, 0x00, + 0xc9, 0xbd, 0x81, 0x00, 0x15, 0x38, 0x81, 0x00, 0x79, 0x4a, 0x81, 0x00, + 0xdd, 0x9b, 0x81, 0x00, 0x19, 0x9e, 0x81, 0x00, 0x69, 0x61, 0x81, 0x00, + 0x89, 0x6e, 0x81, 0x00, 0xb5, 0x70, 0x81, 0x00, 0xd1, 0x32, 0x82, 0x00, + 0xf1, 0x57, 0x81, 0x00, 0xa9, 0x33, 0x82, 0x00, 0x9d, 0x5a, 0x81, 0x00, + 0x3d, 0x35, 0x82, 0x00, 0x89, 0x33, 0x82, 0x00, 0xd9, 0x6e, 0x81, 0x00, + 0x45, 0x70, 0x81, 0x00, 0xfd, 0x61, 0x81, 0x00, 0x59, 0x4b, 0x81, 0x00, + 0x0d, 0x9c, 0x81, 0x00, 0x55, 0x8b, 0x82, 0x00, 0xf1, 0x8e, 0x82, 0x00, + 0xe5, 0x9a, 0x81, 0x00, 0xbd, 0x35, 0x82, 0x00, 0x49, 0x36, 0x81, 0x00, + 0x29, 0x1f, 0x82, 0x00, 0x65, 0x5c, 0x82, 0x00, 0x91, 0xfe, 0x00, 0x00, + 0x51, 0x6f, 0x81, 0x00, 0x29, 0x9b, 0x81, 0x00, 0xa5, 0x6d, 0x81, 0x00, + 0xb5, 0xa2, 0x82, 0x00, 0xe1, 0xaf, 0x82, 0x00, 0xa9, 0x56, 0x82, 0x00, + 0x89, 0x44, 0x81, 0x00, 0x3d, 0x57, 0x82, 0x00, 0xe1, 0x6f, 0x82, 0x00, + 0x01, 0x6f, 0x82, 0x00, 0xdd, 0x72, 0x82, 0x00, 0xe5, 0x3e, 0x81, 0x00, + 0x95, 0x51, 0x81, 0x00, 0xfd, 0xd4, 0x81, 0x00, 0xf5, 0xbc, 0x81, 0x00, + 0x81, 0xb4, 0x81, 0x00, 0xf1, 0x99, 0x81, 0x00, 0x19, 0x31, 0x81, 0x00, + 0x35, 0x8a, 0x82, 0x00, 0xdd, 0xda, 0x81, 0x00, 0x41, 0x3d, 0x81, 0x00, + 0x2d, 0x3e, 0x81, 0x00, 0xe9, 0x89, 0x82, 0x00, 0xc1, 0xd4, 0x81, 0x00, + 0xfd, 0x8d, 0x82, 0x00, 0x99, 0xb6, 0x81, 0x00, 0xbd, 0xa7, 0x81, 0x00, + 0x3d, 0x9f, 0x82, 0x00, 0x5d, 0x03, 0x81, 0x00, 0x6d, 0x92, 0x82, 0x00, + 0x21, 0x8b, 0x82, 0x00, 0x59, 0x9a, 0x81, 0x00, 0xed, 0x27, 0x81, 0x00, + 0xed, 0x94, 0x82, 0x00, 0xfd, 0x8a, 0x81, 0x00, 0x9d, 0x8a, 0x81, 0x00, + 0x41, 0x6b, 0x81, 0x00, 0xe1, 0x6f, 0x81, 0x00, 0x5d, 0x46, 0x82, 0x00, + 0xa1, 0x94, 0x82, 0x00, 0x9d, 0x89, 0x82, 0x00, 0xc9, 0x92, 0x82, 0x00, + 0x79, 0x99, 0x81, 0x00, 0xb1, 0x90, 0x82, 0x00, 0x21, 0x91, 0x82, 0x00, + 0x1d, 0x34, 0x81, 0x00, 0x99, 0xb2, 0x82, 0x00, 0xdd, 0x6a, 0x82, 0x00, + 0x8d, 0xc9, 0x81, 0x00, 0x59, 0x27, 0x82, 0x00, 0xe3, 0x02, 0x01, 0x00, + 0xd9, 0x90, 0x81, 0x00, 0xa5, 0x6b, 0x82, 0x00, 0x6d, 0x3c, 0x82, 0x00, + 0xe5, 0x6d, 0x82, 0x00, 0x05, 0xc2, 0x82, 0x00, 0xc9, 0x6a, 0x81, 0x00, + 0xed, 0x45, 0x82, 0x00, 0x81, 0x6b, 0x81, 0x00, 0x35, 0x3f, 0x82, 0x00, + 0xfd, 0x90, 0x82, 0x00, 0x71, 0xbc, 0x81, 0x00, 0xf1, 0x6b, 0x81, 0x00, + 0x3d, 0x4e, 0x82, 0x00, 0x51, 0x4a, 0x82, 0x00, 0x3d, 0xa2, 0x81, 0x00, + 0x85, 0x06, 0x01, 0x00, 0xd5, 0x54, 0x00, 0x00, 0xb9, 0x7e, 0x82, 0x00, + 0x69, 0x88, 0x82, 0x00, 0x69, 0x5a, 0x82, 0x00, 0xdd, 0x2e, 0x81, 0x00, + 0x15, 0x13, 0x82, 0x00, 0x11, 0x73, 0x81, 0x00, 0x69, 0x80, 0x82, 0x00, + 0x9d, 0x91, 0x81, 0x00, 0x5d, 0x8b, 0x81, 0x00, 0x81, 0x6c, 0x82, 0x00, + 0x8d, 0x8f, 0x81, 0x00, 0x4d, 0x8f, 0x81, 0x00, 0x09, 0x88, 0x81, 0x00, + 0xbd, 0x6d, 0x82, 0x00, 0x01, 0x8e, 0x81, 0x00, 0x1d, 0x5e, 0x82, 0x00, + 0x91, 0x71, 0x81, 0x00, 0xc1, 0x27, 0x81, 0x00, 0x79, 0x75, 0x82, 0x00, + 0x2d, 0xbe, 0x81, 0x00, 0x2d, 0x5b, 0x82, 0x00, 0xe9, 0xa5, 0x82, 0x00, + 0xb5, 0x72, 0x82, 0x00, 0x05, 0x61, 0x00, 0x00, 0x21, 0x7d, 0x82, 0x00, + 0x4d, 0x80, 0x82, 0x00, 0x8d, 0x7f, 0x82, 0x00, 0x01, 0xa0, 0x81, 0x00, + 0xed, 0x7f, 0x82, 0x00, 0x2d, 0x41, 0x81, 0x00, 0xf9, 0x84, 0x81, 0x00, + 0x61, 0x85, 0x82, 0x00, 0x45, 0x72, 0x82, 0x00, 0xf9, 0x54, 0x81, 0x00, + 0x69, 0x2b, 0x82, 0x00, 0x69, 0x51, 0x81, 0x00, 0xc5, 0x55, 0x81, 0x00, + 0x31, 0x56, 0x81, 0x00, 0xa1, 0xa6, 0x81, 0x00, 0x71, 0x50, 0x81, 0x00, + 0x39, 0x2a, 0x82, 0x00, 0x61, 0x53, 0x81, 0x00, 0xc5, 0x73, 0x81, 0x00, + 0xd5, 0x6a, 0x00, 0x00, 0xf1, 0x97, 0x81, 0x00, 0xa9, 0x9b, 0x81, 0x00, + 0xfd, 0x3b, 0x82, 0x00, 0x25, 0xa0, 0x82, 0x00, 0xdd, 0x39, 0x81, 0x00, + 0x71, 0x5d, 0x81, 0x00, 0xbf, 0xfe, 0x00, 0x00, 0x49, 0x95, 0x81, 0x00, + 0x09, 0xcc, 0x81, 0x00, 0x21, 0xa3, 0x82, 0x00, 0x45, 0xaa, 0x81, 0x00, + 0xad, 0x81, 0x82, 0x00, 0x91, 0x67, 0x82, 0x00, 0xbd, 0x85, 0x00, 0x00, + 0x7d, 0x70, 0x82, 0x00, 0xe1, 0x2f, 0x82, 0x00, 0xe9, 0x03, 0x81, 0x00, + 0x81, 0xdb, 0x81, 0x00, 0x95, 0x24, 0x82, 0x00, 0x69, 0x89, 0x82, 0x00, + 0x89, 0xc3, 0x82, 0x00, 0xc5, 0xc4, 0x82, 0x00, 0xbd, 0xf6, 0x00, 0x00, + 0xb1, 0xeb, 0x82, 0x00, 0x09, 0xcb, 0x82, 0x00, 0x0d, 0xcc, 0x82, 0x00, + 0x59, 0xeb, 0x82, 0x00, 0x61, 0xe9, 0x82, 0x00, 0x15, 0xf1, 0x82, 0x00, + 0xe9, 0xcd, 0x82, 0x00, 0x45, 0xdf, 0x82, 0x00, 0x09, 0xf1, 0x82, 0x00, + 0x8d, 0xf7, 0x82, 0x00, 0x8d, 0xca, 0x82, 0x00, 0x89, 0xf3, 0x82, 0x00, + 0xd5, 0xca, 0x82, 0x00, 0xa1, 0x09, 0x83, 0x00, 0xc9, 0xf7, 0x82, 0x00, + 0xfd, 0xef, 0x82, 0x00, 0x99, 0xf8, 0x82, 0x00, 0x25, 0xf9, 0x82, 0x00, + 0x39, 0xfa, 0x82, 0x00, 0x89, 0xed, 0x82, 0x00, 0xc9, 0x88, 0x00, 0x00, + 0xad, 0xe5, 0x82, 0x00, 0x65, 0xda, 0x82, 0x00, 0x7d, 0xc5, 0x82, 0x00, + 0x2d, 0xe6, 0x82, 0x00, 0xb1, 0x89, 0x00, 0x00, 0x31, 0xe4, 0x82, 0x00, + 0xe5, 0xf1, 0x82, 0x00, 0x9d, 0xc8, 0x82, 0x00, 0x55, 0xf3, 0x82, 0x00, + 0x37, 0xfe, 0x00, 0x00, 0x61, 0xc7, 0x82, 0x00, 0xcd, 0xe1, 0x82, 0x00, + 0x6d, 0xe1, 0x82, 0x00, 0xa5, 0xe2, 0x82, 0x00, 0x59, 0xdf, 0x82, 0x00, + 0x29, 0xf4, 0x82, 0x00, 0x09, 0xc7, 0x82, 0x00, 0x55, 0xef, 0x82, 0x00, + 0xe9, 0xec, 0x82, 0x00, 0xd9, 0x07, 0x01, 0x00, 0xbd, 0xdd, 0x82, 0x00, + 0xe1, 0xc5, 0x82, 0x00, 0x4d, 0xe5, 0x82, 0x00, 0x05, 0xe0, 0x82, 0x00, + 0xa5, 0xf9, 0x82, 0x00, 0x0d, 0xc5, 0x82, 0x00, 0x51, 0x8f, 0x00, 0x00, + 0xd9, 0x8a, 0x00, 0x00, 0xad, 0x8b, 0x00, 0x00, 0x91, 0xe6, 0x82, 0x00, + 0xbd, 0xcc, 0x82, 0x00, 0xfd, 0xe9, 0x82, 0x00, 0x8d, 0xd1, 0x82, 0x00, + 0x2d, 0xf1, 0x82, 0x00, 0x2d, 0xf7, 0x82, 0x00, 0x95, 0xfb, 0x82, 0x00, + 0x69, 0xce, 0x82, 0x00, 0xa1, 0xf0, 0x82, 0x00, 0xd5, 0xf0, 0x82, 0x00, + 0xf5, 0xcc, 0x82, 0x00, 0x5f, 0x8c, 0x00, 0x00, 0x81, 0xd9, 0x82, 0x00, + 0x45, 0xc5, 0x82, 0x00, 0xfd, 0xcb, 0x82, 0x00, 0x25, 0xcb, 0x82, 0x00, + 0xbd, 0xeb, 0x82, 0x00, 0x1d, 0xdb, 0x82, 0x00, 0x15, 0xcd, 0x82, 0x00, + 0xf1, 0x8c, 0x00, 0x00, 0xcd, 0xe6, 0x82, 0x00, 0x4d, 0xcf, 0x82, 0x00, + 0x9d, 0xcb, 0x82, 0x00, 0x45, 0x0c, 0x83, 0x00, 0xe5, 0x0d, 0x83, 0x00, + 0x59, 0x0e, 0x83, 0x00, 0x41, 0x0e, 0x83, 0x00, 0x01, 0x0b, 0x83, 0x00, + 0x4d, 0x0a, 0x83, 0x00, 0xd1, 0x0d, 0x83, 0x00, 0x31, 0x0c, 0x83, 0x00, + 0x59, 0x0c, 0x83, 0x00, 0x71, 0x0a, 0x83, 0x00, 0x65, 0x0e, 0x83, 0x00, + 0xf1, 0x0d, 0x83, 0x00, 0x41, 0x0b, 0x83, 0x00, 0xa1, 0x1e, 0x83, 0x00, + 0xb1, 0x1e, 0x83, 0x00, 0x01, 0x2b, 0x83, 0x00, 0xf5, 0x4e, 0x83, 0x00, + 0x11, 0x2b, 0x83, 0x00, 0xb1, 0x27, 0x83, 0x00, 0x99, 0x23, 0x83, 0x00, + 0x01, 0x4a, 0x83, 0x00, 0xed, 0x49, 0x83, 0x00, 0xfd, 0x47, 0x83, 0x00, + 0xcd, 0x4c, 0x83, 0x00, 0xbd, 0x4c, 0x83, 0x00, 0x71, 0x4c, 0x83, 0x00, + 0xd5, 0x27, 0x83, 0x00, 0x4d, 0x25, 0x83, 0x00, 0x95, 0x25, 0x83, 0x00, + 0xe1, 0x4c, 0x83, 0x00, 0x41, 0x4c, 0x83, 0x00, 0x05, 0x03, 0x01, 0x00, + 0x65, 0x11, 0x83, 0x00, 0xe1, 0x44, 0x83, 0x00, 0x21, 0x28, 0x83, 0x00, + 0xbd, 0x28, 0x83, 0x00, 0x79, 0x29, 0x83, 0x00, 0x65, 0x28, 0x83, 0x00, + 0x65, 0x2b, 0x83, 0x00, 0x41, 0x45, 0x83, 0x00, 0xd5, 0x29, 0x83, 0x00, + 0x49, 0x1d, 0x83, 0x00, 0xa1, 0x2a, 0x83, 0x00, 0x5d, 0x30, 0x83, 0x00, + 0x51, 0x48, 0x83, 0x00, 0xe5, 0x48, 0x83, 0x00, 0x29, 0x48, 0x83, 0x00, + 0xf5, 0x23, 0x83, 0x00, 0x11, 0x4a, 0x83, 0x00, 0x79, 0x34, 0x83, 0x00, + 0x91, 0x18, 0x83, 0x00, 0xa5, 0x33, 0x83, 0x00, 0xed, 0x34, 0x83, 0x00, + 0x1d, 0x11, 0x83, 0x00, 0x9d, 0x4e, 0x83, 0x00, 0x95, 0x4d, 0x83, 0x00, + 0xb5, 0x1a, 0x83, 0x00, 0x61, 0x47, 0x83, 0x00, 0x1d, 0x4d, 0x83, 0x00, + 0xed, 0x10, 0x83, 0x00, 0x0d, 0x45, 0x83, 0x00, 0xc1, 0x1e, 0x83, 0x00, + 0x01, 0x20, 0x83, 0x00, 0xe9, 0x21, 0x83, 0x00, 0xf1, 0x25, 0x83, 0x00, + 0xf9, 0x1d, 0x83, 0x00, 0x85, 0x00, 0x01, 0x00, 0xc7, 0x95, 0x00, 0x00, + 0x49, 0x10, 0x83, 0x00, 0xc1, 0x0f, 0x83, 0x00, 0x21, 0x24, 0x83, 0x00, + 0xa5, 0x24, 0x83, 0x00, 0xb9, 0x4a, 0x83, 0x00, 0xb5, 0x2f, 0x83, 0x00, + 0xc1, 0x45, 0x83, 0x00, 0xfd, 0x1c, 0x83, 0x00, 0x71, 0x1d, 0x83, 0x00, + 0xf5, 0x18, 0x83, 0x00, 0x59, 0x19, 0x83, 0x00, 0xf1, 0x19, 0x83, 0x00, + 0xeb, 0x05, 0x01, 0x00, 0x49, 0x2a, 0x83, 0x00, 0xa5, 0x11, 0x83, 0x00, + 0xb9, 0x57, 0x83, 0x00, 0x29, 0x57, 0x83, 0x00, 0x65, 0x4f, 0x83, 0x00, + 0x01, 0x60, 0x83, 0x00, 0xe5, 0x59, 0x83, 0x00, 0x39, 0x51, 0x83, 0x00, + 0xf5, 0x4f, 0x83, 0x00, 0x55, 0x54, 0x83, 0x00, 0x1d, 0x5e, 0x83, 0x00, + 0x21, 0x52, 0x83, 0x00, 0x65, 0x59, 0x83, 0x00, 0x79, 0x50, 0x83, 0x00, + 0x71, 0x4f, 0x83, 0x00, 0x09, 0x59, 0x83, 0x00, 0x3d, 0x63, 0x83, 0x00, + 0xc5, 0x57, 0x83, 0x00, 0x81, 0x5c, 0x83, 0x00, 0xb1, 0x5b, 0x83, 0x00, + 0xdd, 0x53, 0x83, 0x00, 0x11, 0x53, 0x83, 0x00, 0x9d, 0x4f, 0x83, 0x00, + 0x29, 0x50, 0x83, 0x00, 0x25, 0x4f, 0x83, 0x00, 0xd5, 0x58, 0x83, 0x00, + 0xcd, 0x62, 0x83, 0x00, 0x39, 0x60, 0x83, 0x00, 0xf9, 0x5c, 0x83, 0x00, + 0x4d, 0x61, 0x83, 0x00, 0x5d, 0x5f, 0x83, 0x00, 0x2d, 0x54, 0x83, 0x00, + 0xdd, 0x50, 0x83, 0x00, 0x39, 0x57, 0x83, 0x00, 0xa5, 0x55, 0x83, 0x00, + 0x91, 0x63, 0x83, 0x00, 0xa1, 0x62, 0x83, 0x00, 0xc1, 0x5d, 0x83, 0x00, + 0x2d, 0x5e, 0x83, 0x00, 0x45, 0x5f, 0x83, 0x00, 0xa1, 0x51, 0x83, 0x00, + 0x17, 0x08, 0x01, 0x00, 0x19, 0x5b, 0x83, 0x00, 0x6d, 0x5a, 0x83, 0x00, + 0xa9, 0x56, 0x83, 0x00, 0xa5, 0x50, 0x83, 0x00, 0x09, 0x57, 0x83, 0x00, + 0x0d, 0x74, 0x83, 0x00, 0xdd, 0x63, 0x83, 0x00, 0x29, 0x7a, 0x83, 0x00, + 0x01, 0x66, 0x83, 0x00, 0xb9, 0xb2, 0x83, 0x00, 0xd5, 0xa7, 0x83, 0x00, + 0x7d, 0x84, 0x83, 0x00, 0x81, 0x93, 0x83, 0x00, 0x5d, 0xb3, 0x83, 0x00, + 0xa1, 0x93, 0x83, 0x00, 0xe9, 0x93, 0x83, 0x00, 0x45, 0x06, 0x01, 0x00, + 0x21, 0x97, 0x00, 0x00, 0x05, 0xa0, 0x00, 0x00, 0x71, 0x7a, 0x83, 0x00, + 0x5d, 0x67, 0x83, 0x00, 0x51, 0x66, 0x83, 0x00, 0xcd, 0x70, 0x83, 0x00, + 0x55, 0x71, 0x83, 0x00, 0xdd, 0x74, 0x83, 0x00, 0x8d, 0xaa, 0x83, 0x00, + 0x51, 0xa8, 0x83, 0x00, 0xa9, 0xb1, 0x83, 0x00, 0x9d, 0x91, 0x83, 0x00, + 0xd1, 0x84, 0x83, 0x00, 0x2b, 0x96, 0x00, 0x00, 0x61, 0x84, 0x83, 0x00, + 0xad, 0x77, 0x83, 0x00, 0x81, 0x81, 0x83, 0x00, 0x15, 0x82, 0x83, 0x00, + 0xb1, 0x80, 0x83, 0x00, 0xe5, 0xb5, 0x83, 0x00, 0x6d, 0x7e, 0x83, 0x00, + 0xb5, 0x79, 0x83, 0x00, 0x61, 0x97, 0x00, 0x00, 0x91, 0x6e, 0x83, 0x00, + 0x75, 0x8f, 0x83, 0x00, 0x55, 0x87, 0x83, 0x00, 0x59, 0x01, 0x01, 0x00, + 0xf5, 0x9b, 0x00, 0x00, 0x25, 0x67, 0x83, 0x00, 0xc1, 0x88, 0x83, 0x00, + 0xd9, 0x8f, 0x83, 0x00, 0xf5, 0xac, 0x83, 0x00, 0xe9, 0x77, 0x83, 0x00, + 0x9d, 0x6d, 0x83, 0x00, 0xa1, 0xa7, 0x83, 0x00, 0x79, 0x08, 0x01, 0x00, + 0xc9, 0xa4, 0x83, 0x00, 0xfd, 0x9e, 0x00, 0x00, 0x55, 0x8b, 0x83, 0x00, + 0xe5, 0x8a, 0x83, 0x00, 0xcd, 0x6a, 0x83, 0x00, 0xf5, 0x86, 0x83, 0x00, + 0x59, 0x6a, 0x83, 0x00, 0xb9, 0xaa, 0x83, 0x00, 0x15, 0x66, 0x83, 0x00, + 0x51, 0xb2, 0x83, 0x00, 0x9d, 0xb3, 0x83, 0x00, 0xd9, 0xb6, 0x83, 0x00, + 0x59, 0xb1, 0x83, 0x00, 0x91, 0x82, 0x83, 0x00, 0xd5, 0xb0, 0x83, 0x00, + 0x81, 0x86, 0x83, 0x00, 0xc9, 0x7a, 0x83, 0x00, 0x05, 0x85, 0x83, 0x00, + 0x79, 0x7c, 0x83, 0x00, 0x89, 0x65, 0x83, 0x00, 0x55, 0xa5, 0x83, 0x00, + 0xc9, 0xaf, 0x83, 0x00, 0xd5, 0xfd, 0x00, 0x00, 0x79, 0x99, 0x83, 0x00, + 0x91, 0x89, 0x83, 0x00, 0xc5, 0xb5, 0x83, 0x00, 0x0d, 0xb8, 0x83, 0x00, + 0x99, 0xd4, 0x83, 0x00, 0x2d, 0xc0, 0x83, 0x00, 0x9d, 0xc2, 0x83, 0x00, + 0xad, 0xc3, 0x83, 0x00, 0xa1, 0xc6, 0x83, 0x00, 0xb1, 0xc6, 0x83, 0x00, + 0xc5, 0xc2, 0x83, 0x00, 0xa9, 0xd0, 0x83, 0x00, 0x55, 0xbf, 0x83, 0x00, + 0xf9, 0xcf, 0x83, 0x00, 0x29, 0xbf, 0x83, 0x00, 0xc5, 0xe1, 0x83, 0x00, + 0xc1, 0xc0, 0x83, 0x00, 0x95, 0xc0, 0x83, 0x00, 0x4d, 0xd8, 0x83, 0x00, + 0x0d, 0xd7, 0x83, 0x00, 0x15, 0xd8, 0x83, 0x00, 0xf1, 0xd7, 0x83, 0x00, + 0x79, 0xbd, 0x83, 0x00, 0xa1, 0xe1, 0x83, 0x00, 0x35, 0xc2, 0x83, 0x00, + 0xc5, 0xe0, 0x83, 0x00, 0xdd, 0xe0, 0x83, 0x00, 0xc5, 0xdc, 0x83, 0x00, + 0x99, 0xda, 0x83, 0x00, 0x01, 0xda, 0x83, 0x00, 0x4d, 0xb8, 0x83, 0x00, + 0x75, 0xc0, 0x83, 0x00, 0x19, 0xc2, 0x83, 0x00, 0xf9, 0xc9, 0x83, 0x00, + 0x3d, 0xd6, 0x83, 0x00, 0x15, 0xbe, 0x83, 0x00, 0xc9, 0xd6, 0x83, 0x00, + 0x5d, 0xba, 0x83, 0x00, 0x29, 0xd6, 0x83, 0x00, 0x31, 0xb9, 0x83, 0x00, + 0x35, 0xbc, 0x83, 0x00, 0x9d, 0xd8, 0x83, 0x00, 0x5d, 0xdc, 0x83, 0x00, + 0x29, 0xc1, 0x83, 0x00, 0xa9, 0xc2, 0x83, 0x00, 0xe5, 0xc0, 0x83, 0x00, + 0x25, 0xdb, 0x83, 0x00, 0x75, 0xc2, 0x83, 0x00, 0x1d, 0xd0, 0x83, 0x00, + 0x5d, 0xbc, 0x83, 0x00, 0x61, 0xc6, 0x83, 0x00, 0xd5, 0xc2, 0x83, 0x00, + 0x05, 0xbc, 0x83, 0x00, 0x01, 0xc9, 0x83, 0x00, 0xb5, 0xc8, 0x83, 0x00, + 0xed, 0xc8, 0x83, 0x00, 0x55, 0xd6, 0x83, 0x00, 0x15, 0xd9, 0x83, 0x00, + 0xa5, 0xd1, 0x83, 0x00, 0xf1, 0xd5, 0x83, 0x00, 0x01, 0xd9, 0x83, 0x00, + 0x81, 0xb8, 0x83, 0x00, 0x89, 0xe0, 0x83, 0x00, 0xe1, 0xbc, 0x83, 0x00, + 0xa5, 0xdb, 0x83, 0x00, 0xed, 0xe1, 0x83, 0x00, 0x71, 0xc1, 0x83, 0x00, + 0xe9, 0xb7, 0x83, 0x00, 0x6d, 0xc7, 0x83, 0x00, 0x8d, 0xc1, 0x83, 0x00, + 0x1d, 0xc8, 0x83, 0x00, 0xb5, 0xd1, 0x83, 0x00, 0x71, 0xdc, 0x83, 0x00, + 0xe1, 0xc1, 0x83, 0x00, 0xa9, 0xc1, 0x83, 0x00, 0x19, 0xdc, 0x83, 0x00, + 0x39, 0xd8, 0x83, 0x00, 0x4d, 0xcb, 0x83, 0x00, 0xa5, 0xb7, 0x83, 0x00, + 0x69, 0xcb, 0x83, 0x00, 0x8d, 0xc9, 0x83, 0x00, 0xc9, 0xd4, 0x83, 0x00, + 0x11, 0xa9, 0x00, 0x00, 0x99, 0xd6, 0x83, 0x00, 0xe5, 0xdc, 0x83, 0x00, + 0x4d, 0xd4, 0x83, 0x00, 0x1d, 0xc3, 0x83, 0x00, 0x21, 0xdd, 0x83, 0x00, + 0x45, 0xd9, 0x83, 0x00, 0x7d, 0xd3, 0x83, 0x00, 0x3d, 0xd2, 0x83, 0x00, + 0x41, 0xda, 0x83, 0x00, 0xcd, 0xd8, 0x83, 0x00, 0xd9, 0xbf, 0x83, 0x00, + 0x95, 0xbd, 0x83, 0x00, 0xed, 0xbd, 0x83, 0x00, 0x51, 0xc0, 0x83, 0x00, + 0x2d, 0xb8, 0x83, 0x00, 0x49, 0xbb, 0x83, 0x00, 0x31, 0xbb, 0x83, 0x00, + 0xcd, 0xda, 0x83, 0x00, 0xd5, 0xd0, 0x83, 0x00, 0x49, 0xca, 0x83, 0x00, + 0x9d, 0xd5, 0x83, 0x00, 0x81, 0xbf, 0x83, 0x00, 0xd5, 0xcf, 0x83, 0x00, + 0x3d, 0xc9, 0x83, 0x00, 0xdd, 0xd1, 0x83, 0x00, 0xb9, 0xd7, 0x83, 0x00, + 0x25, 0xc7, 0x83, 0x00, 0xe5, 0xa4, 0x00, 0x00, 0x5d, 0xbe, 0x83, 0x00, + 0x21, 0xe1, 0x83, 0x00, 0xf9, 0xe0, 0x83, 0x00, 0x71, 0xb9, 0x83, 0x00, + 0x8d, 0xe1, 0x83, 0x00, 0x25, 0xd9, 0x83, 0x00, 0x49, 0xd7, 0x83, 0x00, + 0xdd, 0xdb, 0x83, 0x00, 0xa9, 0xb9, 0x83, 0x00, 0x55, 0xa1, 0x00, 0x00, + 0x91, 0x07, 0x01, 0x00, 0x59, 0xeb, 0x83, 0x00, 0xc5, 0xe7, 0x83, 0x00, + 0x41, 0xe2, 0x83, 0x00, 0x25, 0xe2, 0x83, 0x00, 0x6d, 0xf5, 0x83, 0x00, + 0x65, 0xeb, 0x83, 0x00, 0x85, 0xf2, 0x83, 0x00, 0x89, 0xf7, 0x83, 0x00, + 0xb1, 0xf2, 0x83, 0x00, 0xa9, 0xf5, 0x83, 0x00, 0xad, 0x00, 0x84, 0x00, + 0xe1, 0x00, 0x84, 0x00, 0x19, 0xfd, 0x83, 0x00, 0x35, 0xee, 0x83, 0x00, + 0xfd, 0xf3, 0x83, 0x00, 0x9d, 0xae, 0x00, 0x00, 0x89, 0xfb, 0x83, 0x00, + 0xb9, 0xfa, 0x83, 0x00, 0x21, 0xf9, 0x83, 0x00, 0xf1, 0xfa, 0x83, 0x00, + 0xd9, 0xf8, 0x83, 0x00, 0xd9, 0xf9, 0x83, 0x00, 0x31, 0x00, 0x84, 0x00, + 0xc5, 0xfe, 0x83, 0x00, 0x49, 0xe7, 0x83, 0x00, 0x05, 0x00, 0x84, 0x00, + 0x4d, 0xff, 0x83, 0x00, 0x6d, 0xf3, 0x83, 0x00, 0x59, 0xfe, 0x83, 0x00, + 0x01, 0xfe, 0x83, 0x00, 0x25, 0xeb, 0x83, 0x00, 0x0d, 0xeb, 0x83, 0x00, + 0x33, 0xae, 0x00, 0x00, 0x35, 0xfd, 0x83, 0x00, 0x81, 0xeb, 0x83, 0x00, + 0x59, 0xfd, 0x83, 0x00, 0x11, 0xf8, 0x83, 0x00, 0xfd, 0xf7, 0x83, 0x00, + 0xc5, 0xed, 0x83, 0x00, 0xad, 0xed, 0x83, 0x00, 0xa1, 0x01, 0x84, 0x00, + 0xe9, 0xe7, 0x83, 0x00, 0xb1, 0xf3, 0x83, 0x00, 0xdd, 0xf2, 0x83, 0x00, + 0x25, 0xf3, 0x83, 0x00, 0xf9, 0xe6, 0x83, 0x00, 0xe5, 0xe2, 0x83, 0x00, + 0x51, 0x02, 0x01, 0x00, 0xa5, 0xe9, 0x83, 0x00, 0x8d, 0xf5, 0x83, 0x00, + 0x51, 0xee, 0x83, 0x00, 0x79, 0xf8, 0x83, 0x00, 0x71, 0xe2, 0x83, 0x00, + 0xf1, 0xe8, 0x83, 0x00, 0x45, 0xe6, 0x83, 0x00, 0x99, 0xf7, 0x83, 0x00, + 0x6d, 0xee, 0x83, 0x00, 0x41, 0xf4, 0x83, 0x00, 0xb9, 0xeb, 0x83, 0x00, + 0x75, 0xe7, 0x83, 0x00, 0xb1, 0xe8, 0x83, 0x00, 0xc5, 0xac, 0x00, 0x00, + 0x61, 0xf1, 0x83, 0x00, 0x1d, 0xf7, 0x00, 0x00, 0x89, 0xee, 0x83, 0x00, + 0xf5, 0xad, 0x00, 0x00, 0xfd, 0xe5, 0x83, 0x00, 0xa9, 0xfd, 0x83, 0x00, + 0x35, 0x02, 0x01, 0x00, 0xb5, 0xfb, 0x83, 0x00, 0xf1, 0xf1, 0x83, 0x00, + 0x2d, 0x10, 0x84, 0x00, 0xe1, 0x15, 0x84, 0x00, 0xb1, 0x19, 0x84, 0x00, + 0xc5, 0x15, 0x84, 0x00, 0xd9, 0x0f, 0x84, 0x00, 0xcd, 0x21, 0x84, 0x00, + 0x49, 0x1e, 0x84, 0x00, 0x4d, 0x1f, 0x84, 0x00, 0xe1, 0x12, 0x84, 0x00, + 0xed, 0x08, 0x84, 0x00, 0xf1, 0x01, 0x84, 0x00, 0x2d, 0x0f, 0x84, 0x00, + 0xed, 0x23, 0x84, 0x00, 0xf5, 0x1e, 0x84, 0x00, 0xe5, 0x20, 0x84, 0x00, + 0x49, 0x20, 0x84, 0x00, 0xad, 0x12, 0x84, 0x00, 0xf1, 0x1a, 0x84, 0x00, + 0x71, 0x1f, 0x84, 0x00, 0xc9, 0x19, 0x84, 0x00, 0xad, 0x18, 0x84, 0x00, + 0x45, 0x0b, 0x84, 0x00, 0x91, 0x0b, 0x84, 0x00, 0x0d, 0x24, 0x84, 0x00, + 0x8d, 0x23, 0x84, 0x00, 0x0d, 0x18, 0x84, 0x00, 0x21, 0x06, 0x84, 0x00, + 0x8d, 0x16, 0x84, 0x00, 0x31, 0x03, 0x84, 0x00, 0x69, 0x09, 0x84, 0x00, + 0xfd, 0x15, 0x84, 0x00, 0xe9, 0x02, 0x84, 0x00, 0x01, 0x02, 0x84, 0x00, + 0xa9, 0x09, 0x84, 0x00, 0x8d, 0x14, 0x84, 0x00, 0x81, 0x1e, 0x84, 0x00, + 0xe1, 0x0b, 0x84, 0x00, 0x75, 0x1c, 0x84, 0x00, 0xad, 0x0a, 0x84, 0x00, + 0x49, 0x10, 0x84, 0x00, 0x71, 0x20, 0x84, 0x00, 0x01, 0x21, 0x84, 0x00, + 0x85, 0x0a, 0x84, 0x00, 0x29, 0x1d, 0x84, 0x00, 0x45, 0x07, 0x84, 0x00, + 0x39, 0x0c, 0x84, 0x00, 0x29, 0x19, 0x84, 0x00, 0x55, 0x1e, 0x84, 0x00, + 0x89, 0x03, 0x84, 0x00, 0xe5, 0x1d, 0x84, 0x00, 0x21, 0x25, 0x84, 0x00, + 0x49, 0x13, 0x84, 0x00, 0x29, 0x1a, 0x84, 0x00, 0x65, 0x02, 0x01, 0x00, + 0xed, 0x12, 0x84, 0x00, 0x45, 0x06, 0x84, 0x00, 0x01, 0x0d, 0x84, 0x00, + 0x89, 0x43, 0x84, 0x00, 0x6d, 0x2a, 0x84, 0x00, 0x01, 0x4d, 0x84, 0x00, + 0x15, 0x28, 0x84, 0x00, 0x69, 0x28, 0x84, 0x00, 0x7d, 0xed, 0x00, 0x00, + 0x09, 0x40, 0x84, 0x00, 0x11, 0x2c, 0x84, 0x00, 0xf9, 0x27, 0x84, 0x00, + 0x91, 0x2d, 0x84, 0x00, 0x79, 0x4c, 0x84, 0x00, 0x89, 0x34, 0x84, 0x00, + 0x19, 0x33, 0x84, 0x00, 0x6d, 0x2f, 0x84, 0x00, 0xc9, 0x2d, 0x84, 0x00, + 0xf1, 0x2e, 0x84, 0x00, 0x7d, 0x2e, 0x84, 0x00, 0x65, 0x25, 0x84, 0x00, + 0xdd, 0x34, 0x84, 0x00, 0xfd, 0x25, 0x84, 0x00, 0x19, 0x29, 0x84, 0x00, + 0xb5, 0x40, 0x84, 0x00, 0xd9, 0x44, 0x84, 0x00, 0x79, 0x29, 0x84, 0x00, + 0xb9, 0x2b, 0x84, 0x00, 0x3d, 0x45, 0x84, 0x00, 0x95, 0x32, 0x84, 0x00, + 0xb9, 0x28, 0x84, 0x00, 0xd1, 0x38, 0x84, 0x00, 0x31, 0x48, 0x84, 0x00, + 0xa9, 0x30, 0x84, 0x00, 0x6d, 0x2c, 0x84, 0x00, 0x99, 0x43, 0x84, 0x00, + 0xd1, 0x32, 0x84, 0x00, 0x6d, 0x33, 0x84, 0x00, 0xfd, 0x2f, 0x84, 0x00, + 0x5d, 0x45, 0x84, 0x00, 0x11, 0x34, 0x84, 0x00, 0xb5, 0x4a, 0x84, 0x00, + 0x75, 0x48, 0x84, 0x00, 0xc5, 0x48, 0x84, 0x00, 0xb1, 0x27, 0x84, 0x00, + 0x31, 0x4a, 0x84, 0x00, 0xd9, 0x49, 0x84, 0x00, 0x59, 0x32, 0x84, 0x00, + 0x01, 0x4c, 0x84, 0x00, 0x39, 0x38, 0x84, 0x00, 0x31, 0x4d, 0x84, 0x00, + 0x55, 0x44, 0x84, 0x00, 0xd9, 0x3d, 0x84, 0x00, 0x55, 0x43, 0x84, 0x00, + 0x51, 0x3c, 0x84, 0x00, 0x91, 0x39, 0x84, 0x00, 0x95, 0x36, 0x84, 0x00, + 0x91, 0x37, 0x84, 0x00, 0xf5, 0x36, 0x84, 0x00, 0xe1, 0x47, 0x84, 0x00, + 0x15, 0x47, 0x84, 0x00, 0xcd, 0x4c, 0x84, 0x00, 0xf5, 0x2b, 0x84, 0x00, + 0x25, 0x46, 0x84, 0x00, 0xe5, 0x3a, 0x84, 0x00, 0xc9, 0x37, 0x84, 0x00, + 0x49, 0x42, 0x84, 0x00, 0x29, 0x2a, 0x84, 0x00, 0xa5, 0x3f, 0x84, 0x00, + 0x59, 0x26, 0x84, 0x00, 0x95, 0x2a, 0x84, 0x00, 0x45, 0x2b, 0x84, 0x00, + 0xc9, 0x5d, 0x84, 0x00, 0xd5, 0x08, 0x01, 0x00, 0xa1, 0x56, 0x84, 0x00, + 0x95, 0x56, 0x84, 0x00, 0x19, 0x57, 0x84, 0x00, 0xe9, 0x56, 0x84, 0x00, + 0x05, 0x57, 0x84, 0x00, 0x35, 0x5f, 0x84, 0x00, 0x1d, 0x62, 0x84, 0x00, + 0xb5, 0x57, 0x84, 0x00, 0x65, 0x63, 0x84, 0x00, 0xed, 0x62, 0x84, 0x00, + 0x21, 0x63, 0x84, 0x00, 0xbd, 0x62, 0x84, 0x00, 0x19, 0x4e, 0x84, 0x00, + 0xb9, 0x53, 0x84, 0x00, 0xb1, 0x5d, 0x84, 0x00, 0xb5, 0x51, 0x84, 0x00, + 0xd5, 0x5f, 0x84, 0x00, 0xf9, 0x55, 0x84, 0x00, 0x65, 0x60, 0x84, 0x00, + 0x59, 0x53, 0x84, 0x00, 0xe5, 0x53, 0x84, 0x00, 0xe9, 0x4d, 0x84, 0x00, + 0x05, 0x09, 0x01, 0x00, 0xe1, 0x5f, 0x84, 0x00, 0xd9, 0x08, 0x01, 0x00, + 0xa9, 0x08, 0x01, 0x00, 0xb5, 0x5b, 0x84, 0x00, 0x31, 0x56, 0x84, 0x00, + 0xa5, 0x63, 0x84, 0x00, 0xcd, 0x60, 0x84, 0x00, 0x91, 0x63, 0x84, 0x00, + 0xed, 0x50, 0x84, 0x00, 0x2d, 0x5e, 0x84, 0x00, 0x31, 0x51, 0x84, 0x00, + 0x15, 0x5c, 0x84, 0x00, 0x61, 0x54, 0x84, 0x00, 0xf5, 0x5e, 0x84, 0x00, + 0xf1, 0x5d, 0x84, 0x00, 0xe1, 0x09, 0x01, 0x00, 0x71, 0x52, 0x84, 0x00, + 0x59, 0x58, 0x84, 0x00, 0x81, 0x5c, 0x84, 0x00, 0x71, 0x57, 0x84, 0x00, + 0x25, 0x57, 0x84, 0x00, 0x71, 0x58, 0x84, 0x00, 0xad, 0x56, 0x84, 0x00, + 0x41, 0x59, 0x84, 0x00, 0x6d, 0x4f, 0x84, 0x00, 0x29, 0x50, 0x84, 0x00, + 0xe1, 0x54, 0x84, 0x00, 0xbd, 0x61, 0x84, 0x00, 0x6d, 0x61, 0x84, 0x00, + 0x05, 0x59, 0x84, 0x00, 0xa5, 0x66, 0x84, 0x00, 0xd9, 0x67, 0x84, 0x00, + 0x45, 0x66, 0x84, 0x00, 0x0d, 0x65, 0x84, 0x00, 0x91, 0x67, 0x84, 0x00, + 0xb9, 0x63, 0x84, 0x00, 0x5d, 0x67, 0x84, 0x00, 0x79, 0x67, 0x84, 0x00, + 0xf9, 0x66, 0x84, 0x00, 0x21, 0x65, 0x84, 0x00, 0x21, 0x67, 0x84, 0x00, + 0xc5, 0x66, 0x84, 0x00, 0x8d, 0x66, 0x84, 0x00, 0x65, 0x66, 0x84, 0x00, + 0x11, 0x68, 0x84, 0x00, 0x51, 0x6c, 0x84, 0x00, 0xad, 0x6e, 0x84, 0x00, + 0x01, 0x6e, 0x84, 0x00, 0xf9, 0x70, 0x84, 0x00, 0x4d, 0x7f, 0x84, 0x00, + 0x7d, 0x6c, 0x84, 0x00, 0x2d, 0x74, 0x84, 0x00, 0x45, 0x6a, 0x84, 0x00, + 0x0d, 0x7b, 0x84, 0x00, 0x09, 0x03, 0x01, 0x00, 0x15, 0x6e, 0x84, 0x00, + 0x45, 0x7a, 0x84, 0x00, 0xe5, 0x6c, 0x84, 0x00, 0x45, 0x6f, 0x84, 0x00, + 0xdd, 0xed, 0x00, 0x00, 0x29, 0x7e, 0x84, 0x00, 0x75, 0x6d, 0x84, 0x00, + 0x95, 0x6b, 0x84, 0x00, 0xb5, 0x6d, 0x84, 0x00, 0x7d, 0x7d, 0x84, 0x00, + 0x5d, 0x6b, 0x84, 0x00, 0xd5, 0x6a, 0x84, 0x00, 0x81, 0x6a, 0x84, 0x00, + 0x85, 0x74, 0x84, 0x00, 0xb1, 0x80, 0x84, 0x00, 0x85, 0x7e, 0x84, 0x00, + 0xcd, 0x7f, 0x84, 0x00, 0x49, 0x81, 0x84, 0x00, 0x69, 0x81, 0x84, 0x00, + 0xed, 0x89, 0x84, 0x00, 0x6d, 0x8a, 0x84, 0x00, 0xfd, 0x89, 0x84, 0x00, + 0x8d, 0x89, 0x84, 0x00, 0x9d, 0x89, 0x84, 0x00, 0xe9, 0x85, 0x84, 0x00, + 0xf9, 0x82, 0x84, 0x00, 0x25, 0x85, 0x84, 0x00, 0x51, 0x8a, 0x84, 0x00, + 0x75, 0x85, 0x84, 0x00, 0x95, 0x84, 0x84, 0x00, 0x81, 0x81, 0x84, 0x00, + 0x71, 0x83, 0x84, 0x00, 0xc1, 0x89, 0x84, 0x00, 0x5d, 0x89, 0x84, 0x00, + 0xd5, 0x89, 0x84, 0x00, 0x6d, 0x89, 0x84, 0x00, 0x7d, 0x89, 0x84, 0x00, + 0x0d, 0x8a, 0x84, 0x00, 0x09, 0x86, 0x84, 0x00, 0x79, 0x8c, 0x84, 0x00, + 0x7d, 0x8a, 0x84, 0x00, 0x0d, 0x8b, 0x84, 0x00, 0x49, 0x94, 0x84, 0x00, + 0x8d, 0x92, 0x84, 0x00, 0xe9, 0x8d, 0x84, 0x00, 0x9d, 0x8b, 0x84, 0x00, + 0xfd, 0x8c, 0x84, 0x00, 0x79, 0x90, 0x84, 0x00, 0x0d, 0x8c, 0x84, 0x00, + 0x45, 0x8c, 0x84, 0x00, 0xe9, 0xa6, 0x84, 0x00, 0xa5, 0xad, 0x84, 0x00, + 0x29, 0x96, 0x84, 0x00, 0xc5, 0x98, 0x84, 0x00, 0x15, 0xc1, 0x84, 0x00, + 0x09, 0xa9, 0x84, 0x00, 0x99, 0xc2, 0x84, 0x00, 0x45, 0xb7, 0x84, 0x00, + 0x31, 0xc1, 0x84, 0x00, 0xd1, 0xb8, 0x84, 0x00, 0x8d, 0x99, 0x84, 0x00, + 0xb9, 0x9a, 0x84, 0x00, 0x25, 0xac, 0x84, 0x00, 0xd9, 0xbf, 0x84, 0x00, + 0xc9, 0xbe, 0x84, 0x00, 0xa1, 0x96, 0x84, 0x00, 0x25, 0xb1, 0x84, 0x00, + 0x51, 0x9b, 0x84, 0x00, 0x91, 0x98, 0x84, 0x00, 0x4d, 0x97, 0x84, 0x00, + 0x1d, 0x97, 0x84, 0x00, 0x7d, 0xa6, 0x84, 0x00, 0xd1, 0xb7, 0x84, 0x00, + 0x2d, 0xab, 0x84, 0x00, 0x85, 0x95, 0x84, 0x00, 0x19, 0xb0, 0x84, 0x00, + 0xf5, 0xad, 0x84, 0x00, 0x29, 0xa9, 0x84, 0x00, 0xc1, 0xa9, 0x84, 0x00, + 0x21, 0x9f, 0x84, 0x00, 0x25, 0xa2, 0x84, 0x00, 0xb1, 0xae, 0x84, 0x00, + 0xc1, 0xaf, 0x84, 0x00, 0xd5, 0xa3, 0x84, 0x00, 0x75, 0xb7, 0x84, 0x00, + 0x41, 0xa2, 0x84, 0x00, 0xe1, 0xbc, 0x84, 0x00, 0x6d, 0xa8, 0x84, 0x00, + 0xbd, 0x9d, 0x84, 0x00, 0x95, 0xb8, 0x84, 0x00, 0x5d, 0x95, 0x84, 0x00, + 0x75, 0xbe, 0x84, 0x00, 0x51, 0xb9, 0x84, 0x00, 0xa9, 0x95, 0x84, 0x00, + 0xc5, 0xc1, 0x84, 0x00, 0x59, 0x9a, 0x84, 0x00, 0x41, 0x96, 0x84, 0x00, + 0x3d, 0xb8, 0x84, 0x00, 0x9d, 0xa8, 0x84, 0x00, 0xe5, 0xa8, 0x84, 0x00, + 0xa5, 0x9b, 0x84, 0x00, 0xf5, 0xa6, 0x84, 0x00, 0x3d, 0xaf, 0x84, 0x00, + 0x15, 0x9a, 0x84, 0x00, 0xf9, 0x98, 0x84, 0x00, 0xed, 0xa9, 0x84, 0x00, + 0x6d, 0xb1, 0x84, 0x00, 0xfd, 0xf0, 0x84, 0x00, 0x25, 0xdf, 0x84, 0x00, + 0x25, 0xed, 0x84, 0x00, 0xe5, 0xd0, 0x84, 0x00, 0xcd, 0xf1, 0x84, 0x00, + 0x09, 0xf2, 0x84, 0x00, 0x35, 0xf2, 0x84, 0x00, 0x55, 0xf2, 0x84, 0x00, + 0xcd, 0xf2, 0x84, 0x00, 0xb1, 0xd3, 0x84, 0x00, 0xf5, 0xd3, 0x84, 0x00, + 0x2d, 0xd4, 0x84, 0x00, 0xc1, 0xd4, 0x84, 0x00, 0xa5, 0x04, 0x85, 0x00, + 0xf9, 0x05, 0x85, 0x00, 0x6d, 0x05, 0x85, 0x00, 0x99, 0x04, 0x85, 0x00, + 0x8d, 0x04, 0x85, 0x00, 0x79, 0xd4, 0x84, 0x00, 0x45, 0xe8, 0x84, 0x00, + 0xb1, 0xc5, 0x84, 0x00, 0x95, 0xdf, 0x84, 0x00, 0x31, 0xdf, 0x84, 0x00, + 0x75, 0xe4, 0x84, 0x00, 0x1d, 0xe0, 0x84, 0x00, 0xbd, 0xc9, 0x84, 0x00, + 0x05, 0xed, 0x84, 0x00, 0xa5, 0x00, 0x85, 0x00, 0x91, 0xfb, 0x84, 0x00, + 0xf9, 0xed, 0x84, 0x00, 0x91, 0xef, 0x84, 0x00, 0x9d, 0xfb, 0x84, 0x00, + 0x81, 0xea, 0x84, 0x00, 0x79, 0xe2, 0x84, 0x00, 0x59, 0xc6, 0x84, 0x00, + 0x61, 0xeb, 0x84, 0x00, 0xa1, 0xeb, 0x84, 0x00, 0xd1, 0xe4, 0x84, 0x00, + 0x9d, 0x02, 0x85, 0x00, 0xa1, 0xf3, 0x84, 0x00, 0x15, 0xcc, 0x84, 0x00, + 0x5d, 0xfb, 0x84, 0x00, 0x81, 0xc5, 0x84, 0x00, 0x15, 0xd5, 0x84, 0x00, + 0x99, 0xd6, 0x84, 0x00, 0x35, 0xe7, 0x84, 0x00, 0xb9, 0xdf, 0x84, 0x00, + 0x45, 0xf4, 0x84, 0x00, 0xb9, 0xc7, 0x84, 0x00, 0x01, 0xdf, 0x84, 0x00, + 0x2d, 0x01, 0x85, 0x00, 0xe1, 0xc7, 0x84, 0x00, 0x25, 0xd1, 0x84, 0x00, + 0xcf, 0xee, 0x00, 0x00, 0xbd, 0xdd, 0x84, 0x00, 0x4d, 0xf3, 0x84, 0x00, + 0xe1, 0xc9, 0x84, 0x00, 0x41, 0xe0, 0x84, 0x00, 0x2d, 0xca, 0x84, 0x00, + 0x9d, 0xd4, 0x84, 0x00, 0x05, 0xeb, 0x84, 0x00, 0xd9, 0x00, 0x85, 0x00, + 0x79, 0xcb, 0x84, 0x00, 0x21, 0xfc, 0x84, 0x00, 0xb9, 0xe8, 0x84, 0x00, + 0xb5, 0xd8, 0x84, 0x00, 0x31, 0xfd, 0x84, 0x00, 0xbd, 0xfb, 0x84, 0x00, + 0x1d, 0x04, 0x85, 0x00, 0x5d, 0x04, 0x85, 0x00, 0x31, 0xed, 0x84, 0x00, + 0x45, 0x06, 0x85, 0x00, 0x5d, 0xec, 0x84, 0x00, 0x25, 0xc3, 0x84, 0x00, + 0x1d, 0xf3, 0x84, 0x00, 0xd9, 0xc6, 0x84, 0x00, 0x2d, 0xec, 0x84, 0x00, + 0xf1, 0xc5, 0x84, 0x00, 0x59, 0xe9, 0x84, 0x00, 0x19, 0xc8, 0x84, 0x00, + 0xb1, 0xef, 0x84, 0x00, 0xb1, 0x00, 0x85, 0x00, 0x49, 0xd3, 0x84, 0x00, + 0x01, 0xc9, 0x84, 0x00, 0xe1, 0xd2, 0x84, 0x00, 0x8d, 0xcb, 0x84, 0x00, + 0xdd, 0xeb, 0x84, 0x00, 0x11, 0xf4, 0x84, 0x00, 0x09, 0xfc, 0x84, 0x00, + 0xd9, 0xf3, 0x84, 0x00, 0x69, 0xc3, 0x84, 0x00, 0xa1, 0xc8, 0x84, 0x00, + 0x2d, 0xee, 0x84, 0x00, 0x71, 0xd6, 0x84, 0x00, 0x79, 0x01, 0x85, 0x00, + 0xbd, 0xee, 0x84, 0x00, 0x25, 0xd8, 0x84, 0x00, 0xdd, 0xf9, 0x84, 0x00, + 0x09, 0xf0, 0x84, 0x00, 0x35, 0xf7, 0x84, 0x00, 0xc9, 0xee, 0x00, 0x00, + 0xd9, 0xfc, 0x84, 0x00, 0x15, 0xd7, 0x84, 0x00, 0xdd, 0xd5, 0x84, 0x00, + 0x1d, 0xde, 0x84, 0x00, 0xd9, 0xf5, 0x84, 0x00, 0x19, 0xf1, 0x84, 0x00, + 0x99, 0xf1, 0x84, 0x00, 0x49, 0xf1, 0x84, 0x00, 0xf1, 0xf4, 0x84, 0x00, + 0xa1, 0xf4, 0x84, 0x00, 0xf1, 0xd0, 0x84, 0x00, 0x3d, 0xcc, 0x84, 0x00, + 0x69, 0xd2, 0x84, 0x00, 0x89, 0xe9, 0x84, 0x00, 0x71, 0xcd, 0x84, 0x00, + 0xc9, 0xd3, 0x84, 0x00, 0x85, 0x06, 0x85, 0x00, 0x89, 0x07, 0x85, 0x00, + 0xe9, 0x06, 0x85, 0x00, 0x4d, 0x07, 0x85, 0x00, 0x11, 0x07, 0x85, 0x00, + 0x25, 0x07, 0x85, 0x00, 0x71, 0x06, 0x85, 0x00, 0x95, 0x06, 0x85, 0x00, + 0xbd, 0x06, 0x85, 0x00, 0x75, 0x07, 0x85, 0x00, 0xb1, 0x07, 0x85, 0x00, + 0x9d, 0x07, 0x85, 0x00, 0xa9, 0x06, 0x85, 0x00, 0xd1, 0x06, 0x85, 0x00, + 0xfd, 0x06, 0x85, 0x00, 0x39, 0x07, 0x85, 0x00, 0x61, 0x07, 0x85, 0x00, + 0x5d, 0x06, 0x85, 0x00, 0x15, 0x09, 0x85, 0x00, 0x79, 0x09, 0x85, 0x00, + 0x35, 0x0a, 0x85, 0x00, 0xbd, 0x09, 0x85, 0x00, 0x0d, 0x0a, 0x85, 0x00, + 0xcd, 0xc0, 0x00, 0x00, 0x7b, 0x02, 0x01, 0x00, 0x4d, 0x0a, 0x85, 0x00, + 0xa9, 0x09, 0x85, 0x00, 0x25, 0x09, 0x85, 0x00, 0xdd, 0x0a, 0x85, 0x00, + 0x6d, 0x0a, 0x85, 0x00, 0x81, 0x08, 0x85, 0x00, 0xc5, 0x07, 0x85, 0x00, + 0x0d, 0x0b, 0x85, 0x00, 0x59, 0x0f, 0x85, 0x00, 0xed, 0x11, 0x85, 0x00, + 0xc9, 0x12, 0x85, 0x00, 0x21, 0x10, 0x85, 0x00, 0xf9, 0x0d, 0x85, 0x00, + 0xd5, 0x11, 0x85, 0x00, 0x51, 0x10, 0x85, 0x00, 0xad, 0x11, 0x85, 0x00, + 0x01, 0x11, 0x85, 0x00, 0x6d, 0x10, 0x85, 0x00, 0x21, 0xb4, 0x01, 0x00, + 0x85, 0x0f, 0x85, 0x00, 0x85, 0x10, 0x85, 0x00, 0x99, 0x0d, 0x85, 0x00, + 0x11, 0x12, 0x85, 0x00, 0x0d, 0x22, 0x85, 0x00, 0x41, 0x17, 0x85, 0x00, + 0xd9, 0x17, 0x85, 0x00, 0x75, 0x20, 0x85, 0x00, 0x7d, 0x2c, 0x85, 0x00, + 0x35, 0x2f, 0x85, 0x00, 0xb9, 0x22, 0x85, 0x00, 0x2d, 0x25, 0x85, 0x00, + 0x9d, 0x23, 0x85, 0x00, 0x61, 0x2f, 0x85, 0x00, 0xa5, 0x27, 0x85, 0x00, + 0xc9, 0x2a, 0x85, 0x00, 0x6d, 0x29, 0x85, 0x00, 0x9d, 0x22, 0x85, 0x00, + 0x31, 0x22, 0x85, 0x00, 0xa5, 0x24, 0x85, 0x00, 0xe1, 0x23, 0x85, 0x00, + 0xb1, 0x2f, 0x85, 0x00, 0xbd, 0x2c, 0x85, 0x00, 0x59, 0x14, 0x85, 0x00, + 0xc9, 0x13, 0x85, 0x00, 0xa1, 0x1c, 0x85, 0x00, 0x45, 0x2c, 0x85, 0x00, + 0xa9, 0x17, 0x85, 0x00, 0xb1, 0x20, 0x85, 0x00, 0x31, 0x1a, 0x85, 0x00, + 0xfd, 0x17, 0x85, 0x00, 0x29, 0x1d, 0x85, 0x00, 0x21, 0x14, 0x85, 0x00, + 0xad, 0x21, 0x85, 0x00, 0xb5, 0x30, 0x85, 0x00, 0x45, 0x31, 0x85, 0x00, + 0x35, 0x27, 0x85, 0x00, 0xd1, 0x31, 0x85, 0x00, 0xc5, 0x14, 0x85, 0x00, + 0xbd, 0x2d, 0x85, 0x00, 0x2d, 0x23, 0x85, 0x00, 0x59, 0x23, 0x85, 0x00, + 0x89, 0x14, 0x85, 0x00, 0x4d, 0x46, 0x85, 0x00, 0x65, 0x47, 0x85, 0x00, + 0x25, 0x36, 0x85, 0x00, 0x51, 0x47, 0x85, 0x00, 0x3d, 0x46, 0x85, 0x00, + 0x8d, 0x3c, 0x85, 0x00, 0x51, 0x4a, 0x85, 0x00, 0x99, 0x4a, 0x85, 0x00, + 0x75, 0x47, 0x85, 0x00, 0x1d, 0x47, 0x85, 0x00, 0x55, 0x36, 0x85, 0x00, + 0x5d, 0x46, 0x85, 0x00, 0xd5, 0x3b, 0x85, 0x00, 0x49, 0x49, 0x85, 0x00, + 0xd5, 0x3a, 0x85, 0x00, 0xe1, 0x39, 0x85, 0x00, 0x41, 0x39, 0x85, 0x00, + 0xe5, 0x38, 0x85, 0x00, 0x09, 0x37, 0x85, 0x00, 0x45, 0x35, 0x85, 0x00, + 0xc9, 0x3c, 0x85, 0x00, 0x75, 0x4b, 0x85, 0x00, 0xb9, 0x45, 0x85, 0x00, + 0xed, 0x48, 0x85, 0x00, 0x21, 0x46, 0x85, 0x00, 0x21, 0x3a, 0x85, 0x00, + 0xa9, 0x40, 0x85, 0x00, 0x01, 0x32, 0x85, 0x00, 0xf5, 0x32, 0x85, 0x00, + 0xfd, 0x37, 0x85, 0x00, 0x89, 0x4e, 0x85, 0x00, 0xdd, 0x50, 0x85, 0x00, + 0xed, 0x50, 0x85, 0x00, 0x5d, 0x57, 0x85, 0x00, 0x09, 0x55, 0x85, 0x00, + 0x49, 0x50, 0x85, 0x00, 0x5d, 0x50, 0x85, 0x00, 0xd1, 0x52, 0x85, 0x00, + 0xf5, 0x52, 0x85, 0x00, 0xe5, 0x4e, 0x85, 0x00, 0xc9, 0x55, 0x85, 0x00, + 0x65, 0x56, 0x85, 0x00, 0xc9, 0x50, 0x85, 0x00, 0x09, 0x4f, 0x85, 0x00, + 0xd7, 0xb4, 0x01, 0x00, 0x9d, 0x55, 0x85, 0x00, 0x0d, 0x53, 0x85, 0x00, + 0xa9, 0x4c, 0x85, 0x00, 0xb9, 0x57, 0x85, 0x00, 0xa5, 0x57, 0x85, 0x00, + 0x0d, 0x51, 0x85, 0x00, 0xfd, 0x5a, 0x85, 0x00, 0xd5, 0x51, 0x85, 0x00, + 0xa9, 0x51, 0x85, 0x00, 0xb1, 0x52, 0x85, 0x00, 0x9d, 0x53, 0x85, 0x00, + 0x39, 0x55, 0x85, 0x00, 0x9d, 0x4e, 0x85, 0x00, 0xc9, 0x57, 0x85, 0x00, + 0x6d, 0x57, 0x85, 0x00, 0x95, 0x4c, 0x85, 0x00, 0x09, 0x57, 0x85, 0x00, + 0x8d, 0x4f, 0x85, 0x00, 0x0f, 0xb5, 0x01, 0x00, 0xfd, 0x59, 0x85, 0x00, + 0x01, 0x4d, 0x85, 0x00, 0xed, 0x59, 0x85, 0x00, 0xd9, 0x59, 0x85, 0x00, + 0x19, 0x4c, 0x85, 0x00, 0x75, 0x6c, 0x85, 0x00, 0x81, 0x6e, 0x85, 0x00, + 0x51, 0x6c, 0x85, 0x00, 0x29, 0x5c, 0x85, 0x00, 0x41, 0x6e, 0x85, 0x00, + 0x79, 0x5e, 0x85, 0x00, 0x9b, 0x05, 0x01, 0x00, 0xad, 0x6e, 0x85, 0x00, + 0xb5, 0x6c, 0x85, 0x00, 0x6d, 0x65, 0x85, 0x00, 0x1d, 0x5f, 0x85, 0x00, + 0x19, 0x6b, 0x85, 0x00, 0x85, 0x79, 0x85, 0x00, 0x71, 0x73, 0x85, 0x00, + 0xb5, 0x8e, 0x85, 0x00, 0xe1, 0x95, 0x85, 0x00, 0x01, 0x82, 0x85, 0x00, + 0x51, 0x90, 0x85, 0x00, 0x2d, 0x82, 0x85, 0x00, 0xd1, 0x90, 0x85, 0x00, + 0xfd, 0x90, 0x85, 0x00, 0xbd, 0x92, 0x85, 0x00, 0x6d, 0x8f, 0x85, 0x00, + 0xcd, 0x92, 0x85, 0x00, 0x55, 0x96, 0x85, 0x00, 0xc5, 0x8e, 0x85, 0x00, + 0x85, 0x72, 0x85, 0x00, 0x5d, 0x8d, 0x85, 0x00, 0x01, 0x83, 0x85, 0x00, + 0xc1, 0x91, 0x85, 0x00, 0x25, 0x70, 0x85, 0x00, 0x0d, 0x91, 0x85, 0x00, + 0xc1, 0x76, 0x85, 0x00, 0x69, 0x71, 0x85, 0x00, 0x41, 0x71, 0x85, 0x00, + 0xf9, 0x7f, 0x85, 0x00, 0x79, 0x70, 0x85, 0x00, 0xf1, 0x93, 0x85, 0x00, + 0x9d, 0x95, 0x85, 0x00, 0xf5, 0x74, 0x85, 0x00, 0x49, 0x74, 0x85, 0x00, + 0x6d, 0x78, 0x85, 0x00, 0xbd, 0x72, 0x85, 0x00, 0xed, 0x8a, 0x85, 0x00, + 0xc9, 0x8c, 0x85, 0x00, 0x99, 0x91, 0x85, 0x00, 0x59, 0x7d, 0x85, 0x00, + 0xbd, 0x71, 0x85, 0x00, 0x75, 0x81, 0x85, 0x00, 0x0d, 0x81, 0x85, 0x00, + 0xa9, 0x79, 0x85, 0x00, 0x21, 0x77, 0x85, 0x00, 0x21, 0x93, 0x85, 0x00, + 0x89, 0x92, 0x85, 0x00, 0xd1, 0x94, 0x85, 0x00, 0x95, 0x96, 0x85, 0x00, + 0x65, 0x83, 0x85, 0x00, 0xd9, 0x73, 0x85, 0x00, 0x65, 0x82, 0x85, 0x00, + 0xdd, 0xb5, 0x01, 0x00, 0x59, 0x75, 0x85, 0x00, 0x21, 0x76, 0x85, 0x00, + 0x55, 0x6f, 0x85, 0x00, 0x6d, 0x95, 0x85, 0x00, 0xe5, 0x83, 0x85, 0x00, + 0x29, 0x84, 0x85, 0x00, 0xad, 0x8f, 0x85, 0x00, 0xf1, 0x6e, 0x85, 0x00, + 0xef, 0x1f, 0x01, 0x00, 0x19, 0x10, 0x01, 0x00, 0x7b, 0x1c, 0x01, 0x00, + 0x87, 0x1c, 0x01, 0x00, 0x8d, 0x1a, 0x01, 0x00, 0xb5, 0x14, 0x01, 0x00, + 0x7d, 0x15, 0x01, 0x00, 0x25, 0x15, 0x01, 0x00, 0xed, 0x14, 0x01, 0x00, + 0xc1, 0x14, 0x01, 0x00, 0xbb, 0x14, 0x01, 0x00, 0x65, 0x22, 0x01, 0x00, + 0xdd, 0x1e, 0x01, 0x00, 0xdd, 0x13, 0x01, 0x00, 0x35, 0x10, 0x01, 0x00, + 0x25, 0x22, 0x01, 0x00, 0x2d, 0x22, 0x01, 0x00, 0x91, 0x13, 0x01, 0x00, + 0x67, 0x10, 0x01, 0x00, 0x21, 0x1d, 0x01, 0x00, 0x65, 0x10, 0x01, 0x00, + 0xab, 0x24, 0x01, 0x00, 0x1d, 0x27, 0x01, 0x00, 0x17, 0x1a, 0x01, 0x00, + 0xa5, 0x13, 0x01, 0x00, 0xb7, 0x1e, 0x01, 0x00, 0xb3, 0x1e, 0x01, 0x00, + 0x9d, 0x1e, 0x01, 0x00, 0x87, 0x1a, 0x01, 0x00, 0x5f, 0x10, 0x01, 0x00, + 0x59, 0x10, 0x01, 0x00, 0x0d, 0x22, 0x01, 0x00, 0x6d, 0x2a, 0x01, 0x00, + 0xd7, 0x1e, 0x01, 0x00, 0x05, 0x22, 0x01, 0x00, 0x1d, 0x14, 0x01, 0x00, + 0x3d, 0x22, 0x01, 0x00, 0xe1, 0x1f, 0x01, 0x00, 0xb3, 0x16, 0x01, 0x00, + 0xc9, 0x15, 0x01, 0x00, 0x9d, 0x1b, 0x01, 0x00, 0xb5, 0x16, 0x01, 0x00, + 0x7d, 0x1b, 0x01, 0x00, 0x83, 0x1b, 0x01, 0x00, 0x43, 0x22, 0x01, 0x00, + 0x25, 0x1a, 0x01, 0x00, 0xab, 0x18, 0x01, 0x00, 0x55, 0x16, 0x01, 0x00, + 0x11, 0x1a, 0x01, 0x00, 0xdf, 0x1e, 0x01, 0x00, 0xd9, 0xc1, 0x00, 0x00, + 0x15, 0xc2, 0x00, 0x00, 0x51, 0xc2, 0x00, 0x00, 0x7d, 0xc5, 0x00, 0x00, + 0x95, 0xca, 0x00, 0x00, 0x19, 0x0c, 0x02, 0x00, 0xfd, 0xca, 0x00, 0x00, + 0x05, 0xcb, 0x00, 0x00, 0x07, 0xd1, 0x00, 0x00, 0xa7, 0xce, 0x00, 0x00, + 0xa3, 0xcf, 0x00, 0x00, 0x1b, 0xcf, 0x00, 0x00, 0x89, 0x32, 0x00, 0x00, + 0xd1, 0x30, 0x00, 0x00, 0xa1, 0x30, 0x00, 0x00, 0xc3, 0x30, 0x00, 0x00, + 0x5d, 0x30, 0x00, 0x00, 0x49, 0x30, 0x00, 0x00, 0x4d, 0x07, 0x01, 0x00, + 0x51, 0x07, 0x01, 0x00, 0xeb, 0x32, 0x00, 0x00, 0x3b, 0x33, 0x00, 0x00, + 0x2d, 0x4b, 0x00, 0x00, 0x6d, 0xf2, 0x00, 0x00, 0x59, 0x3a, 0x00, 0x00, + 0x6b, 0xf2, 0x00, 0x00, 0x41, 0x56, 0x00, 0x00, 0xa9, 0x73, 0x00, 0x00, + 0x8d, 0x7d, 0x00, 0x00, 0xa1, 0x6a, 0x00, 0x00, 0xad, 0xea, 0x00, 0x00, + 0xd9, 0xea, 0x00, 0x00, 0xeb, 0xea, 0x00, 0x00, 0xbd, 0xeb, 0x00, 0x00, + 0x3f, 0x08, 0x01, 0x00, 0xed, 0xa1, 0x00, 0x00, 0x5d, 0xf2, 0x00, 0x00, + 0x59, 0xf2, 0x00, 0x00, 0x4d, 0xf2, 0x00, 0x00, 0x53, 0xf2, 0x00, 0x00, + 0x7b, 0xed, 0x00, 0x00, 0x65, 0xf2, 0x00, 0x00, 0x63, 0xf2, 0x00, 0x00, + 0x67, 0xf2, 0x00, 0x00, 0x69, 0xf2, 0x00, 0x00, 0x4b, 0xf2, 0x00, 0x00, + 0x51, 0xf2, 0x00, 0x00, 0x57, 0xf2, 0x00, 0x00, 0x5f, 0xf2, 0x00, 0x00, + 0x17, 0xb0, 0x00, 0x00, 0x03, 0xb0, 0x00, 0x00, 0x09, 0xb0, 0x00, 0x00, + 0x0d, 0xb0, 0x00, 0x00, 0x21, 0xb0, 0x00, 0x00, 0x6d, 0x07, 0x01, 0x00, + 0x73, 0x07, 0x01, 0x00, 0x85, 0x07, 0x01, 0x00, 0x7f, 0x07, 0x01, 0x00, + 0x83, 0x07, 0x01, 0x00, 0x71, 0x07, 0x01, 0x00, 0x89, 0x07, 0x01, 0x00, + 0x8b, 0x07, 0x01, 0x00, 0x87, 0x07, 0x01, 0x00, 0x79, 0x07, 0x01, 0x00, + 0x77, 0x07, 0x01, 0x00, 0x7b, 0x07, 0x01, 0x00, 0xa1, 0xee, 0x00, 0x00, + 0x53, 0x07, 0x01, 0x00, 0x57, 0x07, 0x01, 0x00, 0x59, 0x07, 0x01, 0x00, + 0x5d, 0x07, 0x01, 0x00, 0x5f, 0x07, 0x01, 0x00, 0x61, 0x07, 0x01, 0x00, + 0x63, 0x07, 0x01, 0x00, 0x65, 0x07, 0x01, 0x00, 0x69, 0x07, 0x01, 0x00, + 0x87, 0xf2, 0x00, 0x00, 0x83, 0xf2, 0x00, 0x00, 0x7b, 0xf2, 0x00, 0x00, + 0x89, 0xf2, 0x00, 0x00, 0x79, 0xf2, 0x00, 0x00, 0x71, 0xf2, 0x00, 0x00, + 0x7f, 0xf2, 0x00, 0x00, 0x6f, 0xf2, 0x00, 0x00, 0x73, 0xf2, 0x00, 0x00, + 0x85, 0xf2, 0x00, 0x00, 0xa7, 0xee, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, + 0x20, 0x00, 0x00, 0x00, 0x1f, 0x00, 0x00, 0x00, 0x50, 0x00, 0x00, 0x00, + 0x02, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, + 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x66, 0xb7, 0x01, 0x00, + 0x0a, 0x07, 0x08, 0x00, 0xb5, 0x12, 0x02, 0x00, 0x51, 0xfb, 0x80, 0x00, + 0xc3, 0x30, 0x00, 0x00, 0xc9, 0x2f, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0xd1, 0xf9, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x29, 0xfb, 0x80, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x9c, 0x18, 0x00, 0x40, + 0x96, 0x00, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xaa, 0xaa, + 0x03, 0x00, 0x40, 0x96, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x2d, 0xe9, 0xf7, 0x4f, 0xb1, 0xf1, 0x00, 0x0b, + 0x04, 0x46, 0x15, 0x46, 0x9a, 0x46, 0x4a, 0xdb, 0x43, 0x8a, 0x81, 0x8a, + 0x5a, 0x44, 0x4b, 0x43, 0x9a, 0x42, 0x44, 0xda, 0x80, 0x68, 0x08, 0xf0, + 0x4b, 0xdb, 0x00, 0x21, 0x01, 0x90, 0xa0, 0x68, 0x08, 0xf0, 0x18, 0xdd, + 0x43, 0x69, 0x06, 0x46, 0x43, 0xf0, 0x00, 0x43, 0x43, 0x61, 0x00, 0x27, + 0x1d, 0xe0, 0x1a, 0xf8, 0x01, 0x9b, 0x4f, 0xf0, 0x08, 0x08, 0x01, 0xe0, + 0xaf, 0x42, 0x18, 0xd0, 0x19, 0xf0, 0x01, 0x0f, 0x0d, 0xd0, 0x20, 0x46, + 0x31, 0x46, 0x07, 0xeb, 0x0b, 0x02, 0xfe, 0xf3, 0x05, 0xf7, 0x30, 0xb1, + 0x73, 0x69, 0x4f, 0xf0, 0xff, 0x30, 0x23, 0xf0, 0x00, 0x43, 0x73, 0x61, + 0x1f, 0xe0, 0x01, 0x37, 0xb8, 0xf1, 0x01, 0x08, 0x4f, 0xea, 0x59, 0x09, + 0xe6, 0xd1, 0xaf, 0x42, 0xdf, 0xdb, 0x73, 0x69, 0xa0, 0x68, 0x23, 0xf0, + 0x00, 0x43, 0x73, 0x61, 0x00, 0x21, 0x08, 0xf0, 0x59, 0xdc, 0xa0, 0x68, + 0x01, 0x21, 0x08, 0xf0, 0x55, 0xdc, 0x20, 0x46, 0x31, 0x46, 0xfe, 0xf3, + 0xff, 0xf2, 0xa0, 0x68, 0x01, 0x99, 0x08, 0xf0, 0xdd, 0xdc, 0x00, 0x20, + 0x01, 0xe0, 0x6f, 0xf0, 0x1c, 0x00, 0xbd, 0xe8, 0xfe, 0x8f, 0x2d, 0xe9, + 0xf0, 0x41, 0x1e, 0x46, 0x05, 0x46, 0x88, 0x46, 0x17, 0x46, 0x1e, 0xf0, + 0xcb, 0xf9, 0x43, 0x68, 0x41, 0x46, 0x9c, 0x69, 0x28, 0x46, 0x3a, 0x46, + 0x33, 0x46, 0xa0, 0x47, 0xbd, 0xe8, 0xf0, 0x81, 0x40, 0x7c, 0x70, 0x47, + 0x13, 0xb5, 0x00, 0xf0, 0x99, 0xd8, 0x78, 0xb1, 0x00, 0x24, 0x09, 0xe0, + 0x00, 0x22, 0x01, 0xa9, 0xff, 0xf3, 0x52, 0xf7, 0x01, 0x98, 0x03, 0x78, + 0x2c, 0x2b, 0x08, 0xbf, 0x01, 0x30, 0x01, 0x34, 0x03, 0x78, 0x00, 0x2b, + 0xf2, 0xd1, 0x00, 0xe0, 0x04, 0x46, 0x20, 0x46, 0x1c, 0xbd, 0x38, 0xb5, + 0xb0, 0xf8, 0x42, 0x30, 0x05, 0x46, 0xb3, 0xb1, 0x40, 0xf2, 0xe9, 0x34, + 0x02, 0xe0, 0x0a, 0x20, 0x03, 0xf0, 0x3e, 0xdf, 0x2b, 0x6b, 0x1a, 0x69, + 0x02, 0xf0, 0x70, 0x42, 0xb2, 0xf1, 0x00, 0x5f, 0x05, 0xd0, 0xb2, 0xf1, + 0x40, 0x5f, 0x02, 0xd0, 0x0a, 0xb1, 0x01, 0x3c, 0xef, 0xd1, 0x1a, 0x68, + 0x22, 0xf0, 0x10, 0x02, 0x1a, 0x60, 0x38, 0xbd, 0x70, 0xb5, 0x90, 0xf8, + 0x78, 0x31, 0x04, 0x46, 0xff, 0x2b, 0x1c, 0xd0, 0x0e, 0x4d, 0x40, 0x6a, + 0xeb, 0x6e, 0x98, 0x47, 0xd5, 0xf8, 0x9c, 0x50, 0x60, 0x6a, 0xa8, 0x47, + 0x01, 0x28, 0x0b, 0xd8, 0x94, 0xf8, 0x14, 0x12, 0x41, 0xb9, 0x0b, 0x46, + 0x20, 0x46, 0x08, 0x4a, 0x03, 0xf0, 0x40, 0xde, 0x01, 0x23, 0x84, 0xf8, + 0x14, 0x32, 0x70, 0xbd, 0x60, 0x6a, 0x94, 0xf8, 0x05, 0x61, 0xa8, 0x47, + 0x30, 0x18, 0x84, 0xf8, 0x06, 0x01, 0x70, 0xbd, 0xe0, 0xa6, 0x85, 0x00, + 0x3d, 0x98, 0x80, 0x00, 0x71, 0xb1, 0x91, 0xf8, 0x08, 0x32, 0x01, 0x2b, + 0x0a, 0xd0, 0x91, 0xf8, 0x75, 0x31, 0x3b, 0xb1, 0x4b, 0x69, 0x1a, 0x6a, + 0x03, 0x4b, 0x13, 0x40, 0x13, 0xb1, 0x08, 0x46, 0x0c, 0xf0, 0x04, 0xbf, + 0x70, 0x47, 0x00, 0xbf, 0x00, 0xfc, 0x01, 0x01, 0xd0, 0xf8, 0x80, 0x11, + 0x10, 0xb5, 0x04, 0x46, 0x99, 0xb1, 0x02, 0x23, 0xc0, 0x68, 0xd4, 0xf8, + 0x84, 0x21, 0x08, 0xf0, 0x27, 0xdb, 0x07, 0x4b, 0x1b, 0x68, 0x53, 0xb9, + 0xd4, 0xf8, 0x80, 0x11, 0xd4, 0xf8, 0x84, 0x21, 0xe0, 0x68, 0x4a, 0x40, + 0x02, 0x23, 0xbd, 0xe8, 0x10, 0x40, 0x08, 0xf0, 0x19, 0x9b, 0x10, 0xbd, + 0xa0, 0x07, 0x02, 0x00, 0xf8, 0xb5, 0x90, 0xf8, 0x17, 0x32, 0x04, 0x46, + 0x01, 0x2b, 0x74, 0xd0, 0x01, 0x23, 0x80, 0xf8, 0x17, 0x32, 0x00, 0x27, + 0x42, 0xe0, 0xa0, 0x68, 0x31, 0x46, 0x00, 0xf0, 0xa5, 0xdb, 0xd4, 0xf8, + 0xf0, 0x30, 0x1b, 0x68, 0x98, 0x42, 0x05, 0xd9, 0x28, 0x46, 0x00, 0x21, + 0x32, 0x46, 0x00, 0xf0, 0x31, 0xdb, 0x41, 0xe0, 0x20, 0x46, 0xff, 0xf7, + 0x8b, 0xff, 0x35, 0x69, 0x00, 0x23, 0xab, 0x71, 0x94, 0xf8, 0x78, 0x31, + 0x31, 0x46, 0x2b, 0x72, 0x94, 0xf8, 0x06, 0x31, 0x84, 0xf8, 0x07, 0x31, + 0x6b, 0x72, 0xd4, 0xf8, 0xfc, 0x31, 0x60, 0x6a, 0x01, 0x33, 0xc4, 0xf8, + 0xfc, 0x31, 0x6a, 0x79, 0x25, 0x4b, 0x82, 0xf0, 0x80, 0x02, 0xd2, 0x09, + 0x5b, 0x6a, 0x98, 0x47, 0xb0, 0xb9, 0xd4, 0xf8, 0xf8, 0x20, 0x6b, 0x79, + 0x7a, 0xb1, 0x18, 0x07, 0x0d, 0xd0, 0x69, 0x78, 0x2b, 0x78, 0x12, 0x69, + 0x43, 0xea, 0x01, 0x23, 0x0f, 0x33, 0x1b, 0x09, 0x19, 0x0a, 0x18, 0xbf, + 0x00, 0x23, 0x93, 0x71, 0x94, 0xf8, 0x78, 0x31, 0x13, 0x72, 0xc4, 0xf8, + 0xf8, 0x60, 0x01, 0x27, 0xd4, 0xf8, 0xf0, 0x30, 0x1b, 0x68, 0x01, 0x2b, + 0x08, 0xd9, 0x04, 0xf1, 0x28, 0x05, 0x28, 0x46, 0x00, 0x21, 0x00, 0xf0, + 0x73, 0xda, 0x06, 0x46, 0x00, 0x28, 0xae, 0xd1, 0x00, 0x23, 0x84, 0xf8, + 0x17, 0x32, 0xc4, 0xf8, 0xf8, 0x30, 0x2f, 0xb1, 0x63, 0x69, 0x04, 0x22, + 0x5a, 0x64, 0x20, 0x46, 0x07, 0xf0, 0x60, 0xdf, 0xe3, 0x8d, 0xd4, 0xf8, + 0xc8, 0x21, 0x93, 0x42, 0x04, 0xd9, 0x20, 0x69, 0xbd, 0xe8, 0xf8, 0x40, + 0x01, 0xf0, 0xe6, 0x9d, 0xd4, 0xf8, 0xcc, 0x21, 0x93, 0x42, 0x04, 0xd2, + 0x20, 0x69, 0xbd, 0xe8, 0xf8, 0x40, 0x01, 0xf0, 0xcf, 0x9d, 0xf8, 0xbd, + 0xe0, 0xa6, 0x85, 0x00, 0x11, 0xf4, 0x7c, 0x4f, 0x2d, 0xe9, 0xf0, 0x41, + 0x04, 0x46, 0x0d, 0x46, 0x56, 0x4e, 0x66, 0xd0, 0x11, 0xf4, 0x80, 0x68, + 0x0e, 0xd0, 0xf3, 0x6d, 0x40, 0x6a, 0x98, 0x47, 0x33, 0x6b, 0x07, 0x1c, + 0x60, 0x6a, 0x18, 0xbf, 0x01, 0x27, 0x98, 0x47, 0x10, 0xf1, 0x00, 0x08, + 0x18, 0xbf, 0x4f, 0xf0, 0x01, 0x08, 0x00, 0xe0, 0x47, 0x46, 0x2a, 0x05, + 0x0c, 0xd5, 0xf3, 0x6d, 0x60, 0x6a, 0x98, 0x47, 0x33, 0x6b, 0x00, 0x28, + 0x18, 0xbf, 0x01, 0x27, 0x60, 0x6a, 0x98, 0x47, 0x00, 0x28, 0x18, 0xbf, + 0x4f, 0xf0, 0x01, 0x08, 0xeb, 0x04, 0x0c, 0xd5, 0xf3, 0x6d, 0x60, 0x6a, + 0x98, 0x47, 0x33, 0x6b, 0x00, 0x28, 0x18, 0xbf, 0x01, 0x27, 0x60, 0x6a, + 0x98, 0x47, 0x00, 0x28, 0x18, 0xbf, 0x4f, 0xf0, 0x01, 0x08, 0xa8, 0x04, + 0x04, 0xd5, 0xd4, 0xf8, 0x38, 0x31, 0x01, 0x33, 0xc4, 0xf8, 0x38, 0x31, + 0x69, 0x04, 0x09, 0xd5, 0xd4, 0xf8, 0x3c, 0x31, 0x01, 0x27, 0x01, 0x33, + 0xc4, 0xf8, 0x3c, 0x31, 0xd4, 0xf8, 0x3c, 0x31, 0xd4, 0xf8, 0x38, 0x31, + 0x2a, 0x04, 0x10, 0xd5, 0xd4, 0xf8, 0x40, 0x31, 0xd4, 0xf8, 0xf4, 0x10, + 0x01, 0x33, 0xc4, 0xf8, 0x40, 0x31, 0x31, 0xb1, 0xa0, 0x68, 0x01, 0x22, + 0x04, 0xf0, 0xe0, 0xd8, 0x00, 0x23, 0xc4, 0xf8, 0xf4, 0x30, 0x4f, 0xf0, + 0x01, 0x08, 0x1f, 0xb9, 0xb8, 0xf1, 0x00, 0x0f, 0x03, 0xd1, 0x0a, 0xe0, + 0xb8, 0xf1, 0x00, 0x0f, 0x04, 0xd0, 0x20, 0x46, 0x00, 0x21, 0x07, 0xf0, + 0xbd, 0xdd, 0x17, 0xb1, 0x20, 0x46, 0x07, 0xf0, 0x07, 0xd9, 0xeb, 0x01, + 0x02, 0xd5, 0x20, 0x46, 0x0c, 0xf0, 0xf2, 0xfd, 0x15, 0xf4, 0x90, 0x3f, + 0x12, 0xd1, 0xb3, 0x6f, 0x60, 0x6a, 0x98, 0x47, 0x70, 0xb9, 0x05, 0x46, + 0x2d, 0xe0, 0x20, 0x46, 0x07, 0xf0, 0x08, 0xda, 0xd4, 0xf8, 0xd8, 0x31, + 0x01, 0x35, 0x9d, 0x42, 0x05, 0xd3, 0x23, 0x6a, 0x43, 0xf4, 0x80, 0x33, + 0x23, 0x62, 0x06, 0xe0, 0x00, 0x25, 0xb3, 0x6e, 0x60, 0x6a, 0x98, 0x47, + 0x01, 0x46, 0x00, 0x28, 0xeb, 0xd1, 0xd4, 0xf8, 0x0c, 0x02, 0x20, 0xb1, + 0x03, 0x78, 0x13, 0xb1, 0x00, 0x21, 0x00, 0xf0, 0x1f, 0xd8, 0x20, 0x46, + 0xff, 0xf7, 0x8e, 0xfe, 0x94, 0xf8, 0x07, 0x31, 0x94, 0xf8, 0x06, 0x21, + 0x9a, 0x42, 0x08, 0xd0, 0x94, 0xf8, 0x05, 0x21, 0x9b, 0x1a, 0xdb, 0xb2, + 0x02, 0x2b, 0x02, 0xd8, 0x20, 0x46, 0x07, 0xf0, 0x07, 0xd9, 0xd4, 0xf8, + 0xd8, 0x01, 0x85, 0x42, 0x34, 0xbf, 0x00, 0x20, 0x01, 0x20, 0xbd, 0xe8, + 0xf0, 0x81, 0x00, 0xbf, 0xe0, 0xa6, 0x85, 0x00, 0x2d, 0xe9, 0xf0, 0x41, + 0x04, 0x46, 0x0d, 0x46, 0x16, 0x46, 0x98, 0x46, 0x40, 0xf2, 0xe9, 0x37, + 0x02, 0xe0, 0x0a, 0x20, 0x03, 0xf0, 0x94, 0xdd, 0x63, 0x69, 0x1a, 0x6d, + 0x00, 0x2a, 0x04, 0xda, 0x01, 0x3f, 0xf6, 0xd1, 0x38, 0x46, 0xbd, 0xe8, + 0xf0, 0x81, 0x06, 0x9a, 0x46, 0x44, 0x36, 0x02, 0xb2, 0xf1, 0x80, 0x7f, + 0x46, 0xf0, 0x00, 0x46, 0x03, 0xd1, 0x2a, 0x78, 0x42, 0xf0, 0x80, 0x72, + 0xb6, 0x18, 0x1e, 0x65, 0x40, 0xf2, 0xe9, 0x36, 0x02, 0xe0, 0x0a, 0x20, + 0x03, 0xf0, 0x78, 0xdd, 0x63, 0x69, 0x1b, 0x6d, 0x00, 0x2b, 0x03, 0xdb, + 0x2b, 0x70, 0x01, 0x20, 0xbd, 0xe8, 0xf0, 0x81, 0x01, 0x3e, 0xf2, 0xd1, + 0x30, 0x46, 0xbd, 0xe8, 0xf0, 0x81, 0xd0, 0xf8, 0x94, 0x31, 0x10, 0xb5, + 0x99, 0x42, 0x04, 0x46, 0x03, 0xd8, 0x0c, 0xf0, 0x73, 0xfd, 0xe0, 0x8d, + 0x10, 0xbd, 0x00, 0x20, 0x10, 0xbd, 0x00, 0x23, 0xc2, 0x6b, 0x0a, 0xb1, + 0x01, 0x3a, 0xc2, 0x63, 0x01, 0x33, 0xdb, 0xb2, 0x10, 0x30, 0x10, 0x2b, + 0xf6, 0xd1, 0x70, 0x47, 0x03, 0x68, 0x2d, 0xe9, 0xf7, 0x4f, 0x01, 0x2a, + 0x14, 0xbf, 0x4f, 0xf0, 0x2a, 0x08, 0x4f, 0xf0, 0x32, 0x08, 0x05, 0x46, + 0x0e, 0x46, 0x58, 0x68, 0x41, 0x46, 0x91, 0x46, 0x04, 0xf0, 0x58, 0xd8, + 0x07, 0x46, 0x48, 0xb9, 0x2b, 0x68, 0x4f, 0xf0, 0xff, 0x30, 0x1b, 0x68, + 0xd3, 0xf8, 0x8c, 0x30, 0x1a, 0x6d, 0x01, 0x32, 0x1a, 0x65, 0x64, 0xe0, + 0x06, 0xf1, 0x0e, 0x0b, 0x59, 0x46, 0x04, 0x69, 0x04, 0x22, 0x01, 0xa8, + 0xff, 0xf3, 0x40, 0xf1, 0x01, 0x9a, 0x4a, 0xf6, 0xfe, 0x13, 0x12, 0xba, + 0xb3, 0xeb, 0x12, 0x4f, 0x0c, 0xbf, 0x2c, 0x49, 0x06, 0xf1, 0x08, 0x01, + 0x20, 0x46, 0x06, 0x22, 0x05, 0xf1, 0x28, 0x0a, 0xff, 0xf3, 0x30, 0xf1, + 0xa0, 0x1d, 0x51, 0x46, 0x06, 0x22, 0xff, 0xf3, 0x2b, 0xf1, 0xb9, 0xf1, + 0x00, 0x0f, 0x0e, 0xd0, 0x00, 0x23, 0x23, 0x73, 0x84, 0xf8, 0x0d, 0x80, + 0x04, 0xf1, 0x0e, 0x00, 0x21, 0x49, 0x06, 0x22, 0xff, 0xf3, 0x1e, 0xf1, + 0x08, 0x23, 0x23, 0x75, 0x06, 0x23, 0x63, 0x75, 0x03, 0xe0, 0x08, 0x23, + 0x23, 0x73, 0x06, 0x23, 0x63, 0x73, 0xa8, 0xf1, 0x1c, 0x08, 0x44, 0x44, + 0x31, 0x46, 0x06, 0x22, 0x20, 0x46, 0xff, 0xf3, 0x0d, 0xf1, 0x00, 0x23, + 0xa3, 0x71, 0x02, 0x23, 0xe3, 0x71, 0x51, 0x46, 0x06, 0x22, 0x04, 0xf1, + 0x08, 0x00, 0xff, 0xf3, 0x03, 0xf1, 0x06, 0xf1, 0x18, 0x01, 0x04, 0x22, + 0x04, 0xf1, 0x0e, 0x00, 0xff, 0xf3, 0xfc, 0xf0, 0x06, 0xf1, 0x08, 0x01, + 0x06, 0x22, 0x04, 0xf1, 0x12, 0x00, 0xff, 0xf3, 0xf5, 0xf0, 0x59, 0x46, + 0x04, 0x22, 0x04, 0xf1, 0x18, 0x00, 0xff, 0xf3, 0xef, 0xf0, 0xd5, 0xf8, + 0x5c, 0x31, 0x28, 0x68, 0x01, 0x33, 0xc5, 0xf8, 0x5c, 0x31, 0x39, 0x46, + 0xd5, 0xf8, 0x68, 0x21, 0x25, 0xf0, 0xfa, 0xd9, 0x01, 0x20, 0xbd, 0xe8, + 0xfe, 0x8f, 0x00, 0xbf, 0x2c, 0x9e, 0x85, 0x00, 0x14, 0xd2, 0x85, 0x00, + 0x10, 0xb5, 0x03, 0x68, 0xd3, 0xf8, 0x00, 0x48, 0x1b, 0x68, 0x93, 0xf8, + 0xab, 0x30, 0x6b, 0xb1, 0xff, 0xf7, 0x63, 0xff, 0x08, 0xe0, 0xa1, 0x68, + 0x29, 0xb1, 0x01, 0x20, 0x00, 0xf0, 0x80, 0xfa, 0x08, 0xb1, 0xff, 0xf7, + 0x5a, 0xff, 0x24, 0x68, 0x00, 0x2c, 0xf4, 0xd1, 0x00, 0x20, 0x10, 0xbd, + 0xf8, 0xb5, 0x06, 0x68, 0x05, 0x46, 0x0f, 0x46, 0x70, 0x68, 0x4f, 0xf4, + 0xbc, 0x71, 0x03, 0xf0, 0x67, 0xdf, 0x04, 0x46, 0x88, 0xb1, 0x00, 0x21, + 0x4f, 0xf4, 0xbc, 0x72, 0xff, 0xf3, 0x18, 0xf1, 0xd5, 0xf8, 0x60, 0x31, + 0x26, 0x60, 0xc4, 0xf8, 0x60, 0x31, 0x95, 0xf8, 0x64, 0x31, 0xc4, 0xf8, + 0x68, 0x71, 0x84, 0xf8, 0x64, 0x31, 0x6b, 0x68, 0x63, 0x60, 0x20, 0x46, + 0xf8, 0xbd, 0x01, 0x46, 0x28, 0xb1, 0x03, 0x68, 0x4f, 0xf4, 0xbc, 0x72, + 0x58, 0x68, 0x03, 0xf0, 0x59, 0x9f, 0x70, 0x47, 0xf8, 0xb5, 0xc3, 0x68, + 0x05, 0x46, 0x0e, 0x46, 0x58, 0x68, 0x38, 0x21, 0x17, 0x46, 0x03, 0xf0, + 0x3f, 0xdf, 0x04, 0x46, 0x00, 0x28, 0x2b, 0xd0, 0x00, 0x21, 0x38, 0x22, + 0xff, 0xf3, 0xf0, 0xf0, 0x01, 0x23, 0x31, 0x46, 0x23, 0x60, 0x63, 0x60, + 0xa3, 0x60, 0x06, 0x22, 0x04, 0xf1, 0x0c, 0x00, 0xff, 0xf3, 0x82, 0xf0, + 0x73, 0x8e, 0x06, 0xf1, 0x09, 0x01, 0xa3, 0x74, 0x33, 0x7a, 0x04, 0xf1, + 0x14, 0x00, 0xe3, 0x74, 0x32, 0x7a, 0xff, 0xf3, 0x77, 0xf0, 0x76, 0x8d, + 0x28, 0x46, 0xa6, 0x86, 0xe7, 0x86, 0x21, 0x46, 0x38, 0x22, 0x21, 0x23, + 0x0b, 0xf0, 0x82, 0xdd, 0x50, 0xb1, 0xeb, 0x68, 0x21, 0x46, 0x58, 0x68, + 0x38, 0x22, 0x03, 0xf0, 0x23, 0xdf, 0x4f, 0xf0, 0xff, 0x30, 0xf8, 0xbd, + 0x6f, 0xf0, 0x1a, 0x00, 0xf8, 0xbd, 0x00, 0x00, 0x70, 0xb5, 0x0d, 0x46, + 0x03, 0x80, 0x19, 0x46, 0x90, 0xf8, 0xcf, 0x30, 0x90, 0xb0, 0x14, 0x46, + 0x17, 0x4e, 0x4f, 0xf0, 0xff, 0x32, 0x00, 0x95, 0x7b, 0xb9, 0x02, 0x92, + 0x03, 0x92, 0x04, 0x92, 0x05, 0x92, 0x0c, 0x22, 0x01, 0x93, 0x06, 0x93, + 0x07, 0x93, 0x08, 0x93, 0x09, 0x93, 0x0a, 0x96, 0x0b, 0x90, 0x0c, 0x92, + 0x0d, 0x93, 0x0e, 0x93, 0x12, 0xe0, 0x5b, 0xb2, 0x00, 0x25, 0x02, 0x92, + 0x03, 0x92, 0x04, 0x92, 0x05, 0x92, 0x07, 0x93, 0x00, 0xf1, 0xd0, 0x02, + 0x0c, 0x23, 0x01, 0x95, 0x06, 0x92, 0x08, 0x95, 0x09, 0x95, 0x0a, 0x96, + 0x0b, 0x90, 0x0c, 0x93, 0x0d, 0x95, 0x0e, 0x95, 0x04, 0x4a, 0x23, 0x46, + 0xc0, 0x68, 0x23, 0xf0, 0xeb, 0xdf, 0x10, 0xb0, 0x70, 0xbd, 0x00, 0xbf, + 0x75, 0xf1, 0x00, 0x00, 0x2c, 0x9e, 0x85, 0x00, 0x1f, 0xb5, 0x83, 0x6d, + 0x04, 0x46, 0x01, 0x2b, 0x16, 0xd1, 0xb0, 0xf8, 0x58, 0x31, 0xdb, 0x07, + 0x12, 0xd4, 0xc3, 0x68, 0x93, 0xf8, 0x70, 0x32, 0x73, 0xb9, 0x02, 0xaa, + 0x03, 0xa9, 0x01, 0xab, 0x0c, 0xf0, 0xcb, 0xf8, 0x02, 0x9a, 0x3a, 0xb1, + 0x20, 0x46, 0x03, 0x99, 0x01, 0x9b, 0xff, 0xf7, 0xab, 0xff, 0x08, 0xb9, + 0x02, 0x23, 0xa3, 0x65, 0x1f, 0xbd, 0x08, 0xb5, 0xb0, 0xf8, 0x58, 0x21, + 0x69, 0xb1, 0x42, 0xf0, 0x01, 0x02, 0xa0, 0xf8, 0x58, 0x21, 0x82, 0x6d, + 0x02, 0x2a, 0x12, 0xd1, 0xc3, 0x68, 0x0c, 0x21, 0xd3, 0xf8, 0x68, 0x01, + 0x51, 0xf0, 0x12, 0xdb, 0x0b, 0xe0, 0xd1, 0x07, 0x09, 0xd5, 0x22, 0xf0, + 0x01, 0x02, 0xa0, 0xf8, 0x58, 0x21, 0x82, 0x6d, 0x1a, 0xb1, 0x01, 0x22, + 0x82, 0x65, 0xff, 0xf7, 0xc5, 0xff, 0x00, 0x20, 0x08, 0xbd, 0x70, 0x47, + 0x10, 0xb5, 0x0c, 0x46, 0x41, 0xb1, 0x8b, 0x68, 0x23, 0xb9, 0xc0, 0x6f, + 0x09, 0x68, 0xff, 0xf7, 0x19, 0xff, 0xa0, 0x60, 0xa0, 0x68, 0x10, 0xbd, + 0xc0, 0x6f, 0x10, 0xbd, 0xf8, 0xb5, 0x8c, 0x69, 0x0b, 0x46, 0x21, 0x69, + 0x8b, 0x42, 0x03, 0xd0, 0xdd, 0x6a, 0x15, 0xb1, 0x2f, 0x68, 0x01, 0xe0, + 0x00, 0x25, 0x2f, 0x46, 0x63, 0x68, 0x11, 0x46, 0xd8, 0x68, 0x03, 0xf0, + 0xb9, 0xde, 0xa3, 0x68, 0x06, 0x46, 0x1b, 0x68, 0x93, 0xf8, 0x95, 0x30, + 0x1b, 0xb1, 0xc3, 0x8a, 0x43, 0xf0, 0x80, 0x03, 0xc3, 0x82, 0x63, 0x68, + 0x93, 0xf8, 0xab, 0x30, 0x8b, 0xb1, 0x20, 0x46, 0x29, 0x46, 0xff, 0xf7, + 0xcf, 0xff, 0x60, 0xb1, 0x31, 0x46, 0x0a, 0xf0, 0xbd, 0xd8, 0x02, 0x28, + 0x07, 0xd1, 0x63, 0x68, 0x31, 0x46, 0xd8, 0x68, 0x01, 0x22, 0x03, 0xf0, + 0x7d, 0xde, 0x01, 0x20, 0xf8, 0xbd, 0xa0, 0x68, 0x31, 0x46, 0x3a, 0x46, + 0x25, 0xf0, 0xb8, 0xd8, 0x00, 0x30, 0x18, 0xbf, 0x01, 0x20, 0xf8, 0xbd, + 0x08, 0xb5, 0x80, 0x68, 0x00, 0xf0, 0x62, 0xfc, 0x00, 0x20, 0x08, 0xbd, + 0x10, 0xb5, 0x04, 0x46, 0xff, 0xf7, 0xf6, 0xff, 0xa0, 0x68, 0xbd, 0xe8, + 0x10, 0x40, 0x03, 0xf0, 0xc1, 0xbb, 0x00, 0x00, 0x38, 0xb5, 0x05, 0x46, + 0x6b, 0x68, 0x80, 0x68, 0x1b, 0x7e, 0xb3, 0xb9, 0x02, 0xf0, 0x6d, 0xf9, + 0x04, 0x46, 0x20, 0xb9, 0xd5, 0xf8, 0x80, 0x00, 0x0a, 0xf0, 0xf4, 0xf9, + 0x04, 0x46, 0x09, 0xf0, 0x51, 0xfc, 0x6b, 0x68, 0xd3, 0xf8, 0x9c, 0x10, + 0x41, 0xb1, 0x0b, 0x78, 0x33, 0xb1, 0x04, 0x4b, 0x00, 0x22, 0x18, 0x68, + 0xff, 0xf3, 0xca, 0xf5, 0x00, 0xe0, 0x00, 0x24, 0x20, 0x46, 0x38, 0xbd, + 0x20, 0x08, 0x02, 0x00, 0x10, 0xb5, 0x43, 0x68, 0x04, 0x46, 0x1b, 0x7e, + 0x53, 0xb1, 0xd0, 0xf8, 0x80, 0x00, 0x0a, 0xf0, 0xec, 0xf9, 0xa0, 0x68, + 0x05, 0xf0, 0x03, 0xfb, 0x63, 0x68, 0x00, 0x22, 0x83, 0xf8, 0x20, 0x20, + 0x10, 0xbd, 0x08, 0xb5, 0x80, 0x69, 0xff, 0xf7, 0xeb, 0xff, 0x00, 0x20, + 0x08, 0xbd, 0x00, 0x00, 0x1f, 0xb5, 0x08, 0x4a, 0x03, 0x46, 0x00, 0x92, + 0x07, 0x4a, 0x08, 0x46, 0x01, 0x92, 0x07, 0x4a, 0x07, 0x49, 0xd2, 0x69, + 0x02, 0x92, 0x1a, 0x68, 0x06, 0x4b, 0xff, 0xf3, 0x15, 0xf2, 0x05, 0xb0, + 0x00, 0xbd, 0x00, 0xbf, 0xf7, 0xba, 0x01, 0x00, 0xbc, 0xba, 0x01, 0x00, + 0xfc, 0x07, 0x02, 0x00, 0xc8, 0xba, 0x01, 0x00, 0xeb, 0xba, 0x01, 0x00, + 0x2d, 0xe9, 0xf8, 0x43, 0x04, 0x46, 0x08, 0x46, 0x15, 0x46, 0x0d, 0xf0, + 0x81, 0xf9, 0x01, 0x46, 0x10, 0xb9, 0xd4, 0xf8, 0x10, 0x90, 0x01, 0xe0, + 0xd0, 0xf8, 0x04, 0x90, 0xa2, 0x68, 0xd9, 0xf8, 0x24, 0x70, 0x12, 0x68, + 0x2b, 0x69, 0x92, 0xf8, 0x95, 0x20, 0x1a, 0xb1, 0xee, 0x8a, 0xc6, 0xf3, + 0xc0, 0x26, 0x09, 0xe0, 0x1e, 0x7b, 0x5b, 0x7b, 0x43, 0xea, 0x06, 0x26, + 0x48, 0xf6, 0x6c, 0x03, 0xf3, 0x1a, 0x5e, 0x42, 0x46, 0xeb, 0x03, 0x06, + 0xd6, 0xb9, 0x63, 0x68, 0x93, 0xf8, 0xab, 0x30, 0xcb, 0xb1, 0x20, 0x46, + 0xff, 0xf7, 0x26, 0xff, 0xa8, 0xb1, 0x29, 0x46, 0x09, 0xf0, 0x06, 0xdf, + 0x04, 0x28, 0x01, 0xd0, 0x01, 0x28, 0x04, 0xd1, 0x63, 0x68, 0x29, 0x46, + 0xd8, 0x68, 0x00, 0x22, 0x4c, 0xe0, 0xa0, 0xf1, 0x05, 0x0c, 0xdc, 0xf1, + 0x00, 0x08, 0x48, 0xeb, 0x0c, 0x08, 0x03, 0xe0, 0x4f, 0xf0, 0x00, 0x08, + 0x00, 0xe0, 0xb0, 0x46, 0x63, 0x68, 0x93, 0xf8, 0x95, 0x30, 0x1b, 0xb1, + 0x16, 0xb9, 0xab, 0x8a, 0x2d, 0x33, 0xab, 0x82, 0x00, 0x2f, 0x33, 0xd0, + 0x06, 0xbb, 0xfb, 0x69, 0xd8, 0x07, 0x0b, 0xd5, 0x63, 0x7d, 0x4b, 0xb1, + 0x20, 0x46, 0x29, 0x46, 0x0c, 0xf0, 0xf2, 0xdb, 0x20, 0xb9, 0x63, 0x68, + 0x29, 0x46, 0xd8, 0x68, 0x32, 0x46, 0x27, 0xe0, 0xb8, 0xf1, 0x00, 0x0f, + 0x0e, 0xd1, 0x63, 0x68, 0x93, 0xf8, 0x96, 0x30, 0x53, 0xb1, 0xd4, 0xf8, + 0x84, 0x00, 0x29, 0x46, 0x0d, 0xf0, 0x4f, 0xf8, 0x20, 0xb9, 0x63, 0x68, + 0x29, 0x46, 0xd8, 0x68, 0x42, 0x46, 0x15, 0xe0, 0x63, 0x68, 0x29, 0x46, + 0xd8, 0x68, 0x03, 0xf0, 0xf1, 0xdd, 0x3b, 0x69, 0x04, 0x46, 0xdb, 0x68, + 0x48, 0x46, 0x39, 0x46, 0x22, 0x46, 0x98, 0x47, 0x60, 0xb1, 0x20, 0x46, + 0xbd, 0xe8, 0xf8, 0x43, 0x03, 0xf0, 0x20, 0x9d, 0x63, 0x68, 0x29, 0x46, + 0xd8, 0x68, 0x3a, 0x46, 0xbd, 0xe8, 0xf8, 0x43, 0x03, 0xf0, 0x82, 0x9d, + 0xbd, 0xe8, 0xf8, 0x83, 0x4a, 0x6a, 0x08, 0xb5, 0x42, 0xf4, 0x80, 0x12, + 0x91, 0xf8, 0x43, 0x30, 0x4a, 0x62, 0xd0, 0xf8, 0x88, 0x20, 0x03, 0xf0, + 0x07, 0x03, 0xd3, 0x18, 0x93, 0xf8, 0x80, 0x20, 0x01, 0x32, 0x83, 0xf8, + 0x80, 0x20, 0xd0, 0xf8, 0x88, 0x30, 0x01, 0x22, 0x83, 0xf8, 0x86, 0x20, + 0xd0, 0xf8, 0x88, 0x30, 0x93, 0xf8, 0x81, 0x10, 0x93, 0xf8, 0x7b, 0x20, + 0x91, 0x42, 0x11, 0xd2, 0x93, 0xf8, 0x80, 0x10, 0x93, 0xf8, 0x7a, 0x20, + 0x91, 0x42, 0x0b, 0xd2, 0x93, 0xf8, 0x82, 0x10, 0x93, 0xf8, 0x7c, 0x20, + 0x91, 0x42, 0x05, 0xd2, 0x93, 0xf8, 0x83, 0x20, 0x93, 0xf8, 0x7d, 0x30, + 0x9a, 0x42, 0x01, 0xd3, 0x0d, 0xf0, 0x34, 0xd8, 0x00, 0x20, 0x08, 0xbd, + 0x73, 0xb5, 0x14, 0x46, 0x05, 0x46, 0x11, 0x46, 0x40, 0x6f, 0xff, 0xf7, + 0x8a, 0xfe, 0x63, 0x68, 0x11, 0x2b, 0x08, 0xd0, 0x12, 0x2b, 0x01, 0xd0, + 0x10, 0x2b, 0x1c, 0xd1, 0xa3, 0x78, 0x03, 0xf0, 0x01, 0x03, 0x2b, 0x75, + 0x17, 0xe0, 0x02, 0xaa, 0x00, 0x23, 0x42, 0xf8, 0x04, 0x3d, 0xa8, 0x68, + 0x94, 0xf8, 0x2f, 0x10, 0x3b, 0xf0, 0xde, 0xdf, 0x06, 0x46, 0x60, 0xb1, + 0x83, 0x79, 0x23, 0xb9, 0x61, 0x88, 0xc1, 0xf3, 0x80, 0x01, 0x26, 0xf0, + 0x97, 0xdf, 0xb3, 0x79, 0x1b, 0xb1, 0xa8, 0x68, 0x31, 0x46, 0x0b, 0xf0, + 0x1e, 0xfd, 0x7c, 0xbd, 0x01, 0x28, 0x0c, 0xbf, 0x88, 0x68, 0x00, 0x20, + 0x70, 0x47, 0x64, 0x29, 0x11, 0xdc, 0x63, 0x29, 0x1e, 0xda, 0x4a, 0x29, + 0x1c, 0xd0, 0x06, 0xdc, 0x07, 0x29, 0x1c, 0xdb, 0x08, 0x29, 0x17, 0xdd, + 0x3c, 0x29, 0x18, 0xd1, 0x14, 0xe0, 0x50, 0x29, 0x12, 0xd0, 0x14, 0xdb, + 0x5c, 0x39, 0x03, 0x29, 0x0d, 0xe0, 0xc3, 0x29, 0x04, 0xdc, 0xc2, 0x29, + 0x0a, 0xda, 0xa8, 0x39, 0x02, 0x29, 0x06, 0xe0, 0xb1, 0xf5, 0x84, 0x7f, + 0x04, 0xd0, 0x06, 0xdb, 0xa1, 0xf5, 0x89, 0x71, 0x01, 0x29, 0x02, 0xd8, + 0x6f, 0xf0, 0x16, 0x00, 0x70, 0x47, 0x00, 0x20, 0x70, 0x47, 0xc8, 0x88, + 0x10, 0xf0, 0x08, 0x00, 0x18, 0xbf, 0x6f, 0xf0, 0x16, 0x00, 0x70, 0x47, + 0x4f, 0xf0, 0xff, 0x33, 0x10, 0xb5, 0xa0, 0xf8, 0x3c, 0x32, 0x04, 0x46, + 0x00, 0xf5, 0x0e, 0x70, 0x06, 0x30, 0x00, 0x21, 0x0c, 0x22, 0xfe, 0xf3, + 0x6f, 0xf6, 0x23, 0x68, 0x5b, 0x6b, 0x23, 0xb9, 0x4f, 0xf0, 0xff, 0x33, + 0xa4, 0xf8, 0x40, 0x32, 0x0b, 0xe0, 0x0f, 0x23, 0xa4, 0xf8, 0x3e, 0x32, + 0xf0, 0x23, 0xa4, 0xf8, 0x40, 0x32, 0x4f, 0xf4, 0x70, 0x63, 0xa4, 0xf8, + 0x42, 0x32, 0x4f, 0xf2, 0x00, 0x03, 0xa4, 0xf8, 0x44, 0x32, 0x10, 0xbd, + 0x2d, 0xe9, 0xf0, 0x4f, 0x87, 0xb0, 0x17, 0x46, 0x03, 0x93, 0xd2, 0xf8, + 0x10, 0x80, 0x69, 0x4b, 0x52, 0x68, 0xdd, 0xf8, 0x40, 0xa0, 0x13, 0x40, + 0x83, 0x46, 0x0d, 0x46, 0x0e, 0x69, 0x00, 0x2b, 0x14, 0xbf, 0x4f, 0xf0, + 0x0c, 0x09, 0x4f, 0xf0, 0x0a, 0x09, 0xba, 0xf1, 0x00, 0x0f, 0x04, 0xd0, + 0x9a, 0xf9, 0x0e, 0x30, 0x99, 0x44, 0x1f, 0xfa, 0x89, 0xf9, 0xab, 0x8a, + 0xc9, 0xeb, 0x06, 0x04, 0x4b, 0x44, 0xab, 0x82, 0x4a, 0x46, 0x2c, 0x61, + 0x20, 0x46, 0x00, 0x21, 0xfe, 0xf3, 0x30, 0xf6, 0x12, 0x9b, 0x09, 0xf1, + 0x0e, 0x09, 0xa3, 0xf8, 0x00, 0x90, 0x98, 0xf8, 0x06, 0x30, 0xfb, 0xb1, + 0x31, 0x46, 0x06, 0x22, 0x20, 0x1d, 0xfe, 0xf3, 0xbf, 0xf5, 0x04, 0xf1, + 0x0a, 0x00, 0x08, 0xf1, 0xbc, 0x01, 0x06, 0x22, 0xfe, 0xf3, 0xb8, 0xf5, + 0xba, 0xf1, 0x00, 0x0f, 0x04, 0xd1, 0x7a, 0x68, 0x4c, 0x4b, 0x13, 0x40, + 0x00, 0x2b, 0x3f, 0xd0, 0xb1, 0x1d, 0x06, 0x22, 0x04, 0xa8, 0xfe, 0xf3, + 0xab, 0xf5, 0x04, 0xf1, 0x10, 0x00, 0x04, 0xa9, 0x06, 0x22, 0xfe, 0xf3, + 0xa5, 0xf5, 0x33, 0xe0, 0x98, 0xf8, 0x12, 0x30, 0x20, 0x1d, 0xe3, 0xb1, + 0xd8, 0xf8, 0xcc, 0x30, 0x1b, 0x06, 0x18, 0xd4, 0x08, 0xf1, 0xbc, 0x01, + 0x06, 0x22, 0xfe, 0xf3, 0x97, 0xf5, 0x31, 0x46, 0x06, 0x22, 0x04, 0xa8, + 0xfe, 0xf3, 0x92, 0xf5, 0xb1, 0x1d, 0x06, 0x22, 0x04, 0xf1, 0x0a, 0x00, + 0xfe, 0xf3, 0x8c, 0xf5, 0x04, 0xf1, 0x10, 0x00, 0x04, 0xa9, 0x06, 0x22, + 0xfe, 0xf3, 0x86, 0xf5, 0x4f, 0xf4, 0x80, 0x76, 0x14, 0xe0, 0x31, 0x46, + 0x06, 0x22, 0xfe, 0xf3, 0x7f, 0xf5, 0xb1, 0x1d, 0x06, 0x22, 0x04, 0xf1, + 0x0a, 0x00, 0xfe, 0xf3, 0x79, 0xf5, 0x04, 0xf1, 0x10, 0x00, 0x08, 0xf1, + 0xbc, 0x01, 0x06, 0x22, 0xfe, 0xf3, 0x72, 0xf5, 0x00, 0x26, 0x01, 0xe0, + 0x4f, 0xf4, 0x00, 0x76, 0x7a, 0x68, 0x29, 0x4b, 0x13, 0x40, 0x53, 0xb3, + 0x9d, 0xf8, 0x44, 0x30, 0x69, 0x6a, 0x03, 0xf0, 0x07, 0x03, 0x48, 0x05, + 0xad, 0xf8, 0x16, 0x30, 0x0f, 0xd4, 0x9b, 0xf8, 0xf8, 0x21, 0x01, 0x2a, + 0x05, 0xd1, 0x41, 0xf4, 0x80, 0x21, 0x69, 0x62, 0x43, 0xf0, 0x20, 0x03, + 0x03, 0xe0, 0x52, 0x01, 0x02, 0xf0, 0x60, 0x02, 0x13, 0x43, 0xad, 0xf8, + 0x16, 0x30, 0x6b, 0x6a, 0x59, 0x06, 0x05, 0xd5, 0xbd, 0xf8, 0x16, 0x30, + 0x43, 0xf0, 0x80, 0x03, 0xad, 0xf8, 0x16, 0x30, 0x04, 0xf1, 0x18, 0x00, + 0x0d, 0xf1, 0x16, 0x01, 0x02, 0x22, 0xfe, 0xf3, 0x41, 0xf5, 0x46, 0xf0, + 0x80, 0x06, 0xba, 0xf1, 0x00, 0x0f, 0x0f, 0xd0, 0x7a, 0x68, 0x10, 0x4b, + 0x13, 0x40, 0x13, 0xb9, 0x04, 0xf1, 0x18, 0x03, 0x01, 0xe0, 0x04, 0xf1, + 0x1a, 0x03, 0x01, 0x22, 0x00, 0x92, 0x58, 0x46, 0x41, 0x46, 0x52, 0x46, + 0x44, 0xf0, 0xf2, 0xda, 0x03, 0x9b, 0x46, 0xf0, 0x08, 0x06, 0x13, 0xb1, + 0x46, 0xf4, 0x80, 0x66, 0xb6, 0xb2, 0xba, 0xf1, 0x00, 0x0f, 0x01, 0xd0, + 0x46, 0xf4, 0x80, 0x46, 0x26, 0x80, 0x20, 0x46, 0x07, 0xb0, 0xbd, 0xe8, + 0xf0, 0x8f, 0x00, 0xbf, 0x40, 0x00, 0x01, 0x80, 0x38, 0xb5, 0x04, 0x46, + 0xd4, 0xf8, 0x74, 0x15, 0x80, 0x68, 0x0c, 0xf0, 0x83, 0xd8, 0xd4, 0xf8, + 0xf8, 0x16, 0xd0, 0xf1, 0x01, 0x05, 0xa0, 0x68, 0x38, 0xbf, 0x00, 0x25, + 0x0c, 0xf0, 0x7a, 0xd8, 0x00, 0xb9, 0x01, 0x35, 0xa0, 0x68, 0xd4, 0xf8, + 0xfc, 0x16, 0x0c, 0xf0, 0x73, 0xd8, 0x00, 0xb9, 0x01, 0x35, 0xd4, 0xf8, + 0xe0, 0x36, 0xa0, 0x68, 0x19, 0x6a, 0x0c, 0xf0, 0x6b, 0xd8, 0x00, 0xb9, + 0x01, 0x35, 0xd4, 0xf8, 0xe0, 0x36, 0x00, 0x22, 0xda, 0x60, 0xa0, 0x68, + 0xd4, 0xf8, 0x3c, 0x15, 0x0c, 0xf0, 0x60, 0xd8, 0x00, 0xb9, 0x01, 0x35, + 0xa0, 0x68, 0xd4, 0xf8, 0x94, 0x17, 0x0c, 0xf0, 0x59, 0xd8, 0x00, 0xb9, + 0x01, 0x35, 0x28, 0x46, 0x38, 0xbd, 0xd0, 0xf8, 0x40, 0x35, 0x70, 0xb5, + 0x5c, 0x8e, 0x05, 0x46, 0x04, 0xf4, 0x40, 0x63, 0xb3, 0xf5, 0x40, 0x6f, + 0x21, 0xd1, 0x03, 0x68, 0x93, 0xf8, 0x46, 0x30, 0x9a, 0x07, 0x0b, 0xd0, + 0x04, 0xf4, 0x70, 0x41, 0xa1, 0xf5, 0x80, 0x53, 0x59, 0x42, 0x41, 0xeb, + 0x03, 0x01, 0xd0, 0xf8, 0x5c, 0x01, 0x42, 0xf0, 0x67, 0xde, 0x80, 0xb9, + 0x20, 0x46, 0xff, 0xf3, 0x1b, 0xf6, 0x40, 0xf4, 0x30, 0x60, 0x86, 0xb2, + 0x20, 0x46, 0xff, 0xf3, 0x15, 0xf6, 0x0e, 0x28, 0x8c, 0xbf, 0x4f, 0xf4, + 0x80, 0x50, 0x4f, 0xf4, 0x00, 0x50, 0x46, 0xea, 0x00, 0x04, 0x04, 0xf4, + 0x70, 0x42, 0x2b, 0x6b, 0xa2, 0xf5, 0x80, 0x5c, 0xdc, 0xf1, 0x00, 0x02, + 0x5b, 0x68, 0x42, 0xeb, 0x0c, 0x02, 0x9a, 0x42, 0x05, 0xd0, 0xd5, 0xf8, + 0x5c, 0x01, 0x01, 0x21, 0x42, 0xf0, 0x68, 0xd9, 0x04, 0x46, 0xd5, 0xf8, + 0x5c, 0x01, 0x21, 0x46, 0x42, 0xf0, 0xb2, 0xde, 0x98, 0xb9, 0x04, 0xf4, + 0x70, 0x44, 0xa4, 0xf5, 0x80, 0x5e, 0xde, 0xf1, 0x00, 0x04, 0x44, 0xeb, + 0x0e, 0x04, 0x0e, 0x34, 0x55, 0xf8, 0x24, 0x30, 0x2e, 0x6b, 0xd5, 0xf8, + 0x5c, 0x01, 0x2b, 0x63, 0x01, 0x21, 0x42, 0xf0, 0x4f, 0xd9, 0x2e, 0x63, + 0x04, 0x46, 0x20, 0x46, 0x70, 0xbd, 0x07, 0x2a, 0x01, 0xdd, 0x4a, 0x68, + 0x0a, 0xb9, 0x02, 0x6b, 0x12, 0x68, 0x03, 0x2a, 0x06, 0xd0, 0x51, 0x1e, + 0x01, 0x29, 0x0d, 0xd8, 0x01, 0x6b, 0x09, 0x68, 0x8a, 0x42, 0x09, 0xd1, + 0x9d, 0xf8, 0x00, 0x10, 0x11, 0xb1, 0x90, 0xf8, 0x29, 0x10, 0x31, 0xb1, + 0x43, 0xb1, 0x1a, 0x60, 0x00, 0x20, 0x70, 0x47, 0x6f, 0xf0, 0x0c, 0x00, + 0x70, 0x47, 0x6f, 0xf0, 0x0a, 0x00, 0x70, 0x47, 0x18, 0x46, 0x70, 0x47, + 0x2d, 0xe9, 0xf0, 0x4f, 0x89, 0xb0, 0x00, 0x23, 0x0f, 0x46, 0x17, 0x99, + 0x05, 0x46, 0x05, 0x92, 0x14, 0x9c, 0x15, 0x9e, 0x06, 0x93, 0x07, 0x93, + 0xdd, 0xf8, 0x48, 0xb0, 0xdd, 0xf8, 0x4c, 0xa0, 0x3b, 0xf0, 0x94, 0xde, + 0x05, 0x99, 0x04, 0x90, 0x01, 0xf0, 0x01, 0x08, 0x28, 0x68, 0x39, 0x46, + 0x22, 0x46, 0x33, 0x46, 0xcd, 0xf8, 0x00, 0x80, 0x1f, 0xf0, 0xf2, 0xdd, + 0x81, 0x46, 0x00, 0x28, 0x40, 0xf0, 0xdc, 0x80, 0xb7, 0xf9, 0x06, 0x30, + 0x00, 0x2b, 0x1b, 0xda, 0xb9, 0x88, 0x3a, 0x89, 0xb8, 0xf1, 0x00, 0x0f, + 0x09, 0xd0, 0x16, 0x9b, 0x49, 0x00, 0x03, 0x93, 0x00, 0x96, 0x01, 0x94, + 0x02, 0x96, 0x28, 0x69, 0x01, 0x31, 0x23, 0x46, 0x08, 0xe0, 0x16, 0x9b, + 0x28, 0x69, 0x03, 0x93, 0xcd, 0xf8, 0x00, 0xa0, 0x01, 0x94, 0x02, 0x96, + 0x49, 0x00, 0x5b, 0x46, 0x39, 0xf0, 0x1c, 0xda, 0x81, 0x46, 0xbb, 0xe0, + 0xba, 0xf1, 0x03, 0x0f, 0x0d, 0xd9, 0x04, 0x22, 0x06, 0xa8, 0x59, 0x46, + 0xfe, 0xf3, 0x1e, 0xf4, 0xba, 0xf1, 0x07, 0x0f, 0x05, 0xd9, 0x07, 0xa8, + 0x0b, 0xf1, 0x04, 0x01, 0x04, 0x22, 0xfe, 0xf3, 0x15, 0xf4, 0x05, 0x99, + 0x06, 0x9b, 0x8a, 0x1e, 0x1f, 0x2a, 0x00, 0xf2, 0x9d, 0x80, 0xdf, 0xe8, + 0x12, 0xf0, 0x20, 0x00, 0x22, 0x00, 0x24, 0x00, 0x28, 0x00, 0x2c, 0x00, + 0x2e, 0x00, 0x36, 0x00, 0x38, 0x00, 0x4a, 0x00, 0x4c, 0x00, 0x51, 0x00, + 0x53, 0x00, 0x55, 0x00, 0x57, 0x00, 0x59, 0x00, 0x5b, 0x00, 0x5d, 0x00, + 0x9b, 0x00, 0x9b, 0x00, 0x9b, 0x00, 0x63, 0x00, 0x65, 0x00, 0x76, 0x00, + 0x78, 0x00, 0x7c, 0x00, 0x7e, 0x00, 0x83, 0x00, 0x85, 0x00, 0x8a, 0x00, + 0x9b, 0x00, 0x95, 0x00, 0x8c, 0x00, 0x43, 0x4b, 0x02, 0xe0, 0x42, 0x4a, + 0x63, 0xe0, 0x42, 0x4b, 0x1b, 0x68, 0x23, 0x60, 0x7a, 0xe0, 0x00, 0x2b, + 0x73, 0xdc, 0x3f, 0x4a, 0x04, 0xe0, 0x3f, 0x4b, 0xf6, 0xe7, 0x00, 0x2b, + 0x6d, 0xdb, 0x3d, 0x4a, 0x13, 0x60, 0x3d, 0x4b, 0x00, 0x22, 0x1a, 0x60, + 0x6c, 0xe0, 0x3c, 0x4b, 0xec, 0xe7, 0x1b, 0xb1, 0x3b, 0x4a, 0x12, 0x68, + 0x00, 0x2a, 0x60, 0xd0, 0x38, 0x4a, 0x13, 0x60, 0x39, 0x4a, 0x00, 0x23, + 0x13, 0x60, 0x39, 0x4a, 0x13, 0x60, 0x39, 0x4a, 0x13, 0x60, 0x4f, 0xf0, + 0xff, 0x32, 0x38, 0x4b, 0xe9, 0xe7, 0x33, 0x4b, 0xd8, 0xe7, 0x32, 0x4a, + 0x11, 0x68, 0x00, 0x29, 0x37, 0xdc, 0x4c, 0xe0, 0x34, 0x4b, 0xd1, 0xe7, + 0x33, 0x4a, 0x32, 0xe0, 0x33, 0x4b, 0xcd, 0xe7, 0x32, 0x4a, 0x2e, 0xe0, + 0x2c, 0x4b, 0xc9, 0xe7, 0x2b, 0x4a, 0x2a, 0xe0, 0xd5, 0xf8, 0x6c, 0x32, + 0xd3, 0xf8, 0xd8, 0x32, 0x9b, 0x68, 0xc2, 0xe7, 0x2d, 0x4b, 0xbf, 0xe7, + 0x2c, 0x4a, 0x13, 0x60, 0x00, 0x2b, 0x39, 0xd0, 0x2b, 0x4a, 0x00, 0x23, + 0x2b, 0x49, 0x13, 0x60, 0x4f, 0xf0, 0xff, 0x32, 0x0a, 0x60, 0x2a, 0x49, + 0x0a, 0x60, 0x2a, 0x4a, 0x13, 0x60, 0x2a, 0x4a, 0x11, 0xe0, 0x2a, 0x4b, + 0xac, 0xe7, 0x00, 0x2b, 0x23, 0xdd, 0x28, 0x4a, 0x0b, 0xe0, 0x28, 0x4b, + 0xa6, 0xe7, 0x5a, 0x1e, 0x09, 0x2a, 0x1c, 0xd8, 0x25, 0x4a, 0x04, 0xe0, + 0x25, 0x4b, 0x9f, 0xe7, 0x00, 0x2b, 0x16, 0xdd, 0x23, 0x4a, 0x13, 0x60, + 0x18, 0xe0, 0x23, 0x4b, 0x98, 0xe7, 0x04, 0x99, 0x8a, 0x79, 0x8a, 0xb9, + 0x00, 0x33, 0x21, 0x4a, 0x18, 0xbf, 0x01, 0x23, 0x13, 0x70, 0x0d, 0xe0, + 0x04, 0x9a, 0x93, 0x79, 0x43, 0xb9, 0x1d, 0x4b, 0x1b, 0x78, 0x8a, 0xe7, + 0x6f, 0xf0, 0x16, 0x09, 0x04, 0xe0, 0x6f, 0xf0, 0x1c, 0x09, 0x01, 0xe0, + 0x6f, 0xf0, 0x06, 0x09, 0x48, 0x46, 0x09, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, + 0xe0, 0x07, 0x02, 0x00, 0xcc, 0x07, 0x02, 0x00, 0xd4, 0x07, 0x02, 0x00, + 0xa8, 0x07, 0x02, 0x00, 0xb4, 0x07, 0x02, 0x00, 0x2c, 0xfe, 0x01, 0x00, + 0xc8, 0x07, 0x02, 0x00, 0xc4, 0x07, 0x02, 0x00, 0xc0, 0x07, 0x02, 0x00, + 0xac, 0x07, 0x02, 0x00, 0x18, 0xfe, 0x01, 0x00, 0x30, 0xfe, 0x01, 0x00, + 0xb0, 0x07, 0x02, 0x00, 0xd8, 0x07, 0x02, 0x00, 0x14, 0xfe, 0x01, 0x00, + 0x20, 0xfe, 0x01, 0x00, 0xbc, 0x07, 0x02, 0x00, 0xd0, 0x07, 0x02, 0x00, + 0x1c, 0xfe, 0x01, 0x00, 0x28, 0xfe, 0x01, 0x00, 0x10, 0xfe, 0x01, 0x00, + 0xb8, 0x07, 0x02, 0x00, 0xa4, 0x07, 0x02, 0x00, 0x38, 0xb5, 0x00, 0x25, + 0x04, 0x46, 0x80, 0xf8, 0xe8, 0x51, 0x26, 0xf0, 0x13, 0xd8, 0xe3, 0x6a, + 0x29, 0x46, 0x98, 0x6a, 0x80, 0x22, 0xfe, 0xf3, 0x8f, 0xf3, 0x20, 0x69, + 0x06, 0xf0, 0xc8, 0xfc, 0xd4, 0xf8, 0x40, 0x01, 0x2b, 0xf0, 0xfa, 0xde, + 0xc4, 0xf8, 0x88, 0x56, 0x38, 0xbd, 0x00, 0x00, 0x2d, 0xe9, 0xf8, 0x43, + 0x98, 0x46, 0x53, 0x6a, 0x0e, 0x46, 0x99, 0x05, 0x04, 0x46, 0x15, 0x46, + 0x9d, 0xf9, 0x20, 0x90, 0x17, 0x69, 0x09, 0xd5, 0x13, 0x6b, 0xa7, 0xf8, + 0x42, 0x30, 0x1b, 0x0c, 0xa7, 0xf8, 0x44, 0x30, 0x3b, 0x88, 0x43, 0xf4, + 0x00, 0x53, 0x3b, 0x80, 0x22, 0x68, 0x6b, 0x6b, 0x92, 0xf8, 0x44, 0x20, + 0x9a, 0xb1, 0xe2, 0x6a, 0x02, 0xeb, 0x46, 0x02, 0xb2, 0xf9, 0x1c, 0x20, + 0x6a, 0xb9, 0x63, 0xb1, 0x1a, 0x69, 0xd2, 0xf8, 0xd4, 0x22, 0x92, 0xf8, + 0x9d, 0x20, 0x03, 0x2a, 0x05, 0xd9, 0xd4, 0xf8, 0x64, 0x01, 0x31, 0x46, + 0x2a, 0x46, 0x3e, 0xf0, 0xf7, 0xdc, 0x04, 0x2e, 0x1d, 0xd1, 0x23, 0x68, + 0xb7, 0xf8, 0x4c, 0x70, 0x93, 0xf8, 0x38, 0x30, 0x3a, 0x46, 0xc3, 0xb1, + 0x28, 0x46, 0x13, 0xf0, 0x7b, 0xd8, 0x04, 0xeb, 0x80, 0x00, 0xd0, 0xf8, + 0x4c, 0x32, 0xd3, 0xf8, 0x58, 0x25, 0xa3, 0xf8, 0xc8, 0x70, 0x01, 0x32, + 0xc3, 0xf8, 0x58, 0x25, 0xd3, 0xf8, 0x60, 0x35, 0xd9, 0x69, 0x8a, 0x42, + 0x88, 0xbf, 0xda, 0x61, 0x1a, 0x6a, 0x01, 0x32, 0x1a, 0x62, 0x4f, 0xf6, + 0xff, 0x72, 0xb8, 0xf1, 0x00, 0x0f, 0x07, 0xd0, 0xe3, 0x6a, 0x06, 0xf1, + 0x0c, 0x01, 0x03, 0xeb, 0x41, 0x03, 0x99, 0x88, 0x49, 0x44, 0x99, 0x80, + 0x4f, 0xf6, 0xff, 0x73, 0x9a, 0x42, 0x03, 0xd0, 0x20, 0x69, 0xa8, 0x21, + 0x3a, 0xf0, 0x2a, 0xd9, 0x23, 0x69, 0x29, 0x46, 0x03, 0xeb, 0x86, 0x03, + 0xd8, 0x68, 0x0d, 0x4b, 0x42, 0x46, 0x5b, 0x6a, 0x98, 0x47, 0x00, 0x28, + 0x12, 0xda, 0x0b, 0x48, 0x0b, 0xf0, 0xe4, 0xfe, 0x0a, 0x4b, 0x1a, 0x68, + 0x01, 0x32, 0x1a, 0x60, 0xb8, 0xf1, 0x00, 0x0f, 0x08, 0xd0, 0xe3, 0x6a, + 0x0c, 0x36, 0x03, 0xeb, 0x46, 0x06, 0xb3, 0x88, 0xc9, 0xeb, 0x03, 0x09, + 0xa6, 0xf8, 0x04, 0x90, 0xbd, 0xe8, 0xf8, 0x83, 0xe0, 0xa6, 0x85, 0x00, + 0xbc, 0x56, 0x86, 0x00, 0xdc, 0x07, 0x02, 0x00, 0x19, 0xb1, 0x40, 0x68, + 0x30, 0x22, 0x03, 0xf0, 0x4d, 0x99, 0x70, 0x47, 0x2d, 0xe9, 0xf0, 0x4f, + 0x0e, 0x46, 0x04, 0x46, 0x11, 0x69, 0xd2, 0xf8, 0x7c, 0x01, 0x9f, 0xb0, + 0xd6, 0xf8, 0x10, 0xb0, 0x13, 0x93, 0x07, 0x90, 0x0c, 0x91, 0x91, 0x46, + 0xbb, 0xf8, 0x00, 0x20, 0x60, 0x68, 0x02, 0xf0, 0x0c, 0x03, 0x9b, 0x08, + 0x02, 0x2b, 0x0f, 0x93, 0x0c, 0xbf, 0xc2, 0xf3, 0xc0, 0x13, 0x00, 0x23, + 0xdb, 0xb2, 0x31, 0x46, 0x2c, 0x9f, 0xdd, 0xf8, 0xb4, 0x80, 0x0e, 0x92, + 0x14, 0x93, 0xff, 0xf3, 0xbb, 0xf3, 0x04, 0x30, 0x0a, 0x90, 0x87, 0xb1, + 0x3b, 0x7a, 0x0b, 0x2b, 0x08, 0xd1, 0x94, 0xf8, 0xf0, 0x37, 0x53, 0xb1, + 0x94, 0xf8, 0xf1, 0x37, 0x3b, 0xb1, 0xbb, 0x79, 0x07, 0x2b, 0x04, 0xd8, + 0x0a, 0x98, 0x97, 0xf9, 0x0f, 0x30, 0xc0, 0x18, 0x0a, 0x90, 0xd4, 0xf8, + 0x88, 0x31, 0x00, 0x2b, 0x19, 0xda, 0xdf, 0xb1, 0x3b, 0x7a, 0x02, 0x2b, + 0x1a, 0xd1, 0x94, 0xf8, 0xa0, 0x24, 0xd2, 0xb9, 0x0c, 0x99, 0x8b, 0x6d, + 0x13, 0xf0, 0x08, 0x03, 0x16, 0xd1, 0xba, 0x79, 0x29, 0x2a, 0x15, 0xd8, + 0x03, 0x2a, 0x13, 0xd9, 0x0b, 0x2a, 0x11, 0xd8, 0x29, 0x9a, 0x01, 0x2a, + 0x0e, 0xd1, 0x0a, 0x9b, 0x08, 0x33, 0x0a, 0x93, 0x08, 0xe0, 0x00, 0x20, + 0x08, 0x90, 0x08, 0xe0, 0x08, 0x97, 0x06, 0xe0, 0x00, 0x21, 0x08, 0x91, + 0x03, 0xe0, 0x00, 0x22, 0x08, 0x92, 0x00, 0xe0, 0x08, 0x93, 0x35, 0x69, + 0x00, 0x21, 0xab, 0x1f, 0x15, 0x93, 0xb3, 0x8a, 0xa5, 0xf1, 0x76, 0x00, + 0x76, 0x33, 0xb3, 0x82, 0x70, 0x22, 0x30, 0x61, 0x12, 0x90, 0xfe, 0xf3, + 0x85, 0xf2, 0x73, 0x6a, 0x5b, 0x05, 0x01, 0xd5, 0x33, 0x8d, 0x22, 0xe0, + 0xd9, 0xf8, 0x04, 0x20, 0x94, 0x4b, 0x13, 0x40, 0xbb, 0xb1, 0x0e, 0x99, + 0x01, 0xf0, 0xfc, 0x03, 0x88, 0x2b, 0x12, 0xd1, 0x9b, 0xf8, 0x04, 0x30, + 0xd8, 0x07, 0x0e, 0xd4, 0x29, 0x98, 0xf2, 0x8a, 0x41, 0x1e, 0x02, 0xf0, + 0x07, 0x02, 0x28, 0x98, 0x5c, 0x32, 0x09, 0xeb, 0x42, 0x02, 0x88, 0x42, + 0xd3, 0x88, 0x08, 0xd1, 0x59, 0x1c, 0xd1, 0x80, 0x05, 0xe0, 0x0f, 0x99, + 0x01, 0x29, 0x08, 0xd1, 0x4f, 0xf0, 0x00, 0x0a, 0x10, 0xe0, 0x0f, 0x9a, + 0x4f, 0xf0, 0x00, 0x0a, 0x01, 0x2a, 0x03, 0xd1, 0x0a, 0xe0, 0x4f, 0xf0, + 0x10, 0x0a, 0x00, 0x23, 0x28, 0x98, 0x1b, 0x01, 0x9b, 0xb2, 0x00, 0xf0, + 0x0f, 0x02, 0x13, 0x43, 0xab, 0xf8, 0x16, 0x30, 0x2a, 0x99, 0x04, 0x29, + 0x07, 0xd1, 0x20, 0x46, 0x0c, 0x99, 0x12, 0x9a, 0x0e, 0xf0, 0x24, 0xde, + 0xad, 0xf8, 0x72, 0x00, 0x19, 0xe0, 0x28, 0x98, 0xb4, 0xf8, 0x46, 0x35, + 0x00, 0xf0, 0x0f, 0x02, 0x29, 0x98, 0x42, 0xea, 0x03, 0x12, 0x41, 0x1e, + 0x28, 0x98, 0x92, 0xb2, 0x88, 0x42, 0x02, 0xd1, 0x01, 0x33, 0xa4, 0xf8, + 0x46, 0x35, 0x2a, 0x99, 0x52, 0x01, 0x47, 0xf6, 0xe0, 0x73, 0x13, 0x40, + 0x01, 0xf0, 0x07, 0x02, 0x13, 0x43, 0xad, 0xf8, 0x72, 0x30, 0x99, 0xf8, + 0xdf, 0x30, 0x23, 0xb9, 0x0e, 0x9a, 0x02, 0xf0, 0xfc, 0x03, 0x80, 0x2b, + 0x01, 0xd1, 0x4a, 0xf0, 0x20, 0x0a, 0x65, 0x4b, 0x08, 0xea, 0x03, 0x03, + 0x23, 0xb1, 0xcd, 0xf8, 0x6c, 0x80, 0xcd, 0xf8, 0x68, 0x80, 0x0e, 0xe0, + 0x0f, 0x9b, 0x01, 0x2b, 0x05, 0xd9, 0x73, 0x6a, 0x00, 0x2b, 0x02, 0xdb, + 0x13, 0xf0, 0x10, 0x03, 0x07, 0xd0, 0x99, 0xf8, 0x48, 0x30, 0x03, 0xf0, + 0x7f, 0x03, 0x1b, 0x93, 0x1a, 0x93, 0x00, 0x23, 0x38, 0xe0, 0x20, 0x6b, + 0x57, 0x49, 0x82, 0x6c, 0x11, 0x40, 0x19, 0xb1, 0x9b, 0xf8, 0x04, 0x10, + 0xc9, 0x07, 0x08, 0xd4, 0x9b, 0xf8, 0x04, 0x30, 0x13, 0xf0, 0x01, 0x03, + 0xe9, 0xd1, 0x42, 0x6c, 0x50, 0x49, 0x11, 0x40, 0x11, 0xb1, 0x1b, 0x92, + 0x1a, 0x92, 0x23, 0xe0, 0x1b, 0xab, 0x00, 0x93, 0x0d, 0xf1, 0x76, 0x03, + 0x01, 0x93, 0x0d, 0xf1, 0x77, 0x03, 0x02, 0x93, 0x1d, 0xab, 0x03, 0x93, + 0x49, 0x46, 0x0d, 0xf1, 0x72, 0x02, 0x1a, 0xab, 0xd4, 0xf8, 0x60, 0x01, + 0x4f, 0xf0, 0x16, 0xd8, 0x73, 0x6a, 0x43, 0xf0, 0x00, 0x62, 0x72, 0x62, + 0xbd, 0xf8, 0x74, 0x20, 0xd1, 0x07, 0x04, 0xd5, 0x43, 0xf0, 0x00, 0x63, + 0x43, 0xf4, 0x00, 0x53, 0x73, 0x62, 0x28, 0x98, 0xd0, 0xf1, 0x01, 0x03, + 0x38, 0xbf, 0x00, 0x23, 0x22, 0x68, 0xd4, 0xf8, 0x60, 0x06, 0x92, 0xf8, + 0x46, 0x20, 0x90, 0xf8, 0x0a, 0xc0, 0x12, 0xf0, 0x03, 0x02, 0x1a, 0x99, + 0x00, 0xf0, 0x32, 0x81, 0x11, 0xf0, 0x00, 0x6f, 0x01, 0xf0, 0x7f, 0x02, + 0x04, 0xd0, 0x07, 0x2a, 0x08, 0xd9, 0x20, 0x2a, 0x2b, 0xd1, 0x05, 0xe0, + 0xdf, 0xf8, 0xc4, 0xe0, 0x1e, 0xf9, 0x02, 0x20, 0x00, 0x2a, 0x24, 0xda, + 0x4a, 0x00, 0x01, 0xd4, 0x00, 0x29, 0x20, 0xdb, 0x21, 0xf4, 0x40, 0x12, + 0x22, 0xf4, 0x60, 0x52, 0x09, 0x01, 0x1a, 0x92, 0x16, 0xd5, 0x81, 0x78, + 0x01, 0x29, 0x13, 0xd9, 0x21, 0x6b, 0x91, 0xf9, 0x4d, 0x10, 0x01, 0x29, + 0x09, 0xd0, 0xd9, 0xf8, 0x04, 0xe0, 0x1e, 0xf0, 0x80, 0x4f, 0x09, 0xd0, + 0x01, 0x31, 0x07, 0xd1, 0x01, 0x7b, 0x49, 0x07, 0x04, 0xd5, 0x42, 0xf4, + 0x80, 0x12, 0x42, 0xf4, 0x80, 0x52, 0x01, 0xe0, 0x42, 0xea, 0xcc, 0x22, + 0x1a, 0x92, 0x1b, 0x99, 0x11, 0xf0, 0x00, 0x6f, 0x01, 0xf0, 0x7f, 0x02, + 0x04, 0xd0, 0x07, 0x2a, 0x06, 0xd9, 0x20, 0x2a, 0x33, 0xd1, 0x03, 0xe0, + 0x16, 0x48, 0x82, 0x56, 0x00, 0x2a, 0x2e, 0xda, 0x1a, 0x9a, 0x50, 0x00, + 0x01, 0xd4, 0x00, 0x2a, 0x29, 0xdb, 0x21, 0xf4, 0x40, 0x12, 0x22, 0xf4, + 0x60, 0x52, 0x09, 0x01, 0x1b, 0x92, 0x1f, 0xd5, 0xd4, 0xf8, 0x60, 0x16, + 0x88, 0x78, 0x01, 0x28, 0x1a, 0xd9, 0x20, 0x6b, 0x90, 0xf9, 0x4d, 0x00, + 0x01, 0x28, 0x09, 0xd0, 0xd9, 0xf8, 0x04, 0xe0, 0x1e, 0xf0, 0x80, 0x4f, + 0x10, 0xd0, 0x01, 0x30, 0x0e, 0xd1, 0x09, 0x7b, 0x48, 0x07, 0x0b, 0xd5, + 0x42, 0xf4, 0x80, 0x12, 0x42, 0xf4, 0x80, 0x52, 0x08, 0xe0, 0x00, 0xbf, + 0x40, 0x00, 0x01, 0x80, 0x7f, 0x00, 0x00, 0x08, 0x40, 0x1b, 0x86, 0x00, + 0x42, 0xea, 0xcc, 0x22, 0x1b, 0x92, 0xb4, 0xf8, 0x28, 0x26, 0x02, 0xf4, + 0x40, 0x62, 0xb2, 0xf5, 0x40, 0x6f, 0x2d, 0xd1, 0x22, 0x6b, 0x10, 0x69, + 0x05, 0x93, 0x0d, 0xf0, 0x7f, 0xfb, 0x1a, 0x9a, 0x00, 0xf4, 0x40, 0x70, + 0xb0, 0xf5, 0x00, 0x7f, 0x14, 0xbf, 0x02, 0x20, 0x03, 0x20, 0x12, 0xf0, + 0x00, 0x6f, 0x05, 0x9b, 0x02, 0xf0, 0x7f, 0x02, 0x0d, 0xd0, 0x20, 0x2a, + 0x29, 0xd0, 0x94, 0xf9, 0xca, 0x24, 0x51, 0x1c, 0x01, 0xd0, 0x06, 0x90, + 0x10, 0xe0, 0xd9, 0xf8, 0x04, 0x20, 0x06, 0x90, 0x12, 0x03, 0x21, 0xd4, + 0x24, 0xe0, 0x9e, 0x49, 0x06, 0x90, 0x8a, 0x56, 0x00, 0x2a, 0xb4, 0xbf, + 0x94, 0xf9, 0xc9, 0x24, 0x94, 0xf9, 0xc8, 0x24, 0x51, 0x1c, 0x19, 0xd0, + 0x90, 0xb2, 0x17, 0xe0, 0x1a, 0x9a, 0x02, 0xf0, 0x7f, 0x02, 0x20, 0x2a, + 0x04, 0xbf, 0x4f, 0xf0, 0x00, 0x62, 0x1a, 0x92, 0x1b, 0x9a, 0x02, 0xf0, + 0x7f, 0x02, 0x20, 0x2a, 0x08, 0xd1, 0x4f, 0xf0, 0x00, 0x62, 0x1b, 0x92, + 0x04, 0xe0, 0x06, 0x90, 0x05, 0x20, 0x03, 0xe0, 0x04, 0x20, 0x01, 0xe0, + 0x02, 0x20, 0x06, 0x90, 0xdd, 0xf8, 0x6c, 0xe0, 0x1a, 0x9a, 0x00, 0x02, + 0x22, 0xf4, 0xe0, 0x62, 0x1e, 0xf0, 0x00, 0x6f, 0x40, 0xea, 0x02, 0x02, + 0x08, 0xbf, 0x06, 0x98, 0x2e, 0xf4, 0xe0, 0x61, 0x14, 0xbf, 0x01, 0x43, + 0x41, 0xea, 0x00, 0x21, 0x12, 0xf0, 0x00, 0x6f, 0x1b, 0x91, 0x1a, 0x92, + 0x94, 0xf8, 0xdc, 0x11, 0x04, 0xd0, 0x01, 0x29, 0x02, 0xd1, 0x42, 0xf4, + 0x00, 0x02, 0x02, 0xe0, 0x11, 0xb9, 0x22, 0xf4, 0x00, 0x02, 0x1a, 0x92, + 0x1b, 0x9a, 0x94, 0xf8, 0xdc, 0x11, 0x12, 0xf0, 0x00, 0x6f, 0x04, 0xd0, + 0x01, 0x29, 0x02, 0xd1, 0x42, 0xf4, 0x00, 0x02, 0x02, 0xe0, 0x11, 0xb9, + 0x22, 0xf4, 0x00, 0x02, 0x1b, 0x92, 0x49, 0x46, 0x20, 0x46, 0x05, 0x93, + 0x11, 0xf0, 0x38, 0xdf, 0x1a, 0x9a, 0x05, 0x9b, 0x12, 0xf0, 0x00, 0x61, + 0x21, 0xd0, 0xd4, 0xf8, 0x58, 0x16, 0x91, 0xf9, 0x05, 0x10, 0x02, 0x29, + 0x0d, 0xd1, 0x02, 0xf4, 0xe0, 0x68, 0x4f, 0xea, 0x18, 0x28, 0xa8, 0xf1, + 0x04, 0x08, 0xb8, 0xf1, 0x01, 0x0f, 0x8c, 0xbf, 0x4f, 0xf0, 0x00, 0x08, + 0x4f, 0xf0, 0x01, 0x08, 0x01, 0xe0, 0x4f, 0xf0, 0x00, 0x08, 0x11, 0x02, + 0x0c, 0xd5, 0x02, 0xf0, 0x7f, 0x02, 0x07, 0x2a, 0x0a, 0xd9, 0x20, 0x2a, + 0x14, 0xbf, 0x02, 0x46, 0x04, 0x22, 0x09, 0x92, 0x06, 0xe0, 0x09, 0x91, + 0x88, 0x46, 0x03, 0xe0, 0x09, 0x90, 0x01, 0xe0, 0x04, 0x21, 0x09, 0x91, + 0x1b, 0x9a, 0x12, 0xf0, 0x00, 0x61, 0x1d, 0xd0, 0x11, 0x02, 0x18, 0xd5, + 0x02, 0xf0, 0x7f, 0x02, 0x07, 0x2a, 0x16, 0xd9, 0x20, 0x2a, 0x08, 0xbf, + 0x04, 0x20, 0x10, 0xe0, 0x1b, 0x98, 0x21, 0xf4, 0xe0, 0x61, 0x20, 0xf4, + 0xe0, 0x60, 0x40, 0xf4, 0x00, 0x70, 0x41, 0xf4, 0x00, 0x71, 0x1b, 0x90, + 0x02, 0x20, 0x1a, 0x91, 0x06, 0x90, 0x0d, 0x92, 0x09, 0x92, 0x90, 0x46, + 0x03, 0xe0, 0x0d, 0x90, 0x01, 0xe0, 0x04, 0x21, 0x0d, 0x91, 0x8b, 0xb1, + 0x0c, 0x9a, 0x1a, 0x99, 0xd2, 0xf8, 0x10, 0x33, 0x29, 0x98, 0x02, 0xeb, + 0xc3, 0x02, 0xc2, 0xf8, 0x14, 0x13, 0xc1, 0xb2, 0xc2, 0xf8, 0x18, 0x13, + 0x01, 0x33, 0x0c, 0x99, 0x03, 0xf0, 0x3f, 0x03, 0xc1, 0xf8, 0x10, 0x33, + 0x07, 0x9a, 0x00, 0x2a, 0x3f, 0xd0, 0xd4, 0xf8, 0x0c, 0xe0, 0xd2, 0xf8, + 0x04, 0x34, 0x07, 0x99, 0xde, 0xf8, 0x80, 0x21, 0x03, 0xf1, 0x40, 0x00, + 0x01, 0xeb, 0xc0, 0x00, 0xde, 0xf8, 0x84, 0xc1, 0x42, 0x60, 0x01, 0xeb, + 0xc3, 0x02, 0xc2, 0xf8, 0x08, 0xc2, 0xf2, 0x8a, 0x34, 0x49, 0x02, 0xf0, + 0x07, 0x02, 0x8a, 0x5c, 0x02, 0x2a, 0x14, 0xd1, 0x07, 0x9a, 0x41, 0x68, + 0xd2, 0xf8, 0x00, 0xe0, 0x29, 0x98, 0x02, 0xeb, 0xce, 0x02, 0xc2, 0xf8, + 0x04, 0x11, 0x1a, 0x99, 0x0e, 0xf1, 0x01, 0x0e, 0x51, 0x60, 0xc1, 0xb2, + 0x91, 0x60, 0x07, 0x99, 0xc2, 0xf8, 0x08, 0xc1, 0x0e, 0xf0, 0x1f, 0x02, + 0x0a, 0x60, 0x1a, 0x99, 0x07, 0x98, 0x03, 0xf1, 0x81, 0x02, 0x40, 0xf8, + 0x32, 0x10, 0x00, 0xeb, 0xc3, 0x02, 0x29, 0x98, 0x01, 0x33, 0xc1, 0xb2, + 0xc2, 0xf8, 0x0c, 0x14, 0x07, 0x99, 0x03, 0xf0, 0x3f, 0x03, 0xc1, 0xf8, + 0x04, 0x34, 0x1a, 0x9b, 0x13, 0xf0, 0x00, 0x6e, 0x1f, 0xd0, 0x03, 0xf4, + 0xe0, 0x60, 0x4f, 0xea, 0x10, 0x20, 0x13, 0xf4, 0x00, 0x0f, 0x1a, 0x4a, + 0x03, 0xf0, 0x7f, 0x01, 0xa0, 0xf1, 0x04, 0x00, 0x08, 0xd0, 0x01, 0x28, + 0x4f, 0xf0, 0x14, 0x00, 0x00, 0xfb, 0x01, 0x22, 0x94, 0xbf, 0xd2, 0x68, + 0x92, 0x68, 0x0c, 0xe0, 0x01, 0x28, 0x4f, 0xf0, 0x14, 0x00, 0x03, 0xd8, + 0x00, 0xfb, 0x01, 0x22, 0x52, 0x68, 0x04, 0xe0, 0x41, 0x43, 0x52, 0x58, + 0x01, 0xe0, 0x03, 0xf0, 0x7f, 0x02, 0x0f, 0x98, 0x11, 0x92, 0x02, 0x28, + 0x00, 0xd0, 0xa8, 0xb9, 0xb4, 0xf8, 0x38, 0x26, 0x0a, 0x99, 0x91, 0x42, + 0x03, 0xdc, 0x72, 0x6a, 0x12, 0xf0, 0x80, 0x62, 0x0d, 0xd0, 0x9b, 0xf8, + 0x04, 0x20, 0x02, 0xf0, 0x01, 0x02, 0x82, 0xf0, 0x01, 0x02, 0x06, 0xe0, + 0x40, 0x1b, 0x86, 0x00, 0xc4, 0xd2, 0x85, 0x00, 0x84, 0x18, 0x86, 0x00, + 0x00, 0x22, 0x10, 0x92, 0x22, 0x6b, 0x52, 0x7d, 0x62, 0xb1, 0xd4, 0xf8, + 0x58, 0x16, 0x09, 0x78, 0x41, 0xb1, 0xbe, 0xf1, 0x00, 0x0f, 0x05, 0xd1, + 0x94, 0x48, 0x03, 0xf0, 0x7f, 0x01, 0x41, 0x56, 0x00, 0x29, 0x0c, 0xdb, + 0x21, 0x68, 0x91, 0xf8, 0x46, 0x10, 0x89, 0x07, 0x2e, 0xd0, 0xbe, 0xf1, + 0x00, 0x0f, 0x2b, 0xd0, 0xd4, 0xf8, 0x58, 0x16, 0x91, 0xf9, 0x05, 0x10, + 0x31, 0xb3, 0x29, 0x98, 0x01, 0x28, 0x12, 0xd9, 0xd4, 0xf8, 0x58, 0x36, + 0x1b, 0x78, 0x0b, 0xb1, 0x16, 0x23, 0x00, 0xe0, 0x30, 0x23, 0x1b, 0x93, + 0x73, 0x6a, 0x06, 0x99, 0x23, 0xf0, 0x00, 0x63, 0x73, 0x62, 0x1b, 0x9b, + 0x43, 0xea, 0x01, 0x23, 0x1b, 0x93, 0x1a, 0x93, 0x10, 0xe0, 0x7a, 0xb1, + 0xd4, 0xf8, 0x58, 0x26, 0x12, 0x78, 0x5a, 0xb1, 0xbe, 0xf1, 0x00, 0x0f, + 0x08, 0xd1, 0x7c, 0x4a, 0x03, 0xf0, 0x7f, 0x03, 0xd3, 0x56, 0x38, 0xea, + 0x23, 0x08, 0x28, 0xbf, 0x4f, 0xf0, 0x01, 0x08, 0x1a, 0x99, 0x11, 0xf0, + 0x00, 0x63, 0x15, 0xd1, 0x01, 0xf0, 0x7f, 0x02, 0x16, 0x2a, 0x11, 0xd8, + 0x74, 0x48, 0x90, 0x40, 0x0e, 0xd5, 0x13, 0x98, 0x40, 0xb1, 0x02, 0x2a, + 0x09, 0xd0, 0x94, 0xf9, 0x5c, 0x26, 0x12, 0xf1, 0xff, 0x32, 0x18, 0xbf, + 0x01, 0x22, 0x00, 0xe0, 0x13, 0x9a, 0x09, 0x92, 0x00, 0xe0, 0x09, 0x93, + 0x1b, 0x9a, 0x12, 0xf0, 0x00, 0x6e, 0x16, 0xd1, 0x02, 0xf0, 0x7f, 0x02, + 0x16, 0x2a, 0x12, 0xd8, 0x67, 0x48, 0x90, 0x40, 0x0f, 0xd5, 0x13, 0x98, + 0x40, 0xb1, 0x02, 0x2a, 0x09, 0xd0, 0x94, 0xf9, 0x5c, 0x26, 0x12, 0xf1, + 0xff, 0x32, 0x18, 0xbf, 0x01, 0x22, 0x00, 0xe0, 0x13, 0x9a, 0x0d, 0x92, + 0x01, 0xe0, 0xcd, 0xf8, 0x34, 0xe0, 0x0f, 0x98, 0xd9, 0xf8, 0x04, 0x20, + 0x02, 0x28, 0x08, 0xbf, 0xc9, 0xf8, 0x60, 0x11, 0x12, 0xf4, 0x80, 0x32, + 0x31, 0xd0, 0x94, 0xf8, 0xce, 0x21, 0x72, 0xb3, 0x94, 0xf8, 0xd1, 0x21, + 0x5a, 0xb3, 0xd4, 0xf8, 0x58, 0x26, 0x92, 0xf9, 0x05, 0x20, 0x03, 0x2a, + 0x27, 0xd0, 0x4b, 0xb9, 0x01, 0xf0, 0x7f, 0x02, 0x02, 0x2a, 0x27, 0xd0, + 0x04, 0x2a, 0x25, 0xd0, 0x0b, 0x2a, 0x23, 0xd0, 0x16, 0x2a, 0x21, 0xd0, + 0x9b, 0xf8, 0x04, 0x30, 0x13, 0xf0, 0x01, 0x03, 0x19, 0xd1, 0x0e, 0x98, + 0x00, 0xf0, 0xfc, 0x02, 0x88, 0x2a, 0x17, 0xd1, 0x73, 0x6a, 0x4a, 0xf4, + 0xa0, 0x4a, 0x43, 0xf4, 0x80, 0x53, 0x73, 0x62, 0xbb, 0xf8, 0x18, 0x30, + 0x01, 0x22, 0x23, 0xf0, 0x60, 0x03, 0x1b, 0x04, 0x1b, 0x0c, 0x43, 0xf0, + 0x20, 0x03, 0xab, 0xf8, 0x18, 0x30, 0x07, 0x92, 0x05, 0xe0, 0x00, 0x23, + 0x02, 0xe0, 0x00, 0x20, 0x07, 0x90, 0x00, 0xe0, 0x07, 0x93, 0x20, 0x46, + 0x0a, 0x9a, 0x15, 0x9b, 0x19, 0xf0, 0x28, 0xda, 0x16, 0xab, 0x20, 0x46, + 0x1b, 0x99, 0x0a, 0x9a, 0x19, 0xf0, 0x22, 0xda, 0x06, 0x22, 0xa5, 0xf1, + 0x40, 0x00, 0x16, 0xa9, 0xfd, 0xf3, 0xac, 0xf6, 0x1b, 0x9b, 0x18, 0x01, + 0x0c, 0xd4, 0x03, 0xf0, 0x7f, 0x03, 0x16, 0x2b, 0x08, 0xd8, 0x30, 0x4a, + 0x9a, 0x40, 0x05, 0xd5, 0x0a, 0x99, 0x0b, 0x0a, 0x05, 0xf8, 0x3c, 0x1c, + 0x05, 0xf8, 0x3b, 0x3c, 0x73, 0x6a, 0x59, 0x05, 0x10, 0xd5, 0x1a, 0x9a, + 0x12, 0x01, 0x0d, 0xd5, 0x17, 0xb1, 0x3a, 0x7a, 0x04, 0x2a, 0x09, 0xd1, + 0x43, 0xf4, 0x00, 0x63, 0x73, 0x62, 0x10, 0x9a, 0x94, 0xf8, 0xc3, 0x34, + 0x00, 0x2b, 0x18, 0xbf, 0x01, 0x22, 0x10, 0x92, 0x1a, 0x99, 0x0b, 0x01, + 0x0a, 0xd4, 0x1f, 0x4a, 0x01, 0xf0, 0x7f, 0x03, 0xd3, 0x56, 0x00, 0x2b, + 0x04, 0xda, 0x15, 0xf8, 0x06, 0x3c, 0x03, 0xf0, 0x0f, 0x03, 0x01, 0xe0, + 0x15, 0xf8, 0x06, 0x3c, 0x0e, 0x98, 0x0b, 0x93, 0xa4, 0x28, 0x0d, 0xd0, + 0x9b, 0xf8, 0x04, 0x30, 0xd8, 0x07, 0x09, 0xd4, 0x07, 0x9a, 0x4a, 0xb9, + 0x09, 0x9a, 0x2b, 0x9b, 0x20, 0x46, 0x0f, 0xf0, 0x7b, 0xdc, 0xab, 0xf8, + 0x02, 0x00, 0x13, 0xe0, 0x07, 0x9b, 0x4b, 0xb1, 0x09, 0x9a, 0x20, 0x46, + 0x40, 0xf6, 0x2a, 0x13, 0x18, 0xf0, 0x64, 0xdf, 0x80, 0xb2, 0x02, 0x30, + 0xab, 0xf8, 0x02, 0x00, 0x0e, 0x98, 0xa4, 0x28, 0x04, 0xd1, 0xbb, 0xf8, + 0x02, 0x30, 0x25, 0xf8, 0x3a, 0x3c, 0x17, 0xe0, 0x9b, 0xf8, 0x04, 0x30, + 0xd9, 0x07, 0x01, 0xd4, 0x07, 0x99, 0x49, 0xb1, 0x00, 0x23, 0x05, 0xf8, + 0x3a, 0x3c, 0x05, 0xf8, 0x39, 0x3c, 0x0b, 0xe0, 0x40, 0x1b, 0x86, 0x00, + 0x00, 0x02, 0x10, 0x28, 0x1b, 0x99, 0x0d, 0x9a, 0x2b, 0x9b, 0x20, 0x46, + 0x0f, 0xf0, 0x4e, 0xdc, 0x25, 0xf8, 0x3a, 0x0c, 0x73, 0x6a, 0x9a, 0x05, + 0x07, 0xd5, 0x32, 0x6b, 0x4a, 0xf4, 0x00, 0x5a, 0x25, 0xf8, 0x34, 0x2c, + 0x12, 0x0c, 0x25, 0xf8, 0x32, 0x2c, 0x28, 0x9a, 0x0a, 0xb9, 0x4a, 0xf0, + 0x08, 0x0a, 0x9b, 0xf8, 0x04, 0x20, 0xd0, 0x07, 0x0f, 0xd4, 0xd9, 0x04, + 0x0d, 0xd4, 0x94, 0xf8, 0xd0, 0x21, 0x0a, 0xb1, 0x5a, 0x06, 0x08, 0xd4, + 0x58, 0x05, 0x04, 0xd4, 0x14, 0x98, 0x10, 0xb1, 0x94, 0xf8, 0xf8, 0x21, + 0x0a, 0xb9, 0x4a, 0xf0, 0x01, 0x0a, 0x0f, 0x99, 0x02, 0x29, 0x11, 0xd1, + 0x94, 0xf8, 0xce, 0x21, 0x72, 0xb1, 0x11, 0x9a, 0x04, 0x2a, 0x0b, 0xd9, + 0xa4, 0x4a, 0x2a, 0x98, 0x12, 0x5c, 0x04, 0xeb, 0x42, 0x02, 0xb2, 0xf8, + 0xfe, 0x21, 0x0a, 0xb1, 0x59, 0x05, 0x01, 0xd5, 0x4a, 0xf4, 0x80, 0x5a, + 0x23, 0x6b, 0x18, 0x69, 0x0d, 0xf0, 0xa2, 0xf8, 0x08, 0x99, 0x00, 0xf4, + 0x40, 0x60, 0xb0, 0xf5, 0x40, 0x6f, 0x08, 0xbf, 0x4a, 0xf4, 0x80, 0x7a, + 0x09, 0xb1, 0x4a, 0xf4, 0x00, 0x4a, 0x25, 0xf8, 0x76, 0xac, 0xef, 0xb1, + 0x94, 0xf8, 0xa0, 0x34, 0x03, 0xbb, 0x0c, 0x98, 0x82, 0x6d, 0x12, 0xf0, + 0x08, 0x02, 0x17, 0xd1, 0x3b, 0x7a, 0x0b, 0x2b, 0x08, 0xd1, 0x94, 0xf8, + 0xf0, 0x37, 0x8b, 0xb1, 0x94, 0xf8, 0xf1, 0x37, 0x73, 0xb1, 0xbb, 0x79, + 0x07, 0x2b, 0x0d, 0xd8, 0xbb, 0x79, 0x29, 0x2b, 0x0c, 0xd8, 0x97, 0xf8, + 0x0c, 0xa0, 0x0a, 0xf0, 0x07, 0x0a, 0x4a, 0xea, 0x03, 0x1a, 0x07, 0xe0, + 0xba, 0x46, 0x05, 0xe0, 0x9a, 0x46, 0x03, 0xe0, 0x92, 0x46, 0x01, 0xe0, + 0x4f, 0xf0, 0x00, 0x0a, 0x73, 0x6a, 0x0d, 0x99, 0x9a, 0x00, 0x44, 0xbf, + 0x4a, 0xf0, 0x08, 0x0a, 0x1f, 0xfa, 0x8a, 0xfa, 0x4b, 0x1e, 0xdb, 0xb2, + 0x01, 0x2b, 0x9c, 0xbf, 0x4a, 0xf4, 0x00, 0x5a, 0x1f, 0xfa, 0x8a, 0xfa, + 0xa5, 0xf1, 0x72, 0x00, 0x59, 0x46, 0x02, 0x22, 0xfd, 0xf3, 0xb4, 0xf5, + 0x00, 0x23, 0x05, 0xf8, 0x70, 0x3c, 0x05, 0xf8, 0x6f, 0x3c, 0x05, 0xf8, + 0x4a, 0x3c, 0x05, 0xf8, 0x49, 0x3c, 0x00, 0x2f, 0x43, 0xd0, 0x94, 0xf8, + 0xa0, 0x34, 0x00, 0x2b, 0x3f, 0xd1, 0x0c, 0x9a, 0x93, 0x6d, 0x1b, 0x07, + 0x3b, 0xd4, 0x3b, 0x7a, 0x0b, 0x2b, 0x0a, 0xd1, 0x94, 0xf8, 0xf0, 0x27, + 0x00, 0x2a, 0x34, 0xd0, 0x94, 0xf8, 0xf1, 0x27, 0x00, 0x2a, 0x30, 0xd0, + 0xba, 0x79, 0x07, 0x2a, 0x2d, 0xd8, 0xba, 0x79, 0x29, 0x2a, 0x2a, 0xd8, + 0x0e, 0x98, 0x00, 0xf4, 0x40, 0x72, 0xb2, 0xf5, 0x40, 0x7f, 0x14, 0x9a, + 0x14, 0xbf, 0x0b, 0xf1, 0x18, 0x01, 0x0b, 0xf1, 0x1e, 0x01, 0x02, 0xb1, + 0x02, 0x31, 0x02, 0x2b, 0x10, 0xd1, 0x12, 0x9b, 0x00, 0x20, 0x3a, 0x18, + 0xb2, 0xf8, 0xbc, 0x20, 0x02, 0x30, 0x9a, 0x75, 0xc2, 0xf3, 0x07, 0x22, + 0xda, 0x75, 0x02, 0x33, 0x0a, 0x28, 0xf4, 0xd1, 0xa5, 0xf1, 0x56, 0x00, + 0x03, 0x22, 0x08, 0xe0, 0x0b, 0x2b, 0xa5, 0xf1, 0x60, 0x00, 0x02, 0xd1, + 0x02, 0x31, 0x10, 0x22, 0x01, 0xe0, 0x97, 0xf9, 0x0e, 0x20, 0xfd, 0xf3, + 0x65, 0xf5, 0x0b, 0xf1, 0x04, 0x03, 0x19, 0x46, 0xa5, 0xf1, 0x50, 0x00, + 0x06, 0x22, 0x0f, 0x93, 0xfd, 0xf3, 0x5c, 0xf5, 0xbd, 0xf8, 0x72, 0x30, + 0x25, 0xf8, 0x2a, 0x3c, 0x00, 0x23, 0x05, 0xf8, 0x28, 0x3c, 0x05, 0xf8, + 0x27, 0x3c, 0x05, 0xf8, 0x26, 0x3c, 0x05, 0xf8, 0x25, 0x3c, 0x05, 0xf8, + 0x24, 0x3c, 0x05, 0xf8, 0x23, 0x3c, 0x05, 0xf8, 0x22, 0x3c, 0x05, 0xf8, + 0x21, 0x3c, 0x05, 0xf8, 0x20, 0x3c, 0x05, 0xf8, 0x1f, 0x3c, 0x10, 0x98, + 0x18, 0xb9, 0xb8, 0xf1, 0x00, 0x0f, 0x01, 0xd1, 0x0b, 0xe1, 0x98, 0x46, + 0x00, 0x22, 0x06, 0x9b, 0x1a, 0x99, 0x20, 0x46, 0x22, 0xf0, 0x96, 0xdc, + 0x1b, 0x99, 0x08, 0x90, 0x00, 0x22, 0x06, 0x9b, 0x20, 0x46, 0x22, 0xf0, + 0x8f, 0xdc, 0x08, 0x99, 0x06, 0x90, 0x11, 0xf0, 0x00, 0x61, 0x11, 0x91, + 0x07, 0xd1, 0x08, 0x9a, 0x02, 0xf0, 0x7f, 0x03, 0x31, 0x4a, 0xd2, 0x56, + 0x00, 0x2a, 0x21, 0xda, 0x2d, 0xe0, 0x08, 0x98, 0x08, 0x9b, 0x00, 0xf4, + 0xe0, 0x61, 0x13, 0xf4, 0x00, 0x0f, 0x4f, 0xea, 0x11, 0x21, 0x2c, 0x4b, + 0x00, 0xf0, 0x7f, 0x02, 0xa1, 0xf1, 0x04, 0x01, 0x08, 0xd0, 0x01, 0x29, + 0x4f, 0xf0, 0x14, 0x01, 0x01, 0xfb, 0x02, 0x33, 0x94, 0xbf, 0xdb, 0x68, + 0x9b, 0x68, 0x09, 0xe0, 0x01, 0x29, 0x4f, 0xf0, 0x14, 0x01, 0x03, 0xd8, + 0x01, 0xfb, 0x02, 0x33, 0x5b, 0x68, 0x01, 0xe0, 0x4a, 0x43, 0x9b, 0x58, + 0x02, 0x3b, 0x18, 0xbf, 0x01, 0x23, 0x53, 0xb1, 0x94, 0xf9, 0x5c, 0x36, + 0x01, 0x2b, 0x08, 0xd0, 0x4a, 0xf4, 0x80, 0x4a, 0x1f, 0xfa, 0x8a, 0xfa, + 0x01, 0x21, 0x0c, 0x91, 0x03, 0xe0, 0x0c, 0x93, 0x01, 0xe0, 0x00, 0x22, + 0x0c, 0x92, 0x06, 0x9b, 0x13, 0xf0, 0x00, 0x62, 0x06, 0xd1, 0x13, 0x49, + 0x03, 0xf0, 0x7f, 0x03, 0xc9, 0x56, 0x00, 0x29, 0x26, 0xda, 0x39, 0xe0, + 0x06, 0x98, 0x10, 0x4b, 0x00, 0xf4, 0xe0, 0x61, 0x4f, 0xea, 0x11, 0x21, + 0x10, 0xf4, 0x00, 0x0f, 0x00, 0xf0, 0x7f, 0x02, 0xa1, 0xf1, 0x04, 0x01, + 0x08, 0xd0, 0x01, 0x29, 0x4f, 0xf0, 0x14, 0x01, 0x01, 0xfb, 0x02, 0x33, + 0x94, 0xbf, 0xdb, 0x68, 0x9b, 0x68, 0x0f, 0xe0, 0x01, 0x29, 0x4f, 0xf0, + 0x14, 0x01, 0x09, 0xd8, 0x01, 0xfb, 0x02, 0x33, 0x5b, 0x68, 0x07, 0xe0, + 0x98, 0xe0, 0x85, 0x00, 0x40, 0x1b, 0x86, 0x00, 0x84, 0x18, 0x86, 0x00, + 0x4a, 0x43, 0x9b, 0x58, 0x02, 0x3b, 0x18, 0xbf, 0x01, 0x23, 0x63, 0xb1, + 0x94, 0xf9, 0x5c, 0x36, 0x01, 0x2b, 0x0a, 0xd0, 0x6f, 0xea, 0x4a, 0x4a, + 0x6f, 0xea, 0x5a, 0x4a, 0x01, 0x21, 0x1f, 0xfa, 0x8a, 0xfa, 0x0e, 0x91, + 0x03, 0xe0, 0x0e, 0x93, 0x01, 0xe0, 0x00, 0x22, 0x0e, 0x92, 0x35, 0xf8, + 0x76, 0x3c, 0xb8, 0xf1, 0x00, 0x0f, 0x02, 0xd0, 0x43, 0xf4, 0x00, 0x63, + 0x01, 0xe0, 0x43, 0xf0, 0x06, 0x03, 0x25, 0xf8, 0x76, 0x3c, 0xb8, 0xf1, + 0x00, 0x0f, 0x0c, 0xbf, 0x14, 0x27, 0x0e, 0x27, 0x3a, 0x46, 0x20, 0x46, + 0x08, 0x99, 0xa5, 0xf1, 0x1e, 0x03, 0x18, 0xf0, 0xff, 0xdf, 0x3a, 0x46, + 0x18, 0xab, 0x20, 0x46, 0x06, 0x99, 0x18, 0xf0, 0xf9, 0xdf, 0x18, 0xa9, + 0x06, 0x22, 0xa5, 0xf1, 0x48, 0x00, 0xfd, 0xf3, 0x83, 0xf4, 0x0c, 0x9b, + 0x09, 0x98, 0x0a, 0x99, 0x00, 0x22, 0x00, 0x93, 0x01, 0x90, 0x1a, 0x9b, + 0x02, 0x91, 0x03, 0x92, 0x41, 0x46, 0x08, 0x9a, 0x20, 0x46, 0x19, 0xf0, + 0x05, 0xd8, 0x25, 0xf8, 0x16, 0x0c, 0x0e, 0x9b, 0x0d, 0x98, 0x0a, 0x99, + 0x00, 0x22, 0x00, 0x93, 0x01, 0x90, 0x02, 0x91, 0x03, 0x92, 0x1b, 0x9b, + 0x06, 0x9a, 0x20, 0x46, 0x41, 0x46, 0x18, 0xf0, 0xf5, 0xdf, 0xa5, 0xf1, + 0x18, 0x07, 0x25, 0xf8, 0x42, 0x0c, 0xa5, 0xf1, 0x14, 0x00, 0xb8, 0xf1, + 0x00, 0x0f, 0x0a, 0xd0, 0x6f, 0xf0, 0x3b, 0x03, 0x05, 0xf8, 0x18, 0x3c, + 0x00, 0x23, 0x05, 0xf8, 0x17, 0x3c, 0x0b, 0xf1, 0x0a, 0x01, 0x06, 0x22, + 0x07, 0xe0, 0x6f, 0xf0, 0x4b, 0x03, 0x05, 0xf8, 0x18, 0x3c, 0x05, 0xf8, + 0x17, 0x8c, 0x0f, 0x99, 0x0c, 0x22, 0xfd, 0xf3, 0x47, 0xf4, 0x0b, 0x98, + 0x11, 0x9a, 0x81, 0xb2, 0x5a, 0xb9, 0x08, 0x98, 0xa0, 0x4a, 0x00, 0xf0, + 0x7f, 0x03, 0xd3, 0x56, 0x00, 0x2b, 0x04, 0xda, 0x15, 0xf8, 0x1e, 0x3c, + 0x03, 0xf0, 0x0f, 0x03, 0x01, 0xe0, 0x15, 0xf8, 0x1e, 0x3c, 0x1b, 0x02, + 0x19, 0x43, 0x0b, 0x91, 0x1e, 0xe0, 0x41, 0x46, 0x06, 0x22, 0xa5, 0xf1, + 0x1e, 0x00, 0xfd, 0xf3, 0x8f, 0xf4, 0x41, 0x46, 0x10, 0x22, 0xa5, 0xf1, + 0x18, 0x00, 0xfd, 0xf3, 0x89, 0xf4, 0xa5, 0xf1, 0x48, 0x00, 0x41, 0x46, + 0x06, 0x22, 0xfd, 0xf3, 0x83, 0xf4, 0x47, 0x46, 0x05, 0xf8, 0x42, 0x8c, + 0x05, 0xf8, 0x41, 0x8c, 0xcd, 0xf8, 0x18, 0x80, 0xcd, 0xf8, 0x20, 0x80, + 0xcd, 0xf8, 0x38, 0x80, 0xcd, 0xf8, 0x30, 0x80, 0x73, 0x6a, 0x58, 0x05, + 0x0a, 0xd5, 0x1a, 0x9a, 0x11, 0x01, 0x07, 0xd5, 0xd4, 0xf8, 0x40, 0x01, + 0x49, 0x46, 0x0a, 0x9b, 0x2a, 0xf0, 0x0a, 0xde, 0x05, 0xf8, 0x43, 0x0c, + 0x25, 0xf8, 0x74, 0xac, 0x0b, 0x99, 0x25, 0xf8, 0x64, 0x1c, 0x1b, 0x9b, + 0x13, 0xf0, 0x00, 0x61, 0x02, 0xd0, 0x94, 0xf8, 0xc0, 0x14, 0x07, 0xe0, + 0x03, 0xf0, 0x7f, 0x03, 0x16, 0x2b, 0x02, 0xd8, 0x7a, 0x4a, 0x9a, 0x40, + 0x00, 0xd4, 0x01, 0x21, 0x08, 0x9a, 0x89, 0xb2, 0x12, 0xf0, 0x00, 0x6a, + 0x04, 0xd0, 0x94, 0xf8, 0xc0, 0xa4, 0x4f, 0xea, 0x8a, 0x0a, 0x0d, 0xe0, + 0x08, 0x98, 0x00, 0xf0, 0x7f, 0x03, 0x16, 0x2b, 0x02, 0xd8, 0x71, 0x4a, + 0x9a, 0x40, 0x01, 0xd4, 0x4f, 0xf0, 0x01, 0x0a, 0x4f, 0xea, 0x8a, 0x0a, + 0x1f, 0xfa, 0x8a, 0xfa, 0x06, 0x9a, 0x4a, 0xea, 0x01, 0x01, 0x12, 0xf0, + 0x00, 0x6a, 0x04, 0xd0, 0x94, 0xf8, 0xc0, 0xa4, 0x4f, 0xea, 0x0a, 0x1a, + 0x0d, 0xe0, 0x06, 0x98, 0x00, 0xf0, 0x7f, 0x03, 0x16, 0x2b, 0x02, 0xd8, + 0x64, 0x4a, 0x9a, 0x40, 0x01, 0xd4, 0x4f, 0xf0, 0x01, 0x0a, 0x4f, 0xea, + 0x0a, 0x1a, 0x1f, 0xfa, 0x8a, 0xfa, 0x23, 0x6b, 0x41, 0xea, 0x0a, 0x0a, + 0x18, 0x69, 0x0c, 0xf0, 0x5d, 0xfe, 0xc0, 0xb2, 0x4a, 0xea, 0x00, 0x2a, + 0x25, 0xf8, 0x62, 0xac, 0xdd, 0xf8, 0x68, 0xb0, 0x1b, 0xf0, 0x00, 0x6a, + 0x02, 0xd0, 0x94, 0xf8, 0xc0, 0xa4, 0x0a, 0xe0, 0x0b, 0xf0, 0x7f, 0x03, + 0x16, 0x2b, 0x02, 0xd8, 0x54, 0x4a, 0x9a, 0x40, 0x01, 0xd4, 0x4f, 0xf0, + 0x01, 0x0a, 0x1f, 0xfa, 0x8a, 0xfa, 0x09, 0x99, 0x4b, 0x1e, 0xdb, 0xb2, + 0x01, 0x2b, 0x07, 0xd8, 0x23, 0x68, 0x4a, 0xf0, 0x10, 0x0a, 0xd3, 0xf8, + 0x8c, 0x30, 0x9a, 0x69, 0x01, 0x32, 0x9a, 0x61, 0x59, 0x46, 0x20, 0x46, + 0x15, 0xf0, 0x92, 0xd9, 0x40, 0xea, 0x0a, 0x00, 0x25, 0xf8, 0x6e, 0x0c, + 0x59, 0x46, 0x20, 0x46, 0x1f, 0xf0, 0xbe, 0xdc, 0x25, 0xf8, 0x6c, 0x0c, + 0x1b, 0x99, 0x20, 0x46, 0x1f, 0xf0, 0xb8, 0xdc, 0x25, 0xf8, 0x6a, 0x0c, + 0x10, 0x9a, 0x12, 0xb9, 0xb8, 0xf1, 0x00, 0x0f, 0x0b, 0xd0, 0x08, 0x99, + 0x20, 0x46, 0x1f, 0xf0, 0xad, 0xdc, 0x25, 0xf8, 0x68, 0x0c, 0x06, 0x99, + 0x20, 0x46, 0x1f, 0xf0, 0xa7, 0xdc, 0x25, 0xf8, 0x66, 0x0c, 0x1a, 0x99, + 0x0b, 0x01, 0x08, 0xd5, 0x09, 0x9b, 0x04, 0x2b, 0x05, 0xd1, 0x0a, 0x9a, + 0x20, 0x46, 0x18, 0xf0, 0x1d, 0xdd, 0x25, 0xf8, 0x38, 0x0c, 0x1b, 0x99, + 0x08, 0x01, 0x08, 0xd5, 0x0d, 0x98, 0x04, 0x28, 0x05, 0xd1, 0x0a, 0x9a, + 0x20, 0x46, 0x18, 0xf0, 0x11, 0xdd, 0x25, 0xf8, 0x36, 0x0c, 0xd9, 0xf8, + 0x04, 0x30, 0x5a, 0x06, 0x40, 0xf1, 0xb9, 0x80, 0x14, 0x99, 0x00, 0x29, + 0x00, 0xf0, 0xb5, 0x80, 0x28, 0x4b, 0x2a, 0x9a, 0x9b, 0x5c, 0x0f, 0x93, + 0x04, 0xeb, 0x43, 0x03, 0xb3, 0xf8, 0xfe, 0xb1, 0xbb, 0xf1, 0x00, 0x0f, + 0x00, 0xf0, 0xa9, 0x80, 0x73, 0x6a, 0x10, 0x93, 0x5b, 0x05, 0x7e, 0xd4, + 0x28, 0x98, 0x00, 0x28, 0x7b, 0xd1, 0x1a, 0x99, 0x20, 0x46, 0x09, 0x9a, + 0x0a, 0x9b, 0x0b, 0x91, 0x18, 0xf0, 0x3a, 0xdc, 0x82, 0x46, 0x97, 0xb1, + 0x08, 0x99, 0x0c, 0x9a, 0x20, 0x46, 0x0e, 0xf0, 0x01, 0xdf, 0x06, 0x99, + 0x03, 0x46, 0x0e, 0x9a, 0x20, 0x46, 0x05, 0x93, 0x0e, 0xf0, 0xfa, 0xde, + 0xb7, 0xf8, 0x02, 0x80, 0x05, 0x9b, 0x35, 0xf8, 0x42, 0x7c, 0x98, 0x44, + 0x1c, 0xe0, 0x07, 0x9a, 0x12, 0xbb, 0x0b, 0x99, 0x09, 0x9a, 0x07, 0x9b, + 0x20, 0x46, 0x0f, 0xf0, 0x29, 0xd9, 0xdd, 0xf8, 0x6c, 0xc0, 0x0d, 0x9a, + 0x61, 0x46, 0x0a, 0x9b, 0x00, 0xeb, 0x0a, 0x08, 0x20, 0x46, 0xcd, 0xf8, + 0x14, 0xc0, 0x18, 0xf0, 0x11, 0xdc, 0xdd, 0xf8, 0x14, 0xc0, 0x07, 0x46, + 0x61, 0x46, 0x20, 0x46, 0x0d, 0x9a, 0x07, 0x9b, 0x0f, 0xf0, 0x14, 0xd9, + 0xc7, 0x19, 0x06, 0xe0, 0x40, 0x1b, 0x86, 0x00, 0x00, 0x02, 0x10, 0x28, + 0x98, 0xe0, 0x85, 0x00, 0x80, 0x46, 0xca, 0xeb, 0x08, 0x03, 0x9b, 0x45, + 0x25, 0xf8, 0x70, 0x8c, 0x25, 0xf8, 0x4a, 0x7c, 0x24, 0xd3, 0x10, 0x9b, + 0x58, 0x06, 0x02, 0xd5, 0x2a, 0x98, 0x01, 0x28, 0x1e, 0xd0, 0xda, 0x44, + 0x20, 0x46, 0x0b, 0x99, 0x09, 0x9a, 0xc8, 0xeb, 0x0a, 0x03, 0x0e, 0xf0, + 0xbf, 0xde, 0xff, 0x28, 0x05, 0xd9, 0xb4, 0xf8, 0x2a, 0x36, 0x98, 0x42, + 0x28, 0xbf, 0x18, 0x46, 0x01, 0xe0, 0x4f, 0xf4, 0x80, 0x70, 0x2a, 0x99, + 0x80, 0xb2, 0x01, 0xf5, 0x45, 0x73, 0x04, 0xeb, 0x43, 0x03, 0x9a, 0x88, + 0x82, 0x42, 0x03, 0xd0, 0x98, 0x80, 0x20, 0x46, 0x25, 0xf0, 0x56, 0xdf, + 0x23, 0x68, 0x93, 0xf8, 0x44, 0x30, 0x00, 0x2b, 0x2d, 0xd0, 0x2a, 0x9a, + 0x03, 0x2a, 0x2a, 0xd8, 0xd4, 0xf8, 0x64, 0x01, 0x0f, 0x99, 0x42, 0x46, + 0x22, 0xe0, 0x23, 0x68, 0x93, 0xf8, 0x44, 0x30, 0x0b, 0xb3, 0x2a, 0x9b, + 0x03, 0x2b, 0x1e, 0xd8, 0x3f, 0xb1, 0x0c, 0x9a, 0x20, 0x46, 0x08, 0x99, + 0x0e, 0xf0, 0x86, 0xde, 0x7a, 0x88, 0x82, 0x18, 0x0f, 0xe0, 0xdd, 0xf8, + 0x68, 0x80, 0x09, 0x9a, 0x41, 0x46, 0x0a, 0x9b, 0x20, 0x46, 0x18, 0xf0, + 0xad, 0xdb, 0x09, 0x9a, 0x05, 0x46, 0x41, 0x46, 0x20, 0x46, 0x3b, 0x46, + 0x0f, 0xf0, 0xb2, 0xd8, 0x42, 0x19, 0xd4, 0xf8, 0x64, 0x01, 0x0f, 0x99, + 0x4b, 0x46, 0x3d, 0xf0, 0xbf, 0xdb, 0x73, 0x6a, 0xbd, 0xf8, 0x72, 0x00, + 0x43, 0xf0, 0x84, 0x03, 0x73, 0x62, 0x1f, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, + 0x38, 0xb5, 0xd1, 0xf8, 0xd8, 0x32, 0x04, 0x46, 0x1d, 0x8c, 0x05, 0xbb, + 0x8b, 0x6d, 0x40, 0xf2, 0x37, 0x15, 0x1d, 0x40, 0x03, 0x6b, 0x00, 0x2d, + 0x14, 0xbf, 0x11, 0x25, 0x01, 0x25, 0x19, 0x68, 0x02, 0x29, 0x07, 0xd1, + 0x90, 0xf8, 0x5c, 0x16, 0x01, 0x31, 0xc9, 0xb2, 0x01, 0x29, 0x98, 0xbf, + 0x45, 0xf0, 0x20, 0x05, 0x5b, 0x7d, 0x53, 0xb1, 0x90, 0x6b, 0x02, 0xf1, + 0x3c, 0x01, 0x21, 0xf0, 0xdd, 0xda, 0x20, 0xb1, 0x94, 0xf9, 0x47, 0x36, + 0x0b, 0xb1, 0x45, 0xf4, 0x80, 0x65, 0x28, 0x46, 0x38, 0xbd, 0x4b, 0x78, + 0x30, 0xb5, 0x01, 0x2b, 0x35, 0xdd, 0xc8, 0x78, 0x8a, 0x78, 0x42, 0xea, + 0x00, 0x22, 0x01, 0x2a, 0x2f, 0xd1, 0x07, 0x2b, 0x30, 0xdd, 0x0a, 0x7a, + 0x4c, 0x7a, 0xa3, 0xf1, 0x08, 0x00, 0x42, 0xea, 0x04, 0x24, 0x00, 0x22, + 0x01, 0xe0, 0x01, 0x32, 0x04, 0x38, 0xa2, 0x42, 0x01, 0xda, 0x04, 0x28, + 0xf9, 0xdc, 0x12, 0x1b, 0x00, 0xeb, 0x82, 0x02, 0x01, 0x2a, 0x1d, 0xdd, + 0x01, 0xf1, 0x08, 0x00, 0x00, 0xeb, 0x84, 0x04, 0xa0, 0x78, 0xe5, 0x78, + 0x02, 0x3a, 0x40, 0xea, 0x05, 0x24, 0x00, 0x20, 0x01, 0xe0, 0x01, 0x30, + 0x04, 0x3a, 0xa0, 0x42, 0x01, 0xda, 0x03, 0x2a, 0xf9, 0xdc, 0x00, 0x1b, + 0x02, 0xeb, 0x80, 0x02, 0x01, 0x2a, 0x09, 0xdd, 0x90, 0x1e, 0x08, 0xd0, + 0x18, 0x1a, 0x48, 0x70, 0x02, 0xe0, 0x6f, 0xf0, 0x16, 0x00, 0x30, 0xbd, + 0x00, 0x20, 0x30, 0xbd, 0x00, 0x20, 0x30, 0xbd, 0x2f, 0x2a, 0x70, 0xb5, + 0x30, 0xd9, 0xb0, 0xf8, 0x80, 0x31, 0x04, 0x6b, 0x0b, 0x60, 0xb0, 0xf8, + 0x82, 0x31, 0xa5, 0x89, 0x4b, 0x60, 0xe3, 0x89, 0x1b, 0x07, 0x43, 0xea, + 0x05, 0x33, 0x05, 0x68, 0x8b, 0x60, 0x2b, 0x69, 0xd0, 0xf8, 0x84, 0x01, + 0xde, 0x6b, 0x3b, 0x2a, 0xce, 0x60, 0xae, 0x68, 0x0e, 0x61, 0x9e, 0x6a, + 0x4e, 0x61, 0xde, 0x6a, 0x8e, 0x61, 0xb5, 0xf8, 0x7a, 0x60, 0x48, 0x62, + 0xd5, 0xf8, 0xb0, 0x00, 0xce, 0x61, 0x08, 0x62, 0x58, 0x68, 0x88, 0x62, + 0x98, 0x6b, 0xc8, 0x62, 0x0d, 0xd9, 0x20, 0x89, 0x08, 0x63, 0x60, 0x89, + 0x48, 0x63, 0x00, 0x20, 0x3f, 0x2a, 0x88, 0x63, 0x06, 0xd9, 0x1b, 0x6c, + 0xcb, 0x63, 0x70, 0xbd, 0x6f, 0xf0, 0x0d, 0x00, 0x70, 0xbd, 0x00, 0x20, + 0x70, 0xbd, 0x2d, 0xe9, 0xf0, 0x4f, 0x85, 0xb0, 0x03, 0x91, 0x01, 0x68, + 0x91, 0x46, 0x91, 0xf8, 0x2f, 0x10, 0x0e, 0xaa, 0x1f, 0x46, 0x05, 0x46, + 0x92, 0xe8, 0x0c, 0x08, 0x11, 0x9e, 0xdd, 0xf8, 0x48, 0xa0, 0xdd, 0xf8, + 0x4c, 0x80, 0x11, 0xb1, 0xb9, 0xf1, 0x14, 0x0f, 0x47, 0xd0, 0xd5, 0xf8, + 0x7c, 0x02, 0x02, 0x92, 0x01, 0x93, 0x41, 0xf0, 0x43, 0xdd, 0x02, 0x9a, + 0x04, 0x46, 0x01, 0x9b, 0x00, 0x28, 0x3c, 0xd0, 0xc0, 0xf8, 0x04, 0x90, + 0x82, 0x60, 0xc3, 0x60, 0xc0, 0xf8, 0x10, 0xb0, 0xb8, 0xf1, 0x00, 0x0f, + 0x01, 0xd0, 0x0a, 0xf1, 0x10, 0x0a, 0xc4, 0xf8, 0x14, 0xa0, 0xba, 0xf1, + 0x00, 0x0f, 0x1f, 0xd0, 0xf6, 0xb1, 0x68, 0x68, 0x51, 0x46, 0x02, 0xf0, + 0x63, 0xd8, 0xe0, 0x63, 0x38, 0xb9, 0xd5, 0xf8, 0x7c, 0x02, 0x21, 0x46, + 0x05, 0xb0, 0xbd, 0xe8, 0xf0, 0x4f, 0x41, 0xf0, 0x33, 0x9d, 0xb8, 0xf1, + 0x00, 0x0f, 0x09, 0xd0, 0x41, 0x46, 0x10, 0x22, 0xfd, 0xf3, 0xa6, 0xf1, + 0xe0, 0x6b, 0x62, 0x69, 0x10, 0x30, 0x31, 0x46, 0x10, 0x3a, 0x01, 0xe0, + 0x62, 0x69, 0x31, 0x46, 0xfd, 0xf3, 0x9c, 0xf1, 0x28, 0x46, 0x03, 0x99, + 0x22, 0x46, 0x3b, 0x46, 0x1d, 0xf0, 0x4a, 0xda, 0x28, 0x46, 0x21, 0x46, + 0x05, 0xb0, 0xbd, 0xe8, 0xf0, 0x4f, 0x20, 0xf0, 0xd5, 0x9d, 0x05, 0xb0, + 0xbd, 0xe8, 0xf0, 0x8f, 0x2d, 0xe9, 0xf0, 0x4f, 0x87, 0xb0, 0x8a, 0x46, + 0x11, 0x99, 0x05, 0x46, 0x0b, 0x29, 0x93, 0x46, 0x03, 0x93, 0xdd, 0xf8, + 0x40, 0x90, 0x12, 0x9c, 0x40, 0xf2, 0x63, 0x81, 0xba, 0xf8, 0x16, 0x30, + 0xa1, 0xf1, 0x0c, 0x06, 0x09, 0xf1, 0x0c, 0x07, 0x03, 0xf4, 0xff, 0x63, + 0xdb, 0x08, 0x38, 0x46, 0x31, 0x46, 0x03, 0x22, 0x02, 0x93, 0xfd, 0xf3, + 0x11, 0xf5, 0xb0, 0xb1, 0x90, 0xf8, 0x02, 0x80, 0xd5, 0xf8, 0x5c, 0x01, + 0x48, 0xf4, 0x30, 0x61, 0xb8, 0xf1, 0x0e, 0x0f, 0x8c, 0xbf, 0x4f, 0xf4, + 0x80, 0x53, 0x4f, 0xf4, 0x00, 0x53, 0x19, 0x43, 0x41, 0xf0, 0x70, 0xdb, + 0x38, 0xb9, 0xd5, 0xf8, 0x68, 0x31, 0x9b, 0x88, 0x99, 0x05, 0x02, 0xd4, + 0x3b, 0xe1, 0xdd, 0xf8, 0x08, 0x80, 0x00, 0x21, 0xac, 0x22, 0x20, 0x46, + 0xfd, 0xf3, 0xb4, 0xf1, 0x59, 0x46, 0x06, 0x22, 0x20, 0x46, 0xfd, 0xf3, + 0x4b, 0xf1, 0x99, 0xf8, 0x0a, 0x30, 0x99, 0xf8, 0x0b, 0xb0, 0x03, 0x99, + 0x43, 0xea, 0x0b, 0x2b, 0x0b, 0xf0, 0x03, 0x03, 0x01, 0x2b, 0x08, 0xbf, + 0x84, 0xf8, 0x34, 0x30, 0xe3, 0x88, 0x00, 0x29, 0x14, 0xbf, 0x4f, 0xf4, + 0x80, 0x72, 0x00, 0x22, 0x13, 0x43, 0xe3, 0x80, 0x51, 0x46, 0xa4, 0xf8, + 0x62, 0xb0, 0x28, 0x46, 0x1e, 0xf0, 0x40, 0xde, 0x51, 0x46, 0x60, 0x85, + 0x28, 0x46, 0x12, 0xf0, 0xcf, 0xde, 0x02, 0x9b, 0xa0, 0x85, 0x43, 0x45, + 0x03, 0xd1, 0xe3, 0x88, 0x43, 0xf0, 0x02, 0x03, 0xe3, 0x80, 0x05, 0xeb, + 0x08, 0x03, 0x93, 0xf8, 0x4c, 0x30, 0x31, 0x46, 0x84, 0xf8, 0x61, 0x30, + 0x99, 0xf8, 0x09, 0x20, 0x99, 0xf8, 0x08, 0x30, 0x38, 0x46, 0x43, 0xea, + 0x02, 0x23, 0xe3, 0x85, 0x00, 0x22, 0xfd, 0xf3, 0xb3, 0xf4, 0x01, 0x46, + 0x48, 0xb1, 0x42, 0x78, 0x20, 0x2a, 0x06, 0xd8, 0x22, 0x72, 0x04, 0xf1, + 0x09, 0x00, 0x02, 0x31, 0xfd, 0xf3, 0x06, 0xf1, 0x01, 0xe0, 0x00, 0x23, + 0x23, 0x72, 0x00, 0x23, 0x00, 0x93, 0x28, 0x46, 0x39, 0x46, 0x32, 0x46, + 0x23, 0x46, 0x1f, 0xf0, 0xc5, 0xd9, 0x00, 0x28, 0x40, 0xf0, 0xdd, 0x80, + 0x38, 0x46, 0x31, 0x46, 0x01, 0x22, 0xfd, 0xf3, 0x95, 0xf4, 0x30, 0xb1, + 0x43, 0x78, 0x08, 0x2b, 0x03, 0xd9, 0xe3, 0x88, 0x43, 0xf0, 0x01, 0x03, + 0xe3, 0x80, 0x48, 0xf4, 0x30, 0x63, 0xb8, 0xf1, 0x0e, 0x0f, 0x8c, 0xbf, + 0x4f, 0xf4, 0x80, 0x58, 0x4f, 0xf4, 0x00, 0x58, 0x43, 0xea, 0x08, 0x08, + 0x1b, 0xf0, 0x02, 0x0f, 0xa4, 0xf8, 0x32, 0x80, 0x0d, 0xd0, 0x38, 0x46, + 0x31, 0x46, 0x06, 0x22, 0xfd, 0xf3, 0x78, 0xf4, 0x38, 0xb1, 0x43, 0x78, + 0x01, 0x2b, 0x04, 0xd9, 0xc2, 0x78, 0x83, 0x78, 0x43, 0xea, 0x02, 0x23, + 0x23, 0x86, 0xd5, 0xf8, 0x68, 0x01, 0x83, 0x79, 0x5b, 0xb1, 0x11, 0x99, + 0x22, 0x46, 0x01, 0x91, 0x53, 0x46, 0x03, 0x99, 0xcd, 0xf8, 0x00, 0x90, + 0x4f, 0xf0, 0x28, 0xde, 0x00, 0x28, 0x00, 0xf0, 0xa2, 0x80, 0x31, 0x46, + 0x38, 0x46, 0x30, 0x22, 0xfd, 0xf3, 0x5a, 0xf4, 0x01, 0x46, 0x18, 0xb1, + 0x28, 0x46, 0x22, 0x46, 0x11, 0xf0, 0x3c, 0xdb, 0x31, 0x46, 0x38, 0x46, + 0x44, 0x22, 0xfd, 0xf3, 0x4f, 0xf4, 0x01, 0x46, 0x18, 0xb1, 0x28, 0x46, + 0x22, 0x46, 0x11, 0xf0, 0x71, 0xda, 0x31, 0x46, 0x38, 0x46, 0x04, 0x97, + 0x05, 0x96, 0xfe, 0xf3, 0x4f, 0xf2, 0x01, 0x46, 0x18, 0xb1, 0x28, 0x46, + 0x22, 0x46, 0x11, 0xf0, 0x21, 0xdc, 0x2b, 0x68, 0x5b, 0x6b, 0xd3, 0xb1, + 0x04, 0x97, 0x05, 0x96, 0x06, 0xe0, 0x28, 0x46, 0x41, 0x46, 0x04, 0xaa, + 0x05, 0xab, 0x1e, 0xf0, 0x81, 0xdb, 0x40, 0xb9, 0x04, 0x98, 0x05, 0x99, + 0xdd, 0x22, 0xfd, 0xf3, 0x2b, 0xf4, 0x80, 0x46, 0x00, 0x28, 0xf0, 0xd1, + 0x07, 0xe0, 0xe3, 0x88, 0x43, 0xf0, 0x04, 0x03, 0xe3, 0x80, 0x98, 0xf8, + 0x08, 0x30, 0x84, 0xf8, 0x6a, 0x30, 0x00, 0x23, 0x38, 0x46, 0x31, 0x46, + 0x31, 0x4a, 0x00, 0x93, 0x1d, 0xf0, 0x3c, 0xda, 0x18, 0xb1, 0xe3, 0x88, + 0x43, 0xf0, 0x08, 0x03, 0xe3, 0x80, 0xe3, 0x88, 0x28, 0x46, 0x23, 0xf4, + 0x66, 0x63, 0xe3, 0x80, 0x39, 0x46, 0x32, 0x46, 0x21, 0xf0, 0x48, 0xd9, + 0x81, 0x46, 0x00, 0x28, 0x4b, 0xd0, 0x03, 0x78, 0x90, 0xf8, 0x01, 0x80, + 0x43, 0xea, 0x08, 0x28, 0xe3, 0x88, 0x18, 0xf4, 0x80, 0x4f, 0x43, 0xf0, + 0x20, 0x03, 0x9b, 0xb2, 0xe3, 0x80, 0x0d, 0xd0, 0x43, 0xf4, 0x00, 0x73, + 0xe3, 0x80, 0x2b, 0x68, 0x93, 0xf8, 0x2f, 0x30, 0x33, 0xb1, 0xd5, 0xf8, + 0xfc, 0x34, 0x1b, 0x78, 0x13, 0xb1, 0x28, 0x46, 0x2f, 0xf0, 0x9e, 0xdc, + 0x18, 0xf0, 0x20, 0x0f, 0x03, 0xd0, 0xe3, 0x88, 0x43, 0xf4, 0x80, 0x63, + 0xe3, 0x80, 0x18, 0xf0, 0x40, 0x0f, 0x03, 0xd0, 0xe3, 0x88, 0x43, 0xf4, + 0x00, 0x63, 0xe3, 0x80, 0x09, 0xf1, 0x03, 0x01, 0x10, 0x22, 0x04, 0xf1, + 0x4d, 0x00, 0xfd, 0xf3, 0x35, 0xf0, 0x32, 0x46, 0x28, 0x46, 0x39, 0x46, + 0x21, 0xf0, 0xdc, 0xd8, 0x06, 0x46, 0xa0, 0xb1, 0x31, 0x78, 0x72, 0x78, + 0x28, 0x46, 0x10, 0xf0, 0x2f, 0xd8, 0x60, 0x86, 0x18, 0xf0, 0x02, 0x00, + 0x0b, 0xd0, 0x70, 0x78, 0x10, 0xf0, 0x04, 0x00, 0x07, 0xd0, 0xe3, 0x88, + 0x00, 0x20, 0x43, 0xf0, 0x40, 0x03, 0xe3, 0x80, 0x01, 0xe0, 0x4f, 0xf0, + 0xff, 0x30, 0x07, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, 0xc5, 0xb6, 0x01, 0x00, + 0x2d, 0xe9, 0xf0, 0x4f, 0xd0, 0xf8, 0x68, 0x61, 0xb5, 0xb0, 0x1d, 0x46, + 0xdd, 0xf8, 0xf8, 0xb0, 0xb3, 0x79, 0x07, 0x91, 0x04, 0x46, 0x3f, 0x9f, + 0xbb, 0xf8, 0x0a, 0xa0, 0x13, 0xb1, 0x30, 0x46, 0x4f, 0xf0, 0x60, 0xdb, + 0xb5, 0xf8, 0x00, 0x80, 0x08, 0xf0, 0xfc, 0x08, 0xa8, 0xf1, 0x80, 0x00, + 0xd0, 0xf1, 0x00, 0x08, 0x48, 0xeb, 0x00, 0x08, 0xb8, 0xf1, 0x00, 0x0f, + 0x11, 0xd0, 0xb3, 0x88, 0x59, 0x07, 0x10, 0xd4, 0x07, 0x9a, 0xd4, 0xf8, + 0x5c, 0x01, 0xd1, 0x8a, 0x01, 0xf4, 0xff, 0x61, 0xc9, 0x08, 0x40, 0xf0, + 0xc3, 0xdf, 0xd0, 0xf1, 0x01, 0x09, 0x38, 0xbf, 0x4f, 0xf0, 0x00, 0x09, + 0x03, 0xe0, 0xc1, 0x46, 0x01, 0xe0, 0x4f, 0xf0, 0x00, 0x09, 0xa7, 0xf1, + 0x0c, 0x01, 0x00, 0x22, 0x0b, 0xf1, 0x0c, 0x00, 0xfd, 0xf3, 0x7a, 0xf3, + 0xb3, 0x68, 0x01, 0x46, 0x02, 0x2b, 0x0a, 0xd0, 0x13, 0xb9, 0x1a, 0xf0, + 0x01, 0x0f, 0x04, 0xe0, 0x01, 0x2b, 0x40, 0xf0, 0x60, 0x81, 0x1a, 0xf0, + 0x02, 0x0f, 0x00, 0xf0, 0x5c, 0x81, 0x30, 0x46, 0x4a, 0x46, 0x4f, 0xf0, + 0x51, 0xdd, 0x00, 0x28, 0x00, 0xf0, 0x55, 0x81, 0x73, 0x7b, 0xda, 0x07, + 0x09, 0xd4, 0x06, 0xf1, 0x0d, 0x00, 0x05, 0xf1, 0x10, 0x01, 0x06, 0x22, + 0xfc, 0xf3, 0x9c, 0xf7, 0x00, 0x28, 0x40, 0xf0, 0x48, 0x81, 0x09, 0xab, + 0x05, 0xf1, 0x10, 0x0a, 0x02, 0x93, 0x20, 0x46, 0x07, 0x99, 0x52, 0x46, + 0x43, 0x46, 0xcd, 0xf8, 0x00, 0xb0, 0x01, 0x97, 0xff, 0xf7, 0x1c, 0xfe, + 0x00, 0x28, 0x40, 0xf0, 0x38, 0x81, 0x9d, 0xf8, 0x2c, 0x30, 0xbd, 0xf8, + 0x56, 0x20, 0x00, 0x93, 0x20, 0x46, 0x51, 0x46, 0x0d, 0xf1, 0x2d, 0x03, + 0x0d, 0xf0, 0xea, 0xde, 0x05, 0x46, 0x30, 0xb1, 0xb8, 0xf1, 0x00, 0x0f, + 0x03, 0xd0, 0xc3, 0x88, 0xdb, 0x05, 0x40, 0xf1, 0x24, 0x81, 0x93, 0x4a, + 0xbd, 0xf8, 0x4e, 0x30, 0x12, 0x68, 0x19, 0xb2, 0xd1, 0x42, 0x44, 0xbf, + 0xd3, 0x18, 0xad, 0xf8, 0x4e, 0x30, 0xe5, 0xb1, 0xea, 0x88, 0xbd, 0xf8, + 0x2a, 0x30, 0x83, 0xea, 0x02, 0x01, 0x88, 0x07, 0x09, 0xd4, 0xb5, 0xf9, + 0x2a, 0x20, 0xbd, 0xf9, 0x4e, 0x30, 0x9a, 0x42, 0xa8, 0xbf, 0x13, 0x46, + 0xad, 0xf8, 0x4e, 0x30, 0x14, 0xe0, 0x91, 0x07, 0x12, 0xd5, 0x9a, 0x07, + 0x10, 0xd4, 0x6a, 0x8d, 0x43, 0xf0, 0x02, 0x03, 0xad, 0xf8, 0x4e, 0x20, + 0xad, 0xf8, 0x2a, 0x30, 0x08, 0xe0, 0xd4, 0xf8, 0x1c, 0x35, 0x2b, 0xb1, + 0xbd, 0xf9, 0x4e, 0x20, 0x1b, 0xb2, 0x9a, 0x42, 0xc0, 0xf2, 0xf3, 0x80, + 0x94, 0xf8, 0xf4, 0x37, 0xd8, 0x07, 0x5d, 0xd5, 0x00, 0x23, 0xad, 0xf8, + 0x8c, 0x30, 0xb3, 0x88, 0x99, 0x07, 0x0b, 0xd5, 0x60, 0x68, 0x39, 0x46, + 0x01, 0xf0, 0xfe, 0xdd, 0x22, 0x90, 0xa8, 0xb1, 0x59, 0x46, 0x3a, 0x46, + 0xfc, 0xf3, 0x4c, 0xf7, 0xad, 0xf8, 0x8c, 0x70, 0xbd, 0xf8, 0x8c, 0x10, + 0x60, 0x68, 0x8c, 0x31, 0x01, 0xf0, 0xf0, 0xdd, 0xbd, 0xf8, 0x8c, 0x30, + 0x05, 0x46, 0x58, 0xb9, 0x23, 0xb1, 0x60, 0x68, 0x22, 0x99, 0x1a, 0x46, + 0x01, 0xf0, 0xf6, 0xdd, 0xd4, 0xf8, 0x68, 0x01, 0x04, 0x21, 0x4f, 0xf0, + 0x51, 0xda, 0xc6, 0xe0, 0x01, 0x26, 0x20, 0x46, 0x09, 0xa9, 0x05, 0xf1, + 0x0c, 0x02, 0x80, 0x33, 0x00, 0x96, 0x0e, 0xf0, 0x95, 0xd8, 0x07, 0x46, + 0xc8, 0xb9, 0x6d, 0x23, 0xb4, 0xf8, 0xf6, 0x27, 0x6b, 0x60, 0x2b, 0x69, + 0x2a, 0x81, 0x0c, 0x33, 0x2b, 0x60, 0x6e, 0x81, 0xd4, 0xf8, 0x68, 0x01, + 0x4f, 0xf0, 0x7a, 0xda, 0x08, 0x23, 0x8d, 0xe8, 0x88, 0x00, 0x02, 0x97, + 0x03, 0x95, 0x2b, 0x68, 0x01, 0x46, 0x04, 0x93, 0x20, 0x46, 0x45, 0x22, + 0x3b, 0x46, 0x17, 0xf0, 0xe1, 0xdc, 0xbd, 0xf8, 0x8c, 0x20, 0x60, 0x68, + 0x8c, 0x32, 0x29, 0x46, 0x01, 0xf0, 0xc4, 0xdd, 0xbd, 0xf8, 0x8c, 0x20, + 0x00, 0x2a, 0x00, 0xf0, 0x96, 0x80, 0x60, 0x68, 0x22, 0x99, 0x01, 0xf0, + 0xbb, 0xdd, 0x90, 0xe0, 0xd4, 0xf8, 0x18, 0x08, 0x0a, 0xf0, 0xf2, 0xd9, + 0x28, 0xb1, 0xd4, 0xf8, 0x18, 0x08, 0x09, 0xa9, 0x0a, 0xf0, 0x30, 0xf8, + 0x85, 0xe0, 0xe5, 0xb9, 0xd4, 0xf8, 0x28, 0x35, 0x02, 0x2b, 0x1a, 0xd1, + 0x07, 0x9b, 0x20, 0x46, 0xb3, 0xf8, 0x16, 0x90, 0xbd, 0xf8, 0x56, 0x30, + 0x09, 0xf4, 0xff, 0x69, 0x23, 0xf0, 0xff, 0x03, 0x43, 0xea, 0xd9, 0x09, + 0x9d, 0xf8, 0x2c, 0x30, 0x1f, 0xfa, 0x89, 0xf9, 0x00, 0x93, 0x51, 0x46, + 0x4a, 0x46, 0x0d, 0xf1, 0x2d, 0x03, 0x0d, 0xf0, 0x33, 0xdd, 0x18, 0xb1, + 0x67, 0xe0, 0x81, 0x46, 0x00, 0xe0, 0xa9, 0x46, 0xb6, 0xf8, 0x04, 0x80, + 0x18, 0xf0, 0x02, 0x08, 0x06, 0xd0, 0x60, 0x68, 0x39, 0x46, 0x01, 0xf0, + 0x75, 0xdd, 0x80, 0x46, 0x00, 0x28, 0x58, 0xd0, 0x9d, 0xb9, 0x20, 0x46, + 0x0d, 0xf0, 0xf6, 0xdc, 0x05, 0x46, 0x00, 0x28, 0x4d, 0xd0, 0xd4, 0xf8, + 0x28, 0x35, 0x02, 0x2b, 0x09, 0xd1, 0x9d, 0xf8, 0x2c, 0x30, 0x20, 0x46, + 0x00, 0x93, 0x51, 0x46, 0x4a, 0x46, 0x0d, 0xf1, 0x2d, 0x03, 0x0d, 0xf0, + 0xaf, 0xdc, 0x69, 0x6e, 0x41, 0xb1, 0x60, 0x68, 0xb5, 0xf8, 0x68, 0x20, + 0x01, 0xf0, 0x66, 0xdd, 0x00, 0x23, 0x6b, 0x66, 0xa5, 0xf8, 0x68, 0x30, + 0xac, 0x22, 0x28, 0x46, 0x09, 0xa9, 0xfc, 0xf3, 0xa1, 0xf6, 0xb3, 0x88, + 0x9a, 0x07, 0x08, 0xd5, 0xc5, 0xf8, 0x64, 0x80, 0x40, 0x46, 0x59, 0x46, + 0x3a, 0x46, 0xfc, 0xf3, 0x97, 0xf6, 0xa5, 0xf8, 0x68, 0x70, 0xd4, 0xf8, + 0x68, 0x01, 0x43, 0x7b, 0xdb, 0x07, 0x22, 0xd4, 0x0d, 0x30, 0xfd, 0xf3, + 0x7d, 0xf3, 0x05, 0x46, 0xe8, 0xb9, 0xd4, 0xf8, 0x68, 0x01, 0x4f, 0xf0, + 0xed, 0xd9, 0x01, 0x28, 0x17, 0xd1, 0xd4, 0xf8, 0x68, 0x01, 0x29, 0x46, + 0x0c, 0xe0, 0x60, 0x68, 0x41, 0x46, 0x3a, 0x46, 0x01, 0xf0, 0x38, 0xdd, + 0xd4, 0xf8, 0x28, 0x35, 0x30, 0x46, 0x02, 0x2b, 0x08, 0xbf, 0xa4, 0xf8, + 0x38, 0x95, 0x08, 0x21, 0x4f, 0xf0, 0x6c, 0xdc, 0x03, 0xe0, 0xb8, 0xf1, + 0x00, 0x0f, 0xec, 0xd1, 0xf0, 0xe7, 0x35, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, + 0xe0, 0x07, 0x02, 0x00, 0x10, 0xb5, 0x04, 0x46, 0x24, 0xf0, 0x92, 0xd8, + 0x20, 0x46, 0xbd, 0xe8, 0x10, 0x40, 0x15, 0xf0, 0xa9, 0x99, 0x38, 0xb5, + 0xd0, 0xf8, 0x60, 0x36, 0xda, 0x7a, 0x9c, 0x7a, 0x92, 0xb1, 0x9d, 0x89, + 0x4f, 0xf6, 0xff, 0x72, 0x95, 0x42, 0x0d, 0xd0, 0x99, 0x7b, 0x41, 0xb9, + 0x9a, 0x78, 0x01, 0x2a, 0x06, 0xd0, 0x19, 0x7b, 0x01, 0xf0, 0x01, 0x01, + 0x81, 0xf0, 0x01, 0x01, 0x00, 0xe0, 0x00, 0x21, 0xc9, 0xb2, 0x0d, 0xe0, + 0x02, 0x6b, 0x8a, 0x42, 0x10, 0xd1, 0x9a, 0x7b, 0x2a, 0xb9, 0x9d, 0x78, + 0x01, 0x2d, 0x04, 0xd0, 0x91, 0xf8, 0x4c, 0x10, 0x02, 0xe0, 0x00, 0x21, + 0x00, 0xe0, 0x11, 0x46, 0x8c, 0x42, 0x03, 0xd0, 0x99, 0x72, 0x00, 0x69, + 0x36, 0xf0, 0xc6, 0xdf, 0x00, 0x20, 0x38, 0xbd, 0x38, 0xb5, 0x0d, 0x46, + 0xd0, 0xf8, 0x60, 0x16, 0x04, 0x46, 0xcb, 0x7a, 0xab, 0x42, 0x0c, 0xd0, + 0x25, 0xb1, 0x0c, 0x31, 0xb0, 0xf8, 0x28, 0x26, 0x14, 0xf0, 0x68, 0xdc, + 0xd4, 0xf8, 0x60, 0x36, 0x20, 0x46, 0xdd, 0x72, 0x21, 0x6b, 0xff, 0xf7, + 0xbc, 0xff, 0x00, 0x20, 0x38, 0xbd, 0x73, 0xb5, 0x03, 0x68, 0x04, 0x46, + 0x5b, 0x7e, 0x00, 0x2b, 0x40, 0xf0, 0xbd, 0x80, 0x03, 0x69, 0x93, 0xf8, + 0xea, 0x20, 0x4a, 0xb1, 0xdb, 0x6e, 0xd3, 0xf8, 0x20, 0x21, 0x40, 0xf2, + 0x04, 0x43, 0x13, 0x40, 0xb3, 0xf5, 0x80, 0x6f, 0x06, 0xd0, 0xae, 0xe0, + 0x18, 0x6e, 0x07, 0xf0, 0xc8, 0xfe, 0x00, 0x28, 0x40, 0xf0, 0xa9, 0x80, + 0x23, 0x68, 0x93, 0xf8, 0x20, 0x30, 0x33, 0xb9, 0x20, 0x69, 0x05, 0xf0, + 0x19, 0xf8, 0x23, 0x68, 0x01, 0x22, 0x83, 0xf8, 0x20, 0x20, 0x23, 0x68, + 0x1b, 0x6f, 0xeb, 0xb9, 0x20, 0x69, 0x05, 0xf0, 0x37, 0xf8, 0x09, 0x30, + 0x18, 0xd1, 0x23, 0x68, 0x1a, 0x6f, 0x91, 0x07, 0x14, 0xd4, 0x42, 0xf0, + 0x02, 0x02, 0x1a, 0x67, 0x25, 0x46, 0x04, 0xf1, 0x20, 0x06, 0xd5, 0xf8, + 0x4c, 0x12, 0x41, 0xb1, 0x8b, 0x79, 0x33, 0xb9, 0x4b, 0x79, 0x23, 0xb1, + 0x8b, 0x7c, 0x13, 0xb1, 0x20, 0x46, 0x39, 0xf0, 0x59, 0xdd, 0x04, 0x35, + 0xb5, 0x42, 0xf0, 0xd1, 0x23, 0x68, 0x1d, 0x6f, 0x1d, 0xb1, 0x20, 0x46, + 0x11, 0xf0, 0x94, 0xdd, 0x73, 0xe0, 0x01, 0x23, 0x84, 0xf8, 0x29, 0x30, + 0x20, 0x46, 0x20, 0xf0, 0x1f, 0xdc, 0x23, 0x68, 0x20, 0x46, 0x59, 0x6b, + 0x03, 0x23, 0x00, 0x93, 0x21, 0xb1, 0x4f, 0xf4, 0x80, 0x72, 0x29, 0x46, + 0x13, 0x46, 0x02, 0xe0, 0x4f, 0xf4, 0x80, 0x72, 0x0b, 0x46, 0x1e, 0xf0, + 0xdd, 0xdb, 0xa0, 0x68, 0x0a, 0xf0, 0x4a, 0xd9, 0x23, 0x68, 0x01, 0x22, + 0x1a, 0x76, 0x94, 0xf8, 0x9d, 0x31, 0x73, 0xb1, 0x20, 0x46, 0x0a, 0xf0, + 0x89, 0xf9, 0xd4, 0xf8, 0x40, 0x35, 0x20, 0x46, 0x59, 0x8e, 0x23, 0xf0, + 0xfd, 0xda, 0x00, 0x23, 0x84, 0xf8, 0x9d, 0x31, 0x20, 0x46, 0x1c, 0xf0, + 0xe1, 0xdd, 0xb4, 0xf8, 0x5c, 0x17, 0x20, 0x46, 0x21, 0xf0, 0x6a, 0xdb, + 0x20, 0x69, 0x04, 0xf0, 0x54, 0xfe, 0x23, 0x68, 0x93, 0xf8, 0x2f, 0x30, + 0x1b, 0xb1, 0xd4, 0xf8, 0x34, 0x07, 0x2f, 0xf0, 0x5b, 0xdc, 0x23, 0x68, + 0x93, 0xf8, 0x31, 0x30, 0x7b, 0xb1, 0x25, 0x46, 0x04, 0xf1, 0x20, 0x06, + 0xd5, 0xf8, 0x4c, 0x12, 0x31, 0xb1, 0x8b, 0x79, 0x23, 0xb9, 0x4b, 0x79, + 0x13, 0xb1, 0x20, 0x46, 0x35, 0xf0, 0x18, 0xdb, 0x04, 0x35, 0xb5, 0x42, + 0xf2, 0xd1, 0x20, 0x46, 0x15, 0xf0, 0x2c, 0xdb, 0x20, 0x46, 0x16, 0xf0, + 0x5e, 0xf8, 0x01, 0x25, 0xd4, 0xf8, 0xac, 0x11, 0x4f, 0xf4, 0x7a, 0x72, + 0x01, 0x23, 0xa0, 0x68, 0x0a, 0xf0, 0x94, 0xd8, 0x20, 0x46, 0x84, 0xf8, + 0xf1, 0x51, 0x25, 0xf0, 0xef, 0xd9, 0x20, 0x46, 0x14, 0xf0, 0x90, 0xdb, + 0x20, 0x46, 0x25, 0xf0, 0x4b, 0xdd, 0x50, 0xb1, 0x20, 0x46, 0x25, 0xf0, + 0x25, 0xdd, 0x20, 0x46, 0x29, 0x46, 0x25, 0xf0, 0x2b, 0xdf, 0x00, 0x20, + 0x01, 0xe0, 0x6f, 0xf0, 0x08, 0x00, 0x7c, 0xbd, 0x2d, 0xe9, 0xf0, 0x4f, + 0x90, 0xf8, 0x75, 0x32, 0x97, 0xb0, 0xdb, 0x06, 0x04, 0x46, 0x0e, 0x46, + 0x01, 0xf1, 0x04, 0x09, 0x00, 0xf1, 0xa5, 0x80, 0xd0, 0xf8, 0x04, 0x38, + 0x99, 0x42, 0x40, 0xf0, 0xa0, 0x80, 0x51, 0x4b, 0x1a, 0x78, 0x9a, 0x46, + 0x00, 0x2a, 0x40, 0xf0, 0x9a, 0x80, 0x01, 0x23, 0x8a, 0xf8, 0x00, 0x30, + 0xb0, 0xf8, 0x3c, 0x52, 0x81, 0xe0, 0x11, 0xf0, 0xd1, 0xda, 0x01, 0x69, + 0xd1, 0xf8, 0xcc, 0x30, 0x98, 0x03, 0x0d, 0xd5, 0x20, 0x46, 0x3a, 0x46, + 0x13, 0x9b, 0x3a, 0xf0, 0x2d, 0xdb, 0x00, 0x28, 0x73, 0xd0, 0x23, 0x68, + 0x03, 0x99, 0xd8, 0x68, 0x01, 0x22, 0x01, 0xf0, 0xf5, 0xdb, 0x6c, 0xe0, + 0x7b, 0x6a, 0x5a, 0x05, 0x07, 0xd5, 0xd4, 0xf8, 0x40, 0x01, 0x31, 0x46, + 0x03, 0xaa, 0x13, 0x9b, 0x2a, 0xf0, 0x20, 0xdb, 0x43, 0xe0, 0x58, 0x07, + 0x07, 0xd5, 0x01, 0x23, 0x20, 0x46, 0x39, 0x46, 0x15, 0xaa, 0x14, 0x93, + 0x1f, 0xf0, 0x6a, 0xdc, 0x05, 0xe0, 0x20, 0x46, 0x03, 0xa9, 0x14, 0xaa, + 0x15, 0xab, 0x0b, 0xf0, 0x8b, 0xf8, 0x00, 0x28, 0x31, 0xd1, 0x23, 0x68, + 0x93, 0xf8, 0xa1, 0x30, 0x01, 0x2b, 0x07, 0xd1, 0x15, 0x99, 0x03, 0x29, + 0x04, 0xd8, 0xd4, 0xf8, 0x40, 0x01, 0x03, 0x22, 0x29, 0xf0, 0xc0, 0xdd, + 0x02, 0xaf, 0x4f, 0xf0, 0x00, 0x08, 0x1c, 0xe0, 0x78, 0x68, 0x03, 0x69, + 0xb3, 0xf8, 0x4c, 0x30, 0x1f, 0xfa, 0x83, 0xfb, 0x1b, 0xb2, 0x00, 0x2b, + 0x09, 0xda, 0x11, 0xf0, 0x85, 0xda, 0x00, 0x23, 0x01, 0x46, 0x5a, 0x46, + 0xd4, 0xf8, 0x60, 0x01, 0x00, 0x93, 0x4d, 0xf0, 0xcf, 0xdc, 0x01, 0x23, + 0x00, 0x93, 0x20, 0x46, 0x15, 0x99, 0x57, 0xf8, 0x04, 0x2f, 0xfe, 0xf7, + 0xb7, 0xf9, 0x08, 0xf1, 0x01, 0x08, 0x14, 0x9b, 0x98, 0x45, 0xdf, 0xdb, + 0x1d, 0xe0, 0x10, 0x30, 0x1b, 0xd1, 0x48, 0x46, 0x13, 0x99, 0x03, 0x9a, + 0xfd, 0xf3, 0x30, 0xf5, 0x94, 0xf8, 0x75, 0x32, 0x73, 0xb1, 0x23, 0x68, + 0x93, 0xf8, 0xb5, 0x30, 0xd9, 0x07, 0x09, 0xd5, 0xb4, 0xf8, 0x3c, 0x32, + 0x01, 0x22, 0x1d, 0x40, 0x13, 0x9b, 0x12, 0xfa, 0x03, 0xf3, 0x25, 0xea, + 0x03, 0x05, 0x04, 0xe0, 0xb4, 0xf8, 0x3c, 0x32, 0x9d, 0x42, 0x0b, 0xd0, + 0x1d, 0x46, 0x4d, 0xb1, 0x48, 0x46, 0x29, 0x46, 0x13, 0xaa, 0xfd, 0xf3, + 0x47, 0xf4, 0x07, 0x46, 0x03, 0x90, 0x00, 0x28, 0x7f, 0xf4, 0x73, 0xaf, + 0x20, 0x46, 0x31, 0x46, 0x14, 0xf0, 0x40, 0xd9, 0x00, 0x23, 0x8a, 0xf8, + 0x00, 0x30, 0x17, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, 0x7c, 0x27, 0x00, 0x00, + 0x2d, 0xe9, 0xf0, 0x4f, 0x9d, 0xb0, 0x27, 0x9f, 0x12, 0x93, 0x0e, 0x92, + 0x7f, 0x89, 0x04, 0x46, 0x11, 0x97, 0x27, 0x9f, 0x10, 0x46, 0x0c, 0x37, + 0x0b, 0x97, 0x28, 0x9f, 0x0d, 0x46, 0x0c, 0x3f, 0x0c, 0x97, 0xb2, 0xf8, + 0x16, 0x90, 0x19, 0x46, 0x09, 0xf4, 0xff, 0x69, 0x4f, 0xea, 0xd9, 0x09, + 0xb9, 0xf1, 0x0e, 0x0f, 0x94, 0xbf, 0x00, 0x27, 0x01, 0x27, 0x10, 0x97, + 0x97, 0x88, 0x0d, 0xf1, 0x70, 0x08, 0x14, 0x97, 0x15, 0xf0, 0xcc, 0xfe, + 0x26, 0x9f, 0x15, 0x90, 0x0a, 0x37, 0x39, 0x46, 0x10, 0x9a, 0x20, 0x46, + 0x13, 0x97, 0x50, 0xf0, 0x8b, 0xd8, 0x00, 0x23, 0x48, 0xf8, 0x10, 0x3d, + 0x06, 0x46, 0x19, 0x93, 0x19, 0xaf, 0x20, 0x46, 0x27, 0x99, 0x28, 0x9a, + 0x43, 0x46, 0x00, 0x97, 0x1c, 0xf0, 0xb0, 0xdc, 0x30, 0xb9, 0x20, 0x46, + 0x27, 0x99, 0x28, 0x9a, 0x43, 0x46, 0x00, 0x97, 0x1e, 0xf0, 0xa8, 0xdc, + 0x16, 0xb1, 0x73, 0x68, 0xdb, 0x07, 0x26, 0xd4, 0x0c, 0x99, 0x0b, 0x98, + 0x32, 0x22, 0xfc, 0xf3, 0xf3, 0xf7, 0x01, 0x46, 0x20, 0xb1, 0x40, 0x78, + 0x02, 0x31, 0x20, 0xf0, 0xb9, 0xdc, 0x70, 0xb9, 0x0c, 0x99, 0x0b, 0x98, + 0x01, 0x22, 0xfc, 0xf3, 0xe7, 0xf7, 0x01, 0x46, 0x50, 0xb1, 0x02, 0x31, + 0x40, 0x78, 0x20, 0xf0, 0xad, 0xdc, 0x00, 0x30, 0x18, 0xbf, 0x01, 0x20, + 0x02, 0xe0, 0x01, 0x27, 0x0d, 0x97, 0x00, 0xe0, 0x0d, 0x90, 0x56, 0xb1, + 0x0d, 0x9f, 0x37, 0xb9, 0x73, 0x68, 0x43, 0xf0, 0x01, 0x03, 0x73, 0x60, + 0x03, 0xe0, 0x00, 0x27, 0x00, 0xe0, 0x01, 0x27, 0x0d, 0x97, 0x0b, 0x98, + 0x0c, 0x99, 0x03, 0x22, 0xfc, 0xf3, 0xc8, 0xf7, 0x23, 0x68, 0x07, 0x46, + 0x08, 0xb1, 0x42, 0x78, 0xaa, 0xb9, 0x93, 0xf8, 0x3f, 0x00, 0x70, 0xb1, + 0xb4, 0xf8, 0x26, 0x06, 0xc3, 0xb2, 0x4b, 0x45, 0x08, 0xd0, 0xfd, 0xf3, + 0x6d, 0xf5, 0xc9, 0xeb, 0x00, 0x0e, 0xde, 0xf1, 0x00, 0x00, 0x40, 0xeb, + 0x0e, 0x00, 0x00, 0xe0, 0x01, 0x20, 0xc0, 0xb2, 0x0f, 0x90, 0x00, 0x27, + 0x10, 0xe0, 0x93, 0xf8, 0x3f, 0x00, 0x50, 0xb1, 0xb4, 0xf8, 0x26, 0x06, + 0xfd, 0xf3, 0x5a, 0xf5, 0x97, 0xf8, 0x02, 0x90, 0xc0, 0xeb, 0x09, 0x07, + 0x78, 0x42, 0x40, 0xeb, 0x07, 0x00, 0xc0, 0xb2, 0x0f, 0x90, 0x07, 0x46, + 0x0f, 0x99, 0x29, 0xb1, 0x15, 0xf1, 0x00, 0x08, 0x18, 0xbf, 0x4f, 0xf0, + 0x01, 0x08, 0x01, 0xe0, 0xdd, 0xf8, 0x3c, 0x80, 0x23, 0x68, 0x5f, 0xfa, + 0x88, 0xf8, 0x93, 0xf8, 0x46, 0x90, 0x19, 0xf0, 0x03, 0x09, 0x23, 0xd0, + 0x94, 0xf8, 0x72, 0x32, 0x4b, 0xb9, 0xb8, 0xf1, 0x00, 0x0f, 0x06, 0xd0, + 0xd5, 0xf8, 0xd4, 0x32, 0xb3, 0xf8, 0x06, 0x90, 0x19, 0xf0, 0x20, 0x09, + 0x1f, 0xd0, 0x0b, 0x99, 0x0c, 0x9a, 0x20, 0x46, 0x20, 0xf0, 0xb6, 0xdc, + 0x0b, 0x99, 0x83, 0x46, 0x0c, 0x9a, 0x20, 0x46, 0x20, 0xf0, 0x7c, 0xdc, + 0x23, 0x68, 0x07, 0x90, 0x93, 0xf9, 0x4c, 0x30, 0x53, 0xb1, 0x20, 0x46, + 0x0b, 0x99, 0x0c, 0x9a, 0x1d, 0xf0, 0xa0, 0xd9, 0x81, 0x46, 0x04, 0xe0, + 0xcb, 0x46, 0xcd, 0xf8, 0x1c, 0x90, 0x00, 0xe0, 0x99, 0x46, 0xb8, 0xf1, + 0x00, 0x0f, 0x6c, 0xd0, 0x02, 0xe0, 0xcb, 0x46, 0xcd, 0xf8, 0x1c, 0x90, + 0x23, 0x68, 0x93, 0xf8, 0x46, 0xa0, 0x1a, 0xf0, 0x03, 0x0a, 0x6c, 0xd0, + 0x07, 0x9a, 0x00, 0x2a, 0x61, 0xd0, 0xbb, 0xf1, 0x00, 0x0f, 0x61, 0xd0, + 0x11, 0x78, 0x20, 0x46, 0x52, 0x78, 0x0f, 0xf0, 0xad, 0xdb, 0xb4, 0xf8, + 0x26, 0xc6, 0x03, 0x46, 0x0c, 0xf4, 0x70, 0x42, 0xb2, 0xf5, 0x00, 0x52, + 0x18, 0xbf, 0x01, 0x22, 0x0e, 0x32, 0x54, 0xf8, 0x22, 0x80, 0x0c, 0xf4, + 0x40, 0x6c, 0xd8, 0xf8, 0x04, 0x10, 0xd4, 0xf8, 0x5c, 0x01, 0x08, 0x93, + 0xcd, 0xf8, 0x24, 0xc0, 0x3f, 0xf0, 0x52, 0xdf, 0x10, 0xf0, 0x08, 0x0f, + 0x08, 0x9b, 0xdd, 0xf8, 0x24, 0xc0, 0x07, 0xd1, 0x98, 0xf8, 0xec, 0xa0, + 0x1a, 0xf1, 0x00, 0x0a, 0x18, 0xbf, 0x4f, 0xf0, 0x01, 0x0a, 0x01, 0xe0, + 0x4f, 0xf0, 0x00, 0x0a, 0x9b, 0xf8, 0x00, 0x20, 0x12, 0xf0, 0x02, 0x02, + 0x03, 0xd0, 0x07, 0x99, 0x4a, 0x78, 0xc2, 0xf3, 0x80, 0x02, 0xbc, 0xf5, + 0x40, 0x6f, 0x05, 0xd1, 0xb4, 0xf8, 0x26, 0x26, 0x9a, 0x42, 0x0b, 0xd1, + 0x00, 0xf0, 0x13, 0xbc, 0xba, 0xf1, 0x00, 0x0f, 0x25, 0xd0, 0x0a, 0xb3, + 0x03, 0xf4, 0x40, 0x62, 0xb2, 0xf5, 0x40, 0x6f, 0x40, 0xf0, 0x09, 0x84, + 0x22, 0x68, 0x92, 0xf8, 0x2f, 0xa0, 0xba, 0xf1, 0x00, 0x0f, 0x40, 0xf0, + 0x05, 0x84, 0x18, 0x46, 0x08, 0x93, 0xfd, 0xf3, 0xaf, 0xf4, 0x80, 0x46, + 0xb4, 0xf8, 0x26, 0x06, 0xfd, 0xf3, 0xaa, 0xf4, 0x80, 0x45, 0x08, 0x9b, + 0x40, 0xf0, 0xfa, 0x83, 0x08, 0xe0, 0xc2, 0x46, 0x09, 0xe0, 0xdd, 0xf8, + 0x1c, 0xa0, 0x04, 0xe0, 0xda, 0x46, 0x02, 0xe0, 0x92, 0x46, 0x00, 0xe0, + 0x9a, 0x46, 0x4f, 0xf0, 0x01, 0x08, 0x23, 0x6b, 0x5b, 0x7d, 0x00, 0x2b, + 0x37, 0xd0, 0x0f, 0x9a, 0x00, 0x2a, 0x34, 0xd0, 0x94, 0xf8, 0x72, 0x32, + 0x33, 0xb9, 0x94, 0xf8, 0x74, 0x32, 0x00, 0x2b, 0x2d, 0xd0, 0xb8, 0xf1, + 0x00, 0x0f, 0x2a, 0xd1, 0x94, 0xf8, 0x49, 0x36, 0x53, 0xb1, 0x19, 0x9b, + 0x00, 0x2b, 0x07, 0xdd, 0x18, 0x9b, 0x1b, 0x78, 0x58, 0x07, 0x03, 0xd5, + 0xd4, 0xf8, 0x58, 0x36, 0x04, 0x22, 0x1a, 0x61, 0x94, 0xf8, 0x49, 0x36, + 0x4b, 0xb1, 0x0d, 0x9b, 0x4b, 0xb9, 0x11, 0x99, 0x89, 0x06, 0x0d, 0xd4, + 0xd4, 0xf8, 0x58, 0x36, 0x04, 0x22, 0xda, 0x60, 0x08, 0xe0, 0x0d, 0x9a, + 0x32, 0xb1, 0x19, 0x9b, 0x00, 0x2b, 0x07, 0xdd, 0x18, 0x9b, 0x1b, 0x78, + 0xda, 0x07, 0x03, 0xd5, 0xd4, 0xf8, 0x58, 0x36, 0x04, 0x22, 0x1a, 0x62, + 0x20, 0x46, 0x25, 0xf0, 0x37, 0xdb, 0x23, 0x68, 0x93, 0xf8, 0x46, 0x30, + 0x9b, 0x07, 0x47, 0xd0, 0x0f, 0x9b, 0x00, 0x2b, 0x44, 0xd0, 0x94, 0xf8, + 0x72, 0x32, 0x33, 0xb9, 0x94, 0xf8, 0x74, 0x32, 0x00, 0x2b, 0x3d, 0xd0, + 0xb8, 0xf1, 0x00, 0x0f, 0x3a, 0xd1, 0xb4, 0xf8, 0x26, 0x36, 0x07, 0x99, + 0x03, 0xf4, 0x40, 0x63, 0xa3, 0xf5, 0x40, 0x60, 0x43, 0x42, 0x43, 0xeb, + 0x00, 0x03, 0x11, 0xb9, 0x0d, 0x9a, 0x32, 0xb9, 0x16, 0xe0, 0x07, 0x99, + 0x8a, 0x78, 0x02, 0xf0, 0x03, 0x02, 0x03, 0x2a, 0x05, 0xd1, 0xd4, 0xf8, + 0x58, 0x26, 0x04, 0x21, 0x91, 0x61, 0x07, 0x9a, 0x52, 0xb1, 0x07, 0x99, + 0x8a, 0x78, 0x02, 0xf0, 0x03, 0x02, 0x02, 0x2a, 0x04, 0xd1, 0x1b, 0xb1, + 0xd4, 0xf8, 0x58, 0x26, 0x04, 0x21, 0xd1, 0x62, 0xbb, 0xf1, 0x00, 0x0f, + 0x0f, 0xd0, 0x07, 0x9a, 0x6a, 0xb1, 0x9b, 0xf8, 0x00, 0x10, 0x52, 0x78, + 0x89, 0x07, 0x08, 0xd4, 0x02, 0xf0, 0x04, 0x02, 0xd2, 0xb2, 0x22, 0xb1, + 0x1b, 0xb1, 0xd4, 0xf8, 0x58, 0x36, 0x04, 0x22, 0xda, 0x62, 0x20, 0x46, + 0x25, 0xf0, 0x9c, 0xdb, 0x23, 0x68, 0x93, 0xf8, 0x2f, 0x30, 0xdb, 0xb1, + 0xd4, 0xf8, 0xfc, 0x34, 0x1b, 0x78, 0xbb, 0xb1, 0xb7, 0xb9, 0x20, 0x46, + 0x59, 0x46, 0x2e, 0xf0, 0xeb, 0xde, 0x88, 0xb1, 0x20, 0x46, 0x39, 0x46, + 0x2e, 0xf0, 0xe8, 0xdf, 0x20, 0x46, 0x2e, 0xf0, 0xdb, 0xdf, 0xb4, 0xf8, + 0x26, 0x36, 0x03, 0xf4, 0x40, 0x63, 0xb3, 0xf5, 0x40, 0x6f, 0x03, 0xd1, + 0x20, 0x46, 0x01, 0x21, 0x2e, 0xf0, 0x4c, 0xdf, 0x94, 0xf8, 0x70, 0x32, + 0x00, 0x2b, 0x00, 0xf0, 0x55, 0x83, 0x1d, 0xb1, 0xd5, 0xf8, 0xdc, 0x72, + 0x0a, 0x97, 0x00, 0xe0, 0x0a, 0x95, 0xb8, 0xf1, 0x00, 0x0f, 0x7c, 0xd0, + 0x23, 0x68, 0x93, 0xf8, 0x46, 0x30, 0x9b, 0x07, 0x2e, 0xd0, 0xab, 0x7c, + 0x33, 0xb9, 0x36, 0xb9, 0x20, 0x46, 0x13, 0x99, 0x10, 0x9a, 0x4f, 0xf0, + 0xb5, 0xdf, 0x06, 0x46, 0x26, 0xb3, 0xbb, 0xf1, 0x00, 0x0f, 0x0e, 0xd0, + 0x07, 0x9b, 0x20, 0x46, 0x31, 0x46, 0x5a, 0x46, 0xcd, 0xf8, 0x00, 0x90, + 0x1d, 0xf0, 0xac, 0xd8, 0xb5, 0xf8, 0x34, 0x35, 0x23, 0xf0, 0x20, 0x03, + 0xa5, 0xf8, 0x34, 0x35, 0x0c, 0xe0, 0xab, 0x7c, 0x53, 0xb9, 0x73, 0x68, + 0xdf, 0x03, 0x07, 0xd5, 0x20, 0x46, 0x31, 0x46, 0x5a, 0x46, 0x5b, 0x46, + 0xcd, 0xf8, 0x00, 0xb0, 0x1d, 0xf0, 0x98, 0xd8, 0x20, 0x46, 0x0b, 0x99, + 0x0c, 0x9a, 0x33, 0x46, 0x1f, 0xf0, 0x82, 0xde, 0x0e, 0x99, 0x20, 0x46, + 0x1d, 0xf0, 0x64, 0xdf, 0x01, 0x46, 0x28, 0x46, 0x1d, 0xf0, 0xa2, 0xdf, + 0x28, 0x46, 0x1d, 0xf0, 0xf7, 0xde, 0x0e, 0x99, 0x20, 0x46, 0x11, 0xf0, + 0xed, 0xdf, 0x01, 0x46, 0x28, 0x46, 0x10, 0xf0, 0x4f, 0xdf, 0xab, 0x79, + 0x83, 0xb9, 0xd5, 0xf8, 0xe0, 0x22, 0xd5, 0xf8, 0xd4, 0x32, 0x11, 0x8a, + 0x92, 0x8a, 0x0a, 0x9f, 0x59, 0x85, 0x9a, 0x85, 0x7b, 0x79, 0x2b, 0xb9, + 0xab, 0x7c, 0x1b, 0xb1, 0x28, 0x46, 0x01, 0x21, 0x35, 0xf0, 0x40, 0xdc, + 0x0a, 0x9f, 0x00, 0x23, 0xbb, 0x71, 0xfb, 0x71, 0x95, 0xf8, 0x12, 0x90, + 0xb9, 0xf1, 0x00, 0x0f, 0x19, 0xd1, 0x97, 0xf8, 0x85, 0x30, 0x01, 0x2b, + 0x15, 0xd1, 0x87, 0xf8, 0x85, 0x90, 0xd4, 0xf8, 0x40, 0x01, 0x26, 0xf0, + 0x01, 0xdd, 0x20, 0x46, 0x29, 0x46, 0x0f, 0x22, 0x4b, 0x46, 0xcd, 0xf8, + 0x00, 0x90, 0xcd, 0xf8, 0x04, 0x90, 0xcd, 0xf8, 0x08, 0x90, 0xcd, 0xf8, + 0x0c, 0x90, 0xcd, 0xf8, 0x10, 0x90, 0x16, 0xf0, 0xe1, 0xdf, 0x00, 0x2d, + 0x59, 0xd0, 0xab, 0x79, 0x00, 0x2b, 0x56, 0xd1, 0xab, 0x7c, 0x00, 0x2b, + 0x53, 0xd0, 0x27, 0x9f, 0xbb, 0x78, 0x7a, 0x78, 0x1b, 0x04, 0x43, 0xea, + 0x02, 0x23, 0x3a, 0x78, 0x13, 0x43, 0xfa, 0x78, 0x43, 0xea, 0x02, 0x62, + 0xbb, 0x79, 0x10, 0x92, 0x7a, 0x79, 0x1b, 0x04, 0x43, 0xea, 0x02, 0x23, + 0x3a, 0x79, 0x13, 0x43, 0xfa, 0x79, 0x0a, 0x9f, 0x43, 0xea, 0x02, 0x69, + 0xfb, 0x69, 0x13, 0xb9, 0x3a, 0x6a, 0x12, 0xb9, 0x32, 0xe0, 0x99, 0x45, + 0x06, 0xd3, 0x99, 0x45, 0x2e, 0xd1, 0x0a, 0x9f, 0x3b, 0x6a, 0x10, 0x9f, + 0x9f, 0x42, 0x29, 0xd2, 0x26, 0x9f, 0x00, 0x23, 0x00, 0x93, 0x01, 0x93, + 0x02, 0x93, 0x03, 0x93, 0x04, 0x93, 0x20, 0x46, 0x07, 0xf1, 0x10, 0x03, + 0x29, 0x46, 0x16, 0x22, 0x16, 0xf0, 0xa6, 0xdf, 0x28, 0x46, 0x0e, 0x99, + 0x12, 0x9a, 0x27, 0x9b, 0x24, 0xf0, 0xa0, 0xdc, 0x0f, 0x9f, 0x9f, 0xb1, + 0xeb, 0x79, 0x4b, 0xb1, 0xab, 0x7c, 0x23, 0xb1, 0x05, 0xf1, 0xbc, 0x00, + 0xfc, 0xf3, 0xb4, 0xf6, 0x10, 0xb9, 0x05, 0xf1, 0xbc, 0x01, 0x01, 0xe0, + 0x05, 0xf1, 0xd6, 0x01, 0x00, 0x22, 0x20, 0x46, 0x13, 0x46, 0x00, 0x92, + 0x22, 0xf0, 0x2c, 0xda, 0x0a, 0x99, 0x10, 0x9f, 0xc1, 0xf8, 0x1c, 0x90, + 0x0f, 0x62, 0xb8, 0xf1, 0x00, 0x0f, 0x00, 0xf0, 0x0d, 0x82, 0xaa, 0x79, + 0xab, 0x7c, 0x00, 0x2a, 0x40, 0xf0, 0x8d, 0x81, 0x00, 0x2b, 0x00, 0xf0, + 0x8a, 0x81, 0x1a, 0xab, 0x00, 0x93, 0x28, 0x9a, 0x28, 0x46, 0x27, 0x99, + 0x0d, 0xf1, 0x6f, 0x03, 0x16, 0xf0, 0x16, 0xd8, 0xbd, 0xf8, 0x68, 0x20, + 0xd5, 0xf8, 0xe4, 0x82, 0xa5, 0xf8, 0x20, 0x25, 0x94, 0xf8, 0xeb, 0x91, + 0xb9, 0xf1, 0x00, 0x0f, 0x67, 0xd1, 0x00, 0x28, 0x4d, 0xd0, 0x98, 0xf8, + 0x00, 0x30, 0x02, 0x2b, 0x1a, 0xd1, 0x28, 0x46, 0x49, 0x46, 0xb8, 0xf8, + 0x26, 0xb0, 0x0a, 0xf0, 0x3c, 0xfb, 0xb4, 0xf8, 0x30, 0x38, 0x84, 0xf8, + 0x32, 0x98, 0x0b, 0xb1, 0xa8, 0xf8, 0x26, 0x30, 0x28, 0x46, 0x1e, 0xf0, + 0xa3, 0xdc, 0xd5, 0xf8, 0xe4, 0x32, 0xa8, 0xf8, 0x26, 0xb0, 0x5b, 0x8b, + 0x00, 0x2b, 0x4a, 0xd0, 0x28, 0x46, 0x10, 0xf0, 0x5f, 0xdf, 0x46, 0xe0, + 0x23, 0x68, 0x5b, 0x6b, 0x3b, 0xb1, 0x94, 0xf8, 0xfa, 0x31, 0x23, 0xb1, + 0xae, 0xb1, 0x96, 0xf8, 0xd2, 0x30, 0x0f, 0x2b, 0x11, 0xd0, 0x98, 0xf8, + 0x02, 0x20, 0x22, 0xb1, 0x20, 0x46, 0x29, 0x46, 0x22, 0xf0, 0xd4, 0xdd, + 0x33, 0xe0, 0x4f, 0xf0, 0xff, 0x33, 0x00, 0x93, 0x20, 0x46, 0x05, 0xf1, + 0xbc, 0x01, 0x13, 0x46, 0x22, 0xf0, 0xca, 0xd9, 0x29, 0xe0, 0x94, 0xf8, + 0x0d, 0x37, 0x33, 0xb3, 0x98, 0xf8, 0x02, 0x30, 0x3b, 0xb1, 0x1e, 0xb1, + 0x73, 0x68, 0x23, 0xf0, 0x00, 0x63, 0x73, 0x60, 0x28, 0x46, 0x16, 0xf0, + 0x9d, 0xd8, 0x28, 0x46, 0x23, 0xf0, 0xba, 0xda, 0x17, 0xe0, 0x98, 0xf8, + 0x08, 0x30, 0x2b, 0xb1, 0xb8, 0xf8, 0x0a, 0x10, 0x11, 0xb9, 0x28, 0x46, + 0x23, 0xf0, 0xde, 0xda, 0xd5, 0xf8, 0xe4, 0x32, 0x5b, 0x8b, 0x53, 0xb1, + 0x98, 0xf8, 0x00, 0x30, 0x02, 0x2b, 0x06, 0xd1, 0xd8, 0xf8, 0x20, 0x30, + 0x01, 0x2b, 0x02, 0xd1, 0x28, 0x46, 0x1e, 0xf0, 0x3d, 0xdc, 0x98, 0xf8, + 0x03, 0x30, 0x1b, 0xb1, 0x28, 0x46, 0x00, 0x21, 0x23, 0xf0, 0xbc, 0xd9, + 0x98, 0xf8, 0x09, 0x30, 0x3b, 0xb9, 0x28, 0x46, 0x0d, 0xf0, 0x82, 0xde, + 0x18, 0xb1, 0x28, 0x46, 0x01, 0x21, 0x23, 0xf0, 0xa9, 0xdb, 0x98, 0xf8, + 0x09, 0x30, 0x5b, 0xb1, 0x14, 0x9f, 0x28, 0x46, 0xc7, 0xf3, 0xc0, 0x11, + 0x15, 0x9a, 0x27, 0x9b, 0x24, 0xf0, 0x86, 0xdb, 0x28, 0x46, 0x00, 0x21, + 0x23, 0xf0, 0x9a, 0xdb, 0x23, 0x6b, 0x5b, 0x7d, 0x00, 0x2b, 0x38, 0xd0, + 0x11, 0x9f, 0x20, 0x46, 0xc7, 0xf3, 0x80, 0x21, 0x24, 0xf0, 0x9a, 0xda, + 0x18, 0x9a, 0x00, 0x2a, 0x2f, 0xd0, 0x19, 0x9b, 0x00, 0x2b, 0x2c, 0xdd, + 0xd4, 0xf8, 0x58, 0x36, 0x93, 0xf9, 0x01, 0x10, 0x01, 0x31, 0x09, 0xd1, + 0x12, 0x78, 0x1b, 0x78, 0xc2, 0xf3, 0x40, 0x02, 0x93, 0x42, 0x03, 0xd0, + 0x20, 0x46, 0x01, 0x21, 0x1f, 0xf0, 0xe6, 0xdd, 0x18, 0x9b, 0x1b, 0x78, + 0xc3, 0xf3, 0x80, 0x03, 0x84, 0xf8, 0x46, 0x36, 0x3b, 0xb9, 0xd4, 0xf8, + 0x58, 0x36, 0x1b, 0x69, 0xd3, 0xf1, 0x01, 0x03, 0x38, 0xbf, 0x00, 0x23, + 0x00, 0xe0, 0x00, 0x23, 0x84, 0xf8, 0x42, 0x36, 0x4e, 0xb1, 0x73, 0x68, + 0x23, 0xf0, 0x04, 0x03, 0x73, 0x60, 0x94, 0xf9, 0x46, 0x26, 0x12, 0xb9, + 0x43, 0xf0, 0x04, 0x03, 0x73, 0x60, 0x23, 0x68, 0x93, 0xf8, 0x46, 0x30, + 0x98, 0x07, 0x33, 0xd0, 0x07, 0x9f, 0x00, 0x2f, 0x30, 0xd0, 0xd4, 0xf8, + 0x58, 0x36, 0x93, 0xf9, 0x06, 0x20, 0x51, 0x1c, 0x25, 0xd1, 0xba, 0x78, + 0x93, 0xf9, 0x05, 0x30, 0x02, 0xf0, 0x03, 0x02, 0x93, 0x42, 0x03, 0xd0, + 0x20, 0x46, 0x0b, 0x21, 0x1f, 0xf0, 0xb0, 0xdd, 0x07, 0x9f, 0xd4, 0xf8, + 0x58, 0x36, 0xba, 0x78, 0xdb, 0x79, 0xc2, 0xf3, 0x80, 0x02, 0x93, 0x42, + 0x03, 0xd0, 0x20, 0x46, 0x0d, 0x21, 0x1f, 0xf0, 0xa3, 0xdd, 0x07, 0x9f, + 0xd4, 0xf8, 0x58, 0x36, 0xba, 0x78, 0x9b, 0x7a, 0xc2, 0xf3, 0x00, 0x12, + 0x93, 0x42, 0x09, 0xd0, 0x20, 0x46, 0x10, 0x21, 0x1f, 0xf0, 0x96, 0xdd, + 0x04, 0xe0, 0x01, 0x2a, 0x0c, 0xbf, 0x03, 0x22, 0x00, 0x22, 0x5a, 0x71, + 0xd4, 0xf8, 0x5c, 0x01, 0xb4, 0xf8, 0x26, 0x16, 0x40, 0xf0, 0x68, 0xd8, + 0x90, 0xb1, 0xd4, 0xf8, 0x5c, 0x01, 0xb4, 0xf8, 0x26, 0x16, 0x3f, 0xf0, + 0xa1, 0xdc, 0x23, 0x6b, 0x18, 0x69, 0x0b, 0xf0, 0x27, 0xfb, 0xb4, 0xf8, + 0x26, 0x36, 0x83, 0x42, 0x04, 0xd1, 0x00, 0x21, 0x20, 0x46, 0x0a, 0x46, + 0x1e, 0xf0, 0x8a, 0xd8, 0x00, 0x2e, 0x42, 0xd0, 0x73, 0x68, 0x5b, 0x06, + 0x40, 0xf1, 0x27, 0x81, 0x0b, 0x9f, 0x16, 0x97, 0x0c, 0x9f, 0x17, 0x97, + 0x06, 0xe0, 0x20, 0x46, 0x39, 0x46, 0x16, 0xaa, 0x17, 0xab, 0x1d, 0xf0, + 0x5b, 0xdb, 0x40, 0xb9, 0x16, 0x98, 0x17, 0x99, 0xdd, 0x22, 0xfc, 0xf3, + 0x05, 0xf4, 0x07, 0x46, 0x00, 0x28, 0xf0, 0xd1, 0x0a, 0xe1, 0xbb, 0x79, + 0x01, 0x2b, 0x40, 0xf0, 0x0e, 0x81, 0x94, 0xf8, 0x0c, 0x22, 0x3b, 0x7a, + 0x53, 0x40, 0x18, 0x07, 0x00, 0xf0, 0x07, 0x81, 0x04, 0xf5, 0x00, 0x79, + 0x09, 0xf1, 0x06, 0x08, 0x40, 0x46, 0xb9, 0x1c, 0x18, 0x22, 0xfc, 0xf3, + 0x4b, 0xf0, 0x23, 0x68, 0x93, 0xf8, 0x30, 0x30, 0x00, 0x2b, 0x00, 0xf0, + 0xf4, 0x80, 0xd4, 0xf8, 0x34, 0x77, 0x43, 0x46, 0x07, 0xf5, 0x63, 0x77, + 0x09, 0xf1, 0x1e, 0x09, 0x18, 0x68, 0x59, 0x68, 0x3a, 0x46, 0x03, 0xc2, + 0x08, 0x33, 0x4b, 0x45, 0x17, 0x46, 0xf7, 0xd1, 0xe3, 0xe0, 0x20, 0x46, + 0x0b, 0x99, 0x0c, 0x9a, 0x10, 0xf0, 0x7a, 0xd9, 0x01, 0x28, 0x02, 0xd1, + 0x20, 0x46, 0x0d, 0xf0, 0x0b, 0xdf, 0xba, 0xf1, 0x00, 0x0f, 0x00, 0xf0, + 0xe7, 0x80, 0x94, 0xf8, 0x6d, 0x35, 0x00, 0x2b, 0x40, 0xf0, 0xe2, 0x80, + 0x20, 0x46, 0x51, 0x46, 0x17, 0xf0, 0xcc, 0xdd, 0xdc, 0xe0, 0x00, 0x2b, + 0x78, 0xd1, 0x0d, 0x9f, 0x1f, 0xb9, 0x11, 0x9f, 0xc7, 0xf3, 0x40, 0x15, + 0x00, 0xe0, 0x01, 0x25, 0xed, 0xb2, 0x9e, 0xb1, 0x73, 0x68, 0x15, 0xb1, + 0x43, 0xf0, 0x04, 0x03, 0x01, 0xe0, 0x23, 0xf0, 0x04, 0x03, 0x73, 0x60, + 0x0c, 0x99, 0x00, 0x23, 0x65, 0x4a, 0x0b, 0x98, 0x00, 0x93, 0x1c, 0xf0, + 0xc9, 0xd9, 0x31, 0x46, 0x02, 0x46, 0x20, 0x46, 0x1f, 0xf0, 0x02, 0xdc, + 0x23, 0x6b, 0x5b, 0x7d, 0xfb, 0xb1, 0x19, 0x9b, 0x00, 0x2b, 0x0e, 0xdd, + 0x18, 0x9b, 0x1a, 0x78, 0x51, 0x07, 0x03, 0xd5, 0xd4, 0xf8, 0x58, 0x26, + 0x04, 0x21, 0x11, 0x61, 0x1b, 0x78, 0x9a, 0x07, 0x03, 0xd5, 0xd4, 0xf8, + 0x58, 0x36, 0x04, 0x22, 0x5a, 0x62, 0x0d, 0x9f, 0x1f, 0xb9, 0xd4, 0xf8, + 0x58, 0x36, 0x04, 0x22, 0xda, 0x61, 0x1d, 0xb9, 0xd4, 0xf8, 0x58, 0x36, + 0x04, 0x22, 0xda, 0x60, 0x20, 0x46, 0x25, 0xf0, 0x0b, 0xd8, 0x23, 0x68, + 0x93, 0xf8, 0x46, 0x30, 0x9b, 0x07, 0x00, 0xf0, 0x95, 0x80, 0x07, 0x9f, + 0x47, 0xb1, 0xbb, 0x78, 0x03, 0xf0, 0x03, 0x03, 0x03, 0x2b, 0x03, 0xd1, + 0xd4, 0xf8, 0x58, 0x36, 0x04, 0x22, 0x9a, 0x62, 0xbb, 0xf1, 0x00, 0x0f, + 0x18, 0xd0, 0x9b, 0xf8, 0x01, 0x10, 0x9b, 0xf8, 0x00, 0x30, 0xb4, 0xf8, + 0x26, 0x26, 0x43, 0xea, 0x01, 0x23, 0xdf, 0x06, 0x03, 0xd4, 0xd4, 0xf8, + 0x58, 0x16, 0x04, 0x20, 0x48, 0x63, 0x98, 0x07, 0x08, 0xd4, 0x02, 0xf4, + 0x40, 0x63, 0xb3, 0xf5, 0x40, 0x6f, 0x03, 0xd1, 0xd4, 0xf8, 0x58, 0x36, + 0x04, 0x22, 0x1a, 0x63, 0x07, 0x9f, 0x2f, 0xb9, 0x0d, 0x9f, 0x1f, 0xb1, + 0xd4, 0xf8, 0x58, 0x36, 0x04, 0x22, 0x5a, 0x61, 0x20, 0x46, 0x25, 0xf0, + 0x85, 0xd8, 0x61, 0xe0, 0x94, 0xf8, 0x57, 0x35, 0x00, 0x2b, 0x5d, 0xd0, + 0x0f, 0x9f, 0x00, 0x2f, 0x5a, 0xd0, 0x11, 0x9f, 0xb9, 0x07, 0x57, 0xd5, + 0x0b, 0x98, 0x0c, 0x99, 0x00, 0x22, 0xfc, 0xf3, 0x35, 0xf3, 0x03, 0x46, + 0x00, 0x28, 0x4f, 0xd0, 0x20, 0x46, 0x99, 0x1c, 0x5a, 0x78, 0x39, 0xf0, + 0x81, 0xd9, 0x05, 0x46, 0x00, 0x28, 0x47, 0xd0, 0x83, 0x7c, 0x00, 0x2b, + 0x44, 0xd1, 0x0e, 0x99, 0x12, 0x9a, 0x16, 0xf0, 0xc7, 0xdb, 0x00, 0x28, + 0x3e, 0xd0, 0x27, 0x9f, 0xd5, 0xf8, 0xd0, 0x62, 0x00, 0x97, 0x28, 0x9f, + 0x20, 0x46, 0x01, 0x97, 0x26, 0x9f, 0x0e, 0x99, 0x07, 0xf1, 0x10, 0x02, + 0x01, 0x23, 0x02, 0x96, 0xfe, 0xf7, 0xe4, 0xfd, 0x02, 0x46, 0x00, 0x28, + 0x2c, 0xd1, 0x21, 0x6b, 0xd4, 0xf8, 0x60, 0x36, 0x50, 0x31, 0x06, 0xf1, + 0x38, 0x00, 0x9b, 0x78, 0x4a, 0xf0, 0x66, 0xdf, 0x28, 0x9f, 0x28, 0x46, + 0x0e, 0x99, 0x12, 0x9a, 0x27, 0x9b, 0x00, 0x97, 0x34, 0xf0, 0x46, 0xda, + 0x1a, 0xe0, 0x4f, 0xf0, 0x00, 0x0a, 0x12, 0xe4, 0x4f, 0xf0, 0x00, 0x0a, + 0xd0, 0x46, 0x10, 0xe4, 0x02, 0x23, 0x84, 0xf8, 0x0e, 0x32, 0x28, 0x46, + 0x01, 0x21, 0x1b, 0xf0, 0x61, 0xde, 0x00, 0x23, 0x0c, 0x99, 0x0b, 0x98, + 0x06, 0x4a, 0x00, 0x93, 0x1c, 0xf0, 0x0c, 0xd9, 0x31, 0x46, 0x02, 0x46, + 0x20, 0x46, 0x1f, 0xf0, 0x45, 0xdb, 0x0a, 0xe7, 0x1d, 0xb0, 0xbd, 0xe8, + 0xf0, 0x8f, 0x00, 0xbf, 0xc5, 0xb6, 0x01, 0x00, 0x2d, 0xe9, 0xf0, 0x4f, + 0x17, 0x69, 0xc1, 0xb0, 0xd7, 0xf8, 0xd8, 0x82, 0x04, 0x46, 0x8b, 0x46, + 0x92, 0x46, 0xd8, 0xf8, 0x2c, 0x00, 0xd8, 0xf8, 0x30, 0x10, 0x00, 0x22, + 0x0f, 0x93, 0xfc, 0xf3, 0xcb, 0xf2, 0x20, 0xb1, 0x81, 0x1c, 0x40, 0x78, + 0x10, 0x91, 0x0d, 0x90, 0x05, 0xe0, 0x9b, 0xf8, 0x08, 0x30, 0x0b, 0xf1, + 0x09, 0x02, 0x10, 0x92, 0x0d, 0x93, 0x00, 0x21, 0x28, 0x22, 0x22, 0xa8, + 0xfb, 0xf3, 0x7c, 0xf7, 0x00, 0x21, 0x28, 0x22, 0x2c, 0xa8, 0xfb, 0xf3, + 0x77, 0xf7, 0xd8, 0xf8, 0x30, 0x10, 0x01, 0x22, 0xd8, 0xf8, 0x2c, 0x00, + 0xfc, 0xf3, 0xae, 0xf2, 0xd8, 0xf8, 0x30, 0x10, 0x05, 0x46, 0x32, 0x22, + 0xd8, 0xf8, 0x2c, 0x00, 0xfc, 0xf3, 0xa6, 0xf2, 0x06, 0x46, 0x3d, 0xb1, + 0x6a, 0x78, 0x10, 0x2a, 0x04, 0xd8, 0x23, 0xa8, 0xa9, 0x1c, 0x22, 0x92, + 0xfb, 0xf3, 0xfa, 0xf6, 0x3e, 0xb1, 0x72, 0x78, 0x10, 0x2a, 0x04, 0xd8, + 0x2d, 0xa8, 0xb1, 0x1c, 0x2c, 0x92, 0xfb, 0xf3, 0xf1, 0xf6, 0xbb, 0xf8, + 0x06, 0x30, 0xd9, 0x07, 0x0b, 0xd5, 0x21, 0x6b, 0x4b, 0x7d, 0x43, 0xb1, + 0x0a, 0x6d, 0x23, 0xa8, 0x54, 0x31, 0x22, 0x92, 0xfb, 0xf3, 0xe4, 0xf6, + 0x00, 0x23, 0x2c, 0x93, 0x08, 0xe0, 0x2c, 0xab, 0x00, 0x93, 0x20, 0x46, + 0x39, 0x46, 0x0b, 0xf1, 0x38, 0x02, 0x22, 0xab, 0x1f, 0xf0, 0x42, 0xde, + 0xb7, 0xf8, 0x62, 0x50, 0xd8, 0xf8, 0x2c, 0x60, 0xb5, 0xf5, 0x80, 0x6f, + 0xd8, 0xf8, 0x30, 0x90, 0x5e, 0xd0, 0xb5, 0xf5, 0x00, 0x6f, 0x5b, 0xd0, + 0x30, 0x46, 0x49, 0x46, 0xfd, 0xf3, 0x76, 0xf0, 0x09, 0x90, 0x18, 0xb1, + 0x41, 0x78, 0x00, 0x26, 0x08, 0x91, 0x0a, 0xe0, 0x30, 0x46, 0x49, 0x46, + 0x30, 0x22, 0xfc, 0xf3, 0x5f, 0xf2, 0x06, 0x46, 0x10, 0xb1, 0x42, 0x78, + 0x08, 0x92, 0x00, 0xe0, 0x08, 0x90, 0x80, 0x2d, 0x0a, 0xd0, 0x03, 0xd8, + 0x10, 0x2d, 0x07, 0xd0, 0x40, 0x2d, 0x04, 0xe0, 0xb5, 0xf5, 0x80, 0x7f, + 0x02, 0xd0, 0xb5, 0xf5, 0x00, 0x7f, 0x37, 0xd1, 0xba, 0x6d, 0x40, 0xf2, + 0x37, 0x13, 0x13, 0x40, 0x00, 0x2b, 0x36, 0xd0, 0x08, 0x9b, 0x00, 0x2e, + 0x08, 0xbf, 0x14, 0x23, 0x40, 0x2d, 0x08, 0x93, 0x1c, 0xd0, 0x00, 0x21, + 0x07, 0x91, 0x3a, 0xe0, 0x16, 0x26, 0x06, 0xfb, 0x05, 0x76, 0x06, 0xf5, + 0xb4, 0x76, 0x58, 0x46, 0x31, 0x1d, 0x06, 0x22, 0xcd, 0xf8, 0x18, 0xc0, + 0xfb, 0xf3, 0x72, 0xf6, 0xdd, 0xf8, 0x18, 0xc0, 0x40, 0xb9, 0x07, 0x9b, + 0x40, 0xa9, 0x01, 0xeb, 0x83, 0x02, 0x0a, 0x36, 0x01, 0x33, 0x42, 0xf8, + 0xb8, 0x6c, 0x07, 0x93, 0x01, 0x35, 0x05, 0xe0, 0x00, 0x23, 0xc1, 0x46, + 0x07, 0x93, 0xa8, 0x46, 0xb4, 0x46, 0x1d, 0x46, 0xd7, 0xf8, 0xcc, 0x22, + 0x95, 0x42, 0xdb, 0xd3, 0x45, 0x46, 0x66, 0x46, 0xc8, 0x46, 0x12, 0xe0, + 0x85, 0xb1, 0x02, 0xe0, 0x00, 0x26, 0x09, 0x96, 0x08, 0x96, 0xba, 0x6d, + 0x40, 0xf2, 0x37, 0x13, 0x13, 0x40, 0x08, 0x9a, 0x00, 0x2b, 0x18, 0xbf, + 0x00, 0x23, 0x18, 0xbf, 0x18, 0x22, 0x07, 0x93, 0x08, 0x92, 0x00, 0xe0, + 0x07, 0x95, 0x40, 0xf2, 0xee, 0x53, 0x01, 0x93, 0x3f, 0xab, 0x02, 0x93, + 0x0f, 0x9b, 0x20, 0x46, 0x00, 0x2b, 0x14, 0xbf, 0x20, 0x21, 0x00, 0x21, + 0x5a, 0x46, 0x07, 0xf1, 0xc2, 0x03, 0xcd, 0xf8, 0x00, 0xb0, 0x1c, 0xf0, + 0x6d, 0xd8, 0x0a, 0x90, 0x30, 0xb9, 0x20, 0x46, 0x0a, 0x99, 0xb7, 0xf8, + 0x0c, 0x23, 0x32, 0xf0, 0xf7, 0xdb, 0x6f, 0xe2, 0x3f, 0x99, 0x20, 0x46, + 0x01, 0xf5, 0xbc, 0x62, 0x0e, 0x32, 0xa1, 0xf1, 0x18, 0x03, 0x0b, 0x91, + 0x0c, 0x92, 0x39, 0x46, 0x5a, 0x46, 0x11, 0x93, 0xfe, 0xf7, 0xa6, 0xfb, + 0x0b, 0x99, 0x08, 0x80, 0xb8, 0xf8, 0x22, 0x30, 0x4b, 0x80, 0x0f, 0x9a, + 0x0b, 0x1d, 0x3f, 0x93, 0x8a, 0xb1, 0x08, 0xf1, 0x24, 0x09, 0x48, 0x46, + 0xfc, 0xf3, 0x18, 0xf3, 0x10, 0xb9, 0x3f, 0x98, 0x49, 0x46, 0x02, 0xe0, + 0x3f, 0x98, 0x07, 0xf1, 0xd6, 0x01, 0x06, 0x22, 0xfb, 0xf3, 0x1e, 0xf6, + 0x3f, 0x9b, 0x06, 0x33, 0x3f, 0x93, 0x3f, 0x9b, 0x00, 0x21, 0x0e, 0x93, + 0x18, 0x46, 0x0d, 0x9a, 0x10, 0x9b, 0x25, 0xf0, 0x0b, 0xdf, 0x01, 0x21, + 0x22, 0x9a, 0x23, 0xab, 0x3f, 0x90, 0x25, 0xf0, 0x05, 0xdf, 0x08, 0x99, + 0x81, 0x46, 0x3f, 0x90, 0x00, 0x29, 0x00, 0xf0, 0x84, 0x80, 0x86, 0xb1, + 0x07, 0x9a, 0x1a, 0xb1, 0x20, 0x46, 0x31, 0x46, 0xfe, 0xf7, 0x99, 0xfb, + 0xdd, 0xf8, 0xfc, 0x90, 0x31, 0x46, 0x48, 0x46, 0x17, 0xf0, 0xc4, 0xd9, + 0x3f, 0x90, 0x73, 0x78, 0x89, 0xf8, 0x01, 0x30, 0x19, 0xe0, 0x80, 0x2d, + 0x0a, 0xd0, 0x03, 0xd8, 0x10, 0x2d, 0x07, 0xd0, 0x40, 0x2d, 0x04, 0xe0, + 0xb5, 0xf5, 0x80, 0x7f, 0x02, 0xd0, 0xb5, 0xf5, 0x00, 0x7f, 0x0d, 0xd1, + 0x90, 0x49, 0x48, 0x46, 0x17, 0xf0, 0xae, 0xd9, 0x39, 0x46, 0x3f, 0x90, + 0x0b, 0xf1, 0x7b, 0x02, 0x20, 0x46, 0x09, 0xf1, 0x04, 0x03, 0x13, 0xf0, + 0x13, 0xd8, 0x4e, 0x46, 0x80, 0x2d, 0x0a, 0xd0, 0x03, 0xd8, 0x10, 0x2d, + 0x07, 0xd0, 0x40, 0x2d, 0x04, 0xe0, 0xb5, 0xf5, 0x80, 0x7f, 0x02, 0xd0, + 0xb5, 0xf5, 0x00, 0x7f, 0x49, 0xd1, 0x07, 0x9b, 0x00, 0x2b, 0x2e, 0xd0, + 0x73, 0x78, 0x07, 0x9a, 0xf3, 0x18, 0x9a, 0x70, 0x99, 0x1c, 0x13, 0x0a, + 0x4b, 0x70, 0x73, 0x78, 0x0d, 0xf1, 0x44, 0x0c, 0x02, 0x33, 0x73, 0x70, + 0x3f, 0x9b, 0x0d, 0x91, 0x02, 0x33, 0x3f, 0x93, 0x4f, 0xf0, 0x00, 0x09, + 0x3b, 0x46, 0x2f, 0x46, 0x65, 0x46, 0x12, 0xe0, 0x0d, 0x99, 0x10, 0x22, + 0x01, 0xeb, 0x09, 0x10, 0x02, 0x30, 0x55, 0xf8, 0x04, 0x1f, 0x06, 0x93, + 0xfb, 0xf3, 0xaa, 0xf5, 0x72, 0x78, 0x09, 0xf1, 0x01, 0x09, 0x10, 0x32, + 0x72, 0x70, 0x3f, 0x9a, 0x06, 0x9b, 0x10, 0x32, 0x3f, 0x92, 0x07, 0x9a, + 0x91, 0x45, 0xe9, 0xd1, 0x3d, 0x46, 0x1f, 0x46, 0x01, 0xe0, 0xdd, 0xf8, + 0x1c, 0x90, 0xd4, 0xf8, 0x6c, 0x32, 0xd3, 0xf8, 0xd8, 0x32, 0x5b, 0x68, + 0x02, 0x2b, 0x0e, 0xd1, 0xb9, 0xf1, 0x00, 0x0f, 0x0b, 0xd0, 0x00, 0x22, + 0x00, 0x92, 0x01, 0x92, 0x02, 0x96, 0x73, 0x78, 0x20, 0x46, 0x02, 0x33, + 0x03, 0x93, 0x57, 0x21, 0x13, 0x46, 0x1d, 0xf0, 0x1f, 0xdb, 0x2c, 0x9a, + 0x2a, 0xb1, 0x3f, 0x98, 0x32, 0x21, 0x2d, 0xab, 0x25, 0xf0, 0x74, 0xde, + 0x3f, 0x90, 0x43, 0x46, 0xd8, 0xf8, 0x2c, 0x60, 0xb8, 0x46, 0x1f, 0x46, + 0x1a, 0xe0, 0x72, 0x78, 0x71, 0x1a, 0x02, 0x31, 0x89, 0x18, 0x99, 0x42, + 0x1a, 0xd8, 0x09, 0x9b, 0xb3, 0x42, 0x17, 0xd0, 0x33, 0x78, 0x01, 0x2b, + 0x0b, 0xd9, 0x30, 0x2b, 0x09, 0xd0, 0x02, 0x32, 0x3f, 0x98, 0x31, 0x46, + 0xfb, 0xf3, 0x62, 0xf5, 0x73, 0x78, 0x3f, 0x9a, 0x02, 0x33, 0xd3, 0x18, + 0x3f, 0x93, 0x73, 0x78, 0x02, 0x33, 0xf6, 0x18, 0x26, 0xb1, 0xf9, 0x6a, + 0x3b, 0x6b, 0xca, 0x18, 0x96, 0x42, 0xde, 0xd3, 0x3b, 0x46, 0x47, 0x46, + 0x98, 0x46, 0x23, 0x68, 0x93, 0xf8, 0x46, 0x30, 0x9a, 0x07, 0x17, 0xd0, + 0xda, 0xf8, 0x04, 0x30, 0xdb, 0x03, 0x13, 0xd5, 0x22, 0x6b, 0x38, 0x46, + 0x13, 0x68, 0x65, 0x32, 0xa3, 0xf1, 0x02, 0x0e, 0xde, 0xf1, 0x00, 0x03, + 0x43, 0xeb, 0x0e, 0x03, 0x36, 0xa9, 0x25, 0xf0, 0x95, 0xdd, 0x3f, 0x98, + 0x2d, 0x21, 0x1a, 0x22, 0x36, 0xab, 0x25, 0xf0, 0x2d, 0xde, 0x3f, 0x90, + 0x94, 0xf8, 0x65, 0x36, 0x33, 0xb1, 0x04, 0xf5, 0xcc, 0x61, 0x3f, 0x98, + 0x04, 0x31, 0x17, 0xf0, 0xf5, 0xd8, 0x3f, 0x90, 0x23, 0x68, 0x93, 0xf8, + 0x46, 0x30, 0x9a, 0x07, 0x1d, 0xd0, 0xda, 0xf8, 0x04, 0x30, 0xdb, 0x03, + 0x19, 0xd5, 0x22, 0x6b, 0x38, 0x46, 0x13, 0x68, 0x65, 0x32, 0xa3, 0xf1, + 0x02, 0x0e, 0xde, 0xf1, 0x00, 0x03, 0x43, 0xeb, 0x0e, 0x03, 0x36, 0xa9, + 0x25, 0xf0, 0x6e, 0xdd, 0x0c, 0x9a, 0x3f, 0x99, 0x20, 0x46, 0x8a, 0x42, + 0x28, 0xbf, 0xc1, 0xeb, 0x02, 0x02, 0x36, 0xab, 0x38, 0xbf, 0x00, 0x22, + 0x25, 0xf0, 0x20, 0xdc, 0x3f, 0x90, 0x23, 0x68, 0x5b, 0x6b, 0x2b, 0xb3, + 0xbb, 0xf8, 0x06, 0x30, 0x5b, 0x07, 0x21, 0xd5, 0x03, 0x22, 0x3d, 0xa8, + 0x1c, 0x49, 0xfb, 0xf3, 0xfb, 0xf4, 0x01, 0x22, 0x02, 0x23, 0x8d, 0xf8, + 0xf9, 0x20, 0x94, 0xf8, 0xfa, 0x21, 0x8d, 0xf8, 0xf7, 0x30, 0x00, 0x23, + 0x8d, 0xf8, 0xf8, 0x30, 0x32, 0xb1, 0x9b, 0xf9, 0x6a, 0x20, 0x9a, 0x42, + 0x03, 0xda, 0x94, 0xf8, 0x0a, 0x37, 0x00, 0xe0, 0x13, 0x46, 0x8d, 0xf8, + 0xfa, 0x30, 0x3f, 0x98, 0xdd, 0x21, 0x07, 0x22, 0x3d, 0xab, 0x25, 0xf0, + 0xd7, 0xdd, 0x3f, 0x90, 0xb5, 0xf5, 0x80, 0x6f, 0x02, 0xd0, 0xb5, 0xf5, + 0x00, 0x6f, 0x07, 0xd1, 0xd7, 0xf8, 0x2c, 0x35, 0x00, 0x2b, 0x2b, 0xd0, + 0x3f, 0x98, 0xd7, 0xf8, 0x28, 0x15, 0x04, 0xe0, 0x08, 0x9b, 0x2b, 0xb3, + 0x09, 0x99, 0x49, 0xb1, 0x3f, 0x98, 0x17, 0xf0, 0x93, 0xd8, 0x3f, 0x90, + 0x1e, 0xe0, 0x00, 0xbf, 0xcc, 0xd2, 0x85, 0x00, 0xd1, 0xb6, 0x01, 0x00, + 0x40, 0x2d, 0x17, 0xd0, 0x80, 0x2d, 0x15, 0xd0, 0x10, 0x2d, 0x13, 0xd0, + 0xb5, 0xf5, 0x80, 0x7f, 0x10, 0xd0, 0xb5, 0xf5, 0x00, 0x7f, 0x0d, 0xd0, + 0x3f, 0x9e, 0x72, 0x49, 0x30, 0x46, 0x17, 0xf0, 0x7b, 0xd8, 0x39, 0x46, + 0x3f, 0x90, 0x0b, 0xf1, 0x6b, 0x02, 0x20, 0x46, 0x06, 0xf1, 0x08, 0x03, + 0x12, 0xf0, 0xe0, 0xde, 0x6b, 0x1e, 0x9b, 0xb2, 0x01, 0x2b, 0x03, 0xd9, + 0x04, 0x2d, 0x01, 0xd0, 0x08, 0x2d, 0x0a, 0xd1, 0xdb, 0xf8, 0x64, 0x00, + 0x00, 0x28, 0x33, 0xd0, 0xbb, 0xf8, 0x68, 0x10, 0x0c, 0x30, 0x0c, 0x39, + 0xfc, 0xf3, 0x44, 0xf6, 0x16, 0xe0, 0x80, 0x2d, 0x0a, 0xd0, 0x03, 0xd8, + 0x10, 0x2d, 0x07, 0xd0, 0x40, 0x2d, 0x04, 0xe0, 0xb5, 0xf5, 0x80, 0x7f, + 0x02, 0xd0, 0xb5, 0xf5, 0x00, 0x7f, 0x1f, 0xd1, 0xdb, 0xf8, 0x64, 0x00, + 0xe0, 0xb1, 0xbb, 0xf8, 0x68, 0x10, 0x0c, 0x30, 0x0c, 0x39, 0x30, 0x22, + 0xfc, 0xf3, 0x20, 0xf0, 0xa0, 0xb1, 0xd4, 0xf8, 0x6c, 0x32, 0xd3, 0xf8, + 0xd8, 0x32, 0x5b, 0x68, 0x02, 0x2b, 0x0d, 0xd1, 0x43, 0x78, 0x10, 0x2b, + 0x0a, 0xd9, 0x02, 0x33, 0x00, 0x22, 0x02, 0x90, 0x03, 0x93, 0x20, 0x46, + 0x57, 0x21, 0x01, 0x23, 0x00, 0x92, 0x01, 0x92, 0x1d, 0xf0, 0x04, 0xda, + 0xbb, 0x6d, 0x58, 0x07, 0x01, 0xd5, 0x04, 0x23, 0x0c, 0xe0, 0x99, 0x07, + 0x01, 0xd5, 0x02, 0x23, 0x08, 0xe0, 0xda, 0x07, 0x01, 0xd5, 0x01, 0x23, + 0x04, 0xe0, 0x13, 0xf4, 0x80, 0x73, 0x18, 0xbf, 0x4f, 0xf4, 0x80, 0x73, + 0xca, 0xf8, 0x40, 0x30, 0x23, 0x68, 0x93, 0xf8, 0x46, 0x30, 0x9d, 0x07, + 0x2a, 0xd0, 0xda, 0xf8, 0x40, 0x30, 0x01, 0x3b, 0x01, 0x2b, 0x09, 0xd8, + 0xda, 0xf8, 0x04, 0x30, 0x58, 0x03, 0x05, 0xd5, 0x20, 0x46, 0x51, 0x46, + 0x06, 0x22, 0x24, 0xf0, 0xd5, 0xda, 0x1b, 0xe0, 0xda, 0xf8, 0x04, 0x30, + 0x59, 0x03, 0x17, 0xd5, 0x51, 0x46, 0x06, 0x22, 0x20, 0x46, 0x24, 0xf0, + 0x6f, 0xda, 0x20, 0x46, 0x16, 0xf0, 0x9c, 0xdc, 0x01, 0x28, 0x01, 0x46, + 0x0c, 0xd1, 0xd4, 0xf8, 0xf8, 0x37, 0x20, 0x46, 0x1a, 0x88, 0x42, 0xf2, + 0x0e, 0x73, 0x01, 0x3a, 0x92, 0xb2, 0x9a, 0x42, 0x98, 0xbf, 0x00, 0x21, + 0x28, 0xf0, 0xce, 0xdc, 0x0c, 0x9a, 0x3f, 0x9b, 0x38, 0x46, 0x9a, 0x42, + 0x2c, 0xbf, 0xc3, 0xeb, 0x02, 0x02, 0x00, 0x22, 0x00, 0x92, 0x20, 0x22, + 0x01, 0x92, 0x00, 0x21, 0x4f, 0xf0, 0xff, 0x32, 0x04, 0xf0, 0x71, 0xfb, + 0x0e, 0x99, 0x3f, 0x90, 0x40, 0x1a, 0x00, 0x23, 0x03, 0x91, 0x04, 0x90, + 0x39, 0x46, 0x55, 0x22, 0x20, 0x46, 0x00, 0x93, 0x01, 0x93, 0x02, 0x93, + 0x16, 0xf0, 0xd8, 0xd9, 0x3f, 0x9d, 0x11, 0x9a, 0x0a, 0x9b, 0xd8, 0xf8, + 0x34, 0x10, 0xad, 0x1a, 0x9d, 0x82, 0x21, 0xb1, 0x60, 0x68, 0xd8, 0xf8, + 0x38, 0x20, 0x00, 0xf0, 0xb5, 0xda, 0x18, 0x3d, 0x60, 0x68, 0x29, 0x46, + 0x00, 0xf0, 0xa0, 0xda, 0xc8, 0xf8, 0x34, 0x00, 0x40, 0xb1, 0x0f, 0x99, + 0xc8, 0xf8, 0x38, 0x50, 0x88, 0xf8, 0x3c, 0x10, 0x2a, 0x46, 0x0b, 0x99, + 0xfb, 0xf3, 0xe8, 0xf3, 0xbb, 0xf8, 0x62, 0x30, 0x20, 0x46, 0xc3, 0xf3, + 0x40, 0x13, 0x00, 0x93, 0x00, 0x23, 0x01, 0x93, 0x02, 0x93, 0xd4, 0xf8, + 0x04, 0x28, 0x0a, 0x99, 0x53, 0x46, 0x1f, 0xf0, 0xaf, 0xd9, 0x0a, 0x9a, + 0x00, 0x28, 0x08, 0xbf, 0x00, 0x22, 0x0a, 0x92, 0x0a, 0x98, 0x41, 0xb0, + 0xbd, 0xe8, 0xf0, 0x8f, 0xe2, 0xd2, 0x85, 0x00, 0x2d, 0xe9, 0xf0, 0x41, + 0x03, 0x68, 0x04, 0x46, 0x93, 0xf8, 0x3f, 0x30, 0xc5, 0x68, 0x13, 0xb1, + 0xb0, 0xf8, 0x26, 0x66, 0x02, 0xe0, 0xfc, 0xf7, 0xde, 0xfe, 0x06, 0x46, + 0x00, 0x22, 0x20, 0x69, 0x31, 0x46, 0x04, 0xf0, 0x19, 0xfa, 0x56, 0x21, + 0x20, 0x69, 0x36, 0xf0, 0x0b, 0xdf, 0xd4, 0xf8, 0x88, 0x31, 0x40, 0x00, + 0x00, 0x2b, 0xc4, 0xf8, 0x04, 0x05, 0x06, 0xda, 0x20, 0x69, 0xb2, 0x21, + 0x36, 0xf0, 0x00, 0xdf, 0x40, 0x00, 0xc4, 0xf8, 0x08, 0x05, 0xa2, 0x21, + 0x20, 0x69, 0x36, 0xf0, 0xf9, 0xde, 0x40, 0x00, 0xc4, 0xf8, 0xec, 0x07, + 0x20, 0x46, 0x15, 0xf0, 0xbb, 0xdb, 0x94, 0xf8, 0xcd, 0x31, 0x33, 0xb9, + 0x20, 0x69, 0x4c, 0x21, 0x36, 0xf0, 0xec, 0xde, 0xc0, 0x09, 0x84, 0xf8, + 0xcd, 0x01, 0x20, 0x46, 0x20, 0xf0, 0x14, 0xd9, 0x20, 0x46, 0x40, 0xf0, + 0xe5, 0xdd, 0x00, 0x27, 0xe3, 0x19, 0xd3, 0xf8, 0x4c, 0x82, 0xb8, 0xf1, + 0x00, 0x0f, 0x05, 0xd0, 0x40, 0x46, 0x22, 0xf0, 0xc3, 0xda, 0x40, 0x46, + 0x22, 0xf0, 0xb6, 0xd8, 0x04, 0x37, 0x20, 0x2f, 0xf0, 0xd1, 0x23, 0x68, + 0x93, 0xf8, 0x3f, 0x30, 0x93, 0xb1, 0x00, 0x23, 0xe2, 0x18, 0xd2, 0xf8, + 0x4c, 0x02, 0x50, 0xb1, 0x02, 0x79, 0x42, 0xb1, 0xd0, 0xf8, 0xd4, 0x32, + 0xdb, 0x8d, 0x1b, 0x04, 0xc5, 0xf8, 0x88, 0x31, 0x22, 0xf0, 0xe2, 0xdc, + 0x02, 0xe0, 0x04, 0x33, 0x20, 0x2b, 0xed, 0xd1, 0x20, 0x46, 0x31, 0x46, + 0x0c, 0xf0, 0x30, 0xdc, 0x20, 0x46, 0x74, 0x21, 0xb4, 0xf8, 0x7a, 0x25, + 0x25, 0xf0, 0x8c, 0xdc, 0x94, 0xf8, 0xd1, 0x21, 0x42, 0xf2, 0x10, 0x73, + 0x00, 0x2a, 0x0c, 0xbf, 0x1a, 0x46, 0x4f, 0xf4, 0xbc, 0x62, 0x20, 0x46, + 0x82, 0x21, 0x25, 0xf0, 0x7f, 0xdc, 0x23, 0x6b, 0x94, 0xf8, 0xd1, 0x11, + 0x18, 0x69, 0x0b, 0xf0, 0xad, 0xfc, 0x01, 0x22, 0x13, 0x46, 0xb4, 0xf8, + 0x78, 0x17, 0x20, 0x46, 0x0d, 0xf0, 0xe8, 0xdd, 0x01, 0x23, 0xb4, 0xf8, + 0x7a, 0x17, 0x00, 0x22, 0x20, 0x46, 0x0d, 0xf0, 0xe1, 0xdd, 0xd4, 0xf8, + 0x40, 0x01, 0x28, 0xf0, 0x5d, 0xdf, 0x20, 0x46, 0xfe, 0xf7, 0xce, 0xfc, + 0x23, 0x68, 0x5b, 0x6b, 0x5b, 0xb1, 0xb5, 0xf8, 0x88, 0x36, 0xd4, 0xf8, + 0x6c, 0x02, 0x9b, 0xb2, 0x43, 0xf0, 0x04, 0x03, 0xa5, 0xf8, 0x88, 0x36, + 0x00, 0x21, 0x1b, 0xf0, 0x3b, 0xda, 0x20, 0x46, 0xfc, 0xf7, 0x0c, 0xfd, + 0xd4, 0xf8, 0x84, 0x11, 0x61, 0xb9, 0x20, 0x46, 0x1f, 0xf0, 0x12, 0xdc, + 0x05, 0x04, 0xc4, 0xf8, 0x84, 0x51, 0x20, 0x46, 0x02, 0x21, 0x1f, 0xf0, + 0x0b, 0xdc, 0x28, 0x43, 0xc4, 0xf8, 0x84, 0x01, 0x23, 0x68, 0x93, 0xf8, + 0xa1, 0x30, 0x01, 0x2b, 0x03, 0xd1, 0xd4, 0xf8, 0x40, 0x01, 0x2a, 0xf0, + 0x1b, 0xd8, 0x20, 0x46, 0x1b, 0xf0, 0x4c, 0xdb, 0x20, 0x46, 0x0b, 0xf0, + 0x3b, 0xdf, 0xb4, 0xf8, 0x5c, 0x17, 0x20, 0x46, 0x20, 0xf0, 0xd2, 0xd8, + 0x20, 0x46, 0x13, 0xf0, 0x89, 0xdd, 0x00, 0x23, 0x84, 0xf8, 0x44, 0x30, + 0x45, 0x4a, 0xe3, 0x68, 0xc3, 0xf8, 0xdc, 0x23, 0x01, 0x23, 0x84, 0xf8, + 0xa8, 0x31, 0x84, 0xf8, 0xaa, 0x31, 0x23, 0x68, 0x93, 0xf8, 0x38, 0x30, + 0x1b, 0xb9, 0x25, 0x46, 0x26, 0x46, 0x00, 0x27, 0x11, 0xe0, 0xff, 0x23, + 0x84, 0xf8, 0x95, 0x38, 0x84, 0xf8, 0x96, 0x38, 0x84, 0xf8, 0x97, 0x38, + 0x84, 0xf8, 0x98, 0x38, 0x84, 0xf8, 0x99, 0x38, 0x84, 0xf8, 0x9a, 0x38, + 0x84, 0xf8, 0x9b, 0x38, 0x84, 0xf8, 0x9c, 0x38, 0xe9, 0xe7, 0x07, 0xf5, + 0x40, 0x71, 0x20, 0x46, 0x1f, 0xf0, 0xc6, 0xdb, 0xb6, 0xf8, 0x20, 0x32, + 0x19, 0x07, 0x06, 0xd1, 0x23, 0xf0, 0x0f, 0x03, 0x00, 0xf0, 0x0f, 0x02, + 0x13, 0x43, 0xa6, 0xf8, 0x20, 0x32, 0xb6, 0xf8, 0x20, 0x32, 0x13, 0xf0, + 0xf0, 0x0f, 0x06, 0xd1, 0x23, 0xf0, 0xf0, 0x03, 0x00, 0xf0, 0xf0, 0x02, + 0x13, 0x43, 0xa6, 0xf8, 0x20, 0x32, 0xb6, 0xf8, 0x20, 0x32, 0x13, 0xf4, + 0x70, 0x6f, 0x06, 0xd1, 0x23, 0xf4, 0x70, 0x63, 0x00, 0xf4, 0x70, 0x62, + 0x13, 0x43, 0xa6, 0xf8, 0x20, 0x32, 0xb6, 0xf8, 0x20, 0x32, 0x1a, 0x0b, + 0x08, 0xd1, 0x1b, 0x05, 0x20, 0xf4, 0x7e, 0x60, 0x1b, 0x0d, 0x20, 0xf0, + 0x1f, 0x00, 0x18, 0x43, 0xa6, 0xf8, 0x20, 0x02, 0x02, 0x37, 0x02, 0x36, + 0x08, 0x2f, 0xc6, 0xd1, 0x23, 0x68, 0x20, 0x46, 0x93, 0xf9, 0x4c, 0x10, + 0x0e, 0xf0, 0xf0, 0xdd, 0x23, 0x68, 0x1a, 0x7e, 0xfa, 0xb1, 0x93, 0xf8, + 0x2f, 0x30, 0xe3, 0xb1, 0x04, 0xf1, 0x20, 0x07, 0xd5, 0xf8, 0x4c, 0x62, + 0x6e, 0xb1, 0xb3, 0x79, 0x5b, 0xb1, 0x23, 0x68, 0x93, 0xf8, 0x38, 0x30, + 0x2b, 0xb1, 0x20, 0x46, 0xd6, 0xf8, 0x4c, 0x15, 0x00, 0x22, 0x39, 0xf0, + 0x6d, 0xd9, 0x00, 0x23, 0xf3, 0x71, 0x04, 0x35, 0xbd, 0x42, 0xeb, 0xd1, + 0x00, 0x23, 0x84, 0xf8, 0x72, 0x32, 0xd4, 0xf8, 0x34, 0x07, 0x2e, 0xf0, + 0x43, 0xd9, 0xd4, 0xf8, 0x68, 0x01, 0x04, 0x21, 0xbd, 0xe8, 0xf0, 0x41, + 0x4d, 0xf0, 0x8a, 0x9d, 0x80, 0x96, 0x98, 0x00, 0x2d, 0xe9, 0xf3, 0x41, + 0x08, 0x9c, 0x07, 0x46, 0x0e, 0x46, 0x15, 0x46, 0x98, 0x46, 0x00, 0x94, + 0x08, 0xf0, 0xc2, 0xfe, 0x10, 0xf1, 0x17, 0x0f, 0x09, 0xd1, 0x38, 0x46, + 0x31, 0x46, 0x2a, 0x46, 0x43, 0x46, 0x08, 0x94, 0x02, 0xb0, 0xbd, 0xe8, + 0xf0, 0x41, 0x09, 0xf0, 0x89, 0x9c, 0x02, 0xb0, 0xbd, 0xe8, 0xf0, 0x81, + 0x2d, 0xe9, 0xf0, 0x4f, 0x1e, 0x69, 0x95, 0xb0, 0x11, 0x91, 0x9a, 0x46, + 0xf3, 0x88, 0xc0, 0xf8, 0x78, 0x28, 0x9d, 0xb2, 0x06, 0x95, 0x05, 0xf0, + 0x0c, 0x08, 0x95, 0x88, 0x93, 0x46, 0x05, 0xf0, 0x03, 0x02, 0x02, 0x2a, + 0x04, 0x46, 0x4f, 0xea, 0x98, 0x08, 0x0d, 0x95, 0x07, 0xd1, 0x1b, 0xb2, + 0x00, 0x2b, 0x04, 0xda, 0xd8, 0xf1, 0x01, 0x03, 0x38, 0xbf, 0x00, 0x23, + 0x00, 0xe0, 0x00, 0x23, 0xba, 0xf8, 0x14, 0x90, 0xdb, 0xb2, 0x0c, 0x93, + 0xa9, 0xf1, 0x0a, 0x09, 0x9b, 0x00, 0xb8, 0xf1, 0x00, 0x0f, 0x03, 0xd1, + 0x17, 0x33, 0x4b, 0x45, 0x80, 0xf2, 0xa4, 0x81, 0x06, 0x9d, 0x05, 0xf0, + 0xfc, 0x07, 0x94, 0x2f, 0x03, 0xd0, 0xa4, 0x2f, 0x01, 0xd0, 0x84, 0x2f, + 0x03, 0xd1, 0xb9, 0xf1, 0x0f, 0x0f, 0x40, 0xf3, 0x97, 0x81, 0xb3, 0x7a, + 0x13, 0xf0, 0x01, 0x03, 0x0a, 0x93, 0x09, 0xd1, 0x20, 0x46, 0x06, 0xf1, + 0x0a, 0x01, 0x38, 0xf0, 0xdf, 0xdb, 0x05, 0x1c, 0x09, 0x90, 0x18, 0xbf, + 0x01, 0x25, 0x01, 0xe0, 0x00, 0x25, 0x09, 0x95, 0x08, 0x95, 0xb8, 0xf1, + 0x00, 0x0f, 0x0e, 0xd1, 0x06, 0xf1, 0x16, 0x05, 0x20, 0x46, 0x29, 0x46, + 0x38, 0xf0, 0xaa, 0xdb, 0x07, 0x90, 0x50, 0xb9, 0x29, 0x46, 0x20, 0x46, + 0x38, 0xf0, 0x0e, 0xdc, 0x0b, 0x90, 0x05, 0x46, 0x06, 0xe0, 0x00, 0x25, + 0x0b, 0x95, 0x07, 0x95, 0x02, 0xe0, 0x07, 0x9d, 0xcd, 0xf8, 0x2c, 0x80, + 0x94, 0xf8, 0xc8, 0x31, 0x23, 0xb9, 0x23, 0x68, 0x93, 0xf8, 0x2c, 0x20, + 0x32, 0xb9, 0x26, 0xe0, 0x20, 0x46, 0x59, 0x46, 0x52, 0x46, 0x00, 0x23, + 0x0f, 0xf0, 0x22, 0xd9, 0x94, 0x2f, 0x03, 0xd0, 0xa4, 0x2f, 0x01, 0xd0, + 0x84, 0x2f, 0x02, 0xd1, 0x08, 0x99, 0x59, 0xbb, 0x03, 0xe0, 0x80, 0x2f, + 0x28, 0xd0, 0x50, 0x2f, 0x26, 0xd0, 0xb8, 0xf1, 0x00, 0x0f, 0x40, 0xf0, + 0xd5, 0x83, 0x08, 0x9a, 0x02, 0xbb, 0x06, 0xf1, 0x0a, 0x00, 0xfb, 0xf3, + 0xa7, 0xf6, 0x00, 0x28, 0x00, 0xf0, 0xcc, 0x83, 0xc5, 0xb9, 0x06, 0xf1, + 0x16, 0x00, 0xfb, 0xf3, 0x9f, 0xf6, 0x98, 0xb9, 0xc4, 0xe3, 0x0a, 0x99, + 0x81, 0xb9, 0x08, 0x9a, 0x42, 0xb1, 0x93, 0xf8, 0x38, 0x20, 0x5a, 0xb1, + 0xb8, 0xf1, 0x00, 0x0f, 0x08, 0xd1, 0x3d, 0xb9, 0x09, 0x99, 0x29, 0xb9, + 0xd3, 0xf8, 0x8c, 0x30, 0x9a, 0x6f, 0x01, 0x32, 0x9a, 0x67, 0xb1, 0xe3, + 0x94, 0xf8, 0xc8, 0x31, 0x6b, 0xb9, 0x15, 0xb9, 0xd4, 0xf8, 0x6c, 0x32, + 0x00, 0xe0, 0x2b, 0x46, 0x93, 0xf8, 0xe5, 0x20, 0x2a, 0xb1, 0x20, 0x46, + 0x59, 0x46, 0x52, 0x46, 0x9b, 0x68, 0x0f, 0xf0, 0xdd, 0xd8, 0xb8, 0xf1, + 0x01, 0x0f, 0x0e, 0xd1, 0xc4, 0x2f, 0x0c, 0xd0, 0xd4, 0x2f, 0x0a, 0xd0, + 0x06, 0xf1, 0x10, 0x00, 0xfb, 0xf3, 0x7e, 0xf6, 0x00, 0x28, 0x40, 0xf0, + 0x93, 0x83, 0x33, 0x7c, 0xd8, 0x07, 0x00, 0xf1, 0x8f, 0x83, 0xda, 0xf8, + 0x10, 0x30, 0xb2, 0x1d, 0x06, 0x33, 0xca, 0xf8, 0x10, 0x30, 0x23, 0x68, + 0x05, 0x92, 0xd3, 0xf8, 0x8c, 0x30, 0x1f, 0xfa, 0x89, 0xf1, 0xda, 0x6c, + 0xaa, 0xf8, 0x14, 0x10, 0x01, 0x32, 0xda, 0x64, 0x20, 0x46, 0x00, 0x91, + 0x5a, 0x46, 0x05, 0x99, 0x13, 0xab, 0x11, 0xf0, 0x2b, 0xdc, 0x30, 0xb1, + 0x23, 0x68, 0xd3, 0xf8, 0x8c, 0x30, 0xda, 0x6f, 0x01, 0x32, 0xda, 0x67, + 0x6e, 0xe3, 0x13, 0x99, 0x11, 0xb1, 0x23, 0x68, 0x9b, 0x6a, 0x0b, 0x62, + 0xb8, 0xf1, 0x01, 0x0f, 0x38, 0xd1, 0xba, 0xf8, 0x14, 0x30, 0xda, 0xf8, + 0x10, 0x00, 0xa3, 0xf1, 0x10, 0x05, 0xaa, 0xf8, 0x14, 0x50, 0x0c, 0x9d, + 0x00, 0xf1, 0x10, 0x02, 0xca, 0xf8, 0x10, 0x20, 0x35, 0xb1, 0x00, 0xf1, + 0x14, 0x02, 0x14, 0x3b, 0xca, 0xf8, 0x10, 0x20, 0xaa, 0xf8, 0x14, 0x30, + 0xa4, 0x2f, 0xba, 0xf8, 0x14, 0x30, 0x0e, 0xd1, 0x0b, 0x69, 0x9b, 0x79, + 0x00, 0x2b, 0x00, 0xf0, 0x49, 0x83, 0x91, 0xf8, 0xdf, 0x30, 0x00, 0x2b, + 0x00, 0xf0, 0x44, 0x83, 0x20, 0x46, 0x06, 0x9a, 0x2f, 0xf0, 0x94, 0xd9, + 0x3e, 0xe3, 0x20, 0x68, 0x90, 0xf8, 0x42, 0x00, 0x00, 0x28, 0x00, 0xf0, + 0x39, 0x83, 0x84, 0x2f, 0x02, 0xd0, 0x94, 0x2f, 0x40, 0xf0, 0x34, 0x83, + 0xd4, 0xf8, 0x40, 0x01, 0x00, 0x97, 0x28, 0xf0, 0x7b, 0xdb, 0x2d, 0xe3, + 0xbb, 0xf8, 0x16, 0x30, 0x0a, 0x9a, 0x03, 0xf4, 0xff, 0x63, 0x70, 0x2b, + 0x94, 0xbf, 0x00, 0x23, 0x01, 0x23, 0x0e, 0x93, 0x00, 0x2a, 0x6b, 0xd1, + 0xb3, 0x8b, 0xad, 0xf8, 0x28, 0x30, 0x9b, 0xb2, 0x0f, 0x93, 0x31, 0xb9, + 0x20, 0x46, 0x06, 0xf1, 0x10, 0x01, 0x0e, 0x9a, 0x4e, 0xf0, 0x2a, 0xdd, + 0x13, 0x90, 0x06, 0x9b, 0x13, 0xf4, 0x00, 0x63, 0x10, 0x93, 0x13, 0x9b, + 0x05, 0xd0, 0x23, 0xb1, 0xb3, 0xf8, 0xbc, 0x20, 0x0f, 0x99, 0x8a, 0x42, + 0x2a, 0xd0, 0xc3, 0xb1, 0xbd, 0xf8, 0x28, 0x20, 0xa3, 0xf8, 0xbc, 0x20, + 0x4c, 0xe0, 0x09, 0xf1, 0xf3, 0x08, 0x04, 0xeb, 0xc8, 0x08, 0x40, 0x46, + 0xfb, 0xf3, 0xe4, 0xf5, 0x80, 0xb9, 0x06, 0xf1, 0x10, 0x00, 0x41, 0x46, + 0x06, 0x22, 0xfb, 0xf3, 0xd1, 0xf0, 0x58, 0xb1, 0x09, 0xf1, 0x01, 0x09, + 0x5f, 0xfa, 0x89, 0xf9, 0x00, 0xe0, 0x99, 0x46, 0x94, 0xf8, 0xe8, 0x37, + 0x4b, 0x45, 0xe6, 0xd2, 0x4f, 0xf0, 0x00, 0x08, 0x10, 0x9b, 0x83, 0xb1, + 0xb8, 0xf1, 0x00, 0x0f, 0x10, 0xd0, 0xb8, 0xf8, 0x06, 0x30, 0x0f, 0x99, + 0x8b, 0x42, 0x23, 0xd1, 0x23, 0x68, 0xd3, 0xf8, 0x8c, 0x30, 0xd3, 0xf8, + 0xbc, 0x21, 0x01, 0x32, 0xc3, 0xf8, 0xbc, 0x21, 0xd4, 0xe2, 0xb8, 0xf1, + 0x00, 0x0f, 0x17, 0xd1, 0x94, 0xf8, 0xe8, 0x37, 0x06, 0xf1, 0x10, 0x01, + 0x03, 0xf1, 0xf3, 0x08, 0x04, 0xeb, 0xc8, 0x08, 0x01, 0x33, 0x84, 0xf8, + 0xe8, 0x37, 0x06, 0x22, 0x40, 0x46, 0xfb, 0xf3, 0xbb, 0xf0, 0x94, 0xf8, + 0xe8, 0x27, 0x0a, 0x23, 0xb2, 0xfb, 0xf3, 0xf1, 0x03, 0xfb, 0x11, 0x23, + 0x84, 0xf8, 0xe8, 0x37, 0xbd, 0xf8, 0x28, 0x30, 0xa8, 0xf8, 0x06, 0x30, + 0x08, 0x99, 0x59, 0xb1, 0x07, 0x9a, 0x4a, 0xb1, 0xab, 0x79, 0x3b, 0xb9, + 0xd5, 0xf8, 0xe4, 0x32, 0x1b, 0x7a, 0x1b, 0xb1, 0x28, 0x46, 0x06, 0x99, + 0x10, 0xf0, 0x68, 0xda, 0xba, 0xf8, 0x14, 0x10, 0xda, 0xf8, 0x10, 0x30, + 0xa1, 0xf1, 0x18, 0x02, 0xaa, 0xf8, 0x14, 0x20, 0x0c, 0x9a, 0x03, 0xf1, + 0x18, 0x09, 0xca, 0xf8, 0x10, 0x90, 0x32, 0xb1, 0x03, 0xf1, 0x1c, 0x09, + 0x1c, 0x39, 0xca, 0xf8, 0x10, 0x90, 0xaa, 0xf8, 0x14, 0x10, 0x0d, 0x99, + 0x06, 0x9a, 0xc1, 0xf3, 0xc0, 0x13, 0x51, 0x04, 0xba, 0xf8, 0x14, 0x80, + 0x0d, 0xd5, 0xb8, 0xf1, 0x07, 0x0f, 0x06, 0xdc, 0x23, 0x68, 0xd3, 0xf8, + 0x8c, 0x30, 0x5a, 0x6e, 0x01, 0x32, 0x5a, 0x66, 0x80, 0xe2, 0xb0, 0x2f, + 0x40, 0xf0, 0x7e, 0x82, 0x27, 0xe0, 0x50, 0x2f, 0x79, 0xd0, 0x10, 0xd8, + 0x20, 0x2f, 0x00, 0xf0, 0x48, 0x82, 0x06, 0xd8, 0x00, 0x2f, 0x00, 0xf0, + 0x44, 0x82, 0x10, 0x2f, 0x40, 0xf0, 0x70, 0x82, 0x41, 0xe0, 0x30, 0x2f, + 0x3f, 0xd0, 0x40, 0x2f, 0x40, 0xf0, 0x6a, 0x82, 0x4f, 0xe0, 0xb0, 0x2f, + 0x0d, 0xd0, 0x05, 0xd8, 0x80, 0x2f, 0x7b, 0xd0, 0xa0, 0x2f, 0x40, 0xf0, + 0x61, 0x82, 0x3f, 0xe1, 0xc0, 0x2f, 0x00, 0xf0, 0x93, 0x81, 0xd0, 0x2f, + 0x40, 0xf0, 0x5a, 0x82, 0x48, 0xe2, 0xb8, 0xf1, 0x05, 0x0f, 0x40, 0xf3, + 0x4f, 0x82, 0x00, 0x2d, 0x00, 0xf0, 0x52, 0x82, 0xaa, 0x79, 0x9a, 0xb1, + 0x2a, 0x79, 0x00, 0x2a, 0x00, 0xf0, 0x4c, 0x82, 0xcd, 0xf8, 0x00, 0x80, + 0x01, 0x93, 0xbb, 0xf8, 0x10, 0x30, 0xd4, 0xf8, 0x34, 0x07, 0x03, 0xf0, + 0x08, 0x03, 0x02, 0x93, 0x29, 0x46, 0x05, 0x9a, 0x4b, 0x46, 0x02, 0xf0, + 0x5c, 0xfb, 0x3b, 0xe2, 0xd4, 0xf8, 0x40, 0x25, 0x92, 0xf9, 0x34, 0x20, + 0x00, 0x2a, 0x00, 0xf0, 0x35, 0x82, 0x00, 0x93, 0x28, 0x46, 0x05, 0x99, + 0x4a, 0x46, 0x43, 0x46, 0x32, 0xf0, 0x52, 0xd8, 0x2c, 0xe2, 0xb8, 0xf1, + 0x05, 0x0f, 0x40, 0xf3, 0x23, 0x82, 0x00, 0x2d, 0x00, 0xf0, 0x26, 0x82, + 0xab, 0x79, 0x00, 0x2b, 0x40, 0xf0, 0x22, 0x82, 0x13, 0x9b, 0x28, 0x46, + 0x00, 0x93, 0x05, 0x99, 0x4a, 0x46, 0x43, 0x46, 0x31, 0xf0, 0xfc, 0xdd, + 0x18, 0xe2, 0x23, 0x68, 0x93, 0xf8, 0x95, 0x30, 0x23, 0xb9, 0x94, 0xf8, + 0x72, 0x32, 0x00, 0x2b, 0x00, 0xf0, 0x10, 0x82, 0x08, 0xf1, 0x18, 0x02, + 0x05, 0x9d, 0x00, 0x23, 0x03, 0x92, 0x20, 0x46, 0x2c, 0x21, 0x06, 0xf1, + 0x10, 0x02, 0x00, 0x93, 0x01, 0x93, 0x02, 0x95, 0x1c, 0xf0, 0x96, 0xdd, + 0x00, 0xe2, 0xb8, 0xf1, 0x0b, 0x0f, 0x40, 0xf3, 0xf7, 0x81, 0xd4, 0xf8, + 0x68, 0x31, 0x9b, 0x79, 0x00, 0x2b, 0x00, 0xf0, 0xf7, 0x81, 0x08, 0x9d, + 0x00, 0x2d, 0x00, 0xf0, 0xf3, 0x81, 0x20, 0x46, 0x59, 0x46, 0x32, 0x46, + 0x05, 0x9b, 0xcd, 0xf8, 0x00, 0x90, 0xcd, 0xf8, 0x04, 0x80, 0xfd, 0xf7, + 0xcd, 0xff, 0xe7, 0xe1, 0xb8, 0xf1, 0x0b, 0x0f, 0x40, 0xf3, 0xde, 0x81, + 0x05, 0x99, 0x33, 0x46, 0x8d, 0xe8, 0x02, 0x02, 0x20, 0x46, 0x07, 0x99, + 0x5a, 0x46, 0xcd, 0xf8, 0x08, 0x80, 0xfe, 0xf7, 0x35, 0xfb, 0xd4, 0xf8, + 0x68, 0x31, 0x9b, 0x79, 0x4b, 0xb1, 0x20, 0x46, 0x59, 0x46, 0x32, 0x46, + 0x05, 0x9b, 0xcd, 0xf8, 0x00, 0x90, 0xcd, 0xf8, 0x04, 0x80, 0xfd, 0xf7, + 0xaf, 0xff, 0x94, 0xf8, 0x72, 0x32, 0x5b, 0xbb, 0xb9, 0xf8, 0x0a, 0x30, + 0xda, 0x07, 0x27, 0xd5, 0x20, 0x46, 0x49, 0x46, 0x42, 0x46, 0x16, 0xf0, + 0x05, 0xdc, 0x08, 0xbb, 0xbb, 0xf8, 0x16, 0x70, 0x07, 0xf4, 0xff, 0x67, + 0xff, 0x08, 0x0e, 0x2f, 0x00, 0xf2, 0xbe, 0x81, 0x09, 0xf1, 0x0c, 0x00, + 0xa8, 0xf1, 0x0c, 0x01, 0x03, 0x22, 0xfb, 0xf3, 0x49, 0xf3, 0x88, 0xb1, + 0x43, 0x78, 0x7b, 0xb1, 0x83, 0x78, 0xbb, 0x42, 0x0c, 0xd1, 0x22, 0x6b, + 0x10, 0x69, 0x04, 0x93, 0x0a, 0xf0, 0x40, 0xfa, 0x04, 0x9b, 0xc0, 0xb2, + 0x83, 0x42, 0x03, 0xd1, 0xd4, 0xf8, 0x68, 0x01, 0x4d, 0xf0, 0x78, 0xdc, + 0x0b, 0x9a, 0x3a, 0xb9, 0x20, 0x46, 0x06, 0xf1, 0x16, 0x01, 0x38, 0xf0, + 0xa5, 0xd9, 0x07, 0x46, 0x08, 0xb9, 0x4d, 0xe0, 0x0b, 0x9f, 0xba, 0x79, + 0x00, 0x2a, 0x49, 0xd1, 0xd7, 0xf8, 0xdc, 0x12, 0xd7, 0xf8, 0xd8, 0x32, + 0x05, 0x91, 0x09, 0xf1, 0x0c, 0x00, 0xa8, 0xf1, 0x0c, 0x01, 0x04, 0x93, + 0xfb, 0xf3, 0x1c, 0xf3, 0x04, 0x9b, 0x06, 0x90, 0x9b, 0x68, 0x0b, 0x2b, + 0x08, 0xd1, 0x38, 0x46, 0x59, 0x46, 0x32, 0x46, 0x4b, 0x46, 0xcd, 0xf8, + 0x00, 0x80, 0x33, 0xf0, 0x57, 0xda, 0x0d, 0xe0, 0x22, 0x68, 0x92, 0xf8, + 0x31, 0x20, 0x4a, 0xb1, 0x0f, 0x2b, 0x07, 0xd1, 0x38, 0x46, 0x59, 0x46, + 0x32, 0x46, 0x4b, 0x46, 0xcd, 0xf8, 0x00, 0x80, 0x33, 0xf0, 0x18, 0xde, + 0xbb, 0x7c, 0xfb, 0xb1, 0x05, 0x9a, 0x92, 0xf8, 0x5a, 0x30, 0xdb, 0xb1, + 0xd4, 0xf8, 0x68, 0x01, 0x06, 0x99, 0x01, 0x22, 0x4d, 0xf0, 0xde, 0xdc, + 0x38, 0xb1, 0x05, 0x99, 0x91, 0xf8, 0x59, 0x30, 0x1b, 0xb9, 0x01, 0x23, + 0x81, 0xf8, 0x59, 0x30, 0x0c, 0xe0, 0xd4, 0xf8, 0x68, 0x01, 0x06, 0x99, + 0x01, 0x22, 0x4d, 0xf0, 0xcf, 0xdc, 0x28, 0xb9, 0x05, 0x9a, 0x92, 0xf8, + 0x59, 0x30, 0x0b, 0xb1, 0x82, 0xf8, 0x59, 0x00, 0x07, 0x9b, 0x00, 0x2b, + 0x00, 0xf0, 0x40, 0x81, 0xd5, 0xf8, 0xd8, 0x32, 0x9b, 0x68, 0x0c, 0x2b, + 0x40, 0xf0, 0x3a, 0x81, 0x4b, 0x46, 0x28, 0x46, 0x59, 0x46, 0x32, 0x46, + 0x23, 0xf0, 0xfe, 0xd9, 0x28, 0x46, 0x00, 0x21, 0x31, 0xf0, 0xc8, 0xdb, + 0x23, 0x68, 0x93, 0xf8, 0x2f, 0x30, 0x23, 0xb1, 0xd4, 0xf8, 0x34, 0x07, + 0x2d, 0xf0, 0xee, 0xdd, 0x26, 0xe1, 0xd5, 0xf8, 0xe4, 0x32, 0x28, 0x46, + 0x99, 0x78, 0x09, 0xf0, 0xce, 0xf8, 0x1f, 0xe1, 0xb8, 0xf1, 0x01, 0x0f, + 0x40, 0xf3, 0x16, 0x81, 0x00, 0x2d, 0x00, 0xf0, 0x19, 0x81, 0xab, 0x79, + 0xb9, 0xf8, 0x00, 0x70, 0x4b, 0xbb, 0x20, 0x46, 0x13, 0x99, 0x1f, 0xf0, + 0x39, 0xdf, 0x13, 0x98, 0x03, 0x7e, 0x9b, 0x07, 0x13, 0xd5, 0x02, 0x21, + 0x4d, 0xf0, 0x66, 0xdf, 0x13, 0x9b, 0x1a, 0x7e, 0x12, 0xf0, 0x08, 0x02, + 0x0b, 0xd1, 0x20, 0x46, 0x29, 0x46, 0x06, 0xf1, 0x10, 0x03, 0x00, 0x97, + 0x01, 0x92, 0xcd, 0xf8, 0x08, 0x90, 0xcd, 0xf8, 0x0c, 0x80, 0x09, 0xf0, + 0x57, 0xfa, 0x07, 0x99, 0x00, 0x29, 0x00, 0xf0, 0xf5, 0x80, 0xd5, 0xf8, + 0xd8, 0x32, 0x9b, 0x68, 0x13, 0xb1, 0x28, 0x46, 0x31, 0xf0, 0xd0, 0xda, + 0x28, 0x46, 0x03, 0x21, 0x9d, 0xe0, 0x13, 0x99, 0x0b, 0x69, 0xab, 0x42, + 0x40, 0xf0, 0xe6, 0x80, 0x20, 0x46, 0x1f, 0xf0, 0x0b, 0xdf, 0x13, 0x98, + 0x03, 0x7e, 0x99, 0x07, 0x10, 0xd5, 0x12, 0x21, 0x4d, 0xf0, 0x38, 0xdf, + 0x00, 0x22, 0x20, 0x46, 0x29, 0x46, 0x06, 0xf1, 0x10, 0x03, 0x00, 0x97, + 0x01, 0x92, 0xcd, 0xf8, 0x08, 0x90, 0xcd, 0xf8, 0x0c, 0x80, 0x09, 0xf0, + 0x2d, 0xfa, 0x99, 0xe0, 0x10, 0x21, 0x4d, 0xf0, 0x27, 0xdf, 0xc9, 0xe0, + 0xb8, 0xf1, 0x01, 0x0f, 0x40, 0xf3, 0xc0, 0x80, 0x2d, 0xb9, 0x09, 0x9a, + 0x00, 0x2a, 0x00, 0xf0, 0xc1, 0x80, 0x17, 0x46, 0x00, 0xe0, 0x2f, 0x46, + 0xd4, 0xf8, 0x6c, 0x12, 0x06, 0xf1, 0x16, 0x00, 0xbc, 0x31, 0x06, 0x22, + 0xfa, 0xf3, 0x92, 0xf6, 0x00, 0x28, 0x40, 0xf0, 0xb3, 0x80, 0x13, 0x9b, + 0xb9, 0xf8, 0x00, 0xb0, 0x33, 0xb9, 0x20, 0x46, 0x06, 0xf1, 0x10, 0x01, + 0x0e, 0x9a, 0x4e, 0xf0, 0xbd, 0xda, 0x13, 0x90, 0x13, 0x99, 0x11, 0xb1, + 0x20, 0x46, 0x1f, 0xf0, 0xcb, 0xde, 0xbb, 0x79, 0x13, 0x98, 0x00, 0x2b, + 0x54, 0xd1, 0x00, 0x28, 0x3b, 0xd0, 0x12, 0x21, 0x4d, 0xf0, 0xf6, 0xde, + 0x13, 0x98, 0x03, 0x7e, 0xda, 0x07, 0x02, 0xd4, 0x43, 0x68, 0x9b, 0x00, + 0x31, 0xd5, 0x01, 0x21, 0x4d, 0xf0, 0xec, 0xde, 0xab, 0xf1, 0x0d, 0x03, + 0x9b, 0xb2, 0x09, 0x2b, 0x07, 0xd8, 0x23, 0x68, 0xd3, 0xf8, 0x8c, 0x30, + 0xd3, 0xf8, 0xf8, 0x21, 0x01, 0x32, 0xc3, 0xf8, 0xf8, 0x21, 0x97, 0xf9, + 0x10, 0x30, 0x02, 0x2b, 0x03, 0xd1, 0xf8, 0x68, 0x0e, 0x21, 0x52, 0xf0, + 0x69, 0xd9, 0x13, 0x9b, 0x1a, 0x7e, 0x12, 0xf0, 0x04, 0x02, 0x0f, 0xd1, + 0xcd, 0xf8, 0x00, 0xb0, 0x5b, 0x68, 0x20, 0x46, 0xc3, 0xf3, 0x40, 0x73, + 0x01, 0x93, 0x39, 0x46, 0x06, 0xf1, 0x10, 0x03, 0xcd, 0xf8, 0x08, 0x90, + 0xcd, 0xf8, 0x0c, 0x80, 0x32, 0xf0, 0x92, 0xd8, 0x13, 0x9b, 0x5a, 0x68, + 0x22, 0xf0, 0x00, 0x52, 0x5a, 0x60, 0x07, 0x9b, 0x00, 0x2b, 0x5d, 0xd0, + 0xab, 0x7c, 0x00, 0x2b, 0x5a, 0xd0, 0xd5, 0xf8, 0xd8, 0x32, 0x5a, 0x68, + 0x9b, 0x68, 0x02, 0x2a, 0x01, 0xd1, 0x08, 0x2b, 0x52, 0xd8, 0x13, 0xb1, + 0x28, 0x46, 0x31, 0xf0, 0x31, 0xda, 0x28, 0x46, 0x02, 0x21, 0x34, 0xf0, + 0x51, 0xd8, 0x49, 0xe0, 0x00, 0x28, 0x47, 0xd0, 0x03, 0x69, 0xbb, 0x42, + 0x44, 0xd1, 0x03, 0x7e, 0xd8, 0x07, 0x41, 0xd5, 0x00, 0x22, 0x20, 0x46, + 0x39, 0x46, 0x06, 0xf1, 0x10, 0x03, 0xcd, 0xf8, 0x00, 0xb0, 0x01, 0x92, + 0xcd, 0xf8, 0x08, 0x90, 0xcd, 0xf8, 0x0c, 0x80, 0x32, 0xf0, 0x60, 0xd8, + 0x20, 0x46, 0x13, 0x99, 0x4e, 0xf0, 0x4c, 0xda, 0x2e, 0xe0, 0xb8, 0xf1, + 0x03, 0x0f, 0x25, 0xdd, 0x55, 0xb3, 0x2a, 0x79, 0x42, 0xb3, 0xaa, 0x79, + 0x32, 0xb3, 0x06, 0xf1, 0x16, 0x00, 0x05, 0xf1, 0xbc, 0x01, 0x06, 0x22, + 0x04, 0x93, 0xfa, 0xf3, 0xfb, 0xf5, 0x04, 0x9b, 0xe0, 0xb9, 0x13, 0x9a, + 0x02, 0x93, 0x01, 0x92, 0xd4, 0xf8, 0x34, 0x07, 0x29, 0x46, 0x05, 0x9a, + 0x4b, 0x46, 0xcd, 0xf8, 0x00, 0x80, 0x08, 0xf0, 0x8f, 0xfe, 0x0f, 0xe0, + 0x20, 0x46, 0x13, 0x99, 0x05, 0x9a, 0x4b, 0x46, 0x8d, 0xe8, 0x00, 0x09, + 0x02, 0x96, 0x10, 0xf0, 0x21, 0xd8, 0x05, 0xe0, 0x23, 0x68, 0xd3, 0xf8, + 0x8c, 0x30, 0x1a, 0x6f, 0x01, 0x32, 0x1a, 0x67, 0x11, 0x98, 0x51, 0x46, + 0x00, 0x22, 0xff, 0xf3, 0xc7, 0xf4, 0x15, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, + 0x23, 0x6b, 0x18, 0x69, 0x0a, 0xf0, 0x90, 0xf8, 0xc0, 0xb2, 0x87, 0x42, + 0x4f, 0xe6, 0x00, 0x00, 0x2d, 0xe9, 0xf0, 0x4f, 0x06, 0x46, 0x92, 0xf8, + 0x2a, 0x30, 0x10, 0x68, 0x0d, 0x46, 0x9b, 0xb0, 0x14, 0x46, 0x91, 0x8b, + 0x05, 0x90, 0xd6, 0xf8, 0x04, 0xa0, 0x2f, 0x69, 0x13, 0xb1, 0x92, 0xf8, + 0x22, 0x80, 0x00, 0xe0, 0x98, 0x46, 0x94, 0xf8, 0x2c, 0x30, 0x9b, 0xb9, + 0x0a, 0x05, 0x11, 0xd5, 0x05, 0xeb, 0x48, 0x02, 0xb2, 0xf8, 0xac, 0x00, + 0xb4, 0xf8, 0x7e, 0x20, 0x90, 0x42, 0x09, 0xd1, 0x33, 0x68, 0xd3, 0xf8, + 0x8c, 0x30, 0xd3, 0xf8, 0xbc, 0x21, 0x01, 0x32, 0xc3, 0xf8, 0xbc, 0x21, + 0x00, 0xf0, 0x79, 0xbc, 0xba, 0x79, 0xc1, 0xf3, 0x80, 0x2b, 0x12, 0xbb, + 0xd7, 0xf8, 0xe4, 0x92, 0x99, 0xf8, 0x08, 0x20, 0x6a, 0xb1, 0x63, 0xb9, + 0xbb, 0xf1, 0x00, 0x0f, 0x09, 0xd1, 0x95, 0xf8, 0xd2, 0x20, 0x63, 0x6a, + 0x52, 0xfa, 0x03, 0xf3, 0xd8, 0x07, 0x02, 0xd4, 0x38, 0x46, 0x0f, 0xf0, + 0x6f, 0xdf, 0x33, 0x68, 0x5b, 0x6b, 0x63, 0xb1, 0x99, 0xf8, 0x18, 0x30, + 0x4b, 0xb1, 0x94, 0xf8, 0x2a, 0x30, 0x33, 0xb1, 0x94, 0xf8, 0x28, 0x30, + 0x1b, 0xb1, 0x38, 0x46, 0x00, 0x21, 0x21, 0xf0, 0xa5, 0xda, 0x23, 0x8c, + 0x5a, 0x07, 0x00, 0xf1, 0x4e, 0x84, 0xa3, 0x8b, 0x03, 0xf4, 0x80, 0x43, + 0x63, 0x63, 0x63, 0xb9, 0xbb, 0x6d, 0x40, 0xf2, 0x37, 0x19, 0x03, 0xea, + 0x09, 0x09, 0xb9, 0xf1, 0x00, 0x0f, 0x27, 0xd0, 0x97, 0xf8, 0x60, 0x90, + 0xb9, 0xf1, 0x00, 0x0f, 0x22, 0xd0, 0x4f, 0xf0, 0x00, 0x09, 0xc4, 0xf8, + 0x38, 0x90, 0x30, 0x46, 0x51, 0x46, 0x2a, 0x46, 0x23, 0x46, 0xcd, 0xf8, + 0x00, 0x80, 0x4f, 0xf0, 0x41, 0xdb, 0x70, 0xb9, 0x63, 0x6b, 0x23, 0xb1, + 0xd5, 0xf8, 0x6c, 0x31, 0x01, 0x33, 0xc5, 0xf8, 0x6c, 0x31, 0x33, 0x68, + 0x93, 0xf8, 0x95, 0x30, 0x00, 0x2b, 0x00, 0xf0, 0x22, 0x84, 0x4f, 0xf0, + 0x01, 0x09, 0x63, 0x6b, 0x23, 0xb1, 0xd5, 0xf8, 0x68, 0x31, 0x01, 0x33, + 0xc5, 0xf8, 0x68, 0x31, 0x94, 0xf8, 0x2c, 0x30, 0x43, 0xb9, 0x08, 0xf1, + 0x54, 0x03, 0xb4, 0xf8, 0x7e, 0x10, 0x05, 0xeb, 0x43, 0x03, 0x9a, 0x88, + 0x99, 0x80, 0x00, 0xe0, 0x00, 0x22, 0x33, 0x68, 0x02, 0x93, 0x93, 0xf8, + 0x95, 0x30, 0x1b, 0xb1, 0xb9, 0xf1, 0x00, 0x0f, 0x40, 0xf0, 0x03, 0x84, + 0x94, 0xf8, 0x2c, 0x30, 0x00, 0x2b, 0x40, 0xf0, 0x29, 0x81, 0xb4, 0xf8, + 0x7e, 0xc0, 0x08, 0xf1, 0x1a, 0x09, 0x1c, 0xf0, 0x0f, 0x03, 0x40, 0xf0, + 0x8a, 0x80, 0x05, 0xeb, 0x89, 0x09, 0xd9, 0xf8, 0x04, 0x10, 0x79, 0xb1, + 0x1a, 0x46, 0x50, 0x46, 0x03, 0x93, 0xff, 0xf3, 0x05, 0xf4, 0x03, 0x9b, + 0x05, 0xeb, 0x88, 0x02, 0xc2, 0xf8, 0x8c, 0x30, 0x08, 0xf1, 0x4c, 0x02, + 0xc9, 0xf8, 0x04, 0x30, 0x45, 0xf8, 0x22, 0x30, 0xbb, 0xf1, 0x00, 0x0f, + 0x00, 0xf0, 0x08, 0x81, 0xe3, 0x68, 0x08, 0xf1, 0x1a, 0x09, 0x04, 0x93, + 0x63, 0x69, 0x05, 0xeb, 0x89, 0x09, 0xc9, 0xf8, 0x04, 0x30, 0x18, 0x69, + 0x9a, 0x8a, 0x31, 0x68, 0xd3, 0xf8, 0x0c, 0xc0, 0x9b, 0x68, 0x00, 0xeb, + 0x02, 0x0e, 0xc9, 0x69, 0xce, 0xeb, 0x0c, 0x0e, 0xc0, 0x1a, 0x89, 0x68, + 0x86, 0x44, 0x72, 0x44, 0x8a, 0x42, 0x22, 0xda, 0x50, 0x46, 0xff, 0xf3, + 0x09, 0xf4, 0xc9, 0xf8, 0x04, 0x00, 0x00, 0x28, 0x00, 0xf0, 0xbb, 0x83, + 0x63, 0x69, 0x00, 0x69, 0x99, 0x68, 0x1a, 0x69, 0x9b, 0x8a, 0x52, 0x1a, + 0xd2, 0x18, 0xfa, 0xf3, 0xf7, 0xf4, 0x61, 0x69, 0x0a, 0x69, 0x8b, 0x68, + 0xd2, 0x1a, 0xd9, 0xf8, 0x04, 0x30, 0x18, 0x69, 0x80, 0x18, 0x18, 0x61, + 0x98, 0x8a, 0x82, 0x1a, 0x9a, 0x82, 0x88, 0x8a, 0x00, 0x22, 0x98, 0x82, + 0x50, 0x46, 0xff, 0xf3, 0xb9, 0xf3, 0x32, 0x68, 0x04, 0x99, 0xd2, 0x69, + 0x05, 0xeb, 0x88, 0x03, 0x92, 0x68, 0xa4, 0x48, 0x52, 0x1a, 0xd6, 0xf8, + 0x28, 0x18, 0x06, 0x3a, 0x52, 0x1a, 0xc3, 0xf8, 0x8c, 0x20, 0x61, 0x68, + 0x08, 0x22, 0xfa, 0xf3, 0xb7, 0xf4, 0x50, 0xb1, 0x9e, 0x48, 0x61, 0x68, + 0x06, 0x22, 0xfa, 0xf3, 0xb1, 0xf4, 0x40, 0xb9, 0x63, 0x68, 0xdb, 0x88, + 0xb3, 0xf5, 0x40, 0x7f, 0x03, 0xd1, 0x6b, 0x68, 0x43, 0xf0, 0x08, 0x03, + 0x02, 0xe0, 0x6b, 0x68, 0x23, 0xf0, 0x08, 0x03, 0x6b, 0x60, 0x96, 0x48, + 0x61, 0x68, 0x08, 0x22, 0xfa, 0xf3, 0x9e, 0xf4, 0xab, 0x68, 0x10, 0xb9, + 0x43, 0xf0, 0x20, 0x03, 0x01, 0xe0, 0x23, 0xf0, 0x20, 0x03, 0xab, 0x60, + 0x96, 0xe0, 0x05, 0xeb, 0x89, 0x00, 0x41, 0x68, 0x04, 0x90, 0x19, 0xb9, + 0x02, 0x99, 0xd1, 0xf8, 0x8c, 0x30, 0x1f, 0xe0, 0x82, 0xea, 0x0c, 0x0c, + 0x3c, 0xf0, 0x0f, 0x0c, 0x04, 0xd1, 0x02, 0xf0, 0x0f, 0x02, 0x01, 0x32, + 0x93, 0x42, 0x19, 0xd0, 0x00, 0x22, 0x50, 0x46, 0xff, 0xf3, 0x6e, 0xf3, + 0x08, 0xf1, 0x1a, 0x02, 0x00, 0x23, 0x05, 0xeb, 0x82, 0x02, 0x53, 0x60, + 0x08, 0xf1, 0x22, 0x02, 0x05, 0xeb, 0x82, 0x02, 0x08, 0xf1, 0x4c, 0x08, + 0x53, 0x60, 0x45, 0xf8, 0x28, 0x30, 0x33, 0x68, 0xd3, 0xf8, 0x8c, 0x30, + 0x1a, 0x6e, 0x01, 0x32, 0x1a, 0x66, 0x3e, 0xe3, 0x08, 0xf1, 0x22, 0x09, + 0x05, 0xeb, 0x89, 0x09, 0xa3, 0x68, 0xd9, 0xf8, 0x04, 0x20, 0x93, 0x42, + 0x11, 0xd9, 0x62, 0x46, 0x50, 0x46, 0xcd, 0xf8, 0x0c, 0xc0, 0xff, 0xf3, + 0x49, 0xf3, 0xdd, 0xf8, 0x0c, 0xc0, 0x04, 0x9a, 0x08, 0xf1, 0x4c, 0x08, + 0xc2, 0xf8, 0x04, 0xc0, 0xc9, 0xf8, 0x04, 0xc0, 0x45, 0xf8, 0x28, 0xc0, + 0xdd, 0xe7, 0x8d, 0xe8, 0x08, 0x04, 0x30, 0x46, 0x09, 0xf1, 0x04, 0x02, + 0x63, 0x68, 0xcd, 0xf8, 0x0c, 0xc0, 0x0b, 0xf0, 0x93, 0xdc, 0xdd, 0xf8, + 0x0c, 0xc0, 0x50, 0x46, 0x61, 0x69, 0x62, 0x46, 0xff, 0xf3, 0x2c, 0xf3, + 0xbb, 0xf1, 0x00, 0x0f, 0x3a, 0xd1, 0x04, 0x9b, 0x5a, 0x68, 0x62, 0x61, + 0xc3, 0xf8, 0x04, 0xb0, 0x08, 0xf1, 0x4c, 0x03, 0x45, 0xf8, 0x23, 0xb0, + 0x13, 0x69, 0x92, 0x8a, 0x03, 0xf1, 0x18, 0x01, 0xc9, 0xf8, 0x04, 0xb0, + 0x61, 0x60, 0xa2, 0xf1, 0x18, 0x01, 0xa1, 0x60, 0x94, 0xf8, 0x29, 0x10, + 0x23, 0x60, 0xe2, 0x60, 0x21, 0xb1, 0x03, 0xf1, 0x1e, 0x01, 0x1e, 0x3a, + 0x61, 0x60, 0xa2, 0x60, 0x94, 0xf8, 0x2a, 0x20, 0x3a, 0xb1, 0x62, 0x68, + 0x84, 0xf8, 0x22, 0x80, 0x02, 0x32, 0x62, 0x60, 0xa2, 0x68, 0x02, 0x3a, + 0xa2, 0x60, 0x1a, 0x78, 0x5b, 0x78, 0x42, 0xea, 0x03, 0x23, 0xa3, 0x83, + 0x63, 0x6b, 0x5b, 0xb1, 0xa3, 0x6b, 0x4b, 0xb1, 0x93, 0xf9, 0x0e, 0x20, + 0x61, 0x68, 0x8a, 0x18, 0x62, 0x60, 0x93, 0xf9, 0x0e, 0x30, 0xa2, 0x68, + 0xd3, 0x1a, 0xa3, 0x60, 0xa3, 0x6b, 0x73, 0xb1, 0x1b, 0x7a, 0x04, 0x2b, + 0x03, 0xd1, 0x30, 0x46, 0x21, 0x46, 0x4f, 0xf0, 0x8b, 0xda, 0xa3, 0x6b, + 0x1b, 0x7a, 0x0b, 0x2b, 0x03, 0xd1, 0x30, 0x46, 0x21, 0x46, 0x4f, 0xf0, + 0x9f, 0xdb, 0xbb, 0xf1, 0x00, 0x0f, 0x40, 0xf0, 0x01, 0x83, 0x33, 0x68, + 0x93, 0xf8, 0x95, 0x30, 0x00, 0x2b, 0x52, 0xd0, 0xbb, 0x68, 0x9b, 0x79, + 0xdb, 0x07, 0x00, 0xf1, 0xd5, 0x82, 0x4c, 0xe0, 0x00, 0xf4, 0xe0, 0x62, + 0x10, 0xf4, 0x00, 0x0f, 0x4f, 0xea, 0x12, 0x22, 0x31, 0x4b, 0x00, 0xf0, + 0x7f, 0x00, 0xa2, 0xf1, 0x04, 0x02, 0x08, 0xd0, 0x01, 0x2a, 0x4f, 0xf0, + 0x14, 0x02, 0x02, 0xfb, 0x00, 0x30, 0x94, 0xbf, 0xc0, 0x68, 0x80, 0x68, + 0x09, 0xe0, 0x01, 0x2a, 0x4f, 0xf0, 0x14, 0x02, 0x03, 0xd8, 0x02, 0xfb, + 0x00, 0x30, 0x40, 0x68, 0x01, 0xe0, 0x50, 0x43, 0x18, 0x58, 0x4f, 0xf4, + 0xfa, 0x73, 0x04, 0xe0, 0x00, 0xf0, 0x7f, 0x00, 0x4f, 0xf4, 0xfa, 0x73, + 0x58, 0x43, 0xb0, 0xfb, 0xf3, 0xf0, 0xcd, 0xf8, 0x21, 0x00, 0x4f, 0xf0, + 0x01, 0x0b, 0x0d, 0xf1, 0x27, 0x00, 0x21, 0x68, 0x18, 0x22, 0x8d, 0xf8, + 0x26, 0xb0, 0xfa, 0xf3, 0xc5, 0xf3, 0x94, 0xf8, 0x2f, 0x30, 0xa3, 0xb1, + 0xbd, 0xf8, 0x27, 0x30, 0x0d, 0xf1, 0x31, 0x01, 0x43, 0xf4, 0x00, 0x73, + 0x06, 0x22, 0x0d, 0xf1, 0x37, 0x00, 0xad, 0xf8, 0x27, 0x30, 0xfa, 0xf3, + 0xb5, 0xf3, 0xd6, 0xf8, 0x6c, 0x12, 0x0d, 0xf1, 0x31, 0x00, 0xbc, 0x31, + 0x06, 0x22, 0xfa, 0xf3, 0xad, 0xf3, 0x33, 0x68, 0x93, 0xf8, 0x95, 0x20, + 0x0a, 0xb9, 0x13, 0x46, 0x01, 0xe0, 0x2d, 0x22, 0x06, 0xab, 0x61, 0x69, + 0x49, 0x6a, 0x48, 0x06, 0x12, 0xd5, 0x09, 0x06, 0x40, 0xf1, 0x59, 0x82, + 0x00, 0x92, 0xd6, 0xf8, 0x3c, 0x01, 0x29, 0x46, 0x22, 0x46, 0x29, 0xf0, + 0x03, 0xda, 0x91, 0xe2, 0x40, 0x1e, 0x86, 0x00, 0xee, 0xb6, 0x01, 0x00, + 0x48, 0x1e, 0x86, 0x00, 0x84, 0x18, 0x86, 0x00, 0x21, 0x68, 0x06, 0x22, + 0x04, 0x31, 0x12, 0xa8, 0xfa, 0xf3, 0x88, 0xf3, 0x21, 0x68, 0x06, 0x22, + 0x0a, 0x31, 0x14, 0xa8, 0xfa, 0xf3, 0x82, 0xf3, 0x21, 0x68, 0x16, 0xa8, + 0x10, 0x31, 0x06, 0x22, 0xfa, 0xf3, 0x7c, 0xf3, 0x94, 0xf8, 0x29, 0x30, + 0x2b, 0xb1, 0x21, 0x68, 0x18, 0xa8, 0x18, 0x31, 0x06, 0x22, 0xfa, 0xf3, + 0x73, 0xf3, 0xa3, 0x8b, 0x13, 0xf4, 0x80, 0x7f, 0x03, 0xf4, 0x00, 0x73, + 0x04, 0xd1, 0x12, 0xaa, 0x62, 0x67, 0x23, 0xb1, 0x16, 0xab, 0x05, 0xe0, + 0x16, 0xaa, 0x62, 0x67, 0x0b, 0xb9, 0x14, 0xab, 0x00, 0xe0, 0x18, 0xab, + 0x23, 0x67, 0xd4, 0xf8, 0x04, 0x90, 0xbb, 0xf1, 0x00, 0x0f, 0x00, 0xf0, + 0x00, 0x81, 0x23, 0x68, 0xe3, 0x66, 0x99, 0xf8, 0x00, 0x30, 0xaa, 0x2b, + 0x30, 0xd1, 0x99, 0xf8, 0x01, 0x30, 0xaa, 0x2b, 0x2c, 0xd1, 0x99, 0xf8, + 0x02, 0x30, 0x03, 0x2b, 0x28, 0xd1, 0x99, 0xf8, 0x03, 0x30, 0x2b, 0xbb, + 0x99, 0xf8, 0x04, 0x30, 0x13, 0xbb, 0x99, 0xf8, 0x05, 0x30, 0x53, 0xb9, + 0xb9, 0xf8, 0x06, 0x30, 0x30, 0x46, 0x19, 0x0a, 0x41, 0xea, 0x03, 0x21, + 0x89, 0xb2, 0x0a, 0xf0, 0xe3, 0xdf, 0x60, 0xb1, 0x14, 0xe0, 0xf8, 0x2b, + 0x12, 0xd1, 0xb9, 0xf8, 0x06, 0x30, 0x30, 0x46, 0x19, 0x0a, 0x41, 0xea, + 0x03, 0x21, 0x89, 0xb2, 0x0a, 0xf0, 0xd6, 0xdf, 0x40, 0xb1, 0xb9, 0xf8, + 0x06, 0x30, 0x4f, 0xea, 0x13, 0x29, 0x49, 0xea, 0x03, 0x29, 0x1f, 0xfa, + 0x89, 0xf9, 0x01, 0xe0, 0xb4, 0xf8, 0x08, 0x90, 0x33, 0x68, 0x93, 0xf8, + 0x95, 0x30, 0xcb, 0xb1, 0xd7, 0xf8, 0xe0, 0x30, 0x4b, 0xb9, 0x63, 0x6b, + 0xa3, 0xb9, 0xba, 0x6d, 0x40, 0xf2, 0x37, 0x13, 0x13, 0x40, 0x7b, 0xb1, + 0x97, 0xf8, 0x60, 0x30, 0x63, 0xb1, 0x30, 0x46, 0x29, 0x46, 0x3a, 0x46, + 0x23, 0x46, 0xcd, 0xf8, 0x00, 0x90, 0xcd, 0xf8, 0x04, 0x80, 0x0c, 0xf0, + 0x0f, 0xde, 0x00, 0x28, 0x40, 0xf0, 0xbf, 0x81, 0xa3, 0x6b, 0x6b, 0xb1, + 0x1b, 0x7a, 0x01, 0x2b, 0x0a, 0xd0, 0x03, 0x2b, 0x08, 0xd0, 0x30, 0x46, + 0x51, 0x46, 0x2a, 0x46, 0x23, 0x46, 0x08, 0xf0, 0x08, 0xfe, 0x00, 0x28, + 0x00, 0xf0, 0xaf, 0x81, 0x63, 0x6f, 0x1b, 0x78, 0xd8, 0x07, 0x07, 0xd5, + 0x33, 0x68, 0xd3, 0xf8, 0x8c, 0x30, 0xd3, 0xf8, 0xd0, 0x21, 0x01, 0x32, + 0xc3, 0xf8, 0xd0, 0x21, 0xa3, 0x6b, 0x33, 0xb1, 0x1b, 0x7a, 0x02, 0x2b, + 0x03, 0xd1, 0x30, 0x46, 0x21, 0x46, 0x4f, 0xf0, 0x59, 0xd9, 0x63, 0x6b, + 0x1b, 0xb9, 0x94, 0xf8, 0x2a, 0x20, 0x1a, 0xb9, 0x21, 0xe0, 0xa3, 0x6b, + 0x93, 0xf9, 0x0e, 0x30, 0x94, 0xf8, 0x2a, 0x20, 0x3a, 0xb1, 0x21, 0x68, + 0x02, 0x33, 0x0a, 0x88, 0x22, 0xf0, 0x80, 0x02, 0x12, 0x04, 0x12, 0x0c, + 0x0a, 0x80, 0x61, 0x68, 0x05, 0xe0, 0xca, 0x1a, 0x12, 0xf8, 0x01, 0x2c, + 0x01, 0xf8, 0x01, 0x2c, 0x71, 0x46, 0x62, 0x69, 0x01, 0xf1, 0xff, 0x3e, + 0x10, 0x69, 0x70, 0x45, 0xf3, 0xd9, 0xc1, 0x18, 0x90, 0x8a, 0x11, 0x61, + 0xc3, 0x1a, 0x93, 0x82, 0x21, 0x60, 0x94, 0xf8, 0x2f, 0x30, 0x93, 0xb1, + 0x20, 0x68, 0x06, 0x22, 0x03, 0x88, 0x80, 0x46, 0x43, 0xf4, 0x00, 0x73, + 0x28, 0xf8, 0x0a, 0x3b, 0x41, 0x46, 0x10, 0x30, 0xfa, 0xf3, 0xa8, 0xf2, + 0xd6, 0xf8, 0x6c, 0x12, 0x40, 0x46, 0xbc, 0x31, 0x06, 0x22, 0xfa, 0xf3, + 0xa1, 0xf2, 0x97, 0xf9, 0x10, 0x30, 0x8b, 0xb1, 0x48, 0xf6, 0x8e, 0x03, + 0x99, 0x45, 0x0d, 0xd1, 0x21, 0x68, 0x62, 0x6b, 0x12, 0x31, 0x00, 0x32, + 0x18, 0xbf, 0x01, 0x22, 0xf8, 0x68, 0x07, 0xf1, 0x18, 0x03, 0x51, 0xf0, + 0xa5, 0xda, 0x00, 0x28, 0x40, 0xf0, 0x47, 0x81, 0x97, 0xf8, 0x30, 0x35, + 0x83, 0xb1, 0x48, 0xf6, 0x8e, 0x03, 0x99, 0x45, 0x0c, 0xd1, 0x21, 0x68, + 0x62, 0x6b, 0x12, 0x31, 0x00, 0x32, 0x18, 0xbf, 0x01, 0x22, 0x78, 0x69, + 0x2b, 0x46, 0x07, 0xf0, 0x88, 0xf8, 0x00, 0x28, 0x40, 0xf0, 0x33, 0x81, + 0x63, 0x69, 0x9a, 0x8a, 0x18, 0x69, 0xdb, 0x68, 0x80, 0x18, 0x1b, 0x1a, + 0x2c, 0x2b, 0x40, 0xf2, 0x2a, 0x81, 0x00, 0x23, 0x06, 0xa9, 0x2d, 0x22, + 0x8d, 0xf8, 0x26, 0x30, 0xfa, 0xf3, 0x68, 0xf2, 0x63, 0x69, 0x94, 0xf8, + 0x22, 0x10, 0xda, 0x8a, 0x01, 0xf0, 0x07, 0x01, 0x22, 0xf0, 0x07, 0x02, + 0x0a, 0x43, 0xda, 0x82, 0x94, 0xf8, 0x29, 0x20, 0x0e, 0xe1, 0xd4, 0xf8, + 0x14, 0xb0, 0x99, 0xf8, 0x00, 0x30, 0xdb, 0xf8, 0x10, 0x20, 0xaa, 0x2b, + 0x04, 0x92, 0xc2, 0xeb, 0x09, 0x08, 0x36, 0xd1, 0x99, 0xf8, 0x01, 0x30, + 0xaa, 0x2b, 0x32, 0xd1, 0x99, 0xf8, 0x02, 0x30, 0x03, 0x2b, 0x2e, 0xd1, + 0x99, 0xf8, 0x03, 0x30, 0x5b, 0xbb, 0x99, 0xf8, 0x04, 0x30, 0x43, 0xbb, + 0x99, 0xf8, 0x05, 0x30, 0x53, 0xb9, 0xb9, 0xf8, 0x06, 0x30, 0x30, 0x46, + 0x19, 0x0a, 0x41, 0xea, 0x03, 0x21, 0x89, 0xb2, 0x0a, 0xf0, 0xde, 0xde, + 0x60, 0xb1, 0x1a, 0xe0, 0xf8, 0x2b, 0x18, 0xd1, 0xb9, 0xf8, 0x06, 0x30, + 0x30, 0x46, 0x19, 0x0a, 0x41, 0xea, 0x03, 0x21, 0x89, 0xb2, 0x0a, 0xf0, + 0xd1, 0xde, 0x70, 0xb1, 0x04, 0x9a, 0xa8, 0xf1, 0x06, 0x08, 0x02, 0xeb, + 0x08, 0x03, 0xbb, 0xf8, 0x14, 0x20, 0xcb, 0xf8, 0x10, 0x30, 0xc8, 0xeb, + 0x02, 0x08, 0xab, 0xf8, 0x14, 0x80, 0xe3, 0x66, 0x26, 0xe0, 0xbb, 0x6d, + 0x99, 0x06, 0x12, 0xd5, 0x48, 0x46, 0x8a, 0x49, 0x08, 0x22, 0xfa, 0xf3, + 0xf5, 0xf1, 0x60, 0xb9, 0x63, 0x69, 0x08, 0xf1, 0x04, 0x08, 0x1a, 0x69, + 0x99, 0x8a, 0x42, 0x44, 0xc8, 0xeb, 0x01, 0x08, 0x1a, 0x61, 0xa3, 0xf8, + 0x14, 0x80, 0xe2, 0x66, 0x10, 0xe0, 0x63, 0x69, 0xa8, 0xf1, 0x0e, 0x08, + 0x99, 0x8a, 0x1a, 0x69, 0x42, 0x44, 0xc8, 0xeb, 0x01, 0x08, 0x1a, 0x61, + 0xa3, 0xf8, 0x14, 0x80, 0x23, 0x89, 0xe2, 0x66, 0x19, 0x0a, 0x41, 0xea, + 0x03, 0x23, 0x93, 0x81, 0xa3, 0x6b, 0x6b, 0xb1, 0x1b, 0x7a, 0x01, 0x2b, + 0x0a, 0xd0, 0x03, 0x2b, 0x08, 0xd0, 0x30, 0x46, 0x51, 0x46, 0x2a, 0x46, + 0x23, 0x46, 0x08, 0xf0, 0xf6, 0xfc, 0x00, 0x28, 0x00, 0xf0, 0x9d, 0x80, + 0xa3, 0x6b, 0x33, 0xb1, 0x1b, 0x7a, 0x02, 0x2b, 0x03, 0xd1, 0x30, 0x46, + 0x21, 0x46, 0x4f, 0xf0, 0x53, 0xd8, 0x06, 0x22, 0x61, 0x6f, 0xe0, 0x6e, + 0xfa, 0xf3, 0xd4, 0xf1, 0xe0, 0x6e, 0x06, 0x22, 0x06, 0x30, 0x21, 0x6f, + 0xfa, 0xf3, 0xce, 0xf1, 0x63, 0x69, 0x94, 0xf8, 0x22, 0x10, 0xda, 0x8a, + 0x01, 0xf0, 0x07, 0x01, 0x22, 0xf0, 0x07, 0x02, 0x0a, 0x43, 0xda, 0x82, + 0x62, 0x6f, 0x12, 0x78, 0xd2, 0x07, 0x07, 0xd5, 0x32, 0x68, 0xd2, 0xf8, + 0x8c, 0x20, 0xd2, 0xf8, 0xd0, 0x11, 0x01, 0x31, 0xc2, 0xf8, 0xd0, 0x11, + 0x97, 0xf8, 0x61, 0x20, 0x72, 0xb1, 0x2a, 0x7e, 0xd0, 0x06, 0x0b, 0xd4, + 0xe2, 0x6e, 0x92, 0x89, 0x11, 0x0a, 0x41, 0xea, 0x02, 0x22, 0x57, 0x49, + 0x12, 0xb2, 0x8a, 0x42, 0x02, 0xd0, 0x5a, 0x6a, 0xd1, 0x06, 0x60, 0xd5, + 0x97, 0xf8, 0x65, 0x20, 0x9a, 0xb1, 0x2a, 0x7e, 0xd2, 0x06, 0x10, 0xd4, + 0xe2, 0x6e, 0x92, 0x89, 0x11, 0x0a, 0x41, 0xea, 0x02, 0x22, 0x4f, 0x49, + 0x12, 0xb2, 0x8a, 0x42, 0x07, 0xd0, 0x26, 0x39, 0x8a, 0x42, 0x04, 0xd0, + 0x5b, 0x6a, 0x00, 0x2b, 0x01, 0xdb, 0xd8, 0x06, 0x49, 0xd5, 0xbb, 0x79, + 0x23, 0xb9, 0xd7, 0xf8, 0xe4, 0x32, 0x01, 0x22, 0x83, 0xf8, 0x2a, 0x20, + 0x96, 0xf8, 0x32, 0x38, 0x01, 0x33, 0x86, 0xf8, 0x32, 0x38, 0x97, 0xf9, + 0x10, 0x30, 0xdb, 0xb1, 0xe1, 0x6e, 0x8b, 0x89, 0x1a, 0x0a, 0x42, 0xea, + 0x03, 0x23, 0x3e, 0x4a, 0x1b, 0xb2, 0x93, 0x42, 0x12, 0xd1, 0x0b, 0x8a, + 0x1a, 0x0a, 0x42, 0xea, 0x03, 0x23, 0xa2, 0x68, 0x9b, 0xb2, 0x0c, 0x3a, + 0x93, 0x42, 0x28, 0xd8, 0x62, 0x6b, 0xf8, 0x68, 0x00, 0x32, 0x18, 0xbf, + 0x01, 0x22, 0x07, 0xf1, 0x18, 0x03, 0x51, 0xf0, 0x7b, 0xd9, 0xf0, 0xb9, + 0x97, 0xf8, 0x30, 0x35, 0x8b, 0xb1, 0xe1, 0x6e, 0x8b, 0x89, 0x1a, 0x0a, + 0x42, 0xea, 0x03, 0x23, 0x2e, 0x4a, 0x1b, 0xb2, 0x93, 0x42, 0x08, 0xd1, + 0x62, 0x6b, 0x78, 0x69, 0x00, 0x32, 0x18, 0xbf, 0x01, 0x22, 0x2b, 0x46, + 0x06, 0xf0, 0x5d, 0xff, 0x48, 0xb9, 0x94, 0xf8, 0x29, 0x20, 0x63, 0x69, + 0x00, 0x93, 0x30, 0x46, 0x29, 0x46, 0x63, 0x6f, 0x1e, 0xf0, 0x4e, 0xdd, + 0x40, 0xe0, 0x33, 0x68, 0x5a, 0x6b, 0xaa, 0xb1, 0x61, 0x69, 0x23, 0x48, + 0xca, 0x8a, 0xd3, 0xf8, 0x90, 0x30, 0x02, 0xf0, 0x07, 0x02, 0x82, 0x5c, + 0x20, 0x48, 0x85, 0x5c, 0x50, 0x46, 0x0c, 0x35, 0x03, 0xeb, 0xc5, 0x05, + 0x6b, 0x68, 0xae, 0x68, 0x01, 0x33, 0x6b, 0x60, 0xfb, 0xf3, 0x7c, 0xf2, + 0x80, 0x19, 0xa8, 0x60, 0x50, 0x46, 0x61, 0x69, 0x00, 0x22, 0xfe, 0xf3, + 0xfb, 0xf7, 0x21, 0xe0, 0x33, 0x6b, 0xd4, 0xf8, 0x80, 0x10, 0x1b, 0x89, + 0x30, 0x46, 0x06, 0x93, 0xa3, 0x69, 0xdb, 0x8a, 0xdb, 0x08, 0x8d, 0xf8, + 0x1c, 0x30, 0x05, 0xeb, 0x48, 0x03, 0x93, 0xf8, 0xac, 0x30, 0x03, 0xf0, + 0x0f, 0x03, 0x01, 0x33, 0x8d, 0xf8, 0x25, 0x30, 0x1b, 0xf0, 0x20, 0xde, + 0x05, 0x9b, 0xcd, 0xf8, 0x1d, 0x00, 0x99, 0x1f, 0xd4, 0xf8, 0x80, 0x00, + 0x13, 0xf0, 0x5c, 0xfb, 0x01, 0x01, 0x3f, 0xf5, 0x0b, 0xad, 0x2b, 0xe5, + 0x1b, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, 0x00, 0xbf, 0xf7, 0xe3, 0x85, 0x00, + 0x8e, 0x88, 0xff, 0xff, 0xb4, 0x88, 0xff, 0xff, 0xc4, 0xd2, 0x85, 0x00, + 0x98, 0xe0, 0x85, 0x00, 0x2d, 0xe9, 0xf0, 0x4f, 0xa7, 0xb0, 0x9a, 0x46, + 0x09, 0x93, 0x9b, 0x8a, 0x00, 0x26, 0x21, 0x2b, 0x04, 0x46, 0x8b, 0x46, + 0x17, 0x46, 0x25, 0x96, 0x12, 0x96, 0x8d, 0xf8, 0x32, 0x60, 0x0d, 0x96, + 0x8d, 0xf8, 0x3b, 0x60, 0x8d, 0xf8, 0x38, 0x60, 0x8d, 0xf8, 0x70, 0x60, + 0x8d, 0xf8, 0x3f, 0x60, 0x0a, 0x92, 0x24, 0x92, 0x1b, 0x96, 0x01, 0xd8, + 0x03, 0x68, 0x46, 0xe0, 0xda, 0xf8, 0x10, 0x50, 0x10, 0x46, 0x29, 0x46, + 0x13, 0xf0, 0x26, 0xfb, 0xab, 0x1d, 0x02, 0x90, 0x04, 0x93, 0xea, 0x88, + 0x93, 0xb2, 0x03, 0xf4, 0x40, 0x71, 0xad, 0xf8, 0x2c, 0x20, 0xa1, 0xf5, + 0x40, 0x7c, 0x10, 0x46, 0x03, 0xf0, 0x0c, 0x0e, 0x03, 0xf0, 0xf0, 0x02, + 0x4f, 0xea, 0x9e, 0x0e, 0x12, 0x09, 0xdc, 0xf1, 0x00, 0x01, 0x41, 0xeb, + 0x0c, 0x01, 0xbe, 0xf1, 0x02, 0x0f, 0x08, 0xbf, 0xd6, 0x08, 0xf6, 0xb2, + 0xad, 0xf8, 0x2e, 0xe0, 0xad, 0xf8, 0x30, 0x20, 0x8d, 0xf8, 0x39, 0x10, + 0x8d, 0xf8, 0x3a, 0x60, 0xb7, 0xf8, 0x04, 0xe0, 0x0e, 0xf0, 0x03, 0x0e, + 0xbe, 0xf1, 0x02, 0x0f, 0x04, 0xd1, 0x00, 0xb2, 0x00, 0x28, 0x01, 0xda, + 0xd2, 0x08, 0x00, 0xe0, 0x00, 0x22, 0xd0, 0xb2, 0x8d, 0xf8, 0x3b, 0x00, + 0x00, 0x29, 0x14, 0xbf, 0x28, 0x22, 0x22, 0x22, 0x06, 0xb1, 0x02, 0x32, + 0x00, 0xb1, 0x04, 0x32, 0x09, 0x98, 0x80, 0x8a, 0x90, 0x42, 0x06, 0xd2, + 0x23, 0x68, 0xd3, 0xf8, 0x8c, 0x30, 0x5a, 0x6e, 0x01, 0x32, 0x5a, 0x66, + 0x77, 0xe3, 0xaa, 0x7a, 0x02, 0xf0, 0x01, 0x02, 0x8d, 0xf8, 0x3c, 0x20, + 0x21, 0xb1, 0x4f, 0xf0, 0x00, 0x08, 0x8d, 0xf8, 0x40, 0x80, 0x13, 0xe0, + 0xd8, 0x05, 0x02, 0xd5, 0x05, 0xf1, 0x0a, 0x01, 0x05, 0xe0, 0x99, 0x05, + 0x4c, 0xbf, 0x05, 0xf1, 0x10, 0x01, 0x05, 0xf1, 0x16, 0x01, 0x20, 0x46, + 0x37, 0xf0, 0x20, 0xda, 0x03, 0x1c, 0x18, 0xbf, 0x01, 0x23, 0x80, 0x46, + 0x8d, 0xf8, 0x40, 0x30, 0x9d, 0xf8, 0x3c, 0x30, 0x43, 0xb9, 0x04, 0x99, + 0x20, 0x46, 0x04, 0x31, 0x37, 0xf0, 0x36, 0xda, 0x06, 0x1c, 0x18, 0xbf, + 0x01, 0x26, 0x00, 0xe0, 0x00, 0x26, 0x94, 0xf8, 0xc8, 0x31, 0x23, 0xb9, + 0x23, 0x68, 0x93, 0xf8, 0x2c, 0x30, 0x33, 0xb9, 0x2d, 0xe0, 0x20, 0x46, + 0x39, 0x46, 0x09, 0x9a, 0x00, 0x23, 0x0d, 0xf0, 0x95, 0xdf, 0x23, 0x68, + 0x93, 0xf8, 0x3f, 0x20, 0x0a, 0xb9, 0x8d, 0xf8, 0x40, 0x20, 0x46, 0xbb, + 0xbd, 0xf8, 0x2c, 0x20, 0xd2, 0x05, 0x05, 0xd4, 0x9d, 0xf8, 0x3c, 0x20, + 0x12, 0xb1, 0x9d, 0xf8, 0x40, 0x20, 0x42, 0xbb, 0x9d, 0xf8, 0x39, 0x20, + 0x12, 0xb1, 0x9d, 0xf8, 0x3c, 0x20, 0x0a, 0xbb, 0x93, 0xf8, 0x2c, 0x30, + 0x00, 0x2b, 0x00, 0xf0, 0x22, 0x83, 0x9d, 0xf8, 0x40, 0x30, 0x00, 0x2b, + 0x00, 0xf0, 0x1d, 0x83, 0x98, 0xf8, 0x06, 0x30, 0x00, 0x2b, 0x40, 0xf0, + 0x18, 0x83, 0x01, 0x26, 0x11, 0xe0, 0x9d, 0xf8, 0x3c, 0x30, 0x1b, 0xb9, + 0x00, 0x2e, 0x00, 0xf0, 0x10, 0x83, 0x00, 0xe0, 0x4e, 0xb1, 0x9d, 0xf8, + 0x39, 0x60, 0x2e, 0xb9, 0x9d, 0xf8, 0x40, 0x30, 0x00, 0x2b, 0x00, 0xf0, + 0x06, 0x83, 0x00, 0xe0, 0x00, 0x26, 0x23, 0x68, 0x93, 0xf8, 0x95, 0x30, + 0x5b, 0xb3, 0xb8, 0xf1, 0x00, 0x0f, 0x28, 0xd0, 0x9d, 0xf8, 0x3c, 0x30, + 0xd8, 0xf8, 0xdc, 0x90, 0x5b, 0xb9, 0x19, 0xf0, 0x01, 0x0f, 0x00, 0xf0, + 0xf4, 0x82, 0x04, 0x98, 0x08, 0xf1, 0xc2, 0x01, 0x04, 0x30, 0x06, 0x22, + 0xf9, 0xf3, 0xe4, 0xf7, 0x14, 0xe0, 0x04, 0x98, 0x04, 0x30, 0xfa, 0xf3, + 0xdb, 0xf4, 0x20, 0xb1, 0x19, 0xf0, 0x08, 0x0f, 0x00, 0xf0, 0xe3, 0x82, + 0x0d, 0xe0, 0x19, 0xf0, 0x04, 0x0f, 0x0a, 0xd1, 0x19, 0xf0, 0x02, 0x0f, + 0x00, 0xf0, 0xdb, 0x82, 0x20, 0x46, 0x04, 0x99, 0x0d, 0xf0, 0x9a, 0xde, + 0x00, 0x28, 0x40, 0xf0, 0xd4, 0x82, 0x09, 0x99, 0x0b, 0x69, 0x06, 0x33, + 0x0b, 0x61, 0x8b, 0x8a, 0x06, 0x3b, 0x8b, 0x82, 0x04, 0x9b, 0x03, 0xf1, + 0x18, 0x02, 0x05, 0x92, 0x9d, 0xf8, 0x39, 0x20, 0x0a, 0xb1, 0x1e, 0x33, + 0x05, 0x93, 0x00, 0x23, 0x8d, 0xf8, 0x3d, 0x30, 0x9d, 0xf8, 0x3a, 0x30, + 0x83, 0xb3, 0x05, 0x9a, 0x13, 0x78, 0x50, 0x78, 0x43, 0xea, 0x00, 0x20, + 0xdb, 0x09, 0x8d, 0xf8, 0x3d, 0x30, 0x83, 0xb1, 0xb8, 0xf1, 0x00, 0x0f, + 0x04, 0xd0, 0x98, 0xf8, 0x19, 0x35, 0x00, 0x2b, 0x40, 0xf0, 0xad, 0x82, + 0x94, 0xf8, 0xcf, 0x31, 0x00, 0x2b, 0x00, 0xf0, 0xa8, 0x82, 0x4b, 0x6a, + 0x43, 0xf0, 0x40, 0x03, 0x4b, 0x62, 0xdf, 0xf8, 0xa8, 0xe5, 0x00, 0xf0, + 0x07, 0x03, 0x1e, 0xf8, 0x03, 0xe0, 0xdf, 0xf8, 0xa0, 0xc5, 0x00, 0xf0, + 0x10, 0x00, 0x1c, 0xf8, 0x0e, 0xe0, 0x00, 0x11, 0x02, 0x32, 0x8d, 0xf8, + 0x32, 0x30, 0xcd, 0xf8, 0x34, 0xe0, 0x8d, 0xf8, 0x38, 0x00, 0x05, 0x92, + 0x8d, 0xf8, 0x70, 0x30, 0x9d, 0xf8, 0x3d, 0x30, 0x1b, 0xb9, 0x8b, 0x8a, + 0x04, 0x3b, 0x8b, 0x82, 0x05, 0xe0, 0x58, 0x46, 0xfa, 0xf3, 0x5c, 0xf5, + 0x83, 0x8a, 0x04, 0x3b, 0x83, 0x82, 0x09, 0x9a, 0x05, 0x99, 0x93, 0x8a, + 0x12, 0x69, 0x07, 0x93, 0xc2, 0xeb, 0x01, 0x08, 0xc8, 0xeb, 0x03, 0x03, + 0x51, 0x46, 0x58, 0x46, 0x06, 0x93, 0xfb, 0xf3, 0xd3, 0xf0, 0x04, 0x99, + 0xc8, 0xeb, 0x00, 0x00, 0x08, 0x90, 0x8b, 0x7d, 0xca, 0x7d, 0x43, 0xea, + 0x02, 0x23, 0xad, 0xf8, 0x8e, 0x30, 0x3e, 0xbb, 0x07, 0x9b, 0x20, 0x46, + 0x00, 0x93, 0x3a, 0x46, 0x25, 0xab, 0x10, 0xf0, 0x2f, 0xda, 0x00, 0x28, + 0x40, 0xf0, 0x5d, 0x82, 0x7d, 0xe2, 0xfa, 0x8a, 0x04, 0x99, 0x02, 0xf4, + 0xff, 0x62, 0x0a, 0x31, 0x70, 0x2a, 0x20, 0x46, 0x94, 0xbf, 0x00, 0x22, + 0x01, 0x22, 0x4d, 0xf0, 0x99, 0xdc, 0x25, 0x90, 0x30, 0xb9, 0x23, 0x68, + 0xd3, 0xf8, 0x8c, 0x30, 0xda, 0x6e, 0x01, 0x32, 0xda, 0x66, 0x46, 0xe2, + 0x03, 0x69, 0xd3, 0xf8, 0xcc, 0x30, 0xc3, 0xf3, 0xc0, 0x13, 0x8d, 0xf8, + 0x3f, 0x30, 0x18, 0xe0, 0xbd, 0xf8, 0x2c, 0x30, 0x13, 0xf4, 0x40, 0x7f, + 0x13, 0xd0, 0x9d, 0xf8, 0x39, 0x30, 0x83, 0xb9, 0x25, 0x9b, 0x73, 0xb9, + 0xfa, 0x8a, 0x0a, 0x31, 0x02, 0xf4, 0xff, 0x62, 0x70, 0x2a, 0x20, 0x46, + 0x94, 0xbf, 0x00, 0x22, 0x01, 0x22, 0x4d, 0xf0, 0x73, 0xdc, 0x25, 0x90, + 0x00, 0x28, 0x00, 0xf0, 0x26, 0x82, 0x25, 0x9b, 0xd3, 0xf8, 0x10, 0x80, + 0xd8, 0xf8, 0xdc, 0x32, 0x03, 0x93, 0x1e, 0xbb, 0x9d, 0xf8, 0x39, 0x30, + 0x03, 0xbb, 0x9d, 0xf8, 0x3c, 0x30, 0x1b, 0xb1, 0xbd, 0xf8, 0x2c, 0x30, + 0xd8, 0x05, 0x12, 0xd4, 0x98, 0xf8, 0x06, 0x20, 0xbd, 0xf8, 0x2c, 0x30, + 0x12, 0xb1, 0xd9, 0x05, 0x0b, 0xd5, 0x11, 0xe0, 0x98, 0xf8, 0x12, 0x20, + 0x03, 0xf4, 0x40, 0x73, 0x00, 0x2a, 0x14, 0xbf, 0x4f, 0xf4, 0x00, 0x72, + 0x00, 0x22, 0x93, 0x42, 0x06, 0xd0, 0x23, 0x68, 0xd3, 0xf8, 0x8c, 0x30, + 0x9a, 0x6d, 0x01, 0x32, 0x9a, 0x65, 0xfa, 0xe1, 0x94, 0xf8, 0x2d, 0x37, + 0x2b, 0xb9, 0x9d, 0xf8, 0x3f, 0x30, 0x13, 0xb9, 0x98, 0xf8, 0x06, 0x20, + 0x42, 0xb9, 0x20, 0x46, 0x39, 0x46, 0x1b, 0xf0, 0x11, 0xdc, 0x81, 0x46, + 0x18, 0xb1, 0x8a, 0xf8, 0x2d, 0x00, 0x00, 0xe0, 0x99, 0x46, 0x98, 0xf8, + 0x06, 0x30, 0x0b, 0xbb, 0x9d, 0xf8, 0x3f, 0x30, 0xf3, 0xb9, 0x49, 0x46, + 0x40, 0x46, 0x1b, 0xf0, 0x43, 0xdc, 0x40, 0x46, 0x1b, 0xf0, 0x98, 0xdb, + 0x39, 0x46, 0x20, 0x46, 0x0f, 0xf0, 0x8e, 0xdc, 0x01, 0x46, 0x40, 0x46, + 0x0e, 0xf0, 0xf0, 0xdb, 0x9d, 0xf8, 0x40, 0x30, 0x63, 0xb1, 0x98, 0xf8, + 0x12, 0x30, 0x4b, 0xb1, 0x98, 0xf8, 0x07, 0x30, 0x33, 0xb1, 0x03, 0x98, + 0x43, 0x79, 0x1b, 0xb9, 0x40, 0x46, 0x01, 0x21, 0x33, 0xf0, 0xe4, 0xd8, + 0x94, 0xf8, 0x2d, 0x37, 0x33, 0xb9, 0x9d, 0xf8, 0x3f, 0x30, 0x1b, 0xb9, + 0x25, 0x9b, 0xd3, 0xf8, 0xfc, 0x30, 0x83, 0xb1, 0xb9, 0xf1, 0x00, 0x0f, + 0x0d, 0xd0, 0x25, 0x9b, 0xd3, 0xf8, 0xf8, 0x10, 0xd3, 0xf8, 0xf4, 0x20, + 0x42, 0xf8, 0x21, 0x90, 0xd3, 0xf8, 0xf8, 0x20, 0x01, 0x32, 0x02, 0xf0, + 0x07, 0x02, 0xc3, 0xf8, 0xf8, 0x20, 0x9d, 0xf8, 0x39, 0x30, 0x23, 0xb1, + 0xb8, 0xf8, 0x62, 0x20, 0xad, 0xf8, 0x78, 0x20, 0x36, 0xe0, 0x98, 0xf8, + 0x06, 0x30, 0x25, 0x99, 0x00, 0x2b, 0x2e, 0xd0, 0x8b, 0x8f, 0xad, 0xf8, + 0x78, 0x30, 0x4b, 0x68, 0x5a, 0x06, 0x1b, 0xd5, 0x9d, 0xf8, 0x3a, 0x20, + 0xc2, 0xb1, 0x04, 0x9a, 0xd2, 0x8a, 0x10, 0x07, 0x14, 0xd1, 0x91, 0xf8, + 0xdf, 0x20, 0x8a, 0xb1, 0x8a, 0x7e, 0xd2, 0x07, 0x0e, 0xd4, 0xbd, 0xf8, + 0x2c, 0x20, 0xd0, 0x04, 0x0a, 0xd5, 0x9a, 0x03, 0x08, 0xd5, 0x0d, 0x9a, + 0x91, 0xf8, 0xd1, 0x30, 0x13, 0x41, 0xdb, 0x07, 0x02, 0xd5, 0x20, 0x46, + 0x2d, 0xf0, 0x36, 0xdb, 0xbd, 0xf8, 0x2c, 0x30, 0x13, 0xf4, 0x80, 0x5f, + 0x25, 0x9b, 0x5a, 0x68, 0x14, 0xbf, 0x42, 0xf4, 0x00, 0x32, 0x22, 0xf4, + 0x00, 0x32, 0x5a, 0x60, 0x02, 0xe0, 0x89, 0x8f, 0xad, 0xf8, 0x78, 0x10, + 0x94, 0xf8, 0x2d, 0x37, 0x1b, 0xb9, 0x25, 0x9b, 0xd3, 0xf8, 0xfc, 0x30, + 0x83, 0xb1, 0xb9, 0xf1, 0x00, 0x0f, 0x0d, 0xd0, 0x25, 0x9b, 0xd3, 0xf8, + 0xf8, 0x10, 0xd3, 0xf8, 0xf4, 0x20, 0x42, 0xf8, 0x21, 0x90, 0xd3, 0xf8, + 0xf8, 0x20, 0x01, 0x32, 0x02, 0xf0, 0x07, 0x02, 0xc3, 0xf8, 0xf8, 0x20, + 0x25, 0x9b, 0xd3, 0xf8, 0x7c, 0x31, 0x5b, 0xb1, 0xd3, 0xf8, 0x08, 0x26, + 0x02, 0x98, 0x03, 0xeb, 0x82, 0x01, 0x01, 0x32, 0x02, 0xf0, 0x3f, 0x02, + 0xc1, 0xf8, 0x0c, 0x06, 0xc3, 0xf8, 0x08, 0x26, 0x98, 0xf8, 0x06, 0x30, + 0x4b, 0xb9, 0x98, 0xf8, 0x12, 0x30, 0x33, 0xb1, 0x9d, 0xf8, 0x3c, 0x30, + 0x1b, 0xb9, 0x16, 0xb9, 0x03, 0x9b, 0x9e, 0x71, 0xde, 0x71, 0x9d, 0xf8, + 0x3c, 0x30, 0x0b, 0xb3, 0x98, 0xf8, 0x06, 0x30, 0x00, 0x2b, 0x40, 0xf0, + 0x2c, 0x81, 0x98, 0xf8, 0x12, 0x30, 0x4b, 0xb1, 0x21, 0x68, 0x04, 0x98, + 0x4e, 0x31, 0x10, 0x30, 0x06, 0x22, 0xf9, 0xf3, 0x19, 0xf6, 0x00, 0x28, + 0x00, 0xf0, 0x1f, 0x81, 0x04, 0x98, 0x04, 0x30, 0xfa, 0xf3, 0x0e, 0xf3, + 0x50, 0xb9, 0x23, 0x68, 0x93, 0xf8, 0x3e, 0x30, 0x33, 0xb9, 0x20, 0x46, + 0x04, 0x99, 0x0d, 0xf0, 0xd5, 0xdc, 0x00, 0x28, 0x40, 0xf0, 0x0f, 0x81, + 0x02, 0x98, 0x9d, 0xf8, 0x3c, 0x30, 0xca, 0xf8, 0x38, 0x00, 0x5b, 0xb9, + 0x2b, 0x78, 0x6a, 0x78, 0x1a, 0x43, 0xab, 0x78, 0x13, 0x43, 0x05, 0xd0, + 0xd4, 0xf8, 0x60, 0x01, 0x02, 0x99, 0x7a, 0x8a, 0x4a, 0xf0, 0x28, 0xde, + 0xda, 0xf8, 0x38, 0x20, 0x12, 0xf0, 0x00, 0x67, 0x1f, 0xd0, 0x02, 0xf4, + 0xe0, 0x60, 0x4f, 0xea, 0x10, 0x20, 0x12, 0xf4, 0x00, 0x0f, 0x8f, 0x4b, + 0x02, 0xf0, 0x7f, 0x01, 0xa0, 0xf1, 0x04, 0x00, 0x08, 0xd0, 0x01, 0x28, + 0x4f, 0xf0, 0x14, 0x00, 0x00, 0xfb, 0x01, 0x33, 0x94, 0xbf, 0xdb, 0x68, + 0x9b, 0x68, 0x0c, 0xe0, 0x01, 0x28, 0x4f, 0xf0, 0x14, 0x00, 0x03, 0xd8, + 0x00, 0xfb, 0x01, 0x33, 0x5b, 0x68, 0x04, 0xe0, 0x41, 0x43, 0x5b, 0x58, + 0x01, 0xe0, 0x02, 0xf0, 0x7f, 0x03, 0x82, 0x49, 0x0b, 0x60, 0x95, 0xf9, + 0x03, 0x30, 0x00, 0x2b, 0x07, 0xda, 0x23, 0x68, 0xd3, 0xf8, 0x8c, 0x30, + 0xd3, 0xf8, 0xd8, 0x12, 0x01, 0x31, 0xc3, 0xf8, 0xd8, 0x12, 0xeb, 0x78, + 0x03, 0xf0, 0x30, 0x03, 0x10, 0x2b, 0x07, 0xd1, 0x23, 0x68, 0xd3, 0xf8, + 0x8c, 0x30, 0xd3, 0xf8, 0xe0, 0x12, 0x01, 0x31, 0xc3, 0xf8, 0xe0, 0x12, + 0x9d, 0xf8, 0x3c, 0x30, 0x00, 0x2b, 0x40, 0xf0, 0x8c, 0x80, 0x23, 0x68, + 0xd3, 0xf8, 0x8c, 0x30, 0xff, 0xb1, 0x02, 0xf4, 0xe0, 0x60, 0x12, 0xf4, + 0x00, 0x0f, 0x4f, 0xea, 0x10, 0x20, 0x6c, 0x49, 0x02, 0xf0, 0x7f, 0x02, + 0xa0, 0xf1, 0x04, 0x00, 0x08, 0xd0, 0x01, 0x28, 0x4f, 0xf0, 0x14, 0x00, + 0x00, 0xfb, 0x02, 0x12, 0x94, 0xbf, 0xd2, 0x68, 0x92, 0x68, 0x0c, 0xe0, + 0x01, 0x28, 0x4f, 0xf0, 0x14, 0x00, 0x03, 0xd8, 0x00, 0xfb, 0x02, 0x12, + 0x52, 0x68, 0x04, 0xe0, 0x42, 0x43, 0x8a, 0x58, 0x01, 0xe0, 0x02, 0xf0, + 0x7f, 0x02, 0x16, 0x2a, 0x3a, 0xd0, 0x0c, 0xd8, 0x0b, 0x2a, 0x25, 0xd0, + 0x04, 0xd8, 0x02, 0x2a, 0x16, 0xd0, 0x04, 0x2a, 0x5b, 0xd1, 0x19, 0xe0, + 0x0c, 0x2a, 0x23, 0xd0, 0x12, 0x2a, 0x56, 0xd1, 0x26, 0xe0, 0x30, 0x2a, + 0x3c, 0xd0, 0x04, 0xd8, 0x18, 0x2a, 0x2d, 0xd0, 0x24, 0x2a, 0x4e, 0xd1, + 0x30, 0xe0, 0x60, 0x2a, 0x40, 0xd0, 0x6c, 0x2a, 0x44, 0xd0, 0x48, 0x2a, + 0x47, 0xd1, 0x35, 0xe0, 0xd3, 0xf8, 0x70, 0x22, 0x01, 0x32, 0xc3, 0xf8, + 0x70, 0x22, 0x40, 0xe0, 0xd3, 0xf8, 0x74, 0x22, 0x01, 0x32, 0xc3, 0xf8, + 0x74, 0x22, 0x3a, 0xe0, 0xd3, 0xf8, 0x78, 0x22, 0x01, 0x32, 0xc3, 0xf8, + 0x78, 0x22, 0x34, 0xe0, 0xd3, 0xf8, 0x7c, 0x22, 0x01, 0x32, 0xc3, 0xf8, + 0x7c, 0x22, 0x2e, 0xe0, 0xd3, 0xf8, 0x80, 0x22, 0x01, 0x32, 0xc3, 0xf8, + 0x80, 0x22, 0x28, 0xe0, 0xd3, 0xf8, 0x84, 0x22, 0x01, 0x32, 0xc3, 0xf8, + 0x84, 0x22, 0x22, 0xe0, 0xd3, 0xf8, 0x88, 0x22, 0x01, 0x32, 0xc3, 0xf8, + 0x88, 0x22, 0x1c, 0xe0, 0xd3, 0xf8, 0x8c, 0x22, 0x01, 0x32, 0xc3, 0xf8, + 0x8c, 0x22, 0x16, 0xe0, 0xd3, 0xf8, 0x90, 0x22, 0x01, 0x32, 0xc3, 0xf8, + 0x90, 0x22, 0x10, 0xe0, 0xd3, 0xf8, 0x94, 0x22, 0x01, 0x32, 0xc3, 0xf8, + 0x94, 0x22, 0x0a, 0xe0, 0xd3, 0xf8, 0x98, 0x22, 0x01, 0x32, 0xc3, 0xf8, + 0x98, 0x22, 0x04, 0xe0, 0xd3, 0xf8, 0x9c, 0x22, 0x01, 0x32, 0xc3, 0xf8, + 0x9c, 0x22, 0x25, 0x99, 0x4b, 0x68, 0x58, 0x03, 0x09, 0xd5, 0x9d, 0xf8, + 0x3c, 0x30, 0x33, 0xb9, 0x2e, 0xb9, 0xd4, 0xf8, 0x40, 0x01, 0x04, 0xaa, + 0x00, 0xf0, 0x1c, 0xfd, 0x03, 0xe0, 0x20, 0x46, 0x04, 0xaa, 0xfe, 0xf7, + 0x43, 0xff, 0x04, 0x9b, 0x1a, 0x7c, 0xd1, 0x07, 0x05, 0xd4, 0x25, 0x9a, + 0xd2, 0xf8, 0x58, 0x11, 0x01, 0x31, 0xc2, 0xf8, 0x58, 0x11, 0x1b, 0x7c, + 0x13, 0xf0, 0x01, 0x0f, 0x25, 0x9b, 0x04, 0xd0, 0xd3, 0xf8, 0x5c, 0x21, + 0x01, 0x32, 0xc3, 0xf8, 0x5c, 0x21, 0x02, 0x9a, 0xc3, 0xf8, 0x64, 0x21, + 0x28, 0xe0, 0x23, 0x68, 0x5a, 0x6b, 0xc2, 0xb1, 0x9d, 0xf8, 0x3c, 0x20, + 0xaa, 0xb9, 0x09, 0x99, 0x14, 0x48, 0xca, 0x8a, 0xd3, 0xf8, 0x90, 0x30, + 0x02, 0xf0, 0x07, 0x02, 0x82, 0x5c, 0x12, 0x48, 0x84, 0x5c, 0x58, 0x46, + 0x0c, 0x34, 0x03, 0xeb, 0xc4, 0x04, 0x63, 0x68, 0xa5, 0x68, 0x01, 0x33, + 0x63, 0x60, 0xfa, 0xf3, 0x47, 0xf6, 0x40, 0x19, 0xa0, 0x60, 0x58, 0x46, + 0x09, 0x99, 0x00, 0x22, 0xfe, 0xf3, 0xc6, 0xf3, 0x06, 0xe0, 0xbd, 0xf8, + 0x2c, 0x30, 0x13, 0xf4, 0x40, 0x7f, 0x7f, 0xf4, 0xb2, 0xad, 0x7a, 0xe5, + 0x27, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, 0x00, 0xbf, 0x84, 0x18, 0x86, 0x00, + 0xb8, 0x07, 0x02, 0x00, 0xc4, 0xd2, 0x85, 0x00, 0x98, 0xe0, 0x85, 0x00, + 0x2d, 0xe9, 0xf0, 0x47, 0xd0, 0xf8, 0x28, 0x38, 0x0e, 0x69, 0x0c, 0x46, + 0xf2, 0x18, 0xd0, 0xf8, 0x04, 0x80, 0x0a, 0x61, 0x89, 0x8a, 0x05, 0x46, + 0xcb, 0x1a, 0x9b, 0xb2, 0xa3, 0x82, 0x31, 0x8a, 0x49, 0x07, 0x07, 0xd5, + 0x01, 0x2b, 0x01, 0xd8, 0x03, 0x68, 0x0f, 0xe0, 0x02, 0x32, 0x02, 0x3b, + 0x22, 0x61, 0xa3, 0x82, 0xa3, 0x8a, 0xd4, 0xf8, 0x10, 0x90, 0x07, 0x2b, + 0x2b, 0x68, 0x05, 0xd9, 0x93, 0xf8, 0x2f, 0x30, 0xb9, 0xf8, 0x06, 0x70, + 0x33, 0xb9, 0x07, 0xe0, 0xd3, 0xf8, 0x8c, 0x30, 0x5a, 0x6e, 0x01, 0x32, + 0x5a, 0x66, 0x4d, 0xe0, 0x40, 0x2f, 0x4b, 0xd0, 0x73, 0x8a, 0xda, 0x07, + 0x24, 0xd4, 0x07, 0xf0, 0x0c, 0x07, 0xbf, 0x10, 0x02, 0x2f, 0x00, 0xd0, + 0xbf, 0xb9, 0x09, 0xf1, 0x10, 0x00, 0xfa, 0xf3, 0x93, 0xf1, 0x18, 0xb9, + 0x99, 0xf8, 0x10, 0x30, 0xdb, 0x07, 0x06, 0xd5, 0x2b, 0x68, 0xd3, 0xf8, + 0x8c, 0x30, 0x5a, 0x6f, 0x01, 0x32, 0x5a, 0x67, 0x32, 0xe0, 0x2b, 0x68, + 0xd3, 0xf8, 0x8c, 0x30, 0xd3, 0xf8, 0xcc, 0x21, 0x01, 0x32, 0xc3, 0xf8, + 0xcc, 0x21, 0xd5, 0xf8, 0x3c, 0x01, 0x28, 0xf0, 0xb3, 0xdb, 0x02, 0x2f, + 0x14, 0xd1, 0x0b, 0xe0, 0x95, 0xf8, 0xcf, 0x31, 0x00, 0x2b, 0x1f, 0xd0, + 0xd5, 0xf8, 0x3c, 0x01, 0x31, 0x46, 0x22, 0x46, 0xbd, 0xe8, 0xf0, 0x47, + 0x28, 0xf0, 0xee, 0x9b, 0x28, 0x46, 0x41, 0x46, 0x32, 0x46, 0x23, 0x46, + 0xbd, 0xe8, 0xf0, 0x47, 0xff, 0xf7, 0x7e, 0xbb, 0x01, 0x2f, 0x07, 0xd8, + 0x28, 0x46, 0x41, 0x46, 0x32, 0x46, 0x23, 0x46, 0xbd, 0xe8, 0xf0, 0x47, + 0xfe, 0xf7, 0x18, 0xba, 0x2b, 0x68, 0xd3, 0xf8, 0x8c, 0x30, 0x1a, 0x6f, + 0x01, 0x32, 0x1a, 0x67, 0x40, 0x46, 0x21, 0x46, 0x00, 0x22, 0xbd, 0xe8, + 0xf0, 0x47, 0xfe, 0xf3, 0x31, 0xb3, 0x2d, 0xe9, 0xf0, 0x47, 0x90, 0xf8, + 0xa0, 0x31, 0x86, 0xb0, 0x04, 0x46, 0x00, 0x2b, 0x40, 0xf0, 0xeb, 0x80, + 0x03, 0x68, 0x18, 0x7e, 0x00, 0x28, 0x00, 0xf0, 0xe7, 0x80, 0x01, 0x23, + 0x84, 0xf8, 0xa0, 0x31, 0x20, 0x69, 0x01, 0xf0, 0x19, 0xfe, 0x23, 0x69, + 0x05, 0x46, 0x93, 0xf8, 0xea, 0x20, 0x52, 0xb1, 0xdb, 0x6e, 0x40, 0xf2, + 0x04, 0x40, 0xd3, 0xf8, 0x20, 0x31, 0x18, 0x40, 0xb0, 0xf5, 0x80, 0x60, + 0x18, 0xbf, 0x01, 0x20, 0x02, 0xe0, 0x18, 0x6e, 0x04, 0xf0, 0xfd, 0xfc, + 0x08, 0xb1, 0x00, 0x26, 0x6d, 0xe0, 0xd4, 0xf8, 0x68, 0x01, 0x04, 0x21, + 0x4b, 0xf0, 0x4a, 0xdf, 0x20, 0x46, 0x1e, 0xf0, 0x3d, 0xda, 0x00, 0xb9, + 0x01, 0x35, 0x26, 0x46, 0x04, 0xf1, 0x20, 0x07, 0xd6, 0xf8, 0x4c, 0x82, + 0xb8, 0xf1, 0x00, 0x0f, 0x57, 0xd0, 0x98, 0xf8, 0x06, 0x90, 0xb9, 0xf1, + 0x00, 0x0f, 0x52, 0xd1, 0x40, 0x46, 0x30, 0xf0, 0x03, 0xd8, 0x98, 0xf8, + 0x05, 0x30, 0x2d, 0x18, 0x00, 0x2b, 0x4a, 0xd0, 0x23, 0x68, 0x20, 0x46, + 0x93, 0xf8, 0x31, 0x30, 0x41, 0x46, 0x00, 0x2b, 0x3c, 0xd0, 0xd8, 0xf8, + 0xcc, 0x30, 0xdb, 0x07, 0x38, 0xd5, 0x06, 0xf0, 0xd9, 0xff, 0x23, 0x68, + 0x2d, 0x18, 0x93, 0xf8, 0x95, 0x30, 0x00, 0x2b, 0x37, 0xd0, 0xd4, 0xf8, + 0x6c, 0x12, 0x20, 0x46, 0xbc, 0x31, 0x4d, 0xf0, 0x0d, 0xd8, 0x82, 0x46, + 0x78, 0xb3, 0x20, 0x46, 0x51, 0x46, 0x1e, 0xf0, 0x25, 0xdc, 0x9a, 0xf8, + 0x18, 0x30, 0x9a, 0x07, 0x1a, 0xd5, 0x02, 0x21, 0x50, 0x46, 0x4c, 0xf0, + 0x51, 0xdc, 0x08, 0x22, 0xcd, 0xf8, 0x00, 0x90, 0x01, 0x92, 0x98, 0xf8, + 0x12, 0x20, 0xd4, 0xf8, 0x6c, 0x32, 0xd2, 0xf1, 0x01, 0x02, 0x38, 0xbf, + 0x00, 0x22, 0x02, 0x92, 0x20, 0x46, 0x41, 0x46, 0x0b, 0x22, 0xbc, 0x33, + 0xcd, 0xf8, 0x0c, 0x90, 0xcd, 0xf8, 0x10, 0x90, 0x14, 0xf0, 0xa8, 0xd9, + 0xd4, 0xf8, 0x6c, 0x32, 0x01, 0x22, 0x83, 0xf8, 0xf0, 0x20, 0x06, 0xe0, + 0x36, 0xf0, 0x52, 0xdb, 0x2d, 0x18, 0x4f, 0xf4, 0x7a, 0x60, 0xfd, 0xf3, + 0xb9, 0xf7, 0x04, 0x36, 0xbe, 0x42, 0x9f, 0xd1, 0x8f, 0xe7, 0xd4, 0xf8, + 0xb4, 0x24, 0x92, 0x19, 0x13, 0x6b, 0x13, 0xb1, 0x50, 0x6a, 0x98, 0x47, + 0x2d, 0x18, 0x34, 0x36, 0x40, 0xf2, 0xac, 0x43, 0x9e, 0x42, 0xf2, 0xd1, + 0x94, 0xf8, 0xf1, 0x31, 0x4b, 0xb1, 0xa0, 0x68, 0xd4, 0xf8, 0xac, 0x11, + 0x06, 0xf0, 0x22, 0xdf, 0x00, 0xb9, 0x01, 0x35, 0x00, 0x23, 0x84, 0xf8, + 0xf1, 0x31, 0x20, 0x46, 0xfa, 0xf7, 0x90, 0xfe, 0x23, 0x68, 0x00, 0x21, + 0x19, 0x76, 0x23, 0x6b, 0x4f, 0xf0, 0xff, 0x32, 0x45, 0x19, 0x18, 0x69, + 0x08, 0xf0, 0xb4, 0xfd, 0x20, 0x46, 0x11, 0xf0, 0x27, 0xde, 0xd4, 0xf8, + 0x78, 0x62, 0x07, 0xe0, 0x00, 0x23, 0x31, 0x1d, 0x60, 0x68, 0x01, 0x22, + 0x00, 0x93, 0xfa, 0xf3, 0xf7, 0xf2, 0x36, 0x68, 0x00, 0x2e, 0xf5, 0xd1, + 0x23, 0x68, 0x93, 0xf8, 0x2f, 0x30, 0x83, 0xb1, 0x26, 0x46, 0x04, 0xf1, + 0x20, 0x07, 0xd6, 0xf8, 0x4c, 0x12, 0x39, 0xb1, 0x8b, 0x79, 0x2b, 0xb1, + 0x0b, 0x79, 0x1b, 0xb1, 0x20, 0x46, 0x06, 0xf0, 0x4f, 0xff, 0x2d, 0x18, + 0x04, 0x36, 0xbe, 0x42, 0xf1, 0xd1, 0xd4, 0xf8, 0x7c, 0x02, 0x10, 0xb1, + 0x06, 0xf0, 0x81, 0xfa, 0x2d, 0x18, 0x20, 0x69, 0x01, 0xf0, 0xd9, 0xfd, + 0x00, 0x23, 0x40, 0x19, 0x84, 0xf8, 0x29, 0x30, 0x84, 0xf8, 0xa0, 0x31, + 0x00, 0xe0, 0x00, 0x20, 0x06, 0xb0, 0xbd, 0xe8, 0xf0, 0x87, 0x00, 0x00, + 0x04, 0x4b, 0x1a, 0x68, 0x22, 0xb1, 0x01, 0x22, 0x80, 0xf8, 0x9d, 0x23, + 0x00, 0x22, 0x1a, 0x60, 0x70, 0x47, 0x00, 0xbf, 0xe4, 0x07, 0x02, 0x00, + 0xf8, 0xb5, 0x14, 0x46, 0x1d, 0x46, 0xd2, 0xf8, 0xf0, 0x30, 0xd2, 0x78, + 0xb4, 0xf8, 0x56, 0x60, 0x03, 0xeb, 0x42, 0x03, 0xb3, 0xf8, 0xbe, 0x20, + 0xf6, 0x43, 0x96, 0x19, 0x36, 0x05, 0x36, 0x0d, 0xb4, 0xf8, 0x5a, 0x30, + 0x0f, 0x46, 0x71, 0x19, 0x99, 0x42, 0x15, 0xdd, 0x61, 0x78, 0x99, 0x42, + 0x54, 0xd8, 0xa1, 0x78, 0x00, 0x29, 0x51, 0xd1, 0x01, 0x3a, 0x12, 0x05, + 0x12, 0x0d, 0x9e, 0x42, 0xa4, 0xf8, 0x56, 0x20, 0x02, 0xd8, 0x9d, 0x1b, + 0xad, 0xb2, 0x2d, 0xb9, 0x24, 0x48, 0x00, 0x21, 0x32, 0x46, 0x06, 0xf0, + 0x63, 0xff, 0x00, 0x25, 0xb4, 0xf8, 0x5a, 0x30, 0x9e, 0x1b, 0xa3, 0x78, + 0x76, 0x1b, 0xeb, 0x18, 0xa4, 0xf8, 0x5a, 0x60, 0xa3, 0x70, 0x35, 0xe0, + 0xe1, 0x78, 0x07, 0xf1, 0x10, 0x00, 0xfa, 0xf3, 0x05, 0xf3, 0x43, 0x6a, + 0x02, 0x46, 0x43, 0xf4, 0x80, 0x63, 0x43, 0x62, 0xe0, 0x78, 0xd4, 0xf8, + 0xf0, 0x10, 0x5c, 0x30, 0x01, 0xeb, 0x40, 0x00, 0xc6, 0x88, 0x4f, 0xf0, + 0x01, 0x0e, 0x33, 0x05, 0x1b, 0x0d, 0x01, 0x36, 0xc6, 0x80, 0x03, 0xf0, + 0x3f, 0x06, 0x04, 0xeb, 0xd6, 0x00, 0x06, 0xf0, 0x07, 0x06, 0x0e, 0xfa, + 0x06, 0xf6, 0x13, 0x85, 0x90, 0xf8, 0x44, 0xe0, 0xa4, 0xf8, 0x56, 0x30, + 0x46, 0xea, 0x0e, 0x06, 0x80, 0xf8, 0x44, 0x60, 0xe3, 0x78, 0xd1, 0xf8, + 0x2c, 0x01, 0xdf, 0xf8, 0x20, 0xe0, 0x03, 0xf0, 0x07, 0x03, 0x86, 0x6c, + 0x1e, 0xf8, 0x03, 0x30, 0xc0, 0x6c, 0xb0, 0x47, 0x01, 0x3d, 0xad, 0xb2, + 0x00, 0x2d, 0xc7, 0xd1, 0xf8, 0xbd, 0x00, 0xbf, 0x31, 0xbd, 0x01, 0x00, + 0x90, 0xe0, 0x85, 0x00, 0x2d, 0xe9, 0xf0, 0x41, 0x92, 0xf8, 0xe5, 0x30, + 0x06, 0x46, 0x14, 0x46, 0xd0, 0xf8, 0x40, 0x51, 0xab, 0xb1, 0x2a, 0x46, + 0x00, 0x23, 0xd2, 0xf8, 0x50, 0x12, 0xa1, 0x42, 0x04, 0xd1, 0x94, 0x33, + 0x00, 0x22, 0x45, 0xf8, 0x23, 0x20, 0x03, 0xe0, 0x01, 0x33, 0x04, 0x32, + 0x0a, 0x2b, 0xf2, 0xd1, 0x70, 0x68, 0x21, 0x46, 0xf4, 0x22, 0xbd, 0xe8, + 0xf0, 0x41, 0xfe, 0xf3, 0x81, 0xb1, 0x82, 0xf8, 0xe4, 0x30, 0x8b, 0x07, + 0x3f, 0xd5, 0xb2, 0xf8, 0x54, 0x30, 0xb2, 0xf8, 0x5c, 0x80, 0x2b, 0xe0, + 0x03, 0xf0, 0x3f, 0x01, 0x04, 0xeb, 0xd1, 0x02, 0x92, 0xf8, 0x4c, 0xc0, + 0x01, 0xf0, 0x07, 0x00, 0x4c, 0xfa, 0x00, 0xf7, 0x17, 0xf0, 0x01, 0x0f, + 0x1b, 0xd0, 0x4f, 0xf0, 0x01, 0x0e, 0x0e, 0xfa, 0x00, 0xfe, 0x92, 0xf8, + 0x44, 0x70, 0x6f, 0xea, 0x0e, 0x0e, 0x57, 0xfa, 0x00, 0xf0, 0x5f, 0xfa, + 0x8e, 0xfe, 0x0e, 0xea, 0x0c, 0x0c, 0xc0, 0x07, 0x82, 0xf8, 0x4c, 0xc0, + 0x09, 0xd5, 0x0e, 0xea, 0x07, 0x07, 0x82, 0xf8, 0x44, 0x70, 0x61, 0x18, + 0x00, 0x22, 0x0a, 0x71, 0xa2, 0x78, 0x01, 0x3a, 0xa2, 0x70, 0x01, 0x33, + 0x1b, 0x05, 0x1b, 0x0d, 0x43, 0x45, 0xd1, 0xd1, 0xd4, 0xf8, 0xf0, 0x20, + 0x6b, 0x68, 0x28, 0x46, 0xd1, 0x58, 0x22, 0x46, 0x24, 0xf0, 0xf8, 0xdf, + 0x94, 0xf8, 0xe8, 0x30, 0x01, 0x3b, 0x84, 0xf8, 0xe8, 0x30, 0xd4, 0xf8, + 0xf0, 0x20, 0x6b, 0x68, 0x30, 0x46, 0xd1, 0x58, 0x22, 0x46, 0x25, 0xf0, + 0xcf, 0xdd, 0xd6, 0xf8, 0x40, 0x01, 0x21, 0x46, 0x00, 0x22, 0xbd, 0xe8, + 0xf0, 0x41, 0x25, 0xf0, 0xc9, 0x9c, 0x00, 0x00, 0x37, 0xb5, 0x04, 0x46, + 0x94, 0xf8, 0x9d, 0x53, 0x00, 0x68, 0x01, 0x2d, 0x08, 0xd1, 0x13, 0xf0, + 0x3d, 0xda, 0x02, 0x28, 0x04, 0xdd, 0x00, 0x23, 0x84, 0xf8, 0x9d, 0x33, + 0x05, 0x4b, 0x1d, 0x60, 0x21, 0x7d, 0x94, 0xf9, 0x28, 0x20, 0x00, 0x91, + 0xe3, 0x7c, 0x03, 0x49, 0x03, 0x48, 0x06, 0xf0, 0x8d, 0xfe, 0x3e, 0xbd, + 0xe4, 0x07, 0x02, 0x00, 0xfc, 0xbc, 0x01, 0x00, 0x6d, 0xbd, 0x01, 0x00, + 0x2d, 0xe9, 0xf0, 0x47, 0x96, 0x88, 0x05, 0x46, 0x17, 0x46, 0x04, 0x68, + 0xb2, 0xf8, 0x0a, 0xa0, 0x06, 0xf0, 0x07, 0x06, 0x4f, 0xf0, 0x00, 0x08, + 0x37, 0xe0, 0x0b, 0x69, 0x60, 0x68, 0xb3, 0xf8, 0x00, 0x90, 0xd5, 0xf8, + 0x78, 0x32, 0x9a, 0x6e, 0x01, 0x32, 0x9a, 0x66, 0x01, 0x22, 0xfe, 0xf3, + 0x0b, 0xf1, 0x23, 0x68, 0x93, 0xf8, 0xa1, 0x30, 0x01, 0x2b, 0x04, 0xd0, + 0x09, 0xf4, 0xc0, 0x69, 0xb9, 0xf5, 0xc0, 0x6f, 0x17, 0xe0, 0x18, 0x21, + 0x71, 0x43, 0x01, 0xf5, 0x20, 0x71, 0x6b, 0x18, 0xda, 0x88, 0x58, 0x88, + 0x90, 0x42, 0x02, 0xd1, 0x69, 0x5a, 0xd9, 0x80, 0x01, 0xe0, 0x01, 0x32, + 0xda, 0x80, 0x08, 0xf1, 0x01, 0x08, 0x01, 0x22, 0x20, 0x46, 0x31, 0x46, + 0x1f, 0xfa, 0x88, 0xf8, 0x21, 0xf0, 0x4e, 0xdf, 0xd0, 0x45, 0x0a, 0xd0, + 0x23, 0x69, 0x02, 0x21, 0x03, 0xeb, 0x86, 0x03, 0xd8, 0x68, 0x13, 0x4b, + 0x9b, 0x6b, 0x98, 0x47, 0x01, 0x46, 0x00, 0x29, 0xc5, 0xd1, 0x23, 0x68, + 0x93, 0xf8, 0xa1, 0x30, 0x01, 0x2b, 0x05, 0xd0, 0x20, 0x46, 0x31, 0x46, + 0x95, 0xf9, 0x2c, 0x20, 0x21, 0xf0, 0x36, 0xdf, 0xfb, 0x88, 0x9a, 0x07, + 0x09, 0xd4, 0xbd, 0xe8, 0xf0, 0x87, 0x01, 0x3d, 0x01, 0x20, 0xed, 0xb2, + 0xfd, 0xf3, 0xe4, 0xf5, 0x15, 0xb9, 0xbd, 0xe8, 0xf0, 0x87, 0x0b, 0x25, + 0xe3, 0x68, 0xd3, 0xf8, 0x70, 0x31, 0xdb, 0x07, 0xf1, 0xd5, 0xbd, 0xe8, + 0xf0, 0x87, 0x00, 0xbf, 0xe0, 0xa6, 0x85, 0x00, 0x2d, 0xe9, 0xf3, 0x47, + 0xd0, 0xf8, 0x00, 0x80, 0x04, 0x46, 0x01, 0xa9, 0xd8, 0xf8, 0x00, 0x05, + 0x4c, 0xf0, 0x8a, 0xda, 0x4f, 0xf0, 0x00, 0x0a, 0x39, 0xe0, 0x6b, 0x68, + 0x5a, 0x03, 0x36, 0xd5, 0x63, 0x68, 0x00, 0x26, 0x55, 0xf8, 0x03, 0x90, + 0x4f, 0x46, 0xd7, 0xf8, 0xf8, 0x30, 0x4b, 0xb3, 0x9a, 0x78, 0x19, 0x79, + 0x00, 0x2a, 0x18, 0xbf, 0x4f, 0xf0, 0x01, 0x0a, 0x19, 0xb1, 0x00, 0x22, + 0x1a, 0x71, 0xda, 0x70, 0x1e, 0xe0, 0xea, 0xb1, 0xda, 0x78, 0x01, 0x32, + 0xd2, 0xb2, 0xda, 0x70, 0x6b, 0x68, 0x13, 0xf4, 0x80, 0x7f, 0x14, 0xbf, + 0x61, 0x8e, 0xa1, 0x8e, 0x4f, 0xf0, 0x64, 0x03, 0xb1, 0xfb, 0xf3, 0xf3, + 0x9a, 0x42, 0x0b, 0xd3, 0xd4, 0xf8, 0x78, 0x32, 0x40, 0x46, 0xd3, 0xf8, + 0xc4, 0x20, 0x49, 0x46, 0x01, 0x32, 0xc3, 0xf8, 0xc4, 0x20, 0x32, 0x46, + 0x25, 0xf0, 0x9c, 0xda, 0x4f, 0xf0, 0x01, 0x0a, 0x01, 0x36, 0xf6, 0xb2, + 0x04, 0x37, 0x08, 0x2e, 0xcd, 0xd1, 0x01, 0xa8, 0x4c, 0xf0, 0x52, 0xda, + 0x05, 0x46, 0x00, 0x28, 0xbf, 0xd1, 0xba, 0xf1, 0x00, 0x0f, 0x06, 0xd1, + 0x23, 0x68, 0x84, 0xf8, 0xa3, 0xa3, 0x98, 0x68, 0xa1, 0x6b, 0x06, 0xf0, + 0x01, 0xdd, 0xbd, 0xe8, 0xfc, 0x87, 0x43, 0x68, 0xf7, 0xb5, 0xcd, 0x58, + 0x06, 0x46, 0x2f, 0x46, 0x00, 0x24, 0x30, 0x46, 0x29, 0x46, 0x22, 0x46, + 0x23, 0xf0, 0x46, 0xdd, 0xd7, 0xf8, 0xd8, 0x30, 0x4b, 0xb1, 0x1b, 0x78, + 0x01, 0x2b, 0x06, 0xd1, 0x25, 0x22, 0x00, 0x92, 0x30, 0x46, 0x29, 0x46, + 0x22, 0x46, 0x25, 0xf0, 0x5b, 0xdc, 0x22, 0x46, 0x01, 0x34, 0x01, 0x23, + 0x30, 0x46, 0x29, 0x46, 0xe4, 0xb2, 0x23, 0xf0, 0x9d, 0xdc, 0x04, 0x37, + 0x08, 0x2c, 0xe2, 0xd1, 0x32, 0x68, 0x00, 0x23, 0x00, 0x93, 0x50, 0x68, + 0x05, 0xf1, 0x10, 0x01, 0x01, 0x22, 0xfa, 0xf3, 0xc7, 0xf0, 0xfe, 0xbd, + 0x10, 0xb5, 0x03, 0x68, 0x04, 0x46, 0x5b, 0x7e, 0x7b, 0xb9, 0x08, 0x49, + 0x08, 0x48, 0x06, 0xf0, 0x8d, 0xfd, 0x20, 0x46, 0xff, 0xf7, 0xf7, 0xfc, + 0x04, 0x49, 0x06, 0x48, 0x06, 0xf0, 0x86, 0xfd, 0x20, 0x46, 0xbd, 0xe8, + 0x10, 0x40, 0xfc, 0xf7, 0x32, 0xbb, 0x10, 0xbd, 0x1f, 0xbd, 0x01, 0x00, + 0xb2, 0xbd, 0x01, 0x00, 0xc0, 0xbd, 0x01, 0x00, 0x2d, 0xe9, 0xf0, 0x4f, + 0xd0, 0xf8, 0x00, 0x80, 0x87, 0xb0, 0x05, 0x46, 0x05, 0xa9, 0xd8, 0xf8, + 0x00, 0x05, 0x4c, 0xf0, 0xe7, 0xd9, 0x00, 0x22, 0x03, 0x92, 0xe5, 0xe0, + 0x02, 0x9a, 0x53, 0x68, 0x5b, 0x03, 0x40, 0xf1, 0xe1, 0x80, 0xd8, 0xf8, + 0x40, 0x31, 0x4f, 0xf0, 0x00, 0x0a, 0x5b, 0x68, 0xd6, 0x58, 0xb1, 0x46, + 0xd9, 0xf8, 0xf8, 0x30, 0x0a, 0xf1, 0x8c, 0x01, 0x5f, 0xfa, 0x8a, 0xf7, + 0x06, 0xeb, 0x41, 0x02, 0x1b, 0xb1, 0x00, 0x23, 0x53, 0x70, 0x06, 0xf8, + 0x11, 0x30, 0x16, 0xf8, 0x11, 0x30, 0x83, 0xb1, 0x00, 0x23, 0x06, 0xf8, + 0x11, 0x30, 0x51, 0x78, 0x01, 0x31, 0xc9, 0xb2, 0x02, 0x29, 0x51, 0x70, + 0x07, 0xd9, 0x53, 0x70, 0x26, 0x22, 0x00, 0x92, 0x28, 0x46, 0x31, 0x46, + 0x3a, 0x46, 0x25, 0xf0, 0xef, 0xdb, 0xd9, 0xf8, 0xd8, 0x40, 0x00, 0x2c, + 0x00, 0xf0, 0xac, 0x80, 0x23, 0x78, 0x03, 0x2b, 0x00, 0xf2, 0xa8, 0x80, + 0xdf, 0xe8, 0x03, 0xf0, 0x95, 0x02, 0x60, 0x7d, 0x28, 0x46, 0x31, 0x46, + 0x22, 0x46, 0x01, 0x23, 0x25, 0xf0, 0x0c, 0xdc, 0x94, 0xf8, 0xe7, 0xb0, + 0xbb, 0xf1, 0x00, 0x0f, 0x1c, 0xd0, 0xbb, 0xf1, 0x01, 0x0f, 0x11, 0xd1, + 0xe1, 0x78, 0x06, 0xf1, 0x10, 0x00, 0xfa, 0xf3, 0xd1, 0xf0, 0x01, 0x46, + 0x50, 0xb1, 0xd8, 0xf8, 0x00, 0x30, 0x5a, 0x46, 0xd8, 0x68, 0xfd, 0xf3, + 0xb5, 0xf7, 0xd5, 0xf8, 0x78, 0x32, 0xda, 0x6b, 0x01, 0x32, 0xda, 0x63, + 0x00, 0x22, 0x84, 0xf8, 0xe7, 0x20, 0x28, 0x46, 0x21, 0x46, 0x25, 0xf0, + 0x2d, 0xdb, 0x7b, 0xe0, 0x94, 0xf8, 0xe8, 0x30, 0x31, 0x2b, 0x08, 0xd9, + 0x27, 0x23, 0x00, 0x93, 0x28, 0x46, 0x31, 0x46, 0x3a, 0x46, 0x01, 0x23, + 0x25, 0xf0, 0xae, 0xdb, 0x6e, 0xe0, 0x94, 0xf8, 0xe6, 0x30, 0x23, 0xb1, + 0x84, 0xf8, 0xe6, 0xb0, 0x84, 0xf8, 0xeb, 0xb0, 0x66, 0xe0, 0xa3, 0x78, + 0x23, 0xb1, 0x94, 0xf8, 0xeb, 0x30, 0x01, 0x33, 0x84, 0xf8, 0xeb, 0x30, + 0x94, 0xf8, 0xeb, 0x30, 0x02, 0x2b, 0x5b, 0xd1, 0xd5, 0xf8, 0x78, 0x32, + 0x28, 0x46, 0x5a, 0x6e, 0x31, 0x46, 0x01, 0x32, 0x5a, 0x66, 0x27, 0x23, + 0x00, 0x93, 0x3a, 0x46, 0x01, 0x23, 0x25, 0xf0, 0x8d, 0xdb, 0x01, 0x23, + 0x28, 0x46, 0x31, 0x46, 0x3a, 0x46, 0x23, 0xf0, 0xd1, 0xdb, 0x01, 0x23, + 0x03, 0x93, 0x45, 0xe0, 0x94, 0xf8, 0xe9, 0x30, 0x5a, 0x1c, 0x03, 0x2b, + 0x84, 0xf8, 0xe9, 0x20, 0x04, 0xd9, 0x30, 0x46, 0x21, 0x46, 0x23, 0xf0, + 0x91, 0xdb, 0x39, 0xe0, 0xaa, 0x7c, 0xeb, 0x7c, 0x00, 0x92, 0x95, 0xf8, + 0x2e, 0x20, 0x28, 0x68, 0x01, 0x92, 0x02, 0x99, 0x3a, 0x46, 0x25, 0xf0, + 0xa5, 0xde, 0xd5, 0xf8, 0x78, 0x32, 0x1a, 0x6d, 0x01, 0x32, 0x1a, 0x65, + 0x28, 0xe0, 0x94, 0xf8, 0xea, 0x30, 0x5a, 0x1c, 0x01, 0x2b, 0x84, 0xf8, + 0xea, 0x20, 0x09, 0xd9, 0xd5, 0xf8, 0x78, 0x32, 0x28, 0x46, 0x5a, 0x6e, + 0x31, 0x46, 0x01, 0x32, 0x5a, 0x66, 0x3a, 0x46, 0x01, 0x23, 0x03, 0xe0, + 0x28, 0x46, 0x31, 0x46, 0x3a, 0x46, 0x00, 0x23, 0x23, 0xf0, 0x9a, 0xdb, + 0x10, 0xe0, 0x94, 0xf8, 0xec, 0x30, 0x5a, 0x1c, 0x3b, 0x2b, 0x84, 0xf8, + 0xec, 0x20, 0x09, 0xd9, 0x28, 0x46, 0x31, 0x46, 0x3a, 0x46, 0x00, 0x23, + 0x24, 0xf0, 0x2a, 0xde, 0x10, 0xb1, 0x04, 0x23, 0x80, 0xf8, 0xe9, 0x30, + 0x0a, 0xf1, 0x01, 0x0a, 0xba, 0xf1, 0x08, 0x0f, 0x09, 0xf1, 0x04, 0x09, + 0x7f, 0xf4, 0x26, 0xaf, 0x05, 0xa8, 0x4c, 0xf0, 0x03, 0xd9, 0x02, 0x90, + 0x00, 0x28, 0x7f, 0xf4, 0x13, 0xaf, 0x03, 0x9a, 0x09, 0x4b, 0x12, 0xb1, + 0x1a, 0x68, 0x01, 0x32, 0x00, 0xe0, 0x03, 0x9a, 0x1a, 0x60, 0x1b, 0x68, + 0x01, 0x2b, 0x05, 0xdd, 0x40, 0x46, 0xff, 0xf7, 0xdb, 0xfe, 0x03, 0x4b, + 0x00, 0x22, 0x1a, 0x60, 0x00, 0x20, 0x07, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, + 0xe8, 0x07, 0x02, 0x00, 0xf8, 0xb5, 0x05, 0x46, 0x17, 0x46, 0xc1, 0xb1, + 0x4b, 0x68, 0x5b, 0x03, 0x15, 0xd5, 0x43, 0x68, 0x00, 0x24, 0xce, 0x58, + 0x33, 0x19, 0xd3, 0xf8, 0xd8, 0x10, 0x59, 0xb1, 0x37, 0xb1, 0x91, 0xf8, + 0xe4, 0x30, 0x01, 0x2b, 0x02, 0xd1, 0x00, 0x23, 0x81, 0xf8, 0xe4, 0x30, + 0x28, 0x46, 0x00, 0x22, 0x25, 0xf0, 0x70, 0xda, 0x04, 0x34, 0x20, 0x2c, + 0xec, 0xd1, 0xf8, 0xbd, 0x2d, 0xe9, 0xf0, 0x43, 0x13, 0x8c, 0x85, 0xb0, + 0x08, 0x2b, 0x04, 0x46, 0x89, 0x46, 0x15, 0x46, 0x92, 0xf8, 0x22, 0x80, + 0x06, 0x68, 0x01, 0xd0, 0x30, 0x46, 0x20, 0xe0, 0x43, 0x68, 0xcf, 0x58, + 0x08, 0xf1, 0x3e, 0x03, 0x11, 0x68, 0x57, 0xf8, 0x23, 0x20, 0xda, 0xb9, + 0xab, 0x69, 0x9b, 0x88, 0x03, 0xf0, 0x03, 0x03, 0x02, 0x2b, 0x0f, 0xd1, + 0x11, 0xf8, 0x03, 0x3c, 0x1b, 0x07, 0x0b, 0xd5, 0x01, 0x23, 0x08, 0xf1, + 0x8c, 0x08, 0x07, 0xf8, 0x18, 0x30, 0xd0, 0xf8, 0x78, 0x32, 0xd3, 0xf8, + 0xb4, 0x20, 0x01, 0x32, 0xc3, 0xf8, 0xb4, 0x20, 0x30, 0x46, 0x49, 0x46, + 0x2a, 0x46, 0xfe, 0xf7, 0xfb, 0xf9, 0x12, 0xe1, 0xd9, 0xf8, 0x04, 0x30, + 0xd8, 0x03, 0x15, 0xd4, 0xab, 0x69, 0x9b, 0x88, 0x03, 0xf0, 0x03, 0x03, + 0x02, 0x2b, 0x0f, 0xd1, 0x11, 0xf8, 0x03, 0x3c, 0x1b, 0x07, 0x0b, 0xd5, + 0x08, 0xf1, 0x8c, 0x03, 0x01, 0x20, 0x07, 0xf8, 0x13, 0x00, 0xd4, 0xf8, + 0x78, 0x32, 0xd3, 0xf8, 0xb4, 0x00, 0x01, 0x30, 0xc3, 0xf8, 0xb4, 0x00, + 0xab, 0x69, 0x9b, 0x88, 0x03, 0xf0, 0x03, 0x03, 0x02, 0x2b, 0xd4, 0xf8, + 0x78, 0x32, 0x38, 0xd1, 0x11, 0xf8, 0x03, 0x0c, 0x00, 0x07, 0x1e, 0xd5, + 0xd3, 0xf8, 0x9c, 0x00, 0x01, 0x30, 0xc3, 0xf8, 0x9c, 0x00, 0xd3, 0xf8, + 0xa0, 0x00, 0x01, 0x30, 0xc3, 0xf8, 0xa0, 0x00, 0x11, 0xf9, 0x03, 0x0c, + 0x00, 0x28, 0x04, 0xda, 0xd3, 0xf8, 0xac, 0x00, 0x01, 0x30, 0xc3, 0xf8, + 0xac, 0x00, 0x11, 0xf8, 0x03, 0x1c, 0x01, 0xf0, 0x30, 0x01, 0x10, 0x29, + 0x20, 0xd1, 0xd3, 0xf8, 0xb0, 0x10, 0x01, 0x31, 0xc3, 0xf8, 0xb0, 0x10, + 0x1a, 0xe0, 0x11, 0xf8, 0x05, 0xcc, 0x11, 0xf8, 0x06, 0x0c, 0x11, 0xf8, + 0x04, 0x1c, 0x4c, 0xea, 0x00, 0x00, 0x01, 0x43, 0x05, 0xd1, 0xd3, 0xf8, + 0xa0, 0x10, 0x01, 0x31, 0xc3, 0xf8, 0xa0, 0x10, 0x0a, 0xe0, 0xd3, 0xf8, + 0xa4, 0x10, 0x01, 0x31, 0xc3, 0xf8, 0xa4, 0x10, 0x04, 0xe0, 0xd3, 0xf8, + 0xa8, 0x10, 0x01, 0x31, 0xc3, 0xf8, 0xa8, 0x10, 0xb5, 0xf8, 0x7e, 0x10, + 0x08, 0x07, 0x40, 0xf0, 0x9a, 0x80, 0xd3, 0x88, 0x09, 0x09, 0x99, 0x42, + 0x23, 0xd1, 0x01, 0x23, 0xc9, 0x18, 0x09, 0x05, 0x13, 0x71, 0x09, 0x0d, + 0xd1, 0x80, 0xd9, 0xf8, 0x28, 0x40, 0x09, 0xf1, 0x1a, 0x01, 0x06, 0x22, + 0x02, 0xa8, 0xf8, 0xf3, 0x6b, 0xf7, 0x30, 0x46, 0x49, 0x46, 0x2a, 0x46, + 0xfe, 0xf7, 0x7e, 0xf9, 0x30, 0x46, 0x02, 0xa9, 0x22, 0x46, 0x4c, 0xf0, + 0x7d, 0xdb, 0x00, 0x28, 0x00, 0xf0, 0x8f, 0x80, 0x48, 0x45, 0x40, 0xf0, + 0x8c, 0x80, 0x30, 0x46, 0x39, 0x46, 0x42, 0x46, 0x25, 0xf0, 0xe8, 0xd8, + 0x85, 0xe0, 0x01, 0xf0, 0x0f, 0x09, 0xc9, 0x1a, 0x09, 0x05, 0x53, 0x78, + 0x09, 0x0d, 0x99, 0x42, 0x05, 0xd2, 0x09, 0xf1, 0x02, 0x03, 0x52, 0xf8, + 0x23, 0x10, 0x19, 0xb9, 0x44, 0xe0, 0xb1, 0xf5, 0x00, 0x6f, 0x0c, 0xd9, + 0x00, 0x22, 0x70, 0x68, 0x69, 0x69, 0xfd, 0xf3, 0x13, 0xf6, 0xd4, 0xf8, + 0x78, 0x32, 0xd3, 0xf8, 0xc0, 0x20, 0x01, 0x32, 0xc3, 0xf8, 0xc0, 0x20, + 0x67, 0xe0, 0xc3, 0xf1, 0x01, 0x03, 0xcb, 0x18, 0x9b, 0xb2, 0x30, 0x46, + 0x39, 0x46, 0x42, 0x46, 0x25, 0xf0, 0x54, 0xd8, 0x08, 0xf1, 0x3e, 0x03, + 0x57, 0xf8, 0x23, 0x30, 0x6b, 0xb1, 0x69, 0x69, 0x09, 0xf1, 0x02, 0x02, + 0x43, 0xf8, 0x22, 0x10, 0xd5, 0xf8, 0x80, 0x20, 0x09, 0xf1, 0x12, 0x09, + 0x43, 0xf8, 0x29, 0x20, 0x9a, 0x78, 0x01, 0x32, 0x9a, 0x70, 0x42, 0x46, + 0x30, 0x46, 0x39, 0x46, 0x25, 0xf0, 0xa8, 0xd8, 0xd4, 0xf8, 0x78, 0x32, + 0xd3, 0xf8, 0xc8, 0x20, 0x01, 0x32, 0xc3, 0xf8, 0xc8, 0x20, 0x94, 0xf8, + 0xa3, 0x33, 0x00, 0x2b, 0x3b, 0xd1, 0x01, 0x23, 0x84, 0xf8, 0xa3, 0x33, + 0xb0, 0x68, 0xa1, 0x6b, 0x64, 0x22, 0x06, 0xf0, 0x2d, 0xda, 0x32, 0xe0, + 0x69, 0x69, 0x09, 0xf1, 0x12, 0x09, 0x42, 0xf8, 0x23, 0x10, 0xd5, 0xf8, + 0x80, 0x30, 0x42, 0xf8, 0x29, 0x30, 0x93, 0x78, 0x01, 0x33, 0x93, 0x70, + 0x94, 0xf8, 0xa3, 0x33, 0x3b, 0xb9, 0x01, 0x23, 0x84, 0xf8, 0xa3, 0x33, + 0xb0, 0x68, 0xa1, 0x6b, 0x64, 0x22, 0x06, 0xf0, 0x15, 0xda, 0xd4, 0xf8, + 0x78, 0x32, 0xd3, 0xf8, 0xbc, 0x20, 0x01, 0x32, 0xc3, 0xf8, 0xbc, 0x20, + 0x13, 0xe0, 0x70, 0x68, 0x69, 0x69, 0x00, 0x22, 0xfd, 0xf3, 0xb2, 0xf5, + 0xd4, 0xf8, 0x78, 0x32, 0x20, 0x46, 0xd3, 0xf8, 0xdc, 0x20, 0x39, 0x46, + 0x01, 0x32, 0xc3, 0xf8, 0xdc, 0x20, 0x01, 0x23, 0x00, 0x93, 0x42, 0x46, + 0x00, 0x23, 0x25, 0xf0, 0xb5, 0xd9, 0x05, 0xb0, 0xbd, 0xe8, 0xf0, 0x83, + 0x03, 0x68, 0x1b, 0x68, 0x19, 0xb1, 0x01, 0x22, 0x83, 0xf8, 0xaa, 0x20, + 0x70, 0x47, 0x83, 0xf8, 0xaa, 0x10, 0x70, 0x47, 0x70, 0xb5, 0xd0, 0xf8, + 0xac, 0x53, 0x02, 0x29, 0x2b, 0x68, 0x08, 0xbf, 0x00, 0xf5, 0x75, 0x74, + 0xd3, 0xf8, 0x8c, 0x20, 0x18, 0xbf, 0x00, 0x24, 0x13, 0x6c, 0x06, 0x46, + 0x50, 0x68, 0x22, 0x69, 0xc3, 0x18, 0x9a, 0x1a, 0x23, 0x61, 0xa3, 0x69, + 0x9a, 0x42, 0x23, 0x78, 0x0e, 0xd2, 0x4b, 0xb9, 0xe2, 0x68, 0x63, 0x69, + 0x9a, 0x42, 0x05, 0xd3, 0x01, 0x23, 0x23, 0x70, 0x63, 0x68, 0x01, 0x33, + 0x63, 0x60, 0x70, 0xbd, 0xe3, 0x68, 0x01, 0x33, 0xe3, 0x60, 0x70, 0xbd, + 0x00, 0x22, 0xe2, 0x60, 0x13, 0xb3, 0x01, 0x29, 0x04, 0xd1, 0x28, 0x46, + 0x03, 0x21, 0x20, 0xf0, 0xe5, 0xde, 0x19, 0xe0, 0x02, 0x29, 0x17, 0xd1, + 0xa8, 0x68, 0xd6, 0xf8, 0xd0, 0x13, 0x06, 0xf0, 0xfd, 0xd9, 0xd6, 0xf8, + 0xcc, 0x33, 0x7b, 0xb1, 0x2b, 0x68, 0x93, 0xf8, 0x74, 0x30, 0x01, 0x2b, + 0x07, 0xd0, 0x28, 0x69, 0x01, 0x21, 0x34, 0xf0, 0x23, 0xd9, 0x2b, 0x68, + 0x01, 0x22, 0x83, 0xf8, 0x74, 0x20, 0x00, 0x23, 0xc6, 0xf8, 0xcc, 0x33, + 0x00, 0x23, 0x23, 0x70, 0x70, 0xbd, 0xd0, 0xf8, 0xac, 0x03, 0x70, 0x47, + 0x2d, 0xe9, 0xf0, 0x4f, 0xd0, 0xf8, 0xac, 0x83, 0xd0, 0xf8, 0xb0, 0x03, + 0xcf, 0xb0, 0x07, 0x90, 0xd8, 0xf8, 0x68, 0x01, 0x1d, 0x46, 0x83, 0x79, + 0x0f, 0x46, 0x92, 0x46, 0x13, 0xb1, 0x04, 0x21, 0x4b, 0xf0, 0x7c, 0xd9, + 0xbb, 0x79, 0x1b, 0xb1, 0x3b, 0x79, 0x00, 0x2b, 0x00, 0xf0, 0x7e, 0x81, + 0xba, 0xf8, 0x00, 0x40, 0xb5, 0xf8, 0x00, 0x90, 0x14, 0xf4, 0x80, 0x44, + 0xb5, 0xf8, 0x02, 0xb0, 0x40, 0xf0, 0x61, 0x81, 0xbb, 0xf1, 0x01, 0x0f, + 0x40, 0xf0, 0x31, 0x81, 0x76, 0xe0, 0xd4, 0xf8, 0xd8, 0x30, 0x00, 0x2b, + 0x00, 0xf0, 0x6a, 0x81, 0x95, 0xf8, 0x03, 0x90, 0x9d, 0xf8, 0x68, 0x31, + 0x4f, 0xea, 0x99, 0x19, 0x03, 0xb3, 0x09, 0xf1, 0xa0, 0x03, 0x58, 0xf8, + 0x23, 0x60, 0xde, 0xb1, 0x33, 0x69, 0xcb, 0xb1, 0x33, 0x7a, 0xbb, 0xb1, + 0x29, 0x46, 0x03, 0x22, 0x4a, 0xa8, 0xf8, 0xf3, 0x31, 0xf6, 0x4a, 0xa8, + 0x06, 0xf1, 0x14, 0x01, 0x32, 0x69, 0x03, 0x30, 0xf8, 0xf3, 0x2a, 0xf6, + 0x31, 0x69, 0x4a, 0xa8, 0x03, 0x31, 0x09, 0xaa, 0xff, 0xf3, 0x12, 0xf1, + 0x58, 0x9b, 0x28, 0x1d, 0x19, 0x1f, 0x09, 0xaa, 0xff, 0xf3, 0x3c, 0xf1, + 0x07, 0xeb, 0x89, 0x03, 0x5b, 0x6f, 0x00, 0x2b, 0x33, 0xd0, 0x1a, 0x69, + 0x58, 0x98, 0x29, 0x46, 0x14, 0x33, 0x03, 0xf0, 0xdd, 0xdd, 0x60, 0xb3, + 0xb5, 0xf8, 0x04, 0x90, 0xb5, 0xf8, 0x06, 0xb0, 0xb9, 0xf1, 0x01, 0x0f, + 0x1d, 0xd1, 0xbb, 0xf1, 0x03, 0x0f, 0x1a, 0xd1, 0xab, 0x7a, 0x10, 0x2b, + 0x17, 0xd1, 0xd4, 0xf8, 0xd8, 0x00, 0x05, 0xf1, 0x0c, 0x01, 0xea, 0x7a, + 0x02, 0x30, 0xf8, 0xf3, 0xe1, 0xf5, 0x05, 0x46, 0x68, 0xb9, 0x20, 0x46, + 0x49, 0x46, 0x97, 0xf9, 0x48, 0x20, 0x4c, 0xf0, 0xd1, 0xd8, 0x84, 0xf8, + 0xde, 0x90, 0x20, 0x46, 0x49, 0x46, 0x2a, 0x46, 0x4c, 0xf0, 0xca, 0xd8, + 0x0c, 0xe0, 0x20, 0x46, 0x01, 0x21, 0x97, 0xf9, 0x48, 0x20, 0x4b, 0xf0, + 0x55, 0xde, 0x0f, 0x25, 0x04, 0xe0, 0x0f, 0x25, 0x4f, 0xf0, 0x03, 0x0b, + 0x4f, 0xf0, 0x01, 0x09, 0xd4, 0xf8, 0xd8, 0x10, 0x07, 0x9b, 0x4a, 0x78, + 0xd8, 0x68, 0x02, 0x32, 0xfd, 0xf3, 0x94, 0xf4, 0x00, 0x23, 0xc4, 0xf8, + 0xd8, 0x30, 0xb9, 0xe0, 0x3e, 0x6d, 0xfb, 0x6c, 0x7d, 0x6d, 0xb6, 0xb1, + 0x0a, 0xe0, 0x29, 0x46, 0x0a, 0xf1, 0x0a, 0x00, 0x06, 0x22, 0x06, 0x93, + 0xf8, 0xf3, 0xac, 0xf5, 0x06, 0x35, 0x06, 0x9b, 0x10, 0xb1, 0x01, 0x34, + 0x9c, 0x42, 0xf2, 0xdb, 0x01, 0x2e, 0x02, 0xd1, 0x9c, 0x42, 0x28, 0xdb, + 0x03, 0xe0, 0x02, 0x2e, 0x01, 0xd1, 0x9c, 0x42, 0x23, 0xda, 0xb8, 0xf8, + 0x82, 0x31, 0x44, 0xf2, 0x1d, 0x32, 0x93, 0x42, 0x2d, 0xd0, 0x0a, 0xd8, + 0x44, 0xf2, 0x16, 0x32, 0x93, 0x42, 0x28, 0xd0, 0x44, 0xf2, 0x1a, 0x32, + 0x93, 0x42, 0x24, 0xd0, 0x44, 0xf2, 0x13, 0x32, 0x0d, 0xe0, 0x44, 0xf2, + 0x2a, 0x32, 0x93, 0x42, 0x1d, 0xd0, 0x02, 0xd8, 0x44, 0xf2, 0x21, 0x32, + 0x05, 0xe0, 0x44, 0xf2, 0x2d, 0x32, 0x93, 0x42, 0x15, 0xd0, 0x44, 0xf2, + 0x52, 0x32, 0x93, 0x42, 0x11, 0xd0, 0x00, 0x22, 0x10, 0xe0, 0x00, 0x26, + 0x03, 0x23, 0x8d, 0xe8, 0x48, 0x00, 0x40, 0x46, 0x17, 0x21, 0x0a, 0xf1, + 0x0a, 0x02, 0x33, 0x46, 0x02, 0x96, 0x03, 0x96, 0x01, 0x25, 0x1a, 0xf0, + 0x23, 0xdb, 0x34, 0x46, 0x80, 0xe0, 0x01, 0x22, 0x0a, 0xf1, 0x0a, 0x04, + 0x21, 0x46, 0x40, 0x46, 0x4c, 0xf0, 0x9a, 0xd9, 0x01, 0x46, 0x10, 0xb1, + 0x40, 0x46, 0x4c, 0xf0, 0x9d, 0xd9, 0x21, 0x46, 0x40, 0x46, 0x4c, 0xf0, + 0xa1, 0xda, 0x04, 0x46, 0x00, 0x28, 0x00, 0xf0, 0x8c, 0x80, 0x39, 0x46, + 0x4b, 0xf0, 0x7c, 0xdf, 0x63, 0x68, 0xda, 0x04, 0x08, 0xd5, 0x07, 0x99, + 0x91, 0xf8, 0x30, 0x20, 0x00, 0x2a, 0x40, 0xf0, 0x82, 0x80, 0x23, 0xf4, + 0x80, 0x53, 0x63, 0x60, 0x40, 0x46, 0x21, 0x46, 0x1d, 0xf0, 0x8e, 0xdd, + 0xb9, 0xf1, 0x00, 0x0f, 0x03, 0xd0, 0xb9, 0xf1, 0x01, 0x0f, 0x76, 0xd1, + 0x12, 0xe0, 0xb7, 0xf9, 0x5c, 0x30, 0x97, 0xf9, 0x48, 0x20, 0x20, 0x46, + 0x01, 0x21, 0x13, 0xb9, 0x4c, 0xf0, 0x2a, 0xd8, 0x01, 0xe0, 0x4b, 0xf0, + 0xb9, 0xdd, 0x26, 0x7e, 0x16, 0xf0, 0x01, 0x06, 0x66, 0xd0, 0x00, 0x26, + 0x35, 0x46, 0x2e, 0xe0, 0xd4, 0xf8, 0xd8, 0x10, 0x41, 0xb1, 0x07, 0x9b, + 0x4a, 0x78, 0xd8, 0x68, 0x02, 0x32, 0xfd, 0xf3, 0xf7, 0xf3, 0x00, 0x23, + 0xc4, 0xf8, 0xd8, 0x30, 0xb7, 0xf8, 0x62, 0x50, 0x00, 0x2d, 0x52, 0xd1, + 0x07, 0x99, 0xc8, 0x68, 0x82, 0x21, 0xfd, 0xf3, 0xdb, 0xf3, 0x06, 0x46, + 0x00, 0x28, 0x4d, 0xd0, 0x10, 0x23, 0x03, 0x70, 0x80, 0x23, 0x43, 0x70, + 0xd8, 0xf8, 0x0c, 0x30, 0xb3, 0xf8, 0x5a, 0x26, 0x73, 0x19, 0x01, 0x35, + 0x80, 0x2d, 0x9a, 0x70, 0xf6, 0xd1, 0xc4, 0xf8, 0xd8, 0x60, 0x00, 0x25, + 0x05, 0xe0, 0x0e, 0x25, 0xbb, 0xf1, 0x03, 0x0f, 0x3a, 0xd8, 0x00, 0x26, + 0x85, 0xb9, 0x7c, 0xb1, 0x23, 0x7e, 0xdb, 0x07, 0x0c, 0xd5, 0x40, 0x46, + 0x39, 0x46, 0x04, 0x22, 0x0a, 0xf1, 0x0a, 0x03, 0x00, 0x95, 0x01, 0x95, + 0xcd, 0xf8, 0x08, 0x90, 0x03, 0x95, 0x04, 0x95, 0x13, 0xf0, 0xd6, 0xda, + 0x0b, 0xf1, 0x01, 0x03, 0x01, 0x93, 0x00, 0x23, 0x03, 0x93, 0x9d, 0xf8, + 0x64, 0x31, 0x38, 0x46, 0x05, 0x93, 0x0a, 0xf1, 0x0a, 0x01, 0x07, 0xf1, + 0xbc, 0x02, 0x23, 0x46, 0xcd, 0xf8, 0x00, 0x90, 0x02, 0x95, 0x04, 0x96, + 0x1e, 0xf0, 0xc0, 0xdb, 0x12, 0xe0, 0x40, 0x46, 0x0a, 0xf1, 0x0a, 0x01, + 0x4c, 0xf0, 0xfc, 0xd8, 0x04, 0x46, 0x00, 0x28, 0x7f, 0xf4, 0x9b, 0xae, + 0x08, 0xe0, 0x06, 0x46, 0x04, 0xe0, 0x00, 0x26, 0x02, 0xe0, 0x00, 0x26, + 0x0d, 0x25, 0xd9, 0xe7, 0x01, 0x25, 0xd7, 0xe7, 0x4f, 0xb0, 0xbd, 0xe8, + 0xf0, 0x8f, 0x30, 0xb5, 0x9d, 0xf8, 0x10, 0x50, 0x9d, 0xf8, 0x14, 0x40, + 0x04, 0x95, 0x05, 0x94, 0xbd, 0xe8, 0x30, 0x40, 0xff, 0xf7, 0x5c, 0xbe, + 0xd0, 0xf8, 0xc0, 0x03, 0x70, 0x47, 0xc0, 0xf8, 0xc0, 0x13, 0x70, 0x47, + 0xd0, 0xf8, 0xac, 0x33, 0x1b, 0x68, 0xdb, 0x69, 0x18, 0x69, 0x04, 0x28, + 0xa8, 0xbf, 0x04, 0x20, 0x70, 0x47, 0x70, 0xb5, 0x03, 0x6b, 0x00, 0x25, + 0x80, 0xf8, 0xd0, 0x58, 0xd0, 0xf8, 0x5c, 0x61, 0x04, 0x46, 0x18, 0x69, + 0x07, 0xf0, 0x58, 0xff, 0x01, 0x46, 0x30, 0x46, 0x3c, 0xf0, 0x8a, 0xdc, + 0x30, 0xb1, 0x20, 0x46, 0x01, 0x21, 0x2a, 0x46, 0xbd, 0xe8, 0x70, 0x40, + 0x1a, 0xf0, 0xb8, 0x9c, 0x70, 0xbd, 0xf0, 0xb5, 0x04, 0x68, 0x8b, 0xb0, + 0x05, 0x46, 0x00, 0x21, 0xe6, 0x68, 0x1f, 0xf0, 0x5d, 0xdd, 0x28, 0x46, + 0x13, 0xf0, 0xa2, 0xd9, 0xd4, 0xf8, 0xe4, 0x36, 0x6b, 0xb1, 0xa0, 0x68, + 0xd4, 0xf8, 0x74, 0x15, 0x06, 0xf0, 0x06, 0xd8, 0x00, 0x23, 0xc4, 0xf8, + 0xe4, 0x36, 0x94, 0xf8, 0x58, 0x35, 0x23, 0xf0, 0x02, 0x03, 0x84, 0xf8, + 0x58, 0x35, 0xd4, 0xf8, 0x5c, 0x01, 0x3c, 0xf0, 0x41, 0xdc, 0x23, 0x69, + 0x93, 0xf8, 0xea, 0x20, 0x62, 0xb1, 0xdb, 0x6e, 0x40, 0xf2, 0x04, 0x40, + 0xd3, 0xf8, 0x20, 0x31, 0x18, 0x40, 0xa0, 0xf5, 0x80, 0x6c, 0xdc, 0xf1, + 0x00, 0x00, 0x40, 0xeb, 0x0c, 0x00, 0x06, 0xe0, 0x18, 0x6e, 0x03, 0xf0, + 0x3a, 0xfd, 0xd0, 0xf1, 0x01, 0x00, 0x38, 0xbf, 0x00, 0x20, 0x00, 0x28, + 0x3e, 0xd0, 0x20, 0x46, 0x06, 0xf0, 0x4a, 0xf8, 0x23, 0x6b, 0xd4, 0xf8, + 0x5c, 0x71, 0x18, 0x69, 0x07, 0xf0, 0x08, 0xff, 0x01, 0x46, 0x38, 0x46, + 0x3c, 0xf0, 0x3a, 0xdc, 0x30, 0xb1, 0x94, 0xf8, 0xd0, 0x28, 0x1a, 0xb9, + 0x20, 0x46, 0x01, 0x21, 0x1a, 0xf0, 0x68, 0xdc, 0x28, 0x46, 0x13, 0xf0, + 0xf5, 0xde, 0x4f, 0xf0, 0x00, 0x43, 0xc6, 0xf8, 0x88, 0x31, 0x0f, 0x21, + 0x20, 0x69, 0x34, 0xf0, 0x97, 0xd8, 0x20, 0x69, 0x40, 0xf2, 0xff, 0x31, + 0x34, 0xf0, 0x80, 0xd8, 0x23, 0x6b, 0x1b, 0x68, 0x02, 0x2b, 0x04, 0xd1, + 0x20, 0x69, 0x94, 0xf8, 0x43, 0x16, 0x34, 0xf0, 0xe5, 0xd8, 0x20, 0x46, + 0x18, 0xf0, 0xb4, 0xde, 0x20, 0x46, 0x18, 0xf0, 0x7d, 0xdc, 0x0a, 0xa9, + 0x00, 0x23, 0x41, 0xf8, 0x28, 0x3d, 0x20, 0x46, 0x69, 0x46, 0x1c, 0xf0, + 0x07, 0xdb, 0x20, 0x46, 0x1f, 0xf0, 0x5c, 0xde, 0x0b, 0xb0, 0xf0, 0xbd, + 0x2d, 0xe9, 0xf0, 0x41, 0x07, 0x68, 0x04, 0x46, 0x86, 0xb0, 0x38, 0x46, + 0x0e, 0x46, 0x15, 0x46, 0x98, 0x46, 0x1d, 0xf0, 0x5b, 0xdb, 0x10, 0xb1, + 0x38, 0x46, 0x1d, 0xf0, 0x4f, 0xdb, 0x0c, 0x9b, 0x38, 0x46, 0x02, 0x93, + 0x00, 0x23, 0x03, 0x93, 0x04, 0x93, 0x21, 0x46, 0x0b, 0x22, 0x2b, 0x46, + 0x8d, 0xe8, 0x40, 0x01, 0x13, 0xf0, 0xe2, 0xd9, 0x06, 0xb0, 0xbd, 0xe8, + 0xf0, 0x81, 0x00, 0x00, 0x2d, 0xe9, 0xf0, 0x4f, 0x04, 0x68, 0xd0, 0xf8, + 0xd8, 0xb2, 0xd0, 0xf8, 0xd0, 0x12, 0x97, 0xb0, 0x05, 0x46, 0xd0, 0xf8, + 0xe8, 0xa2, 0x20, 0x46, 0x07, 0x91, 0x1f, 0xf0, 0xb3, 0xde, 0xdb, 0xf8, + 0x00, 0x10, 0xa0, 0x68, 0x05, 0xf0, 0x6a, 0xdf, 0x28, 0x46, 0x02, 0x21, + 0x2f, 0xf0, 0x94, 0xd8, 0xdb, 0xe1, 0xd4, 0xf8, 0xd8, 0x26, 0x01, 0x33, + 0x52, 0xf8, 0x23, 0x60, 0xb6, 0xf8, 0x32, 0x80, 0x08, 0xf4, 0x70, 0x43, + 0xa3, 0xf5, 0x80, 0x51, 0x4b, 0x42, 0x43, 0xeb, 0x01, 0x03, 0x0e, 0x33, + 0x54, 0xf8, 0x23, 0x70, 0x08, 0xf4, 0x40, 0x63, 0xb3, 0xf5, 0x40, 0x6f, + 0x24, 0xd1, 0x23, 0x68, 0x93, 0xf8, 0x46, 0x30, 0x9a, 0x07, 0x11, 0xd0, + 0xd4, 0xf8, 0x5c, 0x01, 0x79, 0x68, 0x3b, 0xf0, 0x95, 0xdf, 0x03, 0x07, + 0x0a, 0xd4, 0x97, 0xf8, 0xec, 0x30, 0x3b, 0xb1, 0x3b, 0x68, 0x02, 0x2b, + 0x12, 0xd1, 0xd4, 0xf8, 0xfc, 0x34, 0x9b, 0x78, 0x98, 0x07, 0x0d, 0xd5, + 0x40, 0x46, 0xf9, 0xf3, 0x19, 0xf5, 0x40, 0xf4, 0x30, 0x63, 0x9b, 0xb2, + 0x0e, 0x28, 0x8c, 0xbf, 0x4f, 0xf4, 0x80, 0x58, 0x4f, 0xf4, 0x00, 0x58, + 0x48, 0xea, 0x03, 0x08, 0xd4, 0xf8, 0x5c, 0x01, 0x41, 0x46, 0x3c, 0xf0, + 0xc5, 0xdd, 0x00, 0x28, 0x00, 0xf0, 0x94, 0x81, 0x70, 0x8e, 0xf9, 0xf3, + 0x03, 0xf5, 0x40, 0xf4, 0x30, 0x60, 0x1f, 0xfa, 0x80, 0xf8, 0x70, 0x8e, + 0xf9, 0xf3, 0xfc, 0xf4, 0x0e, 0x28, 0x8c, 0xbf, 0x4f, 0xf4, 0x80, 0x51, + 0x4f, 0xf4, 0x00, 0x51, 0x48, 0xea, 0x01, 0x01, 0x28, 0x46, 0x2e, 0xf0, + 0xef, 0xd8, 0x00, 0x28, 0x00, 0xf0, 0x7c, 0x81, 0xd5, 0xf8, 0xe8, 0x32, + 0x00, 0x2b, 0x74, 0xd0, 0xd3, 0xf8, 0xdc, 0x30, 0x00, 0x2b, 0x70, 0xd0, + 0x00, 0x23, 0xa5, 0xf8, 0x5c, 0x30, 0x96, 0xf8, 0xaa, 0x00, 0x4f, 0xf0, + 0x0c, 0x08, 0x08, 0xfb, 0x00, 0xa0, 0xf2, 0x88, 0x1c, 0x30, 0x02, 0xf0, + 0x80, 0x02, 0xd2, 0xf1, 0x01, 0x02, 0x38, 0xbf, 0x00, 0x22, 0x14, 0xa9, + 0xf9, 0xf3, 0x38, 0xf6, 0xbd, 0xf8, 0x50, 0x10, 0xa5, 0xf8, 0x62, 0x10, + 0x96, 0xf8, 0xaa, 0x00, 0x13, 0xa9, 0x08, 0xfb, 0x00, 0xa0, 0x20, 0x30, + 0xf9, 0xf3, 0x8a, 0xf6, 0x13, 0x9b, 0x2b, 0xbb, 0x96, 0xf8, 0xaa, 0x30, + 0x04, 0x22, 0x08, 0xfb, 0x03, 0xa8, 0x15, 0xa8, 0x08, 0xf1, 0x24, 0x01, + 0xf8, 0xf3, 0x64, 0xf3, 0x15, 0xa8, 0x92, 0x49, 0x04, 0x22, 0xf8, 0xf3, + 0x43, 0xf3, 0x48, 0xb9, 0x96, 0xf8, 0xa9, 0x30, 0xa3, 0xf1, 0x08, 0x02, + 0xd2, 0xb2, 0x02, 0x2a, 0x40, 0xf2, 0x3a, 0x81, 0x8d, 0xf8, 0x57, 0x30, + 0x15, 0xa8, 0x13, 0xa9, 0xf9, 0xf3, 0x6a, 0xf6, 0x30, 0xb9, 0x0c, 0x23, + 0x00, 0x90, 0x01, 0x93, 0x96, 0xf8, 0x32, 0x30, 0x02, 0x93, 0x06, 0xe1, + 0x13, 0x9b, 0x20, 0x46, 0x59, 0x07, 0x44, 0xbf, 0x43, 0xf0, 0x02, 0x03, + 0x13, 0x93, 0x13, 0x9b, 0x81, 0x49, 0x9a, 0x07, 0x44, 0xbf, 0x43, 0xf0, + 0x01, 0x03, 0x13, 0x93, 0x13, 0xab, 0x00, 0x93, 0x04, 0x23, 0x01, 0x93, + 0x01, 0x23, 0x02, 0x93, 0xab, 0x68, 0x00, 0x22, 0x03, 0x93, 0x13, 0x46, + 0x19, 0xf0, 0x42, 0xdd, 0x07, 0x23, 0x00, 0x93, 0x00, 0x23, 0x01, 0x93, + 0x96, 0xf8, 0xaa, 0x20, 0x20, 0x46, 0x02, 0x92, 0x03, 0x93, 0x04, 0x93, + 0x29, 0x46, 0x18, 0x22, 0x33, 0x46, 0x13, 0xf0, 0xf1, 0xd8, 0xb6, 0xf8, + 0x62, 0x30, 0xd8, 0x06, 0x0a, 0xd5, 0xaa, 0x6d, 0x40, 0xf2, 0x37, 0x13, + 0x13, 0x40, 0x2b, 0xb9, 0x6d, 0x4b, 0x1b, 0x78, 0x13, 0xb9, 0x00, 0x93, + 0x01, 0x22, 0x34, 0xe0, 0x30, 0x46, 0xf8, 0xf3, 0xed, 0xf7, 0x18, 0xb1, + 0x00, 0x23, 0x00, 0x93, 0x02, 0x22, 0x2c, 0xe0, 0x2b, 0x6d, 0x00, 0x2b, + 0x2e, 0xd0, 0x23, 0x68, 0x93, 0xf8, 0x30, 0x30, 0x63, 0xb1, 0x29, 0xe0, + 0x69, 0x6d, 0x30, 0x46, 0x49, 0x44, 0x06, 0x22, 0xf8, 0xf3, 0xde, 0xf2, + 0x09, 0xf1, 0x06, 0x09, 0x38, 0xb1, 0x08, 0xf1, 0x01, 0x08, 0x01, 0xe0, + 0x99, 0x46, 0x98, 0x46, 0xeb, 0x6c, 0x98, 0x45, 0xee, 0xd3, 0x2b, 0x6d, + 0x01, 0x2b, 0x03, 0xd1, 0xeb, 0x6c, 0x98, 0x45, 0x06, 0xd3, 0x11, 0xe0, + 0x02, 0x2b, 0x0f, 0xd1, 0xeb, 0x6c, 0x98, 0x45, 0x04, 0xd2, 0x0b, 0xe0, + 0x00, 0x23, 0x00, 0x93, 0x03, 0x22, 0x02, 0xe0, 0x00, 0x23, 0x00, 0x93, + 0x04, 0x22, 0x01, 0x92, 0x96, 0xf8, 0x32, 0x20, 0x02, 0x92, 0xb1, 0xe0, + 0x23, 0x68, 0x93, 0xf8, 0x95, 0x30, 0x83, 0xb1, 0xd4, 0xf8, 0x4c, 0x35, + 0x01, 0x2b, 0x09, 0xd1, 0x30, 0x46, 0x04, 0xf5, 0xaa, 0x61, 0x06, 0x22, + 0xf8, 0xf3, 0xac, 0xf2, 0x00, 0x28, 0x40, 0xf0, 0xa9, 0x80, 0x02, 0xe0, + 0x02, 0x2b, 0x00, 0xf0, 0xa5, 0x80, 0x96, 0xf9, 0x34, 0x80, 0xb8, 0xf1, + 0x00, 0x0f, 0x11, 0xd1, 0xd4, 0xf8, 0x5c, 0x01, 0x71, 0x8e, 0x3c, 0xf0, + 0x5d, 0xdb, 0x58, 0xb1, 0x05, 0x23, 0xcd, 0xf8, 0x00, 0x80, 0x01, 0x93, + 0x96, 0xf8, 0x32, 0x30, 0xcd, 0xf8, 0x0c, 0x80, 0x02, 0x93, 0xcd, 0xf8, + 0x10, 0x80, 0x87, 0xe0, 0xb5, 0xf8, 0x62, 0x30, 0x5b, 0xb1, 0xaa, 0x6d, + 0x40, 0xf2, 0x37, 0x13, 0x13, 0x40, 0x33, 0xb1, 0x20, 0x46, 0x29, 0x46, + 0x32, 0x46, 0x2e, 0xf0, 0x13, 0xda, 0x00, 0x28, 0x7e, 0xd1, 0x3b, 0x68, + 0x06, 0xf1, 0x38, 0x00, 0x02, 0x2b, 0x07, 0xd1, 0x7a, 0x7d, 0x2a, 0xb9, + 0xff, 0x23, 0x00, 0x93, 0x01, 0x92, 0x09, 0xa9, 0x01, 0x23, 0x13, 0xe0, + 0x23, 0x68, 0x93, 0xf8, 0x46, 0x30, 0x13, 0xf0, 0x03, 0x03, 0x07, 0xd0, + 0xd5, 0xf8, 0xcc, 0x30, 0x03, 0xf4, 0x80, 0x53, 0xd3, 0xf1, 0x01, 0x03, + 0x38, 0xbf, 0x00, 0x23, 0xff, 0x22, 0x8d, 0xe8, 0x0c, 0x00, 0x00, 0x22, + 0x09, 0xa9, 0x13, 0x46, 0x47, 0xf0, 0x38, 0xdb, 0x23, 0x6b, 0x50, 0x37, + 0x93, 0xf8, 0xec, 0x10, 0x39, 0xb1, 0x71, 0x8e, 0x01, 0xf4, 0x40, 0x61, + 0xb1, 0xf5, 0x40, 0x6f, 0x14, 0xbf, 0x14, 0x21, 0x28, 0x21, 0x38, 0x46, + 0x47, 0xf0, 0xd0, 0xda, 0xd4, 0xf8, 0x60, 0x36, 0x09, 0xa8, 0x39, 0x46, + 0x00, 0x22, 0x9b, 0x78, 0x47, 0xf0, 0x62, 0xda, 0x10, 0xb9, 0x00, 0x90, + 0x09, 0x23, 0x18, 0xe0, 0x9d, 0xf8, 0x38, 0x20, 0x94, 0xf8, 0x38, 0x37, + 0x9a, 0x42, 0x39, 0xd1, 0x96, 0xf9, 0x34, 0x30, 0xd3, 0xb9, 0x72, 0x8e, + 0x20, 0x46, 0x02, 0xf4, 0x70, 0x42, 0x06, 0xf1, 0x38, 0x01, 0xb2, 0xf5, + 0x80, 0x5f, 0x14, 0xbf, 0x02, 0x22, 0x01, 0x22, 0x2d, 0xf0, 0x60, 0xdf, + 0x60, 0xb9, 0x00, 0x90, 0x0a, 0x23, 0x01, 0x93, 0x02, 0x90, 0x03, 0x90, + 0x04, 0x90, 0x1b, 0xe0, 0x34, 0xb7, 0x01, 0x00, 0x17, 0x73, 0x86, 0x00, + 0xa4, 0x07, 0x02, 0x00, 0x23, 0x68, 0x93, 0xf8, 0x30, 0x30, 0x0b, 0xb3, + 0x20, 0x46, 0x31, 0x46, 0x4b, 0xf0, 0x42, 0xde, 0xe0, 0xb1, 0x03, 0x7e, + 0x99, 0x07, 0x19, 0xd5, 0x43, 0x68, 0x13, 0xf4, 0x80, 0x53, 0x15, 0xd1, + 0x0d, 0x22, 0x00, 0x93, 0x01, 0x92, 0x02, 0x93, 0x03, 0x93, 0x04, 0x93, + 0x20, 0x46, 0x29, 0x46, 0x17, 0x22, 0x33, 0x46, 0x12, 0xf0, 0xee, 0xdf, + 0xd4, 0xf8, 0xdc, 0x36, 0x01, 0x3b, 0xc4, 0xf8, 0xdc, 0x36, 0xd4, 0xf8, + 0xdc, 0x36, 0x00, 0x2b, 0x7f, 0xf4, 0x1f, 0xae, 0xd4, 0xf8, 0xdc, 0x66, + 0xf6, 0xb1, 0x00, 0x22, 0x8b, 0xf8, 0x1e, 0x20, 0xd4, 0xf8, 0xdc, 0x36, + 0xd4, 0xf8, 0xd8, 0x16, 0x58, 0x1e, 0x01, 0x33, 0x51, 0xf8, 0x23, 0x30, + 0xdb, 0xf8, 0x04, 0x10, 0xc4, 0xf8, 0xdc, 0x06, 0x01, 0x29, 0x09, 0xd0, + 0x00, 0x92, 0x01, 0x92, 0x02, 0x92, 0x03, 0x92, 0x04, 0x92, 0x20, 0x46, + 0x29, 0x46, 0x20, 0x22, 0x12, 0xf0, 0xc6, 0xdf, 0x28, 0x46, 0x30, 0xf0, + 0x95, 0xdc, 0x29, 0xe0, 0x07, 0x99, 0xea, 0x79, 0x91, 0xf9, 0x34, 0x30, + 0x4a, 0xb1, 0x01, 0x21, 0xd3, 0xf1, 0x01, 0x03, 0x28, 0x46, 0x32, 0x46, + 0x38, 0xbf, 0x00, 0x23, 0x2e, 0xf0, 0x6a, 0xdb, 0x09, 0xe0, 0x01, 0x21, + 0xd3, 0xf1, 0x01, 0x03, 0x28, 0x46, 0x38, 0xbf, 0x00, 0x23, 0x00, 0x92, + 0x01, 0x92, 0x2e, 0xf0, 0x99, 0xdc, 0x95, 0xf9, 0x10, 0x30, 0x02, 0x2b, + 0x03, 0xd1, 0xe8, 0x68, 0x00, 0x21, 0x4f, 0xf0, 0xc5, 0xdc, 0x94, 0xf8, + 0x75, 0x32, 0x28, 0x46, 0x23, 0xf0, 0x04, 0x03, 0x84, 0xf8, 0x75, 0x32, + 0x2e, 0xf0, 0x36, 0xdc, 0x17, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, 0x00, 0xbf, + 0x2d, 0xe9, 0xf0, 0x4f, 0x05, 0x68, 0x89, 0xb0, 0x9a, 0x46, 0x00, 0xf5, + 0x34, 0x73, 0x93, 0xe8, 0x08, 0x03, 0x03, 0x93, 0x2b, 0x68, 0x04, 0x46, + 0x93, 0xf8, 0x3f, 0x30, 0x8b, 0x46, 0x16, 0x46, 0x00, 0x2b, 0x00, 0xf0, + 0x68, 0x81, 0xc3, 0x79, 0x00, 0x2b, 0x00, 0xf0, 0x64, 0x81, 0x83, 0x7c, + 0x05, 0xa8, 0x13, 0xb1, 0x04, 0xf1, 0xd6, 0x01, 0x00, 0xe0, 0x41, 0x46, + 0x06, 0x22, 0xf8, 0xf3, 0xa1, 0xf1, 0x00, 0x23, 0x85, 0xf8, 0x4a, 0x35, + 0x2b, 0x68, 0x93, 0xf8, 0x44, 0x30, 0x1b, 0xb1, 0xd5, 0xf8, 0x64, 0x01, + 0x38, 0xf0, 0xfa, 0xd9, 0x2b, 0x69, 0x93, 0xf8, 0xea, 0x20, 0x42, 0xb1, + 0xdb, 0x6e, 0x40, 0xf2, 0x04, 0x47, 0xd3, 0xf8, 0x20, 0x31, 0x1f, 0x40, + 0xb7, 0xf5, 0x80, 0x67, 0x03, 0xe0, 0x18, 0x6e, 0x03, 0xf0, 0x4d, 0xfa, + 0x07, 0x1c, 0x18, 0xbf, 0x01, 0x27, 0xc7, 0xb1, 0x00, 0x21, 0x20, 0x46, + 0x31, 0xf0, 0xb0, 0xdc, 0x20, 0x46, 0xff, 0xf7, 0xd4, 0xfc, 0xa3, 0x7c, + 0x20, 0x46, 0xd3, 0xf1, 0x01, 0x03, 0x38, 0xbf, 0x00, 0x23, 0x00, 0x93, + 0x00, 0x21, 0x05, 0xaa, 0x08, 0x23, 0xff, 0xf7, 0x43, 0xfd, 0x00, 0x21, + 0x20, 0x46, 0x0a, 0x46, 0x34, 0xf0, 0x6a, 0xdf, 0x24, 0xe1, 0xa3, 0x7c, + 0x00, 0x2b, 0x00, 0xf0, 0x8c, 0x80, 0xd4, 0xf8, 0xdc, 0x32, 0xd3, 0xf8, + 0x90, 0x10, 0x41, 0xb1, 0x93, 0xf8, 0x94, 0x20, 0x68, 0x68, 0xfd, 0xf3, + 0x17, 0xf0, 0xd4, 0xf8, 0xdc, 0x32, 0xc3, 0xf8, 0x90, 0x70, 0xd9, 0xf8, + 0x08, 0x30, 0x23, 0xb1, 0x0d, 0x2b, 0x02, 0xd0, 0x20, 0x46, 0x2e, 0xf0, + 0x39, 0xdd, 0xd5, 0xf8, 0x68, 0x01, 0x04, 0x21, 0x4a, 0xf0, 0x66, 0xdc, + 0x05, 0xa9, 0x28, 0x46, 0x4b, 0xf0, 0x58, 0xdd, 0x00, 0x27, 0x39, 0x46, + 0x81, 0x46, 0x84, 0xf8, 0x94, 0x70, 0x20, 0x46, 0x1e, 0xf0, 0x0e, 0xdf, + 0x39, 0x46, 0x20, 0x46, 0x1b, 0xf0, 0xcc, 0xde, 0x20, 0x46, 0x39, 0x46, + 0x12, 0xf0, 0xbe, 0xd8, 0xbb, 0xf1, 0x00, 0x0f, 0x41, 0xd0, 0x04, 0xf1, + 0xbc, 0x00, 0xf8, 0xf3, 0x1f, 0xf6, 0x00, 0x28, 0x3b, 0xd1, 0x2b, 0x6b, + 0xb8, 0xf8, 0x32, 0x70, 0x18, 0x69, 0x07, 0xf0, 0xcb, 0xfb, 0x87, 0x42, + 0x33, 0xd1, 0xd5, 0xf8, 0x5c, 0x01, 0xb8, 0xf8, 0x32, 0x10, 0x3c, 0xf0, + 0x49, 0xd9, 0x30, 0xb9, 0xd5, 0xf8, 0x5c, 0x01, 0xb8, 0xf8, 0x32, 0x10, + 0x3c, 0xf0, 0xbe, 0xd9, 0x68, 0xb1, 0x66, 0xb9, 0xd5, 0xf8, 0x5c, 0x01, + 0xb8, 0xf8, 0x32, 0x10, 0x3c, 0xf0, 0xea, 0xd8, 0x28, 0xb9, 0x01, 0x23, + 0x85, 0xf8, 0xd0, 0x38, 0xb2, 0x46, 0x65, 0x4f, 0x00, 0xe0, 0x37, 0x46, + 0x08, 0x23, 0x05, 0xa9, 0x01, 0x93, 0x28, 0x46, 0x04, 0xf1, 0xc2, 0x03, + 0x0a, 0x46, 0xcd, 0xf8, 0x00, 0x90, 0x1e, 0xf0, 0x33, 0xd9, 0x03, 0x46, + 0x50, 0xb1, 0x4f, 0xb1, 0x39, 0x46, 0x28, 0x46, 0x52, 0x46, 0x1a, 0xf0, + 0xf7, 0xda, 0x00, 0x28, 0x08, 0xbf, 0x00, 0x27, 0x00, 0xe0, 0x37, 0x46, + 0xb9, 0xf1, 0x00, 0x0f, 0x30, 0xd0, 0x48, 0x46, 0x0e, 0x21, 0x4b, 0xf0, + 0x4d, 0xd9, 0x2b, 0x68, 0x93, 0xf8, 0x44, 0x30, 0x23, 0xb1, 0xd5, 0xf8, + 0x64, 0x01, 0x49, 0x46, 0x38, 0xf0, 0x58, 0xd9, 0x49, 0x46, 0x28, 0x46, + 0x1d, 0xf0, 0x0c, 0xd9, 0x4f, 0xf0, 0x00, 0x09, 0x1c, 0xe0, 0x2b, 0x68, + 0x93, 0xf8, 0x95, 0x30, 0x83, 0xb1, 0xd5, 0xf8, 0x00, 0x05, 0x07, 0xa9, + 0x4b, 0xf0, 0x7e, 0xd9, 0x05, 0xe0, 0x43, 0x68, 0x9f, 0x00, 0x44, 0xbf, + 0x23, 0xf0, 0x00, 0x53, 0x43, 0x60, 0x07, 0xa8, 0x4b, 0xf0, 0x7c, 0xd9, + 0x00, 0x28, 0xf4, 0xd1, 0x4f, 0xf0, 0x01, 0x09, 0x84, 0xf8, 0x12, 0x90, + 0x20, 0x46, 0x19, 0xf0, 0x55, 0xd9, 0x37, 0x46, 0x20, 0x46, 0x00, 0x21, + 0x31, 0xf0, 0xea, 0xdb, 0x05, 0xf5, 0x00, 0x71, 0x28, 0x46, 0x06, 0x31, + 0x21, 0xf0, 0x84, 0xdf, 0x2b, 0x68, 0x93, 0xf8, 0x3f, 0x30, 0x93, 0xb9, + 0x95, 0xf9, 0x47, 0x26, 0x85, 0xf8, 0x42, 0x36, 0x01, 0x32, 0x08, 0xbf, + 0x85, 0xf8, 0x43, 0x36, 0x28, 0x46, 0x1b, 0xf0, 0x55, 0xdd, 0x2b, 0x68, + 0x93, 0xf8, 0x46, 0x30, 0x98, 0x07, 0x02, 0xd0, 0x28, 0x46, 0x1b, 0xf0, + 0x69, 0xdd, 0x04, 0xf1, 0xbc, 0x0b, 0x58, 0x46, 0xf8, 0xf3, 0x86, 0xf5, + 0x01, 0x46, 0x30, 0xb9, 0x20, 0x46, 0x05, 0xaa, 0x08, 0x23, 0xcd, 0xf8, + 0x00, 0x90, 0xff, 0xf7, 0x61, 0xfc, 0x95, 0xf8, 0x72, 0x32, 0x20, 0x46, + 0x33, 0xb9, 0xd5, 0xf8, 0x6c, 0x32, 0x9c, 0x42, 0x02, 0xd1, 0xff, 0xf7, + 0xdc, 0xfb, 0x04, 0xe0, 0x13, 0xf0, 0x20, 0xdb, 0x20, 0x46, 0x12, 0xf0, + 0x83, 0xdd, 0xd8, 0xf8, 0x64, 0x10, 0x49, 0xb1, 0x68, 0x68, 0xb8, 0xf8, + 0x68, 0x20, 0xfc, 0xf3, 0x31, 0xf7, 0x00, 0x23, 0xc8, 0xf8, 0x64, 0x30, + 0xa8, 0xf8, 0x68, 0x30, 0x02, 0x23, 0x05, 0xaa, 0x00, 0x93, 0x28, 0x46, + 0x23, 0x46, 0x00, 0x21, 0x19, 0xf0, 0xd4, 0xdb, 0x20, 0x46, 0x00, 0x21, + 0x19, 0xf0, 0xa2, 0xdd, 0x20, 0x46, 0x19, 0xf0, 0x0b, 0xdd, 0x28, 0x46, + 0x05, 0xf0, 0xea, 0xff, 0x1f, 0xb1, 0x28, 0x46, 0x00, 0x21, 0x52, 0x46, + 0xb8, 0x47, 0x9e, 0xb9, 0x20, 0x46, 0x31, 0x46, 0x32, 0x46, 0x34, 0xf0, + 0x53, 0xde, 0x31, 0x46, 0x06, 0x22, 0x03, 0x98, 0xf8, 0xf3, 0xb2, 0xf0, + 0x58, 0x46, 0x31, 0x46, 0x06, 0x22, 0xf8, 0xf3, 0xad, 0xf0, 0x30, 0x46, + 0x03, 0xe0, 0x4f, 0xf0, 0xff, 0x30, 0x00, 0xe0, 0x00, 0x20, 0x09, 0xb0, + 0xbd, 0xe8, 0xf0, 0x8f, 0xfb, 0x95, 0x00, 0x00, 0x2d, 0xe9, 0xf0, 0x4f, + 0x06, 0x29, 0x89, 0xb0, 0x07, 0x46, 0x0d, 0x46, 0x90, 0x46, 0x9b, 0x46, + 0x9d, 0xf8, 0x48, 0xa0, 0xd0, 0xf8, 0x00, 0x90, 0xd0, 0xf8, 0xd8, 0x62, + 0x49, 0xd0, 0x00, 0x29, 0x2c, 0xd1, 0xba, 0xf1, 0x00, 0x0f, 0x03, 0xd1, + 0x48, 0x46, 0x39, 0x46, 0x35, 0xf0, 0x40, 0xde, 0x99, 0xf8, 0x72, 0x42, + 0x00, 0x2c, 0x3d, 0xd0, 0xd9, 0xf8, 0x00, 0x05, 0x07, 0xa9, 0x4b, 0xf0, + 0xcb, 0xd8, 0x02, 0xe0, 0x23, 0x7e, 0x9a, 0x07, 0x33, 0xd4, 0x07, 0xa8, + 0x4b, 0xf0, 0xcc, 0xd8, 0x04, 0x46, 0x00, 0x28, 0xf6, 0xd1, 0x50, 0xe0, + 0xd9, 0xf8, 0x30, 0x30, 0x18, 0x69, 0x07, 0xf0, 0xb1, 0xfa, 0xd7, 0xf8, + 0xd4, 0x32, 0x5b, 0x8e, 0x83, 0x42, 0x23, 0xd0, 0x48, 0x46, 0x2a, 0xf0, + 0xb5, 0xda, 0xd9, 0xf8, 0x34, 0x07, 0x2a, 0xf0, 0xcf, 0xde, 0x1b, 0xe0, + 0xb3, 0x68, 0x09, 0x3b, 0x01, 0x2b, 0x16, 0xd8, 0x48, 0x46, 0x11, 0x46, + 0x4b, 0xf0, 0x0a, 0xdc, 0x10, 0xb1, 0x0c, 0x21, 0x4b, 0xf0, 0x58, 0xd8, + 0x02, 0x2d, 0x0a, 0xd0, 0xd9, 0xf8, 0x08, 0x00, 0x31, 0x68, 0x05, 0xf0, + 0x5f, 0xdb, 0x05, 0x2d, 0x05, 0xd8, 0x4f, 0xf0, 0xc8, 0x43, 0xab, 0x40, + 0x01, 0xd5, 0x01, 0x24, 0x00, 0xe0, 0x00, 0x24, 0x8d, 0xe8, 0x20, 0x08, + 0x13, 0x9b, 0x48, 0x46, 0x02, 0x93, 0x33, 0x6c, 0x39, 0x46, 0x03, 0x93, + 0x73, 0x6c, 0xba, 0xf1, 0x00, 0x0f, 0x0c, 0xbf, 0x07, 0x22, 0x09, 0x22, + 0x04, 0x93, 0x43, 0x46, 0x12, 0xf0, 0xa4, 0xdd, 0x9c, 0xb1, 0x05, 0x2d, + 0x01, 0xd0, 0x02, 0x2d, 0x07, 0xd1, 0xb2, 0x7f, 0x33, 0x7f, 0x9a, 0x42, + 0x03, 0xd2, 0x38, 0x46, 0x30, 0xf0, 0x6a, 0xda, 0x07, 0xe0, 0x38, 0x46, + 0xff, 0xf7, 0xb6, 0xfb, 0x03, 0xe0, 0x73, 0x68, 0x03, 0x2b, 0xab, 0xd1, + 0xd8, 0xe7, 0x09, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, 0x70, 0xb5, 0x11, 0x46, + 0x86, 0xb0, 0x05, 0x46, 0x16, 0x46, 0x4b, 0xf0, 0xc5, 0xdb, 0x04, 0x46, + 0x00, 0x28, 0x24, 0xd0, 0x90, 0xf8, 0xdf, 0x30, 0x23, 0xb1, 0x28, 0x46, + 0x21, 0x46, 0x01, 0x22, 0x06, 0xf0, 0xf7, 0xfb, 0x20, 0x46, 0x4b, 0xf0, + 0x3d, 0xd9, 0xe3, 0x68, 0x1b, 0xb1, 0x28, 0x46, 0x21, 0x46, 0x3d, 0xf0, + 0x21, 0xdf, 0x00, 0x23, 0x03, 0x22, 0x00, 0x93, 0x01, 0x92, 0x02, 0x93, + 0x03, 0x93, 0x04, 0x93, 0x28, 0x46, 0x21, 0x69, 0x05, 0x22, 0x33, 0x46, + 0x12, 0xf0, 0x64, 0xdd, 0x28, 0x46, 0x21, 0x46, 0x06, 0xb0, 0xbd, 0xe8, + 0x70, 0x40, 0x4b, 0xf0, 0xaf, 0x9b, 0x06, 0xb0, 0x70, 0xbd, 0x00, 0x00, + 0x00, 0x48, 0x70, 0x47, 0x5c, 0xc9, 0x01, 0x00, 0x00, 0x48, 0x70, 0x47, + 0x7c, 0xca, 0x01, 0x00, 0x10, 0xb5, 0x06, 0x49, 0x04, 0x46, 0x40, 0x6e, + 0xf8, 0xf3, 0xa6, 0xf4, 0x28, 0xb9, 0x60, 0x6e, 0x03, 0x49, 0xbd, 0xe8, + 0x10, 0x40, 0xf8, 0xf3, 0x9f, 0xb4, 0x10, 0xbd, 0x0d, 0xaa, 0x86, 0x00, + 0x0a, 0xaa, 0x86, 0x00, 0x70, 0xb5, 0x0c, 0x46, 0x05, 0x69, 0x16, 0x46, + 0x08, 0x46, 0x0a, 0x22, 0x00, 0x21, 0xf7, 0xf3, 0xc9, 0xf7, 0x63, 0x88, + 0x1e, 0x43, 0xeb, 0x6c, 0x66, 0x80, 0x98, 0x06, 0x03, 0xd5, 0x23, 0x88, + 0x43, 0xf4, 0x80, 0x63, 0x23, 0x80, 0xab, 0x6f, 0x42, 0xf2, 0x50, 0x02, + 0x19, 0x8c, 0x91, 0x42, 0x05, 0xd1, 0x5b, 0x8c, 0x05, 0x2b, 0x9c, 0xbf, + 0x46, 0xf0, 0x04, 0x06, 0x66, 0x80, 0x70, 0xbd, 0xd0, 0xf8, 0xec, 0x10, + 0x10, 0xb5, 0x04, 0x46, 0x31, 0xb1, 0x00, 0x68, 0x0c, 0x22, 0xfc, 0xf3, + 0x01, 0xf6, 0x00, 0x23, 0xc4, 0xf8, 0xec, 0x30, 0x10, 0xbd, 0x01, 0x21, + 0x83, 0x6f, 0x10, 0xb5, 0x80, 0xf8, 0x90, 0x10, 0x04, 0x46, 0x58, 0x6a, + 0x06, 0xf0, 0xb4, 0xff, 0x20, 0x46, 0x02, 0x21, 0x31, 0xf0, 0xe4, 0xdd, + 0xa3, 0x68, 0x98, 0x68, 0x05, 0xf0, 0xe8, 0xda, 0x00, 0x20, 0x10, 0xbd, + 0x00, 0xeb, 0x81, 0x03, 0xdb, 0x6f, 0x0a, 0x46, 0x83, 0x67, 0x83, 0x68, + 0x01, 0xf1, 0x0e, 0x01, 0x53, 0xf8, 0x21, 0x10, 0x19, 0x63, 0x90, 0xf8, + 0xeb, 0x30, 0x5b, 0xb1, 0x90, 0xf8, 0xe8, 0x30, 0x43, 0xb9, 0x4f, 0xf4, + 0x00, 0x51, 0x00, 0x6e, 0x00, 0x2a, 0x0c, 0xbf, 0x0a, 0x46, 0x00, 0x22, + 0x00, 0xf0, 0x6a, 0x9e, 0x70, 0x47, 0x00, 0x00, 0x2d, 0xe9, 0xf3, 0x47, + 0x06, 0x46, 0x88, 0x46, 0x22, 0xb1, 0x83, 0x68, 0x1b, 0x68, 0xdb, 0x69, + 0x5f, 0x6b, 0x01, 0xe0, 0x4f, 0xf0, 0xff, 0x37, 0x00, 0x25, 0xaa, 0x46, + 0x2c, 0x46, 0x0a, 0xe0, 0xba, 0xf1, 0x00, 0x0f, 0x02, 0xd0, 0xca, 0xf8, + 0x04, 0x00, 0x00, 0xe0, 0x04, 0x46, 0x01, 0x35, 0xbd, 0x42, 0x0a, 0xd2, + 0x82, 0x46, 0xdf, 0xf8, 0x5c, 0x90, 0x06, 0xeb, 0x88, 0x02, 0xd9, 0xf8, + 0x68, 0x30, 0xd0, 0x68, 0x98, 0x47, 0x00, 0x28, 0xea, 0xd1, 0x30, 0x46, + 0x6a, 0x46, 0x01, 0xa9, 0x33, 0xf0, 0x46, 0xda, 0x06, 0xeb, 0x88, 0x02, + 0xd9, 0xf8, 0x6c, 0x30, 0xd0, 0x68, 0x98, 0x47, 0x0f, 0xe0, 0x00, 0x23, + 0xd4, 0xf8, 0x04, 0x80, 0x21, 0x69, 0x63, 0x60, 0x01, 0x9b, 0x8b, 0x61, + 0xb3, 0x6f, 0x58, 0x6a, 0x08, 0xf0, 0x50, 0xfc, 0x21, 0x46, 0xb0, 0x68, + 0xfe, 0xf7, 0xf4, 0xf9, 0x44, 0x46, 0x00, 0x2c, 0xed, 0xd1, 0xbd, 0x42, + 0x34, 0xbf, 0x00, 0x20, 0x01, 0x20, 0xbd, 0xe8, 0xfc, 0x87, 0x00, 0xbf, + 0xe0, 0xa6, 0x85, 0x00, 0xf8, 0xb5, 0x0e, 0x46, 0x01, 0x31, 0x04, 0x46, + 0x03, 0xd1, 0x83, 0x6f, 0x5e, 0x6a, 0x06, 0xb1, 0x9e, 0x69, 0x94, 0xf8, + 0xe9, 0x50, 0x1d, 0xb9, 0x20, 0x46, 0x29, 0x46, 0x31, 0xf0, 0x66, 0xdd, + 0x20, 0x6e, 0x00, 0xf0, 0x69, 0xdf, 0x78, 0xb1, 0x00, 0x27, 0xe3, 0x19, + 0xd8, 0x68, 0x10, 0xb1, 0x25, 0x4b, 0x9b, 0x68, 0x98, 0x47, 0x04, 0x37, + 0x18, 0x2f, 0xf6, 0xd1, 0xe3, 0x68, 0x1b, 0xb1, 0x20, 0x46, 0x00, 0x21, + 0x31, 0xf0, 0x9e, 0xdd, 0x94, 0xf8, 0xe8, 0x20, 0x42, 0xb1, 0xa3, 0x68, + 0x00, 0x22, 0x20, 0x46, 0x03, 0x21, 0xda, 0x61, 0xbd, 0xe8, 0xf8, 0x40, + 0x32, 0xf0, 0xd2, 0x9e, 0x46, 0xf0, 0x04, 0x01, 0x84, 0xf8, 0xea, 0x20, + 0x20, 0x6e, 0x00, 0xf0, 0xf5, 0xdd, 0xa3, 0x6f, 0x01, 0x21, 0x84, 0xf8, + 0xea, 0x10, 0x1b, 0xb1, 0x58, 0x6a, 0x08, 0xb1, 0x06, 0xf0, 0xfd, 0xfe, + 0x20, 0x46, 0x31, 0xf0, 0x57, 0xde, 0xe3, 0x6e, 0x20, 0x6e, 0xd3, 0xf8, + 0xe0, 0x21, 0x01, 0x21, 0x22, 0xf0, 0x20, 0x02, 0xc3, 0xf8, 0xe0, 0x21, + 0xfb, 0xf3, 0x88, 0xf6, 0x00, 0x21, 0x20, 0x46, 0x31, 0xf0, 0x24, 0xdd, + 0x20, 0x46, 0x32, 0xf0, 0x9f, 0xdf, 0x20, 0x46, 0x01, 0x21, 0x32, 0xf0, + 0x73, 0xdb, 0xa3, 0x68, 0x00, 0x22, 0xda, 0x61, 0x2d, 0xb9, 0x20, 0x46, + 0x02, 0x21, 0xbd, 0xe8, 0xf8, 0x40, 0x31, 0xf0, 0x13, 0x9d, 0xf8, 0xbd, + 0xe0, 0xa6, 0x85, 0x00, 0x83, 0x68, 0x10, 0xb5, 0x1a, 0x68, 0x1b, 0x69, + 0xd2, 0xf8, 0x8c, 0x20, 0x04, 0x46, 0xd2, 0xf8, 0xb4, 0x10, 0x01, 0x31, + 0xc2, 0xf8, 0xb4, 0x10, 0x93, 0xf8, 0xea, 0x20, 0x5a, 0xb1, 0xdb, 0x6e, + 0x40, 0xf2, 0x04, 0x40, 0xd3, 0xf8, 0x20, 0x31, 0x18, 0x40, 0xa0, 0xf5, + 0x80, 0x61, 0x48, 0x42, 0x40, 0xeb, 0x01, 0x00, 0x06, 0xe0, 0x18, 0x6e, + 0x02, 0xf0, 0x09, 0xff, 0xd0, 0xf1, 0x01, 0x00, 0x38, 0xbf, 0x00, 0x20, + 0x20, 0xb1, 0x20, 0x46, 0x4f, 0xf0, 0xff, 0x31, 0xff, 0xf7, 0x72, 0xff, + 0xa0, 0x68, 0x31, 0xf0, 0x7f, 0xdd, 0xa0, 0x68, 0xbd, 0xe8, 0x10, 0x40, + 0x1c, 0xf0, 0xd8, 0x9b, 0x38, 0xb5, 0x04, 0x46, 0x90, 0xf8, 0x90, 0x00, + 0x00, 0x28, 0x2b, 0xd0, 0xa3, 0x68, 0x1b, 0x69, 0x93, 0xf8, 0xea, 0x20, + 0x52, 0xb1, 0xdb, 0x6e, 0x40, 0xf2, 0x04, 0x45, 0xd3, 0xf8, 0x20, 0x31, + 0x1d, 0x40, 0xb5, 0xf5, 0x80, 0x65, 0x18, 0xbf, 0x01, 0x25, 0x03, 0xe0, + 0x18, 0x6e, 0x02, 0xf0, 0xde, 0xfe, 0x05, 0x46, 0xa3, 0x68, 0x15, 0xb1, + 0x00, 0x22, 0x1a, 0x62, 0x0c, 0xe0, 0x98, 0x68, 0x05, 0xf0, 0xbc, 0xd9, + 0x20, 0x46, 0x29, 0x46, 0x31, 0xf0, 0xba, 0xdc, 0x94, 0xf8, 0xe8, 0x30, + 0x13, 0xb9, 0x20, 0x46, 0x31, 0xf0, 0xd2, 0xdf, 0xa3, 0x6f, 0x58, 0x6a, + 0xbd, 0xe8, 0x38, 0x40, 0x06, 0xf0, 0xe6, 0xbe, 0x38, 0xbd, 0x10, 0xb5, + 0x04, 0x69, 0x4f, 0xf4, 0x40, 0x41, 0x20, 0x46, 0x00, 0x22, 0x32, 0xf0, + 0x31, 0xde, 0xd4, 0xf8, 0xf8, 0x30, 0x20, 0x46, 0x1b, 0x69, 0x13, 0xb1, + 0x31, 0xf0, 0x00, 0xda, 0x01, 0xe0, 0x31, 0xf0, 0xb9, 0xdf, 0xe1, 0x6c, + 0x20, 0x6e, 0x11, 0xf0, 0x02, 0x01, 0x18, 0xbf, 0x4f, 0xf4, 0x00, 0x71, + 0x0a, 0x46, 0x00, 0x23, 0xbd, 0xe8, 0x10, 0x40, 0x00, 0xf0, 0xe4, 0x9d, + 0x38, 0xb5, 0x83, 0x68, 0x04, 0x46, 0x1b, 0x68, 0x93, 0xf8, 0x20, 0x50, + 0xfd, 0xb9, 0x01, 0x21, 0x33, 0xf0, 0x86, 0xdc, 0x20, 0x6e, 0x02, 0xf0, + 0x7c, 0xfd, 0x20, 0x46, 0x29, 0x46, 0x31, 0xf0, 0x7d, 0xdc, 0x20, 0x46, + 0x31, 0xf0, 0x98, 0xdf, 0xa0, 0x68, 0xd0, 0xf8, 0x48, 0x38, 0x1b, 0x78, + 0x0b, 0xb1, 0x31, 0xf0, 0xc3, 0xdd, 0xa3, 0x6f, 0x58, 0x6a, 0x06, 0xf0, + 0x2b, 0xfe, 0x00, 0x23, 0x84, 0xf8, 0x5e, 0x30, 0xa3, 0x68, 0x01, 0x22, + 0x1b, 0x68, 0x83, 0xf8, 0x20, 0x20, 0x38, 0xbd, 0x38, 0xb5, 0x01, 0x21, + 0x04, 0x46, 0x33, 0xf0, 0x63, 0xdc, 0x20, 0x6e, 0x02, 0xf0, 0x59, 0xfd, + 0x20, 0x46, 0x00, 0x21, 0x31, 0xf0, 0x5a, 0xdc, 0x20, 0x46, 0x33, 0xf0, + 0xb5, 0xd8, 0x05, 0x46, 0x30, 0xb1, 0x20, 0x46, 0x00, 0x21, 0x33, 0xf0, + 0x53, 0xdc, 0x6f, 0xf0, 0x08, 0x00, 0x38, 0xbd, 0x20, 0x46, 0x4f, 0xf0, + 0xff, 0x31, 0xff, 0xf7, 0xd3, 0xfe, 0x28, 0x46, 0x38, 0xbd, 0x38, 0xb5, + 0x04, 0x46, 0x90, 0xf8, 0x90, 0x00, 0x00, 0x28, 0x44, 0xd0, 0xa3, 0x6f, + 0x00, 0x21, 0x84, 0xf8, 0x90, 0x10, 0x58, 0x6a, 0x06, 0xf0, 0x06, 0xfe, + 0xa3, 0x68, 0x1b, 0x69, 0x93, 0xf8, 0xea, 0x20, 0x52, 0xb1, 0xdb, 0x6e, + 0x40, 0xf2, 0x04, 0x45, 0xd3, 0xf8, 0x20, 0x31, 0x1d, 0x40, 0xb5, 0xf5, + 0x80, 0x65, 0x18, 0xbf, 0x01, 0x25, 0x03, 0xe0, 0x18, 0x6e, 0x02, 0xf0, + 0x3e, 0xfe, 0x05, 0x46, 0x6d, 0xb1, 0x00, 0x25, 0xa3, 0x6f, 0x84, 0xf8, + 0xeb, 0x50, 0x84, 0xf8, 0xea, 0x50, 0x58, 0x6a, 0x29, 0x46, 0x06, 0xf0, + 0xe2, 0xfd, 0xa0, 0x68, 0x31, 0xf0, 0xb2, 0xdc, 0x19, 0xe0, 0x20, 0x6e, + 0x00, 0xf0, 0x1a, 0xde, 0x78, 0xb1, 0xe3, 0x6e, 0xd3, 0xf8, 0x20, 0x31, + 0xd8, 0x07, 0x02, 0xd5, 0x20, 0x46, 0x33, 0xf0, 0x3d, 0xda, 0xa3, 0x68, + 0x98, 0x68, 0xf8, 0xf7, 0xb9, 0xfd, 0x05, 0x46, 0x20, 0x46, 0x33, 0xf0, + 0x23, 0xdc, 0x94, 0xf8, 0xe8, 0x10, 0x11, 0xb9, 0x20, 0x46, 0x33, 0xf0, + 0xff, 0xdb, 0x28, 0x46, 0x38, 0xbd, 0x00, 0x00, 0x70, 0xb5, 0x08, 0x29, + 0x86, 0xb0, 0x04, 0x46, 0x0e, 0x46, 0x00, 0xf3, 0xf4, 0x80, 0x83, 0x68, + 0x7d, 0x49, 0x1b, 0x68, 0x58, 0x69, 0xf8, 0xf3, 0x3d, 0xf2, 0x08, 0x2e, + 0x1c, 0xd1, 0x23, 0x6e, 0x9a, 0x69, 0x92, 0x00, 0x02, 0xd5, 0xda, 0x69, + 0xd6, 0x07, 0x08, 0xd5, 0xe2, 0x6c, 0xd1, 0x07, 0x08, 0xd5, 0x22, 0x6d, + 0x12, 0x06, 0x05, 0xd4, 0xdb, 0x69, 0xdb, 0x07, 0x02, 0xd5, 0x63, 0x6d, + 0x9e, 0x00, 0x03, 0xd4, 0x26, 0x6d, 0x16, 0xf0, 0x80, 0x06, 0x0f, 0xd0, + 0x46, 0xb2, 0x02, 0x2e, 0xcc, 0xbf, 0x05, 0x26, 0x01, 0x26, 0x00, 0xe0, + 0x46, 0xb1, 0xd4, 0xf8, 0xf8, 0x30, 0x5b, 0x68, 0x02, 0x2b, 0x03, 0xdd, + 0xa3, 0x6d, 0x99, 0x00, 0x40, 0xf1, 0xc8, 0x80, 0x0a, 0x22, 0x03, 0xa8, + 0x00, 0x21, 0xf7, 0xf3, 0x73, 0xf5, 0xd4, 0xf8, 0xf8, 0x30, 0x00, 0x22, + 0x1a, 0x81, 0x94, 0xf8, 0x90, 0x50, 0x65, 0xb1, 0xe2, 0x6e, 0xd2, 0xf8, + 0x20, 0x51, 0x05, 0xf0, 0x01, 0x05, 0x46, 0xb9, 0x1b, 0x68, 0x00, 0x2b, + 0x64, 0xd0, 0x20, 0x46, 0x31, 0xf0, 0xca, 0xde, 0x60, 0xe0, 0x00, 0x2e, + 0x5d, 0xd0, 0xbd, 0xf8, 0x0c, 0x20, 0x59, 0x68, 0x42, 0xf0, 0x10, 0x02, + 0x02, 0x29, 0xad, 0xf8, 0x0c, 0x20, 0x62, 0x6d, 0x03, 0xd1, 0x22, 0xf0, + 0x00, 0x52, 0x62, 0x65, 0x26, 0xe0, 0x42, 0xf0, 0x00, 0x52, 0x62, 0x65, + 0x72, 0x07, 0x01, 0xd4, 0x14, 0x22, 0x1a, 0x81, 0x22, 0x6e, 0x90, 0x69, + 0x80, 0x00, 0x02, 0xd5, 0xd0, 0x69, 0xc0, 0x07, 0x08, 0xd5, 0xe0, 0x6c, + 0xc0, 0x07, 0x0a, 0xd5, 0x20, 0x6d, 0x00, 0x06, 0x07, 0xd4, 0xd2, 0x69, + 0xd0, 0x07, 0x04, 0xd5, 0x1a, 0x89, 0x42, 0xf0, 0x40, 0x02, 0x1a, 0x81, + 0x0a, 0xe0, 0x04, 0x29, 0x05, 0xd1, 0xbd, 0xf8, 0x10, 0x20, 0x42, 0xf4, + 0x00, 0x52, 0xad, 0xf8, 0x10, 0x20, 0x00, 0x22, 0x1a, 0x61, 0xda, 0x60, + 0x5a, 0x68, 0x02, 0x2a, 0x12, 0xd1, 0xe2, 0x6c, 0x12, 0xf4, 0x80, 0x4f, + 0xbd, 0xf8, 0x0e, 0x20, 0x08, 0xd0, 0x42, 0xf4, 0x80, 0x72, 0xad, 0xf8, + 0x0e, 0x20, 0x30, 0x22, 0xda, 0x60, 0x20, 0x22, 0x1a, 0x61, 0x03, 0xe0, + 0x22, 0xf4, 0x80, 0x72, 0xad, 0xf8, 0x0e, 0x20, 0x1a, 0x89, 0x16, 0xf0, + 0x02, 0x0f, 0x14, 0xbf, 0x42, 0xf0, 0x01, 0x02, 0x22, 0xf0, 0x01, 0x02, + 0x1a, 0x81, 0x1a, 0x89, 0x16, 0xf0, 0x04, 0x0f, 0x14, 0xbf, 0x42, 0xf0, + 0x08, 0x02, 0x22, 0xf0, 0x08, 0x02, 0x1a, 0x81, 0x0a, 0xe0, 0x35, 0x46, + 0xbd, 0xf8, 0x0c, 0x30, 0x23, 0xf0, 0x10, 0x03, 0xad, 0xf8, 0x0c, 0x30, + 0x63, 0x6d, 0x23, 0xf0, 0x00, 0x53, 0x63, 0x65, 0xd4, 0xf8, 0xf8, 0x30, + 0x61, 0x6d, 0x1e, 0x60, 0xa3, 0x6f, 0x58, 0x6a, 0x07, 0xf0, 0xd7, 0xf9, + 0x94, 0xf8, 0x90, 0x30, 0x1b, 0xb1, 0x15, 0xb1, 0x20, 0x46, 0x33, 0xf0, + 0x63, 0xd9, 0x02, 0x26, 0xbd, 0xf8, 0x0c, 0x30, 0x20, 0x46, 0x00, 0x21, + 0x10, 0x22, 0x00, 0x96, 0x32, 0xf0, 0xc6, 0xdc, 0xbd, 0xf8, 0x0e, 0x30, + 0x20, 0x46, 0x01, 0x21, 0x4f, 0xf4, 0x80, 0x72, 0x00, 0x96, 0x32, 0xf0, + 0xbd, 0xdc, 0xbd, 0xf8, 0x10, 0x30, 0x20, 0x46, 0x31, 0x46, 0x4f, 0xf4, + 0x00, 0x52, 0x00, 0x96, 0x32, 0xf0, 0xb4, 0xdc, 0x20, 0x46, 0x31, 0xf0, + 0xd1, 0xda, 0x94, 0xf8, 0x90, 0x00, 0xb8, 0xb1, 0xa3, 0x6f, 0x1b, 0x68, + 0xb3, 0x42, 0x06, 0xd1, 0xd4, 0xf8, 0xf8, 0x30, 0x1b, 0x68, 0x13, 0xb1, + 0x20, 0x46, 0x31, 0xf0, 0x67, 0xd8, 0x55, 0xb1, 0x20, 0x46, 0x32, 0xf0, + 0x8d, 0xd9, 0x00, 0x20, 0x06, 0xe0, 0x6f, 0xf0, 0x01, 0x00, 0x03, 0xe0, + 0x6f, 0xf0, 0x02, 0x00, 0x00, 0xe0, 0x28, 0x46, 0x06, 0xb0, 0x70, 0xbd, + 0xc6, 0x5c, 0x86, 0x00, 0xf7, 0xb5, 0x85, 0x68, 0xc6, 0x6e, 0x2b, 0x68, + 0x04, 0x46, 0xdb, 0x69, 0x06, 0x27, 0x1b, 0x6a, 0x69, 0x46, 0xc5, 0xf8, + 0xac, 0x38, 0x30, 0x4b, 0x3a, 0x46, 0x18, 0x68, 0x00, 0x90, 0x9b, 0x88, + 0x60, 0x6c, 0xad, 0xf8, 0x04, 0x30, 0x2d, 0x4b, 0x07, 0xfb, 0x00, 0x30, + 0x18, 0x38, 0xf7, 0xf3, 0x2b, 0xf4, 0x04, 0x23, 0xc5, 0xf8, 0xac, 0x38, + 0x03, 0x23, 0x85, 0xf8, 0xa9, 0x38, 0xa0, 0x68, 0x20, 0xf0, 0x8c, 0xdb, + 0x20, 0xb1, 0xd5, 0xf8, 0xac, 0x78, 0xbf, 0x00, 0x01, 0x37, 0xbf, 0xb2, + 0xd4, 0xf8, 0xb8, 0x30, 0x00, 0x22, 0x99, 0x5c, 0x38, 0x0a, 0x79, 0x18, + 0x89, 0xb2, 0x01, 0x39, 0xfd, 0xb2, 0x45, 0xea, 0x01, 0x25, 0x00, 0xf0, + 0x01, 0x00, 0x01, 0xf4, 0x80, 0x71, 0x08, 0x43, 0x6f, 0xea, 0x42, 0x61, + 0x6f, 0xea, 0x51, 0x41, 0xa6, 0xf8, 0x40, 0x15, 0xa6, 0xf8, 0x20, 0x55, + 0xa6, 0xf8, 0x2c, 0x05, 0xa6, 0xf8, 0x40, 0x15, 0x99, 0x5c, 0x01, 0x32, + 0x7f, 0x18, 0x06, 0x2a, 0xbf, 0xb2, 0xe0, 0xd1, 0x20, 0x46, 0x98, 0x21, + 0x5a, 0x78, 0x33, 0xf0, 0x63, 0xda, 0xd4, 0xf8, 0xb8, 0x30, 0x20, 0x46, + 0x9a, 0x21, 0x9a, 0x78, 0x33, 0xf0, 0x5c, 0xda, 0xd4, 0xf8, 0xb8, 0x30, + 0x20, 0x46, 0xda, 0x78, 0x1b, 0x78, 0x9c, 0x21, 0x43, 0xea, 0x02, 0x22, + 0x33, 0xf0, 0x52, 0xda, 0xd4, 0xf8, 0xb8, 0x30, 0x20, 0x46, 0x5a, 0x79, + 0x1b, 0x79, 0x9e, 0x21, 0x43, 0xea, 0x02, 0x22, 0x33, 0xf0, 0x48, 0xda, + 0xfe, 0xbd, 0x00, 0xbf, 0x60, 0xb7, 0x01, 0x00, 0x34, 0xfe, 0x01, 0x00, + 0xf0, 0xb5, 0x04, 0x69, 0x06, 0x46, 0x85, 0xb0, 0x20, 0x46, 0x92, 0x21, + 0x32, 0xf0, 0x20, 0xdf, 0x40, 0x00, 0x80, 0xb2, 0xa6, 0xf8, 0x42, 0x00, + 0x50, 0xb3, 0x00, 0x25, 0x0f, 0x21, 0x68, 0x46, 0x14, 0x4a, 0x2b, 0x46, + 0xf7, 0xf3, 0x68, 0xf4, 0x60, 0x6e, 0x69, 0x46, 0xf8, 0xf3, 0xe8, 0xf0, + 0x60, 0xb1, 0x69, 0x46, 0x60, 0x6e, 0xb6, 0xf8, 0x42, 0x70, 0xf8, 0xf3, + 0xb5, 0xf0, 0x07, 0xeb, 0x45, 0x07, 0x82, 0xb2, 0x39, 0x46, 0x20, 0x46, + 0x33, 0xf0, 0x1c, 0xda, 0x01, 0x35, 0x77, 0x2d, 0xe4, 0xd1, 0x60, 0x6e, + 0x08, 0x49, 0xf8, 0xf3, 0xd3, 0xf0, 0x48, 0xb1, 0x60, 0x6e, 0x06, 0x49, + 0xd4, 0xf8, 0xf8, 0x50, 0xf8, 0xf3, 0xa0, 0xf0, 0x28, 0x81, 0x20, 0x46, + 0x31, 0xf0, 0x0a, 0xda, 0x05, 0xb0, 0xf0, 0xbd, 0xae, 0xac, 0x86, 0x00, + 0x17, 0x7c, 0x86, 0x00, 0x81, 0x6f, 0x10, 0xb5, 0x08, 0x31, 0x04, 0x46, + 0x31, 0xf0, 0x0a, 0xdd, 0xff, 0xf7, 0x06, 0xfc, 0x01, 0x46, 0x20, 0x46, + 0xbd, 0xe8, 0x10, 0x40, 0x31, 0xf0, 0xe2, 0x9c, 0x10, 0xb5, 0x83, 0x6f, + 0x06, 0x4a, 0x1c, 0x6a, 0x40, 0xf2, 0xee, 0x23, 0x94, 0x21, 0x94, 0x42, + 0x14, 0xbf, 0x1a, 0x46, 0x4f, 0xf4, 0x16, 0x62, 0xbd, 0xe8, 0x10, 0x40, + 0x33, 0xf0, 0xe6, 0x99, 0x50, 0x20, 0x08, 0x00, 0x73, 0xb5, 0x04, 0x69, + 0x05, 0x46, 0x20, 0x46, 0x0e, 0x46, 0xff, 0xf7, 0xd9, 0xff, 0xa3, 0x6f, + 0x31, 0x46, 0x58, 0x6a, 0x07, 0xf0, 0x3e, 0xfa, 0x2b, 0x68, 0x01, 0x22, + 0x83, 0xf8, 0x74, 0x20, 0x20, 0x46, 0x31, 0xf0, 0x15, 0xdc, 0xa3, 0x6f, + 0x20, 0x46, 0x99, 0x8a, 0x32, 0xf0, 0xa8, 0xdf, 0xa3, 0x6f, 0x20, 0x46, + 0xd9, 0x8a, 0x32, 0xf0, 0x91, 0xdf, 0x20, 0x46, 0x94, 0xf8, 0x86, 0x10, + 0x31, 0xf0, 0x96, 0xd9, 0xa3, 0x6f, 0x20, 0x46, 0x52, 0x21, 0x9a, 0x8b, + 0x33, 0xf0, 0xbc, 0xd9, 0xa3, 0x6f, 0x50, 0x21, 0xda, 0x8b, 0x20, 0x46, + 0x33, 0xf0, 0xb6, 0xd9, 0x20, 0x46, 0x31, 0xf0, 0x19, 0xdc, 0x20, 0x46, + 0xff, 0xf7, 0xba, 0xff, 0x03, 0x23, 0x00, 0x93, 0x20, 0x46, 0x04, 0x21, + 0x08, 0x22, 0x00, 0x23, 0x32, 0xf0, 0x88, 0xdb, 0x20, 0x46, 0x02, 0xb0, + 0xbd, 0xe8, 0x70, 0x40, 0x30, 0xf0, 0x46, 0x9f, 0x2d, 0xe9, 0xf0, 0x41, + 0x17, 0x46, 0x04, 0x46, 0x0d, 0x46, 0xbd, 0xf8, 0x18, 0x20, 0x9d, 0xf8, + 0x1c, 0x60, 0x98, 0x46, 0x3b, 0xb1, 0x83, 0x68, 0x0c, 0x31, 0xdb, 0x6a, + 0x03, 0xeb, 0x41, 0x03, 0x99, 0x88, 0x71, 0x18, 0x99, 0x80, 0x4f, 0xf6, + 0xff, 0x73, 0x9a, 0x42, 0x03, 0xd0, 0x20, 0x46, 0xa8, 0x21, 0x33, 0xf0, + 0x87, 0xd9, 0x04, 0xeb, 0x85, 0x03, 0xd8, 0x68, 0x09, 0x4b, 0x39, 0x46, + 0x42, 0x46, 0x5b, 0x6a, 0x98, 0x47, 0x00, 0x28, 0x0a, 0xda, 0xb8, 0xf1, + 0x00, 0x0f, 0x07, 0xd0, 0xa3, 0x68, 0x0c, 0x35, 0xdb, 0x6a, 0x03, 0xeb, + 0x45, 0x05, 0xab, 0x88, 0x9e, 0x1b, 0xae, 0x80, 0xbd, 0xe8, 0xf0, 0x81, + 0xe0, 0xa6, 0x85, 0x00, 0x2d, 0xe9, 0xf0, 0x41, 0x04, 0x69, 0x86, 0xb0, + 0x4f, 0xf0, 0xff, 0x31, 0xa1, 0x4a, 0x06, 0x46, 0x20, 0x46, 0xe5, 0x6e, + 0x32, 0xf0, 0x30, 0xdb, 0xd4, 0xf8, 0xf8, 0x30, 0x20, 0x46, 0x19, 0x68, + 0xff, 0xf7, 0xa4, 0xfd, 0xa3, 0x6d, 0x2b, 0xb1, 0x03, 0x23, 0xa5, 0xf8, + 0xb4, 0x36, 0xff, 0x23, 0xa5, 0xf8, 0xb8, 0x36, 0xe3, 0x6c, 0xdb, 0x07, + 0x24, 0xd5, 0x97, 0x4b, 0x1a, 0x68, 0x0a, 0xbb, 0x01, 0x21, 0x19, 0x60, + 0x23, 0x6d, 0x20, 0x6e, 0x1f, 0x06, 0x03, 0xd5, 0x03, 0x21, 0x02, 0xf0, + 0xec, 0xfa, 0x17, 0xe0, 0x02, 0xf0, 0xe9, 0xfa, 0x23, 0x6d, 0x9a, 0x00, + 0x12, 0xd4, 0x20, 0x46, 0x92, 0x21, 0x32, 0xf0, 0x21, 0xde, 0x47, 0x00, + 0xbf, 0xb2, 0x5f, 0xb1, 0xce, 0x37, 0x39, 0x46, 0x20, 0x46, 0x32, 0xf0, + 0x19, 0xde, 0x40, 0xf0, 0x40, 0x02, 0x39, 0x46, 0x20, 0x46, 0x92, 0xb2, + 0x33, 0xf0, 0x2c, 0xd9, 0x4f, 0xf0, 0xff, 0x31, 0xc5, 0xf8, 0x28, 0x11, + 0x20, 0x46, 0x83, 0x4a, 0x32, 0xf0, 0xf2, 0xda, 0x82, 0x4f, 0x02, 0xe0, + 0x0a, 0x20, 0xfb, 0xf3, 0xa1, 0xf6, 0xd5, 0xf8, 0x28, 0x31, 0xdb, 0x07, + 0x01, 0xd4, 0x01, 0x3f, 0xf6, 0xd1, 0x30, 0x46, 0xd5, 0xf8, 0x28, 0x31, + 0xff, 0xf7, 0xa9, 0xfc, 0xd4, 0xf8, 0xf4, 0x30, 0x2b, 0xb9, 0x23, 0x6e, + 0x9a, 0x6a, 0x40, 0xf2, 0x94, 0x53, 0x9a, 0x42, 0x13, 0xd1, 0x20, 0x6e, + 0x76, 0x4a, 0x83, 0x6b, 0x9a, 0x18, 0x01, 0x2a, 0x07, 0xd9, 0x4a, 0xf6, + 0xe6, 0x02, 0x93, 0x42, 0x03, 0xd0, 0x4a, 0xf6, 0xe5, 0x02, 0x93, 0x42, + 0x05, 0xd1, 0x08, 0x23, 0x00, 0x21, 0x28, 0x22, 0x00, 0x93, 0x00, 0xf0, + 0x13, 0xda, 0x00, 0x21, 0x0a, 0x46, 0x20, 0x6e, 0x00, 0xf0, 0xf2, 0xd9, + 0xff, 0xf7, 0xfe, 0xfa, 0x01, 0x46, 0x20, 0x46, 0x31, 0xf0, 0xd8, 0xdb, + 0x20, 0x46, 0xff, 0xf7, 0x37, 0xfe, 0x4f, 0xf4, 0x80, 0x33, 0x00, 0x93, + 0x20, 0x46, 0x06, 0x23, 0x98, 0x21, 0x03, 0xaa, 0x31, 0xf0, 0x0c, 0xdf, + 0x33, 0x68, 0x93, 0xf8, 0x38, 0x30, 0xcb, 0xb1, 0x30, 0x46, 0x20, 0xf0, + 0xd5, 0xd9, 0x01, 0x28, 0x14, 0xd1, 0x00, 0x27, 0x05, 0x97, 0xb8, 0x46, + 0x0b, 0xe0, 0x4f, 0xf4, 0xc0, 0x23, 0x00, 0x93, 0x39, 0x46, 0x20, 0x46, + 0x05, 0xaa, 0x04, 0x23, 0x31, 0xf0, 0x1c, 0xdf, 0x08, 0xf1, 0x01, 0x08, + 0x24, 0x37, 0x33, 0x68, 0xdb, 0x69, 0x1b, 0x6a, 0x98, 0x45, 0xee, 0xd3, + 0x20, 0x46, 0x80, 0x21, 0x08, 0x22, 0x33, 0xf0, 0xbd, 0xd8, 0x20, 0x46, + 0x5c, 0x21, 0x0a, 0x22, 0x33, 0xf0, 0xb8, 0xd8, 0x4f, 0xf0, 0x80, 0x73, + 0x4d, 0x4a, 0xc5, 0xf8, 0x00, 0x31, 0x20, 0x46, 0x4c, 0x49, 0x32, 0xf0, + 0x7d, 0xda, 0x4f, 0xf0, 0x00, 0x43, 0xc5, 0xf8, 0x88, 0x31, 0x4f, 0xf0, + 0x00, 0x73, 0xc5, 0xf8, 0x8c, 0x31, 0x4f, 0xf4, 0x80, 0x43, 0xc5, 0xf8, + 0x28, 0x31, 0x4f, 0xf4, 0x80, 0x33, 0x6b, 0x62, 0x01, 0x21, 0x20, 0x46, + 0x32, 0xf0, 0x58, 0xda, 0x20, 0x6e, 0x02, 0xf0, 0xd7, 0xf9, 0x16, 0x21, + 0x30, 0x83, 0xb4, 0xf8, 0x44, 0x20, 0xa5, 0xf8, 0xa8, 0x06, 0x20, 0x46, + 0x33, 0xf0, 0x90, 0xd8, 0x20, 0x46, 0xc0, 0x21, 0xb4, 0xf8, 0x54, 0x20, + 0x33, 0xf0, 0x8a, 0xd8, 0x20, 0x46, 0xc2, 0x21, 0xb4, 0xf8, 0x56, 0x20, + 0x33, 0xf0, 0x84, 0xd8, 0x36, 0x4b, 0x20, 0x46, 0xc5, 0xf8, 0x60, 0x31, + 0xd5, 0xf8, 0x60, 0x31, 0xb4, 0xf8, 0x88, 0x30, 0x44, 0x21, 0xc5, 0xf8, + 0x64, 0x31, 0x32, 0x4b, 0xb4, 0xf8, 0x8c, 0x20, 0xc5, 0xf8, 0x60, 0x31, + 0xd5, 0xf8, 0x60, 0x31, 0xb4, 0xf8, 0x8a, 0x30, 0xc5, 0xf8, 0x64, 0x31, + 0x33, 0xf0, 0x6c, 0xd8, 0x20, 0x46, 0x46, 0x21, 0xb4, 0xf8, 0x8e, 0x20, + 0x33, 0xf0, 0x66, 0xd8, 0xb5, 0xf8, 0x88, 0x36, 0x1b, 0x05, 0x1b, 0x0d, + 0xa5, 0xf8, 0x88, 0x36, 0x01, 0x23, 0xa5, 0xf8, 0x9c, 0x36, 0x00, 0x25, + 0xb5, 0x64, 0x63, 0x19, 0xd8, 0x68, 0x10, 0xb1, 0x22, 0x4b, 0x5b, 0x68, + 0x98, 0x47, 0x04, 0x35, 0x18, 0x2d, 0xf6, 0xd1, 0x1f, 0x4d, 0xe0, 0x68, + 0x2b, 0x6d, 0x98, 0x47, 0xeb, 0x6e, 0xe0, 0x68, 0x98, 0x47, 0x30, 0x46, + 0xff, 0xf7, 0x06, 0xfe, 0x23, 0x6e, 0x9a, 0x6b, 0x4a, 0xf6, 0x62, 0x13, + 0x9a, 0x42, 0x1a, 0xd1, 0xe3, 0x6c, 0xd8, 0x07, 0x17, 0xd5, 0x23, 0x6d, + 0x19, 0x06, 0x14, 0xd4, 0x9a, 0x00, 0x12, 0xd4, 0x20, 0x46, 0x92, 0x21, + 0x32, 0xf0, 0x1c, 0xdd, 0x45, 0x00, 0xad, 0xb2, 0x5d, 0xb1, 0xce, 0x35, + 0x29, 0x46, 0x20, 0x46, 0x32, 0xf0, 0x14, 0xdd, 0x40, 0xf0, 0x40, 0x02, + 0x29, 0x46, 0x20, 0x46, 0x92, 0xb2, 0x33, 0xf0, 0x27, 0xd8, 0x06, 0xb0, + 0xbd, 0xe8, 0xf0, 0x81, 0x04, 0x04, 0x00, 0x04, 0xec, 0x07, 0x02, 0x00, + 0x02, 0x04, 0x02, 0x04, 0xa1, 0x86, 0x01, 0x00, 0x1d, 0x57, 0xff, 0xff, + 0x00, 0x00, 0x02, 0x40, 0x00, 0x00, 0x06, 0x40, 0x06, 0x00, 0x02, 0x00, + 0x07, 0x00, 0x02, 0x00, 0xe0, 0xa6, 0x85, 0x00, 0x2d, 0xe9, 0xf8, 0x43, + 0x90, 0xf8, 0xe9, 0x60, 0x04, 0x46, 0x0f, 0x46, 0x91, 0x46, 0x85, 0x68, + 0x16, 0xb9, 0x31, 0x46, 0x31, 0xf0, 0x46, 0xd8, 0xa8, 0x68, 0x04, 0xf0, + 0x41, 0xdd, 0x07, 0xf4, 0x70, 0x41, 0xa1, 0xf5, 0x80, 0x52, 0x51, 0x42, + 0x41, 0xeb, 0x02, 0x01, 0x80, 0x46, 0x20, 0x46, 0xff, 0xf7, 0x5a, 0xfa, + 0xa3, 0x6f, 0x39, 0x46, 0x58, 0x6a, 0x06, 0xf0, 0x24, 0xfc, 0xa3, 0x6f, + 0x58, 0x6a, 0x06, 0xf0, 0x00, 0xfa, 0x28, 0x46, 0xff, 0xf7, 0x7c, 0xfe, + 0xb9, 0xf1, 0x00, 0x0f, 0x04, 0xd0, 0x01, 0x21, 0x20, 0x46, 0x0a, 0x46, + 0x32, 0xf0, 0x1e, 0xda, 0x28, 0x46, 0x39, 0x46, 0xff, 0xf7, 0xfa, 0xfd, + 0xa8, 0x68, 0x41, 0x46, 0x04, 0xf0, 0x2e, 0xdd, 0xd4, 0xf8, 0xd4, 0x30, + 0x43, 0xf0, 0x04, 0x03, 0xc4, 0xf8, 0xd4, 0x30, 0x01, 0x23, 0xc4, 0xf8, + 0xd0, 0x30, 0x2e, 0xb9, 0x20, 0x46, 0x02, 0x21, 0xbd, 0xe8, 0xf8, 0x43, + 0x31, 0xf0, 0x0c, 0x98, 0xbd, 0xe8, 0xf8, 0x83, 0xd1, 0xf8, 0xcc, 0x30, + 0x73, 0xb5, 0x43, 0xf4, 0x00, 0x53, 0xc1, 0xf8, 0xcc, 0x30, 0x05, 0x46, + 0x0c, 0x46, 0x34, 0xf0, 0x55, 0xdc, 0x06, 0x46, 0x00, 0x28, 0x40, 0xf0, + 0x84, 0x80, 0xb5, 0xf8, 0x82, 0x31, 0x44, 0xf2, 0x21, 0x32, 0x93, 0x42, + 0x1f, 0xd0, 0x44, 0xf2, 0x13, 0x32, 0x93, 0x42, 0x1b, 0xd0, 0x44, 0xf2, + 0x1a, 0x32, 0x93, 0x42, 0x17, 0xd0, 0x44, 0xf2, 0x2a, 0x32, 0x93, 0x42, + 0x13, 0xd0, 0x44, 0xf2, 0x16, 0x32, 0x93, 0x42, 0x0f, 0xd0, 0x44, 0xf2, + 0x1d, 0x32, 0x93, 0x42, 0x0b, 0xd0, 0x44, 0xf2, 0x2d, 0x32, 0x93, 0x42, + 0x07, 0xd0, 0x44, 0xf2, 0x52, 0x32, 0x93, 0x42, 0x03, 0xd0, 0xab, 0x6b, + 0x5b, 0x7d, 0x00, 0x2b, 0x58, 0xd0, 0x2b, 0x6b, 0x93, 0xf8, 0xec, 0x30, + 0x43, 0xb1, 0xb5, 0xf8, 0x26, 0x36, 0x03, 0xf4, 0x40, 0x63, 0xb3, 0xf5, + 0x40, 0x6f, 0x14, 0xbf, 0x14, 0x23, 0x28, 0x23, 0x2a, 0x68, 0x92, 0xf8, + 0x46, 0x20, 0x12, 0xf0, 0x03, 0x02, 0x07, 0xd0, 0xd4, 0xf8, 0xcc, 0x20, + 0x02, 0xf4, 0x80, 0x52, 0xd2, 0xf1, 0x01, 0x02, 0x38, 0xbf, 0x00, 0x22, + 0x00, 0x92, 0x28, 0x46, 0x21, 0x46, 0x02, 0x22, 0x33, 0xf0, 0x9c, 0xdd, + 0x06, 0x46, 0x00, 0x28, 0x39, 0xd1, 0xd4, 0xf8, 0xf0, 0x12, 0x29, 0xb1, + 0xd5, 0xf8, 0x4c, 0x01, 0x44, 0xf0, 0x8a, 0xdb, 0xc4, 0xf8, 0xf0, 0x62, + 0xd5, 0xf8, 0x4c, 0x01, 0x21, 0x46, 0x44, 0xf0, 0x55, 0xdb, 0xc4, 0xf8, + 0xf0, 0x02, 0x00, 0x28, 0x25, 0xd0, 0xa3, 0x79, 0xbb, 0xb1, 0x94, 0xf8, + 0xf5, 0x32, 0x31, 0x2b, 0x0e, 0xd8, 0x2b, 0x68, 0x1b, 0x7e, 0x2b, 0xb1, + 0x28, 0x46, 0x94, 0xf8, 0xf4, 0x12, 0x0f, 0x4a, 0x1e, 0xf0, 0x3a, 0xdb, + 0xd5, 0xf8, 0x4c, 0x01, 0x94, 0xf8, 0xf4, 0x12, 0x44, 0xf0, 0x80, 0xda, + 0x94, 0xf8, 0xf5, 0x32, 0x84, 0xf8, 0xf4, 0x32, 0x0d, 0xe0, 0xd5, 0xf8, + 0x4c, 0x01, 0x04, 0xf5, 0x3d, 0x71, 0x02, 0xb0, 0xbd, 0xe8, 0x70, 0x40, + 0x44, 0xf0, 0x36, 0x9a, 0x6f, 0xf0, 0x0b, 0x06, 0x01, 0xe0, 0x6f, 0xf0, + 0x1a, 0x06, 0x30, 0x46, 0x02, 0xb0, 0x70, 0xbd, 0x32, 0x9e, 0x85, 0x00, + 0x2d, 0xe9, 0xf0, 0x41, 0x05, 0x46, 0x34, 0xf0, 0xc1, 0xdc, 0x2e, 0x46, + 0x80, 0x46, 0x05, 0xf1, 0x20, 0x07, 0xd6, 0xf8, 0x4c, 0x42, 0x6c, 0xb1, + 0xa3, 0x79, 0x5b, 0xb1, 0x44, 0x45, 0x09, 0xd0, 0x63, 0x79, 0x1b, 0xb1, + 0x28, 0x46, 0x21, 0x46, 0x34, 0xf0, 0x30, 0xd8, 0x28, 0x46, 0x21, 0x46, + 0x34, 0xf0, 0x08, 0xdb, 0x04, 0x36, 0xbe, 0x42, 0xeb, 0xd1, 0xbd, 0xe8, + 0xf0, 0x81, 0x2d, 0xe9, 0xf3, 0x47, 0x0a, 0x9e, 0x80, 0x46, 0x0f, 0x46, + 0x91, 0x46, 0x1d, 0x46, 0xdd, 0xf8, 0x2c, 0xa0, 0xd0, 0xf8, 0xb8, 0x40, + 0x23, 0xe0, 0x63, 0x68, 0x1a, 0xea, 0x03, 0x0f, 0x1e, 0xd0, 0xdb, 0x05, + 0x07, 0xd5, 0x04, 0xf1, 0x0a, 0x01, 0x22, 0x7a, 0x63, 0x7a, 0x28, 0x46, + 0x00, 0x91, 0x31, 0x46, 0x0d, 0xe0, 0x2f, 0xb1, 0x40, 0x46, 0x49, 0x46, + 0x04, 0xf1, 0x08, 0x02, 0xb8, 0x47, 0x48, 0xb1, 0x04, 0xf1, 0x0a, 0x02, + 0x63, 0x7a, 0x28, 0x46, 0x00, 0x92, 0x31, 0x46, 0xdd, 0x22, 0x21, 0xf0, + 0x83, 0xd9, 0x00, 0xe0, 0x28, 0x46, 0x2d, 0x1a, 0x76, 0x19, 0x05, 0x46, + 0x24, 0x68, 0x00, 0x2c, 0xd9, 0xd1, 0x28, 0x46, 0xbd, 0xe8, 0xfc, 0x87, + 0x2d, 0xe9, 0xf0, 0x4f, 0xd1, 0xf8, 0xd4, 0x32, 0x87, 0xb0, 0xb3, 0xf8, + 0x32, 0xb0, 0x8b, 0x79, 0x05, 0x46, 0x0e, 0x46, 0xd0, 0xf8, 0x0c, 0x80, + 0xd0, 0xf8, 0x4c, 0x91, 0x00, 0x2b, 0x00, 0xf0, 0x9f, 0x80, 0x4f, 0xf0, + 0x00, 0x0a, 0x54, 0x46, 0x05, 0xeb, 0x0a, 0x03, 0xd3, 0xf8, 0x4c, 0x72, + 0x7f, 0xb1, 0xbb, 0x79, 0x6b, 0xb9, 0xfb, 0x79, 0x5b, 0xb1, 0xd7, 0xf8, + 0xd4, 0x32, 0x58, 0x8e, 0xf8, 0xf3, 0xa2, 0xf1, 0x04, 0x46, 0x58, 0x46, + 0xf8, 0xf3, 0x9e, 0xf1, 0x84, 0x42, 0x3c, 0x46, 0x06, 0xd1, 0x0a, 0xf1, + 0x04, 0x0a, 0xba, 0xf1, 0x20, 0x0f, 0xe5, 0xd1, 0x00, 0x2c, 0x7f, 0xd0, + 0xd4, 0xf8, 0xd4, 0x32, 0x58, 0x8e, 0xf8, 0xf3, 0x8f, 0xf1, 0x07, 0x46, + 0x58, 0x46, 0xf8, 0xf3, 0x8b, 0xf1, 0x87, 0x42, 0x05, 0xd0, 0xd4, 0xf8, + 0xd4, 0x22, 0xd6, 0xf8, 0xd4, 0x32, 0xd2, 0x8d, 0xda, 0x85, 0x28, 0x46, + 0x04, 0xa9, 0x05, 0xaa, 0x1b, 0xf0, 0x26, 0xd9, 0x21, 0x46, 0xd5, 0xf8, + 0x4c, 0x01, 0x44, 0xf0, 0x7d, 0xd9, 0x18, 0x27, 0x47, 0x43, 0xd5, 0xf8, + 0x4c, 0x01, 0x07, 0xf1, 0x3a, 0x01, 0x44, 0xf0, 0x5f, 0xde, 0x38, 0xb9, + 0x05, 0x9a, 0x04, 0x9b, 0x48, 0x46, 0x21, 0x46, 0x8d, 0xe8, 0x0c, 0x00, + 0x03, 0xf0, 0xc0, 0xff, 0xd5, 0xf8, 0x4c, 0x01, 0x07, 0xf1, 0x40, 0x01, + 0x44, 0xf0, 0x50, 0xde, 0xd4, 0xf8, 0xd4, 0x32, 0x04, 0x99, 0xdd, 0x8d, + 0x40, 0x01, 0xad, 0x02, 0xcd, 0x42, 0x02, 0x90, 0x03, 0xd3, 0xa8, 0x42, + 0x0a, 0xd3, 0x00, 0xe0, 0x10, 0x46, 0x21, 0xf0, 0x7f, 0x43, 0x23, 0xf4, + 0x60, 0x03, 0x98, 0x42, 0x00, 0xeb, 0x05, 0x02, 0xf6, 0xd3, 0x02, 0x90, + 0x03, 0xaa, 0x02, 0xab, 0x05, 0x98, 0x05, 0xf0, 0xe0, 0xfb, 0x20, 0x46, + 0x1a, 0xf0, 0x82, 0xdb, 0x02, 0xa9, 0x03, 0x46, 0x00, 0x22, 0x03, 0xa8, + 0x1f, 0xf0, 0x8a, 0xdf, 0xd6, 0xf8, 0xd4, 0x32, 0x6d, 0x08, 0xdc, 0x8d, + 0x03, 0xa8, 0x2b, 0x46, 0xa4, 0x02, 0x02, 0xa9, 0x00, 0x22, 0x1f, 0xf0, + 0x99, 0xdf, 0x01, 0x26, 0x23, 0x46, 0x01, 0xe0, 0x01, 0x36, 0x1b, 0x19, + 0xab, 0x42, 0xfb, 0xd3, 0x03, 0xa8, 0x02, 0xa9, 0x00, 0x22, 0x1f, 0xf0, + 0x8d, 0xdf, 0x02, 0x9b, 0x05, 0xa8, 0x04, 0xa9, 0x03, 0x9a, 0x1f, 0xf0, + 0x87, 0xdf, 0x04, 0x9b, 0x01, 0x36, 0xc8, 0xf8, 0x80, 0x31, 0x05, 0x9b, + 0xc8, 0xf8, 0x84, 0x31, 0xa3, 0x01, 0x74, 0x43, 0xc8, 0xf8, 0x88, 0x31, + 0xc8, 0xf8, 0x8c, 0x41, 0x07, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, 0x00, 0x20, + 0x10, 0x60, 0x70, 0x47, 0x05, 0xf0, 0x0e, 0xbd, 0x08, 0xb5, 0x05, 0xf0, + 0xf1, 0xfc, 0xc0, 0xb2, 0x08, 0xbd, 0x08, 0x46, 0x11, 0x46, 0x05, 0xf0, + 0x55, 0xbd, 0x00, 0x00, 0x2d, 0xe9, 0xf8, 0x4f, 0x05, 0x46, 0x0f, 0x46, + 0x46, 0x68, 0x00, 0x21, 0x10, 0x46, 0x14, 0x46, 0xc9, 0x22, 0xf7, 0xf3, + 0x05, 0xf0, 0x28, 0x46, 0x39, 0x46, 0x3b, 0xf0, 0xaf, 0xd9, 0x70, 0xb9, + 0x96, 0xf8, 0x50, 0x37, 0x00, 0x2b, 0x01, 0xf0, 0x31, 0x80, 0x06, 0xf5, + 0xaa, 0x61, 0x30, 0x46, 0x0e, 0x31, 0x3a, 0xf0, 0xfd, 0xdb, 0x80, 0x46, + 0x18, 0xb9, 0xbd, 0xe8, 0xf8, 0x8f, 0xd5, 0xf8, 0x10, 0x80, 0xfd, 0xb2, + 0x07, 0xf4, 0x70, 0x47, 0xa7, 0xf5, 0x80, 0x5e, 0xde, 0xf1, 0x00, 0x07, + 0x98, 0xf8, 0x00, 0x00, 0x47, 0xeb, 0x0e, 0x07, 0x05, 0xf0, 0x16, 0xfc, + 0x0e, 0x37, 0x56, 0xf8, 0x27, 0x70, 0x06, 0x46, 0x98, 0xf8, 0x02, 0x00, + 0x05, 0xf0, 0x26, 0xfc, 0x96, 0xf8, 0x11, 0xc0, 0x03, 0x46, 0x1c, 0xf0, + 0x01, 0x0c, 0x97, 0xf8, 0x04, 0x11, 0x02, 0xd0, 0x4f, 0xfa, 0x81, 0xfc, + 0x04, 0xe0, 0x49, 0xb2, 0x18, 0x29, 0xc8, 0xbf, 0xa1, 0xf1, 0x18, 0x0c, + 0x97, 0x4a, 0x96, 0x42, 0x06, 0xd0, 0x97, 0x4a, 0x96, 0x42, 0x06, 0xd0, + 0x96, 0x4a, 0x96, 0x42, 0x05, 0xd1, 0x02, 0xe0, 0x52, 0x20, 0x58, 0x22, + 0x03, 0xe0, 0x58, 0x20, 0x00, 0xe0, 0x7f, 0x20, 0x02, 0x46, 0x39, 0x68, + 0x02, 0x29, 0x69, 0xd1, 0x01, 0x2d, 0x04, 0xd9, 0x0a, 0x2d, 0x8c, 0xbf, + 0x02, 0x21, 0x01, 0x21, 0x00, 0xe0, 0x00, 0x21, 0xdf, 0xf8, 0x40, 0x82, + 0x71, 0x18, 0x46, 0x45, 0x91, 0xf9, 0x06, 0x10, 0x02, 0xd1, 0x0b, 0x2d, + 0x12, 0xd1, 0x47, 0xe0, 0xdf, 0xf8, 0x30, 0x82, 0x46, 0x45, 0x03, 0xd1, + 0x0e, 0x2d, 0x08, 0xbf, 0x36, 0x21, 0x44, 0xe0, 0xdf, 0xf8, 0x24, 0x82, + 0x46, 0x45, 0x03, 0xd0, 0xdf, 0xf8, 0x20, 0x82, 0x46, 0x45, 0x05, 0xd1, + 0x0b, 0x2d, 0x37, 0xd0, 0x0e, 0x2d, 0x08, 0xbf, 0x40, 0x21, 0x36, 0xe0, + 0xdf, 0xf8, 0x10, 0x82, 0x46, 0x45, 0x03, 0xd1, 0x0e, 0x2d, 0x08, 0xbf, + 0x2a, 0x21, 0x2e, 0xe0, 0xdf, 0xf8, 0x04, 0x82, 0x46, 0x45, 0x05, 0xd1, + 0x02, 0x2d, 0x27, 0xd0, 0x0a, 0x2d, 0x08, 0xbf, 0x54, 0x21, 0x24, 0xe0, + 0xdf, 0xf8, 0xf4, 0x81, 0x46, 0x45, 0x03, 0xd1, 0x0a, 0x2d, 0x08, 0xbf, + 0x50, 0x21, 0x1c, 0xe0, 0xdf, 0xf8, 0xe8, 0x81, 0x46, 0x45, 0x03, 0xd1, + 0x0e, 0x2d, 0x08, 0xbf, 0x28, 0x21, 0x14, 0xe0, 0xdf, 0xf8, 0xdc, 0x81, + 0x46, 0x45, 0x03, 0xd1, 0x0b, 0x2d, 0x08, 0xbf, 0x3e, 0x21, 0x0c, 0xe0, + 0xdf, 0xf8, 0xd0, 0x81, 0x46, 0x45, 0x08, 0xd1, 0x0c, 0x2d, 0x08, 0xbf, + 0x44, 0x21, 0x04, 0xe0, 0x4c, 0x21, 0x02, 0xe0, 0x40, 0x21, 0x00, 0xe0, + 0x58, 0x21, 0xcc, 0xeb, 0x01, 0x01, 0x21, 0xea, 0xe1, 0x71, 0x91, 0x42, + 0xa8, 0xbf, 0x11, 0x46, 0x21, 0x70, 0x61, 0x70, 0xa1, 0x70, 0xe1, 0x70, + 0x5b, 0x4a, 0x96, 0x42, 0x08, 0xd0, 0x5b, 0x4a, 0x96, 0x42, 0x05, 0xd0, + 0x5a, 0x4a, 0x96, 0x42, 0x02, 0xd0, 0x5a, 0x4a, 0x96, 0x42, 0x08, 0xd1, + 0x97, 0xf9, 0x04, 0xc1, 0xbc, 0xf1, 0x18, 0x0f, 0xcc, 0xbf, 0xac, 0xf1, + 0x18, 0x0c, 0x4f, 0xf0, 0x00, 0x0c, 0x39, 0x68, 0x02, 0x29, 0x40, 0xf0, + 0x44, 0x81, 0x01, 0x2d, 0x04, 0xd9, 0x0a, 0x2d, 0x8c, 0xbf, 0x05, 0x22, + 0x04, 0x22, 0x00, 0xe0, 0x03, 0x22, 0xdf, 0xf8, 0x3c, 0x81, 0xb2, 0x18, + 0x46, 0x45, 0x92, 0xf9, 0x06, 0x20, 0x03, 0xd1, 0x0b, 0x2d, 0x08, 0xbf, + 0x42, 0x22, 0x4f, 0xe1, 0xdf, 0xf8, 0x4c, 0x81, 0x46, 0x45, 0x06, 0xd1, + 0x02, 0x2d, 0x00, 0xf0, 0x3e, 0x81, 0x0a, 0x2d, 0x08, 0xbf, 0x4a, 0x22, + 0x44, 0xe1, 0xdf, 0xf8, 0x14, 0x81, 0x46, 0x45, 0x03, 0xd1, 0x0b, 0x2d, + 0x08, 0xbf, 0x46, 0x22, 0x3c, 0xe1, 0xdf, 0xf8, 0x08, 0x81, 0x46, 0x45, + 0x03, 0xd0, 0xdf, 0xf8, 0x04, 0x81, 0x46, 0x45, 0x03, 0xd1, 0x0b, 0x2d, + 0x08, 0xbf, 0x40, 0x22, 0x30, 0xe1, 0xdf, 0xf8, 0x14, 0x81, 0x46, 0x45, + 0x03, 0xd0, 0xdf, 0xf8, 0x10, 0x81, 0x46, 0x45, 0x03, 0xd1, 0x0d, 0x2d, + 0x08, 0xbf, 0x2e, 0x22, 0x24, 0xe1, 0xdf, 0xf8, 0x04, 0x81, 0x46, 0x45, + 0x06, 0xd1, 0x0b, 0x2d, 0x00, 0xf0, 0xc8, 0x80, 0x0d, 0x2d, 0x08, 0xbf, + 0x40, 0x22, 0x19, 0xe1, 0xdf, 0xf8, 0xb0, 0x80, 0x46, 0x45, 0x00, 0xf0, + 0x97, 0x80, 0xdf, 0xf8, 0xc0, 0x80, 0x46, 0x45, 0x03, 0xd1, 0x0b, 0x2d, + 0x08, 0xbf, 0x3e, 0x22, 0x0c, 0xe1, 0xdf, 0xf8, 0xb4, 0x80, 0x46, 0x45, + 0x1d, 0xd0, 0xdf, 0xf8, 0xb0, 0x80, 0x46, 0x45, 0x06, 0xd1, 0x02, 0x2d, + 0x00, 0xf0, 0xf9, 0x80, 0x0a, 0x2d, 0x08, 0xbf, 0x4c, 0x22, 0xfd, 0xe0, + 0xdf, 0xf8, 0xb8, 0x80, 0x46, 0x45, 0x06, 0xd1, 0x02, 0x2d, 0x00, 0xf0, + 0xf0, 0x80, 0x0a, 0x2d, 0x08, 0xbf, 0x48, 0x22, 0xf2, 0xe0, 0xdf, 0xf8, + 0xa8, 0x80, 0x46, 0x45, 0x03, 0xd0, 0xdf, 0xf8, 0xa4, 0x80, 0x46, 0x45, + 0x06, 0xd1, 0x02, 0x2d, 0x00, 0xf0, 0xe3, 0x80, 0x0a, 0x2d, 0x08, 0xbf, + 0x50, 0x22, 0xe3, 0xe0, 0xdf, 0xf8, 0x90, 0x80, 0x46, 0x45, 0x0c, 0xd1, + 0x02, 0x2d, 0x00, 0xf0, 0xdc, 0x80, 0x0a, 0x2d, 0x00, 0xf0, 0xd9, 0x80, + 0x03, 0x2d, 0x00, 0xf0, 0xd4, 0x80, 0x09, 0x2d, 0x08, 0xbf, 0x46, 0x22, + 0xd2, 0xe0, 0xdf, 0xf8, 0x74, 0x80, 0x46, 0x45, 0x38, 0xd1, 0x0a, 0x2d, + 0x08, 0xbf, 0x42, 0x22, 0xca, 0xe0, 0x00, 0xbf, 0xbc, 0x10, 0x86, 0x00, + 0xf0, 0x10, 0x86, 0x00, 0x24, 0x11, 0x86, 0x00, 0x34, 0x0d, 0x86, 0x00, + 0x5c, 0x0d, 0x86, 0x00, 0x80, 0x11, 0x86, 0x00, 0xfc, 0x0d, 0x86, 0x00, + 0x40, 0x09, 0x86, 0x00, 0x60, 0xbf, 0x01, 0x00, 0xbc, 0x0c, 0x86, 0x00, + 0xd0, 0x0c, 0x86, 0x00, 0x70, 0x0d, 0x86, 0x00, 0x7c, 0x09, 0x86, 0x00, + 0x90, 0x09, 0x86, 0x00, 0x84, 0x0d, 0x86, 0x00, 0xfc, 0xbf, 0x01, 0x00, + 0xd4, 0xc1, 0x01, 0x00, 0xc0, 0xc1, 0x01, 0x00, 0xe4, 0x0c, 0x86, 0x00, + 0x0c, 0x0d, 0x86, 0x00, 0x20, 0xc7, 0x01, 0x00, 0xcc, 0x09, 0x86, 0x00, + 0xa4, 0x09, 0x86, 0x00, 0xb8, 0x09, 0x86, 0x00, 0xf4, 0x09, 0x86, 0x00, + 0x18, 0x09, 0x86, 0x00, 0xdf, 0xf8, 0xb8, 0x84, 0x46, 0x45, 0x05, 0xd1, + 0xa5, 0xf1, 0x0c, 0x06, 0x01, 0x2e, 0x98, 0xbf, 0x3c, 0x22, 0x8b, 0xe0, + 0xdf, 0xf8, 0xa8, 0x84, 0x46, 0x45, 0x03, 0xd1, 0x0b, 0x2d, 0x88, 0xbf, + 0x40, 0x22, 0x83, 0xe0, 0xdf, 0xf8, 0x9c, 0x84, 0x46, 0x45, 0x05, 0xd1, + 0x0c, 0x2d, 0x7c, 0xd0, 0x0d, 0x2d, 0x08, 0xbf, 0x38, 0x22, 0x79, 0xe0, + 0xdf, 0xf8, 0x8c, 0x84, 0x46, 0x45, 0x05, 0xd1, 0x02, 0x2d, 0x72, 0xd0, + 0x0a, 0x2d, 0x08, 0xbf, 0x3c, 0x22, 0x6f, 0xe0, 0xdf, 0xf8, 0x7c, 0x84, + 0x46, 0x45, 0x03, 0xd1, 0x0b, 0x2d, 0x08, 0xbf, 0x38, 0x22, 0x67, 0xe0, + 0xdf, 0xf8, 0x70, 0x84, 0x46, 0x45, 0x03, 0xd1, 0x0b, 0x2d, 0x08, 0xbf, + 0x32, 0x22, 0x5f, 0xe0, 0xdf, 0xf8, 0x64, 0x84, 0x46, 0x45, 0x07, 0xd1, + 0x0b, 0x2d, 0x03, 0xd0, 0x0c, 0x2d, 0x08, 0xbf, 0x4a, 0x22, 0x55, 0xe0, + 0x38, 0x22, 0x53, 0xe0, 0xdf, 0xf8, 0x50, 0x84, 0x46, 0x45, 0x05, 0xd1, + 0x0c, 0x2d, 0x4a, 0xd0, 0x0d, 0x2d, 0x08, 0xbf, 0x3a, 0x22, 0x49, 0xe0, + 0xdf, 0xf8, 0x40, 0x84, 0x46, 0x45, 0x05, 0xd1, 0xa5, 0xf1, 0x0b, 0x06, + 0x01, 0x2e, 0x98, 0xbf, 0x4a, 0x22, 0x3f, 0xe0, 0xdf, 0xf8, 0x30, 0x84, + 0x46, 0x45, 0x03, 0xd1, 0x0b, 0x2d, 0x08, 0xbf, 0x3c, 0x22, 0x37, 0xe0, + 0xdf, 0xf8, 0x24, 0x84, 0x46, 0x45, 0x05, 0xd1, 0x0c, 0x2d, 0x28, 0xd0, + 0x0d, 0x2d, 0x08, 0xbf, 0x44, 0x22, 0x2d, 0xe0, 0xdf, 0xf8, 0x14, 0x84, + 0x46, 0x45, 0x29, 0xd1, 0x6e, 0x1e, 0x0d, 0x2e, 0x26, 0xd8, 0xdf, 0xf8, + 0x0c, 0x84, 0x18, 0xf8, 0x06, 0x60, 0x00, 0x2e, 0x18, 0xbf, 0x32, 0x46, + 0x1e, 0xe0, 0x33, 0x2d, 0x08, 0xd9, 0x3d, 0x2d, 0x08, 0xd9, 0x63, 0x2d, + 0x08, 0xd9, 0x94, 0x2d, 0x8c, 0xbf, 0x04, 0x22, 0x03, 0x22, 0x04, 0xe0, + 0x00, 0x22, 0x02, 0xe0, 0x01, 0x22, 0x00, 0xe0, 0x02, 0x22, 0xb6, 0x18, + 0x96, 0xf9, 0x06, 0x20, 0x0a, 0xe0, 0x4a, 0x22, 0x08, 0xe0, 0x4c, 0x22, + 0x06, 0xe0, 0x48, 0x22, 0x04, 0xe0, 0x50, 0x22, 0x02, 0xe0, 0x46, 0x22, + 0x00, 0xe0, 0x40, 0x22, 0xcc, 0xeb, 0x02, 0x02, 0x22, 0xea, 0xe2, 0x72, + 0x82, 0x42, 0xa8, 0xbf, 0x02, 0x46, 0x02, 0x29, 0x03, 0xd1, 0x21, 0x78, + 0x8a, 0x42, 0xa8, 0xbf, 0x0a, 0x46, 0x22, 0x71, 0x62, 0x71, 0xa2, 0x71, + 0xe2, 0x71, 0x22, 0x72, 0x62, 0x72, 0xa2, 0x72, 0xe2, 0x72, 0xa4, 0x46, + 0x21, 0x46, 0x00, 0x20, 0x00, 0x26, 0x01, 0x30, 0x81, 0xf8, 0x34, 0x60, + 0x0a, 0x73, 0x81, 0xf8, 0x3c, 0x60, 0x01, 0x31, 0x08, 0x28, 0xf5, 0xd1, + 0x18, 0x7f, 0x97, 0xf8, 0x04, 0x21, 0x10, 0xf0, 0x01, 0x00, 0x01, 0xd0, + 0x50, 0xb2, 0x04, 0xe0, 0x52, 0xb2, 0x18, 0x2a, 0xc8, 0xbf, 0xa2, 0xf1, + 0x18, 0x00, 0x3a, 0x68, 0x02, 0x2a, 0x01, 0xd1, 0x6e, 0x1e, 0x0f, 0xe0, + 0x33, 0x2d, 0x08, 0xd9, 0x3d, 0x2d, 0x08, 0xd9, 0x63, 0x2d, 0x08, 0xd9, + 0x94, 0x2d, 0x8c, 0xbf, 0x04, 0x26, 0x03, 0x26, 0x04, 0xe0, 0x00, 0x26, + 0x02, 0xe0, 0x01, 0x26, 0x00, 0xe0, 0x02, 0x26, 0x9a, 0x57, 0x9e, 0x19, + 0x96, 0xf9, 0x0e, 0x10, 0x96, 0x4e, 0xb3, 0x42, 0x05, 0xd1, 0xa5, 0xf1, + 0x64, 0x06, 0x02, 0x2e, 0x98, 0xbf, 0x3e, 0x21, 0x06, 0xe0, 0x93, 0x4e, + 0xb3, 0x42, 0x03, 0xd1, 0x64, 0x2d, 0x08, 0xbf, 0x38, 0x22, 0x08, 0xe0, + 0x90, 0x4e, 0xb3, 0x42, 0x05, 0xd1, 0xa5, 0xf1, 0x64, 0x06, 0x02, 0x2e, + 0x98, 0xbf, 0x3e, 0x21, 0x02, 0xe0, 0x8d, 0x4e, 0xb3, 0x42, 0x0e, 0xd0, + 0x8c, 0x4e, 0xb3, 0x42, 0x0b, 0xd0, 0x8c, 0x4e, 0xb3, 0x42, 0x08, 0xd0, + 0x8b, 0x4e, 0xb3, 0x42, 0x05, 0xd0, 0x8b, 0x4e, 0xb3, 0x42, 0x02, 0xd0, + 0x8a, 0x4e, 0xb3, 0x42, 0x17, 0xd1, 0xa5, 0xf1, 0x68, 0x06, 0x24, 0x2e, + 0x13, 0xd8, 0x84, 0x4a, 0x93, 0x42, 0x0e, 0xd0, 0x83, 0x4a, 0x93, 0x42, + 0x0b, 0xd0, 0x84, 0x4a, 0x93, 0x42, 0x08, 0xd0, 0x7e, 0x4a, 0x93, 0x42, + 0x11, 0xd0, 0x80, 0x4a, 0x93, 0x42, 0x0e, 0xd0, 0x4a, 0x21, 0x44, 0x22, + 0x01, 0xe0, 0x4a, 0x21, 0x42, 0x22, 0x7e, 0x4e, 0xb3, 0x42, 0x0b, 0xd1, + 0xa5, 0xf1, 0x68, 0x06, 0x20, 0x2e, 0x05, 0xd9, 0x8c, 0x2d, 0x20, 0xd1, + 0x0f, 0xe0, 0x44, 0x21, 0x0a, 0x46, 0x01, 0xe0, 0x40, 0x21, 0x44, 0x22, + 0x77, 0x4e, 0xb3, 0x42, 0x0c, 0xd1, 0x64, 0x2d, 0x08, 0xd0, 0xa5, 0xf1, + 0x68, 0x06, 0x0c, 0x2e, 0x40, 0xf2, 0x58, 0x85, 0x2e, 0xe0, 0x36, 0x21, + 0x0a, 0x46, 0x01, 0xe0, 0x34, 0x21, 0x40, 0x22, 0x70, 0x4e, 0xb3, 0x42, + 0x07, 0xd1, 0xa5, 0xf1, 0x64, 0x06, 0x10, 0x2e, 0x98, 0xbf, 0x42, 0x21, + 0x98, 0xbf, 0x52, 0x22, 0x1e, 0xe0, 0x6c, 0x4e, 0xb3, 0x42, 0x1b, 0xd1, + 0xa5, 0xf1, 0x64, 0x06, 0x08, 0x2e, 0x98, 0xbf, 0x30, 0x21, 0xa5, 0xf1, + 0x6e, 0x06, 0x98, 0xbf, 0x34, 0x22, 0x16, 0x2e, 0x98, 0xbf, 0x46, 0x21, + 0xa5, 0xf1, 0x86, 0x06, 0x02, 0x2e, 0x05, 0xd9, 0x8c, 0x2d, 0x08, 0xbf, + 0x48, 0x21, 0x08, 0xbf, 0x36, 0x22, 0x00, 0xe0, 0x3e, 0x21, 0xa5, 0xf1, + 0x95, 0x06, 0x0f, 0x2e, 0x98, 0xbf, 0x44, 0x22, 0x5d, 0x4e, 0xb3, 0x42, + 0xb3, 0x46, 0x12, 0xd1, 0xa5, 0xf1, 0x6e, 0x06, 0x16, 0x2e, 0xa5, 0xf1, + 0x86, 0x06, 0x98, 0xbf, 0x44, 0x21, 0x98, 0xbf, 0x3a, 0x22, 0x02, 0x2e, + 0x05, 0xd9, 0x8c, 0x2d, 0x08, 0xbf, 0x48, 0x21, 0x08, 0xbf, 0x36, 0x22, + 0x01, 0xe0, 0x3e, 0x21, 0x3a, 0x22, 0x53, 0x4e, 0xb3, 0x42, 0x02, 0xd0, + 0x52, 0x4e, 0xb3, 0x42, 0x04, 0xd1, 0xa5, 0xf1, 0x84, 0x06, 0x08, 0x2e, + 0x98, 0xbf, 0x2c, 0x22, 0x4f, 0x4e, 0xb3, 0x42, 0x02, 0xd1, 0x26, 0x2d, + 0x08, 0xbf, 0x2c, 0x21, 0x12, 0x1a, 0x08, 0x1a, 0x22, 0xea, 0xe2, 0x72, + 0x20, 0xea, 0xe0, 0x70, 0x21, 0x46, 0x00, 0x27, 0x0e, 0x79, 0x01, 0x37, + 0x01, 0x31, 0xce, 0x74, 0x00, 0x26, 0x08, 0x2f, 0x81, 0xf8, 0x43, 0x60, + 0xf6, 0xd1, 0x21, 0x46, 0x01, 0x36, 0x0a, 0x77, 0x81, 0xf8, 0x4c, 0x00, + 0x01, 0x31, 0x08, 0x2e, 0xf8, 0xd1, 0x41, 0x4f, 0xbb, 0x42, 0x00, 0xf0, + 0xf4, 0x80, 0x40, 0x49, 0x8b, 0x42, 0x00, 0xf0, 0xf0, 0x80, 0x3f, 0x49, + 0x8b, 0x42, 0x00, 0xf0, 0xec, 0x80, 0x3e, 0x49, 0x8b, 0x42, 0x00, 0xf0, + 0xe8, 0x80, 0x3d, 0x49, 0x8b, 0x42, 0x00, 0xf0, 0xe4, 0x80, 0x3c, 0x49, + 0x8b, 0x42, 0x00, 0xf0, 0xb5, 0x80, 0x3b, 0x49, 0x8b, 0x42, 0x00, 0xf0, + 0xdc, 0x80, 0x3a, 0x49, 0x8b, 0x42, 0x00, 0xf0, 0xd8, 0x80, 0x39, 0x49, + 0x8b, 0x42, 0x00, 0xf0, 0xd4, 0x80, 0x38, 0x49, 0x8b, 0x42, 0x00, 0xf0, + 0xd0, 0x80, 0x37, 0x49, 0x8b, 0x42, 0x00, 0xf0, 0xcc, 0x80, 0x36, 0x49, + 0x8b, 0x42, 0x00, 0xf0, 0xc8, 0x80, 0x35, 0x49, 0x8b, 0x42, 0x00, 0xf0, + 0xc4, 0x80, 0x34, 0x49, 0x8b, 0x42, 0x00, 0xf0, 0xc0, 0x80, 0x33, 0x49, + 0x8b, 0x42, 0x00, 0xf0, 0xbc, 0x80, 0x32, 0x49, 0x8b, 0x42, 0x00, 0xf0, + 0xb8, 0x80, 0x31, 0x49, 0x8b, 0x42, 0x00, 0xf0, 0xb4, 0x80, 0x30, 0x49, + 0x8b, 0x42, 0x00, 0xf0, 0xb0, 0x80, 0x2f, 0x49, 0x8b, 0x42, 0x00, 0xf0, + 0xac, 0x80, 0x2e, 0x49, 0x8b, 0x42, 0x00, 0xf0, 0xa8, 0x80, 0x2d, 0x49, + 0x8b, 0x42, 0x00, 0xf0, 0xa4, 0x80, 0x2c, 0x49, 0x8b, 0x42, 0x00, 0xf0, + 0xa0, 0x80, 0x2b, 0x49, 0x8b, 0x42, 0x00, 0xf0, 0x9c, 0x80, 0x2a, 0x49, + 0x8b, 0x42, 0x40, 0xf0, 0xd1, 0x80, 0x96, 0xe0, 0xb5, 0x08, 0x86, 0x00, + 0x7f, 0xc6, 0x01, 0x00, 0xd2, 0x08, 0x86, 0x00, 0xdc, 0x05, 0x86, 0x00, + 0x2e, 0x05, 0x86, 0x00, 0x4b, 0x05, 0x86, 0x00, 0x68, 0x05, 0x86, 0x00, + 0x85, 0x05, 0x86, 0x00, 0x33, 0x06, 0x86, 0x00, 0xf9, 0x05, 0x86, 0x00, + 0x6d, 0x06, 0x86, 0x00, 0x8a, 0x06, 0x86, 0x00, 0xa2, 0x05, 0x86, 0x00, + 0xbf, 0x05, 0x86, 0x00, 0x2c, 0x07, 0x86, 0x00, 0xf4, 0x04, 0x86, 0x00, + 0x50, 0xc5, 0x01, 0x00, 0x7e, 0x0a, 0x86, 0x00, 0x9b, 0x0a, 0x86, 0x00, + 0xb8, 0x0a, 0x86, 0x00, 0xf2, 0x0a, 0x86, 0x00, 0xbd, 0x0b, 0x86, 0x00, + 0x98, 0x0e, 0x86, 0x00, 0x74, 0xbf, 0x01, 0x00, 0xab, 0xc3, 0x01, 0x00, + 0xcb, 0xbf, 0x01, 0x00, 0xa0, 0xc1, 0x01, 0x00, 0x41, 0xc2, 0x01, 0x00, + 0x24, 0xc2, 0x01, 0x00, 0x63, 0x0f, 0x86, 0x00, 0x14, 0x10, 0x86, 0x00, + 0xb5, 0x0e, 0x86, 0x00, 0x61, 0xc0, 0x01, 0x00, 0x7e, 0xc0, 0x01, 0x00, + 0x2c, 0xc1, 0x01, 0x00, 0x49, 0xc1, 0x01, 0x00, 0xf2, 0xc0, 0x01, 0x00, + 0x0f, 0xc1, 0x01, 0x00, 0x66, 0xc1, 0x01, 0x00, 0x83, 0xc1, 0x01, 0x00, + 0x88, 0x0c, 0x86, 0x00, 0x84, 0x0d, 0x86, 0x00, 0x98, 0x0d, 0x86, 0x00, + 0x38, 0x11, 0x86, 0x00, 0x68, 0x09, 0x86, 0x00, 0xfc, 0xbf, 0x01, 0x00, + 0xe8, 0xbf, 0x01, 0x00, 0x30, 0xc0, 0x01, 0x00, 0xd4, 0xc1, 0x01, 0x00, + 0x38, 0xc4, 0x01, 0x00, 0xe8, 0xc1, 0x01, 0x00, 0xfc, 0xc1, 0x01, 0x00, + 0x34, 0xc7, 0x01, 0x00, 0x08, 0x0c, 0x02, 0x00, 0x03, 0x2d, 0x0d, 0xd0, + 0x2a, 0x1f, 0x04, 0x2a, 0x0c, 0xd9, 0x09, 0x2d, 0x00, 0xf0, 0x16, 0x84, + 0xa5, 0xf1, 0x0c, 0x02, 0x01, 0x2a, 0x94, 0xbf, 0x2c, 0x22, 0x40, 0x22, + 0x00, 0x20, 0x1d, 0xe0, 0x3c, 0x20, 0x00, 0xe0, 0x40, 0x20, 0x97, 0x4a, + 0x93, 0x42, 0x40, 0xf0, 0x08, 0x84, 0x03, 0x2d, 0x0d, 0xd0, 0x2a, 0x1f, + 0x04, 0x2a, 0x0c, 0xd9, 0x09, 0x2d, 0x00, 0xf0, 0x02, 0x84, 0xa5, 0xf1, + 0x0c, 0x02, 0x01, 0x2a, 0x94, 0xbf, 0x2c, 0x22, 0x40, 0x22, 0x00, 0x20, + 0x11, 0xe0, 0x36, 0x20, 0xf5, 0xe3, 0x40, 0x20, 0x02, 0x46, 0x8c, 0x49, + 0x8b, 0x42, 0x02, 0xd0, 0x8b, 0x49, 0x8b, 0x42, 0x07, 0xd1, 0xea, 0x1e, + 0x08, 0x2a, 0x02, 0xd9, 0x00, 0x20, 0x40, 0x22, 0x01, 0xe0, 0x40, 0x20, + 0x02, 0x46, 0x87, 0x49, 0x8b, 0x42, 0x1e, 0xd1, 0xa5, 0xf1, 0x24, 0x01, + 0x0c, 0x29, 0x0f, 0xd9, 0xa5, 0xf1, 0x34, 0x01, 0x08, 0x29, 0x0e, 0xd9, + 0xa5, 0xf1, 0x64, 0x01, 0x02, 0x29, 0x0d, 0xd9, 0xa5, 0xf1, 0x68, 0x01, + 0x20, 0x29, 0x0c, 0xd9, 0x8c, 0x2d, 0x08, 0xbf, 0x32, 0x22, 0x0a, 0xe0, + 0x30, 0x20, 0x38, 0x22, 0x07, 0xe0, 0x44, 0x20, 0x02, 0x46, 0x04, 0xe0, + 0x3e, 0x20, 0x34, 0x22, 0x01, 0xe0, 0x4a, 0x20, 0x44, 0x22, 0x21, 0x46, + 0x00, 0x26, 0x01, 0x36, 0x0a, 0x75, 0x81, 0xf8, 0x44, 0x00, 0x01, 0x31, + 0x08, 0x2e, 0xf8, 0xd1, 0x21, 0x46, 0x4f, 0xf0, 0x00, 0x08, 0x00, 0x26, + 0x08, 0xf1, 0x01, 0x08, 0x81, 0xf8, 0x24, 0x60, 0x81, 0xf8, 0x54, 0x60, + 0x01, 0x31, 0xb8, 0xf1, 0x08, 0x0f, 0xf4, 0xd1, 0x21, 0x46, 0x01, 0x36, + 0x81, 0xf8, 0x2c, 0x20, 0x81, 0xf8, 0x5c, 0x00, 0x01, 0x31, 0x08, 0x2e, + 0xf7, 0xd1, 0xbb, 0x42, 0x84, 0xf8, 0x64, 0x00, 0x07, 0xd0, 0x65, 0x49, + 0x8b, 0x42, 0x17, 0xd0, 0x64, 0x49, 0x8b, 0x42, 0x40, 0xf0, 0xaa, 0x80, + 0x25, 0xe0, 0x01, 0x2d, 0x50, 0xd0, 0x02, 0x2d, 0x49, 0xd0, 0x03, 0x2d, + 0x55, 0xd0, 0x29, 0x1f, 0x04, 0x29, 0x3c, 0xd9, 0x09, 0x2d, 0x3e, 0xd0, + 0x0a, 0x2d, 0x40, 0xd0, 0x00, 0x21, 0x0b, 0x2d, 0x0e, 0x46, 0x0f, 0x46, + 0x73, 0xd1, 0x42, 0xe0, 0x01, 0x2d, 0x3d, 0xd0, 0x02, 0x2d, 0x4e, 0xd0, + 0x03, 0x2d, 0x3e, 0xd0, 0x29, 0x1f, 0x04, 0x29, 0x3f, 0xd9, 0x09, 0x2d, + 0x42, 0xd0, 0x0a, 0x2d, 0x45, 0xd0, 0x00, 0x21, 0x0b, 0x2d, 0x0e, 0x46, + 0x0f, 0x46, 0x60, 0xd1, 0x44, 0xe0, 0x01, 0x2d, 0x44, 0xd0, 0x02, 0x2d, + 0x55, 0xd0, 0xe9, 0x1e, 0x05, 0x29, 0x0e, 0xd8, 0x03, 0x2d, 0x42, 0xd0, + 0x04, 0x2d, 0x44, 0xd0, 0x08, 0x2d, 0x0c, 0xbf, 0x38, 0x21, 0x3a, 0x21, + 0x0c, 0xbf, 0x36, 0x26, 0x38, 0x26, 0x0c, 0xbf, 0x32, 0x27, 0x34, 0x27, + 0x3c, 0xe0, 0x09, 0x2d, 0x3c, 0xd0, 0x0a, 0x2d, 0x3f, 0xd0, 0x00, 0x21, + 0x0b, 0x2d, 0x0e, 0x46, 0x0f, 0x46, 0x40, 0xd1, 0x3e, 0xe0, 0x3e, 0x21, + 0x3c, 0x26, 0x38, 0x27, 0x14, 0xe0, 0x36, 0x21, 0x34, 0x26, 0x30, 0x27, + 0x10, 0xe0, 0x00, 0x21, 0x0e, 0x46, 0x0f, 0x46, 0x40, 0x22, 0x32, 0xe0, + 0x00, 0x21, 0x0e, 0x46, 0x0f, 0x46, 0x38, 0x22, 0x2d, 0xe0, 0x38, 0x21, + 0x36, 0x26, 0x32, 0x27, 0x02, 0xe0, 0x3a, 0x21, 0x38, 0x26, 0x34, 0x27, + 0x4c, 0x22, 0x24, 0xe0, 0x36, 0x21, 0x34, 0x26, 0x30, 0x27, 0x4a, 0x22, + 0x1f, 0xe0, 0x00, 0x21, 0x0e, 0x46, 0x0f, 0x46, 0x3e, 0x22, 0x1a, 0xe0, + 0x36, 0x22, 0x18, 0xe0, 0x00, 0x21, 0x0e, 0x46, 0x0f, 0x46, 0x2c, 0x22, + 0x13, 0xe0, 0x2e, 0x21, 0x2c, 0x26, 0x28, 0x27, 0x02, 0xe0, 0x38, 0x21, + 0x36, 0x26, 0x32, 0x27, 0x44, 0x22, 0x0a, 0xe0, 0x30, 0x21, 0x2e, 0x26, + 0x2a, 0x27, 0x42, 0x22, 0x05, 0xe0, 0x00, 0x21, 0x0e, 0x46, 0x0f, 0x46, + 0x3c, 0x22, 0x00, 0xe0, 0x2a, 0x22, 0xa1, 0x46, 0x4f, 0xf0, 0x00, 0x08, + 0xb8, 0xf1, 0x04, 0x0f, 0x8c, 0xbf, 0xb2, 0x46, 0xba, 0x46, 0x08, 0xf1, + 0x01, 0x08, 0xb8, 0xf1, 0x08, 0x0f, 0x89, 0xf8, 0x1c, 0x20, 0x89, 0xf8, + 0x4c, 0xa0, 0x09, 0xf1, 0x01, 0x09, 0xef, 0xd1, 0x92, 0x46, 0xa0, 0x46, + 0x00, 0x27, 0x03, 0x2f, 0x8c, 0xbf, 0x89, 0x46, 0xb1, 0x46, 0x01, 0x37, + 0x08, 0x2f, 0x88, 0xf8, 0x2c, 0xa0, 0x88, 0xf8, 0x5c, 0x90, 0x08, 0xf1, + 0x01, 0x08, 0xf2, 0xd1, 0x0e, 0x49, 0x8b, 0x42, 0x06, 0xd0, 0x0e, 0x49, + 0x8b, 0x42, 0x1d, 0xd0, 0x0d, 0x49, 0x8b, 0x42, 0x7a, 0xd1, 0x25, 0xe0, + 0x03, 0x2d, 0x32, 0xd0, 0x09, 0x2d, 0x30, 0xd0, 0x29, 0x1f, 0x04, 0x29, + 0x31, 0xd9, 0x28, 0xe0, 0xef, 0x0e, 0x86, 0x00, 0x63, 0x0f, 0x86, 0x00, + 0x14, 0x10, 0x86, 0x00, 0xdc, 0x05, 0x86, 0x00, 0x9b, 0x0a, 0x86, 0x00, + 0xf2, 0x0a, 0x86, 0x00, 0xd5, 0x0a, 0x86, 0x00, 0xa0, 0x0b, 0x86, 0x00, + 0xda, 0x0b, 0x86, 0x00, 0x03, 0x2d, 0x1e, 0xd0, 0x04, 0x2d, 0x24, 0xd0, + 0x69, 0x1f, 0x02, 0x29, 0x1d, 0xd9, 0x08, 0x2d, 0x1f, 0xd0, 0x09, 0x2d, + 0x0b, 0xd1, 0x20, 0xe0, 0x03, 0x2d, 0x22, 0xd0, 0x04, 0x2d, 0x23, 0xd0, + 0x69, 0x1f, 0x02, 0x29, 0x24, 0xd9, 0x08, 0x2d, 0x26, 0xd0, 0x09, 0x2d, + 0x27, 0xd0, 0x00, 0x21, 0x0e, 0x46, 0x0f, 0x46, 0x26, 0xe0, 0x2e, 0x21, + 0x2c, 0x26, 0x28, 0x27, 0x22, 0xe0, 0x36, 0x21, 0x1b, 0xe0, 0x48, 0x21, + 0x46, 0x26, 0x42, 0x27, 0x1c, 0xe0, 0x52, 0x21, 0x50, 0x26, 0x4c, 0x27, + 0x18, 0xe0, 0x4c, 0x21, 0x4a, 0x26, 0x46, 0x27, 0x14, 0xe0, 0x44, 0x21, + 0x42, 0x26, 0x3e, 0x27, 0x10, 0xe0, 0x32, 0x21, 0x30, 0x26, 0x0c, 0xe0, + 0x34, 0x21, 0x32, 0x26, 0x30, 0x27, 0x09, 0xe0, 0x3a, 0x21, 0x36, 0x26, + 0x32, 0x27, 0x05, 0xe0, 0x38, 0x21, 0x34, 0x26, 0xf6, 0xe7, 0x36, 0x21, + 0x32, 0x26, 0x2e, 0x27, 0xa1, 0x46, 0x4f, 0xf0, 0x00, 0x08, 0xb8, 0xf1, + 0x04, 0x0f, 0x8c, 0xbf, 0xb2, 0x46, 0xba, 0x46, 0x08, 0xf1, 0x01, 0x08, + 0xb8, 0xf1, 0x08, 0x0f, 0x89, 0xf8, 0x4c, 0xa0, 0x09, 0xf1, 0x01, 0x09, + 0xf1, 0xd1, 0xa0, 0x46, 0x00, 0x27, 0x03, 0x2f, 0x8c, 0xbf, 0x89, 0x46, + 0xb1, 0x46, 0x01, 0x37, 0x08, 0x2f, 0x88, 0xf8, 0x5c, 0x90, 0x08, 0xf1, + 0x01, 0x08, 0xf4, 0xd1, 0x91, 0x49, 0x8b, 0x42, 0x2e, 0xd1, 0x03, 0x2d, + 0x0d, 0xd0, 0x29, 0x1f, 0x04, 0x29, 0x05, 0xd9, 0x09, 0x2d, 0x08, 0xd0, + 0x00, 0x21, 0x0e, 0x46, 0x88, 0x46, 0x08, 0xe0, 0x3e, 0x21, 0x3c, 0x26, + 0x4f, 0xf0, 0x38, 0x08, 0x03, 0xe0, 0x3a, 0x21, 0x38, 0x26, 0x4f, 0xf0, + 0x34, 0x08, 0xa1, 0x46, 0x00, 0x27, 0x04, 0x2f, 0x8c, 0xbf, 0xb2, 0x46, + 0xc2, 0x46, 0x01, 0x37, 0x08, 0x2f, 0x89, 0xf8, 0x4c, 0xa0, 0x09, 0xf1, + 0x01, 0x09, 0xf4, 0xd1, 0xa0, 0x46, 0x00, 0x27, 0x03, 0x2f, 0x8c, 0xbf, + 0x89, 0x46, 0xb1, 0x46, 0x01, 0x37, 0x08, 0x2f, 0x88, 0xf8, 0x5c, 0x90, + 0x08, 0xf1, 0x01, 0x08, 0xf4, 0xd1, 0x2d, 0xe0, 0x79, 0x49, 0x8b, 0x42, + 0x27, 0xd1, 0xa5, 0xf1, 0x24, 0x02, 0x0c, 0x2a, 0x0e, 0xd9, 0xa5, 0xf1, + 0x34, 0x02, 0x0c, 0x2a, 0x0d, 0xd9, 0xa5, 0xf1, 0x64, 0x02, 0x28, 0x2a, + 0x0c, 0xd9, 0xa5, 0xf1, 0x95, 0x02, 0x10, 0x2a, 0x0b, 0xd9, 0x00, 0x20, + 0x02, 0x46, 0x0a, 0xe0, 0x34, 0x20, 0x38, 0x22, 0x07, 0xe0, 0x34, 0x20, + 0x3a, 0x22, 0x04, 0xe0, 0x40, 0x20, 0x3c, 0x22, 0x01, 0xe0, 0x48, 0x20, + 0x46, 0x22, 0x21, 0x46, 0x00, 0x26, 0x01, 0x36, 0x0a, 0x75, 0x81, 0xf8, + 0x44, 0x00, 0x01, 0x31, 0x08, 0x2e, 0xf8, 0xd1, 0x05, 0xe0, 0x65, 0x49, + 0x8b, 0x42, 0x52, 0xd0, 0x64, 0x49, 0x8b, 0x42, 0x75, 0xd0, 0x64, 0x49, + 0x8b, 0x42, 0x72, 0xd0, 0x63, 0x49, 0x8b, 0x42, 0x6f, 0xd0, 0x63, 0x49, + 0x8b, 0x42, 0x6c, 0xd0, 0x62, 0x49, 0x8b, 0x42, 0x69, 0xd0, 0x62, 0x49, + 0x8b, 0x42, 0x66, 0xd0, 0x61, 0x49, 0x8b, 0x42, 0x63, 0xd0, 0x61, 0x49, + 0x8b, 0x42, 0x60, 0xd0, 0x60, 0x49, 0x8b, 0x42, 0x5d, 0xd0, 0x60, 0x49, + 0x8b, 0x42, 0x5a, 0xd0, 0x5f, 0x49, 0x8b, 0x42, 0x57, 0xd0, 0x5f, 0x49, + 0x8b, 0x42, 0x54, 0xd0, 0x5e, 0x49, 0x8b, 0x42, 0x51, 0xd0, 0x5e, 0x49, + 0x8b, 0x42, 0x4e, 0xd0, 0x5d, 0x49, 0x8b, 0x42, 0x4b, 0xd0, 0x5d, 0x49, + 0x8b, 0x42, 0x48, 0xd0, 0x5c, 0x49, 0x8b, 0x42, 0x45, 0xd0, 0x5c, 0x49, + 0x8b, 0x42, 0x42, 0xd0, 0x5b, 0x49, 0x8b, 0x42, 0x3f, 0xd0, 0x5b, 0x49, + 0x8b, 0x42, 0x3c, 0xd0, 0x5a, 0x49, 0x8b, 0x42, 0x39, 0xd0, 0x5a, 0x49, + 0x8b, 0x42, 0x36, 0xd0, 0x59, 0x49, 0x8b, 0x42, 0x33, 0xd0, 0x59, 0x49, + 0x8b, 0x42, 0x30, 0xd0, 0x58, 0x49, 0x8b, 0x42, 0x2d, 0xd0, 0x58, 0x49, + 0x8b, 0x42, 0x2a, 0xd0, 0x57, 0x49, 0x8b, 0x42, 0x40, 0xf0, 0xb8, 0x80, + 0x1d, 0xe0, 0xa5, 0xf1, 0x24, 0x02, 0x08, 0x2a, 0x59, 0xd9, 0xa5, 0xf1, + 0x2e, 0x02, 0x02, 0x2a, 0x63, 0xd9, 0xa5, 0xf1, 0x34, 0x02, 0x08, 0x2a, + 0x54, 0xd9, 0xa5, 0xf1, 0x3e, 0x02, 0x02, 0x2a, 0x53, 0xd9, 0xa5, 0xf1, + 0x64, 0x02, 0x08, 0x2a, 0x52, 0xd9, 0xa5, 0xf1, 0x6e, 0x02, 0x1e, 0x2a, + 0x50, 0xd9, 0xa5, 0xf1, 0x95, 0x02, 0x10, 0x2a, 0x4f, 0xd9, 0x00, 0x20, + 0x40, 0xe0, 0xa5, 0xf1, 0x24, 0x01, 0x0c, 0x29, 0x98, 0xbf, 0x34, 0x20, + 0x98, 0xbf, 0x38, 0x22, 0x87, 0xe0, 0x3b, 0x49, 0x8b, 0x42, 0x03, 0xd1, + 0x64, 0x2d, 0x08, 0xbf, 0x38, 0x22, 0x80, 0xe0, 0x39, 0x49, 0x8b, 0x42, + 0x03, 0xd1, 0x24, 0x2d, 0x08, 0xbf, 0x38, 0x22, 0x79, 0xe0, 0x37, 0x49, + 0x8b, 0x42, 0x03, 0xd1, 0x8c, 0x2d, 0x08, 0xbf, 0x3a, 0x22, 0x72, 0xe0, + 0x35, 0x49, 0x8b, 0x42, 0x05, 0xd1, 0x64, 0x2d, 0x2e, 0xd0, 0x8c, 0x2d, + 0x08, 0xbf, 0x48, 0x22, 0x69, 0xe0, 0x22, 0x49, 0x8b, 0x42, 0x05, 0xd1, + 0xa5, 0xf1, 0x95, 0x01, 0x10, 0x29, 0x98, 0xbf, 0x3c, 0x22, 0x60, 0xe0, + 0x1f, 0x49, 0x8b, 0x42, 0x5d, 0xd1, 0xa5, 0xf1, 0x24, 0x01, 0x0c, 0x29, + 0x58, 0xd9, 0xa5, 0xf1, 0x34, 0x01, 0x0c, 0x29, 0x54, 0xd9, 0xa5, 0xf1, + 0x64, 0x01, 0x28, 0x29, 0x98, 0xbf, 0x3c, 0x22, 0x4f, 0xe0, 0x38, 0x20, + 0x02, 0x46, 0x4c, 0xe0, 0x40, 0x20, 0x38, 0x22, 0x49, 0xe0, 0x38, 0x20, + 0x34, 0x22, 0x46, 0xe0, 0x38, 0x20, 0x03, 0xe0, 0x40, 0x20, 0x32, 0x22, + 0x41, 0xe0, 0x40, 0x20, 0x44, 0x22, 0x3e, 0xe0, 0x48, 0x22, 0x3c, 0xe0, + 0x4e, 0x0c, 0x86, 0x00, 0x11, 0x05, 0x86, 0x00, 0xf9, 0x05, 0x86, 0x00, + 0x6d, 0xc5, 0x01, 0x00, 0x8a, 0xc5, 0x01, 0x00, 0xcd, 0xc6, 0x01, 0x00, + 0x45, 0xc6, 0x01, 0x00, 0x8e, 0xc3, 0x01, 0x00, 0x37, 0xc3, 0x01, 0x00, + 0xd5, 0xc0, 0x01, 0x00, 0x18, 0xc4, 0x01, 0x00, 0x10, 0xc0, 0x01, 0x00, + 0x1a, 0xc3, 0x01, 0x00, 0x91, 0xbf, 0x01, 0x00, 0xb0, 0xc6, 0x01, 0x00, + 0x71, 0xc3, 0x01, 0x00, 0xa7, 0xc5, 0x01, 0x00, 0x54, 0xc3, 0x01, 0x00, + 0x43, 0xbf, 0x01, 0x00, 0xe0, 0xc2, 0x01, 0x00, 0x7f, 0xc6, 0x01, 0x00, + 0xae, 0xbf, 0x01, 0x00, 0x00, 0xc7, 0x01, 0x00, 0x9b, 0xc0, 0x01, 0x00, + 0xb8, 0xc0, 0x01, 0x00, 0x62, 0xc6, 0x01, 0x00, 0xfd, 0xc2, 0x01, 0x00, + 0x5e, 0xc2, 0x01, 0x00, 0x7b, 0xc2, 0x01, 0x00, 0x16, 0x06, 0x86, 0x00, + 0x3c, 0x22, 0x21, 0x46, 0x00, 0x26, 0x01, 0x36, 0x0a, 0x75, 0x81, 0xf8, + 0x44, 0x00, 0x01, 0x31, 0x08, 0x2e, 0xf8, 0xd1, 0x83, 0x4a, 0x93, 0x42, + 0x0b, 0xd0, 0x83, 0x4a, 0x93, 0x42, 0x08, 0xd0, 0x82, 0x4a, 0x93, 0x42, + 0x05, 0xd0, 0x82, 0x4a, 0x93, 0x42, 0x02, 0xd0, 0x81, 0x4a, 0x93, 0x42, + 0x71, 0xd1, 0xa5, 0xf1, 0x24, 0x02, 0x08, 0x2a, 0x0a, 0xd8, 0x7e, 0x4a, + 0x93, 0x42, 0x03, 0xd0, 0x34, 0x22, 0x5b, 0x45, 0x01, 0xd1, 0x50, 0xe0, + 0x3a, 0x22, 0x4f, 0xf0, 0x38, 0x0b, 0x58, 0xe0, 0xa5, 0xf1, 0x2e, 0x02, + 0x02, 0x2a, 0x09, 0xd8, 0x5b, 0x45, 0x14, 0xbf, 0x42, 0x22, 0x40, 0x22, + 0x14, 0xbf, 0x4f, 0xf0, 0x38, 0x0b, 0x4f, 0xf0, 0x34, 0x0b, 0x4a, 0xe0, + 0xa5, 0xf1, 0x34, 0x02, 0x08, 0x2a, 0x3c, 0xd9, 0xa5, 0xf1, 0x3e, 0x02, + 0x02, 0x2a, 0x06, 0xd8, 0x5b, 0x45, 0x14, 0xbf, 0x34, 0x22, 0x2c, 0x22, + 0x4f, 0xf0, 0x3a, 0x0b, 0x3b, 0xe0, 0xa5, 0xf1, 0x64, 0x02, 0x08, 0x2a, + 0x07, 0xd8, 0x3e, 0x22, 0x5b, 0x45, 0x14, 0xbf, 0x4f, 0xf0, 0x44, 0x0b, + 0x4f, 0xf0, 0x3a, 0x0b, 0x2f, 0xe0, 0xa5, 0xf1, 0x6e, 0x02, 0x1e, 0x2a, + 0x1a, 0xd8, 0xa5, 0xf1, 0x86, 0x02, 0x02, 0x2a, 0x08, 0xd8, 0x60, 0x4a, + 0x93, 0x42, 0x00, 0xf0, 0xa5, 0x80, 0x5b, 0x45, 0x0c, 0xbf, 0x3c, 0x22, + 0x48, 0x22, 0xa0, 0xe0, 0x8c, 0x2d, 0x14, 0xd1, 0x5a, 0x4a, 0x93, 0x42, + 0x4f, 0xf0, 0x48, 0x02, 0x11, 0xd0, 0x5b, 0x45, 0x0c, 0xbf, 0x4f, 0xf0, + 0x3c, 0x0b, 0x4f, 0xf0, 0x44, 0x0b, 0x10, 0xe0, 0xa5, 0xf1, 0x95, 0x02, + 0x10, 0x2a, 0x09, 0xd9, 0x00, 0x22, 0x93, 0x46, 0x09, 0xe0, 0x44, 0x22, + 0x05, 0xe0, 0x48, 0x22, 0x87, 0xe0, 0x4f, 0xf0, 0x3c, 0x0b, 0x02, 0xe0, + 0x4a, 0x22, 0x4f, 0xf0, 0x46, 0x0b, 0x21, 0x46, 0x00, 0x20, 0x01, 0x30, + 0x81, 0xf8, 0x14, 0xb0, 0x81, 0xf8, 0x44, 0x20, 0x01, 0x31, 0x08, 0x28, + 0xf7, 0xd1, 0x48, 0x4a, 0x93, 0x42, 0x05, 0xd0, 0x47, 0x4a, 0x93, 0x42, + 0x02, 0xd0, 0x22, 0x46, 0x00, 0x23, 0x1e, 0xe0, 0xa5, 0xf1, 0x24, 0x03, + 0x0c, 0x2b, 0x0d, 0xd9, 0xa5, 0xf1, 0x34, 0x03, 0x0c, 0x2b, 0x0b, 0xd9, + 0xa5, 0xf1, 0x64, 0x03, 0x28, 0x2b, 0x07, 0xd9, 0x95, 0x3d, 0x10, 0x2d, + 0x94, 0xbf, 0x40, 0x25, 0x00, 0x25, 0x02, 0xe0, 0x38, 0x25, 0x00, 0xe0, + 0x40, 0x25, 0x23, 0x46, 0x00, 0x22, 0x01, 0x32, 0x1d, 0x75, 0x83, 0xf8, + 0x44, 0x50, 0x01, 0x33, 0x08, 0x2a, 0xf8, 0xd1, 0xdd, 0xe7, 0xe1, 0x18, + 0x91, 0xf8, 0x3c, 0x00, 0x18, 0xb9, 0x92, 0xf8, 0x4c, 0x00, 0x81, 0xf8, + 0x3c, 0x00, 0x3b, 0xb9, 0x94, 0xf8, 0x3d, 0x30, 0x1b, 0xb9, 0x92, 0xf8, + 0x4c, 0x30, 0x84, 0xf8, 0x3d, 0x30, 0x01, 0x23, 0x01, 0x33, 0x01, 0x32, + 0x07, 0x2b, 0xea, 0xd9, 0x23, 0x46, 0x00, 0x22, 0x93, 0xf8, 0x44, 0x10, + 0x19, 0xb9, 0x93, 0xf8, 0x4c, 0x10, 0x83, 0xf8, 0x44, 0x10, 0x01, 0x32, + 0x01, 0x33, 0x08, 0x2a, 0xf4, 0xd1, 0x22, 0x46, 0x00, 0x23, 0xe1, 0x18, + 0x91, 0xf8, 0x34, 0x00, 0x18, 0xb9, 0x92, 0xf8, 0x44, 0x00, 0x81, 0xf8, + 0x34, 0x00, 0x3b, 0xb9, 0x94, 0xf8, 0x35, 0x30, 0x1b, 0xb9, 0x92, 0xf8, + 0x44, 0x30, 0x84, 0xf8, 0x35, 0x30, 0x01, 0x23, 0x01, 0x33, 0x01, 0x32, + 0x07, 0x2b, 0xea, 0xd9, 0x00, 0x23, 0x9c, 0xf8, 0x24, 0x20, 0x1a, 0xb9, + 0x9c, 0xf8, 0x1c, 0x20, 0x8c, 0xf8, 0x24, 0x20, 0x9c, 0xf8, 0x54, 0x20, + 0x1a, 0xb9, 0x9c, 0xf8, 0x4c, 0x20, 0x8c, 0xf8, 0x54, 0x20, 0x01, 0x33, + 0x08, 0x2b, 0x0c, 0xf1, 0x01, 0x0c, 0xec, 0xd1, 0xbd, 0xe8, 0xf8, 0x8f, + 0x44, 0x22, 0x4f, 0xf0, 0x44, 0x0b, 0x7a, 0xe7, 0x3c, 0x21, 0x40, 0x22, + 0xff, 0xf7, 0xb5, 0xba, 0x38, 0x20, 0x40, 0x22, 0x09, 0xe4, 0x34, 0x20, + 0x40, 0x22, 0x09, 0xe4, 0xbd, 0xe8, 0xf8, 0x8f, 0x4b, 0x05, 0x86, 0x00, + 0x68, 0x05, 0x86, 0x00, 0x85, 0x05, 0x86, 0x00, 0x33, 0x06, 0x86, 0x00, + 0xa2, 0x05, 0x86, 0x00, 0xa7, 0x06, 0x86, 0x00, 0x50, 0x06, 0x86, 0x00, + 0x2d, 0xe9, 0xf0, 0x41, 0x4c, 0x69, 0x16, 0x69, 0x23, 0x68, 0x95, 0x8a, + 0x00, 0x2b, 0x18, 0x46, 0x01, 0xda, 0xe8, 0x18, 0x30, 0xd4, 0x62, 0x68, + 0x83, 0x18, 0xab, 0x42, 0x2c, 0xd8, 0x8b, 0x68, 0x02, 0xf1, 0x08, 0x07, + 0xe7, 0x19, 0x30, 0x18, 0x6b, 0xb9, 0x09, 0xe0, 0xe5, 0x18, 0x95, 0xf8, + 0x08, 0xc0, 0xc5, 0x5c, 0xfe, 0x5c, 0x0c, 0xea, 0x05, 0x05, 0xae, 0x42, + 0x1c, 0xd1, 0x01, 0x33, 0x93, 0x42, 0xf3, 0xdb, 0x11, 0xe0, 0x01, 0x2b, + 0x16, 0xd1, 0xad, 0x1a, 0x76, 0x19, 0x0f, 0xe0, 0xe5, 0x18, 0x95, 0xf8, + 0x08, 0x80, 0xc5, 0x5c, 0x17, 0xf8, 0x03, 0xc0, 0x08, 0xea, 0x05, 0x05, + 0xac, 0x45, 0x04, 0xd1, 0x01, 0x33, 0x93, 0x42, 0xf2, 0xdb, 0x01, 0x20, + 0x05, 0xe0, 0x01, 0x30, 0xb0, 0x42, 0x01, 0xd8, 0x00, 0x23, 0xf6, 0xe7, + 0x00, 0x20, 0x0b, 0x7b, 0x0b, 0xb1, 0x80, 0xf0, 0x01, 0x00, 0xbd, 0xe8, + 0xf0, 0x81, 0x03, 0x68, 0x70, 0xb5, 0x04, 0x46, 0x58, 0x68, 0xa3, 0x6a, + 0x0d, 0x46, 0x16, 0x46, 0x23, 0xb9, 0x90, 0x21, 0xfa, 0xf3, 0xb4, 0xf5, + 0xa0, 0x62, 0x80, 0xb1, 0xa0, 0x6a, 0x01, 0x23, 0x03, 0x60, 0xab, 0x8a, + 0x80, 0x22, 0x29, 0x69, 0xc2, 0x60, 0x83, 0x60, 0x46, 0x60, 0x93, 0x42, + 0x38, 0xbf, 0x1a, 0x46, 0x10, 0x30, 0xbd, 0xe8, 0x70, 0x40, 0xf5, 0xf3, + 0xf5, 0xb6, 0x70, 0xbd, 0x68, 0x46, 0x83, 0x69, 0x41, 0x69, 0x20, 0x30, + 0x0b, 0xb5, 0x20, 0x38, 0x03, 0x69, 0x5a, 0x46, 0x51, 0x46, 0x0e, 0xb4, + 0x4a, 0x46, 0x41, 0x46, 0x06, 0xb4, 0xc3, 0x68, 0x82, 0x68, 0x41, 0x68, + 0xfe, 0xb4, 0x03, 0x68, 0xc2, 0x69, 0xef, 0xf3, 0x03, 0x81, 0x0e, 0xb4, + 0x82, 0x69, 0xef, 0xf3, 0x05, 0x81, 0x06, 0xb4, 0x03, 0x48, 0x01, 0x68, + 0x00, 0x29, 0xfe, 0xd0, 0x68, 0x46, 0x88, 0x47, 0x14, 0xb0, 0x00, 0xbd, + 0x78, 0xc2, 0x00, 0x00, 0x0a, 0x49, 0x08, 0x42, 0x02, 0xd0, 0x62, 0xb6, + 0xc9, 0x43, 0x08, 0x40, 0x08, 0x49, 0x08, 0x42, 0x02, 0xd0, 0x61, 0xb6, + 0xc9, 0x43, 0x08, 0x40, 0x06, 0x49, 0x08, 0x40, 0x00, 0x28, 0x03, 0xd0, + 0x05, 0x49, 0x0a, 0x68, 0x02, 0x43, 0x0a, 0x60, 0x70, 0x47, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x40, 0xff, 0xff, 0x00, 0x00, + 0x00, 0xe1, 0x00, 0xe0, 0x0a, 0x49, 0x08, 0x42, 0x02, 0xd0, 0x72, 0xb6, + 0xc9, 0x43, 0x08, 0x40, 0x08, 0x49, 0x08, 0x42, 0x02, 0xd0, 0x71, 0xb6, + 0xc9, 0x43, 0x08, 0x40, 0x06, 0x49, 0x08, 0x40, 0x00, 0x28, 0x04, 0xd0, + 0x05, 0x49, 0x0a, 0x68, 0xc0, 0x43, 0x02, 0x40, 0x0a, 0x60, 0x70, 0x47, + 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x40, 0xff, 0xff, 0x00, 0x00, + 0x80, 0xe1, 0x00, 0xe0, 0x02, 0x49, 0x09, 0x68, 0x90, 0x22, 0x88, 0x58, + 0x70, 0x47, 0x00, 0x00, 0x84, 0xc2, 0x00, 0x00, 0x02, 0x49, 0x09, 0x68, + 0x9c, 0x22, 0x88, 0x50, 0x70, 0x47, 0x00, 0x00, 0x84, 0xc2, 0x00, 0x00, + 0xdd, 0xba, 0xad, 0xbb, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x02, 0x4a, 0x11, 0x68, 0x10, 0x60, 0x08, 0x1c, 0x70, 0x47, 0x00, 0x00, + 0x78, 0xc2, 0x00, 0x00, 0x02, 0x4a, 0x11, 0x68, 0x10, 0x60, 0x08, 0x1c, + 0x70, 0x47, 0x00, 0x00, 0x7c, 0xc2, 0x00, 0x00, 0x03, 0x49, 0x08, 0x60, + 0x03, 0x48, 0x01, 0x68, 0x00, 0x29, 0xfe, 0xd0, 0x88, 0x47, 0xfe, 0xe7, + 0x70, 0xc2, 0x00, 0x00, 0x7c, 0xc2, 0x00, 0x00, 0x63, 0x48, 0x64, 0x49, + 0x00, 0x22, 0x0a, 0x50, 0x01, 0x68, 0x63, 0x4a, 0x0a, 0x40, 0x63, 0x4f, + 0x0f, 0x40, 0x3f, 0x42, 0x32, 0xd1, 0x00, 0x23, 0x98, 0x46, 0x9a, 0x46, + 0x60, 0x4a, 0x0a, 0x40, 0x18, 0x21, 0xca, 0x40, 0x5f, 0x49, 0x43, 0x58, + 0x5f, 0x4c, 0x1c, 0x40, 0x5f, 0x4d, 0xac, 0x42, 0x04, 0xd1, 0x80, 0x46, + 0x5e, 0x4d, 0x45, 0x19, 0xa9, 0x46, 0x0e, 0xe0, 0x5d, 0x4d, 0xac, 0x42, + 0x0b, 0xd1, 0x82, 0x46, 0x5a, 0x4d, 0x45, 0x19, 0xab, 0x46, 0x0f, 0x24, + 0x1d, 0x1c, 0x23, 0x40, 0x59, 0x4c, 0x25, 0x40, 0x2d, 0x0a, 0x2b, 0x43, + 0x9c, 0x46, 0x00, 0x23, 0x98, 0x45, 0x01, 0xd0, 0x9a, 0x45, 0x04, 0xd1, + 0x55, 0x4b, 0xc0, 0x18, 0x01, 0x3a, 0xdc, 0xd1, 0x05, 0xe0, 0x50, 0x46, + 0x00, 0x42, 0x02, 0xd0, 0x40, 0x46, 0x00, 0x42, 0x29, 0xd1, 0xfe, 0xe7, + 0xfc, 0x21, 0x41, 0x58, 0x0a, 0x68, 0x0f, 0x23, 0x13, 0x40, 0x0f, 0x2b, + 0xf1, 0xd0, 0x01, 0x2b, 0x01, 0xd0, 0x04, 0x31, 0xf6, 0xe7, 0x08, 0x31, + 0x4a, 0x4b, 0x13, 0x40, 0x4a, 0x4c, 0xa3, 0x42, 0x06, 0xd1, 0x00, 0xf0, + 0xbb, 0xf8, 0x80, 0x46, 0x00, 0xf0, 0xc4, 0xf8, 0x81, 0x46, 0xe9, 0xe7, + 0x46, 0x4c, 0xa3, 0x42, 0xe6, 0xd1, 0x0b, 0x1f, 0x1b, 0x68, 0x45, 0x4c, + 0x23, 0x40, 0x18, 0x24, 0xe3, 0x40, 0x9c, 0x46, 0x00, 0xf0, 0xaa, 0xf8, + 0x82, 0x46, 0x00, 0xf0, 0xb3, 0xf8, 0x83, 0x46, 0xd8, 0xe7, 0x40, 0x49, + 0x21, 0x22, 0x42, 0x50, 0x2e, 0x4a, 0x3f, 0x49, 0x89, 0x58, 0xff, 0x23, + 0x19, 0x42, 0x19, 0xd0, 0x51, 0x68, 0x3d, 0x4b, 0x19, 0x42, 0x15, 0xd0, + 0x11, 0x68, 0x3c, 0x4b, 0x19, 0x40, 0xd3, 0x6a, 0x10, 0xe0, 0xa3, 0x42, + 0x0e, 0xd0, 0xc0, 0x46, 0x0c, 0xe0, 0x39, 0x49, 0x89, 0x58, 0x19, 0x42, + 0x08, 0xd0, 0x38, 0x49, 0x89, 0x58, 0x19, 0x40, 0x99, 0x42, 0xfa, 0xd1, + 0x2b, 0x4b, 0x11, 0x69, 0x19, 0x42, 0xfc, 0xd0, 0x49, 0x46, 0x3f, 0x42, + 0x04, 0xd1, 0x98, 0x23, 0xcb, 0x58, 0x10, 0x24, 0xe3, 0x40, 0x01, 0xe0, + 0x30, 0x4b, 0xcb, 0x58, 0x1c, 0x24, 0x23, 0x40, 0x00, 0x2b, 0x01, 0xd0, + 0x00, 0xf0, 0x8c, 0xf8, 0x40, 0x46, 0x2d, 0x49, 0x08, 0x60, 0x48, 0x46, + 0x2c, 0x49, 0x08, 0x60, 0x50, 0x46, 0x2c, 0x49, 0x08, 0x60, 0x60, 0x46, + 0x2b, 0x49, 0x08, 0x60, 0x2b, 0x49, 0x0f, 0x60, 0x2b, 0x4d, 0x2c, 0x49, + 0x0d, 0x60, 0x04, 0x3d, 0xad, 0x46, 0x00, 0x9d, 0xec, 0x43, 0x10, 0x23, + 0xdd, 0x41, 0xac, 0x42, 0x01, 0xd0, 0x81, 0xb0, 0x09, 0xe0, 0x24, 0x0c, + 0xa4, 0x00, 0x26, 0x4d, 0x2c, 0x60, 0x6b, 0x46, 0x1b, 0x1b, 0x25, 0x4d, + 0x2b, 0x60, 0x04, 0x3b, 0x9d, 0x46, 0x24, 0x48, 0x24, 0x49, 0x00, 0x22, + 0x04, 0xc0, 0x81, 0x42, 0xfc, 0xd8, 0x0f, 0xf0, 0x27, 0xf9, 0xfe, 0xe7, + 0x00, 0x00, 0x00, 0x18, 0x14, 0x06, 0x00, 0x00, 0xf8, 0xff, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xf0, 0x00, 0x00, 0x00, 0x0f, 0xfc, 0x0f, 0x00, 0x00, + 0xf0, 0x8f, 0x00, 0x00, 0xa0, 0x82, 0x00, 0x00, 0x00, 0x0f, 0x00, 0x00, + 0xe0, 0x80, 0x00, 0x00, 0x00, 0x70, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, + 0x00, 0xff, 0x0f, 0x00, 0x00, 0x2a, 0x08, 0x00, 0x00, 0x0e, 0x08, 0x00, + 0x00, 0x00, 0x00, 0xff, 0xe0, 0x01, 0x00, 0x00, 0x04, 0x06, 0x00, 0x00, + 0x00, 0x00, 0x38, 0x00, 0xff, 0xff, 0x00, 0x00, 0x18, 0x06, 0x00, 0x00, + 0x0c, 0x06, 0x00, 0x00, 0x08, 0x04, 0x00, 0x00, 0x84, 0xc2, 0x00, 0x00, + 0x88, 0xc2, 0x00, 0x00, 0x8c, 0xc2, 0x00, 0x00, 0x90, 0xc2, 0x00, 0x00, + 0x80, 0xc2, 0x00, 0x00, 0x00, 0xc0, 0x03, 0x00, 0xe4, 0xfe, 0x01, 0x00, + 0xec, 0xfe, 0x01, 0x00, 0xe8, 0xfe, 0x01, 0x00, 0xa0, 0x07, 0x02, 0x00, + 0x16, 0x0c, 0x02, 0x00, 0x08, 0x68, 0x0f, 0x22, 0x04, 0x31, 0x02, 0x40, + 0x05, 0x2a, 0xf9, 0xd1, 0x01, 0x4a, 0x10, 0x40, 0xf7, 0x46, 0x00, 0x00, + 0x00, 0xf0, 0xff, 0xff, 0x08, 0x68, 0x0f, 0x22, 0x04, 0x31, 0x02, 0x40, + 0x05, 0x2a, 0xf9, 0xd1, 0x80, 0x22, 0x10, 0x42, 0xf6, 0xd0, 0x01, 0x4a, + 0x10, 0x40, 0xf7, 0x46, 0x00, 0xf0, 0xff, 0xff, 0xfe, 0xe7, 0x00, 0x00, + 0x10, 0xb5, 0x00, 0x21, 0x28, 0x22, 0x04, 0x46, 0xf5, 0xf3, 0x8c, 0xf5, + 0x0a, 0x4b, 0x23, 0x60, 0x0a, 0x4b, 0x63, 0x60, 0x0a, 0x4b, 0xa3, 0x60, + 0x0a, 0x4b, 0xe3, 0x60, 0x0a, 0x4b, 0x23, 0x61, 0x0a, 0x4b, 0x63, 0x61, + 0x0a, 0x4b, 0xa3, 0x61, 0x0a, 0x4b, 0xe3, 0x61, 0x0a, 0x4b, 0x23, 0x62, + 0x0a, 0x4b, 0x63, 0x62, 0x10, 0xbd, 0x00, 0xbf, 0x00, 0x00, 0x00, 0x00, + 0xb3, 0xfd, 0x01, 0x00, 0xb4, 0xfd, 0x01, 0x00, 0xa0, 0x07, 0x02, 0x00, + 0xa0, 0x07, 0x02, 0x00, 0x16, 0x0c, 0x02, 0x00, 0x18, 0x0c, 0x02, 0x00, + 0xcc, 0xae, 0x02, 0x00, 0xcc, 0xae, 0x02, 0x00, 0xe8, 0x35, 0x03, 0x00, + 0x2d, 0xe9, 0xf0, 0x41, 0x96, 0xb0, 0x0a, 0xa8, 0xff, 0xf7, 0xca, 0xff, + 0x0a, 0x9b, 0x0b, 0x9f, 0x0d, 0x9c, 0xff, 0x1a, 0x0c, 0x9b, 0x0f, 0x9a, + 0xe4, 0x1a, 0x5f, 0x4d, 0x0e, 0x9b, 0x3e, 0x19, 0xc3, 0xeb, 0x02, 0x08, + 0x2b, 0x68, 0x5d, 0x48, 0xf6, 0x18, 0x03, 0xf0, 0x1d, 0xf9, 0x04, 0xf5, + 0x7e, 0x73, 0x07, 0x33, 0x9b, 0x0a, 0x46, 0x44, 0x8d, 0xe8, 0x08, 0x01, + 0x08, 0xf5, 0x7e, 0x78, 0x08, 0xf1, 0x07, 0x08, 0x07, 0xf5, 0x7e, 0x72, + 0x4f, 0xea, 0x98, 0x23, 0x07, 0x32, 0x02, 0x93, 0x05, 0x23, 0x39, 0x46, + 0x92, 0x0a, 0x03, 0x93, 0x51, 0x48, 0x23, 0x46, 0x03, 0xf0, 0x04, 0xf9, + 0x50, 0x4c, 0x51, 0x4b, 0x27, 0x68, 0x19, 0x68, 0x28, 0x68, 0xcb, 0x1b, + 0x03, 0xf5, 0x7e, 0x75, 0x07, 0x35, 0xad, 0x0a, 0x8d, 0xe8, 0xa0, 0x00, + 0x07, 0xf5, 0x7e, 0x75, 0x07, 0x35, 0x03, 0x90, 0x00, 0xf5, 0x7e, 0x70, + 0x01, 0xf5, 0x7e, 0x72, 0xad, 0x0a, 0x07, 0x30, 0x80, 0x0a, 0x07, 0x32, + 0x02, 0x95, 0x46, 0x4d, 0x92, 0x0a, 0x04, 0x90, 0x45, 0x48, 0x03, 0xf0, + 0xe5, 0xf8, 0x23, 0x68, 0x29, 0x68, 0x44, 0x48, 0xc9, 0x18, 0x06, 0xf5, + 0xbe, 0x53, 0x01, 0xf5, 0x7e, 0x72, 0x3f, 0x33, 0x9b, 0x0a, 0x07, 0x32, + 0x92, 0x0a, 0x00, 0x93, 0x06, 0xf5, 0xa0, 0x53, 0x03, 0xf0, 0xd4, 0xf8, + 0x3d, 0x4b, 0x3e, 0x48, 0x19, 0x68, 0x03, 0xf0, 0xcf, 0xf8, 0x3d, 0x4b, + 0x26, 0x46, 0x19, 0x68, 0x3c, 0x4b, 0x0a, 0x68, 0x2f, 0x46, 0x9a, 0x42, + 0x03, 0xd0, 0x3b, 0x48, 0x03, 0xf0, 0xc4, 0xf8, 0x24, 0xe0, 0x14, 0x91, + 0x0b, 0x46, 0x04, 0xe0, 0x14, 0x68, 0x36, 0x48, 0x13, 0x1d, 0x84, 0x42, + 0x03, 0xd1, 0x1a, 0x46, 0x15, 0xab, 0x9a, 0x42, 0xf6, 0xd3, 0x34, 0x48, + 0x14, 0xab, 0x00, 0x68, 0xc1, 0xeb, 0x03, 0x0c, 0xc5, 0x1a, 0x84, 0x1a, + 0xc1, 0xeb, 0x02, 0x0e, 0x8d, 0xe8, 0x01, 0x10, 0x2f, 0x48, 0x14, 0x92, + 0xcd, 0xf8, 0x08, 0xc0, 0xcd, 0xf8, 0x0c, 0xe0, 0xcd, 0xf8, 0x10, 0xe0, + 0x05, 0x95, 0x06, 0x95, 0x07, 0x94, 0x08, 0x94, 0x03, 0xf0, 0x9e, 0xf8, + 0x29, 0x4c, 0x20, 0x68, 0x70, 0xb3, 0xb0, 0xf8, 0x06, 0x80, 0xf6, 0xf3, + 0x55, 0xf2, 0x23, 0x68, 0x08, 0xf1, 0xff, 0x38, 0x5c, 0x89, 0x02, 0x46, + 0x08, 0xfb, 0x04, 0xf5, 0x44, 0x34, 0x08, 0xfb, 0x04, 0xf4, 0x05, 0xf5, + 0x7e, 0x73, 0x07, 0x33, 0x9b, 0x12, 0x8d, 0xe8, 0x18, 0x00, 0x04, 0xf5, + 0x7e, 0x73, 0x07, 0x33, 0x9b, 0x12, 0x02, 0x93, 0x41, 0x46, 0x2b, 0x46, + 0x1b, 0x48, 0x03, 0xf0, 0x7d, 0xf8, 0x33, 0x68, 0x3a, 0x68, 0x59, 0x1b, + 0x9b, 0x18, 0x1b, 0x1b, 0x03, 0xf5, 0x7e, 0x70, 0x01, 0xf5, 0x7e, 0x72, + 0x07, 0x30, 0x80, 0x0a, 0x07, 0x32, 0x00, 0x90, 0x92, 0x0a, 0x14, 0x48, + 0x03, 0xf0, 0x6c, 0xf8, 0x16, 0xb0, 0xbd, 0xe8, 0xf0, 0x81, 0x00, 0xbf, + 0xcc, 0x26, 0x00, 0x00, 0xe1, 0x1f, 0x86, 0x00, 0xf0, 0x1f, 0x86, 0x00, + 0x88, 0x26, 0x00, 0x00, 0xc8, 0x26, 0x00, 0x00, 0xa4, 0x26, 0x00, 0x00, + 0x2e, 0x20, 0x86, 0x00, 0x72, 0x20, 0x86, 0x00, 0x90, 0x26, 0x00, 0x00, + 0xac, 0x20, 0x86, 0x00, 0xf4, 0x07, 0x02, 0x00, 0x4b, 0x41, 0x54, 0x53, + 0xc6, 0x20, 0x86, 0x00, 0xf8, 0x07, 0x02, 0x00, 0xe9, 0x20, 0x86, 0x00, + 0xbc, 0x26, 0x00, 0x00, 0x66, 0x21, 0x86, 0x00, 0x92, 0x21, 0x86, 0x00, + 0x08, 0xb5, 0x71, 0x46, 0x04, 0x48, 0x03, 0xf0, 0x3f, 0xf8, 0x40, 0xf6, + 0x39, 0x00, 0xbd, 0xe8, 0x08, 0x40, 0xff, 0xf7, 0xa1, 0xbd, 0x00, 0xbf, + 0x8e, 0x1f, 0x86, 0x00, 0x2d, 0xe9, 0xf0, 0x47, 0x03, 0x68, 0x8e, 0xb0, + 0x02, 0x2b, 0x04, 0x46, 0x18, 0xd1, 0x56, 0x4a, 0x00, 0x21, 0x12, 0x68, + 0x51, 0x61, 0x55, 0x4a, 0x10, 0x68, 0xc1, 0x04, 0x24, 0xd5, 0x54, 0x49, + 0x20, 0xf4, 0x80, 0x50, 0x0b, 0x60, 0xd1, 0x69, 0x52, 0x4b, 0x40, 0xf4, + 0x00, 0x50, 0x19, 0x60, 0x9c, 0x68, 0x04, 0x24, 0x9c, 0x60, 0x10, 0x60, + 0x4f, 0x48, 0x03, 0xf0, 0x17, 0xf8, 0x90, 0xe0, 0x0c, 0x2b, 0x11, 0xd1, + 0x49, 0x4d, 0x2a, 0x68, 0x91, 0x04, 0x0d, 0xd5, 0x22, 0xf4, 0x00, 0x52, + 0x42, 0xf4, 0x00, 0x62, 0x68, 0x60, 0x2a, 0x60, 0x48, 0x48, 0xe1, 0x6c, + 0x03, 0xf0, 0x06, 0xf8, 0x2b, 0x68, 0x1a, 0x05, 0x7d, 0xd5, 0x7b, 0xe0, + 0x10, 0x3b, 0x0f, 0x2b, 0x02, 0xd8, 0xf9, 0xf3, 0xf5, 0xf5, 0x76, 0xe0, + 0x3d, 0x4e, 0x42, 0x48, 0xf1, 0x69, 0x02, 0xf0, 0xf7, 0xff, 0xa3, 0x6c, + 0x22, 0x46, 0x00, 0x93, 0x63, 0x6c, 0x3f, 0x48, 0x01, 0x93, 0xa3, 0x68, + 0x00, 0x27, 0x02, 0x93, 0xe3, 0x68, 0xb9, 0x46, 0x03, 0x93, 0x21, 0x68, + 0xe3, 0x6c, 0x02, 0xf0, 0xe7, 0xff, 0x3a, 0x4b, 0x65, 0x6c, 0x1b, 0x68, + 0x04, 0xf1, 0x10, 0x01, 0xc5, 0xeb, 0x03, 0x0a, 0xe3, 0x69, 0x37, 0x48, + 0x00, 0x93, 0x23, 0x6a, 0x4f, 0xea, 0x9a, 0x0a, 0x01, 0x93, 0x63, 0x6a, + 0xb8, 0x46, 0x02, 0x93, 0xa3, 0x6a, 0x03, 0x93, 0x0e, 0xc9, 0x02, 0xf0, + 0xd1, 0xff, 0xa3, 0x6b, 0x04, 0xf1, 0x2c, 0x01, 0x00, 0x93, 0xe3, 0x6b, + 0x2e, 0x48, 0x01, 0x93, 0x23, 0x6c, 0x02, 0x93, 0x0e, 0xc9, 0x02, 0xf0, + 0xc5, 0xff, 0xeb, 0x68, 0x2b, 0x48, 0x00, 0x93, 0x95, 0xe8, 0x0e, 0x00, + 0x02, 0xf0, 0xbe, 0xff, 0xeb, 0x69, 0x05, 0xf1, 0x10, 0x01, 0x00, 0x93, + 0x0e, 0xc9, 0x27, 0x48, 0x02, 0xf0, 0xb6, 0xff, 0x04, 0xa8, 0xff, 0xf7, + 0x4f, 0xfe, 0x25, 0x48, 0x02, 0xf0, 0xb0, 0xff, 0x1c, 0xe0, 0x7a, 0x59, + 0xd3, 0x07, 0x13, 0xd5, 0xff, 0x2a, 0x11, 0xd9, 0x05, 0x9b, 0x93, 0x42, + 0x08, 0xd2, 0x20, 0x4b, 0x1b, 0x0d, 0x1b, 0x05, 0x9a, 0x42, 0x09, 0xd3, + 0x03, 0xf5, 0x80, 0x13, 0x9a, 0x42, 0x05, 0xd8, 0x1c, 0x48, 0x39, 0x46, + 0x02, 0xf0, 0x9a, 0xff, 0x09, 0xf1, 0x01, 0x09, 0x04, 0x37, 0xb9, 0xf1, + 0x0f, 0x0f, 0x08, 0xf1, 0x01, 0x08, 0x01, 0xd8, 0xd0, 0x45, 0xe0, 0xd1, + 0x33, 0x68, 0x40, 0xf2, 0x03, 0x30, 0x43, 0xf4, 0x80, 0x63, 0x86, 0xe8, + 0x18, 0x00, 0xff, 0xf7, 0xef, 0xfc, 0x00, 0xe0, 0xfe, 0xe7, 0x0e, 0xb0, + 0xbd, 0xe8, 0xf0, 0x87, 0x70, 0x08, 0x02, 0x00, 0xfc, 0x07, 0x02, 0x00, + 0x24, 0x10, 0x00, 0xe0, 0x20, 0x10, 0x00, 0xe0, 0x24, 0xc8, 0x01, 0x00, + 0x28, 0xc8, 0x01, 0x00, 0x34, 0xc8, 0x01, 0x00, 0x41, 0xc8, 0x01, 0x00, + 0xe4, 0xfe, 0x01, 0x00, 0x75, 0xc8, 0x01, 0x00, 0xa8, 0xc8, 0x01, 0x00, + 0xd7, 0xc8, 0x01, 0x00, 0xf5, 0xc8, 0x01, 0x00, 0xfc, 0x1c, 0x86, 0x00, + 0x9d, 0x66, 0x80, 0x00, 0x12, 0xc9, 0x01, 0x00, 0x70, 0xb5, 0x1a, 0x4c, + 0x8a, 0xb0, 0x68, 0x46, 0xff, 0xf7, 0xf8, 0xfd, 0x21, 0x78, 0xc9, 0xb9, + 0x06, 0x98, 0x07, 0x9d, 0x2d, 0x1a, 0x06, 0xd0, 0x2a, 0x46, 0xf5, 0xf3, + 0x81, 0xf3, 0x06, 0x98, 0x29, 0x46, 0xf9, 0xf3, 0x6d, 0xf4, 0x12, 0x4b, + 0x00, 0x22, 0x1a, 0x70, 0x01, 0x23, 0x23, 0x70, 0x10, 0x4b, 0x19, 0x68, + 0xc1, 0xb1, 0x0b, 0x78, 0xb3, 0xb1, 0x0f, 0x4b, 0x18, 0x68, 0xf6, 0xf3, + 0x63, 0xf1, 0x11, 0xe0, 0x0d, 0x4e, 0x31, 0x78, 0x71, 0xb9, 0x08, 0x98, + 0x09, 0x9d, 0x2d, 0x1a, 0x06, 0xd0, 0x2a, 0x46, 0xf5, 0xf3, 0x64, 0xf3, + 0x08, 0x98, 0x29, 0x46, 0xf9, 0xf3, 0x50, 0xf4, 0x00, 0x23, 0x23, 0x70, + 0x01, 0x23, 0x33, 0x70, 0x0a, 0xb0, 0x70, 0xbd, 0x38, 0x08, 0x02, 0x00, + 0x3a, 0x08, 0x02, 0x00, 0xbc, 0x26, 0x00, 0x00, 0x20, 0x08, 0x02, 0x00, + 0x39, 0x08, 0x02, 0x00, 0x0c, 0x4b, 0x1b, 0x68, 0xd3, 0xf8, 0x14, 0x06, + 0xd3, 0xf8, 0x14, 0x26, 0x90, 0x42, 0x0a, 0x4a, 0x18, 0xbf, 0xd3, 0xf8, + 0x14, 0x06, 0x09, 0x4b, 0x11, 0x68, 0x1b, 0x68, 0x40, 0x1a, 0x98, 0x42, + 0x05, 0xd3, 0xb0, 0xfb, 0xf3, 0xf0, 0x03, 0xfb, 0x00, 0x13, 0x13, 0x60, + 0x70, 0x47, 0x00, 0x20, 0x70, 0x47, 0x00, 0xbf, 0x9c, 0x26, 0x00, 0x00, + 0xe4, 0x26, 0x00, 0x00, 0xc8, 0x25, 0x00, 0x00, 0x70, 0xb5, 0x04, 0x46, + 0xfe, 0xf3, 0x86, 0xf3, 0x20, 0x46, 0xfe, 0xf3, 0xc3, 0xf2, 0x05, 0x46, + 0x20, 0x46, 0xfe, 0xf3, 0x43, 0xf2, 0x00, 0x22, 0x06, 0x46, 0x40, 0xf6, + 0x2a, 0x01, 0x20, 0x46, 0xfe, 0xf3, 0xfc, 0xf3, 0x01, 0x22, 0xaa, 0x40, + 0x83, 0x69, 0x1a, 0x42, 0x01, 0xd1, 0x01, 0x35, 0x00, 0xe0, 0x00, 0x25, + 0x20, 0x46, 0x31, 0x46, 0xfe, 0xf3, 0x02, 0xf4, 0x28, 0x46, 0x70, 0xbd, + 0x2d, 0xe9, 0xf0, 0x41, 0x04, 0x46, 0x0e, 0x46, 0xfe, 0xf3, 0x64, 0xf3, + 0x20, 0x46, 0xfe, 0xf3, 0x25, 0xf2, 0x00, 0x22, 0x05, 0x46, 0x40, 0xf6, + 0x2a, 0x01, 0x20, 0x46, 0xfe, 0xf3, 0xde, 0xf3, 0x82, 0x69, 0x07, 0x46, + 0x43, 0x69, 0x46, 0xb1, 0x4f, 0xf4, 0x00, 0x40, 0x42, 0xf0, 0x00, 0x48, + 0x43, 0xf0, 0x00, 0x46, 0xff, 0xf7, 0xc0, 0xfb, 0x07, 0xe0, 0x4f, 0xf4, + 0x00, 0x40, 0x22, 0xf0, 0x00, 0x48, 0x23, 0xf0, 0x00, 0x46, 0xff, 0xf7, + 0xd5, 0xfb, 0x20, 0x46, 0x29, 0x46, 0xc7, 0xf8, 0x18, 0x80, 0x7e, 0x61, + 0xbd, 0xe8, 0xf0, 0x41, 0xfe, 0xf3, 0xd2, 0xb3, 0xff, 0xf7, 0xb0, 0xbf, + 0x10, 0xb5, 0x04, 0x46, 0xfe, 0xf3, 0x36, 0xf3, 0x01, 0x46, 0x20, 0x46, + 0xbd, 0xe8, 0x10, 0x40, 0x00, 0xf0, 0x48, 0xb9, 0x2d, 0xe9, 0xf0, 0x41, + 0x0e, 0x46, 0x50, 0x21, 0x04, 0x46, 0x15, 0x46, 0x98, 0x46, 0xfa, 0xf3, + 0x15, 0xf1, 0x07, 0x46, 0x10, 0xb3, 0x00, 0x21, 0x50, 0x22, 0xf5, 0xf3, + 0xc7, 0xf2, 0x40, 0xf2, 0x3c, 0x73, 0x7b, 0x63, 0x4f, 0xf4, 0x7a, 0x73, + 0xfb, 0x63, 0x1c, 0x23, 0x3b, 0x64, 0x0c, 0x23, 0x7b, 0x64, 0x04, 0x23, + 0x00, 0x20, 0xc7, 0xf8, 0x0c, 0x80, 0x3e, 0x60, 0x7d, 0x60, 0xbc, 0x60, + 0xbb, 0x64, 0x08, 0x49, 0xf5, 0xf3, 0x4e, 0xf7, 0xc0, 0xb2, 0x87, 0xf8, + 0x4c, 0x00, 0x01, 0x38, 0xc0, 0xb2, 0x01, 0x28, 0x02, 0xd9, 0x02, 0x23, + 0x87, 0xf8, 0x4c, 0x30, 0x38, 0x46, 0xbd, 0xe8, 0xf0, 0x81, 0x00, 0xbf, + 0x3e, 0x29, 0x86, 0x00, 0x00, 0x48, 0x70, 0x47, 0x0c, 0xdb, 0x01, 0x00, + 0x00, 0x48, 0x70, 0x47, 0x90, 0xdb, 0x01, 0x00, 0x00, 0x48, 0x70, 0x47, + 0x00, 0xa6, 0x0e, 0x00, 0x38, 0xb5, 0xd2, 0xf8, 0x00, 0x56, 0x04, 0x46, + 0x05, 0xf0, 0x7c, 0x05, 0xad, 0x08, 0xff, 0xf7, 0xeb, 0xff, 0x03, 0xe0, + 0x83, 0x78, 0xab, 0x42, 0x07, 0xd0, 0x0c, 0x30, 0x10, 0xb1, 0x03, 0x88, + 0x00, 0x2b, 0xf7, 0xd1, 0x20, 0x46, 0xff, 0xf7, 0xe3, 0xff, 0x03, 0x88, + 0x4f, 0xf4, 0x7a, 0x70, 0x58, 0x43, 0x38, 0xbd, 0x10, 0xb5, 0x14, 0x46, + 0xff, 0xf7, 0xde, 0xff, 0x01, 0x23, 0xc4, 0xf8, 0x60, 0x36, 0xd4, 0xf8, + 0x64, 0x36, 0xdb, 0xb2, 0xb0, 0xfb, 0xf3, 0xf3, 0x4f, 0xf4, 0x7a, 0x70, + 0x58, 0x43, 0x10, 0xbd, 0x2d, 0xe9, 0xff, 0x47, 0x14, 0x46, 0x00, 0x22, + 0x02, 0x92, 0x03, 0x92, 0x02, 0x6a, 0xc4, 0xf8, 0x20, 0x36, 0x0c, 0x2a, + 0x06, 0x46, 0x89, 0x46, 0xd4, 0xf8, 0x28, 0x26, 0x06, 0xdd, 0x4f, 0xea, + 0x12, 0x48, 0x4f, 0xea, 0x88, 0x58, 0x4f, 0xea, 0x98, 0x58, 0x03, 0xe0, + 0x4f, 0xea, 0x12, 0x28, 0x5f, 0xfa, 0x88, 0xf8, 0x01, 0x25, 0x15, 0xfa, + 0x03, 0xf3, 0x00, 0x27, 0x30, 0x46, 0x49, 0x46, 0x22, 0x46, 0x00, 0x97, + 0xf9, 0xf3, 0x96, 0xf0, 0x05, 0x46, 0x01, 0x22, 0x12, 0xfa, 0x07, 0xf3, + 0x2b, 0x42, 0x07, 0xd0, 0x00, 0x92, 0x30, 0x46, 0x49, 0x46, 0x22, 0x46, + 0xf9, 0xf3, 0x8a, 0xf0, 0x25, 0xea, 0x00, 0x05, 0x01, 0x37, 0x1f, 0x2f, + 0xef, 0xd1, 0x30, 0x46, 0x02, 0xa9, 0x03, 0xaa, 0xf9, 0xf3, 0xaa, 0xf0, + 0x02, 0x9b, 0x00, 0x27, 0x25, 0xea, 0x03, 0x0a, 0x3d, 0x46, 0x01, 0x23, + 0xab, 0x40, 0x13, 0xea, 0x0a, 0x0f, 0x08, 0xd0, 0x30, 0x46, 0x49, 0x46, + 0x22, 0x46, 0xeb, 0xb2, 0xff, 0xf7, 0xb6, 0xff, 0x87, 0x42, 0x38, 0xbf, + 0x07, 0x46, 0x01, 0x35, 0x1f, 0x2d, 0xee, 0xd1, 0x08, 0xf1, 0x02, 0x00, + 0xc0, 0x19, 0x04, 0xb0, 0xbd, 0xe8, 0xf0, 0x87, 0x73, 0xb5, 0x05, 0x46, + 0x14, 0x46, 0x1e, 0x46, 0x00, 0x91, 0x4f, 0xf4, 0xcb, 0x62, 0x00, 0x21, + 0x4f, 0xf0, 0xff, 0x33, 0xfe, 0xf3, 0x30, 0xf1, 0x28, 0x46, 0x00, 0x21, + 0x40, 0xf2, 0x5c, 0x62, 0x23, 0x46, 0x00, 0x96, 0xfe, 0xf3, 0x28, 0xf1, + 0x7c, 0xbd, 0x00, 0x22, 0x38, 0xb5, 0x0c, 0x46, 0x13, 0x46, 0x04, 0x21, + 0x05, 0x46, 0xff, 0xf7, 0xe3, 0xff, 0x01, 0x2c, 0x20, 0xf0, 0xf0, 0x73, + 0x08, 0xbf, 0x43, 0xf0, 0xf0, 0x73, 0x28, 0x46, 0x04, 0x21, 0x4f, 0xf0, + 0xff, 0x32, 0xff, 0xf7, 0xd7, 0xff, 0x01, 0x2c, 0x05, 0xd1, 0x49, 0xf6, + 0x40, 0x40, 0xbd, 0xe8, 0x38, 0x40, 0xf9, 0xf3, 0x71, 0xb5, 0x38, 0xbd, + 0x2d, 0xe9, 0xf0, 0x41, 0x04, 0x46, 0x88, 0x46, 0xfe, 0xf3, 0xfc, 0xf0, + 0x00, 0x21, 0x06, 0x46, 0x20, 0x46, 0xfe, 0xf3, 0xc9, 0xf2, 0x07, 0x46, + 0x20, 0x46, 0x00, 0xf0, 0x12, 0xf9, 0x41, 0x46, 0x05, 0x46, 0x3a, 0x46, + 0x18, 0x23, 0x20, 0x46, 0xff, 0xf7, 0x62, 0xff, 0x0b, 0x23, 0x02, 0x30, + 0x58, 0x43, 0x07, 0x4b, 0x31, 0x46, 0xeb, 0x18, 0xb3, 0xfb, 0xf5, 0xf5, + 0x45, 0x43, 0x20, 0x46, 0xfe, 0xf3, 0xb2, 0xf2, 0x0a, 0x23, 0xb5, 0xfb, + 0xf3, 0xf5, 0xa8, 0xb2, 0xbd, 0xe8, 0xf0, 0x81, 0x3f, 0x42, 0x0f, 0x00, + 0x70, 0xb5, 0x04, 0x46, 0x0e, 0x46, 0xfe, 0xf3, 0xd3, 0xf0, 0x00, 0x21, + 0x05, 0x46, 0x20, 0x46, 0xfe, 0xf3, 0xa0, 0xf2, 0x31, 0x46, 0x02, 0x46, + 0x20, 0x46, 0xff, 0xf7, 0x15, 0xff, 0x29, 0x46, 0x06, 0x46, 0x20, 0x46, + 0xfe, 0xf3, 0x96, 0xf2, 0x30, 0x46, 0x70, 0xbd, 0x70, 0xb5, 0x04, 0x46, + 0x0e, 0x46, 0xfe, 0xf3, 0xbd, 0xf0, 0x00, 0x21, 0x05, 0x46, 0x20, 0x46, + 0xfe, 0xf3, 0x8a, 0xf2, 0x31, 0x46, 0x02, 0x46, 0x20, 0x46, 0xff, 0xf7, + 0x19, 0xff, 0x29, 0x46, 0x06, 0x46, 0x20, 0x46, 0xfe, 0xf3, 0x80, 0xf2, + 0x30, 0x46, 0x70, 0xbd, 0xff, 0xf7, 0xe8, 0xbf, 0x2d, 0xe9, 0xf0, 0x41, + 0x16, 0x4c, 0x05, 0x46, 0x27, 0x68, 0x2f, 0xbb, 0xfe, 0xf3, 0xa2, 0xf0, + 0x39, 0x46, 0x06, 0x46, 0x28, 0x46, 0xfe, 0xf3, 0x6f, 0xf2, 0xd0, 0xf8, + 0x14, 0x86, 0xd0, 0xf8, 0x14, 0x36, 0x07, 0x46, 0x98, 0x45, 0x18, 0xbf, + 0xd0, 0xf8, 0x14, 0x86, 0x42, 0xf2, 0x10, 0x70, 0xf9, 0xf3, 0xfe, 0xf4, + 0xd7, 0xf8, 0x14, 0x36, 0xd7, 0xf8, 0x14, 0x26, 0x28, 0x46, 0x93, 0x42, + 0x18, 0xbf, 0xd7, 0xf8, 0x14, 0x36, 0x31, 0x46, 0xc8, 0xeb, 0x03, 0x08, + 0x64, 0x23, 0x03, 0xfb, 0x08, 0xf3, 0x23, 0x60, 0xfe, 0xf3, 0x50, 0xf2, + 0x20, 0x68, 0xbd, 0xe8, 0xf0, 0x81, 0x00, 0xbf, 0x80, 0x08, 0x02, 0x00, + 0xf8, 0xb5, 0x1f, 0x46, 0x04, 0x46, 0x15, 0x46, 0xfe, 0xf3, 0x72, 0xf0, + 0x00, 0x21, 0x06, 0x46, 0x20, 0x46, 0xfe, 0xf3, 0x3f, 0xf2, 0x02, 0x23, + 0xc0, 0xf8, 0x58, 0x36, 0x57, 0xb1, 0xd0, 0xf8, 0x5c, 0x36, 0x05, 0xf0, + 0x3f, 0x02, 0x23, 0xf4, 0xfc, 0x43, 0x43, 0xea, 0x42, 0x23, 0xc0, 0xf8, + 0x5c, 0x36, 0x04, 0xe0, 0xd0, 0xf8, 0x5c, 0x56, 0x6d, 0x0a, 0x05, 0xf0, + 0x3f, 0x05, 0x20, 0x46, 0x31, 0x46, 0xfe, 0xf3, 0x27, 0xf2, 0x28, 0x46, + 0xf8, 0xbd, 0x01, 0x21, 0xff, 0xf7, 0x31, 0xbf, 0x00, 0x21, 0xff, 0xf7, + 0x2e, 0xbf, 0x08, 0xb1, 0xf9, 0xf3, 0x78, 0xb2, 0x70, 0x47, 0x00, 0x00, + 0xf8, 0xb5, 0x08, 0x4c, 0x05, 0x46, 0x27, 0x68, 0x08, 0xe0, 0x28, 0x46, + 0x3e, 0x68, 0xfe, 0xf3, 0x7b, 0xf1, 0x39, 0x46, 0x7a, 0x68, 0xf9, 0xf3, + 0x75, 0xf7, 0x37, 0x46, 0x00, 0x2f, 0xf4, 0xd1, 0x27, 0x60, 0xf8, 0xbd, + 0x6c, 0x27, 0x00, 0x00, 0x00, 0x23, 0x43, 0x66, 0x70, 0x47, 0xf7, 0xb5, + 0x00, 0x22, 0x01, 0x21, 0x13, 0x46, 0x05, 0x46, 0xf9, 0xf3, 0x0c, 0xf0, + 0x00, 0x24, 0x07, 0x46, 0x21, 0x46, 0x28, 0x22, 0x23, 0x46, 0x28, 0x46, + 0x00, 0x94, 0xfe, 0xf3, 0x29, 0xf0, 0x01, 0x21, 0x06, 0x46, 0x3b, 0x46, + 0x28, 0x46, 0x4f, 0xf0, 0xff, 0x32, 0xf8, 0xf3, 0xfb, 0xf7, 0x28, 0x46, + 0x21, 0x46, 0x28, 0x22, 0x4f, 0xf0, 0xff, 0x33, 0x00, 0x96, 0xfe, 0xf3, + 0x19, 0xf0, 0xfe, 0xbd, 0x70, 0xb5, 0x45, 0x6e, 0x04, 0x46, 0x65, 0xb1, + 0xd0, 0xf8, 0xc8, 0x30, 0x34, 0x33, 0x50, 0xf8, 0x23, 0x20, 0xc3, 0x6d, + 0x9a, 0x42, 0x03, 0xd1, 0x00, 0x6e, 0xa8, 0x47, 0x05, 0x46, 0x00, 0xe0, + 0x00, 0x25, 0x20, 0x46, 0x61, 0x6d, 0xff, 0xf7, 0x39, 0xff, 0xa3, 0x6e, + 0x06, 0x46, 0x53, 0xb1, 0xd4, 0xf8, 0xc8, 0x20, 0x34, 0x32, 0x54, 0xf8, + 0x22, 0x10, 0xe2, 0x6d, 0x91, 0x42, 0x02, 0xd1, 0x20, 0x6e, 0x29, 0x46, + 0x98, 0x47, 0x30, 0x46, 0x70, 0xbd, 0x10, 0xb5, 0x04, 0x46, 0xfe, 0xf3, + 0x23, 0xf1, 0x01, 0x46, 0x20, 0x46, 0xbd, 0xe8, 0x10, 0x40, 0xff, 0xf7, + 0x09, 0xbf, 0x10, 0xb5, 0x04, 0x46, 0xfe, 0xf3, 0x19, 0xf1, 0x01, 0x46, + 0x20, 0x46, 0xbd, 0xe8, 0x10, 0x40, 0xff, 0xf7, 0x2d, 0xbf, 0x70, 0x47, + 0x70, 0xb5, 0x45, 0x6e, 0x04, 0x46, 0x65, 0xb1, 0xd0, 0xf8, 0xc8, 0x30, + 0x34, 0x33, 0x50, 0xf8, 0x23, 0x20, 0xc3, 0x6d, 0x9a, 0x42, 0x03, 0xd1, + 0x00, 0x6e, 0xa8, 0x47, 0x05, 0x46, 0x00, 0xe0, 0x00, 0x25, 0x20, 0x46, + 0x61, 0x6d, 0xff, 0xf7, 0xbf, 0xfe, 0xa3, 0x6e, 0x06, 0x46, 0x53, 0xb1, + 0xd4, 0xf8, 0xc8, 0x20, 0x34, 0x32, 0x54, 0xf8, 0x22, 0x10, 0xe2, 0x6d, + 0x91, 0x42, 0x02, 0xd1, 0x20, 0x6e, 0x29, 0x46, 0x98, 0x47, 0x30, 0x46, + 0x70, 0xbd, 0x70, 0xb5, 0x04, 0x46, 0xfe, 0xf3, 0x65, 0xf1, 0x00, 0x28, + 0x3c, 0xd0, 0xa3, 0x68, 0xb3, 0xf5, 0x02, 0x6f, 0x09, 0xd0, 0x40, 0xf6, + 0x04, 0x02, 0x93, 0x42, 0x07, 0xd1, 0xe5, 0x68, 0x0c, 0x2d, 0x94, 0xbf, + 0x00, 0x25, 0x01, 0x25, 0x02, 0xe0, 0x01, 0x25, 0x00, 0xe0, 0x00, 0x25, + 0xed, 0xb2, 0x4d, 0xb9, 0x20, 0x46, 0x4f, 0xf4, 0x00, 0x61, 0x2a, 0x46, + 0xd4, 0xf8, 0xc8, 0x60, 0xfe, 0xf3, 0x50, 0xf1, 0x30, 0xb9, 0x70, 0xbd, + 0xd4, 0xf8, 0x84, 0x00, 0x10, 0xf5, 0x40, 0x50, 0x1a, 0xd0, 0x00, 0x26, + 0xd0, 0xf8, 0x30, 0x31, 0x23, 0xf0, 0x04, 0x03, 0xc0, 0xf8, 0x30, 0x31, + 0x43, 0xf0, 0x01, 0x03, 0xc0, 0xf8, 0x30, 0x31, 0x1b, 0x09, 0x03, 0xf0, + 0x07, 0x03, 0x03, 0x2b, 0x03, 0xd0, 0x20, 0x46, 0x00, 0x21, 0xfe, 0xf3, + 0xc7, 0xf1, 0x2d, 0xb9, 0x20, 0x46, 0x31, 0x46, 0xbd, 0xe8, 0x70, 0x40, + 0xfe, 0xf3, 0x40, 0xb1, 0x70, 0xbd, 0x43, 0x69, 0x2d, 0xe9, 0xf7, 0x43, + 0x22, 0x2b, 0x05, 0x46, 0x0e, 0x46, 0x40, 0xf3, 0xa6, 0x80, 0xfe, 0xf3, + 0x1b, 0xf1, 0x00, 0x28, 0x00, 0xf0, 0x9f, 0x80, 0x07, 0x2e, 0x00, 0xf2, + 0x9e, 0x80, 0xab, 0x68, 0xb3, 0xf5, 0x02, 0x6f, 0x0b, 0xd0, 0x40, 0xf6, + 0x04, 0x02, 0x93, 0x42, 0x0a, 0xd1, 0xeb, 0x68, 0x0c, 0x2b, 0x94, 0xbf, + 0x4f, 0xf0, 0x00, 0x08, 0x4f, 0xf0, 0x01, 0x08, 0x04, 0xe0, 0x4f, 0xf0, + 0x01, 0x08, 0x01, 0xe0, 0x4f, 0xf0, 0x00, 0x08, 0x5f, 0xfa, 0x88, 0xf8, + 0xb8, 0xf1, 0x00, 0x0f, 0x0a, 0xd1, 0x28, 0x46, 0x4f, 0xf4, 0x00, 0x61, + 0x42, 0x46, 0xd5, 0xf8, 0xc8, 0x90, 0xfe, 0xf3, 0xfb, 0xf0, 0x04, 0x46, + 0x38, 0xb9, 0x79, 0xe0, 0xd5, 0xf8, 0x84, 0x40, 0x14, 0xf5, 0x40, 0x54, + 0x74, 0xd0, 0x4f, 0xf0, 0x00, 0x09, 0x03, 0x2e, 0x03, 0xd0, 0x28, 0x46, + 0x01, 0x21, 0xfe, 0xf3, 0x7d, 0xf1, 0xd4, 0xf8, 0x30, 0x31, 0x23, 0xf0, + 0x04, 0x03, 0xc4, 0xf8, 0x30, 0x31, 0x01, 0x23, 0x9e, 0x42, 0xc4, 0xf8, + 0x30, 0x31, 0x04, 0xd9, 0x04, 0x2e, 0x0c, 0xbf, 0x0d, 0x23, 0x09, 0x23, + 0x00, 0xe0, 0x0d, 0x23, 0xc4, 0xf8, 0x30, 0x31, 0xd4, 0xf8, 0x30, 0x31, + 0x01, 0x2e, 0x23, 0xf0, 0x01, 0x03, 0xc4, 0xf8, 0x30, 0x31, 0x01, 0xd9, + 0x04, 0x2e, 0x36, 0xd1, 0xff, 0x27, 0x00, 0x21, 0x4f, 0xf4, 0xe2, 0x72, + 0x3b, 0x46, 0x28, 0x46, 0x00, 0x97, 0xfd, 0xf3, 0x0d, 0xf7, 0x22, 0x23, + 0x00, 0x93, 0x00, 0x21, 0x4f, 0xf4, 0xee, 0x72, 0x3b, 0x46, 0x28, 0x46, + 0xfd, 0xf3, 0x04, 0xf7, 0x28, 0x23, 0x00, 0x93, 0x00, 0x21, 0x4f, 0xf4, + 0xe6, 0x72, 0x3b, 0x46, 0x28, 0x46, 0xfd, 0xf3, 0xfb, 0xf6, 0x81, 0x23, + 0x00, 0x93, 0x00, 0x21, 0x4f, 0xf4, 0xe8, 0x72, 0x3b, 0x46, 0x28, 0x46, + 0xfd, 0xf3, 0xf2, 0xf6, 0x01, 0x23, 0x00, 0x93, 0x00, 0x21, 0x4f, 0xf4, + 0xa4, 0x72, 0x4f, 0xf0, 0xff, 0x33, 0x28, 0x46, 0xfd, 0xf3, 0xe8, 0xf6, + 0x28, 0x46, 0x00, 0x21, 0x4f, 0xf4, 0xa6, 0x72, 0x4f, 0xf6, 0xff, 0x73, + 0x00, 0x97, 0xfd, 0xf3, 0xdf, 0xf6, 0xd4, 0xf8, 0x30, 0x31, 0x23, 0xf0, + 0x70, 0x03, 0x43, 0xea, 0x06, 0x16, 0xc4, 0xf8, 0x30, 0x61, 0xd4, 0xf8, + 0x30, 0x31, 0x23, 0xf0, 0x08, 0x03, 0xc4, 0xf8, 0x30, 0x31, 0xb8, 0xf1, + 0x00, 0x0f, 0x07, 0xd1, 0x28, 0x46, 0x49, 0x46, 0xfe, 0xf3, 0x94, 0xf0, + 0x02, 0xe0, 0x04, 0x46, 0x00, 0xe0, 0x00, 0x24, 0x20, 0x46, 0xbd, 0xe8, + 0xfe, 0x83, 0x00, 0x20, 0x70, 0x47, 0xff, 0xf7, 0x67, 0xbe, 0xff, 0xf7, + 0x62, 0xbe, 0x2d, 0xe9, 0xf0, 0x41, 0x04, 0x46, 0x0d, 0x46, 0x16, 0x46, + 0xfd, 0xf3, 0xb2, 0xf7, 0x07, 0x46, 0x18, 0xb9, 0x20, 0x46, 0x01, 0x21, + 0xfd, 0xf3, 0xea, 0xf7, 0x20, 0x46, 0x13, 0xf0, 0x73, 0xfd, 0x80, 0x46, + 0x90, 0xb1, 0xce, 0xb1, 0x00, 0x23, 0x2b, 0x80, 0x00, 0x26, 0x06, 0xf1, + 0x82, 0x01, 0x40, 0x46, 0xf4, 0xf3, 0xf6, 0xf5, 0xc3, 0xb2, 0xb3, 0x40, + 0x2a, 0x88, 0x01, 0x36, 0x13, 0x43, 0x05, 0x2e, 0x2b, 0x80, 0xf2, 0xd1, + 0x00, 0x25, 0x01, 0xe0, 0x6f, 0xf0, 0x1d, 0x05, 0x37, 0xb9, 0x20, 0x46, + 0x39, 0x46, 0xfd, 0xf3, 0xcb, 0xf7, 0x01, 0xe0, 0x6f, 0xf0, 0x19, 0x05, + 0x28, 0x46, 0xbd, 0xe8, 0xf0, 0x81, 0x07, 0xb5, 0x00, 0x23, 0x02, 0xa9, + 0x21, 0xf8, 0x02, 0x3d, 0x01, 0x22, 0xff, 0xf7, 0xc6, 0xff, 0xbd, 0xf8, + 0x06, 0x00, 0x0e, 0xbd, 0xd0, 0xf8, 0x6c, 0x32, 0x99, 0x42, 0x05, 0xd1, + 0x88, 0x79, 0xd0, 0xf1, 0x01, 0x00, 0x38, 0xbf, 0x00, 0x20, 0x70, 0x47, + 0x00, 0x20, 0x70, 0x47, 0x03, 0x68, 0x2d, 0xe9, 0xf0, 0x41, 0x1f, 0x68, + 0x04, 0x46, 0xbe, 0x68, 0x0d, 0x46, 0x90, 0x46, 0x30, 0x46, 0x21, 0x69, + 0x02, 0xf0, 0x50, 0xda, 0xb8, 0xf1, 0x00, 0x0f, 0x0a, 0xd0, 0x3b, 0x68, + 0x1b, 0x7e, 0x3b, 0xb1, 0x21, 0x69, 0x30, 0x46, 0x2a, 0x46, 0x01, 0x23, + 0xbd, 0xe8, 0xf0, 0x41, 0x02, 0xf0, 0xfa, 0x99, 0xbd, 0xe8, 0xf0, 0x81, + 0x2d, 0xe9, 0xf3, 0x41, 0x1f, 0x46, 0x03, 0x68, 0x04, 0x46, 0x01, 0x91, + 0x00, 0x92, 0x08, 0x9d, 0xd3, 0xf8, 0x00, 0x80, 0x09, 0xb1, 0x0d, 0x29, + 0x3e, 0xdd, 0x61, 0x68, 0x20, 0x46, 0x00, 0x22, 0xff, 0xf7, 0xd2, 0xff, + 0xe1, 0x68, 0x00, 0x26, 0x66, 0x60, 0x31, 0xb1, 0x23, 0x68, 0x22, 0x89, + 0x1b, 0x68, 0x58, 0x68, 0xf9, 0xf3, 0x6e, 0xf5, 0xe6, 0x60, 0x00, 0x9b, + 0x13, 0xb1, 0xb3, 0xf5, 0x96, 0x7f, 0x26, 0xdb, 0x40, 0x46, 0x29, 0x46, + 0xff, 0xf7, 0xb2, 0xff, 0x20, 0xb3, 0x01, 0x99, 0x51, 0xb1, 0x23, 0x68, + 0x1b, 0x68, 0x58, 0x68, 0xf9, 0xf3, 0x4c, 0xf5, 0xe0, 0x60, 0xf0, 0xb1, + 0x39, 0x46, 0x01, 0x9a, 0xf4, 0xf3, 0x9a, 0xf6, 0x01, 0xa9, 0x04, 0x22, + 0x65, 0x61, 0x04, 0xf1, 0x08, 0x00, 0xf4, 0xf3, 0x93, 0xf6, 0x20, 0x1d, + 0x69, 0x46, 0x04, 0x22, 0xf4, 0xf3, 0x8e, 0xf6, 0x00, 0x98, 0x70, 0xb1, + 0x20, 0x46, 0x61, 0x68, 0x01, 0x22, 0xff, 0xf7, 0x9d, 0xff, 0x00, 0x20, + 0x07, 0xe0, 0x6f, 0xf0, 0x1c, 0x00, 0x04, 0xe0, 0x6f, 0xf0, 0x01, 0x00, + 0x01, 0xe0, 0x6f, 0xf0, 0x1a, 0x00, 0xbd, 0xe8, 0xfc, 0x81, 0x2d, 0xe9, + 0xf0, 0x47, 0x86, 0xb0, 0x03, 0x68, 0x10, 0x9c, 0xdd, 0xf8, 0x44, 0xa0, + 0x16, 0x46, 0x02, 0xf0, 0x01, 0x02, 0x00, 0x92, 0x05, 0x46, 0x22, 0x46, + 0x18, 0x68, 0x53, 0x46, 0x13, 0x9f, 0x16, 0xf0, 0x11, 0xd8, 0x80, 0x46, + 0x00, 0x28, 0x40, 0xf0, 0x9d, 0x80, 0x02, 0x2e, 0x4c, 0xd0, 0x03, 0x2e, + 0x1a, 0xd0, 0x01, 0x2e, 0x40, 0xf0, 0x8b, 0x80, 0x21, 0x46, 0x04, 0x22, + 0x04, 0xa8, 0xf4, 0xf3, 0x59, 0xf6, 0x02, 0x22, 0x21, 0x1d, 0x05, 0xa8, + 0xf4, 0xf3, 0x54, 0xf6, 0x55, 0xf8, 0x10, 0x0b, 0x39, 0x46, 0xbd, 0xf8, + 0x14, 0x80, 0x04, 0x9e, 0x32, 0xf0, 0x8a, 0xd8, 0x41, 0x46, 0x00, 0x90, + 0x32, 0x46, 0x28, 0x46, 0xa3, 0x1d, 0x2b, 0xe0, 0x02, 0x22, 0x21, 0x46, + 0x0d, 0xf1, 0x16, 0x00, 0xf4, 0xf3, 0x40, 0xf6, 0x21, 0x1d, 0x04, 0x22, + 0x04, 0xa8, 0xf4, 0xf3, 0x3b, 0xf6, 0x02, 0x22, 0x05, 0xa8, 0x04, 0xf1, + 0x08, 0x01, 0xf4, 0xf3, 0x35, 0xf6, 0xbd, 0xf8, 0x16, 0x30, 0x01, 0x2b, + 0x60, 0xd1, 0xa3, 0x7a, 0x6a, 0x68, 0x93, 0x42, 0x5f, 0xda, 0x39, 0x46, + 0x4f, 0xf0, 0x18, 0x09, 0x28, 0x68, 0x09, 0xfb, 0x03, 0x59, 0xbd, 0xf8, + 0x14, 0x80, 0x04, 0x9e, 0x32, 0xf0, 0x60, 0xd8, 0x09, 0xf1, 0x10, 0x09, + 0x00, 0x90, 0x41, 0x46, 0x48, 0x46, 0x32, 0x46, 0x04, 0xf1, 0x0b, 0x03, + 0xff, 0xf7, 0x4a, 0xff, 0x80, 0x46, 0x4d, 0xe0, 0x0e, 0x9b, 0x6a, 0x68, + 0x1b, 0x68, 0x93, 0x42, 0x03, 0x93, 0x42, 0xda, 0x00, 0x2b, 0x40, 0xdb, + 0x01, 0x23, 0x06, 0xa9, 0xad, 0xf8, 0x16, 0x30, 0x0b, 0x23, 0x21, 0xf8, + 0x04, 0x3d, 0xa0, 0x1c, 0x32, 0x46, 0xf4, 0xf3, 0x03, 0xf6, 0x0d, 0xf1, + 0x18, 0x09, 0x0d, 0xf1, 0x16, 0x01, 0x32, 0x46, 0x20, 0x46, 0xf4, 0xf3, + 0xfb, 0xf5, 0x59, 0xf8, 0x0c, 0x1d, 0x18, 0x27, 0x01, 0x31, 0x07, 0xfb, + 0x01, 0x51, 0x32, 0x46, 0x04, 0xf1, 0x08, 0x00, 0xf4, 0xf3, 0xf0, 0xf5, + 0x01, 0x22, 0x49, 0x46, 0x04, 0xf1, 0x0a, 0x00, 0xf4, 0xf3, 0xea, 0xf5, + 0x03, 0x99, 0x04, 0x22, 0x07, 0xfb, 0x01, 0x51, 0x20, 0x1d, 0x14, 0x31, + 0xf4, 0xf3, 0xe2, 0xf5, 0x03, 0x9b, 0x01, 0x33, 0x5f, 0x43, 0xea, 0x5b, + 0xeb, 0x19, 0x02, 0xf1, 0x0b, 0x01, 0x8a, 0x45, 0x0e, 0xd3, 0x04, 0xf1, + 0x0b, 0x00, 0x59, 0x68, 0xf4, 0xf3, 0xd4, 0xf5, 0x0a, 0xe0, 0x6f, 0xf0, + 0x16, 0x08, 0x07, 0xe0, 0x6f, 0xf0, 0x24, 0x08, 0x04, 0xe0, 0x6f, 0xf0, + 0x01, 0x08, 0x01, 0xe0, 0x6f, 0xf0, 0x0d, 0x08, 0x40, 0x46, 0x06, 0xb0, + 0xbd, 0xe8, 0xf0, 0x87, 0xf7, 0xb5, 0x03, 0x68, 0x07, 0x46, 0x1d, 0x68, + 0x95, 0xf8, 0x70, 0x22, 0x00, 0x2a, 0x2d, 0xd0, 0x02, 0x89, 0x46, 0x69, + 0x3a, 0xb9, 0x28, 0x46, 0x06, 0xf1, 0xbc, 0x01, 0x13, 0x46, 0x00, 0x92, + 0x1a, 0xf0, 0x26, 0xde, 0x22, 0xe0, 0x99, 0x89, 0x68, 0x68, 0x51, 0x18, + 0xf9, 0xf3, 0xb0, 0xf4, 0x3b, 0x68, 0x04, 0x46, 0x18, 0xb9, 0x9a, 0x68, + 0x01, 0x32, 0x9a, 0x60, 0x16, 0xe0, 0x9b, 0x89, 0xa2, 0x8a, 0x00, 0x69, + 0xf9, 0x68, 0xc0, 0x18, 0xd3, 0x1a, 0xa3, 0x82, 0x3a, 0x89, 0x20, 0x61, + 0xf4, 0xf3, 0x9a, 0xf5, 0xe3, 0x8d, 0xb2, 0x68, 0x43, 0xf0, 0x40, 0x03, + 0x28, 0x46, 0x21, 0x46, 0xe3, 0x85, 0x03, 0xb0, 0xbd, 0xe8, 0xf0, 0x40, + 0x1a, 0xf0, 0xa4, 0x9e, 0x03, 0xb0, 0xf0, 0xbd, 0x38, 0xb5, 0x05, 0x46, + 0x00, 0x24, 0x0b, 0xe0, 0x18, 0x20, 0x00, 0xfb, 0x04, 0x50, 0x10, 0x30, + 0x41, 0x68, 0x21, 0xb1, 0x03, 0x69, 0x13, 0xb1, 0x01, 0x22, 0xff, 0xf7, + 0x93, 0xfe, 0x01, 0x34, 0x6b, 0x68, 0x9c, 0x42, 0xf0, 0xdb, 0x00, 0x20, + 0x38, 0xbd, 0xf8, 0xb5, 0x00, 0x24, 0x07, 0x46, 0x06, 0x46, 0x25, 0x46, + 0x08, 0xe0, 0x3b, 0x68, 0x31, 0x6a, 0x98, 0x68, 0x02, 0xf0, 0xde, 0xd8, + 0x00, 0xb9, 0x01, 0x35, 0x01, 0x34, 0x18, 0x36, 0x7b, 0x68, 0x9c, 0x42, + 0xf3, 0xdb, 0x28, 0x46, 0xf8, 0xbd, 0x00, 0x00, 0x10, 0xb5, 0x8a, 0x6b, + 0x00, 0x23, 0x09, 0xe0, 0xc8, 0x18, 0x90, 0xf8, 0x3c, 0x00, 0x06, 0x4c, + 0x00, 0xf0, 0x7f, 0x00, 0x20, 0x56, 0x00, 0x28, 0x04, 0xdb, 0x01, 0x33, + 0x93, 0x42, 0xf3, 0xd1, 0x00, 0x20, 0x10, 0xbd, 0x01, 0x20, 0x10, 0xbd, + 0x40, 0x1b, 0x86, 0x00, 0x02, 0x29, 0x2d, 0xe9, 0xf8, 0x4f, 0x05, 0x46, + 0x0c, 0x46, 0x16, 0x46, 0x9b, 0x46, 0x14, 0xbf, 0x4f, 0xf0, 0xff, 0x39, + 0x4f, 0xf0, 0x00, 0x09, 0x14, 0xbf, 0x00, 0x27, 0x01, 0x27, 0x4f, 0xf0, + 0x00, 0x08, 0x28, 0xe0, 0x02, 0x2c, 0x14, 0xbf, 0x4f, 0xf0, 0xff, 0x33, + 0x00, 0x23, 0x99, 0x45, 0x11, 0xd0, 0x02, 0x2c, 0xc9, 0xeb, 0x07, 0x02, + 0x08, 0xd1, 0x04, 0x2e, 0x08, 0xd0, 0x06, 0x2e, 0x06, 0xd0, 0x08, 0x2e, + 0x14, 0xbf, 0x04, 0x23, 0x00, 0x23, 0x02, 0xe0, 0x04, 0x23, 0x00, 0xe0, + 0x00, 0x23, 0x9a, 0x42, 0x0e, 0xdd, 0x47, 0xf4, 0x2c, 0x5a, 0x1f, 0xfa, + 0x8a, 0xfa, 0xd5, 0xf8, 0x5c, 0x01, 0x51, 0x46, 0x38, 0xf0, 0x2a, 0xdf, + 0x20, 0xb1, 0x2b, 0xf8, 0x18, 0xa0, 0xb9, 0x46, 0x08, 0xf1, 0x01, 0x08, + 0x01, 0x37, 0x02, 0x2c, 0x0c, 0xbf, 0x0e, 0x23, 0x00, 0x23, 0x9f, 0x42, + 0x02, 0xdc, 0xb8, 0xf1, 0x1f, 0x0f, 0xcd, 0xd9, 0x0a, 0x9b, 0xc3, 0xf8, + 0x00, 0x80, 0xbd, 0xe8, 0xf8, 0x8f, 0x2d, 0xe9, 0xf7, 0x4f, 0x1d, 0x46, + 0x0c, 0x9b, 0x01, 0x92, 0xd0, 0xf8, 0x00, 0x80, 0x46, 0x7b, 0x0c, 0x46, + 0x00, 0x93, 0x00, 0x27, 0xef, 0xe0, 0x07, 0x22, 0x00, 0x21, 0x20, 0x46, + 0xf4, 0xf3, 0x56, 0xf5, 0x00, 0x9b, 0x02, 0x2e, 0x33, 0xf8, 0x02, 0x2b, + 0x5f, 0xfa, 0x82, 0xf9, 0x00, 0x93, 0x84, 0xf8, 0x00, 0x90, 0x08, 0xd1, + 0x04, 0x2d, 0x08, 0xd0, 0x06, 0x2d, 0x06, 0xd0, 0x08, 0x2d, 0x14, 0xbf, + 0x02, 0x23, 0x00, 0x23, 0x02, 0xe0, 0x02, 0x23, 0x00, 0xe0, 0x00, 0x23, + 0xa6, 0xf1, 0x02, 0x0a, 0xda, 0xf1, 0x00, 0x02, 0xc3, 0xeb, 0x09, 0x03, + 0x42, 0xeb, 0x0a, 0x02, 0x93, 0x42, 0x10, 0xdb, 0x02, 0x2e, 0x08, 0xd1, + 0x04, 0x2d, 0x08, 0xd0, 0x06, 0x2d, 0x06, 0xd0, 0x08, 0x2d, 0x14, 0xbf, + 0x02, 0x23, 0x00, 0x23, 0x02, 0xe0, 0x02, 0x23, 0x00, 0xe0, 0x00, 0x23, + 0xc3, 0xeb, 0x09, 0x09, 0x11, 0xe0, 0xa6, 0xf1, 0x02, 0x0c, 0xdc, 0xf1, + 0x00, 0x09, 0x49, 0xeb, 0x0c, 0x09, 0x07, 0xe0, 0xd8, 0xf8, 0x5c, 0x01, + 0x49, 0x46, 0x38, 0xf0, 0x85, 0xde, 0x20, 0xb9, 0x09, 0xf1, 0x01, 0x09, + 0x23, 0x78, 0x99, 0x45, 0xf4, 0xd9, 0x02, 0x2e, 0x94, 0xf8, 0x00, 0xa0, + 0x08, 0xd1, 0x04, 0x2d, 0x08, 0xd0, 0x06, 0x2d, 0x06, 0xd0, 0x08, 0x2d, + 0x14, 0xbf, 0x02, 0x23, 0x00, 0x23, 0x02, 0xe0, 0x02, 0x23, 0x00, 0xe0, + 0x00, 0x23, 0x53, 0x44, 0x02, 0x2e, 0x0c, 0xbf, 0x0e, 0x22, 0x00, 0x22, + 0x93, 0x42, 0x0f, 0xdc, 0x02, 0x2e, 0x08, 0xd1, 0x04, 0x2d, 0x08, 0xd0, + 0x06, 0x2d, 0x06, 0xd0, 0x08, 0x2d, 0x14, 0xbf, 0x02, 0x23, 0x00, 0x23, + 0x02, 0xe0, 0x02, 0x23, 0x00, 0xe0, 0x00, 0x23, 0x9a, 0x44, 0x11, 0xe0, + 0x02, 0x2e, 0x0c, 0xbf, 0x4f, 0xf0, 0x0e, 0x0a, 0x4f, 0xf0, 0x00, 0x0a, + 0x07, 0xe0, 0xd8, 0xf8, 0x5c, 0x01, 0x51, 0x46, 0x38, 0xf0, 0x4c, 0xde, + 0x20, 0xb9, 0x0a, 0xf1, 0xff, 0x3a, 0x23, 0x78, 0x9a, 0x45, 0xf4, 0xd2, + 0x4f, 0xf0, 0x00, 0x0b, 0x64, 0xe0, 0x0b, 0xf1, 0x02, 0x02, 0x53, 0xf8, + 0x22, 0x10, 0xb1, 0xf8, 0x06, 0xc0, 0x48, 0x8e, 0x1c, 0xf0, 0x20, 0x0c, + 0xc3, 0xb2, 0x0d, 0xd0, 0x00, 0xf4, 0x40, 0x72, 0xb2, 0xf5, 0x80, 0x7f, + 0x02, 0xd1, 0x9a, 0x1c, 0x02, 0x3b, 0x06, 0xe0, 0xb2, 0xf5, 0x00, 0x7f, + 0x02, 0xd1, 0x9a, 0x1e, 0x02, 0x33, 0x00, 0xe0, 0x1a, 0x46, 0x4b, 0x45, + 0x01, 0xd3, 0x53, 0x45, 0x03, 0xd9, 0x4a, 0x45, 0x42, 0xd3, 0x52, 0x45, + 0x40, 0xd8, 0xbc, 0xf1, 0x00, 0x0f, 0x16, 0xd0, 0x4b, 0x45, 0x14, 0xd3, + 0x53, 0x45, 0x12, 0xd8, 0x00, 0xf4, 0x40, 0x70, 0xb0, 0xf5, 0x80, 0x7f, + 0x05, 0xd1, 0x20, 0x79, 0xff, 0x28, 0x0a, 0xd0, 0x01, 0x30, 0x20, 0x71, + 0x07, 0xe0, 0xb0, 0xf5, 0x00, 0x7f, 0x04, 0xd1, 0x60, 0x79, 0xff, 0x28, + 0x01, 0xd0, 0x01, 0x30, 0x60, 0x71, 0xc8, 0x88, 0x80, 0x06, 0x0b, 0xd5, + 0x4a, 0x45, 0x09, 0xd3, 0x52, 0x45, 0x07, 0xd8, 0x9a, 0x42, 0x05, 0xd0, + 0xa3, 0x79, 0xff, 0x2b, 0x1a, 0xd0, 0x01, 0x33, 0xa3, 0x71, 0x17, 0xe0, + 0x23, 0x78, 0x0e, 0x2b, 0x0f, 0xd8, 0x40, 0x46, 0xff, 0xf7, 0xc0, 0xfe, + 0x28, 0xb1, 0xe3, 0x78, 0xff, 0x2b, 0x0d, 0xd0, 0x01, 0x33, 0xe3, 0x70, + 0x0a, 0xe0, 0xa3, 0x78, 0xff, 0x2b, 0x07, 0xd0, 0x01, 0x33, 0xa3, 0x70, + 0x04, 0xe0, 0x63, 0x78, 0xff, 0x2b, 0x01, 0xd0, 0x01, 0x33, 0x63, 0x70, + 0x0b, 0xf1, 0x01, 0x0b, 0xd8, 0xf8, 0x18, 0x35, 0x1a, 0x68, 0x93, 0x45, + 0x95, 0xd3, 0x01, 0x37, 0x07, 0x34, 0x0d, 0x9b, 0x9f, 0x42, 0x04, 0xda, + 0x01, 0x9a, 0x13, 0x68, 0x9f, 0x42, 0xff, 0xf6, 0x08, 0xaf, 0x01, 0x9b, + 0x1f, 0x60, 0xbd, 0xe8, 0xfe, 0x8f, 0x2d, 0xe9, 0xf0, 0x47, 0x03, 0xf4, + 0x40, 0x78, 0x04, 0x46, 0x1d, 0x46, 0xd8, 0xb2, 0xa8, 0xf5, 0x00, 0x73, + 0xd3, 0xf1, 0x00, 0x08, 0x48, 0xeb, 0x03, 0x08, 0xa0, 0xf1, 0x02, 0x0c, + 0x86, 0x1c, 0xb8, 0xf1, 0x00, 0x0f, 0x01, 0xd0, 0x33, 0x46, 0x01, 0xe0, + 0x63, 0x46, 0xb4, 0x46, 0x00, 0x27, 0x37, 0xe0, 0x0e, 0x78, 0xa0, 0xf1, + 0x05, 0x09, 0x4e, 0x45, 0x30, 0xdb, 0x00, 0xf1, 0x05, 0x09, 0x4e, 0x45, + 0x2c, 0xdc, 0x91, 0xf8, 0x02, 0x90, 0xb9, 0xf1, 0x00, 0x0f, 0x13, 0xd1, + 0x91, 0xf8, 0x03, 0xa0, 0xba, 0xf1, 0x00, 0x0f, 0x0e, 0xd1, 0x91, 0xf8, + 0x04, 0xa0, 0xba, 0xf1, 0x00, 0x0f, 0x09, 0xd1, 0x91, 0xf8, 0x05, 0xa0, + 0xba, 0xf1, 0x00, 0x0f, 0x04, 0xd1, 0x91, 0xf8, 0x06, 0xa0, 0xba, 0xf1, + 0x00, 0x0f, 0x13, 0xd0, 0x9e, 0x42, 0x06, 0xd1, 0x8e, 0x79, 0x3e, 0xbb, + 0xb8, 0xf1, 0x00, 0x0f, 0x0a, 0xd0, 0x0e, 0x79, 0x09, 0xe0, 0x66, 0x45, + 0x20, 0xd1, 0xb9, 0xf1, 0x00, 0x0f, 0x1d, 0xd1, 0xce, 0x78, 0xde, 0xb9, + 0x0e, 0x79, 0xce, 0xb9, 0x4e, 0x79, 0xbe, 0xb9, 0x01, 0x37, 0x07, 0x31, + 0x97, 0x42, 0xc5, 0xdb, 0xd4, 0xf8, 0xfc, 0x34, 0x1b, 0x78, 0x63, 0xb1, + 0x07, 0xe0, 0x20, 0x46, 0x00, 0x21, 0x27, 0xf0, 0xdf, 0xd8, 0x20, 0x46, + 0x27, 0xf0, 0xd2, 0xd8, 0x03, 0xe0, 0x20, 0x46, 0x01, 0x21, 0x27, 0xf0, + 0xd7, 0xd8, 0x28, 0x46, 0xbd, 0xe8, 0xf0, 0x87, 0x43, 0xf4, 0x30, 0x65, + 0xad, 0xb2, 0x0e, 0x2b, 0xcc, 0xbf, 0x4f, 0xf4, 0x80, 0x53, 0x4f, 0xf4, + 0x00, 0x53, 0x1d, 0x43, 0xd4, 0xf8, 0xfc, 0x34, 0x1b, 0x78, 0x00, 0x2b, + 0xed, 0xd0, 0xe0, 0xe7, 0x2d, 0xe9, 0xf0, 0x43, 0x05, 0x68, 0xdd, 0xb0, + 0x29, 0x6b, 0x06, 0x46, 0x47, 0x7b, 0x09, 0x89, 0x5a, 0x93, 0x00, 0x24, + 0x00, 0xe0, 0x04, 0x21, 0x4f, 0xf0, 0x00, 0x0c, 0x5a, 0x9b, 0x60, 0x46, + 0x09, 0xe0, 0x0c, 0xf1, 0x07, 0x0c, 0x02, 0xeb, 0x0c, 0x08, 0x18, 0xf8, + 0x07, 0x8c, 0xb8, 0xf1, 0x05, 0x0f, 0x03, 0xd8, 0x01, 0x30, 0x98, 0x42, + 0xf3, 0xdb, 0x00, 0xe0, 0x04, 0x46, 0x08, 0x29, 0x00, 0xf2, 0xad, 0x80, + 0x01, 0xa0, 0x50, 0xf8, 0x21, 0xf0, 0x00, 0xbf, 0xeb, 0xd8, 0x00, 0x00, + 0x0f, 0xda, 0x00, 0x00, 0xe1, 0xd8, 0x00, 0x00, 0x0f, 0xda, 0x00, 0x00, + 0x85, 0xd9, 0x00, 0x00, 0x0f, 0xda, 0x00, 0x00, 0x0f, 0xda, 0x00, 0x00, + 0x0f, 0xda, 0x00, 0x00, 0x87, 0xd8, 0x00, 0x00, 0x00, 0x25, 0x4f, 0xf6, + 0xff, 0x70, 0x29, 0x46, 0x14, 0xe0, 0x4f, 0xf6, 0xff, 0x70, 0x00, 0x21, + 0x0d, 0x46, 0x33, 0xe0, 0x0e, 0x19, 0x96, 0xfb, 0xf3, 0xf7, 0x03, 0xfb, + 0x17, 0x66, 0x02, 0xeb, 0xc6, 0x07, 0xbe, 0x1b, 0xb7, 0x78, 0x27, 0xb9, + 0xf7, 0x78, 0x87, 0x42, 0x3c, 0xbf, 0x35, 0x78, 0x38, 0x46, 0x01, 0x31, + 0x99, 0x42, 0xed, 0xdb, 0x00, 0x2d, 0xe8, 0xd0, 0x45, 0xf4, 0x30, 0x60, + 0x0e, 0x2d, 0x8c, 0xbf, 0x4f, 0xf4, 0x80, 0x55, 0x4f, 0xf4, 0x00, 0x55, + 0x28, 0x43, 0x6f, 0xe0, 0x2e, 0x19, 0x96, 0xfb, 0xf3, 0xf7, 0x03, 0xfb, + 0x17, 0x67, 0xfe, 0x00, 0xf7, 0x1b, 0xd6, 0x19, 0x96, 0xf8, 0x01, 0x90, + 0x96, 0xf8, 0x02, 0x80, 0x96, 0xf8, 0x03, 0xc0, 0x09, 0xeb, 0x08, 0x06, + 0x66, 0x44, 0x86, 0x42, 0xbc, 0xbf, 0xb0, 0xb2, 0xd1, 0x5d, 0x01, 0x35, + 0x9d, 0x42, 0xe7, 0xdb, 0x31, 0xb9, 0x94, 0xfb, 0xf3, 0xf1, 0x03, 0xfb, + 0x11, 0x44, 0xe3, 0x00, 0x1c, 0x1b, 0x11, 0x5d, 0x0e, 0x29, 0x8c, 0xbf, + 0x4f, 0xf4, 0x80, 0x50, 0x4f, 0xf4, 0x00, 0x50, 0x01, 0x43, 0x41, 0xf4, + 0x30, 0x60, 0x45, 0xe0, 0x02, 0x2f, 0x42, 0xd1, 0x00, 0x23, 0x5b, 0x93, + 0x5b, 0xab, 0x00, 0x93, 0x28, 0x46, 0x39, 0x46, 0x3a, 0x46, 0x3a, 0xab, + 0xff, 0xf7, 0xa2, 0xfd, 0xd5, 0xf8, 0x18, 0x07, 0x38, 0xb3, 0xd5, 0xf8, + 0x20, 0xe7, 0xbe, 0xf1, 0x00, 0x0f, 0x22, 0xd0, 0x5b, 0x99, 0x00, 0x23, + 0x13, 0xe0, 0x00, 0x22, 0x0d, 0xf5, 0x94, 0x7c, 0x30, 0xf8, 0x13, 0x80, + 0x32, 0xf8, 0x0c, 0xc0, 0xc4, 0x45, 0x06, 0xd1, 0x0d, 0xf5, 0xb8, 0x79, + 0x09, 0xeb, 0x41, 0x08, 0x28, 0xf8, 0x88, 0xcc, 0x01, 0x31, 0x02, 0x32, + 0x40, 0x2a, 0xed, 0xd1, 0x01, 0x33, 0x73, 0x45, 0xe9, 0xdb, 0x20, 0x23, + 0x0d, 0x48, 0x5a, 0x93, 0x5b, 0x91, 0x01, 0xf0, 0xfd, 0xfe, 0x3a, 0xab, + 0x00, 0x93, 0x5b, 0x9b, 0x03, 0xe0, 0x20, 0x23, 0x4a, 0xaa, 0x5a, 0x93, + 0x00, 0x92, 0x01, 0x93, 0x02, 0xa9, 0x5a, 0xaa, 0x30, 0x46, 0x02, 0x23, + 0xff, 0xf7, 0xb5, 0xfd, 0x02, 0xaa, 0x02, 0x21, 0x3c, 0xe7, 0x00, 0x20, + 0x5d, 0xb0, 0xbd, 0xe8, 0xf0, 0x83, 0x00, 0xbf, 0x14, 0xdc, 0x01, 0x00, + 0x70, 0xb5, 0x05, 0x46, 0xbc, 0xb0, 0x04, 0x68, 0x0e, 0x46, 0x09, 0xb1, + 0x08, 0x29, 0x2c, 0xd1, 0x20, 0x23, 0xd4, 0xf8, 0x18, 0x27, 0x3b, 0x93, + 0x23, 0x6b, 0x28, 0x46, 0x1b, 0x89, 0x00, 0x92, 0xd4, 0xf8, 0x20, 0x27, + 0x03, 0xa9, 0x01, 0x92, 0x3b, 0xaa, 0xff, 0xf7, 0x94, 0xfd, 0x6b, 0x7b, + 0x02, 0x2b, 0x12, 0xd1, 0xd4, 0xf8, 0xfc, 0x34, 0x1b, 0x78, 0x73, 0xb1, + 0xd4, 0xf8, 0x34, 0x37, 0xb3, 0xf8, 0xa4, 0x33, 0x03, 0xf4, 0x40, 0x62, + 0xb2, 0xf5, 0x40, 0x6f, 0x05, 0xd1, 0x20, 0x46, 0x03, 0xa9, 0x3b, 0x9a, + 0xff, 0xf7, 0x87, 0xfe, 0x05, 0xe0, 0x28, 0x46, 0x00, 0x21, 0x03, 0xaa, + 0x3b, 0x9b, 0xff, 0xf7, 0xf7, 0xfe, 0xa4, 0xf8, 0x16, 0x07, 0x6b, 0x68, + 0x13, 0xb1, 0xa8, 0x68, 0x31, 0x46, 0x98, 0x47, 0xd4, 0xf8, 0x18, 0x17, + 0xd4, 0xf8, 0x1c, 0x27, 0x60, 0x68, 0xf9, 0xf3, 0x29, 0xf1, 0x00, 0x23, + 0xc4, 0xf8, 0x18, 0x37, 0x60, 0x68, 0x29, 0x46, 0x10, 0x22, 0xf9, 0xf3, + 0x21, 0xf1, 0x3c, 0xb0, 0x70, 0xbd, 0x00, 0x00, 0x2d, 0xe9, 0xf0, 0x47, + 0x0d, 0x46, 0x4f, 0xf0, 0x00, 0x08, 0x40, 0x21, 0x9a, 0xb0, 0x04, 0x46, + 0xc0, 0xf8, 0x20, 0x87, 0xc0, 0xf8, 0x1c, 0x17, 0x40, 0x68, 0x1f, 0x46, + 0x22, 0x9e, 0xf9, 0xf3, 0xfd, 0xf0, 0x03, 0x46, 0xc4, 0xf8, 0x18, 0x07, + 0x00, 0x28, 0x7d, 0xd0, 0x2a, 0x68, 0x62, 0xb9, 0x20, 0x22, 0xc4, 0xf8, + 0x20, 0x27, 0x22, 0x6b, 0x04, 0xf5, 0xe4, 0x61, 0x12, 0x89, 0x20, 0x46, + 0x00, 0x91, 0x31, 0x46, 0xff, 0xf7, 0xf2, 0xfc, 0x25, 0xe0, 0x20, 0x2a, + 0x6f, 0xd8, 0xa9, 0x46, 0x1e, 0xe0, 0x59, 0xf8, 0x04, 0x3f, 0xd4, 0xf8, + 0x5c, 0x01, 0x1f, 0xfa, 0x83, 0xfa, 0x51, 0x46, 0x38, 0xf0, 0x42, 0xdc, + 0x00, 0x28, 0x62, 0xd0, 0xb8, 0xf1, 0x00, 0x0f, 0x05, 0xd0, 0x19, 0xf8, + 0x04, 0x3c, 0x5f, 0xfa, 0x8a, 0xf2, 0x9a, 0x42, 0x59, 0xd9, 0xd4, 0xf8, + 0x20, 0x37, 0xd4, 0xf8, 0x18, 0x27, 0x08, 0xf1, 0x01, 0x08, 0x22, 0xf8, + 0x13, 0xa0, 0x01, 0x33, 0xc4, 0xf8, 0x20, 0x37, 0x2b, 0x68, 0x98, 0x45, + 0xdd, 0xd3, 0xd4, 0xf8, 0x20, 0x37, 0x00, 0x2b, 0x47, 0xd0, 0x60, 0x68, + 0x10, 0x21, 0xf9, 0xf3, 0xbb, 0xf0, 0x05, 0x46, 0x00, 0x28, 0x43, 0xd0, + 0x25, 0x9b, 0x4f, 0xf0, 0x00, 0x08, 0x83, 0x60, 0x9d, 0xf8, 0x8c, 0x30, + 0x46, 0x73, 0x11, 0xae, 0x83, 0x73, 0x24, 0x22, 0xc0, 0xf8, 0x04, 0x80, + 0x04, 0x60, 0x80, 0xf8, 0x0c, 0x80, 0x41, 0x46, 0x30, 0x46, 0xf4, 0xf3, + 0x5d, 0xf2, 0x4f, 0xf0, 0xff, 0x33, 0x02, 0x93, 0x03, 0x93, 0x04, 0x93, + 0x05, 0x93, 0xd4, 0xf8, 0x18, 0x37, 0xc8, 0xeb, 0x07, 0x02, 0x06, 0x93, + 0xd4, 0xf8, 0x20, 0x37, 0x57, 0x42, 0x07, 0x93, 0x19, 0x4b, 0x47, 0xeb, + 0x02, 0x07, 0x0a, 0x93, 0x03, 0x23, 0x0c, 0x93, 0x20, 0x46, 0x02, 0x21, + 0x16, 0x4a, 0x01, 0x23, 0x00, 0x96, 0x01, 0x97, 0xcd, 0xf8, 0x20, 0x80, + 0xcd, 0xf8, 0x24, 0x80, 0x0b, 0x95, 0xcd, 0xf8, 0x34, 0x80, 0xcd, 0xf8, + 0x38, 0x80, 0x19, 0xf0, 0x93, 0xd9, 0x06, 0x46, 0xa8, 0xb9, 0x24, 0x9b, + 0x6b, 0x60, 0x12, 0xe0, 0x6f, 0xf0, 0x15, 0x06, 0x04, 0xe0, 0x6f, 0xf0, + 0x01, 0x06, 0x01, 0xe0, 0x6f, 0xf0, 0x1a, 0x06, 0xd4, 0xf8, 0x18, 0x17, + 0x39, 0xb1, 0x60, 0x68, 0xd4, 0xf8, 0x1c, 0x27, 0xf9, 0xf3, 0x7a, 0xf0, + 0x00, 0x23, 0xc4, 0xf8, 0x18, 0x37, 0x30, 0x46, 0x1a, 0xb0, 0xbd, 0xe8, + 0xf0, 0x87, 0x00, 0xbf, 0x1d, 0xda, 0x00, 0x00, 0x2c, 0x9e, 0x85, 0x00, + 0x10, 0xb5, 0x90, 0xf8, 0x14, 0x37, 0x88, 0xb0, 0x04, 0x46, 0x00, 0x2b, + 0x3e, 0xd0, 0xd0, 0xf8, 0x68, 0x31, 0x9b, 0x79, 0x00, 0x2b, 0x64, 0xd1, + 0x80, 0xf8, 0x14, 0x37, 0x03, 0x68, 0x1b, 0x7e, 0x00, 0x2b, 0x5e, 0xd0, + 0xb0, 0xf8, 0x16, 0x37, 0x00, 0x2b, 0x5a, 0xd0, 0x03, 0x6b, 0x18, 0x69, + 0x03, 0xf0, 0x3c, 0xfc, 0xb4, 0xf8, 0x16, 0x17, 0x88, 0x42, 0x52, 0xd0, + 0x20, 0x46, 0x1b, 0xf0, 0xa5, 0xd8, 0x20, 0x46, 0x01, 0xf0, 0x6e, 0xfd, + 0x20, 0x46, 0xb4, 0xf8, 0x16, 0x17, 0x1a, 0xf0, 0xe3, 0xde, 0x23, 0x68, + 0x93, 0xf8, 0x2f, 0x30, 0x6b, 0xb1, 0xd4, 0xf8, 0x6c, 0x32, 0x20, 0x46, + 0xd3, 0xf8, 0xd4, 0x12, 0x38, 0x31, 0x15, 0xf0, 0x8f, 0xdd, 0x01, 0x46, + 0xc4, 0xf8, 0xac, 0x06, 0x20, 0x46, 0x0e, 0xf0, 0x27, 0xde, 0x20, 0x46, + 0x1d, 0xf0, 0x3e, 0xd9, 0x20, 0x46, 0x00, 0x21, 0x1d, 0xf0, 0x44, 0xdb, + 0x20, 0x46, 0x14, 0xf0, 0xb1, 0xd9, 0x2a, 0xe0, 0x03, 0x68, 0x1b, 0x7e, + 0x3b, 0xb3, 0xd0, 0xf8, 0x68, 0x31, 0x9b, 0x79, 0x1b, 0xbb, 0xd0, 0xf8, + 0x00, 0x05, 0x07, 0xa9, 0x47, 0xf0, 0x0e, 0xda, 0x02, 0xe0, 0x1b, 0x7e, + 0x99, 0x07, 0x1a, 0xd4, 0x07, 0xa8, 0x47, 0xf0, 0x0f, 0xda, 0x03, 0x46, + 0x00, 0x28, 0xf6, 0xd1, 0x03, 0xe0, 0x01, 0x23, 0x84, 0xf8, 0x14, 0x37, + 0x0f, 0xe0, 0x22, 0x6b, 0x08, 0xa9, 0x12, 0x68, 0x41, 0xf8, 0x0c, 0x0d, + 0x00, 0x92, 0x03, 0x22, 0x01, 0x92, 0x02, 0x90, 0x03, 0x90, 0x01, 0x22, + 0x20, 0x46, 0xff, 0xf7, 0xe1, 0xfe, 0x00, 0x28, 0xeb, 0xd0, 0x08, 0xb0, + 0x10, 0xbd, 0x00, 0x20, 0x70, 0x47, 0x00, 0x20, 0x70, 0x47, 0x00, 0x20, + 0x70, 0x47, 0x01, 0x23, 0x80, 0xf8, 0x7a, 0x30, 0x70, 0x47, 0x70, 0xb5, + 0x90, 0xe8, 0x18, 0x00, 0x0d, 0x46, 0x58, 0x68, 0x0c, 0x21, 0xf8, 0xf3, + 0xd9, 0xf7, 0x06, 0x46, 0x30, 0xb1, 0x00, 0x21, 0x0c, 0x22, 0xf4, 0xf3, + 0x8b, 0xf1, 0x2e, 0x51, 0x00, 0x20, 0x70, 0xbd, 0x6f, 0xf0, 0x1a, 0x00, + 0x70, 0xbd, 0x00, 0x00, 0xf8, 0xb5, 0x83, 0x68, 0x06, 0x46, 0x5c, 0x68, + 0x03, 0x68, 0x0f, 0x59, 0x0d, 0x46, 0x58, 0x68, 0x4f, 0xf4, 0x84, 0x71, + 0xf8, 0xf3, 0xc0, 0xf7, 0x78, 0x60, 0x00, 0x28, 0x2d, 0xd0, 0x2b, 0x59, + 0x00, 0x21, 0x58, 0x68, 0x4f, 0xf4, 0x84, 0x72, 0xf4, 0xf3, 0x6e, 0xf1, + 0x33, 0x68, 0xc4, 0x21, 0x58, 0x68, 0x2f, 0x59, 0xf8, 0xf3, 0xb0, 0xf7, + 0xb8, 0x60, 0xf0, 0xb1, 0x2b, 0x59, 0x00, 0x21, 0x98, 0x68, 0xc4, 0x22, + 0xf4, 0xf3, 0x60, 0xf1, 0x2b, 0x59, 0x28, 0x49, 0x9f, 0x68, 0x33, 0x68, + 0x32, 0x46, 0x3b, 0x60, 0x98, 0x68, 0x00, 0x23, 0x01, 0xf0, 0x92, 0xdc, + 0xb8, 0x66, 0x60, 0xb1, 0x2b, 0x59, 0x23, 0x49, 0x9f, 0x68, 0x33, 0x68, + 0x32, 0x46, 0x98, 0x68, 0x00, 0x23, 0x01, 0xf0, 0x87, 0xdc, 0xc7, 0xf8, + 0xc0, 0x00, 0x00, 0x28, 0x33, 0xd1, 0x2b, 0x59, 0x9b, 0x68, 0x0b, 0xb3, + 0x99, 0x6e, 0x39, 0xb1, 0x33, 0x68, 0x98, 0x68, 0x01, 0xf0, 0x5e, 0xdc, + 0x2b, 0x59, 0x00, 0x22, 0x9b, 0x68, 0x9a, 0x66, 0x2b, 0x59, 0x9b, 0x68, + 0xd3, 0xf8, 0xc0, 0x10, 0x41, 0xb1, 0x33, 0x68, 0x98, 0x68, 0x01, 0xf0, + 0x51, 0xdc, 0x2b, 0x59, 0x00, 0x22, 0x9b, 0x68, 0xc3, 0xf8, 0xc0, 0x20, + 0x32, 0x68, 0x2b, 0x59, 0x50, 0x68, 0x99, 0x68, 0xc4, 0x22, 0xf8, 0xf3, + 0x7d, 0xf7, 0x2b, 0x59, 0x00, 0x22, 0x9a, 0x60, 0x2b, 0x59, 0x59, 0x68, + 0x69, 0xb1, 0x33, 0x68, 0x4f, 0xf4, 0x84, 0x72, 0x58, 0x68, 0xf8, 0xf3, + 0x71, 0xf7, 0x2b, 0x59, 0x00, 0x22, 0x5a, 0x60, 0x6f, 0xf0, 0x1a, 0x00, + 0xf8, 0xbd, 0x00, 0x20, 0xf8, 0xbd, 0x6f, 0xf0, 0x1a, 0x00, 0xf8, 0xbd, + 0xa1, 0xec, 0x00, 0x00, 0x4d, 0xe6, 0x00, 0x00, 0x01, 0x46, 0x38, 0xb5, + 0x51, 0xf8, 0xde, 0x5b, 0x04, 0x46, 0x10, 0x22, 0x28, 0x46, 0x14, 0xf0, + 0x6b, 0xdc, 0x28, 0x46, 0x04, 0xf1, 0xee, 0x01, 0x10, 0x22, 0xbd, 0xe8, + 0x38, 0x40, 0x14, 0xf0, 0x63, 0x9c, 0x00, 0x00, 0xf0, 0xb5, 0x1f, 0x4b, + 0xa5, 0xb0, 0x04, 0x68, 0x05, 0x46, 0x20, 0xaa, 0x03, 0xf1, 0x08, 0x07, + 0x18, 0x68, 0x59, 0x68, 0x16, 0x46, 0x03, 0xc6, 0x08, 0x33, 0xbb, 0x42, + 0x32, 0x46, 0xf7, 0xd1, 0x18, 0x68, 0x1b, 0x79, 0x30, 0x60, 0x33, 0x71, + 0x20, 0x46, 0x18, 0xa9, 0x10, 0x22, 0x14, 0xf0, 0x49, 0xdc, 0x1c, 0xa9, + 0x10, 0x22, 0x20, 0x46, 0x14, 0xf0, 0x44, 0xdc, 0x20, 0xa8, 0xf4, 0xf3, + 0x67, 0xf1, 0x6a, 0x68, 0x20, 0x24, 0xc2, 0x32, 0x00, 0x92, 0x06, 0x22, + 0x03, 0x46, 0x01, 0x92, 0x04, 0xae, 0x21, 0x46, 0x20, 0xaa, 0x05, 0xf1, + 0x7e, 0x07, 0x18, 0xa8, 0x02, 0x96, 0x03, 0x94, 0xfa, 0xf3, 0x4a, 0xf0, + 0x31, 0x46, 0x22, 0x46, 0x38, 0x46, 0xf4, 0xf3, 0x5d, 0xf0, 0x05, 0xf1, + 0x9e, 0x00, 0x39, 0x46, 0x22, 0x46, 0xf4, 0xf3, 0x57, 0xf0, 0x25, 0xb0, + 0xf0, 0xbd, 0x00, 0xbf, 0x26, 0xdc, 0x01, 0x00, 0x38, 0xb5, 0x00, 0xf1, + 0x7e, 0x05, 0x04, 0x46, 0x20, 0x21, 0x28, 0x46, 0xf5, 0xf3, 0xbe, 0xf5, + 0x28, 0x46, 0x04, 0xf1, 0x9e, 0x01, 0x20, 0x22, 0xf4, 0xf3, 0x28, 0xf0, + 0x20, 0xb9, 0x20, 0x46, 0xbd, 0xe8, 0x38, 0x40, 0xff, 0xf7, 0x98, 0xbf, + 0x38, 0xbd, 0x00, 0x00, 0xf0, 0xb5, 0x2e, 0x4b, 0xdf, 0xb0, 0x04, 0x46, + 0x0e, 0x46, 0x59, 0xaa, 0x03, 0xf1, 0x10, 0x07, 0x18, 0x68, 0x59, 0x68, + 0x15, 0x46, 0x03, 0xc5, 0x08, 0x33, 0xbb, 0x42, 0x2a, 0x46, 0xf7, 0xd1, + 0x18, 0x68, 0x28, 0x60, 0xb3, 0x6d, 0xd9, 0x07, 0x46, 0xd4, 0x9a, 0x07, + 0x06, 0xd4, 0x03, 0xf0, 0x04, 0x03, 0x02, 0x2b, 0x02, 0xd0, 0x00, 0x2b, + 0x3e, 0xd0, 0x01, 0xe0, 0x20, 0x23, 0x00, 0xe0, 0x10, 0x23, 0x05, 0xad, + 0xa4, 0xf8, 0x7c, 0x30, 0x06, 0xf1, 0xc2, 0x01, 0x28, 0x46, 0x06, 0x22, + 0x04, 0xf1, 0xbe, 0x06, 0xf4, 0xf3, 0x10, 0xf0, 0x04, 0xf1, 0x7e, 0x01, + 0x20, 0x22, 0x30, 0x46, 0xf4, 0xf3, 0x0a, 0xf0, 0x20, 0x46, 0xff, 0xf7, + 0xb5, 0xff, 0x31, 0x46, 0x20, 0x22, 0xa8, 0x1d, 0xf4, 0xf3, 0x02, 0xf0, + 0x59, 0xa8, 0xf4, 0xf3, 0xf3, 0xf0, 0x26, 0x22, 0x01, 0x92, 0xb4, 0xf8, + 0x7c, 0x20, 0x03, 0x46, 0x00, 0x95, 0x03, 0x92, 0x45, 0xad, 0x20, 0x21, + 0x59, 0xaa, 0x04, 0xf1, 0xde, 0x00, 0x02, 0x95, 0xf9, 0xf3, 0xd8, 0xf7, + 0x29, 0x46, 0xb4, 0xf8, 0x7c, 0x20, 0x04, 0xf1, 0x5a, 0x00, 0xf3, 0xf3, + 0xe9, 0xf7, 0x04, 0xf1, 0xfe, 0x00, 0x00, 0x21, 0x08, 0x22, 0xf4, 0xf3, + 0x47, 0xf0, 0x20, 0x46, 0xff, 0xf7, 0xa7, 0xfe, 0x5f, 0xb0, 0xf0, 0xbd, + 0x33, 0xdc, 0x01, 0x00, 0x7f, 0xb5, 0x43, 0x68, 0x04, 0xac, 0x9b, 0x68, + 0x44, 0xf8, 0x08, 0x2d, 0x00, 0x93, 0x0d, 0x46, 0x00, 0x68, 0xb7, 0x21, + 0x22, 0x46, 0x08, 0x23, 0xf8, 0xf7, 0x62, 0xfd, 0x06, 0x46, 0x30, 0xb9, + 0x28, 0x46, 0x21, 0x46, 0x08, 0x22, 0xf3, 0xf3, 0xc7, 0xf7, 0x30, 0x46, + 0x01, 0xe0, 0x4f, 0xf0, 0xff, 0x30, 0x04, 0xb0, 0x70, 0xbd, 0x00, 0x00, + 0x2d, 0xe9, 0xf0, 0x47, 0x00, 0xf1, 0xfe, 0x05, 0x0e, 0x46, 0x92, 0x46, + 0xb2, 0xf8, 0x00, 0x80, 0x29, 0x46, 0x90, 0xf8, 0x7b, 0x20, 0x04, 0x46, + 0xff, 0xf7, 0xd6, 0xff, 0x20, 0xb1, 0x28, 0x46, 0x00, 0x21, 0x08, 0x22, + 0xf4, 0xf3, 0x10, 0xf0, 0x06, 0xf1, 0x12, 0x07, 0x08, 0xf1, 0x58, 0x00, + 0x38, 0x18, 0xdd, 0x23, 0xc3, 0x71, 0x94, 0xf8, 0x7c, 0x30, 0x00, 0xf1, + 0x07, 0x09, 0x06, 0x33, 0x03, 0x72, 0x03, 0x22, 0x09, 0x30, 0x15, 0x49, + 0x08, 0xf1, 0x06, 0x08, 0xf3, 0xf3, 0x98, 0xf7, 0x1f, 0xfa, 0x88, 0xf8, + 0x01, 0x23, 0x89, 0xf8, 0x05, 0x30, 0x08, 0xf1, 0x58, 0x03, 0xff, 0x18, + 0x94, 0xf8, 0x7a, 0x30, 0x04, 0xf1, 0x5a, 0x01, 0x03, 0xf0, 0x03, 0x03, + 0xfb, 0x71, 0xb4, 0xf8, 0x7c, 0x20, 0x07, 0xf1, 0x09, 0x00, 0xf3, 0xf3, + 0x83, 0xf7, 0xb4, 0xf8, 0x7c, 0x30, 0x06, 0xf1, 0x4f, 0x00, 0x02, 0x33, + 0x98, 0x44, 0x29, 0x46, 0x08, 0x22, 0xf3, 0xf3, 0x79, 0xf7, 0xaa, 0xf8, + 0x00, 0x80, 0xb4, 0xf8, 0x7c, 0x00, 0x08, 0x30, 0xbd, 0xe8, 0xf0, 0x87, + 0xbf, 0xb7, 0x01, 0x00, 0x2d, 0xe9, 0xf7, 0x4f, 0x99, 0x46, 0x03, 0x68, + 0xb0, 0xf8, 0x7c, 0x40, 0x05, 0x46, 0x8b, 0x46, 0x58, 0x68, 0x20, 0x21, + 0x92, 0x46, 0xf8, 0xf3, 0x0f, 0xf6, 0x07, 0x46, 0x00, 0x28, 0x74, 0xd0, + 0x2b, 0x68, 0x4f, 0xf4, 0x80, 0x71, 0x58, 0x68, 0xf8, 0xf3, 0x06, 0xf6, + 0x80, 0x46, 0x00, 0x28, 0x61, 0xd0, 0x2b, 0x68, 0x4f, 0xf4, 0x81, 0x71, + 0x58, 0x68, 0xf8, 0xf3, 0xfd, 0xf5, 0x06, 0x46, 0x00, 0x28, 0x70, 0xd0, + 0xba, 0xf1, 0x01, 0x0f, 0x03, 0xd0, 0xba, 0xf1, 0x02, 0x0f, 0x66, 0xd1, + 0x23, 0xe0, 0x05, 0xf1, 0x8e, 0x01, 0x10, 0x22, 0x38, 0x46, 0xf3, 0xf3, + 0x41, 0xf7, 0x0b, 0xf1, 0x9c, 0x01, 0x10, 0x22, 0x07, 0xf1, 0x10, 0x00, + 0xf3, 0xf3, 0x3a, 0xf7, 0x05, 0xf1, 0x5a, 0x01, 0x22, 0x46, 0x48, 0x46, + 0xf3, 0xf3, 0x34, 0xf7, 0x38, 0x46, 0x20, 0x21, 0x32, 0x46, 0xfa, 0xf3, + 0x1d, 0xf2, 0x40, 0x46, 0x32, 0x46, 0x4f, 0xf4, 0x80, 0x71, 0xfa, 0xf3, + 0x47, 0xf2, 0x48, 0x46, 0x21, 0x46, 0x32, 0x46, 0xfa, 0xf3, 0x42, 0xf2, + 0x29, 0xe0, 0xb5, 0xf8, 0x7c, 0x30, 0x0f, 0x2b, 0x08, 0xd8, 0x28, 0x19, + 0xc4, 0xf1, 0x10, 0x02, 0x5a, 0x30, 0x00, 0x21, 0xf3, 0xf3, 0x7c, 0xf7, + 0x10, 0x24, 0x0f, 0xe0, 0x14, 0xf0, 0x07, 0x02, 0x0c, 0xd0, 0x28, 0x19, + 0x5a, 0x30, 0x00, 0x21, 0xc2, 0xf1, 0x08, 0x02, 0xf3, 0xf3, 0x70, 0xf7, + 0x4f, 0xf6, 0xf8, 0x73, 0x23, 0x40, 0x03, 0xf1, 0x08, 0x04, 0xa4, 0xb2, + 0x10, 0x20, 0x0b, 0xf1, 0x9c, 0x01, 0x22, 0x46, 0x05, 0xf1, 0x5a, 0x03, + 0xcd, 0xf8, 0x00, 0x90, 0xf1, 0xf3, 0xe0, 0xf7, 0xc8, 0xb9, 0x08, 0x34, + 0xa4, 0xb2, 0x0c, 0x9b, 0x1c, 0x80, 0x01, 0x24, 0x18, 0xe0, 0x04, 0x46, + 0x06, 0x46, 0x2b, 0x68, 0x39, 0x46, 0x58, 0x68, 0x20, 0x22, 0xf8, 0xf3, + 0xa9, 0xf5, 0x16, 0xb9, 0x0a, 0xe0, 0x04, 0x46, 0x08, 0xe0, 0x2b, 0x68, + 0x31, 0x46, 0x58, 0x68, 0x4f, 0xf4, 0x81, 0x72, 0xf8, 0xf3, 0x9e, 0xf5, + 0x00, 0xe0, 0x00, 0x24, 0x20, 0x46, 0xbd, 0xe8, 0xfe, 0x8f, 0x04, 0x46, + 0x2b, 0x68, 0x41, 0x46, 0x58, 0x68, 0x4f, 0xf4, 0x80, 0x72, 0xf8, 0xf3, + 0x91, 0xf5, 0xe0, 0xe7, 0x2d, 0xe9, 0xf0, 0x4f, 0x9f, 0xb0, 0x05, 0x46, + 0x0e, 0x46, 0x06, 0x92, 0xd0, 0xf8, 0x00, 0xa0, 0x1f, 0x46, 0x00, 0x2b, + 0x00, 0xf0, 0xc5, 0x81, 0x83, 0x68, 0x02, 0x2a, 0x5b, 0x68, 0xfb, 0x58, + 0xd3, 0xf8, 0x04, 0x80, 0x9b, 0x68, 0x07, 0x93, 0x38, 0xd0, 0x04, 0x2a, + 0x00, 0xf0, 0x00, 0x81, 0x00, 0x2a, 0x40, 0xf0, 0xb3, 0x81, 0x07, 0xf1, + 0x1a, 0x02, 0x50, 0x46, 0x69, 0x68, 0x71, 0x23, 0x49, 0xf0, 0x50, 0xd8, + 0x07, 0x46, 0x00, 0x28, 0x00, 0xf0, 0xab, 0x81, 0x04, 0x69, 0x4f, 0xf4, + 0xbe, 0x43, 0x04, 0xf1, 0x12, 0x0b, 0x23, 0x82, 0x06, 0x99, 0x5f, 0x22, + 0x58, 0x46, 0xf3, 0xf3, 0x07, 0xf7, 0x46, 0xf0, 0x88, 0x03, 0x1a, 0x0a, + 0xe2, 0x74, 0x23, 0x75, 0xb8, 0xf8, 0x18, 0x30, 0x08, 0xf1, 0x1c, 0x09, + 0x1a, 0x0a, 0xa3, 0x75, 0x49, 0x46, 0x62, 0x75, 0x50, 0x46, 0x20, 0x22, + 0x14, 0xf0, 0x60, 0xda, 0x49, 0x46, 0x04, 0xf1, 0x1f, 0x00, 0x20, 0x22, + 0xf3, 0xf3, 0x8c, 0xf6, 0x0b, 0x23, 0xc8, 0xf8, 0x00, 0x30, 0xdd, 0xf8, + 0x18, 0x90, 0x87, 0xe1, 0xb8, 0xf8, 0x02, 0x31, 0xb3, 0xf5, 0x00, 0x7f, + 0x02, 0xd1, 0x41, 0xf4, 0x72, 0x76, 0x0a, 0xe0, 0x80, 0x2b, 0x04, 0xd1, + 0x41, 0xf4, 0x9e, 0x56, 0x46, 0xf0, 0x08, 0x06, 0x03, 0xe0, 0x04, 0x2b, + 0x08, 0xbf, 0x41, 0xf4, 0xe4, 0x76, 0x6a, 0x68, 0xb8, 0xf8, 0x04, 0xb0, + 0x92, 0x6d, 0xad, 0xf8, 0x76, 0xb0, 0x02, 0xf0, 0x02, 0x09, 0xb9, 0xf1, + 0x00, 0x0f, 0x0c, 0xbf, 0x4f, 0xf0, 0x04, 0x09, 0x4f, 0xf0, 0x02, 0x09, + 0x0b, 0xf1, 0x71, 0x0b, 0x80, 0x2b, 0x1f, 0xfa, 0x8b, 0xfb, 0x30, 0xd1, + 0x16, 0xf4, 0x80, 0x53, 0x2e, 0xd0, 0x2c, 0x8a, 0x14, 0xf0, 0x01, 0x04, + 0x1b, 0xd1, 0x28, 0x46, 0xff, 0xf7, 0xae, 0xfd, 0x28, 0x46, 0x69, 0x68, + 0xff, 0xf7, 0x14, 0xfe, 0x95, 0xf8, 0x7a, 0x20, 0xb5, 0xf8, 0x7c, 0x30, + 0x8d, 0xe8, 0x04, 0x02, 0x01, 0x22, 0x03, 0x92, 0x50, 0x46, 0x69, 0x68, + 0x05, 0xf1, 0x5a, 0x02, 0x02, 0x94, 0x4b, 0xf0, 0x79, 0xd8, 0x2b, 0x8a, + 0x85, 0xf8, 0x7b, 0x00, 0x43, 0xf0, 0x01, 0x03, 0x2b, 0x82, 0xbd, 0xf8, + 0x76, 0x30, 0xb5, 0xf8, 0x7c, 0x20, 0x13, 0xf0, 0x07, 0x03, 0x02, 0xd1, + 0x02, 0xf1, 0x10, 0x03, 0x01, 0xe0, 0x18, 0x32, 0xd3, 0x1a, 0x9b, 0xb2, + 0x00, 0xe0, 0x00, 0x23, 0x9b, 0x44, 0x07, 0xf1, 0x1a, 0x02, 0x50, 0x46, + 0x69, 0x68, 0x1f, 0xfa, 0x8b, 0xf3, 0x48, 0xf0, 0xc1, 0xdf, 0x07, 0x46, + 0x00, 0x28, 0x00, 0xf0, 0x1c, 0x81, 0x04, 0x69, 0x5f, 0x23, 0x04, 0xf1, + 0x12, 0x0b, 0x00, 0x21, 0x5f, 0x22, 0x23, 0x82, 0x58, 0x46, 0xf3, 0xf3, + 0x79, 0xf6, 0x33, 0x0a, 0xe3, 0x74, 0x26, 0x75, 0xb8, 0xf8, 0x18, 0x30, + 0x08, 0xf1, 0x1c, 0x01, 0x1a, 0x0a, 0xa3, 0x75, 0x62, 0x75, 0x04, 0xf1, + 0x1f, 0x00, 0x20, 0x22, 0xf3, 0xf3, 0x06, 0xf6, 0xb8, 0xf8, 0x04, 0x20, + 0x04, 0xf1, 0x71, 0x00, 0xd8, 0xf8, 0x08, 0x10, 0xf3, 0xf3, 0xfe, 0xf5, + 0xbd, 0xf8, 0x76, 0x30, 0x1a, 0x0a, 0x42, 0xea, 0x03, 0x23, 0xa4, 0xf8, + 0x6f, 0x30, 0xb8, 0xf8, 0x02, 0x31, 0x80, 0x2b, 0x27, 0xd1, 0xf3, 0x04, + 0x25, 0xd5, 0x0d, 0xf1, 0x76, 0x02, 0x28, 0x46, 0x21, 0x46, 0xff, 0xf7, + 0x2b, 0xfe, 0xbd, 0xf8, 0x76, 0x30, 0x04, 0xf1, 0x3f, 0x00, 0x1a, 0x0a, + 0x42, 0xea, 0x03, 0x23, 0xa4, 0xf8, 0x6f, 0x30, 0xa3, 0x7b, 0x02, 0x2b, + 0x04, 0xd1, 0x00, 0x21, 0x10, 0x22, 0xf3, 0xf3, 0x3f, 0xf6, 0x04, 0xe0, + 0x05, 0xf1, 0x8e, 0x01, 0x10, 0x22, 0xf3, 0xf3, 0xd5, 0xf5, 0x58, 0x46, + 0x31, 0x46, 0x08, 0xf1, 0x9c, 0x02, 0x00, 0x23, 0xf5, 0xf3, 0x9a, 0xf2, + 0x00, 0x28, 0x00, 0xf0, 0xcc, 0x80, 0x94, 0xf8, 0x6f, 0x20, 0x94, 0xf8, + 0x70, 0x30, 0x43, 0xea, 0x02, 0x23, 0x22, 0x8a, 0x9b, 0x18, 0x9b, 0xb2, + 0x1a, 0x0a, 0x42, 0xea, 0x03, 0x23, 0x23, 0x82, 0x0c, 0x23, 0x76, 0xe0, + 0x90, 0xf8, 0x7a, 0x30, 0xb0, 0xf8, 0x7c, 0x90, 0x1b, 0x01, 0x03, 0xf0, + 0x30, 0x03, 0x41, 0xea, 0x03, 0x06, 0x46, 0xf4, 0x60, 0x76, 0xb6, 0xb2, + 0x00, 0x23, 0xb0, 0x07, 0x54, 0xbf, 0x09, 0xf1, 0x71, 0x09, 0x09, 0xf1, + 0x79, 0x09, 0x1f, 0xfa, 0x89, 0xf9, 0xad, 0xf8, 0x76, 0x30, 0x07, 0xf1, + 0x1a, 0x02, 0x50, 0x46, 0x69, 0x68, 0x4b, 0x46, 0x48, 0xf0, 0x3c, 0xdf, + 0x07, 0x46, 0x00, 0x28, 0x00, 0xf0, 0x97, 0x80, 0x04, 0x69, 0x5f, 0x23, + 0x04, 0xf1, 0x12, 0x0b, 0x00, 0x21, 0xa9, 0xf1, 0x12, 0x02, 0x23, 0x82, + 0x58, 0x46, 0xf3, 0xf3, 0xf3, 0xf5, 0x33, 0x0a, 0xe3, 0x74, 0x26, 0x75, + 0xb5, 0xf8, 0x7c, 0x30, 0x05, 0xf1, 0xbe, 0x01, 0x1a, 0x0a, 0xa3, 0x75, + 0x62, 0x75, 0x04, 0xf1, 0x1f, 0x00, 0x20, 0x22, 0xf3, 0xf3, 0x80, 0xf5, + 0x04, 0xf1, 0x3f, 0x09, 0x05, 0xf1, 0x8e, 0x0c, 0x61, 0x46, 0x10, 0x22, + 0x48, 0x46, 0xcd, 0xf8, 0x14, 0xc0, 0xf3, 0xf3, 0x75, 0xf5, 0x08, 0x22, + 0x05, 0xf1, 0xfe, 0x01, 0x04, 0xf1, 0x4f, 0x00, 0xf3, 0xf3, 0x6e, 0xf5, + 0x0d, 0xf1, 0x76, 0x03, 0x00, 0x93, 0x28, 0x46, 0x04, 0xf1, 0x71, 0x03, + 0x41, 0x46, 0x06, 0xf0, 0x03, 0x02, 0xff, 0xf7, 0xf3, 0xfd, 0xa3, 0x7b, + 0x48, 0x46, 0x02, 0x2b, 0xdd, 0xf8, 0x14, 0xc0, 0x04, 0xd1, 0x00, 0x21, + 0x10, 0x22, 0xf3, 0xf3, 0xbd, 0xf5, 0x03, 0xe0, 0x61, 0x46, 0x10, 0x22, + 0xf3, 0xf3, 0x54, 0xf5, 0xbd, 0xf8, 0x76, 0x30, 0x1a, 0x0a, 0x42, 0xea, + 0x03, 0x22, 0xa4, 0xf8, 0x6f, 0x20, 0x22, 0x8a, 0x9b, 0x18, 0x9b, 0xb2, + 0x1a, 0x0a, 0x42, 0xea, 0x03, 0x23, 0x23, 0x82, 0x0f, 0x23, 0xc8, 0xf8, + 0x00, 0x30, 0x4f, 0xf0, 0x01, 0x09, 0x41, 0xe0, 0x20, 0x46, 0x06, 0xf0, + 0x03, 0x01, 0x08, 0xf1, 0x8c, 0x02, 0x09, 0xab, 0xf5, 0xf3, 0xc2, 0xf2, + 0x00, 0x28, 0x31, 0xd0, 0x0b, 0xf1, 0x4d, 0x00, 0x09, 0xa9, 0x10, 0x22, + 0xf3, 0xf3, 0x30, 0xf5, 0xb8, 0xf8, 0x02, 0x31, 0xb3, 0xf5, 0x00, 0x7f, + 0x03, 0xd1, 0x7b, 0x6a, 0x43, 0xf0, 0x80, 0x73, 0x7b, 0x62, 0xda, 0xf8, + 0x00, 0x30, 0x93, 0xf8, 0x95, 0x30, 0x4b, 0xb1, 0x06, 0x9b, 0x0b, 0xb1, + 0x02, 0x2b, 0x05, 0xd1, 0x7b, 0x6a, 0x23, 0xf4, 0x40, 0x33, 0x43, 0xf4, + 0x80, 0x33, 0x7b, 0x62, 0x6b, 0x68, 0x39, 0x46, 0x9a, 0x68, 0x50, 0x46, + 0x19, 0xf0, 0x28, 0xde, 0x07, 0x9b, 0xda, 0xf8, 0x08, 0x00, 0xd3, 0xf8, + 0xc0, 0x10, 0x4f, 0xf4, 0x7a, 0x72, 0x00, 0x23, 0x01, 0xf0, 0x32, 0xd8, + 0x01, 0x27, 0x02, 0xe0, 0x00, 0x27, 0x00, 0xe0, 0x07, 0x46, 0x38, 0x46, + 0x1f, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, 0x81, 0x46, 0x03, 0x23, 0xe3, 0x73, + 0xb8, 0xf8, 0x02, 0x31, 0x58, 0x46, 0x80, 0x2b, 0x14, 0xbf, 0xfe, 0x23, + 0x02, 0x23, 0x00, 0xf8, 0x05, 0x3b, 0x08, 0xf1, 0x5c, 0x01, 0x08, 0x22, + 0xf3, 0xf3, 0xee, 0xf4, 0xb9, 0xf1, 0x00, 0x0f, 0xba, 0xd0, 0xa9, 0xe7, + 0xd0, 0xf8, 0x48, 0x31, 0x70, 0xb5, 0x5c, 0x68, 0x06, 0x46, 0xe1, 0x42, + 0x0d, 0x46, 0x40, 0xd0, 0x0b, 0x59, 0x00, 0x2b, 0x3d, 0xd0, 0x59, 0x68, + 0x59, 0xb1, 0x4b, 0xf0, 0x45, 0xd8, 0x2b, 0x59, 0x4f, 0xf4, 0x84, 0x72, + 0x59, 0x68, 0x70, 0x68, 0xf8, 0xf3, 0x90, 0xf3, 0x2b, 0x59, 0x00, 0x22, + 0x5a, 0x60, 0x2b, 0x59, 0x9b, 0x68, 0x00, 0x2b, 0x2b, 0xd0, 0x99, 0x6e, + 0x61, 0xb1, 0xb0, 0x68, 0x01, 0xf0, 0x3a, 0xd8, 0x2b, 0x59, 0xb0, 0x68, + 0x9b, 0x68, 0x99, 0x6e, 0x01, 0xf0, 0x46, 0xd8, 0x2b, 0x59, 0x00, 0x22, + 0x9b, 0x68, 0x9a, 0x66, 0x2b, 0x59, 0x9b, 0x68, 0xd3, 0xf8, 0xc0, 0x10, + 0x71, 0xb1, 0xb0, 0x68, 0x01, 0xf0, 0x28, 0xd8, 0x2b, 0x59, 0xb0, 0x68, + 0x9b, 0x68, 0xd3, 0xf8, 0xc0, 0x10, 0x01, 0xf0, 0x33, 0xd8, 0x2b, 0x59, + 0x00, 0x22, 0x9b, 0x68, 0xc3, 0xf8, 0xc0, 0x20, 0x2b, 0x59, 0xc4, 0x22, + 0x99, 0x68, 0x70, 0x68, 0xf8, 0xf3, 0x60, 0xf3, 0x2b, 0x59, 0x00, 0x22, + 0x9a, 0x60, 0x70, 0xbd, 0xc1, 0x68, 0x10, 0xb5, 0x04, 0x46, 0x21, 0xb1, + 0x00, 0x68, 0xff, 0xf7, 0xaf, 0xff, 0x00, 0x23, 0xe3, 0x60, 0x10, 0xbd, + 0x70, 0xb5, 0xc5, 0x68, 0x04, 0x46, 0x00, 0x2d, 0x52, 0xd0, 0x83, 0x68, + 0x5b, 0x68, 0xeb, 0x58, 0x5b, 0x68, 0x00, 0x2b, 0x4c, 0xd0, 0x1e, 0x8a, + 0x1a, 0x68, 0x04, 0x2e, 0x14, 0xbf, 0x01, 0x26, 0x02, 0x26, 0x0c, 0x2a, + 0x1c, 0xd0, 0x0f, 0x2a, 0x2a, 0xd0, 0x0b, 0x2a, 0x40, 0xd1, 0x93, 0xf8, + 0x04, 0x21, 0x51, 0x1c, 0x02, 0x2a, 0x83, 0xf8, 0x04, 0x11, 0x08, 0xd9, + 0xc1, 0x68, 0x21, 0xb1, 0x40, 0x68, 0x1a, 0x31, 0x0f, 0x22, 0x4a, 0xf0, + 0x7f, 0xdf, 0x20, 0x46, 0x1f, 0xe0, 0x03, 0xf1, 0x5c, 0x00, 0x08, 0x21, + 0xf5, 0xf3, 0xde, 0xf1, 0x20, 0x46, 0x31, 0x46, 0x00, 0x22, 0x22, 0xe0, + 0x93, 0xf8, 0x04, 0x21, 0x51, 0x1c, 0x02, 0x2a, 0x83, 0xf8, 0x04, 0x11, + 0x0f, 0xd8, 0x03, 0xf1, 0x5c, 0x00, 0x08, 0x21, 0xf5, 0xf3, 0xce, 0xf1, + 0x20, 0x46, 0x31, 0x46, 0x02, 0x22, 0x12, 0xe0, 0x93, 0xf8, 0x04, 0x21, + 0x51, 0x1c, 0x02, 0x2a, 0x83, 0xf8, 0x04, 0x11, 0x03, 0xd9, 0xbd, 0xe8, + 0x70, 0x40, 0xff, 0xf7, 0xab, 0xbf, 0x03, 0xf1, 0x5c, 0x00, 0x08, 0x21, + 0xf5, 0xf3, 0xba, 0xf1, 0x20, 0x46, 0x31, 0x46, 0x04, 0x22, 0x2b, 0x46, + 0xbd, 0xe8, 0x70, 0x40, 0xff, 0xf7, 0x6a, 0xbd, 0x70, 0xbd, 0x70, 0xb5, + 0x06, 0x46, 0x00, 0x68, 0x0c, 0x46, 0xff, 0xf7, 0x4d, 0xff, 0x31, 0x68, + 0x00, 0x23, 0xca, 0x18, 0xd2, 0xf8, 0x4c, 0x22, 0x32, 0xb1, 0x52, 0x69, + 0x22, 0xb1, 0xd0, 0x68, 0xa0, 0x42, 0x01, 0xd1, 0x00, 0x20, 0xd0, 0x60, + 0x04, 0x33, 0x20, 0x2b, 0xf1, 0xd1, 0x75, 0x68, 0x63, 0x19, 0x43, 0xb1, + 0x61, 0x59, 0x31, 0xb1, 0x33, 0x68, 0x0c, 0x22, 0x58, 0x68, 0xf8, 0xf3, + 0xd9, 0xf2, 0x00, 0x23, 0x63, 0x51, 0x70, 0xbd, 0x37, 0xb5, 0x0c, 0x46, + 0x15, 0x46, 0x01, 0x46, 0x70, 0xb1, 0x6b, 0xb1, 0x82, 0x68, 0x52, 0x68, + 0x9b, 0x58, 0x0a, 0x8b, 0x98, 0x68, 0x52, 0xb1, 0xc3, 0x88, 0x53, 0xb9, + 0x1a, 0x31, 0x23, 0x46, 0x00, 0x95, 0x4a, 0xf0, 0xd7, 0xdd, 0x05, 0xe0, + 0x4f, 0xf0, 0xff, 0x30, 0x02, 0xe0, 0x10, 0x46, 0x00, 0xe0, 0x00, 0x20, + 0x3e, 0xbd, 0x2d, 0xe9, 0xf0, 0x4f, 0x02, 0x68, 0x89, 0xb0, 0x05, 0x46, + 0x88, 0x46, 0x06, 0x92, 0x99, 0x46, 0x00, 0x2b, 0x00, 0xf0, 0x32, 0x81, + 0x83, 0x68, 0x5b, 0x68, 0x59, 0xf8, 0x03, 0x30, 0x5c, 0x68, 0xd3, 0xf8, + 0x08, 0xa0, 0x00, 0x2c, 0x00, 0xf0, 0x2a, 0x81, 0xba, 0xf1, 0x00, 0x0f, + 0x00, 0xf0, 0x28, 0x81, 0x23, 0x8a, 0x04, 0x2b, 0x14, 0xbf, 0x01, 0x23, + 0x02, 0x23, 0x07, 0x93, 0xb4, 0xf8, 0x02, 0x31, 0x80, 0x2b, 0x05, 0xd0, + 0xb3, 0xf5, 0x00, 0x7f, 0x02, 0xd0, 0x04, 0x2b, 0x40, 0xf0, 0x1a, 0x81, + 0x04, 0xf1, 0x5c, 0x0b, 0x01, 0x20, 0x08, 0x23, 0x08, 0xf1, 0x17, 0x01, + 0x5a, 0x46, 0x98, 0xf8, 0x13, 0x70, 0x98, 0xf8, 0x14, 0x60, 0xf4, 0xf3, + 0x2f, 0xf7, 0x83, 0x45, 0x00, 0xf0, 0x0c, 0x81, 0x23, 0x68, 0x46, 0xea, + 0x07, 0x26, 0x0c, 0x2b, 0x63, 0xd0, 0x0f, 0x2b, 0x00, 0xf0, 0xe3, 0x80, + 0x0b, 0x2b, 0x40, 0xf0, 0x01, 0x81, 0x06, 0xf4, 0xdc, 0x73, 0xb3, 0xf5, + 0x84, 0x7f, 0x40, 0xf0, 0xfb, 0x80, 0x04, 0xf1, 0x3c, 0x07, 0x20, 0x22, + 0x08, 0xf1, 0x1f, 0x01, 0x38, 0x46, 0xf3, 0xf3, 0xad, 0xf3, 0x09, 0xf1, + 0x1a, 0x03, 0x06, 0x93, 0x0a, 0xf1, 0x48, 0x03, 0x00, 0x93, 0xba, 0xf8, + 0x06, 0x30, 0x04, 0xf1, 0x8c, 0x0c, 0xcd, 0xf8, 0x08, 0xc0, 0x01, 0x93, + 0xa3, 0x8a, 0x69, 0x68, 0x03, 0x93, 0xc2, 0x31, 0x06, 0x98, 0x04, 0xf1, + 0x1c, 0x02, 0x3b, 0x46, 0xcd, 0xf8, 0x14, 0xc0, 0xf4, 0xf3, 0x60, 0xf7, + 0x16, 0xf4, 0x80, 0x7f, 0xdd, 0xf8, 0x14, 0xc0, 0x08, 0xd0, 0x40, 0x46, + 0x06, 0xf0, 0x03, 0x01, 0x62, 0x46, 0xf4, 0xf3, 0xb5, 0xf7, 0x00, 0x28, + 0x00, 0xf0, 0xcc, 0x80, 0x98, 0xf8, 0x6f, 0x20, 0x98, 0xf8, 0x70, 0x30, + 0x53, 0xea, 0x02, 0x23, 0x08, 0xd0, 0xe2, 0x88, 0x9a, 0x42, 0x05, 0xd1, + 0x08, 0xf1, 0x71, 0x00, 0xe1, 0x68, 0xf3, 0xf3, 0x5b, 0xf3, 0x28, 0xb1, + 0x68, 0x68, 0x06, 0x99, 0x11, 0x22, 0x4a, 0xf0, 0x7f, 0xde, 0xb5, 0xe0, + 0x84, 0xf8, 0x04, 0x01, 0x2b, 0x68, 0xda, 0xf8, 0xc0, 0x10, 0x98, 0x68, + 0x00, 0xf0, 0xda, 0xde, 0x58, 0x46, 0x08, 0x21, 0xf5, 0xf3, 0xd8, 0xf0, + 0x28, 0x46, 0x07, 0x99, 0x02, 0x22, 0x4b, 0x46, 0xff, 0xf7, 0x8a, 0xfc, + 0xa2, 0xe0, 0x06, 0xf4, 0xd8, 0x73, 0xb3, 0xf5, 0x80, 0x7f, 0x40, 0xf0, + 0x9d, 0x80, 0xf1, 0x05, 0x09, 0xd5, 0x40, 0x46, 0x06, 0xf0, 0x03, 0x01, + 0x04, 0xf1, 0x8c, 0x02, 0xf4, 0xf3, 0x7a, 0xf7, 0x00, 0x28, 0x00, 0xf0, + 0x91, 0x80, 0x00, 0x23, 0x84, 0xf8, 0x04, 0x31, 0x2b, 0x68, 0xda, 0xf8, + 0xc0, 0x10, 0x98, 0x68, 0x00, 0xf0, 0xb4, 0xde, 0x22, 0x8a, 0x09, 0xf1, + 0x1a, 0x06, 0x23, 0x8b, 0x06, 0x98, 0x8d, 0xe8, 0x44, 0x00, 0x69, 0x68, + 0x04, 0xf1, 0xac, 0x02, 0x4a, 0xf0, 0xde, 0xdd, 0xb4, 0xf8, 0x02, 0x31, + 0x80, 0x2b, 0x02, 0xd1, 0x10, 0x23, 0x23, 0x60, 0x34, 0xe0, 0x04, 0x2b, + 0x32, 0xd1, 0x2f, 0x8a, 0x0d, 0x23, 0x17, 0xf0, 0x01, 0x07, 0x23, 0x60, + 0x22, 0xd1, 0x28, 0x46, 0xff, 0xf7, 0x7e, 0xfa, 0x28, 0x46, 0x69, 0x68, + 0xff, 0xf7, 0xe4, 0xfa, 0x95, 0xf8, 0x7a, 0x20, 0xb5, 0xf8, 0x7c, 0x30, + 0x01, 0x2a, 0x14, 0xbf, 0x01, 0x22, 0x02, 0x22, 0x85, 0xf8, 0x7a, 0x20, + 0x00, 0x92, 0x22, 0x8a, 0x06, 0x98, 0x01, 0x92, 0x01, 0x22, 0x03, 0x92, + 0x69, 0x68, 0x05, 0xf1, 0x5a, 0x02, 0x02, 0x97, 0x4a, 0xf0, 0x42, 0xdd, + 0x2b, 0x8a, 0x85, 0xf8, 0x7b, 0x00, 0x43, 0xf0, 0x01, 0x03, 0x2b, 0x82, + 0x58, 0x46, 0x08, 0x21, 0xf5, 0xf3, 0x74, 0xf0, 0x28, 0x46, 0x07, 0x99, + 0x04, 0x22, 0x4b, 0x46, 0xff, 0xf7, 0x26, 0xfc, 0xb4, 0xf8, 0x02, 0x31, + 0xb3, 0xf5, 0x00, 0x7f, 0x05, 0xd1, 0x06, 0x9a, 0x31, 0x46, 0xd2, 0xf8, + 0x44, 0x01, 0x01, 0xf0, 0xf7, 0xfe, 0xb4, 0xf8, 0x02, 0x31, 0x80, 0x2b, + 0x01, 0xd0, 0x04, 0x2b, 0x08, 0xd1, 0x6b, 0x68, 0x06, 0x98, 0x9b, 0x68, + 0x79, 0x21, 0x00, 0x93, 0x32, 0x46, 0x06, 0x23, 0xf8, 0xf7, 0x74, 0xf8, + 0xb4, 0xf8, 0x02, 0x31, 0x80, 0x2b, 0x21, 0xd1, 0x14, 0xe0, 0xf2, 0x05, + 0x07, 0xd5, 0x40, 0x46, 0x06, 0xf0, 0x03, 0x01, 0x04, 0xf1, 0x8c, 0x02, + 0xf4, 0xf3, 0xfe, 0xf6, 0xb0, 0xb1, 0x00, 0x23, 0x84, 0xf8, 0x04, 0x31, + 0x2b, 0x68, 0xda, 0xf8, 0xc0, 0x10, 0x98, 0x68, 0x00, 0xf0, 0x3a, 0xde, + 0x10, 0x23, 0x23, 0x60, 0x28, 0x46, 0xff, 0xf7, 0x23, 0xfe, 0x07, 0xe0, + 0x18, 0x46, 0x06, 0xe0, 0x20, 0x46, 0x04, 0xe0, 0x50, 0x46, 0x02, 0xe0, + 0x00, 0x20, 0x00, 0xe0, 0x01, 0x20, 0x09, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, + 0x2d, 0xe9, 0xf3, 0x47, 0x0b, 0x9e, 0x05, 0x46, 0x90, 0x46, 0x9a, 0x46, + 0x89, 0x46, 0x00, 0x29, 0x41, 0xd0, 0x00, 0x2e, 0x41, 0xd0, 0x83, 0x68, + 0x00, 0x68, 0x5b, 0x68, 0xf3, 0x58, 0x5c, 0x68, 0x9f, 0x68, 0x21, 0x46, + 0x4a, 0xf0, 0x0c, 0xde, 0x09, 0x23, 0x23, 0x60, 0x99, 0xf8, 0x00, 0x30, + 0x28, 0x68, 0x30, 0x2b, 0x6b, 0x68, 0x21, 0x46, 0xb3, 0xf8, 0x62, 0x30, + 0x4a, 0x46, 0x0c, 0xbf, 0x03, 0xf0, 0x80, 0x03, 0x03, 0xf0, 0x04, 0x03, + 0xa4, 0xf8, 0x02, 0x31, 0x0a, 0x9b, 0xcd, 0xf8, 0x00, 0xa0, 0x01, 0x93, + 0x43, 0x46, 0x4a, 0xf0, 0x13, 0xde, 0xf8, 0xb1, 0x6b, 0x69, 0x01, 0x2b, + 0x01, 0xd1, 0xf8, 0x88, 0xd0, 0xb1, 0x4f, 0xf0, 0x00, 0x08, 0x84, 0xf8, + 0x04, 0x81, 0x2b, 0x68, 0xd7, 0xf8, 0xc0, 0x10, 0x98, 0x68, 0x00, 0xf0, + 0xeb, 0xdd, 0x21, 0x8a, 0x0a, 0x23, 0x23, 0x60, 0x28, 0x46, 0x04, 0x29, + 0x14, 0xbf, 0x01, 0x21, 0x02, 0x21, 0x42, 0x46, 0x33, 0x46, 0xff, 0xf7, + 0x99, 0xfb, 0x01, 0x20, 0x02, 0xe0, 0x08, 0x46, 0x00, 0xe0, 0x30, 0x46, + 0xbd, 0xe8, 0xfc, 0x87, 0x70, 0xb5, 0x05, 0x46, 0x0e, 0x46, 0x40, 0x68, + 0x4f, 0xf4, 0x84, 0x71, 0xf8, 0xf3, 0x0a, 0xf1, 0x04, 0x46, 0x48, 0xb1, + 0x00, 0x21, 0x4f, 0xf4, 0x84, 0x72, 0xf3, 0xf3, 0xbb, 0xf2, 0xd5, 0xf8, + 0x48, 0x31, 0x84, 0xe8, 0x60, 0x00, 0xa3, 0x60, 0x20, 0x46, 0x70, 0xbd, + 0x01, 0x46, 0x28, 0xb1, 0x03, 0x68, 0x4f, 0xf4, 0x84, 0x72, 0x58, 0x68, + 0xf8, 0xf3, 0x04, 0xb1, 0x70, 0x47, 0x70, 0xb5, 0x0d, 0x46, 0xb4, 0xb0, + 0x04, 0x46, 0x00, 0x28, 0x36, 0xd0, 0x00, 0x29, 0x34, 0xd0, 0x03, 0x8a, + 0x4a, 0x88, 0x23, 0xf0, 0x02, 0x03, 0x1b, 0x04, 0x1b, 0x0c, 0x12, 0xf0, + 0x01, 0x0f, 0x03, 0x82, 0x0a, 0x88, 0x1a, 0xd0, 0xa2, 0xf1, 0x08, 0x03, + 0x9b, 0xb2, 0x38, 0x2b, 0x24, 0xd8, 0x40, 0x2a, 0x18, 0xd1, 0x00, 0x23, + 0x03, 0xa8, 0x04, 0x31, 0x00, 0x93, 0x4a, 0xf0, 0xf7, 0xdb, 0x06, 0x46, + 0x80, 0xb9, 0x04, 0xf1, 0x1a, 0x00, 0x15, 0xa9, 0x20, 0x22, 0xf3, 0xf3, + 0x1f, 0xf2, 0x23, 0x8a, 0x30, 0x46, 0x43, 0xf0, 0x02, 0x03, 0x23, 0x82, + 0x10, 0xe0, 0x20, 0x2a, 0x0c, 0xd1, 0x43, 0xf0, 0x02, 0x03, 0x03, 0x82, + 0x29, 0x1d, 0x2a, 0x88, 0x04, 0xf1, 0x1a, 0x00, 0xf3, 0xf3, 0x0e, 0xf2, + 0x2d, 0x88, 0x00, 0x20, 0x25, 0x83, 0x01, 0xe0, 0x6f, 0xf0, 0x01, 0x00, + 0x34, 0xb0, 0x70, 0xbd, 0xf0, 0xb5, 0x06, 0x9f, 0x14, 0x46, 0x07, 0x9e, + 0x1a, 0x46, 0x05, 0x9b, 0x50, 0xb1, 0x01, 0x29, 0x07, 0xd1, 0x41, 0x61, + 0x21, 0x46, 0x05, 0x97, 0x06, 0x96, 0xbd, 0xe8, 0xf0, 0x40, 0xff, 0xf7, + 0x3f, 0xbf, 0x00, 0x20, 0xf0, 0xbd, 0x10, 0xb5, 0x88, 0xb1, 0xcc, 0x7b, + 0x03, 0x2c, 0x0b, 0xd1, 0x44, 0x69, 0x01, 0x2c, 0x08, 0xd1, 0x8c, 0x7c, + 0x02, 0x2c, 0x01, 0xd0, 0xfe, 0x2c, 0x05, 0xd1, 0xff, 0xf7, 0xe5, 0xfd, + 0x01, 0x20, 0x10, 0xbd, 0x00, 0x20, 0x10, 0xbd, 0x00, 0x20, 0x10, 0xbd, + 0x2d, 0xe9, 0xf0, 0x41, 0x46, 0x68, 0x17, 0x46, 0xd6, 0xf8, 0xd4, 0x32, + 0xd0, 0xf8, 0x00, 0x80, 0x5a, 0x8e, 0xad, 0xf5, 0x06, 0x7d, 0x02, 0xf4, + 0x70, 0x42, 0xa2, 0xf5, 0x80, 0x55, 0x6a, 0x42, 0x42, 0xeb, 0x05, 0x02, + 0x04, 0x46, 0x40, 0x46, 0x46, 0xf0, 0xe4, 0xdd, 0x4f, 0xf4, 0x00, 0x73, + 0x85, 0x93, 0x05, 0x46, 0x00, 0x28, 0x51, 0xd0, 0x47, 0xb1, 0xe3, 0x68, + 0x00, 0x2b, 0x4d, 0xd1, 0x20, 0x46, 0x29, 0x46, 0xff, 0xf7, 0x9a, 0xf8, + 0x00, 0x28, 0x47, 0xd1, 0xa3, 0x68, 0x20, 0x46, 0x5b, 0x68, 0xeb, 0x58, + 0x9f, 0x68, 0xff, 0xf7, 0x1d, 0xf9, 0xb6, 0xf8, 0x62, 0x30, 0xab, 0x87, + 0x03, 0xb1, 0xe5, 0x60, 0x23, 0x8a, 0x98, 0x07, 0x08, 0xd5, 0x20, 0x22, + 0x07, 0xf1, 0x48, 0x00, 0x04, 0xf1, 0x1a, 0x01, 0xf3, 0xf3, 0xa2, 0xf1, + 0x20, 0x22, 0xfa, 0x80, 0xfb, 0x88, 0x20, 0x2b, 0x1b, 0xd1, 0x85, 0xab, + 0x00, 0x93, 0x40, 0x46, 0x50, 0x21, 0x2a, 0x69, 0x05, 0xab, 0x01, 0xf0, + 0x73, 0xf8, 0x08, 0xab, 0x00, 0x93, 0x85, 0x9b, 0x20, 0x46, 0x0c, 0x3b, + 0x01, 0x93, 0xe3, 0x68, 0x01, 0x21, 0x02, 0x93, 0xd5, 0xf8, 0xe8, 0x20, + 0xd5, 0xf8, 0xec, 0x30, 0xff, 0xf7, 0x80, 0xff, 0xa0, 0xb9, 0x20, 0x46, + 0xff, 0xf7, 0xe2, 0xfc, 0x10, 0xe0, 0x63, 0x68, 0x70, 0x69, 0xb3, 0xf8, + 0x62, 0x30, 0xb3, 0xf5, 0x00, 0x7f, 0x03, 0xd1, 0x06, 0xf1, 0xbc, 0x01, + 0x06, 0x22, 0x02, 0xe0, 0x72, 0x7e, 0x06, 0xf1, 0x1a, 0x01, 0x2b, 0x46, + 0xff, 0xf7, 0x56, 0xfd, 0x0d, 0xf5, 0x06, 0x7d, 0xbd, 0xe8, 0xf0, 0x81, + 0x2d, 0xe9, 0xf0, 0x47, 0xc6, 0x68, 0x05, 0x46, 0x07, 0x68, 0x00, 0x2e, + 0x33, 0xd0, 0x83, 0x68, 0x5b, 0x68, 0xf3, 0x58, 0x9c, 0x68, 0x00, 0x2c, + 0x2d, 0xd0, 0x04, 0xf1, 0x6c, 0x09, 0x48, 0x46, 0x4f, 0xf4, 0x80, 0x71, + 0xf9, 0xf3, 0x60, 0xf0, 0x80, 0x46, 0x00, 0x28, 0x1b, 0xd1, 0x04, 0xf1, + 0x48, 0x01, 0x20, 0x22, 0x48, 0x46, 0xf9, 0xf3, 0x97, 0xf0, 0x20, 0x23, + 0xe3, 0x80, 0x6b, 0x68, 0x06, 0xf1, 0x1a, 0x01, 0xb3, 0xf8, 0x62, 0x30, + 0xb3, 0xf5, 0x00, 0x7f, 0x05, 0xd1, 0xd7, 0xf8, 0x44, 0x01, 0xbd, 0xe8, + 0xf0, 0x47, 0x01, 0xf0, 0x46, 0xbd, 0x28, 0x46, 0x42, 0x46, 0xbd, 0xe8, + 0xf0, 0x47, 0xff, 0xf7, 0x5b, 0xbf, 0x00, 0x22, 0xb8, 0x68, 0xa1, 0x6e, + 0x13, 0x46, 0xbd, 0xe8, 0xf0, 0x47, 0x00, 0xf0, 0x5b, 0x9c, 0xbd, 0xe8, + 0xf0, 0x87, 0x7f, 0xb5, 0x91, 0xf8, 0x94, 0x30, 0x05, 0x46, 0x0c, 0x46, + 0x43, 0xb3, 0xd0, 0xf8, 0x00, 0x05, 0x03, 0xa9, 0x46, 0xf0, 0xd2, 0xd9, + 0x10, 0xe0, 0x33, 0x7e, 0x9b, 0x07, 0x0d, 0xd5, 0x33, 0x69, 0xa3, 0x42, + 0x0a, 0xd1, 0x01, 0x23, 0x4f, 0xf0, 0x02, 0x0e, 0x8d, 0xe8, 0x08, 0x40, + 0x28, 0x46, 0x21, 0x46, 0x32, 0x46, 0x00, 0x23, 0x46, 0xf0, 0xd8, 0xda, + 0x03, 0xa8, 0x46, 0xf0, 0xc5, 0xd9, 0x06, 0x46, 0x00, 0x28, 0xe8, 0xd1, + 0x3c, 0x23, 0xc4, 0xf8, 0x8c, 0x30, 0xf7, 0xf3, 0x4d, 0xf4, 0x01, 0x23, + 0xc4, 0xf8, 0x90, 0x00, 0x84, 0xf8, 0x94, 0x60, 0x84, 0xf8, 0x84, 0x30, + 0x7f, 0xbd, 0x70, 0x47, 0x10, 0xb5, 0xc3, 0xf8, 0xa0, 0x10, 0x08, 0x20, + 0x19, 0x46, 0x1c, 0x46, 0x33, 0xf0, 0x6a, 0xdd, 0x84, 0xf8, 0xa4, 0x00, + 0x10, 0xbd, 0x38, 0xb5, 0x05, 0x7d, 0x04, 0x46, 0xa5, 0xb1, 0x43, 0x7d, + 0x8b, 0xb9, 0xc0, 0x68, 0xa1, 0x69, 0x00, 0xf0, 0x5b, 0xdc, 0xd0, 0xf1, + 0x01, 0x05, 0x38, 0xbf, 0x00, 0x25, 0x01, 0x23, 0x63, 0x75, 0xe3, 0x69, + 0x0b, 0xb1, 0xa0, 0x68, 0x98, 0x47, 0x00, 0x23, 0x63, 0x75, 0x23, 0x75, + 0x00, 0xe0, 0x00, 0x25, 0x28, 0x46, 0x38, 0xbd, 0x00, 0x23, 0x0b, 0x61, + 0x4b, 0x81, 0x0b, 0x72, 0x0b, 0x73, 0x08, 0x46, 0x06, 0x22, 0x19, 0x46, + 0xf3, 0xf3, 0x32, 0xb1, 0x2d, 0xe9, 0xf7, 0x43, 0x9d, 0xf8, 0x28, 0x90, + 0x06, 0x46, 0x0c, 0x46, 0x15, 0x46, 0x98, 0x46, 0xb9, 0xf1, 0x00, 0x0f, + 0x3a, 0xd1, 0xcf, 0x68, 0x00, 0x2f, 0x37, 0xd0, 0x3b, 0x69, 0x00, 0x2b, + 0x34, 0xd0, 0x3b, 0x7a, 0x0b, 0x2b, 0x23, 0xd1, 0xfb, 0x79, 0x43, 0x45, + 0xd1, 0xf8, 0x70, 0x31, 0x09, 0xd1, 0xeb, 0xb1, 0x09, 0x69, 0x9a, 0x79, + 0x38, 0xf0, 0x92, 0xd8, 0xc4, 0xf8, 0x70, 0x91, 0xc4, 0xf8, 0x74, 0x91, + 0x14, 0xe0, 0x00, 0x2b, 0x2f, 0xd0, 0xda, 0x79, 0x42, 0x45, 0x2e, 0xd1, + 0x02, 0x68, 0x91, 0x6a, 0xd4, 0xf8, 0x74, 0x21, 0x91, 0x42, 0x07, 0xd9, + 0x21, 0x69, 0x9a, 0x79, 0x38, 0xf0, 0x7e, 0xd8, 0xc4, 0xf8, 0x70, 0x91, + 0xc4, 0xf8, 0x74, 0x91, 0xd4, 0xf8, 0x70, 0x71, 0xfb, 0x79, 0x43, 0x45, + 0x1e, 0xd0, 0x95, 0xf9, 0x48, 0x20, 0x8d, 0xe8, 0x08, 0x01, 0x31, 0x68, + 0x0e, 0x4b, 0x49, 0x68, 0x0e, 0x48, 0x00, 0xf0, 0xbf, 0xfc, 0x12, 0xe0, + 0xd6, 0xf8, 0x6c, 0x32, 0x9d, 0x42, 0x03, 0xd0, 0xab, 0x79, 0x0b, 0xb9, + 0x4f, 0xea, 0x58, 0x08, 0xb8, 0xf1, 0x03, 0x0f, 0x07, 0xd8, 0x05, 0xeb, + 0x88, 0x05, 0x6f, 0x6f, 0x04, 0xe0, 0x1f, 0x46, 0x02, 0xe0, 0x4f, 0x46, + 0x00, 0xe0, 0x00, 0x27, 0x38, 0x46, 0xbd, 0xe8, 0xfe, 0x83, 0x00, 0xbf, + 0xef, 0xdc, 0x01, 0x00, 0xc1, 0xdc, 0x01, 0x00, 0x00, 0x68, 0xf9, 0xf7, + 0x0c, 0xbc, 0x10, 0xb5, 0x04, 0x68, 0xb4, 0xb0, 0x51, 0xb1, 0x01, 0x71, + 0xc9, 0x22, 0x00, 0x21, 0x01, 0xa8, 0xf3, 0xf3, 0xc3, 0xf0, 0x23, 0x6b, + 0x01, 0xa9, 0x18, 0x69, 0x02, 0xf0, 0x24, 0xfd, 0x34, 0xb0, 0x10, 0xbd, + 0x4f, 0xf0, 0xff, 0x30, 0x70, 0x47, 0x4f, 0xf0, 0xff, 0x30, 0x70, 0x47, + 0x2d, 0xe9, 0xf7, 0x43, 0x0a, 0x9f, 0x0b, 0x9e, 0x0c, 0x46, 0x05, 0x46, + 0x90, 0x46, 0x99, 0x46, 0x00, 0x97, 0x01, 0x96, 0x3f, 0xf0, 0xc6, 0xdd, + 0x4b, 0x46, 0x28, 0x46, 0x21, 0x46, 0x42, 0x46, 0x00, 0x97, 0x01, 0x96, + 0x3f, 0xf0, 0xac, 0xde, 0x21, 0x46, 0x01, 0x22, 0x28, 0x46, 0x3f, 0xf0, + 0x8f, 0xde, 0xb4, 0xf8, 0x34, 0x35, 0xd9, 0x06, 0x06, 0xd5, 0x28, 0x46, + 0x21, 0x46, 0x03, 0xb0, 0xbd, 0xe8, 0xf0, 0x43, 0x3d, 0xf0, 0xbe, 0x9c, + 0x03, 0xb0, 0xbd, 0xe8, 0xf0, 0x83, 0x40, 0x6b, 0x70, 0x47, 0xf8, 0xb5, + 0x04, 0x46, 0x0e, 0x46, 0x17, 0x46, 0x90, 0xf8, 0x56, 0x51, 0xfe, 0xf3, + 0x07, 0xf6, 0x60, 0xb1, 0x0f, 0xe0, 0x73, 0x6a, 0xdb, 0x06, 0x06, 0xd4, + 0x94, 0xf8, 0x57, 0x31, 0x43, 0xf0, 0x02, 0x03, 0x84, 0xf8, 0x57, 0x31, + 0x03, 0xe0, 0x38, 0x3f, 0x38, 0x36, 0x37, 0x2f, 0xf1, 0xd8, 0x84, 0xf8, + 0x56, 0x51, 0xf8, 0xbd, 0xf8, 0xb5, 0x04, 0x46, 0x0e, 0x46, 0x17, 0x46, + 0x90, 0xf8, 0x56, 0x51, 0xfe, 0xf3, 0x50, 0xf6, 0x60, 0xb1, 0x0f, 0xe0, + 0xf3, 0x88, 0xda, 0x06, 0x06, 0xd4, 0x94, 0xf8, 0x57, 0x31, 0x43, 0xf0, + 0x01, 0x03, 0x84, 0xf8, 0x57, 0x31, 0x03, 0xe0, 0x08, 0x3f, 0x08, 0x36, + 0x07, 0x2f, 0xf1, 0xd8, 0x84, 0xf8, 0x56, 0x51, 0xf8, 0xbd, 0x2d, 0xe9, + 0xf0, 0x41, 0xa2, 0xb0, 0x04, 0x46, 0x88, 0x46, 0x90, 0xf8, 0x55, 0x61, + 0x90, 0xf8, 0x56, 0x71, 0x90, 0xf8, 0x54, 0x51, 0x88, 0x22, 0x68, 0x46, + 0xf2, 0xf3, 0xe4, 0xf7, 0x20, 0x46, 0x41, 0x46, 0xff, 0xf3, 0x2e, 0xf0, + 0x00, 0x28, 0x32, 0xd1, 0x00, 0x9b, 0x84, 0xf8, 0x56, 0x71, 0x9d, 0x42, + 0x84, 0xf8, 0x54, 0x51, 0x29, 0xd0, 0x1b, 0xb9, 0x94, 0xf8, 0x57, 0x21, + 0x72, 0xb1, 0x11, 0xe0, 0x02, 0x2b, 0x04, 0xd1, 0x94, 0xf8, 0x57, 0x21, + 0x12, 0xf0, 0x01, 0x0f, 0x05, 0xe0, 0x01, 0x2b, 0x06, 0xd1, 0x94, 0xf8, + 0x57, 0x21, 0x12, 0xf0, 0x02, 0x0f, 0x01, 0xd1, 0xfe, 0x22, 0x12, 0xe0, + 0x85, 0xb9, 0x0b, 0xe0, 0x01, 0x2d, 0x02, 0xd1, 0x12, 0xf0, 0x01, 0x0f, + 0x03, 0xe0, 0x02, 0x2d, 0x03, 0xd1, 0x12, 0xf0, 0x02, 0x0f, 0x05, 0xd1, + 0x07, 0xe0, 0x35, 0xb9, 0x94, 0xf8, 0x55, 0x21, 0xb2, 0x42, 0x02, 0xd2, + 0x00, 0x22, 0x84, 0xf8, 0x56, 0x21, 0x84, 0xf8, 0x54, 0x31, 0x22, 0xb0, + 0xbd, 0xe8, 0xf0, 0x81, 0x10, 0xb5, 0x04, 0x46, 0xff, 0xf3, 0x88, 0xf0, + 0x00, 0x23, 0x84, 0xf8, 0x57, 0x31, 0xa4, 0xf8, 0x58, 0x31, 0xc4, 0xf8, + 0x5c, 0x31, 0x84, 0xf8, 0x56, 0x31, 0x10, 0xbd, 0x38, 0xb5, 0x04, 0x46, + 0x0d, 0x46, 0xff, 0xf3, 0xe7, 0xf0, 0x00, 0xbb, 0xa3, 0x6d, 0xdd, 0xb1, + 0xeb, 0xb9, 0xd4, 0xf8, 0x54, 0x21, 0x0e, 0x4b, 0x13, 0x40, 0x7b, 0xb1, + 0x94, 0xf8, 0x54, 0x31, 0x02, 0x2b, 0x04, 0xd1, 0x94, 0xf8, 0x57, 0x31, + 0x13, 0xf0, 0x01, 0x0f, 0x05, 0xe0, 0x01, 0x2b, 0x06, 0xd1, 0x94, 0xf8, + 0x57, 0x31, 0x13, 0xf0, 0x02, 0x0f, 0x01, 0xd1, 0xfe, 0x23, 0x00, 0xe0, + 0x00, 0x23, 0x84, 0xf8, 0x56, 0x31, 0x38, 0xbd, 0x0b, 0xb1, 0x84, 0xf8, + 0x56, 0x01, 0x38, 0xbd, 0xff, 0x00, 0x00, 0xff, 0xf0, 0xb5, 0x91, 0xb0, + 0xad, 0xf1, 0x04, 0x06, 0x04, 0x46, 0x05, 0x46, 0xb6, 0x46, 0x00, 0x23, + 0x09, 0xe0, 0x07, 0x69, 0x01, 0x33, 0x97, 0xf8, 0x07, 0xc0, 0x4e, 0xf8, + 0x04, 0xcf, 0xd7, 0xf8, 0x34, 0xc0, 0x87, 0xf8, 0x07, 0xc0, 0xb4, 0xf9, + 0x10, 0x70, 0x04, 0x30, 0xbb, 0x42, 0xf0, 0xdb, 0x20, 0x46, 0xff, 0xf3, + 0xa9, 0xf1, 0x00, 0x23, 0x04, 0xe0, 0x2a, 0x69, 0x56, 0xf8, 0x04, 0x1f, + 0x01, 0x33, 0xd1, 0x71, 0xb4, 0xf9, 0x10, 0x20, 0x04, 0x35, 0x93, 0x42, + 0xf5, 0xdb, 0x11, 0xb0, 0xf0, 0xbd, 0x38, 0xb5, 0x15, 0x46, 0x04, 0x46, + 0xff, 0xf3, 0x2c, 0xf2, 0x2b, 0x68, 0x0b, 0xb1, 0x02, 0x23, 0xa3, 0x65, + 0x38, 0xbd, 0x0e, 0x29, 0x73, 0xb5, 0x05, 0x46, 0x0b, 0xd0, 0x0f, 0x29, + 0x10, 0xd1, 0x11, 0x46, 0x01, 0xa8, 0x04, 0x22, 0xf2, 0xf3, 0x32, 0xf7, + 0x28, 0x46, 0x01, 0x99, 0xf3, 0xf7, 0x27, 0xff, 0x08, 0xe0, 0xb0, 0xf8, + 0x58, 0x31, 0x00, 0x20, 0x03, 0xf0, 0x01, 0x03, 0x13, 0x60, 0x01, 0xe0, + 0xff, 0xf3, 0x52, 0xf2, 0x7c, 0xbd, 0xf8, 0xb5, 0x04, 0x46, 0x0f, 0x46, + 0x86, 0x6e, 0xff, 0xf3, 0xf3, 0xf6, 0x05, 0x46, 0x80, 0xb9, 0x04, 0x22, + 0x07, 0xf1, 0x14, 0x01, 0x04, 0xf5, 0xae, 0x70, 0xf2, 0xf3, 0x14, 0xf7, + 0xd4, 0xf8, 0x5c, 0x31, 0x4f, 0xf4, 0x7a, 0x72, 0x53, 0x43, 0x71, 0x1c, + 0xc4, 0xf8, 0x5c, 0x31, 0x08, 0xbf, 0xa6, 0x66, 0x28, 0x46, 0xf8, 0xbd, + 0x83, 0x6e, 0x01, 0x33, 0x01, 0xd0, 0xfe, 0xf3, 0xab, 0xb5, 0x70, 0x47, + 0xf8, 0xb5, 0x0c, 0x29, 0x04, 0x46, 0x0d, 0x46, 0x17, 0x46, 0x90, 0xf8, + 0x53, 0x61, 0x0d, 0xd1, 0x00, 0x21, 0x01, 0x22, 0xff, 0xf3, 0x4a, 0xf1, + 0x20, 0x46, 0x00, 0x21, 0x01, 0x22, 0xff, 0xf3, 0x01, 0xf1, 0x00, 0x23, + 0x84, 0xf8, 0xce, 0x30, 0x84, 0xf8, 0xcd, 0x30, 0xa3, 0x6e, 0x29, 0x46, + 0x58, 0x1c, 0x08, 0xbf, 0x84, 0xf8, 0x56, 0x31, 0x20, 0x46, 0x3a, 0x46, + 0xff, 0xf3, 0x56, 0xf2, 0xb4, 0xf8, 0x6c, 0x30, 0x03, 0xf0, 0xc0, 0x03, + 0xc0, 0x2b, 0x16, 0xd1, 0xd4, 0xf8, 0x5c, 0x31, 0x9b, 0xb1, 0x94, 0xf8, + 0x53, 0x31, 0xb3, 0x42, 0x0f, 0xd9, 0xe3, 0x68, 0xa1, 0x68, 0x98, 0x68, + 0x00, 0xf0, 0x42, 0xda, 0xe3, 0x68, 0xa1, 0x68, 0x98, 0x68, 0xd4, 0xf8, + 0x5c, 0x21, 0x01, 0x23, 0x00, 0xf0, 0xf2, 0xd9, 0x4f, 0xf0, 0xff, 0x33, + 0xa3, 0x66, 0xf8, 0xbd, 0x2d, 0xe9, 0xf8, 0x43, 0x04, 0x46, 0x89, 0x46, + 0xff, 0xf3, 0x1e, 0xf7, 0xf7, 0xf3, 0x02, 0xf2, 0x94, 0xf8, 0x54, 0x31, + 0x80, 0x46, 0x01, 0x2b, 0x1d, 0xd8, 0x26, 0x46, 0x00, 0x25, 0x16, 0xe0, + 0x77, 0x69, 0xbb, 0x79, 0x02, 0x2b, 0x10, 0xd1, 0xb4, 0xf8, 0x6c, 0x30, + 0xdb, 0x05, 0x0c, 0xd5, 0x20, 0x46, 0x49, 0x46, 0x42, 0x46, 0xf3, 0xf7, + 0x0b, 0xfe, 0x30, 0xb9, 0x04, 0x23, 0xbb, 0x71, 0x94, 0xf8, 0xcd, 0x30, + 0x01, 0x3b, 0x84, 0xf8, 0xcd, 0x30, 0x01, 0x35, 0x04, 0x36, 0xb4, 0xf9, + 0x10, 0x30, 0x9d, 0x42, 0xe4, 0xdb, 0xbd, 0xe8, 0xf8, 0x83, 0x70, 0x47, + 0x00, 0x20, 0x70, 0x47, 0x70, 0x47, 0x00, 0x20, 0x70, 0x47, 0x70, 0x47, + 0x00, 0x20, 0x70, 0x47, 0x70, 0x47, 0x00, 0x20, 0x70, 0x47, 0x70, 0x47, + 0x70, 0x47, 0x70, 0x47, 0x70, 0x47, 0x70, 0x47, 0x70, 0x47, 0x70, 0x47, + 0x70, 0x47, 0x4f, 0xf0, 0xff, 0x30, 0x70, 0x47, 0x70, 0x47, 0x00, 0x20, + 0x70, 0x47, 0x00, 0x20, 0x70, 0x47, 0x70, 0x47, 0x70, 0x47, 0x70, 0x47, + 0x00, 0x20, 0x70, 0x47, 0x70, 0x47, 0x2d, 0xe9, 0xff, 0x41, 0x0b, 0x9e, + 0x0c, 0x46, 0xb6, 0xf8, 0x62, 0x50, 0x0a, 0x9f, 0x15, 0xf0, 0x0f, 0x0f, + 0xdd, 0xf8, 0x30, 0x80, 0x14, 0xd0, 0x40, 0xf2, 0x37, 0x15, 0x3d, 0x40, + 0x85, 0xb1, 0x00, 0x97, 0x01, 0x96, 0xcd, 0xf8, 0x08, 0x80, 0x0b, 0xf0, + 0x91, 0xdf, 0x98, 0xf9, 0x34, 0x30, 0x33, 0xb1, 0x63, 0x78, 0x02, 0x2b, + 0x03, 0xd9, 0x02, 0x3b, 0x63, 0x70, 0x84, 0x1e, 0x00, 0xe0, 0x04, 0x46, + 0x20, 0x46, 0x04, 0xb0, 0xbd, 0xe8, 0xf0, 0x81, 0xf0, 0xb5, 0x06, 0x9d, + 0x0f, 0x46, 0xb5, 0xf8, 0x62, 0x40, 0x05, 0x9e, 0x14, 0xf4, 0x74, 0x7f, + 0x07, 0xd0, 0x40, 0xf2, 0x37, 0x14, 0x34, 0x40, 0x1c, 0xb1, 0xbd, 0xe8, + 0xf0, 0x40, 0x0b, 0xf0, 0xa5, 0x9d, 0x38, 0x46, 0xf0, 0xbd, 0x00, 0x00, + 0x2d, 0xe9, 0xf0, 0x4f, 0x8f, 0xb0, 0x0b, 0x46, 0x93, 0x46, 0x1d, 0x99, + 0x00, 0x22, 0x05, 0x46, 0x1a, 0x9e, 0xdd, 0xf8, 0x6c, 0xa0, 0x09, 0x92, + 0x0a, 0x92, 0x05, 0x93, 0xdd, 0xf8, 0x60, 0x90, 0x19, 0x9f, 0x30, 0xf0, + 0x67, 0xd8, 0x05, 0x9b, 0x0b, 0xf0, 0x01, 0x02, 0xd0, 0xf8, 0xd8, 0x82, + 0x04, 0x46, 0x00, 0x92, 0x19, 0x46, 0x28, 0x68, 0x32, 0x46, 0x53, 0x46, + 0x13, 0xf0, 0xc4, 0xdf, 0x00, 0x28, 0x40, 0xf0, 0xb5, 0x81, 0x03, 0x2f, + 0x0c, 0xd9, 0x04, 0x22, 0x09, 0xa8, 0x49, 0x46, 0xf2, 0xf3, 0x12, 0xf6, + 0x07, 0x2f, 0x05, 0xd9, 0x0a, 0xa8, 0x09, 0xf1, 0x04, 0x01, 0x04, 0x22, + 0xf2, 0xf3, 0x0a, 0xf6, 0xbb, 0xf1, 0x13, 0x0f, 0x00, 0xf2, 0x85, 0x81, + 0xdf, 0xe8, 0x1b, 0xf0, 0x14, 0x00, 0x18, 0x00, 0x83, 0x01, 0x83, 0x01, + 0x45, 0x00, 0x22, 0x00, 0x86, 0x00, 0x91, 0x00, 0xa2, 0x00, 0xa8, 0x00, + 0xb6, 0x00, 0x83, 0x01, 0x83, 0x01, 0xb9, 0x00, 0x7a, 0x01, 0x7f, 0x01, + 0x83, 0x01, 0x83, 0x01, 0xf7, 0x00, 0x0b, 0x01, 0x28, 0x46, 0x0a, 0xf0, + 0xcf, 0xdc, 0x8d, 0xe0, 0x28, 0x46, 0x09, 0x99, 0x0a, 0xf0, 0xf4, 0xdc, + 0x00, 0x28, 0x0c, 0xbf, 0x6f, 0xf0, 0x1c, 0x07, 0x00, 0x27, 0x7c, 0xe1, + 0xa4, 0x79, 0x00, 0x2c, 0x40, 0xf0, 0x60, 0x81, 0xd8, 0xf8, 0x2c, 0x10, + 0x41, 0xb1, 0x68, 0x68, 0xd8, 0xf8, 0x30, 0x20, 0xf7, 0xf3, 0x92, 0xf4, + 0xc8, 0xf8, 0x2c, 0x40, 0xc8, 0xf8, 0x30, 0x40, 0x00, 0x2f, 0x00, 0xf0, + 0x6a, 0x81, 0x68, 0x68, 0x39, 0x46, 0xf7, 0xf3, 0x77, 0xf4, 0xc8, 0xf8, + 0x2c, 0x00, 0x00, 0x28, 0x00, 0xf0, 0x4b, 0x81, 0xc8, 0xf8, 0x30, 0x70, + 0x49, 0x46, 0x3a, 0x46, 0xf2, 0xf3, 0xc0, 0xf5, 0x37, 0xe1, 0xa3, 0x79, + 0x00, 0x2b, 0x00, 0xf0, 0x43, 0x81, 0x48, 0x46, 0x04, 0xf1, 0xbc, 0x01, + 0x06, 0x22, 0xf2, 0xf3, 0x99, 0xf5, 0x07, 0x46, 0xc0, 0xb9, 0xa2, 0x6d, + 0xb4, 0xf8, 0x62, 0x30, 0x8d, 0xe8, 0x14, 0x00, 0xd4, 0xf8, 0xd4, 0x22, + 0x31, 0x46, 0x02, 0x92, 0x28, 0x46, 0x52, 0x46, 0xff, 0xf7, 0x31, 0xff, + 0x32, 0x1a, 0x01, 0x46, 0xa0, 0x6d, 0xb4, 0xf8, 0x62, 0x30, 0x52, 0x44, + 0x8d, 0xe8, 0x11, 0x00, 0x28, 0x46, 0xff, 0xf7, 0x4b, 0xff, 0x34, 0xe1, + 0x28, 0x46, 0x49, 0x46, 0x46, 0xf0, 0xa8, 0xd9, 0x00, 0x28, 0x00, 0xf0, + 0x1e, 0x81, 0xd0, 0xf8, 0xe8, 0x40, 0x00, 0x2c, 0x00, 0xf0, 0x19, 0x81, + 0xd0, 0xf8, 0xec, 0x30, 0x9a, 0x45, 0xc0, 0xf2, 0x1f, 0x81, 0x62, 0x78, + 0x30, 0x46, 0x21, 0x46, 0x02, 0x32, 0xf2, 0xf3, 0x83, 0xf5, 0x63, 0x78, + 0x00, 0x27, 0xf6, 0x18, 0xf7, 0x70, 0x18, 0xe1, 0xb4, 0xf9, 0x5e, 0x30, + 0x2b, 0xb9, 0xb4, 0xf9, 0x5c, 0x30, 0x00, 0x33, 0x18, 0xbf, 0x01, 0x23, + 0xec, 0xe0, 0x02, 0x23, 0xea, 0xe0, 0x09, 0x9b, 0x02, 0x2b, 0x04, 0xd1, + 0x00, 0x23, 0xa4, 0xf8, 0x5c, 0x30, 0x01, 0x23, 0x05, 0xe0, 0x00, 0x33, + 0x18, 0xbf, 0x01, 0x23, 0xa4, 0xf8, 0x5c, 0x30, 0x00, 0x23, 0xa4, 0xf8, + 0x5e, 0x30, 0xda, 0xe0, 0xd5, 0xf8, 0x34, 0x07, 0xfa, 0xf7, 0x90, 0xf8, + 0x30, 0x60, 0xd4, 0xe0, 0xd5, 0xf8, 0x34, 0x07, 0x09, 0x9c, 0xfa, 0xf7, + 0x8f, 0xf8, 0x84, 0x42, 0x00, 0xf3, 0xe2, 0x80, 0xd5, 0xf8, 0x34, 0x07, + 0x09, 0x99, 0xfa, 0xf7, 0x84, 0xf8, 0xc6, 0xe0, 0xb5, 0xf8, 0xbe, 0x38, + 0xc2, 0xe0, 0x2b, 0x68, 0x93, 0xf8, 0xa0, 0x30, 0x00, 0x2b, 0x38, 0xd0, + 0x72, 0x49, 0x06, 0x22, 0x07, 0xa8, 0xf2, 0xf3, 0x41, 0xf5, 0x31, 0x46, + 0x04, 0x22, 0x0c, 0xa8, 0xf2, 0xf3, 0x3c, 0xf5, 0x31, 0x1d, 0x04, 0x22, + 0x0d, 0xa8, 0xf2, 0xf3, 0x37, 0xf5, 0x07, 0xa8, 0x06, 0xf1, 0x08, 0x01, + 0x06, 0x22, 0xf2, 0xf3, 0x31, 0xf5, 0x0d, 0x9b, 0x53, 0xb9, 0xd5, 0xf8, + 0x68, 0x21, 0x91, 0x79, 0x81, 0xb9, 0x52, 0x69, 0x01, 0x2a, 0x0d, 0xd0, + 0x2a, 0x68, 0x92, 0xf8, 0x3f, 0x20, 0x4a, 0xb9, 0x07, 0xaa, 0x00, 0x92, + 0x10, 0x36, 0x28, 0x46, 0x21, 0x46, 0x0c, 0x9a, 0x01, 0x96, 0x17, 0xf0, + 0xc9, 0xde, 0x71, 0xe0, 0x2b, 0x68, 0x1b, 0x7e, 0x00, 0x2b, 0x00, 0xf0, + 0xa6, 0x80, 0x28, 0x46, 0x21, 0x46, 0x07, 0xaa, 0x06, 0xf1, 0x10, 0x03, + 0x17, 0xf0, 0xa8, 0xde, 0x64, 0xe0, 0x03, 0x2f, 0x40, 0xf2, 0xa0, 0x80, + 0x09, 0x99, 0x00, 0x29, 0x04, 0xdb, 0x28, 0x46, 0x0b, 0xaa, 0x2f, 0xf0, + 0x85, 0xde, 0x04, 0x46, 0x0c, 0xb1, 0x23, 0x79, 0x76, 0xe0, 0x0b, 0x9b, + 0x1e, 0x33, 0x40, 0xf0, 0x8f, 0x80, 0x34, 0x60, 0x8c, 0xe0, 0xba, 0xf1, + 0x07, 0x0f, 0x40, 0xf3, 0x8b, 0x80, 0x0a, 0x9e, 0x03, 0x2e, 0x05, 0xd0, + 0xa6, 0xf1, 0x02, 0x01, 0x4e, 0x42, 0x46, 0xeb, 0x01, 0x06, 0x00, 0xe0, + 0x00, 0x26, 0x09, 0x99, 0x00, 0x29, 0x21, 0xdb, 0x28, 0x46, 0x0b, 0xaa, + 0x2f, 0xf0, 0x66, 0xde, 0x04, 0x46, 0xd8, 0xb9, 0x0b, 0x9b, 0x1e, 0x33, + 0x1a, 0xd1, 0x0a, 0x9b, 0x00, 0x2b, 0x17, 0xdd, 0x22, 0x46, 0x23, 0x46, + 0x86, 0xf0, 0x01, 0x06, 0x28, 0x46, 0x09, 0x99, 0x00, 0x96, 0x2f, 0xf0, + 0xef, 0xda, 0x04, 0x46, 0x70, 0xb1, 0x28, 0x46, 0x21, 0x46, 0x2f, 0xf0, + 0xd3, 0xdf, 0x07, 0x46, 0x50, 0xb1, 0x28, 0x46, 0x21, 0x46, 0x2f, 0xf0, + 0x27, 0xdf, 0x05, 0xe0, 0x00, 0x27, 0x03, 0xe0, 0x07, 0x46, 0x01, 0xe0, + 0x6f, 0xf0, 0x1a, 0x07, 0x0a, 0x9b, 0x03, 0x2b, 0x57, 0xd0, 0x00, 0x2f, + 0x55, 0xd1, 0x00, 0x2b, 0x27, 0xdd, 0x02, 0x2b, 0x02, 0xd0, 0x22, 0x79, + 0x00, 0x2a, 0x4e, 0xd1, 0x2a, 0x68, 0x12, 0x6f, 0x92, 0x07, 0x48, 0xd1, + 0xa2, 0x79, 0x92, 0xb1, 0x02, 0x2b, 0x05, 0xd0, 0x28, 0x46, 0x21, 0x46, + 0x2f, 0xf0, 0xe0, 0xdd, 0x07, 0x46, 0x40, 0xe0, 0x63, 0x79, 0x1b, 0xb1, + 0x28, 0x46, 0x21, 0x46, 0x2f, 0xf0, 0x24, 0xdc, 0x28, 0x46, 0x21, 0x46, + 0x2f, 0xf0, 0xfc, 0xde, 0x35, 0xe0, 0x63, 0x7e, 0x28, 0x46, 0x00, 0x92, + 0x01, 0x92, 0x21, 0x46, 0x04, 0xf1, 0x1a, 0x02, 0x2a, 0xf0, 0x8e, 0xd9, + 0x2b, 0xe0, 0x63, 0x79, 0x4b, 0xb3, 0x28, 0x46, 0x21, 0x46, 0x2f, 0xf0, + 0x0f, 0xdc, 0x24, 0xe0, 0x95, 0xf8, 0xc3, 0x34, 0x33, 0x60, 0x00, 0x27, + 0x1f, 0xe0, 0x09, 0x9b, 0x85, 0xf8, 0xc3, 0x34, 0xf9, 0xe7, 0x6f, 0xf0, + 0x16, 0x07, 0x18, 0xe0, 0x6f, 0xf0, 0x06, 0x07, 0x15, 0xe0, 0x6f, 0xf0, + 0x1a, 0x07, 0x12, 0xe0, 0x6f, 0xf0, 0x05, 0x07, 0x0f, 0xe0, 0x6f, 0xf0, + 0x1d, 0x07, 0x0c, 0xe0, 0x6f, 0xf0, 0x1c, 0x07, 0x09, 0xe0, 0x6f, 0xf0, + 0x03, 0x07, 0x06, 0xe0, 0x27, 0x46, 0x04, 0xe0, 0x6f, 0xf0, 0x0d, 0x07, + 0x01, 0xe0, 0x6f, 0xf0, 0x08, 0x07, 0x38, 0x46, 0x0f, 0xb0, 0xbd, 0xe8, + 0xf0, 0x8f, 0x00, 0xbf, 0x2c, 0x9e, 0x85, 0x00, 0x70, 0xb5, 0x05, 0x46, + 0x0e, 0x46, 0x1c, 0xf0, 0xe9, 0xdd, 0x04, 0x46, 0xc0, 0xb1, 0x31, 0x46, + 0x28, 0x46, 0x40, 0xf2, 0x6c, 0x52, 0x1c, 0xf0, 0xf3, 0xde, 0x06, 0x46, + 0x20, 0xb9, 0x28, 0x46, 0x21, 0x46, 0x1c, 0xf0, 0x4f, 0xde, 0x0a, 0xe0, + 0x21, 0x46, 0x40, 0xf2, 0x65, 0x52, 0xf2, 0xf3, 0x45, 0xf4, 0x28, 0x46, + 0x21, 0x46, 0x40, 0xf2, 0x65, 0x52, 0xf7, 0xf3, 0xfb, 0xf2, 0x34, 0x46, + 0x20, 0x46, 0x70, 0xbd, 0x30, 0xb5, 0x05, 0x4c, 0x85, 0x68, 0xa5, 0x42, + 0x03, 0xd0, 0xbd, 0xe8, 0x30, 0x40, 0xf2, 0xf3, 0x99, 0xb7, 0x00, 0x20, + 0x30, 0xbd, 0x00, 0xbf, 0x08, 0x00, 0x00, 0x20, 0x8b, 0x79, 0x10, 0xb5, + 0x04, 0x4c, 0x0b, 0xb1, 0x01, 0x23, 0x23, 0x70, 0x2f, 0xf0, 0x2a, 0xdc, + 0x00, 0x23, 0x23, 0x70, 0x10, 0xbd, 0x00, 0xbf, 0xf4, 0x0b, 0x02, 0x00, + 0x05, 0x4b, 0x02, 0x69, 0x19, 0x78, 0x29, 0xb1, 0xd2, 0xf8, 0xd0, 0x20, + 0x12, 0xb1, 0x00, 0x22, 0x1a, 0x70, 0x70, 0x47, 0x1a, 0xf0, 0xa8, 0x9d, + 0xf4, 0x0b, 0x02, 0x00, 0x38, 0xb5, 0x05, 0x46, 0xf3, 0xf7, 0x93, 0xfa, + 0x01, 0x28, 0x01, 0x46, 0x07, 0xdd, 0x04, 0x4c, 0x01, 0x23, 0x28, 0x46, + 0x23, 0x70, 0xfa, 0xf3, 0x23, 0xf6, 0x00, 0x23, 0x23, 0x70, 0x38, 0xbd, + 0xec, 0x0b, 0x02, 0x00, 0x10, 0xb5, 0x07, 0x4c, 0x23, 0x78, 0x01, 0x2b, + 0x09, 0xd0, 0x06, 0x4b, 0x1b, 0x78, 0x01, 0x2b, 0x05, 0xd0, 0x01, 0x23, + 0x23, 0x70, 0xfa, 0xf3, 0x83, 0xf7, 0x00, 0x23, 0x23, 0x70, 0x10, 0xbd, + 0x00, 0x0c, 0x02, 0x00, 0xec, 0x0b, 0x02, 0x00, 0x10, 0xb5, 0x04, 0x46, + 0xf9, 0xf3, 0xaa, 0xf7, 0x00, 0x23, 0x84, 0xf8, 0x17, 0x32, 0x84, 0xf8, + 0x18, 0x32, 0x10, 0xbd, 0x10, 0xb5, 0x90, 0xf8, 0x16, 0x32, 0x04, 0x46, + 0x5b, 0xb1, 0x08, 0x4b, 0x1b, 0x68, 0x43, 0xb1, 0xd0, 0xf8, 0x80, 0x11, + 0xd0, 0xf8, 0x84, 0x21, 0x02, 0x23, 0xc0, 0x68, 0x4a, 0x40, 0xfb, 0xf3, + 0x03, 0xf4, 0x20, 0x46, 0xbd, 0xe8, 0x10, 0x40, 0xf9, 0xf3, 0x3e, 0xb6, + 0xa0, 0x07, 0x02, 0x00, 0x0f, 0xb4, 0x30, 0xb5, 0x11, 0x4a, 0xad, 0xf5, + 0x03, 0x7d, 0x96, 0x45, 0x15, 0xd0, 0x10, 0x4a, 0x96, 0x45, 0x12, 0xd0, + 0x87, 0xab, 0x68, 0x46, 0x40, 0xf2, 0x01, 0x21, 0x86, 0x9a, 0x81, 0x93, + 0xf2, 0xf3, 0x52, 0xf5, 0x00, 0x25, 0x04, 0x46, 0x04, 0xe0, 0x1d, 0xf8, + 0x05, 0x00, 0xf7, 0xf3, 0x95, 0xf1, 0x01, 0x35, 0xa5, 0x42, 0xf8, 0xdb, + 0x00, 0xe0, 0x00, 0x24, 0x20, 0x46, 0x0d, 0xf5, 0x03, 0x7d, 0xbd, 0xe8, + 0x30, 0x40, 0x04, 0xb0, 0x70, 0x47, 0x00, 0xbf, 0xdb, 0x62, 0x82, 0x00, + 0xfb, 0x54, 0x82, 0x00, 0x2d, 0xe9, 0xf0, 0x47, 0x8c, 0xb0, 0x14, 0x9f, + 0x0e, 0x46, 0x98, 0x46, 0x39, 0x46, 0x00, 0x23, 0x04, 0x46, 0x15, 0x46, + 0x08, 0x93, 0x2f, 0xf0, 0xd1, 0xdd, 0x81, 0x46, 0xd0, 0xf8, 0xdc, 0xa2, + 0x65, 0xb1, 0xb8, 0xf1, 0x03, 0x0f, 0x09, 0xd9, 0x29, 0x46, 0x04, 0x22, + 0x08, 0xa8, 0xf2, 0xf3, 0x87, 0xf3, 0x08, 0xa8, 0x29, 0x46, 0x04, 0x22, + 0xf2, 0xf3, 0x82, 0xf3, 0x5f, 0x2e, 0x20, 0xdc, 0x5e, 0x2e, 0x80, 0xf2, + 0xc5, 0x81, 0x35, 0x2e, 0x79, 0xd0, 0x0e, 0xdc, 0x16, 0x2e, 0x00, 0xf0, + 0x7d, 0x81, 0x03, 0xdc, 0x15, 0x2e, 0x40, 0xf0, 0x35, 0x82, 0x6b, 0xe1, + 0x1c, 0x2e, 0x00, 0xf0, 0x8a, 0x81, 0x2f, 0x2e, 0x40, 0xf0, 0x2e, 0x82, + 0x33, 0xe1, 0x37, 0x2e, 0x00, 0xf0, 0xcd, 0x80, 0xc0, 0xf2, 0xac, 0x80, + 0x38, 0x2e, 0x00, 0xf0, 0xef, 0x80, 0x39, 0x2e, 0x40, 0xf0, 0x22, 0x82, + 0x09, 0xe1, 0xd7, 0x2e, 0x00, 0xf0, 0xbf, 0x81, 0x0d, 0xdc, 0xa5, 0x2e, + 0x00, 0xf0, 0x46, 0x81, 0x03, 0xdc, 0x9f, 0x2e, 0x40, 0xf0, 0x16, 0x82, + 0x73, 0xe1, 0xc4, 0x2e, 0x16, 0xd0, 0xc5, 0x2e, 0x40, 0xf0, 0x10, 0x82, + 0x30, 0xe0, 0xb6, 0xf5, 0x9f, 0x7f, 0x00, 0xf0, 0xc5, 0x81, 0x03, 0xdc, + 0xd8, 0x2e, 0x40, 0xf0, 0x07, 0x82, 0xae, 0xe1, 0x40, 0xf2, 0x3f, 0x13, + 0x9e, 0x42, 0x00, 0xf0, 0xca, 0x81, 0xb6, 0xf5, 0xa0, 0x7f, 0x40, 0xf0, + 0xfd, 0x81, 0xcf, 0xe1, 0xa3, 0x48, 0xff, 0xf7, 0x6d, 0xff, 0x01, 0x23, + 0xb8, 0xf1, 0x07, 0x0f, 0xc8, 0xbf, 0x69, 0x68, 0x20, 0x46, 0xd8, 0xbf, + 0x00, 0x21, 0x8d, 0xf8, 0x2f, 0x30, 0x09, 0x91, 0x13, 0xf0, 0xbe, 0xdc, + 0x07, 0x46, 0x00, 0x28, 0x40, 0xf0, 0xf0, 0x81, 0x08, 0x99, 0xca, 0x07, + 0x00, 0xf1, 0xd5, 0x81, 0x20, 0x46, 0x89, 0xb2, 0x16, 0xf0, 0x12, 0xdc, + 0x28, 0x60, 0xe5, 0xe1, 0x01, 0x23, 0xb8, 0xf1, 0x07, 0x0f, 0xc8, 0xbf, + 0x69, 0x68, 0x20, 0x46, 0xd8, 0xbf, 0x00, 0x21, 0x8d, 0xf8, 0x2f, 0x30, + 0x09, 0x91, 0x13, 0xf0, 0xa3, 0xdc, 0x07, 0x46, 0x00, 0x28, 0x40, 0xf0, + 0xd5, 0x81, 0x08, 0x9a, 0xd3, 0x07, 0x00, 0xf1, 0xba, 0x81, 0x91, 0xb2, + 0x20, 0x46, 0x12, 0x0c, 0x1c, 0xf0, 0x30, 0xdc, 0xca, 0xe1, 0x23, 0x68, + 0x1b, 0x7e, 0x00, 0x2b, 0x00, 0xf0, 0xc1, 0x81, 0xb8, 0xf1, 0x05, 0x0f, + 0x40, 0xf2, 0xc0, 0x81, 0xb8, 0xf1, 0x0d, 0x0f, 0x0b, 0xd9, 0x20, 0x46, + 0x05, 0xf1, 0x08, 0x01, 0xa8, 0xf1, 0x08, 0x02, 0x03, 0xf0, 0x3c, 0xdb, + 0x07, 0x46, 0x00, 0x28, 0x40, 0xf0, 0xb4, 0x81, 0x09, 0xe0, 0x29, 0x46, + 0x04, 0xa8, 0x06, 0x22, 0xf2, 0xf3, 0xe4, 0xf2, 0x00, 0x23, 0x06, 0x93, + 0x04, 0xad, 0x4f, 0xf0, 0x0e, 0x08, 0x99, 0xf8, 0x06, 0x60, 0xb6, 0xb9, + 0xda, 0xf8, 0x90, 0x10, 0x31, 0xb1, 0x60, 0x68, 0x9a, 0xf8, 0x94, 0x20, + 0xf7, 0xf3, 0x90, 0xf1, 0xca, 0xf8, 0x90, 0x60, 0x8a, 0xf8, 0x94, 0x80, + 0x60, 0x68, 0x41, 0x46, 0xf7, 0xf3, 0x78, 0xf1, 0xca, 0xf8, 0x90, 0x00, + 0x18, 0xb1, 0x29, 0x46, 0x42, 0x46, 0xf2, 0xf3, 0xc5, 0xf2, 0x48, 0x46, + 0x29, 0x46, 0x2b, 0xf0, 0x6b, 0xdb, 0xda, 0xf8, 0x90, 0x70, 0x00, 0x2f, + 0x0c, 0xbf, 0x07, 0x46, 0x00, 0x27, 0x83, 0xe1, 0x00, 0x23, 0x00, 0x93, + 0x20, 0x46, 0x29, 0x46, 0x42, 0x46, 0x09, 0xab, 0xf3, 0xf7, 0x29, 0xfe, + 0x07, 0x46, 0x00, 0x28, 0x40, 0xf0, 0x78, 0x81, 0x09, 0x9a, 0x03, 0x2a, + 0x00, 0xf0, 0x63, 0x81, 0x23, 0x6b, 0x19, 0x68, 0x8a, 0x42, 0x07, 0xd0, + 0x5b, 0x68, 0xd3, 0xf1, 0x01, 0x03, 0x38, 0xbf, 0x00, 0x23, 0x0e, 0x33, + 0x54, 0xf8, 0x23, 0x30, 0xd3, 0xf8, 0xf0, 0x30, 0x69, 0xe1, 0x00, 0x23, + 0x00, 0x93, 0x20, 0x46, 0x29, 0x46, 0x42, 0x46, 0x09, 0xab, 0xf3, 0xf7, + 0x0a, 0xfe, 0x07, 0x46, 0x00, 0x28, 0x40, 0xf0, 0x59, 0x81, 0x08, 0x9a, + 0x02, 0xf1, 0x64, 0x03, 0x67, 0x2b, 0x00, 0xf2, 0x3f, 0x81, 0x09, 0x9b, + 0x03, 0x2b, 0x04, 0xd0, 0x21, 0x6b, 0x09, 0x68, 0x8b, 0x42, 0x40, 0xf0, + 0x4b, 0x81, 0x00, 0x2a, 0x04, 0xdb, 0x20, 0x46, 0x21, 0x6b, 0x2b, 0xf0, + 0x69, 0xdc, 0x02, 0x46, 0x23, 0x6b, 0xc3, 0xf8, 0xfc, 0x20, 0xc3, 0xf8, + 0xf0, 0x20, 0x3d, 0xe1, 0x00, 0x23, 0x00, 0x93, 0x20, 0x46, 0x29, 0x46, + 0x42, 0x46, 0x09, 0xab, 0xf3, 0xf7, 0xe3, 0xfd, 0x07, 0x46, 0x00, 0x28, + 0x40, 0xf0, 0x32, 0x81, 0x09, 0x9a, 0x03, 0x2a, 0x00, 0xf0, 0x1d, 0x81, + 0x23, 0x6b, 0x19, 0x68, 0x8a, 0x42, 0x07, 0xd0, 0x5b, 0x68, 0xd3, 0xf1, + 0x01, 0x03, 0x38, 0xbf, 0x00, 0x23, 0x0e, 0x33, 0x54, 0xf8, 0x23, 0x30, + 0xd3, 0xf8, 0xf4, 0x30, 0x23, 0xe1, 0x00, 0x23, 0x00, 0x93, 0x20, 0x46, + 0x29, 0x46, 0x42, 0x46, 0x09, 0xab, 0xf3, 0xf7, 0xc4, 0xfd, 0x07, 0x46, + 0x00, 0x28, 0x40, 0xf0, 0x13, 0x81, 0x08, 0x9b, 0x64, 0x2b, 0x00, 0xf2, + 0xfe, 0x80, 0x09, 0x9a, 0x03, 0x2a, 0x04, 0xd0, 0x21, 0x6b, 0x09, 0x68, + 0x8a, 0x42, 0x40, 0xf0, 0x07, 0x81, 0x22, 0x6b, 0xc2, 0xf8, 0x00, 0x31, + 0xc2, 0xf8, 0xf4, 0x30, 0x00, 0xe1, 0x23, 0x68, 0x08, 0x9d, 0x93, 0xf8, + 0x3f, 0x30, 0x00, 0x2b, 0x40, 0xf0, 0xec, 0x80, 0xd4, 0xf8, 0x68, 0x01, + 0x83, 0x79, 0x13, 0xb1, 0x04, 0x21, 0x44, 0xf0, 0x45, 0xdd, 0x00, 0x35, + 0x94, 0xf8, 0x72, 0x32, 0x18, 0xbf, 0x01, 0x25, 0x84, 0xf8, 0x50, 0x57, + 0x84, 0xf8, 0x59, 0x55, 0x00, 0x2b, 0x40, 0xf0, 0xb1, 0x80, 0x04, 0xf5, + 0xaa, 0x61, 0xd4, 0xf8, 0x5c, 0x01, 0x0d, 0xb1, 0x0e, 0x31, 0x00, 0xe0, + 0x0a, 0x31, 0x36, 0xf0, 0x09, 0xdb, 0x9a, 0xe0, 0x01, 0x23, 0x00, 0x22, + 0x02, 0x93, 0x20, 0x46, 0x0e, 0x49, 0x13, 0x46, 0x8d, 0xe8, 0x20, 0x01, + 0x03, 0x97, 0x13, 0xf0, 0x1b, 0xdc, 0x8e, 0xe0, 0xb9, 0xf9, 0x5e, 0x30, + 0x2b, 0xb9, 0xb9, 0xf9, 0x5c, 0x30, 0x00, 0x33, 0x18, 0xbf, 0x01, 0x23, + 0x00, 0xe0, 0x02, 0x23, 0x2b, 0x60, 0x8d, 0xe0, 0x08, 0x9b, 0x02, 0x2b, + 0x08, 0xd1, 0x00, 0x23, 0xa9, 0xf8, 0x5c, 0x30, 0x01, 0x23, 0x09, 0xe0, + 0x25, 0xdd, 0x01, 0x00, 0x1c, 0x73, 0x86, 0x00, 0x00, 0x33, 0x18, 0xbf, + 0x01, 0x23, 0xa9, 0xf8, 0x5c, 0x30, 0x00, 0x23, 0xa9, 0xf8, 0x5e, 0x30, + 0x78, 0xe0, 0x23, 0x68, 0x01, 0x21, 0x18, 0x69, 0xfb, 0xf3, 0x7a, 0xf3, + 0x72, 0xe0, 0xa8, 0xf1, 0x04, 0x08, 0x06, 0x23, 0xb8, 0xfb, 0xf3, 0xf3, + 0x2b, 0x60, 0xd4, 0xf8, 0x00, 0x05, 0x00, 0x23, 0x0a, 0xa9, 0x08, 0x93, + 0x45, 0xf0, 0x80, 0xda, 0x11, 0xe0, 0x3b, 0x7e, 0x98, 0x07, 0x0e, 0xd5, + 0x08, 0x98, 0x2a, 0x68, 0x43, 0x1c, 0x9a, 0x42, 0x08, 0x93, 0xc0, 0xf0, + 0x8f, 0x80, 0x06, 0x22, 0x02, 0xfb, 0x00, 0x50, 0x07, 0xf1, 0x1a, 0x01, + 0x04, 0x30, 0xf2, 0xf3, 0xbf, 0xf1, 0x0a, 0xa8, 0x45, 0xf0, 0x72, 0xda, + 0x07, 0x46, 0x00, 0x28, 0xe7, 0xd1, 0x85, 0xe0, 0xb8, 0xf1, 0x07, 0x0f, + 0xc8, 0xbf, 0x69, 0x68, 0x20, 0x46, 0xd8, 0xbf, 0x00, 0x21, 0x13, 0xf0, + 0x43, 0xdb, 0x07, 0x46, 0x00, 0x28, 0x75, 0xd1, 0x3e, 0x49, 0x3f, 0x48, + 0xff, 0xf7, 0xde, 0xfd, 0x23, 0x6b, 0x0d, 0xf1, 0x2f, 0x02, 0x00, 0x92, + 0x18, 0x69, 0x31, 0x46, 0x42, 0x46, 0x2b, 0x46, 0x02, 0xf0, 0x37, 0xfc, + 0x25, 0xe0, 0xd4, 0xf8, 0x68, 0x31, 0x9f, 0x79, 0x00, 0x2f, 0x56, 0xd1, + 0x94, 0xf8, 0x16, 0x37, 0x63, 0xe0, 0xd4, 0xf8, 0x68, 0x31, 0x9b, 0x79, + 0x00, 0x2b, 0x4e, 0xd1, 0x22, 0x6b, 0x20, 0x46, 0x12, 0x68, 0x29, 0x46, + 0x00, 0x92, 0x01, 0x22, 0x01, 0x92, 0x02, 0x93, 0x03, 0x93, 0xfd, 0xf7, + 0x23, 0xff, 0x0c, 0xe0, 0x99, 0xf8, 0x06, 0x30, 0x00, 0x2b, 0x41, 0xd1, + 0x99, 0xf8, 0x11, 0x30, 0x00, 0x2b, 0x3d, 0xd0, 0xd9, 0xf8, 0x0c, 0x00, + 0x29, 0x46, 0x0b, 0xf0, 0x7b, 0xfc, 0x07, 0x46, 0x3e, 0xe0, 0x23, 0x68, + 0x1b, 0x7e, 0x00, 0x2b, 0x35, 0xd0, 0x20, 0x46, 0x29, 0x46, 0x42, 0x46, + 0x12, 0xf0, 0x3a, 0xdd, 0x00, 0x27, 0x33, 0xe0, 0xb8, 0xf1, 0x43, 0x0f, + 0x2e, 0xd9, 0x1e, 0x4c, 0x29, 0x46, 0x03, 0x22, 0x20, 0x46, 0xf2, 0xf3, + 0x61, 0xf1, 0xeb, 0x78, 0x29, 0x1d, 0xe3, 0x70, 0x14, 0x22, 0x1a, 0x48, + 0xf2, 0xf3, 0x5a, 0xf1, 0x05, 0xf1, 0x18, 0x01, 0x1d, 0x22, 0x18, 0x48, + 0xf2, 0xf3, 0x54, 0xf1, 0x05, 0xf1, 0x35, 0x01, 0x0e, 0x22, 0x16, 0x48, + 0xf2, 0xf3, 0x4e, 0xf1, 0xe0, 0xe7, 0x6f, 0xf0, 0x14, 0x07, 0x13, 0xe0, + 0x6f, 0xf0, 0x1c, 0x07, 0x10, 0xe0, 0x6f, 0xf0, 0x02, 0x07, 0x0d, 0xe0, + 0x6f, 0xf0, 0x1b, 0x07, 0x0a, 0xe0, 0x6f, 0xf0, 0x0f, 0x07, 0x07, 0xe0, + 0x6f, 0xf0, 0x16, 0x07, 0x04, 0xe0, 0x6f, 0xf0, 0x03, 0x07, 0x01, 0xe0, + 0x6f, 0xf0, 0x0d, 0x07, 0x38, 0x46, 0x0c, 0xb0, 0xbd, 0xe8, 0xf0, 0x87, + 0x08, 0x9b, 0x2b, 0x60, 0xf8, 0xe7, 0x00, 0xbf, 0xb1, 0xdd, 0x01, 0x00, + 0x31, 0xdd, 0x01, 0x00, 0x68, 0x00, 0x02, 0x00, 0x34, 0xc7, 0x01, 0x00, + 0x98, 0xc2, 0x01, 0x00, 0x08, 0x0c, 0x02, 0x00, 0x2d, 0xe9, 0xff, 0x47, + 0x0c, 0x9c, 0x05, 0x46, 0xd2, 0xf8, 0xd4, 0x62, 0x17, 0x46, 0x98, 0x46, + 0xd4, 0xf8, 0x00, 0xa0, 0x00, 0x94, 0x0c, 0xf0, 0x51, 0xd9, 0x2a, 0x68, + 0x92, 0xf8, 0x46, 0x30, 0x98, 0x07, 0x39, 0xd0, 0xd7, 0xf8, 0xcc, 0x30, + 0xd9, 0x04, 0x35, 0xd4, 0x96, 0xf9, 0x34, 0x10, 0x00, 0x29, 0x31, 0xd1, + 0x52, 0x6b, 0x7a, 0xb3, 0x13, 0xf0, 0x02, 0x09, 0x2c, 0xd1, 0x02, 0xa8, + 0x16, 0x49, 0x03, 0x22, 0x27, 0x68, 0xf2, 0xf3, 0xfd, 0xf0, 0x02, 0x23, + 0x8d, 0xf8, 0x0b, 0x30, 0x01, 0x23, 0x8d, 0xf8, 0x0d, 0x30, 0x95, 0xf8, + 0xfa, 0x31, 0x47, 0x44, 0x8d, 0xf8, 0x0c, 0x90, 0x33, 0xb1, 0x96, 0xf9, + 0x6a, 0x30, 0x00, 0x2b, 0x03, 0xda, 0x95, 0xf8, 0x0a, 0x97, 0x00, 0xe0, + 0x99, 0x46, 0xd0, 0x44, 0xb8, 0x45, 0x02, 0xab, 0x28, 0xbf, 0xc7, 0xeb, + 0x08, 0x01, 0x00, 0x93, 0x38, 0xbf, 0x00, 0x21, 0x38, 0x46, 0x07, 0x23, + 0xdd, 0x22, 0x8d, 0xf8, 0x0e, 0x90, 0x1c, 0xf0, 0xe3, 0xd9, 0x23, 0x68, + 0x09, 0x33, 0x23, 0x60, 0xbd, 0xe8, 0xff, 0x87, 0xc3, 0xb7, 0x01, 0x00, + 0x2d, 0xe9, 0xf0, 0x41, 0x90, 0x46, 0xd0, 0xf8, 0xd8, 0x22, 0x06, 0x46, + 0x52, 0x68, 0x0d, 0x46, 0x01, 0x2a, 0x03, 0x68, 0xd0, 0xf8, 0xdc, 0x42, + 0x06, 0xd0, 0xa1, 0xf1, 0x04, 0x0e, 0xde, 0xf1, 0x00, 0x07, 0x47, 0xeb, + 0x0e, 0x07, 0x00, 0xe0, 0x00, 0x27, 0x1a, 0x68, 0x61, 0x6a, 0xd2, 0x69, + 0x12, 0x6d, 0x91, 0x42, 0x38, 0xbf, 0x62, 0x62, 0x4d, 0xb9, 0xd4, 0xf8, + 0x90, 0x10, 0x31, 0xb1, 0x58, 0x68, 0x94, 0xf8, 0x94, 0x20, 0xf6, 0xf3, + 0x69, 0xf7, 0xc4, 0xf8, 0x90, 0x50, 0x30, 0x46, 0x29, 0x46, 0x42, 0x46, + 0x26, 0xf0, 0xd2, 0xdc, 0x0f, 0xb1, 0x00, 0x23, 0x63, 0x62, 0xbd, 0xe8, + 0xf0, 0x81, 0x70, 0xb5, 0x06, 0x46, 0x0d, 0x46, 0x1f, 0xf0, 0xea, 0xdc, + 0x29, 0x46, 0x04, 0x46, 0x30, 0x46, 0xf9, 0xf7, 0xcb, 0xf9, 0x20, 0x46, + 0x70, 0xbd, 0x00, 0x00, 0x10, 0xb5, 0x88, 0xb0, 0x0a, 0x9c, 0x00, 0x94, + 0x0b, 0x9c, 0x01, 0x94, 0x0c, 0x9c, 0x02, 0x94, 0x0d, 0x9c, 0x03, 0x94, + 0x0e, 0x9c, 0x04, 0x94, 0x0f, 0x9c, 0x05, 0x94, 0x10, 0x9c, 0x06, 0x94, + 0x11, 0x9c, 0x07, 0x94, 0xf4, 0xf3, 0x34, 0xf5, 0x04, 0x4b, 0x04, 0x21, + 0x04, 0x46, 0xd3, 0xf8, 0x8c, 0x30, 0x0a, 0x46, 0x98, 0x47, 0x20, 0x46, + 0x08, 0xb0, 0x10, 0xbd, 0xe0, 0xa6, 0x85, 0x00, 0x38, 0xb5, 0x90, 0xf8, + 0xa1, 0x31, 0x04, 0x46, 0x63, 0xb9, 0x03, 0x68, 0x1b, 0x6f, 0x4b, 0xb1, + 0xd0, 0xf8, 0x1c, 0x58, 0xf6, 0xf3, 0xae, 0xf3, 0xd4, 0xf8, 0x20, 0x38, + 0xeb, 0x1a, 0x1b, 0x18, 0xc4, 0xf8, 0x1c, 0x38, 0x20, 0x46, 0xbd, 0xe8, + 0x38, 0x40, 0x15, 0xf0, 0xf5, 0x9e, 0x2d, 0xe9, 0xf0, 0x41, 0x04, 0x46, + 0x1b, 0xf0, 0xde, 0xda, 0x23, 0x6b, 0x1b, 0x68, 0x02, 0x2b, 0x47, 0xd1, + 0x20, 0x69, 0x2c, 0xf0, 0x67, 0xda, 0x00, 0x28, 0x3a, 0xd0, 0x23, 0x68, + 0x93, 0xf8, 0x42, 0x20, 0x00, 0x2a, 0x3d, 0xd0, 0xd4, 0xf8, 0x68, 0x21, + 0x91, 0x79, 0x00, 0x29, 0x38, 0xd1, 0x93, 0xf8, 0x3f, 0x30, 0x00, 0x2b, + 0x34, 0xd0, 0xd4, 0xf8, 0x6c, 0x32, 0xb4, 0xf8, 0x28, 0x06, 0xd3, 0xf8, + 0xd4, 0x22, 0x52, 0x8e, 0x90, 0x42, 0x2b, 0xd1, 0xd4, 0xf8, 0xf8, 0x27, + 0x42, 0xf2, 0x0e, 0x70, 0x15, 0x88, 0x01, 0x3d, 0xad, 0xb2, 0x85, 0x42, + 0x1a, 0xd8, 0xd2, 0x78, 0x20, 0x46, 0x2a, 0xb1, 0xd3, 0xf8, 0xe0, 0x32, + 0x1b, 0x69, 0x5b, 0x42, 0x93, 0x42, 0x00, 0xdc, 0x01, 0x21, 0x1f, 0xf0, + 0xcd, 0xd8, 0xd4, 0xf8, 0xf8, 0x37, 0x1b, 0x79, 0x93, 0xb1, 0xd4, 0xf8, + 0x6c, 0x22, 0xd2, 0xf8, 0xe0, 0x22, 0x12, 0x69, 0x52, 0x42, 0x9a, 0x42, + 0x0a, 0xdd, 0x20, 0x46, 0x00, 0x21, 0x05, 0xe0, 0x20, 0x46, 0x01, 0x21, + 0x1f, 0xf0, 0xba, 0xd8, 0x20, 0x46, 0x01, 0x21, 0x1f, 0xf0, 0x9c, 0xd8, + 0x00, 0x26, 0xa3, 0x19, 0xd3, 0xf8, 0x4c, 0x52, 0xad, 0xb1, 0xd5, 0xf8, + 0x8c, 0x70, 0x97, 0xb9, 0xab, 0x79, 0x83, 0xb1, 0xab, 0x6d, 0x9b, 0x07, + 0x0d, 0xd5, 0x95, 0xf8, 0x84, 0x30, 0x53, 0xb1, 0xf6, 0xf3, 0x40, 0xf3, + 0xd5, 0xf8, 0x90, 0x10, 0x29, 0xf0, 0xf6, 0xd9, 0x18, 0xb1, 0xc5, 0xf8, + 0x88, 0x70, 0x85, 0xf8, 0x84, 0x70, 0x04, 0x36, 0x20, 0x2e, 0xe2, 0xd1, + 0x23, 0x6b, 0x1b, 0x68, 0x02, 0x2b, 0x6d, 0xd1, 0x20, 0x69, 0x2c, 0xf0, + 0xfd, 0xd9, 0x00, 0x28, 0x68, 0xd0, 0xd4, 0xf8, 0x68, 0x31, 0x9b, 0x79, + 0x00, 0x2b, 0x63, 0xd1, 0x23, 0x68, 0x93, 0xf8, 0x3f, 0x30, 0x00, 0x2b, + 0x5e, 0xd0, 0xd4, 0xf8, 0x6c, 0x32, 0xb4, 0xf8, 0x28, 0x26, 0xd3, 0xf8, + 0xd4, 0x32, 0x5b, 0x8e, 0x9a, 0x42, 0x55, 0xd1, 0x20, 0x46, 0x92, 0x21, + 0x16, 0xf0, 0xc2, 0xd8, 0x40, 0x00, 0x85, 0xb2, 0x00, 0x2d, 0x4d, 0xd0, + 0x05, 0xf1, 0x18, 0x07, 0x39, 0x46, 0x20, 0x46, 0x16, 0xf0, 0xb8, 0xd8, + 0x05, 0xf1, 0x1a, 0x01, 0x06, 0x46, 0x20, 0x46, 0x16, 0xf0, 0xb2, 0xd8, + 0x39, 0x46, 0x80, 0x46, 0x20, 0x46, 0x16, 0xf0, 0xad, 0xd8, 0x86, 0x42, + 0xec, 0xd1, 0xd4, 0xf8, 0xf8, 0x37, 0x46, 0xea, 0x08, 0x46, 0x9a, 0x68, + 0x9e, 0x60, 0x96, 0x42, 0x8c, 0xbf, 0xc2, 0xeb, 0x06, 0x02, 0x00, 0x22, + 0x3a, 0xb1, 0x5a, 0x79, 0x01, 0x32, 0x5a, 0x71, 0xd4, 0xf8, 0xf8, 0x37, + 0x00, 0x22, 0x9a, 0x71, 0x05, 0xe0, 0x99, 0x79, 0x01, 0x31, 0x99, 0x71, + 0xd4, 0xf8, 0xf8, 0x37, 0x5a, 0x71, 0xd4, 0xf8, 0xf8, 0x57, 0x6b, 0x79, + 0x05, 0x2b, 0x0e, 0xd9, 0xeb, 0x68, 0xcb, 0xb9, 0x23, 0x6b, 0x18, 0x69, + 0x02, 0xf0, 0x5c, 0xfd, 0x23, 0x6b, 0xe8, 0x60, 0x18, 0x69, 0x4f, 0xf4, + 0xe1, 0x51, 0xbd, 0xe8, 0xf0, 0x41, 0x02, 0xf0, 0x56, 0xbd, 0xab, 0x79, + 0x01, 0x2b, 0x09, 0xd9, 0xe9, 0x68, 0x39, 0xb1, 0x23, 0x6b, 0x18, 0x69, + 0x02, 0xf0, 0x4d, 0xfd, 0xd4, 0xf8, 0xf8, 0x37, 0x00, 0x22, 0xda, 0x60, + 0xbd, 0xe8, 0xf0, 0x81, 0x2d, 0xe9, 0xf0, 0x4f, 0x87, 0xb0, 0x9a, 0x46, + 0x04, 0x46, 0x0f, 0x46, 0x16, 0x46, 0xdd, 0xf8, 0x40, 0x80, 0x11, 0x9d, + 0x9d, 0xf8, 0x48, 0x90, 0xf9, 0xf7, 0xf7, 0xf8, 0xd4, 0xf8, 0xb0, 0x23, + 0x83, 0x46, 0x05, 0x92, 0xf6, 0xf3, 0x44, 0xf2, 0x00, 0xf5, 0x7e, 0x73, + 0x07, 0x33, 0xb3, 0xf5, 0xa0, 0x5f, 0x02, 0x46, 0x02, 0xd2, 0x24, 0x48, + 0x24, 0x49, 0x17, 0xe0, 0x58, 0x46, 0x0b, 0xf0, 0x2f, 0xdf, 0xd4, 0xf8, + 0xc0, 0x33, 0x98, 0x42, 0x15, 0xd3, 0x03, 0x23, 0x00, 0x93, 0x00, 0x23, + 0x01, 0x93, 0x02, 0x93, 0x03, 0x93, 0x58, 0x46, 0x17, 0x21, 0x06, 0xf1, + 0x0a, 0x02, 0x01, 0x23, 0x13, 0xf0, 0xe4, 0xdc, 0x1a, 0x48, 0x19, 0x49, + 0xd4, 0xf8, 0xc0, 0x23, 0x07, 0xb0, 0xbd, 0xe8, 0xf0, 0x4f, 0xff, 0xf7, + 0x75, 0xbb, 0x05, 0x9a, 0x92, 0xf8, 0x46, 0x30, 0x98, 0x07, 0x15, 0xd0, + 0xba, 0x6d, 0x40, 0xf2, 0x37, 0x13, 0x13, 0x40, 0x83, 0xb1, 0x9b, 0xf8, + 0x69, 0x37, 0xd9, 0x07, 0x0c, 0xd5, 0x6b, 0x68, 0xda, 0x03, 0x09, 0xd5, + 0x2b, 0x6c, 0x01, 0x2b, 0x06, 0xd1, 0x00, 0x22, 0x58, 0x46, 0x29, 0x46, + 0x13, 0x46, 0x00, 0x92, 0x12, 0xf0, 0x5e, 0xdd, 0x20, 0x46, 0x39, 0x46, + 0x32, 0x46, 0x53, 0x46, 0xcd, 0xf8, 0x40, 0x80, 0x11, 0x95, 0xcd, 0xf8, + 0x48, 0x90, 0x07, 0xb0, 0xbd, 0xe8, 0xf0, 0x4f, 0x23, 0xf0, 0x9a, 0x9a, + 0x57, 0xdd, 0x01, 0x00, 0x00, 0xdd, 0x01, 0x00, 0x75, 0xdd, 0x01, 0x00, + 0x0c, 0x2a, 0x70, 0xb5, 0x04, 0x46, 0x0d, 0x46, 0x16, 0x46, 0x54, 0xd8, + 0x32, 0x4b, 0x93, 0x40, 0x51, 0xd5, 0xd0, 0xf8, 0xb4, 0x36, 0x4b, 0xb1, + 0xd3, 0xf8, 0xd8, 0x32, 0x33, 0xb1, 0x5b, 0x68, 0x01, 0x2b, 0x48, 0xd0, + 0x03, 0x2b, 0x46, 0xd0, 0x02, 0x2b, 0x44, 0xd0, 0x20, 0x46, 0x16, 0xf0, + 0x31, 0xde, 0x00, 0x28, 0x3f, 0xd1, 0xd4, 0xf8, 0x68, 0x31, 0x5b, 0x69, + 0x01, 0x2b, 0x3a, 0xd0, 0x45, 0xb1, 0xab, 0x79, 0x33, 0xb1, 0xab, 0x6d, + 0x9a, 0x07, 0x03, 0xd5, 0xd5, 0xf8, 0x88, 0x30, 0x00, 0x2b, 0x37, 0xd1, + 0xd4, 0xf8, 0x18, 0x08, 0xff, 0xf3, 0xda, 0xf1, 0x28, 0xb1, 0xd4, 0xf8, + 0x68, 0x01, 0x09, 0x21, 0x44, 0xf0, 0xf8, 0xd9, 0x17, 0xe0, 0xd4, 0xf8, + 0x68, 0x01, 0x08, 0x2e, 0x83, 0x79, 0x01, 0xd0, 0x0c, 0x2e, 0x01, 0xd1, + 0x7b, 0xb1, 0x28, 0xe0, 0x00, 0x2b, 0x24, 0xd0, 0xd4, 0xf8, 0x28, 0x35, + 0x02, 0x2b, 0x03, 0xd0, 0x94, 0xf8, 0xf4, 0x37, 0xdb, 0x07, 0x1e, 0xd5, + 0x09, 0x21, 0x44, 0xf0, 0xe1, 0xd9, 0x00, 0x20, 0x70, 0xbd, 0x08, 0x2e, + 0x1a, 0xd1, 0x20, 0x46, 0x29, 0x46, 0x02, 0x22, 0x00, 0x23, 0x26, 0xf0, + 0x23, 0xda, 0x00, 0x28, 0x14, 0xbf, 0x4f, 0xf0, 0xff, 0x30, 0x00, 0x20, + 0x70, 0xbd, 0x20, 0x46, 0x29, 0x46, 0x32, 0x46, 0xbd, 0xe8, 0x70, 0x40, + 0x2a, 0xf0, 0xca, 0x9d, 0x6f, 0xf0, 0x19, 0x00, 0x70, 0xbd, 0x18, 0x46, + 0x70, 0xbd, 0x6f, 0xf0, 0x18, 0x00, 0x70, 0xbd, 0x00, 0x20, 0x70, 0xbd, + 0x00, 0x00, 0xa8, 0x12, 0x38, 0xb5, 0x01, 0x22, 0x0c, 0x46, 0xd1, 0xf8, + 0x4c, 0x15, 0x05, 0x46, 0x2f, 0xf0, 0x86, 0xdd, 0x28, 0x46, 0x21, 0x46, + 0xbd, 0xe8, 0x38, 0x40, 0x2e, 0xf0, 0x54, 0x99, 0x10, 0xb5, 0x0c, 0x46, + 0x2e, 0xf0, 0x14, 0xda, 0x18, 0xb9, 0x94, 0xf8, 0xf5, 0x32, 0x84, 0xf8, + 0xf4, 0x32, 0x10, 0xbd, 0x03, 0x68, 0x1a, 0x68, 0x53, 0x6b, 0x23, 0xb1, + 0x92, 0xf8, 0x44, 0x30, 0x0b, 0xb1, 0x31, 0xf0, 0xeb, 0x9f, 0x18, 0x46, + 0x70, 0x47, 0x03, 0x6a, 0x30, 0xb5, 0x00, 0x2b, 0x2b, 0xd0, 0x03, 0x68, + 0x0c, 0x69, 0x1b, 0x68, 0x8d, 0x8a, 0x93, 0xf8, 0x95, 0x30, 0x3b, 0xb1, + 0xcb, 0x8a, 0x03, 0xf0, 0x80, 0x03, 0x00, 0x2b, 0x0c, 0xbf, 0x1e, 0x23, + 0x0c, 0x23, 0x00, 0xe0, 0x0c, 0x23, 0x03, 0xf1, 0x0b, 0x02, 0x95, 0x42, + 0x17, 0xd3, 0xe2, 0x18, 0xe3, 0x5c, 0x54, 0x78, 0x1b, 0x02, 0x1b, 0x19, + 0x9b, 0xb2, 0xb3, 0xf5, 0x00, 0x6f, 0x0e, 0xd1, 0x93, 0x78, 0x1b, 0x09, + 0x04, 0x2b, 0x0a, 0xd1, 0xd3, 0x7a, 0x01, 0x2b, 0x07, 0xd1, 0x43, 0x6a, + 0x01, 0x33, 0x43, 0x62, 0xc3, 0x68, 0x01, 0x33, 0xc3, 0x60, 0x00, 0x20, + 0x30, 0xbd, 0xbd, 0xe8, 0x30, 0x40, 0x40, 0xf0, 0x37, 0x9d, 0x38, 0xb1, + 0x03, 0x68, 0x2b, 0xb1, 0x21, 0xb9, 0x93, 0xf8, 0x0b, 0x27, 0x0a, 0xb1, + 0x83, 0xf8, 0x0b, 0x17, 0x18, 0xf0, 0x32, 0x9f, 0xb0, 0xf8, 0x54, 0x38, + 0x0b, 0xb1, 0x1a, 0xf0, 0xcb, 0x98, 0x70, 0x47, 0xf8, 0xf7, 0x76, 0xbf, + 0xfe, 0xf7, 0x5e, 0xbd, 0x38, 0xb5, 0x05, 0x46, 0xd0, 0xf8, 0xb4, 0x00, + 0x58, 0xb1, 0x03, 0x78, 0x4b, 0xb1, 0xf2, 0xf7, 0xbb, 0xfa, 0x04, 0x46, + 0x30, 0xb9, 0xd5, 0xf8, 0xb4, 0x00, 0x01, 0x21, 0xf2, 0xf3, 0x78, 0xf4, + 0x00, 0xe0, 0x01, 0x24, 0x28, 0x46, 0xf4, 0xf3, 0x39, 0xf7, 0x34, 0xb9, + 0xd5, 0xf8, 0xb4, 0x00, 0x21, 0x46, 0xbd, 0xe8, 0x38, 0x40, 0xf2, 0xf3, + 0x6b, 0xb4, 0x38, 0xbd, 0x2d, 0xe9, 0xf0, 0x4f, 0x87, 0xb0, 0x03, 0x93, + 0x11, 0x9b, 0x15, 0x9f, 0x04, 0x93, 0x14, 0x9b, 0x8a, 0x46, 0x16, 0x46, + 0xdd, 0xf8, 0x40, 0xb0, 0x12, 0x9d, 0xdd, 0xf8, 0x4c, 0x80, 0x05, 0x93, + 0x27, 0xb1, 0xb9, 0x68, 0x11, 0xb1, 0x01, 0x20, 0xf2, 0xf7, 0xb6, 0xff, + 0x04, 0x46, 0x00, 0x28, 0x35, 0xd0, 0x03, 0x68, 0x06, 0xf0, 0x01, 0x02, + 0x00, 0x92, 0x18, 0x68, 0x51, 0x46, 0x2a, 0x46, 0x43, 0x46, 0x12, 0xf0, + 0x9d, 0xdf, 0x81, 0x46, 0x00, 0x28, 0x2a, 0xd1, 0x11, 0x2e, 0x02, 0xd0, + 0x13, 0x2e, 0x11, 0xd1, 0x09, 0xe0, 0x28, 0x46, 0xf2, 0xf3, 0xda, 0xf2, + 0x00, 0x28, 0x20, 0xd1, 0x04, 0xf5, 0xb8, 0x70, 0x29, 0x46, 0x06, 0x22, + 0x03, 0xe0, 0x04, 0xf5, 0xb6, 0x70, 0x29, 0x46, 0x04, 0x22, 0xf1, 0xf3, + 0xdd, 0xf5, 0x14, 0xe0, 0x04, 0x9b, 0x20, 0x46, 0x11, 0x93, 0x05, 0x9b, + 0x51, 0x46, 0x14, 0x93, 0x03, 0x9b, 0x32, 0x46, 0xcd, 0xf8, 0x40, 0xb0, + 0x12, 0x95, 0xcd, 0xf8, 0x4c, 0x80, 0x15, 0x97, 0x07, 0xb0, 0xbd, 0xe8, + 0xf0, 0x4f, 0xfc, 0xf3, 0xad, 0xb7, 0x6f, 0xf0, 0x16, 0x09, 0x48, 0x46, + 0x07, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, 0x00, 0x00, 0x38, 0xb5, 0xd0, 0xf8, + 0x68, 0x41, 0x0c, 0xb1, 0xa5, 0x68, 0x00, 0xe0, 0x25, 0x46, 0x04, 0x4c, + 0x25, 0x60, 0xfd, 0xf3, 0x77, 0xf0, 0x41, 0x1c, 0x01, 0xd1, 0x00, 0x23, + 0x23, 0x60, 0x38, 0xbd, 0xe4, 0x0b, 0x02, 0x00, 0x03, 0x4a, 0x13, 0x68, + 0x13, 0xb1, 0x00, 0x21, 0x11, 0x60, 0x18, 0x46, 0x70, 0x47, 0x00, 0xbf, + 0xe4, 0x0b, 0x02, 0x00, 0x2d, 0xe9, 0xf0, 0x41, 0x16, 0x46, 0x02, 0x68, + 0x0c, 0x46, 0x12, 0x68, 0x1f, 0x46, 0x92, 0xf8, 0x95, 0x20, 0x05, 0x46, + 0x09, 0x69, 0xa3, 0x8a, 0x12, 0xb1, 0xe2, 0x8a, 0x10, 0x06, 0x07, 0xd5, + 0x15, 0x2b, 0x05, 0xdd, 0x08, 0x48, 0x0e, 0x31, 0x06, 0x22, 0xf1, 0xf3, + 0x73, 0xf5, 0x38, 0xb1, 0x28, 0x46, 0x21, 0x46, 0x32, 0x46, 0x3b, 0x46, + 0xbd, 0xe8, 0xf0, 0x41, 0xfd, 0xf3, 0xe8, 0xb2, 0x4f, 0xf0, 0xff, 0x30, + 0xbd, 0xe8, 0xf0, 0x81, 0xc7, 0xb7, 0x01, 0x00, 0x70, 0xb5, 0x04, 0x46, + 0x1d, 0x46, 0xff, 0xf3, 0xa9, 0xf1, 0x06, 0x46, 0x40, 0xb1, 0x63, 0x68, + 0x93, 0xf8, 0xab, 0x30, 0x23, 0xb1, 0xe0, 0x6f, 0x29, 0x46, 0xf2, 0xf7, + 0xad, 0xfc, 0xb0, 0x60, 0x30, 0x46, 0x70, 0xbd, 0x38, 0xb5, 0x43, 0x68, + 0x04, 0x46, 0x93, 0xf8, 0xab, 0x30, 0x0d, 0x46, 0x13, 0xb1, 0x88, 0x68, + 0xf2, 0xf7, 0xbf, 0xfc, 0x20, 0x46, 0x29, 0x46, 0xbd, 0xe8, 0x38, 0x40, + 0xff, 0xf3, 0x68, 0xb2, 0x2d, 0xe9, 0xf3, 0x47, 0x07, 0x46, 0x0e, 0x46, + 0x92, 0x46, 0x1d, 0x46, 0x00, 0x2b, 0x59, 0xd0, 0x01, 0x29, 0x57, 0xd1, + 0x4f, 0xf4, 0xc0, 0x73, 0x01, 0x93, 0xfa, 0xf3, 0x0d, 0xf6, 0x4f, 0xf4, + 0x40, 0x71, 0x80, 0x46, 0xf6, 0xf3, 0xf6, 0xf3, 0x04, 0x46, 0x00, 0x28, + 0x52, 0xd0, 0x00, 0x21, 0x4f, 0xf4, 0x40, 0x72, 0xf1, 0xf3, 0xa6, 0xf5, + 0x38, 0x46, 0x31, 0x46, 0x22, 0x46, 0x01, 0xab, 0xf1, 0xf3, 0x36, 0xf4, + 0x1e, 0x30, 0x37, 0xd1, 0x20, 0x22, 0x22, 0x71, 0x04, 0x22, 0x01, 0x9b, + 0x62, 0x71, 0xd0, 0x22, 0xa2, 0x71, 0x02, 0x22, 0x4f, 0xea, 0x43, 0x09, + 0xe2, 0x71, 0x4a, 0x23, 0x62, 0x22, 0x23, 0x70, 0x22, 0x72, 0x0b, 0x23, + 0xa9, 0x22, 0x63, 0x70, 0x62, 0x72, 0xff, 0x23, 0x04, 0xeb, 0x09, 0x02, + 0xa3, 0x70, 0xe3, 0x70, 0x02, 0xf8, 0x02, 0x3c, 0x02, 0xf8, 0x01, 0x3c, + 0x05, 0xf1, 0x0c, 0x03, 0x99, 0x45, 0x0e, 0xdd, 0x2a, 0x46, 0x51, 0x46, + 0x04, 0xf1, 0x0a, 0x00, 0xf1, 0xf3, 0x14, 0xf5, 0x38, 0x46, 0x31, 0x46, + 0x22, 0x46, 0x4f, 0xea, 0x69, 0x03, 0x10, 0xf0, 0x8f, 0xfb, 0x05, 0x46, + 0x01, 0xe0, 0x6f, 0xf0, 0x0e, 0x05, 0x40, 0x46, 0x21, 0x46, 0x4f, 0xf4, + 0x40, 0x72, 0xf6, 0xf3, 0xbf, 0xf3, 0x0f, 0xe0, 0x40, 0x46, 0x21, 0x46, + 0x4f, 0xf4, 0x40, 0x72, 0xf6, 0xf3, 0xb8, 0xf3, 0x2b, 0x46, 0x38, 0x46, + 0x31, 0x46, 0x52, 0x46, 0xf0, 0xf3, 0x1c, 0xf5, 0x05, 0x46, 0x01, 0xe0, + 0x4f, 0xf0, 0xff, 0x35, 0x28, 0x46, 0xbd, 0xe8, 0xfc, 0x87, 0x2d, 0xe9, + 0xff, 0x41, 0x80, 0x46, 0x1e, 0x46, 0x9f, 0x6b, 0x15, 0x69, 0x46, 0xf0, + 0x8b, 0xd8, 0x04, 0x46, 0xc8, 0xb9, 0x3b, 0x7a, 0x02, 0x2b, 0x16, 0xd1, + 0xab, 0x79, 0xa3, 0xb1, 0xb6, 0xf8, 0x68, 0x30, 0x8b, 0xb1, 0xaa, 0x6d, + 0x40, 0xf2, 0x37, 0x13, 0x13, 0x40, 0x63, 0xb1, 0x95, 0xf8, 0x84, 0x30, + 0x4b, 0xb9, 0x95, 0xf9, 0x48, 0x20, 0x31, 0x6f, 0x8d, 0xe8, 0x81, 0x00, + 0x02, 0x90, 0x11, 0x23, 0x40, 0x46, 0x45, 0xf0, 0x47, 0xdc, 0x20, 0x46, + 0x04, 0xb0, 0xbd, 0xe8, 0xf0, 0x81, 0xf8, 0xb5, 0xd0, 0xf8, 0xb0, 0x43, + 0xd0, 0xf8, 0xac, 0x73, 0x21, 0xf0, 0x9e, 0xda, 0x94, 0xf8, 0x2f, 0x30, + 0x06, 0x46, 0xfb, 0xb1, 0x00, 0x25, 0x7b, 0x19, 0xd3, 0xf8, 0x4c, 0x42, + 0xbc, 0xb1, 0xa3, 0x79, 0xab, 0xb1, 0x23, 0x79, 0x9b, 0xb1, 0xa3, 0x6d, + 0x9b, 0x07, 0x10, 0xd5, 0x94, 0xf8, 0x84, 0x30, 0x6b, 0xb1, 0xf5, 0xf3, + 0xf1, 0xf7, 0xd4, 0xf8, 0x90, 0x10, 0x28, 0xf0, 0xa7, 0xde, 0x30, 0xb1, + 0x00, 0x23, 0xc4, 0xf8, 0x88, 0x30, 0xc4, 0xf8, 0x8c, 0x30, 0x84, 0xf8, + 0x84, 0x30, 0x04, 0x35, 0x20, 0x2d, 0xe0, 0xd1, 0x30, 0x46, 0xf8, 0xbd, + 0xf0, 0xb5, 0x85, 0xb0, 0x0a, 0x9f, 0x0e, 0x46, 0x00, 0x97, 0x0b, 0x9f, + 0x1d, 0x46, 0x01, 0x97, 0x0c, 0x9f, 0x04, 0x46, 0x02, 0x97, 0x0d, 0x9f, + 0x03, 0x97, 0x28, 0xf0, 0x7d, 0xdf, 0xb3, 0x79, 0x5b, 0xb1, 0x29, 0x46, + 0x20, 0x46, 0x45, 0xf0, 0xb1, 0xd9, 0x01, 0x46, 0x28, 0xb1, 0x20, 0x46, + 0x05, 0xb0, 0xbd, 0xe8, 0xf0, 0x40, 0x45, 0xf0, 0xa1, 0x98, 0x05, 0xb0, + 0xf0, 0xbd, 0x00, 0x00, 0x2d, 0xe9, 0xf3, 0x41, 0x1f, 0x46, 0x03, 0x68, + 0x04, 0x46, 0x1b, 0x7e, 0x0d, 0x46, 0x16, 0x46, 0x00, 0x2b, 0x4a, 0xd0, + 0x90, 0xf8, 0x75, 0x32, 0x00, 0x2b, 0x46, 0xd1, 0xd1, 0xf8, 0x00, 0x80, + 0x40, 0x46, 0xfe, 0xf7, 0x3c, 0xfc, 0x03, 0x69, 0x02, 0x46, 0x99, 0x79, + 0xb1, 0xb1, 0x81, 0x7e, 0xc8, 0x07, 0x13, 0xd5, 0xd3, 0xf8, 0xcc, 0x10, + 0x49, 0x05, 0x0f, 0xd4, 0xb4, 0xf8, 0x26, 0x16, 0x01, 0xf4, 0x70, 0x41, + 0xa1, 0xf5, 0x80, 0x50, 0x41, 0x42, 0x41, 0xeb, 0x00, 0x01, 0x10, 0x31, + 0x53, 0xf8, 0x21, 0x30, 0x13, 0xb1, 0x93, 0xf8, 0xdf, 0x30, 0x33, 0xbb, + 0x51, 0x68, 0x00, 0x29, 0x23, 0xdb, 0x16, 0x4b, 0x0b, 0x40, 0x1b, 0xb1, + 0xb8, 0xf8, 0x16, 0x30, 0x03, 0xf0, 0x07, 0x03, 0x49, 0x06, 0x1a, 0xd5, + 0x12, 0x49, 0x20, 0x46, 0xcb, 0x5c, 0x02, 0xa9, 0x41, 0xf8, 0x04, 0x3d, + 0x3b, 0x60, 0x0a, 0xf0, 0xbb, 0xd9, 0x01, 0x30, 0x0f, 0xd0, 0x01, 0x9b, + 0x3a, 0x68, 0x9a, 0x42, 0x0b, 0xd0, 0x0c, 0x4a, 0x3b, 0x60, 0xd2, 0x5c, + 0xb8, 0xf8, 0x16, 0x30, 0x02, 0xf0, 0x07, 0x02, 0x23, 0xf0, 0x07, 0x03, + 0x13, 0x43, 0xa8, 0xf8, 0x16, 0x30, 0x20, 0x46, 0x29, 0x46, 0x32, 0x46, + 0x3b, 0x46, 0x14, 0xf0, 0x37, 0xdc, 0xbd, 0xe8, 0xfc, 0x81, 0x00, 0xbf, + 0x40, 0x00, 0x01, 0x80, 0xc4, 0xd2, 0x85, 0x00, 0x24, 0xfe, 0x01, 0x00, + 0x00, 0x20, 0x70, 0x47, 0x70, 0x47, 0x00, 0x20, 0x70, 0x47, 0x70, 0x47, + 0x00, 0x20, 0x70, 0x47, 0x70, 0x47, 0x70, 0x47, 0x70, 0x47, 0x70, 0x47, + 0x00, 0x20, 0x70, 0x47, 0x00, 0x20, 0x70, 0x47, 0x00, 0x20, 0x70, 0x47, + 0x70, 0x47, 0x00, 0x20, 0x70, 0x47, 0x70, 0x47, 0x70, 0x47, 0x00, 0x20, + 0x70, 0x47, 0x00, 0x20, 0x70, 0x47, 0x70, 0x47, 0x70, 0x47, 0x70, 0x47, + 0x70, 0x47, 0x00, 0x20, 0x70, 0x47, 0x00, 0x00, 0xc2, 0x69, 0x38, 0xb5, + 0x12, 0x05, 0x04, 0x46, 0x0d, 0x46, 0x03, 0x69, 0x14, 0xd5, 0x02, 0x68, + 0xd2, 0xf8, 0x8c, 0x10, 0x8a, 0x6b, 0x01, 0x32, 0x8a, 0x63, 0x4f, 0xf4, + 0x7a, 0x71, 0xb2, 0xfb, 0xf1, 0xf0, 0x01, 0xfb, 0x10, 0x21, 0x19, 0xb9, + 0x06, 0x48, 0xd9, 0x6b, 0xff, 0xf7, 0x12, 0xf8, 0xe3, 0x69, 0x23, 0xf4, + 0x00, 0x63, 0xe3, 0x61, 0x20, 0x46, 0x29, 0x46, 0xbd, 0xe8, 0x38, 0x40, + 0x2d, 0xf0, 0xf8, 0x9a, 0x2c, 0xbf, 0x01, 0x00, 0xf8, 0xb5, 0x04, 0x46, + 0x0f, 0x46, 0x16, 0x46, 0x1d, 0x46, 0xf8, 0xf7, 0x59, 0xf9, 0x20, 0x46, + 0x39, 0x46, 0x32, 0x46, 0x2b, 0x46, 0x1d, 0xf0, 0xfb, 0xd9, 0x20, 0x46, + 0xbd, 0xe8, 0xf8, 0x40, 0xf8, 0xf7, 0x5a, 0xb8, 0x08, 0xb5, 0x11, 0xf0, + 0xf5, 0xdf, 0x38, 0xb1, 0x43, 0x6a, 0x19, 0x03, 0x04, 0xd4, 0x02, 0x68, + 0x12, 0xb1, 0x43, 0xf4, 0x00, 0x23, 0x43, 0x62, 0x08, 0xbd, 0x70, 0xb5, + 0x03, 0x68, 0x04, 0x46, 0x93, 0xf8, 0x42, 0x30, 0x0e, 0x46, 0x15, 0x46, + 0x23, 0xb1, 0xd0, 0xf8, 0x40, 0x01, 0x01, 0x22, 0xf8, 0xf7, 0x72, 0xfb, + 0x20, 0x46, 0x31, 0x46, 0x2a, 0x46, 0xbd, 0xe8, 0x70, 0x40, 0x25, 0xf0, + 0x07, 0x9b, 0x70, 0x47, 0x73, 0xb5, 0x02, 0xf5, 0x45, 0x74, 0x00, 0xeb, + 0x44, 0x04, 0x40, 0xf6, 0x2a, 0x16, 0xa5, 0x88, 0xa6, 0x80, 0x06, 0x9e, + 0x00, 0x96, 0x03, 0xf0, 0x5b, 0xdf, 0xa5, 0x80, 0x7c, 0xbd, 0x70, 0xb5, + 0x0c, 0x46, 0x16, 0x46, 0x4d, 0x6c, 0x18, 0xf0, 0xb9, 0xdb, 0x20, 0xb9, + 0xb3, 0x02, 0x02, 0xd5, 0x63, 0x6c, 0x65, 0x64, 0xa3, 0x64, 0x70, 0xbd, + 0x70, 0xb5, 0x05, 0x68, 0x04, 0x46, 0x2b, 0x68, 0x0e, 0x46, 0x93, 0xf8, + 0x30, 0x30, 0x4b, 0xb1, 0x2b, 0x6b, 0x18, 0x69, 0x00, 0xf0, 0x18, 0xfe, + 0x73, 0x8e, 0x98, 0x42, 0x1c, 0xbf, 0xd5, 0xf8, 0x40, 0x25, 0x53, 0x86, + 0x20, 0x46, 0x31, 0x46, 0xbd, 0xe8, 0x70, 0x40, 0x29, 0xf0, 0xaa, 0x98, + 0x07, 0x4b, 0x1b, 0x78, 0x3b, 0xb1, 0x07, 0x4b, 0x1b, 0x68, 0x98, 0x42, + 0x03, 0xd2, 0x06, 0x4b, 0x53, 0xf8, 0x20, 0x30, 0x0b, 0xb9, 0x35, 0xf0, + 0x5d, 0x99, 0x18, 0x46, 0x70, 0x47, 0x00, 0xbf, 0x8c, 0x01, 0x02, 0x00, + 0x70, 0x00, 0x02, 0x00, 0x74, 0x00, 0x02, 0x00, 0x00, 0x20, 0x70, 0x47, + 0x07, 0x4b, 0x1b, 0x78, 0x3b, 0xb1, 0x07, 0x4b, 0x1b, 0x68, 0x98, 0x42, + 0x03, 0xd2, 0x06, 0x4b, 0x53, 0xf8, 0x20, 0x30, 0x0b, 0xb9, 0x34, 0xf0, + 0x4d, 0x9d, 0x18, 0x46, 0x70, 0x47, 0x00, 0xbf, 0x8c, 0x01, 0x02, 0x00, + 0x88, 0x01, 0x02, 0x00, 0x64, 0xff, 0x01, 0x00, 0x2c, 0x4b, 0x2d, 0xe9, + 0xf0, 0x41, 0x05, 0x46, 0x0c, 0x46, 0xd3, 0xf8, 0x00, 0x80, 0x00, 0x26, + 0x0b, 0xe0, 0x29, 0x4f, 0x28, 0x46, 0x07, 0xeb, 0xc6, 0x07, 0x39, 0x46, + 0xf1, 0xf3, 0xfc, 0xf3, 0x10, 0xb9, 0xfb, 0x78, 0x9c, 0x42, 0x43, 0xd0, + 0x01, 0x36, 0x46, 0x45, 0xf1, 0xd1, 0x23, 0x4b, 0x00, 0x26, 0xd3, 0xf8, + 0x00, 0x80, 0x0f, 0xe0, 0x21, 0x4f, 0x28, 0x46, 0x07, 0xeb, 0xc6, 0x07, + 0x39, 0x46, 0xf1, 0xf3, 0xe9, 0xf3, 0x30, 0xb9, 0xfb, 0x78, 0x9c, 0x42, + 0x03, 0xd1, 0x1d, 0x4b, 0x01, 0x22, 0x1a, 0x70, 0x10, 0xe0, 0x01, 0x36, + 0x46, 0x45, 0xed, 0xd1, 0x0c, 0xbb, 0x1a, 0x4b, 0x26, 0x46, 0xd3, 0xf8, + 0x00, 0x80, 0x0b, 0xe0, 0x18, 0x4f, 0x28, 0x46, 0x07, 0xeb, 0xc6, 0x07, + 0x39, 0x46, 0xf1, 0xf3, 0xd1, 0xf3, 0x10, 0xb9, 0x38, 0x1d, 0xbd, 0xe8, + 0xf0, 0x81, 0x01, 0x36, 0x46, 0x45, 0xf1, 0xd1, 0x12, 0x4b, 0x13, 0x4f, + 0xd3, 0xf8, 0x00, 0x80, 0x00, 0x26, 0x06, 0xe0, 0x39, 0x46, 0x28, 0x46, + 0xf1, 0xf3, 0xc0, 0xf3, 0x04, 0x37, 0x40, 0xb1, 0x01, 0x36, 0x46, 0x45, + 0xf6, 0xd1, 0x28, 0x46, 0x21, 0x46, 0xbd, 0xe8, 0xf0, 0x41, 0x34, 0xf0, + 0x15, 0x9c, 0x0a, 0x48, 0xbd, 0xe8, 0xf0, 0x81, 0xe8, 0x0b, 0x02, 0x00, + 0x18, 0xdd, 0x01, 0x00, 0x84, 0x01, 0x02, 0x00, 0x68, 0x00, 0x02, 0x00, + 0x8c, 0x01, 0x02, 0x00, 0xf8, 0x0b, 0x02, 0x00, 0xc4, 0xdd, 0x01, 0x00, + 0xfc, 0x0b, 0x02, 0x00, 0xb1, 0xdd, 0x01, 0x00, 0xca, 0x02, 0x86, 0x00, + 0x10, 0xb5, 0x03, 0x4c, 0x21, 0x60, 0x35, 0xf0, 0x23, 0xd8, 0x00, 0x23, + 0x23, 0x60, 0x10, 0xbd, 0x04, 0x0c, 0x02, 0x00, 0x38, 0xb5, 0x0d, 0x46, + 0x00, 0x24, 0x08, 0xe0, 0x08, 0x49, 0x28, 0x46, 0x01, 0xeb, 0xc4, 0x01, + 0x04, 0x22, 0xf1, 0xf3, 0x9b, 0xf2, 0x30, 0xb1, 0x01, 0x34, 0x05, 0x4b, + 0x1b, 0x68, 0x9c, 0x42, 0xf2, 0xd3, 0x00, 0x20, 0x38, 0xbd, 0x01, 0x20, + 0x38, 0xbd, 0x00, 0xbf, 0xc4, 0xdd, 0x01, 0x00, 0xf8, 0x0b, 0x02, 0x00, + 0x2d, 0xe9, 0xf0, 0x47, 0x23, 0x4b, 0x8e, 0xb0, 0x1d, 0x68, 0x23, 0x4b, + 0x07, 0x46, 0x88, 0x46, 0xd3, 0xf8, 0x00, 0x90, 0x00, 0x2d, 0x39, 0xd0, + 0x03, 0x6b, 0xa9, 0x68, 0x18, 0x69, 0x6a, 0x46, 0x00, 0x24, 0x00, 0xf0, + 0x6b, 0xfd, 0x26, 0x46, 0x2c, 0xe0, 0x1c, 0x4b, 0x03, 0xeb, 0xc4, 0x0a, + 0xab, 0x68, 0x01, 0x2b, 0x04, 0xd1, 0x9a, 0xf8, 0x05, 0x00, 0xff, 0xf7, + 0x37, 0xff, 0x03, 0xe0, 0x9a, 0xf8, 0x04, 0x00, 0xff, 0xf7, 0x1c, 0xff, + 0x07, 0xa9, 0x35, 0xf0, 0xb9, 0xd9, 0x00, 0x23, 0x07, 0xaa, 0x99, 0x5c, + 0x1d, 0xf8, 0x03, 0x20, 0x11, 0x42, 0x0f, 0xd0, 0x38, 0x46, 0x51, 0x46, + 0x34, 0xf0, 0x90, 0xdb, 0x40, 0xb1, 0xb8, 0xf1, 0x00, 0x0f, 0x05, 0xd0, + 0x08, 0xeb, 0x86, 0x00, 0x51, 0x46, 0x04, 0x22, 0xf1, 0xf3, 0x88, 0xf3, + 0x01, 0x36, 0x02, 0xe0, 0x01, 0x33, 0x1c, 0x2b, 0xe6, 0xd1, 0x01, 0x34, + 0x4c, 0x45, 0xd0, 0xd1, 0x30, 0x46, 0x00, 0xe0, 0x28, 0x46, 0x0e, 0xb0, + 0xbd, 0xe8, 0xf0, 0x87, 0x04, 0x0c, 0x02, 0x00, 0xf8, 0x0b, 0x02, 0x00, + 0xc4, 0xdd, 0x01, 0x00, 0xf8, 0xb5, 0x07, 0x46, 0x0e, 0x46, 0x00, 0x24, + 0x0e, 0xe0, 0x0a, 0x4b, 0x0c, 0x25, 0x05, 0xfb, 0x04, 0x35, 0x38, 0x46, + 0x29, 0x46, 0xf1, 0xf3, 0x1d, 0xf3, 0x20, 0xb9, 0x2b, 0x79, 0x9e, 0x42, + 0x01, 0xd1, 0xa8, 0x68, 0xf8, 0xbd, 0x01, 0x34, 0x03, 0x4b, 0x1b, 0x68, + 0x9c, 0x42, 0xec, 0xd3, 0x00, 0x20, 0xf8, 0xbd, 0x00, 0xdd, 0x01, 0x00, + 0xf0, 0x0b, 0x02, 0x00, 0x01, 0x29, 0x03, 0x46, 0x10, 0xd0, 0xd0, 0xf8, + 0xbc, 0x20, 0x08, 0x2a, 0xd0, 0xf8, 0xb0, 0x20, 0x08, 0xbf, 0x41, 0xf4, + 0x00, 0x71, 0xa2, 0xf8, 0xd8, 0x13, 0xb2, 0xf8, 0xda, 0x03, 0x00, 0x22, + 0x80, 0xb2, 0xa3, 0xf8, 0x20, 0x26, 0x70, 0x47, 0x4f, 0xf6, 0xff, 0x70, + 0x70, 0x47, 0xd0, 0xf8, 0xb0, 0x30, 0xa3, 0xf8, 0xd8, 0x13, 0xa3, 0xf8, + 0xda, 0x23, 0x70, 0x47, 0xd0, 0xf8, 0xb0, 0x30, 0x00, 0x21, 0x30, 0xb5, + 0xa3, 0xf8, 0xd8, 0x13, 0x01, 0x24, 0xb3, 0xf8, 0xda, 0x23, 0x02, 0x25, + 0xa3, 0xf8, 0xd8, 0x43, 0xb3, 0xf8, 0xda, 0x43, 0xa3, 0xf8, 0xd8, 0x53, + 0xb3, 0xf8, 0xda, 0x33, 0xa4, 0xb2, 0xa0, 0xf8, 0x20, 0x16, 0x9b, 0xb2, + 0xc2, 0xf3, 0x03, 0x11, 0x41, 0xea, 0x02, 0x72, 0x44, 0xea, 0x03, 0x20, + 0x42, 0xea, 0x00, 0x30, 0x30, 0xbd, 0xd0, 0xf8, 0xb0, 0x30, 0x00, 0x22, + 0xa3, 0xf8, 0xfc, 0x13, 0xa0, 0xf8, 0x20, 0x26, 0xb3, 0xf8, 0xfe, 0x03, + 0x80, 0xb2, 0x70, 0x47, 0xd0, 0xf8, 0xb0, 0x30, 0x41, 0xea, 0x02, 0x42, + 0xc3, 0xf8, 0xfc, 0x23, 0x70, 0x47, 0x00, 0x23, 0x80, 0xf8, 0xe3, 0x30, + 0x00, 0xf5, 0x80, 0x52, 0xff, 0x23, 0x00, 0xf5, 0x8a, 0x50, 0x82, 0xf8, + 0x3a, 0x30, 0x80, 0xf8, 0x30, 0x30, 0x70, 0x47, 0xff, 0xf7, 0xc0, 0xbf, + 0x00, 0x20, 0x70, 0x47, 0xb0, 0xf8, 0xda, 0x30, 0x03, 0xf4, 0x70, 0x43, + 0xb3, 0xf5, 0x80, 0x5f, 0x09, 0xd1, 0x03, 0x2a, 0x17, 0xdd, 0xa2, 0xf1, + 0x65, 0x03, 0x03, 0x2b, 0x13, 0xd9, 0xa2, 0xf1, 0xc9, 0x03, 0x0f, 0x2b, + 0x0f, 0xd9, 0x13, 0x2a, 0x0d, 0xdc, 0xa2, 0xf1, 0x34, 0x03, 0x64, 0x2b, + 0x09, 0xd9, 0xa2, 0xf1, 0xa9, 0x03, 0x1f, 0x2b, 0x07, 0xd9, 0xd1, 0x3a, + 0x07, 0x2a, 0x94, 0xbf, 0x00, 0x20, 0x01, 0x20, 0x70, 0x47, 0x00, 0x20, + 0x70, 0x47, 0x00, 0x20, 0x70, 0x47, 0xb0, 0xf8, 0xda, 0x30, 0x03, 0xf4, + 0x70, 0x42, 0xb2, 0xf5, 0x00, 0x5f, 0x06, 0xd1, 0xdb, 0xb2, 0xc0, 0x18, + 0x00, 0xf5, 0x9a, 0x50, 0x2f, 0x30, 0x00, 0x79, 0x00, 0xe0, 0x00, 0x20, + 0x40, 0xb2, 0x70, 0x47, 0x0b, 0x78, 0x10, 0xb5, 0x80, 0xf8, 0x2c, 0x36, + 0x4b, 0x78, 0x80, 0xf8, 0x2d, 0x36, 0x8b, 0x78, 0x80, 0xf8, 0x2e, 0x36, + 0xcb, 0x78, 0x80, 0xf8, 0x2f, 0x36, 0x00, 0x23, 0xca, 0x18, 0x14, 0x79, + 0xc2, 0x18, 0x01, 0x33, 0x08, 0x2b, 0x82, 0xf8, 0x30, 0x46, 0xf7, 0xd1, + 0x10, 0xbd, 0x22, 0xb1, 0x00, 0xf5, 0x80, 0x53, 0x00, 0x22, 0x9a, 0x60, + 0x9a, 0x81, 0x00, 0xf5, 0x82, 0x50, 0x01, 0x60, 0x01, 0x20, 0x70, 0x47, + 0x6f, 0xf0, 0x16, 0x00, 0x70, 0x47, 0xf8, 0xb5, 0x00, 0xf5, 0x90, 0x56, + 0x96, 0xf8, 0x3e, 0x30, 0x04, 0x46, 0x8b, 0x42, 0x0d, 0x46, 0x17, 0x46, + 0x03, 0xd0, 0xd0, 0xf8, 0x88, 0x30, 0x03, 0xb1, 0x98, 0x47, 0x04, 0xf5, + 0x92, 0x54, 0x27, 0x80, 0x86, 0xf8, 0x3e, 0x50, 0xf8, 0xbd, 0x00, 0x20, + 0x70, 0x47, 0x10, 0xb5, 0x90, 0xf8, 0xe9, 0x30, 0x94, 0xb0, 0x43, 0xf0, + 0x01, 0x03, 0x80, 0xf8, 0xe9, 0x30, 0x04, 0x46, 0x00, 0x21, 0x30, 0x22, + 0x01, 0xa8, 0xf1, 0xf3, 0xbf, 0xf1, 0x00, 0x21, 0x10, 0x22, 0x0d, 0xa8, + 0xf1, 0xf3, 0xba, 0xf1, 0x00, 0x21, 0x04, 0x22, 0x13, 0xa8, 0xf1, 0xf3, + 0xb5, 0xf1, 0x11, 0xa8, 0x00, 0x21, 0x08, 0x22, 0xf1, 0xf3, 0xb0, 0xf1, + 0x94, 0xf8, 0xe9, 0x30, 0x00, 0x20, 0x23, 0xf0, 0x01, 0x03, 0x84, 0xf8, + 0xe9, 0x30, 0x14, 0xb0, 0x10, 0xbd, 0x00, 0x21, 0x09, 0xf0, 0x3b, 0xbb, + 0xc3, 0x69, 0x70, 0xb5, 0xdc, 0x68, 0x1b, 0x6d, 0x05, 0x46, 0xdb, 0x07, + 0x0e, 0x46, 0x07, 0xd5, 0x20, 0x46, 0xfa, 0xf3, 0xd1, 0xf0, 0x18, 0xb1, + 0xeb, 0x69, 0x9b, 0x69, 0x98, 0x00, 0x0f, 0xd4, 0xeb, 0x69, 0x1a, 0x6d, + 0xd1, 0x07, 0x39, 0xd5, 0x5a, 0x6d, 0x12, 0x06, 0x36, 0xd4, 0xd8, 0x68, + 0xfa, 0xf3, 0x60, 0xf2, 0x00, 0x28, 0x31, 0xd0, 0xeb, 0x69, 0x9b, 0x69, + 0x9b, 0x00, 0x2d, 0xd5, 0xd5, 0xf8, 0xf8, 0x30, 0x98, 0x07, 0x29, 0xd4, + 0x63, 0x69, 0xe6, 0xb1, 0x06, 0xf4, 0x70, 0x42, 0xb2, 0xf5, 0x00, 0x5f, + 0x17, 0xd1, 0x22, 0x2b, 0x11, 0x49, 0xcc, 0xbf, 0x0c, 0x23, 0x00, 0x23, + 0xf2, 0xb2, 0xd8, 0xbf, 0x0f, 0x21, 0x20, 0x46, 0x9a, 0x40, 0x01, 0x23, + 0xfa, 0xf3, 0xac, 0xf0, 0x63, 0x69, 0x0c, 0x49, 0x22, 0x2b, 0x20, 0x46, + 0xd8, 0xbf, 0x70, 0x21, 0xcc, 0xbf, 0x4f, 0xf4, 0x00, 0x72, 0x10, 0x22, + 0x05, 0xe0, 0x06, 0x49, 0x20, 0x46, 0x22, 0x2b, 0xd8, 0xbf, 0x0f, 0x21, + 0x00, 0x22, 0x01, 0x23, 0xbd, 0xe8, 0x70, 0x40, 0xfa, 0xf3, 0x96, 0xb0, + 0x70, 0xbd, 0x00, 0xbf, 0x00, 0xf0, 0x55, 0x55, 0x00, 0x0e, 0x55, 0x55, + 0x08, 0xb5, 0x14, 0x29, 0xd0, 0xf8, 0xa8, 0x20, 0x02, 0xd0, 0x15, 0x29, + 0x0e, 0xd1, 0x09, 0xe0, 0x92, 0xf9, 0x1a, 0x20, 0x02, 0xa9, 0x41, 0xf8, + 0x04, 0x2f, 0x18, 0x46, 0x04, 0x22, 0xf1, 0xf3, 0xdb, 0xf0, 0x01, 0xe0, + 0x03, 0x9b, 0x93, 0x76, 0x00, 0x20, 0x08, 0xbd, 0x6f, 0xf0, 0x16, 0x00, + 0x08, 0xbd, 0x10, 0xb5, 0x90, 0xf8, 0x1a, 0x36, 0x0c, 0x46, 0x2b, 0xb1, + 0x02, 0x31, 0x22, 0x46, 0x09, 0xf0, 0x1c, 0xff, 0xa3, 0x78, 0x63, 0x70, + 0x10, 0xbd, 0x01, 0x21, 0x09, 0xf0, 0x1c, 0xbb, 0x10, 0xb5, 0x00, 0x23, + 0x04, 0x46, 0xe2, 0x18, 0x01, 0x33, 0x7f, 0x21, 0x65, 0x2b, 0x82, 0xf8, + 0x91, 0x16, 0xf8, 0xd1, 0x20, 0x46, 0xff, 0xf7, 0xf0, 0xff, 0x20, 0x46, + 0xbd, 0xe8, 0x10, 0x40, 0xff, 0xf7, 0x6f, 0xbf, 0x04, 0x4b, 0x1b, 0x78, + 0x01, 0x2b, 0x02, 0xd1, 0x00, 0x20, 0x00, 0x70, 0x70, 0x47, 0x15, 0xf0, + 0xb5, 0xbf, 0x00, 0xbf, 0x38, 0x08, 0x02, 0x00, 0x04, 0x4b, 0x1b, 0x78, + 0x01, 0x2b, 0x02, 0xd1, 0x00, 0x20, 0x00, 0x70, 0x70, 0x47, 0x15, 0xf0, + 0xd1, 0xbf, 0x00, 0xbf, 0x38, 0x08, 0x02, 0x00, 0x10, 0xb5, 0x14, 0x46, + 0xff, 0xf7, 0xf0, 0xff, 0x28, 0xb1, 0x00, 0x21, 0x0a, 0x46, 0xbd, 0xe8, + 0x10, 0x40, 0xf1, 0xf3, 0x7b, 0xb4, 0x20, 0x46, 0x10, 0xbd, 0x00, 0x22, + 0xff, 0xf7, 0xf0, 0xbf, 0x2d, 0xe9, 0xf0, 0x41, 0x05, 0x46, 0x0c, 0x46, + 0x17, 0x46, 0x1e, 0x46, 0xff, 0xf7, 0xdc, 0xff, 0x38, 0xb1, 0x28, 0x46, + 0x21, 0x46, 0x3a, 0x46, 0x33, 0x46, 0xbd, 0xe8, 0xf0, 0x41, 0x15, 0xf0, + 0xed, 0xbf, 0x30, 0x46, 0xbd, 0xe8, 0xf0, 0x81, 0x00, 0x23, 0xff, 0xf7, + 0xe9, 0xbf, 0xc3, 0x69, 0x18, 0x69, 0x3f, 0xf0, 0x41, 0x9c, 0xc3, 0x69, + 0x18, 0x69, 0x3f, 0xf0, 0x33, 0x9c, 0x70, 0xb5, 0x05, 0x46, 0x0c, 0x46, + 0x16, 0x46, 0xff, 0xf7, 0x2b, 0xfe, 0x21, 0x46, 0x00, 0xea, 0x06, 0x02, + 0x28, 0x46, 0xbd, 0xe8, 0x70, 0x40, 0xff, 0xf7, 0x3a, 0xbe, 0x70, 0xb5, + 0x05, 0x46, 0x0c, 0x46, 0x16, 0x46, 0xff, 0xf7, 0x1d, 0xfe, 0x40, 0xea, + 0x06, 0x02, 0x21, 0x46, 0x28, 0x46, 0x92, 0xb2, 0xbd, 0xe8, 0x70, 0x40, + 0xff, 0xf7, 0x2b, 0xbe, 0xf8, 0xb5, 0x05, 0x46, 0x0c, 0x46, 0x16, 0x46, + 0x1f, 0x46, 0xff, 0xf7, 0x0d, 0xfe, 0x20, 0xea, 0x06, 0x02, 0x3e, 0x40, + 0x32, 0x43, 0x28, 0x46, 0x21, 0x46, 0x92, 0xb2, 0xbd, 0xe8, 0xf8, 0x40, + 0xff, 0xf7, 0x19, 0xbe, 0xf8, 0xb5, 0x1f, 0x46, 0x06, 0x9b, 0x15, 0x46, + 0x19, 0x80, 0x07, 0x9e, 0x0c, 0x46, 0xff, 0xf7, 0xf9, 0xfd, 0x08, 0x9b, + 0x30, 0x80, 0x1c, 0x80, 0x33, 0x88, 0x2f, 0x40, 0x23, 0xea, 0x05, 0x03, + 0x43, 0xea, 0x07, 0x05, 0x09, 0x9b, 0x1d, 0x80, 0xf8, 0xbd, 0xd0, 0xf8, + 0xb0, 0x30, 0xa3, 0xf8, 0xfc, 0x13, 0xb3, 0xf8, 0xfe, 0x13, 0x0a, 0x40, + 0xa3, 0xf8, 0xfe, 0x23, 0x00, 0x23, 0xa0, 0xf8, 0x20, 0x36, 0x70, 0x47, + 0xd0, 0xf8, 0xb0, 0x30, 0xa3, 0xf8, 0xfc, 0x13, 0xb3, 0xf8, 0xfe, 0x13, + 0x89, 0xb2, 0x0a, 0x43, 0xa3, 0xf8, 0xfe, 0x23, 0x00, 0x23, 0xa0, 0xf8, + 0x20, 0x36, 0x70, 0x47, 0x10, 0xb5, 0xd0, 0xf8, 0xb0, 0x40, 0x13, 0x40, + 0xa4, 0xf8, 0xfc, 0x13, 0xb4, 0xf8, 0xfe, 0x13, 0x89, 0xb2, 0x21, 0xea, + 0x02, 0x02, 0x1a, 0x43, 0x00, 0x23, 0xa4, 0xf8, 0xfe, 0x23, 0xa0, 0xf8, + 0x20, 0x36, 0x10, 0xbd, 0x70, 0xb5, 0x0b, 0x46, 0x05, 0x46, 0x2d, 0xe0, + 0x1c, 0x46, 0x56, 0x1e, 0x34, 0xf8, 0x02, 0x2b, 0x91, 0x04, 0x02, 0xf4, + 0x40, 0x42, 0x89, 0x0c, 0xb2, 0xf5, 0x80, 0x4f, 0x12, 0xd0, 0x01, 0xdc, + 0x3a, 0xb1, 0x1d, 0xe0, 0xb2, 0xf5, 0x00, 0x4f, 0x11, 0xd0, 0xb2, 0xf5, + 0x40, 0x4f, 0x17, 0xd1, 0x12, 0xe0, 0x1c, 0x46, 0x5a, 0x88, 0x28, 0x46, + 0x34, 0xf8, 0x04, 0x3f, 0xff, 0xf7, 0xce, 0xff, 0x01, 0x3e, 0x0d, 0xe0, + 0x28, 0x46, 0x5a, 0x88, 0xff, 0xf7, 0xe2, 0xfd, 0x08, 0xe0, 0x28, 0x46, + 0x5a, 0x88, 0xff, 0xf7, 0xa8, 0xff, 0x03, 0xe0, 0x28, 0x46, 0x5a, 0x88, + 0xff, 0xf7, 0xb0, 0xff, 0xa3, 0x1c, 0x72, 0x1e, 0x00, 0x2a, 0xcf, 0xdc, + 0x70, 0xbd, 0xf8, 0xb5, 0x1f, 0x46, 0x06, 0x9b, 0x15, 0x46, 0x19, 0x80, + 0x07, 0x9e, 0x0c, 0x46, 0xff, 0xf7, 0xbf, 0xfd, 0x08, 0x9b, 0x30, 0x80, + 0x1c, 0x80, 0x33, 0x88, 0x2f, 0x40, 0x23, 0xea, 0x05, 0x03, 0x43, 0xea, + 0x07, 0x05, 0x09, 0x9b, 0x1d, 0x80, 0xf8, 0xbd, 0x29, 0xb1, 0x40, 0xf2, + 0x3b, 0x41, 0x4f, 0xf6, 0xf8, 0x72, 0xff, 0xf7, 0x82, 0xbf, 0x02, 0x49, + 0x04, 0x22, 0xff, 0xf7, 0xab, 0xbf, 0x00, 0xbf, 0x8c, 0xde, 0x01, 0x00, + 0x58, 0xb1, 0xb0, 0xf8, 0xde, 0x00, 0xb0, 0xf5, 0x00, 0x6f, 0x05, 0xd0, + 0xb0, 0xf5, 0x40, 0x6f, 0x0c, 0xbf, 0x80, 0x20, 0x00, 0x20, 0x70, 0x47, + 0x40, 0x20, 0x70, 0x47, 0x01, 0x23, 0x80, 0xf8, 0xe1, 0x30, 0x70, 0x47, + 0x80, 0xf8, 0x24, 0x16, 0x70, 0x47, 0x90, 0xf9, 0x24, 0x06, 0x70, 0x47, + 0x70, 0x47, 0x10, 0xb1, 0xc3, 0x69, 0x03, 0xb1, 0x59, 0x77, 0x70, 0x47, + 0x10, 0xb1, 0xc3, 0x69, 0x03, 0xb1, 0x19, 0x77, 0x70, 0x47, 0x90, 0xf8, + 0xe3, 0x30, 0x10, 0xb5, 0x04, 0x46, 0x00, 0x2b, 0x5f, 0xd1, 0x64, 0x22, + 0xa0, 0xf8, 0x9c, 0x28, 0xa0, 0xf8, 0x9e, 0x28, 0x4f, 0xf4, 0x48, 0x72, + 0xa0, 0xf8, 0xa4, 0x28, 0x64, 0x22, 0xa0, 0xf8, 0xa6, 0x28, 0xa0, 0xf8, + 0xa8, 0x28, 0xa0, 0xf8, 0xaa, 0x28, 0xa0, 0xf8, 0xac, 0x28, 0xa0, 0xf8, + 0xae, 0x28, 0xa0, 0xf8, 0xb0, 0x28, 0xa0, 0xf8, 0xb2, 0x28, 0xa0, 0xf8, + 0xb4, 0x28, 0x0a, 0x22, 0xa0, 0xf8, 0x36, 0x28, 0xa0, 0xf8, 0x54, 0x28, + 0xa0, 0xf8, 0x3a, 0x28, 0xa0, 0xf8, 0x5c, 0x28, 0xa0, 0xf8, 0x38, 0x28, + 0xa0, 0xf8, 0x56, 0x28, 0xa0, 0xf8, 0x3c, 0x28, 0xa0, 0xf8, 0x5e, 0x28, + 0xa0, 0xf8, 0x2a, 0x28, 0xa0, 0xf8, 0x28, 0x28, 0xa0, 0xf8, 0x2c, 0x28, + 0xa0, 0xf8, 0x2e, 0x28, 0x14, 0x22, 0xa0, 0xf8, 0x32, 0x28, 0xa0, 0xf8, + 0x34, 0x28, 0x0a, 0x22, 0xa0, 0xf8, 0x90, 0x27, 0xa0, 0xf8, 0x92, 0x27, + 0x50, 0x22, 0xa0, 0xf8, 0x94, 0x27, 0x0a, 0x22, 0xc0, 0xf8, 0xa0, 0x38, + 0xa0, 0xf8, 0x30, 0x38, 0xa0, 0xf8, 0xac, 0x37, 0xa0, 0xf8, 0xae, 0x37, + 0xa0, 0xf8, 0x4a, 0x28, 0xa0, 0xf8, 0x48, 0x28, 0xc0, 0xf8, 0x58, 0x38, + 0xc0, 0xf8, 0x60, 0x38, 0x43, 0x6a, 0xa0, 0xf8, 0x4c, 0x28, 0xa0, 0xf8, + 0x4e, 0x28, 0x14, 0x22, 0xa0, 0xf8, 0x50, 0x28, 0xa0, 0xf8, 0x52, 0x28, + 0x03, 0xb1, 0x98, 0x47, 0x01, 0x23, 0x84, 0xf8, 0xe3, 0x30, 0x10, 0xbd, + 0x08, 0xb5, 0x00, 0xf5, 0x96, 0x53, 0x99, 0x6a, 0x41, 0xb1, 0xc3, 0x69, + 0x18, 0x69, 0x3f, 0xf0, 0xff, 0xda, 0xd0, 0xf1, 0x01, 0x00, 0x38, 0xbf, + 0x00, 0x20, 0x08, 0xbd, 0x08, 0x46, 0x08, 0xbd, 0x2d, 0xe9, 0xf8, 0x4f, + 0x0c, 0x46, 0xd1, 0xf8, 0x10, 0xa0, 0xd1, 0xf8, 0x00, 0x80, 0x9b, 0x46, + 0x89, 0x68, 0xe3, 0x68, 0x00, 0x27, 0x43, 0xea, 0x81, 0x23, 0x11, 0x46, + 0x9a, 0xb2, 0x05, 0x46, 0xbd, 0xf8, 0x28, 0x90, 0x3e, 0x46, 0xff, 0xf7, + 0x01, 0xfd, 0x1b, 0xe0, 0xba, 0xf1, 0x20, 0x0f, 0x0b, 0xd1, 0x58, 0xf8, + 0x07, 0x20, 0x28, 0x46, 0x59, 0x46, 0x12, 0x0c, 0xff, 0xf7, 0xf6, 0xfc, + 0x28, 0x46, 0x49, 0x46, 0x38, 0xf8, 0x07, 0x20, 0x08, 0xe0, 0xba, 0xf1, + 0x10, 0x0f, 0x0c, 0xbf, 0x38, 0xf8, 0x16, 0x20, 0x18, 0xf8, 0x06, 0x20, + 0x28, 0x46, 0x49, 0x46, 0xff, 0xf7, 0xe6, 0xfc, 0x01, 0x36, 0x04, 0x37, + 0x63, 0x68, 0x9e, 0x42, 0xe0, 0xd3, 0xbd, 0xe8, 0xf8, 0x8f, 0x2d, 0xe9, + 0xf7, 0x4f, 0x0c, 0x46, 0x01, 0x93, 0xd1, 0xf8, 0x10, 0x80, 0x0e, 0x68, + 0xe3, 0x68, 0x89, 0x68, 0x4f, 0xf0, 0x00, 0x0a, 0x43, 0xea, 0x81, 0x23, + 0x11, 0x46, 0x9a, 0xb2, 0x05, 0x46, 0xbd, 0xf8, 0x30, 0x70, 0xd1, 0x46, + 0xff, 0xf7, 0xca, 0xfc, 0x22, 0xe0, 0xb8, 0xf1, 0x20, 0x0f, 0x28, 0x46, + 0x39, 0x46, 0x0d, 0xd1, 0xff, 0xf7, 0xb7, 0xfc, 0x01, 0x99, 0x83, 0x46, + 0x46, 0xf8, 0x0a, 0x00, 0x28, 0x46, 0xff, 0xf7, 0xb0, 0xfc, 0x4b, 0xea, + 0x00, 0x40, 0x46, 0xf8, 0x0a, 0x00, 0x0b, 0xe0, 0xb8, 0xf1, 0x10, 0x0f, + 0x04, 0xd1, 0xff, 0xf7, 0xa6, 0xfc, 0x26, 0xf8, 0x19, 0x00, 0x03, 0xe0, + 0xff, 0xf7, 0xa1, 0xfc, 0x06, 0xf8, 0x09, 0x00, 0x09, 0xf1, 0x01, 0x09, + 0x0a, 0xf1, 0x04, 0x0a, 0x63, 0x68, 0x99, 0x45, 0xd9, 0xd3, 0xbd, 0xe8, + 0xfe, 0x8f, 0x7f, 0xb5, 0x02, 0x93, 0x08, 0x9b, 0x03, 0x91, 0x05, 0x93, + 0x09, 0x9b, 0x01, 0x92, 0x04, 0x93, 0x01, 0xa9, 0x0a, 0x9b, 0x98, 0x47, + 0x07, 0xb0, 0x00, 0xbd, 0x7f, 0xb5, 0x02, 0x93, 0x08, 0x9b, 0x03, 0x91, + 0x05, 0x93, 0x09, 0x9b, 0x01, 0x92, 0x04, 0x93, 0x01, 0xa9, 0x0a, 0x9b, + 0x98, 0x47, 0x07, 0xb0, 0x00, 0xbd, 0x00, 0x00, 0xf0, 0xb5, 0x3f, 0x4b, + 0x8b, 0xb0, 0xd0, 0xf8, 0xb0, 0x40, 0x07, 0x46, 0x0d, 0x46, 0x6a, 0x46, + 0x03, 0xf1, 0x10, 0x0e, 0x18, 0x68, 0x59, 0x68, 0x16, 0x46, 0x03, 0xc6, + 0x08, 0x33, 0x73, 0x45, 0x32, 0x46, 0xf7, 0xd1, 0x18, 0x68, 0x37, 0x4b, + 0x30, 0x60, 0x05, 0xaa, 0x03, 0xf1, 0x10, 0x0e, 0x18, 0x68, 0x59, 0x68, + 0x16, 0x46, 0x03, 0xc6, 0x08, 0x33, 0x73, 0x45, 0x32, 0x46, 0xf7, 0xd1, + 0x18, 0x68, 0x30, 0x60, 0x0d, 0xb1, 0x6b, 0x46, 0x00, 0xe0, 0x05, 0xab, + 0xfa, 0x69, 0x00, 0x21, 0x10, 0x69, 0x14, 0x22, 0x3f, 0xf0, 0x32, 0xda, + 0x00, 0x23, 0xa4, 0xf8, 0x68, 0x35, 0x00, 0x2d, 0x4f, 0xf4, 0x80, 0x73, + 0xa4, 0xf8, 0xc0, 0x37, 0x0c, 0xbf, 0x40, 0x23, 0x41, 0x23, 0xa4, 0xf8, + 0x0c, 0x35, 0x41, 0xf6, 0x02, 0x23, 0xa4, 0xf8, 0x14, 0x35, 0x4f, 0xf0, + 0x00, 0x03, 0xa4, 0xf8, 0x08, 0x35, 0xa4, 0xf8, 0x0a, 0x35, 0xa4, 0xf8, + 0x4c, 0x35, 0x4f, 0xf0, 0x14, 0x03, 0xa4, 0xf8, 0x6a, 0x35, 0x40, 0xf6, + 0x26, 0x03, 0xa4, 0xf8, 0x68, 0x35, 0x4f, 0xf0, 0x00, 0x03, 0xa4, 0xf8, + 0x00, 0x35, 0x4f, 0xf0, 0xd0, 0x03, 0xa4, 0xf8, 0x02, 0x35, 0x0c, 0xbf, + 0xfa, 0x26, 0x1e, 0x26, 0xb4, 0xf8, 0x02, 0x35, 0x00, 0x25, 0x02, 0xe0, + 0x0a, 0x20, 0xf5, 0xf3, 0x09, 0xf2, 0xb5, 0x42, 0x09, 0xda, 0xb4, 0xf8, + 0x0e, 0x35, 0x01, 0x35, 0x1b, 0x06, 0xf5, 0xd4, 0x03, 0xe0, 0x0a, 0x20, + 0xf5, 0xf3, 0xfe, 0xf1, 0x00, 0xe0, 0x0b, 0x25, 0x01, 0x3d, 0x08, 0xd0, + 0xb4, 0xf8, 0x0e, 0x35, 0x58, 0x05, 0xf4, 0xd5, 0x03, 0xe0, 0x0a, 0x20, + 0xf5, 0xf3, 0xf2, 0xf1, 0x00, 0xe0, 0x0b, 0x25, 0x01, 0x3d, 0x03, 0xd0, + 0xb4, 0xf8, 0x90, 0x36, 0xd9, 0x05, 0xf4, 0xd4, 0x0b, 0xb0, 0xf0, 0xbd, + 0xce, 0xb7, 0x01, 0x00, 0xe2, 0xb7, 0x01, 0x00, 0xd0, 0xf8, 0xf8, 0x30, + 0x0a, 0xb1, 0x0b, 0x43, 0x01, 0xe0, 0x23, 0xea, 0x01, 0x03, 0xc0, 0xf8, + 0xf8, 0x30, 0x70, 0x47, 0x10, 0xb5, 0xd0, 0xf8, 0xf8, 0x30, 0x21, 0xb1, + 0x43, 0xf0, 0x10, 0x03, 0xc0, 0xf8, 0xf8, 0x30, 0x10, 0xbd, 0x23, 0xf0, + 0x10, 0x03, 0xd2, 0x07, 0xc0, 0xf8, 0xf8, 0x30, 0x0b, 0xd5, 0x00, 0xf5, + 0x8e, 0x53, 0x5c, 0x6b, 0xc3, 0x69, 0x1a, 0x6a, 0x9b, 0x6e, 0x9a, 0x42, + 0x88, 0xbf, 0xc3, 0xeb, 0x02, 0x01, 0xc4, 0xf8, 0x90, 0x10, 0x10, 0xbd, + 0xc3, 0x69, 0x10, 0xb5, 0x58, 0x21, 0x04, 0x46, 0x47, 0xf6, 0x7f, 0x72, + 0x18, 0x69, 0x3f, 0xf0, 0xa1, 0xd9, 0xe3, 0x69, 0x5a, 0x21, 0x18, 0x69, + 0x47, 0xf6, 0x7f, 0x72, 0x3f, 0xf0, 0x9a, 0xd9, 0xe3, 0x69, 0x70, 0x21, + 0x18, 0x69, 0x47, 0xf6, 0x7f, 0x72, 0x3f, 0xf0, 0x93, 0xd9, 0xe3, 0x69, + 0x72, 0x21, 0x18, 0x69, 0x47, 0xf6, 0x7f, 0x72, 0xbd, 0xe8, 0x10, 0x40, + 0x3f, 0xf0, 0x8a, 0x99, 0x38, 0xb5, 0xd0, 0xf8, 0xb0, 0x30, 0x04, 0x46, + 0xd3, 0xf8, 0x20, 0x31, 0xc3, 0x69, 0x0d, 0x46, 0x1a, 0x6d, 0xd0, 0x07, + 0x07, 0xd5, 0xd8, 0x68, 0xf9, 0xf3, 0x3c, 0xf5, 0x18, 0xb1, 0xe3, 0x69, + 0x9b, 0x69, 0x99, 0x00, 0x0e, 0xd4, 0xe3, 0x69, 0x1a, 0x6d, 0xd2, 0x07, + 0x15, 0xd5, 0x5a, 0x6d, 0x10, 0x06, 0x12, 0xd4, 0xd8, 0x68, 0xf9, 0xf3, + 0xcb, 0xf6, 0x70, 0xb1, 0xe3, 0x69, 0x9b, 0x69, 0x99, 0x00, 0x0a, 0xd5, + 0x20, 0x46, 0x1d, 0xb9, 0x29, 0x46, 0xff, 0xf7, 0x47, 0xfc, 0x14, 0xe0, + 0xb4, 0xf8, 0xda, 0x10, 0xff, 0xf7, 0x42, 0xfc, 0x00, 0xe0, 0x75, 0xb1, + 0x06, 0x22, 0x20, 0x46, 0x0a, 0x49, 0xff, 0xf7, 0x81, 0xfd, 0xd4, 0xf8, + 0xa8, 0x30, 0x93, 0xf8, 0x2c, 0x30, 0x01, 0x2b, 0x0a, 0xd1, 0x20, 0x46, + 0x06, 0x49, 0x04, 0x22, 0x02, 0xe0, 0x06, 0x49, 0x20, 0x46, 0x0e, 0x22, + 0xbd, 0xe8, 0x38, 0x40, 0xff, 0xf7, 0x70, 0xbd, 0x38, 0xbd, 0x00, 0xbf, + 0x80, 0xde, 0x01, 0x00, 0xaa, 0xe4, 0x01, 0x00, 0xb2, 0xe4, 0x01, 0x00, + 0xa0, 0xf8, 0xde, 0x10, 0x70, 0x47, 0xa0, 0xf8, 0xda, 0x10, 0x70, 0x47, + 0xb0, 0xf8, 0xda, 0x00, 0x70, 0x47, 0x40, 0xf6, 0xc3, 0x13, 0x98, 0x42, + 0x0a, 0xd9, 0x41, 0xf2, 0xc8, 0x43, 0x98, 0x42, 0x08, 0xd9, 0x41, 0xf2, + 0x44, 0x63, 0x98, 0x42, 0x8c, 0xbf, 0x03, 0x20, 0x02, 0x20, 0x70, 0x47, + 0x00, 0x20, 0x70, 0x47, 0x01, 0x20, 0x70, 0x47, 0x70, 0x47, 0x00, 0x00, + 0x10, 0xb5, 0x00, 0x23, 0x06, 0x4a, 0x99, 0x00, 0x32, 0xf8, 0x23, 0x40, + 0x84, 0x42, 0x02, 0xd1, 0x52, 0x18, 0x50, 0x88, 0x10, 0xbd, 0x01, 0x33, + 0x0e, 0x2b, 0xf3, 0xd1, 0x00, 0x20, 0x10, 0xbd, 0x48, 0xde, 0x01, 0x00, + 0x08, 0xb5, 0xc8, 0xb2, 0xff, 0xf7, 0xea, 0xff, 0xbd, 0xe8, 0x08, 0x40, + 0xff, 0xf7, 0xd1, 0xbf, 0x70, 0xb5, 0x06, 0x46, 0x0d, 0x46, 0x10, 0x46, + 0x14, 0x46, 0x00, 0x21, 0x1c, 0x22, 0xf0, 0xf3, 0x85, 0xf5, 0x00, 0x22, + 0x06, 0xf5, 0x92, 0x51, 0x0e, 0x4b, 0x09, 0x7a, 0xd3, 0x5a, 0x19, 0xb1, + 0x94, 0x2b, 0x01, 0xd9, 0xa5, 0x2b, 0x11, 0xd9, 0x02, 0x2d, 0x02, 0xd1, + 0x0e, 0x2b, 0x04, 0xd9, 0x0c, 0xe0, 0x01, 0x2d, 0x0a, 0xd1, 0x0e, 0x2b, + 0x08, 0xd9, 0xd9, 0x08, 0x01, 0x20, 0x03, 0xf0, 0x07, 0x03, 0x10, 0xfa, + 0x03, 0xf3, 0x60, 0x5c, 0x03, 0x43, 0x63, 0x54, 0x04, 0x32, 0x38, 0x2a, + 0xe0, 0xd1, 0x70, 0xbd, 0x48, 0xde, 0x01, 0x00, 0x30, 0xb5, 0x00, 0xf5, + 0x92, 0x50, 0x04, 0x7a, 0x00, 0x22, 0x0f, 0x4b, 0xd3, 0x5a, 0x43, 0xf4, + 0x30, 0x60, 0x0e, 0x2b, 0x8c, 0xbf, 0x4f, 0xf4, 0x80, 0x55, 0x4f, 0xf4, + 0x00, 0x55, 0x28, 0x43, 0x1c, 0xb1, 0x94, 0x2b, 0x01, 0xd9, 0xa5, 0x2b, + 0x08, 0xd9, 0x02, 0x29, 0x02, 0xd1, 0x0e, 0x2b, 0x04, 0xd8, 0x30, 0xbd, + 0x01, 0x29, 0x01, 0xd1, 0x0e, 0x2b, 0x03, 0xd8, 0x04, 0x32, 0x38, 0x2a, + 0xe3, 0xd1, 0xff, 0x20, 0x30, 0xbd, 0x00, 0xbf, 0x48, 0xde, 0x01, 0x00, + 0x10, 0xb5, 0x90, 0xf8, 0xb2, 0x32, 0x0b, 0x60, 0x90, 0xf8, 0x2b, 0x36, + 0x4b, 0xb1, 0x90, 0xf8, 0x2a, 0x36, 0x90, 0xf8, 0xf8, 0x46, 0x5b, 0xb2, + 0x14, 0xb1, 0x5b, 0x42, 0x43, 0xf0, 0x80, 0x43, 0x0b, 0x60, 0x12, 0xb1, + 0x90, 0xf8, 0xf7, 0x36, 0x13, 0x70, 0x00, 0x20, 0x10, 0xbd, 0x30, 0xb5, + 0x00, 0xf5, 0x80, 0x55, 0x95, 0xf8, 0x3b, 0x50, 0x03, 0x9c, 0xad, 0x00, + 0x0e, 0x29, 0x15, 0x70, 0x06, 0xd8, 0x00, 0x2c, 0xa8, 0xbf, 0x00, 0x19, + 0x90, 0xf8, 0x1e, 0x21, 0x1a, 0x70, 0x30, 0xbd, 0x7f, 0x22, 0x1a, 0x70, + 0xa1, 0xf1, 0x22, 0x02, 0x34, 0xea, 0x24, 0x04, 0x28, 0xbf, 0x04, 0x24, + 0x1e, 0x2a, 0x03, 0xd8, 0x02, 0x19, 0x92, 0xf8, 0x83, 0x21, 0x1a, 0x70, + 0xa1, 0xf1, 0x64, 0x02, 0x28, 0x2a, 0x03, 0xd8, 0x02, 0x19, 0x92, 0xf8, + 0xe8, 0x21, 0x1a, 0x70, 0x95, 0x39, 0x10, 0x29, 0x03, 0xd8, 0x00, 0x19, + 0x90, 0xf8, 0x4d, 0x22, 0x1a, 0x70, 0x30, 0xbd, 0x2d, 0xe9, 0xff, 0x47, + 0x00, 0x24, 0x07, 0x46, 0x88, 0x46, 0x91, 0x46, 0x9a, 0x46, 0xff, 0x25, + 0x26, 0x46, 0x41, 0x46, 0x0d, 0xf1, 0x0f, 0x02, 0x0d, 0xf1, 0x0e, 0x03, + 0x38, 0x46, 0x00, 0x94, 0xff, 0xf7, 0xbf, 0xff, 0x07, 0xf5, 0x98, 0x53, + 0x9b, 0x79, 0x9d, 0xf8, 0x0e, 0x20, 0x59, 0xb2, 0x8a, 0x42, 0xc6, 0xbf, + 0xc3, 0xeb, 0x02, 0x03, 0xdb, 0xb2, 0x00, 0x23, 0x01, 0x34, 0xb3, 0x42, + 0x28, 0xbf, 0x1e, 0x46, 0xab, 0x42, 0x38, 0xbf, 0x1d, 0x46, 0x14, 0x2c, + 0x8d, 0xf8, 0x0e, 0x30, 0xdf, 0xd1, 0x89, 0xf8, 0x00, 0x60, 0x8a, 0xf8, + 0x00, 0x50, 0xbd, 0xe8, 0xff, 0x87, 0x70, 0x47, 0x90, 0xf8, 0x29, 0x06, + 0x70, 0x47, 0x2d, 0xe9, 0xf0, 0x4f, 0xb0, 0xf8, 0xda, 0x30, 0xc2, 0x69, + 0x03, 0xf4, 0x70, 0x43, 0xb3, 0xf5, 0x80, 0x5f, 0x14, 0xbf, 0x02, 0x25, + 0x01, 0x25, 0xa5, 0xb0, 0x52, 0x6c, 0x05, 0x95, 0x40, 0xf2, 0x39, 0x51, + 0xd0, 0xf8, 0xa8, 0x50, 0x8a, 0x42, 0x04, 0x46, 0x07, 0x95, 0x03, 0xd0, + 0x40, 0xf2, 0x8b, 0x51, 0x8a, 0x42, 0x05, 0xd1, 0xa3, 0xf5, 0x80, 0x51, + 0x4b, 0x42, 0x43, 0xeb, 0x01, 0x03, 0x00, 0xe0, 0x00, 0x23, 0xdb, 0xb2, + 0x00, 0x21, 0x65, 0x22, 0x0a, 0xa8, 0x08, 0x93, 0xf0, 0xf3, 0x9a, 0xf4, + 0xb4, 0xf8, 0xda, 0x50, 0x05, 0xf4, 0x40, 0x73, 0xb3, 0xf5, 0x40, 0x7f, + 0x04, 0x95, 0xee, 0xb2, 0x0b, 0xd0, 0xb3, 0xf5, 0x00, 0x7f, 0x03, 0xd1, + 0xdd, 0x2e, 0x05, 0xd8, 0x02, 0x36, 0x04, 0xe0, 0x02, 0x2e, 0x01, 0xd9, + 0x02, 0x3e, 0x00, 0xe0, 0x00, 0x26, 0x20, 0x46, 0x05, 0x99, 0xff, 0xf7, + 0x59, 0xfb, 0x20, 0x46, 0xff, 0xf7, 0x65, 0xfa, 0x00, 0x25, 0xb0, 0x46, + 0x09, 0x90, 0xa3, 0x46, 0x03, 0x95, 0x4f, 0xf0, 0xff, 0x0a, 0xa9, 0x46, + 0x26, 0x46, 0xe8, 0xb2, 0x06, 0x90, 0x04, 0x99, 0x20, 0x46, 0x2a, 0x46, + 0xff, 0xf7, 0x30, 0xfa, 0x00, 0x28, 0x5f, 0xd0, 0x96, 0xf8, 0xb2, 0x72, + 0x94, 0xf8, 0xac, 0x30, 0x0d, 0xf1, 0x28, 0x0c, 0x05, 0xf8, 0x0c, 0x70, + 0x63, 0xb1, 0x20, 0x46, 0x41, 0x46, 0x05, 0x9a, 0x06, 0x9b, 0xcd, 0xf8, + 0x08, 0xc0, 0xff, 0xf7, 0x8c, 0xfa, 0xdd, 0xf8, 0x08, 0xc0, 0x38, 0x18, + 0x05, 0xf8, 0x0c, 0x00, 0x41, 0x46, 0x0d, 0xf1, 0x8f, 0x02, 0x0d, 0xf1, + 0x8e, 0x03, 0x20, 0x46, 0x00, 0x95, 0xff, 0xf7, 0x28, 0xff, 0x9d, 0xf8, + 0x8e, 0x30, 0x96, 0xf8, 0x2c, 0x26, 0x9a, 0x42, 0x28, 0xbf, 0x1a, 0x46, + 0x04, 0xf5, 0x98, 0x53, 0x9b, 0x79, 0x59, 0xb2, 0x8a, 0x42, 0xc8, 0xbf, + 0xc3, 0xeb, 0x02, 0x02, 0x0a, 0xab, 0xe9, 0x5c, 0xcc, 0xbf, 0xd2, 0xb2, + 0x00, 0x22, 0x8d, 0xf8, 0x8e, 0x20, 0x8a, 0x42, 0x28, 0xbf, 0x0a, 0x46, + 0x94, 0xf8, 0xe0, 0x10, 0xea, 0x54, 0x64, 0x29, 0x04, 0xd8, 0x4a, 0x43, + 0x64, 0x20, 0x92, 0xfb, 0xf0, 0xf2, 0xea, 0x54, 0x0a, 0xab, 0xe8, 0x5c, + 0x9d, 0xf8, 0x8f, 0x10, 0x96, 0xf8, 0x91, 0x26, 0x88, 0x42, 0x28, 0xbf, + 0x01, 0x46, 0x09, 0x98, 0x8a, 0x42, 0x94, 0xbf, 0xc0, 0xeb, 0x02, 0x00, + 0xc0, 0xeb, 0x01, 0x00, 0xc1, 0xb2, 0x03, 0x9a, 0xe9, 0x54, 0x06, 0x9b, + 0x51, 0x45, 0x38, 0xbf, 0x8a, 0x46, 0x49, 0x45, 0x88, 0xbf, 0x1a, 0x46, + 0x03, 0x92, 0x49, 0x45, 0x28, 0xbf, 0x89, 0x46, 0x01, 0x35, 0x01, 0x36, + 0x14, 0x2d, 0x92, 0xd1, 0x65, 0x22, 0x04, 0xf5, 0xa2, 0x60, 0x00, 0x21, + 0xf0, 0xf3, 0x02, 0xf4, 0x03, 0x9d, 0x00, 0x22, 0x94, 0xf8, 0x1a, 0x06, + 0x84, 0xf8, 0x18, 0x96, 0x84, 0xf8, 0x29, 0xa6, 0x84, 0xf8, 0x2a, 0xa6, + 0x84, 0xf8, 0xf8, 0x26, 0x84, 0xf8, 0x19, 0x56, 0x23, 0x46, 0x0a, 0xa9, + 0x51, 0x5c, 0x83, 0xf8, 0x75, 0x15, 0x08, 0xb1, 0x08, 0x9d, 0x15, 0xb1, + 0xc1, 0xeb, 0x09, 0x01, 0x01, 0xe0, 0xca, 0xeb, 0x01, 0x01, 0x01, 0x32, + 0x83, 0xf8, 0x10, 0x15, 0x01, 0x33, 0x14, 0x2a, 0xed, 0xd1, 0x00, 0x23, + 0x5a, 0x46, 0x07, 0x9d, 0x92, 0xf9, 0x10, 0x15, 0xb5, 0xf9, 0xe6, 0x03, + 0x01, 0x33, 0x41, 0x18, 0xdb, 0xb2, 0x82, 0xf8, 0x10, 0x15, 0x01, 0x32, + 0x04, 0x2b, 0xf2, 0xd1, 0xe3, 0x6a, 0x0b, 0xb1, 0x20, 0x46, 0x98, 0x47, + 0x25, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, 0x7f, 0x29, 0x38, 0xb5, 0x04, 0x46, + 0x26, 0xd8, 0x00, 0x23, 0xe2, 0x18, 0x01, 0x33, 0x65, 0x2b, 0x82, 0xf8, + 0xb2, 0x12, 0xf9, 0xd1, 0x00, 0x23, 0xe2, 0x69, 0x84, 0xf8, 0xf7, 0x36, + 0x10, 0x7f, 0xf0, 0xb1, 0xd4, 0xf8, 0xf8, 0x10, 0x89, 0x07, 0x17, 0xd4, + 0xd4, 0xf8, 0xb0, 0x30, 0xd3, 0xf8, 0x20, 0x31, 0x03, 0xf0, 0x01, 0x03, + 0x83, 0xf0, 0x01, 0x05, 0x13, 0xb1, 0x10, 0x69, 0x3e, 0xf0, 0x54, 0xdf, + 0x20, 0x46, 0xff, 0xf7, 0xe4, 0xfe, 0x4d, 0xb9, 0xe3, 0x69, 0x18, 0x69, + 0x3e, 0xf0, 0x38, 0xdf, 0x28, 0x46, 0x38, 0xbd, 0x05, 0x20, 0x38, 0xbd, + 0x18, 0x46, 0x38, 0xbd, 0x00, 0x20, 0x38, 0xbd, 0x70, 0xb5, 0x00, 0xf5, + 0x2c, 0x76, 0x0d, 0x46, 0x04, 0x46, 0x04, 0x22, 0xb0, 0x1c, 0xf0, 0xf3, + 0x2d, 0xf3, 0x29, 0x1d, 0x08, 0x22, 0xb0, 0x1d, 0xf0, 0xf3, 0x28, 0xf3, + 0x04, 0xf5, 0x2e, 0x70, 0x05, 0xf1, 0x0c, 0x01, 0x08, 0x22, 0x06, 0x30, + 0xf0, 0xf3, 0x20, 0xf3, 0x04, 0xf5, 0x38, 0x70, 0x05, 0xf1, 0x34, 0x01, + 0x08, 0x22, 0x06, 0x30, 0xf0, 0xf3, 0x18, 0xf3, 0x04, 0xf5, 0x3a, 0x70, + 0x05, 0xf1, 0x3c, 0x01, 0x08, 0x22, 0x06, 0x30, 0xf0, 0xf3, 0x10, 0xf3, + 0x04, 0xf5, 0x30, 0x70, 0x05, 0xf1, 0x14, 0x01, 0x08, 0x22, 0x06, 0x30, + 0xf0, 0xf3, 0x08, 0xf3, 0x04, 0xf5, 0x32, 0x70, 0x05, 0xf1, 0x1c, 0x01, + 0x08, 0x22, 0x06, 0x30, 0xf0, 0xf3, 0x00, 0xf3, 0x04, 0xf5, 0x34, 0x70, + 0x05, 0xf1, 0x24, 0x01, 0x08, 0x22, 0x06, 0x30, 0xf0, 0xf3, 0xf8, 0xf2, + 0x04, 0xf5, 0x36, 0x70, 0x05, 0xf1, 0x2c, 0x01, 0x08, 0x22, 0x06, 0x30, + 0xf0, 0xf3, 0xf0, 0xf2, 0x04, 0xf5, 0x3c, 0x70, 0x05, 0xf1, 0x44, 0x01, + 0x08, 0x22, 0x06, 0x30, 0xf0, 0xf3, 0xe8, 0xf2, 0x04, 0xf5, 0x3e, 0x70, + 0x05, 0xf1, 0x4c, 0x01, 0x08, 0x22, 0x06, 0x30, 0xf0, 0xf3, 0xe0, 0xf2, + 0x04, 0xf5, 0x40, 0x70, 0x05, 0xf1, 0x54, 0x01, 0x08, 0x22, 0x06, 0x30, + 0xf0, 0xf3, 0xd8, 0xf2, 0x04, 0xf5, 0x42, 0x70, 0x06, 0x30, 0x05, 0xf1, + 0x5c, 0x01, 0x08, 0x22, 0xf0, 0xf3, 0xd0, 0xf2, 0x95, 0xf8, 0x64, 0x30, + 0x84, 0xf8, 0x16, 0x33, 0xd4, 0xf8, 0xb0, 0x30, 0xd3, 0xf8, 0x20, 0x51, + 0x15, 0xf0, 0x01, 0x05, 0x09, 0xd1, 0x20, 0x46, 0xff, 0xf7, 0x63, 0xfe, + 0x5d, 0xb1, 0xe3, 0x69, 0x18, 0x69, 0xbd, 0xe8, 0x70, 0x40, 0x3e, 0xf0, + 0xb5, 0x9e, 0xe3, 0x69, 0x01, 0x25, 0x18, 0x69, 0x3e, 0xf0, 0xc4, 0xde, + 0xef, 0xe7, 0x70, 0xbd, 0x80, 0xf8, 0xe0, 0x10, 0x70, 0x47, 0xc3, 0x69, + 0x99, 0x61, 0x70, 0x47, 0x80, 0xf8, 0xd5, 0x10, 0x41, 0x76, 0x70, 0x47, + 0x70, 0xb5, 0x04, 0x46, 0x0d, 0x46, 0xff, 0xf7, 0x01, 0xf9, 0x22, 0x46, + 0x21, 0x46, 0x00, 0x23, 0xe8, 0x18, 0x06, 0x7d, 0x16, 0xb1, 0x81, 0xf8, + 0x38, 0x66, 0x02, 0xe0, 0x00, 0x79, 0x81, 0xf8, 0x38, 0x06, 0x01, 0x33, + 0x01, 0x31, 0x08, 0x2b, 0xf2, 0xd1, 0x00, 0x23, 0xe9, 0x18, 0x91, 0xf8, + 0x44, 0x00, 0x10, 0xb1, 0x82, 0xf8, 0x48, 0x06, 0x02, 0xe0, 0x09, 0x79, + 0x82, 0xf8, 0x48, 0x16, 0x01, 0x33, 0x01, 0x32, 0x08, 0x2b, 0xf1, 0xd1, + 0xe3, 0x69, 0x18, 0x69, 0x3e, 0xf0, 0x90, 0xde, 0x20, 0x46, 0xff, 0xf7, + 0x20, 0xfe, 0xe3, 0x69, 0x18, 0x69, 0xbd, 0xe8, 0x70, 0x40, 0x3e, 0xf0, + 0x73, 0x9e, 0x80, 0xf8, 0xd9, 0x10, 0x70, 0x47, 0x70, 0x47, 0x00, 0x00, + 0xf0, 0xb5, 0xc1, 0x69, 0x85, 0xb0, 0x4b, 0x7f, 0x04, 0x46, 0x00, 0x2b, + 0x6a, 0xd0, 0x90, 0xf8, 0x1a, 0x36, 0x00, 0x2b, 0x4a, 0xd0, 0x08, 0x69, + 0x3f, 0x22, 0x28, 0x21, 0x3e, 0xf0, 0x40, 0xde, 0xe3, 0x69, 0x24, 0x21, + 0x18, 0x69, 0x10, 0x22, 0x3e, 0xf0, 0x3a, 0xde, 0xe3, 0x69, 0x94, 0xf8, + 0x29, 0x26, 0x18, 0x69, 0x26, 0x21, 0x12, 0x01, 0x3e, 0xf0, 0x32, 0xde, + 0xe3, 0x69, 0x32, 0x21, 0x18, 0x69, 0xb4, 0xf8, 0xfc, 0x26, 0x3e, 0xf0, + 0x2b, 0xde, 0x26, 0x46, 0x00, 0x25, 0x26, 0x4a, 0x02, 0xab, 0x10, 0x68, + 0x51, 0x68, 0x03, 0xc3, 0xe3, 0x69, 0x18, 0x69, 0x02, 0xab, 0x59, 0x5d, + 0x3e, 0xf0, 0xf6, 0xdd, 0xe3, 0x69, 0x96, 0xf9, 0x14, 0x25, 0x07, 0x46, + 0xb9, 0x1d, 0x18, 0x69, 0x92, 0xb2, 0x3e, 0xf0, 0x15, 0xde, 0x96, 0xf9, + 0x14, 0x25, 0xe3, 0x69, 0x02, 0xeb, 0xd2, 0x72, 0x52, 0x10, 0x52, 0x42, + 0x18, 0x69, 0x07, 0xf1, 0x0e, 0x01, 0x92, 0xb2, 0x01, 0x35, 0x3e, 0xf0, + 0x07, 0xde, 0x01, 0x36, 0x08, 0x2d, 0xda, 0xd1, 0xe3, 0x69, 0x03, 0x22, + 0x00, 0x92, 0x80, 0x22, 0x18, 0x69, 0x01, 0x21, 0x13, 0x46, 0x3e, 0xf0, + 0xc7, 0xdd, 0x1b, 0xe0, 0x03, 0x46, 0x04, 0x22, 0x93, 0xf9, 0x14, 0x05, + 0xc5, 0x1d, 0x48, 0xbf, 0x00, 0xf1, 0x0e, 0x05, 0x25, 0xf0, 0x07, 0x05, + 0x01, 0x32, 0x83, 0xf8, 0x14, 0x55, 0x01, 0x33, 0x0c, 0x2a, 0xf1, 0xd1, + 0x94, 0xf9, 0x14, 0x25, 0x08, 0x69, 0x07, 0x32, 0xd2, 0x10, 0x4e, 0x21, + 0x92, 0xb2, 0x05, 0xb0, 0xbd, 0xe8, 0xf0, 0x40, 0x3e, 0xf0, 0xde, 0x9d, + 0x05, 0xb0, 0xf0, 0xbd, 0xf6, 0xb7, 0x01, 0x00, 0x90, 0xf8, 0x1a, 0x06, + 0x70, 0x47, 0x00, 0xf5, 0x82, 0x53, 0x1b, 0x79, 0x3b, 0xb1, 0x80, 0xf8, + 0x1a, 0x16, 0x80, 0xf8, 0x1b, 0x16, 0x00, 0xf5, 0x90, 0x50, 0x80, 0xf8, + 0x3c, 0x10, 0x70, 0x47, 0x01, 0x23, 0x2d, 0xe9, 0xf0, 0x43, 0x0b, 0x73, + 0x0b, 0x68, 0x91, 0x46, 0x43, 0xf0, 0x08, 0x02, 0x0a, 0x60, 0xb0, 0xf9, + 0xfa, 0x26, 0x85, 0xb0, 0x01, 0x32, 0x04, 0xbf, 0x43, 0xf0, 0x09, 0x03, + 0x0b, 0x60, 0x90, 0xf8, 0x1a, 0x36, 0x05, 0x46, 0x0c, 0x46, 0x1b, 0xb1, + 0x0b, 0x68, 0x43, 0xf0, 0x02, 0x03, 0x0b, 0x60, 0x2f, 0x46, 0x26, 0x46, + 0x4f, 0xf0, 0x00, 0x08, 0x97, 0xf8, 0xb2, 0x32, 0x28, 0x46, 0xb3, 0x77, + 0x49, 0x46, 0x0d, 0xf1, 0x0f, 0x03, 0x0d, 0xf1, 0x0e, 0x02, 0xcd, 0xf8, + 0x00, 0x80, 0xff, 0xf7, 0x02, 0xfd, 0x9d, 0xf8, 0x0f, 0x30, 0x08, 0xf1, + 0x01, 0x08, 0x86, 0xf8, 0xb0, 0x31, 0x97, 0xf8, 0x75, 0x35, 0x01, 0x37, + 0x86, 0xf8, 0x79, 0x32, 0x01, 0x36, 0xb8, 0xf1, 0x14, 0x0f, 0xe3, 0xd1, + 0x95, 0xf8, 0x1a, 0x36, 0x33, 0xb3, 0xeb, 0x69, 0x1b, 0x7f, 0x1b, 0xb3, + 0x28, 0x46, 0xff, 0xf7, 0x38, 0xf9, 0x95, 0xf8, 0x18, 0x36, 0x28, 0x46, + 0xa3, 0x75, 0x95, 0xf8, 0x18, 0x36, 0xe3, 0x75, 0x95, 0xf8, 0x19, 0x36, + 0xa3, 0x76, 0x95, 0xf8, 0x19, 0x36, 0xe3, 0x76, 0x08, 0xf0, 0xe4, 0xff, + 0x23, 0x68, 0x10, 0xb1, 0x43, 0xf0, 0x03, 0x03, 0x01, 0xe0, 0x23, 0xf0, + 0x03, 0x03, 0x28, 0x46, 0x23, 0x60, 0x04, 0xf1, 0x0d, 0x01, 0x04, 0xf1, + 0x15, 0x02, 0x08, 0xf0, 0xdf, 0xff, 0x28, 0x46, 0xff, 0xf7, 0x1b, 0xf9, + 0x05, 0xb0, 0xbd, 0xe8, 0xf0, 0x83, 0x90, 0xf8, 0xd8, 0x30, 0x13, 0xb1, + 0x00, 0x23, 0x80, 0xf8, 0xd8, 0x30, 0x00, 0x20, 0x70, 0x47, 0xc3, 0x69, + 0x01, 0x20, 0x93, 0xf8, 0x81, 0x30, 0x0b, 0x70, 0x70, 0x47, 0x73, 0xb5, + 0xc3, 0x69, 0x4f, 0xf0, 0x03, 0x02, 0x83, 0xf8, 0x81, 0x10, 0xc3, 0x69, + 0x01, 0x29, 0x00, 0x92, 0x0d, 0x46, 0x4f, 0xf0, 0x01, 0x02, 0x4f, 0xf0, + 0x00, 0x01, 0x04, 0x46, 0x18, 0x69, 0x8c, 0xbf, 0x13, 0x46, 0x0b, 0x46, + 0x3e, 0xf0, 0x0c, 0xdd, 0xe3, 0x69, 0x5a, 0x7f, 0x00, 0x2a, 0x31, 0xd0, + 0xd4, 0xf8, 0xb0, 0x20, 0xd2, 0xf8, 0x20, 0x21, 0x02, 0xf0, 0x01, 0x02, + 0x82, 0xf0, 0x01, 0x06, 0x12, 0xb1, 0x18, 0x69, 0x3e, 0xf0, 0x62, 0xdd, + 0x02, 0x22, 0x01, 0x2d, 0x20, 0x46, 0x4f, 0xf4, 0x82, 0x61, 0x0d, 0xd9, + 0x13, 0x46, 0xff, 0xf7, 0x3f, 0xf9, 0xa5, 0xf1, 0x02, 0x0e, 0x01, 0x22, + 0xde, 0xf1, 0x00, 0x03, 0x20, 0x46, 0x4f, 0xf4, 0x82, 0x61, 0x43, 0xeb, + 0x0e, 0x03, 0x07, 0xe0, 0x00, 0x23, 0xff, 0xf7, 0x31, 0xf9, 0x20, 0x46, + 0x4f, 0xf4, 0x82, 0x61, 0x01, 0x22, 0x2b, 0x46, 0xff, 0xf7, 0x2a, 0xf9, + 0x36, 0xb9, 0xe3, 0x69, 0x18, 0x69, 0x02, 0xb0, 0xbd, 0xe8, 0x70, 0x40, + 0x3e, 0xf0, 0x28, 0x9d, 0x02, 0xb0, 0x70, 0xbd, 0x38, 0xb5, 0x90, 0xf8, + 0xe2, 0x30, 0x04, 0x46, 0x00, 0x2b, 0x69, 0xd1, 0x01, 0x22, 0x80, 0xf8, + 0xe2, 0x20, 0xd0, 0xf8, 0xb0, 0x20, 0xa0, 0xf8, 0xda, 0x10, 0xd2, 0xf8, + 0x20, 0x21, 0x00, 0xf5, 0x82, 0x52, 0x13, 0x60, 0xd0, 0xf8, 0xf8, 0x30, + 0x9a, 0x07, 0x06, 0xd4, 0x90, 0xf8, 0xa0, 0x2e, 0x1a, 0xb9, 0x43, 0xf0, + 0x20, 0x03, 0xc0, 0xf8, 0xf8, 0x30, 0x25, 0x6a, 0x00, 0x2d, 0x4f, 0xd0, + 0x01, 0x21, 0x20, 0x46, 0xff, 0xf7, 0x58, 0xf9, 0xb4, 0xf8, 0xda, 0x10, + 0xb4, 0xf8, 0xde, 0x30, 0x01, 0xf4, 0x40, 0x61, 0x99, 0x42, 0x03, 0xd0, + 0xe3, 0x69, 0x18, 0x69, 0x3e, 0xf0, 0x86, 0xdc, 0x01, 0x21, 0x04, 0xf5, + 0x96, 0x53, 0x83, 0xf8, 0x2d, 0x10, 0x20, 0x46, 0xff, 0xf7, 0x46, 0xfb, + 0x20, 0x46, 0xa8, 0x47, 0x00, 0x23, 0x84, 0xf8, 0xe1, 0x30, 0x20, 0x46, + 0xff, 0xf7, 0x78, 0xfe, 0xe3, 0x69, 0x20, 0x46, 0x93, 0xf8, 0x81, 0x10, + 0xff, 0xf7, 0x6d, 0xff, 0xe3, 0x69, 0x93, 0xf8, 0x80, 0x20, 0x01, 0x2a, + 0xb4, 0xf8, 0xda, 0x20, 0x02, 0xf4, 0x70, 0x42, 0x09, 0xd1, 0xb2, 0xf5, + 0x00, 0x5f, 0x01, 0xd1, 0x9a, 0x6f, 0x09, 0xe0, 0xda, 0x6f, 0x01, 0x2a, + 0x88, 0xbf, 0x00, 0x22, 0x04, 0xe0, 0xb2, 0xf5, 0x00, 0x5f, 0x0c, 0xbf, + 0x1a, 0x6f, 0x5a, 0x6f, 0xda, 0x66, 0xd9, 0x6e, 0x20, 0x46, 0x00, 0x22, + 0xfe, 0xf7, 0x3b, 0xff, 0x00, 0x23, 0x84, 0xf8, 0xe2, 0x30, 0xe3, 0x69, + 0x92, 0x21, 0x18, 0x69, 0x3e, 0xf0, 0x7e, 0xdc, 0x04, 0xf5, 0x92, 0x54, + 0x40, 0x00, 0x60, 0x80, 0x38, 0xbd, 0x10, 0xb5, 0x90, 0xf8, 0xe9, 0x30, + 0x00, 0x2b, 0x2a, 0xd0, 0xdb, 0x07, 0x19, 0xd5, 0xd0, 0xf8, 0xf0, 0x30, + 0x8b, 0x42, 0x0f, 0xd1, 0xc3, 0x69, 0xd3, 0xf8, 0x8c, 0x40, 0x1b, 0x19, + 0x83, 0xf8, 0x82, 0x20, 0xc3, 0x69, 0xd3, 0xf8, 0x8c, 0x40, 0x07, 0x2c, + 0x01, 0xd0, 0x01, 0x34, 0x00, 0xe0, 0x00, 0x24, 0xc3, 0xf8, 0x8c, 0x40, + 0x90, 0xf8, 0xe9, 0x30, 0x23, 0xf0, 0x01, 0x03, 0x80, 0xf8, 0xe9, 0x30, + 0x90, 0xf8, 0xe9, 0x30, 0x13, 0xf0, 0x02, 0x0f, 0x09, 0xd0, 0x23, 0xf0, + 0x02, 0x03, 0x80, 0xf8, 0xe9, 0x30, 0xc3, 0x69, 0x18, 0x69, 0xbd, 0xe8, + 0x10, 0x40, 0x3e, 0xf0, 0x8f, 0x9c, 0x10, 0xbd, 0x0b, 0x46, 0x90, 0xf8, + 0xe9, 0x10, 0xb1, 0xb9, 0x01, 0x2b, 0x02, 0xd0, 0x02, 0x2b, 0x04, 0xd1, + 0x01, 0xe0, 0xc0, 0xf8, 0xf0, 0x20, 0x80, 0xf8, 0xe9, 0x30, 0xc3, 0x69, + 0x1b, 0x6a, 0xc0, 0xf8, 0xec, 0x30, 0x00, 0xf5, 0x80, 0x53, 0x93, 0xf8, + 0x25, 0x30, 0x23, 0xb1, 0x11, 0x46, 0x6f, 0xf0, 0x5e, 0x02, 0xff, 0xf7, + 0xb4, 0xbf, 0x70, 0x47, 0x10, 0xb5, 0x04, 0x46, 0xff, 0xf7, 0x0e, 0xfb, + 0x02, 0x21, 0xc2, 0xb2, 0x20, 0x46, 0xbd, 0xe8, 0x10, 0x40, 0xff, 0xf7, + 0xd9, 0xbf, 0x08, 0xf0, 0x38, 0xbf, 0x00, 0x23, 0xc1, 0x69, 0x1a, 0x46, + 0xc8, 0x18, 0x90, 0xf9, 0x82, 0x00, 0x01, 0x33, 0x08, 0x2b, 0x02, 0x44, + 0xf8, 0xd1, 0x00, 0x2a, 0xb8, 0xbf, 0x07, 0x32, 0xd2, 0x08, 0x50, 0xb2, + 0x70, 0x47, 0x01, 0x21, 0x06, 0xf0, 0x6c, 0xbb, 0x70, 0x47, 0x13, 0xb5, + 0x04, 0x46, 0x08, 0xf0, 0xc8, 0xfe, 0xe2, 0x69, 0x13, 0x6a, 0x01, 0x33, + 0x13, 0x62, 0x94, 0xf8, 0xe8, 0x10, 0x00, 0x29, 0x72, 0xd0, 0x04, 0xf5, + 0x9c, 0x50, 0x41, 0x88, 0x19, 0xb1, 0xa4, 0xf8, 0x86, 0x18, 0xa4, 0xf8, + 0x88, 0x18, 0xc1, 0x88, 0x19, 0xb1, 0xa4, 0xf8, 0x80, 0x18, 0xa4, 0xf8, + 0x7c, 0x18, 0x04, 0xf5, 0x9c, 0x51, 0x89, 0x88, 0x19, 0xb1, 0xa4, 0xf8, + 0x7a, 0x18, 0xa4, 0xf8, 0x7e, 0x18, 0x12, 0x6e, 0xb3, 0xfb, 0xf2, 0xf1, + 0x02, 0xfb, 0x11, 0x33, 0x23, 0xb9, 0x20, 0x46, 0xb4, 0xf8, 0xda, 0x10, + 0xfe, 0xf7, 0xe0, 0xfe, 0xd4, 0xf8, 0xf8, 0x30, 0x13, 0xf0, 0x0e, 0x0f, + 0x05, 0xd1, 0x20, 0x46, 0x01, 0x21, 0x94, 0xf8, 0xda, 0x20, 0xff, 0xf7, + 0x8b, 0xff, 0x94, 0xf8, 0xe9, 0x30, 0x4b, 0xb1, 0xe3, 0x69, 0x1a, 0x6a, + 0xd4, 0xf8, 0xec, 0x30, 0xd3, 0x1a, 0x05, 0x2b, 0x02, 0xd9, 0x00, 0x23, + 0x84, 0xf8, 0xe9, 0x30, 0x04, 0xf5, 0x82, 0x53, 0x9a, 0x68, 0x2a, 0xb1, + 0xe3, 0x69, 0x19, 0x6a, 0x1b, 0x6e, 0x8a, 0x1a, 0x9a, 0x42, 0x0c, 0xd3, + 0xd4, 0xf8, 0xf8, 0x30, 0x98, 0x07, 0x08, 0xd4, 0x20, 0x46, 0xfe, 0xf7, + 0x1b, 0xfe, 0x20, 0xb1, 0xe2, 0x69, 0x04, 0xf5, 0x82, 0x53, 0x12, 0x6a, + 0x9a, 0x60, 0xd4, 0xf8, 0xf8, 0x30, 0x19, 0x07, 0x1e, 0xd1, 0xd4, 0xf8, + 0x8c, 0x30, 0x0b, 0xb1, 0x20, 0x46, 0x98, 0x47, 0xe3, 0x69, 0x18, 0x69, + 0x3e, 0xf0, 0x5c, 0xdb, 0x68, 0xb1, 0xe3, 0x69, 0x01, 0xa9, 0x18, 0x69, + 0x0d, 0xf1, 0x07, 0x02, 0x3e, 0xf0, 0x5e, 0xdb, 0x20, 0x46, 0x9d, 0xf8, + 0x07, 0x10, 0xbd, 0xf8, 0x04, 0x20, 0xfe, 0xf7, 0x56, 0xfe, 0xd4, 0xf8, + 0xf8, 0x30, 0x1a, 0x07, 0x02, 0xd1, 0x20, 0x46, 0x08, 0xf0, 0xa5, 0xfe, + 0x00, 0x20, 0x1c, 0xbd, 0x00, 0xf5, 0x98, 0x53, 0x1b, 0x7d, 0x0b, 0xb1, + 0x04, 0xf0, 0xda, 0xbf, 0x70, 0x47, 0x00, 0x23, 0xc1, 0x69, 0xc9, 0x18, + 0x01, 0x33, 0x08, 0x2b, 0x81, 0xf8, 0x82, 0x20, 0xf8, 0xd1, 0x00, 0x23, + 0xc2, 0x69, 0xa4, 0x21, 0xd2, 0x18, 0x01, 0x33, 0x08, 0x2b, 0x82, 0xf8, + 0x82, 0x10, 0xf7, 0xd1, 0xc3, 0x69, 0x00, 0x22, 0xc3, 0xf8, 0x8c, 0x20, + 0xda, 0x6e, 0x03, 0x2a, 0x07, 0xd1, 0x00, 0xf5, 0x80, 0x52, 0x91, 0x69, + 0xc9, 0x07, 0x02, 0xd5, 0x1b, 0x6a, 0x08, 0x33, 0x13, 0x61, 0x00, 0xf5, + 0x8a, 0x53, 0x30, 0x33, 0x00, 0x22, 0x4f, 0xf6, 0xa4, 0x71, 0x01, 0x32, + 0x23, 0xf8, 0x02, 0x1f, 0x10, 0x2a, 0x19, 0x84, 0xf7, 0xd1, 0x00, 0xf5, + 0x8e, 0x50, 0x00, 0x23, 0x80, 0xf8, 0x32, 0x30, 0x70, 0x47, 0x00, 0x00, + 0x49, 0xf6, 0x75, 0x33, 0x4b, 0x60, 0x00, 0x23, 0x0b, 0x60, 0x4f, 0xf4, + 0x34, 0x02, 0x98, 0x42, 0xac, 0xbf, 0x01, 0x23, 0x4f, 0xf0, 0xff, 0x33, + 0x02, 0xfb, 0x03, 0x02, 0x2d, 0xe9, 0xf0, 0x41, 0x4f, 0xf0, 0xb4, 0x74, + 0x92, 0xfb, 0xf4, 0xf0, 0x04, 0xfb, 0x10, 0x22, 0x21, 0x48, 0x00, 0xfb, + 0x03, 0x23, 0x00, 0x2b, 0x05, 0xdb, 0xda, 0x13, 0x01, 0x32, 0xb5, 0x2a, + 0x0d, 0xdd, 0x1b, 0x18, 0x08, 0xe0, 0x5a, 0x42, 0xd2, 0x13, 0x01, 0x32, + 0x52, 0x10, 0x52, 0x42, 0x5a, 0x32, 0x04, 0xda, 0x03, 0xf5, 0x34, 0x03, + 0x4f, 0xf0, 0xff, 0x34, 0x00, 0xe0, 0x01, 0x24, 0x00, 0x20, 0x02, 0x46, + 0x05, 0x46, 0x4e, 0x68, 0xab, 0x42, 0x0f, 0x68, 0xdf, 0xf8, 0x4c, 0xc0, + 0x46, 0xfa, 0x02, 0xf8, 0x09, 0xdd, 0xb8, 0x44, 0x17, 0x41, 0xf6, 0x1b, + 0x4e, 0x60, 0x5c, 0xf8, 0x00, 0x60, 0xc1, 0xf8, 0x00, 0x80, 0xad, 0x19, + 0x09, 0xe0, 0xc8, 0xeb, 0x07, 0x08, 0x17, 0x41, 0xf6, 0x19, 0x4e, 0x60, + 0x5c, 0xf8, 0x00, 0x60, 0xc1, 0xf8, 0x00, 0x80, 0xad, 0x1b, 0x01, 0x32, + 0x04, 0x30, 0x12, 0x2a, 0xdf, 0xd1, 0x4b, 0x68, 0x63, 0x43, 0x4b, 0x60, + 0x0b, 0x68, 0x5c, 0x43, 0x0c, 0x60, 0xbd, 0xe8, 0xf0, 0x81, 0x00, 0xbf, + 0x00, 0x00, 0x4c, 0xff, 0x94, 0xde, 0x01, 0x00, 0x38, 0xb5, 0x00, 0xf5, + 0x8e, 0x53, 0x05, 0x46, 0x99, 0x6b, 0x08, 0xe0, 0x0b, 0x68, 0x4f, 0xf4, + 0x3d, 0x72, 0xa3, 0x63, 0xeb, 0x69, 0x98, 0x68, 0xf4, 0xf3, 0xe2, 0xf5, + 0xa1, 0x6b, 0x05, 0xf5, 0x8e, 0x54, 0x00, 0x29, 0xf2, 0xd1, 0x05, 0xf5, + 0x92, 0x55, 0x10, 0x35, 0x4f, 0xf6, 0xce, 0x73, 0xa1, 0x63, 0x65, 0x63, + 0xa5, 0xf8, 0x94, 0x30, 0xc5, 0xf8, 0x90, 0x10, 0x38, 0xbd, 0x00, 0xf5, + 0x8e, 0x53, 0x10, 0xb5, 0x5c, 0x6b, 0x00, 0xf5, 0x96, 0x53, 0x99, 0x6a, + 0x19, 0xb1, 0xc3, 0x69, 0x18, 0x69, 0x3e, 0xf0, 0xf9, 0xda, 0x00, 0x23, + 0x63, 0x70, 0xa3, 0x70, 0x10, 0xbd, 0x08, 0xb5, 0x33, 0xb9, 0x00, 0xf5, + 0x90, 0x50, 0x90, 0xf8, 0x27, 0x10, 0x18, 0x46, 0x11, 0x60, 0x08, 0xbd, + 0x29, 0xb1, 0x01, 0x29, 0x03, 0xd0, 0x02, 0x29, 0x01, 0xd0, 0x03, 0x29, + 0x07, 0xd1, 0x00, 0xf5, 0x90, 0x53, 0x83, 0xf8, 0x27, 0x10, 0xff, 0xf7, + 0xda, 0xff, 0x00, 0x20, 0x08, 0xbd, 0x6f, 0xf0, 0x1c, 0x00, 0x08, 0xbd, + 0x80, 0xea, 0xe0, 0x73, 0xa3, 0xeb, 0xe0, 0x73, 0x00, 0x20, 0x01, 0xe0, + 0x01, 0x30, 0xc0, 0xb2, 0x53, 0xfa, 0x00, 0xf2, 0x00, 0x2a, 0xf9, 0xdc, + 0x70, 0x47, 0x10, 0xb5, 0x00, 0x23, 0x02, 0x46, 0x18, 0x46, 0x4f, 0xf0, + 0x80, 0x41, 0x19, 0x41, 0x0c, 0x18, 0x94, 0x42, 0x4f, 0xea, 0x50, 0x00, + 0x9c, 0xbf, 0xc4, 0xeb, 0x02, 0x02, 0x08, 0x43, 0x02, 0x33, 0x20, 0x2b, + 0xf1, 0xd1, 0x90, 0x42, 0x38, 0xbf, 0x01, 0x30, 0x10, 0xbd, 0xc3, 0x69, + 0x83, 0xf8, 0x90, 0x10, 0xc3, 0x69, 0x83, 0xf8, 0x91, 0x20, 0xc3, 0x69, + 0x83, 0xf8, 0x92, 0x10, 0xc3, 0x69, 0x83, 0xf8, 0x93, 0x20, 0x70, 0x47, + 0xc3, 0x69, 0x83, 0xf8, 0x92, 0x10, 0x70, 0x47, 0x00, 0xf5, 0x98, 0x53, + 0x93, 0xf9, 0x36, 0x00, 0x93, 0xf9, 0x35, 0x30, 0x98, 0x42, 0xb4, 0xbf, + 0x01, 0x20, 0x02, 0x20, 0x70, 0x47, 0x00, 0x00, 0x00, 0x48, 0x70, 0x47, + 0xce, 0xe4, 0x01, 0x00, 0x10, 0xb5, 0x0c, 0x46, 0x00, 0x21, 0x08, 0xf0, + 0x9c, 0xf8, 0x20, 0x70, 0x01, 0x20, 0x10, 0xbd, 0x70, 0x47, 0x08, 0x46, + 0x70, 0x47, 0x00, 0x20, 0x70, 0x47, 0x00, 0xf5, 0x8e, 0x50, 0x80, 0x6b, + 0x03, 0xe0, 0xc3, 0x88, 0x8b, 0x42, 0x02, 0xd0, 0x00, 0x68, 0x00, 0x28, + 0xf9, 0xd1, 0x70, 0x47, 0xb0, 0xf8, 0xda, 0x10, 0xff, 0xf7, 0xf1, 0xbf, + 0x70, 0xb5, 0x04, 0x46, 0x0d, 0x46, 0xff, 0xf7, 0xec, 0xff, 0x05, 0xf4, + 0x70, 0x43, 0xb3, 0xf5, 0x80, 0x5f, 0xe3, 0x69, 0xea, 0xb2, 0x08, 0xbf, + 0x42, 0xf4, 0x80, 0x72, 0x06, 0x46, 0xa0, 0x21, 0x18, 0x69, 0x3e, 0xf0, + 0x53, 0xda, 0xa3, 0x6a, 0x04, 0xf5, 0x8e, 0x51, 0x16, 0xb1, 0x06, 0xf5, + 0x17, 0x72, 0x02, 0xe0, 0x04, 0xf5, 0x92, 0x52, 0x10, 0x32, 0x4a, 0x63, + 0x13, 0xb1, 0x20, 0x46, 0x29, 0x46, 0x98, 0x47, 0x36, 0xb3, 0x04, 0xf5, + 0x8e, 0x53, 0x5a, 0x6b, 0x53, 0x78, 0x73, 0xb1, 0xe3, 0x69, 0x04, 0xf5, + 0x96, 0x56, 0xb1, 0x6a, 0x18, 0x69, 0x3e, 0xf0, 0x4b, 0xda, 0xe3, 0x69, + 0x00, 0x22, 0x18, 0x69, 0xb1, 0x6a, 0x13, 0x46, 0x3e, 0xf0, 0xc2, 0xd9, + 0x12, 0xe0, 0x04, 0xf5, 0x90, 0x53, 0x93, 0xf8, 0x27, 0x30, 0x6b, 0xb1, + 0x03, 0x2b, 0x0b, 0xd0, 0xe3, 0x69, 0xd2, 0xf8, 0x90, 0x20, 0x19, 0x6a, + 0x9b, 0x6e, 0x8a, 0x1a, 0x9a, 0x42, 0x03, 0xd3, 0x20, 0x46, 0x02, 0x21, + 0xff, 0xf7, 0xb2, 0xff, 0x20, 0x46, 0x29, 0x46, 0xbd, 0xe8, 0x70, 0x40, + 0xfe, 0xf7, 0xfa, 0xbc, 0xe0, 0x29, 0x10, 0xb5, 0x04, 0x46, 0x13, 0xdc, + 0x41, 0xf4, 0x30, 0x63, 0x9b, 0xb2, 0x0e, 0x29, 0xcc, 0xbf, 0x4f, 0xf4, + 0x80, 0x51, 0x4f, 0xf4, 0x00, 0x51, 0x19, 0x43, 0xff, 0xf7, 0xa0, 0xff, + 0x01, 0x23, 0x20, 0x46, 0x84, 0xf8, 0xd8, 0x30, 0x08, 0xf0, 0x0b, 0xff, + 0x00, 0x20, 0x10, 0xbd, 0x6f, 0xf0, 0x12, 0x00, 0x10, 0xbd, 0x70, 0xb5, + 0x0d, 0x46, 0x04, 0x46, 0xd0, 0xf8, 0xb0, 0x60, 0xff, 0xf7, 0x91, 0xfc, + 0x1d, 0xbb, 0x04, 0xf5, 0x96, 0x56, 0x0a, 0x21, 0x20, 0x46, 0xf2, 0x8e, + 0xfe, 0xf7, 0x1e, 0xfc, 0x20, 0x46, 0x40, 0xf2, 0x4b, 0x41, 0x2a, 0x46, + 0xfe, 0xf7, 0x18, 0xfc, 0x20, 0x46, 0x29, 0x46, 0x06, 0xf0, 0x4a, 0xf8, + 0xe3, 0x69, 0xf5, 0x86, 0x1b, 0x6d, 0x13, 0xf0, 0x02, 0x03, 0x51, 0xd0, + 0x32, 0x8f, 0xd4, 0xf8, 0xb0, 0x30, 0x4f, 0xf4, 0x7a, 0x70, 0xa3, 0xf8, + 0x9c, 0x24, 0xb2, 0x8f, 0xa3, 0xf8, 0x9e, 0x24, 0xf4, 0xf3, 0xe4, 0xf1, + 0x45, 0xe0, 0xe3, 0x69, 0x1b, 0x6d, 0x9b, 0x07, 0x1e, 0xd5, 0xd4, 0xf8, + 0xb0, 0x20, 0x04, 0xf5, 0x96, 0x53, 0xb2, 0xf8, 0x9c, 0x14, 0xb2, 0xf8, + 0x9e, 0x24, 0x89, 0xb2, 0x92, 0xb2, 0x99, 0x63, 0xda, 0x63, 0xb6, 0xf8, + 0x9c, 0x34, 0x4f, 0xf4, 0x7a, 0x70, 0x23, 0xf4, 0x00, 0x73, 0x1b, 0x04, + 0x1b, 0x0c, 0xa6, 0xf8, 0x9c, 0x34, 0xb6, 0xf8, 0x9e, 0x34, 0x9b, 0xb2, + 0x43, 0xf4, 0x00, 0x73, 0xa6, 0xf8, 0x9e, 0x34, 0xf4, 0xf3, 0xc0, 0xf1, + 0x29, 0x46, 0x20, 0x46, 0x01, 0x22, 0xff, 0xf7, 0x91, 0xff, 0x05, 0x46, + 0xd8, 0xb9, 0x04, 0xf5, 0x96, 0x56, 0xf3, 0x8e, 0x5b, 0xb9, 0x0a, 0x21, + 0x20, 0x46, 0xfe, 0xf7, 0xc4, 0xfb, 0x40, 0xf2, 0x4b, 0x41, 0xf0, 0x86, + 0x4f, 0xf6, 0xff, 0x72, 0x20, 0x46, 0xfe, 0xf7, 0xc7, 0xfb, 0x20, 0x46, + 0x01, 0x21, 0x05, 0xf0, 0xf9, 0xff, 0x20, 0x46, 0x0a, 0x21, 0x4f, 0xf4, + 0x94, 0x72, 0xfe, 0xf7, 0x95, 0xfd, 0x00, 0xe0, 0x1d, 0x46, 0x28, 0x46, + 0x70, 0xbd, 0x38, 0xb5, 0x05, 0x46, 0x0c, 0x46, 0xff, 0xf7, 0x1f, 0xfc, + 0x28, 0x46, 0x3c, 0xb9, 0x06, 0xf0, 0xd0, 0xfd, 0x28, 0x46, 0x4f, 0xf4, + 0x40, 0x41, 0x04, 0xf0, 0x9b, 0xfe, 0x0f, 0xe0, 0x21, 0x46, 0x00, 0x22, + 0xff, 0xf7, 0x5e, 0xff, 0x04, 0x46, 0x48, 0xb9, 0x28, 0x46, 0x21, 0x46, + 0x70, 0x22, 0x23, 0x46, 0x06, 0xf0, 0x1a, 0xfd, 0x28, 0x46, 0x5e, 0x21, + 0x05, 0xf0, 0x48, 0xfa, 0x20, 0x46, 0x38, 0xbd, 0xf8, 0xb5, 0x05, 0x46, + 0x0c, 0x46, 0xff, 0xf7, 0xfe, 0xfb, 0x28, 0x46, 0x21, 0x46, 0x34, 0xb9, + 0x05, 0xf5, 0x96, 0x55, 0x06, 0xf0, 0x64, 0xf8, 0x26, 0x46, 0xac, 0x86, + 0x11, 0xe0, 0x01, 0x22, 0xff, 0xf7, 0x3e, 0xff, 0x06, 0x46, 0x60, 0xb9, + 0x05, 0xf5, 0x96, 0x57, 0xbb, 0x8e, 0x23, 0xb9, 0x28, 0x46, 0x0a, 0x21, + 0xfe, 0xf7, 0x71, 0xfb, 0xb8, 0x86, 0x28, 0x46, 0x21, 0x46, 0x06, 0xf0, + 0x4f, 0xf8, 0x30, 0x46, 0xf8, 0xbd, 0xf7, 0xb5, 0x08, 0x9e, 0x04, 0x46, + 0x0d, 0x46, 0x1f, 0x46, 0x3b, 0xb1, 0x03, 0x2a, 0x05, 0xd9, 0x68, 0x46, + 0x19, 0x46, 0x04, 0x22, 0xef, 0xf3, 0x5a, 0xf5, 0x01, 0xe0, 0x00, 0x23, + 0x00, 0x93, 0xa8, 0x2d, 0x00, 0xf0, 0x05, 0x81, 0x17, 0xdc, 0x5c, 0x2d, + 0x00, 0xf0, 0xb9, 0x80, 0x09, 0xdc, 0x3c, 0x2d, 0x00, 0xf0, 0xaa, 0x80, + 0x4a, 0x2d, 0x00, 0xf0, 0x9c, 0x80, 0x1b, 0x2d, 0x40, 0xf0, 0xf4, 0x80, + 0x27, 0xe0, 0x5e, 0x2d, 0x2e, 0xd0, 0xc0, 0xf2, 0xb3, 0x80, 0x5f, 0x2d, + 0x3b, 0xd0, 0x87, 0x2d, 0x40, 0xf0, 0xea, 0x80, 0x18, 0xe0, 0xc3, 0x2d, + 0x76, 0xd0, 0x06, 0xdc, 0xaa, 0x2d, 0x46, 0xd0, 0x7e, 0xdb, 0xc2, 0x2d, + 0x40, 0xf0, 0xe0, 0x80, 0xe1, 0xe0, 0xd4, 0x2d, 0x00, 0xf0, 0xb7, 0x80, + 0x03, 0xdc, 0xd3, 0x2d, 0x40, 0xf0, 0xd8, 0x80, 0xa4, 0xe0, 0xa5, 0xf5, + 0x9a, 0x75, 0x03, 0x3d, 0x01, 0x2d, 0x00, 0xf2, 0xd1, 0x80, 0xe3, 0xe0, + 0x20, 0x46, 0xff, 0xf7, 0xbe, 0xfc, 0x38, 0x60, 0xde, 0xe0, 0xe3, 0x69, + 0x1d, 0x7f, 0x00, 0x2d, 0x40, 0xf0, 0xd4, 0x80, 0x20, 0x46, 0xfe, 0xf7, + 0x2a, 0xfb, 0xd6, 0xe0, 0x01, 0x23, 0x33, 0x70, 0xe3, 0x69, 0x5b, 0x7f, + 0x00, 0x2b, 0x00, 0xf0, 0xc1, 0x80, 0x20, 0x46, 0xfe, 0xf7, 0x97, 0xfc, + 0x20, 0x46, 0xbd, 0xf8, 0x00, 0x10, 0xfe, 0xf7, 0x08, 0xfb, 0x38, 0x60, + 0x0f, 0xe0, 0x01, 0x23, 0x33, 0x70, 0xe3, 0x69, 0x5b, 0x7f, 0x00, 0x2b, + 0x00, 0xf0, 0xb0, 0x80, 0x20, 0x46, 0xfe, 0xf7, 0x86, 0xfc, 0x00, 0x9a, + 0x20, 0x46, 0x91, 0xb2, 0x12, 0x0c, 0xfe, 0xf7, 0x01, 0xfb, 0x20, 0x46, + 0xfe, 0xf7, 0x81, 0xfc, 0xb0, 0xe0, 0xe3, 0x69, 0x5a, 0x7f, 0x00, 0x2a, + 0x00, 0xf0, 0x9e, 0x80, 0x18, 0x69, 0x3e, 0xf0, 0xf5, 0xd8, 0x20, 0x46, + 0xfe, 0xf7, 0x71, 0xfc, 0x00, 0x23, 0x3b, 0x60, 0xd4, 0xf8, 0xbc, 0x20, + 0x08, 0x2a, 0x13, 0xd1, 0x0d, 0xf1, 0x07, 0x02, 0x20, 0x46, 0x0d, 0xf1, + 0x06, 0x01, 0x8d, 0xf8, 0x06, 0x30, 0x8d, 0xf8, 0x07, 0x30, 0x08, 0xf0, + 0x25, 0xfb, 0x9d, 0xf9, 0x06, 0x20, 0x9d, 0xf9, 0x07, 0x30, 0x92, 0xb2, + 0x9b, 0xb2, 0x43, 0xea, 0x02, 0x23, 0x3b, 0x60, 0x20, 0x46, 0xfe, 0xf7, + 0x58, 0xfc, 0xe3, 0x69, 0x18, 0x69, 0x3e, 0xf0, 0xbd, 0xd8, 0x83, 0xe0, + 0xe3, 0x69, 0x1b, 0x7f, 0x00, 0x2b, 0x74, 0xd0, 0x3b, 0x88, 0x03, 0x2b, + 0x34, 0xbf, 0x6f, 0xf0, 0x0c, 0x05, 0x6f, 0xf0, 0x01, 0x05, 0x78, 0xe0, + 0xe3, 0x69, 0x1b, 0x7f, 0x00, 0x2b, 0x14, 0xbf, 0x6f, 0xf0, 0x0c, 0x05, + 0x6f, 0xf0, 0x03, 0x05, 0x6f, 0xe0, 0xe3, 0x69, 0x1b, 0x7f, 0x00, 0x2b, + 0x64, 0xd1, 0x23, 0x6b, 0x00, 0x2b, 0x5f, 0xd0, 0x20, 0x46, 0x00, 0x99, + 0x98, 0x47, 0x1b, 0xe0, 0xe3, 0x69, 0x1b, 0x7f, 0x00, 0x2b, 0x59, 0xd1, + 0x20, 0x46, 0x00, 0x99, 0x7a, 0x68, 0xbb, 0x68, 0xff, 0xf7, 0x79, 0xfe, + 0x10, 0xe0, 0xe3, 0x69, 0x1b, 0x7f, 0x00, 0x2b, 0x4e, 0xd1, 0x20, 0x46, + 0x00, 0x99, 0xff, 0xf7, 0xe4, 0xfe, 0x07, 0xe0, 0xe3, 0x69, 0x1b, 0x7f, + 0x00, 0x2b, 0x45, 0xd1, 0x20, 0x46, 0x00, 0x99, 0xff, 0xf7, 0xfc, 0xfe, + 0x05, 0x46, 0x46, 0xe0, 0xe3, 0x69, 0x04, 0xf5, 0x80, 0x54, 0xda, 0x6e, + 0x3a, 0x60, 0xa5, 0x69, 0x15, 0xf0, 0x01, 0x05, 0x3d, 0xd0, 0x42, 0xf0, + 0x80, 0x02, 0x3a, 0x60, 0x38, 0xe0, 0x00, 0x9b, 0x04, 0x2b, 0x32, 0xd8, + 0xe2, 0x69, 0xd1, 0x6e, 0x99, 0x42, 0x31, 0xd0, 0x15, 0x7f, 0xd3, 0x66, + 0x00, 0x2d, 0x2e, 0xd0, 0x10, 0x69, 0x3e, 0xf0, 0x77, 0xd8, 0x00, 0x9b, + 0x23, 0xb1, 0x20, 0x46, 0x00, 0x21, 0x01, 0x22, 0xfe, 0xf7, 0xd5, 0xfa, + 0xe3, 0x69, 0x01, 0x22, 0xd9, 0x6e, 0x20, 0x46, 0xfe, 0xf7, 0xcf, 0xfa, + 0xe3, 0x69, 0x00, 0x28, 0x18, 0x69, 0x0c, 0xbf, 0x6f, 0xf0, 0x02, 0x05, + 0x00, 0x25, 0x3e, 0xf0, 0x4d, 0xd8, 0x14, 0xe0, 0x6f, 0xf0, 0x16, 0x05, + 0x11, 0xe0, 0x6f, 0xf0, 0x0c, 0x05, 0x0e, 0xe0, 0x6f, 0xf0, 0x0a, 0x05, + 0x0b, 0xe0, 0x6f, 0xf0, 0x03, 0x05, 0x08, 0xe0, 0x1d, 0x46, 0x06, 0xe0, + 0x6f, 0xf0, 0x04, 0x05, 0x03, 0xe0, 0x6f, 0xf0, 0x1c, 0x05, 0x00, 0xe0, + 0x00, 0x25, 0x28, 0x46, 0xfe, 0xbd, 0xc3, 0x69, 0x9b, 0x69, 0x9b, 0x00, + 0x07, 0xd5, 0xd0, 0xf8, 0xb0, 0x30, 0x03, 0x22, 0xa3, 0xf8, 0xb4, 0x26, + 0xff, 0x22, 0xa3, 0xf8, 0xb8, 0x26, 0x70, 0x47, 0x2d, 0xe9, 0xf0, 0x41, + 0x98, 0x46, 0x88, 0xb0, 0x00, 0x23, 0x07, 0x93, 0x0e, 0x9b, 0x04, 0x46, + 0x03, 0x2b, 0x0d, 0x46, 0x0f, 0x9e, 0x11, 0x9f, 0x04, 0xd9, 0x07, 0xa8, + 0x41, 0x46, 0x04, 0x22, 0xef, 0xf3, 0x1c, 0xf4, 0x07, 0x99, 0x40, 0xf2, + 0x85, 0x20, 0x0b, 0x1c, 0x18, 0xbf, 0x01, 0x23, 0x85, 0x42, 0x1a, 0x46, + 0x00, 0xf0, 0x18, 0x81, 0x35, 0xd8, 0x40, 0xf2, 0x5b, 0x20, 0x85, 0x42, + 0x00, 0xf0, 0x82, 0x80, 0x11, 0xd8, 0x53, 0x2d, 0x09, 0xd8, 0x52, 0x2d, + 0x80, 0xf0, 0x46, 0x81, 0x50, 0x2d, 0x00, 0xf0, 0x43, 0x81, 0x51, 0x2d, + 0x40, 0xf0, 0x42, 0x81, 0x83, 0xe0, 0x40, 0xf2, 0x5a, 0x23, 0x9d, 0x42, + 0x40, 0xf0, 0x3c, 0x81, 0x6b, 0xe0, 0x40, 0xf2, 0x7b, 0x23, 0x9d, 0x42, + 0x00, 0xf0, 0xb9, 0x80, 0x09, 0xd8, 0x40, 0xf2, 0x6a, 0x23, 0x9d, 0x42, + 0x56, 0xd0, 0x40, 0xf2, 0x7a, 0x23, 0x9d, 0x42, 0x40, 0xf0, 0x2c, 0x81, + 0x76, 0xe0, 0xb5, 0xf5, 0x20, 0x7f, 0x00, 0xf0, 0xe0, 0x80, 0xb5, 0xf5, + 0x21, 0x7f, 0x00, 0xf0, 0xec, 0x80, 0x40, 0xf2, 0x7e, 0x23, 0x9d, 0x42, + 0x40, 0xf0, 0x1e, 0x81, 0xd0, 0xe0, 0x40, 0xf2, 0xd6, 0x23, 0x9d, 0x42, + 0x00, 0xf0, 0x16, 0x81, 0x1e, 0xd8, 0x40, 0xf2, 0x93, 0x23, 0x9d, 0x42, + 0x4d, 0xd0, 0x0a, 0xd8, 0x40, 0xf2, 0x86, 0x23, 0x9d, 0x42, 0x00, 0xf0, + 0xdf, 0x80, 0x40, 0xf2, 0x91, 0x23, 0x9d, 0x42, 0x40, 0xf0, 0x08, 0x81, + 0x3d, 0xe0, 0xb5, 0xf5, 0x27, 0x7f, 0x00, 0xf0, 0xdb, 0x80, 0x40, 0xf2, + 0x9d, 0x23, 0x9d, 0x42, 0x00, 0xf0, 0xda, 0x80, 0x40, 0xf2, 0x95, 0x23, + 0x9d, 0x42, 0x40, 0xf0, 0xf9, 0x80, 0x36, 0xe0, 0x40, 0xf2, 0xdd, 0x23, + 0x9d, 0x42, 0x00, 0xf0, 0xed, 0x80, 0x09, 0xd8, 0x40, 0xf2, 0xda, 0x23, + 0x9d, 0x42, 0x00, 0xf0, 0xcf, 0x80, 0xb5, 0xf5, 0x37, 0x7f, 0x40, 0xf0, + 0xe9, 0x80, 0xd6, 0xe0, 0xb5, 0xf5, 0x3d, 0x7f, 0x07, 0xd0, 0xc0, 0xf0, + 0xe3, 0x80, 0xa5, 0xf5, 0x3e, 0x73, 0x06, 0x3b, 0x01, 0x2b, 0x00, 0xf2, + 0xdd, 0x80, 0x6f, 0xf0, 0x16, 0x05, 0xed, 0xe0, 0x20, 0x46, 0xfe, 0xf7, + 0x22, 0xfb, 0x20, 0x46, 0x31, 0x46, 0xfe, 0xf7, 0xbe, 0xfa, 0x20, 0x46, + 0xfe, 0xf7, 0x1f, 0xfb, 0xcc, 0xe0, 0x94, 0xf8, 0xe8, 0x30, 0xa1, 0xe0, + 0x84, 0xf8, 0xe8, 0x30, 0xc6, 0xe0, 0x04, 0xf5, 0x9c, 0x54, 0x61, 0x80, + 0xc2, 0xe0, 0x04, 0xf5, 0x9c, 0x54, 0xa1, 0x80, 0xbe, 0xe0, 0x04, 0xf5, + 0x9c, 0x54, 0xe1, 0x80, 0xba, 0xe0, 0x01, 0x23, 0x0e, 0x93, 0x20, 0x46, + 0x33, 0x46, 0x08, 0xb0, 0xbd, 0xe8, 0xf0, 0x41, 0xfe, 0xf7, 0xf0, 0xb9, + 0xe3, 0x69, 0x1a, 0x7f, 0x00, 0x2a, 0x00, 0xf0, 0xbe, 0x80, 0xd4, 0xf8, + 0xb0, 0x20, 0xd2, 0xf8, 0x20, 0x21, 0x02, 0xf0, 0x01, 0x02, 0x82, 0xf0, + 0x01, 0x07, 0x12, 0xb1, 0x18, 0x69, 0x3d, 0xf0, 0x6f, 0xdf, 0x20, 0x46, + 0xff, 0xf7, 0x23, 0xff, 0x20, 0x46, 0xfe, 0xf7, 0xe8, 0xfa, 0x04, 0xf5, + 0x90, 0x50, 0x45, 0x7a, 0x81, 0x79, 0xc2, 0x79, 0x03, 0x7a, 0x00, 0x95, + 0x85, 0x7a, 0x01, 0x95, 0xc5, 0x7a, 0x02, 0x95, 0x90, 0xf8, 0x21, 0x00, + 0x00, 0x25, 0x03, 0x90, 0x20, 0x46, 0x04, 0x95, 0xfe, 0xf7, 0xdf, 0xf9, + 0x30, 0x60, 0x20, 0x46, 0xfe, 0xf7, 0xd5, 0xfa, 0x00, 0x2f, 0x40, 0xf0, + 0x97, 0x80, 0xe3, 0x69, 0x3d, 0x46, 0x18, 0x69, 0x3d, 0xf0, 0x36, 0xdf, + 0x90, 0xe0, 0x0a, 0x16, 0x02, 0xf0, 0x0f, 0x02, 0x01, 0x2a, 0x00, 0xf2, + 0x89, 0x80, 0x0d, 0x15, 0x05, 0xf0, 0x03, 0x05, 0x01, 0x2d, 0x00, 0xf2, + 0x83, 0x80, 0x88, 0x15, 0x00, 0xf0, 0x03, 0x00, 0x03, 0x28, 0x7d, 0xd0, + 0x0e, 0x14, 0x06, 0xf0, 0x0f, 0x06, 0x01, 0x2e, 0x78, 0xd8, 0x0f, 0x12, + 0xff, 0xb2, 0xa7, 0xf1, 0x0a, 0x03, 0xdb, 0xb2, 0x05, 0x2b, 0x71, 0xd8, + 0xcb, 0xb2, 0x01, 0x2b, 0x01, 0xd9, 0x03, 0x2b, 0x6c, 0xd1, 0x04, 0xf5, + 0x90, 0x54, 0x0e, 0x2f, 0x28, 0xbf, 0x0e, 0x27, 0x09, 0x0f, 0xa7, 0x71, + 0xe3, 0x71, 0x26, 0x72, 0x65, 0x72, 0xa0, 0x72, 0xe2, 0x72, 0x84, 0xf8, + 0x21, 0x10, 0x49, 0xe0, 0x08, 0xa9, 0x01, 0x23, 0x41, 0xf8, 0x04, 0x3d, + 0x07, 0xe0, 0xb4, 0xf8, 0xda, 0x10, 0x20, 0x46, 0xfe, 0xf7, 0xce, 0xfd, + 0x08, 0xa9, 0x41, 0xf8, 0x04, 0x0d, 0x30, 0x46, 0x3a, 0x46, 0x32, 0xe0, + 0x04, 0xf5, 0x80, 0x54, 0x84, 0xf8, 0x3b, 0x10, 0x34, 0xe0, 0x04, 0xf5, + 0x80, 0x54, 0x94, 0xf8, 0x3b, 0x30, 0x08, 0xa9, 0x41, 0xf8, 0x04, 0x3d, + 0x30, 0x46, 0x23, 0xe0, 0xd4, 0xf8, 0xf8, 0x30, 0xc3, 0xf3, 0x00, 0x13, + 0x33, 0x60, 0x25, 0xe0, 0x20, 0x46, 0x32, 0x46, 0x00, 0x23, 0x02, 0xe0, + 0x20, 0x46, 0x32, 0x46, 0x01, 0x23, 0xff, 0xf7, 0xd8, 0xfb, 0x1b, 0xe0, + 0x20, 0x46, 0x01, 0x21, 0x08, 0xf0, 0x6b, 0xf9, 0x00, 0x25, 0x08, 0xa9, + 0x41, 0xf8, 0x04, 0x5d, 0x30, 0x46, 0x04, 0x22, 0xef, 0xf3, 0xd0, 0xf2, + 0x24, 0xe0, 0x20, 0x46, 0x00, 0x21, 0x07, 0xaa, 0x08, 0xf0, 0x7b, 0xfa, + 0x30, 0x46, 0x07, 0xa9, 0x04, 0x22, 0xef, 0xf3, 0xc5, 0xf2, 0x03, 0xe0, + 0x20, 0x46, 0x00, 0x22, 0x08, 0xf0, 0x71, 0xfa, 0x00, 0x25, 0x13, 0xe0, + 0x01, 0x91, 0x02, 0x92, 0x29, 0x46, 0x20, 0x46, 0x42, 0x46, 0x33, 0x46, + 0x00, 0x97, 0xfe, 0xf7, 0xc9, 0xf9, 0x10, 0xf1, 0x17, 0x0f, 0x0c, 0xbf, + 0x05, 0x46, 0x00, 0x25, 0x04, 0xe0, 0x6f, 0xf0, 0x03, 0x05, 0x01, 0xe0, + 0x6f, 0xf0, 0x1c, 0x05, 0x28, 0x46, 0x08, 0xb0, 0xbd, 0xe8, 0xf0, 0x81, + 0xd0, 0xf8, 0xf8, 0x30, 0x13, 0xf0, 0x06, 0x0f, 0x0c, 0xbf, 0x00, 0x20, + 0x01, 0x20, 0x70, 0x47, 0xf8, 0xb5, 0x0d, 0x46, 0xb0, 0xf8, 0xda, 0x10, + 0x04, 0x46, 0x16, 0x46, 0x1f, 0x46, 0xfe, 0xf7, 0x63, 0xfd, 0x40, 0xb9, + 0xb4, 0xf9, 0xfc, 0x30, 0x33, 0x60, 0xb4, 0xf9, 0xfe, 0x30, 0x3b, 0x60, + 0xb4, 0xf9, 0x00, 0x31, 0x2b, 0x60, 0xf8, 0xbd, 0xd0, 0xf8, 0xa8, 0x00, + 0x70, 0x47, 0x00, 0x00, 0x2d, 0xe9, 0xf0, 0x41, 0xc3, 0x69, 0x05, 0x46, + 0x5b, 0x69, 0x0c, 0x46, 0x0a, 0x2b, 0xcf, 0x88, 0x8e, 0x88, 0x06, 0xd9, + 0x48, 0x8a, 0x10, 0xf4, 0x80, 0x70, 0x02, 0xd1, 0x01, 0x23, 0xcb, 0x77, + 0x31, 0xe0, 0x28, 0x46, 0xff, 0xf7, 0xe8, 0xff, 0xb4, 0xf8, 0x08, 0x80, + 0x1b, 0x4b, 0xff, 0xb2, 0x4f, 0xea, 0x98, 0x28, 0x7f, 0x2f, 0x13, 0xf9, + 0x08, 0x30, 0xc8, 0xbf, 0xa7, 0xf5, 0x80, 0x77, 0xff, 0x18, 0x16, 0xf4, + 0x00, 0x6f, 0x05, 0xf5, 0x9a, 0x53, 0x14, 0xbf, 0x93, 0xf9, 0x1b, 0x30, + 0x93, 0xf9, 0x1a, 0x30, 0x90, 0xf9, 0x5f, 0x10, 0xff, 0x18, 0xe2, 0x8a, + 0x79, 0x18, 0x7f, 0x29, 0x02, 0xf4, 0xff, 0x62, 0xc8, 0xbf, 0xa1, 0xf5, + 0x80, 0x71, 0xd2, 0x10, 0x42, 0xf4, 0x30, 0x63, 0x0e, 0x2a, 0xcc, 0xbf, + 0x4f, 0xf4, 0x80, 0x52, 0x4f, 0xf4, 0x00, 0x52, 0x28, 0x46, 0x49, 0xb2, + 0x1a, 0x43, 0xff, 0xf7, 0xa6, 0xfb, 0x01, 0x46, 0xb2, 0x0b, 0x20, 0x77, + 0x49, 0xb2, 0x28, 0x46, 0x02, 0xf0, 0x01, 0x02, 0xbd, 0xe8, 0xf0, 0x41, + 0x07, 0xf0, 0xb4, 0xbc, 0x0e, 0x02, 0x02, 0x00, 0xc3, 0x69, 0x98, 0x6e, + 0x70, 0x47, 0xc3, 0x69, 0x99, 0x66, 0x70, 0x47, 0x10, 0xb5, 0x0c, 0x89, + 0x03, 0x99, 0x02, 0x9b, 0x02, 0x91, 0x04, 0x99, 0x03, 0x91, 0x05, 0x99, + 0x04, 0x91, 0x06, 0x99, 0x05, 0x91, 0x00, 0x69, 0x11, 0x46, 0x22, 0x46, + 0xbd, 0xe8, 0x10, 0x40, 0x2a, 0xf0, 0x38, 0x9b, 0xb0, 0xfb, 0xf1, 0xf3, + 0x10, 0xb5, 0x01, 0xf0, 0x01, 0x04, 0x01, 0xfb, 0x13, 0x00, 0x04, 0xeb, + 0x51, 0x01, 0x08, 0xe0, 0x5b, 0x00, 0x88, 0x42, 0x04, 0xd3, 0x40, 0x1a, + 0x01, 0x33, 0x04, 0xeb, 0x40, 0x00, 0x00, 0xe0, 0x40, 0x00, 0x01, 0x3a, + 0xd2, 0xb2, 0xff, 0x2a, 0xf2, 0xd1, 0x88, 0x42, 0x28, 0xbf, 0x01, 0x33, + 0x18, 0x46, 0x10, 0xbd, 0xd0, 0xf8, 0xa8, 0x30, 0x01, 0x22, 0x5a, 0x86, + 0x70, 0x47, 0xb0, 0xf8, 0xda, 0x10, 0xd0, 0xf8, 0xa8, 0x20, 0xcb, 0xb2, + 0x01, 0xf4, 0x70, 0x41, 0xb1, 0xf5, 0x00, 0x5f, 0x03, 0xd1, 0xd3, 0x18, + 0x93, 0xf8, 0xe7, 0x34, 0x87, 0xe0, 0x70, 0x2b, 0x5d, 0xd0, 0x1c, 0xd8, + 0x38, 0x2b, 0x48, 0xd0, 0x0c, 0xd8, 0x2c, 0x2b, 0x3c, 0xd0, 0x04, 0xd8, + 0x24, 0x2b, 0x33, 0xd0, 0x28, 0x2b, 0x79, 0xd1, 0x33, 0xe0, 0x30, 0x2b, + 0x37, 0xd0, 0x34, 0x2b, 0x74, 0xd1, 0x37, 0xe0, 0x64, 0x2b, 0x41, 0xd0, + 0x04, 0xd8, 0x3c, 0x2b, 0x38, 0xd0, 0x40, 0x2b, 0x6c, 0xd1, 0x38, 0xe0, + 0x68, 0x2b, 0x3c, 0xd0, 0x6c, 0x2b, 0x67, 0xd1, 0x3c, 0xe0, 0x88, 0x2b, + 0x4f, 0xd0, 0x0c, 0xd8, 0x7c, 0x2b, 0x43, 0xd0, 0x04, 0xd8, 0x74, 0x2b, + 0x3a, 0xd0, 0x78, 0x2b, 0x5c, 0xd1, 0x3a, 0xe0, 0x80, 0x2b, 0x3e, 0xd0, + 0x84, 0x2b, 0x57, 0xd1, 0x3e, 0xe0, 0x99, 0x2b, 0x48, 0xd0, 0x04, 0xd8, + 0x8c, 0x2b, 0x3f, 0xd0, 0x95, 0x2b, 0x4f, 0xd1, 0x3f, 0xe0, 0xa1, 0x2b, + 0x46, 0xd0, 0xa5, 0x2b, 0x47, 0xd0, 0x9d, 0x2b, 0x48, 0xd1, 0x3e, 0xe0, + 0x92, 0xf8, 0xf6, 0x34, 0x45, 0xe0, 0x92, 0xf8, 0xf7, 0x34, 0x42, 0xe0, + 0x92, 0xf8, 0xf8, 0x34, 0x3f, 0xe0, 0x92, 0xf8, 0xf9, 0x34, 0x3c, 0xe0, + 0x92, 0xf8, 0xfa, 0x34, 0x39, 0xe0, 0x92, 0xf8, 0xfb, 0x34, 0x36, 0xe0, + 0x92, 0xf8, 0xfc, 0x34, 0x33, 0xe0, 0x92, 0xf8, 0xfd, 0x34, 0x30, 0xe0, + 0x92, 0xf8, 0xfe, 0x34, 0x2d, 0xe0, 0x92, 0xf8, 0xff, 0x34, 0x2a, 0xe0, + 0x92, 0xf8, 0x00, 0x35, 0x27, 0xe0, 0x92, 0xf8, 0x01, 0x35, 0x24, 0xe0, + 0x92, 0xf8, 0x02, 0x35, 0x21, 0xe0, 0x92, 0xf8, 0x03, 0x35, 0x1e, 0xe0, + 0x92, 0xf8, 0x04, 0x35, 0x1b, 0xe0, 0x92, 0xf8, 0x05, 0x35, 0x18, 0xe0, + 0x92, 0xf8, 0x06, 0x35, 0x15, 0xe0, 0x92, 0xf8, 0x07, 0x35, 0x12, 0xe0, + 0x92, 0xf8, 0x08, 0x35, 0x0f, 0xe0, 0x92, 0xf8, 0x09, 0x35, 0x0c, 0xe0, + 0x92, 0xf8, 0x0a, 0x35, 0x09, 0xe0, 0x92, 0xf8, 0x0b, 0x35, 0x06, 0xe0, + 0x92, 0xf8, 0x0c, 0x35, 0x03, 0xe0, 0x92, 0xf8, 0x0d, 0x35, 0x00, 0xe0, + 0x00, 0x23, 0xd2, 0xf8, 0xe4, 0x14, 0x90, 0xf8, 0x2a, 0x26, 0x8a, 0x1a, + 0xd3, 0x18, 0x58, 0xb2, 0x70, 0x47, 0x08, 0x46, 0x70, 0x47, 0x49, 0xb2, + 0x48, 0x1c, 0x40, 0x10, 0x49, 0x10, 0x08, 0x31, 0xc0, 0xf1, 0x08, 0x00, + 0x41, 0xea, 0x00, 0x10, 0x80, 0xb2, 0x70, 0x47, 0xb0, 0xf8, 0xda, 0x20, + 0xd0, 0xf8, 0xa8, 0x30, 0x02, 0xf4, 0x70, 0x42, 0xb2, 0xf5, 0x00, 0x5f, + 0x06, 0xd1, 0x93, 0xf8, 0x3c, 0x05, 0x43, 0xb2, 0x01, 0x33, 0x03, 0xd0, + 0xc0, 0xb2, 0x70, 0x47, 0x00, 0x20, 0x70, 0x47, 0x00, 0x20, 0x70, 0x47, + 0x38, 0xb5, 0x04, 0x46, 0xd0, 0xf8, 0xa8, 0x50, 0xff, 0xf7, 0xe6, 0xff, + 0x10, 0xb9, 0x95, 0xf8, 0x46, 0x05, 0x40, 0xb1, 0xb4, 0xf8, 0xda, 0x00, + 0x00, 0xf4, 0x70, 0x40, 0xa0, 0xf5, 0x00, 0x53, 0x58, 0x42, 0x40, 0xeb, + 0x03, 0x00, 0x38, 0xbd, 0x30, 0xb5, 0xd0, 0xf8, 0xa8, 0x00, 0x8f, 0xb0, + 0x00, 0x23, 0x00, 0x25, 0x01, 0xac, 0x1d, 0x55, 0x01, 0x33, 0x32, 0x2b, + 0xf9, 0xd1, 0x53, 0x1c, 0x90, 0xf8, 0xe9, 0x33, 0x06, 0xd1, 0x11, 0xb1, + 0xb0, 0xf9, 0x3e, 0x25, 0x03, 0xe0, 0xb0, 0xf9, 0x40, 0x25, 0x11, 0xe0, + 0x81, 0xb1, 0xa0, 0x2b, 0x4f, 0xf0, 0x00, 0x03, 0x8d, 0xf8, 0x04, 0x30, + 0x1d, 0xbf, 0x8d, 0xf8, 0x05, 0x30, 0x8d, 0xf8, 0x06, 0x30, 0x8d, 0xf8, + 0x07, 0x30, 0x8d, 0xf8, 0x06, 0x30, 0x8d, 0xf8, 0x08, 0x30, 0x31, 0xe0, + 0xa0, 0x2b, 0x4f, 0xf0, 0x00, 0x03, 0x15, 0xd0, 0x01, 0x21, 0x8d, 0xf8, + 0x18, 0x10, 0x8d, 0xf8, 0x19, 0x10, 0xfe, 0x21, 0x8d, 0xf8, 0x1c, 0x10, + 0x8d, 0xf8, 0x1d, 0x10, 0xff, 0x21, 0x8d, 0xf8, 0x1a, 0x30, 0x8d, 0xf8, + 0x1b, 0x30, 0x8d, 0xf8, 0x1e, 0x30, 0x8d, 0xf8, 0x1f, 0x10, 0x8d, 0xf8, + 0x22, 0x30, 0x17, 0xe0, 0x02, 0x21, 0x8d, 0xf8, 0x18, 0x10, 0xfc, 0x21, + 0x8d, 0xf8, 0x19, 0x30, 0x8d, 0xf8, 0x1a, 0x30, 0x8d, 0xf8, 0x1b, 0x30, + 0x8d, 0xf8, 0x1c, 0x10, 0x8d, 0xf8, 0x22, 0x30, 0xfe, 0x21, 0x04, 0x23, + 0x8d, 0xf8, 0x1d, 0x10, 0x8d, 0xf8, 0x1e, 0x10, 0x8d, 0xf8, 0x1f, 0x10, + 0x8d, 0xf8, 0x30, 0x30, 0x0e, 0xab, 0x9a, 0x18, 0x12, 0xf9, 0x34, 0x0c, + 0x0f, 0xb0, 0x30, 0xbd, 0x10, 0xb5, 0xc1, 0x69, 0x00, 0xf5, 0x81, 0x52, + 0x0b, 0x6a, 0x12, 0x68, 0xd0, 0xf8, 0xa8, 0x40, 0x93, 0x42, 0x01, 0xd3, + 0x9b, 0x1a, 0x01, 0xe0, 0xd2, 0x43, 0xd3, 0x18, 0x94, 0xf8, 0xbc, 0x42, + 0x90, 0xf8, 0xda, 0x20, 0x94, 0x42, 0x05, 0xd1, 0x88, 0x6e, 0x83, 0x42, + 0x34, 0xbf, 0x00, 0x20, 0x01, 0x20, 0x10, 0xbd, 0x01, 0x20, 0x10, 0xbd, + 0x70, 0x47, 0xd0, 0xf8, 0xa8, 0x30, 0x93, 0xf8, 0x06, 0x04, 0x00, 0x28, + 0x08, 0xbf, 0x10, 0x20, 0x70, 0x47, 0x00, 0x00, 0x10, 0x23, 0x16, 0x4a, + 0x30, 0xb5, 0x19, 0x46, 0x04, 0x24, 0x49, 0xb2, 0x49, 0x10, 0xc9, 0xb2, + 0x02, 0x42, 0x4d, 0xb2, 0x03, 0xd0, 0xcb, 0x18, 0xdb, 0xb2, 0xaa, 0x40, + 0x02, 0xe0, 0xea, 0x40, 0x5b, 0x1a, 0xdb, 0xb2, 0x01, 0x3c, 0xf0, 0xd1, + 0x02, 0x42, 0x01, 0xd1, 0x01, 0x3b, 0xdb, 0xb2, 0x03, 0xeb, 0x43, 0x01, + 0x5b, 0xb2, 0xc9, 0xb2, 0x03, 0x2b, 0x0a, 0x46, 0x0c, 0xdd, 0x03, 0x3b, + 0xd8, 0x40, 0x0d, 0x28, 0x01, 0xd9, 0xca, 0x1c, 0x06, 0xe0, 0x0a, 0x28, + 0x01, 0xd9, 0x8a, 0x1c, 0x02, 0xe0, 0x08, 0x28, 0x88, 0xbf, 0x4a, 0x1c, + 0x50, 0xb2, 0x30, 0xbd, 0x00, 0x00, 0xff, 0xff, 0xd0, 0xf8, 0xa8, 0x30, + 0x00, 0x22, 0x83, 0xf8, 0x90, 0x23, 0x83, 0xf8, 0x91, 0x23, 0x83, 0xf8, + 0x92, 0x23, 0x83, 0xf8, 0x93, 0x23, 0x83, 0xf8, 0x94, 0x23, 0x70, 0x47, + 0x70, 0x47, 0x08, 0xb5, 0x40, 0xf2, 0xa4, 0x41, 0xfd, 0xf7, 0x63, 0xfe, + 0x00, 0xf4, 0x40, 0x40, 0x08, 0xbd, 0x70, 0xb5, 0x0c, 0x46, 0x40, 0xf2, + 0x39, 0x41, 0x06, 0x46, 0xfd, 0xf7, 0x59, 0xfe, 0x00, 0xf4, 0x60, 0x70, + 0xc0, 0x11, 0xe0, 0x80, 0x40, 0xf2, 0xb5, 0x41, 0x30, 0x46, 0xfd, 0xf7, + 0x50, 0xfe, 0x40, 0xf2, 0xfb, 0x41, 0x05, 0x46, 0x30, 0x46, 0xfd, 0xf7, + 0x4a, 0xfe, 0xeb, 0xb2, 0xc0, 0xb2, 0x2d, 0x0a, 0x23, 0x80, 0x65, 0x80, + 0xa0, 0x80, 0x70, 0xbd, 0x08, 0xb5, 0x40, 0xf2, 0xfb, 0x41, 0xfd, 0xf7, + 0x3e, 0xfe, 0x00, 0xf4, 0xfe, 0x40, 0x00, 0x0a, 0x08, 0xbd, 0x2d, 0xe9, + 0xf8, 0x43, 0x0d, 0x46, 0x40, 0xf2, 0xb7, 0x61, 0x04, 0x46, 0x91, 0x46, + 0xfd, 0xf7, 0x31, 0xfe, 0x40, 0xf2, 0xb6, 0x61, 0x80, 0x46, 0x20, 0x46, + 0xfd, 0xf7, 0x2b, 0xfe, 0x40, 0xf2, 0xb5, 0x61, 0x07, 0x46, 0x20, 0x46, + 0xfd, 0xf7, 0x25, 0xfe, 0x40, 0xf2, 0xb4, 0x61, 0x06, 0x46, 0x20, 0x46, + 0x00, 0x24, 0xfd, 0xf7, 0x1e, 0xfe, 0x21, 0x46, 0x23, 0x46, 0x50, 0xfa, + 0x04, 0xf2, 0x12, 0xf0, 0x01, 0x02, 0x02, 0xd1, 0x01, 0x31, 0xc9, 0xb2, + 0x00, 0xe0, 0x01, 0x22, 0x01, 0x33, 0xdb, 0xb2, 0x10, 0x2b, 0x12, 0xd0, + 0x01, 0x34, 0x00, 0x2a, 0xef, 0xd0, 0x01, 0x22, 0x0d, 0xe0, 0xa3, 0xf1, + 0x10, 0x04, 0x56, 0xfa, 0x04, 0xf4, 0xe4, 0x07, 0x02, 0xd4, 0x01, 0x31, + 0xc9, 0xb2, 0x00, 0xe0, 0x01, 0x22, 0x01, 0x33, 0xdb, 0xb2, 0x1f, 0x2b, + 0x0f, 0xd8, 0x00, 0x2a, 0xef, 0xd0, 0x01, 0x22, 0x0b, 0xe0, 0xa3, 0xf1, + 0x20, 0x04, 0x57, 0xfa, 0x04, 0xf4, 0xe4, 0x07, 0x02, 0xd4, 0x01, 0x31, + 0xc9, 0xb2, 0x00, 0xe0, 0x01, 0x22, 0x01, 0x33, 0xdb, 0xb2, 0x2f, 0x2b, + 0x0f, 0xd8, 0x00, 0x2a, 0xef, 0xd0, 0x01, 0x22, 0x0b, 0xe0, 0xa3, 0xf1, + 0x30, 0x04, 0x48, 0xfa, 0x04, 0xf4, 0xe4, 0x07, 0x02, 0xd4, 0x01, 0x31, + 0xc9, 0xb2, 0x00, 0xe0, 0x01, 0x22, 0x01, 0x33, 0xdb, 0xb2, 0x3f, 0x2b, + 0x04, 0xd9, 0x4f, 0xf0, 0x0f, 0x0c, 0x00, 0x23, 0x3f, 0x24, 0x02, 0xe0, + 0x00, 0x2a, 0xea, 0xd0, 0xf7, 0xe7, 0x48, 0xfa, 0x0c, 0xf2, 0x12, 0xf0, + 0x01, 0x02, 0x02, 0xd1, 0x01, 0x3c, 0xe4, 0xb2, 0x00, 0xe0, 0x01, 0x22, + 0x01, 0x33, 0xdb, 0xb2, 0x10, 0x2b, 0x14, 0xd0, 0x0c, 0xf1, 0xff, 0x3c, + 0x00, 0x2a, 0xee, 0xd0, 0x01, 0x22, 0x0e, 0xe0, 0xc3, 0xf1, 0x1f, 0x0c, + 0x47, 0xfa, 0x0c, 0xfc, 0x1c, 0xf0, 0x01, 0x0f, 0x02, 0xd1, 0x01, 0x3c, + 0xe4, 0xb2, 0x00, 0xe0, 0x01, 0x22, 0x01, 0x33, 0xdb, 0xb2, 0x1f, 0x2b, + 0x10, 0xd8, 0x00, 0x2a, 0xee, 0xd0, 0x01, 0x22, 0x0c, 0xe0, 0xc3, 0xf1, + 0x2f, 0x07, 0x56, 0xfa, 0x07, 0xf7, 0x17, 0xf0, 0x01, 0x0f, 0x02, 0xd1, + 0x01, 0x3c, 0xe4, 0xb2, 0x00, 0xe0, 0x01, 0x22, 0x01, 0x33, 0xdb, 0xb2, + 0x2f, 0x2b, 0x10, 0xd8, 0x00, 0x2a, 0xee, 0xd0, 0x01, 0x22, 0x0c, 0xe0, + 0xc3, 0xf1, 0x3f, 0x06, 0x50, 0xfa, 0x06, 0xf6, 0x16, 0xf0, 0x01, 0x0f, + 0x02, 0xd1, 0x01, 0x3c, 0xe4, 0xb2, 0x00, 0xe0, 0x01, 0x22, 0x01, 0x33, + 0xdb, 0xb2, 0x3f, 0x2b, 0x01, 0xd8, 0x00, 0x2a, 0xee, 0xd0, 0x2c, 0x70, + 0x89, 0xf8, 0x00, 0x10, 0xbd, 0xe8, 0xf8, 0x83, 0x38, 0xb5, 0x40, 0xf2, + 0x23, 0x41, 0xd0, 0xf8, 0xa8, 0x40, 0x05, 0x46, 0xfd, 0xf7, 0x79, 0xfd, + 0xc0, 0xb2, 0xa4, 0xf8, 0x64, 0x03, 0x4f, 0xf4, 0xaa, 0x61, 0x28, 0x46, + 0xfd, 0xf7, 0x71, 0xfd, 0x80, 0x05, 0x80, 0x0d, 0xa4, 0xf8, 0x68, 0x03, + 0x40, 0xf2, 0x34, 0x41, 0x28, 0x46, 0xfd, 0xf7, 0x68, 0xfd, 0xc0, 0xb2, + 0x7f, 0x28, 0xa4, 0xf8, 0x66, 0x03, 0xc4, 0xbf, 0xa0, 0xf5, 0x80, 0x70, + 0xa4, 0xf8, 0x66, 0x03, 0x40, 0xf2, 0x32, 0x41, 0x28, 0x46, 0xfd, 0xf7, + 0x5a, 0xfd, 0xc0, 0xb2, 0x7f, 0x28, 0xc4, 0xbf, 0xa0, 0xf5, 0x80, 0x70, + 0x80, 0xb2, 0x84, 0xf8, 0xbc, 0x03, 0x38, 0xbd, 0x2d, 0xe9, 0xf8, 0x43, + 0xb0, 0xf8, 0xda, 0x20, 0x04, 0x46, 0x02, 0xf4, 0x70, 0x42, 0xb2, 0xf5, + 0x80, 0x5f, 0xd0, 0xf8, 0xa8, 0x30, 0x07, 0xd1, 0xb3, 0xf8, 0x92, 0x05, + 0x03, 0xb2, 0x01, 0x33, 0x55, 0xd0, 0x80, 0xb2, 0xbd, 0xe8, 0xf8, 0x83, + 0xb3, 0xf8, 0x90, 0x35, 0x1a, 0xb2, 0x01, 0x32, 0x02, 0xd0, 0x98, 0xb2, + 0xbd, 0xe8, 0xf8, 0x83, 0x40, 0xf2, 0xa5, 0x41, 0xfd, 0xf7, 0x31, 0xfd, + 0x40, 0xf2, 0xa5, 0x41, 0x81, 0x46, 0x20, 0x46, 0xfd, 0xf7, 0x2b, 0xfd, + 0x40, 0xf2, 0x0d, 0x41, 0x80, 0x46, 0x20, 0x46, 0xfd, 0xf7, 0x25, 0xfd, + 0x40, 0xf2, 0x0d, 0x41, 0x07, 0x46, 0x20, 0x46, 0xfd, 0xf7, 0x1f, 0xfd, + 0x40, 0xf2, 0xa2, 0x41, 0x06, 0x46, 0x20, 0x46, 0xfd, 0xf7, 0x19, 0xfd, + 0x40, 0xf2, 0xa2, 0x41, 0x05, 0x46, 0x20, 0x46, 0xfd, 0xf7, 0x13, 0xfd, + 0x08, 0xf4, 0xe0, 0x48, 0x01, 0x23, 0x4f, 0xea, 0x28, 0x38, 0x03, 0xfa, + 0x08, 0xf8, 0x06, 0xf4, 0xe0, 0x66, 0x00, 0xf4, 0xe0, 0x60, 0x36, 0x12, + 0x00, 0x12, 0x13, 0xfa, 0x06, 0xf6, 0x13, 0xfa, 0x00, 0xf0, 0x5f, 0xfa, + 0x89, 0xf9, 0x1f, 0xfa, 0x88, 0xf8, 0xc1, 0x44, 0xff, 0xb2, 0x4f, 0x44, + 0xb6, 0xb2, 0xed, 0xb2, 0x80, 0xb2, 0xbf, 0x19, 0x28, 0x18, 0x07, 0xeb, + 0x40, 0x00, 0x28, 0x30, 0x98, 0x40, 0x80, 0xb2, 0xb0, 0xf5, 0xc8, 0x6f, + 0x38, 0xbf, 0x4f, 0xf4, 0xc8, 0x60, 0xbd, 0xe8, 0xf8, 0x83, 0x4f, 0xf4, + 0xc8, 0x70, 0xbd, 0xe8, 0xf8, 0x83, 0x70, 0xb5, 0x0d, 0x46, 0x40, 0xf2, + 0x39, 0x41, 0x04, 0x46, 0xfd, 0xf7, 0xdf, 0xfc, 0x40, 0xf6, 0x7f, 0x43, + 0x03, 0x40, 0x43, 0xea, 0xc5, 0x13, 0x20, 0x46, 0x40, 0xf2, 0x39, 0x41, + 0x40, 0xf6, 0xff, 0x72, 0x9b, 0xb2, 0xbd, 0xe8, 0x70, 0x40, 0xfd, 0xf7, + 0xc1, 0xbe, 0x70, 0xb5, 0x0c, 0x1c, 0x18, 0xbf, 0x01, 0x24, 0x05, 0x46, + 0x80, 0x22, 0xe3, 0x01, 0x4f, 0xf4, 0x96, 0x61, 0xfd, 0xf7, 0xb6, 0xfe, + 0x28, 0x46, 0xa3, 0x03, 0x4f, 0xf4, 0x96, 0x61, 0x4f, 0xf4, 0x80, 0x42, + 0xfd, 0xf7, 0xae, 0xfe, 0x28, 0x46, 0x40, 0xf2, 0x3b, 0x41, 0x40, 0x22, + 0xa3, 0x01, 0xbd, 0xe8, 0x70, 0x40, 0xfd, 0xf7, 0xa5, 0xbe, 0x70, 0xb5, + 0x0c, 0x46, 0x05, 0x46, 0xff, 0xf7, 0x6c, 0xfe, 0x62, 0x88, 0x23, 0x88, + 0x06, 0x46, 0x43, 0xea, 0x02, 0x23, 0x28, 0x46, 0x40, 0xf2, 0xb5, 0x41, + 0x4f, 0xf6, 0xff, 0x72, 0x9b, 0xb2, 0xfd, 0xf7, 0x93, 0xfe, 0x36, 0x02, + 0xa3, 0x88, 0xb6, 0xb2, 0x28, 0x46, 0x33, 0x43, 0x40, 0xf2, 0xfb, 0x41, + 0x47, 0xf6, 0xff, 0x72, 0xfd, 0xf7, 0x88, 0xfe, 0x62, 0x88, 0x23, 0x88, + 0x28, 0x46, 0x43, 0xea, 0x02, 0x23, 0x40, 0xf2, 0xfc, 0x41, 0x4f, 0xf6, + 0xff, 0x72, 0x9b, 0xb2, 0xfd, 0xf7, 0x7c, 0xfe, 0xa3, 0x88, 0x28, 0x46, + 0x47, 0xf6, 0xff, 0x72, 0x33, 0x43, 0x40, 0xf2, 0xfd, 0x41, 0xfd, 0xf7, + 0x73, 0xfe, 0x28, 0x46, 0xe1, 0x88, 0xff, 0xf7, 0x98, 0xff, 0x28, 0x46, + 0x01, 0x21, 0xbd, 0xe8, 0x70, 0x40, 0xff, 0xf7, 0xa8, 0xbf, 0x70, 0xb5, + 0x0c, 0x1c, 0x18, 0xbf, 0x01, 0x24, 0x05, 0x46, 0x23, 0x02, 0x4f, 0xf4, + 0x96, 0x61, 0x4f, 0xf4, 0x80, 0x72, 0xfd, 0xf7, 0x5d, 0xfe, 0x01, 0x22, + 0x28, 0x46, 0x40, 0xf2, 0x4c, 0x41, 0x23, 0x46, 0xfd, 0xf7, 0x56, 0xfe, + 0x23, 0x03, 0x28, 0x46, 0x4f, 0xf4, 0x96, 0x61, 0x4f, 0xf4, 0x80, 0x52, + 0xfd, 0xf7, 0x4e, 0xfe, 0x63, 0x03, 0x28, 0x46, 0x4f, 0xf4, 0x96, 0x61, + 0x4f, 0xf4, 0x00, 0x52, 0xfd, 0xf7, 0x46, 0xfe, 0x20, 0x22, 0x63, 0x01, + 0x28, 0x46, 0x4f, 0xf4, 0x96, 0x61, 0xfd, 0xf7, 0x3f, 0xfe, 0x63, 0x02, + 0x28, 0x46, 0x40, 0xf2, 0xae, 0x41, 0x4f, 0xf4, 0x00, 0x72, 0xfd, 0xf7, + 0x37, 0xfe, 0xb5, 0xf8, 0xda, 0x30, 0x03, 0xf4, 0x70, 0x43, 0xb3, 0xf5, + 0x00, 0x5f, 0x10, 0xd1, 0x28, 0x46, 0xa3, 0x02, 0x4f, 0xf4, 0x96, 0x61, + 0x4f, 0xf4, 0x80, 0x62, 0xfd, 0xf7, 0x28, 0xfe, 0x28, 0x46, 0x40, 0xf2, + 0xe5, 0x41, 0x08, 0x22, 0xe3, 0x00, 0xbd, 0xe8, 0x70, 0x40, 0xfd, 0xf7, + 0x1f, 0xbe, 0x70, 0xbd, 0x09, 0x02, 0x70, 0xb5, 0x8c, 0xb2, 0x23, 0x46, + 0x40, 0xf2, 0xfb, 0x41, 0x4f, 0xf4, 0xfe, 0x42, 0x05, 0x46, 0xfd, 0xf7, + 0x13, 0xfe, 0x28, 0x46, 0x40, 0xf2, 0xfd, 0x41, 0x4f, 0xf4, 0xfe, 0x42, + 0x23, 0x46, 0xbd, 0xe8, 0x70, 0x40, 0xfd, 0xf7, 0x09, 0xbe, 0x70, 0xb5, + 0x0e, 0x46, 0x04, 0x46, 0x15, 0x46, 0x33, 0x46, 0x40, 0xf2, 0x45, 0x61, + 0x40, 0xf2, 0xff, 0x32, 0xfd, 0xf7, 0xfe, 0xfd, 0x20, 0x46, 0x2b, 0x46, + 0x40, 0xf2, 0x46, 0x61, 0x40, 0xf2, 0xff, 0x32, 0xfd, 0xf7, 0xf6, 0xfd, + 0x20, 0x46, 0x33, 0x46, 0x40, 0xf2, 0x47, 0x61, 0x40, 0xf2, 0xff, 0x32, + 0xfd, 0xf7, 0xee, 0xfd, 0x20, 0x46, 0x2b, 0x46, 0x4f, 0xf4, 0xc9, 0x61, + 0x40, 0xf2, 0xff, 0x32, 0xfd, 0xf7, 0xe6, 0xfd, 0x20, 0x46, 0x33, 0x46, + 0x40, 0xf2, 0x49, 0x61, 0x40, 0xf2, 0xff, 0x32, 0xfd, 0xf7, 0xde, 0xfd, + 0x20, 0x46, 0x40, 0xf2, 0x4a, 0x61, 0x40, 0xf2, 0xff, 0x32, 0x2b, 0x46, + 0xbd, 0xe8, 0x70, 0x40, 0xfd, 0xf7, 0xd4, 0xbd, 0x01, 0x49, 0x0c, 0x22, + 0xfd, 0xf7, 0xe2, 0xbd, 0xec, 0xe9, 0x01, 0x00, 0x2d, 0xe9, 0xf0, 0x47, + 0x1f, 0x46, 0xbd, 0xf8, 0x2c, 0x50, 0xbd, 0xf8, 0x24, 0x30, 0xbd, 0xf8, + 0x20, 0xe0, 0x89, 0x46, 0x90, 0x46, 0xbd, 0xf8, 0x28, 0x10, 0x05, 0xf0, + 0x03, 0x02, 0x03, 0xf0, 0x0f, 0x03, 0x42, 0xea, 0x03, 0x23, 0x43, 0xea, + 0x0e, 0x33, 0x4f, 0xea, 0x81, 0x1e, 0x5f, 0xfa, 0x8e, 0xfe, 0x43, 0xea, + 0x0e, 0x03, 0x01, 0xf0, 0x03, 0x01, 0x43, 0xea, 0x01, 0x13, 0x43, 0xea, + 0x82, 0x03, 0x40, 0xf2, 0xb6, 0x41, 0x4f, 0xf6, 0xff, 0x72, 0x9b, 0xb2, + 0x04, 0x46, 0xbd, 0xf8, 0x30, 0x60, 0xfd, 0xf7, 0xa3, 0xfd, 0x0f, 0x22, + 0x07, 0xea, 0x02, 0x03, 0xef, 0x02, 0x20, 0x46, 0x40, 0xf2, 0xb7, 0x41, + 0xbf, 0xb2, 0xfd, 0xf7, 0x99, 0xfd, 0x36, 0x03, 0x3b, 0x46, 0x20, 0x46, + 0x40, 0xf2, 0xb1, 0x41, 0x4f, 0xf4, 0x60, 0x52, 0xfd, 0xf7, 0x90, 0xfd, + 0xb6, 0xb2, 0x06, 0x22, 0x20, 0x46, 0x21, 0x49, 0xfd, 0xf7, 0x9c, 0xfd, + 0x20, 0x46, 0x40, 0xf2, 0xae, 0x41, 0x4f, 0xf4, 0x70, 0x42, 0x33, 0x46, + 0xfd, 0xf7, 0x82, 0xfd, 0x4f, 0xea, 0x48, 0x23, 0x20, 0x46, 0x40, 0xf2, + 0xb1, 0x41, 0x4f, 0xf4, 0x00, 0x72, 0x03, 0xf4, 0x7e, 0x43, 0xfd, 0xf7, + 0x77, 0xfd, 0x01, 0x22, 0xd9, 0xf1, 0x01, 0x03, 0x38, 0xbf, 0x00, 0x23, + 0x20, 0x46, 0x40, 0xf2, 0x4d, 0x41, 0xfd, 0xf7, 0x6d, 0xfd, 0xb4, 0xf8, + 0xda, 0x30, 0x03, 0xf4, 0x70, 0x43, 0xb3, 0xf5, 0x00, 0x5f, 0x11, 0xd1, + 0x20, 0x46, 0x40, 0xf2, 0xb1, 0x41, 0x4f, 0xf4, 0xc0, 0x52, 0x3b, 0x46, + 0xfd, 0xf7, 0x5e, 0xfd, 0xed, 0x00, 0x4f, 0xf6, 0xf8, 0x73, 0x20, 0x46, + 0x40, 0xf2, 0xe6, 0x41, 0x18, 0x22, 0x2b, 0x40, 0xfd, 0xf7, 0x54, 0xfd, + 0x20, 0x46, 0x40, 0xf2, 0xae, 0x41, 0x4f, 0xf4, 0x70, 0x42, 0x33, 0x46, + 0xbd, 0xe8, 0xf0, 0x47, 0xfd, 0xf7, 0x4a, 0xbd, 0x20, 0xee, 0x01, 0x00, + 0x10, 0xb5, 0x04, 0x46, 0x86, 0xb0, 0x31, 0xb9, 0x0f, 0x49, 0x0e, 0x22, + 0x06, 0xb0, 0xbd, 0xe8, 0x10, 0x40, 0xfd, 0xf7, 0x4f, 0xbd, 0x09, 0x22, + 0x0c, 0x49, 0xfd, 0xf7, 0x4b, 0xfd, 0x00, 0x21, 0x03, 0x22, 0x06, 0x23, + 0x00, 0x93, 0x02, 0x92, 0x04, 0x23, 0x03, 0x92, 0x20, 0x46, 0x0a, 0x46, + 0x04, 0x91, 0x01, 0x93, 0xff, 0xf7, 0x5e, 0xff, 0x20, 0x46, 0x01, 0x21, + 0x06, 0xb0, 0xbd, 0xe8, 0x10, 0x40, 0xff, 0xf7, 0xbc, 0xbe, 0x00, 0xbf, + 0x18, 0xe7, 0x01, 0x00, 0x12, 0xe8, 0x01, 0x00, 0xd0, 0xf8, 0xa8, 0x30, + 0xd3, 0xf8, 0x74, 0x15, 0x29, 0xb1, 0xc3, 0x69, 0x4f, 0xf4, 0x20, 0x72, + 0x98, 0x68, 0xf3, 0xf3, 0xdd, 0xb3, 0x70, 0x47, 0xf8, 0xb5, 0xd0, 0xf8, + 0xa8, 0x30, 0x06, 0x46, 0xd3, 0xf8, 0x7c, 0x55, 0xd3, 0xf8, 0x78, 0x75, + 0x00, 0x24, 0x0d, 0xe0, 0x14, 0x23, 0x63, 0x43, 0xe9, 0x18, 0x0a, 0x69, + 0x49, 0x68, 0xf0, 0x69, 0x4a, 0x43, 0x80, 0x68, 0xe9, 0x58, 0xd2, 0x08, + 0xf3, 0xf3, 0xc6, 0xf3, 0x01, 0x34, 0xe4, 0xb2, 0xbc, 0x42, 0xef, 0xd3, + 0xf8, 0xbd, 0x38, 0xb5, 0xd0, 0xf8, 0xa8, 0x40, 0x05, 0x46, 0xd4, 0xf8, + 0x7c, 0x35, 0x73, 0xb1, 0x01, 0x21, 0xff, 0xf7, 0xdb, 0xff, 0xea, 0x69, + 0xd4, 0xf8, 0x78, 0x35, 0x90, 0x68, 0x14, 0x22, 0x5a, 0x43, 0xd4, 0xf8, + 0x7c, 0x15, 0xbd, 0xe8, 0x38, 0x40, 0xf3, 0xf3, 0xab, 0xb3, 0x38, 0xbd, + 0x00, 0xf5, 0x98, 0x53, 0x19, 0x69, 0x10, 0xb5, 0x04, 0x46, 0x29, 0xb1, + 0xc3, 0x69, 0x42, 0xf6, 0x08, 0x52, 0x98, 0x68, 0xf3, 0xf3, 0x9e, 0xf3, + 0x20, 0x46, 0xff, 0xf7, 0xb3, 0xff, 0x20, 0x46, 0xff, 0xf7, 0xd7, 0xff, + 0xe3, 0x69, 0xd4, 0xf8, 0xa8, 0x10, 0x98, 0x68, 0x40, 0xf2, 0xcc, 0x52, + 0xbd, 0xe8, 0x10, 0x40, 0xf3, 0xf3, 0x8e, 0xb3, 0x10, 0xb5, 0x4f, 0xf4, + 0x80, 0x52, 0x04, 0x46, 0x00, 0x23, 0x40, 0xf2, 0xc9, 0x61, 0xfd, 0xf7, + 0xbd, 0xfc, 0xd4, 0xf8, 0xa8, 0x30, 0xb3, 0xf8, 0xc2, 0x24, 0xd2, 0xb1, + 0x93, 0xf8, 0xe9, 0x33, 0x20, 0x46, 0xa0, 0x2b, 0x40, 0xf2, 0x89, 0x61, + 0x01, 0xd1, 0x23, 0x22, 0x00, 0xe0, 0x30, 0x22, 0xfd, 0xf7, 0xc6, 0xfa, + 0xd4, 0xf8, 0xa8, 0x30, 0xb3, 0xf8, 0xc2, 0x34, 0x02, 0x2b, 0x0e, 0xd1, + 0x4f, 0xf4, 0x80, 0x52, 0x20, 0x46, 0x40, 0xf2, 0xc9, 0x61, 0x13, 0x46, + 0xfd, 0xf7, 0x9e, 0xfc, 0x05, 0xe0, 0x20, 0x46, 0x40, 0xf2, 0x89, 0x61, + 0x23, 0x22, 0xfd, 0xf7, 0xb1, 0xfa, 0x20, 0x46, 0x04, 0x22, 0x27, 0x49, + 0xfd, 0xf7, 0xa4, 0xfc, 0x20, 0x46, 0x00, 0x22, 0x40, 0xf2, 0x79, 0x61, + 0xfd, 0xf7, 0xa6, 0xfa, 0x20, 0x46, 0x08, 0x22, 0x22, 0x49, 0xfd, 0xf7, + 0x99, 0xfc, 0xd4, 0xf8, 0xa8, 0x30, 0x20, 0x46, 0xb3, 0xf8, 0xc2, 0x24, + 0x4f, 0xf4, 0xd9, 0x61, 0xfd, 0xf7, 0x98, 0xfa, 0x20, 0x46, 0x06, 0x22, + 0x1c, 0x49, 0xfd, 0xf7, 0x8b, 0xfc, 0xd4, 0xf8, 0xa8, 0x30, 0x4f, 0xf4, + 0x80, 0x72, 0xb3, 0xf8, 0xc2, 0x34, 0x20, 0x46, 0x1a, 0x41, 0x01, 0x3a, + 0x4f, 0xf4, 0xd0, 0x61, 0x92, 0xb2, 0xfd, 0xf7, 0x85, 0xfa, 0xd4, 0xf8, + 0xa8, 0x30, 0x4f, 0xf4, 0xa0, 0x72, 0xb3, 0xf8, 0xc2, 0x34, 0x20, 0x46, + 0x1a, 0x41, 0x01, 0x3a, 0x92, 0xb2, 0x40, 0xf2, 0x81, 0x61, 0xfd, 0xf7, + 0x77, 0xfa, 0xd4, 0xf8, 0xa8, 0x30, 0x20, 0x46, 0xb3, 0xf8, 0xc2, 0x34, + 0x40, 0xf2, 0x7f, 0x61, 0x01, 0x3b, 0x9b, 0xb2, 0x01, 0x2b, 0x9a, 0xbf, + 0x08, 0x4a, 0xd2, 0x5c, 0x34, 0x22, 0xfd, 0xf7, 0x67, 0xfa, 0x07, 0x49, + 0x20, 0x46, 0x0e, 0x22, 0xbd, 0xe8, 0x10, 0x40, 0xfd, 0xf7, 0x58, 0xbc, + 0x54, 0xee, 0x01, 0x00, 0x5c, 0xee, 0x01, 0x00, 0x6c, 0xee, 0x01, 0x00, + 0xbc, 0xe9, 0x01, 0x00, 0x38, 0xee, 0x01, 0x00, 0x70, 0xb5, 0x40, 0xf2, + 0x3c, 0x41, 0x04, 0x46, 0xfd, 0xf7, 0x45, 0xfa, 0x40, 0xf2, 0x3b, 0x41, + 0x06, 0x46, 0x20, 0x46, 0xfd, 0xf7, 0x3f, 0xfa, 0x46, 0xf0, 0x01, 0x02, + 0x05, 0x46, 0x40, 0xf2, 0x3c, 0x41, 0x20, 0x46, 0x92, 0xb2, 0xfd, 0xf7, + 0x41, 0xfa, 0x45, 0xf0, 0x01, 0x02, 0x20, 0x46, 0x40, 0xf2, 0x3b, 0x41, + 0x92, 0xb2, 0xfd, 0xf7, 0x39, 0xfa, 0x4f, 0xf6, 0xfe, 0x72, 0x20, 0x46, + 0x32, 0x40, 0x40, 0xf2, 0x3c, 0x41, 0xfd, 0xf7, 0x31, 0xfa, 0x4f, 0xf6, + 0xfe, 0x72, 0x20, 0x46, 0x2a, 0x40, 0x40, 0xf2, 0x3b, 0x41, 0xfd, 0xf7, + 0x29, 0xfa, 0x20, 0x46, 0x32, 0x46, 0x40, 0xf2, 0x3c, 0x41, 0xfd, 0xf7, + 0x23, 0xfa, 0x20, 0x46, 0x40, 0xf2, 0x3b, 0x41, 0x2a, 0x46, 0xbd, 0xe8, + 0x70, 0x40, 0xfd, 0xf7, 0x1b, 0xba, 0x80, 0x22, 0x38, 0xb5, 0x0d, 0x46, + 0x13, 0x46, 0x40, 0xf2, 0xd1, 0x61, 0x04, 0x46, 0xfd, 0xf7, 0xf8, 0xfb, + 0x0d, 0xb1, 0x01, 0x2d, 0x05, 0xd1, 0x20, 0x46, 0x4f, 0xf4, 0xda, 0x61, + 0x0f, 0x22, 0xfd, 0xf7, 0x09, 0xfa, 0x20, 0x46, 0xbd, 0xe8, 0x38, 0x40, + 0xff, 0xf7, 0xae, 0xbf, 0x2d, 0xe9, 0xf0, 0x41, 0x0d, 0x46, 0xb0, 0xf8, + 0xda, 0x10, 0x04, 0x46, 0x01, 0xf4, 0x70, 0x41, 0xb1, 0xf5, 0x00, 0x5f, + 0x14, 0xbf, 0xa5, 0x21, 0x89, 0x21, 0x1f, 0x46, 0x16, 0x46, 0xfd, 0xf7, + 0xab, 0xf9, 0xb4, 0xf8, 0xda, 0x10, 0x00, 0xf0, 0x0f, 0x08, 0x01, 0xf4, + 0x70, 0x41, 0xb1, 0xf5, 0x00, 0x5f, 0x14, 0xbf, 0xa5, 0x21, 0x89, 0x21, + 0x20, 0x46, 0xfd, 0xf7, 0x9d, 0xf9, 0x00, 0xf0, 0xf0, 0x00, 0xa8, 0xeb, + 0x10, 0x18, 0x85, 0xf8, 0x00, 0x80, 0xb4, 0xf8, 0xda, 0x10, 0x20, 0x46, + 0x01, 0xf4, 0x70, 0x41, 0xb1, 0xf5, 0x00, 0x5f, 0x14, 0xbf, 0xa6, 0x21, + 0x8a, 0x21, 0xfd, 0xf7, 0x8b, 0xf9, 0xb4, 0xf8, 0xda, 0x10, 0x00, 0xf0, + 0x0f, 0x05, 0x01, 0xf4, 0x70, 0x41, 0xb1, 0xf5, 0x00, 0x5f, 0x14, 0xbf, + 0xa6, 0x21, 0x8a, 0x21, 0x20, 0x46, 0xfd, 0xf7, 0x7d, 0xf9, 0x00, 0xf0, + 0xf0, 0x00, 0xa5, 0xeb, 0x10, 0x15, 0x35, 0x70, 0xb4, 0xf8, 0xda, 0x10, + 0x20, 0x46, 0x01, 0xf4, 0x70, 0x41, 0xb1, 0xf5, 0x00, 0x5f, 0x14, 0xbf, + 0xa7, 0x21, 0x8b, 0x21, 0xfd, 0xf7, 0x6c, 0xf9, 0xb4, 0xf8, 0xda, 0x10, + 0x00, 0xf0, 0x0f, 0x05, 0x01, 0xf4, 0x70, 0x41, 0xb1, 0xf5, 0x00, 0x5f, + 0x14, 0xbf, 0xa7, 0x21, 0x8b, 0x21, 0x20, 0x46, 0xfd, 0xf7, 0x5e, 0xf9, + 0x00, 0xf0, 0xf0, 0x00, 0xa5, 0xeb, 0x10, 0x15, 0x3d, 0x70, 0xb4, 0xf8, + 0xda, 0x10, 0x20, 0x46, 0x01, 0xf4, 0x70, 0x41, 0xb1, 0xf5, 0x00, 0x5f, + 0x14, 0xbf, 0xa8, 0x21, 0x8c, 0x21, 0xfd, 0xf7, 0x4d, 0xf9, 0xb4, 0xf8, + 0xda, 0x10, 0x00, 0xf0, 0x0f, 0x05, 0x01, 0xf4, 0x70, 0x41, 0x20, 0x46, + 0xb1, 0xf5, 0x00, 0x5f, 0x14, 0xbf, 0xa8, 0x21, 0x8c, 0x21, 0xfd, 0xf7, + 0x3f, 0xf9, 0x06, 0x9b, 0x00, 0xf0, 0xf0, 0x00, 0xa5, 0xeb, 0x10, 0x15, + 0x1d, 0x70, 0xbd, 0xe8, 0xf0, 0x81, 0x00, 0x00, 0x10, 0xb5, 0xd0, 0xf8, + 0xa8, 0x30, 0x04, 0x46, 0x93, 0xf8, 0xe9, 0x33, 0xa0, 0x2b, 0x03, 0xd1, + 0x11, 0x49, 0x04, 0x22, 0xfd, 0xf7, 0x6a, 0xfb, 0x20, 0x46, 0x4f, 0xf4, + 0x8e, 0x71, 0x00, 0x22, 0xfd, 0xf7, 0x3b, 0xf9, 0x20, 0x46, 0x0d, 0x49, + 0x18, 0x22, 0xfd, 0xf7, 0x5f, 0xfb, 0x04, 0xf5, 0x98, 0x53, 0xdb, 0x89, + 0x0b, 0xb1, 0x9b, 0xb2, 0x00, 0xe0, 0x0c, 0x23, 0x20, 0x46, 0xff, 0x22, + 0x40, 0xf2, 0x34, 0x61, 0xfd, 0xf7, 0x40, 0xfb, 0x05, 0x49, 0x20, 0x46, + 0x09, 0x22, 0xbd, 0xe8, 0x10, 0x40, 0xfd, 0xf7, 0x4b, 0xbb, 0x00, 0xbf, + 0x80, 0xee, 0x01, 0x00, 0x88, 0xee, 0x01, 0x00, 0xb8, 0xee, 0x01, 0x00, + 0xb0, 0xf8, 0xda, 0x10, 0x10, 0xb5, 0x01, 0xf4, 0x70, 0x41, 0x04, 0x46, + 0xb1, 0xf5, 0x00, 0x5f, 0x14, 0xbf, 0xa5, 0x21, 0x89, 0x21, 0x88, 0x22, + 0xfd, 0xf7, 0x0d, 0xf9, 0xb4, 0xf8, 0xda, 0x10, 0x20, 0x46, 0x01, 0xf4, + 0x70, 0x41, 0xb1, 0xf5, 0x00, 0x5f, 0x14, 0xbf, 0xa6, 0x21, 0x8a, 0x21, + 0x88, 0x22, 0xfd, 0xf7, 0x00, 0xf9, 0xb4, 0xf8, 0xda, 0x10, 0x20, 0x46, + 0x01, 0xf4, 0x70, 0x41, 0xb1, 0xf5, 0x00, 0x5f, 0x14, 0xbf, 0xa7, 0x21, + 0x8b, 0x21, 0x88, 0x22, 0xfd, 0xf7, 0xf3, 0xf8, 0xb4, 0xf8, 0xda, 0x10, + 0x20, 0x46, 0x01, 0xf4, 0x70, 0x41, 0xb1, 0xf5, 0x00, 0x5f, 0x14, 0xbf, + 0xa8, 0x21, 0x8c, 0x21, 0x88, 0x22, 0xbd, 0xe8, 0x10, 0x40, 0xfd, 0xf7, + 0xe4, 0xb8, 0x00, 0x00, 0x70, 0xb5, 0x05, 0x46, 0x0e, 0x46, 0x00, 0x24, + 0x07, 0x4b, 0x32, 0x5b, 0x19, 0x5b, 0x28, 0x46, 0x02, 0x34, 0xfd, 0xf7, + 0xd8, 0xf8, 0x18, 0x2c, 0xf6, 0xd1, 0x04, 0x49, 0x28, 0x46, 0x22, 0x46, + 0xbd, 0xe8, 0x70, 0x40, 0xfd, 0xf7, 0xf8, 0xba, 0x66, 0xed, 0x01, 0x00, + 0x4a, 0xe9, 0x01, 0x00, 0x70, 0xb5, 0x04, 0x22, 0x0d, 0x46, 0x07, 0x49, + 0x06, 0x46, 0xfd, 0xf7, 0xed, 0xfa, 0x00, 0x24, 0x05, 0x4b, 0x2a, 0x5b, + 0x19, 0x5b, 0x30, 0x46, 0x02, 0x34, 0xfd, 0xf7, 0xbc, 0xf8, 0x30, 0x2c, + 0xf6, 0xd1, 0x70, 0xbd, 0x0a, 0xe8, 0x01, 0x00, 0xe8, 0xea, 0x01, 0x00, + 0x2d, 0xe9, 0xf0, 0x41, 0x04, 0x46, 0x1f, 0x46, 0x15, 0x46, 0xb0, 0xf8, + 0xda, 0x80, 0xff, 0xf7, 0x72, 0xf9, 0x08, 0xf4, 0x70, 0x48, 0xb8, 0xf5, + 0x00, 0x5f, 0x14, 0xbf, 0x4f, 0xf0, 0xa5, 0x08, 0x4f, 0xf0, 0x89, 0x08, + 0x02, 0x46, 0x41, 0x46, 0x20, 0x46, 0x9d, 0xf8, 0x18, 0x60, 0xfd, 0xf7, + 0x9c, 0xf8, 0x29, 0x46, 0x20, 0x46, 0xff, 0xf7, 0x5e, 0xf9, 0xb4, 0xf8, + 0xda, 0x80, 0x02, 0x46, 0x08, 0xf4, 0x70, 0x48, 0xb8, 0xf5, 0x00, 0x5f, + 0x14, 0xbf, 0x4f, 0xf0, 0xa6, 0x08, 0x4f, 0xf0, 0x8a, 0x08, 0x20, 0x46, + 0x41, 0x46, 0xfd, 0xf7, 0x88, 0xf8, 0x39, 0x46, 0x20, 0x46, 0xff, 0xf7, + 0x4a, 0xf9, 0xb4, 0xf8, 0xda, 0x50, 0x02, 0x46, 0x05, 0xf4, 0x70, 0x45, + 0xb5, 0xf5, 0x00, 0x5f, 0x14, 0xbf, 0xa7, 0x25, 0x8b, 0x25, 0x20, 0x46, + 0x29, 0x46, 0xfd, 0xf7, 0x76, 0xf8, 0x31, 0x46, 0x20, 0x46, 0xff, 0xf7, + 0x38, 0xf9, 0xb4, 0xf8, 0xda, 0x50, 0x02, 0x46, 0x05, 0xf4, 0x70, 0x45, + 0xb5, 0xf5, 0x00, 0x5f, 0x14, 0xbf, 0xa8, 0x25, 0x8c, 0x25, 0x20, 0x46, + 0x29, 0x46, 0xbd, 0xe8, 0xf0, 0x41, 0xfd, 0xf7, 0x62, 0xb8, 0x00, 0x00, + 0x01, 0x29, 0x70, 0xb5, 0x04, 0x46, 0x0d, 0x46, 0x16, 0xd1, 0x06, 0x22, + 0x29, 0x49, 0xfd, 0xf7, 0x81, 0xfa, 0x20, 0x46, 0x3a, 0x21, 0x2a, 0x46, + 0x2b, 0x46, 0xfd, 0xf7, 0x27, 0xfa, 0x08, 0x22, 0x20, 0x46, 0x13, 0x46, + 0x4f, 0xf4, 0x8d, 0x71, 0xfd, 0xf7, 0x20, 0xfa, 0x20, 0x46, 0x7f, 0x21, + 0x00, 0x22, 0xfd, 0xf7, 0x46, 0xf8, 0x32, 0xe0, 0x79, 0xb9, 0x1f, 0x49, + 0x06, 0x22, 0xfd, 0xf7, 0x69, 0xfa, 0x20, 0x46, 0x3a, 0x21, 0x01, 0x22, + 0x2b, 0x46, 0xfd, 0xf7, 0x0f, 0xfa, 0x08, 0x22, 0x20, 0x46, 0x4f, 0xf4, + 0x8d, 0x71, 0x13, 0x46, 0x1f, 0xe0, 0x02, 0x29, 0x1f, 0xd1, 0xb0, 0xf8, + 0xda, 0x30, 0x7d, 0x21, 0x03, 0xf4, 0x70, 0x43, 0xb3, 0xf5, 0x00, 0x5f, + 0x01, 0xd1, 0x03, 0x22, 0x00, 0xe0, 0x2a, 0x46, 0xfd, 0xf7, 0x25, 0xf8, + 0x20, 0x46, 0x28, 0x21, 0x0f, 0x22, 0x01, 0x23, 0xfd, 0xf7, 0xf4, 0xf9, + 0x80, 0x22, 0x13, 0x46, 0x20, 0x46, 0x4f, 0xf4, 0x89, 0x71, 0xfd, 0xf7, + 0xed, 0xf9, 0x20, 0x46, 0x05, 0x21, 0x07, 0x22, 0x02, 0x23, 0xfd, 0xf7, + 0xe7, 0xf9, 0x20, 0x46, 0x40, 0xf2, 0x37, 0x61, 0x4f, 0xf4, 0x40, 0x42, + 0x00, 0x23, 0xbd, 0xe8, 0x70, 0x40, 0xfd, 0xf7, 0x1f, 0xba, 0x00, 0xbf, + 0x22, 0xed, 0x01, 0x00, 0x2e, 0xed, 0x01, 0x00, 0x2d, 0xe9, 0xf1, 0x4f, + 0xd0, 0xf8, 0xa8, 0x30, 0x04, 0x46, 0x93, 0xf8, 0x0a, 0x90, 0x93, 0xf8, + 0x0c, 0xa0, 0xdd, 0x7a, 0xde, 0x7c, 0x49, 0xf4, 0x00, 0x79, 0x1a, 0x7d, + 0x49, 0xea, 0x05, 0x19, 0x93, 0xf8, 0x16, 0xb0, 0x0f, 0xfa, 0x8a, 0xf5, + 0x93, 0xf8, 0x17, 0x80, 0x49, 0xea, 0x05, 0x35, 0x46, 0xf4, 0x00, 0x76, + 0xad, 0xb2, 0x46, 0xea, 0x02, 0x16, 0x23, 0x49, 0x09, 0x22, 0x4b, 0xf4, + 0x00, 0x7b, 0x5f, 0x7d, 0x4b, 0xea, 0x08, 0x1b, 0x93, 0xf8, 0x18, 0x80, + 0xfd, 0xf7, 0x04, 0xfa, 0x20, 0x46, 0x2b, 0x46, 0x40, 0xf2, 0xdb, 0x41, + 0x47, 0xf2, 0xff, 0x32, 0xfd, 0xf7, 0xea, 0xf9, 0x20, 0x46, 0x2b, 0x46, + 0x40, 0xf2, 0xdc, 0x41, 0x47, 0xf2, 0xff, 0x32, 0xfd, 0xf7, 0xe2, 0xf9, + 0x46, 0xea, 0x07, 0x36, 0x20, 0x46, 0x2b, 0x46, 0x40, 0xf2, 0x0a, 0x41, + 0x47, 0xf2, 0xff, 0x32, 0xfd, 0xf7, 0xd8, 0xf9, 0x4b, 0xea, 0x08, 0x38, + 0x20, 0x46, 0xb3, 0xb2, 0x40, 0xf2, 0x0b, 0x41, 0x47, 0xf2, 0xff, 0x32, + 0xfd, 0xf7, 0xce, 0xf9, 0x20, 0x46, 0x1f, 0xfa, 0x88, 0xf3, 0x40, 0xf2, + 0x0c, 0x41, 0x47, 0xf2, 0xff, 0x32, 0xfd, 0xf7, 0xc5, 0xf9, 0x20, 0x22, + 0x20, 0x46, 0x82, 0x21, 0x13, 0x46, 0xfd, 0xf7, 0x7d, 0xf9, 0x01, 0x22, + 0x20, 0x46, 0x7c, 0x21, 0x13, 0x46, 0x01, 0xb0, 0xbd, 0xe8, 0xf0, 0x4f, + 0xfd, 0xf7, 0x74, 0xb9, 0xda, 0xe6, 0x01, 0x00, 0x70, 0xb5, 0x06, 0x22, + 0x0d, 0x46, 0x45, 0x49, 0x04, 0x46, 0xfd, 0xf7, 0xbf, 0xf9, 0x00, 0x26, + 0x43, 0x4b, 0x20, 0x46, 0x99, 0x5b, 0xfc, 0xf7, 0x79, 0xff, 0xa8, 0x53, + 0x02, 0x36, 0x18, 0x2e, 0xf6, 0xd1, 0x07, 0x21, 0x01, 0x22, 0x20, 0x46, + 0xfc, 0xf7, 0x87, 0xff, 0x10, 0x22, 0xff, 0x21, 0x13, 0x46, 0x20, 0x46, + 0xfd, 0xf7, 0x56, 0xf9, 0x04, 0x22, 0x13, 0x46, 0x20, 0x46, 0x40, 0xf2, + 0x1f, 0x11, 0xfd, 0xf7, 0x4f, 0xf9, 0x0c, 0x22, 0x20, 0x46, 0x36, 0x49, + 0xfd, 0xf7, 0x9e, 0xf9, 0x01, 0x22, 0x3a, 0x21, 0x13, 0x46, 0x20, 0x46, + 0xfd, 0xf7, 0x44, 0xf9, 0x04, 0x22, 0x3a, 0x21, 0x13, 0x46, 0x20, 0x46, + 0xfd, 0xf7, 0x3e, 0xf9, 0x08, 0x22, 0x13, 0x46, 0x20, 0x46, 0x4f, 0xf4, + 0x8d, 0x71, 0xfd, 0xf7, 0x37, 0xf9, 0x08, 0x22, 0x05, 0x21, 0x13, 0x46, + 0x20, 0x46, 0xfd, 0xf7, 0x31, 0xf9, 0x01, 0x22, 0x13, 0x46, 0x20, 0x46, + 0x4f, 0xf4, 0x8d, 0x71, 0xfd, 0xf7, 0x2a, 0xf9, 0x12, 0x22, 0x20, 0x46, + 0x24, 0x49, 0xfd, 0xf7, 0x79, 0xf9, 0x20, 0x22, 0x82, 0x21, 0x13, 0x46, + 0x20, 0x46, 0xfd, 0xf7, 0x1f, 0xf9, 0xb4, 0xf8, 0xda, 0x30, 0x03, 0xf4, + 0x70, 0x43, 0xb3, 0xf5, 0x00, 0x5f, 0x09, 0xd1, 0xd4, 0xf8, 0xa8, 0x30, + 0x9e, 0x7a, 0xda, 0x7a, 0x46, 0xf4, 0x00, 0x76, 0x46, 0xea, 0x02, 0x16, + 0x1d, 0x7b, 0x01, 0xe0, 0x00, 0x25, 0x2e, 0x46, 0x01, 0x22, 0x20, 0x46, + 0x13, 0x46, 0x4f, 0xf4, 0x9b, 0x61, 0xfd, 0xf7, 0x47, 0xf9, 0x20, 0x46, + 0xb3, 0x00, 0x4f, 0xf4, 0x9b, 0x61, 0x40, 0xf6, 0xfc, 0x72, 0xfd, 0xf7, + 0x3f, 0xf9, 0x02, 0x22, 0x20, 0x46, 0x13, 0x46, 0x4f, 0xf4, 0x9b, 0x61, + 0xfd, 0xf7, 0x38, 0xf9, 0x2b, 0x03, 0x20, 0x46, 0x4f, 0xf4, 0x9b, 0x61, + 0x4f, 0xf4, 0xe0, 0x42, 0x03, 0xf4, 0x70, 0x43, 0xfd, 0xf7, 0x2e, 0xf9, + 0x07, 0x49, 0x20, 0x46, 0x06, 0x22, 0xbd, 0xe8, 0x70, 0x40, 0xfd, 0xf7, + 0x39, 0xb9, 0x00, 0xbf, 0x2c, 0xef, 0x01, 0x00, 0x66, 0xed, 0x01, 0x00, + 0xc2, 0xe7, 0x01, 0x00, 0xda, 0xe7, 0x01, 0x00, 0xfe, 0xe7, 0x01, 0x00, + 0x38, 0xb5, 0xd0, 0xf8, 0xa8, 0x50, 0x04, 0x46, 0xff, 0x22, 0xb5, 0xf8, + 0x66, 0x33, 0x40, 0xf2, 0x34, 0x41, 0xfd, 0xf7, 0x11, 0xf9, 0xb5, 0xf8, + 0x64, 0x33, 0x20, 0x46, 0xff, 0x22, 0x40, 0xf2, 0x23, 0x41, 0xfd, 0xf7, + 0x09, 0xf9, 0x20, 0x46, 0xb5, 0xf8, 0x68, 0x23, 0x4f, 0xf4, 0xaa, 0x61, + 0xfc, 0xf7, 0x1c, 0xff, 0x20, 0x46, 0x04, 0x49, 0x04, 0x22, 0xfd, 0xf7, + 0x0f, 0xf9, 0x14, 0x20, 0xbd, 0xe8, 0x38, 0x40, 0xf2, 0xf3, 0xf4, 0xb4, + 0xe0, 0xea, 0x01, 0x00, 0x2d, 0xe9, 0xf0, 0x47, 0xc3, 0x69, 0xd0, 0xf8, + 0xa8, 0x40, 0x1b, 0x6d, 0x0f, 0x46, 0x40, 0xf2, 0x23, 0x41, 0x03, 0xf4, + 0x80, 0x58, 0x05, 0x46, 0x94, 0xf8, 0x44, 0xa3, 0xfc, 0xf7, 0xf5, 0xfe, + 0x40, 0xf2, 0x34, 0x41, 0x06, 0x46, 0x28, 0x46, 0xfc, 0xf7, 0xef, 0xfe, + 0x38, 0x46, 0xff, 0xf7, 0x45, 0xf8, 0x94, 0xf8, 0x44, 0x23, 0xb8, 0xf1, + 0x00, 0x0f, 0x0c, 0xbf, 0x4f, 0xf0, 0x09, 0x08, 0x4f, 0xf0, 0x06, 0x08, + 0x94, 0xf8, 0x48, 0x33, 0xb4, 0xf8, 0x64, 0x73, 0x00, 0x2a, 0x00, 0xf0, + 0x8c, 0x80, 0xff, 0x1a, 0xf6, 0xb2, 0x3f, 0x18, 0xbf, 0x1b, 0x4f, 0xfa, + 0x87, 0xf9, 0xb9, 0xf1, 0x00, 0x0f, 0x1e, 0xda, 0xeb, 0x69, 0x28, 0x46, + 0x1b, 0x6d, 0x03, 0xf4, 0x80, 0x53, 0x00, 0x2b, 0x14, 0xbf, 0x03, 0x22, + 0x08, 0x22, 0xc9, 0xf1, 0x00, 0x03, 0x0c, 0xbf, 0x0b, 0x21, 0x04, 0x21, + 0x9a, 0x42, 0xa8, 0xbf, 0x1a, 0x46, 0xb4, 0xf8, 0x68, 0x33, 0x01, 0xfb, + 0x02, 0x32, 0x4f, 0xf4, 0xaa, 0x61, 0x92, 0xb2, 0xfc, 0xf7, 0xc4, 0xfe, + 0x19, 0xf1, 0x03, 0x0f, 0x06, 0xda, 0xf2, 0x1c, 0x05, 0xe0, 0xb9, 0xf1, + 0x03, 0x0f, 0x01, 0xdd, 0xf2, 0x1e, 0x00, 0xe0, 0x32, 0x46, 0xb4, 0xf8, + 0x64, 0x33, 0x12, 0xb2, 0x19, 0xb2, 0xc8, 0x1c, 0x82, 0x42, 0x02, 0xdd, + 0x03, 0x33, 0x9b, 0xb2, 0x03, 0xe0, 0x8a, 0x42, 0xb8, 0xbf, 0x0a, 0x46, + 0x93, 0xb2, 0xba, 0xf1, 0x00, 0x0f, 0x12, 0xd0, 0x1a, 0xb2, 0xb2, 0x42, + 0x0f, 0xd0, 0x28, 0x46, 0x40, 0xf2, 0x23, 0x41, 0xff, 0x22, 0xfd, 0xf7, + 0x85, 0xf8, 0x28, 0x46, 0x23, 0x49, 0x04, 0x22, 0xfd, 0xf7, 0x92, 0xf8, + 0x14, 0x20, 0xf2, 0xf3, 0x79, 0xf4, 0x00, 0x26, 0x00, 0xe0, 0x01, 0x26, + 0xb4, 0xf8, 0x66, 0x23, 0x7f, 0xb2, 0x11, 0xb2, 0xc8, 0xeb, 0x01, 0x00, + 0x7f, 0x42, 0x87, 0x42, 0xbb, 0xb2, 0xbc, 0xbf, 0xc8, 0xeb, 0x02, 0x03, + 0x9b, 0xb2, 0x18, 0xb2, 0x09, 0x31, 0x88, 0x42, 0xc8, 0xbf, 0x02, 0xf1, + 0x09, 0x03, 0xb5, 0xf8, 0xda, 0x20, 0xc8, 0xbf, 0x9b, 0xb2, 0x02, 0xf4, + 0x70, 0x42, 0xb2, 0xf5, 0x00, 0x5f, 0x0c, 0xbf, 0x94, 0xf9, 0x4b, 0x83, + 0x94, 0xf9, 0x4c, 0x83, 0x43, 0x44, 0x9b, 0xb2, 0xba, 0xf1, 0x00, 0x0f, + 0x05, 0xd0, 0x28, 0x46, 0x40, 0xf2, 0x34, 0x41, 0xff, 0x22, 0xfd, 0xf7, + 0x4f, 0xf8, 0x28, 0x46, 0x40, 0xf2, 0x23, 0x41, 0xfc, 0xf7, 0x59, 0xfe, + 0x94, 0xf8, 0xbc, 0x33, 0x84, 0xf8, 0xbd, 0x03, 0x84, 0xf8, 0xbe, 0x03, + 0x84, 0xf8, 0xbf, 0x33, 0x00, 0xe0, 0x01, 0x26, 0x30, 0x46, 0xbd, 0xe8, + 0xf0, 0x87, 0x00, 0xbf, 0x34, 0xe7, 0x01, 0x00, 0x2d, 0xe9, 0xf0, 0x41, + 0x04, 0x46, 0x0f, 0x46, 0x90, 0x46, 0x35, 0x49, 0x06, 0x22, 0x1e, 0x46, + 0x06, 0x9d, 0xfd, 0xf7, 0x41, 0xf8, 0x20, 0x46, 0x40, 0xf2, 0x82, 0x41, + 0x4f, 0xf6, 0xff, 0x72, 0x3b, 0x46, 0xfd, 0xf7, 0x27, 0xf8, 0x20, 0x46, + 0x40, 0xf2, 0x81, 0x41, 0xff, 0x22, 0x43, 0x46, 0xfd, 0xf7, 0x20, 0xf8, + 0x3e, 0xb9, 0x20, 0x46, 0x40, 0xf2, 0x81, 0x41, 0x4f, 0xf4, 0x80, 0x72, + 0x33, 0x46, 0xfd, 0xf7, 0x17, 0xf8, 0x20, 0x46, 0x26, 0x49, 0x03, 0x22, + 0xfd, 0xf7, 0x24, 0xf8, 0xbd, 0xf8, 0x1c, 0x30, 0x0a, 0x27, 0x5f, 0x43, + 0x00, 0x26, 0x05, 0xe0, 0xbe, 0x42, 0x36, 0xdc, 0x64, 0x20, 0xf2, 0xf3, + 0x03, 0xf4, 0x01, 0x36, 0x20, 0x46, 0x40, 0xf2, 0x81, 0x41, 0xfc, 0xf7, + 0x10, 0xfe, 0x83, 0x05, 0xf2, 0xd4, 0x40, 0xf2, 0x83, 0x41, 0x20, 0x46, + 0xfc, 0xf7, 0x09, 0xfe, 0x40, 0xf2, 0x84, 0x41, 0x06, 0x46, 0x20, 0x46, + 0xfc, 0xf7, 0x03, 0xfe, 0x40, 0xea, 0x06, 0x40, 0x28, 0x60, 0x40, 0xf2, + 0x85, 0x41, 0x20, 0x46, 0xfc, 0xf7, 0xfb, 0xfd, 0x40, 0xf2, 0x86, 0x41, + 0x06, 0x46, 0x20, 0x46, 0xfc, 0xf7, 0xf5, 0xfd, 0x40, 0xea, 0x06, 0x40, + 0x68, 0x60, 0x40, 0xf2, 0x87, 0x41, 0x20, 0x46, 0xfc, 0xf7, 0xed, 0xfd, + 0x4f, 0xf4, 0x91, 0x61, 0x06, 0x46, 0x20, 0x46, 0xfc, 0xf7, 0xe7, 0xfd, + 0x40, 0xea, 0x06, 0x40, 0xa8, 0x60, 0x01, 0x25, 0x00, 0xe0, 0x00, 0x25, + 0x20, 0x46, 0x05, 0x49, 0x06, 0x22, 0xfc, 0xf7, 0xdf, 0xff, 0x28, 0x46, + 0xbd, 0xe8, 0xf0, 0x81, 0x18, 0xeb, 0x01, 0x00, 0x7e, 0xed, 0x01, 0x00, + 0xa2, 0xe7, 0x01, 0x00, 0x70, 0xb5, 0x40, 0xf2, 0x4a, 0x41, 0x05, 0x46, + 0xfc, 0xf7, 0xcd, 0xfd, 0x40, 0xf0, 0x44, 0x00, 0x86, 0xb2, 0x4f, 0xf6, + 0xbf, 0x74, 0x28, 0x46, 0x32, 0x46, 0x34, 0x40, 0x40, 0xf2, 0x4a, 0x41, + 0xfc, 0xf7, 0xcc, 0xfd, 0x22, 0x46, 0x28, 0x46, 0x40, 0xf2, 0x4a, 0x41, + 0xfc, 0xf7, 0xc6, 0xfd, 0x04, 0x20, 0xf2, 0xf3, 0xa5, 0xf3, 0x4f, 0xf6, + 0xbb, 0x72, 0x28, 0x46, 0x40, 0xf2, 0x4a, 0x41, 0x22, 0x40, 0xbd, 0xe8, + 0x70, 0x40, 0xfc, 0xf7, 0xb9, 0xbd, 0x38, 0xb5, 0x05, 0x46, 0x41, 0xf2, + 0x89, 0x34, 0x04, 0xe0, 0x64, 0x20, 0xf2, 0xf3, 0x93, 0xf3, 0x01, 0x3c, + 0x07, 0xd0, 0x28, 0x46, 0x40, 0xf2, 0x51, 0x41, 0xfc, 0xf7, 0x9f, 0xfd, + 0x10, 0xf4, 0x40, 0x4f, 0xf2, 0xd1, 0x28, 0x46, 0x40, 0xf2, 0x51, 0x41, + 0xfc, 0xf7, 0x97, 0xfd, 0x10, 0xf4, 0x40, 0x4f, 0x14, 0xbf, 0x00, 0x20, + 0x01, 0x20, 0x38, 0xbd, 0x40, 0xf2, 0x4c, 0x41, 0x4f, 0xf6, 0xfc, 0x72, + 0xfc, 0xf7, 0x61, 0xbf, 0x38, 0xb5, 0xc3, 0x69, 0x04, 0x46, 0x0d, 0x46, + 0x18, 0x69, 0x8e, 0x21, 0x3c, 0xf0, 0x3e, 0xdb, 0xe3, 0x69, 0x41, 0x19, + 0x18, 0x69, 0x49, 0x00, 0xbd, 0xe8, 0x38, 0x40, 0x3c, 0xf0, 0x36, 0x9b, + 0x2d, 0xe9, 0xf0, 0x41, 0x0c, 0x46, 0x27, 0x21, 0x05, 0x46, 0x17, 0x46, + 0xff, 0xf7, 0xe8, 0xff, 0x10, 0xf0, 0x01, 0x06, 0x1d, 0xbf, 0x4f, 0xf6, + 0xf0, 0x76, 0x06, 0x40, 0x4f, 0xf6, 0xf0, 0x78, 0x4f, 0xf0, 0x01, 0x08, + 0x28, 0x21, 0x28, 0x46, 0xff, 0xf7, 0xda, 0xff, 0x00, 0xea, 0x08, 0x00, + 0xb0, 0x42, 0x0a, 0xd0, 0x01, 0x3c, 0x63, 0x1c, 0x00, 0x2b, 0x02, 0xdd, + 0x14, 0x20, 0xf2, 0xf3, 0x47, 0xf3, 0x00, 0x2c, 0xee, 0xdc, 0x00, 0x20, + 0x00, 0xe0, 0x01, 0x20, 0x07, 0xb1, 0x3c, 0x60, 0xbd, 0xe8, 0xf0, 0x81, + 0xc3, 0x69, 0x70, 0xb5, 0x04, 0x46, 0x0d, 0x46, 0x18, 0x69, 0x8e, 0x21, + 0x16, 0x46, 0x3c, 0xf0, 0x03, 0xdb, 0xe3, 0x69, 0x41, 0x19, 0x18, 0x69, + 0x49, 0x00, 0x32, 0x46, 0xbd, 0xe8, 0x70, 0x40, 0x3c, 0xf0, 0x18, 0x9b, + 0x70, 0xb5, 0x04, 0x46, 0xd0, 0xf8, 0xa8, 0x50, 0x0e, 0x46, 0x89, 0xb3, + 0x40, 0xf2, 0xda, 0x61, 0x42, 0xf2, 0x08, 0x02, 0xfc, 0xf7, 0x16, 0xff, + 0x20, 0x46, 0x40, 0xf2, 0xa6, 0x51, 0x05, 0x22, 0xfc, 0xf7, 0x38, 0xfd, + 0x20, 0x46, 0x40, 0xf2, 0xa2, 0x51, 0xc3, 0x22, 0xfc, 0xf7, 0x32, 0xfd, + 0x20, 0x46, 0x40, 0xf2, 0xa5, 0x51, 0x07, 0x22, 0xfc, 0xf7, 0x2c, 0xfd, + 0x20, 0x46, 0x40, 0xf2, 0x83, 0x51, 0x4f, 0xf4, 0x48, 0x72, 0xfc, 0xf7, + 0x25, 0xfd, 0x20, 0x46, 0x40, 0xf2, 0x84, 0x51, 0x00, 0x22, 0xfc, 0xf7, + 0x1f, 0xfd, 0x20, 0x46, 0x40, 0xf2, 0x85, 0x51, 0x4f, 0xf4, 0x00, 0x72, + 0xfc, 0xf7, 0x18, 0xfd, 0x20, 0x46, 0x40, 0xf2, 0x86, 0x51, 0x00, 0x22, + 0xfc, 0xf7, 0x12, 0xfd, 0x20, 0x46, 0x27, 0x21, 0xff, 0xf7, 0x78, 0xff, + 0x1e, 0xb1, 0x40, 0xf0, 0x01, 0x06, 0xb6, 0xb2, 0x02, 0xe0, 0x4f, 0xf6, + 0xfe, 0x76, 0x06, 0x40, 0x95, 0xf8, 0x94, 0x33, 0x05, 0x22, 0xed, 0x18, + 0x95, 0xf8, 0x95, 0x33, 0x20, 0x46, 0x5a, 0x43, 0x26, 0x21, 0x04, 0x2a, + 0x98, 0xbf, 0x05, 0x22, 0xff, 0xf7, 0x9c, 0xff, 0x10, 0x36, 0xb6, 0xb2, + 0x20, 0x46, 0x27, 0x21, 0x32, 0x46, 0xbd, 0xe8, 0x70, 0x40, 0xff, 0xf7, + 0x93, 0xbf, 0x70, 0xb5, 0xd0, 0xf8, 0xa8, 0x30, 0x0d, 0x46, 0x00, 0x21, + 0x83, 0xf8, 0x46, 0x13, 0x04, 0x46, 0xff, 0xf7, 0x9b, 0xff, 0x15, 0xb1, + 0x20, 0x46, 0xff, 0xf7, 0xab, 0xfd, 0x03, 0x22, 0x20, 0x46, 0x13, 0x46, + 0x40, 0xf6, 0x7a, 0x01, 0xfc, 0xf7, 0xc0, 0xfe, 0x20, 0x46, 0x40, 0xf2, + 0xda, 0x61, 0x42, 0xf2, 0x08, 0x02, 0x00, 0x23, 0xbd, 0xe8, 0x70, 0x40, + 0xfc, 0xf7, 0xb6, 0xbe, 0x10, 0xb5, 0x00, 0x21, 0x04, 0x46, 0xff, 0xf7, + 0xdc, 0xff, 0x20, 0x46, 0xbd, 0xe8, 0x10, 0x40, 0xfe, 0xf7, 0x44, 0xbe, + 0x70, 0xb5, 0x01, 0x22, 0x04, 0x46, 0x40, 0xf6, 0x05, 0x01, 0xd0, 0xf8, + 0xa8, 0x50, 0xfc, 0xf7, 0x95, 0xfe, 0x20, 0x46, 0x07, 0x22, 0x05, 0x23, + 0x40, 0xf2, 0x2f, 0x41, 0xfc, 0xf7, 0x9c, 0xfe, 0x20, 0x46, 0x30, 0x21, + 0xf8, 0x23, 0x4f, 0xf4, 0xff, 0x62, 0xfc, 0xf7, 0x95, 0xfe, 0x06, 0x23, + 0x20, 0x46, 0x30, 0x21, 0x07, 0x22, 0xfc, 0xf7, 0x8f, 0xfe, 0x20, 0x46, + 0x40, 0xf2, 0x14, 0x41, 0x41, 0xf6, 0x10, 0x62, 0xfc, 0xf7, 0xa2, 0xfc, + 0x20, 0x46, 0x40, 0xf2, 0x15, 0x41, 0x4f, 0xf4, 0xc8, 0x62, 0xfc, 0xf7, + 0x9b, 0xfc, 0x4f, 0xf4, 0x77, 0x43, 0x20, 0x46, 0x40, 0xf2, 0xdf, 0x41, + 0x4f, 0xf4, 0x7f, 0x42, 0xfc, 0xf7, 0x78, 0xfe, 0x20, 0x46, 0xff, 0xf7, + 0xb1, 0xfe, 0x20, 0x46, 0x27, 0x22, 0x0c, 0x49, 0xfc, 0xf7, 0x82, 0xfe, + 0x20, 0x46, 0xff, 0x22, 0xb5, 0xf8, 0xc6, 0x35, 0x40, 0xf2, 0x32, 0x41, + 0xfc, 0xf7, 0x68, 0xfe, 0xb5, 0xf8, 0xc8, 0x35, 0x4f, 0xf4, 0x7f, 0x42, + 0x1b, 0x02, 0x20, 0x46, 0x40, 0xf2, 0x32, 0x41, 0x13, 0x40, 0xbd, 0xe8, + 0x70, 0x40, 0xfc, 0xf7, 0x5b, 0xbe, 0x00, 0xbf, 0x84, 0xed, 0x01, 0x00, + 0x00, 0x29, 0x14, 0xbf, 0x02, 0x23, 0x00, 0x23, 0x10, 0xb5, 0x00, 0x2a, + 0x18, 0xbf, 0x43, 0xf0, 0x01, 0x03, 0x40, 0xf2, 0x4d, 0x41, 0x03, 0x22, + 0x04, 0x46, 0xfc, 0xf7, 0x49, 0xfe, 0x20, 0x46, 0x40, 0xf2, 0x4c, 0x41, + 0x03, 0x22, 0xbd, 0xe8, 0x10, 0x40, 0xfc, 0xf7, 0x33, 0xbe, 0x00, 0x00, + 0x2d, 0xe9, 0xf0, 0x4f, 0x04, 0x46, 0xc5, 0xb0, 0x00, 0x26, 0x01, 0x91, + 0x15, 0x46, 0x43, 0x96, 0x42, 0x96, 0xfc, 0xf7, 0xce, 0xfd, 0xe3, 0x69, + 0x4f, 0xf0, 0x80, 0x51, 0x18, 0x69, 0x0a, 0x46, 0x3c, 0xf0, 0xd8, 0xd9, + 0x05, 0x20, 0xf2, 0xf3, 0x27, 0xf2, 0x33, 0x46, 0x20, 0x46, 0x4f, 0xf4, + 0x89, 0x61, 0x4f, 0xf4, 0x80, 0x42, 0xfc, 0xf7, 0x23, 0xfe, 0x4f, 0xf4, + 0xa8, 0x42, 0x20, 0x46, 0x40, 0xf2, 0x55, 0x41, 0xfc, 0xf7, 0x36, 0xfc, + 0x40, 0xf2, 0x56, 0x41, 0x20, 0x46, 0xfc, 0xf7, 0x26, 0xfc, 0x00, 0xf0, + 0x0f, 0x00, 0x05, 0x28, 0x0c, 0xbf, 0x4f, 0xf4, 0xa8, 0x42, 0x45, 0xf2, + 0x01, 0x42, 0x20, 0x46, 0x40, 0xf2, 0x55, 0x41, 0xfc, 0xf7, 0x24, 0xfc, + 0x00, 0x26, 0x4f, 0xf0, 0xa0, 0x08, 0xb1, 0x46, 0xb2, 0x46, 0x37, 0x46, + 0x40, 0xf2, 0x56, 0x41, 0x20, 0x46, 0xfc, 0xf7, 0x0e, 0xfc, 0x00, 0x09, + 0x4f, 0xea, 0x00, 0x5b, 0x40, 0xf2, 0x57, 0x41, 0x20, 0x46, 0xfc, 0xf7, + 0x06, 0xfc, 0x4f, 0xea, 0x1b, 0x5b, 0xb8, 0xf1, 0x90, 0x0f, 0x4b, 0xea, + 0x00, 0x3b, 0x1f, 0xdc, 0x7f, 0x2e, 0x1d, 0xdc, 0x4f, 0xea, 0x8b, 0x43, + 0x9b, 0x0c, 0xb3, 0xf5, 0x00, 0x5f, 0xc8, 0xbf, 0xa3, 0xf5, 0x80, 0x43, + 0x03, 0xf5, 0x00, 0x62, 0xb2, 0xf5, 0x80, 0x5f, 0x23, 0xd8, 0x02, 0xa9, + 0x21, 0xf8, 0x1a, 0x30, 0x44, 0xa9, 0x01, 0xeb, 0x89, 0x02, 0x52, 0xf8, + 0x08, 0x1c, 0xca, 0x44, 0xcb, 0x18, 0x42, 0xf8, 0x08, 0x3c, 0x8a, 0xf0, + 0x40, 0x0a, 0x89, 0xf0, 0x01, 0x09, 0x01, 0x36, 0x4f, 0xea, 0x1b, 0x3b, + 0x0b, 0xf0, 0x0c, 0x0b, 0x4b, 0xea, 0x07, 0x1b, 0x18, 0xf0, 0x01, 0x0f, + 0x4f, 0xf6, 0xcc, 0x77, 0x0b, 0xea, 0x07, 0x07, 0x02, 0xd0, 0xfb, 0xb2, + 0x40, 0x2b, 0x02, 0xd1, 0xb8, 0xf1, 0x01, 0x08, 0xb8, 0xd1, 0xe3, 0x69, + 0x00, 0x22, 0x18, 0x69, 0x4f, 0xf0, 0x80, 0x51, 0x3c, 0xf0, 0x60, 0xd9, + 0x20, 0x46, 0xfc, 0xf7, 0x50, 0xfd, 0x42, 0x9b, 0x9b, 0x11, 0x42, 0x93, + 0x43, 0x9b, 0x9b, 0x11, 0x80, 0x2e, 0x43, 0x93, 0x24, 0xd1, 0x00, 0x23, + 0x41, 0xa9, 0x18, 0x46, 0x0e, 0xe0, 0x42, 0xea, 0x07, 0x0c, 0x02, 0xac, + 0x34, 0xf9, 0x1c, 0xc0, 0x01, 0x32, 0xc6, 0xeb, 0x0c, 0x04, 0x40, 0x2a, + 0x04, 0xfb, 0x04, 0x00, 0xf3, 0xd1, 0x01, 0x33, 0x02, 0x2b, 0x04, 0xd0, + 0x9f, 0x01, 0x51, 0xf8, 0x04, 0x6f, 0x00, 0x22, 0xeb, 0xe7, 0x01, 0x9c, + 0x28, 0x60, 0x80, 0x09, 0x20, 0x60, 0x06, 0x4b, 0xa0, 0xf5, 0x3a, 0x60, + 0x18, 0x38, 0x98, 0x42, 0x8c, 0xbf, 0x00, 0x20, 0x01, 0x20, 0x00, 0xe0, + 0x00, 0x20, 0x45, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, 0x48, 0xf4, 0xff, 0x0f, + 0x38, 0xb5, 0x04, 0x46, 0x08, 0x46, 0xfe, 0xf7, 0xe3, 0xfc, 0xe3, 0x69, + 0xa0, 0xf1, 0x9d, 0x05, 0xa0, 0x21, 0x18, 0x69, 0x3c, 0xf0, 0x3e, 0xd9, + 0x2a, 0xb2, 0x6f, 0xf0, 0x61, 0x03, 0x9a, 0x42, 0xb8, 0xbf, 0x1a, 0x46, + 0xc1, 0xb2, 0x52, 0xb2, 0x20, 0x46, 0xbd, 0xe8, 0x38, 0x40, 0xfd, 0xf7, + 0xb8, 0xbc, 0x2d, 0xe9, 0xf0, 0x4f, 0x00, 0xf5, 0x82, 0x53, 0x1b, 0x79, + 0xd7, 0xb0, 0x04, 0x46, 0x0d, 0x46, 0xd0, 0xf8, 0xa8, 0x70, 0x00, 0x2b, + 0x00, 0xf0, 0x76, 0x82, 0xc3, 0x69, 0x6a, 0x21, 0x18, 0x69, 0x3c, 0xf0, + 0x1f, 0xd9, 0x40, 0x00, 0x86, 0xb2, 0x00, 0x2e, 0x00, 0xf0, 0x6c, 0x82, + 0x20, 0x46, 0xfe, 0xf7, 0xf4, 0xfc, 0xe3, 0x69, 0x02, 0x46, 0x10, 0xb9, + 0x18, 0x69, 0x31, 0x46, 0x60, 0xe2, 0x18, 0x69, 0x31, 0x46, 0x3c, 0xf0, + 0x0d, 0xd9, 0x01, 0x28, 0x00, 0xf0, 0x5c, 0x82, 0x06, 0xf1, 0x6e, 0x03, + 0x9b, 0xb2, 0x04, 0x93, 0x06, 0xf1, 0xaa, 0x03, 0x06, 0xf1, 0x06, 0x0b, + 0x06, 0xf1, 0x3a, 0x0a, 0x9b, 0xb2, 0x1f, 0xfa, 0x8b, 0xfb, 0x1f, 0xfa, + 0x8a, 0xfa, 0x05, 0x93, 0x00, 0x2d, 0x00, 0xf0, 0x38, 0x82, 0x20, 0x46, + 0x40, 0xf2, 0xf9, 0x41, 0xfc, 0xf7, 0x37, 0xfb, 0x02, 0x07, 0x00, 0xf1, + 0x41, 0x82, 0x06, 0xad, 0xab, 0x1c, 0x01, 0x93, 0x1a, 0xab, 0x02, 0x93, + 0x0d, 0xf1, 0x6a, 0x03, 0x03, 0x93, 0x20, 0x46, 0x00, 0x23, 0x40, 0xf2, + 0x76, 0x41, 0x40, 0xf2, 0xff, 0x12, 0x00, 0x95, 0xfc, 0xf7, 0x5b, 0xfd, + 0x2b, 0x1d, 0x00, 0x93, 0xab, 0x1d, 0x01, 0x93, 0x1b, 0xab, 0x02, 0x93, + 0x0d, 0xf1, 0x6e, 0x03, 0x03, 0x93, 0x20, 0x46, 0x00, 0x23, 0x40, 0xf2, + 0x77, 0x41, 0x40, 0xf2, 0xff, 0x12, 0xfc, 0xf7, 0x4a, 0xfd, 0x05, 0xf1, + 0x08, 0x03, 0x00, 0x93, 0x05, 0xf1, 0x0a, 0x03, 0x01, 0x93, 0x1c, 0xab, + 0x02, 0x93, 0x0d, 0xf1, 0x72, 0x03, 0x03, 0x93, 0x20, 0x46, 0x40, 0xf2, + 0xaa, 0x41, 0x48, 0xf2, 0xff, 0x12, 0x48, 0xf2, 0x7f, 0x03, 0xfc, 0xf7, + 0x36, 0xfd, 0x05, 0xf1, 0x0c, 0x03, 0x00, 0x93, 0x05, 0xf1, 0x0e, 0x03, + 0x01, 0x93, 0x1d, 0xab, 0x16, 0x22, 0x02, 0x93, 0x0d, 0xf1, 0x76, 0x03, + 0x03, 0x93, 0x20, 0x46, 0x13, 0x46, 0x40, 0xf2, 0x3b, 0x41, 0xfc, 0xf7, + 0x24, 0xfd, 0x05, 0xf1, 0x10, 0x03, 0x00, 0x93, 0x05, 0xf1, 0x12, 0x03, + 0x01, 0x93, 0x1e, 0xab, 0x02, 0x93, 0x0d, 0xf1, 0x7a, 0x03, 0x46, 0x22, + 0x03, 0x93, 0x20, 0x46, 0x00, 0x23, 0x40, 0xf2, 0x3c, 0x41, 0xfc, 0xf7, + 0x12, 0xfd, 0xb4, 0xf8, 0xda, 0x30, 0x05, 0xf1, 0x14, 0x02, 0x03, 0xf4, + 0x70, 0x43, 0xb3, 0xf5, 0x00, 0x5f, 0x05, 0xf1, 0x16, 0x03, 0x8d, 0xe8, + 0x0c, 0x00, 0x1f, 0xab, 0x02, 0x93, 0x41, 0xf2, 0x2b, 0x02, 0x0d, 0xf1, + 0x7e, 0x03, 0x03, 0x93, 0x20, 0x46, 0x40, 0xf2, 0x4c, 0x41, 0x13, 0x46, + 0x37, 0xd1, 0xfc, 0xf7, 0xf8, 0xfc, 0x05, 0xf1, 0x18, 0x03, 0x00, 0x93, + 0x05, 0xf1, 0x1a, 0x03, 0x01, 0x93, 0x20, 0xab, 0x02, 0x93, 0x0d, 0xf1, + 0x82, 0x03, 0x03, 0x93, 0x20, 0x46, 0x40, 0xf2, 0x4d, 0x41, 0x44, 0xf2, + 0x2b, 0x02, 0x44, 0xf2, 0x0a, 0x03, 0xfc, 0xf7, 0xe4, 0xfc, 0x05, 0xf1, + 0x1c, 0x03, 0x00, 0x93, 0x05, 0xf1, 0x1e, 0x03, 0x01, 0x93, 0x21, 0xab, + 0x07, 0x22, 0x02, 0x93, 0x0d, 0xf1, 0x86, 0x03, 0x03, 0x93, 0x20, 0x46, + 0x13, 0x46, 0x40, 0xf2, 0xf9, 0x41, 0xfc, 0xf7, 0xd2, 0xfc, 0x05, 0xf1, + 0x20, 0x03, 0x00, 0x93, 0x22, 0xab, 0x22, 0x35, 0x02, 0x93, 0x07, 0x22, + 0x0d, 0xf1, 0x8a, 0x03, 0x03, 0x93, 0x01, 0x95, 0x20, 0x46, 0x40, 0xf2, + 0xfa, 0x41, 0x13, 0x46, 0x36, 0xe0, 0xfc, 0xf7, 0xc0, 0xfc, 0x05, 0xf1, + 0x18, 0x03, 0x00, 0x93, 0x05, 0xf1, 0x1a, 0x03, 0x01, 0x93, 0x20, 0xab, + 0x02, 0x93, 0x0d, 0xf1, 0x82, 0x03, 0x03, 0x93, 0x20, 0x46, 0x40, 0xf2, + 0x4d, 0x41, 0x44, 0xf2, 0x2b, 0x02, 0x44, 0xf2, 0x22, 0x03, 0xfc, 0xf7, + 0xac, 0xfc, 0x05, 0xf1, 0x1c, 0x03, 0x00, 0x93, 0x05, 0xf1, 0x1e, 0x03, + 0x01, 0x93, 0x21, 0xab, 0x07, 0x22, 0x02, 0x93, 0x0d, 0xf1, 0x86, 0x03, + 0x03, 0x93, 0x20, 0x46, 0x13, 0x46, 0x40, 0xf2, 0xf9, 0x41, 0xfc, 0xf7, + 0x9a, 0xfc, 0x05, 0xf1, 0x20, 0x03, 0x00, 0x93, 0x22, 0xab, 0x22, 0x35, + 0x02, 0x93, 0x0d, 0xf1, 0x8a, 0x03, 0x03, 0x93, 0x01, 0x95, 0x20, 0x46, + 0x40, 0xf2, 0xfa, 0x41, 0x07, 0x22, 0x00, 0x23, 0xfc, 0xf7, 0x89, 0xfc, + 0x2e, 0xab, 0x00, 0x93, 0x0d, 0xf1, 0xba, 0x03, 0x01, 0x93, 0x42, 0xab, + 0x01, 0x22, 0x02, 0x93, 0x0d, 0xf5, 0x85, 0x73, 0x03, 0x93, 0x20, 0x46, + 0x13, 0x46, 0x07, 0x21, 0xfc, 0xf7, 0x02, 0xfc, 0x2f, 0xab, 0x00, 0x93, + 0x0d, 0xf1, 0xbe, 0x03, 0x01, 0x93, 0x43, 0xab, 0x10, 0x22, 0x02, 0x93, + 0x0d, 0xf5, 0x87, 0x73, 0x03, 0x93, 0x20, 0x46, 0x13, 0x46, 0xff, 0x21, + 0xfc, 0xf7, 0xf2, 0xfb, 0x30, 0xab, 0x00, 0x93, 0x0d, 0xf1, 0xc2, 0x03, + 0x01, 0x93, 0x44, 0xab, 0x04, 0x22, 0x02, 0x93, 0x0d, 0xf5, 0x89, 0x73, + 0x03, 0x93, 0x20, 0x46, 0x13, 0x46, 0x40, 0xf2, 0x1f, 0x11, 0xfc, 0xf7, + 0xe1, 0xfb, 0x0f, 0xab, 0x00, 0x93, 0x0d, 0xf1, 0x3e, 0x03, 0x01, 0x93, + 0x23, 0xab, 0x40, 0xf6, 0x44, 0x02, 0x02, 0x93, 0x0d, 0xf1, 0x8e, 0x03, + 0x03, 0x93, 0x20, 0x46, 0x13, 0x46, 0x40, 0xf6, 0x38, 0x11, 0xfc, 0xf7, + 0x46, 0xfc, 0x10, 0xab, 0x00, 0x93, 0x0d, 0xf1, 0x42, 0x03, 0x01, 0x93, + 0x24, 0xab, 0x02, 0x93, 0x0d, 0xf1, 0x92, 0x03, 0x03, 0x93, 0x20, 0x46, + 0x40, 0xf6, 0x39, 0x11, 0x40, 0xf6, 0x44, 0x02, 0x40, 0xf6, 0x04, 0x03, + 0xfc, 0xf7, 0x33, 0xfc, 0x31, 0xab, 0x00, 0x93, 0x0d, 0xf1, 0xc6, 0x03, + 0x01, 0x93, 0x45, 0xab, 0x01, 0x22, 0x02, 0x93, 0x0d, 0xf5, 0x8b, 0x73, + 0x03, 0x93, 0x20, 0x46, 0x13, 0x46, 0x3a, 0x21, 0xfc, 0xf7, 0xac, 0xfb, + 0x32, 0xab, 0x00, 0x93, 0x0d, 0xf1, 0xca, 0x03, 0x01, 0x93, 0x46, 0xab, + 0x08, 0x22, 0x02, 0x93, 0x0d, 0xf5, 0x8d, 0x73, 0x03, 0x93, 0x20, 0x46, + 0x13, 0x46, 0x4f, 0xf4, 0x8d, 0x71, 0xfc, 0xf7, 0x9b, 0xfb, 0x33, 0xab, + 0x00, 0x93, 0x0d, 0xf1, 0xce, 0x03, 0x01, 0x93, 0x47, 0xab, 0x08, 0x22, + 0x02, 0x93, 0x0d, 0xf5, 0x8f, 0x73, 0x03, 0x93, 0x20, 0x46, 0x13, 0x46, + 0x05, 0x21, 0xfc, 0xf7, 0x8b, 0xfb, 0x34, 0xab, 0x00, 0x93, 0x0d, 0xf1, + 0xd2, 0x03, 0x01, 0x93, 0x48, 0xab, 0x04, 0x22, 0x02, 0x93, 0x0d, 0xf5, + 0x91, 0x73, 0x03, 0x93, 0x20, 0x46, 0x13, 0x46, 0x3a, 0x21, 0xfc, 0xf7, + 0x7b, 0xfb, 0x35, 0xab, 0x00, 0x93, 0x0d, 0xf1, 0xd6, 0x03, 0x01, 0x93, + 0x49, 0xab, 0x01, 0x22, 0x02, 0x93, 0x0d, 0xf5, 0x93, 0x73, 0x03, 0x93, + 0x20, 0x46, 0x13, 0x46, 0x4f, 0xf4, 0x8d, 0x71, 0xfc, 0xf7, 0x6a, 0xfb, + 0x11, 0xab, 0x00, 0x93, 0x0d, 0xf1, 0x46, 0x03, 0x01, 0x93, 0x25, 0xab, + 0x02, 0x93, 0x0d, 0xf1, 0x96, 0x03, 0x03, 0x93, 0x20, 0x46, 0x40, 0xf2, + 0xd7, 0x41, 0x47, 0xf2, 0xcb, 0x02, 0x42, 0xf2, 0x4b, 0x03, 0xfc, 0xf7, + 0xce, 0xfb, 0x36, 0xab, 0x00, 0x93, 0x0d, 0xf1, 0xda, 0x03, 0x01, 0x93, + 0x4a, 0xab, 0x20, 0x22, 0x02, 0x93, 0x0d, 0xf5, 0x95, 0x73, 0x03, 0x93, + 0x20, 0x46, 0x13, 0x46, 0x82, 0x21, 0xfc, 0xf7, 0x47, 0xfb, 0x3a, 0x7b, + 0xbb, 0x7a, 0xf9, 0x7a, 0x12, 0x03, 0x43, 0xf4, 0x00, 0x73, 0x42, 0xf0, + 0x03, 0x02, 0x43, 0xea, 0x01, 0x13, 0x42, 0xea, 0x83, 0x03, 0x12, 0xaa, + 0x00, 0x92, 0x0d, 0xf1, 0x4a, 0x02, 0x01, 0x92, 0x26, 0xaa, 0x02, 0x92, + 0x0d, 0xf1, 0x9a, 0x02, 0x03, 0x92, 0x20, 0x46, 0x4f, 0xf4, 0x9b, 0x61, + 0x47, 0xf6, 0xff, 0x72, 0x9b, 0xb2, 0xfc, 0xf7, 0xa0, 0xfb, 0x00, 0x25, + 0xe3, 0x69, 0x0d, 0xf1, 0x18, 0x09, 0x18, 0x69, 0x05, 0xeb, 0x0b, 0x01, + 0x39, 0xf8, 0x05, 0x20, 0x3b, 0xf0, 0x36, 0xdf, 0xe3, 0x69, 0x0d, 0xf1, + 0x68, 0x08, 0x18, 0x69, 0x05, 0xeb, 0x0a, 0x01, 0x38, 0xf8, 0x05, 0x20, + 0x3b, 0xf0, 0x2c, 0xdf, 0xe2, 0x69, 0x09, 0xeb, 0x05, 0x03, 0x0b, 0xf1, + 0x02, 0x01, 0x10, 0x69, 0x49, 0x19, 0x5a, 0x88, 0x3b, 0xf0, 0x22, 0xdf, + 0xe2, 0x69, 0x08, 0xeb, 0x05, 0x03, 0x0a, 0xf1, 0x02, 0x01, 0x10, 0x69, + 0x49, 0x19, 0x5a, 0x88, 0x04, 0x35, 0x3b, 0xf0, 0x17, 0xdf, 0x34, 0x2d, + 0xd4, 0xd1, 0x00, 0x25, 0xe3, 0x69, 0x04, 0x9a, 0x0d, 0xf1, 0xb8, 0x09, + 0xa9, 0x18, 0x18, 0x69, 0x39, 0xf8, 0x05, 0x20, 0x3b, 0xf0, 0x0a, 0xdf, + 0xe3, 0x69, 0x0d, 0xf5, 0x84, 0x78, 0x18, 0x69, 0x05, 0x9b, 0x38, 0xf8, + 0x05, 0x20, 0xe9, 0x18, 0x3b, 0xf0, 0x00, 0xdf, 0x04, 0x9b, 0xe2, 0x69, + 0x99, 0x1c, 0x09, 0xeb, 0x05, 0x03, 0x10, 0x69, 0x49, 0x19, 0x5a, 0x88, + 0x3b, 0xf0, 0xf6, 0xde, 0x05, 0x9b, 0xe2, 0x69, 0x99, 0x1c, 0x08, 0xeb, + 0x05, 0x03, 0x10, 0x69, 0x49, 0x19, 0x5a, 0x88, 0x04, 0x35, 0x3b, 0xf0, + 0xeb, 0xde, 0x24, 0x2d, 0xd4, 0xd1, 0xe3, 0x69, 0xb1, 0x1c, 0x18, 0x69, + 0x0d, 0x22, 0x3b, 0xf0, 0xe3, 0xde, 0xe3, 0x69, 0x31, 0x1d, 0x18, 0x69, + 0x09, 0x22, 0x3b, 0xf0, 0xdd, 0xde, 0xe3, 0x69, 0x06, 0xf1, 0xe6, 0x01, + 0x1a, 0x6a, 0x18, 0x69, 0xc7, 0xf8, 0x38, 0x24, 0xb7, 0xf8, 0x3c, 0x24, + 0x3b, 0xf0, 0xd2, 0xde, 0xe3, 0x69, 0x31, 0x46, 0x18, 0x69, 0x01, 0x22, + 0x3b, 0xf0, 0xcc, 0xde, 0x57, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, 0x00, 0x00, + 0x38, 0xb5, 0x5b, 0x21, 0x04, 0x46, 0xfd, 0x22, 0xfc, 0xf7, 0x7b, 0xfa, + 0x20, 0x46, 0x04, 0x21, 0x40, 0x22, 0xfc, 0xf7, 0x84, 0xfa, 0x20, 0x46, + 0x4f, 0xf4, 0x90, 0x71, 0x10, 0x22, 0xfc, 0xf7, 0x7e, 0xfa, 0x20, 0x46, + 0x78, 0x21, 0x80, 0x22, 0xfc, 0xf7, 0x79, 0xfa, 0x20, 0x46, 0x40, 0xf2, + 0x29, 0x11, 0x02, 0x22, 0xfc, 0xf7, 0x73, 0xfa, 0x20, 0x46, 0x57, 0x21, + 0x01, 0x22, 0xfc, 0xf7, 0x6e, 0xfa, 0x20, 0x46, 0x5b, 0x21, 0x02, 0x22, + 0xfc, 0xf7, 0x69, 0xfa, 0x41, 0xf2, 0x88, 0x30, 0xf1, 0xf3, 0xb2, 0xf6, + 0x14, 0x4d, 0x02, 0xe0, 0x0a, 0x20, 0xf1, 0xf3, 0xad, 0xf6, 0x5c, 0x21, + 0x20, 0x46, 0xfc, 0xf7, 0x7f, 0xf8, 0x80, 0x06, 0x01, 0xd4, 0x01, 0x3d, + 0xf4, 0xd1, 0x5c, 0x21, 0x20, 0x46, 0xfc, 0xf7, 0x77, 0xf8, 0x81, 0x06, + 0x03, 0xd5, 0x20, 0x46, 0x5c, 0x21, 0xfc, 0xf7, 0x71, 0xf8, 0x20, 0x46, + 0x5b, 0x21, 0xfd, 0x22, 0xfc, 0xf7, 0x3b, 0xfa, 0x20, 0x46, 0x57, 0x21, + 0xfe, 0x22, 0xfc, 0xf7, 0x36, 0xfa, 0x20, 0x46, 0x40, 0xf2, 0x29, 0x11, + 0xfd, 0x22, 0xbd, 0xe8, 0x38, 0x40, 0xfc, 0xf7, 0x2e, 0xba, 0x00, 0xbf, + 0x41, 0x42, 0x0f, 0x00, 0x2d, 0xe9, 0xf8, 0x43, 0x00, 0xf5, 0x80, 0x53, + 0x9d, 0x6a, 0x88, 0x4b, 0x4f, 0xf4, 0x84, 0x76, 0xb5, 0xfb, 0xf3, 0xf5, + 0x75, 0x43, 0x1a, 0x23, 0x57, 0x21, 0xb5, 0xfb, 0xf3, 0xf5, 0x04, 0x46, + 0xfc, 0xf7, 0x4a, 0xf8, 0x17, 0x21, 0x5f, 0xfa, 0x80, 0xf8, 0x20, 0x46, + 0xfc, 0xf7, 0x44, 0xf8, 0x18, 0x21, 0x20, 0x46, 0xfc, 0xf7, 0x40, 0xf8, + 0x40, 0xf2, 0x05, 0x11, 0xfb, 0x22, 0x07, 0x46, 0x20, 0x46, 0xfc, 0xf7, + 0x08, 0xfa, 0x20, 0x46, 0x04, 0x21, 0x40, 0x22, 0xfc, 0xf7, 0x11, 0xfa, + 0x20, 0x46, 0x4f, 0xf4, 0x90, 0x71, 0x10, 0x22, 0xfc, 0xf7, 0x0b, 0xfa, + 0x20, 0x46, 0x57, 0x21, 0x02, 0x22, 0xfc, 0xf7, 0x06, 0xfa, 0x20, 0x46, + 0x40, 0xf2, 0x05, 0x11, 0x04, 0x22, 0xfc, 0xf7, 0x00, 0xfa, 0x20, 0x46, + 0x4f, 0xf4, 0x83, 0x71, 0x2a, 0x22, 0xfc, 0xf7, 0x34, 0xf8, 0xad, 0xb2, + 0x20, 0x46, 0x40, 0xf2, 0x07, 0x11, 0x6e, 0x22, 0xfc, 0xf7, 0x2d, 0xf8, + 0xea, 0xb2, 0x20, 0x46, 0x31, 0x46, 0xfc, 0xf7, 0x28, 0xf8, 0x2a, 0x0a, + 0x20, 0x46, 0x40, 0xf2, 0x09, 0x11, 0x02, 0xf0, 0x1f, 0x02, 0xfc, 0xf7, + 0x20, 0xf8, 0x20, 0x46, 0x40, 0xf2, 0x05, 0x11, 0xfd, 0x22, 0xfc, 0xf7, + 0xd2, 0xf9, 0x20, 0x46, 0x4f, 0xf4, 0x83, 0x71, 0x01, 0x22, 0xfc, 0xf7, + 0xda, 0xf9, 0x32, 0x20, 0xf1, 0xf3, 0x24, 0xf6, 0x5a, 0x4d, 0x02, 0xe0, + 0x0a, 0x20, 0xf1, 0xf3, 0x1f, 0xf6, 0x20, 0x46, 0x4f, 0xf4, 0x85, 0x71, + 0xfb, 0xf7, 0xf0, 0xff, 0xc2, 0x07, 0x01, 0xd4, 0x01, 0x3d, 0xf3, 0xd1, + 0x20, 0x46, 0x4f, 0xf4, 0x85, 0x71, 0xfb, 0xf7, 0xe7, 0xff, 0x10, 0xf0, + 0x01, 0x0f, 0x20, 0x46, 0x06, 0xd1, 0xfa, 0xb2, 0x18, 0x21, 0x0b, 0x25, + 0xfc, 0xf7, 0xbb, 0xf9, 0x2f, 0x46, 0x0a, 0xe0, 0x40, 0xf2, 0x0f, 0x11, + 0xfb, 0xf7, 0xd8, 0xff, 0x00, 0xf0, 0x1f, 0x05, 0x1d, 0x2d, 0x01, 0xd8, + 0xaf, 0x1c, 0x00, 0xe0, 0x0b, 0x27, 0x19, 0x21, 0x20, 0x46, 0xfb, 0xf7, + 0xcd, 0xff, 0x4f, 0xf4, 0x83, 0x71, 0xfe, 0x22, 0x06, 0x46, 0x20, 0x46, + 0xfc, 0xf7, 0x95, 0xf9, 0x20, 0x46, 0x40, 0xf2, 0x05, 0x11, 0xfb, 0x22, + 0xfc, 0xf7, 0x8f, 0xf9, 0x20, 0x46, 0x40, 0xf2, 0x05, 0x11, 0x04, 0x22, + 0xfc, 0xf7, 0x97, 0xf9, 0x20, 0x46, 0x40, 0xf2, 0x05, 0x11, 0x02, 0x22, + 0xfc, 0xf7, 0x91, 0xf9, 0x20, 0x46, 0x4f, 0xf4, 0x83, 0x71, 0x01, 0x22, + 0xfc, 0xf7, 0x8b, 0xf9, 0x32, 0x20, 0xf1, 0xf3, 0xd5, 0xf5, 0xdf, 0xf8, + 0xcc, 0x90, 0x02, 0xe0, 0x0a, 0x20, 0xf1, 0xf3, 0xcf, 0xf5, 0x20, 0x46, + 0x4f, 0xf4, 0x85, 0x71, 0xfb, 0xf7, 0xa0, 0xff, 0xc3, 0x07, 0x02, 0xd4, + 0xb9, 0xf1, 0x01, 0x09, 0xf2, 0xd1, 0x20, 0x46, 0x4f, 0xf4, 0x85, 0x71, + 0xfb, 0xf7, 0x96, 0xff, 0x10, 0xf0, 0x01, 0x0f, 0x20, 0x46, 0x05, 0xd1, + 0xf2, 0xb2, 0x19, 0x21, 0xfb, 0xf7, 0xa5, 0xff, 0x09, 0x26, 0x05, 0xe0, + 0x4f, 0xf4, 0x88, 0x71, 0xfb, 0xf7, 0x88, 0xff, 0x00, 0xf0, 0x1f, 0x06, + 0x20, 0x46, 0xfe, 0x22, 0x4f, 0xf4, 0x83, 0x71, 0xfc, 0xf7, 0x4f, 0xf9, + 0x20, 0x46, 0xfb, 0x22, 0x40, 0xf2, 0x05, 0x11, 0xfc, 0xf7, 0x49, 0xf9, + 0x42, 0x46, 0x4f, 0xea, 0x46, 0x18, 0x48, 0xea, 0x86, 0x28, 0x48, 0xea, + 0x06, 0x08, 0x20, 0x46, 0x57, 0x21, 0xfb, 0xf7, 0x86, 0xff, 0x20, 0x46, + 0x42, 0x46, 0x40, 0xf6, 0x33, 0x11, 0xfb, 0xf7, 0xb1, 0xff, 0x42, 0x46, + 0x4f, 0xea, 0x85, 0x28, 0x20, 0x46, 0x48, 0xea, 0x45, 0x18, 0x40, 0xf6, + 0x34, 0x11, 0xfb, 0xf7, 0xa7, 0xff, 0x20, 0x46, 0x46, 0xea, 0x08, 0x02, + 0x40, 0xf6, 0x35, 0x11, 0xfb, 0xf7, 0xa0, 0xff, 0x20, 0x46, 0x48, 0xea, + 0x05, 0x02, 0x40, 0xf6, 0x36, 0x11, 0xfb, 0xf7, 0x99, 0xff, 0x47, 0xea, + 0x47, 0x17, 0xfa, 0x05, 0x20, 0x46, 0x40, 0xf6, 0x37, 0x11, 0xd2, 0x0d, + 0xbd, 0xe8, 0xf8, 0x43, 0xfb, 0xf7, 0x8e, 0xbf, 0x40, 0x42, 0x0f, 0x00, + 0x41, 0x42, 0x0f, 0x00, 0x70, 0xb5, 0x04, 0x46, 0x0e, 0x46, 0x00, 0x25, + 0x6b, 0x4b, 0x20, 0x46, 0x59, 0x5b, 0xfb, 0xf7, 0x39, 0xff, 0x70, 0x53, + 0x02, 0x35, 0x30, 0x2d, 0xf6, 0xd1, 0x18, 0x22, 0x20, 0x46, 0x67, 0x49, + 0xfc, 0xf7, 0x70, 0xf9, 0x3a, 0x21, 0xfb, 0x22, 0x20, 0x46, 0xfc, 0xf7, + 0xfa, 0xf8, 0x01, 0x22, 0x20, 0x46, 0x4f, 0xf4, 0x8d, 0x71, 0xfc, 0xf7, + 0x02, 0xf9, 0x36, 0x21, 0x01, 0x22, 0x20, 0x46, 0xfc, 0xf7, 0xfd, 0xf8, + 0x10, 0x22, 0x4f, 0xf4, 0x8d, 0x71, 0x20, 0x46, 0xfc, 0xf7, 0xf7, 0xf8, + 0x14, 0x20, 0xf1, 0xf3, 0x41, 0xf5, 0x3a, 0x21, 0x01, 0x22, 0x20, 0x46, + 0xfc, 0xf7, 0xef, 0xf8, 0x14, 0x20, 0xf1, 0xf3, 0x39, 0xf5, 0xb4, 0xf8, + 0xda, 0x30, 0x3a, 0x21, 0x03, 0xf4, 0x70, 0x43, 0x01, 0x22, 0xb3, 0xf5, + 0x00, 0x5f, 0x20, 0x46, 0x05, 0xd0, 0x00, 0x23, 0xfc, 0xf7, 0xee, 0xf8, + 0x20, 0x46, 0xca, 0x21, 0x04, 0x22, 0x13, 0x46, 0xfc, 0xf7, 0xe8, 0xf8, + 0x08, 0x22, 0x20, 0x46, 0x4f, 0xf4, 0x8d, 0x71, 0xfc, 0xf7, 0xd3, 0xf8, + 0x25, 0x21, 0x0e, 0x22, 0x20, 0x46, 0xfb, 0xf7, 0x08, 0xff, 0x25, 0x21, + 0x01, 0x22, 0x20, 0x46, 0xfc, 0xf7, 0xc9, 0xf8, 0xb4, 0xf8, 0xda, 0x30, + 0x28, 0x21, 0x03, 0xf4, 0x70, 0x43, 0x1e, 0x22, 0xb3, 0xf5, 0x80, 0x5f, + 0x20, 0x46, 0x01, 0xd1, 0x08, 0x23, 0x00, 0xe0, 0x0c, 0x23, 0xfc, 0xf7, + 0xc9, 0xf8, 0x14, 0x20, 0xf1, 0xf3, 0x04, 0xf5, 0x05, 0x21, 0x08, 0x22, + 0x20, 0x46, 0xfb, 0xf7, 0xec, 0xfe, 0x80, 0x22, 0x4f, 0xf4, 0x89, 0x71, + 0x20, 0x46, 0xfc, 0xf7, 0xac, 0xf8, 0x14, 0x20, 0xf1, 0xf3, 0xf6, 0xf4, + 0xff, 0x21, 0x10, 0x22, 0x20, 0x46, 0xfc, 0xf7, 0xa4, 0xf8, 0x44, 0x22, + 0x40, 0xf2, 0x1f, 0x11, 0x20, 0x46, 0xfc, 0xf7, 0x9e, 0xf8, 0x14, 0x20, + 0xf1, 0xf3, 0xe8, 0xf4, 0x0b, 0x21, 0x07, 0x22, 0x20, 0x46, 0xfc, 0xf7, + 0x96, 0xf8, 0x10, 0x22, 0x40, 0xf2, 0x13, 0x11, 0x20, 0x46, 0xfc, 0xf7, + 0x90, 0xf8, 0x14, 0x20, 0xf1, 0xf3, 0xda, 0xf4, 0x07, 0x21, 0x01, 0x22, + 0x20, 0x46, 0xfb, 0xf7, 0xc2, 0xfe, 0x14, 0x20, 0xf1, 0xf3, 0xd2, 0xf4, + 0x02, 0x23, 0x03, 0x22, 0x20, 0x46, 0xfc, 0x21, 0xfc, 0xf7, 0x8e, 0xf8, + 0xfd, 0x21, 0x20, 0x46, 0xa6, 0x22, 0xfb, 0xf7, 0xb4, 0xfe, 0x44, 0x22, + 0x40, 0xf2, 0x1f, 0x11, 0x20, 0x46, 0xfc, 0xf7, 0x74, 0xf8, 0x14, 0x20, + 0xf1, 0xf3, 0xbe, 0xf4, 0xff, 0x21, 0x10, 0x22, 0x20, 0x46, 0xfc, 0xf7, + 0x6c, 0xf8, 0x14, 0x20, 0xf1, 0xf3, 0xb6, 0xf4, 0xb4, 0xf8, 0xda, 0x30, + 0x20, 0x46, 0x03, 0xf4, 0x70, 0x43, 0xb3, 0xf5, 0x80, 0x5f, 0x02, 0xd1, + 0x10, 0x49, 0x08, 0x22, 0x01, 0xe0, 0x10, 0x49, 0x06, 0x22, 0xfc, 0xf7, + 0xbd, 0xf8, 0x20, 0x46, 0x59, 0x21, 0xcc, 0x22, 0xfb, 0xf7, 0x8f, 0xfe, + 0x20, 0x46, 0x5c, 0x21, 0x2e, 0x22, 0xfb, 0xf7, 0x8a, 0xfe, 0x20, 0x46, + 0x78, 0x21, 0xd7, 0x22, 0xfb, 0xf7, 0x85, 0xfe, 0x20, 0x46, 0x92, 0x21, + 0x15, 0x22, 0xbd, 0xe8, 0x70, 0x40, 0xfb, 0xf7, 0x7e, 0xbe, 0x00, 0xbf, + 0xe8, 0xea, 0x01, 0x00, 0x56, 0xe7, 0x01, 0x00, 0x86, 0xe7, 0x01, 0x00, + 0x96, 0xe7, 0x01, 0x00, 0x2d, 0xe9, 0xf0, 0x4f, 0x00, 0x27, 0x89, 0xb0, + 0x89, 0x46, 0x40, 0xf2, 0x45, 0x61, 0x06, 0x46, 0x05, 0x97, 0x06, 0x97, + 0x07, 0x97, 0xd0, 0xf8, 0xa8, 0x80, 0xfb, 0xf7, 0x8c, 0xfe, 0x40, 0xf2, + 0x46, 0x61, 0x85, 0x05, 0x30, 0x46, 0xfb, 0xf7, 0x86, 0xfe, 0x3c, 0x49, + 0x84, 0x05, 0x06, 0x22, 0x30, 0x46, 0xfc, 0xf7, 0x83, 0xf8, 0x30, 0x46, + 0x39, 0x46, 0x3a, 0x46, 0xfe, 0xf7, 0x63, 0xfa, 0x05, 0xab, 0x00, 0x93, + 0x4f, 0xf4, 0xfa, 0x73, 0x01, 0x93, 0x49, 0x46, 0x30, 0x46, 0x20, 0x22, + 0x3b, 0x46, 0xff, 0xf7, 0x27, 0xf8, 0xad, 0x0d, 0xa4, 0x0d, 0x81, 0x46, + 0x00, 0x28, 0x47, 0xd0, 0x05, 0xab, 0x93, 0xe8, 0x08, 0x0c, 0x0b, 0xeb, + 0x0a, 0x02, 0x01, 0x2a, 0x3f, 0xd9, 0x18, 0x46, 0x03, 0x93, 0xfd, 0xf7, + 0x73, 0xf9, 0x04, 0x46, 0x58, 0x46, 0xfd, 0xf7, 0x6f, 0xf9, 0xa4, 0xf1, + 0x14, 0x02, 0x12, 0xb2, 0xba, 0x42, 0x03, 0x9b, 0x06, 0xdb, 0x3a, 0xfa, + 0x02, 0xf1, 0x3e, 0xd0, 0x55, 0x1c, 0x2a, 0xfa, 0x05, 0xf5, 0x06, 0xe0, + 0x51, 0x42, 0x1a, 0xfa, 0x01, 0xf1, 0x36, 0xd0, 0xd5, 0x43, 0x0a, 0xfa, + 0x05, 0xf5, 0x24, 0xb2, 0xc4, 0xf1, 0x1e, 0x04, 0xa3, 0x40, 0xa0, 0xf1, + 0x0b, 0x07, 0x3f, 0xb2, 0x00, 0x2f, 0xc3, 0xeb, 0x05, 0x05, 0x02, 0xdb, + 0x3a, 0xfa, 0x07, 0xfa, 0x02, 0xe0, 0x7f, 0x42, 0x1a, 0xfa, 0x07, 0xfa, + 0x23, 0xd0, 0x00, 0xb2, 0xc0, 0xf1, 0x1f, 0x00, 0x0b, 0xfa, 0x00, 0xfb, + 0x95, 0xfb, 0xf1, 0xf5, 0x9b, 0xfb, 0xfa, 0xfa, 0x05, 0xfb, 0x15, 0xa0, + 0xfd, 0xf7, 0x49, 0xf9, 0xad, 0x05, 0x84, 0x05, 0xad, 0x0d, 0xa4, 0x0d, + 0x00, 0xe0, 0xb9, 0x46, 0x30, 0x46, 0x29, 0x46, 0x22, 0x46, 0xfe, 0xf7, + 0x06, 0xfa, 0x30, 0x46, 0x08, 0x49, 0x06, 0x22, 0xfc, 0xf7, 0x1c, 0xf8, + 0xa8, 0xf8, 0xb8, 0x52, 0xa8, 0xf8, 0xba, 0x42, 0x02, 0xe0, 0x89, 0x46, + 0x00, 0xe0, 0xd1, 0x46, 0x48, 0x46, 0x09, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, + 0x10, 0xea, 0x01, 0x00, 0x24, 0xea, 0x01, 0x00, 0x38, 0xb5, 0x04, 0x46, + 0x0d, 0x46, 0xa9, 0xb1, 0x04, 0x22, 0x11, 0x49, 0xfc, 0xf7, 0x04, 0xf8, + 0xd4, 0xf8, 0xa8, 0x30, 0x20, 0x46, 0x93, 0xf8, 0xe9, 0x33, 0x40, 0xf6, + 0x4a, 0x11, 0xa0, 0x2b, 0x0c, 0xbf, 0x40, 0xf2, 0x4f, 0x12, 0xa7, 0x22, + 0xfb, 0xf7, 0xfe, 0xfd, 0x20, 0x46, 0x09, 0x49, 0x0e, 0x22, 0x01, 0xe0, + 0x08, 0x49, 0x0a, 0x22, 0xfb, 0xf7, 0xee, 0xff, 0xe3, 0x69, 0x29, 0x1c, + 0x18, 0x69, 0x18, 0xbf, 0x01, 0x21, 0xbd, 0xe8, 0x38, 0x40, 0x3b, 0xf0, + 0xf7, 0x9b, 0x00, 0xbf, 0x1c, 0xea, 0x01, 0x00, 0x98, 0xeb, 0x01, 0x00, + 0x30, 0xea, 0x01, 0x00, 0x70, 0xb5, 0x0d, 0x46, 0x06, 0x22, 0x28, 0x49, + 0xed, 0xb2, 0x04, 0x46, 0xd0, 0xf8, 0xa8, 0x60, 0xfb, 0xf7, 0xd4, 0xff, + 0x0c, 0x2d, 0x07, 0xd9, 0x04, 0xf5, 0x8a, 0x53, 0x93, 0xf9, 0x30, 0x50, + 0x00, 0x35, 0x18, 0xbf, 0x01, 0x25, 0x00, 0xe0, 0x00, 0x25, 0x96, 0xf8, + 0x1a, 0x35, 0x00, 0x2b, 0x32, 0xd0, 0x20, 0x46, 0x40, 0xf6, 0x42, 0x11, + 0xfb, 0xf7, 0xbd, 0xfd, 0x00, 0xb2, 0x0d, 0xb1, 0x0f, 0x38, 0x00, 0xe0, + 0x00, 0x30, 0xd4, 0xf8, 0xf8, 0x30, 0x18, 0xbf, 0x01, 0x20, 0x13, 0xf0, + 0x06, 0x0f, 0x21, 0xd1, 0x96, 0xf8, 0x2c, 0x30, 0xab, 0x42, 0x00, 0xd1, + 0xe0, 0xb1, 0xe3, 0x69, 0xd8, 0x68, 0x99, 0x68, 0x55, 0xb1, 0x01, 0x22, + 0xf0, 0xf3, 0xe4, 0xf7, 0x20, 0x46, 0x01, 0x21, 0xff, 0xf7, 0x98, 0xff, + 0x01, 0x23, 0x86, 0xf8, 0x2c, 0x30, 0x08, 0xe0, 0x2a, 0x46, 0xf0, 0xf3, + 0xd9, 0xf7, 0x20, 0x46, 0x29, 0x46, 0xff, 0xf7, 0x8d, 0xff, 0x86, 0xf8, + 0x2c, 0x50, 0x20, 0x46, 0x06, 0x49, 0x0c, 0x22, 0xfb, 0xf7, 0x92, 0xff, + 0x05, 0x49, 0x20, 0x46, 0x04, 0x22, 0xbd, 0xe8, 0x70, 0x40, 0xfb, 0xf7, + 0x8b, 0xbf, 0x00, 0xbf, 0xde, 0xeb, 0x01, 0x00, 0x08, 0xee, 0x01, 0x00, + 0xf8, 0xed, 0x01, 0x00, 0x70, 0xb5, 0x0c, 0x46, 0xb0, 0xf8, 0xda, 0x10, + 0x15, 0x46, 0xd0, 0xf8, 0xa8, 0x60, 0xfc, 0xf7, 0x43, 0xfa, 0x28, 0xb9, + 0x96, 0xf8, 0x4c, 0x34, 0x23, 0x70, 0x96, 0xf8, 0x4d, 0x34, 0x01, 0xe0, + 0x00, 0x23, 0x23, 0x70, 0x2b, 0x70, 0x70, 0xbd, 0x07, 0xb5, 0x40, 0xf2, + 0x56, 0x43, 0x00, 0x93, 0x40, 0xf2, 0x55, 0x42, 0x40, 0xf2, 0x57, 0x43, + 0xfc, 0xf7, 0x8f, 0xf8, 0x0e, 0xbd, 0xf0, 0xb5, 0x14, 0x46, 0x01, 0x32, + 0x8b, 0xb0, 0x06, 0x46, 0x0d, 0x46, 0xd0, 0xf8, 0xa8, 0x70, 0x02, 0xd1, + 0xfd, 0xf7, 0xa7, 0xfe, 0x44, 0xb2, 0x97, 0xf9, 0x66, 0x75, 0xeb, 0xb2, + 0x01, 0x37, 0x93, 0xfb, 0xf7, 0xf7, 0x07, 0x23, 0x03, 0x93, 0x20, 0x23, + 0x05, 0x93, 0x01, 0x23, 0xff, 0xb2, 0x02, 0x93, 0x06, 0xab, 0x01, 0x93, + 0x30, 0x46, 0x07, 0xf5, 0xa0, 0x73, 0x01, 0xa9, 0x04, 0x93, 0xff, 0xf7, + 0xd3, 0xff, 0x06, 0x9b, 0xc0, 0x37, 0x1b, 0x0d, 0xdb, 0xb2, 0x06, 0x93, + 0x30, 0x46, 0x07, 0xab, 0x01, 0xa9, 0x01, 0x93, 0x04, 0x97, 0xff, 0xf7, + 0xc7, 0xff, 0x00, 0x21, 0x06, 0x98, 0x08, 0xaa, 0x09, 0xab, 0xf3, 0xf3, + 0x49, 0xf1, 0x00, 0x21, 0x40, 0x20, 0x0d, 0xf1, 0x26, 0x03, 0x0d, 0xf1, + 0x22, 0x02, 0xf3, 0xf3, 0x41, 0xf1, 0xbd, 0xf9, 0x24, 0x10, 0xbd, 0xf9, + 0x26, 0x30, 0x99, 0x42, 0x09, 0xda, 0xbd, 0xf9, 0x22, 0x00, 0x59, 0x1a, + 0xf3, 0xf3, 0xe8, 0xf1, 0xbd, 0xf8, 0x24, 0x60, 0xad, 0xf8, 0x22, 0x00, + 0x08, 0xe0, 0xbd, 0xf9, 0x20, 0x00, 0xc9, 0x1a, 0xf3, 0xf3, 0xde, 0xf1, + 0xbd, 0xf8, 0x26, 0x60, 0xad, 0xf8, 0x20, 0x00, 0xbd, 0xf9, 0x20, 0x00, + 0xbd, 0xf9, 0x22, 0x10, 0xf3, 0xf3, 0xde, 0xf1, 0x33, 0xb2, 0x03, 0x2b, + 0x01, 0xdd, 0x04, 0x3e, 0x01, 0xe0, 0xc6, 0xf1, 0x04, 0x06, 0x36, 0xb2, + 0xb5, 0x40, 0xb3, 0x1e, 0x01, 0x22, 0x12, 0xfa, 0x03, 0xf3, 0x00, 0xeb, + 0x80, 0x00, 0x28, 0x18, 0xc0, 0x18, 0x01, 0x3e, 0x50, 0xfa, 0x06, 0xf6, + 0x74, 0x43, 0xe0, 0x08, 0x80, 0xb2, 0x0b, 0xb0, 0xf0, 0xbd, 0x30, 0xb5, + 0x18, 0x23, 0x87, 0xb0, 0x03, 0x93, 0x00, 0x23, 0xd0, 0xf8, 0xa8, 0x40, + 0x80, 0x22, 0x04, 0x93, 0x20, 0x23, 0x05, 0x93, 0x40, 0xf2, 0x76, 0x61, + 0x13, 0x46, 0x05, 0x46, 0x02, 0x92, 0xfb, 0xf7, 0xcd, 0xfe, 0x04, 0xf1, + 0x9c, 0x03, 0x06, 0xa9, 0x41, 0xf8, 0x14, 0x3d, 0x28, 0x46, 0xff, 0xf7, + 0x67, 0xff, 0x40, 0xf2, 0x71, 0x61, 0x28, 0x46, 0xfb, 0xf7, 0xcf, 0xfc, + 0x40, 0xf2, 0x73, 0x61, 0xa4, 0xf8, 0x9c, 0x02, 0x28, 0x46, 0xfb, 0xf7, + 0xc8, 0xfc, 0x40, 0xf2, 0x74, 0x61, 0xa4, 0xf8, 0x9e, 0x02, 0x28, 0x46, + 0xfb, 0xf7, 0xc1, 0xfc, 0x40, 0xf2, 0x75, 0x61, 0xa4, 0xf8, 0xa2, 0x02, + 0x28, 0x46, 0xfb, 0xf7, 0xba, 0xfc, 0x40, 0xf2, 0x79, 0x61, 0xa4, 0xf8, + 0xa0, 0x02, 0x28, 0x46, 0xfb, 0xf7, 0xb3, 0xfc, 0x40, 0xf2, 0x76, 0x61, + 0xa4, 0xf8, 0xa4, 0x02, 0x28, 0x46, 0xfb, 0xf7, 0xac, 0xfc, 0x40, 0xf2, + 0xda, 0x61, 0xa4, 0xf8, 0xa6, 0x02, 0x28, 0x46, 0xfb, 0xf7, 0xa5, 0xfc, + 0x40, 0xf2, 0x25, 0x51, 0xa4, 0xf8, 0xa8, 0x02, 0x28, 0x46, 0xfb, 0xf7, + 0x9e, 0xfc, 0x94, 0xf8, 0x67, 0x35, 0xa4, 0xf8, 0xaa, 0x02, 0x84, 0xf8, + 0xac, 0x32, 0x4f, 0xf4, 0x8f, 0x61, 0x28, 0x46, 0xfb, 0xf7, 0x93, 0xfc, + 0x4f, 0xf4, 0x9a, 0x61, 0xa4, 0xf8, 0xae, 0x02, 0x28, 0x46, 0xfb, 0xf7, + 0x8c, 0xfc, 0x40, 0xf2, 0x24, 0x51, 0xa4, 0xf8, 0xb0, 0x02, 0x28, 0x46, + 0xfb, 0xf7, 0x85, 0xfc, 0xb4, 0xf8, 0x68, 0x35, 0xc0, 0x0b, 0xa4, 0xf8, + 0xb4, 0x32, 0x94, 0xf8, 0x07, 0x34, 0xa4, 0xf8, 0xb2, 0x02, 0x84, 0xf8, + 0xb6, 0x32, 0x94, 0xf8, 0x08, 0x34, 0x84, 0xf8, 0xb7, 0x32, 0x07, 0xb0, + 0x30, 0xbd, 0x30, 0xb5, 0x40, 0xf2, 0xdf, 0x41, 0x89, 0xb0, 0xd0, 0xf8, + 0xa8, 0x40, 0x05, 0x46, 0xfb, 0xf7, 0x6b, 0xfc, 0x80, 0xb2, 0xc3, 0xb2, + 0x7f, 0x2b, 0xa4, 0xf8, 0x4c, 0x30, 0xc4, 0xbf, 0xa3, 0xf5, 0x80, 0x73, + 0xa4, 0xf8, 0x4c, 0x30, 0x00, 0x0a, 0x7f, 0x28, 0xa4, 0xf8, 0x4e, 0x00, + 0x06, 0xab, 0xc4, 0xbf, 0xa0, 0xf5, 0x80, 0x70, 0xa4, 0xf8, 0x4e, 0x00, + 0x01, 0x93, 0x02, 0x23, 0x02, 0x93, 0x11, 0x23, 0x03, 0x93, 0x3b, 0x23, + 0x04, 0x93, 0x28, 0x46, 0x20, 0x23, 0x01, 0xa9, 0x05, 0x93, 0xff, 0xf7, + 0xdd, 0xfe, 0x06, 0x9b, 0x3f, 0x2b, 0x01, 0xd9, 0x80, 0x3b, 0x06, 0x93, + 0x06, 0x9b, 0x23, 0x65, 0x07, 0x9b, 0x3f, 0x2b, 0x01, 0xd9, 0x80, 0x3b, + 0x07, 0x93, 0x07, 0x9b, 0x40, 0xf2, 0x34, 0x41, 0x63, 0x65, 0x28, 0x46, + 0xfb, 0xf7, 0x37, 0xfc, 0xc0, 0xb2, 0x7f, 0x28, 0xc4, 0xbf, 0xa0, 0xf5, + 0x80, 0x70, 0x80, 0xb2, 0x84, 0xf8, 0x58, 0x00, 0x40, 0xf2, 0x24, 0x41, + 0x28, 0x46, 0xfb, 0xf7, 0x2a, 0xfc, 0x00, 0x0a, 0xa4, 0xf8, 0x5a, 0x00, + 0x40, 0xf2, 0x25, 0x41, 0x28, 0x46, 0xfb, 0xf7, 0x22, 0xfc, 0x06, 0xab, + 0x01, 0x93, 0x02, 0x23, 0x02, 0x93, 0x0d, 0x23, 0xc0, 0xb2, 0x03, 0x93, + 0x1c, 0x23, 0xa4, 0xf8, 0x5c, 0x00, 0x04, 0x93, 0x28, 0x46, 0x20, 0x23, + 0x01, 0xa9, 0x05, 0x93, 0xff, 0xf7, 0xa4, 0xfe, 0x06, 0x9b, 0x23, 0x64, + 0x07, 0x9b, 0x63, 0x64, 0x09, 0xb0, 0x30, 0xbd, 0x7f, 0xb5, 0x00, 0x23, + 0x02, 0x93, 0x10, 0x23, 0x04, 0x93, 0x0d, 0xf1, 0x16, 0x03, 0x00, 0x93, + 0x01, 0x23, 0x01, 0x93, 0x69, 0x46, 0x55, 0x23, 0x03, 0x93, 0xff, 0xf7, + 0x8f, 0xfe, 0xbd, 0xf8, 0x16, 0x00, 0x07, 0xb0, 0x00, 0xbd, 0x2d, 0xe9, + 0xf0, 0x47, 0xd0, 0xf8, 0xa8, 0x90, 0x04, 0x46, 0x99, 0xf8, 0x46, 0x35, + 0x4b, 0xb9, 0xff, 0xf7, 0xe3, 0xff, 0x40, 0xf3, 0x07, 0x26, 0x45, 0xb2, + 0xad, 0xb2, 0xb6, 0xb2, 0x2f, 0x46, 0xb0, 0x46, 0x07, 0xe0, 0xb9, 0xf8, + 0x4a, 0x85, 0xb9, 0xf8, 0x4c, 0x75, 0xb9, 0xf8, 0x4e, 0x65, 0xb9, 0xf8, + 0x50, 0x55, 0xb4, 0xf8, 0xda, 0x30, 0x20, 0x46, 0x03, 0xf4, 0x70, 0x43, + 0xb3, 0xf5, 0x00, 0x5f, 0x0c, 0xbf, 0xb9, 0xf8, 0x66, 0x90, 0xb9, 0xf8, + 0x68, 0x90, 0x4f, 0xf0, 0xff, 0x32, 0x01, 0x21, 0xfd, 0xf7, 0xa0, 0xfc, + 0x01, 0x21, 0x0f, 0xfa, 0x89, 0xf2, 0x82, 0x46, 0x20, 0x46, 0xfd, 0xf7, + 0x99, 0xfc, 0x00, 0x21, 0x1f, 0xfa, 0x80, 0xf9, 0x4f, 0xf0, 0xff, 0x32, + 0x20, 0x46, 0xfd, 0xf7, 0x91, 0xfc, 0xc9, 0xeb, 0x0a, 0x0a, 0x1f, 0xfa, + 0x8a, 0xfa, 0xca, 0xeb, 0x08, 0x08, 0x1f, 0xfa, 0x88, 0xf8, 0xca, 0xeb, + 0x07, 0x07, 0xff, 0x22, 0x43, 0x46, 0xbf, 0xb2, 0xc9, 0xeb, 0x00, 0x09, + 0x40, 0xf6, 0x52, 0x11, 0x20, 0x46, 0xfb, 0xf7, 0x9b, 0xfd, 0x20, 0x46, + 0xff, 0x22, 0x3b, 0x46, 0x40, 0xf6, 0x53, 0x11, 0xfb, 0xf7, 0x94, 0xfd, + 0x20, 0x46, 0xff, 0x22, 0x43, 0x46, 0x40, 0xf6, 0x56, 0x11, 0xfb, 0xf7, + 0x8d, 0xfd, 0x1f, 0xfa, 0x89, 0xf9, 0x20, 0x46, 0xff, 0x22, 0x3b, 0x46, + 0x40, 0xf6, 0x57, 0x11, 0xfb, 0xf7, 0x84, 0xfd, 0xc9, 0xeb, 0x06, 0x03, + 0x20, 0x46, 0xff, 0x22, 0x40, 0xf6, 0x48, 0x11, 0x9b, 0xb2, 0xfb, 0xf7, + 0x7b, 0xfd, 0xc9, 0xeb, 0x05, 0x05, 0x20, 0x46, 0x40, 0xf6, 0x49, 0x11, + 0xff, 0x22, 0xab, 0xb2, 0xbd, 0xe8, 0xf0, 0x47, 0xfb, 0xf7, 0x70, 0xbd, + 0x2d, 0xe9, 0xf0, 0x47, 0x92, 0x46, 0x3e, 0x4a, 0x92, 0xb0, 0xd0, 0xf8, + 0xa8, 0x50, 0x04, 0x46, 0x0b, 0x46, 0x6e, 0x46, 0x02, 0xf1, 0x20, 0x0e, + 0x10, 0x68, 0x51, 0x68, 0x37, 0x46, 0x03, 0xc7, 0x08, 0x32, 0x72, 0x45, + 0x3e, 0x46, 0xf7, 0xd1, 0x12, 0x88, 0x09, 0xae, 0x3a, 0x80, 0x35, 0x4a, + 0x02, 0xf1, 0x20, 0x0e, 0x10, 0x68, 0x51, 0x68, 0x37, 0x46, 0x03, 0xc7, + 0x08, 0x32, 0x72, 0x45, 0x3e, 0x46, 0xf7, 0xd1, 0x12, 0x88, 0x20, 0x46, + 0x3a, 0x80, 0x9b, 0xb1, 0x00, 0x22, 0x40, 0xf6, 0x0f, 0x11, 0xfb, 0xf7, + 0x5f, 0xfb, 0x95, 0xf8, 0xe9, 0x33, 0x09, 0xaf, 0xa0, 0x2b, 0x14, 0xbf, + 0x4f, 0xf0, 0x10, 0x08, 0x4f, 0xf0, 0x11, 0x08, 0x14, 0xbf, 0x05, 0x21, + 0x03, 0x21, 0x26, 0x4b, 0x26, 0x4a, 0x12, 0xe0, 0x01, 0x22, 0x4f, 0xf4, + 0x11, 0x61, 0xfb, 0xf7, 0x4b, 0xfb, 0x95, 0xf8, 0xe9, 0x33, 0x23, 0x4a, + 0xa0, 0x2b, 0x23, 0x4b, 0x6f, 0x46, 0x14, 0xbf, 0x4f, 0xf0, 0x10, 0x08, + 0x4f, 0xf0, 0x11, 0x08, 0x14, 0xbf, 0x0e, 0x21, 0x0a, 0x21, 0x08, 0xbf, + 0x1a, 0x46, 0x00, 0x23, 0x05, 0xe0, 0x16, 0x46, 0x30, 0x88, 0x01, 0x33, + 0x24, 0x32, 0x82, 0x45, 0x06, 0xd0, 0x8b, 0x42, 0x1f, 0xfa, 0x83, 0xf9, + 0xf5, 0xdb, 0x4f, 0xf6, 0xff, 0x79, 0x0b, 0xe0, 0x00, 0x25, 0x07, 0xe0, + 0x20, 0x46, 0x37, 0xf8, 0x02, 0x1b, 0x36, 0xf8, 0x02, 0x2f, 0xfb, 0xf7, + 0x23, 0xfb, 0x01, 0x35, 0x45, 0x45, 0xf5, 0xdb, 0x20, 0x46, 0xfd, 0xf7, + 0xbd, 0xfb, 0x10, 0xb1, 0x20, 0x46, 0xff, 0xf7, 0x16, 0xff, 0x20, 0x46, + 0x0f, 0xfa, 0x89, 0xf9, 0xfd, 0xf7, 0x26, 0xff, 0xb9, 0xf1, 0xff, 0x3f, + 0x0c, 0xbf, 0x4f, 0xf0, 0xff, 0x30, 0x00, 0x20, 0x12, 0xb0, 0xbd, 0xe8, + 0xf0, 0x87, 0x00, 0xbf, 0x00, 0xb8, 0x01, 0x00, 0x22, 0xb8, 0x01, 0x00, + 0x34, 0x02, 0x02, 0x00, 0xec, 0x06, 0x02, 0x00, 0xe8, 0x04, 0x02, 0x00, + 0xa0, 0x02, 0x02, 0x00, 0x2d, 0xe9, 0xf0, 0x43, 0x25, 0x4b, 0x8b, 0xb0, + 0x91, 0x46, 0x04, 0x46, 0x0d, 0x46, 0x01, 0xaa, 0x03, 0xf1, 0x20, 0x07, + 0x18, 0x68, 0x59, 0x68, 0x16, 0x46, 0x03, 0xc6, 0x08, 0x33, 0xbb, 0x42, + 0x32, 0x46, 0xf7, 0xd1, 0x1b, 0x88, 0x33, 0x80, 0xd4, 0xf8, 0xa8, 0x30, + 0x93, 0xf8, 0xe9, 0x83, 0xb8, 0xf1, 0xa0, 0x0f, 0x0c, 0xbf, 0x4f, 0xf0, + 0x11, 0x08, 0x4f, 0xf0, 0x10, 0x08, 0x65, 0xb9, 0x2e, 0x46, 0x2f, 0x46, + 0x17, 0xe0, 0x01, 0xab, 0x99, 0x5b, 0x20, 0x46, 0xfb, 0xf7, 0xcb, 0xfa, + 0x01, 0x37, 0x29, 0xf8, 0x06, 0x00, 0x02, 0x36, 0x01, 0xe0, 0x00, 0x26, + 0x37, 0x46, 0x47, 0x45, 0xf1, 0xdb, 0x0a, 0xe0, 0x01, 0xab, 0x99, 0x5b, + 0x39, 0xf8, 0x06, 0x20, 0x20, 0x46, 0xfb, 0xf7, 0xc5, 0xfa, 0x01, 0x37, + 0x02, 0x36, 0x47, 0x45, 0xf4, 0xdb, 0x20, 0x46, 0xfd, 0xf7, 0x5e, 0xfb, + 0x10, 0xb1, 0x20, 0x46, 0xff, 0xf7, 0xb7, 0xfe, 0x2d, 0xb9, 0x20, 0x46, + 0x0b, 0xb0, 0xbd, 0xe8, 0xf0, 0x43, 0xfd, 0xf7, 0xc5, 0xbe, 0x0b, 0xb0, + 0xbd, 0xe8, 0xf0, 0x83, 0x22, 0xb8, 0x01, 0x00, 0x30, 0xb5, 0x87, 0xb0, + 0x05, 0xab, 0x00, 0x93, 0x02, 0x23, 0x01, 0x93, 0x00, 0x23, 0x02, 0x93, + 0x50, 0x23, 0x0c, 0x46, 0x03, 0x93, 0x69, 0x46, 0x10, 0x23, 0x15, 0x46, + 0x04, 0x93, 0xff, 0xf7, 0x25, 0xfd, 0xbd, 0xf8, 0x14, 0x30, 0x23, 0x80, + 0xbd, 0xf8, 0x16, 0x30, 0x2b, 0x80, 0x07, 0xb0, 0x30, 0xbd, 0x07, 0xb5, + 0x40, 0xf2, 0x56, 0x43, 0x00, 0x93, 0x40, 0xf2, 0x55, 0x42, 0x40, 0xf2, + 0x57, 0x43, 0xfb, 0xf7, 0x75, 0xfd, 0x0e, 0xbd, 0x2d, 0xe9, 0xf0, 0x4f, + 0xb0, 0xf8, 0xda, 0x30, 0x89, 0xb0, 0x03, 0xf4, 0x70, 0x43, 0xb3, 0xf5, + 0x00, 0x5f, 0x04, 0x46, 0x8b, 0x46, 0xd0, 0xf8, 0xa8, 0x50, 0x02, 0xd1, + 0xb5, 0xf8, 0xc4, 0x33, 0x04, 0xe0, 0xb3, 0xf5, 0x80, 0x5f, 0x06, 0xd1, + 0xb5, 0xf8, 0xc6, 0x33, 0x1a, 0xb2, 0x01, 0x32, 0x08, 0xbf, 0x70, 0x23, + 0x00, 0xe0, 0x70, 0x23, 0x07, 0x22, 0x04, 0x92, 0x20, 0x22, 0x06, 0x92, + 0x01, 0x22, 0x00, 0x27, 0x03, 0x92, 0x1b, 0x06, 0x07, 0xaa, 0x02, 0x92, + 0x01, 0x93, 0xb8, 0x46, 0x3e, 0x46, 0x0b, 0xeb, 0x07, 0x0a, 0xf1, 0x07, + 0x9a, 0xf8, 0x03, 0x90, 0x03, 0xd5, 0x95, 0xf9, 0x66, 0x35, 0x00, 0x2b, + 0x50, 0xd1, 0xb4, 0xf8, 0xda, 0x30, 0x03, 0xf4, 0x70, 0x43, 0xb3, 0xf5, + 0x00, 0x5f, 0x00, 0xf0, 0x86, 0x80, 0x1b, 0xf8, 0x07, 0x80, 0x08, 0xe0, + 0x1f, 0xfa, 0x88, 0xf8, 0xb5, 0xf8, 0x3e, 0x34, 0x1a, 0xb2, 0xb2, 0xf1, + 0xff, 0x3f, 0x18, 0xbf, 0x99, 0x46, 0x9a, 0xf8, 0x01, 0x30, 0x9a, 0xf8, + 0x02, 0x20, 0x1b, 0x02, 0x43, 0xea, 0x02, 0x43, 0x01, 0x9a, 0x20, 0x46, + 0x13, 0x43, 0x43, 0xea, 0x08, 0x03, 0x07, 0x93, 0x95, 0xf9, 0x66, 0x35, + 0x02, 0xa9, 0x01, 0x33, 0xb6, 0xfb, 0xf3, 0xf3, 0xc0, 0x33, 0x05, 0x93, + 0xff, 0xf7, 0x97, 0xff, 0x07, 0xab, 0x02, 0x93, 0x95, 0xf9, 0x66, 0x35, + 0x20, 0x46, 0x01, 0x33, 0xb6, 0xfb, 0xf3, 0xf3, 0x03, 0xf5, 0xa0, 0x73, + 0x02, 0xa9, 0x05, 0x93, 0xff, 0xf7, 0xa6, 0xfc, 0x9a, 0xf8, 0x04, 0x20, + 0x07, 0x9b, 0x12, 0x05, 0x23, 0xf0, 0x7f, 0x43, 0x42, 0xea, 0x09, 0x72, + 0x23, 0xf4, 0x70, 0x03, 0x13, 0x43, 0x07, 0x93, 0x95, 0xf9, 0x66, 0x35, + 0x20, 0x46, 0x01, 0x33, 0xb6, 0xfb, 0xf3, 0xf3, 0x03, 0xf5, 0xa0, 0x73, + 0x02, 0xa9, 0x05, 0x93, 0xff, 0xf7, 0x71, 0xff, 0x01, 0x36, 0x05, 0x37, + 0x80, 0x2e, 0xa0, 0xd1, 0x95, 0xf9, 0x66, 0x35, 0x00, 0x2b, 0x3e, 0xd0, + 0x4f, 0xea, 0x09, 0x79, 0x5e, 0x46, 0x4f, 0xf4, 0x80, 0x75, 0x01, 0x9a, + 0x20, 0x46, 0x48, 0xea, 0x02, 0x03, 0x96, 0xf8, 0x42, 0x21, 0x02, 0xa9, + 0x43, 0xea, 0x02, 0x43, 0x96, 0xf8, 0x41, 0x21, 0x05, 0xf1, 0x80, 0x07, + 0x43, 0xea, 0x02, 0x23, 0x07, 0x93, 0x05, 0x95, 0xff, 0xf7, 0x51, 0xff, + 0x07, 0xab, 0x20, 0x46, 0x02, 0xa9, 0x02, 0x93, 0x05, 0x97, 0xff, 0xf7, + 0x67, 0xfc, 0x07, 0x9b, 0x96, 0xf8, 0x44, 0x21, 0x23, 0xf0, 0x7f, 0x43, + 0x49, 0xea, 0x02, 0x52, 0x23, 0xf4, 0x70, 0x03, 0x13, 0x43, 0x20, 0x46, + 0x02, 0xa9, 0x01, 0x35, 0x07, 0x93, 0x05, 0x97, 0x05, 0x36, 0xff, 0xf7, + 0x38, 0xff, 0xb5, 0xf5, 0xa0, 0x7f, 0xd0, 0xd1, 0x09, 0xe0, 0xb5, 0xf8, + 0x40, 0x84, 0x0f, 0xfa, 0x88, 0xf3, 0x01, 0x33, 0x7f, 0xf4, 0x76, 0xaf, + 0x4f, 0xf0, 0x0f, 0x08, 0x74, 0xe7, 0x09, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, + 0xb0, 0xf8, 0xda, 0x30, 0xd0, 0xf8, 0xa8, 0x20, 0x03, 0xf4, 0x70, 0x43, + 0xb3, 0xf5, 0x00, 0x5f, 0x03, 0xd1, 0xd2, 0xf8, 0x74, 0x15, 0xff, 0xf7, + 0x25, 0xbf, 0x70, 0x47, 0x2d, 0xe9, 0xf0, 0x41, 0x00, 0x24, 0x86, 0xb0, + 0x05, 0x46, 0x05, 0x94, 0xd0, 0xf8, 0xa8, 0x60, 0xfd, 0xf7, 0xe9, 0xfa, + 0x07, 0x23, 0x02, 0x93, 0x20, 0x23, 0x04, 0x93, 0x01, 0x23, 0x80, 0x46, + 0x01, 0x93, 0x96, 0xf9, 0x66, 0x35, 0x1b, 0xb1, 0xe0, 0x07, 0x13, 0xd4, + 0x67, 0x08, 0x00, 0xe0, 0x27, 0x46, 0x21, 0x46, 0x28, 0x46, 0x4f, 0xfa, + 0x88, 0xf2, 0xff, 0xf7, 0x22, 0xfc, 0x06, 0xab, 0x43, 0xf8, 0x04, 0x0d, + 0x07, 0xf5, 0x10, 0x77, 0x28, 0x46, 0x69, 0x46, 0x00, 0x93, 0x03, 0x97, + 0xff, 0xf7, 0xef, 0xfe, 0x01, 0x34, 0xe4, 0xb2, 0x80, 0x2c, 0xe2, 0xd1, + 0x96, 0xf9, 0x66, 0x35, 0x7b, 0xb1, 0x01, 0x23, 0x01, 0x93, 0x40, 0x24, + 0x05, 0xab, 0x00, 0x93, 0x04, 0xf5, 0x10, 0x73, 0x01, 0x34, 0x28, 0x46, + 0x69, 0x46, 0xe4, 0xb2, 0x03, 0x93, 0xff, 0xf7, 0xda, 0xfe, 0x80, 0x2c, + 0xf2, 0xd1, 0x06, 0xb0, 0xbd, 0xe8, 0xf0, 0x81, 0xf0, 0xb5, 0x04, 0x46, + 0x87, 0xb0, 0xd0, 0xf8, 0xa8, 0x70, 0x00, 0x29, 0x3c, 0xd0, 0x07, 0x23, + 0x02, 0x93, 0x20, 0x23, 0x04, 0x93, 0x01, 0x23, 0x01, 0x93, 0x05, 0xab, + 0x97, 0xf8, 0xc2, 0x62, 0x00, 0x93, 0x00, 0x25, 0x2b, 0xe0, 0x06, 0xf1, + 0xc0, 0x03, 0x20, 0x46, 0x69, 0x46, 0x03, 0x93, 0xff, 0xf7, 0xd8, 0xfb, + 0x05, 0xf1, 0xc0, 0x03, 0x20, 0x46, 0x69, 0x46, 0x03, 0x93, 0xff, 0xf7, + 0xb4, 0xfe, 0x06, 0xf5, 0xa0, 0x73, 0x20, 0x46, 0x69, 0x46, 0x03, 0x93, + 0xff, 0xf7, 0xca, 0xfb, 0x05, 0xf5, 0xa0, 0x73, 0x20, 0x46, 0x69, 0x46, + 0x03, 0x93, 0xff, 0xf7, 0xa6, 0xfe, 0x06, 0xf5, 0x10, 0x73, 0x20, 0x46, + 0x69, 0x46, 0x03, 0x93, 0xff, 0xf7, 0xbc, 0xfb, 0x05, 0xf5, 0x10, 0x73, + 0x20, 0x46, 0x69, 0x46, 0x03, 0x93, 0xff, 0xf7, 0x98, 0xfe, 0x01, 0x35, + 0xed, 0xb2, 0x97, 0xf8, 0xc2, 0x32, 0xab, 0x42, 0xcf, 0xd2, 0x0c, 0xe0, + 0xb0, 0xf8, 0xda, 0x30, 0x03, 0xf4, 0x70, 0x43, 0xb3, 0xf5, 0x00, 0x5f, + 0x02, 0xd1, 0x04, 0x49, 0xff, 0xf7, 0x92, 0xfe, 0x20, 0x46, 0xff, 0xf7, + 0x6b, 0xff, 0x07, 0xb0, 0xf0, 0xbd, 0x00, 0xbf, 0x14, 0xa0, 0x02, 0x00, + 0x7f, 0xb5, 0x09, 0x02, 0x06, 0xab, 0x23, 0xf8, 0x02, 0x1d, 0x00, 0x93, + 0x01, 0x23, 0x01, 0x93, 0x00, 0x23, 0x02, 0x93, 0x57, 0x23, 0x03, 0x93, + 0x69, 0x46, 0x10, 0x23, 0x04, 0x93, 0xff, 0xf7, 0x6e, 0xfe, 0x07, 0xb0, + 0x00, 0xbd, 0x2d, 0xe9, 0xf0, 0x41, 0xd0, 0xf8, 0xa8, 0x30, 0x8a, 0xb0, + 0x83, 0xf8, 0x34, 0x10, 0x83, 0xf8, 0xc1, 0x12, 0x93, 0xf9, 0x66, 0x35, + 0x05, 0x46, 0x0c, 0x46, 0x53, 0xb1, 0x11, 0xf0, 0x01, 0x03, 0x18, 0xbf, + 0x08, 0x23, 0x4f, 0xf4, 0x8f, 0x61, 0x4f, 0xf0, 0x0c, 0x02, 0xfb, 0xf7, + 0xcf, 0xfa, 0x64, 0x08, 0x07, 0x23, 0x4f, 0xf0, 0x20, 0x08, 0x03, 0x93, + 0x04, 0xf5, 0xa0, 0x73, 0x0a, 0xae, 0x04, 0x93, 0x0d, 0xeb, 0x08, 0x03, + 0x46, 0xf8, 0x24, 0x3d, 0x01, 0x27, 0x28, 0x46, 0x31, 0x46, 0xcd, 0xf8, + 0x14, 0x80, 0x02, 0x97, 0xc0, 0x34, 0xff, 0xf7, 0x5b, 0xfb, 0x09, 0xab, + 0x28, 0x46, 0x31, 0x46, 0x01, 0x93, 0x04, 0x94, 0xcd, 0xf8, 0x14, 0x80, + 0xff, 0xf7, 0x52, 0xfb, 0x09, 0x9b, 0x28, 0x46, 0xda, 0xb2, 0xad, 0xf8, + 0x18, 0x20, 0x1a, 0x0a, 0x1b, 0x0c, 0xdb, 0xb2, 0xad, 0xf8, 0x1c, 0x30, + 0x08, 0x9b, 0xd2, 0xb2, 0x1b, 0x0f, 0x03, 0xf0, 0x07, 0x03, 0x06, 0xa9, + 0xad, 0xf8, 0x1a, 0x20, 0xad, 0xf8, 0x1e, 0x30, 0xfd, 0xf7, 0xf5, 0xfb, + 0x08, 0x99, 0x28, 0x46, 0x09, 0x0d, 0xc9, 0xb2, 0xff, 0xf7, 0x9a, 0xff, + 0x28, 0x46, 0x39, 0x46, 0xfd, 0xf7, 0xcf, 0xfb, 0x0a, 0xb0, 0xbd, 0xe8, + 0xf0, 0x81, 0x00, 0x00, 0xf0, 0xb5, 0x51, 0x4f, 0x8f, 0xb0, 0x6e, 0x46, + 0x04, 0x46, 0x0f, 0xcf, 0x0f, 0xc6, 0x97, 0xe8, 0x0f, 0x00, 0x86, 0xe8, + 0x0f, 0x00, 0x20, 0x46, 0x4c, 0x49, 0x04, 0x22, 0xbd, 0xf8, 0x58, 0x50, + 0xfb, 0xf7, 0x8c, 0xfa, 0x9d, 0xf8, 0x68, 0x30, 0x20, 0x46, 0x5b, 0x00, + 0x40, 0xf2, 0xa3, 0x61, 0x02, 0x22, 0xfb, 0xf7, 0x71, 0xfa, 0x9d, 0xf8, + 0x5c, 0x30, 0xbb, 0xb1, 0x0e, 0xab, 0x4f, 0xf4, 0x00, 0x22, 0x43, 0xf8, + 0x04, 0x2d, 0x08, 0x93, 0x01, 0x23, 0x09, 0x93, 0x18, 0x23, 0x0a, 0x93, + 0x20, 0x23, 0x0c, 0x93, 0x00, 0x23, 0x0b, 0x93, 0x40, 0x26, 0x20, 0x46, + 0x08, 0xa9, 0xff, 0xf7, 0xe0, 0xfd, 0x0b, 0x9b, 0x01, 0x33, 0x01, 0x3e, + 0x0b, 0x93, 0xf6, 0xd1, 0x20, 0x46, 0x05, 0xeb, 0x45, 0x05, 0xfd, 0xf7, + 0x8b, 0xfd, 0x01, 0x35, 0x20, 0x46, 0x40, 0xf2, 0xa1, 0x61, 0xbd, 0xf8, + 0x6c, 0x20, 0xfb, 0xf7, 0x63, 0xf8, 0xad, 0xb2, 0x20, 0x46, 0x40, 0xf2, + 0xa2, 0x61, 0xbd, 0xf8, 0x70, 0x20, 0xfb, 0xf7, 0x5b, 0xf8, 0x2a, 0x46, + 0x20, 0x46, 0x40, 0xf2, 0x7e, 0x61, 0xfb, 0xf7, 0x55, 0xf8, 0x20, 0x46, + 0x2a, 0x49, 0x04, 0x22, 0xfb, 0xf7, 0x48, 0xfa, 0x01, 0x35, 0x14, 0x22, + 0x6a, 0x43, 0x01, 0x3a, 0x20, 0x46, 0x4f, 0xf4, 0xc8, 0x61, 0x92, 0xb2, + 0xfb, 0xf7, 0x46, 0xf8, 0x00, 0x22, 0x20, 0x46, 0x40, 0xf2, 0x77, 0x61, + 0xfb, 0xf7, 0x40, 0xf8, 0x08, 0x23, 0x09, 0x93, 0x15, 0x23, 0x00, 0x25, + 0x0a, 0x93, 0x20, 0x23, 0x0e, 0xa9, 0x0c, 0x93, 0x0d, 0xeb, 0x05, 0x03, + 0x41, 0xf8, 0x18, 0x3d, 0x20, 0x46, 0x0b, 0x95, 0xff, 0xf7, 0x9b, 0xfd, + 0x20, 0x46, 0x40, 0xf2, 0x7b, 0x61, 0xbd, 0xf8, 0x60, 0x20, 0xfb, 0xf7, + 0x29, 0xf8, 0x20, 0x46, 0x40, 0xf2, 0x7c, 0x61, 0xbd, 0xf8, 0x64, 0x20, + 0xfb, 0xf7, 0x22, 0xf8, 0x2a, 0x46, 0x20, 0x46, 0x40, 0xf2, 0x7d, 0x61, + 0xfb, 0xf7, 0x1c, 0xf8, 0x29, 0x46, 0x20, 0x46, 0xff, 0xf7, 0x04, 0xff, + 0x20, 0x46, 0x0d, 0x49, 0x04, 0x22, 0xfb, 0xf7, 0x0b, 0xfa, 0x0c, 0x4d, + 0x02, 0xe0, 0x0a, 0x20, 0xf0, 0xf3, 0xf0, 0xf5, 0x20, 0x46, 0x40, 0xf2, + 0x76, 0x61, 0xfa, 0xf7, 0xfe, 0xff, 0xc3, 0x07, 0x01, 0xd5, 0x01, 0x3d, + 0xf3, 0xd1, 0x0f, 0xb0, 0xf0, 0xbd, 0x00, 0xbf, 0x44, 0xb8, 0x01, 0x00, + 0x64, 0xe8, 0x01, 0x00, 0xbe, 0xe9, 0x01, 0x00, 0xc6, 0xe9, 0x01, 0x00, + 0xa1, 0x86, 0x01, 0x00, 0x2d, 0xe9, 0xf0, 0x43, 0xd0, 0xf8, 0xa8, 0x90, + 0x8b, 0xb0, 0x07, 0x46, 0x88, 0x46, 0x03, 0x26, 0x05, 0x24, 0x0f, 0x2c, + 0xa8, 0xbf, 0x0f, 0x24, 0x00, 0x25, 0xa3, 0xb2, 0x01, 0x93, 0x38, 0x46, + 0x01, 0x21, 0x2a, 0x46, 0x2b, 0x46, 0x00, 0x95, 0x02, 0x95, 0x03, 0x95, + 0x04, 0x95, 0xfd, 0xf7, 0xf7, 0xfb, 0xdb, 0x23, 0x02, 0x93, 0x4f, 0xf4, + 0xaf, 0x63, 0x04, 0x93, 0x4f, 0xf4, 0x82, 0x43, 0x05, 0x93, 0x80, 0x23, + 0x01, 0x22, 0x07, 0x93, 0x38, 0x46, 0x29, 0x46, 0x2b, 0x46, 0x00, 0x95, + 0x01, 0x95, 0x03, 0x92, 0x06, 0x95, 0x08, 0x95, 0xff, 0xf7, 0x24, 0xff, + 0xb8, 0xf1, 0x00, 0x0f, 0x1e, 0xd1, 0x40, 0xf2, 0xba, 0x61, 0x38, 0x46, + 0xfa, 0xf7, 0xb7, 0xff, 0x4f, 0xf6, 0xc0, 0x75, 0x80, 0x01, 0x05, 0x40, + 0x40, 0xf2, 0xbb, 0x61, 0x38, 0x46, 0xfa, 0xf7, 0xae, 0xff, 0x83, 0x01, + 0x1b, 0xb2, 0x9b, 0x11, 0x5b, 0x43, 0x2d, 0xb2, 0xad, 0x11, 0x05, 0xfb, + 0x05, 0x35, 0xb5, 0xf5, 0x00, 0x5f, 0x01, 0xda, 0xa4, 0x1b, 0x03, 0xe0, + 0xb5, 0xf5, 0x80, 0x4f, 0x04, 0xdb, 0xa4, 0x19, 0x01, 0x3e, 0xf6, 0xb2, + 0xff, 0x2e, 0xb4, 0xd1, 0x09, 0x2c, 0xd4, 0xbf, 0x24, 0xea, 0xe4, 0x74, + 0x09, 0x24, 0xc9, 0xf8, 0x38, 0x40, 0x20, 0x46, 0x0b, 0xb0, 0xbd, 0xe8, + 0xf0, 0x83, 0xf8, 0xb5, 0xd0, 0xf8, 0xa8, 0x60, 0x07, 0x46, 0xd6, 0xf8, + 0x7c, 0x55, 0x00, 0x24, 0x05, 0xe0, 0x29, 0x46, 0x38, 0x46, 0xff, 0xf7, + 0xf8, 0xfc, 0x01, 0x34, 0x14, 0x35, 0xd6, 0xf8, 0x78, 0x35, 0x9c, 0x42, + 0xf5, 0xd3, 0xf8, 0xbd, 0xf0, 0xb5, 0xc3, 0x69, 0xd0, 0xf8, 0xa8, 0x40, + 0x87, 0xb0, 0x06, 0x46, 0x80, 0x21, 0x98, 0x68, 0xf1, 0xf3, 0x1a, 0xf0, + 0x05, 0x46, 0x00, 0x28, 0x00, 0xf0, 0x8d, 0x80, 0xb4, 0xf8, 0x1c, 0x34, + 0x00, 0x22, 0x03, 0xf4, 0x80, 0x7e, 0x03, 0xf4, 0x00, 0x73, 0x1f, 0xfa, + 0x83, 0xfc, 0x1f, 0xfa, 0x8e, 0xfe, 0x03, 0x46, 0x02, 0xf0, 0x10, 0x07, + 0x00, 0x20, 0xff, 0xb2, 0x02, 0xf0, 0x01, 0x01, 0x23, 0xf8, 0x02, 0x0b, + 0xcf, 0xb1, 0xbc, 0xf1, 0x00, 0x0f, 0x03, 0xd0, 0xd4, 0xf8, 0x1c, 0x14, + 0xc1, 0xf3, 0x80, 0x21, 0x12, 0xf0, 0x08, 0x0f, 0xd4, 0xf8, 0x18, 0x04, + 0x03, 0xd0, 0x00, 0xf4, 0x7f, 0x00, 0x00, 0x0c, 0x07, 0xe0, 0x12, 0xf0, + 0x20, 0x0f, 0x03, 0xd0, 0x00, 0xf4, 0x7f, 0x40, 0x00, 0x0a, 0x00, 0xe0, + 0xc0, 0xb2, 0x23, 0xf8, 0x02, 0x0c, 0xbe, 0xf1, 0x00, 0x0f, 0x01, 0xd0, + 0x00, 0x2f, 0x42, 0xd1, 0x12, 0xf0, 0x04, 0x0f, 0x02, 0xf0, 0x02, 0x07, + 0x17, 0xd0, 0xd4, 0xf8, 0x0c, 0x04, 0x47, 0xb1, 0x33, 0xf8, 0x02, 0x7c, + 0x09, 0xb1, 0x00, 0x0e, 0x0b, 0xe0, 0x00, 0xf4, 0x7f, 0x00, 0x00, 0x0c, + 0x07, 0xe0, 0x33, 0xf8, 0x02, 0x7c, 0x19, 0xb1, 0x00, 0xf4, 0x7f, 0x40, + 0x00, 0x0a, 0x00, 0xe0, 0xc0, 0xb2, 0x38, 0x43, 0x23, 0xf8, 0x02, 0x0c, + 0x25, 0xe0, 0x90, 0x06, 0x10, 0xd5, 0x27, 0xb1, 0x33, 0xf8, 0x02, 0x7c, + 0xd4, 0xf8, 0x10, 0x04, 0x03, 0xe0, 0x33, 0xf8, 0x02, 0x7c, 0xd4, 0xf8, + 0x14, 0x04, 0x09, 0xb1, 0x01, 0x0e, 0x13, 0xe0, 0x00, 0xf4, 0x7f, 0x01, + 0x09, 0x0c, 0x0f, 0xe0, 0x27, 0xb1, 0x33, 0xf8, 0x02, 0x7c, 0xd4, 0xf8, + 0x10, 0x04, 0x03, 0xe0, 0x33, 0xf8, 0x02, 0x7c, 0xd4, 0xf8, 0x14, 0x04, + 0x19, 0xb1, 0x00, 0xf4, 0x7f, 0x41, 0x09, 0x0a, 0x00, 0xe0, 0xc1, 0xb2, + 0x39, 0x43, 0x23, 0xf8, 0x02, 0x1c, 0x01, 0x32, 0x40, 0x2a, 0x91, 0xd1, + 0x0f, 0x23, 0x06, 0xa9, 0x03, 0x93, 0x00, 0x23, 0x04, 0x93, 0x41, 0xf8, + 0x14, 0x5d, 0x10, 0x23, 0x30, 0x46, 0x02, 0x92, 0x05, 0x93, 0xff, 0xf7, + 0x5c, 0xfc, 0xf3, 0x69, 0x29, 0x46, 0x98, 0x68, 0x80, 0x22, 0xf0, 0xf3, + 0x99, 0xf7, 0x07, 0xb0, 0xf0, 0xbd, 0x30, 0xb5, 0x87, 0xb0, 0x05, 0xab, + 0x00, 0x93, 0x01, 0x23, 0x01, 0x93, 0x18, 0x23, 0x02, 0x93, 0x20, 0x23, + 0x04, 0x93, 0x00, 0x23, 0x03, 0x93, 0x4f, 0xf4, 0x00, 0x23, 0x05, 0x46, + 0x05, 0x93, 0x81, 0x24, 0x06, 0xe0, 0x28, 0x46, 0x69, 0x46, 0xff, 0xf7, + 0x3e, 0xfc, 0x03, 0x9b, 0x01, 0x33, 0x03, 0x93, 0x01, 0x3c, 0xf6, 0xd1, + 0x07, 0xb0, 0x30, 0xbd, 0x70, 0xb5, 0xd0, 0xf8, 0xa8, 0x30, 0x86, 0xb0, + 0x93, 0xf8, 0x9a, 0x55, 0x04, 0x46, 0x45, 0xb1, 0x2e, 0xe0, 0x31, 0x4b, + 0x14, 0x21, 0x01, 0xfb, 0x05, 0x31, 0x20, 0x46, 0xff, 0xf7, 0x27, 0xfc, + 0x01, 0x35, 0x2e, 0x4b, 0x1b, 0x68, 0x9d, 0x42, 0xf3, 0xd3, 0x2d, 0x4b, + 0x06, 0xad, 0x5a, 0x68, 0x1b, 0x68, 0x01, 0x92, 0x10, 0x22, 0x02, 0x92, + 0x00, 0x26, 0x08, 0x22, 0x45, 0xf8, 0x18, 0x3d, 0x20, 0x46, 0x69, 0x46, + 0x03, 0x96, 0x04, 0x92, 0xff, 0xf7, 0x11, 0xfc, 0xe3, 0x69, 0x1b, 0x6b, + 0x08, 0x2b, 0x0d, 0xd1, 0x23, 0x4b, 0x20, 0x46, 0x5a, 0x68, 0x1b, 0x68, + 0x01, 0x92, 0x12, 0x22, 0x02, 0x92, 0x69, 0x46, 0x20, 0x22, 0x03, 0x96, + 0x04, 0x92, 0x00, 0x93, 0xff, 0xf7, 0xff, 0xfb, 0x10, 0x23, 0x04, 0x93, + 0x0d, 0xf1, 0x16, 0x03, 0x00, 0x93, 0x72, 0x23, 0x08, 0x25, 0x01, 0x26, + 0xad, 0xf8, 0x16, 0x30, 0x20, 0x46, 0x00, 0x23, 0x69, 0x46, 0x03, 0x93, + 0x02, 0x95, 0x01, 0x96, 0xff, 0xf7, 0xed, 0xfb, 0x82, 0x23, 0x20, 0x46, + 0x69, 0x46, 0xad, 0xf8, 0x16, 0x30, 0x03, 0x96, 0xff, 0xf7, 0xe5, 0xfb, + 0x06, 0x23, 0x69, 0x46, 0x20, 0x46, 0xad, 0xf8, 0x16, 0x30, 0x03, 0x95, + 0xff, 0xf7, 0xdd, 0xfb, 0x20, 0x46, 0xff, 0xf7, 0xb3, 0xfc, 0x20, 0x46, + 0xff, 0xf7, 0xd3, 0xfe, 0x20, 0x46, 0xff, 0xf7, 0xe3, 0xfe, 0x20, 0x46, + 0xff, 0xf7, 0xb8, 0xfc, 0x20, 0x46, 0xff, 0xf7, 0x7a, 0xff, 0x06, 0xb0, + 0x70, 0xbd, 0x00, 0xbf, 0x10, 0xf4, 0x01, 0x00, 0xf0, 0xef, 0x01, 0x00, + 0xf4, 0xf0, 0x01, 0x00, 0x80, 0xfd, 0x01, 0x00, 0xf0, 0xb5, 0xb0, 0xf8, + 0xda, 0x30, 0xd0, 0xf8, 0xa8, 0x40, 0x03, 0xf4, 0x70, 0x43, 0xb3, 0xf5, + 0x00, 0x5f, 0x0c, 0xbf, 0x94, 0xf8, 0x40, 0x33, 0x94, 0xf8, 0x41, 0x33, + 0x87, 0xb0, 0x84, 0xf8, 0x42, 0x33, 0x94, 0xf8, 0x42, 0x33, 0x05, 0x46, + 0x84, 0xf8, 0x43, 0x33, 0xb0, 0xf8, 0xda, 0x30, 0x03, 0xf4, 0x70, 0x43, + 0xb3, 0xf5, 0x00, 0x5f, 0x10, 0xd1, 0x94, 0xf8, 0x49, 0x33, 0x5a, 0xb2, + 0x00, 0x2a, 0x06, 0xdc, 0xc3, 0x69, 0x1b, 0x6d, 0xda, 0x04, 0x01, 0xd5, + 0x34, 0x23, 0x00, 0xe0, 0x30, 0x23, 0x84, 0xf8, 0x48, 0x33, 0x94, 0xf8, + 0x5c, 0x63, 0x0f, 0xe0, 0x94, 0xf8, 0x4a, 0x33, 0x5a, 0xb2, 0x00, 0x2a, + 0x06, 0xdc, 0xc3, 0x69, 0x1b, 0x6d, 0xdb, 0x00, 0x01, 0xd5, 0x34, 0x23, + 0x00, 0xe0, 0x30, 0x23, 0x94, 0xf8, 0x5d, 0x63, 0x84, 0xf8, 0x48, 0x33, + 0x76, 0xb2, 0x00, 0x2e, 0x48, 0xdd, 0x40, 0xf2, 0xdf, 0x41, 0x28, 0x46, + 0xfa, 0xf7, 0x07, 0xfe, 0xc3, 0xb2, 0x00, 0x0a, 0x80, 0xb2, 0x81, 0xb2, + 0x02, 0x2e, 0xa8, 0xbf, 0x02, 0x26, 0x7f, 0x2b, 0xc8, 0xbf, 0xa3, 0xf5, + 0x80, 0x73, 0x0a, 0xb2, 0x06, 0xeb, 0x46, 0x06, 0xc8, 0xbf, 0x9b, 0xb2, + 0xf6, 0xb2, 0x7f, 0x2a, 0xc8, 0xbf, 0xa0, 0xf5, 0x80, 0x71, 0x77, 0xb2, + 0xc8, 0xbf, 0x89, 0xb2, 0xbf, 0xb2, 0xca, 0x1b, 0xdf, 0x1b, 0x92, 0xb2, + 0xff, 0xb2, 0x47, 0xea, 0x02, 0x22, 0x92, 0xb2, 0x28, 0x46, 0x40, 0xf2, + 0xdf, 0x41, 0xfa, 0xf7, 0xed, 0xfd, 0x05, 0xab, 0x00, 0x93, 0x02, 0x23, + 0x01, 0x93, 0x11, 0x23, 0x02, 0x93, 0x0f, 0x23, 0x03, 0x93, 0x28, 0x46, + 0x08, 0x23, 0x69, 0x46, 0x04, 0x93, 0xff, 0xf7, 0x67, 0xf8, 0x9d, 0xf8, + 0x14, 0x30, 0x28, 0x46, 0x9b, 0x1b, 0x8d, 0xf8, 0x14, 0x30, 0x9d, 0xf8, + 0x15, 0x30, 0x69, 0x46, 0x9e, 0x1b, 0x8d, 0xf8, 0x15, 0x60, 0xff, 0xf7, + 0x3c, 0xfb, 0x28, 0x46, 0xfd, 0xf7, 0xf0, 0xff, 0x94, 0xf8, 0x4d, 0x13, + 0x00, 0x23, 0xff, 0x22, 0x84, 0xf8, 0x9a, 0x23, 0x84, 0xf8, 0x47, 0x33, + 0x84, 0xf8, 0x9c, 0x33, 0xb1, 0xb1, 0x84, 0xf8, 0x42, 0x33, 0x84, 0xf8, + 0x43, 0x33, 0x28, 0x46, 0x40, 0xf2, 0x23, 0x41, 0xb4, 0xf8, 0x50, 0x33, + 0xfa, 0xf7, 0x9e, 0xff, 0x28, 0x46, 0x4f, 0xf4, 0xaa, 0x61, 0xb4, 0xf8, + 0x60, 0x23, 0xfa, 0xf7, 0xb1, 0xfd, 0x28, 0x46, 0x04, 0x49, 0x04, 0x22, + 0xfa, 0xf7, 0xa4, 0xff, 0x28, 0x46, 0xfd, 0xf7, 0x1d, 0xf8, 0x07, 0xb0, + 0xf0, 0xbd, 0x00, 0xbf, 0xf0, 0xed, 0x01, 0x00, 0x38, 0xb5, 0xb0, 0xf8, + 0xda, 0x20, 0x04, 0x46, 0x02, 0xf4, 0x70, 0x42, 0xb2, 0xf5, 0x00, 0x5f, + 0xd0, 0xf8, 0xa8, 0x30, 0x0a, 0xd1, 0x93, 0xf9, 0xf1, 0x23, 0x01, 0x32, + 0x2d, 0xd1, 0xb3, 0xf9, 0xf8, 0x23, 0x01, 0x32, 0x29, 0xd1, 0xb3, 0xf9, + 0x2c, 0x25, 0x24, 0xe0, 0xb2, 0xf5, 0x80, 0x5f, 0x2c, 0xd1, 0x93, 0xf9, + 0x5b, 0x25, 0x01, 0x32, 0x1f, 0xd1, 0x93, 0xf9, 0xf3, 0x23, 0x01, 0x32, + 0x1b, 0xd1, 0x93, 0xf9, 0x5c, 0x25, 0x01, 0x32, 0x17, 0xd1, 0xb3, 0xf9, + 0x00, 0x24, 0x01, 0x32, 0x13, 0xd1, 0xb3, 0xf9, 0x30, 0x25, 0x01, 0x32, + 0x0f, 0xd1, 0xb3, 0xf9, 0x02, 0x24, 0x01, 0x32, 0x0b, 0xd1, 0xb3, 0xf9, + 0x34, 0x25, 0x01, 0x32, 0x07, 0xd1, 0xb3, 0xf9, 0x04, 0x24, 0x01, 0x32, + 0x03, 0xd1, 0xb3, 0xf9, 0x38, 0x25, 0x01, 0x32, 0x08, 0xd0, 0x01, 0x25, + 0x10, 0x22, 0x83, 0xf8, 0x66, 0x55, 0x20, 0x46, 0x4f, 0xf4, 0x9a, 0x61, + 0x13, 0x46, 0x07, 0xe0, 0x00, 0x25, 0x83, 0xf8, 0x66, 0x55, 0x20, 0x46, + 0x4f, 0xf4, 0x9a, 0x61, 0x10, 0x22, 0x2b, 0x46, 0xfa, 0xf7, 0x3a, 0xff, + 0x4f, 0xf4, 0x8f, 0x61, 0x03, 0x22, 0x2b, 0x46, 0x20, 0x46, 0xfa, 0xf7, + 0x33, 0xff, 0x20, 0x46, 0xff, 0xf7, 0x7e, 0xfe, 0x20, 0x46, 0xfd, 0xf7, + 0xc9, 0xfb, 0x20, 0x46, 0xfe, 0xf7, 0x7e, 0xf8, 0x20, 0x46, 0xbd, 0xe8, + 0x38, 0x40, 0xff, 0xf7, 0xe7, 0xbe, 0x2d, 0xe9, 0xf0, 0x47, 0x8a, 0xb0, + 0x1e, 0x46, 0x0d, 0xf1, 0x27, 0x03, 0x05, 0x46, 0xd0, 0xf8, 0xa8, 0x40, + 0x88, 0x46, 0x00, 0x93, 0x09, 0xa9, 0x0d, 0xf1, 0x26, 0x03, 0x17, 0x46, + 0x0d, 0xf1, 0x25, 0x02, 0xfd, 0xf7, 0x28, 0xfb, 0x28, 0x46, 0x08, 0xa9, + 0x0d, 0xf1, 0x22, 0x02, 0xff, 0xf7, 0x78, 0xfa, 0x28, 0x46, 0xff, 0xf7, + 0x0d, 0xf9, 0x07, 0x23, 0x04, 0x93, 0x20, 0x23, 0x06, 0x93, 0x07, 0xab, + 0x02, 0x93, 0x01, 0x23, 0x03, 0x93, 0x4f, 0xf4, 0x50, 0x73, 0x81, 0x46, + 0x05, 0x93, 0x4f, 0xf0, 0x00, 0x0a, 0x35, 0xe0, 0x13, 0xb1, 0x18, 0xf0, + 0x01, 0x0f, 0x2f, 0xd1, 0x5b, 0xb2, 0x01, 0x33, 0xb8, 0xfb, 0xf3, 0xf3, + 0x03, 0xf5, 0xa0, 0x73, 0x28, 0x46, 0x02, 0xa9, 0x05, 0x93, 0xfe, 0xf7, + 0x8d, 0xff, 0x07, 0x9b, 0xbd, 0xf8, 0x22, 0xa0, 0x1b, 0x0d, 0x4f, 0xea, + 0x8a, 0x5a, 0x1b, 0x05, 0x4f, 0xea, 0x9a, 0x5a, 0x4a, 0xea, 0x03, 0x0a, + 0xbd, 0xf8, 0x20, 0x30, 0x28, 0x46, 0x9b, 0x05, 0x9b, 0x0d, 0x4a, 0xea, + 0x83, 0x2a, 0x02, 0xa9, 0xcd, 0xf8, 0x1c, 0xa0, 0xff, 0xf7, 0x59, 0xfa, + 0x94, 0xf9, 0x66, 0x35, 0x28, 0x46, 0x01, 0x33, 0xb8, 0xfb, 0xf3, 0xf3, + 0x03, 0xf5, 0xe0, 0x73, 0x02, 0xa9, 0xcd, 0xf8, 0x1c, 0x90, 0x05, 0x93, + 0xff, 0xf7, 0x4b, 0xfa, 0x08, 0xf1, 0x01, 0x08, 0xb8, 0x45, 0x94, 0xf8, + 0x66, 0x35, 0xc5, 0xd9, 0xbb, 0xb1, 0x7f, 0x2f, 0x15, 0xd1, 0x4f, 0xf4, + 0xc0, 0x77, 0x28, 0x46, 0x02, 0xa9, 0x05, 0x97, 0xcd, 0xf8, 0x1c, 0xa0, + 0xff, 0xf7, 0x39, 0xfa, 0x07, 0xf1, 0x80, 0x03, 0x28, 0x46, 0x02, 0xa9, + 0x01, 0x37, 0xcd, 0xf8, 0x1c, 0x90, 0x05, 0x93, 0xff, 0xf7, 0x2f, 0xfa, + 0xb7, 0xf5, 0xe0, 0x7f, 0xeb, 0xd1, 0xbd, 0xf8, 0x20, 0x20, 0x06, 0xf1, + 0x34, 0x03, 0x04, 0xeb, 0x43, 0x03, 0x9a, 0x80, 0xbd, 0xf8, 0x22, 0x20, + 0x04, 0xeb, 0x46, 0x06, 0x5a, 0x81, 0xa6, 0xf8, 0x78, 0x90, 0x9d, 0xf8, + 0x24, 0x30, 0x84, 0xf8, 0x7e, 0x30, 0x9d, 0xf8, 0x25, 0x30, 0x84, 0xf8, + 0x7f, 0x30, 0x9d, 0xf8, 0x26, 0x30, 0x84, 0xf8, 0x80, 0x30, 0x9d, 0xf8, + 0x27, 0x30, 0x84, 0xf8, 0x81, 0x30, 0x0a, 0xb0, 0xbd, 0xe8, 0xf0, 0x87, + 0x2d, 0xe9, 0xf0, 0x41, 0xd0, 0xf8, 0xa8, 0x40, 0x86, 0xb0, 0x94, 0xf9, + 0x07, 0x14, 0x4f, 0xf0, 0xff, 0x32, 0x89, 0xb2, 0x06, 0x46, 0xfe, 0xf7, + 0x26, 0xff, 0x94, 0xf9, 0x67, 0x35, 0x05, 0x46, 0x02, 0x2b, 0x08, 0xd1, + 0x94, 0xf9, 0x08, 0x14, 0x30, 0x46, 0x89, 0xb2, 0x4f, 0xf0, 0xff, 0x32, + 0xfe, 0xf7, 0x19, 0xff, 0x00, 0xe0, 0x00, 0x20, 0x07, 0x23, 0x02, 0x93, + 0x20, 0x23, 0x04, 0x93, 0x01, 0x23, 0x2f, 0x1a, 0x01, 0x93, 0x30, 0x46, + 0x05, 0xab, 0xb4, 0xf8, 0x68, 0x15, 0x4f, 0xf0, 0xff, 0x32, 0x00, 0x93, + 0xfe, 0xf7, 0x07, 0xff, 0x00, 0x23, 0xc0, 0x19, 0xa4, 0xf8, 0x6a, 0x35, + 0x48, 0xbf, 0xa4, 0xf8, 0x6a, 0x05, 0x00, 0x25, 0x94, 0xf8, 0x66, 0x35, + 0x0b, 0xb1, 0xe9, 0x07, 0x1c, 0xd4, 0x5b, 0xb2, 0x01, 0x33, 0x95, 0xfb, + 0xf3, 0xf3, 0xdb, 0xb2, 0x03, 0xf5, 0x10, 0x73, 0x03, 0x93, 0xb4, 0xf8, + 0x68, 0x35, 0xb4, 0xf9, 0x6a, 0x85, 0xab, 0x42, 0x29, 0x46, 0x30, 0x46, + 0x4f, 0xf0, 0xff, 0x32, 0x38, 0xbf, 0xc7, 0xeb, 0x08, 0x08, 0xfe, 0xf7, + 0xe4, 0xfe, 0xc8, 0xeb, 0x00, 0x00, 0x05, 0x90, 0x69, 0x46, 0x30, 0x46, + 0xff, 0xf7, 0xb5, 0xf9, 0x01, 0x35, 0xed, 0xb2, 0x80, 0x2d, 0xd9, 0xd1, + 0x94, 0xf9, 0x66, 0x35, 0x7b, 0xb1, 0x01, 0x23, 0x01, 0x93, 0x05, 0xab, + 0x00, 0x93, 0x40, 0x24, 0x04, 0xf5, 0x10, 0x73, 0x01, 0x34, 0x30, 0x46, + 0x69, 0x46, 0xe4, 0xb2, 0x03, 0x93, 0xff, 0xf7, 0xa0, 0xf9, 0x80, 0x2c, + 0xf4, 0xd1, 0x06, 0xb0, 0xbd, 0xe8, 0xf0, 0x81, 0x70, 0xb5, 0x00, 0x23, + 0x86, 0xb0, 0x02, 0x93, 0x10, 0x23, 0x04, 0x93, 0x05, 0xab, 0x00, 0x93, + 0x02, 0x23, 0x04, 0x46, 0xad, 0xf8, 0x14, 0x10, 0x01, 0x93, 0x0e, 0x46, + 0x50, 0x23, 0x69, 0x46, 0x15, 0x46, 0xad, 0xf8, 0x16, 0x20, 0x03, 0x93, + 0xff, 0xf7, 0x85, 0xf9, 0x20, 0x46, 0xfc, 0xf7, 0xcb, 0xfc, 0x78, 0xb3, + 0x20, 0x46, 0x40, 0xf6, 0x46, 0x11, 0x40, 0xf2, 0xff, 0x32, 0x33, 0x46, + 0xfa, 0xf7, 0xf4, 0xfd, 0x20, 0x46, 0x40, 0xf6, 0x47, 0x11, 0x40, 0xf2, + 0xff, 0x32, 0x2b, 0x46, 0xfa, 0xf7, 0xec, 0xfd, 0x20, 0x46, 0x4f, 0xf4, + 0x15, 0x61, 0x40, 0xf2, 0xff, 0x32, 0x33, 0x46, 0xfa, 0xf7, 0xe4, 0xfd, + 0x20, 0x46, 0x40, 0xf6, 0x51, 0x11, 0x40, 0xf2, 0xff, 0x32, 0x2b, 0x46, + 0xfa, 0xf7, 0xdc, 0xfd, 0x20, 0x46, 0x40, 0xf6, 0x54, 0x11, 0x40, 0xf2, + 0xff, 0x32, 0x33, 0x46, 0xfa, 0xf7, 0xd4, 0xfd, 0x20, 0x46, 0x40, 0xf6, + 0x55, 0x11, 0x40, 0xf2, 0xff, 0x32, 0x2b, 0x46, 0xfa, 0xf7, 0xcc, 0xfd, + 0x06, 0xb0, 0x70, 0xbd, 0xf0, 0xb5, 0x29, 0x4b, 0x8b, 0xb0, 0x04, 0x46, + 0x05, 0xad, 0x0e, 0x46, 0x0f, 0xcb, 0x85, 0xe8, 0x0f, 0x00, 0x04, 0xf5, + 0x82, 0x53, 0x1b, 0x79, 0xd4, 0xf8, 0xa8, 0x50, 0x1b, 0xb1, 0x95, 0xf8, + 0xe0, 0x34, 0x00, 0x2b, 0x3e, 0xd0, 0x20, 0x46, 0x20, 0x49, 0x08, 0x22, + 0xfa, 0xf7, 0xc4, 0xfd, 0x07, 0x23, 0x02, 0x93, 0x20, 0x23, 0x04, 0x93, + 0x04, 0x23, 0x01, 0x93, 0x01, 0x27, 0x05, 0xab, 0x00, 0x93, 0x85, 0xf8, + 0x6a, 0x70, 0x4f, 0xf4, 0x50, 0x73, 0x20, 0x46, 0x69, 0x46, 0x03, 0x93, + 0xff, 0xf7, 0x25, 0xf9, 0x00, 0x23, 0x09, 0x93, 0x09, 0xab, 0x01, 0x97, + 0x00, 0x93, 0x4f, 0xf4, 0x51, 0x75, 0x20, 0x46, 0x69, 0x46, 0x03, 0x95, + 0xff, 0xf7, 0x19, 0xf9, 0x01, 0x35, 0x40, 0xf2, 0x5e, 0x33, 0x9d, 0x42, + 0xf5, 0xd1, 0x20, 0x46, 0x0d, 0x49, 0x12, 0x22, 0xfa, 0xf7, 0x9c, 0xfd, + 0x76, 0x00, 0x4f, 0xf6, 0xfe, 0x73, 0x20, 0x46, 0x40, 0xf2, 0xa9, 0x41, + 0x40, 0xf2, 0xff, 0x12, 0x33, 0x40, 0xfa, 0xf7, 0x7f, 0xfd, 0x20, 0x46, + 0x40, 0xf2, 0xa3, 0x61, 0x10, 0x22, 0x00, 0x23, 0xfa, 0xf7, 0x78, 0xfd, + 0x0b, 0xb0, 0xf0, 0xbd, 0x64, 0xb8, 0x01, 0x00, 0x3a, 0xe9, 0x01, 0x00, + 0x98, 0xe9, 0x01, 0x00, 0x30, 0xb5, 0x18, 0x23, 0x87, 0xb0, 0x03, 0x93, + 0x20, 0x23, 0xd0, 0xf8, 0xa8, 0x40, 0x05, 0x93, 0x80, 0x23, 0x02, 0x93, + 0x00, 0x23, 0x06, 0xa9, 0x04, 0x93, 0x04, 0xf1, 0x9c, 0x03, 0x05, 0x46, + 0x41, 0xf8, 0x14, 0x3d, 0xff, 0xf7, 0xe1, 0xf8, 0x28, 0x46, 0xb4, 0xf8, + 0x9c, 0x22, 0x40, 0xf2, 0x71, 0x61, 0xfa, 0xf7, 0x6f, 0xfb, 0x28, 0x46, + 0xb4, 0xf8, 0x9e, 0x22, 0x40, 0xf2, 0x73, 0x61, 0xfa, 0xf7, 0x68, 0xfb, + 0x28, 0x46, 0xb4, 0xf8, 0xa2, 0x22, 0x40, 0xf2, 0x74, 0x61, 0xfa, 0xf7, + 0x61, 0xfb, 0x28, 0x46, 0xb4, 0xf8, 0xa0, 0x22, 0x40, 0xf2, 0x75, 0x61, + 0xfa, 0xf7, 0x5a, 0xfb, 0x28, 0x46, 0xb4, 0xf8, 0xa4, 0x22, 0x40, 0xf2, + 0x79, 0x61, 0xfa, 0xf7, 0x53, 0xfb, 0x28, 0x46, 0xb4, 0xf8, 0xa6, 0x22, + 0x40, 0xf2, 0x76, 0x61, 0xfa, 0xf7, 0x4c, 0xfb, 0x28, 0x46, 0xb4, 0xf8, + 0xa8, 0x22, 0x40, 0xf2, 0xda, 0x61, 0xfa, 0xf7, 0x45, 0xfb, 0x28, 0x46, + 0xb4, 0xf8, 0xaa, 0x22, 0x40, 0xf2, 0x25, 0x51, 0xfa, 0xf7, 0x3e, 0xfb, + 0x28, 0x46, 0xb4, 0xf8, 0xae, 0x22, 0x4f, 0xf4, 0x8f, 0x61, 0xfa, 0xf7, + 0x37, 0xfb, 0x28, 0x46, 0xb4, 0xf8, 0xb0, 0x22, 0x4f, 0xf4, 0x9a, 0x61, + 0xfa, 0xf7, 0x30, 0xfb, 0xb4, 0xf8, 0xb2, 0x32, 0x4f, 0xf4, 0x00, 0x42, + 0xdb, 0x03, 0x28, 0x46, 0x13, 0x40, 0x40, 0xf2, 0x24, 0x51, 0xfa, 0xf7, + 0x0b, 0xfd, 0x94, 0xf8, 0xac, 0x32, 0x28, 0x46, 0x84, 0xf8, 0x67, 0x35, + 0xb4, 0xf8, 0xb4, 0x32, 0xa4, 0xf8, 0x68, 0x35, 0x94, 0xf8, 0xb6, 0x32, + 0x84, 0xf8, 0x07, 0x34, 0x94, 0xf8, 0xb7, 0x32, 0x84, 0xf8, 0x08, 0x34, + 0xff, 0xf7, 0x72, 0xfe, 0x07, 0xb0, 0x30, 0xbd, 0x2d, 0xe9, 0xf0, 0x4f, + 0xc3, 0x69, 0x0e, 0x46, 0x4f, 0xf0, 0x80, 0x51, 0xbb, 0xb0, 0x04, 0x46, + 0xd0, 0xf8, 0xa8, 0x50, 0x17, 0x46, 0x18, 0x69, 0x0a, 0x46, 0x3a, 0xf0, + 0x91, 0xd8, 0x05, 0x20, 0xf0, 0xf3, 0xe0, 0xf0, 0x20, 0x46, 0x4f, 0xf4, + 0x89, 0x61, 0x4f, 0xf4, 0x80, 0x42, 0x00, 0x23, 0xfa, 0xf7, 0xdc, 0xfc, + 0x01, 0x22, 0x20, 0x46, 0x40, 0xf2, 0x0a, 0x51, 0x13, 0x46, 0xfa, 0xf7, + 0xd5, 0xfc, 0x0d, 0xf1, 0xe6, 0x03, 0x34, 0x93, 0x01, 0x23, 0x35, 0x93, + 0x11, 0x23, 0x36, 0x93, 0x0f, 0x23, 0x37, 0x93, 0x20, 0x46, 0x08, 0x23, + 0x34, 0xa9, 0x38, 0x93, 0xfe, 0xf7, 0x68, 0xfd, 0x00, 0x2e, 0x40, 0xf0, + 0x4a, 0x81, 0xb4, 0xf8, 0xda, 0x30, 0x03, 0xf4, 0x70, 0x43, 0xb3, 0xf5, + 0x00, 0x5f, 0x0c, 0xd1, 0xe3, 0x69, 0x95, 0xf8, 0xbf, 0x64, 0x1b, 0x6d, + 0x03, 0xf4, 0x80, 0x53, 0x00, 0x2b, 0x0c, 0xbf, 0x08, 0x23, 0x06, 0x23, + 0xff, 0x2e, 0x08, 0xbf, 0x1e, 0x46, 0x9d, 0xf8, 0xe6, 0x30, 0x6f, 0xf0, + 0x02, 0x02, 0x02, 0xfb, 0x06, 0x32, 0x3a, 0xab, 0x03, 0xf8, 0x01, 0x2d, + 0x34, 0x93, 0x20, 0x46, 0x10, 0x23, 0x34, 0xa9, 0x37, 0x93, 0x77, 0x00, + 0xff, 0xf7, 0x23, 0xf8, 0x4f, 0xf6, 0xfe, 0x73, 0xfe, 0x22, 0x20, 0x46, + 0x40, 0xf2, 0x0a, 0x51, 0x3b, 0x40, 0xfa, 0xf7, 0x95, 0xfc, 0x95, 0xf8, + 0xc0, 0x54, 0xff, 0x2d, 0x00, 0xf0, 0xec, 0x80, 0x00, 0x2d, 0x00, 0xf0, + 0xcb, 0x80, 0x10, 0x2d, 0x28, 0xbf, 0x10, 0x25, 0xc5, 0xf1, 0x24, 0x07, + 0xff, 0xb2, 0xf6, 0xb2, 0x72, 0xb2, 0x7b, 0xb2, 0x9a, 0x42, 0x03, 0xdc, + 0x00, 0x2e, 0x14, 0xbf, 0x37, 0x46, 0x01, 0x27, 0x7a, 0xb2, 0xaa, 0x42, + 0x05, 0xf1, 0x01, 0x06, 0xcc, 0xbf, 0x5f, 0xfa, 0x86, 0xfb, 0xbb, 0x46, + 0xcb, 0xeb, 0x06, 0x06, 0x0d, 0x23, 0xf6, 0xb2, 0x36, 0x93, 0x20, 0x23, + 0x4f, 0xfa, 0x86, 0xf8, 0x38, 0x93, 0x09, 0xab, 0x03, 0xeb, 0xc8, 0x03, + 0x00, 0x93, 0x4f, 0xfa, 0x8b, 0xf3, 0x5b, 0x00, 0x01, 0x93, 0x73, 0x00, + 0x01, 0x33, 0x03, 0xf0, 0xff, 0x03, 0x02, 0x93, 0x6b, 0x00, 0x01, 0x33, + 0x03, 0x93, 0x05, 0xf1, 0x01, 0x0a, 0x4f, 0xea, 0x48, 0x03, 0x4f, 0xea, + 0x4a, 0x00, 0x59, 0x1c, 0xcd, 0xf8, 0x18, 0xb0, 0x07, 0x96, 0x05, 0x90, + 0x04, 0x91, 0x4f, 0xf0, 0x00, 0x09, 0x93, 0x46, 0x1e, 0x46, 0x01, 0x9b, + 0xab, 0x45, 0x35, 0x93, 0xca, 0xbf, 0x7b, 0xb2, 0xcd, 0xf8, 0xdc, 0xa0, + 0x37, 0x93, 0x37, 0x9b, 0x00, 0x9a, 0x4b, 0x44, 0x5b, 0x00, 0x20, 0x46, + 0x34, 0xa9, 0x37, 0x93, 0x34, 0x92, 0xfe, 0xf7, 0xdd, 0xfc, 0x02, 0x9b, + 0x0a, 0xe0, 0x3a, 0xa8, 0x00, 0xeb, 0x83, 0x02, 0x52, 0xf8, 0xc4, 0x1c, + 0x02, 0x33, 0x41, 0xf0, 0x80, 0x01, 0x42, 0xf8, 0xc4, 0x1c, 0xdb, 0xb2, + 0x03, 0x9a, 0x93, 0x42, 0xf1, 0xdd, 0x00, 0x23, 0x13, 0xe0, 0x3a, 0xa8, + 0x00, 0xeb, 0x86, 0x02, 0x52, 0xf8, 0xc4, 0x1c, 0x00, 0xeb, 0x83, 0x02, + 0x42, 0xf8, 0xc4, 0x1c, 0x04, 0x99, 0x00, 0xeb, 0x81, 0x02, 0x52, 0xf8, + 0xc4, 0x1c, 0x00, 0xeb, 0x83, 0x02, 0x02, 0x33, 0x42, 0xf8, 0xc0, 0x1c, + 0xdb, 0xb2, 0xb3, 0x42, 0xe9, 0xdb, 0x05, 0x9a, 0x09, 0xab, 0x34, 0x93, + 0x20, 0x46, 0x4f, 0xea, 0x49, 0x03, 0x34, 0xa9, 0x09, 0xf1, 0x25, 0x09, + 0x35, 0x92, 0x37, 0x93, 0xfe, 0xf7, 0x8b, 0xff, 0xb9, 0xf1, 0x4a, 0x0f, + 0xb5, 0xd1, 0x0e, 0x23, 0x5a, 0x46, 0x2b, 0xa8, 0xdd, 0xf8, 0x18, 0xb0, + 0x36, 0x93, 0x10, 0x23, 0x38, 0x93, 0xaa, 0x42, 0x00, 0xeb, 0x48, 0x03, + 0x34, 0x93, 0xc8, 0xbf, 0x7f, 0xb2, 0x4f, 0xfa, 0x8b, 0xf3, 0x20, 0x46, + 0x34, 0xa9, 0x07, 0x9e, 0x35, 0x93, 0xd4, 0xbf, 0xcd, 0xf8, 0xdc, 0xa0, + 0x37, 0x97, 0xfe, 0xf7, 0x8b, 0xfc, 0x0a, 0xe0, 0x3a, 0xa9, 0x01, 0xeb, + 0x46, 0x03, 0x33, 0xf8, 0x3c, 0x2c, 0x01, 0x36, 0x42, 0xf4, 0x00, 0x62, + 0x23, 0xf8, 0x3c, 0x2c, 0xf6, 0xb2, 0xae, 0x42, 0xf2, 0xd9, 0x00, 0x23, + 0x0a, 0xe0, 0x3a, 0xaa, 0x02, 0xeb, 0x48, 0x01, 0x31, 0xf8, 0x3c, 0x1c, + 0x02, 0xeb, 0x43, 0x02, 0x01, 0x33, 0x22, 0xf8, 0x3c, 0x1c, 0xdb, 0xb2, + 0x43, 0x45, 0xf2, 0xdb, 0x2b, 0xab, 0x34, 0x93, 0x20, 0x46, 0x00, 0x23, + 0x34, 0xa9, 0xcd, 0xf8, 0xd4, 0xa0, 0x37, 0x93, 0xfe, 0xf7, 0x47, 0xff, + 0x01, 0x22, 0x13, 0x46, 0x20, 0x46, 0x40, 0xf2, 0x0e, 0x51, 0xfa, 0xf7, + 0xbb, 0xfb, 0x4f, 0xf4, 0x7e, 0x42, 0x6b, 0x02, 0x13, 0x40, 0x20, 0x46, + 0x40, 0xf2, 0x0e, 0x51, 0xfa, 0xf7, 0xb2, 0xfb, 0x20, 0x46, 0x40, 0xf2, + 0x0f, 0x51, 0x7f, 0x22, 0x2b, 0x46, 0xfa, 0xf7, 0xab, 0xfb, 0x20, 0x46, + 0x40, 0xf2, 0x0f, 0x51, 0x4f, 0xf4, 0x7e, 0x52, 0xeb, 0x01, 0x1b, 0xe0, + 0x20, 0x46, 0x40, 0xf2, 0x0e, 0x51, 0x01, 0x22, 0x00, 0x23, 0xfa, 0xf7, + 0x9d, 0xfb, 0x20, 0x46, 0x40, 0xf2, 0x0e, 0x51, 0x4f, 0xf4, 0x7e, 0x42, + 0x00, 0x23, 0xfa, 0xf7, 0x95, 0xfb, 0x20, 0x46, 0x40, 0xf2, 0x0f, 0x51, + 0x7f, 0x22, 0x00, 0x23, 0xfa, 0xf7, 0x8e, 0xfb, 0x20, 0x46, 0x40, 0xf2, + 0x0f, 0x51, 0x4f, 0xf4, 0x7e, 0x52, 0x00, 0x23, 0xfa, 0xf7, 0x86, 0xfb, + 0xe3, 0x69, 0x4f, 0xf0, 0x80, 0x51, 0x18, 0x69, 0x00, 0x22, 0x39, 0xf0, + 0x29, 0xdf, 0x20, 0x46, 0xfd, 0xf7, 0xb8, 0xfb, 0x3b, 0xb0, 0xbd, 0xe8, + 0xf0, 0x8f, 0x3e, 0x46, 0xc7, 0xe6, 0x38, 0xb5, 0x40, 0xf2, 0xa4, 0x41, + 0x05, 0x46, 0xd0, 0xf8, 0xa8, 0x40, 0xfa, 0xf7, 0x7e, 0xf9, 0x80, 0x0b, + 0x80, 0xb2, 0x03, 0x28, 0x12, 0xd1, 0x05, 0xf5, 0x82, 0x53, 0x1b, 0x79, + 0x73, 0xb1, 0x28, 0x46, 0x40, 0xf2, 0x73, 0x41, 0xfa, 0xf7, 0x71, 0xf9, + 0x94, 0xf9, 0x66, 0x35, 0xc0, 0x05, 0xc0, 0x0d, 0x01, 0x33, 0x58, 0x43, + 0x00, 0xeb, 0xd0, 0x70, 0x40, 0x10, 0x01, 0xe0, 0x94, 0xf8, 0xc1, 0x02, + 0x40, 0xb2, 0x38, 0xbd, 0x70, 0xb5, 0xc6, 0xb0, 0x01, 0xad, 0xd0, 0xf8, + 0xa8, 0x60, 0x04, 0x46, 0x00, 0x21, 0x28, 0x46, 0x4f, 0xf4, 0x80, 0x72, + 0xeb, 0xf3, 0xb8, 0xf3, 0x07, 0x23, 0x43, 0x93, 0x20, 0x23, 0x45, 0x93, + 0x96, 0xf8, 0x6a, 0x30, 0x41, 0x95, 0x43, 0xb9, 0x1e, 0x23, 0x42, 0x93, + 0x20, 0x46, 0x4f, 0xf4, 0x50, 0x73, 0x41, 0xa9, 0x44, 0x93, 0xfe, 0xf7, + 0xbc, 0xfe, 0x40, 0x23, 0x42, 0x93, 0x20, 0x46, 0x80, 0x23, 0x41, 0xa9, + 0x44, 0x93, 0xfe, 0xf7, 0xb4, 0xfe, 0x46, 0xb0, 0x70, 0xbd, 0x00, 0x00, + 0x30, 0xb5, 0x07, 0x23, 0x89, 0xb0, 0x03, 0x93, 0x20, 0x23, 0x05, 0x93, + 0x06, 0xab, 0x01, 0x93, 0x01, 0x23, 0x02, 0x93, 0x00, 0x23, 0x04, 0x46, + 0xd0, 0xf8, 0xa8, 0x50, 0x04, 0x93, 0x08, 0xe0, 0x20, 0x46, 0x01, 0xa9, + 0xfe, 0xf7, 0x9d, 0xfe, 0x04, 0x9b, 0x01, 0x33, 0x04, 0x93, 0x06, 0x9b, + 0x01, 0x33, 0x06, 0x93, 0x06, 0x9b, 0x7f, 0x2b, 0xf2, 0xd9, 0x4f, 0xf4, + 0x30, 0x73, 0x04, 0x93, 0x00, 0x23, 0x07, 0xe0, 0x01, 0xa9, 0xfe, 0xf7, + 0x8c, 0xfe, 0x04, 0x9b, 0x01, 0x33, 0x04, 0x93, 0x06, 0x9b, 0x01, 0x33, + 0x06, 0x93, 0x06, 0x9b, 0x20, 0x46, 0x7f, 0x2b, 0xf2, 0xd9, 0x09, 0x22, + 0x5a, 0x49, 0xfa, 0xf7, 0x0b, 0xfb, 0x01, 0x21, 0x20, 0x46, 0xfd, 0xf7, + 0x7d, 0xf8, 0x24, 0x22, 0x20, 0x46, 0x57, 0x49, 0xfa, 0xf7, 0x02, 0xfb, + 0x20, 0x46, 0xfc, 0xf7, 0xab, 0xfb, 0x40, 0x08, 0x80, 0xb2, 0xe6, 0x28, + 0x06, 0xdc, 0x20, 0x46, 0xfc, 0xf7, 0xa4, 0xfb, 0x43, 0x08, 0x19, 0x33, + 0x9b, 0xb2, 0x00, 0xe0, 0xff, 0x23, 0xff, 0x22, 0x20, 0x46, 0x40, 0xf2, + 0xa5, 0x41, 0xfa, 0xf7, 0xdb, 0xfa, 0x20, 0x46, 0xff, 0xf7, 0x84, 0xff, + 0xb5, 0xf8, 0xe6, 0x23, 0xb5, 0xf8, 0xe4, 0x33, 0x20, 0x46, 0x03, 0xeb, + 0x42, 0x05, 0xad, 0x01, 0x4f, 0xf6, 0xc0, 0x73, 0x2b, 0x40, 0x4f, 0xf4, + 0x9a, 0x61, 0x47, 0xf6, 0xc0, 0x72, 0xfa, 0xf7, 0xc7, 0xfa, 0x20, 0x46, + 0x09, 0x22, 0x41, 0x49, 0xfa, 0xf7, 0xd4, 0xfa, 0xb4, 0xf8, 0xda, 0x30, + 0x20, 0x46, 0x03, 0xf4, 0x70, 0x43, 0x28, 0x21, 0x1e, 0x22, 0xb3, 0xf5, + 0x00, 0x5f, 0x14, 0xbf, 0x18, 0x23, 0x1c, 0x23, 0xfa, 0xf7, 0x72, 0xfa, + 0x01, 0x22, 0x20, 0x46, 0x3a, 0x21, 0x13, 0x46, 0xfa, 0xf7, 0x6c, 0xfa, + 0x08, 0x22, 0x13, 0x46, 0x20, 0x46, 0x4f, 0xf4, 0x8d, 0x71, 0xfa, 0xf7, + 0x65, 0xfa, 0x20, 0x46, 0x25, 0x21, 0x0c, 0x22, 0xfa, 0xf7, 0x8b, 0xf8, + 0xb4, 0xf8, 0xda, 0x30, 0x02, 0x22, 0x03, 0xf4, 0x70, 0x43, 0x3a, 0x21, + 0xb3, 0xf5, 0x00, 0x5f, 0x08, 0xbf, 0x13, 0x46, 0x20, 0x46, 0x18, 0xbf, + 0x00, 0x23, 0xfa, 0xf7, 0x51, 0xfa, 0x08, 0x22, 0x13, 0x46, 0x20, 0x46, + 0x05, 0x21, 0xfa, 0xf7, 0x4b, 0xfa, 0x20, 0x46, 0x06, 0x22, 0x25, 0x49, + 0xfa, 0xf7, 0x9a, 0xfa, 0x47, 0xf2, 0x08, 0x02, 0x20, 0x46, 0x40, 0xf2, + 0xd7, 0x41, 0x4f, 0xf4, 0x00, 0x53, 0xfa, 0xf7, 0x7f, 0xfa, 0x20, 0x46, + 0xfc, 0xf7, 0x3a, 0xfb, 0x10, 0x23, 0x05, 0x93, 0x0d, 0xf1, 0x1e, 0x03, + 0x01, 0x93, 0x01, 0x23, 0x08, 0x25, 0xad, 0xf8, 0x1e, 0x00, 0x02, 0x93, + 0x20, 0x46, 0x06, 0x23, 0x01, 0xa9, 0x04, 0x93, 0x03, 0x95, 0xfe, 0xf7, + 0xf0, 0xfd, 0x20, 0x46, 0x0f, 0x22, 0x15, 0x49, 0xfa, 0xf7, 0x78, 0xfa, + 0x20, 0x46, 0x35, 0x21, 0xff, 0x22, 0x00, 0x23, 0xfa, 0xf7, 0x1e, 0xfa, + 0x20, 0x46, 0x36, 0x21, 0x03, 0x22, 0x00, 0x23, 0xfa, 0xf7, 0x18, 0xfa, + 0x20, 0x46, 0x2a, 0x46, 0x2b, 0x46, 0x4f, 0xf4, 0x8d, 0x71, 0xfa, 0xf7, + 0x11, 0xfa, 0x4f, 0xf4, 0x80, 0x62, 0x20, 0x46, 0x40, 0xf2, 0xa4, 0x41, + 0x13, 0x46, 0xfa, 0xf7, 0x4b, 0xfa, 0x20, 0x46, 0xfd, 0xf7, 0x2e, 0xf8, + 0x09, 0xb0, 0x30, 0xbd, 0x08, 0xec, 0x01, 0x00, 0x1a, 0xec, 0x01, 0x00, + 0x62, 0xec, 0x01, 0x00, 0x74, 0xec, 0x01, 0x00, 0x38, 0xef, 0x01, 0x00, + 0x2d, 0xe9, 0xf0, 0x41, 0x04, 0x46, 0xd0, 0xf8, 0xa8, 0x50, 0xfc, 0xf7, + 0xdc, 0xf9, 0xb0, 0xf5, 0x40, 0x4f, 0x48, 0xd1, 0xe3, 0x69, 0xe0, 0x21, + 0x18, 0x69, 0x39, 0xf0, 0xf7, 0xdd, 0xb5, 0xf8, 0x2e, 0x80, 0x07, 0x46, + 0xc8, 0xeb, 0x00, 0x08, 0x40, 0xf2, 0xa5, 0x41, 0x20, 0x46, 0xfa, 0xf7, + 0x32, 0xf8, 0x00, 0xf4, 0xe0, 0x60, 0x06, 0x0a, 0x01, 0x23, 0xb3, 0x40, + 0x1f, 0xfa, 0x88, 0xf8, 0x98, 0x45, 0x30, 0xdd, 0x95, 0xf8, 0xc1, 0x34, + 0xef, 0x85, 0xb3, 0x42, 0x08, 0xd9, 0x01, 0x36, 0x20, 0x46, 0x40, 0xf2, + 0xa5, 0x41, 0x4f, 0xf4, 0xe0, 0x62, 0x33, 0x02, 0xfa, 0xf7, 0x0c, 0xfa, + 0x20, 0x46, 0xff, 0xf7, 0x92, 0xfe, 0xb4, 0xf8, 0xda, 0x30, 0x80, 0xb2, + 0x03, 0xf4, 0x70, 0x43, 0xb3, 0xf5, 0x00, 0x5f, 0x0c, 0xbf, 0x85, 0xf8, + 0x54, 0x04, 0x85, 0xf8, 0x55, 0x04, 0x28, 0x86, 0x6e, 0x86, 0xd4, 0xf8, + 0xa8, 0x30, 0x40, 0x00, 0x93, 0xf9, 0x66, 0x35, 0x40, 0xf2, 0xa4, 0x41, + 0x01, 0x33, 0x90, 0xfb, 0xf3, 0xf3, 0x40, 0xf2, 0xff, 0x12, 0x20, 0x46, + 0x9b, 0xb2, 0xbd, 0xe8, 0xf0, 0x41, 0xfa, 0xf7, 0xe9, 0xb9, 0xbd, 0xe8, + 0xf0, 0x81, 0x00, 0x00, 0x2d, 0xe9, 0xf0, 0x4f, 0x04, 0x46, 0x85, 0xb0, + 0x0f, 0x46, 0xd0, 0xf8, 0xa8, 0x50, 0xff, 0xf7, 0xa1, 0xff, 0xd4, 0xf8, + 0xb0, 0x30, 0xd3, 0xf8, 0x20, 0x31, 0x03, 0xf0, 0x01, 0x03, 0x83, 0xf0, + 0x01, 0x02, 0x01, 0x92, 0x1b, 0xb1, 0xe3, 0x69, 0x18, 0x69, 0x39, 0xf0, + 0xe9, 0xdd, 0x07, 0x21, 0x20, 0x46, 0xf9, 0xf7, 0x9d, 0xff, 0xff, 0x21, + 0xc6, 0xb2, 0x20, 0x46, 0xf9, 0xf7, 0x98, 0xff, 0x40, 0xf2, 0x1f, 0x11, + 0x5f, 0xfa, 0x80, 0xf8, 0x20, 0x46, 0xf9, 0xf7, 0x91, 0xff, 0x40, 0xf2, + 0x3b, 0x41, 0x5f, 0xfa, 0x80, 0xf9, 0x20, 0x46, 0xf9, 0xf7, 0xc7, 0xff, + 0x40, 0xf2, 0x3c, 0x41, 0x82, 0x46, 0x20, 0x46, 0xf9, 0xf7, 0xc1, 0xff, + 0x40, 0xf2, 0xd7, 0x41, 0x83, 0x46, 0x20, 0x46, 0xf9, 0xf7, 0xbb, 0xff, + 0x4f, 0xf4, 0x9b, 0x61, 0x02, 0x90, 0x20, 0x46, 0xf9, 0xf7, 0xb5, 0xff, + 0x0f, 0x22, 0x03, 0x90, 0x3f, 0x49, 0x20, 0x46, 0xfa, 0xf7, 0xb2, 0xf9, + 0x01, 0x22, 0x07, 0x21, 0x13, 0x46, 0x20, 0x46, 0xfa, 0xf7, 0x58, 0xf9, + 0x10, 0x22, 0xff, 0x21, 0x13, 0x46, 0x20, 0x46, 0xfa, 0xf7, 0x52, 0xf9, + 0x04, 0x22, 0x13, 0x46, 0x40, 0xf2, 0x1f, 0x11, 0x20, 0x46, 0xfa, 0xf7, + 0x4b, 0xf9, 0x0a, 0x20, 0xef, 0xf3, 0x86, 0xf5, 0x20, 0x22, 0x20, 0x46, + 0x4f, 0xf4, 0x9a, 0x61, 0x13, 0x46, 0xfa, 0xf7, 0x83, 0xf9, 0x0a, 0x20, + 0xef, 0xf3, 0x7c, 0xf5, 0x01, 0x2f, 0x20, 0x46, 0x1c, 0xd1, 0x40, 0xf2, + 0x76, 0x41, 0xf9, 0xf7, 0x88, 0xff, 0x40, 0xf2, 0x77, 0x41, 0xc7, 0x05, + 0x20, 0x46, 0xf9, 0xf7, 0x82, 0xff, 0xc0, 0x05, 0xc0, 0x0d, 0xff, 0x0d, + 0xff, 0x28, 0xa5, 0xf8, 0x6e, 0x05, 0x88, 0xbf, 0xa0, 0xf5, 0x00, 0x70, + 0xff, 0x2f, 0xa5, 0xf8, 0x6c, 0x75, 0x88, 0xbf, 0xa7, 0xf5, 0x00, 0x77, + 0x80, 0xb2, 0xbf, 0xb2, 0xc5, 0x1b, 0x09, 0xe0, 0x40, 0xf2, 0x75, 0x41, + 0xf9, 0xf7, 0x6b, 0xff, 0xc5, 0x05, 0xed, 0x0d, 0xff, 0x2d, 0x88, 0xbf, + 0xa5, 0xf5, 0x00, 0x75, 0x20, 0x46, 0x07, 0x21, 0x32, 0x46, 0xf9, 0xf7, + 0x3a, 0xff, 0x20, 0x46, 0xff, 0x21, 0x42, 0x46, 0xf9, 0xf7, 0x35, 0xff, + 0x20, 0x46, 0x40, 0xf2, 0x1f, 0x11, 0x4a, 0x46, 0xf9, 0xf7, 0x2f, 0xff, + 0x20, 0x46, 0x40, 0xf2, 0x3b, 0x41, 0x52, 0x46, 0xf9, 0xf7, 0x5a, 0xff, + 0x20, 0x46, 0x40, 0xf2, 0x3c, 0x41, 0x5a, 0x46, 0xf9, 0xf7, 0x54, 0xff, + 0x20, 0x46, 0x40, 0xf2, 0xd7, 0x41, 0x02, 0x9a, 0xf9, 0xf7, 0x4e, 0xff, + 0x20, 0x46, 0x4f, 0xf4, 0x9b, 0x61, 0x03, 0x9a, 0xf9, 0xf7, 0x48, 0xff, + 0x01, 0x9b, 0x1b, 0xb9, 0xe3, 0x69, 0x18, 0x69, 0x39, 0xf0, 0x2e, 0xdd, + 0x28, 0xb2, 0x05, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, 0xea, 0xeb, 0x01, 0x00, + 0x41, 0x43, 0x92, 0x02, 0x9b, 0x01, 0x00, 0xfb, 0x03, 0x20, 0x01, 0xf5, + 0x00, 0x41, 0x01, 0xeb, 0x40, 0x00, 0x49, 0x00, 0x90, 0xfb, 0xf1, 0xf0, + 0x70, 0x47, 0x30, 0xb5, 0x00, 0x23, 0x8b, 0xb0, 0x07, 0x93, 0x08, 0x93, + 0x09, 0x93, 0x07, 0x23, 0x03, 0x93, 0x4f, 0xf0, 0x20, 0x03, 0x00, 0x29, + 0x05, 0x93, 0x06, 0xab, 0x18, 0xbf, 0x4f, 0xf4, 0x30, 0x71, 0x01, 0x93, + 0x4f, 0xf0, 0x01, 0x03, 0x05, 0x46, 0x04, 0x91, 0x02, 0x93, 0x05, 0xd1, + 0x07, 0xa9, 0x08, 0xaa, 0x09, 0xab, 0xfb, 0xf7, 0x67, 0xfe, 0x08, 0xe0, + 0xb0, 0xf9, 0x02, 0x31, 0x08, 0x93, 0xb0, 0xf9, 0x04, 0x31, 0x09, 0x93, + 0xb0, 0xf9, 0x06, 0x31, 0x07, 0x93, 0x00, 0x24, 0x07, 0xa9, 0x0e, 0xc9, + 0x20, 0x46, 0xff, 0xf7, 0xc7, 0xff, 0x01, 0xa9, 0x06, 0x90, 0x28, 0x46, + 0xfe, 0xf7, 0x69, 0xfc, 0x04, 0x9b, 0x01, 0x34, 0x01, 0x33, 0x80, 0x2c, + 0x04, 0x93, 0xef, 0xd1, 0x0b, 0xb0, 0x30, 0xbd, 0x2d, 0xe9, 0xf0, 0x41, + 0x04, 0x46, 0x8a, 0xb0, 0x0d, 0x46, 0x49, 0xb1, 0x40, 0xf2, 0xd7, 0x41, + 0xf9, 0xf7, 0xe1, 0xfe, 0x01, 0xa9, 0x06, 0x46, 0x20, 0x46, 0xfc, 0xf7, + 0x19, 0xff, 0x00, 0xe0, 0x0e, 0x46, 0x20, 0x22, 0x13, 0x46, 0x4f, 0xf4, + 0x9a, 0x61, 0x20, 0x46, 0xfa, 0xf7, 0xc4, 0xf8, 0x64, 0x20, 0xef, 0xf3, + 0xbd, 0xf4, 0x40, 0xf2, 0x76, 0x41, 0x20, 0x46, 0xf9, 0xf7, 0xcb, 0xfe, + 0x40, 0xf2, 0xa6, 0x41, 0x07, 0x46, 0x20, 0x46, 0xf9, 0xf7, 0xc5, 0xfe, + 0x80, 0x46, 0xff, 0x05, 0x4f, 0xea, 0xc8, 0x58, 0xff, 0x0d, 0x4f, 0xea, + 0xd8, 0x58, 0x20, 0x46, 0x07, 0xa9, 0x08, 0xaa, 0x09, 0xab, 0x87, 0xf4, + 0x80, 0x77, 0x88, 0xf4, 0x80, 0x78, 0xfb, 0xf7, 0x13, 0xfe, 0xc8, 0xeb, + 0x07, 0x00, 0x00, 0xf5, 0xfe, 0x70, 0x03, 0x30, 0x07, 0xa9, 0x80, 0x10, + 0x0e, 0xc9, 0xff, 0xf7, 0x79, 0xff, 0x47, 0x00, 0x4d, 0xb1, 0x20, 0x46, + 0x01, 0xa9, 0xfc, 0xf7, 0x9b, 0xfd, 0x20, 0x46, 0x40, 0xf2, 0xd7, 0x41, + 0x32, 0x46, 0xf9, 0xf7, 0xa9, 0xfe, 0x38, 0x46, 0x0a, 0xb0, 0xbd, 0xe8, + 0xf0, 0x81, 0x2d, 0xe9, 0xf8, 0x4f, 0x9d, 0xf8, 0x28, 0x50, 0x8b, 0x46, + 0x92, 0x46, 0x99, 0x46, 0x9d, 0xf8, 0x2c, 0x70, 0xbd, 0xb1, 0x00, 0x26, + 0x6f, 0xf0, 0x00, 0x48, 0x35, 0x46, 0x28, 0x46, 0x59, 0x46, 0x52, 0x46, + 0x4b, 0x46, 0xff, 0xf7, 0x55, 0xff, 0x40, 0x45, 0x04, 0xda, 0x01, 0x36, + 0xf6, 0xb2, 0xbe, 0x42, 0x1b, 0xd0, 0x80, 0x46, 0x01, 0x35, 0x80, 0x2d, + 0xef, 0xd1, 0x6f, 0xf0, 0x00, 0x40, 0xbd, 0xe8, 0xf8, 0x8f, 0x4f, 0xf0, + 0xff, 0x36, 0x7f, 0x24, 0x20, 0x46, 0x59, 0x46, 0x52, 0x46, 0x4b, 0x46, + 0xff, 0xf7, 0x3e, 0xff, 0xb0, 0x42, 0x04, 0xdd, 0x01, 0x35, 0xed, 0xb2, + 0xbd, 0x42, 0x04, 0xd0, 0x06, 0x46, 0x14, 0xf1, 0xff, 0x34, 0xef, 0xd2, + 0x20, 0x46, 0xbd, 0xe8, 0xf8, 0x8f, 0x2d, 0xe9, 0xf0, 0x4f, 0x8b, 0xb0, + 0x04, 0x46, 0x00, 0x25, 0x08, 0xab, 0x07, 0xaa, 0x88, 0x46, 0x06, 0xa9, + 0xd0, 0xf8, 0xa8, 0xa0, 0x06, 0x95, 0x07, 0x95, 0x08, 0x95, 0xfb, 0xf7, + 0xb1, 0xfd, 0x20, 0x46, 0x0d, 0xf1, 0x26, 0x01, 0x0d, 0xf1, 0x27, 0x02, + 0xfe, 0xf7, 0xca, 0xf8, 0x9d, 0xf8, 0x26, 0x30, 0x06, 0xaf, 0x03, 0x93, + 0x01, 0x23, 0x97, 0xe8, 0x80, 0x0a, 0x00, 0x93, 0x03, 0x9b, 0x4a, 0x46, + 0x01, 0x93, 0x39, 0x46, 0x5b, 0x46, 0x20, 0x46, 0xff, 0xf7, 0xa1, 0xff, + 0x9d, 0xf8, 0x27, 0x30, 0x4a, 0x46, 0x04, 0x93, 0x01, 0x93, 0x06, 0x46, + 0x5b, 0x46, 0x00, 0x95, 0x20, 0x46, 0x39, 0x46, 0xff, 0xf7, 0x95, 0xff, + 0x9a, 0xf8, 0xe8, 0x33, 0x81, 0x46, 0x23, 0xb3, 0xb4, 0xf9, 0x04, 0x31, + 0xb4, 0xf9, 0x02, 0xc1, 0x05, 0x93, 0x01, 0x23, 0xb4, 0xf9, 0x06, 0xb1, + 0x00, 0x93, 0x03, 0x9b, 0x62, 0x46, 0x01, 0x93, 0x59, 0x46, 0x05, 0x9b, + 0x20, 0x46, 0xcd, 0xf8, 0x08, 0xc0, 0xff, 0xf7, 0x7e, 0xff, 0x04, 0x9b, + 0xdd, 0xf8, 0x08, 0xc0, 0x07, 0x46, 0x01, 0x93, 0x00, 0x95, 0x20, 0x46, + 0x59, 0x46, 0x62, 0x46, 0x05, 0x9b, 0xff, 0xf7, 0x72, 0xff, 0xbe, 0x42, + 0xb8, 0xbf, 0x3e, 0x46, 0x81, 0x45, 0xa8, 0xbf, 0x81, 0x46, 0xb8, 0xf1, + 0x01, 0x0f, 0x02, 0xd0, 0xb8, 0xf1, 0x03, 0x0f, 0x02, 0xd1, 0x76, 0x10, + 0xca, 0xf8, 0x44, 0x64, 0xa8, 0xf1, 0x02, 0x08, 0x5f, 0xfa, 0x88, 0xf8, + 0xb8, 0xf1, 0x01, 0x0f, 0x9c, 0xbf, 0x4f, 0xea, 0x69, 0x03, 0xca, 0xf8, + 0x48, 0x34, 0x0b, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, 0xf0, 0xb5, 0xd0, 0xf8, + 0xa8, 0x40, 0x00, 0x23, 0x85, 0xb0, 0x01, 0x93, 0x02, 0x93, 0x03, 0x93, + 0x94, 0xf8, 0x58, 0x34, 0x05, 0x46, 0x00, 0x2b, 0x79, 0xd0, 0xff, 0xf7, + 0x5a, 0xfc, 0x06, 0x46, 0x08, 0xb1, 0x7f, 0x28, 0x73, 0xd1, 0x02, 0xaa, + 0x03, 0xab, 0x28, 0x46, 0x01, 0xa9, 0xfb, 0xf7, 0x35, 0xfd, 0x40, 0xf2, + 0x3e, 0x61, 0x28, 0x46, 0xf9, 0xf7, 0xd1, 0xfd, 0x40, 0xf2, 0xa6, 0x41, + 0xc7, 0x05, 0x28, 0x46, 0xf9, 0xf7, 0xcb, 0xfd, 0xc0, 0x05, 0xc0, 0x0d, + 0xff, 0x0d, 0xff, 0x28, 0x86, 0xbf, 0xa0, 0xf5, 0x80, 0x70, 0x80, 0xb2, + 0x00, 0xf5, 0x80, 0x70, 0xff, 0x2f, 0x88, 0xbf, 0xa7, 0xf5, 0x80, 0x77, + 0xc0, 0xf5, 0xfe, 0x70, 0x8c, 0xbf, 0xbf, 0xb2, 0x07, 0xf5, 0x80, 0x77, + 0x03, 0x30, 0x38, 0x18, 0x80, 0x10, 0x80, 0xb2, 0xbe, 0xb9, 0x94, 0xf8, + 0x56, 0x34, 0x01, 0x33, 0xdb, 0xb2, 0x04, 0x2b, 0x84, 0xf8, 0x56, 0x34, + 0x41, 0xd9, 0x01, 0xa9, 0x0e, 0xc9, 0x84, 0xf8, 0x56, 0x64, 0xff, 0xf7, + 0x73, 0xfe, 0xd4, 0xf8, 0x48, 0x24, 0x43, 0x10, 0x04, 0x3b, 0x93, 0x42, + 0xb8, 0xbf, 0x13, 0x46, 0xc4, 0xf8, 0x44, 0x34, 0x19, 0xe0, 0x7f, 0x2e, + 0x2f, 0xd1, 0x94, 0xf8, 0x57, 0x34, 0x01, 0x33, 0xdb, 0xb2, 0x04, 0x2b, + 0x84, 0xf8, 0x57, 0x34, 0x27, 0xd9, 0x00, 0x23, 0x01, 0xa9, 0x84, 0xf8, + 0x57, 0x34, 0x0e, 0xc9, 0xff, 0xf7, 0x58, 0xfe, 0xd4, 0xf8, 0x44, 0x24, + 0x43, 0x10, 0x04, 0x33, 0x93, 0x42, 0xa8, 0xbf, 0x13, 0x46, 0xc4, 0xf8, + 0x48, 0x34, 0xd5, 0xf8, 0xa8, 0x20, 0x9b, 0xb2, 0xd2, 0xf8, 0x48, 0x14, + 0xd2, 0xf8, 0x44, 0x24, 0x93, 0x42, 0xb4, 0xbf, 0x18, 0x46, 0x10, 0x46, + 0x81, 0x42, 0x01, 0xdd, 0x8b, 0xb2, 0x02, 0xe0, 0x9a, 0x42, 0xb8, 0xbf, + 0x93, 0xb2, 0x28, 0x46, 0x40, 0xf2, 0xa7, 0x41, 0xff, 0x22, 0xf9, 0xf7, + 0x59, 0xff, 0x05, 0xb0, 0xf0, 0xbd, 0x30, 0xb5, 0xd0, 0xf8, 0xa8, 0x50, + 0x9b, 0xb0, 0x04, 0x46, 0x02, 0x46, 0x00, 0x23, 0x92, 0xf9, 0x10, 0x05, + 0x01, 0xa9, 0x40, 0x42, 0x58, 0x50, 0x04, 0x33, 0x01, 0x32, 0x50, 0x2b, + 0xf6, 0xd1, 0x95, 0xf8, 0x6a, 0x30, 0x6b, 0xb9, 0x07, 0x23, 0x17, 0x93, + 0x20, 0x23, 0x19, 0x93, 0x14, 0x23, 0x16, 0x93, 0x15, 0x91, 0x4f, 0xf4, + 0x50, 0x73, 0x20, 0x46, 0x15, 0xa9, 0x18, 0x93, 0xfe, 0xf7, 0xbb, 0xfa, + 0xd4, 0xf8, 0xa8, 0x20, 0x94, 0xf8, 0x29, 0x36, 0xd2, 0xf8, 0x48, 0x14, + 0xd2, 0xf8, 0x44, 0x24, 0x93, 0x42, 0xb4, 0xbf, 0x18, 0x46, 0x10, 0x46, + 0x81, 0x42, 0x01, 0xdd, 0x8b, 0xb2, 0x02, 0xe0, 0x9a, 0x42, 0xb8, 0xbf, + 0x93, 0xb2, 0x20, 0x46, 0x40, 0xf2, 0xa7, 0x41, 0xff, 0x22, 0xf9, 0xf7, + 0x1d, 0xff, 0x95, 0xf8, 0xe8, 0x33, 0xf3, 0xb1, 0x94, 0xf8, 0x29, 0x26, + 0xb5, 0xf8, 0xe6, 0x33, 0x20, 0x46, 0xd3, 0x1a, 0x1b, 0x02, 0x4f, 0xf4, + 0x7f, 0x42, 0x13, 0x40, 0x40, 0xf2, 0xd1, 0x41, 0xf9, 0xf7, 0x0c, 0xff, + 0x94, 0xf8, 0x29, 0x26, 0x95, 0xf8, 0x25, 0x35, 0x95, 0xf8, 0xe6, 0x13, + 0x9b, 0x1a, 0xd3, 0x1a, 0x5b, 0x1a, 0x5b, 0xb2, 0x20, 0x46, 0x40, 0xf2, + 0xd1, 0x41, 0xff, 0x22, 0x9b, 0xb2, 0xf9, 0xf7, 0xfb, 0xfe, 0x20, 0x46, + 0xfb, 0xf7, 0x02, 0xfd, 0x1b, 0xb0, 0x30, 0xbd, 0x2d, 0xe9, 0xf0, 0x41, + 0x04, 0x46, 0x0d, 0x46, 0xfb, 0xf7, 0x97, 0xfe, 0x29, 0x46, 0x07, 0x46, + 0x20, 0x46, 0xfb, 0xf7, 0x98, 0xfd, 0x39, 0x46, 0x05, 0x46, 0x20, 0x46, + 0xfb, 0xf7, 0x93, 0xfd, 0x40, 0x22, 0xb5, 0xf5, 0x40, 0x4f, 0x0c, 0xbf, + 0x13, 0x46, 0x00, 0x23, 0x07, 0x46, 0x40, 0xf2, 0xda, 0x61, 0x20, 0x46, + 0xd4, 0xf8, 0xa8, 0x60, 0xf9, 0xf7, 0xd8, 0xfe, 0x10, 0x22, 0xb5, 0xf5, + 0x40, 0x4f, 0x14, 0xbf, 0x13, 0x46, 0x00, 0x23, 0x20, 0x46, 0x40, 0xf2, + 0xa3, 0x61, 0xf9, 0xf7, 0xcd, 0xfe, 0xa5, 0xf5, 0x40, 0x4e, 0x01, 0x22, + 0xde, 0xf1, 0x00, 0x03, 0x43, 0xeb, 0x0e, 0x03, 0x20, 0x46, 0x40, 0xf2, + 0x6e, 0x41, 0xf9, 0xf7, 0xc1, 0xfe, 0xaf, 0x42, 0x00, 0xf0, 0x93, 0x80, + 0xb7, 0xf5, 0x40, 0x4f, 0x02, 0xd1, 0x20, 0x46, 0xff, 0xf7, 0x64, 0xfb, + 0xb5, 0xf5, 0x40, 0x4f, 0x20, 0x46, 0x3a, 0xd1, 0xff, 0xf7, 0x5b, 0xff, + 0xd4, 0xf8, 0xa8, 0x30, 0x32, 0x8e, 0x93, 0xf9, 0x66, 0x35, 0x52, 0x00, + 0x01, 0x33, 0x92, 0xfb, 0xf3, 0xf3, 0x20, 0x46, 0x40, 0xf2, 0xa4, 0x41, + 0x40, 0xf2, 0xff, 0x12, 0x9b, 0xb2, 0xf9, 0xf7, 0xa1, 0xfe, 0x73, 0x8e, + 0x20, 0x46, 0x1b, 0x02, 0x40, 0xf2, 0xa5, 0x41, 0x4f, 0xf4, 0xe0, 0x62, + 0x03, 0xf4, 0x7f, 0x43, 0xf9, 0xf7, 0x96, 0xfe, 0x04, 0x22, 0x20, 0x46, + 0x00, 0x23, 0x40, 0xf2, 0x1f, 0x11, 0xf9, 0xf7, 0x4d, 0xfe, 0xe3, 0x69, + 0xe0, 0x21, 0x18, 0x69, 0x39, 0xf0, 0x54, 0xda, 0x00, 0x21, 0xf0, 0x85, + 0x20, 0x46, 0xfb, 0xf7, 0xc4, 0xff, 0xff, 0x23, 0x86, 0xf8, 0x34, 0x30, + 0x20, 0x46, 0x40, 0xf2, 0xa9, 0x41, 0x4f, 0xf4, 0x00, 0x42, 0x00, 0x23, + 0xf9, 0xf7, 0x7a, 0xfe, 0x02, 0xe0, 0x01, 0x21, 0xfb, 0xf7, 0xb5, 0xff, + 0x20, 0x46, 0x40, 0xf2, 0xa4, 0x41, 0x4f, 0xf4, 0x60, 0x42, 0x2b, 0x46, + 0xf9, 0xf7, 0x6e, 0xfe, 0xb5, 0xf5, 0x40, 0x4f, 0x0f, 0xd1, 0x20, 0x46, + 0xfb, 0xf7, 0x36, 0xfd, 0x40, 0xf2, 0xa4, 0x41, 0x00, 0x28, 0x0c, 0xbf, + 0x4f, 0xf4, 0x00, 0x53, 0x00, 0x23, 0x4f, 0xf4, 0x00, 0x52, 0x20, 0x46, + 0xf9, 0xf7, 0x5c, 0xfe, 0x13, 0xe0, 0x4e, 0xf2, 0x01, 0x03, 0x9d, 0x42, + 0x0f, 0xd1, 0x20, 0x46, 0xfb, 0xf7, 0x63, 0xfc, 0x01, 0x46, 0x20, 0x46, + 0xff, 0xf7, 0x86, 0xf8, 0x20, 0x46, 0x40, 0xf2, 0xa9, 0x41, 0xf9, 0xf7, + 0x5a, 0xfc, 0xc0, 0xb2, 0x40, 0x10, 0x86, 0xf8, 0xc1, 0x02, 0x96, 0xf9, + 0x67, 0x35, 0x20, 0x46, 0x01, 0x2b, 0x0d, 0xdd, 0x40, 0xf2, 0xa4, 0x41, + 0xf9, 0xf7, 0x4d, 0xfc, 0x00, 0xf4, 0x80, 0x43, 0x9b, 0x13, 0x20, 0x46, + 0x40, 0xf2, 0x25, 0x51, 0x4f, 0xf4, 0x00, 0x42, 0xdb, 0x03, 0x04, 0xe0, + 0x40, 0xf2, 0x25, 0x51, 0x4f, 0xf4, 0x00, 0x42, 0x00, 0x23, 0xbd, 0xe8, + 0xf0, 0x41, 0xf9, 0xf7, 0x2b, 0xbe, 0xbd, 0xe8, 0xf0, 0x81, 0x38, 0xb5, + 0x00, 0x22, 0xd0, 0xf8, 0xa8, 0x30, 0x80, 0xf8, 0x2b, 0x26, 0x93, 0xf8, + 0xe0, 0x24, 0x04, 0x46, 0x92, 0xb1, 0x90, 0xf9, 0x2a, 0x26, 0xd3, 0xf8, + 0x48, 0x14, 0x8a, 0x42, 0x03, 0xdb, 0xd3, 0xf8, 0x10, 0x35, 0x9a, 0x42, + 0x08, 0xda, 0x20, 0x46, 0x4e, 0xf2, 0x01, 0x01, 0xff, 0xf7, 0x1a, 0xff, + 0x01, 0x23, 0x84, 0xf8, 0x2b, 0x36, 0x38, 0xbd, 0x04, 0xf5, 0x82, 0x53, + 0x1b, 0x79, 0x83, 0xb1, 0x20, 0x46, 0xfb, 0xf7, 0xac, 0xfd, 0x00, 0x21, + 0x05, 0x46, 0x20, 0x46, 0xff, 0xf7, 0x0a, 0xff, 0x20, 0x46, 0xff, 0xf7, + 0xa6, 0xfe, 0x20, 0x46, 0x29, 0x46, 0xbd, 0xe8, 0x38, 0x40, 0xff, 0xf7, + 0x01, 0xbf, 0x38, 0xbd, 0x7f, 0xb5, 0x0d, 0xf1, 0x16, 0x03, 0x00, 0x93, + 0x01, 0x23, 0x01, 0x93, 0x00, 0x23, 0x02, 0x93, 0x57, 0x23, 0x03, 0x93, + 0x69, 0x46, 0x10, 0x23, 0x04, 0x93, 0xfd, 0xf7, 0x89, 0xfe, 0xbd, 0xf8, + 0x16, 0x00, 0x00, 0x0a, 0x07, 0xb0, 0x00, 0xbd, 0x10, 0xb5, 0x00, 0x23, + 0x88, 0xb0, 0x05, 0x93, 0x10, 0x23, 0x07, 0x93, 0x0d, 0xf1, 0x06, 0x03, + 0x03, 0x93, 0x01, 0x23, 0x04, 0x46, 0xad, 0xf8, 0x06, 0x10, 0x04, 0x93, + 0x03, 0xa9, 0x55, 0x23, 0x06, 0x93, 0xfe, 0xf7, 0x54, 0xf9, 0x20, 0x46, + 0xfb, 0xf7, 0x86, 0xfc, 0x10, 0xb1, 0x20, 0x46, 0xfd, 0xf7, 0xdf, 0xff, + 0x08, 0xb0, 0x10, 0xbd, 0x2d, 0xe9, 0xf0, 0x41, 0x04, 0x46, 0xd0, 0xf8, + 0xa8, 0x50, 0x00, 0x26, 0x16, 0xe0, 0xb4, 0xf8, 0xda, 0x20, 0x02, 0xf4, + 0x70, 0x42, 0xb2, 0xf5, 0x80, 0x5f, 0x06, 0xd1, 0x1a, 0x79, 0x22, 0xb1, + 0x89, 0x04, 0x20, 0x46, 0x89, 0x0c, 0x9a, 0x78, 0x05, 0xe0, 0x5a, 0x79, + 0x2a, 0xb1, 0x89, 0x04, 0xda, 0x78, 0x20, 0x46, 0x89, 0x0c, 0xf9, 0xf7, + 0x92, 0xfb, 0x01, 0x36, 0x06, 0x22, 0x72, 0x43, 0xc1, 0x49, 0x8b, 0x18, + 0x89, 0x5a, 0x4f, 0xf6, 0xff, 0x72, 0x91, 0x42, 0xdf, 0xd1, 0x20, 0x46, + 0x73, 0x21, 0x00, 0x22, 0xf9, 0xf7, 0x83, 0xfb, 0x20, 0x46, 0x32, 0x21, + 0x6a, 0x22, 0xf9, 0xf7, 0x7e, 0xfb, 0x19, 0x22, 0x20, 0x46, 0x33, 0x21, + 0xf9, 0xf7, 0x79, 0xfb, 0x95, 0xf8, 0xec, 0x23, 0x1a, 0xb1, 0x20, 0x46, + 0x33, 0x21, 0xf9, 0xf7, 0x72, 0xfb, 0xc2, 0x21, 0x6f, 0x22, 0x20, 0x46, + 0xf9, 0xf7, 0x6d, 0xfb, 0x90, 0x21, 0x10, 0x22, 0x20, 0x46, 0xf9, 0xf7, + 0x68, 0xfb, 0x10, 0x21, 0x00, 0x22, 0x20, 0x46, 0xf9, 0xf7, 0x63, 0xfb, + 0x9b, 0x21, 0x07, 0x22, 0x20, 0x46, 0xf9, 0xf7, 0x5e, 0xfb, 0x1d, 0x21, + 0x02, 0x22, 0x20, 0x46, 0xf9, 0xf7, 0x59, 0xfb, 0x1e, 0x21, 0x06, 0x22, + 0x20, 0x46, 0xf9, 0xf7, 0x54, 0xfb, 0x20, 0x46, 0x40, 0xf2, 0xea, 0x41, + 0x44, 0xf2, 0x88, 0x62, 0xf9, 0xf7, 0x7e, 0xfb, 0xb4, 0xf8, 0xda, 0x30, + 0x03, 0xf4, 0x70, 0x43, 0xb3, 0xf5, 0x00, 0x5f, 0x40, 0xf0, 0x4c, 0x81, + 0xb4, 0xf8, 0xfe, 0x3f, 0x95, 0xf8, 0xe9, 0x83, 0x1a, 0xb2, 0xb8, 0xf1, + 0xa0, 0x0f, 0x0c, 0xbf, 0x4f, 0xf0, 0x04, 0x08, 0x4f, 0xf0, 0x02, 0x08, + 0x01, 0x32, 0x18, 0xbf, 0x98, 0x46, 0x09, 0xe0, 0x04, 0xf5, 0x80, 0x53, + 0xb3, 0xf8, 0x00, 0x80, 0x0f, 0xfa, 0x88, 0xf3, 0x01, 0x33, 0x08, 0xbf, + 0x4f, 0xf0, 0x02, 0x08, 0x4f, 0xfa, 0x88, 0xf8, 0x1f, 0xfa, 0x88, 0xf8, + 0x07, 0x22, 0x43, 0x46, 0x20, 0x46, 0x40, 0xf2, 0xeb, 0x41, 0xf9, 0xf7, + 0x37, 0xfd, 0xb4, 0xf8, 0xda, 0x30, 0x03, 0xf4, 0x70, 0x43, 0xb3, 0xf5, + 0x00, 0x5f, 0x08, 0xd0, 0xb3, 0xf5, 0x80, 0x5f, 0x07, 0xd1, 0x95, 0xf8, + 0x3b, 0x65, 0x00, 0x36, 0x18, 0xbf, 0x01, 0x26, 0x02, 0xe0, 0x00, 0x26, + 0x00, 0xe0, 0x01, 0x26, 0x37, 0x01, 0x33, 0x46, 0x0f, 0x22, 0x20, 0x46, + 0x40, 0xf2, 0xf2, 0x41, 0xbf, 0xb2, 0xf9, 0xf7, 0x1b, 0xfd, 0xf0, 0x22, + 0x20, 0x46, 0x40, 0xf2, 0xf2, 0x41, 0x3b, 0x46, 0xf9, 0xf7, 0x14, 0xfd, + 0x33, 0x46, 0x0f, 0x22, 0x20, 0x46, 0x40, 0xf2, 0xf1, 0x41, 0xf9, 0xf7, + 0x0d, 0xfd, 0xf0, 0x22, 0x20, 0x46, 0x40, 0xf2, 0xf1, 0x41, 0x3b, 0x46, + 0xf9, 0xf7, 0x06, 0xfd, 0x4f, 0xea, 0x08, 0x23, 0x20, 0x46, 0x40, 0xf2, + 0xf2, 0x41, 0x4f, 0xf4, 0xe0, 0x62, 0x03, 0xf4, 0x7f, 0x43, 0xf9, 0xf7, + 0xfb, 0xfc, 0xb4, 0xf8, 0xda, 0x30, 0x20, 0x46, 0x03, 0xf4, 0x70, 0x43, + 0xb3, 0xf5, 0x80, 0x5f, 0x04, 0xf5, 0x98, 0x53, 0x0c, 0xbf, 0x9e, 0x89, + 0x5e, 0x89, 0x40, 0xf2, 0xeb, 0x41, 0x73, 0x02, 0x03, 0xf4, 0x7e, 0x43, + 0x4f, 0xf4, 0x00, 0x72, 0xf9, 0xf7, 0xe6, 0xfc, 0xb4, 0xf8, 0xda, 0x30, + 0x03, 0xf4, 0x70, 0x43, 0xb3, 0xf5, 0x80, 0x5f, 0x07, 0xd0, 0x04, 0xf5, + 0x9a, 0x53, 0x9b, 0x8a, 0x1a, 0xb2, 0x01, 0x32, 0x01, 0xd0, 0x9b, 0x02, + 0x00, 0xe0, 0xb3, 0x02, 0x4f, 0xf4, 0x80, 0x62, 0x03, 0xf4, 0x7c, 0x43, + 0x20, 0x46, 0x40, 0xf2, 0xeb, 0x41, 0xf9, 0xf7, 0xcd, 0xfc, 0x40, 0xf2, + 0xeb, 0x41, 0x20, 0x46, 0xd4, 0xf8, 0xa8, 0x60, 0xf9, 0xf7, 0xd5, 0xfa, + 0x00, 0xf4, 0x80, 0x60, 0x80, 0x12, 0x86, 0xf8, 0x47, 0x05, 0x40, 0xf2, + 0xeb, 0x41, 0x20, 0x46, 0xd4, 0xf8, 0xa8, 0x60, 0xf9, 0xf7, 0xc9, 0xfa, + 0x00, 0xf4, 0x00, 0x70, 0x40, 0x12, 0x86, 0xf8, 0x48, 0x05, 0xd4, 0xf8, + 0xa8, 0x30, 0x20, 0x46, 0x93, 0xf8, 0x47, 0x15, 0x93, 0xf8, 0x48, 0x25, + 0x8a, 0x1a, 0x18, 0xbf, 0x01, 0x22, 0x83, 0xf8, 0x46, 0x25, 0xfb, 0xf7, + 0x75, 0xfb, 0x83, 0x02, 0x03, 0xf4, 0x7c, 0x43, 0x20, 0x46, 0x40, 0xf6, + 0x46, 0x11, 0x4f, 0xf4, 0x80, 0x62, 0xf9, 0xf7, 0x9d, 0xfc, 0x20, 0x46, + 0x3d, 0x49, 0x06, 0x22, 0xf9, 0xf7, 0xaa, 0xfc, 0x04, 0xf5, 0x90, 0x53, + 0x93, 0xf8, 0x3d, 0x30, 0x2b, 0xb1, 0x0f, 0x22, 0x20, 0x46, 0x77, 0x21, + 0x13, 0x46, 0xf9, 0xf7, 0x4b, 0xfc, 0x20, 0x46, 0x00, 0x21, 0xff, 0xf7, + 0xa7, 0xfe, 0x95, 0xf8, 0x9a, 0x35, 0x2b, 0xb9, 0x20, 0x46, 0xfd, 0xf7, + 0xa3, 0xf9, 0x20, 0x46, 0xfd, 0xf7, 0xf6, 0xf9, 0xe3, 0x69, 0x7a, 0x21, + 0x18, 0x69, 0x39, 0xf0, 0x45, 0xd8, 0x95, 0xf8, 0xec, 0x23, 0x40, 0x00, + 0x86, 0xb2, 0x2a, 0xb1, 0x26, 0xb1, 0xe3, 0x69, 0xb1, 0x1c, 0x18, 0x69, + 0x39, 0xf0, 0x58, 0xd8, 0x95, 0xf8, 0xed, 0x23, 0x2a, 0xb1, 0x26, 0xb1, + 0xe3, 0x69, 0x31, 0x46, 0x18, 0x69, 0x39, 0xf0, 0x4f, 0xd8, 0x95, 0xf8, + 0xbb, 0x34, 0xdb, 0xb1, 0x04, 0x22, 0x13, 0x46, 0x20, 0x46, 0x40, 0xf2, + 0x1d, 0x11, 0xf9, 0xf7, 0x1b, 0xfc, 0x20, 0x46, 0x9f, 0x21, 0x3f, 0x22, + 0x95, 0xf8, 0xbc, 0x34, 0xf9, 0xf7, 0x14, 0xfc, 0x20, 0x46, 0x9e, 0x21, + 0x3f, 0x22, 0x95, 0xf8, 0xbd, 0x34, 0xf9, 0xf7, 0x0d, 0xfc, 0x20, 0x46, + 0x77, 0x21, 0x0f, 0x22, 0x95, 0xf8, 0xbe, 0x34, 0xf9, 0xf7, 0x06, 0xfc, + 0xb4, 0xf8, 0xda, 0x30, 0x03, 0xf4, 0x70, 0x43, 0xb3, 0xf5, 0x80, 0x5f, + 0x37, 0xd1, 0x95, 0xf9, 0x58, 0x35, 0x00, 0x2b, 0x33, 0xd0, 0xb4, 0x21, + 0x24, 0x22, 0x20, 0x46, 0xf9, 0xf7, 0x21, 0xfa, 0xb7, 0x21, 0x24, 0x22, + 0x20, 0x46, 0xf9, 0xf7, 0x1c, 0xfa, 0x03, 0x22, 0xb8, 0x21, 0x20, 0x46, + 0xf9, 0xf7, 0x17, 0xfa, 0x95, 0xf9, 0x58, 0x25, 0x02, 0x2a, 0x0b, 0xd1, + 0x20, 0x46, 0xb8, 0x21, 0xf9, 0xf7, 0x0f, 0xfa, 0x20, 0x46, 0xb5, 0x21, + 0x01, 0x22, 0x0d, 0xe0, 0xe0, 0x06, 0x02, 0x00, 0x80, 0xeb, 0x01, 0x00, + 0x03, 0x2a, 0x12, 0xd1, 0x20, 0x46, 0xb8, 0x21, 0x02, 0x22, 0xf9, 0xf7, + 0x00, 0xfa, 0x20, 0x46, 0xb5, 0x21, 0x00, 0x22, 0xbd, 0xe8, 0xf0, 0x41, + 0xf9, 0xf7, 0xf9, 0xb9, 0xb3, 0xf5, 0x80, 0x5f, 0x3f, 0xf4, 0xc0, 0xae, + 0x4f, 0xf0, 0x02, 0x08, 0xc6, 0xe6, 0xbd, 0xe8, 0xf0, 0x81, 0x00, 0xbf, + 0xff, 0xf7, 0x3e, 0xbe, 0x2d, 0xe9, 0xf0, 0x43, 0xd0, 0xf8, 0xa8, 0x60, + 0x8d, 0xb0, 0x96, 0xf9, 0x66, 0x35, 0x04, 0x46, 0x0d, 0x46, 0x0f, 0x46, + 0xab, 0xb1, 0x5f, 0x4b, 0x0b, 0x40, 0x00, 0x2b, 0x03, 0xda, 0x01, 0x3b, + 0x63, 0xf0, 0x01, 0x03, 0x01, 0x33, 0x0c, 0x22, 0x01, 0x2b, 0x20, 0x46, + 0x4f, 0xf4, 0x8f, 0x61, 0x01, 0xd1, 0x08, 0x23, 0x00, 0xe0, 0x00, 0x23, + 0xf9, 0xf7, 0xe6, 0xfb, 0x05, 0xeb, 0xd5, 0x75, 0x6d, 0x10, 0x07, 0x23, + 0x4f, 0xf0, 0x20, 0x09, 0x03, 0x93, 0x05, 0xf5, 0xa0, 0x73, 0x86, 0xf8, + 0x34, 0x70, 0x86, 0xf8, 0xc1, 0x72, 0x04, 0x93, 0x0c, 0xaf, 0x0d, 0xeb, + 0x09, 0x03, 0x47, 0xf8, 0x2c, 0x3d, 0x4f, 0xf0, 0x01, 0x08, 0x39, 0x46, + 0x20, 0x46, 0xcd, 0xf8, 0x14, 0x90, 0xcd, 0xf8, 0x08, 0x80, 0xfd, 0xf7, + 0x6b, 0xfc, 0x05, 0xf1, 0xc0, 0x03, 0x39, 0x46, 0x04, 0x93, 0x20, 0x46, + 0x09, 0xab, 0x01, 0x93, 0xcd, 0xf8, 0x14, 0x90, 0xfd, 0xf7, 0x60, 0xfc, + 0x09, 0x9b, 0x20, 0x46, 0xda, 0xb2, 0xad, 0xf8, 0x18, 0x20, 0x1a, 0x0a, + 0x1b, 0x0c, 0xdb, 0xb2, 0xad, 0xf8, 0x1c, 0x30, 0x08, 0x9b, 0xd2, 0xb2, + 0x1b, 0x0f, 0x03, 0xf0, 0x07, 0x03, 0x06, 0xa9, 0xad, 0xf8, 0x1e, 0x30, + 0xad, 0xf8, 0x1a, 0x20, 0xfb, 0xf7, 0x03, 0xfd, 0x9d, 0xf8, 0x27, 0x10, + 0x20, 0x46, 0x01, 0xf0, 0x7f, 0x01, 0xfb, 0xf7, 0x83, 0xfd, 0x08, 0x99, + 0x20, 0x46, 0x09, 0x0d, 0xc9, 0xb2, 0xfe, 0xf7, 0xa1, 0xf8, 0x20, 0x46, + 0x41, 0x46, 0xfb, 0xf7, 0xd6, 0xfc, 0x08, 0x9a, 0x20, 0x46, 0x91, 0x0a, + 0x89, 0x05, 0x92, 0x05, 0x92, 0x0d, 0x89, 0x0d, 0xfe, 0xf7, 0x78, 0xfd, + 0x05, 0xf5, 0xe0, 0x73, 0x39, 0x46, 0x04, 0x93, 0x20, 0x46, 0x0a, 0xab, + 0x01, 0x93, 0xfd, 0xf7, 0x27, 0xfc, 0x20, 0x46, 0xbd, 0xf8, 0x28, 0x10, + 0xff, 0xf7, 0x9e, 0xfd, 0x05, 0xf5, 0x10, 0x73, 0x39, 0x46, 0x04, 0x93, + 0x20, 0x46, 0x0b, 0xab, 0x01, 0x93, 0xfd, 0xf7, 0x19, 0xfc, 0x0b, 0x9f, + 0x4f, 0xf6, 0xf8, 0x73, 0xff, 0x00, 0x3b, 0x40, 0x20, 0x46, 0x40, 0xf2, + 0xa6, 0x61, 0x41, 0xf6, 0xff, 0x72, 0xf9, 0xf7, 0x6b, 0xfb, 0x96, 0xf9, + 0x67, 0x35, 0x43, 0x45, 0x29, 0xdd, 0x40, 0xf2, 0x25, 0x51, 0x20, 0x46, + 0xf9, 0xf7, 0x71, 0xf9, 0xc0, 0xb2, 0x85, 0x42, 0xd4, 0xbf, 0x00, 0x25, + 0x01, 0x25, 0x20, 0x46, 0x40, 0xf2, 0x25, 0x51, 0x4f, 0xf4, 0x80, 0x72, + 0x2b, 0x02, 0xf9, 0xf7, 0x55, 0xfb, 0x20, 0x46, 0x40, 0xf2, 0x25, 0x51, + 0x4f, 0xf4, 0x00, 0x72, 0x6b, 0x02, 0xf9, 0xf7, 0x4d, 0xfb, 0x20, 0x46, + 0x40, 0xf2, 0x25, 0x51, 0x4f, 0xf4, 0x80, 0x62, 0xab, 0x02, 0xf9, 0xf7, + 0x45, 0xfb, 0x20, 0x46, 0x40, 0xf2, 0x25, 0x51, 0x4f, 0xf4, 0x00, 0x62, + 0xeb, 0x02, 0xf9, 0xf7, 0x3d, 0xfb, 0x0d, 0xb0, 0xbd, 0xe8, 0xf0, 0x83, + 0x01, 0x00, 0x00, 0x80, 0x38, 0xb5, 0x0c, 0x46, 0x00, 0x21, 0x05, 0x46, + 0xff, 0xf7, 0x3c, 0xfc, 0x28, 0x46, 0x21, 0x46, 0xbd, 0xe8, 0x38, 0x40, + 0xff, 0xf7, 0x28, 0xbf, 0x2d, 0xe9, 0xf0, 0x4f, 0x8b, 0xb0, 0x05, 0x92, + 0x04, 0x46, 0x04, 0x91, 0xfb, 0xf7, 0xcb, 0xfa, 0x40, 0xf2, 0x3b, 0x41, + 0x02, 0x90, 0x20, 0x46, 0xf9, 0xf7, 0x2d, 0xf9, 0xc0, 0xf3, 0x80, 0x10, + 0x06, 0xa9, 0x03, 0x90, 0x20, 0x46, 0xfb, 0xf7, 0xc6, 0xfa, 0x4f, 0xf4, + 0x7a, 0x70, 0xee, 0xf3, 0x0f, 0xf7, 0x4f, 0xf4, 0x7a, 0x70, 0xee, 0xf3, + 0x0b, 0xf7, 0x04, 0xf5, 0x98, 0x53, 0x1a, 0x69, 0x00, 0x23, 0x98, 0x46, + 0xd1, 0x18, 0x91, 0xf8, 0x20, 0x10, 0x19, 0xb1, 0x08, 0xf1, 0x01, 0x08, + 0x1f, 0xfa, 0x88, 0xf8, 0x01, 0x33, 0x04, 0x2b, 0xf4, 0xd1, 0x14, 0x27, + 0x00, 0x26, 0xd0, 0xe0, 0xd4, 0xf8, 0xb0, 0x30, 0xd3, 0xf8, 0x20, 0x31, + 0x03, 0xf0, 0x01, 0x03, 0x83, 0xf0, 0x01, 0x09, 0x1b, 0xb1, 0xe3, 0x69, + 0x18, 0x69, 0x38, 0xf0, 0x09, 0xdf, 0x20, 0x46, 0xfa, 0xf7, 0xbd, 0xfe, + 0x04, 0xf5, 0x98, 0x53, 0x1b, 0x69, 0x20, 0x46, 0x03, 0xeb, 0x45, 0x03, + 0x99, 0x8c, 0xff, 0xf7, 0xab, 0xff, 0x20, 0x46, 0x01, 0x99, 0xfd, 0xf7, + 0xe5, 0xff, 0xb9, 0xf1, 0x00, 0x0f, 0x03, 0xd1, 0xe3, 0x69, 0x18, 0x69, + 0x38, 0xf0, 0xde, 0xde, 0x4f, 0xf4, 0x00, 0x42, 0x40, 0xf2, 0xa4, 0x41, + 0x13, 0x46, 0x20, 0x46, 0xf9, 0xf7, 0xd0, 0xfa, 0x41, 0xf2, 0x88, 0x30, + 0xee, 0xf3, 0xc8, 0xf6, 0x41, 0xf2, 0x88, 0x30, 0xee, 0xf3, 0xc4, 0xf6, + 0x41, 0xf2, 0x88, 0x30, 0xee, 0xf3, 0xc0, 0xf6, 0x20, 0x46, 0x40, 0xf2, + 0xa6, 0x41, 0xf9, 0xf7, 0xce, 0xf8, 0x4f, 0xea, 0xc0, 0x59, 0x4f, 0xea, + 0xd9, 0x59, 0xb9, 0xf1, 0xff, 0x0f, 0x86, 0xbf, 0xa9, 0xf5, 0x80, 0x79, + 0x1f, 0xfa, 0x89, 0xf9, 0x09, 0xf5, 0x80, 0x79, 0x4f, 0xf0, 0x10, 0x0b, + 0x4f, 0xf0, 0x00, 0x0a, 0x20, 0x46, 0x40, 0xf2, 0x3e, 0x61, 0xf9, 0xf7, + 0xb8, 0xf8, 0x0b, 0xf1, 0xff, 0x3b, 0xc0, 0x05, 0xc0, 0x0d, 0x1f, 0xfa, + 0x8b, 0xfb, 0x82, 0x44, 0xbb, 0xf1, 0x00, 0x0f, 0xf0, 0xd1, 0x4f, 0xea, + 0x1a, 0x1a, 0x1f, 0xfa, 0x8a, 0xfa, 0xba, 0xf1, 0xff, 0x0f, 0x8c, 0xbf, + 0xaa, 0xf5, 0x80, 0x7a, 0x0a, 0xf5, 0x80, 0x7a, 0x38, 0x46, 0x00, 0x21, + 0x08, 0xaa, 0x09, 0xab, 0xf0, 0xf3, 0xb8, 0xf4, 0x04, 0xf5, 0x98, 0x53, + 0x1b, 0x69, 0x00, 0x21, 0x5b, 0x19, 0x93, 0xf8, 0x20, 0x00, 0x0d, 0xf1, + 0x22, 0x02, 0x0d, 0xf1, 0x26, 0x03, 0xf0, 0xf3, 0xab, 0xf4, 0xbd, 0xf9, + 0x24, 0x10, 0xbd, 0xf9, 0x26, 0x30, 0x1f, 0xfa, 0x8a, 0xfa, 0x99, 0x42, + 0x09, 0xda, 0xbd, 0xf9, 0x22, 0x00, 0x59, 0x1a, 0xf0, 0xf3, 0x50, 0xf5, + 0xbd, 0xf8, 0x24, 0xb0, 0xad, 0xf8, 0x22, 0x00, 0x08, 0xe0, 0xbd, 0xf9, + 0x20, 0x00, 0xc9, 0x1a, 0xf0, 0xf3, 0x46, 0xf5, 0xbd, 0xf8, 0x26, 0xb0, + 0xad, 0xf8, 0x20, 0x00, 0xbd, 0xf9, 0x20, 0x00, 0xbd, 0xf9, 0x22, 0x10, + 0xf0, 0xf3, 0x46, 0xf5, 0x0f, 0xfa, 0x8b, 0xf3, 0x03, 0x2b, 0xcc, 0xbf, + 0xab, 0xf1, 0x04, 0x0b, 0xcb, 0xf1, 0x04, 0x0b, 0x0f, 0xfa, 0x8b, 0xfb, + 0x0b, 0xf1, 0xff, 0x33, 0x01, 0x22, 0x12, 0xfa, 0x03, 0xf3, 0x00, 0xeb, + 0x80, 0x00, 0xc3, 0x18, 0x43, 0xfa, 0x0b, 0xfb, 0x0b, 0xf1, 0x0c, 0x03, + 0x18, 0x2b, 0x14, 0xd8, 0x04, 0xf5, 0x98, 0x53, 0x1b, 0x69, 0x2a, 0x1d, + 0x53, 0xf8, 0x22, 0x00, 0x04, 0x9b, 0x83, 0x44, 0x4f, 0xea, 0x99, 0x09, + 0x03, 0xf8, 0x06, 0xb0, 0xc9, 0xf1, 0x7f, 0x09, 0x05, 0x9b, 0x09, 0xeb, + 0x9a, 0x0a, 0x03, 0xf8, 0x06, 0xa0, 0x01, 0x36, 0xb6, 0xb2, 0x01, 0x35, + 0xab, 0xb2, 0x43, 0x45, 0xff, 0xf4, 0x32, 0xaf, 0x01, 0x37, 0x65, 0x2f, + 0x03, 0xd0, 0xfb, 0xb2, 0x01, 0x93, 0x00, 0x25, 0xf4, 0xe7, 0x20, 0x46, + 0x03, 0x99, 0xfb, 0xf7, 0x62, 0xfb, 0x20, 0x46, 0x06, 0xa9, 0xfb, 0xf7, + 0x7a, 0xfb, 0x20, 0x46, 0x02, 0x99, 0xff, 0xf7, 0x25, 0xfb, 0x30, 0x46, + 0x0b, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, 0x00, 0x00, 0x2d, 0xe9, 0xf0, 0x4f, + 0x87, 0xb0, 0x04, 0x46, 0xd0, 0xf8, 0xa8, 0x70, 0xfb, 0xf7, 0xb5, 0xf9, + 0x82, 0x46, 0x20, 0x46, 0xfe, 0xf7, 0x93, 0xfe, 0x4f, 0xf4, 0x89, 0x71, + 0x5f, 0xfa, 0x80, 0xf9, 0x20, 0x46, 0xf8, 0xf7, 0xd5, 0xff, 0x07, 0x21, + 0x83, 0x46, 0x20, 0x46, 0xf8, 0xf7, 0xd0, 0xff, 0x00, 0xf0, 0x01, 0x00, + 0x00, 0x90, 0xff, 0x21, 0x20, 0x46, 0xf8, 0xf7, 0xc9, 0xff, 0x00, 0xf0, + 0x10, 0x00, 0x80, 0xb2, 0x01, 0x90, 0x40, 0xf2, 0x1f, 0x11, 0x20, 0x46, + 0xf8, 0xf7, 0xc0, 0xff, 0x00, 0xf0, 0x04, 0x00, 0x80, 0xb2, 0x02, 0x90, + 0x40, 0xf2, 0xab, 0x41, 0x20, 0x46, 0xf8, 0xf7, 0xf4, 0xff, 0xd4, 0xf8, + 0xb0, 0x30, 0xd3, 0xf8, 0x20, 0x31, 0x03, 0xf0, 0x01, 0x03, 0x83, 0xf0, + 0x01, 0x02, 0x03, 0x92, 0x1b, 0xb1, 0xe3, 0x69, 0x18, 0x69, 0x38, 0xf0, + 0xf1, 0xdd, 0x00, 0x21, 0x20, 0x46, 0xff, 0xf7, 0xdd, 0xfa, 0x20, 0x46, + 0xfa, 0xf7, 0xa1, 0xfd, 0x40, 0xf2, 0x3b, 0x41, 0x20, 0x46, 0xf8, 0xf7, + 0xda, 0xff, 0x04, 0xa9, 0xc0, 0xf3, 0x80, 0x18, 0x20, 0x46, 0xfb, 0xf7, + 0x74, 0xf9, 0x20, 0x46, 0x01, 0x21, 0xfb, 0xf7, 0x00, 0xfb, 0x20, 0x46, + 0x7f, 0x21, 0xff, 0xf7, 0x85, 0xfe, 0x01, 0x22, 0x13, 0x46, 0x20, 0x46, + 0x07, 0x21, 0xf9, 0xf7, 0x75, 0xf9, 0x10, 0x22, 0x13, 0x46, 0x20, 0x46, + 0xff, 0x21, 0xf9, 0xf7, 0x6f, 0xf9, 0x04, 0x22, 0x13, 0x46, 0x40, 0xf2, + 0x1f, 0x11, 0x20, 0x46, 0xf9, 0xf7, 0x68, 0xf9, 0x20, 0x46, 0xfe, 0xf7, + 0x7b, 0xfe, 0x06, 0x22, 0x47, 0x49, 0x20, 0x46, 0xf9, 0xf7, 0xb4, 0xf9, + 0x20, 0x46, 0xff, 0xf7, 0xa9, 0xfb, 0x00, 0x21, 0x06, 0x46, 0x20, 0x46, + 0xfd, 0xf7, 0xa0, 0xfe, 0x00, 0x22, 0x20, 0x46, 0x01, 0x21, 0xf9, 0xf7, + 0x29, 0xfb, 0x40, 0xf2, 0xab, 0x41, 0x20, 0x46, 0xf8, 0xf7, 0x9f, 0xff, + 0x40, 0xf2, 0x3e, 0x61, 0x20, 0x46, 0xf8, 0xf7, 0x9a, 0xff, 0xc5, 0x05, + 0xed, 0x0d, 0x2b, 0x46, 0x20, 0x46, 0x40, 0xf2, 0xa6, 0x41, 0x40, 0xf2, + 0xff, 0x12, 0xf9, 0xf7, 0x81, 0xf9, 0x97, 0xf8, 0xe8, 0x33, 0x0b, 0xb3, + 0x20, 0x46, 0x34, 0x49, 0x09, 0x22, 0xf9, 0xf7, 0x8b, 0xf9, 0x00, 0x22, + 0x20, 0x46, 0x01, 0x21, 0xf9, 0xf7, 0x08, 0xfb, 0x40, 0xf2, 0xab, 0x41, + 0x20, 0x46, 0xf8, 0xf7, 0x7e, 0xff, 0x40, 0xf2, 0x3e, 0x61, 0x20, 0x46, + 0xf8, 0xf7, 0x79, 0xff, 0xc3, 0x05, 0x40, 0xf2, 0x9a, 0x41, 0x20, 0x46, + 0x40, 0xf2, 0xff, 0x12, 0xdb, 0x0d, 0xf9, 0xf7, 0x61, 0xf9, 0x20, 0x46, + 0x26, 0x49, 0x09, 0x22, 0xf9, 0xf7, 0x6e, 0xf9, 0x20, 0x46, 0x40, 0xf2, + 0xa6, 0x41, 0x40, 0xf2, 0xff, 0x12, 0x2b, 0x46, 0xf9, 0xf7, 0x54, 0xf9, + 0x00, 0x23, 0x4f, 0xf4, 0x80, 0x52, 0x20, 0x46, 0x40, 0xf2, 0x4c, 0x41, + 0xf9, 0xf7, 0x4c, 0xf9, 0x20, 0x46, 0x31, 0x46, 0xfd, 0xf7, 0x4e, 0xfe, + 0x20, 0x46, 0x41, 0x46, 0xfb, 0xf7, 0x83, 0xfa, 0x20, 0x46, 0x04, 0xa9, + 0xfb, 0xf7, 0x9b, 0xfa, 0x20, 0x46, 0x49, 0x46, 0xff, 0xf7, 0x04, 0xfe, + 0x20, 0x46, 0x51, 0x46, 0xff, 0xf7, 0x42, 0xfa, 0x20, 0x46, 0x4f, 0xf4, + 0x89, 0x71, 0x5a, 0x46, 0xf8, 0xf7, 0x1b, 0xff, 0x20, 0x46, 0x07, 0x21, + 0x01, 0x22, 0x00, 0x9b, 0xf9, 0xf7, 0xea, 0xf8, 0x20, 0x46, 0xff, 0x21, + 0x10, 0x22, 0x01, 0x9b, 0xf9, 0xf7, 0xe4, 0xf8, 0x02, 0x9b, 0x20, 0x46, + 0x40, 0xf2, 0x1f, 0x11, 0x04, 0x22, 0xf9, 0xf7, 0xdd, 0xf8, 0x03, 0x9b, + 0x1b, 0xb9, 0xe3, 0x69, 0x18, 0x69, 0x38, 0xf0, 0x1f, 0xdd, 0x07, 0xb0, + 0xbd, 0xe8, 0xf0, 0x8f, 0xae, 0xe8, 0x01, 0x00, 0xba, 0xe8, 0x01, 0x00, + 0xcc, 0xe8, 0x01, 0x00, 0x2d, 0xe9, 0xf0, 0x4f, 0x04, 0x46, 0x95, 0xb0, + 0xd0, 0xf8, 0xa8, 0x50, 0x40, 0xf2, 0xe7, 0x30, 0x0e, 0x46, 0xee, 0xf3, + 0x01, 0xf5, 0x07, 0x21, 0x20, 0x46, 0xf8, 0xf7, 0xd3, 0xfe, 0xff, 0x21, + 0x5f, 0xfa, 0x80, 0xf8, 0x20, 0x46, 0xf8, 0xf7, 0xcd, 0xfe, 0x40, 0xf2, + 0x1f, 0x11, 0x5f, 0xfa, 0x80, 0xf9, 0x20, 0x46, 0xf8, 0xf7, 0xc6, 0xfe, + 0x05, 0x21, 0x5f, 0xfa, 0x80, 0xfa, 0x20, 0x46, 0xf8, 0xf7, 0xc0, 0xfe, + 0xc0, 0xb2, 0x00, 0x90, 0x25, 0x21, 0x20, 0x46, 0xf8, 0xf7, 0xba, 0xfe, + 0xc0, 0xb2, 0x01, 0x90, 0x4f, 0xf4, 0x89, 0x71, 0x20, 0x46, 0xf8, 0xf7, + 0xb3, 0xfe, 0xc0, 0xb2, 0x02, 0x90, 0x4f, 0xf0, 0x00, 0x0b, 0x88, 0x4f, + 0x20, 0x46, 0x37, 0xf8, 0x0b, 0x10, 0xf8, 0xf7, 0xe6, 0xfe, 0x07, 0xab, + 0x23, 0xf8, 0x0b, 0x00, 0x0b, 0xf1, 0x02, 0x0b, 0xbb, 0xf1, 0x1c, 0x0f, + 0xf1, 0xd1, 0xd4, 0xf8, 0xb0, 0x30, 0xd3, 0xf8, 0x20, 0x31, 0x03, 0xf0, + 0x01, 0x03, 0x83, 0xf0, 0x01, 0x02, 0x03, 0x92, 0x1b, 0xb1, 0xe3, 0x69, + 0x18, 0x69, 0x38, 0xf0, 0xdb, 0xdc, 0x40, 0xf2, 0xa4, 0x41, 0x20, 0x46, + 0xf8, 0xf7, 0x8e, 0xfe, 0x00, 0x21, 0x04, 0x90, 0x20, 0x46, 0xff, 0xf7, + 0xc1, 0xf9, 0x95, 0xf8, 0xc1, 0x52, 0x7f, 0x21, 0x20, 0x46, 0x05, 0x95, + 0xff, 0xf7, 0x78, 0xfd, 0x01, 0x22, 0x07, 0x21, 0x13, 0x46, 0x20, 0x46, + 0xf9, 0xf7, 0x68, 0xf8, 0x10, 0x22, 0xff, 0x21, 0x13, 0x46, 0x20, 0x46, + 0xf9, 0xf7, 0x62, 0xf8, 0x04, 0x22, 0x13, 0x46, 0x20, 0x46, 0x40, 0xf2, + 0x1f, 0x11, 0xf9, 0xf7, 0x5b, 0xf8, 0x36, 0x22, 0x20, 0x46, 0x68, 0x49, + 0xf9, 0xf7, 0xaa, 0xf8, 0x20, 0x46, 0xfb, 0xf7, 0x53, 0xf9, 0x40, 0x08, + 0x80, 0xb2, 0xe6, 0x28, 0x06, 0xdc, 0x20, 0x46, 0xfb, 0xf7, 0x4c, 0xf9, + 0x43, 0x08, 0x19, 0x33, 0x9b, 0xb2, 0x00, 0xe0, 0xff, 0x23, 0xff, 0x22, + 0x20, 0x46, 0x40, 0xf2, 0xa5, 0x41, 0xf9, 0xf7, 0x83, 0xf8, 0x25, 0x21, + 0x0c, 0x22, 0x20, 0x46, 0xf8, 0xf7, 0x67, 0xfe, 0x08, 0x22, 0x13, 0x46, + 0x05, 0x21, 0x20, 0x46, 0xf9, 0xf7, 0x36, 0xf8, 0x09, 0x22, 0x57, 0x49, + 0x20, 0x46, 0xf9, 0xf7, 0x85, 0xf8, 0x20, 0x46, 0xfb, 0xf7, 0x2e, 0xf9, + 0x10, 0x23, 0x12, 0x93, 0x01, 0x23, 0xad, 0xf8, 0x4e, 0x00, 0x08, 0x25, + 0x0f, 0x93, 0x20, 0x46, 0x0d, 0xf1, 0x4e, 0x03, 0x4f, 0xf0, 0x06, 0x0b, + 0x0e, 0xa9, 0x10, 0x95, 0x0e, 0x93, 0xcd, 0xf8, 0x44, 0xb0, 0xfd, 0xf7, + 0xe2, 0xfb, 0x01, 0x2e, 0x20, 0x46, 0x0b, 0xd1, 0x49, 0x49, 0x5a, 0x46, + 0xf9, 0xf7, 0x68, 0xf8, 0x20, 0x22, 0x20, 0x46, 0x82, 0x21, 0x13, 0x46, + 0xf9, 0xf7, 0x0e, 0xf8, 0x04, 0x26, 0x05, 0xe0, 0x44, 0x49, 0x5a, 0x46, + 0xf9, 0xf7, 0x5c, 0xf8, 0x0a, 0x26, 0x07, 0x25, 0x01, 0x22, 0x46, 0xf4, + 0x00, 0x76, 0x13, 0x46, 0x20, 0x46, 0x4f, 0xf4, 0x9b, 0x61, 0x46, 0xea, + 0x05, 0x15, 0xf9, 0xf7, 0x3d, 0xf8, 0xab, 0x00, 0x20, 0x46, 0x4f, 0xf4, + 0x9b, 0x61, 0x40, 0xf6, 0xfc, 0x72, 0xf9, 0xf7, 0x35, 0xf8, 0x02, 0x22, + 0x13, 0x46, 0x20, 0x46, 0x4f, 0xf4, 0x9b, 0x61, 0xf9, 0xf7, 0x2e, 0xf8, + 0x20, 0x46, 0x4f, 0xf4, 0x9b, 0x61, 0x4f, 0xf4, 0xe0, 0x42, 0x4f, 0xf4, + 0x00, 0x53, 0xf9, 0xf7, 0x25, 0xf8, 0x20, 0x22, 0x13, 0x46, 0x20, 0x46, + 0x4f, 0xf4, 0x9a, 0x61, 0xf9, 0xf7, 0x1e, 0xf8, 0x01, 0x21, 0x00, 0x22, + 0x20, 0x46, 0xf9, 0xf7, 0xad, 0xf9, 0x20, 0x46, 0x40, 0xf2, 0x76, 0x41, + 0xf8, 0xf7, 0x23, 0xfe, 0x03, 0x04, 0x02, 0xd4, 0x0a, 0x20, 0xee, 0xf3, + 0x0b, 0xf4, 0x20, 0x46, 0x07, 0x21, 0x42, 0x46, 0xf8, 0xf7, 0xf3, 0xfd, + 0x20, 0x46, 0xff, 0x21, 0x4a, 0x46, 0xf8, 0xf7, 0xee, 0xfd, 0x20, 0x46, + 0x40, 0xf2, 0x1f, 0x11, 0x52, 0x46, 0xf8, 0xf7, 0xe8, 0xfd, 0x20, 0x46, + 0x05, 0x21, 0x00, 0x9a, 0xf8, 0xf7, 0xe3, 0xfd, 0x20, 0x46, 0x25, 0x21, + 0x01, 0x9a, 0xf8, 0xf7, 0xde, 0xfd, 0x20, 0x46, 0x4f, 0xf4, 0x89, 0x71, + 0x02, 0x9a, 0xf8, 0xf7, 0xd8, 0xfd, 0x00, 0x25, 0x07, 0xab, 0x79, 0x5b, + 0x5a, 0x5b, 0x20, 0x46, 0x02, 0x35, 0xf8, 0xf7, 0x01, 0xfe, 0x1c, 0x2d, + 0xf6, 0xd1, 0x05, 0x9b, 0x20, 0x46, 0x59, 0xb2, 0xff, 0xf7, 0xa8, 0xfc, + 0x04, 0x9a, 0x20, 0x46, 0x40, 0xf2, 0xa4, 0x41, 0xf8, 0xf7, 0xc3, 0xfd, + 0x03, 0x9a, 0x1a, 0xb9, 0xe3, 0x69, 0x18, 0x69, 0x38, 0xf0, 0xda, 0xdb, + 0x40, 0xf2, 0xe7, 0x30, 0xee, 0xf3, 0xcc, 0xf3, 0x15, 0xb0, 0xbd, 0xe8, + 0xf0, 0x8f, 0x00, 0xbf, 0x24, 0xeb, 0x01, 0x00, 0x80, 0xec, 0x01, 0x00, + 0xec, 0xec, 0x01, 0x00, 0xfe, 0xec, 0x01, 0x00, 0x0a, 0xed, 0x01, 0x00, + 0x73, 0xb5, 0xd0, 0xf8, 0xb0, 0x30, 0x04, 0x46, 0xd3, 0xf8, 0x20, 0x31, + 0xd0, 0xf8, 0xa8, 0x50, 0x03, 0xf0, 0x01, 0x03, 0x83, 0xf0, 0x01, 0x06, + 0x1b, 0xb1, 0xc3, 0x69, 0x18, 0x69, 0x38, 0xf0, 0xcb, 0xdb, 0x04, 0xf5, + 0x82, 0x53, 0x1b, 0x79, 0x23, 0xbb, 0xb4, 0xf8, 0xda, 0x20, 0x02, 0xf4, + 0x70, 0x42, 0xb2, 0xf5, 0x00, 0x5f, 0x06, 0xd1, 0x04, 0x22, 0xad, 0xf8, + 0x00, 0x20, 0x0c, 0x22, 0xad, 0xf8, 0x02, 0x20, 0x05, 0xe0, 0xff, 0x22, + 0xad, 0xf8, 0x00, 0x20, 0xad, 0xf8, 0x02, 0x20, 0xf0, 0x22, 0x20, 0x46, + 0x69, 0x46, 0xad, 0xf8, 0x04, 0x20, 0xad, 0xf8, 0x06, 0x30, 0xfb, 0xf7, + 0xec, 0xf8, 0x20, 0x46, 0x96, 0x21, 0xfd, 0xf7, 0x93, 0xfc, 0x20, 0x46, + 0x01, 0x21, 0xff, 0xf7, 0x79, 0xfe, 0x5b, 0xe0, 0x20, 0x46, 0xff, 0xf7, + 0x6f, 0xfd, 0x20, 0x46, 0xfe, 0xf7, 0x2e, 0xfc, 0x20, 0x46, 0x00, 0x21, + 0xfe, 0xf7, 0x69, 0xfe, 0x20, 0x46, 0x38, 0x49, 0x0f, 0x22, 0xf8, 0xf7, + 0x8b, 0xff, 0x95, 0xf8, 0xe8, 0x33, 0xdb, 0xb1, 0x20, 0x46, 0x01, 0x21, + 0xfe, 0xf7, 0x5d, 0xfe, 0x95, 0xf9, 0x24, 0x35, 0x20, 0x46, 0x40, 0xf2, + 0xd1, 0x41, 0xff, 0x22, 0x9b, 0xb2, 0xf8, 0xf7, 0x69, 0xff, 0x95, 0xf8, + 0x25, 0x35, 0x20, 0x46, 0x40, 0xf2, 0xd1, 0x41, 0x4f, 0xf4, 0x7f, 0x42, + 0x1b, 0x02, 0xf8, 0xf7, 0x5f, 0xff, 0x20, 0x46, 0x29, 0x49, 0x0c, 0x22, + 0xf8, 0xf7, 0x6c, 0xff, 0x05, 0x22, 0x28, 0x49, 0x20, 0x46, 0xf8, 0xf7, + 0x67, 0xff, 0xd4, 0xf8, 0xa8, 0x30, 0xd3, 0xf8, 0x48, 0x24, 0xd3, 0xf8, + 0x44, 0x34, 0x3c, 0x2b, 0xb4, 0xbf, 0x19, 0x46, 0x3c, 0x21, 0x8a, 0x42, + 0x01, 0xdd, 0x93, 0xb2, 0x03, 0xe0, 0x3b, 0x2b, 0xd4, 0xbf, 0x9b, 0xb2, + 0x3c, 0x23, 0x20, 0x46, 0x40, 0xf2, 0xa7, 0x41, 0xff, 0x22, 0xf8, 0xf7, + 0x3d, 0xff, 0xb4, 0xf8, 0xda, 0x30, 0x20, 0x46, 0x03, 0xf4, 0x70, 0x43, + 0xb3, 0xf5, 0x00, 0x5f, 0x0c, 0xbf, 0x95, 0xf8, 0x54, 0x34, 0x95, 0xf8, + 0x55, 0x34, 0x4f, 0xf4, 0x40, 0x41, 0x2b, 0x86, 0xff, 0xf7, 0x36, 0xf8, + 0x40, 0xf2, 0x76, 0x41, 0x20, 0x46, 0xf8, 0xf7, 0x36, 0xfd, 0xc0, 0x05, + 0xc0, 0x0d, 0xa5, 0xf8, 0x6c, 0x05, 0x40, 0xf2, 0x77, 0x41, 0x20, 0x46, + 0xf8, 0xf7, 0x2d, 0xfd, 0xd5, 0xf8, 0x34, 0x34, 0xc0, 0x05, 0xc0, 0x0d, + 0xa5, 0xf8, 0x6e, 0x05, 0x1b, 0xb1, 0x20, 0x46, 0x01, 0x21, 0xfc, 0xf7, + 0xac, 0xf9, 0x1e, 0xb9, 0xe3, 0x69, 0x18, 0x69, 0x38, 0xf0, 0x14, 0xdb, + 0x7c, 0xbd, 0x00, 0xbf, 0x40, 0xeb, 0x01, 0x00, 0x5e, 0xeb, 0x01, 0x00, + 0x76, 0xeb, 0x01, 0x00, 0xf8, 0xb5, 0xd0, 0xf8, 0xa8, 0x40, 0x01, 0x23, + 0x84, 0xf8, 0x61, 0x30, 0x00, 0x23, 0x84, 0xf8, 0xc0, 0x33, 0xb0, 0xf8, + 0xda, 0x30, 0x05, 0x46, 0x03, 0xf4, 0x70, 0x43, 0xb3, 0xf5, 0x00, 0x5f, + 0x02, 0xd1, 0x94, 0xf8, 0xc1, 0x33, 0x04, 0xe0, 0xb3, 0xf5, 0x80, 0x5f, + 0x06, 0xd1, 0x94, 0xf8, 0xc2, 0x33, 0x02, 0x2b, 0x02, 0xd1, 0x01, 0x23, + 0x84, 0xf8, 0xc0, 0x33, 0xb5, 0xf8, 0xda, 0x30, 0x28, 0x46, 0x03, 0xf4, + 0x70, 0x43, 0xb3, 0xf5, 0x80, 0x5f, 0x0c, 0xbf, 0x94, 0xf8, 0xeb, 0x33, + 0x94, 0xf8, 0xea, 0x33, 0x00, 0x26, 0x84, 0xf8, 0xe9, 0x33, 0x63, 0x8b, + 0x01, 0x27, 0xa4, 0xf8, 0xbe, 0x32, 0x04, 0x22, 0x22, 0x49, 0x26, 0x70, + 0x84, 0xf8, 0xc2, 0x62, 0x84, 0xf8, 0xc3, 0x62, 0x84, 0xf8, 0xc4, 0x62, + 0x84, 0xf8, 0x67, 0x75, 0xf8, 0xf7, 0xda, 0xfe, 0x28, 0x46, 0x39, 0x46, + 0xfb, 0xf7, 0xc3, 0xfa, 0x04, 0x22, 0x1b, 0x49, 0x28, 0x46, 0xf8, 0xf7, + 0xd1, 0xfe, 0x28, 0x46, 0xfd, 0xf7, 0x32, 0xff, 0x28, 0x46, 0xff, 0xf7, + 0xb3, 0xfa, 0x28, 0x46, 0xff, 0xf7, 0xf4, 0xfe, 0x84, 0xf8, 0x2c, 0x60, + 0xb5, 0xf8, 0xda, 0x10, 0x28, 0x46, 0xfa, 0xf7, 0x31, 0xf8, 0x28, 0x46, + 0xfd, 0xf7, 0x47, 0xf8, 0x4f, 0xf4, 0x80, 0x42, 0x13, 0x46, 0x4f, 0xf4, + 0x89, 0x61, 0x28, 0x46, 0xf8, 0xf7, 0xa4, 0xfe, 0x64, 0x20, 0xee, 0xf3, + 0x9d, 0xf2, 0x33, 0x46, 0x28, 0x46, 0x4f, 0xf4, 0x89, 0x61, 0x4f, 0xf4, + 0x80, 0x42, 0xf8, 0xf7, 0x99, 0xfe, 0x28, 0x46, 0x4f, 0xf4, 0x40, 0x41, + 0xfe, 0xf7, 0x9e, 0xff, 0x41, 0xf2, 0x88, 0x33, 0xe3, 0x86, 0x84, 0xf8, + 0x9a, 0x75, 0xf8, 0xbd, 0x6c, 0xe8, 0x01, 0x00, 0x9a, 0xe8, 0x01, 0x00, + 0x2d, 0xe9, 0xf0, 0x4f, 0xd0, 0xf8, 0xa8, 0x60, 0x15, 0x46, 0x03, 0xf1, + 0x34, 0x02, 0x06, 0xeb, 0x42, 0x02, 0xb2, 0xf8, 0x04, 0x80, 0x06, 0xeb, + 0x43, 0x03, 0xb2, 0xf8, 0x0a, 0x90, 0xb3, 0xf8, 0x78, 0x70, 0x89, 0xb0, + 0x04, 0x46, 0x4a, 0x46, 0x8a, 0x46, 0x41, 0x46, 0xfe, 0xf7, 0x5c, 0xf8, + 0x20, 0x46, 0x39, 0x46, 0xff, 0xf7, 0x8c, 0xf8, 0x07, 0x23, 0x04, 0x93, + 0x20, 0x23, 0x06, 0x93, 0x4f, 0xea, 0x88, 0x58, 0x01, 0x23, 0x03, 0x93, + 0x4f, 0xea, 0x98, 0x58, 0x07, 0xab, 0x02, 0x93, 0x4f, 0xea, 0x88, 0x28, + 0x4f, 0xf0, 0x00, 0x0b, 0x2f, 0xe0, 0x13, 0xb1, 0x1a, 0xf0, 0x01, 0x0f, + 0x29, 0xd1, 0x5b, 0xb2, 0x01, 0x33, 0xba, 0xfb, 0xf3, 0xf3, 0x03, 0xf5, + 0xa0, 0x73, 0x20, 0x46, 0x02, 0xa9, 0x05, 0x93, 0xfc, 0xf7, 0xf0, 0xfe, + 0x07, 0x9a, 0x4f, 0xea, 0x89, 0x53, 0x4f, 0xea, 0x12, 0x5b, 0x9b, 0x0d, + 0x4f, 0xea, 0x0b, 0x5b, 0x43, 0xea, 0x0b, 0x0b, 0x20, 0x46, 0x02, 0xa9, + 0x4b, 0xea, 0x08, 0x0b, 0xcd, 0xf8, 0x1c, 0xb0, 0xfd, 0xf7, 0xc1, 0xf9, + 0x96, 0xf9, 0x66, 0x35, 0x20, 0x46, 0x01, 0x33, 0xba, 0xfb, 0xf3, 0xf3, + 0x03, 0xf5, 0xe0, 0x73, 0x02, 0xa9, 0x05, 0x93, 0x07, 0x97, 0xfd, 0xf7, + 0xb4, 0xf9, 0x0a, 0xf1, 0x01, 0x0a, 0xaa, 0x45, 0x96, 0xf8, 0x66, 0x35, + 0xcb, 0xd9, 0xb3, 0xb1, 0x7f, 0x2d, 0x14, 0xd1, 0x4f, 0xf4, 0xc0, 0x75, + 0x20, 0x46, 0x02, 0xa9, 0x05, 0x95, 0xcd, 0xf8, 0x1c, 0xb0, 0xfd, 0xf7, + 0xa2, 0xf9, 0x05, 0xf1, 0x80, 0x03, 0x20, 0x46, 0x02, 0xa9, 0x01, 0x35, + 0x07, 0x97, 0x05, 0x93, 0xfd, 0xf7, 0x99, 0xf9, 0xb5, 0xf5, 0xe0, 0x7f, + 0xec, 0xd1, 0x96, 0xf8, 0x81, 0x00, 0x96, 0xf8, 0x7e, 0x10, 0x96, 0xf8, + 0x7f, 0x20, 0x96, 0xf8, 0x80, 0x30, 0x00, 0x90, 0x20, 0x46, 0xfb, 0xf7, + 0x39, 0xfb, 0x09, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, 0x70, 0xb5, 0x00, 0x21, + 0x04, 0x46, 0xd0, 0xf8, 0xa8, 0x50, 0x0b, 0x46, 0x7f, 0x22, 0xff, 0xf7, + 0x6f, 0xff, 0x20, 0x46, 0xfe, 0xf7, 0x86, 0xf8, 0x20, 0x46, 0xb5, 0xf8, + 0xb8, 0x12, 0xb5, 0xf8, 0xba, 0x22, 0xfa, 0xf7, 0xe6, 0xff, 0x20, 0x46, + 0x40, 0xf2, 0xd1, 0x61, 0x04, 0x22, 0x00, 0x23, 0xbd, 0xe8, 0x70, 0x40, + 0xf8, 0xf7, 0xe6, 0xbd, 0x70, 0xb5, 0x04, 0x46, 0xd0, 0xf8, 0xa8, 0x30, + 0x0d, 0x46, 0xa9, 0xb1, 0x93, 0xf8, 0xbc, 0x32, 0x00, 0x2b, 0x29, 0xd0, + 0xff, 0xf7, 0xd8, 0xff, 0x20, 0x46, 0x04, 0x22, 0x00, 0x23, 0x40, 0xf2, + 0xd1, 0x61, 0xf8, 0xf7, 0xd3, 0xfd, 0x80, 0x22, 0x20, 0x46, 0x40, 0xf2, + 0x76, 0x61, 0x13, 0x46, 0xbd, 0xe8, 0x70, 0x40, 0xf8, 0xf7, 0xca, 0xbd, + 0x04, 0x22, 0x13, 0x46, 0x40, 0xf2, 0xd1, 0x61, 0xf8, 0xf7, 0xc4, 0xfd, + 0x80, 0x22, 0x20, 0x46, 0x2b, 0x46, 0x40, 0xf2, 0x76, 0x61, 0xf8, 0xf7, + 0xbd, 0xfd, 0x20, 0x46, 0x29, 0x46, 0xfe, 0xf7, 0xd7, 0xff, 0x20, 0x46, + 0x29, 0x46, 0x2a, 0x46, 0xbd, 0xe8, 0x70, 0x40, 0xfd, 0xf7, 0x9c, 0xbf, + 0x70, 0xbd, 0x00, 0x00, 0x10, 0xb5, 0x04, 0x46, 0x11, 0xb9, 0x10, 0x49, + 0x13, 0x22, 0x18, 0xe0, 0x12, 0x22, 0x0f, 0x49, 0xf8, 0xf7, 0xb8, 0xfd, + 0x01, 0x21, 0x00, 0x22, 0x20, 0x46, 0xfb, 0xf7, 0x49, 0xff, 0x0c, 0x49, + 0x06, 0x22, 0x20, 0x46, 0xf8, 0xf7, 0xae, 0xfd, 0xb4, 0xf8, 0xda, 0x30, + 0x20, 0x46, 0x03, 0xf4, 0x70, 0x43, 0xb3, 0xf5, 0x00, 0x5f, 0x0c, 0xbf, + 0x06, 0x49, 0x07, 0x49, 0x1e, 0x22, 0xbd, 0xe8, 0x10, 0x40, 0xf8, 0xf7, + 0x9f, 0xbd, 0x00, 0xbf, 0x74, 0xe8, 0x01, 0x00, 0x44, 0xea, 0x01, 0x00, + 0xa2, 0xe8, 0x01, 0x00, 0x68, 0xea, 0x01, 0x00, 0xa4, 0xea, 0x01, 0x00, + 0x2d, 0xe9, 0xf0, 0x41, 0x04, 0x46, 0x0f, 0x46, 0x15, 0x46, 0x40, 0xf2, + 0xda, 0x61, 0x48, 0xf2, 0x80, 0x02, 0x1e, 0x46, 0x9d, 0xf8, 0x18, 0x80, + 0xf8, 0xf7, 0x66, 0xfd, 0x20, 0x46, 0xfa, 0xf7, 0x3f, 0xfc, 0xb8, 0xb1, + 0x40, 0xf6, 0x52, 0x11, 0x20, 0x46, 0xf8, 0xf7, 0x7a, 0xfb, 0xff, 0x22, + 0xc3, 0xb2, 0x40, 0xf6, 0x48, 0x11, 0x20, 0x46, 0xf8, 0xf7, 0x64, 0xfd, + 0x40, 0xf6, 0x53, 0x11, 0x20, 0x46, 0xf8, 0xf7, 0x6e, 0xfb, 0x40, 0xf6, + 0x49, 0x11, 0xc3, 0xb2, 0xff, 0x22, 0x20, 0x46, 0xf8, 0xf7, 0x58, 0xfd, + 0xd4, 0xf8, 0xa8, 0x30, 0x93, 0xf8, 0x46, 0x35, 0x7b, 0xb1, 0x40, 0xf2, + 0xeb, 0x41, 0x20, 0x46, 0xf8, 0xf7, 0x5d, 0xfb, 0x00, 0xf4, 0x00, 0x73, + 0x5b, 0x12, 0x20, 0x46, 0x40, 0xf2, 0xeb, 0x41, 0x4f, 0xf4, 0x80, 0x62, + 0x9b, 0x02, 0xf8, 0xf7, 0x43, 0xfd, 0x7b, 0x1e, 0xff, 0x22, 0x9b, 0xb2, + 0x20, 0x46, 0x40, 0xf2, 0x42, 0x61, 0xf8, 0xf7, 0x3b, 0xfd, 0x4f, 0xf6, + 0xff, 0x73, 0x9d, 0x42, 0x01, 0xd0, 0x01, 0x3d, 0xad, 0xb2, 0x20, 0x46, + 0x4f, 0xf4, 0xc8, 0x61, 0x4f, 0xf6, 0xff, 0x72, 0x2b, 0x46, 0xf8, 0xf7, + 0x2d, 0xfd, 0x20, 0x46, 0x40, 0xf2, 0x41, 0x61, 0x4f, 0xf6, 0xff, 0x72, + 0x33, 0x46, 0xf8, 0xf7, 0x25, 0xfd, 0x20, 0x46, 0xb8, 0xf1, 0x00, 0x0f, + 0x05, 0xd0, 0x08, 0x49, 0x04, 0x22, 0xbd, 0xe8, 0xf0, 0x41, 0xf8, 0xf7, + 0x2d, 0xbd, 0x40, 0xf2, 0x3f, 0x61, 0x01, 0x22, 0xf8, 0xf7, 0x30, 0xfb, + 0x20, 0x46, 0x01, 0x21, 0xbd, 0xe8, 0xf0, 0x41, 0xff, 0xf7, 0x60, 0xbf, + 0x00, 0xee, 0x01, 0x00, 0xf8, 0xb5, 0x0f, 0x46, 0x40, 0xf2, 0x3b, 0x41, + 0x04, 0x46, 0xf8, 0xf7, 0x16, 0xfb, 0x40, 0xf2, 0x3c, 0x41, 0x06, 0x46, + 0x20, 0x46, 0xf8, 0xf7, 0x10, 0xfb, 0x05, 0x46, 0x20, 0x46, 0x77, 0xb1, + 0x0e, 0x22, 0x10, 0x49, 0xf8, 0xf7, 0x0c, 0xfd, 0x20, 0x46, 0x01, 0x21, + 0xff, 0xf7, 0x46, 0xff, 0x0d, 0x49, 0x20, 0x46, 0x07, 0x22, 0xbd, 0xe8, + 0xf8, 0x40, 0xf8, 0xf7, 0x01, 0xbd, 0x04, 0x22, 0x0a, 0x49, 0xf8, 0xf7, + 0xfd, 0xfc, 0x20, 0x46, 0x32, 0x46, 0x40, 0xf2, 0x3b, 0x41, 0xf8, 0xf7, + 0xff, 0xfa, 0x20, 0x46, 0x40, 0xf2, 0x3c, 0x41, 0x2a, 0x46, 0xbd, 0xe8, + 0xf8, 0x40, 0xf8, 0xf7, 0xf7, 0xba, 0x00, 0xbf, 0x08, 0xe9, 0x01, 0x00, + 0x24, 0xe9, 0x01, 0x00, 0x32, 0xe9, 0x01, 0x00, 0x70, 0xb5, 0x04, 0x46, + 0x0d, 0x46, 0xf8, 0xf7, 0x6a, 0xfc, 0x20, 0x22, 0x6b, 0x01, 0x20, 0x46, + 0x4f, 0xf4, 0x96, 0x61, 0xf8, 0xf7, 0xca, 0xfc, 0x00, 0x23, 0x20, 0x46, + 0x40, 0xf2, 0xb1, 0x41, 0x4f, 0xf4, 0x00, 0x72, 0xf8, 0xf7, 0xc2, 0xfc, + 0xb4, 0xf8, 0xda, 0x30, 0x03, 0xf4, 0x70, 0x43, 0xb3, 0xf5, 0x00, 0x5f, + 0x04, 0xd1, 0xd5, 0xf1, 0x01, 0x03, 0x38, 0xbf, 0x00, 0x23, 0x00, 0xe0, + 0x00, 0x23, 0x00, 0x2d, 0x0c, 0xbf, 0x20, 0x26, 0x00, 0x26, 0x20, 0x46, + 0x60, 0x22, 0x46, 0xea, 0x83, 0x13, 0x4f, 0xf4, 0x82, 0x61, 0xf8, 0xf7, + 0xa9, 0xfc, 0x20, 0x46, 0x4f, 0xf4, 0x82, 0x61, 0x80, 0x22, 0xeb, 0x01, + 0xf8, 0xf7, 0xa2, 0xfc, 0x20, 0x46, 0xbd, 0xe8, 0x70, 0x40, 0xf8, 0xf7, + 0x3a, 0xbc, 0x00, 0x00, 0x2d, 0xe9, 0xf0, 0x4f, 0xc3, 0xb0, 0x19, 0x93, + 0x9d, 0xf8, 0x34, 0x31, 0x9d, 0xf8, 0x30, 0x91, 0x0c, 0x93, 0x9d, 0xf8, + 0x38, 0x31, 0xbd, 0xf8, 0x44, 0x71, 0x0d, 0x93, 0x9d, 0xf8, 0x3c, 0x31, + 0xd0, 0xf8, 0xa8, 0xb0, 0x0e, 0x93, 0x9d, 0xf8, 0x40, 0x31, 0x15, 0x46, + 0x0f, 0x93, 0x4e, 0x4b, 0x04, 0x46, 0x88, 0x46, 0x24, 0xaa, 0x03, 0xf1, + 0x20, 0x0e, 0x18, 0x68, 0x59, 0x68, 0x16, 0x46, 0x03, 0xc6, 0x08, 0x33, + 0x73, 0x45, 0x32, 0x46, 0xf7, 0xd1, 0x18, 0x68, 0x18, 0x23, 0x30, 0x60, + 0x34, 0x93, 0x3e, 0xab, 0x01, 0x26, 0x32, 0x93, 0x20, 0x46, 0x20, 0x23, + 0x36, 0x93, 0x8d, 0xf8, 0x06, 0x61, 0x8d, 0xf8, 0x07, 0x61, 0x33, 0x96, + 0x35, 0x96, 0xfe, 0xf7, 0x6f, 0xfe, 0x40, 0xf2, 0xd7, 0x41, 0x10, 0x90, + 0x20, 0x46, 0xf8, 0xf7, 0x6e, 0xfa, 0xc0, 0xf3, 0xc0, 0x00, 0x11, 0x90, + 0x40, 0xf2, 0xd7, 0x41, 0x20, 0x46, 0xf8, 0xf7, 0x66, 0xfa, 0x00, 0xf4, + 0xe0, 0x40, 0x00, 0x0b, 0x12, 0x90, 0x36, 0x49, 0x20, 0x46, 0x06, 0x22, + 0xf8, 0xf7, 0x60, 0xfc, 0x20, 0x46, 0x34, 0x49, 0x0f, 0x22, 0xf8, 0xf7, + 0x5b, 0xfc, 0x20, 0x46, 0x31, 0x46, 0x1b, 0xaa, 0xfc, 0xf7, 0x60, 0xff, + 0x20, 0x46, 0x31, 0x46, 0x00, 0x22, 0xfc, 0xf7, 0xcf, 0xfe, 0xb9, 0xf1, + 0x00, 0x0f, 0x17, 0xd1, 0x20, 0x46, 0x31, 0x46, 0xff, 0xf7, 0x62, 0xff, + 0xd4, 0xf8, 0xb0, 0x30, 0xd3, 0xf8, 0x20, 0x31, 0xda, 0x07, 0x10, 0xd5, + 0xe3, 0x69, 0xb8, 0x21, 0x18, 0x69, 0x42, 0xf2, 0x10, 0x72, 0x38, 0xf0, + 0x13, 0xd8, 0xe3, 0x69, 0x18, 0x69, 0x38, 0xf0, 0x41, 0xd8, 0xcd, 0xf8, + 0x28, 0x90, 0x03, 0xe0, 0x00, 0x23, 0x0a, 0x93, 0x00, 0xe0, 0x0a, 0x96, + 0x20, 0x46, 0x01, 0x21, 0xfa, 0xf7, 0xb3, 0xfd, 0x20, 0x46, 0x01, 0x21, + 0xff, 0xf7, 0x68, 0xfe, 0x20, 0x46, 0x01, 0x21, 0xfa, 0xf7, 0xcc, 0xfe, + 0x40, 0xf2, 0xea, 0x41, 0x20, 0x46, 0xf8, 0xf7, 0x1e, 0xfa, 0x40, 0xf2, + 0xeb, 0x41, 0x13, 0x90, 0x20, 0x46, 0xf8, 0xf7, 0x18, 0xfa, 0x40, 0xf2, + 0xeb, 0x41, 0x14, 0x90, 0x20, 0x46, 0xf8, 0xf7, 0x12, 0xfa, 0x00, 0xf0, + 0x07, 0x03, 0x40, 0xf2, 0xeb, 0x41, 0x20, 0x46, 0xdb, 0x00, 0x38, 0x22, + 0xf8, 0xf7, 0xfa, 0xfb, 0x9b, 0xf8, 0xc1, 0x32, 0x20, 0x46, 0x3c, 0xa9, + 0x0b, 0x93, 0xfa, 0xf7, 0xa2, 0xfb, 0x95, 0xb1, 0x2b, 0x7a, 0x20, 0x46, + 0x63, 0xb1, 0x69, 0x7a, 0xff, 0xf7, 0xb4, 0xf8, 0x6b, 0x7a, 0x0b, 0x93, + 0x09, 0xe0, 0x00, 0xbf, 0x84, 0xb8, 0x01, 0x00, 0x3c, 0xe7, 0x01, 0x00, + 0x7a, 0xe9, 0x01, 0x00, 0x29, 0x46, 0xfa, 0xf7, 0x3a, 0xfd, 0x40, 0xf2, + 0x9c, 0x41, 0x20, 0x46, 0xf8, 0xf7, 0xe9, 0xf9, 0x40, 0xf2, 0x31, 0x61, + 0x15, 0x90, 0x20, 0x46, 0xf8, 0xf7, 0xe3, 0xf9, 0x40, 0xf2, 0xd6, 0x61, + 0x16, 0x90, 0x20, 0x46, 0xf8, 0xf7, 0xdd, 0xf9, 0x40, 0xf2, 0xda, 0x61, + 0x17, 0x90, 0x20, 0x46, 0xf8, 0xf7, 0xd7, 0xf9, 0x00, 0x21, 0x18, 0x90, + 0x20, 0x46, 0xfa, 0xf7, 0xc2, 0xff, 0x20, 0x46, 0xa4, 0x49, 0x07, 0x22, + 0xf8, 0xf7, 0xd0, 0xfb, 0x40, 0xab, 0x2d, 0x93, 0x01, 0x23, 0x2e, 0x93, + 0x07, 0x23, 0x2f, 0x93, 0x75, 0xb1, 0x9b, 0xf9, 0x66, 0x35, 0x6a, 0x7a, + 0x01, 0x33, 0x92, 0xfb, 0xf3, 0xf3, 0x03, 0xf5, 0x10, 0x73, 0x30, 0x93, + 0x20, 0x46, 0x20, 0x23, 0x2d, 0xa9, 0x31, 0x93, 0xfc, 0xf7, 0x4a, 0xfc, + 0x40, 0x9b, 0x4f, 0xf6, 0xf8, 0x72, 0xdb, 0x00, 0x1a, 0x40, 0x20, 0x46, + 0x40, 0xf2, 0x71, 0x61, 0x40, 0x93, 0xf8, 0xf7, 0xb7, 0xf9, 0x20, 0x46, + 0x92, 0x49, 0x0c, 0x22, 0xf8, 0xf7, 0xaa, 0xfb, 0x0d, 0xf1, 0x8e, 0x0a, + 0x56, 0x46, 0x00, 0x25, 0x20, 0x46, 0x36, 0xf8, 0x02, 0x1f, 0xf8, 0xf7, + 0x61, 0xf9, 0x37, 0xab, 0x58, 0x55, 0x01, 0x35, 0x12, 0x2d, 0xf5, 0xd1, + 0x07, 0x22, 0x20, 0x46, 0x4f, 0xf4, 0x8b, 0x71, 0xf8, 0xf7, 0x6d, 0xf9, + 0xb4, 0xf8, 0xda, 0x30, 0x03, 0xf4, 0x70, 0x43, 0xb3, 0xf5, 0x00, 0x5f, + 0x05, 0xd1, 0x20, 0x46, 0x40, 0xf2, 0x2d, 0x11, 0x01, 0x22, 0xf8, 0xf7, + 0x60, 0xf9, 0x07, 0x22, 0x20, 0x46, 0x4f, 0xf4, 0x96, 0x71, 0xf8, 0xf7, + 0x5a, 0xf9, 0xb4, 0xf8, 0xda, 0x30, 0x03, 0xf4, 0x70, 0x43, 0xb3, 0xf5, + 0x00, 0x5f, 0x14, 0xd1, 0x20, 0x46, 0x6a, 0x21, 0xc2, 0x22, 0xf8, 0xf7, + 0x4e, 0xf9, 0x20, 0x46, 0x98, 0x21, 0x0c, 0x22, 0xf8, 0xf7, 0x49, 0xf9, + 0x20, 0x46, 0x40, 0xf2, 0x2f, 0x11, 0x03, 0x22, 0xf8, 0xf7, 0x43, 0xf9, + 0x20, 0x46, 0x97, 0x21, 0xf9, 0x22, 0xf8, 0xf7, 0x3e, 0xf9, 0x0b, 0x21, + 0x07, 0x22, 0x20, 0x46, 0xf8, 0xf7, 0x39, 0xf9, 0x10, 0x22, 0x20, 0x46, + 0x40, 0xf2, 0x13, 0x11, 0xf8, 0xf7, 0x33, 0xf9, 0x1d, 0x21, 0x01, 0x22, + 0x20, 0x46, 0xf8, 0xf7, 0x2e, 0xf9, 0x01, 0x22, 0x20, 0x46, 0x4f, 0xf4, + 0x8a, 0x71, 0xf8, 0xf7, 0x28, 0xf9, 0xb4, 0xf8, 0xda, 0x30, 0x03, 0xf4, + 0x70, 0x43, 0xb3, 0xf5, 0x00, 0x5f, 0x04, 0xd1, 0x20, 0x46, 0x2e, 0x21, + 0x10, 0x22, 0xf8, 0xf7, 0x1c, 0xf9, 0x20, 0x46, 0x4f, 0xf4, 0x95, 0x71, + 0x08, 0x22, 0xf8, 0xf7, 0x16, 0xf9, 0x20, 0x46, 0x09, 0x21, 0x02, 0x22, + 0xf8, 0xf7, 0x11, 0xf9, 0x04, 0x22, 0x13, 0x46, 0x20, 0x46, 0x40, 0xf2, + 0x1f, 0x11, 0xf8, 0xf7, 0xdf, 0xfa, 0x20, 0x46, 0xff, 0x21, 0x10, 0x22, + 0x00, 0x23, 0xf8, 0xf7, 0xd9, 0xfa, 0x20, 0x46, 0x07, 0x21, 0x01, 0x22, + 0x00, 0x23, 0xf8, 0xf7, 0xd3, 0xfa, 0x20, 0x46, 0x05, 0x21, 0x08, 0x22, + 0x00, 0x23, 0xf8, 0xf7, 0xcd, 0xfa, 0x4f, 0xf4, 0x00, 0x42, 0x13, 0x46, + 0x20, 0x46, 0x40, 0xf2, 0xda, 0x61, 0xf8, 0xf7, 0x07, 0xfb, 0x41, 0x46, + 0x19, 0x9a, 0x0b, 0x9b, 0x20, 0x46, 0xfd, 0xf7, 0x23, 0xf9, 0x00, 0x25, + 0x83, 0xb2, 0x01, 0x93, 0x01, 0x21, 0x2a, 0x46, 0x2b, 0x46, 0x06, 0x46, + 0x20, 0x46, 0x00, 0x95, 0x02, 0x95, 0x03, 0x95, 0x04, 0x95, 0xfa, 0xf7, + 0x25, 0xfd, 0x0c, 0x9b, 0xaf, 0x42, 0x08, 0xbf, 0x4f, 0xf4, 0x82, 0x47, + 0x00, 0x93, 0x0d, 0x9b, 0x20, 0x46, 0x01, 0x93, 0x0e, 0x9b, 0x41, 0x46, + 0x02, 0x93, 0x0f, 0x9b, 0x2a, 0x46, 0x03, 0x93, 0x4f, 0xf4, 0xaf, 0x63, + 0x04, 0x93, 0x80, 0x23, 0x07, 0x93, 0x4b, 0x46, 0x05, 0x97, 0x06, 0x95, + 0x08, 0x95, 0xfd, 0xf7, 0x4d, 0xf8, 0x9b, 0xf9, 0x09, 0x34, 0x00, 0x2b, + 0x2f, 0xd0, 0x2c, 0xe0, 0x20, 0x46, 0x32, 0xa9, 0xfc, 0xf7, 0x72, 0xfb, + 0x3e, 0x9b, 0x43, 0xf3, 0x0b, 0x33, 0x87, 0x2b, 0x25, 0xdd, 0x01, 0x3e, + 0x00, 0x25, 0xb3, 0xb2, 0x01, 0x93, 0x20, 0x46, 0x01, 0x21, 0x2a, 0x46, + 0x2b, 0x46, 0x00, 0x95, 0x02, 0x95, 0x03, 0x95, 0x04, 0x95, 0xfa, 0xf7, + 0xef, 0xfc, 0x0c, 0x9b, 0x20, 0x46, 0x00, 0x93, 0x0d, 0x9b, 0x41, 0x46, + 0x01, 0x93, 0x0e, 0x9b, 0x2a, 0x46, 0x02, 0x93, 0x0f, 0x9b, 0x05, 0x97, + 0x03, 0x93, 0x4f, 0xf4, 0xaf, 0x63, 0x04, 0x93, 0x80, 0x23, 0x07, 0x93, + 0x4b, 0x46, 0x06, 0x95, 0x08, 0x95, 0xfd, 0xf7, 0x1b, 0xf8, 0x00, 0x2e, + 0xd0, 0xd1, 0x41, 0xaa, 0x03, 0x32, 0x20, 0x46, 0x0d, 0xf5, 0x83, 0x71, + 0xfa, 0xf7, 0x73, 0xfa, 0x9d, 0xf8, 0x07, 0x21, 0x3f, 0x2a, 0x55, 0xd8, + 0x9d, 0xf9, 0x06, 0x31, 0x00, 0x2b, 0x51, 0xdb, 0x3f, 0x2b, 0x4f, 0xdc, + 0x52, 0xb2, 0x9a, 0x42, 0x4c, 0xdc, 0xb8, 0xf1, 0x00, 0x0f, 0x28, 0xd1, + 0x18, 0x23, 0x42, 0xad, 0x2f, 0x93, 0x3f, 0xab, 0x45, 0xf8, 0x54, 0x3d, + 0x29, 0x46, 0x20, 0x46, 0x30, 0x92, 0xfc, 0xf7, 0x25, 0xfb, 0x9d, 0xf9, + 0x06, 0x31, 0x29, 0x46, 0x20, 0x46, 0x3f, 0x9e, 0x30, 0x93, 0x45, 0x46, + 0xfc, 0xf7, 0x1c, 0xfb, 0x0e, 0xe0, 0x00, 0xbf, 0x48, 0xe7, 0x01, 0x00, + 0xb4, 0xeb, 0x01, 0x00, 0x42, 0xa9, 0x3f, 0xab, 0x41, 0xf8, 0x54, 0x3d, + 0x20, 0x46, 0x30, 0x95, 0x3f, 0x96, 0xfc, 0xf7, 0xf0, 0xfd, 0x01, 0x35, + 0x9d, 0xf9, 0x07, 0x21, 0x6b, 0xb2, 0x9a, 0x42, 0xf0, 0xdc, 0x18, 0x23, + 0x2f, 0x93, 0x3e, 0x23, 0x42, 0xad, 0x30, 0x93, 0x3f, 0xab, 0x45, 0xf8, + 0x54, 0x3d, 0x20, 0x46, 0x29, 0x46, 0xfc, 0xf7, 0xfb, 0xfa, 0x3f, 0x23, + 0x20, 0x46, 0x29, 0x46, 0x30, 0x93, 0xfc, 0xf7, 0xd8, 0xfd, 0x01, 0x23, + 0x20, 0x46, 0x29, 0x46, 0x30, 0x93, 0xfc, 0xf7, 0xef, 0xfa, 0x00, 0x23, + 0x20, 0x46, 0x29, 0x46, 0x30, 0x93, 0xfc, 0xf7, 0xcc, 0xfd, 0x20, 0x46, + 0xfc, 0xf7, 0x65, 0xfb, 0x20, 0x46, 0x40, 0xf2, 0xea, 0x41, 0x13, 0x9a, + 0xf8, 0xf7, 0x58, 0xf8, 0x20, 0x46, 0x40, 0xf2, 0xeb, 0x41, 0x14, 0x9a, + 0xf8, 0xf7, 0x52, 0xf8, 0x20, 0x46, 0xd7, 0x21, 0x02, 0x22, 0x00, 0x23, + 0xf8, 0xf7, 0xf0, 0xf9, 0x08, 0x22, 0x13, 0x46, 0x20, 0x46, 0xd7, 0x21, + 0xf8, 0xf7, 0xea, 0xf9, 0x00, 0x23, 0x20, 0x46, 0x4f, 0xf4, 0x94, 0x71, + 0x08, 0x22, 0xf8, 0xf7, 0xe3, 0xf9, 0x20, 0x46, 0x4f, 0xf4, 0x8b, 0x71, + 0x00, 0x22, 0xf8, 0xf7, 0x08, 0xf8, 0x20, 0x46, 0x40, 0xf2, 0x9c, 0x41, + 0x15, 0x9a, 0xf8, 0xf7, 0x33, 0xf8, 0x20, 0x46, 0x40, 0xf2, 0x31, 0x61, + 0x16, 0x9a, 0xf8, 0xf7, 0x2d, 0xf8, 0x20, 0x46, 0x40, 0xf2, 0xd6, 0x61, + 0x17, 0x9a, 0xf8, 0xf7, 0x27, 0xf8, 0x18, 0x9d, 0x20, 0x46, 0x45, 0xf0, + 0x01, 0x02, 0x92, 0xb2, 0x40, 0xf2, 0xda, 0x61, 0xf8, 0xf7, 0x1e, 0xf8, + 0x20, 0x46, 0x01, 0x21, 0xfa, 0xf7, 0xff, 0xfd, 0x11, 0x9d, 0x20, 0x46, + 0xeb, 0x00, 0x40, 0xf2, 0xd7, 0x41, 0x08, 0x22, 0xf8, 0xf7, 0xf8, 0xf9, + 0x12, 0x9d, 0x20, 0x46, 0x2b, 0x03, 0x40, 0xf2, 0xd7, 0x41, 0x4f, 0xf4, + 0xe0, 0x42, 0xf8, 0xf7, 0xef, 0xf9, 0x20, 0x46, 0xfb, 0xf7, 0x6a, 0xfa, + 0x00, 0x25, 0x56, 0x46, 0x37, 0xab, 0x5a, 0x5d, 0x20, 0x46, 0x36, 0xf8, + 0x02, 0x1f, 0x01, 0x35, 0xf7, 0xf7, 0xcb, 0xff, 0x12, 0x2d, 0xf5, 0xd1, + 0x4f, 0xf4, 0x00, 0x62, 0x00, 0x23, 0x20, 0x46, 0x40, 0xf2, 0x4c, 0x41, + 0xf8, 0xf7, 0xd8, 0xf9, 0x20, 0x46, 0x00, 0x21, 0xff, 0xf7, 0x24, 0xfc, + 0x20, 0x46, 0x00, 0x21, 0xfa, 0xf7, 0x67, 0xfb, 0x20, 0x46, 0x40, 0xf2, + 0x3b, 0x41, 0x01, 0x22, 0x00, 0x23, 0xf8, 0xf7, 0xc9, 0xf9, 0x00, 0x23, + 0x4f, 0xf4, 0x00, 0x62, 0x20, 0x46, 0x40, 0xf6, 0x38, 0x11, 0xf8, 0xf7, + 0xc1, 0xf9, 0x20, 0x46, 0x00, 0x21, 0xff, 0xf7, 0xe7, 0xfc, 0x20, 0x46, + 0x00, 0x21, 0x1b, 0xaa, 0xfc, 0xf7, 0xd4, 0xfc, 0x20, 0x46, 0x08, 0x49, + 0x0f, 0x22, 0xf8, 0xf7, 0xc5, 0xf9, 0x0a, 0x9d, 0x1d, 0xb9, 0xe3, 0x69, + 0x18, 0x69, 0x37, 0xf0, 0xb3, 0xdd, 0x20, 0x46, 0x10, 0x99, 0xfc, 0xf7, + 0xaf, 0xfe, 0x43, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, 0xde, 0xe8, 0x01, 0x00, + 0x2d, 0xe9, 0xf0, 0x4f, 0x8d, 0xb0, 0xdd, 0xf8, 0x58, 0x90, 0x9b, 0x46, + 0x01, 0x23, 0x80, 0x46, 0x92, 0x46, 0x89, 0xf8, 0x08, 0x30, 0x64, 0x24, + 0x00, 0x25, 0x2e, 0x19, 0x76, 0x10, 0x00, 0x21, 0xb6, 0xb2, 0xdb, 0x23, + 0x89, 0xf8, 0x09, 0x60, 0x01, 0x27, 0x4a, 0x46, 0x03, 0x93, 0x40, 0x46, + 0x0b, 0x46, 0x00, 0x91, 0x01, 0x91, 0x02, 0x91, 0x04, 0x97, 0x05, 0x91, + 0xff, 0xf7, 0xe8, 0xfc, 0x18, 0x23, 0x08, 0x93, 0x3f, 0x23, 0x09, 0x93, + 0x0b, 0xab, 0x06, 0x93, 0x40, 0x46, 0x20, 0x23, 0x06, 0xa9, 0x0a, 0x93, + 0x07, 0x97, 0xfc, 0xf7, 0x19, 0xfa, 0x0b, 0x9b, 0x1a, 0x05, 0x12, 0x15, + 0x52, 0x43, 0x43, 0xf3, 0x0b, 0x33, 0x03, 0xfb, 0x03, 0x23, 0x0f, 0x4a, + 0x18, 0x46, 0xd9, 0x17, 0x82, 0x45, 0x7b, 0xeb, 0x01, 0x03, 0x28, 0xbf, + 0x34, 0x46, 0x38, 0xbf, 0x35, 0x46, 0x4f, 0xf0, 0xff, 0x33, 0x12, 0xeb, + 0x0a, 0x02, 0x43, 0xeb, 0x0b, 0x03, 0x82, 0x42, 0x73, 0xeb, 0x01, 0x07, + 0x03, 0xd2, 0x50, 0x45, 0x71, 0xeb, 0x0b, 0x03, 0x02, 0xd3, 0x63, 0x1b, + 0x01, 0x2b, 0xbc, 0xdc, 0x30, 0x46, 0x0d, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, + 0x30, 0xf8, 0xff, 0xff, 0xf7, 0xb5, 0x04, 0x46, 0xd0, 0xf8, 0xa8, 0x70, + 0x90, 0xf8, 0xda, 0x00, 0x0e, 0x46, 0xf8, 0xf7, 0x0d, 0xfc, 0x40, 0xf6, + 0xb4, 0x12, 0x90, 0x42, 0x05, 0x46, 0xb4, 0xf8, 0xda, 0x30, 0x08, 0xd0, + 0xdb, 0xb2, 0x01, 0x2b, 0x07, 0xd0, 0x00, 0x02, 0xa0, 0xf5, 0xc4, 0x20, + 0xa0, 0xf5, 0x80, 0x60, 0x03, 0xe0, 0x1a, 0x48, 0x01, 0xe0, 0x4f, 0xf4, + 0x52, 0x30, 0x00, 0x22, 0x4f, 0xf4, 0x7a, 0x71, 0xf9, 0xf7, 0x1a, 0xff, + 0xa0, 0xfb, 0x00, 0x23, 0x20, 0x46, 0x00, 0x96, 0xff, 0xf7, 0x82, 0xff, + 0xa0, 0xf1, 0x28, 0x02, 0x92, 0xb2, 0x1d, 0x2a, 0x1b, 0xd9, 0x27, 0x28, + 0x09, 0xd9, 0x40, 0xf6, 0xb4, 0x13, 0x9d, 0x42, 0x08, 0xd0, 0x2d, 0x02, + 0xa5, 0xf5, 0xbe, 0x20, 0xa0, 0xf5, 0x00, 0x70, 0x04, 0xe0, 0x4f, 0xf4, + 0x34, 0x30, 0x01, 0xe0, 0x4f, 0xf4, 0x70, 0x30, 0x00, 0x22, 0x4f, 0xf4, + 0x7a, 0x71, 0xf9, 0xf7, 0xf9, 0xfe, 0xa0, 0xfb, 0x00, 0x23, 0x20, 0x46, + 0x00, 0x96, 0xff, 0xf7, 0x61, 0xff, 0x04, 0x38, 0x87, 0xf8, 0xc2, 0x02, + 0xfe, 0xbd, 0x00, 0xbf, 0x00, 0x8e, 0x03, 0x00, 0x2d, 0xe9, 0xf0, 0x4f, + 0xd0, 0xf8, 0xa8, 0x30, 0x8f, 0xb0, 0x16, 0x46, 0x18, 0x22, 0x93, 0xf8, + 0xf4, 0x73, 0x0a, 0x92, 0x0d, 0xaa, 0x08, 0x92, 0x01, 0xfb, 0x01, 0xfb, + 0x20, 0x22, 0x7b, 0xb2, 0x0c, 0x92, 0x01, 0x22, 0x09, 0x92, 0xb3, 0xf1, + 0xff, 0x3f, 0x08, 0xbf, 0x01, 0x27, 0x3f, 0x22, 0x03, 0x23, 0x05, 0x46, + 0x0b, 0x92, 0x07, 0x93, 0x4f, 0xf0, 0x05, 0x08, 0x06, 0x23, 0x00, 0x24, + 0x03, 0x93, 0x47, 0xf6, 0xff, 0x73, 0x32, 0x46, 0x05, 0x93, 0x28, 0x46, + 0x23, 0x46, 0x21, 0x46, 0x4f, 0xf0, 0x01, 0x09, 0x00, 0x94, 0x01, 0x94, + 0x02, 0x94, 0xcd, 0xf8, 0x10, 0x90, 0xff, 0xf7, 0x31, 0xfc, 0x28, 0x46, + 0x08, 0xa9, 0xfc, 0xf7, 0x6b, 0xf9, 0x0d, 0x9b, 0x1a, 0x05, 0x12, 0x15, + 0x52, 0x43, 0x43, 0xf3, 0x0b, 0x33, 0x03, 0xfb, 0x03, 0x23, 0x5b, 0x45, + 0x72, 0x7a, 0x07, 0xd2, 0x00, 0x2f, 0x4e, 0xd1, 0xc8, 0xf1, 0x00, 0x0a, + 0x5f, 0xfa, 0x8a, 0xfa, 0xcc, 0x46, 0x01, 0xe0, 0xc2, 0x46, 0xa4, 0x46, + 0x4f, 0xfa, 0x8a, 0xf9, 0x1f, 0xfa, 0x89, 0xf9, 0x09, 0xeb, 0x02, 0x04, + 0x06, 0x97, 0xa4, 0xb2, 0x67, 0x46, 0xc9, 0xeb, 0x04, 0x02, 0x92, 0xb2, + 0x3f, 0xb1, 0x5b, 0x45, 0x07, 0xd9, 0xca, 0xeb, 0x02, 0x0a, 0x06, 0x9f, + 0x86, 0xf8, 0x09, 0xa0, 0x27, 0xe0, 0x5b, 0x45, 0x24, 0xd3, 0x23, 0xb2, + 0x7f, 0x2b, 0x21, 0xdc, 0x00, 0x2b, 0x1f, 0xdb, 0x06, 0x23, 0x03, 0x93, + 0x01, 0x23, 0x00, 0x21, 0x04, 0x93, 0x47, 0xf6, 0xff, 0x73, 0x32, 0x46, + 0x74, 0x72, 0x05, 0x93, 0x28, 0x46, 0x0b, 0x46, 0x00, 0x91, 0x01, 0x91, + 0x02, 0x91, 0xff, 0xf7, 0xeb, 0xfb, 0x28, 0x46, 0x08, 0xa9, 0xfc, 0xf7, + 0x25, 0xf9, 0x0d, 0x9b, 0x4c, 0x44, 0x1a, 0x05, 0x12, 0x15, 0x52, 0x43, + 0x43, 0xf3, 0x0b, 0x33, 0x03, 0xfb, 0x03, 0x23, 0xa4, 0xb2, 0xcc, 0xe7, + 0x06, 0x9f, 0x07, 0x9b, 0x4f, 0xfa, 0x88, 0xf8, 0x4f, 0xea, 0x68, 0x08, + 0x01, 0x3b, 0x5f, 0xfa, 0x88, 0xf8, 0x07, 0x93, 0x8c, 0xd1, 0x0f, 0xb0, + 0xbd, 0xe8, 0xf0, 0x8f, 0x2d, 0xe9, 0xf0, 0x4f, 0x8d, 0xb0, 0x03, 0x93, + 0xc3, 0x69, 0xd0, 0xf8, 0xa8, 0x80, 0x04, 0x46, 0x0e, 0x46, 0x98, 0x68, + 0x4f, 0xf4, 0x80, 0x61, 0x17, 0x46, 0xed, 0xf3, 0x13, 0xf7, 0x05, 0x46, + 0x00, 0x28, 0x00, 0xf0, 0x87, 0x80, 0x04, 0xf5, 0x80, 0x53, 0xde, 0x61, + 0x20, 0x46, 0x01, 0x21, 0xff, 0xf7, 0x7a, 0xfb, 0x98, 0xf8, 0x2c, 0x30, + 0x43, 0xb1, 0x20, 0x46, 0x3f, 0x49, 0x06, 0x22, 0xf8, 0xf7, 0x5a, 0xf8, + 0x20, 0x46, 0x00, 0x21, 0xfc, 0xf7, 0x4a, 0xf8, 0xa6, 0xb1, 0x01, 0x23, + 0x3b, 0x4a, 0x86, 0xea, 0xe6, 0x71, 0xa1, 0xeb, 0xe6, 0x71, 0x5a, 0x43, + 0xb2, 0xfb, 0xf1, 0xf9, 0x1f, 0xfa, 0x89, 0xf9, 0x01, 0xfb, 0x09, 0xf1, + 0x01, 0x33, 0x91, 0x42, 0x9b, 0xb2, 0xef, 0xd1, 0xb9, 0xf5, 0x80, 0x7f, + 0x02, 0xd9, 0x56, 0xe0, 0x4f, 0xf0, 0x02, 0x09, 0x4f, 0xf0, 0x24, 0x0b, + 0x0b, 0xfb, 0x06, 0xfb, 0x49, 0xf6, 0x40, 0x43, 0x9b, 0xfb, 0xf3, 0xfb, + 0x4f, 0xea, 0x0b, 0x4b, 0x64, 0x23, 0x4f, 0xf0, 0x00, 0x08, 0x9b, 0xfb, + 0xf3, 0xfb, 0xaa, 0x46, 0x46, 0x46, 0x26, 0xe0, 0x40, 0x46, 0x0a, 0xa9, + 0xf9, 0xf7, 0x90, 0xf8, 0x0b, 0x9a, 0xd8, 0x44, 0x7a, 0x43, 0x03, 0xd4, + 0xd2, 0x13, 0x01, 0x32, 0x52, 0x10, 0x04, 0xe0, 0x52, 0x42, 0xd2, 0x13, + 0x01, 0x32, 0x52, 0x10, 0x52, 0x42, 0x0a, 0x9b, 0x92, 0x05, 0x92, 0x0d, + 0x7b, 0x43, 0x03, 0xd4, 0xdb, 0x13, 0x01, 0x33, 0x5b, 0x10, 0x04, 0xe0, + 0x5b, 0x42, 0xdb, 0x13, 0x01, 0x33, 0x5b, 0x10, 0x5b, 0x42, 0x9b, 0x05, + 0x9b, 0x0d, 0x43, 0xea, 0x82, 0x23, 0x01, 0x36, 0x4a, 0xf8, 0x04, 0x3b, + 0xb6, 0xb2, 0x4e, 0x45, 0xd6, 0xd1, 0x06, 0x22, 0x20, 0x46, 0x13, 0x49, + 0xf7, 0xf7, 0xfe, 0xff, 0x15, 0x23, 0x07, 0x93, 0x00, 0x27, 0x20, 0x23, + 0x20, 0x46, 0x05, 0xa9, 0x09, 0x93, 0x05, 0x95, 0x06, 0x96, 0x08, 0x97, + 0xfc, 0xf7, 0x65, 0xfb, 0x03, 0x9b, 0x20, 0x46, 0x00, 0x93, 0x31, 0x46, + 0x4f, 0xf6, 0xff, 0x72, 0x3b, 0x46, 0xff, 0xf7, 0x55, 0xfa, 0xe3, 0x69, + 0x29, 0x46, 0x98, 0x68, 0x4f, 0xf4, 0x80, 0x62, 0xed, 0xf3, 0x98, 0xf6, + 0x0d, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, 0x00, 0xbf, 0xae, 0xe7, 0x01, 0x00, + 0x00, 0x5a, 0x62, 0x02, 0xfc, 0xe8, 0x01, 0x00, 0x70, 0xb5, 0x00, 0xf5, + 0x80, 0x53, 0xd0, 0xf8, 0xa8, 0x50, 0x00, 0x22, 0xda, 0x61, 0x95, 0xf8, + 0x2c, 0x30, 0x04, 0x46, 0x3b, 0xb1, 0x2b, 0x49, 0x06, 0x22, 0xf7, 0xf7, + 0xc9, 0xff, 0x20, 0x46, 0x01, 0x21, 0xfb, 0xf7, 0xb9, 0xff, 0x20, 0x46, + 0x40, 0xf2, 0x44, 0x61, 0xf7, 0xf7, 0xbd, 0xfd, 0x10, 0xf0, 0x01, 0x03, + 0x09, 0xd0, 0x20, 0x46, 0x00, 0x21, 0xff, 0xf7, 0xf7, 0xf9, 0x02, 0x22, + 0x20, 0x46, 0x40, 0xf2, 0x3f, 0x61, 0x13, 0x46, 0x06, 0xe0, 0x81, 0x07, + 0x06, 0xd5, 0x20, 0x46, 0x40, 0xf2, 0x53, 0x41, 0x4f, 0xf4, 0x00, 0x42, + 0xf7, 0xf7, 0x98, 0xff, 0x20, 0x46, 0x1a, 0x49, 0x09, 0x22, 0xf7, 0xf7, + 0xa5, 0xff, 0x20, 0x46, 0x00, 0x21, 0xff, 0xf7, 0xb9, 0xfa, 0x20, 0x46, + 0xf9, 0xf7, 0x5a, 0xfe, 0x30, 0xb1, 0x20, 0x46, 0xfc, 0xf7, 0x8c, 0xf9, + 0x01, 0x46, 0x20, 0x46, 0xfe, 0xf7, 0xa2, 0xf9, 0x95, 0xf8, 0x47, 0x35, + 0x20, 0x46, 0x9b, 0x02, 0x03, 0xf4, 0x7c, 0x43, 0x40, 0xf2, 0xeb, 0x41, + 0x4f, 0xf4, 0x80, 0x62, 0xf7, 0xf7, 0x78, 0xff, 0xb5, 0xf8, 0x4e, 0x35, + 0x7b, 0xb1, 0x20, 0x46, 0xff, 0x22, 0x40, 0xf6, 0x48, 0x11, 0xf7, 0xf7, + 0x6f, 0xff, 0xb5, 0xf8, 0x50, 0x35, 0x20, 0x46, 0x40, 0xf6, 0x49, 0x11, + 0xff, 0x22, 0xbd, 0xe8, 0x70, 0x40, 0xf7, 0xf7, 0x65, 0xbf, 0x70, 0xbd, + 0x04, 0xea, 0x01, 0x00, 0xd2, 0xed, 0x01, 0x00, 0x70, 0xb5, 0x05, 0x46, + 0x88, 0xb0, 0x0c, 0x46, 0xf8, 0xf7, 0xdf, 0xfd, 0x28, 0x46, 0x34, 0xb9, + 0xff, 0xf7, 0x90, 0xff, 0x28, 0x46, 0x21, 0x46, 0xff, 0xf7, 0x7c, 0xfa, + 0x20, 0xe0, 0x21, 0x46, 0x01, 0x22, 0xf9, 0xf7, 0x1f, 0xf9, 0x04, 0x46, + 0xc8, 0xb9, 0x28, 0x46, 0x01, 0x21, 0xff, 0xf7, 0x71, 0xfa, 0x0d, 0x4b, + 0x40, 0x26, 0x03, 0x93, 0x15, 0x23, 0x05, 0x93, 0x28, 0x46, 0x10, 0x23, + 0x03, 0xa9, 0x07, 0x93, 0x04, 0x96, 0x06, 0x94, 0xfc, 0xf7, 0xbf, 0xfa, + 0x28, 0x46, 0x31, 0x46, 0x4f, 0xf6, 0xff, 0x72, 0x23, 0x46, 0x00, 0x94, + 0xff, 0xf7, 0xb0, 0xf9, 0x00, 0xe0, 0x01, 0x24, 0x20, 0x46, 0x08, 0xb0, + 0x70, 0xbd, 0x00, 0xbf, 0x8e, 0x01, 0x02, 0x00, 0x2d, 0xe9, 0xf8, 0x43, + 0x0f, 0x01, 0x04, 0x46, 0xd0, 0xf8, 0xa8, 0x90, 0xfd, 0xf7, 0xab, 0xfb, + 0x40, 0xf2, 0xd7, 0x41, 0x06, 0x46, 0x05, 0x46, 0x20, 0x46, 0xf7, 0xf7, + 0x2a, 0xfd, 0x99, 0xf9, 0x25, 0x35, 0x80, 0x46, 0x58, 0x1c, 0x0e, 0xd0, + 0x00, 0x2b, 0xb8, 0xbf, 0x03, 0x33, 0x40, 0x22, 0xb7, 0xeb, 0xa3, 0x0f, + 0x20, 0x46, 0x40, 0xf2, 0xd7, 0x41, 0x01, 0xda, 0x00, 0x23, 0x00, 0xe0, + 0x13, 0x46, 0xf7, 0xf7, 0x07, 0xff, 0x04, 0xf5, 0x80, 0x53, 0xdb, 0x69, + 0x20, 0x46, 0x4b, 0xb1, 0xff, 0xf7, 0x3a, 0xff, 0x05, 0x20, 0xed, 0xf3, + 0xf9, 0xf2, 0x20, 0x46, 0x1b, 0x49, 0x70, 0x22, 0x00, 0x23, 0x01, 0xe0, + 0x19, 0x49, 0x70, 0x22, 0xff, 0xf7, 0x8a, 0xfe, 0x20, 0x46, 0x31, 0x46, + 0xfe, 0xf7, 0xb8, 0xfb, 0x4f, 0xf0, 0x0b, 0x09, 0x01, 0x21, 0x20, 0x46, + 0xfd, 0xf7, 0x0e, 0xfe, 0xc6, 0x1b, 0x00, 0x2e, 0x33, 0x46, 0xb8, 0xbf, + 0xf3, 0x1c, 0x05, 0xeb, 0xa3, 0x05, 0x01, 0x3d, 0x7f, 0x2d, 0xa8, 0xbf, + 0x7f, 0x25, 0x25, 0xea, 0xe5, 0x75, 0x20, 0x46, 0x29, 0x46, 0x04, 0x36, + 0xfe, 0xf7, 0xa0, 0xfb, 0x08, 0x2e, 0x02, 0xd9, 0xb9, 0xf1, 0x01, 0x09, + 0xe4, 0xd1, 0x20, 0x46, 0xff, 0xf7, 0x0a, 0xff, 0x20, 0x46, 0x40, 0xf2, + 0xd7, 0x41, 0x42, 0x46, 0xf7, 0xf7, 0xe4, 0xfc, 0x20, 0x46, 0xfd, 0xf7, + 0x50, 0xfb, 0xbd, 0xe8, 0xf8, 0x83, 0x00, 0xbf, 0x00, 0x09, 0x3d, 0x00, + 0x70, 0xb5, 0xb1, 0xf1, 0xff, 0x3f, 0x04, 0x46, 0x15, 0x46, 0x9d, 0xf9, + 0x10, 0x60, 0x01, 0xd0, 0x8b, 0x19, 0x0c, 0xe0, 0x22, 0xb9, 0x90, 0xf8, + 0x29, 0x16, 0xff, 0xf7, 0x89, 0xff, 0x01, 0xe0, 0x01, 0x32, 0x04, 0xd0, + 0x20, 0x46, 0x29, 0x46, 0xff, 0xf7, 0x82, 0xff, 0x83, 0x19, 0x20, 0x46, + 0x19, 0x46, 0xbd, 0xe8, 0x70, 0x40, 0xfe, 0xf7, 0x6d, 0xbb, 0x2d, 0xe9, + 0xf0, 0x43, 0x91, 0xb0, 0x05, 0x46, 0xd0, 0xf8, 0xa8, 0x40, 0xfd, 0xf7, + 0x26, 0xfb, 0x1c, 0x23, 0x8d, 0xf8, 0x39, 0x30, 0x01, 0x23, 0x8d, 0xf8, + 0x38, 0x30, 0xb5, 0xf8, 0xda, 0x30, 0x5f, 0xfa, 0x80, 0xf8, 0x03, 0xf4, + 0x70, 0x42, 0xb2, 0xf5, 0x80, 0x5f, 0x08, 0xd1, 0xda, 0xb2, 0x40, 0x2a, + 0x01, 0xd8, 0x1b, 0x22, 0x00, 0xe0, 0x2d, 0x22, 0x8d, 0xf8, 0x39, 0x20, + 0x32, 0xe0, 0xb2, 0xf5, 0x00, 0x5f, 0x2f, 0xd1, 0xb4, 0xf8, 0x2a, 0x15, + 0x0b, 0xb2, 0x01, 0x33, 0x04, 0xd0, 0x4f, 0xf6, 0xff, 0x73, 0x00, 0x29, + 0x08, 0xbf, 0x19, 0x46, 0xb4, 0xf8, 0xf6, 0x33, 0x1a, 0xb2, 0x01, 0x32, + 0x05, 0xd0, 0x4f, 0xf6, 0xff, 0x72, 0x00, 0x2b, 0x08, 0xbf, 0x13, 0x46, + 0x01, 0xe0, 0x4f, 0xf4, 0x91, 0x73, 0xb4, 0xf8, 0x2c, 0x75, 0x94, 0xf8, + 0xf0, 0x23, 0x38, 0xb2, 0x01, 0x30, 0x04, 0xd0, 0x4f, 0xf6, 0xff, 0x70, + 0x00, 0x2f, 0x08, 0xbf, 0x07, 0x46, 0xb4, 0xf8, 0xf8, 0x63, 0x30, 0xb2, + 0x01, 0x30, 0x04, 0xd0, 0x4f, 0xf6, 0xff, 0x70, 0x00, 0x2e, 0x08, 0xbf, + 0x06, 0x46, 0x94, 0xf8, 0xf1, 0x93, 0x93, 0xe0, 0xdb, 0xb2, 0x40, 0x2b, + 0x2f, 0xd8, 0xb4, 0xf8, 0x2e, 0x15, 0x0b, 0xb2, 0x01, 0x33, 0x04, 0xd0, + 0x4f, 0xf6, 0xff, 0x73, 0x00, 0x29, 0x08, 0xbf, 0x19, 0x46, 0xb4, 0xf8, + 0xfa, 0x33, 0x1a, 0xb2, 0x01, 0x32, 0x05, 0xd0, 0x4f, 0xf6, 0xff, 0x72, + 0x00, 0x2b, 0x08, 0xbf, 0x13, 0x46, 0x01, 0xe0, 0x4f, 0xf4, 0x91, 0x73, + 0xb4, 0xf8, 0x30, 0x75, 0x94, 0xf8, 0x59, 0x25, 0x38, 0xb2, 0x01, 0x30, + 0x04, 0xd0, 0x4f, 0xf6, 0xff, 0x70, 0x00, 0x2f, 0x08, 0xbf, 0x07, 0x46, + 0xb4, 0xf8, 0x00, 0x64, 0x30, 0xb2, 0x01, 0x30, 0x04, 0xd0, 0x4f, 0xf6, + 0xff, 0x70, 0x00, 0x2e, 0x08, 0xbf, 0x06, 0x46, 0x94, 0xf8, 0x5b, 0x95, + 0x60, 0xe0, 0x8c, 0x2b, 0x2f, 0xd8, 0xb4, 0xf8, 0x32, 0x15, 0x0b, 0xb2, + 0x01, 0x33, 0x04, 0xd0, 0x4f, 0xf6, 0xff, 0x73, 0x00, 0x29, 0x08, 0xbf, + 0x19, 0x46, 0xb4, 0xf8, 0xfc, 0x33, 0x1a, 0xb2, 0x01, 0x32, 0x05, 0xd0, + 0x4f, 0xf6, 0xff, 0x72, 0x00, 0x2b, 0x08, 0xbf, 0x13, 0x46, 0x01, 0xe0, + 0x4f, 0xf4, 0x91, 0x73, 0xb4, 0xf8, 0x34, 0x75, 0x94, 0xf8, 0xf2, 0x23, + 0x38, 0xb2, 0x01, 0x30, 0x04, 0xd0, 0x4f, 0xf6, 0xff, 0x70, 0x00, 0x2f, + 0x08, 0xbf, 0x07, 0x46, 0xb4, 0xf8, 0x02, 0x64, 0x30, 0xb2, 0x01, 0x30, + 0x04, 0xd0, 0x4f, 0xf6, 0xff, 0x70, 0x00, 0x2e, 0x08, 0xbf, 0x06, 0x46, + 0x94, 0xf8, 0xf3, 0x93, 0x2e, 0xe0, 0xb4, 0xf8, 0x36, 0x15, 0x0b, 0xb2, + 0x01, 0x33, 0x04, 0xd0, 0x4f, 0xf6, 0xff, 0x73, 0x00, 0x29, 0x08, 0xbf, + 0x19, 0x46, 0xb4, 0xf8, 0xfe, 0x33, 0x1a, 0xb2, 0x01, 0x32, 0x05, 0xd0, + 0x4f, 0xf6, 0xff, 0x72, 0x00, 0x2b, 0x08, 0xbf, 0x13, 0x46, 0x01, 0xe0, + 0x4f, 0xf4, 0x91, 0x73, 0xb4, 0xf8, 0x38, 0x75, 0x94, 0xf8, 0x5a, 0x25, + 0x38, 0xb2, 0x01, 0x30, 0x04, 0xd0, 0x4f, 0xf6, 0xff, 0x70, 0x00, 0x2f, + 0x08, 0xbf, 0x07, 0x46, 0xb4, 0xf8, 0x04, 0x64, 0x30, 0xb2, 0x01, 0x30, + 0x04, 0xd0, 0x4f, 0xf6, 0xff, 0x70, 0x00, 0x2e, 0x08, 0xbf, 0x06, 0x46, + 0x94, 0xf8, 0x5c, 0x95, 0x09, 0xb2, 0x48, 0x1c, 0x05, 0xd0, 0x28, 0x46, + 0xff, 0xf7, 0x8e, 0xfe, 0x84, 0xf8, 0x07, 0x04, 0x14, 0xe0, 0x19, 0xb2, + 0x4b, 0x1c, 0x06, 0xd0, 0x28, 0x46, 0x0c, 0xaa, 0xff, 0xf7, 0xb0, 0xfc, + 0x9d, 0xf8, 0x39, 0x30, 0x08, 0xe0, 0x53, 0xb2, 0x01, 0x33, 0x02, 0xd0, + 0x84, 0xf8, 0x07, 0x24, 0x04, 0xe0, 0x9d, 0xf8, 0x39, 0x30, 0x0b, 0xb1, + 0x84, 0xf8, 0x07, 0x34, 0x39, 0xb2, 0x48, 0x1c, 0x05, 0xd0, 0x28, 0x46, + 0xff, 0xf7, 0x70, 0xfe, 0x84, 0xf8, 0x08, 0x04, 0x11, 0xe0, 0x31, 0xb2, + 0x4a, 0x1c, 0x08, 0xd0, 0x28, 0x46, 0x0c, 0xaa, 0xff, 0xf7, 0x92, 0xfc, + 0x9d, 0xf8, 0x39, 0x30, 0x84, 0xf8, 0x08, 0x34, 0x05, 0xe0, 0x4f, 0xfa, + 0x89, 0xf3, 0x01, 0x33, 0x18, 0xbf, 0x84, 0xf8, 0x08, 0x94, 0x94, 0xf9, + 0xef, 0x33, 0x01, 0x33, 0x02, 0xd0, 0xff, 0x23, 0x84, 0xf8, 0x08, 0x34, + 0x94, 0xf8, 0x08, 0x24, 0x51, 0xb2, 0x4b, 0x1c, 0x74, 0xd0, 0x94, 0xf8, + 0x07, 0x34, 0x58, 0xb2, 0x81, 0x42, 0xd8, 0xbf, 0x84, 0xf8, 0x08, 0x34, + 0x94, 0xf8, 0x08, 0x34, 0xd8, 0xbf, 0x84, 0xf8, 0x07, 0x24, 0x8d, 0xf8, + 0x39, 0x30, 0x00, 0x26, 0xdb, 0x23, 0x03, 0x93, 0x01, 0x27, 0x33, 0x46, + 0x28, 0x46, 0x31, 0x46, 0x0c, 0xaa, 0x00, 0x96, 0x01, 0x96, 0x02, 0x96, + 0x04, 0x97, 0x05, 0x96, 0xff, 0xf7, 0xc0, 0xf8, 0x18, 0x23, 0x09, 0x93, + 0x20, 0x23, 0x0b, 0x93, 0x08, 0x97, 0x0f, 0xab, 0x28, 0x46, 0x07, 0xa9, + 0x07, 0x93, 0x0a, 0x96, 0xfb, 0xf7, 0xf2, 0xfd, 0x06, 0xf1, 0x40, 0x03, + 0x28, 0x46, 0x07, 0xa9, 0x01, 0x36, 0x0a, 0x93, 0xfc, 0xf7, 0xcd, 0xf8, + 0x40, 0x2e, 0xee, 0xd1, 0x94, 0xf9, 0x07, 0x24, 0x94, 0xf9, 0x08, 0x34, + 0xd3, 0x18, 0x03, 0xeb, 0xd3, 0x73, 0x5b, 0x10, 0xa4, 0xf8, 0x68, 0x35, + 0xb5, 0xf8, 0xda, 0x30, 0x03, 0xf4, 0x70, 0x42, 0xb2, 0xf5, 0x00, 0x5f, + 0x05, 0xd1, 0xb4, 0xf8, 0x5e, 0x25, 0x12, 0xb1, 0xa4, 0xf8, 0x68, 0x25, + 0x10, 0xe0, 0xdb, 0xb2, 0x40, 0x2b, 0x03, 0xd8, 0xb4, 0xf8, 0x60, 0x35, + 0x13, 0xb1, 0x07, 0xe0, 0x8c, 0x2b, 0x02, 0xd8, 0xb4, 0xf8, 0x62, 0x35, + 0x13, 0xb9, 0xb4, 0xf8, 0x64, 0x35, 0x0b, 0xb1, 0xa4, 0xf8, 0x68, 0x35, + 0x28, 0x46, 0x40, 0xf2, 0x24, 0x51, 0x4f, 0xf4, 0x00, 0x42, 0x00, 0x23, + 0xf7, 0xf7, 0x16, 0xfd, 0x94, 0xf9, 0x66, 0x35, 0xb4, 0xf8, 0x68, 0x25, + 0x01, 0x33, 0x92, 0xfb, 0xf3, 0xf3, 0x9b, 0xb2, 0x28, 0x46, 0x40, 0xf2, + 0x25, 0x51, 0xff, 0x22, 0xf7, 0xf7, 0x08, 0xfd, 0x02, 0x23, 0x84, 0xf8, + 0x67, 0x35, 0x29, 0xe0, 0x01, 0x23, 0x84, 0xf8, 0x67, 0x35, 0x28, 0x46, + 0x40, 0xf2, 0x25, 0x51, 0xff, 0x22, 0x7f, 0x23, 0xf7, 0xf7, 0xfa, 0xfc, + 0x28, 0x46, 0x40, 0xf2, 0x25, 0x51, 0x4f, 0xf4, 0x80, 0x72, 0x00, 0x23, + 0xf7, 0xf7, 0xf2, 0xfc, 0x28, 0x46, 0x40, 0xf2, 0x25, 0x51, 0x4f, 0xf4, + 0x00, 0x72, 0x00, 0x23, 0xf7, 0xf7, 0xea, 0xfc, 0x28, 0x46, 0x40, 0xf2, + 0x25, 0x51, 0x4f, 0xf4, 0x80, 0x62, 0x00, 0x23, 0xf7, 0xf7, 0xe2, 0xfc, + 0x28, 0x46, 0x40, 0xf2, 0x25, 0x51, 0x4f, 0xf4, 0x00, 0x62, 0x00, 0x23, + 0xf7, 0xf7, 0xda, 0xfc, 0x00, 0x23, 0xa4, 0xf8, 0x6a, 0x35, 0x28, 0x46, + 0x40, 0xf2, 0x25, 0x51, 0x94, 0xf9, 0x66, 0x65, 0xf7, 0xf7, 0xdf, 0xfa, + 0x01, 0x36, 0xb6, 0xb2, 0xc0, 0xb2, 0x46, 0x43, 0x94, 0xf9, 0x66, 0x35, + 0xa4, 0xf8, 0x68, 0x65, 0x13, 0xb1, 0x28, 0x46, 0xfc, 0xf7, 0x3e, 0xfe, + 0x94, 0xf8, 0xef, 0x33, 0x28, 0x46, 0x5a, 0xb2, 0x01, 0x32, 0x08, 0xbf, + 0x94, 0xf8, 0x07, 0x34, 0x00, 0x21, 0x8d, 0xf8, 0x39, 0x30, 0xdb, 0x23, + 0x03, 0x93, 0x01, 0x23, 0x0c, 0xaa, 0x04, 0x93, 0x0b, 0x46, 0x00, 0x91, + 0x01, 0x91, 0x02, 0x91, 0x05, 0x91, 0xff, 0xf7, 0x11, 0xf8, 0x28, 0x46, + 0x41, 0x46, 0xfe, 0xf7, 0x71, 0xf9, 0x28, 0x46, 0x40, 0xf2, 0x71, 0x61, + 0xf7, 0xf7, 0xb3, 0xfa, 0xb4, 0xf8, 0x6a, 0x25, 0x40, 0xf2, 0x71, 0x61, + 0xa0, 0xeb, 0xc2, 0x02, 0x92, 0xb2, 0x28, 0x46, 0xf7, 0xf7, 0xb4, 0xfa, + 0x28, 0x46, 0xfb, 0xf7, 0xb8, 0xfd, 0x11, 0xb0, 0xbd, 0xe8, 0xf0, 0x83, + 0x2d, 0xe9, 0xf0, 0x4f, 0xc3, 0xb0, 0x05, 0x92, 0x04, 0x46, 0x16, 0x22, + 0x0f, 0x46, 0x13, 0xa8, 0x00, 0x21, 0x11, 0x93, 0xe8, 0xf3, 0xf8, 0xf4, + 0x65, 0x4b, 0x1f, 0xaa, 0x03, 0xf1, 0x08, 0x06, 0x18, 0x68, 0x59, 0x68, + 0x15, 0x46, 0x03, 0xc5, 0x08, 0x33, 0xb3, 0x42, 0x2a, 0x46, 0xf7, 0xd1, + 0x18, 0x68, 0x9b, 0x88, 0x28, 0x60, 0xab, 0x80, 0x5d, 0x4b, 0x23, 0xaa, + 0x03, 0xf1, 0x08, 0x06, 0x18, 0x68, 0x59, 0x68, 0x15, 0x46, 0x03, 0xc5, + 0x08, 0x33, 0xb3, 0x42, 0x2a, 0x46, 0xf7, 0xd1, 0x18, 0x68, 0x9b, 0x88, + 0x28, 0x60, 0xab, 0x80, 0x56, 0x4d, 0x48, 0xf2, 0x67, 0x01, 0x28, 0x68, + 0xad, 0xf8, 0xf0, 0x10, 0x69, 0x68, 0x48, 0xf2, 0x45, 0x22, 0x36, 0xab, + 0xad, 0xf8, 0xf4, 0x20, 0x03, 0xc3, 0x27, 0xaa, 0x05, 0xf1, 0x08, 0x03, + 0x10, 0x35, 0x18, 0x68, 0x59, 0x68, 0x16, 0x46, 0x03, 0xc6, 0x08, 0x33, + 0xab, 0x42, 0x32, 0x46, 0xf7, 0xd1, 0x18, 0x68, 0x4a, 0x4d, 0x9b, 0x88, + 0x30, 0x60, 0x69, 0x68, 0x28, 0x68, 0xb3, 0x80, 0x38, 0xab, 0x03, 0xc3, + 0x2b, 0xaa, 0xa5, 0xf1, 0x0e, 0x03, 0x06, 0x3d, 0x18, 0x68, 0x59, 0x68, + 0x16, 0x46, 0x03, 0xc6, 0x08, 0x33, 0xab, 0x42, 0x32, 0x46, 0xf7, 0xd1, + 0x18, 0x68, 0x9b, 0x88, 0x30, 0x60, 0xb3, 0x80, 0x47, 0xf6, 0x97, 0x33, + 0xad, 0xf8, 0xf8, 0x30, 0xad, 0xf8, 0xfc, 0x30, 0xe3, 0x69, 0x00, 0x26, + 0x98, 0x68, 0x30, 0x21, 0x3a, 0x96, 0x3b, 0x96, 0xd4, 0xf8, 0xa8, 0x50, + 0xed, 0xf3, 0xde, 0xf2, 0x06, 0x90, 0x00, 0x28, 0x00, 0xf0, 0x7d, 0x82, + 0x40, 0xf2, 0xdb, 0x61, 0x20, 0x46, 0xf7, 0xf7, 0x2c, 0xfa, 0x40, 0xf2, + 0xda, 0x61, 0x0c, 0x90, 0x20, 0x46, 0xf7, 0xf7, 0x26, 0xfa, 0x30, 0x49, + 0x0d, 0x90, 0x04, 0x22, 0x20, 0x46, 0xf7, 0xf7, 0x23, 0xfc, 0x05, 0x99, + 0x07, 0x29, 0x59, 0xd8, 0xdf, 0xe8, 0x01, 0xf0, 0x0b, 0x04, 0x58, 0x58, + 0x58, 0x17, 0x27, 0x1f, 0x07, 0x26, 0x0d, 0xf1, 0x8c, 0x0a, 0x13, 0xaa, + 0x0d, 0xf1, 0xac, 0x08, 0x51, 0xe0, 0x00, 0x21, 0x0a, 0x46, 0x20, 0x46, + 0x0b, 0x46, 0x00, 0x96, 0x0d, 0xf1, 0x7c, 0x0a, 0xfa, 0xf7, 0x2c, 0xf9, + 0x07, 0x26, 0x13, 0xaa, 0x43, 0xe0, 0x05, 0xf1, 0x82, 0x02, 0x01, 0x26, + 0x0d, 0xf1, 0xf0, 0x0a, 0x0d, 0xf1, 0xf8, 0x08, 0x3d, 0xe0, 0x05, 0xf1, + 0x82, 0x02, 0x01, 0x26, 0x0d, 0xf1, 0xf4, 0x0a, 0x0d, 0xf1, 0xfc, 0x08, + 0x35, 0xe0, 0x41, 0xab, 0x03, 0x33, 0x41, 0xaa, 0x00, 0x93, 0x41, 0xa9, + 0x01, 0x32, 0x0d, 0xf5, 0x83, 0x73, 0x20, 0x46, 0xf9, 0xf7, 0xf0, 0xff, + 0x9d, 0xf8, 0x04, 0x21, 0x9d, 0xf8, 0x05, 0x31, 0x00, 0x21, 0x43, 0xea, + 0x02, 0x23, 0xad, 0xf8, 0x5a, 0x30, 0x00, 0x23, 0x9d, 0xf8, 0x06, 0x21, + 0xad, 0xf8, 0x5c, 0x30, 0x9d, 0xf8, 0x07, 0x31, 0xad, 0xf8, 0x60, 0x10, + 0x43, 0xea, 0x02, 0x23, 0xad, 0xf8, 0x5e, 0x30, 0x04, 0x26, 0x0d, 0xf1, + 0xd8, 0x0a, 0x13, 0xaa, 0x0d, 0xf1, 0xe0, 0x08, 0x0d, 0xe0, 0x00, 0xbf, + 0xa8, 0xb8, 0x01, 0x00, 0xb6, 0xb8, 0x01, 0x00, 0xcc, 0xb8, 0x01, 0x00, + 0x78, 0xee, 0x01, 0x00, 0x00, 0x26, 0xb2, 0x46, 0x32, 0x46, 0x0d, 0xf1, + 0x9c, 0x08, 0x4f, 0xf0, 0x40, 0x0e, 0x10, 0x23, 0xdf, 0xf8, 0x20, 0xb2, + 0x8d, 0xe8, 0x08, 0x40, 0x00, 0x21, 0x0b, 0x23, 0x20, 0x46, 0xcd, 0xf8, + 0x08, 0xb0, 0xf7, 0xf7, 0x27, 0xfd, 0x05, 0x22, 0x7b, 0x49, 0x20, 0x46, + 0xf7, 0xf7, 0xae, 0xfb, 0x20, 0x46, 0xf9, 0xf7, 0x40, 0xfb, 0x4f, 0xf4, + 0x80, 0x52, 0x13, 0x46, 0x0e, 0x90, 0x40, 0xf2, 0xa4, 0x41, 0x20, 0x46, + 0xf7, 0xf7, 0x90, 0xfb, 0x00, 0x21, 0x20, 0x46, 0xfd, 0xf7, 0x96, 0xfc, + 0x40, 0xf2, 0xdb, 0x41, 0x20, 0x46, 0xf7, 0xf7, 0x96, 0xf9, 0x70, 0x49, + 0x06, 0x22, 0x0f, 0x90, 0x20, 0x46, 0xf7, 0xf7, 0x93, 0xfb, 0xb4, 0xf8, + 0xda, 0x30, 0x20, 0x46, 0x03, 0xf4, 0x70, 0x43, 0xb3, 0xf5, 0x00, 0x5f, + 0x0c, 0xbf, 0x6a, 0x49, 0x6a, 0x49, 0x12, 0x22, 0xf7, 0xf7, 0x86, 0xfb, + 0x40, 0xf2, 0xd7, 0x41, 0x20, 0x46, 0xf7, 0xf7, 0x7e, 0xf9, 0x06, 0x99, + 0x10, 0x90, 0x20, 0x46, 0xfb, 0xf7, 0xfa, 0xf9, 0x20, 0x46, 0x40, 0xf2, + 0x3b, 0x41, 0xf7, 0xf7, 0x74, 0xf9, 0xc0, 0xf3, 0x80, 0x10, 0x07, 0x90, + 0x18, 0xb1, 0x20, 0x46, 0x3a, 0xa9, 0xf9, 0xf7, 0x0c, 0xfb, 0x57, 0xb9, + 0x07, 0x9a, 0x1a, 0xb9, 0x20, 0x46, 0x29, 0x8e, 0xfe, 0xf7, 0x1e, 0xf8, + 0x20, 0x46, 0x34, 0xa9, 0xf9, 0xf7, 0x01, 0xfb, 0x34, 0xaf, 0xb7, 0xf8, + 0x02, 0x90, 0x3b, 0x88, 0x4f, 0xea, 0x09, 0x19, 0x49, 0xea, 0x03, 0x29, + 0xbb, 0x88, 0x38, 0x68, 0x79, 0x68, 0x49, 0xea, 0x03, 0x09, 0x32, 0xab, + 0x03, 0xc3, 0x1f, 0xfa, 0x89, 0xf9, 0x2f, 0xa8, 0x00, 0x21, 0x0a, 0x22, + 0xe8, 0xf3, 0xac, 0xf3, 0xb9, 0xf1, 0x00, 0x0f, 0x0a, 0xd1, 0x2f, 0xa8, + 0x4b, 0x49, 0x0a, 0x22, 0xad, 0xf8, 0xc8, 0x90, 0xad, 0xf8, 0xca, 0x90, + 0xad, 0xf8, 0xcc, 0x90, 0xe8, 0xf3, 0x3a, 0xf3, 0x20, 0x46, 0x32, 0xa9, + 0xf9, 0xf7, 0x85, 0xfc, 0x00, 0x27, 0x04, 0x22, 0x20, 0x46, 0x44, 0x49, + 0xf7, 0xf7, 0x36, 0xfb, 0x4f, 0xf0, 0x10, 0x09, 0x39, 0x46, 0x0a, 0x23, + 0x20, 0x46, 0x41, 0x4a, 0x01, 0x97, 0xcd, 0xf8, 0x00, 0x90, 0xcd, 0xf8, + 0x08, 0xb0, 0xf7, 0xf7, 0x9d, 0xfc, 0x20, 0x23, 0x39, 0x46, 0x01, 0x93, + 0x20, 0x46, 0x0a, 0x23, 0x3a, 0x4a, 0xcd, 0xf8, 0x00, 0x90, 0xcd, 0xf8, + 0x08, 0xb0, 0xf7, 0xf7, 0x91, 0xfc, 0x20, 0x46, 0x40, 0xf2, 0x53, 0x41, + 0x40, 0xf2, 0xa4, 0x72, 0xf7, 0xf7, 0x1e, 0xf9, 0xb5, 0xf8, 0xc8, 0x73, + 0x40, 0xf6, 0xa6, 0x63, 0x00, 0x2f, 0x08, 0xbf, 0x1f, 0x46, 0x05, 0x9b, + 0x05, 0x2b, 0x01, 0xd1, 0x7f, 0x42, 0xbf, 0xb2, 0x04, 0xf5, 0x80, 0x53, + 0xdb, 0x69, 0x2b, 0xb1, 0x20, 0x46, 0xff, 0xf7, 0x2b, 0xfb, 0x05, 0x20, + 0xec, 0xf3, 0xea, 0xf6, 0x3f, 0xb2, 0x4f, 0xf4, 0x7a, 0x71, 0x01, 0x23, + 0x79, 0x43, 0x58, 0x22, 0x20, 0x46, 0xff, 0xf7, 0x7b, 0xfa, 0x40, 0xf2, + 0xda, 0x61, 0x4f, 0xf6, 0xff, 0x72, 0x20, 0x46, 0xf7, 0xf7, 0xf8, 0xf8, + 0xb4, 0xf8, 0xda, 0x30, 0x20, 0x46, 0x03, 0xf4, 0x70, 0x43, 0xb3, 0xf5, + 0x00, 0x5f, 0x0b, 0xbf, 0x95, 0xf8, 0x95, 0x15, 0x95, 0xf8, 0x96, 0x25, + 0x05, 0x91, 0x05, 0x92, 0xfc, 0xf7, 0x57, 0xff, 0xff, 0x23, 0xc0, 0xb2, + 0xcd, 0xf8, 0x24, 0x80, 0xb1, 0x46, 0x0a, 0x90, 0x2e, 0x46, 0x08, 0x93, + 0x4f, 0xf0, 0x00, 0x08, 0x55, 0x46, 0xa0, 0xe0, 0x00, 0x21, 0xad, 0xf8, + 0x00, 0x11, 0x35, 0xf8, 0x02, 0x7b, 0x05, 0x9a, 0x07, 0xf4, 0x70, 0x67, + 0x3f, 0x0a, 0x2a, 0xb3, 0x04, 0x2f, 0x03, 0xd0, 0x08, 0x9b, 0x04, 0x2b, + 0x1e, 0xd1, 0x19, 0xe0, 0x0a, 0x9b, 0x05, 0x9a, 0x99, 0x18, 0xc9, 0xb2, + 0x4b, 0xb2, 0x31, 0xea, 0x23, 0x01, 0x28, 0xbf, 0x7f, 0x21, 0x10, 0xe0, + 0x56, 0xef, 0x01, 0x00, 0xaa, 0xe6, 0x01, 0x00, 0xb6, 0xe6, 0x01, 0x00, + 0x3a, 0xed, 0x01, 0x00, 0xd2, 0xeb, 0x01, 0x00, 0x5e, 0xed, 0x01, 0x00, + 0xec, 0xe6, 0x01, 0x00, 0x6b, 0x56, 0x01, 0x00, 0x0a, 0x99, 0x20, 0x46, + 0xfb, 0xf7, 0xad, 0xff, 0xf9, 0xb2, 0x08, 0x91, 0x09, 0x9b, 0x42, 0xa9, + 0x33, 0xf8, 0x02, 0x2b, 0x09, 0x93, 0x01, 0xeb, 0x47, 0x03, 0x33, 0xf8, + 0x4c, 0x3c, 0x1b, 0xb1, 0xd2, 0xb2, 0x42, 0xea, 0x03, 0x22, 0x92, 0xb2, + 0x03, 0x3f, 0xbf, 0xb2, 0x20, 0x46, 0x40, 0xf2, 0x52, 0x41, 0xf7, 0xf7, + 0x97, 0xf8, 0x01, 0x2f, 0x0b, 0x97, 0x15, 0xd8, 0x6b, 0x4b, 0x10, 0x27, + 0x4f, 0xf0, 0x45, 0x0a, 0x02, 0x93, 0x20, 0x46, 0x00, 0x21, 0x0d, 0xf1, + 0xfe, 0x02, 0x01, 0x23, 0x8d, 0xe8, 0x80, 0x04, 0xf7, 0xf7, 0xe5, 0xfb, + 0x20, 0x46, 0x00, 0x21, 0x40, 0xaa, 0x01, 0x23, 0x8d, 0xe8, 0x80, 0x0c, + 0xf7, 0xf7, 0xea, 0xfb, 0x20, 0x46, 0x40, 0xf2, 0x51, 0x41, 0x35, 0xf8, + 0x02, 0x2c, 0xf7, 0xf7, 0x77, 0xf8, 0x20, 0x46, 0xfa, 0xf7, 0xbb, 0xfa, + 0x00, 0x28, 0x7b, 0xd0, 0x60, 0x23, 0xdf, 0xf8, 0x68, 0xa1, 0x10, 0x27, + 0x00, 0x21, 0x01, 0x93, 0x20, 0x46, 0x0b, 0x23, 0x19, 0xaa, 0x00, 0x97, + 0xcd, 0xf8, 0x08, 0xa0, 0xf7, 0xf7, 0xc3, 0xfb, 0x40, 0x23, 0x01, 0x93, + 0x00, 0x21, 0x19, 0xaa, 0x0b, 0x23, 0x20, 0x46, 0x00, 0x97, 0xcd, 0xf8, + 0x08, 0xb0, 0xf7, 0xf7, 0xc5, 0xfb, 0x0b, 0x9a, 0x01, 0x2a, 0x0b, 0xd8, + 0x45, 0x23, 0x01, 0x93, 0x4c, 0x4b, 0x20, 0x46, 0x02, 0x93, 0x00, 0x21, + 0x0d, 0xf1, 0xfe, 0x02, 0x01, 0x23, 0x00, 0x97, 0xf7, 0xf7, 0xb6, 0xfb, + 0x10, 0x23, 0x60, 0x27, 0x8d, 0xe8, 0x88, 0x00, 0x20, 0x46, 0x00, 0x21, + 0x06, 0xf1, 0x82, 0x02, 0x0b, 0x23, 0xcd, 0xf8, 0x08, 0xa0, 0xf7, 0xf7, + 0x9c, 0xfb, 0x08, 0xf1, 0x01, 0x08, 0xc8, 0x45, 0x7f, 0xf4, 0x5c, 0xaf, + 0x60, 0x23, 0x01, 0x93, 0x3c, 0x4b, 0x06, 0xf1, 0x82, 0x07, 0x35, 0x46, + 0x02, 0x93, 0x10, 0x26, 0x20, 0x46, 0x00, 0x21, 0x3a, 0x46, 0x0b, 0x23, + 0x00, 0x96, 0xf7, 0xf7, 0x88, 0xfb, 0x01, 0x23, 0xa5, 0xf8, 0x98, 0x30, + 0x50, 0x23, 0x01, 0x93, 0x20, 0x46, 0x00, 0x21, 0x3a, 0x46, 0x04, 0x23, + 0x00, 0x96, 0xcd, 0xf8, 0x08, 0xb0, 0xf7, 0xf7, 0x87, 0xfb, 0x55, 0x23, + 0x01, 0x93, 0x20, 0x46, 0x00, 0x21, 0x05, 0xf1, 0x8c, 0x02, 0x02, 0x23, + 0x00, 0x96, 0xcd, 0xf8, 0x08, 0xb0, 0xf7, 0xf7, 0x7b, 0xfb, 0x20, 0x46, + 0xf9, 0xf7, 0xc0, 0xf8, 0xa0, 0xb1, 0x40, 0xa9, 0x0d, 0xf5, 0x81, 0x72, + 0x20, 0x46, 0xfb, 0xf7, 0x57, 0xfd, 0x20, 0x46, 0xfb, 0xf7, 0xec, 0xfb, + 0xbd, 0xf8, 0x00, 0x11, 0x05, 0x46, 0xbd, 0xf8, 0x02, 0x21, 0x20, 0x46, + 0xfc, 0xf7, 0xca, 0xfb, 0x20, 0x46, 0x29, 0x46, 0xfd, 0xf7, 0xfa, 0xfb, + 0x11, 0x99, 0x11, 0xb9, 0x20, 0x46, 0xff, 0xf7, 0x11, 0xfa, 0x20, 0x46, + 0x06, 0x99, 0xf9, 0xf7, 0xf1, 0xfe, 0x20, 0x46, 0x40, 0xf2, 0xd7, 0x41, + 0x10, 0x9a, 0xf6, 0xf7, 0xe7, 0xff, 0xe3, 0x69, 0x06, 0x99, 0x98, 0x68, + 0x30, 0x22, 0xed, 0xf3, 0x8f, 0xf0, 0x20, 0x46, 0x40, 0xf2, 0xdb, 0x41, + 0x0f, 0x9a, 0xf6, 0xf7, 0xdb, 0xff, 0x00, 0x22, 0x20, 0x46, 0x40, 0xf2, + 0x53, 0x41, 0xf6, 0xf7, 0xd5, 0xff, 0x07, 0x9a, 0x1a, 0xb1, 0x20, 0x46, + 0x3a, 0xa9, 0xf9, 0xf7, 0x10, 0xfb, 0x20, 0x46, 0x0e, 0x99, 0xfd, 0xf7, + 0xbb, 0xfa, 0x20, 0x46, 0x40, 0xf2, 0xda, 0x61, 0x0d, 0x9a, 0xf6, 0xf7, + 0xc5, 0xff, 0x20, 0x46, 0x40, 0xf2, 0xdb, 0x61, 0x0c, 0x9a, 0xf6, 0xf7, + 0xbf, 0xff, 0x43, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, 0xa5, 0x50, 0x01, 0x00, + 0x6b, 0x56, 0x01, 0x00, 0x2d, 0xe9, 0xf0, 0x4f, 0x87, 0xb0, 0x04, 0x46, + 0xf9, 0xf7, 0x3f, 0xf9, 0x04, 0xa9, 0x06, 0x46, 0x20, 0x46, 0xd4, 0xf8, + 0xa8, 0x50, 0xf9, 0xf7, 0x40, 0xf9, 0x20, 0x46, 0xf9, 0xf7, 0x5a, 0xf9, + 0x40, 0xf2, 0xd7, 0x41, 0x02, 0x90, 0x20, 0x46, 0xf6, 0xf7, 0x97, 0xff, + 0x03, 0x90, 0x20, 0x46, 0xfd, 0xf7, 0x8e, 0xfb, 0x83, 0x46, 0x26, 0xb9, + 0x20, 0x46, 0xfc, 0xf7, 0x08, 0xfe, 0x82, 0x46, 0x01, 0xe0, 0x4f, 0xf0, + 0xff, 0x0a, 0xb4, 0xf8, 0xda, 0x30, 0x4f, 0xf0, 0x2a, 0x08, 0x03, 0xf4, + 0x70, 0x43, 0xb3, 0xf5, 0x00, 0x5f, 0x0c, 0xbf, 0x95, 0xf8, 0x1e, 0x75, + 0x95, 0xf8, 0x1f, 0x75, 0x20, 0x46, 0x7f, 0xb2, 0x39, 0x46, 0x0f, 0x22, + 0x3c, 0x23, 0xcd, 0xf8, 0x00, 0x80, 0xff, 0xf7, 0xa3, 0xfa, 0x95, 0xf8, + 0x46, 0x95, 0xb9, 0xf1, 0x00, 0x0f, 0x00, 0xf0, 0x92, 0x80, 0x20, 0x46, + 0x40, 0xf2, 0xeb, 0x41, 0xf6, 0xf7, 0x69, 0xff, 0x12, 0x21, 0xc0, 0xf3, + 0x40, 0x23, 0x01, 0x22, 0x20, 0x46, 0xf7, 0xf7, 0x11, 0xf9, 0x6a, 0x78, + 0x00, 0x21, 0x52, 0x1a, 0x18, 0xbf, 0x01, 0x22, 0x0b, 0x46, 0x20, 0x46, + 0xff, 0xf7, 0xb6, 0xfc, 0x20, 0x46, 0xfb, 0xf7, 0x4b, 0xfb, 0x40, 0xf3, + 0x07, 0x23, 0x40, 0xb2, 0xa5, 0xf8, 0x4a, 0x35, 0xa5, 0xf8, 0x4c, 0x05, + 0x40, 0xf2, 0xeb, 0x41, 0x20, 0x46, 0xf6, 0xf7, 0x4a, 0xff, 0x00, 0xf4, + 0x80, 0x63, 0x9b, 0x12, 0x20, 0x46, 0x5b, 0x02, 0x40, 0xf2, 0xeb, 0x41, + 0x4f, 0xf4, 0x00, 0x72, 0xf7, 0xf7, 0x30, 0xf9, 0x00, 0x21, 0x07, 0x22, + 0x0b, 0x46, 0x20, 0x46, 0xff, 0xf7, 0x96, 0xfc, 0x20, 0x46, 0xfb, 0xf7, + 0x2b, 0xfb, 0x40, 0xf3, 0x07, 0x23, 0x40, 0xb2, 0xa5, 0xf8, 0x4e, 0x35, + 0xa5, 0xf8, 0x50, 0x05, 0xff, 0x22, 0x20, 0x46, 0xb5, 0xf8, 0x4a, 0x35, + 0x40, 0xf6, 0x52, 0x11, 0xf7, 0xf7, 0x18, 0xf9, 0x20, 0x46, 0xff, 0x22, + 0xb5, 0xf8, 0x4c, 0x35, 0x40, 0xf6, 0x53, 0x11, 0xf7, 0xf7, 0x10, 0xf9, + 0x20, 0x46, 0xff, 0x22, 0xb5, 0xf8, 0x4a, 0x35, 0x40, 0xf6, 0x56, 0x11, + 0xf7, 0xf7, 0x08, 0xf9, 0x20, 0x46, 0xff, 0x22, 0xb5, 0xf8, 0x4c, 0x35, + 0x40, 0xf6, 0x57, 0x11, 0xf7, 0xf7, 0x00, 0xf9, 0x20, 0x46, 0xff, 0x22, + 0xb5, 0xf8, 0x4e, 0x35, 0x40, 0xf6, 0x48, 0x11, 0xf7, 0xf7, 0xf8, 0xf8, + 0xff, 0x22, 0x20, 0x46, 0xb5, 0xf8, 0x50, 0x35, 0x40, 0xf6, 0x49, 0x11, + 0xf7, 0xf7, 0xf0, 0xf8, 0x95, 0xf8, 0x4c, 0x35, 0xb5, 0xf8, 0x4a, 0x15, + 0x20, 0x46, 0x43, 0xea, 0x01, 0x21, 0x89, 0xb2, 0xfd, 0xf7, 0x04, 0xfb, + 0x95, 0xf8, 0x47, 0x35, 0x20, 0x46, 0x9b, 0x02, 0x40, 0xf2, 0xeb, 0x41, + 0x4f, 0xf4, 0x80, 0x62, 0x03, 0xf4, 0x7c, 0x43, 0xf7, 0xf7, 0xda, 0xf8, + 0x95, 0xf8, 0x48, 0x35, 0x20, 0x46, 0x5b, 0x02, 0x40, 0xf2, 0xeb, 0x41, + 0x4f, 0xf4, 0x00, 0x72, 0x03, 0xf4, 0x7e, 0x43, 0xf7, 0xf7, 0xce, 0xf8, + 0x10, 0xe0, 0x0f, 0x22, 0x3c, 0x23, 0x20, 0x46, 0x39, 0x46, 0xcd, 0xf8, + 0x00, 0x80, 0xff, 0xf7, 0x03, 0xfa, 0x6a, 0x78, 0x20, 0x46, 0x00, 0x32, + 0x49, 0x46, 0x18, 0xbf, 0x01, 0x22, 0x4b, 0x46, 0xff, 0xf7, 0x28, 0xfc, + 0x20, 0x46, 0xf8, 0xf7, 0x73, 0xff, 0x10, 0xb1, 0x20, 0x46, 0xfb, 0xf7, + 0xcc, 0xfa, 0x00, 0x21, 0x0b, 0x46, 0x7f, 0x22, 0x20, 0x46, 0xfc, 0xf7, + 0x8a, 0xf9, 0x20, 0x46, 0x59, 0x46, 0xfb, 0xf7, 0xb1, 0xfd, 0x20, 0x46, + 0x02, 0x99, 0xf9, 0xf7, 0x89, 0xfa, 0x20, 0x46, 0x04, 0xa9, 0xf9, 0xf7, + 0xfe, 0xf9, 0x20, 0x46, 0x40, 0xf2, 0xd7, 0x41, 0x03, 0x9a, 0xf6, 0xf7, + 0xb7, 0xfe, 0x20, 0x46, 0x1e, 0xb1, 0x31, 0x46, 0xfd, 0xf7, 0xa2, 0xf9, + 0x02, 0xe0, 0x51, 0x46, 0xfd, 0xf7, 0x5c, 0xfd, 0x07, 0xb0, 0xbd, 0xe8, + 0xf0, 0x8f, 0x00, 0x00, 0x2d, 0xe9, 0xf0, 0x4f, 0x98, 0x46, 0xc3, 0x69, + 0xd0, 0xf8, 0xa8, 0x60, 0xa7, 0xb0, 0x04, 0x46, 0x0f, 0x46, 0x98, 0x68, + 0x4f, 0xf4, 0x83, 0x71, 0x15, 0x46, 0xec, 0xf3, 0x39, 0xf7, 0x82, 0x46, + 0x00, 0x28, 0x00, 0xf0, 0xe8, 0x81, 0xb8, 0xf1, 0x02, 0x0f, 0x16, 0xd1, + 0x0e, 0xe0, 0x3b, 0x46, 0x19, 0x78, 0x94, 0xf8, 0xda, 0x20, 0x01, 0x3d, + 0x06, 0x3f, 0x91, 0x42, 0x0a, 0xd1, 0x20, 0x46, 0x59, 0x88, 0x9a, 0x88, + 0xf9, 0xf7, 0x63, 0xfa, 0x01, 0x25, 0xcc, 0xe1, 0x6b, 0x1e, 0x06, 0x22, + 0x02, 0xfb, 0x03, 0x77, 0x00, 0x2d, 0xea, 0xd1, 0xc5, 0xe1, 0xb8, 0xf1, + 0x01, 0x0f, 0x40, 0xf0, 0xc1, 0x81, 0x20, 0x46, 0xf9, 0xf7, 0x03, 0xf8, + 0x00, 0x21, 0x09, 0x90, 0x20, 0x46, 0xfd, 0xf7, 0x61, 0xf9, 0x00, 0x25, + 0x7b, 0x4f, 0x20, 0x46, 0x79, 0x5b, 0xf6, 0xf7, 0x23, 0xfe, 0x18, 0xab, + 0x58, 0x53, 0x02, 0x35, 0x18, 0x2d, 0xf5, 0xd1, 0x40, 0xf2, 0x31, 0x61, + 0x20, 0x46, 0xf6, 0xf7, 0x56, 0xfe, 0x15, 0x22, 0x0a, 0x90, 0x40, 0xf2, + 0x31, 0x61, 0x20, 0x46, 0xf7, 0xf7, 0x32, 0xf8, 0x40, 0xf2, 0x4c, 0x41, + 0x20, 0x46, 0xf6, 0xf7, 0x4a, 0xfe, 0x40, 0xf2, 0x4d, 0x41, 0x0b, 0x90, + 0x20, 0x46, 0xf6, 0xf7, 0x44, 0xfe, 0x4f, 0xf4, 0x96, 0x61, 0x0c, 0x90, + 0x20, 0x46, 0xf6, 0xf7, 0x3e, 0xfe, 0x40, 0xf2, 0xb1, 0x41, 0x0d, 0x90, + 0x20, 0x46, 0xf6, 0xf7, 0x38, 0xfe, 0x40, 0xf2, 0xf9, 0x41, 0x0e, 0x90, + 0x20, 0x46, 0xf6, 0xf7, 0x32, 0xfe, 0x40, 0xf2, 0xfa, 0x41, 0x0f, 0x90, + 0x20, 0x46, 0xf6, 0xf7, 0x2c, 0xfe, 0x40, 0xf6, 0x38, 0x11, 0x10, 0x90, + 0x20, 0x46, 0xf6, 0xf7, 0x26, 0xfe, 0x40, 0xf6, 0x39, 0x11, 0x11, 0x90, + 0x20, 0x46, 0xf6, 0xf7, 0x20, 0xfe, 0x40, 0xf2, 0x3b, 0x41, 0x12, 0x90, + 0x20, 0x46, 0xf6, 0xf7, 0x1a, 0xfe, 0x40, 0xf2, 0x3c, 0x41, 0x13, 0x90, + 0x20, 0x46, 0xf6, 0xf7, 0x14, 0xfe, 0x40, 0xf2, 0xda, 0x61, 0x14, 0x90, + 0x20, 0x46, 0xf6, 0xf7, 0x0e, 0xfe, 0x40, 0xf2, 0xdb, 0x61, 0x15, 0x90, + 0x20, 0x46, 0xf6, 0xf7, 0x08, 0xfe, 0x40, 0xf2, 0xb7, 0x41, 0x16, 0x90, + 0x20, 0x46, 0xf6, 0xf7, 0x02, 0xfe, 0x40, 0xf2, 0x3b, 0x41, 0x17, 0x90, + 0x20, 0x46, 0xf6, 0xf7, 0xfc, 0xfd, 0xc0, 0xf3, 0x80, 0x19, 0xb9, 0xf1, + 0x00, 0x0f, 0x07, 0xd0, 0x20, 0x46, 0x24, 0xa9, 0xf8, 0xf7, 0x93, 0xff, + 0x96, 0xf8, 0xc1, 0x62, 0x07, 0x96, 0x01, 0xe0, 0xcd, 0xf8, 0x1c, 0x90, + 0x20, 0x46, 0x30, 0x99, 0xfd, 0xf7, 0xa2, 0xfc, 0x06, 0x22, 0x20, 0x46, + 0x3d, 0x49, 0xf6, 0xf7, 0xe7, 0xff, 0xb4, 0xf8, 0xda, 0x30, 0x03, 0xf4, + 0x70, 0x43, 0xb3, 0xf5, 0x00, 0x5f, 0x04, 0xd1, 0x20, 0x46, 0x98, 0x21, + 0x03, 0x22, 0xf6, 0xf7, 0xb2, 0xfd, 0x20, 0x46, 0x36, 0x49, 0x19, 0x22, + 0xf6, 0xf7, 0xd6, 0xff, 0x20, 0x46, 0x35, 0x49, 0x18, 0x22, 0xf6, 0xf7, + 0xd1, 0xff, 0xb4, 0xf8, 0xda, 0x30, 0x4f, 0xf0, 0x03, 0x08, 0x03, 0xf4, + 0x70, 0x43, 0xb3, 0xf5, 0x00, 0x5f, 0x14, 0xbf, 0x04, 0x23, 0x00, 0x23, + 0x08, 0x93, 0x23, 0xe1, 0xb3, 0xb2, 0x00, 0x93, 0xbb, 0xb2, 0x00, 0x25, + 0x01, 0x93, 0x1f, 0xfa, 0x88, 0xf3, 0x2a, 0x46, 0x02, 0x93, 0x20, 0x46, + 0x08, 0x9b, 0x29, 0x46, 0x03, 0x95, 0x04, 0x95, 0xf9, 0xf7, 0xd4, 0xf9, + 0x20, 0x46, 0x01, 0x21, 0xf9, 0xf7, 0x35, 0xf9, 0x2b, 0x46, 0x20, 0x46, + 0x22, 0x49, 0x3c, 0x22, 0xfe, 0xf7, 0x2e, 0xff, 0x20, 0x46, 0x4f, 0xf4, + 0x89, 0x71, 0x2a, 0x46, 0xf6, 0xf7, 0x7b, 0xfd, 0x21, 0xab, 0x00, 0x93, + 0x4f, 0xf4, 0xfa, 0x7b, 0x2b, 0x46, 0x20, 0x46, 0x4f, 0xf4, 0x80, 0x61, + 0x20, 0x22, 0xcd, 0xf8, 0x04, 0xb0, 0xf9, 0xf7, 0x4b, 0xff, 0x03, 0x46, + 0x30, 0xb9, 0x17, 0x48, 0x06, 0x93, 0xf5, 0xf7, 0xc1, 0xfb, 0x06, 0x9b, + 0x1d, 0x46, 0x45, 0xe0, 0x2b, 0x46, 0x20, 0x46, 0x11, 0x49, 0x78, 0x22, + 0xfe, 0xf7, 0x0c, 0xff, 0x20, 0x46, 0x4f, 0xf4, 0x89, 0x71, 0x2a, 0x46, + 0xf6, 0xf7, 0x59, 0xfd, 0x1e, 0xab, 0x8d, 0xe8, 0x08, 0x08, 0x20, 0x46, + 0x4f, 0xf4, 0x80, 0x61, 0x20, 0x22, 0x2b, 0x46, 0xf9, 0xf7, 0x2c, 0xff, + 0xa0, 0xb9, 0x83, 0x46, 0x08, 0x48, 0xf5, 0xf7, 0xa3, 0xfb, 0x5d, 0x46, + 0x28, 0xe0, 0x00, 0xbf, 0x00, 0xe7, 0x01, 0x00, 0x2c, 0xee, 0x01, 0x00, + 0xca, 0xee, 0x01, 0x00, 0xfc, 0xee, 0x01, 0x00, 0x80, 0x84, 0x1e, 0x00, + 0x2e, 0xe8, 0x01, 0x00, 0x48, 0xe8, 0x01, 0x00, 0x22, 0x9a, 0x1f, 0x99, + 0x23, 0x9b, 0xb1, 0xeb, 0x42, 0x0f, 0x0d, 0xd9, 0x02, 0xeb, 0x82, 0x02, + 0x91, 0x42, 0x09, 0xd2, 0x20, 0x9a, 0xb2, 0xeb, 0x43, 0x0f, 0x05, 0xd9, + 0x03, 0xeb, 0x83, 0x03, 0x9a, 0x42, 0x2c, 0xbf, 0x00, 0x25, 0x01, 0x25, + 0x16, 0xf1, 0xff, 0x36, 0x02, 0xd3, 0x00, 0x2d, 0x84, 0xd0, 0x01, 0x25, + 0x17, 0xf1, 0xff, 0x37, 0x03, 0xd3, 0x00, 0x2d, 0x00, 0xf0, 0xa0, 0x80, + 0x01, 0x25, 0x18, 0xf1, 0xff, 0x38, 0x02, 0xd3, 0x00, 0x2d, 0x00, 0xf0, + 0x9b, 0x80, 0x20, 0x46, 0x40, 0xf2, 0xd1, 0x61, 0x04, 0x22, 0x00, 0x23, + 0xf6, 0xf7, 0x22, 0xff, 0x2d, 0xb1, 0x20, 0x46, 0x4f, 0xf4, 0x80, 0x61, + 0xfa, 0xf7, 0x90, 0xfe, 0x05, 0x46, 0x20, 0x46, 0xfe, 0xf7, 0x52, 0xff, + 0x20, 0x46, 0x40, 0xf2, 0x31, 0x61, 0x0a, 0x9a, 0xf6, 0xf7, 0x2c, 0xfd, + 0x20, 0x46, 0x40, 0xf2, 0x4c, 0x41, 0x0b, 0x9a, 0xf6, 0xf7, 0x26, 0xfd, + 0x20, 0x46, 0x40, 0xf2, 0x4d, 0x41, 0x0c, 0x9a, 0xf6, 0xf7, 0x20, 0xfd, + 0x20, 0x46, 0x4f, 0xf4, 0x96, 0x61, 0x0d, 0x9a, 0xf6, 0xf7, 0x1a, 0xfd, + 0x20, 0x46, 0x40, 0xf2, 0xb1, 0x41, 0x0e, 0x9a, 0xf6, 0xf7, 0x14, 0xfd, + 0x20, 0x46, 0x40, 0xf2, 0xf9, 0x41, 0x0f, 0x9a, 0xf6, 0xf7, 0x0e, 0xfd, + 0x20, 0x46, 0x40, 0xf2, 0xfa, 0x41, 0x10, 0x9a, 0xf6, 0xf7, 0x08, 0xfd, + 0x20, 0x46, 0x40, 0xf6, 0x38, 0x11, 0x11, 0x9a, 0xf6, 0xf7, 0x02, 0xfd, + 0x20, 0x46, 0x40, 0xf6, 0x39, 0x11, 0x12, 0x9a, 0xf6, 0xf7, 0xfc, 0xfc, + 0x20, 0x46, 0x40, 0xf2, 0x3b, 0x41, 0x13, 0x9a, 0xf6, 0xf7, 0xf6, 0xfc, + 0x20, 0x46, 0x40, 0xf2, 0x3c, 0x41, 0x14, 0x9a, 0xf6, 0xf7, 0xf0, 0xfc, + 0x20, 0x46, 0x40, 0xf2, 0xda, 0x61, 0x15, 0x9a, 0xf6, 0xf7, 0xea, 0xfc, + 0x20, 0x46, 0x40, 0xf2, 0xdb, 0x61, 0x16, 0x9a, 0xf6, 0xf7, 0xe4, 0xfc, + 0x20, 0x46, 0x40, 0xf2, 0xb7, 0x41, 0x17, 0x9a, 0xf6, 0xf7, 0xde, 0xfc, + 0x20, 0x46, 0x40, 0xf2, 0x4c, 0x41, 0x04, 0x22, 0x00, 0x23, 0xf6, 0xf7, + 0xbd, 0xfe, 0x00, 0x26, 0x17, 0x4b, 0x20, 0x46, 0x99, 0x5b, 0x18, 0xab, + 0x9a, 0x5b, 0x02, 0x36, 0xf6, 0xf7, 0x9d, 0xfc, 0x18, 0x2e, 0xf5, 0xd1, + 0x20, 0x46, 0xb9, 0xf1, 0x00, 0x0f, 0x03, 0xd0, 0x07, 0x99, 0xfd, 0xf7, + 0x73, 0xfb, 0x02, 0xe0, 0x49, 0x46, 0xf8, 0xf7, 0xe6, 0xff, 0x20, 0x46, + 0x09, 0x99, 0xfc, 0xf7, 0xad, 0xff, 0x20, 0x46, 0x00, 0x21, 0xf9, 0xf7, + 0x36, 0xf8, 0x00, 0xe0, 0x00, 0x25, 0xe3, 0x69, 0x51, 0x46, 0x98, 0x68, + 0x4f, 0xf4, 0x83, 0x72, 0xec, 0xf3, 0x5e, 0xf5, 0x00, 0xe0, 0x05, 0x46, + 0x28, 0x46, 0x27, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, 0x06, 0x26, 0xdb, 0xe6, + 0x04, 0x27, 0xfb, 0xe7, 0x00, 0xe7, 0x01, 0x00, 0xf7, 0xb5, 0x04, 0x46, + 0xf8, 0xf7, 0x2d, 0xfe, 0xe2, 0x69, 0x04, 0xf5, 0x81, 0x53, 0x12, 0x6a, + 0xd4, 0xf8, 0xa8, 0x50, 0x1a, 0x60, 0xb4, 0xf8, 0xda, 0x30, 0x00, 0x22, + 0x85, 0xf8, 0xbc, 0x32, 0x04, 0xf5, 0x80, 0x53, 0x83, 0xf8, 0x24, 0x20, + 0xd4, 0xf8, 0xb0, 0x30, 0x07, 0x46, 0xd3, 0xf8, 0x20, 0x31, 0x03, 0xf0, + 0x01, 0x03, 0x83, 0xf0, 0x01, 0x06, 0x53, 0xb1, 0xe3, 0x69, 0xb8, 0x21, + 0x18, 0x69, 0x42, 0xf2, 0x10, 0x72, 0x36, 0xf0, 0x4d, 0xda, 0xe3, 0x69, + 0x18, 0x69, 0x36, 0xf0, 0x7b, 0xda, 0x20, 0x46, 0x01, 0x21, 0xfe, 0xf7, + 0x87, 0xf9, 0x0f, 0x22, 0x24, 0x49, 0x20, 0x46, 0xf6, 0xf7, 0x6a, 0xfe, + 0x20, 0x46, 0xf9, 0xf7, 0x23, 0xfb, 0x20, 0x46, 0x00, 0x21, 0xfd, 0xf7, + 0x6f, 0xf8, 0x00, 0x21, 0x20, 0x46, 0x0a, 0x46, 0xfc, 0xf7, 0x36, 0xf8, + 0x20, 0x46, 0xf8, 0xf7, 0x1a, 0xfa, 0x04, 0xf5, 0x82, 0x53, 0x1b, 0x79, + 0x6b, 0xb1, 0x20, 0x46, 0xfd, 0xf7, 0x2c, 0xfc, 0x20, 0x46, 0x00, 0x21, + 0xfc, 0xf7, 0x29, 0xfd, 0x95, 0xf8, 0xe8, 0x33, 0x1b, 0xb1, 0x20, 0x46, + 0x01, 0x21, 0xfc, 0xf7, 0x22, 0xfd, 0x20, 0x46, 0xff, 0xf7, 0x96, 0xfc, + 0x00, 0x21, 0x7f, 0x23, 0x0a, 0x46, 0x00, 0x93, 0x20, 0x46, 0x01, 0x23, + 0xff, 0xf7, 0x9c, 0xfd, 0xff, 0x23, 0x85, 0xf8, 0x07, 0x34, 0x85, 0xf8, + 0x08, 0x34, 0x20, 0x46, 0xfe, 0xf7, 0x7f, 0xff, 0x20, 0x46, 0x39, 0x46, + 0xfc, 0xf7, 0x2a, 0xff, 0x20, 0x46, 0x00, 0x21, 0xfe, 0xf7, 0x46, 0xf9, + 0x36, 0xb9, 0xe3, 0x69, 0x18, 0x69, 0x03, 0xb0, 0xbd, 0xe8, 0xf0, 0x40, + 0x36, 0xf0, 0x1a, 0x9a, 0x03, 0xb0, 0xf0, 0xbd, 0xce, 0xe9, 0x01, 0x00, + 0x01, 0x29, 0xd0, 0xf8, 0xa8, 0x30, 0x01, 0xd1, 0xfc, 0xf7, 0x24, 0xbc, + 0xb3, 0xf8, 0x6c, 0x25, 0xb3, 0xf8, 0x6e, 0x35, 0xff, 0x2b, 0x88, 0xbf, + 0xa3, 0xf5, 0x00, 0x73, 0xff, 0x2a, 0x88, 0xbf, 0xa2, 0xf5, 0x00, 0x72, + 0x9b, 0xb2, 0x92, 0xb2, 0x9a, 0x1a, 0x10, 0xb2, 0x70, 0x47, 0x70, 0xb5, + 0xd0, 0xf8, 0xa8, 0x30, 0xd3, 0xf8, 0xd0, 0x63, 0xd3, 0xf8, 0xcc, 0x53, + 0xd3, 0xf8, 0xd4, 0x43, 0xff, 0xf7, 0xde, 0xff, 0x63, 0x1e, 0x05, 0xfb, + 0x10, 0x65, 0x01, 0x26, 0x16, 0xfa, 0x03, 0xf3, 0xed, 0x18, 0x55, 0xfa, + 0x04, 0xf4, 0x60, 0xb2, 0x70, 0xbd, 0x2d, 0xe9, 0xf0, 0x41, 0xb0, 0xf8, + 0xda, 0x30, 0x06, 0x46, 0x03, 0xf4, 0x70, 0x42, 0xb2, 0xf5, 0x00, 0x5f, + 0xd0, 0xf8, 0xa8, 0x40, 0x04, 0xd1, 0xb4, 0xf8, 0x54, 0x83, 0xb4, 0xf8, + 0x84, 0x75, 0x13, 0xe0, 0xdb, 0xb2, 0x94, 0x2b, 0x03, 0xd9, 0xb4, 0xf8, + 0x86, 0x75, 0x02, 0x23, 0x08, 0xe0, 0x63, 0x2b, 0x03, 0xd9, 0xb4, 0xf8, + 0x88, 0x75, 0x01, 0x23, 0x02, 0xe0, 0xb4, 0xf8, 0x8a, 0x75, 0x00, 0x23, + 0x04, 0xeb, 0x43, 0x03, 0xb3, 0xf8, 0x56, 0x83, 0xb8, 0xf1, 0xff, 0x0f, + 0x1c, 0xd0, 0x01, 0x21, 0x30, 0x46, 0xff, 0xf7, 0xbe, 0xff, 0x19, 0x38, + 0x47, 0x43, 0x3f, 0xb2, 0x00, 0x2f, 0xcc, 0xbf, 0x07, 0xf5, 0xfa, 0x75, + 0xa7, 0xf5, 0xfa, 0x75, 0x4f, 0xf4, 0x7a, 0x73, 0x95, 0xfb, 0xf3, 0xf5, + 0xad, 0xb2, 0x45, 0x44, 0xad, 0xb2, 0x30, 0x46, 0x40, 0xf2, 0x34, 0x41, + 0xff, 0x22, 0x2b, 0x46, 0xf6, 0xf7, 0xa0, 0xfd, 0xa4, 0xf8, 0x66, 0x53, + 0xbd, 0xe8, 0xf0, 0x81, 0x70, 0xb5, 0xd0, 0xf8, 0xa8, 0x30, 0x01, 0x29, + 0xd3, 0xf8, 0xdc, 0x63, 0xd3, 0xf8, 0xd8, 0x53, 0xd3, 0xf8, 0xe0, 0x43, + 0x03, 0xd1, 0x02, 0x21, 0xfc, 0xf7, 0xa8, 0xfb, 0x09, 0xe0, 0x40, 0xf2, + 0x75, 0x41, 0xf6, 0xf7, 0x98, 0xfb, 0xc0, 0x05, 0xc0, 0x0d, 0xff, 0x28, + 0x88, 0xbf, 0xa0, 0xf5, 0x00, 0x70, 0x00, 0xfb, 0x15, 0x60, 0x63, 0x1f, + 0x01, 0x25, 0x15, 0xfa, 0x03, 0xf3, 0x04, 0x3c, 0xc0, 0x18, 0x20, 0x41, + 0x40, 0xb2, 0x70, 0xbd, 0x10, 0xb5, 0xd0, 0xf8, 0xa8, 0x30, 0xcc, 0xb2, + 0xd3, 0xf8, 0xd4, 0x04, 0x02, 0x0e, 0x7f, 0x2a, 0x44, 0xea, 0x00, 0x20, + 0xc8, 0xbf, 0xa2, 0xf5, 0x80, 0x72, 0xc3, 0xf8, 0xd4, 0x04, 0xd3, 0xf8, + 0xd8, 0x04, 0x8a, 0x1a, 0x12, 0x18, 0xc3, 0xf8, 0xd8, 0x24, 0x92, 0x10, + 0xc3, 0xf8, 0xdc, 0x24, 0x10, 0xbd, 0x08, 0x22, 0x70, 0xb5, 0x13, 0x46, + 0x04, 0x46, 0x57, 0x21, 0xf6, 0xf7, 0x16, 0xfd, 0x56, 0x21, 0x20, 0x46, + 0xf6, 0xf7, 0x26, 0xfb, 0x00, 0xf0, 0xf8, 0x05, 0x56, 0x21, 0x2a, 0x46, + 0x20, 0x46, 0xf6, 0xf7, 0x36, 0xfb, 0x01, 0x20, 0xec, 0xf3, 0x46, 0xf1, + 0x56, 0x21, 0x45, 0xf0, 0x03, 0x02, 0x20, 0x46, 0xf6, 0xf7, 0x2d, 0xfb, + 0x01, 0x20, 0xec, 0xf3, 0x3d, 0xf1, 0x56, 0x21, 0x45, 0xf0, 0x07, 0x02, + 0x20, 0x46, 0xf6, 0xf7, 0x24, 0xfb, 0x4f, 0xf4, 0x96, 0x70, 0xec, 0xf3, + 0x33, 0xf1, 0x20, 0x46, 0x57, 0x21, 0x08, 0x22, 0x00, 0x23, 0xbd, 0xe8, + 0x70, 0x40, 0xf6, 0xf7, 0xed, 0xbc, 0x00, 0x00, 0x2d, 0xe9, 0xf0, 0x4f, + 0xb5, 0x4b, 0x8b, 0xb0, 0x04, 0x46, 0x0d, 0x46, 0x06, 0xaa, 0x03, 0xf1, + 0x08, 0x07, 0x18, 0x68, 0x59, 0x68, 0x16, 0x46, 0x03, 0xc6, 0x08, 0x33, + 0xbb, 0x42, 0x32, 0x46, 0xf7, 0xd1, 0x18, 0x68, 0x30, 0x60, 0x99, 0x88, + 0x9b, 0x79, 0xb1, 0x80, 0xb3, 0x71, 0xd4, 0xf8, 0xa8, 0x70, 0x00, 0x23, + 0xaa, 0x4e, 0x1a, 0x01, 0x91, 0x59, 0xa9, 0x42, 0x03, 0xd0, 0x01, 0x33, + 0x0e, 0x2b, 0xf7, 0xd1, 0x57, 0xe3, 0x20, 0x46, 0x91, 0x21, 0xb6, 0x18, + 0x00, 0x22, 0xf6, 0xf7, 0xee, 0xfa, 0x20, 0x46, 0x38, 0x21, 0x07, 0x22, + 0xf6, 0xf7, 0xe9, 0xfa, 0x0a, 0x22, 0x20, 0x46, 0x88, 0x21, 0xf6, 0xf7, + 0xe4, 0xfa, 0xd4, 0xf8, 0xa8, 0x30, 0x93, 0xf8, 0x82, 0x25, 0x1a, 0xb1, + 0x20, 0x46, 0x88, 0x21, 0xf6, 0xf7, 0xdb, 0xfa, 0x2a, 0x21, 0x20, 0x46, + 0x32, 0x7a, 0xf6, 0xf7, 0xd6, 0xfa, 0x30, 0x21, 0x03, 0x22, 0x20, 0x46, + 0x73, 0x7a, 0xf6, 0xf7, 0xa5, 0xfc, 0x91, 0x21, 0x03, 0x22, 0x20, 0x46, + 0xb3, 0x7a, 0xf6, 0xf7, 0x9f, 0xfc, 0xf3, 0x7a, 0x38, 0x21, 0x0f, 0x22, + 0x20, 0x46, 0xf6, 0xf7, 0x99, 0xfc, 0x91, 0x21, 0x00, 0x22, 0x20, 0x46, + 0xf6, 0xf7, 0xbf, 0xfa, 0x38, 0x21, 0x07, 0x22, 0x20, 0x46, 0xf6, 0xf7, + 0xba, 0xfa, 0x33, 0x7b, 0x30, 0x21, 0x0c, 0x22, 0x9b, 0x00, 0x20, 0x46, + 0xf6, 0xf7, 0x88, 0xfc, 0x5e, 0x21, 0x0f, 0x22, 0x20, 0x46, 0x73, 0x7b, + 0xf6, 0xf7, 0x82, 0xfc, 0xb3, 0x7b, 0x5e, 0x21, 0x1b, 0x01, 0xf0, 0x22, + 0x20, 0x46, 0xf6, 0xf7, 0x7b, 0xfc, 0x6c, 0x21, 0x20, 0x46, 0xf2, 0x7b, + 0xf6, 0xf7, 0xa1, 0xfa, 0x08, 0x22, 0x20, 0x46, 0x38, 0x21, 0xf6, 0xf7, + 0x9c, 0xfa, 0x91, 0x21, 0x20, 0x46, 0x03, 0x22, 0xf6, 0xf7, 0x97, 0xfa, + 0x0a, 0xaa, 0x55, 0x19, 0x20, 0x46, 0x5e, 0x21, 0x15, 0xf8, 0x11, 0x2c, + 0xf6, 0xf7, 0x8f, 0xfa, 0x01, 0x22, 0x20, 0x46, 0x7e, 0x21, 0xf6, 0xf7, + 0x8a, 0xfa, 0x97, 0xf8, 0xee, 0x23, 0x1a, 0xb1, 0x20, 0x46, 0x38, 0x21, + 0xf6, 0xf7, 0x83, 0xfa, 0x07, 0x22, 0x13, 0x46, 0x20, 0x46, 0x2a, 0x21, + 0xf6, 0xf7, 0x52, 0xfc, 0x20, 0x46, 0x2c, 0x21, 0x00, 0x22, 0xf6, 0xf7, + 0x78, 0xfa, 0x20, 0x46, 0x2a, 0x21, 0x0c, 0x22, 0xf6, 0xf7, 0x73, 0xfa, + 0x01, 0x22, 0x20, 0x46, 0x2c, 0x21, 0xf6, 0xf7, 0x6e, 0xfa, 0xd4, 0xf8, + 0xa8, 0x30, 0x93, 0xf8, 0x52, 0x25, 0x2a, 0xb3, 0x93, 0xf8, 0x53, 0x25, + 0x20, 0x46, 0x5e, 0x21, 0xf6, 0xf7, 0x63, 0xfa, 0xd4, 0xf8, 0xa8, 0x30, + 0x20, 0x46, 0x93, 0xf8, 0x54, 0x25, 0x2a, 0x21, 0xf6, 0xf7, 0x5b, 0xfa, + 0xd4, 0xf8, 0xa8, 0x30, 0x20, 0x46, 0x93, 0xf8, 0x55, 0x25, 0x2b, 0x21, + 0xf6, 0xf7, 0x53, 0xfa, 0xd4, 0xf8, 0xa8, 0x30, 0x20, 0x46, 0x93, 0xf8, + 0x56, 0x25, 0x2c, 0x21, 0xf6, 0xf7, 0x4b, 0xfa, 0xd4, 0xf8, 0xa8, 0x30, + 0x20, 0x46, 0x2d, 0x21, 0x93, 0xf8, 0x57, 0x25, 0xf6, 0xf7, 0x43, 0xfa, + 0xb4, 0xf8, 0xda, 0x30, 0x03, 0xf4, 0x70, 0x43, 0xb3, 0xf5, 0x80, 0x5f, + 0x04, 0xd1, 0x20, 0x46, 0xbf, 0x21, 0xee, 0x22, 0xf6, 0xf7, 0x37, 0xfa, + 0x02, 0x22, 0x13, 0x46, 0x20, 0x46, 0x40, 0xf2, 0x1f, 0x11, 0xf6, 0xf7, + 0x05, 0xfc, 0x04, 0x22, 0xf7, 0x21, 0x13, 0x46, 0x20, 0x46, 0xf6, 0xf7, + 0xff, 0xfb, 0xf1, 0x21, 0x03, 0x22, 0x00, 0x23, 0x20, 0x46, 0xf6, 0xf7, + 0xf9, 0xfb, 0xf2, 0x21, 0xf8, 0x22, 0x90, 0x23, 0x20, 0x46, 0xf6, 0xf7, + 0xf3, 0xfb, 0xa2, 0x23, 0xf3, 0x21, 0xff, 0x22, 0x20, 0x46, 0xf6, 0xf7, + 0xed, 0xfb, 0xb4, 0xf8, 0xda, 0x30, 0x03, 0xf4, 0x70, 0x43, 0xb3, 0xf5, + 0x00, 0x5f, 0x04, 0xd1, 0xd4, 0xf8, 0xa8, 0x30, 0x93, 0xf8, 0x18, 0x35, + 0x06, 0xe0, 0xb3, 0xf5, 0x80, 0x5f, 0x06, 0xd1, 0xd4, 0xf8, 0xa8, 0x30, + 0x93, 0xf8, 0x19, 0x35, 0x01, 0x2b, 0x00, 0xf0, 0x5e, 0x82, 0x00, 0x23, + 0x20, 0x46, 0x9d, 0x21, 0x04, 0x22, 0xf6, 0xf7, 0xd1, 0xfb, 0x00, 0x23, + 0x44, 0x21, 0x20, 0x46, 0x02, 0x93, 0xf6, 0xf7, 0xdf, 0xf9, 0xc0, 0xb2, + 0x03, 0x90, 0x40, 0xf2, 0x2b, 0x11, 0x20, 0x46, 0xf6, 0xf7, 0xd8, 0xf9, + 0xc0, 0xb2, 0x04, 0x90, 0x44, 0x21, 0x20, 0x46, 0x07, 0x22, 0xf6, 0xf7, + 0xae, 0xfb, 0x0e, 0x22, 0x20, 0x46, 0x40, 0xf2, 0x2b, 0x11, 0xf6, 0xf7, + 0xa8, 0xfb, 0x02, 0x9a, 0x04, 0xf5, 0x80, 0x53, 0x9d, 0x6a, 0x0a, 0xb1, + 0x68, 0x00, 0x00, 0xe0, 0x28, 0x46, 0x1a, 0x4b, 0x9d, 0x42, 0x05, 0xd9, + 0x19, 0x4f, 0xbd, 0x42, 0x8c, 0xbf, 0x04, 0x27, 0x02, 0x27, 0x00, 0xe0, + 0x01, 0x27, 0xb4, 0xf8, 0xda, 0x80, 0x08, 0xf4, 0x70, 0x48, 0xb8, 0xf5, + 0x00, 0x5f, 0x05, 0xd1, 0x73, 0x68, 0x4f, 0xea, 0x40, 0x09, 0x03, 0xeb, + 0x43, 0x0a, 0x02, 0xe0, 0x4f, 0xf0, 0x00, 0x09, 0xca, 0x46, 0x10, 0x22, + 0x0e, 0x49, 0xf8, 0xf7, 0xc1, 0xf9, 0x0d, 0x49, 0x01, 0x90, 0x79, 0x43, + 0x10, 0x22, 0x28, 0x46, 0xf8, 0xf7, 0xba, 0xf9, 0xb8, 0xf5, 0x00, 0x5f, + 0x05, 0x90, 0x11, 0xd1, 0x50, 0x46, 0x02, 0x21, 0x10, 0x22, 0xf8, 0xf7, + 0xb1, 0xf9, 0x06, 0x46, 0x0b, 0xe0, 0x00, 0xbf, 0xd4, 0xb8, 0x01, 0x00, + 0x08, 0x04, 0x02, 0x00, 0x80, 0xba, 0x8c, 0x01, 0x00, 0x75, 0x19, 0x03, + 0x40, 0x42, 0x0f, 0x00, 0x00, 0x26, 0x4f, 0x21, 0x02, 0x22, 0x20, 0x46, + 0xf6, 0xf7, 0x99, 0xf9, 0xca, 0x4b, 0x4f, 0xea, 0xc5, 0x0b, 0x03, 0xfb, + 0x07, 0xf8, 0xbb, 0xfb, 0xf8, 0xf8, 0x08, 0xf1, 0x01, 0x08, 0x4f, 0xea, + 0x58, 0x08, 0x08, 0xf1, 0xff, 0x38, 0x5f, 0xfa, 0x88, 0xf8, 0x52, 0x21, + 0x07, 0x22, 0x20, 0x46, 0x4f, 0xea, 0x98, 0x03, 0xf6, 0xf7, 0x58, 0xfb, + 0x53, 0x21, 0x60, 0x22, 0x20, 0x46, 0x4f, 0xea, 0x48, 0x13, 0xf6, 0xf7, + 0x51, 0xfb, 0x08, 0xf1, 0x01, 0x03, 0x5f, 0x43, 0xbb, 0x4a, 0xbb, 0xfb, + 0xf7, 0xfb, 0xbb, 0x4f, 0x5a, 0x44, 0xb2, 0xfb, 0xf7, 0xf7, 0x01, 0x3f, + 0xff, 0xb2, 0x51, 0x21, 0x3a, 0x46, 0x20, 0x46, 0x00, 0x93, 0xf6, 0xf7, + 0x6a, 0xf9, 0x05, 0x9a, 0x30, 0x46, 0x11, 0x01, 0x10, 0x22, 0xf8, 0xf7, + 0x69, 0xf9, 0x01, 0x37, 0x47, 0x43, 0x00, 0x9b, 0x7b, 0x43, 0x04, 0xd4, + 0xdf, 0x13, 0x01, 0x37, 0x7f, 0x10, 0x01, 0x3f, 0x07, 0xe0, 0x6f, 0xea, + 0x08, 0x08, 0x08, 0xfb, 0x07, 0xf7, 0xff, 0x13, 0x01, 0x37, 0x6f, 0xea, + 0x67, 0x07, 0x3b, 0x0a, 0x53, 0x21, 0x0f, 0x22, 0xdb, 0xb2, 0x20, 0x46, + 0xf6, 0xf7, 0x20, 0xfb, 0x54, 0x21, 0xfa, 0xb2, 0x20, 0x46, 0xf6, 0xf7, + 0x46, 0xf9, 0x0a, 0x23, 0x03, 0xfb, 0x0a, 0xfa, 0xa2, 0x4f, 0x45, 0x21, + 0xb9, 0xfb, 0xf7, 0xf9, 0xba, 0xfb, 0xf9, 0xf8, 0x09, 0xfb, 0x18, 0xaa, + 0x4f, 0xea, 0x5a, 0x02, 0x12, 0x05, 0x0a, 0xf0, 0x01, 0x0a, 0x4f, 0xea, + 0x59, 0x03, 0x02, 0xeb, 0x99, 0x02, 0x4f, 0xea, 0x0a, 0x5a, 0xb2, 0xfb, + 0xf3, 0xf2, 0x53, 0x44, 0xb3, 0xfb, 0xf9, 0xf9, 0x4f, 0xea, 0x18, 0x13, + 0x09, 0xeb, 0x02, 0x07, 0x20, 0x46, 0x1f, 0x22, 0xdb, 0xb2, 0xf6, 0xf7, + 0xf7, 0xfa, 0x4f, 0xea, 0x08, 0x13, 0x46, 0x21, 0x20, 0x46, 0x4f, 0xf4, + 0xf8, 0x72, 0x03, 0xf0, 0xf0, 0x03, 0xf6, 0xf7, 0xed, 0xfa, 0x3b, 0x0c, + 0xdb, 0xb2, 0x46, 0x21, 0x0f, 0x22, 0x20, 0x46, 0xf6, 0xf7, 0xe6, 0xfa, + 0x3a, 0x0a, 0x47, 0x21, 0x20, 0x46, 0xd2, 0xb2, 0xf6, 0xf7, 0x0b, 0xf9, + 0x48, 0x21, 0xfa, 0xb2, 0x20, 0x46, 0xf6, 0xf7, 0x06, 0xf9, 0x02, 0x9b, + 0x41, 0xf2, 0x94, 0x19, 0x00, 0x2b, 0x08, 0xbf, 0x4f, 0xf4, 0xfa, 0x59, + 0xa9, 0xf5, 0xd8, 0x79, 0x4f, 0xf4, 0xf5, 0x73, 0xa9, 0xf1, 0x03, 0x09, + 0x99, 0xfb, 0xf3, 0xf9, 0x03, 0xfb, 0x09, 0xfa, 0x0a, 0xf5, 0x2a, 0x7a, + 0x4f, 0xf4, 0x25, 0x62, 0x4f, 0xea, 0x4a, 0x2a, 0xba, 0xfb, 0xf2, 0xfa, + 0x40, 0xf2, 0x7c, 0x67, 0x07, 0xfb, 0x0a, 0xf7, 0xa7, 0xf5, 0x58, 0x37, + 0xa7, 0xf5, 0xc0, 0x67, 0xb7, 0xfb, 0xf3, 0xf7, 0x0c, 0xbf, 0x4f, 0xf4, + 0x82, 0x7b, 0x4f, 0xf4, 0xe1, 0x7b, 0x7f, 0x0a, 0x4f, 0xea, 0xc9, 0x03, + 0x07, 0xf0, 0x1c, 0x02, 0x43, 0xea, 0x92, 0x02, 0x42, 0x21, 0x20, 0x46, + 0x92, 0xb2, 0xf6, 0xf7, 0xd2, 0xf8, 0x07, 0xf0, 0x1f, 0x02, 0x43, 0x21, + 0x20, 0x46, 0x42, 0xf0, 0x20, 0x02, 0xf6, 0xf7, 0xca, 0xf8, 0x4f, 0xea, + 0x4b, 0x22, 0x4f, 0xf4, 0x87, 0x73, 0xb2, 0xfb, 0xf3, 0xf3, 0x03, 0xfb, + 0x0a, 0xfa, 0x63, 0x4a, 0x4f, 0xea, 0x5a, 0x2a, 0x62, 0x4b, 0xb2, 0xfb, + 0xfa, 0xf2, 0xd3, 0x18, 0x4f, 0xf4, 0x12, 0x41, 0xb3, 0xfb, 0xf1, 0xf3, + 0x03, 0xf0, 0x0f, 0x01, 0x5e, 0x4b, 0x20, 0x46, 0xb3, 0xfb, 0xfa, 0xf3, + 0xa3, 0xf5, 0x4c, 0x23, 0xa3, 0xf5, 0x00, 0x63, 0x1a, 0x0c, 0x41, 0xea, + 0x02, 0x12, 0x92, 0xb2, 0x40, 0x21, 0xf6, 0xf7, 0xa6, 0xf8, 0x58, 0x4a, + 0x4f, 0xf0, 0x25, 0x53, 0xb3, 0xfb, 0xfa, 0xf3, 0xa3, 0xf5, 0x46, 0x33, + 0xb2, 0xfb, 0xfa, 0xfa, 0x4f, 0xf4, 0xb8, 0x41, 0xa3, 0xf5, 0x00, 0x73, + 0xaa, 0xf5, 0x6e, 0x3a, 0xb3, 0xfb, 0xf1, 0xf3, 0xaa, 0xf5, 0x00, 0x7a, + 0x03, 0xf0, 0x0f, 0x03, 0xba, 0xfb, 0xf1, 0xf2, 0x43, 0xea, 0x02, 0x12, + 0x41, 0x21, 0x20, 0x46, 0x92, 0xb2, 0xf6, 0xf7, 0x88, 0xf8, 0x06, 0xf1, + 0x74, 0x43, 0x4f, 0xf4, 0x96, 0x67, 0x03, 0xf5, 0x90, 0x03, 0x93, 0xfb, + 0xf7, 0xf3, 0x29, 0x27, 0x5f, 0x43, 0x4f, 0xf4, 0x5c, 0x73, 0x03, 0xfb, + 0x08, 0xf8, 0x40, 0xf2, 0x2b, 0x53, 0x03, 0xfb, 0x09, 0xf9, 0x09, 0xf5, + 0xe4, 0x61, 0x0b, 0xfb, 0x08, 0xf0, 0x0c, 0x31, 0x10, 0x22, 0xf8, 0xf7, + 0x73, 0xf8, 0x07, 0xf5, 0xd8, 0x17, 0x00, 0xeb, 0x67, 0x00, 0x90, 0xfb, + 0xf7, 0xf7, 0xff, 0xb2, 0x3c, 0x2f, 0x94, 0xbf, 0x4f, 0xf0, 0x00, 0x08, + 0x4f, 0xf0, 0x01, 0x08, 0xb8, 0xf1, 0x00, 0x0f, 0x00, 0xd0, 0x7f, 0x08, + 0x04, 0x3f, 0xff, 0xb2, 0x3c, 0x21, 0x3f, 0x22, 0x20, 0x46, 0x3b, 0x46, + 0xf6, 0xf7, 0x2a, 0xfa, 0x3c, 0x21, 0x40, 0x22, 0x4f, 0xea, 0x88, 0x13, + 0x20, 0x46, 0xf6, 0xf7, 0x23, 0xfa, 0xb4, 0xf8, 0xda, 0x30, 0x03, 0xf4, + 0x70, 0x43, 0xb3, 0xf5, 0x00, 0x5f, 0x04, 0xd1, 0xd4, 0xf8, 0xa8, 0x30, + 0x93, 0xf8, 0x27, 0x35, 0x06, 0xe0, 0xb3, 0xf5, 0x80, 0x5f, 0x1a, 0xd1, + 0xd4, 0xf8, 0xa8, 0x30, 0x93, 0xf8, 0x28, 0x35, 0x01, 0x2b, 0x14, 0xd1, + 0x01, 0x9a, 0x40, 0xf2, 0x45, 0x10, 0x50, 0x43, 0x31, 0x46, 0x10, 0x22, + 0xf8, 0xf7, 0x36, 0xf8, 0x04, 0x37, 0x08, 0xf1, 0x01, 0x08, 0x08, 0xfb, + 0x07, 0xf7, 0x9e, 0x21, 0x47, 0x43, 0xc0, 0x22, 0x20, 0x46, 0x40, 0x23, + 0xf6, 0xf7, 0xfa, 0xf9, 0x0c, 0xe0, 0x01, 0x9b, 0x96, 0x20, 0x58, 0x43, + 0x31, 0x46, 0x10, 0x22, 0xf8, 0xf7, 0x22, 0xf8, 0x04, 0x37, 0x08, 0xf1, + 0x01, 0x08, 0x08, 0xfb, 0x07, 0xf7, 0x47, 0x43, 0xb7, 0xf5, 0x16, 0x0f, + 0xd4, 0xbf, 0x00, 0x26, 0x01, 0x26, 0x73, 0x1c, 0x03, 0xeb, 0x43, 0x03, + 0x97, 0xfb, 0xf3, 0xf7, 0xb7, 0xf5, 0x00, 0x3f, 0x16, 0xdb, 0xa7, 0xf5, + 0xc0, 0x33, 0xdb, 0x13, 0x01, 0x33, 0x5b, 0x10, 0xdb, 0xb2, 0x10, 0xe0, + 0x40, 0x4b, 0x4c, 0x00, 0x3f, 0x42, 0x0f, 0x00, 0x40, 0x42, 0x0f, 0x00, + 0xa0, 0x86, 0x01, 0x00, 0x00, 0x00, 0x68, 0x60, 0x00, 0x21, 0xf6, 0xff, + 0x00, 0x00, 0x84, 0xa3, 0x00, 0x00, 0x30, 0x2a, 0x00, 0x23, 0x3d, 0x21, + 0x3f, 0x22, 0x20, 0x46, 0xf6, 0xf7, 0xc2, 0xf9, 0x3d, 0x21, 0x40, 0x22, + 0xb3, 0x01, 0x20, 0x46, 0xf6, 0xf7, 0xbc, 0xf9, 0x26, 0x4b, 0x57, 0x21, + 0x20, 0x22, 0x9d, 0x42, 0x20, 0x46, 0x06, 0xd9, 0x13, 0x46, 0xf6, 0xf7, + 0xb3, 0xf9, 0x23, 0x4b, 0x9d, 0x42, 0x04, 0xd8, 0x08, 0xe0, 0x00, 0x23, + 0xf6, 0xf7, 0xac, 0xf9, 0x04, 0xe0, 0x10, 0x22, 0x20, 0x46, 0x57, 0x21, + 0x13, 0x46, 0x03, 0xe0, 0x20, 0x46, 0x57, 0x21, 0x10, 0x22, 0x00, 0x23, + 0xf6, 0xf7, 0xa0, 0xf9, 0x01, 0x9a, 0x4a, 0x21, 0xb2, 0xf5, 0x34, 0x1f, + 0x20, 0x46, 0x03, 0xdd, 0x02, 0x22, 0xf6, 0xf7, 0x88, 0xf9, 0x02, 0xe0, + 0xfd, 0x22, 0xf6, 0xf7, 0x76, 0xf9, 0x0c, 0x22, 0x13, 0x46, 0x44, 0x21, + 0x20, 0x46, 0xf6, 0xf7, 0x8d, 0xf9, 0x01, 0x20, 0xeb, 0xf3, 0xc8, 0xf5, + 0x20, 0x46, 0xff, 0xf7, 0x6a, 0xfc, 0x20, 0x46, 0x44, 0x21, 0x03, 0x9a, + 0xf5, 0xf7, 0xad, 0xff, 0x04, 0x9a, 0x20, 0x46, 0x40, 0xf2, 0x2b, 0x11, + 0x0b, 0xb0, 0xbd, 0xe8, 0xf0, 0x4f, 0xf5, 0xf7, 0xa4, 0xbf, 0x04, 0x22, + 0x13, 0x46, 0x20, 0x46, 0x9d, 0x21, 0xf6, 0xf7, 0x73, 0xf9, 0x01, 0x23, + 0xa0, 0xe5, 0x0b, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, 0x80, 0xba, 0x8c, 0x01, + 0x00, 0x75, 0x19, 0x03, 0x08, 0xb5, 0xf8, 0xf7, 0x50, 0xf9, 0xa0, 0xf5, + 0x40, 0x4e, 0xde, 0xf1, 0x00, 0x00, 0x40, 0xeb, 0x0e, 0x00, 0x08, 0xbd, + 0x70, 0xb5, 0x00, 0x23, 0x13, 0x70, 0x0b, 0x70, 0x00, 0xf5, 0x82, 0x53, + 0x1b, 0x79, 0x04, 0x46, 0x0d, 0x46, 0x16, 0x46, 0x03, 0xb3, 0x40, 0xf2, + 0xab, 0x41, 0xf5, 0xf7, 0xa2, 0xff, 0x10, 0xf4, 0x00, 0x4f, 0x20, 0x46, + 0x02, 0xd0, 0x40, 0xf2, 0xab, 0x41, 0x08, 0xe0, 0x40, 0xf2, 0x3c, 0x61, + 0xf5, 0xf7, 0x97, 0xff, 0x03, 0x04, 0x06, 0xd5, 0x20, 0x46, 0x40, 0xf2, + 0x3c, 0x61, 0xf5, 0xf7, 0x90, 0xff, 0x40, 0x08, 0x28, 0x70, 0x20, 0x46, + 0xff, 0xf7, 0xd0, 0xff, 0x08, 0xb1, 0x94, 0xf8, 0x10, 0x05, 0x2b, 0x78, + 0xc0, 0x18, 0x30, 0x70, 0x70, 0xbd, 0x38, 0xb5, 0xd0, 0xf8, 0xa8, 0x40, + 0x05, 0x46, 0x94, 0xf8, 0x42, 0x33, 0x5b, 0xb1, 0x00, 0x21, 0xf9, 0xf7, + 0x3b, 0xfa, 0x28, 0x46, 0x19, 0x21, 0x00, 0x22, 0xf9, 0xf7, 0xfa, 0xf9, + 0x10, 0xb9, 0x01, 0x23, 0x84, 0xf8, 0x45, 0x33, 0x38, 0xbd, 0x38, 0xb5, + 0xd0, 0xf8, 0xa8, 0x50, 0x04, 0x46, 0x95, 0xf8, 0x42, 0x33, 0x83, 0xb9, + 0x90, 0xf8, 0xe9, 0x30, 0xda, 0x07, 0x44, 0xbf, 0x23, 0xf0, 0x01, 0x03, + 0x80, 0xf8, 0xe9, 0x30, 0x90, 0xf8, 0xe9, 0x30, 0x99, 0x07, 0x2f, 0xd5, + 0x23, 0xf0, 0x02, 0x03, 0x80, 0xf8, 0xe9, 0x30, 0x38, 0xbd, 0x95, 0xf8, + 0x47, 0x33, 0x23, 0xb9, 0xd1, 0xf1, 0x01, 0x03, 0x38, 0xbf, 0x00, 0x23, + 0x00, 0xe0, 0x01, 0x23, 0x85, 0xf8, 0x47, 0x33, 0xf1, 0xb1, 0x01, 0x23, + 0x85, 0xf8, 0x46, 0x33, 0x00, 0x23, 0xc5, 0xf8, 0x6c, 0x33, 0x85, 0xf8, + 0x45, 0x33, 0x20, 0x46, 0xff, 0xf7, 0xbd, 0xff, 0x95, 0xf8, 0x43, 0x33, + 0x00, 0x33, 0x18, 0xbf, 0x01, 0x23, 0x85, 0xf8, 0x44, 0x33, 0x13, 0xb1, + 0x20, 0x46, 0xf9, 0xf7, 0x0b, 0xf8, 0x20, 0x46, 0xf8, 0xf7, 0xbc, 0xf8, + 0x20, 0x46, 0x01, 0x21, 0xbd, 0xe8, 0x38, 0x40, 0xf9, 0xf7, 0xee, 0xb9, + 0x38, 0xbd, 0xf7, 0xb5, 0xd0, 0xf8, 0xa8, 0x40, 0x00, 0x23, 0x01, 0x93, + 0x00, 0x93, 0x94, 0xf8, 0x42, 0x33, 0x05, 0x46, 0x00, 0x2b, 0x00, 0xf0, + 0xcd, 0x80, 0x94, 0xf8, 0x46, 0x33, 0x00, 0x2b, 0x00, 0xf0, 0xc8, 0x80, + 0xd0, 0xf8, 0xb0, 0x30, 0xd3, 0xf8, 0x20, 0x31, 0xd9, 0x07, 0x40, 0xf1, + 0xc1, 0x80, 0x94, 0xf8, 0x45, 0x63, 0x00, 0x2e, 0x40, 0xf0, 0xa0, 0x80, + 0x31, 0x46, 0x32, 0x46, 0xf9, 0xf7, 0x90, 0xf9, 0x00, 0x28, 0x00, 0xf0, + 0x99, 0x80, 0x28, 0x46, 0x69, 0x46, 0x01, 0xaa, 0xf9, 0xf7, 0xb4, 0xfa, + 0x00, 0x28, 0x00, 0xf0, 0x91, 0x80, 0x01, 0x9b, 0xc4, 0xf8, 0x6c, 0x33, + 0x94, 0xf8, 0x46, 0x33, 0x01, 0x2b, 0x40, 0xf0, 0x89, 0x80, 0x94, 0xf8, + 0x91, 0xe3, 0x94, 0xf8, 0x90, 0x03, 0x00, 0x9a, 0x73, 0x46, 0x31, 0x46, + 0x1e, 0xe0, 0x5f, 0xb2, 0xdc, 0x37, 0x54, 0xf8, 0x27, 0xc0, 0x62, 0x45, + 0x36, 0xbf, 0x44, 0xf8, 0x27, 0x20, 0x4f, 0xf0, 0x00, 0x0c, 0x62, 0x46, + 0x54, 0xf8, 0x27, 0x70, 0x38, 0xbf, 0x4f, 0xf0, 0x01, 0x0c, 0x01, 0x33, + 0xdb, 0xb2, 0xc9, 0x19, 0x01, 0x36, 0x5f, 0xb2, 0xf6, 0xb2, 0x07, 0x2f, + 0xc8, 0xbf, 0x00, 0x23, 0xbc, 0xf1, 0x00, 0x0f, 0x02, 0xd0, 0x00, 0x92, + 0x00, 0x9a, 0x15, 0xe0, 0x4f, 0xfa, 0x86, 0xfc, 0x47, 0xb2, 0xbc, 0x45, + 0xdb, 0xdb, 0xf6, 0xe7, 0x5f, 0xb2, 0xdc, 0x37, 0x01, 0x33, 0x54, 0xf8, + 0x27, 0xc0, 0xdb, 0xb2, 0x44, 0xf8, 0x27, 0x20, 0x89, 0x18, 0x01, 0x36, + 0x5a, 0xb2, 0x07, 0x2a, 0xc8, 0xbf, 0x00, 0x23, 0xf6, 0xb2, 0x62, 0x46, + 0x77, 0xb2, 0x07, 0x2f, 0xec, 0xdd, 0x43, 0xb2, 0x07, 0x2b, 0x00, 0x92, + 0x05, 0xdc, 0x00, 0x23, 0x01, 0x30, 0x84, 0xf8, 0x92, 0x33, 0x84, 0xf8, + 0x90, 0x03, 0x94, 0xf9, 0x90, 0x33, 0x08, 0x2b, 0x3a, 0xd1, 0x94, 0xf8, + 0x94, 0x33, 0xe3, 0x18, 0x93, 0xf8, 0x97, 0x23, 0x93, 0xf8, 0x99, 0x63, + 0x94, 0xf8, 0x92, 0x33, 0xfc, 0x2b, 0x02, 0xd8, 0x01, 0x33, 0x84, 0xf8, + 0x92, 0x33, 0x94, 0xf8, 0x92, 0x33, 0x93, 0x42, 0x28, 0xd1, 0x0e, 0xf1, + 0x01, 0x03, 0x84, 0xf8, 0x91, 0x33, 0x5b, 0xb2, 0x07, 0x2b, 0x02, 0xdd, + 0x00, 0x23, 0x84, 0xf8, 0x91, 0x33, 0x06, 0x23, 0x84, 0xf8, 0x90, 0x33, + 0x28, 0x46, 0xf8, 0xf7, 0x83, 0xff, 0x18, 0xb9, 0x28, 0x46, 0xf8, 0xf7, + 0x0d, 0xf8, 0x10, 0xe0, 0x94, 0xf8, 0x93, 0x33, 0xfc, 0x2b, 0x02, 0xd8, + 0x01, 0x33, 0x84, 0xf8, 0x93, 0x33, 0x94, 0xf8, 0x93, 0x33, 0xb3, 0x42, + 0x05, 0xd1, 0x94, 0xf8, 0x94, 0x33, 0x13, 0xb9, 0x01, 0x23, 0x84, 0xf8, + 0x94, 0x33, 0x00, 0x23, 0x84, 0xf8, 0x92, 0x33, 0x94, 0xf8, 0x46, 0x13, + 0x00, 0x23, 0x01, 0x29, 0x84, 0xf8, 0x45, 0x33, 0x28, 0x46, 0x02, 0xd1, + 0xf9, 0xf7, 0x26, 0xf9, 0x02, 0xe0, 0x19, 0x46, 0xf9, 0xf7, 0x7d, 0xf9, + 0x28, 0x46, 0xd4, 0xf8, 0x6c, 0x13, 0xf9, 0xf7, 0xcd, 0xfa, 0x00, 0x23, + 0x84, 0xf8, 0x47, 0x33, 0x94, 0xf8, 0x9c, 0x33, 0x13, 0xb9, 0x01, 0x23, + 0x84, 0xf8, 0x9c, 0x33, 0xfe, 0xbd, 0x38, 0xb5, 0x15, 0x46, 0xd0, 0xf8, + 0xa8, 0x40, 0x7a, 0xb1, 0x94, 0xf8, 0x43, 0x13, 0x94, 0xf8, 0x42, 0x23, + 0xc3, 0x69, 0x42, 0xea, 0x41, 0x04, 0x2c, 0x60, 0x18, 0x69, 0x8c, 0x21, + 0x35, 0xf0, 0xfc, 0xdb, 0x44, 0xea, 0x00, 0x40, 0x28, 0x60, 0x38, 0xbd, + 0xcb, 0x08, 0x0d, 0xd1, 0x01, 0xf0, 0x01, 0x03, 0xc1, 0xf3, 0x40, 0x01, + 0x84, 0xf8, 0x42, 0x33, 0x84, 0xf8, 0x43, 0x13, 0x23, 0xb9, 0x01, 0x21, + 0xbd, 0xe8, 0x38, 0x40, 0xf9, 0xf7, 0x49, 0xb9, 0x38, 0xbd, 0x2d, 0xe9, + 0xf8, 0x43, 0x04, 0x46, 0x88, 0x46, 0x17, 0x46, 0xd0, 0xf8, 0xa8, 0x60, + 0x4f, 0xf0, 0x00, 0x09, 0xf7, 0xf7, 0xe3, 0xfb, 0x20, 0x46, 0x01, 0x21, + 0xfd, 0xf7, 0x38, 0xfb, 0x4d, 0x46, 0x0d, 0xe0, 0x01, 0x21, 0x00, 0x22, + 0xf6, 0xf7, 0x9c, 0xf9, 0x38, 0x46, 0xeb, 0xf3, 0x01, 0xf4, 0x20, 0x46, + 0xfb, 0xf7, 0x8b, 0xfc, 0x01, 0x35, 0x1f, 0xfa, 0x80, 0xf9, 0xed, 0xb2, + 0x45, 0x45, 0x20, 0x46, 0xee, 0xd3, 0x00, 0x21, 0xfd, 0xf7, 0x22, 0xfb, + 0x86, 0xf8, 0xc0, 0x92, 0xbd, 0xe8, 0xf8, 0x83, 0x2d, 0xe9, 0xf0, 0x43, + 0xb0, 0xf8, 0xda, 0x30, 0xd0, 0xf8, 0xa8, 0x50, 0x8b, 0xb0, 0x85, 0xf8, + 0xbc, 0x32, 0xd0, 0xf8, 0xb0, 0x30, 0x04, 0x46, 0xd3, 0xf8, 0x20, 0x31, + 0x03, 0xf0, 0x01, 0x03, 0x83, 0xf0, 0x01, 0x09, 0x53, 0xb1, 0xc3, 0x69, + 0xb8, 0x21, 0x18, 0x69, 0x42, 0xf2, 0x10, 0x72, 0x35, 0xf0, 0xc2, 0xdb, + 0xe3, 0x69, 0x18, 0x69, 0x35, 0xf0, 0xf0, 0xdb, 0x40, 0xf2, 0xa5, 0x41, + 0x20, 0x46, 0xf5, 0xf7, 0xe0, 0xfd, 0x00, 0xf4, 0xe0, 0x60, 0x07, 0x0a, + 0x20, 0x46, 0xf7, 0xf7, 0x72, 0xff, 0x00, 0x21, 0x80, 0x46, 0x20, 0x46, + 0xfc, 0xf7, 0xd0, 0xf8, 0x4f, 0xf4, 0x40, 0x41, 0x20, 0x46, 0xfc, 0xf7, + 0xcb, 0xf8, 0x20, 0x46, 0xfb, 0xf7, 0x6a, 0xfc, 0xd4, 0xf8, 0xa8, 0x30, + 0xd3, 0xf8, 0x48, 0x24, 0xd3, 0xf8, 0x44, 0x34, 0x40, 0x2b, 0xb4, 0xbf, + 0x19, 0x46, 0x40, 0x21, 0x8a, 0x42, 0x01, 0xdd, 0x93, 0xb2, 0x03, 0xe0, + 0x3f, 0x2b, 0xd4, 0xbf, 0x9b, 0xb2, 0x40, 0x23, 0xff, 0x22, 0x20, 0x46, + 0x40, 0xf2, 0xa7, 0x41, 0xf5, 0xf7, 0xa6, 0xff, 0x00, 0x23, 0x20, 0x46, + 0x40, 0xf2, 0xa5, 0x41, 0x4f, 0xf4, 0xe0, 0x62, 0xf5, 0xf7, 0x9e, 0xff, + 0x4f, 0xf4, 0x7a, 0x72, 0x32, 0x21, 0x20, 0x46, 0xff, 0xf7, 0x7b, 0xff, + 0x01, 0x21, 0x20, 0x46, 0x95, 0xf8, 0xc0, 0x62, 0xfd, 0xf7, 0xbc, 0xfa, + 0x20, 0x46, 0xf7, 0xf7, 0x60, 0xfb, 0x3b, 0x02, 0x20, 0x46, 0x40, 0xf2, + 0xa5, 0x41, 0x4f, 0xf4, 0xe0, 0x62, 0xf5, 0xf7, 0x87, 0xff, 0x00, 0x21, + 0x20, 0x46, 0xfc, 0xf7, 0x8d, 0xf8, 0x95, 0xf8, 0xc4, 0x72, 0x01, 0x2f, + 0x3a, 0xd1, 0x20, 0x46, 0x07, 0xa9, 0xfd, 0xf7, 0x2d, 0xfe, 0x39, 0x46, + 0x20, 0x46, 0xfa, 0xf7, 0x27, 0xfc, 0xd4, 0xf8, 0xa8, 0x30, 0xd3, 0xf8, + 0x48, 0x24, 0xd3, 0xf8, 0x44, 0x34, 0x3e, 0x2b, 0xb4, 0xbf, 0x19, 0x46, + 0x3e, 0x21, 0x8a, 0x42, 0x01, 0xdd, 0x93, 0xb2, 0x03, 0xe0, 0x3d, 0x2b, + 0xd4, 0xbf, 0x9b, 0xb2, 0x3e, 0x23, 0x20, 0x46, 0x40, 0xf2, 0xa7, 0x41, + 0xff, 0x22, 0xf5, 0xf7, 0x5f, 0xff, 0x00, 0x23, 0x20, 0x46, 0x40, 0xf2, + 0xa5, 0x41, 0x4f, 0xf4, 0xe0, 0x62, 0xf5, 0xf7, 0x57, 0xff, 0x20, 0x46, + 0x32, 0x21, 0x4f, 0xf4, 0x7a, 0x72, 0xff, 0xf7, 0x34, 0xff, 0x95, 0xf8, + 0xc0, 0x32, 0xdb, 0xb9, 0x95, 0xf8, 0xc2, 0x32, 0x20, 0x46, 0x04, 0x33, + 0x85, 0xf8, 0xc2, 0x32, 0x01, 0x21, 0xfa, 0xf7, 0xf5, 0xfb, 0x11, 0xe0, + 0x00, 0x21, 0x01, 0x23, 0xdb, 0x22, 0x8d, 0xf8, 0x24, 0x30, 0x03, 0x92, + 0x04, 0x93, 0x20, 0x46, 0x07, 0xaa, 0x0b, 0x46, 0x8d, 0xf8, 0x25, 0x60, + 0x00, 0x91, 0x01, 0x91, 0x02, 0x91, 0x05, 0x91, 0xfd, 0xf7, 0x96, 0xfa, + 0x20, 0x46, 0x41, 0x46, 0xfc, 0xf7, 0x38, 0xf8, 0x20, 0x46, 0x09, 0x49, + 0x04, 0x22, 0xf5, 0xf7, 0x3b, 0xff, 0xb9, 0xf1, 0x00, 0x0f, 0x03, 0xd1, + 0xe3, 0x69, 0x18, 0x69, 0x35, 0xf0, 0x28, 0xdb, 0x20, 0x46, 0x00, 0x21, + 0xfd, 0xf7, 0x48, 0xfa, 0x0b, 0xb0, 0xbd, 0xe8, 0xf0, 0x83, 0x00, 0xbf, + 0xba, 0xe7, 0x01, 0x00, 0x08, 0x29, 0x03, 0xd0, 0x0a, 0x29, 0x03, 0xd0, + 0x02, 0x29, 0x03, 0xd1, 0xff, 0xf7, 0x86, 0xb8, 0xff, 0xf7, 0x1a, 0xbf, + 0x70, 0x47, 0x10, 0xb5, 0x04, 0x46, 0xf7, 0xf7, 0xda, 0xfa, 0x20, 0x46, + 0x00, 0x21, 0xfc, 0xf7, 0x0f, 0xf8, 0x20, 0x46, 0x08, 0x21, 0xbd, 0xe8, + 0x10, 0x40, 0xff, 0xf7, 0xe7, 0xbf, 0x38, 0xb5, 0x00, 0xf5, 0x80, 0x53, + 0x93, 0xf8, 0x24, 0x30, 0x04, 0x46, 0xd0, 0xf8, 0xa8, 0x50, 0x13, 0xb9, + 0xf7, 0xf7, 0x36, 0xfe, 0xe0, 0xb1, 0xd4, 0xf8, 0xf8, 0x30, 0x59, 0x07, + 0x06, 0xd1, 0x94, 0xf8, 0xf5, 0x30, 0x1b, 0xb9, 0x20, 0x46, 0x09, 0x21, + 0xff, 0xf7, 0xd0, 0xff, 0xd4, 0xf8, 0xf8, 0x30, 0x1a, 0x07, 0x0d, 0xd1, + 0x04, 0xf5, 0x80, 0x52, 0x92, 0xf9, 0x2c, 0x20, 0x42, 0xb9, 0x1b, 0x06, + 0x06, 0xd4, 0x94, 0xf8, 0xf5, 0x30, 0x1b, 0xb9, 0x20, 0x46, 0x02, 0x21, + 0xff, 0xf7, 0xbe, 0xff, 0xd4, 0xf8, 0xf8, 0x30, 0x13, 0xf0, 0x0e, 0x0f, + 0x02, 0xd1, 0x20, 0x46, 0xfb, 0xf7, 0x92, 0xfc, 0xd4, 0xf8, 0xf8, 0x30, + 0x13, 0xf0, 0x06, 0x0f, 0x3e, 0xd1, 0xd5, 0xf8, 0x34, 0x24, 0x4a, 0xb3, + 0xe3, 0x69, 0xd5, 0xf8, 0x38, 0x14, 0x18, 0x6a, 0x41, 0x1a, 0x91, 0x42, + 0x34, 0xd3, 0x6a, 0x21, 0x18, 0x69, 0x35, 0xf0, 0x85, 0xda, 0x41, 0x00, + 0x89, 0xb2, 0xb1, 0xb1, 0xe3, 0x69, 0x18, 0x69, 0x35, 0xf0, 0x7e, 0xda, + 0x88, 0xb9, 0x40, 0xf2, 0x76, 0x41, 0x20, 0x46, 0xf5, 0xf7, 0xbd, 0xfc, + 0xc0, 0x05, 0xc0, 0x0d, 0xa5, 0xf8, 0x6c, 0x05, 0x40, 0xf2, 0x77, 0x41, + 0x20, 0x46, 0xf5, 0xf7, 0xb4, 0xfc, 0xc0, 0x05, 0xc0, 0x0d, 0xa5, 0xf8, + 0x6e, 0x05, 0x20, 0x46, 0x00, 0x21, 0xf9, 0xf7, 0x36, 0xf9, 0x11, 0xe0, + 0x40, 0xf2, 0x76, 0x41, 0x20, 0x46, 0xf5, 0xf7, 0xa6, 0xfc, 0xc0, 0x05, + 0xc0, 0x0d, 0xa5, 0xf8, 0x6c, 0x05, 0x40, 0xf2, 0x77, 0x41, 0x20, 0x46, + 0xf5, 0xf7, 0x9d, 0xfc, 0xc0, 0x05, 0xc0, 0x0d, 0xa5, 0xf8, 0x6e, 0x05, + 0x20, 0x46, 0xf7, 0xf7, 0x2e, 0xfe, 0xb0, 0xf5, 0x40, 0x4f, 0x0b, 0xd0, + 0x20, 0x46, 0xfb, 0xf7, 0x0a, 0xfb, 0x20, 0xb1, 0x00, 0x23, 0x7f, 0x28, + 0x85, 0xf8, 0x56, 0x34, 0x02, 0xd0, 0x00, 0x23, 0x85, 0xf8, 0x57, 0x34, + 0x38, 0xbd, 0x00, 0x00, 0x2d, 0xe9, 0xf0, 0x41, 0x5f, 0xfa, 0x81, 0xf8, + 0x04, 0x46, 0xd0, 0xf8, 0xa8, 0x50, 0x40, 0x46, 0x0e, 0x46, 0xf6, 0xf7, + 0x33, 0xf9, 0x31, 0x46, 0x07, 0x46, 0x20, 0x46, 0xf6, 0xf7, 0x13, 0xf9, + 0x20, 0x46, 0xb4, 0xf8, 0xda, 0x10, 0xf9, 0xf7, 0x95, 0xfe, 0x04, 0x22, + 0x20, 0x46, 0x5b, 0x49, 0xf5, 0xf7, 0x6e, 0xfe, 0x41, 0x46, 0x20, 0x46, + 0xff, 0xf7, 0x2a, 0xf9, 0x0a, 0x20, 0xeb, 0xf3, 0x51, 0xf2, 0x4f, 0xf4, + 0x00, 0x42, 0x13, 0x46, 0x4f, 0xf4, 0x89, 0x61, 0x20, 0x46, 0xf5, 0xf7, + 0x4d, 0xfe, 0x20, 0x46, 0xf8, 0xf7, 0x0e, 0xfa, 0x78, 0x00, 0x05, 0x21, + 0x00, 0x22, 0xf7, 0xf7, 0x33, 0xfc, 0x39, 0x46, 0x00, 0x22, 0x80, 0x46, + 0x4f, 0xf4, 0x20, 0x10, 0xf7, 0xf7, 0x2c, 0xfc, 0x40, 0xf2, 0x57, 0x61, + 0x07, 0x46, 0x1f, 0xfa, 0x88, 0xf2, 0x20, 0x46, 0xf5, 0xf7, 0x50, 0xfc, + 0x20, 0x46, 0x4f, 0xf4, 0xcb, 0x61, 0xba, 0xb2, 0xf5, 0xf7, 0x4a, 0xfc, + 0x4f, 0xf4, 0x00, 0x73, 0x20, 0x46, 0x4f, 0xf4, 0x89, 0x61, 0x4f, 0xf4, + 0x40, 0x72, 0xf5, 0xf7, 0x27, 0xfe, 0x94, 0xf8, 0xda, 0x30, 0x0e, 0x2b, + 0x07, 0xd0, 0xb5, 0xf8, 0x62, 0x20, 0x13, 0xb2, 0xb3, 0xf1, 0xff, 0x3f, + 0x08, 0xbf, 0x15, 0x22, 0x00, 0xe0, 0x1e, 0x22, 0xa5, 0xf8, 0x40, 0x25, + 0x20, 0x46, 0x00, 0x21, 0x12, 0xb2, 0xfa, 0xf7, 0xa3, 0xf8, 0x20, 0xb1, + 0x20, 0x46, 0x00, 0x21, 0x14, 0x22, 0xfa, 0xf7, 0x9d, 0xf8, 0x94, 0xf8, + 0xda, 0x30, 0x38, 0x22, 0x0e, 0x2b, 0x0c, 0xbf, 0x18, 0x23, 0x00, 0x23, + 0x20, 0x46, 0x40, 0xf2, 0xeb, 0x41, 0xf5, 0xf7, 0x01, 0xfe, 0xb4, 0xf8, + 0xda, 0x30, 0x20, 0x46, 0x03, 0xf4, 0x70, 0x43, 0xb3, 0xf5, 0x00, 0x5f, + 0x0c, 0xbf, 0xb5, 0xf8, 0x66, 0x20, 0xb5, 0xf8, 0x68, 0x20, 0x01, 0x21, + 0x13, 0xb2, 0xb3, 0xf1, 0xff, 0x3f, 0x08, 0xbf, 0x02, 0x22, 0xa5, 0xf8, + 0x3e, 0x25, 0x12, 0xb2, 0xfa, 0xf7, 0x7a, 0xf8, 0x18, 0x22, 0x20, 0x46, + 0x20, 0x49, 0xf5, 0xf7, 0xf7, 0xfd, 0x20, 0x46, 0xf7, 0xf7, 0x48, 0xfb, + 0xb4, 0xf8, 0xda, 0x20, 0x95, 0xf8, 0xbc, 0x32, 0xd2, 0xb2, 0x80, 0xb1, + 0x0e, 0x2b, 0x02, 0xd9, 0x0e, 0x2a, 0x05, 0xd9, 0x01, 0xe0, 0x0e, 0x2a, + 0x02, 0xd8, 0x20, 0x46, 0x01, 0x21, 0x01, 0xe0, 0x20, 0x46, 0x00, 0x21, + 0x32, 0x46, 0xbd, 0xe8, 0xf0, 0x41, 0xfc, 0xf7, 0xe5, 0xbf, 0x93, 0x42, + 0x20, 0x46, 0x01, 0xd1, 0x01, 0x2b, 0x03, 0xd1, 0x08, 0x21, 0xff, 0xf7, + 0xab, 0xfe, 0x01, 0xe0, 0xfc, 0xf7, 0xbe, 0xff, 0x00, 0x21, 0x0a, 0x46, + 0x20, 0x46, 0xfb, 0xf7, 0xc5, 0xf8, 0x20, 0x46, 0xfe, 0xf7, 0xd5, 0xff, + 0x20, 0x46, 0x01, 0x21, 0xff, 0xf7, 0x53, 0xfc, 0x04, 0xf5, 0x82, 0x53, + 0x1b, 0x79, 0x2b, 0xb1, 0x20, 0x46, 0x03, 0x21, 0xbd, 0xe8, 0xf0, 0x41, + 0xfb, 0xf7, 0x57, 0xbd, 0xbd, 0xe8, 0xf0, 0x81, 0x72, 0xe6, 0x01, 0x00, + 0x7a, 0xe6, 0x01, 0x00, 0x80, 0x68, 0xf4, 0xf3, 0x31, 0xb1, 0x00, 0x00, + 0x30, 0xb5, 0x84, 0x88, 0x04, 0xf0, 0x03, 0x03, 0x01, 0x2b, 0x08, 0xd0, + 0x02, 0x2b, 0x0c, 0xd0, 0x00, 0x2b, 0x2b, 0xd1, 0x08, 0x78, 0x05, 0x23, + 0xb0, 0xfb, 0xf3, 0xf0, 0x30, 0xbd, 0x0b, 0x78, 0x14, 0x4a, 0x03, 0xf0, + 0x07, 0x03, 0xd0, 0x5c, 0x30, 0xbd, 0x0d, 0x78, 0xcb, 0x78, 0x08, 0x79, + 0x05, 0xf0, 0x7f, 0x02, 0x29, 0x06, 0x43, 0xea, 0x00, 0x20, 0x42, 0xf0, + 0x00, 0x63, 0x02, 0xd5, 0x43, 0xf4, 0x80, 0x63, 0x05, 0xe0, 0xa1, 0x06, + 0x44, 0xbf, 0x42, 0xf0, 0x00, 0x63, 0x43, 0xf4, 0x40, 0x73, 0x01, 0x06, + 0x48, 0xbf, 0x43, 0xf4, 0x00, 0x03, 0x42, 0x06, 0x48, 0xbf, 0x43, 0xf4, + 0x80, 0x03, 0x00, 0xf0, 0x30, 0x00, 0x43, 0xea, 0x00, 0x40, 0x30, 0xbd, + 0x4f, 0xf4, 0x00, 0x70, 0x30, 0xbd, 0x00, 0xbf, 0xce, 0xe4, 0x01, 0x00, + 0x70, 0xb5, 0x86, 0x68, 0x04, 0x46, 0xd4, 0xf8, 0xf8, 0x11, 0xb0, 0x68, + 0xf4, 0xf3, 0xda, 0xf0, 0xff, 0x23, 0x84, 0xf8, 0xe2, 0x31, 0x4f, 0xf0, + 0xff, 0x33, 0xa3, 0x61, 0x23, 0x68, 0x00, 0x22, 0x9a, 0x71, 0x33, 0x6b, + 0x02, 0x21, 0x05, 0x46, 0x18, 0x69, 0xf5, 0xf7, 0x65, 0xff, 0x20, 0x46, + 0x38, 0xf0, 0xdc, 0xdb, 0xd5, 0xf1, 0x01, 0x00, 0x38, 0xbf, 0x00, 0x20, + 0x70, 0xbd, 0x38, 0xb5, 0x0b, 0x68, 0x04, 0x46, 0x0d, 0x46, 0x73, 0xb1, + 0xd3, 0xf8, 0x7c, 0x11, 0x29, 0xb1, 0x03, 0x68, 0x40, 0xf2, 0x0c, 0x72, + 0xd8, 0x68, 0xeb, 0xf3, 0xff, 0xf3, 0x23, 0x68, 0x29, 0x68, 0xd8, 0x68, + 0x62, 0x69, 0xeb, 0xf3, 0xf9, 0xf3, 0x23, 0x68, 0x29, 0x46, 0xd8, 0x68, + 0x10, 0x22, 0xbd, 0xe8, 0x38, 0x40, 0xeb, 0xf3, 0xf1, 0xb3, 0x03, 0x68, + 0x70, 0xb5, 0x10, 0x21, 0x05, 0x46, 0xd8, 0x68, 0xeb, 0xf3, 0xda, 0xf3, + 0x04, 0x46, 0xa0, 0xb1, 0x2b, 0x68, 0x69, 0x69, 0xd8, 0x68, 0xeb, 0xf3, + 0xd3, 0xf3, 0x06, 0x46, 0x20, 0x60, 0x28, 0xb9, 0x21, 0x46, 0x28, 0x46, + 0xff, 0xf7, 0xcf, 0xff, 0x34, 0x46, 0x06, 0xe0, 0x00, 0x23, 0xc0, 0xf8, + 0x7c, 0x31, 0x21, 0x46, 0x28, 0x46, 0x39, 0xf0, 0xa5, 0xdc, 0x20, 0x46, + 0x70, 0xbd, 0x37, 0xb5, 0x05, 0x46, 0x01, 0xa9, 0xd0, 0xf8, 0x00, 0x05, + 0x39, 0xf0, 0xbc, 0xdd, 0x09, 0xe0, 0x28, 0x46, 0x21, 0x46, 0x3a, 0xf0, + 0x17, 0xd8, 0x63, 0x6c, 0x1b, 0xb9, 0x28, 0x46, 0x21, 0x46, 0x3a, 0xf0, + 0x27, 0xd9, 0x01, 0xa8, 0x39, 0xf0, 0xb6, 0xdd, 0x04, 0x46, 0x00, 0x28, + 0xef, 0xd1, 0x3e, 0xbd, 0xf8, 0xb5, 0xd0, 0xf8, 0x98, 0x43, 0x0f, 0x46, + 0xe3, 0x88, 0xfb, 0xb1, 0x0b, 0x88, 0x07, 0x2b, 0x1c, 0xd9, 0xa2, 0x88, + 0x9a, 0x42, 0x1c, 0xd1, 0x0e, 0x1d, 0x30, 0x46, 0x04, 0xf1, 0x08, 0x01, + 0xe6, 0xf3, 0xe6, 0xf5, 0x50, 0xb1, 0x11, 0xe0, 0x63, 0x19, 0x30, 0x46, + 0x0a, 0x49, 0x93, 0xf8, 0x48, 0x20, 0xe6, 0xf3, 0x99, 0xf5, 0x01, 0x35, + 0x36, 0x18, 0x00, 0xe0, 0x05, 0x46, 0xe3, 0x88, 0x9d, 0x42, 0xf1, 0xdb, + 0x40, 0x23, 0x3b, 0x80, 0x00, 0x20, 0xf8, 0xbd, 0x4f, 0xf0, 0xff, 0x30, + 0xf8, 0xbd, 0x4f, 0xf0, 0xff, 0x30, 0xf8, 0xbd, 0xf4, 0x30, 0x86, 0x00, + 0x2d, 0xe9, 0xf3, 0x47, 0x88, 0x46, 0x15, 0x46, 0x00, 0x28, 0x58, 0xd0, + 0x00, 0x29, 0x56, 0xd0, 0x0a, 0x88, 0xd0, 0xf8, 0x04, 0xa0, 0xd0, 0xf8, + 0x98, 0x73, 0xd0, 0xf8, 0x94, 0x63, 0x00, 0x2a, 0x48, 0xd0, 0xb1, 0xf8, + 0x02, 0x90, 0x00, 0x24, 0x19, 0xf0, 0x01, 0x09, 0xfc, 0x80, 0xbc, 0x80, + 0x24, 0xd0, 0x40, 0x2a, 0x13, 0xd1, 0x04, 0x31, 0x38, 0x46, 0x23, 0x46, + 0x00, 0x94, 0x3d, 0xf0, 0x7d, 0xde, 0xa0, 0x42, 0x38, 0xdb, 0xb6, 0xf8, + 0x02, 0x21, 0x12, 0xf0, 0x40, 0x02, 0x31, 0xd0, 0x00, 0x2d, 0x37, 0xd0, + 0xda, 0xf8, 0x0c, 0x00, 0x3c, 0xf0, 0x12, 0xde, 0x33, 0xe0, 0xa2, 0xf1, + 0x08, 0x03, 0x9b, 0xb2, 0x37, 0x2b, 0x27, 0xd8, 0x07, 0xf1, 0x08, 0x00, + 0x04, 0x31, 0xe6, 0xf3, 0x95, 0xf4, 0xb8, 0xf8, 0x00, 0x80, 0xa7, 0xf8, + 0x04, 0x80, 0x24, 0xe0, 0x20, 0x2a, 0x1e, 0xd8, 0x04, 0x31, 0x07, 0xf1, + 0x48, 0x00, 0xe6, 0xf3, 0x89, 0xf4, 0xb6, 0xf8, 0x02, 0x41, 0xb8, 0xf8, + 0x00, 0x80, 0x01, 0x23, 0x14, 0xf0, 0x40, 0x04, 0xa7, 0xf8, 0x04, 0x90, + 0xa7, 0xf8, 0x06, 0x80, 0xc6, 0xf8, 0xcc, 0x30, 0x0f, 0xd0, 0x6d, 0xb1, + 0xda, 0xf8, 0x0c, 0x00, 0x3c, 0xf0, 0xe8, 0xdd, 0x4c, 0x46, 0x08, 0xe0, + 0x14, 0x46, 0x06, 0xe0, 0x4f, 0xf0, 0xff, 0x34, 0x03, 0xe0, 0x6f, 0xf0, + 0x01, 0x04, 0x00, 0xe0, 0x2c, 0x46, 0x20, 0x46, 0xbd, 0xe8, 0xfc, 0x87, + 0x10, 0xb5, 0x0d, 0xf0, 0x79, 0xfa, 0x04, 0x46, 0xf1, 0xf7, 0x36, 0xf9, + 0x20, 0x46, 0xbd, 0xe8, 0x10, 0x40, 0xea, 0xf3, 0x5b, 0xb6, 0xaa, 0xaa, + 0x03, 0x00, 0x19, 0x58, 0x00, 0x00, 0x10, 0x18, 0x00, 0x00, 0x0f, 0xac, + 0x00, 0x00, 0x14, 0x72, 0x00, 0x00, 0x50, 0xf2, 0x00, 0x00, 0x40, 0x96, + 0x00, 0x00, 0x50, 0xf2, 0x01, 0x00, 0x00, 0x50, 0xf2, 0x02, 0x00, 0x00, + 0x00, 0x50, 0xf2, 0x02, 0x01, 0x00, 0x00, 0x90, 0x4c, 0x00, 0xaa, 0xaa, + 0x03, 0x00, 0x19, 0x58, 0x00, 0x00, 0x50, 0xf2, 0x02, 0x01, 0x01, 0x00, + 0x00, 0x03, 0x64, 0x00, 0x00, 0x27, 0xa4, 0x00, 0x00, 0x41, 0x43, 0x5e, + 0x00, 0x61, 0x32, 0x2f, 0x00, 0x00, 0x50, 0xf2, 0x04, 0x00, 0x00, 0x50, + 0xf2, 0x00, 0x00, 0x0f, 0xac, 0x00, 0x00, 0x14, 0x72, 0x00, 0x00, 0x01, + 0xaf, 0x81, 0x01, 0x00, 0x00, 0x10, 0x18, 0x00, 0x00, 0x50, 0xf2, 0x00, + 0x00, 0x0f, 0xac, 0x00, 0x00, 0x40, 0x96, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x10, 0x18, 0x00, 0x00, 0x0c, 0x0b, 0x12, 0x0f, 0x18, 0x0a, + 0x24, 0x0e, 0x30, 0x09, 0x48, 0x0d, 0x60, 0x08, 0x6c, 0x0c, 0x0c, 0x12, + 0x18, 0x24, 0x30, 0x48, 0x60, 0x6c, 0x5e, 0x00, 0x60, 0x00, 0x62, 0x00, + 0x78, 0x00, 0xd4, 0x00, 0x09, 0x2f, 0x16, 0x0e, 0x0e, 0x05, 0x69, 0x6c, + 0x30, 0x6d, 0x61, 0x63, 0x61, 0x64, 0x64, 0x72, 0x3d, 0x30, 0x30, 0x3a, + 0x31, 0x31, 0x3a, 0x32, 0x32, 0x3a, 0x33, 0x33, 0x3a, 0x34, 0x34, 0x3a, + 0x35, 0x35, 0x00, 0x62, 0x6f, 0x61, 0x72, 0x64, 0x74, 0x79, 0x70, 0x65, + 0x3d, 0x30, 0x78, 0x66, 0x66, 0x66, 0x66, 0x00, 0x62, 0x6f, 0x61, 0x72, + 0x64, 0x72, 0x65, 0x76, 0x3d, 0x30, 0x78, 0x31, 0x30, 0x00, 0x62, 0x6f, + 0x61, 0x72, 0x64, 0x66, 0x6c, 0x61, 0x67, 0x73, 0x3d, 0x38, 0x00, 0x61, + 0x61, 0x30, 0x3d, 0x33, 0x00, 0x73, 0x72, 0x6f, 0x6d, 0x72, 0x65, 0x76, + 0x3d, 0x32, 0x00, 0x00, 0x0f, 0xac, 0x00, 0x00, 0x50, 0xf2, 0x00, 0xaa, + 0xaa, 0x03, 0x00, 0x19, 0x58, 0x00, 0xcc, 0x01, 0x02, 0x00, 0x00, 0x00, + 0xd4, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, + 0x00, 0x00, 0x6e, 0x84, 0x0b, 0x00, 0x00, 0x00, 0xd4, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x0c, 0x12, + 0x18, 0x24, 0x30, 0x48, 0x60, 0x6c, 0x00, 0x00, 0x10, 0x09, 0x1e, 0x09, + 0x1f, 0x09, 0x24, 0x09, 0x25, 0x09, 0x26, 0x09, 0x20, 0x09, 0x21, 0x09, + 0x27, 0x09, 0x28, 0x09, 0x29, 0x09, 0x22, 0x09, 0x23, 0x09, 0x30, 0x09, + 0x31, 0x09, 0x32, 0x09, 0x12, 0x09, 0x0f, 0x09, 0x00, 0x09, 0x01, 0x09, + 0x06, 0x09, 0x07, 0x09, 0x08, 0x09, 0x02, 0x09, 0x03, 0x09, 0x09, 0x09, + 0x0a, 0x09, 0x0b, 0x09, 0x04, 0x09, 0x05, 0x09, 0x0c, 0x09, 0x0d, 0x09, + 0x0e, 0x09, 0x11, 0x09, 0x00, 0xfc, 0x07, 0x00, 0x69, 0xa5, 0x05, 0x00, + 0xff, 0x01, 0x00, 0x00, 0x69, 0x5d, 0x0a, 0x00, 0x00, 0x04, 0x08, 0x00, + 0x97, 0x5e, 0x0a, 0x00, 0x01, 0x02, 0x00, 0x00, 0x97, 0xa6, 0x05, 0x00, + 0x06, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, + 0x06, 0x00, 0x00, 0x00, 0x0e, 0x00, 0x00, 0x00, 0x0e, 0x00, 0x00, 0x00, + 0x0e, 0x00, 0x00, 0x00, 0x0e, 0x00, 0x00, 0x00, 0x16, 0x01, 0x2d, 0x01, + 0x2c, 0x01, 0x6a, 0x00, 0x98, 0x00, 0x97, 0x00, 0x2f, 0x01, 0x0b, 0x00, + 0x13, 0x01, 0x1d, 0x00, 0x14, 0x01, 0x2e, 0x00, 0x2a, 0x01, 0x09, 0x00, + 0x1f, 0x01, 0x07, 0x00, 0xff, 0x00, 0x05, 0x00, 0x21, 0x84, 0x23, 0x84, + 0x34, 0x83, 0x84, 0x80, 0x67, 0x82, 0x56, 0x80, 0x34, 0x82, 0x84, 0x80, + 0x67, 0x82, 0x56, 0x80, 0x34, 0x82, 0x97, 0x7a, 0x97, 0x7a, 0x97, 0x7a, + 0x97, 0x7a, 0x87, 0x7a, 0x87, 0x7a, 0x97, 0x7b, 0x97, 0x7a, 0x87, 0x7a, + 0x87, 0x7a, 0x97, 0x7b, 0xff, 0xee, 0xdd, 0xcc, 0xbb, 0x99, 0x88, 0x77, + 0x66, 0x55, 0x44, 0x33, 0x22, 0x11, 0x00, 0x00, 0x59, 0x4d, 0x80, 0x00, + 0x95, 0x57, 0x80, 0x00, 0x49, 0x58, 0x80, 0x00, 0x31, 0x56, 0x80, 0x00, + 0x0d, 0x5a, 0x80, 0x00, 0xc1, 0x58, 0x80, 0x00, 0x29, 0x5a, 0x80, 0x00, + 0x45, 0x5a, 0x80, 0x00, 0x79, 0x57, 0x80, 0x00, 0x4d, 0x56, 0x80, 0x00, + 0x75, 0x5a, 0x80, 0x00, 0x25, 0x55, 0x80, 0x00, 0xf1, 0x59, 0x80, 0x00, + 0x0d, 0x58, 0x80, 0x00, 0x69, 0x54, 0x80, 0x00, 0xc1, 0x4e, 0x80, 0x00, + 0xe9, 0x51, 0x80, 0x00, 0x55, 0x52, 0x80, 0x00, 0xc9, 0x51, 0x80, 0x00, + 0xdd, 0x58, 0x80, 0x00, 0x51, 0x51, 0x80, 0x00, 0xd1, 0x55, 0x80, 0x00, + 0xa5, 0x55, 0x80, 0x00, 0x15, 0x56, 0x80, 0x00, 0xe1, 0x4f, 0x80, 0x00, + 0x89, 0x55, 0x80, 0x00, 0xfd, 0x4e, 0x80, 0x00, 0x25, 0x50, 0x80, 0x00, + 0x0d, 0x03, 0x01, 0x00, 0xed, 0x4d, 0x80, 0x00, 0x85, 0x4e, 0x80, 0x00, + 0xa9, 0x4f, 0x80, 0x00, 0xd9, 0x4d, 0x80, 0x00, 0x09, 0x4e, 0x80, 0x00, + 0x51, 0x4c, 0x80, 0x00, 0x65, 0x4c, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xc1, 0x4f, 0x80, 0x00, + 0x25, 0x52, 0x80, 0x00, 0xf9, 0x51, 0x80, 0x00, 0xc7, 0x28, 0x00, 0x00, + 0x28, 0x00, 0x00, 0x00, 0x73, 0x64, 0x5f, 0x6c, 0x65, 0x76, 0x65, 0x6c, + 0x5f, 0x74, 0x72, 0x69, 0x67, 0x67, 0x65, 0x72, 0x00, 0x73, 0x70, 0x69, + 0x5f, 0x70, 0x75, 0x5f, 0x65, 0x6e, 0x61, 0x62, 0x00, 0x61, 0x72, 0x70, + 0x5f, 0x6d, 0x61, 0x63, 0x61, 0x64, 0x64, 0x72, 0x00, 0x61, 0x72, 0x70, + 0x5f, 0x72, 0x65, 0x6d, 0x6f, 0x74, 0x65, 0x69, 0x70, 0x00, 0x00, 0x00, + 0xf8, 0x3b, 0x86, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0x00, 0x00, 0x00, + 0xff, 0x3b, 0x86, 0x00, 0x01, 0x00, 0x00, 0x00, 0x07, 0x00, 0x00, 0x00, + 0x0b, 0x3c, 0x86, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x1b, 0x3c, 0x86, 0x00, 0x03, 0x00, 0x00, 0x00, 0x07, 0x00, 0x00, 0x00, + 0x26, 0x3c, 0x86, 0x00, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x37, 0x3c, 0x86, 0x00, 0x05, 0x00, 0x00, 0x00, 0x08, 0x00, 0x30, 0x00, + 0x41, 0x3c, 0x86, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0xb1, 0xb9, 0x01, 0x00, 0x08, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, + 0xbd, 0xb9, 0x01, 0x00, 0x09, 0x00, 0x00, 0x00, 0x07, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x70, 0x66, 0x6e, 0x5f, 0x73, 0x75, 0x73, 0x70, 0x65, 0x6e, 0x64, 0x00, + 0x58, 0x40, 0x86, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, 0x14, 0x00, + 0x60, 0x40, 0x86, 0x00, 0x01, 0x00, 0x00, 0x00, 0x08, 0x00, 0x88, 0x00, + 0x68, 0x40, 0x86, 0x00, 0x02, 0x00, 0x00, 0x00, 0x08, 0x00, 0x38, 0x00, + 0x70, 0x40, 0x86, 0x00, 0x03, 0x00, 0x00, 0x00, 0x08, 0x00, 0x08, 0x00, + 0x7e, 0x40, 0x86, 0x00, 0x04, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, + 0x82, 0x40, 0x86, 0x00, 0x05, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x8b, 0x40, 0x86, 0x00, 0x06, 0x00, 0x00, 0x00, 0x08, 0x00, 0x38, 0x00, + 0x44, 0xba, 0x01, 0x00, 0x07, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x35, 0x2e, 0x39, 0x30, 0x2e, 0x32, 0x33, 0x30, 0x2e, 0x31, 0x32, 0x00, + 0x77, 0x6c, 0x25, 0x64, 0x3a, 0x20, 0x25, 0x73, 0x20, 0x25, 0x73, 0x20, + 0x76, 0x65, 0x72, 0x73, 0x69, 0x6f, 0x6e, 0x20, 0x25, 0x73, 0x20, 0x46, + 0x57, 0x49, 0x44, 0x20, 0x30, 0x31, 0x2d, 0x25, 0x78, 0x0a, 0x00, 0x4e, + 0x6f, 0x76, 0x20, 0x20, 0x37, 0x20, 0x32, 0x30, 0x31, 0x34, 0x00, 0x31, + 0x36, 0x3a, 0x30, 0x33, 0x3a, 0x34, 0x35, 0x00, 0x5c, 0x78, 0x25, 0x30, + 0x32, 0x58, 0x00, 0x77, 0x6c, 0x63, 0x5f, 0x69, 0x6f, 0x76, 0x61, 0x72, + 0x73, 0x32, 0x00, 0x72, 0x73, 0x73, 0x69, 0x5f, 0x6f, 0x66, 0x66, 0x73, + 0x65, 0x74, 0x00, 0x50, 0x5a, 0x44, 0x3a, 0x20, 0x25, 0x64, 0x3e, 0x25, + 0x64, 0x20, 0x6f, 0x72, 0x20, 0x25, 0x64, 0x3e, 0x25, 0x64, 0x20, 0x61, + 0x3d, 0x25, 0x64, 0x0a, 0x00, 0x6c, 0x6f, 0x77, 0x5f, 0x72, 0x73, 0x73, + 0x69, 0x5f, 0x74, 0x72, 0x69, 0x67, 0x67, 0x65, 0x72, 0x00, 0x6c, 0x6f, + 0x77, 0x5f, 0x72, 0x73, 0x73, 0x69, 0x5f, 0x64, 0x75, 0x72, 0x61, 0x74, + 0x69, 0x6f, 0x6e, 0x00, 0x74, 0x63, 0x5f, 0x65, 0x6e, 0x61, 0x62, 0x6c, + 0x65, 0x00, 0x74, 0x63, 0x5f, 0x70, 0x65, 0x72, 0x69, 0x6f, 0x64, 0x00, + 0x74, 0x63, 0x5f, 0x68, 0x69, 0x5f, 0x77, 0x6d, 0x00, 0x74, 0x63, 0x5f, + 0x6c, 0x6f, 0x5f, 0x77, 0x6d, 0x00, 0x74, 0x63, 0x5f, 0x73, 0x74, 0x61, + 0x74, 0x75, 0x73, 0x00, 0x61, 0x73, 0x73, 0x6f, 0x63, 0x5f, 0x73, 0x74, + 0x61, 0x74, 0x65, 0x00, 0x64, 0x79, 0x6e, 0x74, 0x78, 0x00, 0x74, 0x78, + 0x5f, 0x73, 0x74, 0x61, 0x74, 0x5f, 0x63, 0x68, 0x6b, 0x00, 0x74, 0x78, + 0x5f, 0x73, 0x74, 0x61, 0x74, 0x5f, 0x63, 0x68, 0x6b, 0x5f, 0x70, 0x72, + 0x64, 0x00, 0x74, 0x78, 0x5f, 0x73, 0x74, 0x61, 0x74, 0x5f, 0x63, 0x68, + 0x6b, 0x5f, 0x72, 0x61, 0x74, 0x69, 0x6f, 0x00, 0x74, 0x78, 0x5f, 0x73, + 0x74, 0x61, 0x74, 0x5f, 0x63, 0x68, 0x6b, 0x5f, 0x6e, 0x75, 0x6d, 0x00, + 0x72, 0x78, 0x5f, 0x72, 0x61, 0x74, 0x65, 0x00, 0x69, 0x73, 0x5f, 0x57, + 0x50, 0x53, 0x5f, 0x65, 0x6e, 0x72, 0x6f, 0x6c, 0x6c, 0x65, 0x65, 0x00, + 0x69, 0x73, 0x5f, 0x77, 0x70, 0x73, 0x5f, 0x65, 0x6e, 0x72, 0x6f, 0x6c, + 0x6c, 0x65, 0x65, 0x00, 0x13, 0xbb, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00, + 0x06, 0x00, 0x00, 0x00, 0x39, 0xbb, 0x01, 0x00, 0x02, 0x00, 0x00, 0x00, + 0x06, 0x00, 0x00, 0x00, 0x4a, 0xbb, 0x01, 0x00, 0x03, 0x00, 0x00, 0x00, + 0x06, 0x00, 0x00, 0x00, 0x5c, 0xbb, 0x01, 0x00, 0x04, 0x00, 0x00, 0x00, + 0x06, 0x00, 0x00, 0x00, 0x66, 0xbb, 0x01, 0x00, 0x05, 0x00, 0x00, 0x00, + 0x06, 0x00, 0x00, 0x00, 0x70, 0xbb, 0x01, 0x00, 0x06, 0x00, 0x00, 0x00, + 0x06, 0x00, 0x00, 0x00, 0x79, 0xbb, 0x01, 0x00, 0x07, 0x00, 0x00, 0x00, + 0x06, 0x00, 0x00, 0x00, 0x82, 0xbb, 0x01, 0x00, 0x08, 0x00, 0x00, 0x00, + 0x06, 0x00, 0x00, 0x00, 0x8c, 0xbb, 0x01, 0x00, 0x09, 0x00, 0x00, 0x00, + 0x06, 0x00, 0x00, 0x00, 0x98, 0xbb, 0x01, 0x00, 0x0a, 0x00, 0x00, 0x00, + 0x06, 0x00, 0x00, 0x00, 0x9e, 0xbb, 0x01, 0x00, 0x0b, 0x00, 0x00, 0x00, + 0x06, 0x00, 0x00, 0x00, 0xaa, 0xbb, 0x01, 0x00, 0x0c, 0x00, 0x00, 0x00, + 0x06, 0x00, 0x00, 0x00, 0xba, 0xbb, 0x01, 0x00, 0x0d, 0x00, 0x00, 0x00, + 0x06, 0x00, 0x00, 0x00, 0xcc, 0xbb, 0x01, 0x00, 0x0e, 0x00, 0x00, 0x00, + 0x06, 0x00, 0x00, 0x00, 0xdc, 0xbb, 0x01, 0x00, 0x0f, 0x00, 0x00, 0x00, + 0x06, 0x00, 0x00, 0x00, 0xe4, 0xbb, 0x01, 0x00, 0x10, 0x00, 0x00, 0x00, + 0x01, 0x00, 0x00, 0x00, 0xf4, 0xbb, 0x01, 0x00, 0x10, 0x00, 0x00, 0x00, + 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x05, 0xa5, 0x81, 0x00, 0xfd, 0xa5, 0x81, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0d, 0xcd, 0x82, 0x00, + 0x89, 0xe6, 0x82, 0x00, 0xf5, 0xcb, 0x82, 0x00, 0xed, 0xcc, 0x82, 0x00, + 0x77, 0x6c, 0x63, 0x5f, 0x61, 0x6d, 0x70, 0x64, 0x75, 0x5f, 0x72, 0x65, + 0x63, 0x76, 0x5f, 0x61, 0x64, 0x64, 0x62, 0x61, 0x5f, 0x72, 0x65, 0x71, + 0x5f, 0x70, 0x72, 0x65, 0x5f, 0x70, 0x61, 0x74, 0x63, 0x68, 0x00, 0x77, + 0x6c, 0x63, 0x5f, 0x61, 0x6d, 0x70, 0x64, 0x75, 0x5f, 0x72, 0x65, 0x73, + 0x74, 0x61, 0x72, 0x74, 0x00, 0x73, 0x74, 0x72, 0x61, 0x6e, 0x67, 0x65, + 0x20, 0x63, 0x61, 0x73, 0x65, 0x2e, 0x2e, 0x2e, 0x72, 0x65, 0x6c, 0x65, + 0x61, 0x73, 0x65, 0x20, 0x69, 0x73, 0x20, 0x25, 0x64, 0x2c, 0x20, 0x64, + 0x65, 0x6c, 0x74, 0x61, 0x20, 0x25, 0x64, 0x2c, 0x20, 0x69, 0x6e, 0x69, + 0x2d, 0x3e, 0x72, 0x65, 0x6d, 0x5f, 0x77, 0x69, 0x6e, 0x64, 0x6f, 0x77, + 0x20, 0x25, 0x64, 0x0a, 0x00, 0x25, 0x73, 0x3a, 0x20, 0x61, 0x6d, 0x70, + 0x64, 0x75, 0x2d, 0x3e, 0x6d, 0x61, 0x78, 0x5f, 0x70, 0x64, 0x75, 0x3d, + 0x25, 0x64, 0x2c, 0x20, 0x61, 0x6d, 0x70, 0x64, 0x75, 0x2d, 0x3e, 0x62, + 0x61, 0x5f, 0x74, 0x78, 0x5f, 0x77, 0x73, 0x69, 0x7a, 0x65, 0x3d, 0x25, + 0x64, 0x2c, 0x20, 0x61, 0x6d, 0x70, 0x64, 0x75, 0x2d, 0x3e, 0x62, 0x61, + 0x5f, 0x72, 0x78, 0x5f, 0x77, 0x73, 0x69, 0x7a, 0x65, 0x3d, 0x25, 0x64, + 0x0a, 0x00, 0x25, 0x73, 0x3a, 0x20, 0x77, 0x6c, 0x20, 0x64, 0x6f, 0x77, + 0x6e, 0x21, 0x0a, 0x00, 0x25, 0x73, 0x3a, 0x20, 0x77, 0x6c, 0x20, 0x75, + 0x70, 0x21, 0x0a, 0x00, 0xa6, 0xcb, 0x86, 0x00, 0x10, 0x00, 0x00, 0x00, + 0x06, 0x00, 0x00, 0x00, 0x52, 0x9b, 0x86, 0x00, 0x01, 0x00, 0x00, 0x00, + 0x01, 0x00, 0x00, 0x00, 0x5d, 0x9b, 0x86, 0x00, 0x02, 0x00, 0x20, 0x00, + 0x07, 0x00, 0x00, 0x00, 0x6f, 0x9b, 0x86, 0x00, 0x03, 0x00, 0x40, 0x00, + 0x08, 0x00, 0x07, 0x00, 0x7c, 0x9b, 0x86, 0x00, 0x04, 0x00, 0x40, 0x00, + 0x08, 0x00, 0x04, 0x00, 0x8b, 0x9b, 0x86, 0x00, 0x05, 0x00, 0x40, 0x00, + 0x08, 0x00, 0x04, 0x00, 0x9a, 0x9b, 0x86, 0x00, 0x06, 0x00, 0x00, 0x00, + 0x08, 0x00, 0x04, 0x00, 0xab, 0x9b, 0x86, 0x00, 0x0d, 0x00, 0x10, 0x00, + 0x07, 0x00, 0x00, 0x00, 0xa7, 0x9b, 0x86, 0x00, 0x0e, 0x00, 0x20, 0x00, + 0x07, 0x00, 0x00, 0x00, 0xb4, 0x9b, 0x86, 0x00, 0x07, 0x00, 0x10, 0x00, + 0x07, 0x00, 0x00, 0x00, 0xbf, 0x9b, 0x86, 0x00, 0x08, 0x00, 0x00, 0x00, + 0x08, 0x00, 0x10, 0x00, 0xd6, 0x9b, 0x86, 0x00, 0x09, 0x00, 0x00, 0x00, + 0x06, 0x00, 0x00, 0x00, 0xc9, 0x9b, 0x86, 0x00, 0x24, 0x00, 0x00, 0x00, + 0x06, 0x00, 0x00, 0x00, 0xfe, 0xc7, 0x86, 0x00, 0x0a, 0x00, 0x00, 0x00, + 0x06, 0x00, 0x00, 0x00, 0xab, 0x72, 0x86, 0x00, 0x0f, 0x00, 0x00, 0x00, + 0x01, 0x00, 0x00, 0x00, 0xd5, 0x9b, 0x86, 0x00, 0x0b, 0x00, 0x80, 0x00, + 0x01, 0x00, 0x00, 0x00, 0xda, 0x9b, 0x86, 0x00, 0x0c, 0x00, 0x00, 0x00, + 0x05, 0x00, 0x00, 0x00, 0xe5, 0x9b, 0x86, 0x00, 0x1d, 0x00, 0x00, 0x00, + 0x03, 0x00, 0x00, 0x00, 0xfa, 0x9b, 0x86, 0x00, 0x1e, 0x00, 0x00, 0x00, + 0x07, 0x00, 0x00, 0x00, 0x13, 0x9c, 0x86, 0x00, 0x1f, 0x00, 0x00, 0x00, + 0x07, 0x00, 0x00, 0x00, 0x25, 0x9c, 0x86, 0x00, 0x21, 0x00, 0x00, 0x00, + 0x05, 0x00, 0x00, 0x00, 0x3b, 0x9c, 0x86, 0x00, 0x20, 0x00, 0x00, 0x00, + 0x03, 0x00, 0x00, 0x00, 0x49, 0x9c, 0x86, 0x00, 0x11, 0x00, 0x80, 0x00, + 0x01, 0x00, 0x00, 0x00, 0x4f, 0x9c, 0x86, 0x00, 0x18, 0x00, 0x40, 0x00, + 0x08, 0x00, 0x06, 0x00, 0x53, 0x9c, 0x86, 0x00, 0x19, 0x00, 0x00, 0x00, + 0x05, 0x00, 0x00, 0x00, 0x61, 0x9c, 0x86, 0x00, 0x1a, 0x00, 0x00, 0x00, + 0x01, 0x00, 0x00, 0x00, 0x6c, 0x9c, 0x86, 0x00, 0x1b, 0x00, 0x40, 0x00, + 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0xd5, 0x50, 0x83, 0x00, 0x21, 0x57, 0x83, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x77, 0x6c, 0x25, 0x64, + 0x3a, 0x20, 0x50, 0x48, 0x59, 0x54, 0x58, 0x20, 0x65, 0x72, 0x72, 0x6f, + 0x72, 0x28, 0x25, 0x64, 0x29, 0x0a, 0x00, 0x54, 0x54, 0x54, 0x54, 0x54, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x50, 0x50, 0x50, + 0x50, 0x50, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x23, + 0x03, 0x00, 0x00, 0x00, 0x00, 0x08, 0x4c, 0x4c, 0x4c, 0x4c, 0x4c, 0x4c, + 0x14, 0x14, 0x14, 0x00, 0x00, 0x01, 0x00, 0x00, 0x64, 0x64, 0x64, 0x64, + 0x64, 0x64, 0x64, 0x64, 0x64, 0x64, 0x64, 0x64, 0x64, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x01, 0x00, 0x00, 0x00, 0x00, 0x64, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x58, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x54, 0x54, 0x54, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x50, 0x50, 0x50, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x23, 0x4c, + 0x4c, 0x4c, 0x4c, 0x4c, 0x4c, 0x4c, 0x4c, 0x4c, 0x4c, 0x4c, 0x4c, 0x4c, + 0x00, 0x00, 0x00, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x03, 0x00, 0x00, 0x00, 0x00, 0x01, 0x42, 0x42, + 0x42, 0x32, 0x42, 0x42, 0x14, 0x14, 0x14, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x03, 0x00, 0x00, 0x00, 0x00, 0x01, 0x3e, 0x3e, 0x42, 0x34, 0x3e, 0x42, + 0x14, 0x14, 0x14, 0x00, 0x00, 0x00, 0x00, 0x00, 0x54, 0x54, 0x54, 0x00, + 0x54, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x23, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00, 0x00, 0x00, 0x01, 0x44, 0x44, + 0x44, 0x38, 0x44, 0x40, 0x14, 0x14, 0x14, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x32, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x32, 0x42, + 0x42, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x08, 0x48, 0x4a, 0x4a, 0x4a, 0x4a, 0x4a, 0x4a, + 0x4a, 0x4a, 0x4a, 0x4a, 0x4a, 0x48, 0x00, 0x00, 0x00, 0x34, 0x34, 0x34, + 0x34, 0x34, 0x34, 0x34, 0x34, 0x34, 0x00, 0x00, 0x00, 0x00, 0x4e, 0x4e, + 0x4e, 0x4e, 0x4e, 0x4e, 0x4e, 0x4e, 0x4e, 0x4e, 0x4e, 0x4e, 0x4e, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x08, 0x54, 0x54, 0x54, 0x00, 0x54, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x50, 0x50, 0x50, 0x00, 0x50, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x23, 0x3a, 0x3e, 0x38, 0x00, + 0x42, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x0a, 0x00, 0x00, 0x00, 0x00, 0x64, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x58, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x3c, 0x42, 0x42, 0x42, 0x42, 0x42, + 0x42, 0x42, 0x42, 0x42, 0x3c, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x34, + 0x4a, 0x4e, 0x4e, 0x4e, 0x4e, 0x4e, 0x4e, 0x4e, 0x4a, 0x38, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x36, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, + 0x44, 0x44, 0x36, 0x4a, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x2e, 0x44, 0x44, + 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x2e, 0x46, 0x3a, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x08, 0x3c, 0x3e, 0x3e, 0x3e, 0x3e, 0x3e, 0x3e, 0x3e, 0x3e, 0x3e, + 0x3c, 0x3e, 0x3e, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x34, 0x44, 0x44, 0x44, 0x44, + 0x44, 0x44, 0x44, 0x44, 0x44, 0x38, 0x44, 0x40, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, + 0x5c, 0x5c, 0x5c, 0x5c, 0x5c, 0x5c, 0x5c, 0x5c, 0x5c, 0x5c, 0x5c, 0x5c, + 0x5c, 0x00, 0x00, 0x50, 0x50, 0x50, 0x50, 0x50, 0x50, 0x50, 0x50, 0x50, + 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, + 0x00, 0x01, 0x4e, 0x4e, 0x4e, 0x34, 0x4c, 0x38, 0x1e, 0x1e, 0x1e, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00, 0x00, 0x00, 0x01, 0x42, 0x44, + 0x42, 0x30, 0x44, 0x30, 0x14, 0x14, 0x14, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x03, 0x00, 0x00, 0x00, 0x00, 0x01, 0x3e, 0x3e, 0x3e, 0x3c, 0x3e, 0x3e, + 0x14, 0x14, 0x14, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00, 0x00, + 0x00, 0x01, 0x44, 0x44, 0x44, 0x36, 0x4c, 0x38, 0x14, 0x14, 0x14, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00, 0x00, 0x00, 0x01, 0x3e, 0x3e, + 0x30, 0x36, 0x3a, 0x2c, 0x14, 0x14, 0x14, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, + 0x42, 0x00, 0x00, 0x00, 0x2e, 0x34, 0x34, 0x34, 0x34, 0x34, 0x34, 0x34, + 0x34, 0x00, 0x00, 0x00, 0x00, 0x4a, 0x4a, 0x4a, 0x4a, 0x4a, 0x4a, 0x4a, + 0x4a, 0x4a, 0x4a, 0x4a, 0x4a, 0x4a, 0x00, 0x00, 0x00, 0x2e, 0x34, 0x34, + 0x34, 0x34, 0x34, 0x34, 0x34, 0x34, 0x00, 0x00, 0x00, 0x00, 0x3e, 0x3e, + 0x3e, 0x4a, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x28, 0x28, 0x28, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x46, 0x44, 0x44, 0x4a, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0a, 0x38, 0x44, 0x44, 0x44, + 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x38, 0x44, 0x44, 0x00, 0x00, 0x00, + 0x2c, 0x38, 0x38, 0x38, 0x38, 0x38, 0x30, 0x34, 0x34, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x42, 0x42, + 0x42, 0x42, 0x42, 0x42, 0x14, 0x14, 0x14, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3e, 0x3e, 0x3e, 0x3e, 0x3e, 0x3e, + 0x14, 0x14, 0x14, 0x00, 0x00, 0x00, 0x00, 0x00, 0x54, 0x54, 0x54, 0x54, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x50, 0x50, + 0x50, 0x50, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x23, 0x38, 0x44, 0x44, 0x4a, 0x4a, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x34, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x34, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x54, + 0x54, 0x54, 0x54, 0x54, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x48, 0x48, 0x48, 0x48, 0x48, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x23, 0x54, 0x54, 0x54, 0x54, 0x54, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x50, 0x50, 0x50, 0x50, 0x50, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x23, 0x54, 0x54, 0x54, + 0x00, 0x54, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x48, + 0x48, 0x48, 0x00, 0x48, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x23, 0x5c, 0x5c, 0x5c, 0x00, 0x50, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x50, 0x48, 0x50, 0x00, 0x44, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x23, 0x4c, 0x4c, 0x4c, 0x4c, 0x4c, + 0x4c, 0x4c, 0x4c, 0x4c, 0x4c, 0x4c, 0x4c, 0x4c, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x09, + 0x01, 0x00, 0x00, 0x00, 0x00, 0x01, 0x3e, 0x3e, 0x3e, 0x32, 0x3e, 0x36, + 0x14, 0x14, 0x14, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, + 0x00, 0x01, 0x3e, 0x3e, 0x3e, 0x34, 0x3e, 0x38, 0x14, 0x14, 0x14, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x01, 0x42, 0x42, + 0x42, 0x3c, 0x42, 0x3c, 0x1e, 0x1e, 0x1e, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x01, 0x00, 0x00, 0x00, 0x00, 0x01, 0x4e, 0x4e, 0x4e, 0x36, 0x4c, 0x38, + 0x1e, 0x1e, 0x1e, 0x00, 0x00, 0x00, 0x00, 0x00, 0x54, 0x54, 0x54, 0x54, + 0x54, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x48, 0x48, + 0x48, 0x48, 0x48, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x23, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x46, 0x46, + 0x46, 0x48, 0x4a, 0x48, 0x17, 0x17, 0x17, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x61, 0x0a, 0x86, 0x00, 0x7e, 0x0a, 0x86, 0x00, 0x9b, 0x0a, 0x86, 0x00, + 0x0f, 0x0b, 0x86, 0x00, 0x49, 0x0b, 0x86, 0x00, 0x66, 0x0b, 0x86, 0x00, + 0x63, 0x0f, 0x86, 0x00, 0x24, 0x0e, 0x86, 0x00, 0x41, 0x0e, 0x86, 0x00, + 0x14, 0x10, 0x86, 0x00, 0x6b, 0x10, 0x86, 0x00, 0x31, 0x10, 0x86, 0x00, + 0x9c, 0x10, 0x86, 0x00, 0xd0, 0x10, 0x86, 0x00, 0x04, 0x11, 0x86, 0x00, + 0x60, 0x11, 0x86, 0x00, 0xb1, 0x11, 0x86, 0x00, 0x83, 0x0b, 0x86, 0x00, + 0xa0, 0x0b, 0x86, 0x00, 0x0c, 0x0f, 0x86, 0x00, 0xf7, 0x0b, 0x86, 0x00, + 0xce, 0x11, 0x86, 0x00, 0x31, 0x0c, 0x86, 0x00, 0x6b, 0x0c, 0x86, 0x00, + 0x94, 0x11, 0x86, 0x00, 0xda, 0x0b, 0x86, 0x00, 0x5e, 0x0e, 0x86, 0x00, + 0x4e, 0x0c, 0x86, 0x00, 0x29, 0x0f, 0x86, 0x00, 0xb8, 0x0a, 0x86, 0x00, + 0xd5, 0x0a, 0x86, 0x00, 0xf2, 0x0a, 0x86, 0x00, 0x7b, 0x0e, 0x86, 0x00, + 0x4e, 0x10, 0x86, 0x00, 0xbd, 0x0b, 0x86, 0x00, 0x98, 0x0e, 0x86, 0x00, + 0x9d, 0x0f, 0x86, 0x00, 0xb5, 0x0e, 0x86, 0x00, 0x88, 0x0c, 0x86, 0x00, + 0xd2, 0x0e, 0x86, 0x00, 0x14, 0x0c, 0x86, 0x00, 0x29, 0x0f, 0x86, 0x00, + 0xba, 0x0f, 0x86, 0x00, 0x2c, 0x0b, 0x86, 0x00, 0x44, 0x0a, 0x86, 0x00, + 0x80, 0x0f, 0x86, 0x00, 0x46, 0x0f, 0x86, 0x00, 0xef, 0x0e, 0x86, 0x00, + 0x44, 0xc0, 0x01, 0x00, 0x2c, 0xc1, 0x01, 0x00, 0x49, 0xc1, 0x01, 0x00, + 0xf2, 0xc0, 0x01, 0x00, 0x61, 0xc0, 0x01, 0x00, 0x66, 0xc1, 0x01, 0x00, + 0x41, 0xc2, 0x01, 0x00, 0xa0, 0xc1, 0x01, 0x00, 0xcb, 0xbf, 0x01, 0x00, + 0xab, 0xc3, 0x01, 0x00, 0x74, 0xbf, 0x01, 0x00, 0x0f, 0xc1, 0x01, 0x00, + 0x7e, 0xc0, 0x01, 0x00, 0x83, 0xc1, 0x01, 0x00, 0x24, 0xc2, 0x01, 0x00, + 0x28, 0xc6, 0x01, 0x00, 0x98, 0xc2, 0x01, 0x00, 0x38, 0x38, 0x38, 0x38, + 0x38, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x34, 0x34, + 0x34, 0x34, 0x34, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x3a, 0x3a, 0x3a, 0x3a, 0x46, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x38, 0x44, 0x44, 0x44, 0x4a, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x2a, 0x00, + 0x00, 0x00, 0x00, 0x54, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x44, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x18, 0x09, 0x86, 0x00, 0xc0, 0x0d, 0x86, 0x00, + 0xe8, 0x0d, 0x86, 0x00, 0x20, 0x0d, 0x86, 0x00, 0xac, 0x0d, 0x86, 0x00, + 0xfc, 0xbf, 0x01, 0x00, 0xdc, 0xc3, 0x01, 0x00, 0xec, 0xc6, 0x01, 0x00, + 0xcc, 0xc2, 0x01, 0x00, 0xc8, 0xc3, 0x01, 0x00, 0xb8, 0xc2, 0x01, 0x00, + 0xe8, 0xbf, 0x01, 0x00, 0x30, 0xc0, 0x01, 0x00, 0xd4, 0xc1, 0x01, 0x00, + 0xf0, 0xc3, 0x01, 0x00, 0x38, 0xc4, 0x01, 0x00, 0xe8, 0xc1, 0x01, 0x00, + 0x20, 0xc7, 0x01, 0x00, 0xc0, 0xc1, 0x01, 0x00, 0x9c, 0xc6, 0x01, 0x00, + 0x50, 0xc7, 0x01, 0x00, 0x04, 0xc4, 0x01, 0x00, 0xfc, 0xc1, 0x01, 0x00, + 0x10, 0xc2, 0x01, 0x00, 0x34, 0xc7, 0x01, 0x00, 0x34, 0x3a, 0x3a, 0x3a, + 0x3a, 0x3a, 0x3a, 0x3a, 0x3a, 0x3a, 0x3a, 0x2c, 0x2c, 0x00, 0x00, 0x00, + 0x32, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x54, 0x54, 0x54, 0x00, 0x54, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x48, 0x48, 0x48, 0x00, 0x48, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x23, 0x3e, 0x48, 0x48, 0x42, 0x46, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0a, 0x00, + 0x38, 0x38, 0x3e, 0x42, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x0a, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x44, 0x44, + 0x44, 0x4c, 0x4c, 0x4c, 0x17, 0x17, 0x17, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x32, 0x32, 0x32, 0x38, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x38, 0x38, 0x38, 0x38, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x4c, 0x00, 0x00, 0x00, 0x4c, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x50, 0x00, 0x00, 0x00, 0x50, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, + 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, + 0x17, 0x17, 0x17, 0x00, 0x00, 0x00, 0x00, 0x00, 0x38, 0x3e, 0x38, 0x3e, + 0x42, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x0a, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00, 0x00, 0x00, 0x01, 0x44, 0x44, + 0x44, 0x34, 0x44, 0x44, 0x14, 0x14, 0x14, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x03, 0x00, 0x00, 0x00, 0x00, 0x08, 0x44, 0x44, 0x44, 0x38, 0x44, 0x44, + 0x14, 0x14, 0x14, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x0f, 0x00, 0x15, 0x00, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x64, 0x64, + 0x64, 0x64, 0x64, 0x64, 0x24, 0x24, 0x24, 0x00, 0x00, 0x01, 0x00, 0x00, + 0xc8, 0xe6, 0x86, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, 0x0c, 0x00, + 0xd7, 0xe6, 0x86, 0x00, 0x01, 0x00, 0x00, 0x00, 0x07, 0x00, 0x04, 0x00, + 0xe9, 0xe6, 0x86, 0x00, 0x02, 0x00, 0x00, 0x00, 0x08, 0x00, 0x08, 0x00, + 0xfb, 0xe6, 0x86, 0x00, 0x03, 0x00, 0x00, 0x00, 0x07, 0x00, 0x04, 0x00, + 0x0b, 0xe7, 0x86, 0x00, 0x04, 0x00, 0x00, 0x00, 0x08, 0x00, 0x1c, 0x00, + 0x1b, 0xe7, 0x86, 0x00, 0x05, 0x00, 0x00, 0x00, 0x08, 0x00, 0x0c, 0x00, + 0x2c, 0xe7, 0x86, 0x00, 0x06, 0x00, 0x00, 0x00, 0x07, 0x00, 0x04, 0x00, + 0x43, 0xe7, 0x86, 0x00, 0x07, 0x00, 0x00, 0x00, 0x07, 0x00, 0x04, 0x00, + 0xf4, 0xc7, 0x01, 0x00, 0x08, 0x00, 0x00, 0x00, 0x07, 0x00, 0x04, 0x00, + 0x04, 0xc8, 0x01, 0x00, 0x09, 0x00, 0x00, 0x00, 0x07, 0x00, 0x04, 0x00, + 0x18, 0xc8, 0x01, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x08, 0x00, 0x90, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x70, 0x6b, 0x74, 0x5f, 0x66, 0x69, 0x6c, 0x74, 0x65, 0x72, 0x5f, 0x69, + 0x63, 0x6d, 0x70, 0x00, 0x70, 0x6b, 0x74, 0x5f, 0x66, 0x69, 0x6c, 0x74, + 0x65, 0x72, 0x5f, 0x69, 0x63, 0x6d, 0x70, 0x5f, 0x63, 0x6e, 0x74, 0x00, + 0x77, 0x61, 0x6b, 0x65, 0x5f, 0x70, 0x61, 0x63, 0x6b, 0x65, 0x74, 0x00, + 0x53, 0x65, 0x74, 0x20, 0x42, 0x52, 0x50, 0x54, 0x20, 0x61, 0x74, 0x20, + 0x25, 0x78, 0x0a, 0x00, 0x0a, 0x46, 0x57, 0x49, 0x44, 0x20, 0x30, 0x31, + 0x2d, 0x25, 0x78, 0x0a, 0x00, 0x0a, 0x54, 0x52, 0x41, 0x50, 0x20, 0x25, + 0x78, 0x28, 0x25, 0x78, 0x29, 0x3a, 0x20, 0x70, 0x63, 0x20, 0x25, 0x78, + 0x2c, 0x20, 0x6c, 0x72, 0x20, 0x25, 0x78, 0x2c, 0x20, 0x73, 0x70, 0x20, + 0x25, 0x78, 0x2c, 0x20, 0x70, 0x73, 0x72, 0x20, 0x25, 0x78, 0x2c, 0x20, + 0x78, 0x70, 0x73, 0x72, 0x20, 0x25, 0x78, 0x0a, 0x00, 0x20, 0x20, 0x72, + 0x30, 0x20, 0x25, 0x78, 0x2c, 0x20, 0x72, 0x31, 0x20, 0x25, 0x78, 0x2c, + 0x20, 0x72, 0x32, 0x20, 0x25, 0x78, 0x2c, 0x20, 0x72, 0x33, 0x20, 0x25, + 0x78, 0x2c, 0x20, 0x72, 0x34, 0x20, 0x25, 0x78, 0x2c, 0x20, 0x72, 0x35, + 0x20, 0x25, 0x78, 0x2c, 0x20, 0x72, 0x36, 0x20, 0x25, 0x78, 0x0a, 0x00, + 0x20, 0x20, 0x72, 0x37, 0x20, 0x25, 0x78, 0x2c, 0x20, 0x72, 0x38, 0x20, + 0x25, 0x78, 0x2c, 0x20, 0x72, 0x39, 0x20, 0x25, 0x78, 0x2c, 0x20, 0x72, + 0x31, 0x30, 0x20, 0x25, 0x78, 0x2c, 0x20, 0x72, 0x31, 0x31, 0x20, 0x25, + 0x78, 0x2c, 0x20, 0x72, 0x31, 0x32, 0x20, 0x25, 0x78, 0x0a, 0x00, 0x0a, + 0x20, 0x20, 0x20, 0x73, 0x70, 0x2b, 0x30, 0x20, 0x25, 0x30, 0x38, 0x78, + 0x20, 0x25, 0x30, 0x38, 0x78, 0x20, 0x25, 0x30, 0x38, 0x78, 0x20, 0x25, + 0x30, 0x38, 0x78, 0x0a, 0x00, 0x20, 0x20, 0x73, 0x70, 0x2b, 0x31, 0x30, + 0x20, 0x25, 0x30, 0x38, 0x78, 0x20, 0x25, 0x30, 0x38, 0x78, 0x20, 0x25, + 0x30, 0x38, 0x78, 0x20, 0x25, 0x30, 0x38, 0x78, 0x0a, 0x00, 0x73, 0x70, + 0x2b, 0x25, 0x78, 0x20, 0x25, 0x30, 0x38, 0x78, 0x0a, 0x00, 0x64, 0x65, + 0x61, 0x64, 0x6d, 0x61, 0x6e, 0x5f, 0x74, 0x6f, 0x00, 0x72, 0x61, 0x6d, + 0x73, 0x74, 0x62, 0x79, 0x64, 0x69, 0x73, 0x00, 0x70, 0x61, 0x25, 0x64, + 0x3d, 0x30, 0x78, 0x25, 0x25, 0x78, 0x00, 0x70, 0x64, 0x25, 0x64, 0x3d, + 0x30, 0x78, 0x25, 0x25, 0x78, 0x00, 0x6e, 0x76, 0x72, 0x61, 0x6d, 0x5f, + 0x6f, 0x76, 0x65, 0x72, 0x72, 0x69, 0x64, 0x65, 0x00, 0x00, 0x00, 0x00, + 0x86, 0x06, 0x02, 0x00, 0xd0, 0x09, 0x00, 0x00, 0x80, 0x06, 0x02, 0x00, + 0x3e, 0x3e, 0x00, 0x00, 0x82, 0x06, 0x02, 0x00, 0x3e, 0x02, 0x00, 0x00, + 0x00, 0x07, 0x02, 0x00, 0x3c, 0x00, 0x00, 0x00, 0x84, 0x06, 0x02, 0x00, + 0x12, 0x02, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, 0x03, 0x00, 0x01, 0x00, + 0x64, 0x01, 0x02, 0x00, 0xc0, 0x00, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, + 0x03, 0x00, 0x01, 0x00, 0x66, 0x01, 0x02, 0x00, 0x0a, 0x00, 0x00, 0x00, + 0x60, 0x01, 0x04, 0x00, 0x04, 0x00, 0x01, 0x00, 0x64, 0x01, 0x02, 0x00, + 0x14, 0x00, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, 0x07, 0x00, 0x01, 0x00, + 0x64, 0x01, 0x02, 0x00, 0x83, 0x01, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, + 0x25, 0x00, 0x01, 0x00, 0x64, 0x01, 0x02, 0x00, 0xf4, 0x01, 0x00, 0x00, + 0x60, 0x01, 0x04, 0x00, 0x96, 0x05, 0x01, 0x00, 0x64, 0x01, 0x02, 0x00, + 0x2b, 0x04, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, 0x96, 0x05, 0x01, 0x00, + 0x66, 0x01, 0x02, 0x00, 0x00, 0x01, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, + 0xd7, 0x01, 0x01, 0x00, 0x64, 0x01, 0x02, 0x00, 0x3c, 0x00, 0x00, 0x00, + 0x60, 0x01, 0x04, 0x00, 0xdc, 0x01, 0x01, 0x00, 0x66, 0x01, 0x02, 0x00, + 0x34, 0x00, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, 0xe2, 0x01, 0x01, 0x00, + 0x64, 0x01, 0x02, 0x00, 0x30, 0x00, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, + 0xe7, 0x01, 0x01, 0x00, 0x66, 0x01, 0x02, 0x00, 0x2c, 0x00, 0x00, 0x00, + 0x60, 0x01, 0x04, 0x00, 0xed, 0x01, 0x01, 0x00, 0x64, 0x01, 0x02, 0x00, + 0x2c, 0x00, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, 0xf2, 0x01, 0x01, 0x00, + 0x66, 0x01, 0x02, 0x00, 0x28, 0x00, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, + 0xf8, 0x01, 0x01, 0x00, 0x64, 0x01, 0x02, 0x00, 0x28, 0x00, 0x00, 0x00, + 0x60, 0x01, 0x04, 0x00, 0xfd, 0x01, 0x01, 0x00, 0x66, 0x01, 0x02, 0x00, + 0x28, 0x00, 0x00, 0x00, 0xff, 0xff, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x60, 0x01, 0x04, 0x00, 0x05, 0x00, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x19, 0x00, 0x24, 0x01, 0x04, 0x00, 0x04, 0x00, 0x00, 0x00, + 0x28, 0x01, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x2c, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x30, 0x01, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x34, 0x01, 0x04, 0x00, 0x0a, 0x04, 0x70, 0x00, 0x34, 0x01, 0x04, 0x00, + 0xef, 0xbe, 0xd4, 0x00, 0x34, 0x01, 0x04, 0x00, 0x05, 0x00, 0x00, 0xff, + 0x34, 0x01, 0x04, 0x00, 0x01, 0xff, 0x02, 0xff, 0x30, 0x01, 0x04, 0x00, + 0x18, 0x00, 0x00, 0x00, 0x34, 0x01, 0x04, 0x00, 0x0a, 0x04, 0xe0, 0x00, + 0x34, 0x01, 0x04, 0x00, 0xef, 0xbe, 0x48, 0x00, 0x34, 0x01, 0x04, 0x00, + 0x05, 0x00, 0x00, 0xff, 0x34, 0x01, 0x04, 0x00, 0x01, 0xff, 0x02, 0xff, + 0x34, 0x01, 0x04, 0x00, 0x00, 0x10, 0x18, 0x01, 0x34, 0x01, 0x04, 0x00, + 0x02, 0x03, 0x00, 0x10, 0x34, 0x01, 0x04, 0x00, 0x18, 0xf1, 0xf2, 0xf3, + 0x34, 0x01, 0x04, 0x00, 0xbb, 0xcc, 0x00, 0x00, 0x30, 0x01, 0x04, 0x00, + 0x68, 0x06, 0x00, 0x00, 0x34, 0x01, 0x04, 0x00, 0x14, 0x04, 0x70, 0x00, + 0x34, 0x01, 0x04, 0x00, 0xef, 0xbe, 0x58, 0x01, 0x34, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x00, 0xff, 0x34, 0x01, 0x04, 0x00, 0x01, 0xff, 0x02, 0xff, + 0x34, 0x01, 0x04, 0x00, 0x00, 0x10, 0x18, 0x01, 0x34, 0x01, 0x04, 0x00, + 0x02, 0x03, 0x03, 0x09, 0x34, 0x01, 0x04, 0x00, 0xbf, 0x00, 0x00, 0x10, + 0x34, 0x01, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x30, 0x01, 0x04, 0x00, + 0x38, 0x00, 0x00, 0x00, 0x34, 0x01, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x30, 0x01, 0x04, 0x00, 0x88, 0x06, 0x00, 0x00, 0x34, 0x01, 0x04, 0x00, + 0x14, 0x04, 0x80, 0x00, 0x34, 0x01, 0x04, 0x00, 0xef, 0xbe, 0x18, 0x02, + 0x34, 0x01, 0x04, 0x00, 0x00, 0x00, 0x03, 0x09, 0x34, 0x01, 0x04, 0x00, + 0xbf, 0x00, 0x00, 0x03, 0x34, 0x01, 0x04, 0x00, 0x00, 0x01, 0x02, 0x03, + 0x34, 0x01, 0x04, 0x00, 0x04, 0x05, 0x00, 0x01, 0x34, 0x01, 0x04, 0x00, + 0x02, 0x03, 0x04, 0x05, 0x34, 0x01, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x30, 0x01, 0x04, 0x00, 0x58, 0x00, 0x00, 0x00, 0x34, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x30, 0x01, 0x04, 0x00, 0x38, 0x00, 0x00, 0x00, + 0x34, 0x01, 0x04, 0x00, 0x0f, 0x20, 0x00, 0x07, 0x34, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x94, 0x00, 0x34, 0x01, 0x04, 0x00, 0x00, 0x00, 0x00, 0x90, + 0x34, 0x01, 0x04, 0x00, 0x74, 0x75, 0x76, 0x77, 0x34, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x34, 0x01, 0x04, 0x00, 0x00, 0x00, 0x05, 0x00, + 0x34, 0x01, 0x04, 0x00, 0xff, 0xff, 0xff, 0xff, 0x30, 0x01, 0x04, 0x00, + 0x68, 0x02, 0x00, 0x00, 0x34, 0x01, 0x04, 0x00, 0x6e, 0x84, 0x33, 0x00, + 0x34, 0x01, 0x04, 0x00, 0xdc, 0xba, 0x50, 0x00, 0x34, 0x01, 0x04, 0x00, + 0xd4, 0x00, 0x00, 0xab, 0x34, 0x01, 0x04, 0x00, 0xba, 0xda, 0xba, 0xda, + 0x34, 0x01, 0x04, 0x00, 0x00, 0x10, 0x18, 0xf1, 0x34, 0x01, 0x04, 0x00, + 0xf2, 0xf3, 0x00, 0x10, 0x34, 0x01, 0x04, 0x00, 0x18, 0xf1, 0xf2, 0xf3, + 0x34, 0x01, 0x04, 0x00, 0x10, 0x00, 0x00, 0x00, 0x34, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x34, 0x01, 0x04, 0x00, 0x00, 0x00, 0x0a, 0x00, + 0x34, 0x01, 0x04, 0x00, 0x01, 0x00, 0x00, 0x0e, 0x34, 0x01, 0x04, 0x00, + 0x42, 0x52, 0x43, 0x4d, 0x34, 0x01, 0x04, 0x00, 0x5f, 0x54, 0x45, 0x53, + 0x34, 0x01, 0x04, 0x00, 0x54, 0x5f, 0x53, 0x53, 0x34, 0x01, 0x04, 0x00, + 0x49, 0x44, 0x01, 0x04, 0x34, 0x01, 0x04, 0x00, 0x82, 0x84, 0x8b, 0x96, + 0x34, 0x01, 0x04, 0x00, 0x03, 0x01, 0x01, 0x06, 0x34, 0x01, 0x04, 0x00, + 0x02, 0x00, 0x00, 0x00, 0x30, 0x01, 0x04, 0x00, 0x68, 0x00, 0x00, 0x00, + 0x34, 0x01, 0x04, 0x00, 0x0a, 0x04, 0x28, 0x02, 0x34, 0x01, 0x04, 0x00, + 0xdc, 0xba, 0x80, 0x00, 0x34, 0x01, 0x04, 0x00, 0x00, 0x00, 0xff, 0xff, + 0x34, 0x01, 0x04, 0x00, 0xff, 0xff, 0xff, 0xff, 0x34, 0x01, 0x04, 0x00, + 0x00, 0x10, 0x18, 0xf1, 0x34, 0x01, 0x04, 0x00, 0xf2, 0xf3, 0x00, 0x10, + 0x34, 0x01, 0x04, 0x00, 0x18, 0xf1, 0xf2, 0xf3, 0x34, 0x01, 0x04, 0x00, + 0xd0, 0xaf, 0x00, 0x00, 0x34, 0x01, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x34, 0x01, 0x04, 0x00, 0x00, 0x00, 0x00, 0x01, 0x34, 0x01, 0x04, 0x00, + 0x02, 0x00, 0x00, 0x0e, 0x34, 0x01, 0x04, 0x00, 0x42, 0x52, 0x43, 0x4d, + 0x34, 0x01, 0x04, 0x00, 0x5f, 0x54, 0x45, 0x53, 0x34, 0x01, 0x04, 0x00, + 0x54, 0x5f, 0x53, 0x53, 0x34, 0x01, 0x04, 0x00, 0x49, 0x44, 0x01, 0x04, + 0x34, 0x01, 0x04, 0x00, 0x82, 0x84, 0x8b, 0x96, 0x34, 0x01, 0x04, 0x00, + 0x03, 0x01, 0x01, 0x06, 0x34, 0x01, 0x04, 0x00, 0x02, 0x01, 0x00, 0x00, + 0x30, 0x01, 0x04, 0x00, 0x68, 0x04, 0x00, 0x00, 0x34, 0x01, 0x04, 0x00, + 0x0a, 0x04, 0x28, 0x02, 0x34, 0x01, 0x04, 0x00, 0xdc, 0xba, 0x80, 0x00, + 0x34, 0x01, 0x04, 0x00, 0x00, 0x00, 0xff, 0xff, 0x34, 0x01, 0x04, 0x00, + 0xff, 0xff, 0xff, 0xff, 0x34, 0x01, 0x04, 0x00, 0x00, 0x10, 0x18, 0xf1, + 0x34, 0x01, 0x04, 0x00, 0xf2, 0xf3, 0x00, 0x10, 0x34, 0x01, 0x04, 0x00, + 0x18, 0xf1, 0xf2, 0xf3, 0x34, 0x01, 0x04, 0x00, 0xd0, 0xaf, 0x00, 0x00, + 0x34, 0x01, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x34, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x34, 0x01, 0x04, 0x00, 0x02, 0x00, 0x00, 0x0e, + 0x34, 0x01, 0x04, 0x00, 0x42, 0x52, 0x43, 0x4d, 0x34, 0x01, 0x04, 0x00, + 0x5f, 0x54, 0x45, 0x53, 0x34, 0x01, 0x04, 0x00, 0x54, 0x5f, 0x53, 0x53, + 0x34, 0x01, 0x04, 0x00, 0x49, 0x44, 0x01, 0x04, 0x34, 0x01, 0x04, 0x00, + 0x82, 0x84, 0x8b, 0x96, 0x34, 0x01, 0x04, 0x00, 0x03, 0x01, 0x01, 0x06, + 0x34, 0x01, 0x04, 0x00, 0x02, 0x01, 0x00, 0x00, 0x00, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x90, 0x04, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, + 0xa0, 0x04, 0x02, 0x00, 0xf1, 0xf3, 0x00, 0x00, 0xb0, 0x04, 0x02, 0x00, + 0xef, 0xfd, 0x00, 0x00, 0xa8, 0x04, 0x02, 0x00, 0xff, 0xff, 0x00, 0x00, + 0xa8, 0x04, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0xaa, 0x04, 0x02, 0x00, + 0x00, 0x00, 0x00, 0x00, 0xa4, 0x04, 0x02, 0x00, 0xcf, 0x1a, 0x00, 0x00, + 0xac, 0x04, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0xbc, 0x04, 0x02, 0x00, + 0x00, 0x00, 0x00, 0x00, 0xa6, 0x04, 0x02, 0x00, 0xd7, 0x02, 0x00, 0x00, + 0xb6, 0x04, 0x02, 0x00, 0xff, 0xfd, 0x00, 0x00, 0xae, 0x04, 0x02, 0x00, + 0xff, 0xff, 0x00, 0x00, 0x06, 0x04, 0x02, 0x00, 0x01, 0x00, 0x00, 0x00, + 0x06, 0x04, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0c, 0x04, 0x02, 0x00, + 0x18, 0x00, 0x00, 0x00, 0x06, 0x04, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x48, 0x04, 0x02, 0x00, 0x00, 0x0c, 0x00, 0x00, 0x02, 0x04, 0x02, 0x00, + 0xa0, 0x07, 0x00, 0x00, 0x02, 0x05, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x05, 0x02, 0x00, 0x00, 0x40, 0x00, 0x00, 0x02, 0x05, 0x02, 0x00, + 0x04, 0x00, 0x00, 0x00, 0x00, 0x05, 0x02, 0x00, 0x00, 0x40, 0x00, 0x00, + 0x02, 0x05, 0x02, 0x00, 0x08, 0x00, 0x00, 0x00, 0x00, 0x05, 0x02, 0x00, + 0x00, 0x40, 0x00, 0x00, 0x02, 0x05, 0x02, 0x00, 0x0c, 0x00, 0x00, 0x00, + 0x00, 0x05, 0x02, 0x00, 0x00, 0x40, 0x00, 0x00, 0x02, 0x05, 0x02, 0x00, + 0xc0, 0x00, 0x00, 0x00, 0x80, 0x05, 0x02, 0x00, 0xff, 0xff, 0x00, 0x00, + 0x82, 0x05, 0x02, 0x00, 0xff, 0xff, 0x00, 0x00, 0x84, 0x05, 0x02, 0x00, + 0xff, 0xff, 0x00, 0x00, 0x86, 0x05, 0x02, 0x00, 0xff, 0xff, 0x00, 0x00, + 0x88, 0x05, 0x02, 0x00, 0xff, 0xff, 0x00, 0x00, 0x9c, 0x05, 0x02, 0x00, + 0xf0, 0xff, 0x00, 0x00, 0x40, 0x05, 0x02, 0x00, 0x00, 0x80, 0x00, 0x00, + 0x20, 0x05, 0x02, 0x00, 0x06, 0x0f, 0x00, 0x00, 0x40, 0x05, 0x02, 0x00, + 0x00, 0x80, 0x00, 0x00, 0x40, 0x05, 0x02, 0x00, 0x00, 0x81, 0x00, 0x00, + 0x20, 0x05, 0x02, 0x00, 0x10, 0x1d, 0x00, 0x00, 0x40, 0x05, 0x02, 0x00, + 0x00, 0x81, 0x00, 0x00, 0x40, 0x05, 0x02, 0x00, 0x00, 0x82, 0x00, 0x00, + 0x20, 0x05, 0x02, 0x00, 0x1e, 0x28, 0x00, 0x00, 0x40, 0x05, 0x02, 0x00, + 0x00, 0x82, 0x00, 0x00, 0x40, 0x05, 0x02, 0x00, 0x00, 0x83, 0x00, 0x00, + 0x20, 0x05, 0x02, 0x00, 0x29, 0x31, 0x00, 0x00, 0x40, 0x05, 0x02, 0x00, + 0x00, 0x83, 0x00, 0x00, 0x40, 0x05, 0x02, 0x00, 0x00, 0x84, 0x00, 0x00, + 0x20, 0x05, 0x02, 0x00, 0x32, 0x3f, 0x00, 0x00, 0x40, 0x05, 0x02, 0x00, + 0x00, 0x84, 0x00, 0x00, 0x40, 0x05, 0x02, 0x00, 0x00, 0x85, 0x00, 0x00, + 0x20, 0x05, 0x02, 0x00, 0x40, 0x41, 0x00, 0x00, 0x40, 0x05, 0x02, 0x00, + 0x00, 0x85, 0x00, 0x00, 0x12, 0x06, 0x02, 0x00, 0x01, 0x00, 0x00, 0x00, + 0x2e, 0x06, 0x02, 0x00, 0xcd, 0xcc, 0x00, 0x00, 0x30, 0x06, 0x02, 0x00, + 0x0c, 0x00, 0x00, 0x00, 0x00, 0x06, 0x02, 0x00, 0x04, 0x80, 0x00, 0x00, + 0x96, 0x06, 0x02, 0x00, 0x08, 0x00, 0x00, 0x00, 0x9a, 0x06, 0x02, 0x00, + 0xe4, 0x00, 0x00, 0x00, 0x88, 0x06, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x9c, 0x06, 0x02, 0x00, 0x02, 0x00, 0x00, 0x00, 0x88, 0x06, 0x02, 0x00, + 0x00, 0x10, 0x00, 0x00, 0x9c, 0x06, 0x02, 0x00, 0x02, 0x00, 0x00, 0x00, + 0x88, 0x06, 0x02, 0x00, 0x00, 0x20, 0x00, 0x00, 0x9c, 0x06, 0x02, 0x00, + 0x02, 0x00, 0x00, 0x00, 0x88, 0x06, 0x02, 0x00, 0x00, 0x30, 0x00, 0x00, + 0x9c, 0x06, 0x02, 0x00, 0x02, 0x00, 0x00, 0x00, 0x88, 0x06, 0x02, 0x00, + 0x0b, 0x0f, 0x00, 0x00, 0x9e, 0x06, 0x02, 0x00, 0x07, 0x00, 0x00, 0x00, + 0x10, 0x05, 0x02, 0x00, 0x0b, 0x00, 0x00, 0x00, 0x50, 0x04, 0x02, 0x00, + 0x01, 0x4e, 0x00, 0x00, 0x52, 0x04, 0x02, 0x00, 0x5b, 0x01, 0x00, 0x00, + 0xe4, 0x04, 0x02, 0x00, 0x90, 0x00, 0x00, 0x00, 0x04, 0x04, 0x02, 0x00, + 0xb4, 0x00, 0x00, 0x00, 0x54, 0x05, 0x02, 0x00, 0xff, 0x3f, 0x00, 0x00, + 0x60, 0x01, 0x04, 0x00, 0x04, 0x00, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x64, 0x01, 0x04, 0x00, 0xb4, 0x00, 0x00, 0x00, + 0x64, 0x01, 0x04, 0x00, 0x47, 0x00, 0x47, 0x00, 0x64, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x64, 0x00, 0x64, 0x01, 0x04, 0x00, 0x30, 0x09, 0x40, 0x00, + 0x60, 0x01, 0x04, 0x00, 0x0d, 0x00, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, + 0x02, 0x00, 0x02, 0x00, 0x64, 0x01, 0x04, 0x00, 0x01, 0x00, 0x80, 0x00, + 0x64, 0x01, 0x04, 0x00, 0x05, 0x00, 0x00, 0x00, 0x64, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x80, 0x00, 0x64, 0x01, 0x04, 0x00, 0x64, 0x00, 0x64, 0x00, + 0x64, 0x01, 0x04, 0x00, 0x0e, 0x00, 0x47, 0x00, 0x64, 0x01, 0x04, 0x00, + 0x00, 0x05, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, 0x15, 0x00, 0x01, 0x03, + 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x42, 0x08, 0x64, 0x01, 0x04, 0x00, + 0xde, 0x0b, 0x07, 0x00, 0x64, 0x01, 0x04, 0x00, 0x0a, 0x00, 0x00, 0x00, + 0x60, 0x01, 0x04, 0x00, 0x1a, 0x00, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, + 0x00, 0xc0, 0x64, 0x0b, 0x60, 0x01, 0x04, 0x00, 0x1d, 0x00, 0x01, 0x03, + 0x64, 0x01, 0x04, 0x00, 0x10, 0x27, 0x00, 0x00, 0x64, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x7a, 0x03, 0x60, 0x01, 0x04, 0x00, 0x20, 0x00, 0x01, 0x03, + 0x64, 0x01, 0x04, 0x00, 0x06, 0x00, 0x10, 0x27, 0x60, 0x01, 0x04, 0x00, + 0x23, 0x00, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0xf6, 0x06, + 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0xa8, 0x0a, 0x64, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x32, 0x00, 0x64, 0x01, 0x04, 0x00, 0x0a, 0x0e, 0x0b, 0x09, + 0x64, 0x01, 0x04, 0x00, 0x0e, 0x02, 0x00, 0x00, 0x64, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x52, 0x0a, 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x3f, 0x01, + 0x64, 0x01, 0x04, 0x00, 0xff, 0xff, 0x00, 0x0c, 0x64, 0x01, 0x04, 0x00, + 0x32, 0x04, 0x6e, 0x06, 0x64, 0x01, 0x04, 0x00, 0x02, 0x00, 0xf2, 0x09, + 0x60, 0x01, 0x04, 0x00, 0x2e, 0x00, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x00, 0x80, 0x60, 0x01, 0x04, 0x00, 0x32, 0x00, 0x01, 0x03, + 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x32, 0x0b, 0x60, 0x01, 0x04, 0x00, + 0x34, 0x00, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0xcc, 0x05, + 0x60, 0x01, 0x04, 0x00, 0x58, 0x00, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, + 0x42, 0x52, 0x43, 0x4d, 0x64, 0x01, 0x04, 0x00, 0x5f, 0x54, 0x45, 0x53, + 0x64, 0x01, 0x04, 0x00, 0x54, 0x5f, 0x53, 0x53, 0x64, 0x01, 0x04, 0x00, + 0x49, 0x44, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, 0x60, 0x00, 0x01, 0x03, + 0x64, 0x01, 0x04, 0x00, 0x39, 0x00, 0x00, 0x00, 0x64, 0x01, 0x04, 0x00, + 0x50, 0x00, 0x00, 0x00, 0x64, 0x01, 0x04, 0x00, 0xc0, 0x00, 0x00, 0x00, + 0x60, 0x01, 0x04, 0x00, 0x70, 0x00, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, + 0xaa, 0x03, 0xaa, 0x03, 0x64, 0x01, 0x04, 0x00, 0xaa, 0x03, 0xaa, 0x03, + 0x64, 0x01, 0x04, 0x00, 0xaa, 0x03, 0xaa, 0x03, 0x64, 0x01, 0x04, 0x00, + 0xaa, 0x03, 0xaa, 0x03, 0x64, 0x01, 0x04, 0x00, 0xec, 0x03, 0xd6, 0x03, + 0x64, 0x01, 0x04, 0x00, 0xc0, 0x03, 0xaa, 0x03, 0x64, 0x01, 0x04, 0x00, + 0xf7, 0x03, 0xe1, 0x03, 0x64, 0x01, 0x04, 0x00, 0xcb, 0x03, 0xb5, 0x03, + 0x64, 0x01, 0x04, 0x00, 0xaa, 0x03, 0xaa, 0x03, 0x64, 0x01, 0x04, 0x00, + 0xaa, 0x03, 0xaa, 0x03, 0x64, 0x01, 0x04, 0x00, 0xaa, 0x03, 0xaa, 0x03, + 0x64, 0x01, 0x04, 0x00, 0xaa, 0x03, 0xaa, 0x03, 0x64, 0x01, 0x04, 0x00, + 0xec, 0x03, 0xd6, 0x03, 0x64, 0x01, 0x04, 0x00, 0xc0, 0x03, 0xaa, 0x03, + 0x64, 0x01, 0x04, 0x00, 0xf7, 0x03, 0xe1, 0x03, 0x64, 0x01, 0x04, 0x00, + 0xcb, 0x03, 0xb5, 0x03, 0x64, 0x01, 0x04, 0x00, 0x02, 0x04, 0x02, 0x04, + 0x64, 0x01, 0x04, 0x00, 0x02, 0x04, 0x02, 0x04, 0x64, 0x01, 0x04, 0x00, + 0x0e, 0x04, 0x02, 0x04, 0x64, 0x01, 0x04, 0x00, 0x02, 0x04, 0x1a, 0x04, + 0x64, 0x01, 0x04, 0x00, 0x02, 0x04, 0x02, 0x04, 0x64, 0x01, 0x04, 0x00, + 0x02, 0x04, 0x02, 0x04, 0x64, 0x01, 0x04, 0x00, 0x02, 0x04, 0x02, 0x04, + 0x64, 0x01, 0x04, 0x00, 0x26, 0x04, 0x02, 0x04, 0x64, 0x01, 0x04, 0x00, + 0x02, 0x04, 0x02, 0x04, 0x64, 0x01, 0x04, 0x00, 0x02, 0x04, 0x02, 0x04, + 0x64, 0x01, 0x04, 0x00, 0x0e, 0x04, 0x02, 0x04, 0x64, 0x01, 0x04, 0x00, + 0x02, 0x04, 0x1a, 0x04, 0x64, 0x01, 0x04, 0x00, 0x02, 0x04, 0x02, 0x04, + 0x64, 0x01, 0x04, 0x00, 0x02, 0x04, 0x02, 0x04, 0x64, 0x01, 0x04, 0x00, + 0x02, 0x04, 0x02, 0x04, 0x64, 0x01, 0x04, 0x00, 0x26, 0x04, 0x02, 0x04, + 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x1f, 0x00, 0x64, 0x01, 0x04, 0x00, + 0xff, 0x03, 0x1f, 0x00, 0x64, 0x01, 0x04, 0x00, 0x02, 0x00, 0x00, 0x00, + 0x64, 0x01, 0x04, 0x00, 0x02, 0x00, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, + 0x98, 0x00, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x1f, 0x00, + 0x64, 0x01, 0x04, 0x00, 0xff, 0x03, 0x1f, 0x00, 0x64, 0x01, 0x04, 0x00, + 0x01, 0x00, 0x00, 0x00, 0x64, 0x01, 0x04, 0x00, 0x01, 0x00, 0x00, 0x00, + 0x60, 0x01, 0x04, 0x00, 0xa0, 0x00, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x1f, 0x00, 0x64, 0x01, 0x04, 0x00, 0xff, 0x03, 0x1f, 0x00, + 0x64, 0x01, 0x04, 0x00, 0x01, 0x00, 0x00, 0x00, 0x64, 0x01, 0x04, 0x00, + 0x01, 0x00, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, 0xa8, 0x00, 0x01, 0x03, + 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x1f, 0x00, 0x64, 0x01, 0x04, 0x00, + 0xff, 0x03, 0x1f, 0x00, 0x64, 0x01, 0x04, 0x00, 0x01, 0x00, 0x00, 0x00, + 0x64, 0x01, 0x04, 0x00, 0x01, 0x00, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, + 0xb8, 0x00, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, 0xe7, 0x00, 0xec, 0x00, + 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x7b, 0x00, 0x64, 0x01, 0x04, 0x00, + 0x7e, 0x00, 0x00, 0x00, 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x4f, 0x51, 0x64, 0x01, 0x04, 0x00, + 0x3f, 0x00, 0x00, 0x00, 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x00, 0x10, + 0x60, 0x01, 0x04, 0x00, 0xc0, 0x00, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, + 0x37, 0x24, 0x37, 0x24, 0x64, 0x01, 0x04, 0x00, 0x37, 0x24, 0x37, 0x24, + 0x60, 0x01, 0x04, 0x00, 0x93, 0x01, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, + 0x0f, 0x00, 0x40, 0x00, 0x64, 0x01, 0x04, 0x00, 0xe6, 0x06, 0x00, 0x00, + 0x60, 0x01, 0x04, 0x00, 0x97, 0x01, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, + 0x1a, 0x08, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, 0xa0, 0x01, 0x01, 0x03, + 0x64, 0x01, 0x04, 0x00, 0xff, 0xff, 0xff, 0xff, 0x64, 0x01, 0x04, 0x00, + 0xff, 0xff, 0xff, 0xff, 0x64, 0x01, 0x04, 0x00, 0xff, 0xff, 0xff, 0xff, + 0x64, 0x01, 0x04, 0x00, 0xff, 0xff, 0xff, 0xff, 0x64, 0x01, 0x04, 0x00, + 0xff, 0xff, 0xff, 0xff, 0x64, 0x01, 0x04, 0x00, 0xff, 0xff, 0xff, 0xff, + 0x64, 0x01, 0x04, 0x00, 0xff, 0xff, 0xff, 0xff, 0x64, 0x01, 0x04, 0x00, + 0xff, 0xff, 0xff, 0xff, 0x60, 0x01, 0x04, 0x00, 0xbc, 0x01, 0x01, 0x03, + 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x05, 0x00, 0x60, 0x01, 0x04, 0x00, + 0xc5, 0x01, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x10, 0x03, + 0x64, 0x01, 0x04, 0x00, 0xe0, 0x00, 0xff, 0xff, 0x64, 0x01, 0x04, 0x00, + 0x03, 0x09, 0xbf, 0x00, 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x03, 0x09, + 0x64, 0x01, 0x04, 0x00, 0xbf, 0x00, 0x00, 0x10, 0x64, 0x01, 0x04, 0x00, + 0x03, 0x09, 0xbf, 0x00, 0x64, 0x01, 0x04, 0x00, 0x00, 0x03, 0x00, 0x00, + 0x60, 0x01, 0x04, 0x00, 0xcd, 0x01, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, + 0xff, 0xff, 0xff, 0xff, 0x64, 0x01, 0x04, 0x00, 0xff, 0xff, 0xff, 0xff, + 0x64, 0x01, 0x04, 0x00, 0xff, 0xff, 0xff, 0xff, 0x64, 0x01, 0x04, 0x00, + 0xff, 0xff, 0xff, 0xff, 0x64, 0x01, 0x04, 0x00, 0xff, 0xff, 0xff, 0xff, + 0x64, 0x01, 0x04, 0x00, 0xff, 0xff, 0xff, 0xff, 0x64, 0x01, 0x04, 0x00, + 0xff, 0xff, 0xff, 0xff, 0x64, 0x01, 0x04, 0x00, 0xff, 0xff, 0xff, 0xff, + 0x64, 0x01, 0x04, 0x00, 0x20, 0x00, 0xcb, 0x01, 0x64, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x54, 0x00, 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0xab, 0x08, + 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x10, 0x04, 0x64, 0x01, 0x04, 0x00, + 0x84, 0x00, 0x02, 0x00, 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x14, 0x00, + 0x64, 0x01, 0x04, 0x00, 0xcf, 0x01, 0x02, 0x00, 0x64, 0x01, 0x04, 0x00, + 0x44, 0x00, 0x00, 0x00, 0x64, 0x01, 0x04, 0x00, 0xaf, 0x08, 0x02, 0x00, + 0x64, 0x01, 0x04, 0x00, 0x10, 0x04, 0x64, 0x00, 0x64, 0x01, 0x04, 0x00, + 0x02, 0x02, 0x00, 0x00, 0x64, 0x01, 0x04, 0x00, 0x10, 0x00, 0xca, 0x01, + 0x64, 0x01, 0x04, 0x00, 0x02, 0x00, 0x3c, 0x00, 0x64, 0x01, 0x04, 0x00, + 0x00, 0x00, 0xaa, 0x08, 0x64, 0x01, 0x04, 0x00, 0x02, 0x00, 0x10, 0x04, + 0x64, 0x01, 0x04, 0x00, 0x54, 0x00, 0x02, 0x08, 0x64, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x64, 0x01, 0x04, 0x00, 0xce, 0x01, 0x00, 0x00, + 0x64, 0x01, 0x04, 0x00, 0x34, 0x00, 0x00, 0x00, 0x64, 0x01, 0x04, 0x00, + 0xae, 0x08, 0x00, 0x00, 0x64, 0x01, 0x04, 0x00, 0x10, 0x04, 0x44, 0x00, + 0x64, 0x01, 0x04, 0x00, 0x02, 0x0a, 0x00, 0x00, 0x64, 0x01, 0x04, 0x00, + 0x08, 0x00, 0xc9, 0x01, 0x64, 0x01, 0x04, 0x00, 0x02, 0x00, 0x30, 0x00, + 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0xa9, 0x08, 0x64, 0x01, 0x04, 0x00, + 0x02, 0x00, 0x10, 0x04, 0x64, 0x01, 0x04, 0x00, 0x3c, 0x00, 0x02, 0x10, + 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x04, 0x00, 0x64, 0x01, 0x04, 0x00, + 0xcd, 0x01, 0x00, 0x00, 0x64, 0x01, 0x04, 0x00, 0x2c, 0x00, 0x00, 0x00, + 0x64, 0x01, 0x04, 0x00, 0xad, 0x08, 0x00, 0x00, 0x64, 0x01, 0x04, 0x00, + 0x10, 0x04, 0x34, 0x00, 0x64, 0x01, 0x04, 0x00, 0x02, 0x12, 0x00, 0x00, + 0x64, 0x01, 0x04, 0x00, 0x04, 0x00, 0xc8, 0x01, 0x64, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x2c, 0x00, 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0xa8, 0x08, + 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x10, 0x04, 0x64, 0x01, 0x04, 0x00, + 0x30, 0x00, 0x02, 0x19, 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x64, 0x01, 0x04, 0x00, 0xcc, 0x01, 0x02, 0x00, 0x64, 0x01, 0x04, 0x00, + 0x2c, 0x00, 0x00, 0x00, 0x64, 0x01, 0x04, 0x00, 0xac, 0x08, 0x02, 0x00, + 0x64, 0x01, 0x04, 0x00, 0x10, 0x04, 0x30, 0x00, 0x64, 0x01, 0x04, 0x00, + 0x02, 0x1a, 0x00, 0x00, 0x64, 0x01, 0x04, 0x00, 0xc0, 0x00, 0x0a, 0x04, + 0x64, 0x01, 0x04, 0x00, 0x70, 0x00, 0x00, 0x00, 0x64, 0x01, 0x04, 0x00, + 0x3a, 0x01, 0x0a, 0x04, 0x64, 0x01, 0x04, 0x00, 0x28, 0x02, 0x2c, 0xc0, + 0x64, 0x01, 0x04, 0x00, 0xf2, 0x02, 0x0a, 0x04, 0x64, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x64, 0x01, 0x04, 0x00, 0x60, 0x00, 0x14, 0x04, + 0x64, 0x01, 0x04, 0x00, 0x38, 0x00, 0x00, 0x00, 0x64, 0x01, 0x04, 0x00, + 0x02, 0x01, 0x14, 0x04, 0x64, 0x01, 0x04, 0x00, 0x14, 0x01, 0x2c, 0xc0, + 0x64, 0x01, 0x04, 0x00, 0xde, 0x01, 0x14, 0x04, 0x64, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x80, 0x00, 0x64, 0x01, 0x04, 0x00, 0x22, 0x00, 0x37, 0x04, + 0x64, 0x01, 0x04, 0x00, 0x15, 0x00, 0x00, 0x00, 0x64, 0x01, 0x04, 0x00, + 0xdf, 0x00, 0x37, 0x04, 0x64, 0x01, 0x04, 0x00, 0x65, 0x00, 0x2c, 0xc0, + 0x64, 0x01, 0x04, 0x00, 0x2e, 0x01, 0x37, 0x04, 0x64, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x2f, 0x00, 0x64, 0x01, 0x04, 0x00, 0x11, 0x00, 0x6e, 0x84, + 0x64, 0x01, 0x04, 0x00, 0x0b, 0x00, 0x00, 0x00, 0x64, 0x01, 0x04, 0x00, + 0xd4, 0x00, 0x6e, 0x84, 0x64, 0x01, 0x04, 0x00, 0x33, 0x00, 0x2c, 0xc0, + 0x64, 0x01, 0x04, 0x00, 0xfc, 0x00, 0x6e, 0x84, 0x64, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x18, 0x00, 0x64, 0x01, 0x04, 0x00, 0x02, 0x00, 0x8a, 0x9d, + 0x64, 0x01, 0x04, 0x00, 0xfb, 0x00, 0x02, 0x08, 0x64, 0x01, 0x04, 0x00, + 0xc5, 0x4e, 0xfa, 0x00, 0x64, 0x01, 0x04, 0x00, 0x02, 0x0a, 0x83, 0x34, + 0x64, 0x01, 0x04, 0x00, 0xfe, 0x00, 0x02, 0x10, 0x64, 0x01, 0x04, 0x00, + 0x62, 0x27, 0xf9, 0x00, 0x64, 0x01, 0x04, 0x00, 0x02, 0x12, 0x42, 0x1a, + 0x64, 0x01, 0x04, 0x00, 0xfd, 0x00, 0x02, 0x19, 0x64, 0x01, 0x04, 0x00, + 0xb1, 0x13, 0xf8, 0x00, 0x64, 0x01, 0x04, 0x00, 0x02, 0x1a, 0x81, 0x11, + 0x64, 0x01, 0x04, 0x00, 0xfc, 0x00, 0x02, 0x1c, 0x64, 0x01, 0x04, 0x00, + 0xc1, 0x0f, 0xfc, 0x00, 0x60, 0x01, 0x04, 0x00, 0x7b, 0x03, 0x01, 0x03, + 0x64, 0x01, 0x04, 0x00, 0x07, 0x00, 0x14, 0x00, 0x64, 0x01, 0x04, 0x00, + 0x1e, 0x00, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, 0x83, 0x03, 0x01, 0x03, + 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x00, 0xf0, 0x64, 0x01, 0x04, 0x00, + 0xc3, 0x30, 0x10, 0x92, 0x64, 0x01, 0x04, 0x00, 0x50, 0x31, 0x80, 0x22, + 0x64, 0x01, 0x04, 0x00, 0xc3, 0x30, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, + 0x88, 0x03, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x10, 0x04, + 0x60, 0x01, 0x04, 0x00, 0x8c, 0x03, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, + 0x80, 0x00, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, 0x8e, 0x03, 0x01, 0x03, + 0x64, 0x01, 0x04, 0x00, 0x05, 0x00, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, + 0x0b, 0x04, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, 0x07, 0x02, 0x00, 0x00, + 0x60, 0x01, 0x04, 0x00, 0x13, 0x04, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x01, 0x00, 0x60, 0x01, 0x04, 0x00, 0x15, 0x04, 0x01, 0x03, + 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x0c, 0x00, 0x60, 0x01, 0x04, 0x00, + 0x53, 0x05, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, 0x18, 0x00, 0x00, 0x00, + 0x64, 0x01, 0x04, 0x00, 0x98, 0x3a, 0x98, 0x3a, 0x64, 0x01, 0x04, 0x00, + 0xa6, 0x0e, 0x64, 0x00, 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0xf4, 0x01, + 0x64, 0x01, 0x04, 0x00, 0x05, 0x00, 0x00, 0x00, 0x64, 0x01, 0x04, 0x00, + 0xa8, 0x61, 0xa8, 0x61, 0x64, 0x01, 0x04, 0x00, 0x30, 0x75, 0x1e, 0x00, + 0x60, 0x01, 0x04, 0x00, 0x5c, 0x05, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, + 0x50, 0xc3, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, 0x5e, 0x05, 0x01, 0x03, + 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x14, 0x05, 0x64, 0x01, 0x04, 0x00, + 0x50, 0xc3, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, 0x62, 0x05, 0x01, 0x03, + 0x64, 0x01, 0x04, 0x00, 0x20, 0x4e, 0x00, 0x00, 0x64, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x0f, 0x00, 0x64, 0x01, 0x04, 0x00, 0xf4, 0x01, 0x04, 0x00, + 0x60, 0x01, 0x04, 0x00, 0x68, 0x05, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x31, 0x00, 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x03, 0x00, + 0x64, 0x01, 0x04, 0x00, 0x01, 0x00, 0x07, 0x00, 0x64, 0x01, 0x04, 0x00, + 0xc8, 0xaf, 0x00, 0x00, 0x64, 0x01, 0x04, 0x00, 0x88, 0x13, 0x00, 0x00, + 0x64, 0x01, 0x04, 0x00, 0x2c, 0x17, 0xff, 0x00, 0x60, 0x01, 0x04, 0x00, + 0x6f, 0x05, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x2c, 0x01, + 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0xa0, 0x0f, 0x60, 0x01, 0x04, 0x00, + 0x72, 0x05, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x03, 0x00, + 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x2c, 0x01, 0x64, 0x01, 0x04, 0x00, + 0xc0, 0x00, 0x00, 0x00, 0x64, 0x01, 0x04, 0x00, 0x88, 0x13, 0x00, 0x00, + 0x64, 0x01, 0x04, 0x00, 0x64, 0x00, 0x00, 0x00, 0x64, 0x01, 0x04, 0x00, + 0xdc, 0x05, 0x40, 0x1f, 0x60, 0x01, 0x04, 0x00, 0x79, 0x05, 0x01, 0x03, + 0x64, 0x01, 0x04, 0x00, 0x01, 0x00, 0x01, 0x00, 0x64, 0x01, 0x04, 0x00, + 0x02, 0x00, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, 0x7c, 0x05, 0x01, 0x03, + 0x64, 0x01, 0x04, 0x00, 0x02, 0x00, 0x00, 0x00, 0x64, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x40, 0x9c, 0x64, 0x01, 0x04, 0x00, 0x20, 0x4e, 0x00, 0x00, + 0x64, 0x01, 0x04, 0x00, 0xb8, 0x0b, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, + 0x81, 0x05, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x20, 0x4e, + 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x05, 0x00, 0x64, 0x01, 0x04, 0x00, + 0xdc, 0x05, 0x3f, 0x00, 0x64, 0x01, 0x04, 0x00, 0x71, 0x02, 0x00, 0x00, + 0x64, 0x01, 0x04, 0x00, 0x30, 0x75, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, + 0x89, 0x05, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, 0xc4, 0x09, 0xa0, 0x0f, + 0x60, 0x01, 0x04, 0x00, 0x8c, 0x05, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, + 0x02, 0x00, 0xd0, 0x07, 0x60, 0x01, 0x04, 0x00, 0x8e, 0x05, 0x01, 0x03, + 0x64, 0x01, 0x04, 0x00, 0x20, 0x4e, 0x20, 0x4e, 0x60, 0x01, 0x04, 0x00, + 0x94, 0x05, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0xbe, 0x00, + 0x60, 0x01, 0x04, 0x00, 0xb0, 0x05, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, + 0x00, 0x00, 0xe8, 0x03, 0x60, 0x01, 0x04, 0x00, 0xec, 0x05, 0x01, 0x03, + 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, + 0xf5, 0x05, 0x01, 0x03, 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x88, 0x13, + 0x60, 0x01, 0x04, 0x00, 0x03, 0x00, 0x02, 0x00, 0x64, 0x01, 0x04, 0x00, + 0x1f, 0x00, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, 0x04, 0x00, 0x02, 0x00, + 0x64, 0x01, 0x04, 0x00, 0xff, 0x03, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, + 0x05, 0x00, 0x02, 0x00, 0x64, 0x01, 0x04, 0x00, 0x1f, 0x00, 0x00, 0x00, + 0x60, 0x01, 0x04, 0x00, 0x06, 0x00, 0x02, 0x00, 0x64, 0x01, 0x04, 0x00, + 0x07, 0x00, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, 0x07, 0x00, 0x02, 0x00, + 0x64, 0x01, 0x04, 0x00, 0x04, 0x00, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, + 0x08, 0x00, 0x02, 0x00, 0x64, 0x01, 0x04, 0x00, 0xff, 0xff, 0x00, 0x00, + 0x60, 0x01, 0x04, 0x00, 0x09, 0x00, 0x02, 0x00, 0x64, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, 0x0a, 0x00, 0x02, 0x00, + 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, + 0x0b, 0x00, 0x02, 0x00, 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x60, 0x01, 0x04, 0x00, 0x0c, 0x00, 0x02, 0x00, 0x64, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, 0x0d, 0x00, 0x02, 0x00, + 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, + 0x0e, 0x00, 0x02, 0x00, 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x60, 0x01, 0x04, 0x00, 0x0f, 0x00, 0x02, 0x00, 0x64, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, 0x10, 0x00, 0x02, 0x00, + 0x64, 0x01, 0x04, 0x00, 0x1f, 0x00, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, + 0x11, 0x00, 0x02, 0x00, 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x60, 0x01, 0x04, 0x00, 0x12, 0x00, 0x02, 0x00, 0x64, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, 0x13, 0x00, 0x02, 0x00, + 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x60, 0x01, 0x04, 0x00, + 0x15, 0x00, 0x02, 0x00, 0x64, 0x01, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x60, 0x01, 0x04, 0x00, 0x16, 0x00, 0x02, 0x00, 0x64, 0x01, 0x04, 0x00, + 0x00, 0x00, 0x00, 0x00, 0xff, 0xff, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x63, 0x62, 0x75, 0x63, 0x6b, 0x5f, 0x73, 0x77, 0x66, 0x72, 0x65, 0x71, + 0x00, 0x00, 0x00, 0x00, 0xe0, 0x2e, 0x01, 0x01, 0x01, 0x50, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0xc8, 0x32, 0x02, 0x01, 0x01, 0x49, 0x00, 0x00, + 0x89, 0x9d, 0xd8, 0x00, 0x40, 0x38, 0x03, 0x01, 0x01, 0x42, 0x00, 0x00, + 0xaa, 0xaa, 0xaa, 0x00, 0x00, 0x3c, 0x04, 0x01, 0x01, 0x3e, 0x00, 0x00, + 0x00, 0x00, 0x80, 0x00, 0x48, 0x3f, 0x05, 0x01, 0x01, 0x39, 0x00, 0x00, + 0xd0, 0x5e, 0x42, 0x00, 0xa0, 0x41, 0x06, 0x01, 0x01, 0x39, 0x00, 0x00, + 0x49, 0x92, 0x24, 0x00, 0x00, 0x4b, 0x07, 0x01, 0x01, 0x32, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x58, 0x4d, 0x08, 0x01, 0x01, 0x30, 0x00, 0x00, + 0x07, 0x1f, 0x7c, 0x00, 0x20, 0x4e, 0x09, 0x01, 0x01, 0x30, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0xc0, 0x5d, 0x0a, 0x01, 0x01, 0x28, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0xa8, 0x61, 0x0b, 0x01, 0x01, 0x26, 0x00, 0x00, + 0x66, 0x66, 0x66, 0x00, 0x90, 0x65, 0x0c, 0x01, 0x01, 0x24, 0x00, 0x00, + 0xc4, 0x4e, 0xec, 0x00, 0x30, 0x75, 0x0d, 0x01, 0x01, 0x20, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x18, 0x92, 0x0e, 0x02, 0x01, 0x33, 0x00, 0x00, + 0xf9, 0x3e, 0x56, 0x00, 0x00, 0x96, 0x0f, 0x02, 0x01, 0x32, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x40, 0x9c, 0x10, 0x02, 0x01, 0x30, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x80, 0xbb, 0x11, 0x02, 0x01, 0x28, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x09, 0xdc, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x08, 0x00, 0x08, 0x00, 0x08, 0xdc, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00, + 0x08, 0x00, 0x0b, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x6d, 0x6b, 0x65, 0x65, 0x70, 0x5f, 0x61, 0x6c, + 0x69, 0x76, 0x65, 0x00, 0x5b, 0x57, 0x4c, 0x41, 0x4e, 0x5d, 0x63, 0x6f, + 0x75, 0x6e, 0x74, 0x20, 0x3d, 0x20, 0x25, 0x64, 0x0a, 0x00, 0x49, 0x6e, + 0x69, 0x74, 0x20, 0x43, 0x6f, 0x75, 0x6e, 0x74, 0x65, 0x72, 0x00, 0x47, + 0x72, 0x6f, 0x75, 0x70, 0x20, 0x6b, 0x65, 0x79, 0x20, 0x65, 0x78, 0x70, + 0x61, 0x6e, 0x73, 0x69, 0x6f, 0x6e, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x62, 0x74, 0x61, 0x00, + 0x41, 0x4d, 0x50, 0x2d, 0x25, 0x30, 0x32, 0x78, 0x2d, 0x25, 0x30, 0x32, + 0x78, 0x2d, 0x25, 0x30, 0x32, 0x78, 0x2d, 0x25, 0x30, 0x32, 0x78, 0x2d, + 0x25, 0x30, 0x32, 0x78, 0x2d, 0x25, 0x30, 0x32, 0x78, 0x00, 0x62, 0x74, + 0x61, 0x6d, 0x70, 0x00, 0x62, 0x74, 0x61, 0x6d, 0x70, 0x5f, 0x66, 0x6c, + 0x61, 0x67, 0x73, 0x00, 0x62, 0x74, 0x61, 0x6d, 0x70, 0x5f, 0x63, 0x68, + 0x61, 0x6e, 0x00, 0x62, 0x74, 0x61, 0x6d, 0x70, 0x5f, 0x31, 0x31, 0x6e, + 0x5f, 0x73, 0x75, 0x70, 0x70, 0x6f, 0x72, 0x74, 0x00, 0x62, 0x74, 0x61, + 0x6d, 0x70, 0x5f, 0x66, 0x62, 0x00, 0x62, 0x74, 0x61, 0x6d, 0x70, 0x5f, + 0x73, 0x74, 0x61, 0x74, 0x65, 0x6c, 0x6f, 0x67, 0x00, 0x77, 0x6c, 0x25, + 0x64, 0x2e, 0x25, 0x64, 0x3a, 0x20, 0x25, 0x73, 0x3a, 0x20, 0x73, 0x63, + 0x62, 0x20, 0x6b, 0x65, 0x79, 0x20, 0x69, 0x64, 0x20, 0x25, 0x64, 0x20, + 0x64, 0x6f, 0x65, 0x73, 0x20, 0x6e, 0x6f, 0x74, 0x20, 0x6d, 0x61, 0x74, + 0x63, 0x68, 0x20, 0x25, 0x64, 0x0a, 0x00, 0x77, 0x6c, 0x63, 0x5f, 0x6b, + 0x65, 0x79, 0x5f, 0x6c, 0x6f, 0x6f, 0x6b, 0x75, 0x70, 0x00, 0x00, 0x00, + 0x77, 0x6c, 0x63, 0x5f, 0x61, 0x70, 0x5f, 0x70, 0x72, 0x6f, 0x63, 0x65, + 0x73, 0x73, 0x5f, 0x61, 0x73, 0x73, 0x6f, 0x63, 0x72, 0x65, 0x71, 0x00, + 0x70, 0x61, 0x74, 0x63, 0x68, 0x5f, 0x69, 0x6f, 0x76, 0x61, 0x72, 0x73, + 0x00, 0x72, 0x65, 0x61, 0x64, 0x20, 0x73, 0x68, 0x6d, 0x65, 0x6d, 0x0a, + 0x00, 0x25, 0x73, 0x3a, 0x20, 0x44, 0x6f, 0x20, 0x57, 0x4c, 0x43, 0x5f, + 0x47, 0x45, 0x54, 0x5f, 0x50, 0x48, 0x59, 0x52, 0x45, 0x47, 0x2f, 0x57, + 0x4c, 0x43, 0x5f, 0x53, 0x45, 0x54, 0x5f, 0x50, 0x48, 0x59, 0x5f, 0x52, + 0x45, 0x47, 0x00, 0x25, 0x73, 0x3a, 0x20, 0x72, 0x65, 0x6a, 0x65, 0x63, + 0x74, 0x20, 0x64, 0x75, 0x65, 0x20, 0x74, 0x6f, 0x20, 0x6e, 0x6f, 0x20, + 0x6d, 0x65, 0x6d, 0x28, 0x25, 0x64, 0x29, 0x0a, 0x00, 0x25, 0x73, 0x3a, + 0x20, 0x72, 0x65, 0x6a, 0x65, 0x63, 0x74, 0x20, 0x64, 0x75, 0x65, 0x20, + 0x74, 0x6f, 0x20, 0x6f, 0x76, 0x65, 0x72, 0x20, 0x6d, 0x61, 0x78, 0x61, + 0x73, 0x73, 0x6f, 0x63, 0x28, 0x25, 0x64, 0x29, 0x0a, 0x00, 0x6f, 0x74, + 0x70, 0x72, 0x61, 0x77, 0x00, 0x66, 0x61, 0x62, 0x69, 0x64, 0x00, 0x61, + 0x6d, 0x70, 0x64, 0x75, 0x5f, 0x72, 0x74, 0x73, 0x00, 0x77, 0x6c, 0x63, + 0x5f, 0x69, 0x6f, 0x63, 0x74, 0x6c, 0x5f, 0x70, 0x61, 0x74, 0x63, 0x68, + 0x6d, 0x6f, 0x64, 0x00, 0x20, 0x79, 0x86, 0x00, 0x00, 0x00, 0x00, 0x40, + 0x03, 0x00, 0x00, 0x00, 0x9a, 0xdd, 0x01, 0x00, 0x08, 0x00, 0x08, 0x00, + 0x08, 0x00, 0x00, 0x00, 0x3d, 0x7d, 0x86, 0x00, 0x01, 0x00, 0x08, 0x80, + 0x08, 0x00, 0x00, 0x00, 0x89, 0x76, 0x86, 0x00, 0x02, 0x00, 0x00, 0x40, + 0x08, 0x00, 0x00, 0x00, 0xcc, 0xbb, 0x86, 0x00, 0x03, 0x00, 0x00, 0x40, + 0x06, 0x00, 0x00, 0x00, 0xab, 0x9b, 0x86, 0x00, 0x04, 0x00, 0x10, 0x00, + 0x07, 0x00, 0x00, 0x00, 0xa1, 0xdd, 0x01, 0x00, 0x05, 0x00, 0x00, 0x00, + 0x05, 0x00, 0x00, 0x00, 0x64, 0x7d, 0x86, 0x00, 0x06, 0x00, 0x00, 0x00, + 0x08, 0x00, 0x1c, 0x00, 0xa7, 0xdd, 0x01, 0x00, 0x07, 0x00, 0x00, 0x00, + 0x01, 0x00, 0x00, 0x00, 0xd6, 0x9b, 0x86, 0x00, 0x09, 0x00, 0x00, 0x00, + 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x6c, 0x09, 0x02, 0x00, 0x71, 0x09, + 0x03, 0x00, 0x76, 0x09, 0x04, 0x00, 0x7b, 0x09, 0x05, 0x00, 0x80, 0x09, + 0x06, 0x00, 0x85, 0x09, 0x07, 0x00, 0x8a, 0x09, 0x08, 0x00, 0x8f, 0x09, + 0x09, 0x00, 0x94, 0x09, 0x0a, 0x00, 0x99, 0x09, 0x0b, 0x00, 0x9e, 0x09, + 0x0c, 0x00, 0xa3, 0x09, 0x0d, 0x00, 0xa8, 0x09, 0x0e, 0x00, 0xb4, 0x09, + 0x4c, 0x84, 0xff, 0xe0, 0xb0, 0x84, 0xf7, 0xf7, 0xf9, 0x84, 0xf7, 0xff, + 0x3c, 0xc4, 0x07, 0x00, 0x3b, 0xc4, 0x07, 0x00, 0x00, 0x00, 0x2d, 0x00, + 0xa7, 0x90, 0x1a, 0x00, 0x47, 0x09, 0x0e, 0x00, 0x01, 0x20, 0x07, 0x00, + 0x8b, 0x93, 0x03, 0x00, 0x38, 0xca, 0x01, 0x00, 0x2a, 0xe5, 0x00, 0x00, + 0x97, 0x72, 0x00, 0x00, 0x4c, 0x39, 0x00, 0x00, 0xa6, 0x1c, 0x00, 0x00, + 0x53, 0x0e, 0x00, 0x00, 0x29, 0x07, 0x00, 0x00, 0x95, 0x03, 0x00, 0x00, + 0xca, 0x01, 0x00, 0x00, 0xe5, 0x00, 0x00, 0x00, 0x73, 0x00, 0x00, 0x00, + 0x39, 0x00, 0x00, 0x00, 0x1d, 0x00, 0x00, 0x00, 0x2e, 0x66, 0x61, 0x62, + 0x2e, 0x00, 0x25, 0x73, 0x2e, 0x66, 0x61, 0x62, 0x2e, 0x25, 0x64, 0x00, + 0x77, 0x6c, 0x25, 0x64, 0x3a, 0x20, 0x53, 0x63, 0x61, 0x6e, 0x20, 0x69, + 0x6e, 0x20, 0x70, 0x72, 0x6f, 0x67, 0x72, 0x65, 0x73, 0x73, 0x2c, 0x20, + 0x73, 0x6b, 0x69, 0x70, 0x70, 0x69, 0x6e, 0x67, 0x20, 0x74, 0x78, 0x70, + 0x6f, 0x77, 0x65, 0x72, 0x20, 0x63, 0x6f, 0x6e, 0x74, 0x72, 0x6f, 0x6c, + 0x0a, 0x00, 0x70, 0x6f, 0x77, 0x65, 0x72, 0x20, 0x61, 0x64, 0x6a, 0x21, + 0x0a, 0x00, 0x63, 0x63, 0x6b, 0x62, 0x77, 0x32, 0x30, 0x32, 0x67, 0x70, + 0x6f, 0x00, 0x63, 0x63, 0x6b, 0x62, 0x77, 0x32, 0x30, 0x75, 0x6c, 0x32, + 0x67, 0x70, 0x6f, 0x00, 0x6c, 0x65, 0x67, 0x6f, 0x66, 0x64, 0x6d, 0x62, + 0x77, 0x32, 0x30, 0x32, 0x67, 0x70, 0x6f, 0x00, 0x6c, 0x65, 0x67, 0x6f, + 0x66, 0x64, 0x6d, 0x62, 0x77, 0x32, 0x30, 0x75, 0x6c, 0x32, 0x67, 0x70, + 0x6f, 0x00, 0x6d, 0x63, 0x73, 0x62, 0x77, 0x32, 0x30, 0x32, 0x67, 0x70, + 0x6f, 0x00, 0x6d, 0x63, 0x73, 0x62, 0x77, 0x32, 0x30, 0x75, 0x6c, 0x32, + 0x67, 0x70, 0x6f, 0x00, 0x6d, 0x63, 0x73, 0x62, 0x77, 0x34, 0x30, 0x32, + 0x67, 0x70, 0x6f, 0x00, 0x6c, 0x65, 0x67, 0x6f, 0x66, 0x64, 0x6d, 0x62, + 0x77, 0x32, 0x30, 0x35, 0x67, 0x6c, 0x70, 0x6f, 0x00, 0x6c, 0x65, 0x67, + 0x6f, 0x66, 0x64, 0x6d, 0x62, 0x77, 0x32, 0x30, 0x75, 0x6c, 0x35, 0x67, + 0x6c, 0x70, 0x6f, 0x00, 0x6c, 0x65, 0x67, 0x6f, 0x66, 0x64, 0x6d, 0x62, + 0x77, 0x32, 0x30, 0x35, 0x67, 0x6d, 0x70, 0x6f, 0x00, 0x6c, 0x65, 0x67, + 0x6f, 0x66, 0x64, 0x6d, 0x62, 0x77, 0x32, 0x30, 0x75, 0x6c, 0x35, 0x67, + 0x6d, 0x70, 0x6f, 0x00, 0x6c, 0x65, 0x67, 0x6f, 0x66, 0x64, 0x6d, 0x62, + 0x77, 0x32, 0x30, 0x35, 0x67, 0x68, 0x70, 0x6f, 0x00, 0x6c, 0x65, 0x67, + 0x6f, 0x66, 0x64, 0x6d, 0x62, 0x77, 0x32, 0x30, 0x75, 0x6c, 0x35, 0x67, + 0x68, 0x70, 0x6f, 0x00, 0x6d, 0x63, 0x73, 0x62, 0x77, 0x32, 0x30, 0x35, + 0x67, 0x6c, 0x70, 0x6f, 0x00, 0x6d, 0x63, 0x73, 0x62, 0x77, 0x32, 0x30, + 0x75, 0x6c, 0x35, 0x67, 0x6c, 0x70, 0x6f, 0x00, 0x6d, 0x63, 0x73, 0x62, + 0x77, 0x34, 0x30, 0x35, 0x67, 0x6c, 0x70, 0x6f, 0x00, 0x6d, 0x63, 0x73, + 0x62, 0x77, 0x32, 0x30, 0x35, 0x67, 0x6d, 0x70, 0x6f, 0x00, 0x6d, 0x63, + 0x73, 0x62, 0x77, 0x32, 0x30, 0x75, 0x6c, 0x35, 0x67, 0x6d, 0x70, 0x6f, + 0x00, 0x6d, 0x63, 0x73, 0x62, 0x77, 0x34, 0x30, 0x35, 0x67, 0x6d, 0x70, + 0x6f, 0x00, 0x6d, 0x63, 0x73, 0x62, 0x77, 0x32, 0x30, 0x35, 0x67, 0x68, + 0x70, 0x6f, 0x00, 0x6d, 0x63, 0x73, 0x62, 0x77, 0x32, 0x30, 0x75, 0x6c, + 0x35, 0x67, 0x68, 0x70, 0x6f, 0x00, 0x6d, 0x63, 0x73, 0x62, 0x77, 0x34, + 0x30, 0x35, 0x67, 0x68, 0x70, 0x6f, 0x00, 0x6d, 0x63, 0x73, 0x33, 0x32, + 0x70, 0x6f, 0x00, 0x6c, 0x65, 0x67, 0x6f, 0x66, 0x64, 0x6d, 0x34, 0x30, + 0x64, 0x75, 0x70, 0x70, 0x6f, 0x00, 0x62, 0x77, 0x34, 0x30, 0x70, 0x6f, + 0x00, 0x63, 0x64, 0x64, 0x70, 0x6f, 0x00, 0x73, 0x74, 0x62, 0x63, 0x70, + 0x6f, 0x00, 0x62, 0x77, 0x64, 0x75, 0x70, 0x70, 0x6f, 0x00, 0x74, 0x78, + 0x70, 0x69, 0x64, 0x32, 0x67, 0x61, 0x30, 0x00, 0x74, 0x78, 0x70, 0x69, + 0x64, 0x32, 0x67, 0x61, 0x31, 0x00, 0x6d, 0x61, 0x78, 0x70, 0x32, 0x67, + 0x61, 0x30, 0x00, 0x6d, 0x61, 0x78, 0x70, 0x32, 0x67, 0x61, 0x31, 0x00, + 0x70, 0x61, 0x32, 0x67, 0x77, 0x30, 0x61, 0x30, 0x00, 0x70, 0x61, 0x32, + 0x67, 0x77, 0x30, 0x61, 0x31, 0x00, 0x70, 0x61, 0x32, 0x67, 0x77, 0x31, + 0x61, 0x30, 0x00, 0x70, 0x61, 0x32, 0x67, 0x77, 0x31, 0x61, 0x31, 0x00, + 0x70, 0x61, 0x32, 0x67, 0x77, 0x32, 0x61, 0x30, 0x00, 0x70, 0x61, 0x32, + 0x67, 0x77, 0x32, 0x61, 0x31, 0x00, 0x69, 0x74, 0x74, 0x32, 0x67, 0x61, + 0x30, 0x00, 0x69, 0x74, 0x74, 0x32, 0x67, 0x61, 0x31, 0x00, 0x63, 0x63, + 0x6b, 0x32, 0x67, 0x70, 0x6f, 0x00, 0x6f, 0x66, 0x64, 0x6d, 0x32, 0x67, + 0x70, 0x6f, 0x00, 0x6d, 0x63, 0x73, 0x32, 0x67, 0x70, 0x6f, 0x30, 0x00, + 0x6d, 0x63, 0x73, 0x32, 0x67, 0x70, 0x6f, 0x31, 0x00, 0x6d, 0x63, 0x73, + 0x32, 0x67, 0x70, 0x6f, 0x32, 0x00, 0x6d, 0x63, 0x73, 0x32, 0x67, 0x70, + 0x6f, 0x33, 0x00, 0x6d, 0x63, 0x73, 0x32, 0x67, 0x70, 0x6f, 0x34, 0x00, + 0x6d, 0x63, 0x73, 0x32, 0x67, 0x70, 0x6f, 0x35, 0x00, 0x6d, 0x63, 0x73, + 0x32, 0x67, 0x70, 0x6f, 0x36, 0x00, 0x6d, 0x63, 0x73, 0x32, 0x67, 0x70, + 0x6f, 0x37, 0x00, 0x74, 0x78, 0x70, 0x69, 0x64, 0x35, 0x67, 0x6c, 0x61, + 0x30, 0x00, 0x74, 0x78, 0x70, 0x69, 0x64, 0x35, 0x67, 0x6c, 0x61, 0x31, + 0x00, 0x6d, 0x61, 0x78, 0x70, 0x35, 0x67, 0x6c, 0x61, 0x30, 0x00, 0x6d, + 0x61, 0x78, 0x70, 0x35, 0x67, 0x6c, 0x61, 0x31, 0x00, 0x70, 0x61, 0x35, + 0x67, 0x6c, 0x77, 0x30, 0x61, 0x30, 0x00, 0x70, 0x61, 0x35, 0x67, 0x6c, + 0x77, 0x30, 0x61, 0x31, 0x00, 0x70, 0x61, 0x35, 0x67, 0x6c, 0x77, 0x31, + 0x61, 0x30, 0x00, 0x70, 0x61, 0x35, 0x67, 0x6c, 0x77, 0x31, 0x61, 0x31, + 0x00, 0x70, 0x61, 0x35, 0x67, 0x6c, 0x77, 0x32, 0x61, 0x30, 0x00, 0x70, + 0x61, 0x35, 0x67, 0x6c, 0x77, 0x32, 0x61, 0x31, 0x00, 0x6f, 0x66, 0x64, + 0x6d, 0x35, 0x67, 0x6c, 0x70, 0x6f, 0x00, 0x6d, 0x63, 0x73, 0x35, 0x67, + 0x6c, 0x70, 0x6f, 0x30, 0x00, 0x6d, 0x63, 0x73, 0x35, 0x67, 0x6c, 0x70, + 0x6f, 0x31, 0x00, 0x6d, 0x63, 0x73, 0x35, 0x67, 0x6c, 0x70, 0x6f, 0x32, + 0x00, 0x6d, 0x63, 0x73, 0x35, 0x67, 0x6c, 0x70, 0x6f, 0x33, 0x00, 0x6d, + 0x63, 0x73, 0x35, 0x67, 0x6c, 0x70, 0x6f, 0x34, 0x00, 0x6d, 0x63, 0x73, + 0x35, 0x67, 0x6c, 0x70, 0x6f, 0x35, 0x00, 0x6d, 0x63, 0x73, 0x35, 0x67, + 0x6c, 0x70, 0x6f, 0x36, 0x00, 0x6d, 0x63, 0x73, 0x35, 0x67, 0x6c, 0x70, + 0x6f, 0x37, 0x00, 0x74, 0x78, 0x70, 0x69, 0x64, 0x35, 0x67, 0x61, 0x30, + 0x00, 0x74, 0x78, 0x70, 0x69, 0x64, 0x35, 0x67, 0x61, 0x31, 0x00, 0x6d, + 0x61, 0x78, 0x70, 0x35, 0x67, 0x61, 0x30, 0x00, 0x6d, 0x61, 0x78, 0x70, + 0x35, 0x67, 0x61, 0x31, 0x00, 0x70, 0x61, 0x35, 0x67, 0x77, 0x30, 0x61, + 0x30, 0x00, 0x70, 0x61, 0x35, 0x67, 0x77, 0x30, 0x61, 0x31, 0x00, 0x70, + 0x61, 0x35, 0x67, 0x77, 0x31, 0x61, 0x30, 0x00, 0x70, 0x61, 0x35, 0x67, + 0x77, 0x31, 0x61, 0x31, 0x00, 0x70, 0x61, 0x35, 0x67, 0x77, 0x32, 0x61, + 0x30, 0x00, 0x70, 0x61, 0x35, 0x67, 0x77, 0x32, 0x61, 0x31, 0x00, 0x69, + 0x74, 0x74, 0x35, 0x67, 0x61, 0x30, 0x00, 0x69, 0x74, 0x74, 0x35, 0x67, + 0x61, 0x31, 0x00, 0x6f, 0x66, 0x64, 0x6d, 0x35, 0x67, 0x70, 0x6f, 0x00, + 0x6d, 0x63, 0x73, 0x35, 0x67, 0x70, 0x6f, 0x30, 0x00, 0x6d, 0x63, 0x73, + 0x35, 0x67, 0x70, 0x6f, 0x31, 0x00, 0x6d, 0x63, 0x73, 0x35, 0x67, 0x70, + 0x6f, 0x32, 0x00, 0x6d, 0x63, 0x73, 0x35, 0x67, 0x70, 0x6f, 0x33, 0x00, + 0x6d, 0x63, 0x73, 0x35, 0x67, 0x70, 0x6f, 0x34, 0x00, 0x6d, 0x63, 0x73, + 0x35, 0x67, 0x70, 0x6f, 0x35, 0x00, 0x6d, 0x63, 0x73, 0x35, 0x67, 0x70, + 0x6f, 0x36, 0x00, 0x6d, 0x63, 0x73, 0x35, 0x67, 0x70, 0x6f, 0x37, 0x00, + 0x74, 0x78, 0x70, 0x69, 0x64, 0x35, 0x67, 0x68, 0x61, 0x30, 0x00, 0x74, + 0x78, 0x70, 0x69, 0x64, 0x35, 0x67, 0x68, 0x61, 0x31, 0x00, 0x6d, 0x61, + 0x78, 0x70, 0x35, 0x67, 0x68, 0x61, 0x30, 0x00, 0x6d, 0x61, 0x78, 0x70, + 0x35, 0x67, 0x68, 0x61, 0x31, 0x00, 0x70, 0x61, 0x35, 0x67, 0x68, 0x77, + 0x30, 0x61, 0x30, 0x00, 0x70, 0x61, 0x35, 0x67, 0x68, 0x77, 0x30, 0x61, + 0x31, 0x00, 0x70, 0x61, 0x35, 0x67, 0x68, 0x77, 0x31, 0x61, 0x30, 0x00, + 0x70, 0x61, 0x35, 0x67, 0x68, 0x77, 0x31, 0x61, 0x31, 0x00, 0x70, 0x61, + 0x35, 0x67, 0x68, 0x77, 0x32, 0x61, 0x30, 0x00, 0x70, 0x61, 0x35, 0x67, + 0x68, 0x77, 0x32, 0x61, 0x31, 0x00, 0x6f, 0x66, 0x64, 0x6d, 0x35, 0x67, + 0x68, 0x70, 0x6f, 0x00, 0x6d, 0x63, 0x73, 0x35, 0x67, 0x68, 0x70, 0x6f, + 0x30, 0x00, 0x6d, 0x63, 0x73, 0x35, 0x67, 0x68, 0x70, 0x6f, 0x31, 0x00, + 0x6d, 0x63, 0x73, 0x35, 0x67, 0x68, 0x70, 0x6f, 0x32, 0x00, 0x6d, 0x63, + 0x73, 0x35, 0x67, 0x68, 0x70, 0x6f, 0x33, 0x00, 0x6d, 0x63, 0x73, 0x35, + 0x67, 0x68, 0x70, 0x6f, 0x34, 0x00, 0x6d, 0x63, 0x73, 0x35, 0x67, 0x68, + 0x70, 0x6f, 0x35, 0x00, 0x6d, 0x63, 0x73, 0x35, 0x67, 0x68, 0x70, 0x6f, + 0x36, 0x00, 0x6d, 0x63, 0x73, 0x35, 0x67, 0x68, 0x70, 0x6f, 0x37, 0x00, + 0x61, 0x6e, 0x74, 0x73, 0x77, 0x69, 0x74, 0x63, 0x68, 0x00, 0x61, 0x61, + 0x35, 0x67, 0x00, 0x74, 0x73, 0x73, 0x69, 0x70, 0x6f, 0x73, 0x32, 0x67, + 0x00, 0x65, 0x78, 0x74, 0x70, 0x61, 0x67, 0x61, 0x69, 0x6e, 0x32, 0x67, + 0x00, 0x70, 0x64, 0x65, 0x74, 0x72, 0x61, 0x6e, 0x67, 0x65, 0x32, 0x67, + 0x00, 0x74, 0x72, 0x69, 0x73, 0x6f, 0x32, 0x67, 0x00, 0x61, 0x6e, 0x74, + 0x73, 0x77, 0x63, 0x74, 0x6c, 0x32, 0x67, 0x00, 0x74, 0x73, 0x73, 0x69, + 0x70, 0x6f, 0x73, 0x35, 0x67, 0x00, 0x65, 0x78, 0x74, 0x70, 0x61, 0x67, + 0x61, 0x69, 0x6e, 0x35, 0x67, 0x00, 0x70, 0x64, 0x65, 0x74, 0x72, 0x61, + 0x6e, 0x67, 0x65, 0x35, 0x67, 0x00, 0x74, 0x72, 0x69, 0x73, 0x6f, 0x35, + 0x67, 0x00, 0x61, 0x6e, 0x74, 0x73, 0x77, 0x63, 0x74, 0x6c, 0x35, 0x67, + 0x00, 0x65, 0x6c, 0x6e, 0x61, 0x32, 0x67, 0x00, 0x65, 0x6c, 0x6e, 0x61, + 0x35, 0x67, 0x00, 0x74, 0x65, 0x6d, 0x70, 0x6f, 0x66, 0x66, 0x73, 0x65, + 0x74, 0x00, 0x70, 0x68, 0x79, 0x63, 0x61, 0x6c, 0x5f, 0x74, 0x65, 0x6d, + 0x70, 0x64, 0x65, 0x6c, 0x74, 0x61, 0x00, 0x70, 0x61, 0x32, 0x67, 0x77, + 0x30, 0x61, 0x33, 0x00, 0x70, 0x61, 0x32, 0x67, 0x77, 0x31, 0x61, 0x33, + 0x00, 0x6d, 0x61, 0x78, 0x70, 0x35, 0x67, 0x61, 0x33, 0x00, 0x6d, 0x61, + 0x78, 0x70, 0x35, 0x67, 0x6c, 0x61, 0x33, 0x00, 0x70, 0x61, 0x35, 0x67, + 0x77, 0x30, 0x61, 0x33, 0x00, 0x70, 0x61, 0x35, 0x67, 0x6c, 0x77, 0x30, + 0x61, 0x33, 0x00, 0x70, 0x61, 0x35, 0x67, 0x77, 0x31, 0x61, 0x33, 0x00, + 0x70, 0x61, 0x35, 0x67, 0x6c, 0x77, 0x31, 0x61, 0x33, 0x00, 0x70, 0x61, + 0x35, 0x67, 0x77, 0x32, 0x61, 0x33, 0x00, 0x70, 0x61, 0x35, 0x67, 0x6c, + 0x77, 0x32, 0x61, 0x33, 0x00, 0x00, 0x3b, 0x49, 0x17, 0x20, 0x3c, 0x49, + 0xc5, 0x27, 0x4d, 0x84, 0xff, 0x83, 0x4c, 0xc4, 0x00, 0x1f, 0xb7, 0x84, + 0xff, 0x80, 0xb1, 0x84, 0xff, 0xdf, 0xb0, 0xc4, 0x08, 0x08, 0xfa, 0x84, + 0xf7, 0xff, 0xf9, 0xc4, 0x08, 0x00, 0x60, 0x30, 0x18, 0x0c, 0x6c, 0x48, + 0x24, 0x12, 0x00, 0x00, 0xa8, 0xe5, 0x01, 0x00, 0x35, 0x01, 0x08, 0x30, + 0x08, 0x00, 0x03, 0x00, 0xb2, 0xe5, 0x01, 0x00, 0x43, 0x01, 0x00, 0x00, + 0x01, 0x00, 0x00, 0x00, 0xbc, 0xe5, 0x01, 0x00, 0x2d, 0x01, 0x08, 0x00, + 0x01, 0x00, 0x00, 0x00, 0xc9, 0xe5, 0x01, 0x00, 0x48, 0x01, 0x08, 0x00, + 0x03, 0x00, 0x00, 0x00, 0xd9, 0xe5, 0x01, 0x00, 0x49, 0x01, 0x08, 0x00, + 0x03, 0x00, 0x00, 0x00, 0xe6, 0xe5, 0x01, 0x00, 0x4a, 0x01, 0x08, 0x00, + 0x03, 0x00, 0x00, 0x00, 0xf4, 0xe5, 0x01, 0x00, 0x4e, 0x01, 0x08, 0x00, + 0x03, 0x00, 0x00, 0x00, 0xff, 0xe5, 0x01, 0x00, 0x3d, 0x01, 0x40, 0x00, + 0x07, 0x00, 0x07, 0x00, 0x0b, 0xe6, 0x01, 0x00, 0x7a, 0x01, 0x00, 0x04, + 0x07, 0x00, 0x00, 0x00, 0x19, 0xe6, 0x01, 0x00, 0x3f, 0x01, 0x00, 0x00, + 0x06, 0x00, 0x00, 0x00, 0x24, 0xe6, 0x01, 0x00, 0x40, 0x01, 0x00, 0x00, + 0x02, 0x00, 0x00, 0x00, 0x2f, 0xe6, 0x01, 0x00, 0x7c, 0x01, 0x00, 0x00, + 0x02, 0x00, 0x00, 0x00, 0x3c, 0xe6, 0x01, 0x00, 0x42, 0x01, 0x00, 0x00, + 0x07, 0x00, 0x00, 0x00, 0x48, 0xe6, 0x01, 0x00, 0x28, 0x00, 0x08, 0x00, + 0x03, 0x00, 0x00, 0x00, 0x59, 0xe6, 0x01, 0x00, 0x29, 0x00, 0x00, 0x00, + 0x01, 0x00, 0x00, 0x00, 0x66, 0xe6, 0x01, 0x00, 0x7f, 0x01, 0x00, 0x00, + 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x70, 0x68, 0x79, 0x00, 0x74, 0x78, 0x69, 0x6e, + 0x73, 0x74, 0x70, 0x77, 0x72, 0x00, 0x70, 0x68, 0x79, 0x5f, 0x6d, 0x75, + 0x74, 0x65, 0x64, 0x00, 0x70, 0x68, 0x79, 0x5f, 0x77, 0x61, 0x74, 0x63, + 0x68, 0x64, 0x6f, 0x67, 0x00, 0x70, 0x68, 0x79, 0x5f, 0x67, 0x6c, 0x69, + 0x74, 0x63, 0x68, 0x74, 0x68, 0x72, 0x73, 0x68, 0x00, 0x70, 0x68, 0x79, + 0x5f, 0x6e, 0x6f, 0x69, 0x73, 0x65, 0x5f, 0x75, 0x70, 0x00, 0x70, 0x68, + 0x79, 0x5f, 0x6e, 0x6f, 0x69, 0x73, 0x65, 0x5f, 0x64, 0x77, 0x6e, 0x00, + 0x70, 0x68, 0x79, 0x5f, 0x70, 0x65, 0x72, 0x63, 0x61, 0x6c, 0x00, 0x70, + 0x68, 0x79, 0x5f, 0x72, 0x78, 0x69, 0x71, 0x65, 0x73, 0x74, 0x00, 0x70, + 0x68, 0x79, 0x6e, 0x6f, 0x69, 0x73, 0x65, 0x5f, 0x73, 0x72, 0x6f, 0x6d, + 0x00, 0x6e, 0x75, 0x6d, 0x5f, 0x73, 0x74, 0x72, 0x65, 0x61, 0x6d, 0x00, + 0x62, 0x61, 0x6e, 0x64, 0x5f, 0x72, 0x61, 0x6e, 0x67, 0x65, 0x00, 0x73, + 0x75, 0x62, 0x62, 0x61, 0x6e, 0x64, 0x35, 0x67, 0x76, 0x65, 0x72, 0x00, + 0x6d, 0x69, 0x6e, 0x5f, 0x74, 0x78, 0x70, 0x6f, 0x77, 0x65, 0x72, 0x00, + 0x70, 0x68, 0x79, 0x5f, 0x6f, 0x63, 0x6c, 0x73, 0x63, 0x64, 0x65, 0x6e, + 0x61, 0x62, 0x6c, 0x65, 0x00, 0x70, 0x68, 0x79, 0x5f, 0x72, 0x78, 0x61, + 0x6e, 0x74, 0x73, 0x65, 0x6c, 0x00, 0x70, 0x68, 0x79, 0x5f, 0x63, 0x72, + 0x73, 0x5f, 0x77, 0x61, 0x72, 0x00, 0x4a, 0xc4, 0x44, 0x00, 0x4a, 0x44, + 0x80, 0x00, 0x3b, 0x04, 0x01, 0x00, 0x01, 0x00, 0x3c, 0x04, 0x01, 0x00, + 0x01, 0x00, 0x3c, 0x04, 0x01, 0x00, 0x00, 0x00, 0x3b, 0x04, 0x01, 0x00, + 0x00, 0x00, 0x3b, 0x04, 0x02, 0x00, 0x02, 0x00, 0x3c, 0x04, 0x02, 0x00, + 0x02, 0x00, 0x3c, 0x04, 0x02, 0x00, 0x00, 0x00, 0x3b, 0x04, 0x02, 0x00, + 0x00, 0x00, 0xdb, 0x04, 0xff, 0x03, 0xa6, 0x02, 0xdb, 0x04, 0x00, 0x70, + 0x00, 0x20, 0x9a, 0x05, 0xff, 0x03, 0x26, 0x00, 0x9b, 0x05, 0xff, 0x03, + 0x89, 0x00, 0x9c, 0x05, 0xff, 0x03, 0x8a, 0x00, 0x9c, 0x05, 0x00, 0xfc, + 0x00, 0x20, 0x9d, 0x05, 0x00, 0x3c, 0x00, 0x2c, 0x9d, 0x05, 0xff, 0x03, + 0x8c, 0x00, 0xd8, 0x04, 0x01, 0x00, 0x00, 0x00, 0xd8, 0x04, 0x02, 0x00, + 0x00, 0x00, 0xd7, 0x04, 0x08, 0x00, 0x00, 0x00, 0x00, 0x40, 0x01, 0x40, + 0x02, 0x40, 0x03, 0x40, 0x04, 0x40, 0x05, 0x40, 0x06, 0x40, 0x07, 0x40, + 0x07, 0x5b, 0x07, 0x80, 0x98, 0x00, 0x16, 0x01, 0x2c, 0x01, 0x6a, 0x00, + 0x0b, 0x00, 0x1b, 0x00, 0x13, 0x01, 0x1d, 0x00, 0x14, 0x01, 0x2e, 0x00, + 0x2a, 0x01, 0x12, 0x01, 0x4c, 0x04, 0x00, 0x08, 0x00, 0x08, 0x4d, 0x04, + 0x00, 0x20, 0x00, 0x00, 0xb0, 0x04, 0x00, 0x01, 0x00, 0x01, 0xb6, 0x44, + 0xff, 0xff, 0xb7, 0x04, 0x0f, 0x00, 0x0f, 0x00, 0x4a, 0xc4, 0x44, 0x00, + 0x4a, 0x44, 0x80, 0x00, 0xd7, 0x04, 0x08, 0x00, 0x08, 0x00, 0xd7, 0x04, + 0x00, 0x70, 0x00, 0x20, 0x31, 0xc6, 0x15, 0x00, 0xd6, 0x06, 0x03, 0x00, + 0x00, 0x00, 0xda, 0xc6, 0x8f, 0x00, 0x4c, 0x04, 0x00, 0x10, 0x00, 0x10, + 0x4d, 0x04, 0x00, 0x40, 0x00, 0x40, 0x4c, 0x04, 0x00, 0x08, 0x00, 0x08, + 0x4d, 0x04, 0x00, 0x20, 0x00, 0x00, 0x3b, 0x04, 0x02, 0x00, 0x02, 0x00, + 0x3c, 0x04, 0x02, 0x00, 0x00, 0x00, 0x3b, 0x04, 0x01, 0x00, 0x01, 0x00, + 0x3c, 0x04, 0x01, 0x00, 0x00, 0x00, 0xd7, 0x44, 0x00, 0x00, 0xd7, 0x04, + 0x01, 0x00, 0x01, 0x00, 0xd7, 0x04, 0x40, 0x00, 0x00, 0x00, 0xd7, 0x04, + 0x01, 0x00, 0x01, 0x00, 0xd7, 0x04, 0x40, 0x00, 0x40, 0x00, 0x10, 0x04, + 0x08, 0x00, 0x08, 0x00, 0xda, 0x06, 0x20, 0x00, 0x00, 0x00, 0x42, 0x49, + 0x02, 0x00, 0x3b, 0x49, 0x00, 0x00, 0x3c, 0x49, 0x00, 0x00, 0x4a, 0xc4, + 0x44, 0x00, 0x4a, 0x44, 0x80, 0x00, 0x38, 0x09, 0x40, 0x00, 0x40, 0x00, + 0x38, 0x09, 0x04, 0x00, 0x04, 0x00, 0x39, 0x09, 0x40, 0x00, 0x00, 0x00, + 0x39, 0x09, 0x04, 0x00, 0x04, 0x00, 0xd7, 0x04, 0x02, 0x00, 0x02, 0x00, + 0xd7, 0x04, 0x80, 0x00, 0x00, 0x00, 0xd7, 0x04, 0x01, 0x00, 0x01, 0x00, + 0xd7, 0x04, 0x40, 0x00, 0x40, 0x00, 0xd7, 0x04, 0x08, 0x00, 0x08, 0x00, + 0xd7, 0x04, 0x00, 0x70, 0x00, 0x20, 0xda, 0x06, 0x40, 0x00, 0x40, 0x00, + 0xa4, 0x04, 0x00, 0x20, 0x00, 0x00, 0x4c, 0x84, 0xff, 0xe7, 0x3b, 0x84, + 0x0c, 0x00, 0x4c, 0x04, 0x00, 0x08, 0x00, 0x08, 0x4d, 0x04, 0x00, 0x20, + 0x00, 0x20, 0xb0, 0x04, 0x00, 0x01, 0x00, 0x01, 0x25, 0x64, 0x20, 0x09, + 0x20, 0x25, 0x64, 0x20, 0x0a, 0x00, 0x45, 0x72, 0x72, 0x6f, 0x72, 0x20, + 0x67, 0x65, 0x74, 0x74, 0x69, 0x6e, 0x67, 0x20, 0x6c, 0x6f, 0x77, 0x20, + 0x69, 0x71, 0x20, 0x65, 0x73, 0x74, 0x0a, 0x00, 0x45, 0x72, 0x72, 0x6f, + 0x72, 0x20, 0x67, 0x65, 0x74, 0x74, 0x69, 0x6e, 0x67, 0x20, 0x68, 0x69, + 0x67, 0x68, 0x20, 0x69, 0x71, 0x20, 0x65, 0x73, 0x74, 0x0a, 0x00, 0x00, + 0xa3, 0xc6, 0x01, 0x00, 0xa3, 0x86, 0xfe, 0xff, 0x4a, 0xc4, 0x80, 0x00, + 0x4a, 0x84, 0x7f, 0x00, 0x3b, 0x84, 0xed, 0xff, 0x3c, 0x04, 0x02, 0x00, + 0x02, 0x00, 0x4c, 0x84, 0xd0, 0xef, 0x4d, 0x84, 0xd7, 0xbf, 0x4d, 0x04, + 0x04, 0x00, 0x04, 0x00, 0x4d, 0x04, 0x03, 0x00, 0x01, 0x00, 0xf9, 0x84, + 0xf8, 0xff, 0xfa, 0x84, 0xf8, 0xff, 0x0a, 0x46, 0xa0, 0x00, 0x6a, 0x44, + 0x19, 0x00, 0x4d, 0x04, 0x04, 0x00, 0x00, 0x00, 0x4c, 0x04, 0x04, 0x00, + 0x04, 0x00, 0xd7, 0x04, 0x01, 0x00, 0x01, 0x00, 0xd7, 0x04, 0x40, 0x00, + 0x40, 0x00, 0xd7, 0x04, 0x01, 0x00, 0x01, 0x00, 0xd7, 0x04, 0x40, 0x00, + 0x00, 0x00, 0x37, 0x06, 0x00, 0xc0, 0x00, 0x80, 0xd7, 0x04, 0x01, 0x00, + 0x00, 0x00, 0xd9, 0x04, 0x01, 0x00, 0x01, 0x00, 0xd9, 0x04, 0x02, 0x00, + 0x00, 0x00, 0x76, 0x06, 0x80, 0x00, 0x80, 0x00, 0xda, 0x06, 0x01, 0x00, + 0x01, 0x00, 0x6c, 0x08, 0x04, 0x00, 0x04, 0x00, 0x6c, 0x08, 0x40, 0x00, + 0x40, 0x00, 0x6c, 0x08, 0x00, 0x04, 0x00, 0x04, 0xd6, 0x06, 0x03, 0x00, + 0x00, 0x00, 0xda, 0x06, 0x08, 0x00, 0x08, 0x00, 0x3b, 0x04, 0x02, 0x00, + 0x02, 0x00, 0x3c, 0x04, 0x02, 0x00, 0x00, 0x00, 0x3b, 0x04, 0x10, 0x00, + 0x10, 0x00, 0x3c, 0x04, 0x40, 0x00, 0x00, 0x00, 0x4b, 0x44, 0xff, 0xff, + 0x34, 0x06, 0x00, 0xff, 0x00, 0x00, 0xda, 0xc6, 0x80, 0x00, 0x0a, 0xc0, + 0x28, 0x02, 0x0a, 0x80, 0xd7, 0xfd, 0xda, 0x86, 0x7f, 0xff, 0xa4, 0x04, + 0x00, 0x40, 0x00, 0x40, 0xa4, 0x04, 0x00, 0x40, 0x00, 0x00, 0xda, 0xc6, + 0x40, 0x00, 0x3b, 0x04, 0x04, 0x00, 0x00, 0x00, 0x38, 0x09, 0x40, 0x00, + 0x00, 0x00, 0x38, 0x09, 0x04, 0x00, 0x00, 0x00, 0xd7, 0x04, 0x02, 0x00, + 0x00, 0x00, 0xd7, 0x04, 0x01, 0x00, 0x00, 0x00, 0xd7, 0x04, 0x08, 0x00, + 0x00, 0x00, 0xd8, 0x04, 0x01, 0x00, 0x00, 0x00, 0xd8, 0x04, 0x02, 0x00, + 0x00, 0x00, 0x76, 0x06, 0x80, 0x00, 0x00, 0x00, 0xda, 0x06, 0x01, 0x00, + 0x00, 0x00, 0x6c, 0x08, 0x04, 0x00, 0x00, 0x00, 0x6c, 0x08, 0x40, 0x00, + 0x00, 0x00, 0x6c, 0x08, 0x00, 0x04, 0x00, 0x00, 0xa4, 0x04, 0x00, 0x80, + 0x00, 0x80, 0xa4, 0x04, 0x00, 0x40, 0x00, 0x40, 0xa4, 0x04, 0x00, 0x20, + 0x00, 0x20, 0xb0, 0x04, 0x80, 0x00, 0x00, 0x00, 0x3b, 0x04, 0x40, 0x00, + 0x00, 0x00, 0xa9, 0x04, 0x00, 0x80, 0x00, 0x80, 0x18, 0x08, 0x87, 0x46, + 0x60, 0x00, 0x42, 0x46, 0x07, 0x00, 0x8b, 0x46, 0x00, 0x00, 0x76, 0x46, + 0xa1, 0xb8, 0x76, 0x06, 0x80, 0x00, 0x00, 0x00, 0xda, 0x06, 0x01, 0x00, + 0x00, 0x00, 0x6c, 0x08, 0x04, 0x00, 0x00, 0x00, 0x6c, 0x08, 0x40, 0x00, + 0x00, 0x00, 0x6c, 0x08, 0x00, 0x04, 0x00, 0x00, 0xda, 0x06, 0x00, 0x80, + 0x00, 0x80, 0xd3, 0x06, 0x00, 0x80, 0x00, 0x80, 0xd3, 0x06, 0x00, 0x80, + 0x00, 0x00, 0xda, 0x06, 0x00, 0x80, 0x00, 0x00, 0x42, 0x49, 0x07, 0x00, + 0x3b, 0x49, 0x17, 0x20, 0x3c, 0x49, 0xc5, 0x27, 0xd1, 0x06, 0x04, 0x00, + 0x00, 0x00, 0x4b, 0x06, 0x40, 0x00, 0x40, 0x00, 0x3b, 0x49, 0x17, 0x20, + 0x3c, 0x49, 0xc5, 0x27, 0x4b, 0x06, 0x01, 0x00, 0x01, 0x00, 0x4b, 0x06, + 0x08, 0x00, 0x08, 0x00, 0x42, 0x49, 0x00, 0x00, 0x42, 0x49, 0x0f, 0x00, + 0x42, 0x49, 0x00, 0x00, 0x3b, 0x49, 0x17, 0x00, 0x3c, 0x49, 0xc5, 0x07, + 0x3b, 0x04, 0x02, 0x00, 0x02, 0x00, 0x3c, 0x04, 0x02, 0x00, 0x00, 0x00, + 0x3b, 0x04, 0x10, 0x00, 0x10, 0x00, 0x3c, 0x04, 0x40, 0x00, 0x00, 0x00, + 0x4c, 0x04, 0x00, 0x10, 0x00, 0x10, 0x4d, 0x04, 0x00, 0x40, 0x00, 0x40, + 0x4c, 0x04, 0x08, 0x00, 0x08, 0x00, 0x4d, 0x04, 0x08, 0x00, 0x08, 0x00, + 0x4c, 0x04, 0x20, 0x00, 0x20, 0x00, 0x4d, 0x04, 0x20, 0x00, 0x00, 0x00, + 0xf9, 0x04, 0x02, 0x00, 0x02, 0x00, 0xfa, 0x04, 0x02, 0x00, 0x02, 0x00, + 0xf9, 0x04, 0x04, 0x00, 0x04, 0x00, 0xfa, 0x04, 0x04, 0x00, 0x04, 0x00, + 0xf9, 0x04, 0x01, 0x00, 0x01, 0x00, 0xfa, 0x04, 0x01, 0x00, 0x01, 0x00, + 0x4c, 0x04, 0x08, 0x00, 0x08, 0x00, 0x4d, 0x04, 0x08, 0x00, 0x00, 0x00, + 0x4c, 0x04, 0x20, 0x00, 0x20, 0x00, 0x4d, 0x04, 0x20, 0x00, 0x20, 0x00, + 0xf9, 0x04, 0x02, 0x00, 0x02, 0x00, 0xfa, 0x04, 0x02, 0x00, 0x00, 0x00, + 0xf9, 0x04, 0x04, 0x00, 0x04, 0x00, 0xfa, 0x04, 0x04, 0x00, 0x00, 0x00, + 0xf9, 0x04, 0x01, 0x00, 0x01, 0x00, 0xfa, 0x04, 0x01, 0x00, 0x00, 0x00, + 0x4a, 0xc4, 0x44, 0x00, 0x4a, 0x44, 0x80, 0x00, 0x36, 0x00, 0x1a, 0x01, + 0x3a, 0x00, 0x25, 0x00, 0x28, 0x00, 0x05, 0x00, 0x12, 0x01, 0xff, 0x00, + 0x1f, 0x01, 0x0b, 0x00, 0x13, 0x01, 0x07, 0x00, 0xfc, 0x00, 0xfd, 0x00, + 0xff, 0x00, 0xc0, 0x00, 0xca, 0x00, 0xc5, 0x00, 0x12, 0x00, 0x57, 0x00, + 0x59, 0x00, 0x5c, 0x00, 0x78, 0x00, 0x92, 0x00, 0xda, 0x06, 0x20, 0x00, + 0x20, 0x00, 0x10, 0x04, 0x08, 0x00, 0x00, 0x00, 0x03, 0x05, 0xa4, 0x04, + 0xd0, 0x04, 0xd9, 0x04, 0xda, 0x04, 0xa6, 0x04, 0x38, 0x09, 0x39, 0x09, + 0xd8, 0x04, 0xd0, 0x04, 0xd7, 0x04, 0xa5, 0x04, 0x0d, 0x04, 0xa2, 0x04, + 0xd0, 0x04, 0x01, 0x00, 0x00, 0x00, 0xd3, 0x04, 0xff, 0x00, 0x00, 0x00, + 0xd3, 0x04, 0x00, 0xff, 0x00, 0x00, 0xd0, 0x04, 0x10, 0x00, 0x00, 0x00, + 0xd0, 0x04, 0x04, 0x00, 0x00, 0x00, 0xd0, 0x04, 0x02, 0x00, 0x00, 0x00, + 0xd2, 0x04, 0xff, 0x00, 0x00, 0x00, 0xd2, 0x04, 0x00, 0xff, 0x00, 0x00, + 0xd0, 0x04, 0x08, 0x00, 0x00, 0x00, 0x10, 0x04, 0x80, 0x00, 0x00, 0x00, + 0xa8, 0x44, 0x0a, 0x00, 0xeb, 0x04, 0xc0, 0x01, 0x00, 0x00, 0x6a, 0x04, + 0xff, 0xff, 0x19, 0x00, 0x10, 0x04, 0x02, 0x00, 0x00, 0x00, 0x10, 0x04, + 0x01, 0x00, 0x00, 0x00, 0x42, 0x49, 0x0f, 0x00, 0x42, 0x49, 0x00, 0x00, + 0x42, 0x49, 0x0f, 0x00, 0x4a, 0x44, 0x84, 0x00, 0x4a, 0x44, 0x80, 0x00, + 0xd3, 0x46, 0x22, 0x22, 0xd3, 0x46, 0x20, 0x22, 0x3b, 0x04, 0x01, 0x00, + 0x01, 0x00, 0x3c, 0x04, 0x01, 0x00, 0x00, 0x00, 0x38, 0x09, 0x00, 0x08, + 0x00, 0x08, 0x39, 0x09, 0x00, 0x08, 0x00, 0x08, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x80, 0x07, 0x00, 0x04, 0x00, 0x04, 0x80, 0x07, 0x00, 0x02, + 0x00, 0x02, 0xd7, 0x04, 0x08, 0x00, 0x00, 0x00, 0xd8, 0x04, 0x01, 0x00, + 0x00, 0x00, 0xd8, 0x04, 0x02, 0x00, 0x00, 0x00, 0x3b, 0x04, 0x04, 0x00, + 0x04, 0x00, 0x3c, 0x04, 0x04, 0x00, 0x00, 0x00, 0x03, 0x05, 0x01, 0x00, + 0x00, 0x00, 0x03, 0x05, 0x04, 0x00, 0x00, 0x00, 0x03, 0x05, 0x10, 0x00, + 0x10, 0x00, 0xa4, 0x04, 0x00, 0x40, 0x00, 0x00, 0xa4, 0x04, 0x00, 0x80, + 0x00, 0x80, 0xd0, 0x04, 0x20, 0x00, 0x00, 0x00, 0xa4, 0x04, 0xff, 0x01, + 0x00, 0x00, 0xa5, 0x04, 0xff, 0x00, 0xff, 0x00, 0xa5, 0x04, 0x00, 0x70, + 0x00, 0x50, 0xa5, 0x04, 0x00, 0x07, 0x00, 0x00, 0x0d, 0x04, 0xff, 0x00, + 0x40, 0x00, 0x0d, 0x04, 0x00, 0x07, 0x00, 0x04, 0xa2, 0x04, 0xff, 0x00, + 0x40, 0x00, 0xa2, 0x04, 0x00, 0x07, 0x00, 0x04, 0xa8, 0x04, 0xff, 0x00, + 0x01, 0x00, 0xa6, 0x04, 0x00, 0x80, 0x00, 0x80, 0xa6, 0x04, 0xff, 0x01, + 0xff, 0x00, 0x9a, 0x04, 0xff, 0x01, 0xff, 0x00, 0xd7, 0x04, 0x08, 0x00, + 0x00, 0x00, 0xd7, 0x04, 0x00, 0x70, 0x00, 0x20, 0x03, 0x05, 0x01, 0x00, + 0x00, 0x00, 0x03, 0x05, 0x04, 0x00, 0x00, 0x00, 0xa4, 0x04, 0x00, 0x40, + 0x00, 0x00, 0xa4, 0x04, 0x00, 0x80, 0x00, 0x00, 0xd0, 0x04, 0x20, 0x00, + 0x00, 0x00, 0xa5, 0x04, 0xff, 0x00, 0xff, 0x00, 0xa5, 0x04, 0x00, 0x70, + 0x00, 0x50, 0xa5, 0x04, 0x00, 0x07, 0x00, 0x00, 0x0d, 0x04, 0xff, 0x00, + 0x40, 0x00, 0x0d, 0x04, 0x00, 0x07, 0x00, 0x06, 0xa2, 0x04, 0xff, 0x00, + 0x40, 0x00, 0xa2, 0x04, 0x00, 0x07, 0x00, 0x06, 0xd9, 0x04, 0x70, 0x00, + 0x20, 0x00, 0xd9, 0x04, 0x00, 0x07, 0x00, 0x03, 0xd9, 0x04, 0x00, 0x70, + 0x00, 0x10, 0xda, 0x04, 0x00, 0x10, 0x00, 0x00, 0xda, 0x04, 0x00, 0x20, + 0x00, 0x20, 0xa6, 0x04, 0x00, 0x80, 0x00, 0x80, 0x38, 0x09, 0x04, 0x00, + 0x04, 0x00, 0x39, 0x09, 0x04, 0x00, 0x04, 0x00, 0xa4, 0x04, 0x00, 0x10, + 0x00, 0x10, 0xd7, 0x04, 0x08, 0x00, 0x08, 0x00, 0xd7, 0x04, 0x00, 0x70, + 0x00, 0x10, 0xd7, 0x04, 0x08, 0x00, 0x08, 0x00, 0xd7, 0x04, 0x00, 0x70, + 0x00, 0x30, 0x10, 0x04, 0x02, 0x00, 0x02, 0x00, 0x10, 0x04, 0x01, 0x00, + 0x00, 0x00, 0xd9, 0x04, 0x04, 0x00, 0x00, 0x00, 0xd9, 0x04, 0x08, 0x00, + 0x08, 0x00, 0xd9, 0x04, 0x04, 0x00, 0x04, 0x00, 0xd9, 0x04, 0x08, 0x00, + 0x00, 0x00, 0x9a, 0x05, 0xff, 0x03, 0x26, 0x00, 0x9b, 0x05, 0xff, 0x03, + 0xa5, 0x00, 0x9c, 0x05, 0xff, 0x03, 0xa6, 0x00, 0x9c, 0x05, 0x00, 0xfc, + 0x00, 0x28, 0x9d, 0x05, 0x00, 0x3c, 0x00, 0x1c, 0x9d, 0x05, 0xff, 0x03, + 0xa8, 0x00, 0x53, 0x44, 0xa9, 0x0a, 0x3d, 0x49, 0xc0, 0x00, 0x07, 0x00, + 0xff, 0x00, 0x1f, 0x01, 0x3a, 0x00, 0x1a, 0x01, 0x05, 0x00, 0x82, 0x00, + 0x86, 0x00, 0x2e, 0x01, 0x13, 0x01, 0x7d, 0x00, 0x28, 0x00, 0x81, 0x04, + 0x00, 0x02, 0x00, 0x02, 0x3a, 0x09, 0x80, 0x00, 0x80, 0x00, 0x23, 0x04, + 0xff, 0x00, 0x49, 0x00, 0x34, 0x04, 0xff, 0x00, 0xfc, 0xff, 0x16, 0x04, + 0xff, 0x00, 0xa4, 0xff, 0x16, 0x04, 0x00, 0xff, 0x00, 0x9f, 0x24, 0x04, + 0x00, 0xff, 0x00, 0x2a, 0x23, 0x04, 0x00, 0xff, 0x00, 0x2d, 0x25, 0x04, + 0xff, 0x00, 0x0f, 0x00, 0x00, 0x05, 0xff, 0x00, 0x0f, 0x00, 0x00, 0x05, + 0x00, 0xff, 0x00, 0x0f, 0x20, 0x04, 0xff, 0x00, 0x0a, 0x00, 0x34, 0x04, + 0x00, 0x07, 0x00, 0x01, 0xff, 0x04, 0x00, 0xfc, 0x00, 0x18, 0xd6, 0x06, + 0x03, 0x00, 0x01, 0x00, 0xda, 0x06, 0x08, 0x00, 0x00, 0x00, 0xda, 0x06, + 0x80, 0x00, 0x00, 0x00, 0x10, 0x04, 0x02, 0x00, 0x00, 0x00, 0x10, 0x04, + 0x01, 0x00, 0x01, 0x00, 0x4a, 0xc4, 0x44, 0x00, 0x4a, 0x44, 0x80, 0x00, + 0x4a, 0xc4, 0x44, 0x00, 0x4a, 0x44, 0x80, 0x00, 0x53, 0x84, 0xff, 0x7f, + 0x53, 0xc4, 0x00, 0x80, 0x3b, 0x04, 0x01, 0x00, 0x01, 0x00, 0x3c, 0x04, + 0x01, 0x00, 0x01, 0x00, 0x3c, 0x04, 0x01, 0x00, 0x00, 0x00, 0x3b, 0x04, + 0x01, 0x00, 0x00, 0x00, 0xb1, 0x04, 0x00, 0x04, 0x00, 0x00, 0xb1, 0x04, + 0x00, 0x80, 0x00, 0x00, 0xf9, 0x04, 0x01, 0x00, 0x01, 0x00, 0xfa, 0x04, + 0x01, 0x00, 0x00, 0x00, 0xce, 0x46, 0x00, 0x00, 0xcb, 0x46, 0x00, 0x00, + 0xcc, 0x46, 0x00, 0x00, 0xcd, 0x46, 0x00, 0x00, 0x9d, 0x46, 0xff, 0x07, + 0xa4, 0x46, 0x00, 0x00, 0xa5, 0x46, 0x00, 0x00, 0x7a, 0x46, 0x03, 0x00, + 0x73, 0x46, 0x70, 0x17, 0x74, 0x46, 0x44, 0x04, 0x75, 0x46, 0x3f, 0x00, + 0x70, 0x46, 0x81, 0x06, 0x8c, 0x46, 0x49, 0x00, 0xc9, 0x46, 0x00, 0x06, + 0x80, 0x46, 0xff, 0x00, 0x81, 0x46, 0x3f, 0x01, 0xda, 0xc6, 0x40, 0x00, + 0xdb, 0xc6, 0x03, 0x00, 0xd7, 0xc6, 0x01, 0x00, 0x31, 0xc6, 0x00, 0x18, + 0x3b, 0x44, 0x00, 0x00, 0x3c, 0x44, 0x00, 0x00, 0x4c, 0x44, 0x00, 0x00, + 0xe6, 0x44, 0x00, 0x00, 0xf9, 0x44, 0x00, 0x00, 0xb0, 0x44, 0x00, 0x00, + 0x38, 0x49, 0x00, 0x00, 0xb0, 0x44, 0x00, 0x00, 0x4e, 0x44, 0x00, 0x00, + 0x67, 0xc5, 0x03, 0x00, 0x4a, 0xc4, 0x44, 0x00, 0x4a, 0x44, 0x80, 0x00, + 0x48, 0x04, 0x00, 0x03, 0x00, 0x01, 0x08, 0x06, 0xff, 0x00, 0x17, 0x00, + 0x04, 0x06, 0xff, 0x07, 0xea, 0x03, 0x4c, 0x04, 0x00, 0x18, 0x00, 0x18, + 0x4d, 0x04, 0x00, 0x60, 0x00, 0x60, 0x38, 0x09, 0xff, 0x01, 0xff, 0x01, + 0x39, 0x09, 0xff, 0x01, 0x9e, 0x00, 0x3b, 0x04, 0x03, 0x00, 0x03, 0x00, + 0x3c, 0x04, 0x03, 0x00, 0x00, 0x00, 0xda, 0x46, 0xff, 0xff, 0xdb, 0xc6, + 0x03, 0x00, 0xd1, 0x06, 0x04, 0x00, 0x04, 0x00, 0xb7, 0x04, 0x00, 0x7f, + 0x00, 0x6c, 0xb1, 0x04, 0x00, 0x20, 0x00, 0x00, 0x39, 0x09, 0x00, 0x02, + 0x00, 0x00, 0x38, 0x09, 0x00, 0x02, 0x00, 0x02, 0xb0, 0x04, 0x08, 0x00, + 0x08, 0x00, 0xb0, 0x04, 0x00, 0x08, 0x00, 0x08, 0x39, 0x09, 0x00, 0x08, + 0x00, 0x00, 0x38, 0x09, 0x00, 0x08, 0x00, 0x08, 0x3b, 0x04, 0x04, 0x00, + 0x04, 0x00, 0x3c, 0x04, 0x04, 0x00, 0x00, 0x00, 0x38, 0x09, 0x04, 0x00, + 0x04, 0x00, 0x39, 0x09, 0x04, 0x00, 0x04, 0x00, 0xa4, 0x04, 0x00, 0x10, + 0x00, 0x10, 0xd7, 0x04, 0x04, 0x00, 0x04, 0x00, 0xd7, 0x04, 0x00, 0x0f, + 0x00, 0x00, 0xda, 0x46, 0xff, 0xff, 0x03, 0x05, 0x08, 0x00, 0x08, 0x00, + 0x5f, 0x36, 0x29, 0x1f, 0x5f, 0x36, 0x29, 0x1f, 0x5f, 0x36, 0x29, 0x1f, + 0x5f, 0x36, 0x29, 0x1f, 0x0a, 0x00, 0x09, 0x00, 0x06, 0x00, 0x05, 0x00, + 0x0a, 0x00, 0x09, 0x00, 0x06, 0x00, 0x05, 0x00, 0x0a, 0x00, 0x09, 0x00, + 0x06, 0x00, 0x05, 0x00, 0x0a, 0x00, 0x09, 0x00, 0x06, 0x00, 0x05, 0x00, + 0x0a, 0x00, 0x09, 0x00, 0x06, 0x00, 0x05, 0x00, 0x0a, 0x00, 0x09, 0x00, + 0x06, 0x00, 0x05, 0x00, 0x0a, 0x00, 0x09, 0x00, 0x06, 0x00, 0x05, 0x00, + 0x0a, 0x00, 0x09, 0x00, 0x06, 0x00, 0x05, 0x00, 0x0a, 0x00, 0x09, 0x00, + 0x06, 0x00, 0x05, 0x00, 0x0a, 0x00, 0x09, 0x00, 0x06, 0x00, 0x05, 0x00, + 0x0a, 0x00, 0x09, 0x00, 0x06, 0x00, 0x05, 0x00, 0x0a, 0x00, 0x09, 0x00, + 0x06, 0x00, 0x05, 0x00, 0x0a, 0x00, 0x09, 0x00, 0x06, 0x00, 0x05, 0x00, + 0x0a, 0x00, 0x09, 0x00, 0x06, 0x00, 0x05, 0x00, 0x0a, 0x00, 0x09, 0x00, + 0x06, 0x00, 0x05, 0x00, 0x0a, 0x00, 0x09, 0x00, 0x06, 0x00, 0x05, 0x00, + 0x0e, 0x00, 0x00, 0x00, 0x00, 0x02, 0x00, 0x03, 0x00, 0x04, 0x00, 0x06, + 0x00, 0x08, 0x00, 0x0b, 0x00, 0x10, 0x01, 0x10, 0x02, 0x10, 0x03, 0x10, + 0x04, 0x10, 0x05, 0x10, 0x06, 0x10, 0x07, 0x10, 0x07, 0x17, 0x07, 0x20, + 0x07, 0x2d, 0x07, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x00, 0x03, + 0x00, 0x04, 0x00, 0x06, 0x00, 0x08, 0x00, 0x0b, 0x00, 0x10, 0x01, 0x10, + 0x02, 0x10, 0x03, 0x10, 0x04, 0x10, 0x05, 0x10, 0x06, 0x10, 0x07, 0x10, + 0x07, 0x17, 0x07, 0x20, 0x07, 0x2d, 0x07, 0x40, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0xf8, 0x41, 0x01, 0x00, 0xf8, 0x21, 0x00, 0x00, + 0xfb, 0x21, 0x00, 0x00, 0xfb, 0x41, 0x00, 0x00, 0xdb, 0xfe, 0x01, 0x00, + 0x7b, 0x21, 0x00, 0x00, 0x33, 0x21, 0x00, 0x00, 0xeb, 0x40, 0x00, 0x00, + 0xa3, 0xfe, 0x01, 0x00, 0x4b, 0x02, 0x00, 0x00, 0x94, 0xfd, 0x01, 0x00, + 0x10, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x08, 0x00, 0x00, 0x00, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, + 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, + 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, + 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, + 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, + 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, + 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, + 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, + 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, + 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, + 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, 0x4d, 0x01, + 0x09, 0x0f, 0x14, 0x18, 0xfe, 0x07, 0x0b, 0x0f, 0xfb, 0xfe, 0x01, 0x05, + 0x08, 0x0b, 0x0e, 0x11, 0x14, 0x17, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x03, 0x06, 0x09, 0x0c, 0x0f, 0x12, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x06, 0x09, 0x0c, 0x0f, 0x12, 0x15, + 0x18, 0x1b, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0xeb, 0x00, 0x00, + 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, + 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, + 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x02, 0x03, 0x01, 0x03, 0x02, 0x01, + 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, + 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, + 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, + 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, + 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x02, 0x03, + 0x01, 0x03, 0x02, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, + 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, + 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x04, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, + 0x05, 0x00, 0x00, 0x00, 0x09, 0x00, 0x00, 0x00, 0x0d, 0x00, 0x00, 0x00, + 0x4d, 0x00, 0x00, 0x00, 0x8d, 0x00, 0x00, 0x00, 0x0d, 0x00, 0x00, 0x00, + 0x4d, 0x00, 0x00, 0x00, 0x8d, 0x00, 0x00, 0x00, 0xcd, 0x00, 0x00, 0x00, + 0x4f, 0x00, 0x00, 0x00, 0x8f, 0x00, 0x00, 0x00, 0xcf, 0x00, 0x00, 0x00, + 0xd3, 0x00, 0x00, 0x00, 0x13, 0x01, 0x00, 0x00, 0x13, 0x05, 0x00, 0x00, + 0x13, 0x09, 0x00, 0x00, 0x53, 0x09, 0x00, 0x00, 0x53, 0x0d, 0x00, 0x00, + 0x53, 0x11, 0x00, 0x00, 0x93, 0x11, 0x00, 0x00, 0x93, 0x51, 0x00, 0x00, + 0x93, 0x91, 0x00, 0x00, 0x93, 0xd1, 0x00, 0x00, 0x93, 0x11, 0x01, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, + 0x08, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x05, 0x00, 0x00, 0x00, + 0x09, 0x00, 0x00, 0x00, 0x0d, 0x00, 0x00, 0x00, 0x4d, 0x00, 0x00, 0x00, + 0x8d, 0x00, 0x00, 0x00, 0x0d, 0x00, 0x00, 0x00, 0x4d, 0x00, 0x00, 0x00, + 0x8d, 0x00, 0x00, 0x00, 0xcd, 0x00, 0x00, 0x00, 0x4f, 0x00, 0x00, 0x00, + 0x8f, 0x00, 0x00, 0x00, 0xcf, 0x00, 0x00, 0x00, 0xd3, 0x00, 0x00, 0x00, + 0x13, 0x01, 0x00, 0x00, 0x13, 0x05, 0x00, 0x00, 0x13, 0x09, 0x00, 0x00, + 0x53, 0x09, 0x00, 0x00, 0x53, 0x0d, 0x00, 0x00, 0x53, 0x11, 0x00, 0x00, + 0x53, 0x51, 0x00, 0x00, 0x53, 0x91, 0x00, 0x00, 0x53, 0xd1, 0x00, 0x00, + 0x53, 0x11, 0x01, 0x00, 0x53, 0x51, 0x01, 0x00, 0x53, 0x91, 0x01, 0x00, + 0x53, 0xd1, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x04, 0x02, 0x04, + 0x03, 0x04, 0x04, 0x04, 0x05, 0x04, 0x06, 0x04, 0x07, 0x04, 0x08, 0x04, + 0x09, 0x04, 0x0a, 0x04, 0x8b, 0x05, 0x8c, 0x05, 0x8d, 0x05, 0x8e, 0x05, + 0x8f, 0x05, 0x90, 0x00, 0x91, 0x00, 0x92, 0x00, 0x93, 0x01, 0x94, 0x01, + 0x95, 0x01, 0x96, 0x01, 0x97, 0x01, 0x98, 0x01, 0x99, 0x01, 0x9a, 0x01, + 0x9b, 0x01, 0x9c, 0x01, 0x9d, 0x01, 0x9e, 0x01, 0x9f, 0x01, 0xa0, 0x01, + 0xa1, 0x01, 0xa2, 0x01, 0xa3, 0x01, 0xa4, 0x01, 0xa5, 0x01, 0x00, 0x00, + 0x08, 0xf1, 0x01, 0x00, 0x40, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0xdc, 0xf7, 0x01, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x10, 0x00, 0x00, 0x00, 0xcc, 0xf0, 0x01, 0x00, 0x0a, 0x00, 0x00, 0x00, + 0x0b, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x00, 0x00, 0x00, + 0xdc, 0xfa, 0x01, 0x00, 0x14, 0x00, 0x00, 0x00, 0x0c, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x20, 0x00, 0x00, 0x00, 0x30, 0xfb, 0x01, 0x00, + 0x94, 0x00, 0x00, 0x00, 0x0d, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x20, 0x00, 0x00, 0x00, 0xc4, 0xf3, 0x01, 0x00, 0x26, 0x00, 0x00, 0x00, + 0x0e, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, + 0x70, 0xef, 0x01, 0x00, 0x40, 0x00, 0x00, 0x00, 0x0f, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x60, 0xef, 0x01, 0x00, + 0x10, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x08, 0x00, 0x00, 0x00, 0x88, 0xf1, 0x01, 0x00, 0x3c, 0x00, 0x00, 0x00, + 0x11, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, + 0x44, 0xf2, 0x01, 0x00, 0x60, 0x00, 0x00, 0x00, 0x12, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x20, 0x00, 0x00, 0x00, 0xc4, 0xf1, 0x01, 0x00, + 0x80, 0x00, 0x00, 0x00, 0x14, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x08, 0x00, 0x00, 0x00, 0xa8, 0xf6, 0x01, 0x00, 0x9a, 0x00, 0x00, 0x00, + 0x17, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, + 0xf4, 0xef, 0x01, 0x00, 0x6c, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x5c, 0xf8, 0x01, 0x00, + 0xa0, 0x00, 0x00, 0x00, 0x18, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, + 0x08, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x05, 0x00, 0x00, 0x00, + 0x09, 0x00, 0x00, 0x00, 0x0d, 0x00, 0x00, 0x00, 0x4d, 0x00, 0x00, 0x00, + 0x8d, 0x00, 0x00, 0x00, 0x0d, 0x00, 0x00, 0x00, 0x4d, 0x00, 0x00, 0x00, + 0x8d, 0x00, 0x00, 0x00, 0xcd, 0x00, 0x00, 0x00, 0x52, 0x00, 0x00, 0x00, + 0x92, 0x00, 0x00, 0x00, 0xd2, 0x00, 0x00, 0x00, 0xd6, 0x00, 0x00, 0x00, + 0x16, 0x01, 0x00, 0x00, 0x16, 0x05, 0x00, 0x00, 0x16, 0x09, 0x00, 0x00, + 0x56, 0x09, 0x00, 0x00, 0x56, 0x0d, 0x00, 0x00, 0x56, 0x11, 0x00, 0x00, + 0x96, 0x11, 0x00, 0x00, 0x96, 0x51, 0x00, 0x00, 0x96, 0x91, 0x00, 0x00, + 0x96, 0xd1, 0x00, 0x00, 0x96, 0x11, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, + 0x01, 0x00, 0x00, 0x00, 0x05, 0x00, 0x00, 0x00, 0x09, 0x00, 0x00, 0x00, + 0x0d, 0x00, 0x00, 0x00, 0x4d, 0x00, 0x00, 0x00, 0x8d, 0x00, 0x00, 0x00, + 0x0d, 0x00, 0x00, 0x00, 0x4d, 0x00, 0x00, 0x00, 0x8d, 0x00, 0x00, 0x00, + 0xcd, 0x00, 0x00, 0x00, 0x52, 0x00, 0x00, 0x00, 0x92, 0x00, 0x00, 0x00, + 0xd2, 0x00, 0x00, 0x00, 0xd6, 0x00, 0x00, 0x00, 0x16, 0x01, 0x00, 0x00, + 0x16, 0x05, 0x00, 0x00, 0x16, 0x09, 0x00, 0x00, 0x56, 0x09, 0x00, 0x00, + 0x56, 0x0d, 0x00, 0x00, 0x56, 0x11, 0x00, 0x00, 0x56, 0x51, 0x00, 0x00, + 0x56, 0x91, 0x00, 0x00, 0x56, 0xd1, 0x00, 0x00, 0x56, 0x11, 0x01, 0x00, + 0x56, 0x51, 0x01, 0x00, 0x56, 0x91, 0x01, 0x00, 0x56, 0xd1, 0x01, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x1a, 0x00, 0x34, 0x00, 0x4e, 0x00, 0x68, 0x00, + 0x9c, 0x00, 0xd0, 0x00, 0xea, 0x00, 0x04, 0x01, 0x34, 0x00, 0x68, 0x00, + 0x9c, 0x00, 0xd0, 0x00, 0x38, 0x01, 0xa0, 0x01, 0xd4, 0x01, 0x08, 0x02, + 0x4e, 0x00, 0x9c, 0x00, 0xea, 0x00, 0x38, 0x01, 0xd4, 0x01, 0x70, 0x02, + 0xbe, 0x02, 0x0c, 0x03, 0x68, 0x00, 0xd0, 0x00, 0x38, 0x01, 0xa0, 0x01, + 0x70, 0x02, 0x40, 0x03, 0xa8, 0x03, 0x10, 0x04, 0x18, 0x00, 0x9c, 0x00, + 0xd0, 0x00, 0x04, 0x01, 0xea, 0x00, 0x38, 0x01, 0x86, 0x01, 0xd0, 0x00, + 0x04, 0x01, 0x04, 0x01, 0x38, 0x01, 0x6c, 0x01, 0x6c, 0x01, 0xa0, 0x01, + 0x38, 0x01, 0x86, 0x01, 0x86, 0x01, 0xd4, 0x01, 0x22, 0x02, 0x22, 0x02, + 0x70, 0x02, 0x04, 0x01, 0x38, 0x01, 0x6c, 0x01, 0x38, 0x01, 0x6c, 0x01, + 0xa0, 0x01, 0xd4, 0x01, 0xa0, 0x01, 0xd4, 0x01, 0x08, 0x02, 0x08, 0x02, + 0x3c, 0x02, 0x86, 0x01, 0xd4, 0x01, 0x22, 0x02, 0xd4, 0x01, 0x22, 0x02, + 0x70, 0x02, 0xbe, 0x02, 0x70, 0x02, 0xbe, 0x02, 0x0c, 0x03, 0x0c, 0x03, + 0x5a, 0x03, 0x36, 0x00, 0x6c, 0x00, 0xa2, 0x00, 0xd8, 0x00, 0x44, 0x01, + 0xb0, 0x01, 0xe6, 0x01, 0x1c, 0x02, 0x6c, 0x00, 0xd8, 0x00, 0x44, 0x01, + 0xb0, 0x01, 0x88, 0x02, 0x60, 0x03, 0xcc, 0x03, 0x38, 0x04, 0xa2, 0x00, + 0x44, 0x01, 0xe6, 0x01, 0x88, 0x02, 0xcc, 0x03, 0x10, 0x05, 0xb2, 0x05, + 0x54, 0x06, 0xd8, 0x00, 0xb0, 0x01, 0x88, 0x02, 0x60, 0x03, 0x10, 0x05, + 0xc0, 0x06, 0x98, 0x07, 0x70, 0x08, 0x18, 0x00, 0x44, 0x01, 0xb0, 0x01, + 0x1c, 0x02, 0xe6, 0x01, 0x88, 0x02, 0x2a, 0x03, 0xb0, 0x01, 0x1c, 0x02, + 0x1c, 0x02, 0x88, 0x02, 0xf4, 0x02, 0xf4, 0x02, 0x60, 0x03, 0x88, 0x02, + 0x2a, 0x03, 0x2a, 0x03, 0xcc, 0x03, 0x6e, 0x04, 0x6e, 0x04, 0x10, 0x05, + 0x1c, 0x02, 0x88, 0x02, 0xf4, 0x02, 0x88, 0x02, 0xf4, 0x02, 0x60, 0x03, + 0xcc, 0x03, 0x60, 0x03, 0xcc, 0x03, 0x38, 0x04, 0x38, 0x04, 0xa4, 0x04, + 0x2a, 0x03, 0xcc, 0x03, 0x6e, 0x04, 0xcc, 0x03, 0x6e, 0x04, 0x10, 0x05, + 0xb2, 0x05, 0x10, 0x05, 0xb2, 0x05, 0x54, 0x06, 0x54, 0x06, 0xf6, 0x06, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x01, 0x00, 0x10, 0x00, 0x10, 0x00, 0x20, 0x00, 0x01, 0x00, 0x30, 0x00, + 0x10, 0x00, 0x40, 0x00, 0x22, 0x00, 0x50, 0x00, 0x22, 0x01, 0x60, 0x00, + 0x22, 0x02, 0x70, 0x00, 0x22, 0x03, 0x80, 0x00, 0x22, 0x04, 0x90, 0x00, + 0x22, 0x05, 0xa0, 0x00, 0x22, 0x06, 0xb0, 0x00, 0x22, 0x07, 0xc0, 0x00, + 0x22, 0x08, 0xd0, 0x00, 0x22, 0x09, 0xf0, 0x00, 0x22, 0x0a, 0x10, 0x00, + 0x22, 0x0b, 0x20, 0x00, 0x22, 0x0c, 0x30, 0x00, 0x22, 0x0d, 0x40, 0x00, + 0x22, 0x0e, 0x50, 0x00, 0x22, 0x0f, 0x60, 0x00, 0x05, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x30, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x50, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x90, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xa0, + 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xb0, 0x08, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xc0, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xd0, + 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xe0, 0x08, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xf0, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x09, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, 0x09, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x20, 0x19, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x30, + 0x19, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x19, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x50, 0x19, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x60, + 0x19, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x19, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x80, 0x19, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x90, + 0x19, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xa0, 0x19, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xb0, 0x19, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xc0, + 0x19, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xd0, 0x19, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xe0, 0x19, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xf0, + 0x19, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1a, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x10, 0x1a, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, + 0x1a, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x30, 0x1a, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x40, 0x1a, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x50, + 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x60, 0x02, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x70, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, + 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x90, 0x02, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xa0, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xb0, + 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xc0, 0x0a, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xd0, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xe0, + 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xf0, 0x0a, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x0b, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, + 0x0b, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x0b, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x30, 0x0b, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, + 0x0b, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x50, 0x1b, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x60, 0x1b, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, + 0x1b, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x1b, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x90, 0x1b, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xa0, + 0x1b, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xb0, 0x1b, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xc0, 0x1b, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xd0, + 0x1b, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xe0, 0x1b, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xf0, 0x1b, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x1c, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, 0x1c, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x20, 0x1c, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x30, + 0x1c, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x1c, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x50, 0x1c, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x60, + 0x1c, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x1c, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x80, 0x1c, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x90, + 0x1c, 0x00, 0x00, 0x00, 0x28, 0xf5, 0x01, 0x00, 0x60, 0x00, 0x00, 0x00, + 0x12, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x00, 0x00, 0x00, + 0x5f, 0x36, 0x29, 0x1f, 0x5f, 0x36, 0x29, 0x1f, 0x5f, 0x36, 0x29, 0x1f, + 0x5f, 0x36, 0x29, 0x1f, 0x6e, 0x6f, 0x63, 0x72, 0x63, 0x00, 0x53, 0x44, + 0x49, 0x4f, 0x00, 0x43, 0x44, 0x43, 0x00, 0x00, 0x0d, 0x16, 0x80, 0x00, + 0x8d, 0x13, 0x80, 0x00, 0x25, 0x11, 0x80, 0x00, 0x29, 0x14, 0x80, 0x00, + 0x1d, 0x13, 0x80, 0x00, 0xa1, 0x16, 0x80, 0x00, 0xbd, 0x04, 0x01, 0x00, + 0x01, 0x13, 0x80, 0x00, 0x2d, 0x13, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x1d, 0x16, 0x80, 0x00, 0xc5, 0x27, 0x00, 0x00, 0x77, 0x6c, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0xf0, 0x25, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x05, 0x00, 0x00, 0x00, 0xff, 0xff, 0xff, 0xff, + 0x14, 0x00, 0x00, 0x00, 0x05, 0x00, 0x00, 0x00, 0xff, 0xff, 0xff, 0xff, + 0x01, 0x00, 0x05, 0x06, 0x05, 0x00, 0x00, 0x00, 0x05, 0x00, 0x00, 0x00, + 0x05, 0x00, 0x00, 0x00, 0x0e, 0x0e, 0x0e, 0x0e, 0x0e, 0x02, 0x09, 0x0d, + 0x0a, 0x08, 0x0d, 0x01, 0x09, 0x0d, 0x0a, 0x08, 0x0d, 0x01, 0x09, 0x0d, + 0x0a, 0x08, 0x0d, 0x01, 0x09, 0x0d, 0x0a, 0x08, 0x0d, 0x01, 0x09, 0x0e, + 0x0a, 0x09, 0x0e, 0x06, 0x0a, 0x0e, 0x0b, 0x09, 0x0e, 0x02, 0x09, 0x3a, + 0x16, 0x0e, 0x0e, 0x05, 0x09, 0x3a, 0x16, 0x0e, 0x0e, 0x05, 0x0a, 0x0e, + 0x0b, 0x09, 0x0e, 0x05, 0x0a, 0x0e, 0x0b, 0x09, 0x0e, 0x02, 0x0a, 0x0e, + 0x0b, 0x09, 0x0e, 0x02, 0x14, 0xc0, 0xc0, 0x15, 0x11, 0x05, 0x14, 0xc0, + 0xc0, 0x15, 0x11, 0x05, 0x14, 0xc0, 0xc0, 0x15, 0x11, 0x05, 0x14, 0xc0, + 0xc0, 0x15, 0x11, 0x05, 0x14, 0xc0, 0xc0, 0x15, 0x11, 0x05, 0x09, 0x3a, + 0x16, 0x0e, 0x0e, 0x05, 0x14, 0xc0, 0xc0, 0x15, 0x11, 0x05, 0x14, 0xc0, + 0xc0, 0x15, 0x11, 0x05, 0x09, 0x3a, 0x16, 0x0e, 0x0e, 0x05, 0x09, 0x3a, + 0x16, 0x0e, 0x0e, 0x05, 0x09, 0x3a, 0x16, 0x0e, 0x0e, 0x05, 0x14, 0xc0, + 0xc0, 0x15, 0x11, 0x05, 0x09, 0x3a, 0x16, 0x0e, 0x0e, 0x05, 0x09, 0x3a, + 0x16, 0x0e, 0x0e, 0x05, 0x09, 0x3a, 0x16, 0x0e, 0x0e, 0x05, 0x09, 0xb2, + 0x1c, 0x0e, 0x0e, 0x05, 0x12, 0xb1, 0x19, 0x11, 0x11, 0x08, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x73, 0x64, 0x70, 0x63, 0x6d, 0x64, 0x65, 0x76, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x40, 0xff, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xc9, 0x93, 0x80, 0x00, + 0x95, 0xa9, 0x80, 0x00, 0xbd, 0xa9, 0x80, 0x00, 0xd5, 0x93, 0x80, 0x00, + 0xb5, 0x93, 0x80, 0x00, 0x75, 0x93, 0x80, 0x00, 0xd1, 0x91, 0x80, 0x00, + 0x00, 0x00, 0x00, 0x00, 0xb1, 0xa9, 0x80, 0x00, 0xd5, 0x45, 0x02, 0x00, + 0xb1, 0x45, 0x02, 0x00, 0x9d, 0x45, 0x02, 0x00, 0x55, 0xaa, 0x80, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x21, 0xaa, 0x80, 0x00, 0x85, 0xaa, 0x80, 0x00, + 0x31, 0xaa, 0x80, 0x00, 0x6d, 0xaa, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x98, 0xc2, 0x01, 0x00, 0x5f, 0x5f, 0x00, 0x01, 0x43, 0x00, 0x40, 0x00, + 0x44, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x34, 0xc7, 0x01, 0x00, + 0x01, 0x00, 0x00, 0x00, 0x41, 0x00, 0x00, 0x00, 0x01, 0x00, 0xf9, 0x18, + 0x01, 0x0d, 0xe4, 0x00, 0xf4, 0xde, 0xf1, 0x06, 0xfc, 0x0f, 0x27, 0xfa, + 0xff, 0x1d, 0xf0, 0x10, 0x18, 0x09, 0x0a, 0xf2, 0x10, 0xe0, 0x17, 0x14, + 0x04, 0x11, 0x14, 0xf1, 0xfa, 0xf2, 0xdb, 0xf7, 0xfc, 0xe2, 0xfb, 0xe1, + 0xee, 0x13, 0x0d, 0xff, 0x1c, 0xe9, 0x1a, 0x17, 0x18, 0x03, 0x00, 0xda, + 0xe8, 0x03, 0xe6, 0x17, 0xe4, 0xe9, 0xf3, 0xff, 0x12, 0x13, 0x05, 0xe1, + 0x04, 0xe2, 0x25, 0xf7, 0x06, 0xf2, 0xec, 0xf1, 0xfc, 0x11, 0xe9, 0x14, + 0xf0, 0xe0, 0xf6, 0xf2, 0xe8, 0x09, 0x10, 0x10, 0x01, 0x1d, 0xd9, 0xfa, + 0x04, 0x0f, 0x0f, 0x06, 0x0c, 0xde, 0x1c, 0x00, 0xff, 0x0d, 0x07, 0x18, + 0x1a, 0xf6, 0x0e, 0xe4, 0x16, 0x0f, 0xf9, 0x05, 0xec, 0x18, 0x1b, 0x0a, + 0x1e, 0xff, 0x00, 0x26, 0xe2, 0xff, 0xe5, 0x0a, 0x14, 0x18, 0x07, 0x05, + 0xea, 0x0f, 0xf2, 0xe4, 0xe6, 0xf6, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, + 0x08, 0x09, 0x0a, 0x08, 0x08, 0x07, 0x07, 0x01, 0x02, 0x02, 0x02, 0x02, + 0x02, 0x02, 0x02, 0x02, 0x02, 0x02, 0x02, 0x02, 0x02, 0x02, 0x02, 0x02, + 0x02, 0x02, 0x01, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0xc5, 0x01, 0x1d, 0xff, 0xe0, 0xff, 0xc0, 0xff, 0xe0, 0xff, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xff, 0x00, 0x00, 0x00, 0x00, 0x6b, 0x03, 0x82, 0xfe, + 0xe7, 0xff, 0xcc, 0xff, 0xe7, 0xff, 0x08, 0x00, 0x02, 0x00, 0x00, 0x00, + 0xd7, 0x01, 0x0b, 0xff, 0xee, 0xff, 0xdc, 0xff, 0xee, 0xff, 0xa7, 0x03, + 0x3c, 0xfe, 0xec, 0xff, 0x17, 0x00, 0xec, 0xff, 0x72, 0x03, 0x85, 0xfe, + 0xae, 0xfe, 0xf8, 0x01, 0xae, 0xfe, 0x07, 0x00, 0x04, 0x00, 0x00, 0x00, + 0x98, 0x01, 0x60, 0xff, 0xcb, 0xff, 0x96, 0xff, 0xcb, 0xff, 0x9c, 0x03, + 0x45, 0xfe, 0x25, 0x00, 0xc1, 0xff, 0x25, 0x00, 0xb1, 0x03, 0x16, 0xfe, + 0xe4, 0xfe, 0xa5, 0x01, 0xe4, 0xfe, 0x07, 0x00, 0x14, 0x00, 0x01, 0x00, + 0xbf, 0x01, 0x31, 0xff, 0xf2, 0x00, 0x49, 0xfe, 0xf2, 0x00, 0x87, 0x03, + 0x61, 0xfe, 0x33, 0xff, 0x62, 0x01, 0x33, 0xff, 0x80, 0x03, 0x78, 0xfe, + 0xda, 0xfe, 0xe9, 0x00, 0xda, 0xfe, 0x08, 0x00, 0x15, 0x00, 0x01, 0x00, + 0xbf, 0x01, 0x31, 0xff, 0x18, 0x01, 0x0e, 0xfe, 0x18, 0x01, 0x87, 0x03, + 0x61, 0xfe, 0x16, 0xff, 0x7c, 0x01, 0x16, 0xff, 0x80, 0x03, 0x78, 0xfe, + 0x8f, 0xff, 0x93, 0x00, 0x8f, 0xff, 0x09, 0x00, 0x16, 0x00, 0x01, 0x00, + 0xbf, 0x01, 0x31, 0xff, 0x62, 0x00, 0x55, 0xff, 0x62, 0x00, 0x87, 0x03, + 0x61, 0xfe, 0x1f, 0xff, 0x6b, 0x01, 0x1f, 0xff, 0x79, 0x03, 0x7e, 0xfe, + 0xf4, 0xfe, 0x5d, 0x00, 0xf4, 0xfe, 0x08, 0x00, 0x17, 0x00, 0x01, 0x00, + 0xbc, 0x01, 0x31, 0xff, 0x74, 0x00, 0x42, 0xff, 0x74, 0x00, 0x87, 0x03, + 0x61, 0xfe, 0x52, 0xff, 0x02, 0x01, 0x52, 0xff, 0x80, 0x03, 0x78, 0xfe, + 0x7f, 0xff, 0xf1, 0xff, 0x7f, 0xff, 0x08, 0x00, 0x18, 0x00, 0x01, 0x00, + 0xb4, 0x01, 0x31, 0xff, 0xdf, 0xff, 0x1d, 0x00, 0xdf, 0xff, 0x88, 0x03, + 0x61, 0xfe, 0x87, 0xff, 0x90, 0xff, 0x87, 0xff, 0x7f, 0x03, 0x78, 0xfe, + 0xcd, 0xfe, 0xf4, 0x01, 0xcd, 0xfe, 0x08, 0x00, 0x19, 0x00, 0x01, 0x00, + 0xad, 0x01, 0x31, 0xff, 0xb8, 0xff, 0x3e, 0x00, 0xb8, 0xff, 0x82, 0x03, + 0x61, 0xfe, 0xaa, 0xff, 0xb1, 0xff, 0xaa, 0xff, 0x7f, 0x03, 0x78, 0xfe, + 0xc7, 0xfe, 0xfe, 0x01, 0xc7, 0xfe, 0x08, 0x00, 0x1a, 0x00, 0x01, 0x00, + 0x93, 0x01, 0x54, 0xff, 0xd9, 0xff, 0x0c, 0x00, 0xd9, 0xff, 0x1b, 0x03, + 0xc7, 0xfe, 0x4c, 0xff, 0x38, 0x00, 0x4c, 0xff, 0x33, 0x03, 0xb8, 0xfe, + 0x80, 0xff, 0x28, 0x00, 0x80, 0xff, 0x08, 0x00, 0x1b, 0x00, 0x01, 0x00, + 0x89, 0x01, 0x54, 0xff, 0xcf, 0xff, 0x13, 0x00, 0xcf, 0xff, 0x17, 0x03, + 0xc7, 0xfe, 0x00, 0xff, 0x50, 0x00, 0x00, 0xff, 0x2e, 0x03, 0xbd, 0xfe, + 0x8b, 0xff, 0x25, 0x00, 0x8b, 0xff, 0x08, 0x00, 0x1e, 0x00, 0x01, 0x00, + 0xbb, 0x01, 0x19, 0xff, 0xc3, 0xff, 0x1d, 0x00, 0xc3, 0xff, 0x6b, 0x03, + 0x61, 0xfe, 0x66, 0xff, 0x48, 0x00, 0x66, 0xff, 0x7c, 0x03, 0x78, 0xfe, + 0x56, 0xff, 0x4f, 0x00, 0x56, 0xff, 0x08, 0x00, 0x2c, 0x00, 0x01, 0x00, + 0xbf, 0x01, 0x31, 0xff, 0xe0, 0x00, 0x71, 0xfe, 0xe0, 0x00, 0x87, 0x03, + 0x61, 0xfe, 0x8b, 0xff, 0xc4, 0x00, 0x8b, 0xff, 0x80, 0x03, 0x78, 0xfe, + 0xb2, 0xfe, 0xc0, 0x00, 0xb2, 0xfe, 0x08, 0x00, 0x01, 0x00, 0x00, 0x00, + 0x6c, 0x09, 0x00, 0x00, 0x0b, 0x0a, 0x00, 0x07, 0x0a, 0x88, 0x88, 0x80, + 0x02, 0x00, 0x00, 0x00, 0x71, 0x09, 0x00, 0x00, 0x0b, 0x0a, 0x00, 0x07, + 0x0a, 0x88, 0x88, 0x80, 0x03, 0x00, 0x00, 0x00, 0x76, 0x09, 0x00, 0x00, + 0x0b, 0x0a, 0x00, 0x07, 0x0a, 0x88, 0x88, 0x80, 0x04, 0x00, 0x00, 0x00, + 0x7b, 0x09, 0x00, 0x00, 0x0b, 0x0a, 0x00, 0x07, 0x0a, 0x88, 0x88, 0x80, + 0x05, 0x00, 0x00, 0x00, 0x80, 0x09, 0x00, 0x00, 0x0b, 0x0a, 0x00, 0x07, + 0x0a, 0x88, 0x88, 0x80, 0x06, 0x00, 0x00, 0x00, 0x85, 0x09, 0x00, 0x00, + 0x0b, 0x0a, 0x00, 0x07, 0x0a, 0x88, 0x88, 0x80, 0x07, 0x00, 0x00, 0x00, + 0x8a, 0x09, 0x00, 0x00, 0x0b, 0x0a, 0x00, 0x07, 0x0a, 0x88, 0x88, 0x80, + 0x08, 0x00, 0x00, 0x00, 0x8f, 0x09, 0x00, 0x00, 0x0b, 0x0a, 0x00, 0x07, + 0x0a, 0x88, 0x88, 0x80, 0x09, 0x00, 0x00, 0x00, 0x94, 0x09, 0x00, 0x00, + 0x0b, 0x0a, 0x00, 0x07, 0x0a, 0x88, 0x88, 0x80, 0x0a, 0x00, 0x00, 0x00, + 0x99, 0x09, 0x00, 0x00, 0x0b, 0x0a, 0x00, 0x07, 0x0a, 0x88, 0x88, 0x80, + 0x0b, 0x00, 0x00, 0x00, 0x9e, 0x09, 0x00, 0x00, 0x0b, 0x0a, 0x00, 0x07, + 0x0a, 0x88, 0x88, 0x80, 0x0c, 0x00, 0x00, 0x00, 0xa3, 0x09, 0x00, 0x00, + 0x0b, 0x0a, 0x00, 0x07, 0x0a, 0x88, 0x88, 0x80, 0x0d, 0x00, 0x00, 0x00, + 0xa8, 0x09, 0x00, 0x00, 0x0b, 0x0a, 0x00, 0x07, 0x0a, 0x88, 0x88, 0x80, + 0x0e, 0x00, 0x00, 0x00, 0xb4, 0x09, 0x00, 0x00, 0x0b, 0x0a, 0x00, 0x07, + 0x0a, 0x88, 0x88, 0x80, 0x00, 0x00, 0x01, 0x00, 0x9f, 0x01, 0x52, 0x07, + 0x40, 0x00, 0x80, 0x00, 0x40, 0x00, 0x18, 0x03, 0x78, 0x06, 0x40, 0x00, + 0x80, 0x00, 0x40, 0x00, 0x0a, 0x03, 0x2e, 0x06, 0x40, 0x00, 0x80, 0x00, + 0x40, 0x00, 0x08, 0x00, 0x01, 0x00, 0x01, 0x00, 0x92, 0x01, 0x37, 0x07, + 0x03, 0x01, 0x3b, 0x00, 0x03, 0x01, 0x9f, 0x02, 0x02, 0x07, 0x44, 0x00, + 0x36, 0x00, 0x44, 0x00, 0x60, 0x02, 0x47, 0x07, 0x5d, 0x00, 0xa7, 0x00, + 0x5d, 0x00, 0x08, 0x00, 0x02, 0x00, 0x01, 0x00, 0x9f, 0x01, 0x52, 0x07, + 0x40, 0x00, 0x80, 0x00, 0x40, 0x00, 0x18, 0x03, 0x78, 0x06, 0xc0, 0x00, + 0x80, 0x01, 0xc0, 0x00, 0x0a, 0x03, 0x2e, 0x06, 0x40, 0x00, 0x80, 0x00, + 0x40, 0x00, 0x08, 0x00, 0x03, 0x00, 0x01, 0x00, 0x2e, 0x01, 0x31, 0x07, + 0x81, 0x00, 0x02, 0x01, 0x81, 0x00, 0x92, 0x02, 0xb8, 0x06, 0xcd, 0x00, + 0x9a, 0x01, 0xcd, 0x00, 0xf2, 0x02, 0xe0, 0x06, 0xaa, 0x00, 0x54, 0x01, + 0xaa, 0x00, 0x08, 0x00, 0x14, 0x00, 0x01, 0x00, 0x68, 0x01, 0x5c, 0xff, + 0xf2, 0x00, 0xc6, 0xfe, 0xf2, 0x00, 0xf0, 0x02, 0xb8, 0xfe, 0x33, 0xff, + 0xcb, 0x00, 0x33, 0xff, 0xff, 0x02, 0xe0, 0xfe, 0x03, 0xff, 0x49, 0xff, + 0x03, 0xff, 0x08, 0x00, 0x15, 0x00, 0x01, 0x00, 0x68, 0x01, 0x5c, 0xff, + 0x95, 0x00, 0x52, 0xff, 0x95, 0x00, 0xf0, 0x02, 0xb8, 0xfe, 0x33, 0xff, + 0xa4, 0x00, 0x33, 0xff, 0xff, 0x02, 0xe0, 0xfe, 0x00, 0xff, 0xef, 0xfe, + 0x00, 0xff, 0x08, 0x00, 0x16, 0x00, 0x01, 0x00, 0x68, 0x01, 0x5c, 0xff, + 0x62, 0x00, 0x9c, 0xff, 0x62, 0x00, 0xf0, 0x02, 0xb8, 0xfe, 0x33, 0xff, + 0x7c, 0x00, 0x33, 0xff, 0xff, 0x02, 0xe0, 0xfe, 0x00, 0xff, 0xa0, 0xfe, + 0x00, 0xff, 0x08, 0x00, 0x17, 0x00, 0x01, 0x00, 0x5e, 0x01, 0x5c, 0xff, + 0x8c, 0xff, 0x52, 0x00, 0x8c, 0xff, 0xf0, 0x02, 0xb8, 0xfe, 0x33, 0xff, + 0x28, 0x00, 0x33, 0xff, 0xff, 0x02, 0xe0, 0xfe, 0x7f, 0xff, 0x15, 0xff, + 0x7f, 0xff, 0x08, 0x00, 0x18, 0x00, 0x01, 0x00, 0x45, 0x01, 0x5c, 0xff, + 0xe0, 0xff, 0xd8, 0xff, 0xe0, 0xff, 0xf4, 0x02, 0xb8, 0xfe, 0x00, 0xff, + 0x29, 0xfe, 0x00, 0xff, 0xfe, 0x02, 0xe0, 0xfe, 0xfa, 0xfe, 0xaa, 0x00, + 0xfa, 0xfe, 0x08, 0x00, 0x19, 0x00, 0x01, 0x00, 0x2b, 0x01, 0x5c, 0xff, + 0xcd, 0xff, 0xc0, 0xff, 0xcd, 0xff, 0xe0, 0x02, 0xb8, 0xfe, 0x00, 0xff, + 0x29, 0xfe, 0x00, 0xff, 0xfd, 0x02, 0xe0, 0xfe, 0xfa, 0xfe, 0xaa, 0x00, + 0xfa, 0xfe, 0x08, 0x00, 0x1a, 0x00, 0x01, 0x00, 0x15, 0x01, 0x97, 0xff, + 0xd9, 0xff, 0x8b, 0xff, 0xa8, 0xff, 0x7d, 0x02, 0x2e, 0xff, 0xc0, 0xff, + 0x40, 0xff, 0x70, 0xff, 0x66, 0x02, 0x48, 0xff, 0x80, 0xff, 0x80, 0xfe, + 0xe0, 0xfe, 0x08, 0x00, 0x1b, 0x00, 0x01, 0x00, 0xf5, 0x00, 0x97, 0xff, + 0xcf, 0xff, 0x6d, 0xff, 0x92, 0xff, 0x72, 0x02, 0x2e, 0xff, 0x5e, 0xff, + 0x1b, 0xfe, 0x95, 0xfe, 0x65, 0x02, 0x48, 0xff, 0xc2, 0xff, 0x46, 0xff, + 0x75, 0xff, 0x08, 0x00, 0x1e, 0x00, 0x01, 0x00, 0x2e, 0x01, 0x31, 0xff, + 0xc3, 0xff, 0x86, 0xff, 0xc3, 0xff, 0x92, 0x02, 0xb8, 0xfe, 0x33, 0xff, + 0x66, 0xfe, 0x33, 0xff, 0xf2, 0x02, 0xe0, 0xfe, 0x56, 0xff, 0xac, 0xfe, + 0x56, 0xff, 0x08, 0x00, 0x28, 0x00, 0x01, 0x00, 0x68, 0x01, 0x5c, 0xff, + 0xf2, 0x00, 0xc6, 0xfe, 0xf2, 0x00, 0xf0, 0x02, 0xb8, 0xfe, 0xcd, 0x00, + 0x35, 0xff, 0xcd, 0x00, 0xff, 0x02, 0xe0, 0xfe, 0xff, 0x01, 0x72, 0x01, + 0xff, 0x01, 0x08, 0x00, 0x05, 0x01, 0x00, 0x08, 0x00, 0x01, 0xff, 0xff, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xa2, 0x00, 0x00, 0x00, + 0x00, 0xff, 0x00, 0xff, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xff, + 0x00, 0x00, 0x00, 0x00, 0x78, 0x02, 0xa0, 0xfe, 0x80, 0xff, 0x00, 0xff, + 0x80, 0xff, 0x08, 0x00, 0x01, 0x00, 0x00, 0x00, 0x76, 0x01, 0x79, 0xff, + 0xf0, 0xff, 0xe0, 0xff, 0xf0, 0xff, 0x1f, 0x03, 0x74, 0xfe, 0xce, 0xff, + 0xe0, 0xff, 0xce, 0xff, 0xee, 0x02, 0x2b, 0xfe, 0x2c, 0xff, 0x32, 0x00, + 0x2c, 0xff, 0x08, 0x00, 0x02, 0x00, 0x00, 0x00, 0x77, 0x01, 0x16, 0xff, + 0xdb, 0xff, 0xb4, 0xff, 0xdb, 0xff, 0x1f, 0x03, 0x74, 0xfe, 0xe0, 0xff, + 0xec, 0xff, 0xe0, 0xff, 0xec, 0x02, 0xf2, 0xfe, 0x80, 0xff, 0x1e, 0x00, + 0x80, 0xff, 0x08, 0x00, 0x03, 0x00, 0x00, 0x00, 0x77, 0x01, 0x16, 0xff, + 0xdb, 0xff, 0xb4, 0xff, 0xdb, 0xff, 0x1f, 0x03, 0x74, 0xfe, 0xe0, 0xff, + 0xec, 0xff, 0xe0, 0xff, 0xec, 0x02, 0xf2, 0xfe, 0x6c, 0xff, 0x23, 0x00, + 0x6c, 0xff, 0x08, 0x00, 0x04, 0x00, 0x00, 0x00, 0x33, 0x01, 0xae, 0xff, + 0xcb, 0xff, 0x96, 0xff, 0xcb, 0xff, 0x0b, 0x03, 0x85, 0xfe, 0xcb, 0xff, + 0x0a, 0x00, 0xcb, 0xff, 0xfd, 0x02, 0x2b, 0xfe, 0x2c, 0xff, 0xca, 0x00, + 0x2c, 0xff, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0xb5, 0x04, 0x46, + 0xe0, 0xf3, 0xa0, 0xf1, 0x00, 0x21, 0x44, 0x22, 0x05, 0x46, 0xe1, 0xf3, + 0x0b, 0xf2, 0x63, 0x69, 0x15, 0x2b, 0x2b, 0x60, 0x01, 0xd0, 0x16, 0x2b, + 0x01, 0xd9, 0x10, 0x4b, 0x6b, 0x60, 0x6b, 0x68, 0xc3, 0xb1, 0xac, 0x60, + 0x20, 0x46, 0xea, 0xf3, 0x57, 0xf2, 0xe8, 0x60, 0x20, 0x46, 0xea, 0xf3, + 0x1b, 0xf2, 0x06, 0x46, 0x18, 0xb9, 0x20, 0x46, 0x01, 0x21, 0xea, 0xf3, + 0x53, 0xf2, 0x6b, 0x68, 0x20, 0x46, 0x9b, 0x68, 0x98, 0x47, 0x05, 0x46, + 0x2e, 0xb9, 0x20, 0x46, 0x31, 0x46, 0xea, 0xf3, 0x49, 0xf2, 0x00, 0xe0, + 0x1d, 0x46, 0x28, 0x46, 0x70, 0xbd, 0x00, 0xbf, 0xb4, 0xfd, 0x01, 0x00, + 0x2d, 0xe9, 0xf0, 0x47, 0x04, 0x46, 0x0f, 0x46, 0x91, 0x46, 0x98, 0x46, + 0xea, 0xf3, 0xfc, 0xf1, 0x05, 0x46, 0x18, 0xb9, 0x20, 0x46, 0x01, 0x21, + 0xea, 0xf3, 0x34, 0xf2, 0x20, 0x46, 0xea, 0xf3, 0xf3, 0xf1, 0xc0, 0xb1, + 0x20, 0x46, 0xea, 0xf3, 0xe5, 0xf1, 0xa0, 0xb9, 0x20, 0x46, 0xff, 0xf7, + 0xb5, 0xff, 0x82, 0x46, 0x90, 0xb1, 0x20, 0x46, 0xec, 0xf7, 0x2b, 0xfa, + 0xda, 0xf8, 0x04, 0x30, 0x50, 0x46, 0x5e, 0x69, 0x39, 0x46, 0x4a, 0x46, + 0x43, 0x46, 0xb0, 0x47, 0x06, 0x46, 0x20, 0x46, 0xec, 0xf7, 0x1d, 0xfa, + 0x04, 0xe0, 0x6f, 0xf0, 0x18, 0x06, 0x01, 0xe0, 0x4f, 0xf0, 0xff, 0x36, + 0x1d, 0xb9, 0x20, 0x46, 0x29, 0x46, 0xea, 0xf3, 0x0d, 0xf2, 0x30, 0x46, + 0xbd, 0xe8, 0xf0, 0x87, 0x05, 0x23, 0xc0, 0xf8, 0x94, 0x31, 0x20, 0x23, + 0xc0, 0xf8, 0x9c, 0x31, 0x23, 0x4b, 0x01, 0x22, 0x1b, 0x68, 0xc0, 0xf8, + 0x98, 0x21, 0xc0, 0xf8, 0xac, 0x21, 0x4f, 0xf0, 0x64, 0x02, 0xc0, 0xf8, + 0xb0, 0x21, 0x4f, 0xf0, 0x06, 0x02, 0x00, 0x2b, 0xc0, 0xf8, 0xc0, 0x21, + 0x40, 0xf2, 0x3c, 0x72, 0x0c, 0xbf, 0x07, 0x23, 0x00, 0x23, 0xc0, 0xf8, + 0xc4, 0x21, 0x4f, 0xf0, 0x08, 0x02, 0xc0, 0xf8, 0xa0, 0x31, 0xc0, 0xf8, + 0xc8, 0x21, 0x4f, 0xf0, 0x10, 0x03, 0x4f, 0xf0, 0x15, 0x02, 0xc0, 0xf8, + 0xa4, 0x31, 0xc0, 0xf8, 0xb8, 0x31, 0xc0, 0xf8, 0xbc, 0x31, 0xc0, 0xf8, + 0xcc, 0x21, 0xc0, 0xf8, 0xd0, 0x31, 0x03, 0xd0, 0x0e, 0x4b, 0x1b, 0x68, + 0x01, 0x3b, 0x00, 0xe0, 0x03, 0x23, 0x1c, 0x22, 0xc0, 0xf8, 0xd4, 0x31, + 0x04, 0x23, 0xc0, 0xf8, 0xd8, 0x31, 0xc0, 0xf8, 0xdc, 0x21, 0xc0, 0xf8, + 0xe8, 0x31, 0x0c, 0x22, 0x06, 0x23, 0xc0, 0xf8, 0xe0, 0x21, 0xc0, 0xf8, + 0xec, 0x31, 0x10, 0x22, 0x00, 0x23, 0xc0, 0xf8, 0xe4, 0x21, 0xc0, 0xf8, + 0xf0, 0x31, 0x70, 0x47, 0xec, 0x26, 0x00, 0x00, 0xd4, 0x25, 0x00, 0x00, + 0xd0, 0xf8, 0x10, 0x12, 0x38, 0xb5, 0x04, 0x46, 0x69, 0xb1, 0x80, 0x68, + 0xe1, 0xf3, 0x04, 0xf7, 0xd4, 0xf8, 0x10, 0x12, 0x05, 0x46, 0xe8, 0x22, + 0xa0, 0x68, 0xe5, 0xf3, 0xa1, 0xf7, 0x00, 0x23, 0xc4, 0xf8, 0x10, 0x32, + 0x00, 0xe0, 0x0d, 0x46, 0x28, 0x46, 0x38, 0xbd, 0x1f, 0xb5, 0x04, 0x46, + 0x06, 0x23, 0x80, 0x68, 0xe8, 0x21, 0x03, 0x93, 0xe5, 0xf3, 0x82, 0xf7, + 0xc4, 0xf8, 0x10, 0x02, 0x68, 0xb1, 0x00, 0x21, 0xe8, 0x22, 0xe1, 0xf3, + 0x33, 0xf1, 0x00, 0x23, 0x00, 0x93, 0xa0, 0x68, 0xd4, 0xf8, 0x10, 0x12, + 0x03, 0xaa, 0x1c, 0x23, 0xe1, 0xf3, 0x76, 0xf7, 0x01, 0xe0, 0x4f, 0xf0, + 0xff, 0x30, 0x04, 0xb0, 0x10, 0xbd, 0x00, 0x00, 0x2d, 0xe9, 0xf0, 0x41, + 0x8a, 0xb0, 0x1d, 0x46, 0xdd, 0xf8, 0x40, 0x80, 0x94, 0x4b, 0x08, 0x46, + 0xc3, 0xf8, 0x00, 0x80, 0x11, 0x46, 0x17, 0x46, 0xe8, 0xf3, 0xd4, 0xf6, + 0x00, 0x28, 0x00, 0xf0, 0x19, 0x81, 0x28, 0x46, 0x4f, 0xf4, 0x07, 0x71, + 0xe5, 0xf3, 0x56, 0xf7, 0x04, 0x46, 0x00, 0x28, 0x00, 0xf0, 0x11, 0x81, + 0x00, 0x21, 0x4f, 0xf4, 0x07, 0x72, 0xe1, 0xf3, 0x05, 0xf1, 0xa5, 0x60, + 0xc4, 0xf8, 0x14, 0x80, 0x20, 0x46, 0xff, 0xf7, 0x55, 0xff, 0x86, 0x4b, + 0x1e, 0x68, 0xc4, 0xf8, 0x0c, 0x62, 0x1e, 0xb1, 0x36, 0x78, 0x00, 0x36, + 0x18, 0xbf, 0x01, 0x26, 0x82, 0x4b, 0x04, 0xf1, 0x28, 0x00, 0x1a, 0x68, + 0x01, 0x21, 0x00, 0x2a, 0x14, 0xbf, 0x31, 0x22, 0x11, 0x22, 0xe2, 0xf3, + 0x09, 0xf0, 0x00, 0x23, 0x00, 0x93, 0x01, 0x93, 0x02, 0x93, 0x38, 0x46, + 0x29, 0x46, 0x42, 0x46, 0x11, 0x9b, 0x05, 0xf0, 0xd7, 0xfc, 0xe0, 0x60, + 0x00, 0x28, 0x00, 0xf0, 0xdb, 0x80, 0xe9, 0xf3, 0xed, 0xf7, 0x20, 0x60, + 0xe0, 0x68, 0xea, 0xf3, 0x07, 0xf0, 0x67, 0x69, 0x73, 0x4a, 0x7b, 0x68, + 0x73, 0x49, 0x03, 0xf0, 0x01, 0x03, 0x83, 0xf0, 0x01, 0x03, 0xd4, 0xf8, + 0x00, 0xc0, 0x00, 0x2b, 0x18, 0xbf, 0x11, 0x46, 0x84, 0xf8, 0x76, 0x31, + 0x40, 0xf6, 0x29, 0x03, 0x9c, 0x45, 0x60, 0x60, 0xd4, 0xf8, 0x08, 0xe0, + 0xe2, 0x68, 0x07, 0xf5, 0x00, 0x73, 0x03, 0xd1, 0x10, 0xb1, 0x07, 0xf5, + 0x08, 0x77, 0x01, 0xe0, 0x07, 0xf5, 0x04, 0x77, 0x00, 0x97, 0xd4, 0xf8, + 0xb8, 0x01, 0x01, 0x90, 0xd4, 0xf8, 0xbc, 0x01, 0x02, 0x90, 0xd4, 0xf8, + 0xc4, 0x01, 0x03, 0x90, 0x4f, 0xf0, 0xff, 0x30, 0x04, 0x90, 0xd4, 0xf8, + 0xc0, 0x01, 0x05, 0x90, 0x08, 0x20, 0x06, 0x90, 0x00, 0x20, 0x07, 0x90, + 0x70, 0x46, 0xee, 0xf7, 0xa9, 0xff, 0x60, 0x62, 0x00, 0x28, 0x00, 0xf0, + 0x9b, 0x80, 0xd4, 0xf8, 0x0c, 0x12, 0xb1, 0xb1, 0x0b, 0x78, 0xa3, 0xb1, + 0xe3, 0xf3, 0x6e, 0xf6, 0x55, 0x49, 0x22, 0x46, 0xd4, 0xf8, 0x0c, 0x02, + 0xe1, 0xf3, 0x30, 0xf6, 0xd4, 0xf8, 0x0c, 0x02, 0x52, 0x49, 0x22, 0x46, + 0xe1, 0xf3, 0x64, 0xf6, 0x2e, 0xb1, 0x20, 0x46, 0xff, 0xf7, 0x44, 0xff, + 0x00, 0x28, 0x40, 0xf0, 0x81, 0x80, 0x01, 0x21, 0x0a, 0x46, 0x60, 0x6a, + 0xe3, 0xf3, 0x5e, 0xf6, 0x20, 0x46, 0x00, 0x21, 0xe2, 0x68, 0x2b, 0x46, + 0x03, 0xf0, 0x9e, 0xfb, 0x20, 0x61, 0x00, 0x28, 0x72, 0xd0, 0x00, 0x21, + 0x0b, 0x46, 0x20, 0x46, 0x45, 0x4a, 0xe5, 0xf3, 0x19, 0xf2, 0x00, 0x23, + 0xc4, 0xf8, 0x90, 0x01, 0x84, 0xf8, 0x79, 0x31, 0x42, 0x48, 0xe6, 0xf3, + 0x7d, 0xf6, 0x10, 0xb3, 0xe1, 0xf3, 0xac, 0xf2, 0x01, 0x23, 0x83, 0x40, + 0x3f, 0x48, 0xc4, 0xf8, 0x80, 0x31, 0xe6, 0xf3, 0x73, 0xf6, 0x10, 0xb1, + 0xe1, 0xf3, 0xa2, 0xf2, 0x08, 0xb1, 0xd4, 0xf8, 0x80, 0x01, 0xc4, 0xf8, + 0x84, 0x01, 0x3a, 0x49, 0x00, 0x20, 0xe1, 0xf3, 0xed, 0xf4, 0x03, 0x0c, + 0xa4, 0xf8, 0x88, 0x31, 0xa4, 0xf8, 0x8a, 0x01, 0x3b, 0xb1, 0x00, 0x21, + 0x20, 0x46, 0x35, 0x4a, 0x0b, 0x46, 0xe5, 0xf3, 0xef, 0xf1, 0xc4, 0xf8, + 0x8c, 0x01, 0x00, 0x20, 0x32, 0x49, 0xe1, 0xf3, 0xdb, 0xf4, 0x01, 0x28, + 0x09, 0xd1, 0x84, 0xf8, 0x16, 0x02, 0x30, 0x49, 0x00, 0x20, 0xe1, 0xf3, + 0xd3, 0xf4, 0x01, 0x28, 0x04, 0xbf, 0x2e, 0x4b, 0x18, 0x60, 0x20, 0x46, + 0xe8, 0xf3, 0x4e, 0xf4, 0x18, 0xb3, 0x00, 0x20, 0xc4, 0xf8, 0xa0, 0x01, + 0x2a, 0x49, 0xe1, 0xf3, 0xc5, 0xf4, 0x28, 0xb1, 0x01, 0x23, 0x84, 0xf8, + 0xf9, 0x31, 0x28, 0x48, 0xee, 0xf7, 0xf4, 0xfb, 0x00, 0x20, 0x27, 0x49, + 0xe1, 0xf3, 0xba, 0xf4, 0x88, 0xb1, 0x25, 0x49, 0x00, 0x20, 0xe1, 0xf3, + 0xb5, 0xf4, 0x4f, 0xf0, 0x80, 0x73, 0x00, 0xf0, 0x0f, 0x00, 0x0a, 0xa9, + 0x01, 0xf8, 0x01, 0x0d, 0x4f, 0xf4, 0x40, 0x72, 0x00, 0x93, 0x20, 0x46, + 0x0f, 0x23, 0xe1, 0xf7, 0xf7, 0xfd, 0x1d, 0x48, 0x1d, 0x49, 0x22, 0x46, + 0xe5, 0xf3, 0x60, 0xf5, 0x1c, 0x48, 0xeb, 0xf7, 0x35, 0xf9, 0x08, 0xe0, + 0xa0, 0x68, 0x21, 0x46, 0x4f, 0xf4, 0x07, 0x72, 0xe5, 0xf3, 0x54, 0xf6, + 0x00, 0x24, 0x00, 0xe0, 0x04, 0x46, 0x20, 0x46, 0x0a, 0xb0, 0xbd, 0xe8, + 0xf0, 0x81, 0x00, 0xbf, 0xf4, 0x26, 0x00, 0x00, 0xbc, 0x26, 0x00, 0x00, + 0xec, 0x26, 0x00, 0x00, 0xae, 0x27, 0x86, 0x00, 0xb6, 0x27, 0x86, 0x00, + 0xdd, 0x9b, 0x80, 0x00, 0x51, 0x29, 0x00, 0x00, 0x65, 0xa6, 0x80, 0x00, + 0x05, 0x28, 0x86, 0x00, 0x0e, 0x28, 0x86, 0x00, 0x17, 0x28, 0x86, 0x00, + 0x49, 0x9b, 0x80, 0x00, 0x1f, 0x28, 0x86, 0x00, 0x94, 0xb9, 0x01, 0x00, + 0xa0, 0x07, 0x02, 0x00, 0x2a, 0x28, 0x86, 0x00, 0x34, 0x28, 0x86, 0x00, + 0xa5, 0xb9, 0x01, 0x00, 0x4d, 0x28, 0x86, 0x00, 0xe5, 0x9a, 0x80, 0x00, + 0xd5, 0x96, 0x80, 0x00, 0x38, 0xb5, 0x00, 0x25, 0x04, 0x46, 0x80, 0xf8, + 0x75, 0x51, 0x00, 0x69, 0x03, 0xf0, 0x22, 0xfb, 0x20, 0x46, 0xe8, 0xf3, + 0xfb, 0xf5, 0xe0, 0x68, 0x29, 0x46, 0xe9, 0xf3, 0xb5, 0xf6, 0xd4, 0xf8, + 0x90, 0x01, 0x28, 0xb1, 0xe5, 0xf3, 0xf4, 0xf0, 0xd4, 0xf8, 0x90, 0x01, + 0xe5, 0xf3, 0x3a, 0xf1, 0xd4, 0xf8, 0x8c, 0x01, 0x28, 0xb1, 0xe5, 0xf3, + 0xeb, 0xf0, 0xd4, 0xf8, 0x8c, 0x01, 0xe5, 0xf3, 0x31, 0xf1, 0xe0, 0x68, + 0x05, 0xf0, 0x14, 0xfa, 0xd4, 0xf8, 0x10, 0x32, 0x23, 0xb1, 0x1b, 0x78, + 0x13, 0xb1, 0x20, 0x46, 0xff, 0xf7, 0x46, 0xfe, 0xa0, 0x68, 0x21, 0x46, + 0x4f, 0xf4, 0x07, 0x72, 0xbd, 0xe8, 0x38, 0x40, 0xe5, 0xf3, 0xee, 0xb5, + 0x7f, 0xb5, 0x06, 0x46, 0x4f, 0xf4, 0xbc, 0x71, 0x40, 0x68, 0xe5, 0xf3, + 0xd7, 0xf5, 0x04, 0x46, 0xc0, 0xb1, 0x00, 0x21, 0x4f, 0xf4, 0xbc, 0x72, + 0xe0, 0xf3, 0x88, 0xf7, 0x0b, 0x4b, 0x26, 0x60, 0x00, 0x93, 0x0b, 0x4b, + 0x00, 0x25, 0x01, 0x93, 0x30, 0x68, 0x23, 0x46, 0x09, 0x49, 0x0a, 0x4a, + 0x02, 0x95, 0x03, 0x95, 0x02, 0xf0, 0xc6, 0xde, 0x4f, 0xf4, 0x96, 0x63, + 0xc4, 0xf8, 0x60, 0x31, 0x84, 0xf8, 0x64, 0x51, 0x20, 0x46, 0x04, 0xb0, + 0x70, 0xbd, 0x00, 0xbf, 0x49, 0x03, 0x01, 0x00, 0xc1, 0x2d, 0x00, 0x00, + 0xcc, 0xb9, 0x01, 0x00, 0x85, 0x3b, 0x86, 0x00, 0x10, 0xb5, 0x04, 0x46, + 0x70, 0xb1, 0x03, 0x68, 0x22, 0x46, 0x18, 0x68, 0x06, 0x49, 0x02, 0xf0, + 0xe3, 0xde, 0x23, 0x68, 0x21, 0x46, 0x58, 0x68, 0x4f, 0xf4, 0xbc, 0x72, + 0xbd, 0xe8, 0x10, 0x40, 0xe5, 0xf3, 0xae, 0xb5, 0x10, 0xbd, 0x00, 0xbf, + 0x85, 0x3b, 0x86, 0x00, 0x70, 0xb5, 0x04, 0x46, 0x00, 0x28, 0x2b, 0xd0, + 0x81, 0x68, 0x69, 0xb1, 0xc3, 0x68, 0x98, 0x68, 0xee, 0xf3, 0x56, 0xf2, + 0xe3, 0x68, 0xd0, 0xf1, 0x01, 0x05, 0xa1, 0x68, 0x98, 0x68, 0x38, 0xbf, + 0x00, 0x25, 0xee, 0xf3, 0x5f, 0xf2, 0x00, 0xe0, 0x0d, 0x46, 0x61, 0x6f, + 0x00, 0x26, 0xa6, 0x65, 0x29, 0xb1, 0xe3, 0x68, 0xa2, 0x6f, 0x58, 0x68, + 0xe5, 0xf3, 0x8c, 0xf5, 0x66, 0x67, 0x20, 0x46, 0xed, 0xf7, 0x24, 0xff, + 0xe3, 0x68, 0x22, 0x46, 0x18, 0x68, 0x07, 0x49, 0x02, 0xf0, 0xae, 0xde, + 0xe3, 0x68, 0x21, 0x46, 0x58, 0x68, 0x4f, 0xf4, 0xb0, 0x72, 0xe5, 0xf3, + 0x7b, 0xf5, 0x00, 0xe0, 0x05, 0x46, 0x28, 0x46, 0x70, 0xbd, 0x00, 0xbf, + 0xeb, 0x3d, 0x86, 0x00, 0x30, 0xb5, 0x4f, 0xf4, 0xb0, 0x71, 0x85, 0xb0, + 0x05, 0x46, 0x40, 0x68, 0xe5, 0xf3, 0x5c, 0xf5, 0x04, 0x46, 0xe0, 0xb1, + 0x00, 0x21, 0x4f, 0xf4, 0xb0, 0x72, 0xe0, 0xf3, 0x0d, 0xf7, 0xe5, 0x60, + 0xa8, 0x68, 0xc5, 0xf8, 0x18, 0x48, 0x0d, 0x49, 0x22, 0x46, 0x00, 0x23, + 0xee, 0xf3, 0x40, 0xf2, 0xa0, 0x60, 0x60, 0xb1, 0x0a, 0x4b, 0x28, 0x68, + 0x00, 0x93, 0x00, 0x23, 0x01, 0x93, 0x02, 0x93, 0x03, 0x93, 0x08, 0x49, + 0x08, 0x4a, 0x23, 0x46, 0x02, 0xf0, 0x42, 0xde, 0x18, 0xb1, 0x20, 0x46, + 0xff, 0xf7, 0xa0, 0xff, 0x00, 0x24, 0x20, 0x46, 0x05, 0xb0, 0x30, 0xbd, + 0x31, 0x2f, 0x00, 0x00, 0xd9, 0xe1, 0x80, 0x00, 0x50, 0xba, 0x01, 0x00, + 0xeb, 0x3d, 0x86, 0x00, 0x38, 0xb5, 0x04, 0x46, 0xd0, 0xf8, 0x84, 0x00, + 0x0d, 0x46, 0x08, 0xb1, 0x02, 0xf0, 0x38, 0xfd, 0xd4, 0xf8, 0x80, 0x00, + 0x08, 0xb1, 0x05, 0xf0, 0xf1, 0xfb, 0xe0, 0x6f, 0x08, 0xb1, 0xff, 0xf7, + 0x6d, 0xff, 0x60, 0x6f, 0x08, 0xb1, 0xff, 0xf7, 0x7f, 0xff, 0xa0, 0x68, + 0x08, 0xb1, 0x00, 0xf0, 0x03, 0xfd, 0x28, 0x46, 0x21, 0x46, 0x8c, 0x22, + 0xbd, 0xe8, 0x38, 0x40, 0xe5, 0xf3, 0x1e, 0xb5, 0x2d, 0xe9, 0xf0, 0x4f, + 0x07, 0x46, 0x89, 0xb0, 0x8b, 0x46, 0x00, 0x20, 0x8c, 0x21, 0x90, 0x46, + 0x1d, 0x46, 0x13, 0x9e, 0xe5, 0xf3, 0x02, 0xf5, 0x04, 0x46, 0x00, 0x28, + 0x7b, 0xd0, 0x00, 0x21, 0x8c, 0x22, 0xe0, 0xf3, 0xb3, 0xf6, 0x26, 0x60, + 0x38, 0x46, 0x05, 0xf0, 0x83, 0xf8, 0x07, 0xab, 0x01, 0x90, 0x05, 0x93, + 0x2a, 0x46, 0x82, 0x46, 0x4f, 0xf0, 0x00, 0x09, 0x20, 0x46, 0x41, 0xf2, + 0xe4, 0x41, 0x33, 0x46, 0xcd, 0xf8, 0x00, 0x90, 0xcd, 0xf8, 0x08, 0xb0, + 0xcd, 0xf8, 0x0c, 0x80, 0x04, 0x94, 0x00, 0xf0, 0x75, 0xfd, 0x05, 0x46, + 0x00, 0x28, 0x57, 0xd0, 0xa0, 0x60, 0x04, 0xf0, 0xe5, 0xdb, 0x2b, 0x69, + 0x60, 0x60, 0xe3, 0x60, 0x2d, 0x4b, 0x10, 0x21, 0xa3, 0x64, 0x2d, 0x4a, + 0x33, 0x46, 0x27, 0x61, 0x64, 0x64, 0x38, 0x46, 0xe0, 0xf3, 0xcc, 0xf6, + 0x2b, 0x69, 0x31, 0x46, 0x1b, 0x6e, 0x29, 0x48, 0x9a, 0x6b, 0x29, 0x4b, + 0xee, 0xf7, 0x52, 0xfa, 0x32, 0x46, 0x48, 0x46, 0x12, 0x99, 0x27, 0x4b, + 0x8d, 0xe8, 0x80, 0x01, 0x02, 0xf0, 0x28, 0xfe, 0x06, 0x46, 0x00, 0x28, + 0x34, 0xd1, 0x63, 0x68, 0x01, 0x27, 0x83, 0xf8, 0x78, 0x70, 0xdf, 0xf8, + 0x94, 0x80, 0x36, 0x21, 0x3a, 0x46, 0xd5, 0xf8, 0x7c, 0x02, 0x25, 0xf0, + 0x0d, 0xda, 0xc4, 0xf8, 0x3c, 0x80, 0x28, 0x46, 0xff, 0xf7, 0x48, 0xff, + 0x60, 0x67, 0x08, 0xb3, 0x63, 0x68, 0x28, 0x46, 0x83, 0xf8, 0xa4, 0x70, + 0xc4, 0xf8, 0x78, 0x80, 0xff, 0xf7, 0xc4, 0xfe, 0xe0, 0x67, 0xb8, 0xb1, + 0x28, 0x46, 0x05, 0xf0, 0x11, 0xfb, 0xc4, 0xf8, 0x80, 0x00, 0x88, 0xb1, + 0x28, 0x46, 0x02, 0xf0, 0x7f, 0xfc, 0xc4, 0xf8, 0x84, 0x00, 0x58, 0xb1, + 0x0f, 0x4b, 0x02, 0x96, 0x8d, 0xe8, 0x48, 0x00, 0x03, 0x96, 0x28, 0x68, + 0x0d, 0x49, 0x0e, 0x4a, 0x23, 0x46, 0x02, 0xf0, 0x8d, 0xdd, 0x20, 0xb1, + 0x20, 0x46, 0x51, 0x46, 0xff, 0xf7, 0x56, 0xff, 0x00, 0x24, 0x20, 0x46, + 0x09, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, 0x00, 0xbf, 0x55, 0xf7, 0x80, 0x00, + 0xfb, 0x41, 0x86, 0x00, 0x94, 0x8d, 0x02, 0x00, 0xbc, 0xba, 0x01, 0x00, + 0x29, 0xfb, 0x80, 0x00, 0x99, 0xf8, 0x80, 0x00, 0x7c, 0xd2, 0x85, 0x00, + 0xc5, 0x42, 0x86, 0x00, 0xef, 0xbe, 0xad, 0x0d, 0x02, 0x4b, 0x01, 0x22, + 0x1a, 0x70, 0xeb, 0xf7, 0x8f, 0xba, 0x00, 0xbf, 0x38, 0x08, 0x02, 0x00, + 0xd0, 0xf8, 0xac, 0x11, 0x10, 0xb5, 0x04, 0x46, 0x29, 0xb1, 0x80, 0x68, + 0xee, 0xf3, 0x34, 0xf1, 0x00, 0x23, 0xc4, 0xf8, 0xac, 0x31, 0xd4, 0xf8, + 0xc4, 0x11, 0x29, 0xb1, 0xa0, 0x68, 0xee, 0xf3, 0x2b, 0xf1, 0x00, 0x23, + 0xc4, 0xf8, 0xc4, 0x31, 0xd4, 0xf8, 0x74, 0x15, 0x29, 0xb1, 0xa0, 0x68, + 0xee, 0xf3, 0x22, 0xf1, 0x00, 0x23, 0xc4, 0xf8, 0x74, 0x35, 0xd4, 0xf8, + 0xf8, 0x16, 0x29, 0xb1, 0xa0, 0x68, 0xee, 0xf3, 0x19, 0xf1, 0x00, 0x23, + 0xc4, 0xf8, 0xf8, 0x36, 0xd4, 0xf8, 0xfc, 0x16, 0x29, 0xb1, 0xa0, 0x68, + 0xee, 0xf3, 0x10, 0xf1, 0x00, 0x23, 0xc4, 0xf8, 0xfc, 0x36, 0xd4, 0xf8, + 0xe0, 0x36, 0x19, 0x6a, 0x31, 0xb1, 0xa0, 0x68, 0xee, 0xf3, 0x06, 0xf1, + 0xd4, 0xf8, 0xe0, 0x36, 0x00, 0x22, 0x1a, 0x62, 0xd4, 0xf8, 0x3c, 0x15, + 0x29, 0xb1, 0xa0, 0x68, 0xee, 0xf3, 0xfc, 0xf0, 0x00, 0x23, 0xc4, 0xf8, + 0x3c, 0x35, 0xd4, 0xf8, 0x94, 0x17, 0x29, 0xb1, 0xa0, 0x68, 0xee, 0xf3, + 0xf3, 0xf0, 0x00, 0x23, 0xc4, 0xf8, 0x94, 0x37, 0xd4, 0xf8, 0xb0, 0x18, + 0x29, 0xb1, 0xa0, 0x68, 0xee, 0xf3, 0xea, 0xf0, 0x00, 0x23, 0xc4, 0xf8, + 0xb0, 0x38, 0x10, 0xbd, 0x10, 0xb5, 0x04, 0x46, 0x00, 0x68, 0x05, 0xf0, + 0xdd, 0xff, 0xd4, 0xf8, 0x48, 0x01, 0x20, 0xb1, 0x05, 0xf0, 0x66, 0xfb, + 0x00, 0x23, 0xc4, 0xf8, 0x48, 0x31, 0xd4, 0xf8, 0x58, 0x31, 0x13, 0xb1, + 0x00, 0x23, 0xc4, 0xf8, 0x58, 0x31, 0xd4, 0xf8, 0x3c, 0x01, 0x20, 0xb1, + 0x05, 0xf0, 0xf6, 0xfa, 0x00, 0x23, 0xc4, 0xf8, 0x3c, 0x31, 0xd4, 0xf8, + 0x40, 0x01, 0x20, 0xb1, 0x01, 0xf0, 0xa6, 0xfa, 0x00, 0x23, 0xc4, 0xf8, + 0x40, 0x31, 0xd4, 0xf8, 0x4c, 0x01, 0x20, 0xb1, 0x05, 0xf0, 0x1c, 0xfc, + 0x00, 0x23, 0xc4, 0xf8, 0x4c, 0x31, 0xd4, 0xf8, 0x54, 0x01, 0x20, 0xb1, + 0x05, 0xf0, 0x92, 0xfb, 0x00, 0x23, 0xc4, 0xf8, 0x54, 0x31, 0xd4, 0xf8, + 0x60, 0x01, 0x20, 0xb1, 0x07, 0xf0, 0x84, 0xf9, 0x00, 0x23, 0xc4, 0xf8, + 0x60, 0x31, 0xd4, 0xf8, 0x38, 0x31, 0x13, 0xb1, 0x00, 0x23, 0xc4, 0xf8, + 0x38, 0x31, 0xd4, 0xf8, 0x64, 0x01, 0x20, 0xb1, 0x02, 0xf0, 0x40, 0xfa, + 0x00, 0x23, 0xc4, 0xf8, 0x64, 0x31, 0xd4, 0xf8, 0x00, 0x05, 0x20, 0xb1, + 0x07, 0xf0, 0x62, 0xfa, 0x00, 0x23, 0xc4, 0xf8, 0x00, 0x35, 0x10, 0xbd, + 0x38, 0xb5, 0x03, 0x68, 0x04, 0x46, 0xd0, 0xf8, 0x60, 0x56, 0x1a, 0x49, + 0x58, 0x69, 0xe1, 0xf3, 0x07, 0xf2, 0x28, 0x70, 0x23, 0x68, 0x18, 0x49, + 0x58, 0x69, 0xd4, 0xf8, 0x60, 0x56, 0xe1, 0xf3, 0xff, 0xf1, 0xe8, 0x70, + 0xd4, 0xf8, 0x60, 0x36, 0x1a, 0x78, 0x0a, 0xb1, 0x0f, 0x2a, 0x01, 0xd1, + 0x01, 0x22, 0x1a, 0x70, 0xd4, 0xf8, 0x60, 0x36, 0x01, 0x21, 0x1a, 0x78, + 0x5a, 0x70, 0xd4, 0xf8, 0x60, 0x56, 0x28, 0x46, 0xe0, 0xf3, 0xa8, 0xf7, + 0xa8, 0x70, 0xd4, 0xf8, 0x60, 0x36, 0xda, 0x78, 0x0a, 0xb1, 0x0f, 0x2a, + 0x01, 0xd1, 0x01, 0x22, 0xda, 0x70, 0xd4, 0xf8, 0x60, 0x36, 0x01, 0x21, + 0xda, 0x78, 0x1a, 0x71, 0xd4, 0xf8, 0x60, 0x46, 0xe0, 0x1c, 0xe0, 0xf3, + 0x95, 0xf7, 0x60, 0x71, 0x38, 0xbd, 0x00, 0xbf, 0x3d, 0x79, 0x86, 0x00, + 0x52, 0x79, 0x86, 0x00, 0x03, 0x68, 0x70, 0xb5, 0x5d, 0x69, 0x04, 0x46, + 0x14, 0x49, 0x28, 0x46, 0xe1, 0xf3, 0xca, 0xf1, 0x40, 0xb2, 0x20, 0xb9, + 0x28, 0x46, 0x12, 0x49, 0xe1, 0xf3, 0xc4, 0xf1, 0x40, 0xb2, 0x43, 0x1e, + 0x0e, 0x2b, 0x0e, 0xd8, 0x01, 0x28, 0x03, 0xd1, 0xd4, 0xf8, 0x60, 0x26, + 0x00, 0x23, 0x04, 0xe0, 0x02, 0x28, 0x06, 0xd1, 0xd4, 0xf8, 0x60, 0x26, + 0x01, 0x23, 0x93, 0x71, 0xd4, 0xf8, 0x60, 0x26, 0xd3, 0x71, 0x08, 0x49, + 0x28, 0x46, 0x26, 0x6b, 0xe1, 0xf3, 0xac, 0xf1, 0x86, 0xf8, 0x04, 0x01, + 0x20, 0x46, 0xf1, 0xf3, 0x47, 0xf5, 0x01, 0x20, 0x70, 0xbd, 0x00, 0xbf, + 0xc6, 0x5c, 0x86, 0x00, 0xcb, 0x5c, 0x86, 0x00, 0x0e, 0x5d, 0x86, 0x00, + 0x70, 0xb5, 0x04, 0x46, 0x21, 0x46, 0x00, 0x68, 0x07, 0xf0, 0xbc, 0xf9, + 0xc4, 0xf8, 0x00, 0x05, 0x00, 0x28, 0x52, 0xd0, 0x20, 0x68, 0x05, 0xf0, + 0xf7, 0xfe, 0x20, 0x68, 0x21, 0x46, 0x01, 0xf0, 0x63, 0xfb, 0xc4, 0xf8, + 0x34, 0x07, 0x00, 0x28, 0x49, 0xd0, 0x2c, 0x4b, 0x20, 0x46, 0xc4, 0xf8, + 0x58, 0x31, 0x05, 0xf0, 0x4b, 0xfa, 0xc4, 0xf8, 0x3c, 0x01, 0x00, 0x28, + 0x41, 0xd0, 0x20, 0x46, 0x01, 0xf0, 0x2c, 0xfa, 0xc4, 0xf8, 0x40, 0x01, + 0x00, 0x28, 0x3c, 0xd0, 0x20, 0x46, 0x07, 0xf0, 0x7d, 0xf8, 0xc4, 0xf8, + 0x60, 0x01, 0x00, 0x28, 0x37, 0xd0, 0x20, 0x68, 0x21, 0x46, 0xa2, 0x68, + 0x1f, 0x4b, 0x05, 0xf0, 0x07, 0xfb, 0xc4, 0xf8, 0x7c, 0x02, 0x00, 0x28, + 0x2f, 0xd0, 0x20, 0x46, 0x02, 0xf0, 0xd6, 0xf9, 0xc4, 0xf8, 0x64, 0x01, + 0x00, 0x28, 0x2a, 0xd0, 0x19, 0x4b, 0x00, 0x25, 0x01, 0x26, 0xc4, 0xf8, + 0x38, 0x31, 0xa4, 0xf8, 0x30, 0x58, 0x84, 0xf8, 0x88, 0x58, 0x84, 0xf8, + 0x8a, 0x58, 0x84, 0xf8, 0x89, 0x68, 0x20, 0x46, 0x05, 0xf0, 0x72, 0xfa, + 0xc4, 0xf8, 0x48, 0x01, 0x00, 0x28, 0x18, 0xd0, 0x23, 0x68, 0x28, 0x46, + 0x83, 0xf8, 0xa3, 0x60, 0x23, 0x68, 0x83, 0xf8, 0xa9, 0x60, 0x23, 0x68, + 0x83, 0xf8, 0xa0, 0x60, 0x70, 0xbd, 0x29, 0x20, 0x70, 0xbd, 0x2a, 0x20, + 0x70, 0xbd, 0x31, 0x20, 0x70, 0xbd, 0x32, 0x20, 0x70, 0xbd, 0x35, 0x20, + 0x70, 0xbd, 0x39, 0x20, 0x70, 0xbd, 0x3c, 0x20, 0x70, 0xbd, 0x43, 0x20, + 0x70, 0xbd, 0x00, 0xbf, 0xef, 0xbe, 0xad, 0xde, 0x9d, 0x6d, 0x81, 0x00, + 0xef, 0xbe, 0xad, 0x0d, 0xf0, 0xb5, 0xd0, 0xf8, 0x40, 0x55, 0x00, 0x21, + 0xac, 0x22, 0x87, 0xb0, 0x04, 0x46, 0x28, 0x46, 0xe0, 0xf3, 0x84, 0xf4, + 0x64, 0x23, 0xeb, 0x85, 0x03, 0x23, 0x85, 0xf8, 0x60, 0x30, 0x00, 0x22, + 0x01, 0x23, 0xd4, 0xf8, 0x5c, 0x01, 0x4f, 0xf4, 0x2c, 0x51, 0x24, 0xf0, + 0x69, 0xdb, 0xff, 0x28, 0x04, 0xd1, 0x23, 0x6b, 0x18, 0x69, 0x19, 0x68, + 0xef, 0xf7, 0x0e, 0xff, 0x21, 0x68, 0x68, 0x86, 0x23, 0x6b, 0xa4, 0xf8, + 0x26, 0x06, 0x91, 0xf8, 0x46, 0x60, 0xff, 0x27, 0x00, 0x21, 0x00, 0xf4, + 0x40, 0x60, 0x1a, 0x89, 0xb0, 0xf5, 0x40, 0x6f, 0x14, 0xbf, 0x14, 0x20, + 0x28, 0x20, 0x1b, 0x68, 0x8d, 0xe8, 0x82, 0x00, 0x03, 0x90, 0x06, 0xf0, + 0x03, 0x06, 0xd4, 0xf8, 0x60, 0x06, 0x02, 0x96, 0x80, 0x78, 0x04, 0x90, + 0x05, 0xf1, 0x38, 0x00, 0x2f, 0xf0, 0x6e, 0xdc, 0x23, 0x68, 0x93, 0xf8, + 0x46, 0x30, 0x98, 0x07, 0x03, 0xd0, 0xeb, 0x88, 0x43, 0xf0, 0x20, 0x03, + 0xeb, 0x80, 0x07, 0xb0, 0xf0, 0xbd, 0x00, 0x00, 0x38, 0xb5, 0x04, 0x46, + 0x2c, 0x49, 0x80, 0x68, 0x22, 0x46, 0x00, 0x23, 0xed, 0xf3, 0x78, 0xf7, + 0xc4, 0xf8, 0xac, 0x01, 0x00, 0x28, 0x4d, 0xd0, 0xa0, 0x68, 0x28, 0x49, + 0x22, 0x46, 0x00, 0x23, 0xed, 0xf3, 0x6e, 0xf7, 0xc4, 0xf8, 0xc4, 0x01, + 0x00, 0x28, 0x43, 0xd0, 0xa0, 0x68, 0x24, 0x49, 0x22, 0x46, 0x00, 0x23, + 0xed, 0xf3, 0x64, 0xf7, 0xc4, 0xf8, 0x74, 0x05, 0x00, 0x28, 0x39, 0xd0, + 0xa0, 0x68, 0x20, 0x49, 0x22, 0x46, 0x00, 0x23, 0xed, 0xf3, 0x5a, 0xf7, + 0xc4, 0xf8, 0xf8, 0x06, 0x00, 0x28, 0x2f, 0xd0, 0xa0, 0x68, 0x1c, 0x49, + 0x22, 0x46, 0x00, 0x23, 0xed, 0xf3, 0x50, 0xf7, 0xc4, 0xf8, 0xfc, 0x06, + 0x30, 0xb3, 0xa0, 0x68, 0x18, 0x49, 0x22, 0x46, 0x00, 0x23, 0xd4, 0xf8, + 0xe0, 0x56, 0xed, 0xf3, 0x45, 0xf7, 0x28, 0x62, 0xe0, 0xb1, 0xa0, 0x68, + 0x14, 0x49, 0x22, 0x46, 0x00, 0x23, 0xed, 0xf3, 0x3d, 0xf7, 0xc4, 0xf8, + 0x3c, 0x05, 0x98, 0xb1, 0xa0, 0x68, 0x11, 0x49, 0x22, 0x46, 0x00, 0x23, + 0xed, 0xf3, 0x34, 0xf7, 0xc4, 0xf8, 0x94, 0x07, 0x50, 0xb1, 0x00, 0x23, + 0xa0, 0x68, 0x0d, 0x49, 0x22, 0x46, 0xed, 0xf3, 0x2b, 0xf7, 0xc4, 0xf8, + 0xb0, 0x08, 0x00, 0x30, 0x18, 0xbf, 0x01, 0x20, 0x38, 0xbd, 0x00, 0xbf, + 0x3d, 0xaa, 0x81, 0x00, 0x3d, 0x70, 0x81, 0x00, 0x25, 0x3e, 0x81, 0x00, + 0x95, 0x91, 0x81, 0x00, 0x85, 0x8f, 0x81, 0x00, 0x25, 0x6e, 0x81, 0x00, + 0x89, 0x59, 0x81, 0x00, 0x39, 0x6b, 0x81, 0x00, 0x49, 0x6f, 0x81, 0x00, + 0xf8, 0xb5, 0x42, 0xf6, 0x01, 0x31, 0x00, 0x25, 0xff, 0x23, 0x01, 0x26, + 0x64, 0x27, 0x04, 0x46, 0x80, 0xf8, 0x47, 0x36, 0x80, 0xf8, 0xc4, 0x34, + 0xa0, 0xf8, 0x28, 0x16, 0x80, 0xf8, 0x28, 0x60, 0x80, 0xf8, 0x68, 0x77, + 0x80, 0xf8, 0x42, 0x56, 0x80, 0xf8, 0x4c, 0x66, 0x80, 0xf8, 0x43, 0x56, + 0x80, 0xf8, 0x49, 0x66, 0x80, 0xf8, 0x46, 0x56, 0x02, 0x21, 0x4f, 0xf0, + 0xff, 0x32, 0x04, 0xf0, 0x4d, 0xd8, 0x20, 0x46, 0x31, 0x46, 0x2a, 0x46, + 0x04, 0xf0, 0x48, 0xd8, 0x20, 0x46, 0x0c, 0x21, 0x4f, 0xf0, 0xff, 0x32, + 0x04, 0xf0, 0x42, 0xd8, 0x20, 0x46, 0x0b, 0x21, 0x2a, 0x46, 0x04, 0xf0, + 0x3d, 0xd8, 0x20, 0x46, 0x0e, 0x21, 0x4f, 0xf0, 0xff, 0x32, 0x04, 0xf0, + 0x37, 0xd8, 0x20, 0x46, 0x0d, 0x21, 0x2a, 0x46, 0x04, 0xf0, 0x32, 0xd8, + 0x20, 0x46, 0x0f, 0x21, 0x4f, 0xf0, 0xff, 0x32, 0x04, 0xf0, 0x2c, 0xd8, + 0x04, 0x21, 0x02, 0x22, 0x20, 0x46, 0x04, 0xf0, 0x27, 0xd8, 0xd4, 0xf8, + 0x60, 0x36, 0x03, 0x22, 0x84, 0xf8, 0x48, 0x66, 0x9a, 0x71, 0xd4, 0xf8, + 0x60, 0x36, 0x40, 0xf6, 0x2a, 0x11, 0xda, 0x71, 0xa4, 0xf8, 0x2a, 0x16, + 0xa4, 0xf8, 0x2c, 0x16, 0xa4, 0xf8, 0x2e, 0x16, 0xa4, 0xf8, 0x30, 0x16, + 0xa4, 0xf8, 0x32, 0x16, 0xa4, 0xf8, 0x34, 0x16, 0xa4, 0xf8, 0x36, 0x16, + 0x40, 0xf6, 0x2b, 0x11, 0xa4, 0xf8, 0x38, 0x16, 0x21, 0x68, 0xa4, 0xf8, + 0x7a, 0x55, 0x81, 0xf8, 0x95, 0x50, 0xa4, 0xf8, 0x3e, 0x26, 0x02, 0x22, + 0xa4, 0xf8, 0x40, 0x26, 0x04, 0x22, 0x07, 0x21, 0xa4, 0xf8, 0x3c, 0x26, + 0x0f, 0x22, 0xa4, 0xf8, 0x3a, 0x16, 0xa4, 0xf8, 0x7c, 0x58, 0xa4, 0xf8, + 0x7e, 0x78, 0x84, 0xf8, 0xea, 0x51, 0x84, 0xf8, 0xeb, 0x51, 0x84, 0xf8, + 0x1e, 0x52, 0x84, 0xf8, 0xee, 0x51, 0x84, 0xf8, 0xec, 0x51, 0x84, 0xf8, + 0xfa, 0x61, 0x84, 0xf8, 0x0b, 0x57, 0x84, 0xf8, 0x0c, 0x27, 0x84, 0xf8, + 0xa0, 0x54, 0x23, 0x46, 0xd3, 0xf8, 0x90, 0x24, 0xc3, 0xf8, 0x80, 0x22, + 0x95, 0x71, 0x01, 0x35, 0x04, 0x33, 0x04, 0x2d, 0xf6, 0xd1, 0x23, 0x68, + 0x00, 0x25, 0x01, 0x26, 0x84, 0xf8, 0x50, 0x57, 0x4f, 0xf0, 0xff, 0x32, + 0x83, 0xf8, 0x4d, 0x60, 0x5a, 0x63, 0x23, 0x68, 0x04, 0xf5, 0xcc, 0x67, + 0x83, 0xf8, 0x42, 0x60, 0x23, 0x68, 0x0b, 0x22, 0x83, 0xf8, 0x43, 0x50, + 0x23, 0x68, 0x84, 0xf8, 0xcf, 0x51, 0x83, 0xf8, 0x39, 0x50, 0x23, 0x68, + 0x38, 0x1d, 0x83, 0xf8, 0xaa, 0x60, 0x23, 0x68, 0x84, 0xf8, 0xdf, 0x51, + 0x84, 0xf8, 0xe0, 0x61, 0xc4, 0xf8, 0xe4, 0x51, 0x84, 0xf8, 0xe1, 0x51, + 0x29, 0x46, 0xdd, 0x66, 0xe0, 0xf3, 0x18, 0xf3, 0xdd, 0x23, 0x84, 0xf8, + 0x64, 0x36, 0x09, 0x23, 0x03, 0x22, 0x84, 0xf8, 0x65, 0x36, 0xb8, 0x1d, + 0x1a, 0x49, 0xe0, 0xf3, 0xa9, 0xf2, 0x02, 0x23, 0x84, 0xf8, 0x69, 0x36, + 0x23, 0x68, 0x84, 0xf8, 0x56, 0x65, 0x84, 0xf8, 0x57, 0x65, 0x83, 0xf8, + 0x4c, 0x50, 0x64, 0x23, 0xa4, 0xf8, 0x8c, 0x38, 0x23, 0x68, 0x84, 0xf8, + 0x92, 0x57, 0xa4, 0xf8, 0x90, 0x57, 0x93, 0xf8, 0x46, 0x20, 0x92, 0x07, + 0x0c, 0xd0, 0x93, 0xf9, 0x4c, 0x30, 0x4b, 0xb1, 0xd4, 0xf8, 0xfc, 0x04, + 0x24, 0x30, 0xf3, 0xf3, 0xf7, 0xf3, 0xd4, 0xf8, 0xfc, 0x04, 0x32, 0x30, + 0xf3, 0xf3, 0xf2, 0xf3, 0x22, 0x68, 0x01, 0x23, 0x4f, 0xf4, 0x48, 0x71, + 0x84, 0xf8, 0x25, 0x38, 0xa4, 0xf8, 0x5c, 0x17, 0x82, 0xf8, 0xa2, 0x30, + 0x23, 0x68, 0xff, 0x22, 0x83, 0xf8, 0xb5, 0x20, 0xf8, 0xbd, 0x00, 0xbf, + 0xc5, 0xb6, 0x01, 0x00, 0x41, 0xf2, 0xe4, 0x43, 0x98, 0x42, 0x40, 0xf0, + 0xc8, 0x80, 0x44, 0xf2, 0x20, 0x33, 0x99, 0x42, 0x00, 0xf0, 0xc5, 0x80, + 0x44, 0xf2, 0x25, 0x33, 0x99, 0x42, 0x00, 0xf0, 0xc0, 0x80, 0x44, 0xf2, + 0x03, 0x33, 0x99, 0x42, 0x00, 0xf0, 0xbb, 0x80, 0x44, 0xf2, 0x21, 0x33, + 0x99, 0x42, 0x00, 0xf0, 0xb6, 0x80, 0x44, 0xf2, 0x24, 0x33, 0x99, 0x42, + 0x00, 0xf0, 0xb1, 0x80, 0x44, 0xf2, 0x18, 0x33, 0x99, 0x42, 0x00, 0xf0, + 0xac, 0x80, 0x44, 0xf2, 0x19, 0x33, 0x99, 0x42, 0x00, 0xf0, 0xa7, 0x80, + 0x44, 0xf2, 0x1a, 0x33, 0x99, 0x42, 0x00, 0xf0, 0xa2, 0x80, 0x44, 0xf2, + 0x11, 0x33, 0x99, 0x42, 0x00, 0xf0, 0x9d, 0x80, 0x44, 0xf2, 0x13, 0x33, + 0x99, 0x42, 0x00, 0xf0, 0x98, 0x80, 0x44, 0xf2, 0x12, 0x33, 0x99, 0x42, + 0x00, 0xf0, 0x93, 0x80, 0x44, 0xf2, 0x14, 0x33, 0x99, 0x42, 0x00, 0xf0, + 0x8e, 0x80, 0x44, 0xf2, 0x15, 0x33, 0x99, 0x42, 0x00, 0xf0, 0x89, 0x80, + 0x44, 0xf2, 0x16, 0x33, 0x99, 0x42, 0x00, 0xf0, 0x84, 0x80, 0x44, 0xf2, + 0x1b, 0x33, 0x99, 0x42, 0x7f, 0xd0, 0x44, 0xf2, 0x1c, 0x33, 0x99, 0x42, + 0x7b, 0xd0, 0x44, 0xf2, 0x1d, 0x33, 0x99, 0x42, 0x77, 0xd0, 0xa1, 0xf5, + 0x86, 0x43, 0xa3, 0xf1, 0x28, 0x02, 0x92, 0xb2, 0x02, 0x2a, 0x70, 0xd9, + 0x2b, 0x3b, 0x9b, 0xb2, 0x02, 0x2b, 0x6c, 0xd9, 0x44, 0xf2, 0x41, 0x33, + 0x99, 0x42, 0x68, 0xd0, 0x44, 0xf2, 0x40, 0x33, 0x99, 0x42, 0x64, 0xd0, + 0xa1, 0xf5, 0x86, 0x43, 0x50, 0x3b, 0x9b, 0xb2, 0x02, 0x2b, 0x5e, 0xd9, + 0x44, 0xf2, 0x53, 0x33, 0x99, 0x42, 0x5a, 0xd0, 0x44, 0xf2, 0x57, 0x33, + 0x99, 0x42, 0x56, 0xd0, 0x4a, 0xf6, 0x9d, 0x13, 0x99, 0x42, 0x52, 0xd0, + 0x44, 0xf2, 0x54, 0x33, 0x99, 0x42, 0x4e, 0xd0, 0x44, 0xf2, 0x2f, 0x33, + 0x99, 0x42, 0x4a, 0xd0, 0x44, 0xf2, 0x2e, 0x33, 0x99, 0x42, 0x46, 0xd0, + 0x44, 0xf2, 0x34, 0x33, 0x99, 0x42, 0x42, 0xd0, 0x44, 0xf2, 0x35, 0x33, + 0x99, 0x42, 0x3e, 0xd0, 0x44, 0xf2, 0x36, 0x33, 0x99, 0x42, 0x3a, 0xd0, + 0xa1, 0xf5, 0x86, 0x43, 0xa3, 0xf1, 0x37, 0x02, 0x92, 0xb2, 0x02, 0x2a, + 0x33, 0xd9, 0x44, 0xf2, 0x16, 0x72, 0x91, 0x42, 0x2f, 0xd0, 0x44, 0xf2, + 0x27, 0x72, 0x91, 0x42, 0x2b, 0xd0, 0x44, 0xf2, 0x43, 0x32, 0x91, 0x42, + 0x27, 0xd0, 0xa3, 0xf1, 0x60, 0x02, 0x92, 0xb2, 0x01, 0x2a, 0x22, 0xd9, + 0xa3, 0xf1, 0x46, 0x02, 0x92, 0xb2, 0x02, 0x2a, 0x1d, 0xd9, 0xa3, 0xf1, + 0x31, 0x02, 0x92, 0xb2, 0x01, 0x2a, 0x18, 0xd9, 0x55, 0x3b, 0x9b, 0xb2, + 0x01, 0x2b, 0x14, 0xd9, 0xa1, 0xf5, 0x86, 0x43, 0x58, 0x3b, 0x9b, 0xb2, + 0x01, 0x2b, 0x0e, 0xd9, 0x44, 0xf2, 0x63, 0x33, 0x99, 0x42, 0x0c, 0xd0, + 0x44, 0xf2, 0x70, 0x30, 0xc0, 0xeb, 0x01, 0x0c, 0xdc, 0xf1, 0x00, 0x00, + 0x40, 0xeb, 0x0c, 0x00, 0x70, 0x47, 0x00, 0x20, 0x70, 0x47, 0x01, 0x20, + 0x70, 0x47, 0x01, 0x20, 0x70, 0x47, 0x83, 0x6b, 0x70, 0xb5, 0x00, 0x25, + 0x83, 0xf8, 0x4c, 0x50, 0xc3, 0x6b, 0x01, 0x26, 0x83, 0xf8, 0x4c, 0x60, + 0x04, 0x46, 0x81, 0x6b, 0xe3, 0xf7, 0x35, 0xfb, 0xe1, 0x6b, 0x20, 0x46, + 0xe3, 0xf7, 0x31, 0xfb, 0x29, 0x46, 0x20, 0x46, 0xf8, 0xf3, 0x78, 0xf0, + 0xa3, 0x6b, 0x20, 0x46, 0x83, 0xf8, 0x4d, 0x50, 0xe3, 0x6b, 0x31, 0x46, + 0x83, 0xf8, 0x4d, 0x50, 0xd4, 0xf8, 0x60, 0x36, 0x4f, 0xf0, 0xff, 0x35, + 0xde, 0x72, 0xd4, 0xf8, 0x60, 0x36, 0x9d, 0x81, 0xf8, 0xf3, 0x66, 0xf0, + 0xd4, 0xf8, 0x60, 0x36, 0x9b, 0x78, 0xb3, 0x42, 0x0c, 0xd9, 0xa3, 0x6b, + 0xff, 0x22, 0x83, 0xf8, 0x4d, 0x50, 0xe3, 0x6b, 0x83, 0xf8, 0x4d, 0x20, + 0xb4, 0xf8, 0xcb, 0x34, 0x43, 0xf0, 0x80, 0x03, 0xa4, 0xf8, 0xcb, 0x34, + 0x70, 0xbd, 0x00, 0x00, 0xf8, 0xb5, 0x04, 0x46, 0x00, 0x28, 0x00, 0xf0, + 0x9a, 0x80, 0x01, 0xf0, 0xbf, 0xfb, 0x06, 0x46, 0x20, 0x46, 0x03, 0xf0, + 0xb5, 0xdf, 0x00, 0xb9, 0x01, 0x36, 0xd4, 0xf8, 0xf0, 0x16, 0x49, 0xb1, + 0x60, 0x68, 0xd4, 0xf8, 0xf4, 0x26, 0xe5, 0xf3, 0x0d, 0xf0, 0x00, 0x23, + 0xc4, 0xf8, 0xf4, 0x36, 0xc4, 0xf8, 0xf0, 0x36, 0x20, 0x46, 0xd4, 0xf8, + 0x18, 0x15, 0xfa, 0xf3, 0xd5, 0xf6, 0x20, 0x46, 0xd4, 0xf8, 0xd8, 0x16, + 0xfa, 0xf3, 0xd0, 0xf6, 0xd4, 0xf8, 0x20, 0x15, 0x20, 0x46, 0xfa, 0xf3, + 0xcb, 0xf6, 0xd4, 0xf8, 0x2c, 0x15, 0x21, 0xb1, 0x60, 0x68, 0x4f, 0xf4, + 0x96, 0x62, 0xe4, 0xf3, 0xf1, 0xf7, 0xd4, 0xf8, 0x7c, 0x02, 0x20, 0xb1, + 0x04, 0xf0, 0xf6, 0xff, 0x00, 0x23, 0xc4, 0xf8, 0x7c, 0x32, 0x25, 0x46, + 0x04, 0xf1, 0x20, 0x07, 0x06, 0xe0, 0xd5, 0xf8, 0x4c, 0x12, 0x11, 0xb1, + 0x20, 0x46, 0x1d, 0xf0, 0x83, 0xdb, 0x04, 0x35, 0xbd, 0x42, 0xf6, 0xd1, + 0x01, 0x21, 0x20, 0x46, 0x33, 0xf0, 0x12, 0xdd, 0x20, 0x46, 0x01, 0xf0, + 0x0f, 0xfe, 0x27, 0x6b, 0xb9, 0x69, 0x11, 0xb1, 0x20, 0x46, 0x32, 0xf0, + 0x9d, 0xdf, 0x00, 0x25, 0xbd, 0x61, 0xd4, 0xf8, 0x5c, 0x01, 0x01, 0xf0, + 0xf5, 0xfe, 0x20, 0x46, 0xff, 0xf7, 0x52, 0xfb, 0x20, 0x46, 0xff, 0xf7, + 0xa5, 0xfb, 0x20, 0x46, 0xd4, 0xf8, 0x2c, 0x18, 0xe1, 0xf7, 0x6c, 0xfe, + 0xc4, 0xf8, 0x2c, 0x58, 0xd4, 0xf8, 0xb8, 0x54, 0x06, 0xe0, 0x29, 0x46, + 0x60, 0x68, 0x10, 0x22, 0xef, 0x68, 0xe4, 0xf3, 0xb3, 0xf7, 0x3d, 0x46, + 0x00, 0x2d, 0xf6, 0xd1, 0xc4, 0xf8, 0xb8, 0x54, 0x20, 0x68, 0x16, 0x49, + 0x22, 0x46, 0x02, 0xf0, 0xd5, 0xd8, 0xd4, 0xf8, 0x34, 0x07, 0x18, 0xb1, + 0x00, 0xf0, 0x98, 0xff, 0xc4, 0xf8, 0x34, 0x57, 0xd4, 0xf8, 0x68, 0x01, + 0x20, 0xb1, 0x06, 0xf0, 0xe3, 0xfd, 0x00, 0x23, 0xc4, 0xf8, 0x68, 0x31, + 0xd4, 0xf8, 0x18, 0x17, 0x51, 0xb1, 0x60, 0x68, 0xd4, 0xf8, 0x1c, 0x27, + 0xe4, 0xf3, 0x92, 0xf7, 0x00, 0x23, 0xc4, 0xf8, 0x18, 0x37, 0x01, 0xe0, + 0x08, 0xf0, 0xf8, 0xdf, 0xd4, 0xf8, 0x78, 0x22, 0x20, 0x46, 0x61, 0x68, + 0x00, 0x2a, 0xf7, 0xd1, 0x00, 0xf0, 0x02, 0xfc, 0x00, 0xe0, 0x06, 0x46, + 0x30, 0x46, 0xf8, 0xbd, 0xbb, 0x5c, 0x86, 0x00, 0x2d, 0xe9, 0xf0, 0x4f, + 0x8d, 0xb0, 0x06, 0x92, 0xdd, 0xf8, 0x5c, 0x80, 0x1a, 0x9a, 0x99, 0x46, + 0x00, 0x23, 0x07, 0x91, 0x0a, 0x93, 0x00, 0x92, 0x07, 0x46, 0x41, 0x46, + 0x06, 0x98, 0x18, 0x9a, 0x19, 0x9b, 0x9d, 0xf8, 0x58, 0xb0, 0xdd, 0xf8, + 0x6c, 0xa0, 0x09, 0xf0, 0x55, 0xf8, 0x06, 0x46, 0x10, 0xb1, 0x1e, 0x23, + 0x0a, 0x93, 0x20, 0xe3, 0xff, 0xf7, 0xe4, 0xfa, 0x40, 0x46, 0x49, 0x46, + 0x0a, 0xaa, 0x00, 0xf0, 0xc7, 0xfc, 0x04, 0x46, 0x00, 0x28, 0x00, 0xf0, + 0x16, 0x83, 0xd0, 0xf8, 0x60, 0x36, 0xff, 0x22, 0xc0, 0xf8, 0x04, 0x80, + 0x05, 0x68, 0x83, 0xf8, 0x1c, 0x21, 0x83, 0x6b, 0x87, 0x60, 0x03, 0x63, + 0x43, 0x6b, 0x49, 0x46, 0xc3, 0x62, 0xae, 0x4b, 0xc5, 0xf8, 0x04, 0x90, + 0xc5, 0xf8, 0xb0, 0x30, 0x1a, 0x9b, 0xc5, 0xf8, 0x0c, 0x80, 0xc0, 0xf8, + 0x78, 0x31, 0x03, 0x23, 0x85, 0xf8, 0x21, 0xb0, 0x80, 0xf8, 0x69, 0x37, + 0x4f, 0xf0, 0xff, 0x33, 0xc0, 0xf8, 0xcc, 0x38, 0x80, 0xf8, 0x9d, 0x61, + 0xff, 0xf7, 0x04, 0xfd, 0x20, 0x46, 0xf9, 0xf3, 0x97, 0xf7, 0x20, 0x46, + 0x04, 0xf0, 0x64, 0xff, 0x06, 0x46, 0x00, 0x28, 0x40, 0xf0, 0xf4, 0x82, + 0x20, 0x46, 0x39, 0x46, 0x42, 0x46, 0x4b, 0x46, 0x06, 0xf0, 0xd4, 0xfc, + 0xc4, 0xf8, 0x68, 0x01, 0x08, 0xb9, 0x1f, 0x23, 0xb0, 0xe2, 0x99, 0x4b, + 0x02, 0x96, 0x8d, 0xe8, 0x48, 0x00, 0x03, 0x96, 0x97, 0x49, 0x98, 0x4a, + 0x23, 0x46, 0x20, 0x68, 0x02, 0xf0, 0x06, 0xd8, 0x96, 0x4b, 0x02, 0x96, + 0x8d, 0xe8, 0x48, 0x00, 0x03, 0x96, 0x95, 0x49, 0x95, 0x4a, 0x23, 0x46, + 0x20, 0x68, 0x01, 0xf0, 0xfb, 0xdf, 0x18, 0x9a, 0x19, 0x9b, 0x02, 0x92, + 0x1a, 0x9a, 0x03, 0x93, 0x04, 0x92, 0x20, 0x46, 0x07, 0x99, 0x06, 0x9a, + 0x4b, 0x46, 0xcd, 0xf8, 0x00, 0xb0, 0xcd, 0xf8, 0x04, 0x80, 0x01, 0xf0, + 0x11, 0xfb, 0x06, 0x46, 0x0a, 0x90, 0x00, 0x28, 0x40, 0xf0, 0xbe, 0x82, + 0x23, 0x69, 0x18, 0x6e, 0xeb, 0xf7, 0x31, 0xf9, 0xa4, 0xf8, 0xbe, 0x08, + 0x20, 0x46, 0xf7, 0xf3, 0x01, 0xf6, 0x08, 0xb9, 0x14, 0x23, 0x79, 0xe2, + 0x31, 0x46, 0x0b, 0xaa, 0x20, 0x46, 0xf9, 0xf3, 0x85, 0xf2, 0x31, 0x46, + 0x20, 0x46, 0xbd, 0xf8, 0x2c, 0x20, 0x01, 0x36, 0xf9, 0xf3, 0x88, 0xf2, + 0x06, 0x2e, 0xf1, 0xd1, 0x01, 0x27, 0x85, 0xf8, 0x9a, 0x70, 0x04, 0xf5, + 0xbe, 0x72, 0x20, 0x69, 0x05, 0xf1, 0x14, 0x01, 0x1a, 0xf0, 0xc8, 0xdc, + 0x77, 0x49, 0x68, 0x69, 0xe0, 0xf3, 0x0e, 0xf5, 0x76, 0x49, 0x06, 0x46, + 0x68, 0x69, 0xe0, 0xf3, 0x09, 0xf5, 0x75, 0x49, 0xa4, 0xf8, 0x62, 0x08, + 0x68, 0x69, 0xe0, 0xf3, 0x03, 0xf5, 0xb4, 0xf8, 0x62, 0x38, 0xa4, 0xf8, + 0x64, 0x08, 0xa4, 0xf8, 0x78, 0x37, 0xa4, 0xf8, 0x7a, 0x07, 0x6f, 0x49, + 0x68, 0x69, 0xe0, 0xf3, 0xf7, 0xf4, 0x6e, 0x49, 0xa4, 0xf8, 0x54, 0x08, + 0x68, 0x69, 0xe0, 0xf3, 0xf1, 0xf4, 0x84, 0xf8, 0x56, 0x08, 0x6b, 0x49, + 0x68, 0x69, 0xe0, 0xf3, 0xeb, 0xf4, 0x84, 0xf8, 0x58, 0x08, 0x69, 0x49, + 0x68, 0x69, 0xe0, 0xf3, 0xe5, 0xf4, 0x84, 0xf8, 0x5a, 0x08, 0x67, 0x49, + 0x68, 0x69, 0xe0, 0xf3, 0xdf, 0xf4, 0x84, 0xf8, 0x57, 0x08, 0x65, 0x49, + 0x68, 0x69, 0xe0, 0xf3, 0xd9, 0xf4, 0x84, 0xf8, 0x59, 0x08, 0x63, 0x49, + 0x68, 0x69, 0xe0, 0xf3, 0xd3, 0xf4, 0x84, 0xf8, 0x5b, 0x08, 0x61, 0x49, + 0x68, 0x69, 0xe0, 0xf3, 0xcd, 0xf4, 0x84, 0xf8, 0x5c, 0x08, 0x5f, 0x49, + 0x68, 0x69, 0xe0, 0xf3, 0xc7, 0xf4, 0x84, 0xf8, 0x5e, 0x08, 0x5d, 0x49, + 0x68, 0x69, 0xe0, 0xf3, 0xc1, 0xf4, 0x84, 0xf8, 0x60, 0x08, 0x5b, 0x49, + 0x68, 0x69, 0xe0, 0xf3, 0xbb, 0xf4, 0x84, 0xf8, 0x5d, 0x08, 0x59, 0x49, + 0x68, 0x69, 0xe0, 0xf3, 0xb5, 0xf4, 0x84, 0xf8, 0x5f, 0x08, 0x57, 0x49, + 0x68, 0x69, 0xe0, 0xf3, 0xaf, 0xf4, 0x84, 0xf8, 0x61, 0x08, 0x20, 0x46, + 0xff, 0xf7, 0x9a, 0xfa, 0xd4, 0xf8, 0x60, 0x36, 0x22, 0x6b, 0x84, 0xf8, + 0xf0, 0x77, 0x84, 0xf8, 0xf1, 0x77, 0x10, 0x69, 0x19, 0x78, 0xda, 0x78, + 0xf0, 0xf7, 0xd7, 0xf8, 0xe2, 0x6a, 0x20, 0x69, 0x00, 0x23, 0xc1, 0x18, + 0xd1, 0xf8, 0xa0, 0x70, 0xd1, 0x18, 0x04, 0x33, 0x18, 0x2b, 0x4f, 0x60, + 0xf7, 0xd1, 0x04, 0xf5, 0xcb, 0x77, 0x39, 0x46, 0x1a, 0xf0, 0x74, 0xdd, + 0x06, 0x22, 0x05, 0xf1, 0x4e, 0x00, 0x39, 0x46, 0xdf, 0xf3, 0x88, 0xf7, + 0xb4, 0xf8, 0x82, 0x31, 0x44, 0xf2, 0x1d, 0x32, 0x93, 0x42, 0x1d, 0xd0, + 0x0a, 0xd8, 0x44, 0xf2, 0x16, 0x32, 0x93, 0x42, 0x18, 0xd0, 0x44, 0xf2, + 0x1a, 0x32, 0x93, 0x42, 0x14, 0xd0, 0x44, 0xf2, 0x13, 0x32, 0x0d, 0xe0, + 0x44, 0xf2, 0x2a, 0x32, 0x93, 0x42, 0x0d, 0xd0, 0x02, 0xd8, 0x44, 0xf2, + 0x21, 0x32, 0x05, 0xe0, 0x44, 0xf2, 0x2d, 0x32, 0x93, 0x42, 0x05, 0xd0, + 0x44, 0xf2, 0x52, 0x32, 0x93, 0x42, 0x01, 0xd0, 0x00, 0x23, 0x00, 0xe0, + 0x01, 0x23, 0x0e, 0x33, 0x54, 0xf8, 0x23, 0x30, 0x20, 0x46, 0x23, 0x63, + 0xff, 0xf7, 0x8a, 0xfa, 0x08, 0xb9, 0x18, 0x23, 0xa8, 0xe1, 0x21, 0x6b, + 0x0f, 0x22, 0x40, 0xf2, 0xff, 0x33, 0xa1, 0xf8, 0x06, 0x21, 0xa1, 0xf8, + 0x08, 0x31, 0x01, 0xf1, 0xfc, 0x02, 0x01, 0xf5, 0x80, 0x73, 0x20, 0x46, + 0x00, 0xf0, 0x88, 0xff, 0x23, 0x6b, 0xd3, 0xf8, 0xfc, 0x20, 0xc3, 0xf8, + 0xf8, 0x20, 0xc3, 0xf8, 0xf0, 0x20, 0xd3, 0xf8, 0x00, 0x21, 0xc3, 0xf8, + 0xf4, 0x20, 0x1a, 0x68, 0x02, 0x2a, 0x07, 0xd1, 0x01, 0x22, 0x5a, 0x75, + 0x23, 0x6b, 0x20, 0x46, 0x03, 0x21, 0x5a, 0x7d, 0x03, 0xf0, 0x30, 0xdc, + 0xf2, 0x07, 0x2f, 0xd5, 0x00, 0x22, 0x2e, 0xe0, 0x0c, 0xe6, 0x5a, 0x05, + 0x79, 0xdb, 0x81, 0x00, 0x78, 0xd4, 0x85, 0x00, 0xbb, 0x5c, 0x86, 0x00, + 0xa9, 0x36, 0x00, 0x00, 0x04, 0xbc, 0x01, 0x00, 0x07, 0xbb, 0x01, 0x00, + 0xd6, 0x68, 0x86, 0x00, 0xe2, 0x68, 0x86, 0x00, 0xf5, 0x68, 0x86, 0x00, + 0x07, 0x69, 0x86, 0x00, 0x1c, 0x69, 0x86, 0x00, 0x2b, 0x69, 0x86, 0x00, + 0x3a, 0x69, 0x86, 0x00, 0x49, 0x69, 0x86, 0x00, 0x5a, 0x69, 0x86, 0x00, + 0x6b, 0x69, 0x86, 0x00, 0x7c, 0x69, 0x86, 0x00, 0x8a, 0x69, 0x86, 0x00, + 0x98, 0x69, 0x86, 0x00, 0xa6, 0x69, 0x86, 0x00, 0xb6, 0x69, 0x86, 0x00, + 0xc6, 0x69, 0x86, 0x00, 0x01, 0x22, 0x85, 0xf8, 0x46, 0x20, 0x20, 0x46, + 0x0a, 0x21, 0x03, 0xf0, 0xf7, 0xdb, 0x21, 0x6b, 0x20, 0x46, 0x1c, 0x31, + 0xfb, 0xf3, 0x50, 0xf4, 0x7f, 0x23, 0x21, 0x6b, 0x00, 0x93, 0x23, 0x68, + 0x00, 0x22, 0x93, 0xf8, 0x46, 0x30, 0x01, 0xf1, 0x1c, 0x00, 0x03, 0xf0, + 0x03, 0x03, 0x50, 0x31, 0x01, 0x93, 0x13, 0x46, 0x2e, 0xf0, 0xa6, 0xdf, + 0x20, 0x46, 0xf7, 0xf3, 0x11, 0xf5, 0x4f, 0xf4, 0xd1, 0x63, 0xc4, 0xf8, + 0x74, 0x38, 0x20, 0x46, 0xff, 0xf7, 0x3e, 0xfa, 0x07, 0x46, 0x0a, 0x90, + 0x00, 0x28, 0x40, 0xf0, 0x5f, 0x81, 0x20, 0x46, 0x49, 0x46, 0xff, 0xf7, + 0xf3, 0xfa, 0x08, 0xb9, 0x20, 0x23, 0x1f, 0xe1, 0x20, 0x46, 0x01, 0xf0, + 0xbd, 0xfc, 0xc4, 0xf8, 0x5c, 0x01, 0x08, 0xb9, 0x21, 0x23, 0x17, 0xe1, + 0x20, 0x46, 0xff, 0xf7, 0x9b, 0xfa, 0x39, 0x46, 0xa7, 0x4a, 0xa8, 0x4b, + 0x20, 0x46, 0x00, 0x97, 0x01, 0x94, 0x06, 0xf0, 0x17, 0xfc, 0xa6, 0x4b, + 0x1a, 0x1d, 0x07, 0xca, 0x1b, 0x68, 0x8d, 0xe8, 0x07, 0x00, 0x07, 0x21, + 0x20, 0x46, 0x22, 0x46, 0x08, 0xf0, 0x2c, 0xdd, 0x04, 0x21, 0x20, 0x46, + 0xa0, 0x4a, 0xa1, 0x4b, 0x00, 0x97, 0x01, 0x94, 0x06, 0xf0, 0x04, 0xfc, + 0x00, 0x28, 0xc4, 0xf8, 0x8c, 0x07, 0x01, 0xda, 0x22, 0x23, 0xf3, 0xe0, + 0x20, 0x46, 0x41, 0x46, 0x08, 0xf0, 0x9e, 0xdd, 0x08, 0xb9, 0x64, 0x23, + 0xec, 0xe0, 0x4f, 0xf0, 0xff, 0x33, 0xc4, 0xf8, 0x04, 0x08, 0x97, 0x49, + 0x00, 0x93, 0x20, 0x46, 0x96, 0x4a, 0x97, 0x4b, 0x00, 0xf0, 0xda, 0xde, + 0xc4, 0xf8, 0x2c, 0x08, 0x00, 0x28, 0x00, 0xf0, 0x15, 0x81, 0x20, 0x46, + 0x01, 0xf0, 0x8b, 0xfb, 0x08, 0xb1, 0x23, 0x23, 0xd6, 0xe0, 0x23, 0x68, + 0x06, 0x22, 0x93, 0xf8, 0xa1, 0x30, 0xa5, 0xf8, 0x64, 0x20, 0x01, 0x2b, + 0x02, 0xd1, 0x40, 0x23, 0xa5, 0xf8, 0x64, 0x30, 0xd5, 0xf8, 0x8c, 0x30, + 0x06, 0x22, 0x1a, 0x80, 0x4f, 0xf4, 0x39, 0x72, 0x5a, 0x80, 0xd5, 0xf8, + 0x90, 0x30, 0xc4, 0x22, 0x01, 0x27, 0x04, 0xf5, 0x00, 0x71, 0x20, 0x46, + 0x1f, 0x80, 0x5a, 0x80, 0x06, 0x31, 0x09, 0xf0, 0x3b, 0xdd, 0xd4, 0xf8, + 0x3c, 0x01, 0x0e, 0xf0, 0xc5, 0xdd, 0x08, 0xb1, 0x84, 0xf8, 0xcf, 0x71, + 0x02, 0x23, 0x84, 0xf8, 0xc0, 0x34, 0x1e, 0x23, 0x84, 0xf8, 0xcb, 0x34, + 0x10, 0x23, 0x84, 0xf8, 0xcc, 0x34, 0x23, 0x6b, 0x5b, 0x89, 0x02, 0x2b, + 0x02, 0xd8, 0x1c, 0x23, 0x84, 0xf8, 0xcb, 0x34, 0xff, 0x23, 0x00, 0x21, + 0x84, 0xf8, 0xca, 0x34, 0x84, 0xf8, 0xc9, 0x34, 0x84, 0xf8, 0xc8, 0x34, + 0x20, 0x46, 0xf8, 0xf3, 0xd7, 0xf1, 0x23, 0x68, 0x00, 0x27, 0x83, 0xf8, + 0xb4, 0x70, 0x4f, 0xf0, 0xff, 0x33, 0xc4, 0xf8, 0xd4, 0x31, 0x20, 0x46, + 0x39, 0x46, 0xf3, 0xf3, 0xe3, 0xf1, 0x20, 0x46, 0x84, 0xf8, 0xdc, 0x71, + 0xff, 0xf7, 0x95, 0xfc, 0x33, 0x07, 0x48, 0xbf, 0x84, 0xf8, 0xdc, 0x71, + 0xf0, 0x06, 0x03, 0xd5, 0x20, 0x46, 0x00, 0x21, 0xf3, 0xf3, 0xd4, 0xf1, + 0xb1, 0x07, 0x0e, 0xd5, 0xa2, 0x6b, 0x00, 0x23, 0x82, 0xf8, 0x4d, 0x30, + 0xe2, 0x6b, 0x82, 0xf8, 0x4d, 0x30, 0xb4, 0xf8, 0xcb, 0x34, 0x23, 0xf0, + 0x80, 0x03, 0x1b, 0x04, 0x1b, 0x0c, 0xa4, 0xf8, 0xcb, 0x34, 0x72, 0x07, + 0x03, 0xd5, 0x20, 0x46, 0x00, 0x21, 0xf7, 0xf3, 0x21, 0xf5, 0x33, 0x06, + 0x07, 0xd5, 0xb4, 0xf8, 0xcb, 0x34, 0x23, 0xf0, 0x10, 0x03, 0x1b, 0x04, + 0x1b, 0x0c, 0xa4, 0xf8, 0xcb, 0x34, 0x23, 0x68, 0x93, 0xf8, 0x42, 0x30, + 0x9b, 0xb1, 0x16, 0xf0, 0x60, 0x0f, 0x10, 0xd0, 0x06, 0xf0, 0x20, 0x01, + 0x06, 0xf0, 0x40, 0x02, 0x20, 0x46, 0x00, 0x29, 0x14, 0xbf, 0x00, 0x21, + 0x6f, 0xf0, 0x00, 0x01, 0x00, 0x2a, 0x14, 0xbf, 0x00, 0x22, 0x6f, 0xf0, + 0x00, 0x02, 0x00, 0xf0, 0x93, 0xfb, 0x02, 0x23, 0x8d, 0xf8, 0x20, 0x30, + 0x00, 0x23, 0x8d, 0xf8, 0x21, 0x30, 0x8d, 0xf8, 0x22, 0x30, 0x8d, 0xf8, + 0x23, 0x30, 0x8d, 0xf8, 0x24, 0x30, 0x8d, 0xf8, 0x25, 0x30, 0xb4, 0xf8, + 0x82, 0x31, 0x44, 0xf2, 0x1d, 0x32, 0x93, 0x42, 0x1d, 0xd0, 0x0a, 0xd8, + 0x44, 0xf2, 0x16, 0x32, 0x93, 0x42, 0x18, 0xd0, 0x44, 0xf2, 0x1a, 0x32, + 0x93, 0x42, 0x14, 0xd0, 0x44, 0xf2, 0x13, 0x32, 0x0d, 0xe0, 0x44, 0xf2, + 0x2a, 0x32, 0x93, 0x42, 0x0d, 0xd0, 0x02, 0xd8, 0x44, 0xf2, 0x21, 0x32, + 0x05, 0xe0, 0x44, 0xf2, 0x2d, 0x32, 0x93, 0x42, 0x05, 0xd0, 0x44, 0xf2, + 0x52, 0x32, 0x93, 0x42, 0x01, 0xd0, 0x00, 0x26, 0x00, 0xe0, 0x01, 0x26, + 0x06, 0xf1, 0x0e, 0x07, 0x54, 0xf8, 0x27, 0x90, 0x08, 0xa9, 0x20, 0x46, + 0x4a, 0x46, 0x32, 0xf0, 0x03, 0xdc, 0xc9, 0xf8, 0x18, 0x00, 0x54, 0xf8, + 0x27, 0x10, 0x88, 0x69, 0x10, 0xb9, 0x37, 0x23, 0x0a, 0x93, 0x35, 0xe0, + 0x44, 0x30, 0x50, 0x31, 0x28, 0x22, 0xdf, 0xf3, 0xa9, 0xf5, 0x54, 0xf8, + 0x27, 0x30, 0x20, 0x46, 0x9b, 0x69, 0x9e, 0x62, 0xeb, 0x6d, 0x43, 0xf0, + 0x04, 0x03, 0xeb, 0x65, 0x1d, 0x4b, 0xc8, 0xf8, 0x0c, 0x40, 0xc8, 0xf8, + 0x08, 0x30, 0xed, 0xf7, 0x25, 0xfd, 0xba, 0xf1, 0x00, 0x0f, 0x02, 0xd0, + 0x00, 0x23, 0xca, 0xf8, 0x00, 0x30, 0x23, 0x68, 0x17, 0x49, 0x58, 0x69, + 0xe0, 0xf3, 0xba, 0xf2, 0x80, 0xb1, 0x00, 0x21, 0x0a, 0x46, 0xe0, 0xf3, + 0x75, 0xf1, 0x14, 0x4b, 0xc0, 0xb2, 0x18, 0x60, 0x08, 0xe0, 0xba, 0xf1, + 0x00, 0x0f, 0x04, 0xd0, 0x0a, 0x9b, 0x00, 0x24, 0xca, 0xf8, 0x00, 0x30, + 0x00, 0xe0, 0x54, 0x46, 0x20, 0x46, 0x0d, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, + 0x20, 0x46, 0xff, 0xf7, 0x0f, 0xfc, 0xee, 0xe7, 0x39, 0xae, 0x82, 0x00, + 0x01, 0xae, 0x82, 0x00, 0xdc, 0xbc, 0x01, 0x00, 0xd5, 0xa1, 0x81, 0x00, + 0xad, 0xa1, 0x81, 0x00, 0x2d, 0x57, 0x81, 0x00, 0x41, 0x57, 0x81, 0x00, + 0x19, 0x57, 0x81, 0x00, 0xb5, 0x42, 0x82, 0x00, 0x13, 0xbb, 0x01, 0x00, + 0xe0, 0x07, 0x02, 0x00, 0x09, 0x21, 0x20, 0x23, 0x08, 0x22, 0x10, 0xb5, + 0x01, 0x61, 0x10, 0x24, 0x81, 0x61, 0x01, 0x21, 0x03, 0x60, 0x43, 0x60, + 0x42, 0x61, 0x40, 0xf2, 0x3c, 0x73, 0xc1, 0x61, 0x04, 0x62, 0x82, 0x63, + 0x40, 0x24, 0x00, 0x22, 0x41, 0x64, 0x40, 0xf2, 0x9e, 0x31, 0x83, 0x60, + 0x84, 0x62, 0x04, 0x23, 0x0f, 0x24, 0x02, 0x64, 0xc1, 0x64, 0x42, 0x66, + 0x03, 0x21, 0x02, 0x22, 0xc3, 0x60, 0x43, 0x62, 0xc3, 0x62, 0x04, 0x63, + 0x43, 0x63, 0x01, 0x65, 0x42, 0x65, 0x83, 0x65, 0xc1, 0x65, 0x02, 0x66, + 0x10, 0xbd, 0x38, 0xb5, 0x05, 0x46, 0x0c, 0x46, 0x00, 0x29, 0x28, 0xd0, + 0x49, 0x6d, 0x11, 0xb1, 0xc0, 0x22, 0xe4, 0xf3, 0xe7, 0xf3, 0xd4, 0xf8, + 0x8c, 0x10, 0x39, 0xb1, 0x28, 0x46, 0x4f, 0xf4, 0x39, 0x72, 0xe4, 0xf3, + 0xdf, 0xf3, 0x00, 0x23, 0xc4, 0xf8, 0x8c, 0x30, 0xd4, 0xf8, 0x90, 0x10, + 0x31, 0xb1, 0x28, 0x46, 0xc4, 0x22, 0xe4, 0xf3, 0xd5, 0xf3, 0x00, 0x23, + 0xc4, 0xf8, 0x90, 0x30, 0xe1, 0x69, 0x29, 0xb1, 0x28, 0x46, 0x68, 0x22, + 0xe4, 0xf3, 0xcc, 0xf3, 0x00, 0x23, 0xe3, 0x61, 0x28, 0x46, 0x21, 0x46, + 0xb8, 0x22, 0xbd, 0xe8, 0x38, 0x40, 0xe4, 0xf3, 0xc3, 0xb3, 0x38, 0xbd, + 0xf8, 0xb5, 0x16, 0x46, 0xb8, 0x22, 0x05, 0x46, 0x0f, 0x46, 0x09, 0xf0, + 0xa1, 0xdf, 0x04, 0x46, 0x10, 0xb9, 0x40, 0xf2, 0xe9, 0x33, 0x2b, 0xe0, + 0x28, 0x46, 0x39, 0x46, 0x68, 0x22, 0x09, 0xf0, 0x97, 0xdf, 0xe0, 0x61, + 0x10, 0xb9, 0x40, 0xf2, 0x04, 0x43, 0x21, 0xe0, 0xff, 0xf7, 0x90, 0xff, + 0x28, 0x46, 0x39, 0x46, 0xc0, 0x22, 0x09, 0xf0, 0x8b, 0xdf, 0x60, 0x65, + 0x10, 0xb9, 0x40, 0xf2, 0xeb, 0x33, 0x15, 0xe0, 0x28, 0x46, 0x39, 0x46, + 0x4f, 0xf4, 0x39, 0x72, 0x09, 0xf0, 0x80, 0xdf, 0xc4, 0xf8, 0x8c, 0x00, + 0x10, 0xb9, 0x4f, 0xf4, 0x7b, 0x73, 0x09, 0xe0, 0x28, 0x46, 0x39, 0x46, + 0xc4, 0x22, 0x09, 0xf0, 0x75, 0xdf, 0xc4, 0xf8, 0x90, 0x00, 0x38, 0xb9, + 0x40, 0xf2, 0xed, 0x33, 0x21, 0x46, 0x33, 0x60, 0x28, 0x46, 0xff, 0xf7, + 0x94, 0xff, 0x00, 0x24, 0x20, 0x46, 0xf8, 0xbd, 0x38, 0xb5, 0x0d, 0x46, + 0x04, 0x46, 0x00, 0x28, 0x00, 0xf0, 0xe7, 0x80, 0xd0, 0xf8, 0x18, 0x15, + 0x39, 0xb1, 0x28, 0x46, 0x4f, 0xf4, 0x84, 0x72, 0xe4, 0xf3, 0x74, 0xf3, + 0x00, 0x23, 0xc4, 0xf8, 0x18, 0x35, 0xd4, 0xf8, 0x20, 0x15, 0x39, 0xb1, + 0x28, 0x46, 0x4f, 0xf4, 0x84, 0x72, 0xe4, 0xf3, 0x69, 0xf3, 0x00, 0x23, + 0xc4, 0xf8, 0x20, 0x35, 0xd4, 0xf8, 0xb4, 0x14, 0x39, 0xb1, 0x28, 0x46, + 0x40, 0xf2, 0xac, 0x42, 0xe4, 0xf3, 0x5e, 0xf3, 0x00, 0x23, 0xc4, 0xf8, + 0xb4, 0x34, 0xd4, 0xf8, 0x40, 0x15, 0x31, 0xb1, 0x28, 0x46, 0xac, 0x22, + 0xe4, 0xf3, 0x54, 0xf3, 0x00, 0x23, 0xc4, 0xf8, 0x40, 0x35, 0xd4, 0xf8, + 0x6c, 0x12, 0x29, 0xb1, 0x28, 0x46, 0x09, 0xf0, 0x93, 0xde, 0x00, 0x23, + 0xc4, 0xf8, 0x6c, 0x32, 0xd4, 0xf8, 0xfc, 0x14, 0x31, 0xb1, 0x28, 0x46, + 0x40, 0x22, 0xe4, 0xf3, 0x41, 0xf3, 0x00, 0x23, 0xc4, 0xf8, 0xfc, 0x34, + 0xd4, 0xf8, 0x84, 0x16, 0x69, 0xb1, 0x23, 0x68, 0x5b, 0xb1, 0xdb, 0x69, + 0x4b, 0xb1, 0x9b, 0x69, 0x0c, 0x22, 0x01, 0x33, 0x5a, 0x43, 0x28, 0x46, + 0xe4, 0xf3, 0x30, 0xf3, 0x00, 0x23, 0xc4, 0xf8, 0x84, 0x36, 0xd4, 0xf8, + 0xbc, 0x14, 0x19, 0xb1, 0x28, 0x46, 0xb4, 0x22, 0xe4, 0xf3, 0x26, 0xf3, + 0xd4, 0xf8, 0x90, 0x14, 0x21, 0xb1, 0x28, 0x46, 0x4f, 0xf4, 0xae, 0x62, + 0xe4, 0xf3, 0x1e, 0xf3, 0xd4, 0xf8, 0x58, 0x16, 0x31, 0xb1, 0x28, 0x46, + 0x38, 0x22, 0xe4, 0xf3, 0x17, 0xf3, 0x00, 0x23, 0xc4, 0xf8, 0x58, 0x36, + 0xd4, 0xf8, 0x60, 0x16, 0x39, 0xb1, 0x28, 0x46, 0x4f, 0xf4, 0x90, 0x72, + 0xe4, 0xf3, 0x0c, 0xf3, 0x00, 0x23, 0xc4, 0xf8, 0x60, 0x36, 0xd4, 0xf8, + 0xf8, 0x17, 0x31, 0xb1, 0x28, 0x46, 0x10, 0x22, 0xe4, 0xf3, 0x02, 0xf3, + 0x00, 0x23, 0xc4, 0xf8, 0xf8, 0x37, 0xd4, 0xf8, 0xd8, 0x16, 0x39, 0xb1, + 0x28, 0x46, 0x4f, 0xf4, 0x84, 0x72, 0xe4, 0xf3, 0xf7, 0xf2, 0x00, 0x23, + 0xc4, 0xf8, 0xd8, 0x36, 0xd4, 0xf8, 0xe0, 0x16, 0x31, 0xb1, 0x28, 0x46, + 0x24, 0x22, 0xe4, 0xf3, 0xed, 0xf2, 0x00, 0x23, 0xc4, 0xf8, 0xe0, 0x36, + 0xd4, 0xf8, 0xec, 0x16, 0x31, 0xb1, 0x28, 0x46, 0x68, 0x22, 0xe4, 0xf3, + 0xe3, 0xf2, 0x00, 0x23, 0xc4, 0xf8, 0xec, 0x36, 0xd4, 0xf8, 0x44, 0x17, + 0x31, 0xb1, 0x28, 0x46, 0xec, 0x22, 0xe4, 0xf3, 0xd9, 0xf2, 0x00, 0x23, + 0xc4, 0xf8, 0x44, 0x37, 0xa1, 0x6b, 0x21, 0xb1, 0x28, 0x46, 0x4f, 0xf4, + 0x06, 0x72, 0xe4, 0xf3, 0xcf, 0xf2, 0x63, 0x6b, 0x7b, 0xb1, 0x99, 0x6a, + 0x31, 0xb1, 0x80, 0x22, 0x28, 0x46, 0xe4, 0xf3, 0xc7, 0xf2, 0x63, 0x6b, + 0x00, 0x22, 0x9a, 0x62, 0x28, 0x46, 0x61, 0x6b, 0x2c, 0x22, 0xe4, 0xf3, + 0xbf, 0xf2, 0x00, 0x23, 0x63, 0x63, 0x21, 0x68, 0x21, 0xb1, 0x28, 0x46, + 0xff, 0xf7, 0xc7, 0xfe, 0x00, 0x23, 0x23, 0x60, 0x23, 0x69, 0xb3, 0xb1, + 0xd3, 0xf8, 0xf8, 0x10, 0x18, 0x22, 0x28, 0x46, 0xe4, 0xf3, 0xae, 0xf2, + 0x23, 0x69, 0x00, 0x22, 0xd9, 0x6f, 0xc3, 0xf8, 0xf8, 0x20, 0x19, 0xb1, + 0x28, 0x46, 0x58, 0x22, 0xe4, 0xf3, 0xa4, 0xf2, 0x28, 0x46, 0x21, 0x69, + 0xfc, 0x22, 0xe4, 0xf3, 0x9f, 0xf2, 0x00, 0x23, 0x23, 0x61, 0x28, 0x46, + 0x21, 0x46, 0x40, 0xf6, 0xd4, 0x02, 0xbd, 0xe8, 0x38, 0x40, 0xe4, 0xf3, + 0x95, 0xb2, 0x38, 0xbd, 0x2d, 0xe9, 0xf0, 0x41, 0x16, 0x46, 0x40, 0xf6, + 0xd4, 0x02, 0x05, 0x46, 0x0f, 0x46, 0x09, 0xf0, 0x71, 0xde, 0x04, 0x46, + 0x00, 0x28, 0x3d, 0xd0, 0x26, 0x23, 0xc0, 0xf8, 0x28, 0x38, 0x39, 0x46, + 0x28, 0x46, 0x32, 0x46, 0xff, 0xf7, 0xbe, 0xfe, 0x20, 0x60, 0x00, 0x28, + 0x00, 0xf0, 0x1a, 0x81, 0x90, 0x4b, 0x04, 0x60, 0x1b, 0x68, 0x39, 0x46, + 0xc0, 0xf8, 0x9c, 0x30, 0xfc, 0x22, 0x28, 0x46, 0x09, 0xf0, 0x58, 0xde, + 0x80, 0x46, 0x20, 0x61, 0x10, 0xb9, 0x40, 0xf2, 0xed, 0x33, 0x08, 0xe1, + 0x84, 0x60, 0x39, 0x46, 0x28, 0x46, 0x18, 0x22, 0x09, 0xf0, 0x4c, 0xde, + 0xc8, 0xf8, 0xf8, 0x00, 0xc0, 0xb1, 0x28, 0x46, 0x39, 0x46, 0x58, 0x22, + 0xd4, 0xf8, 0x10, 0x80, 0x09, 0xf0, 0x42, 0xde, 0xc8, 0xf8, 0x7c, 0x00, + 0x70, 0xb1, 0x23, 0x69, 0x28, 0x46, 0xda, 0x6f, 0x39, 0x46, 0x2c, 0x32, + 0xc3, 0xf8, 0x80, 0x20, 0x4f, 0xf4, 0x84, 0x72, 0x09, 0xf0, 0x34, 0xde, + 0xc4, 0xf8, 0x18, 0x05, 0x30, 0xb9, 0x02, 0xe0, 0x40, 0xf2, 0xee, 0x33, + 0xe3, 0xe0, 0x40, 0xf2, 0xef, 0x33, 0xe0, 0xe0, 0x28, 0x46, 0x39, 0x46, + 0x4f, 0xf4, 0x84, 0x72, 0x09, 0xf0, 0x24, 0xde, 0xc4, 0xf8, 0x20, 0x05, + 0x10, 0xb9, 0x4f, 0xf4, 0x7c, 0x73, 0xd4, 0xe0, 0x28, 0x46, 0x39, 0x46, + 0x40, 0xf2, 0xac, 0x42, 0x09, 0xf0, 0x18, 0xde, 0xc4, 0xf8, 0xb4, 0x04, + 0x10, 0xb9, 0x40, 0xf2, 0xf1, 0x33, 0xc8, 0xe0, 0x28, 0x46, 0x39, 0x46, + 0xac, 0x22, 0x09, 0xf0, 0x0d, 0xde, 0xc4, 0xf8, 0x40, 0x05, 0x10, 0xb9, + 0x40, 0xf2, 0xf2, 0x33, 0xbd, 0xe0, 0x39, 0x46, 0x28, 0x46, 0xec, 0xf7, + 0x03, 0xff, 0x01, 0x46, 0xc4, 0xf8, 0x6c, 0x02, 0x10, 0xb9, 0x40, 0xf2, + 0xf3, 0x33, 0xb2, 0xe0, 0x20, 0x46, 0x1c, 0xf0, 0x49, 0xd9, 0x28, 0x46, + 0x39, 0x46, 0x40, 0x22, 0x09, 0xf0, 0xf4, 0xdd, 0xc4, 0xf8, 0xfc, 0x04, + 0x10, 0xb9, 0x4f, 0xf4, 0x7d, 0x73, 0xa4, 0xe0, 0x23, 0x68, 0x0c, 0x22, + 0xdb, 0x69, 0x28, 0x46, 0x9b, 0x69, 0x39, 0x46, 0x01, 0x33, 0x5a, 0x43, + 0x09, 0xf0, 0xe4, 0xdd, 0xc4, 0xf8, 0x84, 0x06, 0x10, 0xb9, 0x40, 0xf2, + 0xf5, 0x33, 0x94, 0xe0, 0x28, 0x46, 0x39, 0x46, 0xb4, 0x22, 0x09, 0xf0, + 0xd9, 0xdd, 0xc4, 0xf8, 0xbc, 0x04, 0x10, 0xb9, 0x40, 0xf2, 0xf6, 0x33, + 0x89, 0xe0, 0x28, 0x46, 0x39, 0x46, 0x4f, 0xf4, 0xae, 0x62, 0x09, 0xf0, + 0xcd, 0xdd, 0xc4, 0xf8, 0x90, 0x04, 0xa8, 0xb1, 0x00, 0xf5, 0xae, 0x73, + 0xc4, 0xf8, 0x94, 0x34, 0x00, 0xf5, 0x2e, 0x73, 0x00, 0xf5, 0x82, 0x60, + 0x04, 0x30, 0xc4, 0xf8, 0x9c, 0x04, 0xc4, 0xf8, 0x98, 0x34, 0x28, 0x46, + 0x39, 0x46, 0x38, 0x22, 0x09, 0xf0, 0xb8, 0xdd, 0xc4, 0xf8, 0x58, 0x06, + 0x30, 0xb9, 0x02, 0xe0, 0x40, 0xf2, 0xf7, 0x33, 0x67, 0xe0, 0x4f, 0xf4, + 0x7e, 0x73, 0x64, 0xe0, 0x28, 0x46, 0x39, 0x46, 0x4f, 0xf4, 0x90, 0x72, + 0x09, 0xf0, 0xa8, 0xdd, 0xc4, 0xf8, 0x60, 0x06, 0x38, 0xb1, 0x28, 0x46, + 0x39, 0x46, 0x10, 0x22, 0x09, 0xf0, 0xa0, 0xdd, 0xc4, 0xf8, 0xf8, 0x07, + 0x10, 0xb9, 0x40, 0xf2, 0xf9, 0x33, 0x50, 0xe0, 0x28, 0x46, 0x39, 0x46, + 0x4f, 0xf4, 0x84, 0x72, 0x09, 0xf0, 0x94, 0xdd, 0xc4, 0xf8, 0xd8, 0x06, + 0x10, 0xb9, 0x40, 0xf2, 0xfa, 0x33, 0x44, 0xe0, 0x28, 0x46, 0x39, 0x46, + 0x24, 0x22, 0x09, 0xf0, 0x89, 0xdd, 0xc4, 0xf8, 0xe0, 0x06, 0x10, 0xb9, + 0x40, 0xf2, 0xfd, 0x33, 0x39, 0xe0, 0x28, 0x46, 0x39, 0x46, 0x68, 0x22, + 0x09, 0xf0, 0x7e, 0xdd, 0xc4, 0xf8, 0xec, 0x06, 0x10, 0xb9, 0x40, 0xf2, + 0xfe, 0x33, 0x2e, 0xe0, 0x28, 0x46, 0x39, 0x46, 0xec, 0x22, 0x09, 0xf0, + 0x73, 0xdd, 0xc4, 0xf8, 0x44, 0x07, 0x10, 0xb9, 0x40, 0xf2, 0xff, 0x33, + 0x23, 0xe0, 0x28, 0x46, 0x39, 0x46, 0x4f, 0xf4, 0x06, 0x72, 0x09, 0xf0, + 0x67, 0xdd, 0xa0, 0x63, 0x58, 0xb1, 0x00, 0xf5, 0x86, 0x70, 0xe0, 0x63, + 0x39, 0x46, 0x28, 0x46, 0x2c, 0x22, 0x09, 0xf0, 0x5d, 0xdd, 0x80, 0x46, + 0x60, 0x63, 0x30, 0xb9, 0x02, 0xe0, 0x40, 0xf2, 0x01, 0x43, 0x0c, 0xe0, + 0x40, 0xf2, 0x02, 0x43, 0x09, 0xe0, 0x28, 0x46, 0x39, 0x46, 0x80, 0x22, + 0x09, 0xf0, 0x4e, 0xdd, 0xc8, 0xf8, 0x28, 0x00, 0x38, 0xb9, 0x40, 0xf2, + 0x03, 0x43, 0x33, 0x60, 0x20, 0x46, 0x29, 0x46, 0xff, 0xf7, 0xdc, 0xfd, + 0x00, 0x24, 0x20, 0x46, 0xbd, 0xe8, 0xf0, 0x81, 0xbc, 0x26, 0x00, 0x00, + 0x70, 0xb5, 0x04, 0x46, 0x00, 0x28, 0x34, 0xd0, 0x05, 0x46, 0x00, 0xf1, + 0x28, 0x06, 0xd5, 0xf8, 0x50, 0x12, 0x21, 0xb1, 0x23, 0x68, 0xf4, 0x22, + 0x58, 0x68, 0xe4, 0xf3, 0x49, 0xf1, 0x04, 0x35, 0xb5, 0x42, 0xf4, 0xd1, + 0xa1, 0x6b, 0x69, 0xb1, 0x94, 0xf8, 0xa3, 0x33, 0x1b, 0xb1, 0x23, 0x68, + 0x98, 0x68, 0xec, 0xf3, 0xf3, 0xf5, 0x23, 0x68, 0xa1, 0x6b, 0x98, 0x68, + 0xec, 0xf3, 0x00, 0xf6, 0x00, 0x23, 0xa3, 0x63, 0xd4, 0xf8, 0x78, 0x12, + 0x21, 0xb1, 0x23, 0x68, 0xe8, 0x22, 0x58, 0x68, 0xe4, 0xf3, 0x2e, 0xf1, + 0x23, 0x68, 0x22, 0x46, 0x18, 0x68, 0x06, 0x49, 0x01, 0xf0, 0x54, 0xda, + 0x23, 0x68, 0x21, 0x46, 0x58, 0x68, 0x4f, 0xf4, 0x6a, 0x72, 0xbd, 0xe8, + 0x70, 0x40, 0xe4, 0xf3, 0x1f, 0xb1, 0x70, 0xbd, 0x67, 0x89, 0x86, 0x00, + 0xd0, 0xf8, 0x40, 0x31, 0x48, 0x1c, 0x18, 0xbf, 0x83, 0xf8, 0x9c, 0x13, + 0x50, 0x1c, 0x83, 0xf8, 0x9e, 0x13, 0x83, 0xf8, 0x9f, 0x23, 0x18, 0xbf, + 0x83, 0xf8, 0x9d, 0x23, 0x70, 0x47, 0x00, 0x00, 0xf0, 0xb5, 0x4f, 0xf4, + 0x6a, 0x71, 0x85, 0xb0, 0x05, 0x46, 0x40, 0x68, 0xe4, 0xf3, 0xf4, 0xf0, + 0x04, 0x46, 0x00, 0x28, 0x00, 0xf0, 0xc6, 0x80, 0x00, 0x21, 0x4f, 0xf4, + 0x6a, 0x72, 0xdf, 0xf3, 0xa3, 0xf2, 0x25, 0x60, 0x68, 0x68, 0xe8, 0x21, + 0xe4, 0xf3, 0xe6, 0xf0, 0xc4, 0xf8, 0x78, 0x02, 0x00, 0x28, 0x00, 0xf0, + 0xa9, 0x80, 0x00, 0x21, 0xe8, 0x22, 0xdf, 0xf3, 0x95, 0xf2, 0x20, 0x20, + 0x84, 0xf8, 0xa2, 0x03, 0x08, 0x21, 0x4f, 0xf4, 0x7a, 0x70, 0xe1, 0x74, + 0x21, 0x75, 0x60, 0x86, 0x06, 0x21, 0xc8, 0x20, 0x01, 0x23, 0x00, 0x22, + 0x84, 0xf8, 0x27, 0x10, 0xa0, 0x86, 0xff, 0x21, 0x05, 0x26, 0x02, 0x20, + 0x27, 0x68, 0xa3, 0x72, 0x63, 0x73, 0xa3, 0x73, 0xe3, 0x73, 0x84, 0xf8, + 0x94, 0x33, 0x84, 0xf8, 0x95, 0x33, 0x84, 0xf8, 0x96, 0x33, 0x84, 0xf8, + 0x97, 0x33, 0x84, 0xf8, 0x98, 0x33, 0x84, 0xf8, 0x99, 0x33, 0x84, 0xf8, + 0x9a, 0x33, 0x84, 0xf8, 0x9b, 0x33, 0xa3, 0x74, 0x84, 0xf8, 0x28, 0x10, + 0x22, 0x74, 0x62, 0x74, 0x22, 0x73, 0xe2, 0x72, 0x84, 0xf8, 0x29, 0x60, + 0x84, 0xf8, 0x2a, 0x20, 0x84, 0xf8, 0x2b, 0x00, 0x3f, 0x68, 0x97, 0xf8, + 0xa1, 0x70, 0x84, 0xf8, 0x9e, 0x13, 0x9f, 0x42, 0x0c, 0xbf, 0x1f, 0x46, + 0x03, 0x27, 0x84, 0xf8, 0x9f, 0x13, 0x4f, 0xf4, 0x00, 0x61, 0x84, 0xf8, + 0x2c, 0x70, 0xe1, 0x63, 0x84, 0xf8, 0x2d, 0x30, 0x66, 0x75, 0xa0, 0x75, + 0x23, 0x46, 0x05, 0x21, 0x02, 0x20, 0x01, 0x32, 0xd9, 0x75, 0xd8, 0x77, + 0x01, 0x33, 0x08, 0x2a, 0xf7, 0xd1, 0x00, 0x27, 0x01, 0x26, 0x20, 0x46, + 0x84, 0xf8, 0x2e, 0x70, 0x84, 0xf8, 0x2f, 0x60, 0x09, 0xf0, 0x5c, 0xdf, + 0x20, 0x46, 0x85, 0xf8, 0xc3, 0x64, 0x0b, 0xf0, 0x77, 0xdd, 0x04, 0x21, + 0x28, 0x46, 0x2a, 0x4a, 0x2a, 0x4b, 0x00, 0x97, 0x01, 0x94, 0x05, 0xf0, + 0x23, 0xff, 0xb8, 0x42, 0x60, 0x60, 0x39, 0xdb, 0x27, 0x4b, 0x28, 0x68, + 0x00, 0x93, 0x27, 0x4b, 0x27, 0x49, 0x01, 0x93, 0x27, 0x4b, 0x28, 0x4a, + 0x03, 0x93, 0x23, 0x46, 0x02, 0x97, 0x01, 0xf0, 0x69, 0xd9, 0x07, 0x46, + 0x50, 0xbb, 0xa8, 0x68, 0x24, 0x49, 0x22, 0x46, 0x3b, 0x46, 0xec, 0xf3, + 0x51, 0xf5, 0xa0, 0x63, 0x10, 0xb3, 0x22, 0x4b, 0x84, 0xf8, 0x7c, 0x62, + 0x1a, 0x1d, 0x07, 0xca, 0x1b, 0x68, 0x8d, 0xe8, 0x07, 0x00, 0x22, 0x46, + 0x28, 0x46, 0x06, 0x21, 0x08, 0xf0, 0x1c, 0xd8, 0xff, 0x23, 0x84, 0xf8, + 0xa1, 0x33, 0x2b, 0x68, 0x20, 0x46, 0x93, 0xf8, 0x42, 0x10, 0x0c, 0xf0, + 0x9f, 0xdd, 0xc8, 0x23, 0xc4, 0xf8, 0xe0, 0x32, 0x20, 0x46, 0x0b, 0xf0, + 0x7f, 0xdf, 0x20, 0x46, 0x31, 0x46, 0xed, 0xf7, 0xee, 0xf8, 0x84, 0xf8, + 0xa3, 0x73, 0x0d, 0xe0, 0xd4, 0xf8, 0x78, 0x12, 0x19, 0xb1, 0x68, 0x68, + 0xe8, 0x22, 0xe4, 0xf3, 0x41, 0xf0, 0x21, 0x46, 0x68, 0x68, 0x4f, 0xf4, + 0x6a, 0x72, 0xe4, 0xf3, 0x3b, 0xf0, 0x00, 0x24, 0x20, 0x46, 0x05, 0xb0, + 0xf0, 0xbd, 0x00, 0xbf, 0x95, 0xcb, 0x82, 0x00, 0x1d, 0xcb, 0x82, 0x00, + 0x45, 0xcf, 0x82, 0x00, 0xf1, 0x8c, 0x00, 0x00, 0xa0, 0xe0, 0x85, 0x00, + 0x79, 0xd9, 0x82, 0x00, 0x67, 0x89, 0x86, 0x00, 0xad, 0x8b, 0x00, 0x00, + 0xec, 0xbc, 0x01, 0x00, 0x70, 0xb5, 0x0a, 0x4b, 0x86, 0xb0, 0x0d, 0x46, + 0x6c, 0x46, 0x03, 0xf1, 0x18, 0x06, 0x18, 0x68, 0x59, 0x68, 0x22, 0x46, + 0x03, 0xc2, 0x08, 0x33, 0xb3, 0x42, 0x14, 0x46, 0xf7, 0xd1, 0x28, 0x46, + 0x69, 0x46, 0x18, 0x22, 0xdf, 0xf3, 0x54, 0xf1, 0x06, 0xb0, 0x70, 0xbd, + 0xf5, 0xb6, 0x01, 0x00, 0x70, 0xb5, 0xd0, 0xf8, 0xac, 0x63, 0x04, 0x46, + 0xd0, 0xf8, 0xb0, 0x53, 0x30, 0x46, 0x00, 0xf0, 0x7b, 0xf8, 0xd4, 0xf8, + 0xd0, 0x13, 0xb0, 0x68, 0xec, 0xf3, 0xb4, 0xf4, 0xb0, 0x68, 0xd4, 0xf8, + 0xd0, 0x13, 0xec, 0xf3, 0xc1, 0xf4, 0x00, 0x23, 0x22, 0x46, 0xc4, 0xf8, + 0xd0, 0x33, 0x28, 0x46, 0x05, 0x49, 0x01, 0xf0, 0x1d, 0xd9, 0xe8, 0x68, + 0x21, 0x46, 0x4f, 0xf4, 0x7e, 0x72, 0xbd, 0xe8, 0x70, 0x40, 0xe3, 0xf3, + 0xe9, 0xb7, 0x00, 0xbf, 0xab, 0x99, 0x86, 0x00, 0x2d, 0xe9, 0xff, 0x41, + 0x3c, 0x23, 0xc1, 0xf8, 0x24, 0x37, 0x05, 0x23, 0xc1, 0xf8, 0x28, 0x37, + 0x05, 0x46, 0x0f, 0x46, 0xc0, 0x68, 0x4f, 0xf4, 0x7e, 0x71, 0xe3, 0xf3, + 0xc7, 0xf7, 0x04, 0x46, 0x00, 0x28, 0x3d, 0xd0, 0x00, 0x21, 0x4f, 0xf4, + 0x7e, 0x72, 0x4f, 0xf0, 0x00, 0x08, 0xdf, 0xf3, 0x75, 0xf1, 0xc4, 0xf8, + 0xac, 0x73, 0xc4, 0xf8, 0xb0, 0x53, 0x84, 0xf8, 0x01, 0x80, 0x20, 0x46, + 0xe6, 0xf7, 0x40, 0xfc, 0xc4, 0xf8, 0xc0, 0x03, 0x38, 0x46, 0x00, 0xf0, + 0x4d, 0xf8, 0x06, 0x46, 0x38, 0xb1, 0x21, 0x46, 0xe8, 0x68, 0x4f, 0xf4, + 0x7e, 0x72, 0xe3, 0xf3, 0xb7, 0xf7, 0x44, 0x46, 0x1e, 0xe0, 0x20, 0x46, + 0x04, 0xf5, 0x63, 0x71, 0xff, 0xf7, 0x8c, 0xff, 0xb8, 0x68, 0x0e, 0x49, + 0x22, 0x46, 0x33, 0x46, 0xec, 0xf3, 0x8e, 0xf4, 0xc4, 0xf8, 0xd0, 0x03, + 0x78, 0xb1, 0x20, 0x46, 0x0f, 0xf0, 0x12, 0xdd, 0x09, 0x4b, 0x28, 0x46, + 0x00, 0x93, 0x09, 0x4b, 0x09, 0x49, 0x01, 0x93, 0x09, 0x4a, 0x23, 0x46, + 0x02, 0x96, 0x03, 0x96, 0x01, 0xf0, 0x8c, 0xd8, 0x00, 0xe0, 0x04, 0x46, + 0x20, 0x46, 0x04, 0xb0, 0xbd, 0xe8, 0xf0, 0x81, 0x8d, 0x25, 0x83, 0x00, + 0x9d, 0x11, 0x83, 0x00, 0xeb, 0x05, 0x01, 0x00, 0xcc, 0xbd, 0x01, 0x00, + 0xab, 0x99, 0x86, 0x00, 0x38, 0xb5, 0xd0, 0xf8, 0x30, 0x57, 0x04, 0x46, + 0x6d, 0xb1, 0x07, 0x49, 0x22, 0x46, 0x00, 0x68, 0x01, 0xf0, 0xaa, 0xd8, + 0x60, 0x68, 0x29, 0x46, 0x4f, 0xf4, 0x0a, 0x62, 0xe3, 0xf3, 0x78, 0xf7, + 0x00, 0x23, 0xc4, 0xf8, 0x30, 0x37, 0x38, 0xbd, 0x52, 0x9e, 0x86, 0x00, + 0xf0, 0xb5, 0x4f, 0xf4, 0x0a, 0x61, 0x85, 0xb0, 0x04, 0x46, 0x40, 0x68, + 0xe3, 0xf3, 0x5a, 0xf7, 0x05, 0x46, 0x20, 0xb9, 0xc4, 0xf8, 0x30, 0x07, + 0x4f, 0xf0, 0xff, 0x30, 0xd4, 0xe0, 0x00, 0x21, 0x4f, 0xf4, 0x0a, 0x62, + 0xdf, 0xf3, 0x06, 0xf1, 0x22, 0x68, 0x05, 0xf1, 0x20, 0x03, 0x2b, 0x60, + 0x00, 0x26, 0x08, 0x23, 0x6b, 0x61, 0x2e, 0x61, 0xdc, 0x21, 0x13, 0x66, + 0x20, 0x46, 0x63, 0x4a, 0x63, 0x4b, 0x00, 0x96, 0x01, 0x94, 0x05, 0xf0, + 0xeb, 0xfd, 0xb0, 0x42, 0xa8, 0x61, 0x05, 0xda, 0x20, 0x46, 0xff, 0xf7, + 0xbf, 0xff, 0x6f, 0xf0, 0x01, 0x00, 0xb5, 0xe0, 0x5d, 0x4b, 0x00, 0x22, + 0x43, 0xf8, 0x04, 0x2b, 0xf2, 0x07, 0x1f, 0xd5, 0x5b, 0x49, 0x01, 0x27, + 0x0a, 0x78, 0x0d, 0x2a, 0x07, 0xfa, 0x02, 0xfe, 0x03, 0xdc, 0xd2, 0x19, + 0x17, 0xfa, 0x02, 0xf0, 0x01, 0xe0, 0x4f, 0xf4, 0x00, 0x40, 0xca, 0x78, + 0x01, 0x21, 0x11, 0xfa, 0x02, 0xf7, 0x0d, 0x2a, 0x47, 0xea, 0x0e, 0x07, + 0x47, 0xea, 0x00, 0x00, 0x03, 0xdc, 0x52, 0x18, 0x11, 0xfa, 0x02, 0xf2, + 0x01, 0xe0, 0x4f, 0xf4, 0x00, 0x42, 0x02, 0x43, 0x43, 0xf8, 0x04, 0x2c, + 0xb0, 0x07, 0x23, 0xd5, 0x4a, 0x49, 0x01, 0x27, 0x4a, 0x78, 0x53, 0xf8, + 0x04, 0xec, 0x0d, 0x2a, 0x07, 0xfa, 0x02, 0xfc, 0x03, 0xdc, 0xd2, 0x19, + 0x17, 0xfa, 0x02, 0xf0, 0x01, 0xe0, 0x4f, 0xf4, 0x00, 0x40, 0x8a, 0x78, + 0x01, 0x21, 0x11, 0xfa, 0x02, 0xf7, 0x0d, 0x2a, 0x47, 0xea, 0x0c, 0x07, + 0x47, 0xea, 0x00, 0x00, 0x03, 0xdc, 0x52, 0x18, 0x11, 0xfa, 0x02, 0xf2, + 0x01, 0xe0, 0x4f, 0xf4, 0x00, 0x42, 0x02, 0x43, 0x42, 0xea, 0x0e, 0x02, + 0x43, 0xf8, 0x04, 0x2c, 0x71, 0x07, 0x23, 0xd5, 0x37, 0x49, 0x01, 0x27, + 0x0a, 0x79, 0x53, 0xf8, 0x04, 0xec, 0x0d, 0x2a, 0x07, 0xfa, 0x02, 0xfc, + 0x03, 0xdc, 0xd2, 0x19, 0x17, 0xfa, 0x02, 0xf0, 0x01, 0xe0, 0x4f, 0xf4, + 0x00, 0x40, 0x4a, 0x79, 0x01, 0x21, 0x11, 0xfa, 0x02, 0xf7, 0x0d, 0x2a, + 0x47, 0xea, 0x0c, 0x07, 0x47, 0xea, 0x00, 0x00, 0x03, 0xdc, 0x52, 0x18, + 0x11, 0xfa, 0x02, 0xf2, 0x01, 0xe0, 0x4f, 0xf4, 0x00, 0x42, 0x02, 0x43, + 0x42, 0xea, 0x0e, 0x02, 0x43, 0xf8, 0x04, 0x2c, 0x32, 0x07, 0x23, 0xd5, + 0x24, 0x49, 0x01, 0x27, 0x8a, 0x79, 0x53, 0xf8, 0x04, 0xec, 0x0d, 0x2a, + 0x07, 0xfa, 0x02, 0xfc, 0x03, 0xdc, 0xd2, 0x19, 0x17, 0xfa, 0x02, 0xf0, + 0x01, 0xe0, 0x4f, 0xf4, 0x00, 0x40, 0xca, 0x79, 0x01, 0x21, 0x11, 0xfa, + 0x02, 0xf7, 0x0d, 0x2a, 0x47, 0xea, 0x0c, 0x07, 0x47, 0xea, 0x00, 0x00, + 0x03, 0xdc, 0x52, 0x18, 0x11, 0xfa, 0x02, 0xf2, 0x01, 0xe0, 0x4f, 0xf4, + 0x00, 0x42, 0x02, 0x43, 0x42, 0xea, 0x0e, 0x02, 0x43, 0xf8, 0x04, 0x2c, + 0x01, 0x36, 0x10, 0x2e, 0x7f, 0xf4, 0x65, 0xaf, 0x11, 0x4b, 0x00, 0x26, + 0x03, 0x93, 0x31, 0x46, 0x10, 0x4a, 0x23, 0x46, 0x20, 0x68, 0x00, 0x96, + 0x01, 0x96, 0x02, 0x96, 0x00, 0xf0, 0x90, 0xdf, 0x0d, 0x4b, 0x1a, 0x1d, + 0x07, 0xca, 0x1b, 0x68, 0x8d, 0xe8, 0x07, 0x00, 0x20, 0x46, 0x03, 0x21, + 0x22, 0x46, 0x07, 0xf0, 0x4f, 0xde, 0xc4, 0xf8, 0x30, 0x57, 0x30, 0x46, + 0x05, 0xb0, 0xf0, 0xbd, 0x01, 0x57, 0x83, 0x00, 0xa1, 0x56, 0x83, 0x00, + 0x84, 0x27, 0x00, 0x00, 0x90, 0xe0, 0x85, 0x00, 0x9d, 0x50, 0x83, 0x00, + 0x52, 0x9e, 0x86, 0x00, 0x1c, 0xbf, 0x01, 0x00, 0x30, 0xb5, 0x8c, 0x89, + 0x42, 0xf2, 0x56, 0x05, 0xac, 0x42, 0x08, 0xd8, 0x42, 0xf2, 0x55, 0x05, + 0xac, 0x42, 0x23, 0xd2, 0x42, 0xf2, 0x50, 0x05, 0xac, 0x42, 0x2f, 0xd1, + 0x08, 0xe0, 0x42, 0xf2, 0x60, 0x01, 0x8c, 0x42, 0x1f, 0xd0, 0x4e, 0xf2, + 0xf5, 0x41, 0x8c, 0x42, 0x26, 0xd1, 0x1f, 0xe0, 0xc9, 0x89, 0x01, 0x29, + 0x04, 0xd1, 0x6f, 0xf0, 0x3b, 0x01, 0x11, 0x60, 0x0f, 0x21, 0x03, 0xe0, + 0x6f, 0xf0, 0x45, 0x01, 0x11, 0x60, 0x14, 0x21, 0x19, 0x60, 0x03, 0x68, + 0xd3, 0xf8, 0x80, 0x30, 0xdb, 0x04, 0x18, 0xd5, 0x13, 0x68, 0x02, 0x3b, + 0x13, 0x60, 0x30, 0xbd, 0x6f, 0xf0, 0x4a, 0x01, 0x11, 0x60, 0x14, 0x22, + 0x08, 0xe0, 0x6f, 0xf0, 0x4a, 0x01, 0x11, 0x60, 0x0f, 0x22, 0x03, 0xe0, + 0x6f, 0xf0, 0x95, 0x01, 0x11, 0x60, 0x96, 0x22, 0x1a, 0x60, 0x30, 0xbd, + 0x6f, 0xf0, 0x4a, 0x01, 0x11, 0x60, 0x14, 0x22, 0x1a, 0x60, 0x30, 0xbd, + 0x38, 0xb5, 0x04, 0x46, 0x06, 0x25, 0xe0, 0x68, 0x20, 0xb1, 0x04, 0x4b, + 0x1b, 0x68, 0x98, 0x47, 0x00, 0x23, 0xe3, 0x60, 0x04, 0x34, 0x01, 0x3d, + 0xf5, 0xd1, 0x38, 0xbd, 0xe0, 0xa6, 0x85, 0x00, 0x43, 0x6c, 0x1f, 0x2b, + 0x05, 0xd8, 0x4f, 0xf0, 0x00, 0x70, 0x18, 0x41, 0x00, 0xf0, 0x01, 0x00, + 0x70, 0x47, 0x00, 0x20, 0x70, 0x47, 0x01, 0x6e, 0xb0, 0xf8, 0x4a, 0x30, + 0x10, 0xb5, 0x8a, 0x6a, 0xb3, 0xb1, 0xff, 0x2b, 0x16, 0xd9, 0x18, 0x0b, + 0x01, 0x38, 0x01, 0x28, 0x14, 0xd8, 0x03, 0xf4, 0x70, 0x60, 0x00, 0x0a, + 0x09, 0x28, 0x0f, 0xd8, 0x78, 0xb1, 0x03, 0xf0, 0xf0, 0x00, 0x90, 0x28, + 0x0a, 0xd8, 0x03, 0xf0, 0x0f, 0x00, 0x09, 0x28, 0x8c, 0xbf, 0x00, 0x20, + 0x01, 0x20, 0x04, 0xe0, 0x18, 0x46, 0x02, 0xe0, 0x01, 0x20, 0x00, 0xe0, + 0x00, 0x20, 0xcc, 0x6a, 0x41, 0xf2, 0xe4, 0x41, 0x8c, 0x42, 0x15, 0xd1, + 0xa2, 0xf5, 0x82, 0x61, 0x07, 0x39, 0x01, 0x29, 0x03, 0xd8, 0x3f, 0x2b, + 0x98, 0xbf, 0x00, 0x20, 0x10, 0xbd, 0x40, 0xf2, 0x0c, 0x41, 0x8a, 0x42, + 0x07, 0xd0, 0x40, 0xf2, 0x21, 0x41, 0x8a, 0x42, 0x04, 0xd1, 0x50, 0x2b, + 0x98, 0xbf, 0x00, 0x20, 0x10, 0xbd, 0x00, 0x20, 0x10, 0xbd, 0xc3, 0x6e, + 0x4f, 0xf0, 0x40, 0x70, 0x30, 0xb5, 0xc3, 0xf8, 0x60, 0x01, 0x00, 0x20, + 0x1c, 0xe0, 0x11, 0xf8, 0x03, 0x4c, 0x11, 0xf8, 0x04, 0x5c, 0x24, 0x04, + 0x44, 0xea, 0x05, 0x64, 0x11, 0xf8, 0x01, 0x5c, 0x07, 0x30, 0x2c, 0x43, + 0x11, 0xf8, 0x02, 0x5c, 0x44, 0xea, 0x05, 0x24, 0xc3, 0xf8, 0x64, 0x41, + 0x11, 0xf8, 0x06, 0x4c, 0x11, 0xf8, 0x07, 0x5c, 0x24, 0x02, 0x44, 0xea, + 0x05, 0x44, 0x11, 0xf8, 0x05, 0x5c, 0x2c, 0x43, 0xc3, 0xf8, 0x64, 0x41, + 0x07, 0x31, 0x90, 0x42, 0xdf, 0xd3, 0x30, 0xbd, 0x90, 0xf8, 0x5e, 0x30, + 0x10, 0xb5, 0x04, 0x46, 0x3b, 0xb9, 0x04, 0x4b, 0x04, 0x49, 0x1a, 0x68, + 0xff, 0xf7, 0xcd, 0xff, 0x01, 0x23, 0x84, 0xf8, 0x5e, 0x30, 0x10, 0xbd, + 0x4c, 0xaf, 0x02, 0x00, 0x50, 0xaf, 0x02, 0x00, 0xd0, 0xf8, 0x50, 0x18, + 0x10, 0xb5, 0x04, 0x46, 0x41, 0xb1, 0xd0, 0xf8, 0x4c, 0x28, 0x40, 0x68, + 0x92, 0x00, 0xe3, 0xf3, 0x9b, 0xf5, 0x00, 0x23, 0xc4, 0xf8, 0x50, 0x38, + 0xd4, 0xf8, 0x48, 0x18, 0x59, 0xb1, 0x60, 0x68, 0xdf, 0xf3, 0xee, 0xf4, + 0x60, 0x68, 0xd4, 0xf8, 0x48, 0x18, 0xe8, 0x22, 0xe3, 0xf3, 0x8c, 0xf5, + 0x00, 0x23, 0xc4, 0xf8, 0x48, 0x38, 0x10, 0xbd, 0x2d, 0xe9, 0xf0, 0x4f, + 0x03, 0x68, 0x04, 0x69, 0x8b, 0xb0, 0xde, 0x69, 0x82, 0x46, 0xe3, 0x6b, + 0x17, 0x46, 0x08, 0xa8, 0x08, 0x21, 0x68, 0x4a, 0xde, 0xf3, 0x66, 0xf7, + 0xe3, 0x68, 0x00, 0x2b, 0x40, 0xf0, 0xbe, 0x80, 0xe1, 0x6e, 0x20, 0x6e, + 0x01, 0xf5, 0x00, 0x71, 0xd4, 0xf8, 0x00, 0x90, 0xe1, 0xf3, 0x4a, 0xf3, + 0xa3, 0x68, 0x01, 0x46, 0x98, 0x68, 0xec, 0xf3, 0xe3, 0xf1, 0x00, 0x28, + 0x00, 0xf0, 0xb7, 0x80, 0x22, 0x6e, 0xe1, 0x6e, 0x17, 0xb1, 0x01, 0xf5, + 0x00, 0x73, 0x00, 0xe0, 0x3b, 0x46, 0x01, 0xf5, 0x08, 0x71, 0x07, 0xb1, + 0x37, 0x68, 0x8d, 0xe8, 0x82, 0x00, 0x71, 0x68, 0x4f, 0xf0, 0xff, 0x37, + 0x02, 0x91, 0xb1, 0x68, 0x04, 0x97, 0x03, 0x91, 0xf1, 0x68, 0xdf, 0xf8, + 0x54, 0x81, 0x05, 0x91, 0xa1, 0x68, 0x48, 0x46, 0xd1, 0xf8, 0x28, 0x18, + 0xcd, 0xf8, 0x1c, 0x80, 0x06, 0x91, 0x08, 0xa9, 0xec, 0xf7, 0xf4, 0xfd, + 0x00, 0x25, 0xe0, 0x60, 0xe3, 0x6e, 0x00, 0x95, 0x32, 0x68, 0x02, 0x95, + 0x01, 0x92, 0x03, 0x95, 0x04, 0x97, 0x05, 0x95, 0x06, 0x95, 0xcd, 0xf8, + 0x1c, 0x80, 0x83, 0x46, 0x08, 0xa9, 0x22, 0x6e, 0x03, 0xf5, 0x10, 0x73, + 0x48, 0x46, 0xec, 0xf7, 0xdf, 0xfd, 0xe3, 0x6e, 0x20, 0x61, 0x00, 0x95, + 0x32, 0x68, 0xc5, 0xeb, 0x0b, 0x0e, 0xde, 0xf1, 0x00, 0x0b, 0x4b, 0xeb, + 0x0e, 0x0b, 0x01, 0x92, 0x02, 0x95, 0x03, 0x95, 0x04, 0x97, 0x05, 0x95, + 0x06, 0x95, 0xcd, 0xf8, 0x1c, 0x80, 0xa8, 0x42, 0x08, 0xbf, 0x4b, 0xf0, + 0x01, 0x0b, 0x08, 0xa9, 0x22, 0x6e, 0x03, 0xf5, 0x20, 0x73, 0x48, 0x46, + 0xec, 0xf7, 0xc2, 0xfd, 0xe3, 0x6e, 0x60, 0x61, 0x00, 0x95, 0x32, 0x68, + 0x02, 0x95, 0x01, 0x92, 0x03, 0x95, 0x04, 0x97, 0x05, 0x95, 0x06, 0x95, + 0xcd, 0xf8, 0x1c, 0x80, 0xa8, 0x42, 0x08, 0xbf, 0x4b, 0xf0, 0x01, 0x0b, + 0x08, 0xa9, 0x22, 0x6e, 0x03, 0xf5, 0x30, 0x73, 0x48, 0x46, 0xec, 0xf7, + 0xab, 0xfd, 0xe3, 0x6e, 0xa0, 0x61, 0x00, 0x95, 0x32, 0x68, 0x02, 0x95, + 0x01, 0x92, 0x03, 0x95, 0x04, 0x97, 0x05, 0x95, 0x06, 0x95, 0xcd, 0xf8, + 0x1c, 0x80, 0xa8, 0x42, 0x08, 0xbf, 0x4b, 0xf0, 0x01, 0x0b, 0x08, 0xa9, + 0x22, 0x6e, 0x03, 0xf5, 0x40, 0x73, 0x48, 0x46, 0xec, 0xf7, 0x94, 0xfd, + 0xe3, 0x6e, 0xe0, 0x61, 0x00, 0x95, 0x32, 0x68, 0x02, 0x95, 0x01, 0x92, + 0x03, 0x95, 0x04, 0x97, 0x05, 0x95, 0x06, 0x95, 0xcd, 0xf8, 0x1c, 0x80, + 0xa8, 0x42, 0x08, 0xbf, 0x4b, 0xf0, 0x01, 0x0b, 0x08, 0xa9, 0x48, 0x46, + 0x22, 0x6e, 0x03, 0xf5, 0x50, 0x73, 0xec, 0xf7, 0x7d, 0xfd, 0x20, 0x62, + 0xa8, 0x42, 0x14, 0xbf, 0x58, 0x46, 0x4b, 0xf0, 0x01, 0x00, 0xa8, 0xb9, + 0x25, 0x46, 0x06, 0x26, 0xe8, 0x68, 0x30, 0xb1, 0x0b, 0x4b, 0x0c, 0x49, + 0xd3, 0xf8, 0x84, 0x30, 0x98, 0x47, 0xc5, 0xf8, 0xa0, 0x00, 0x04, 0x35, + 0x01, 0x3e, 0xf3, 0xd1, 0xa1, 0x6f, 0x50, 0x46, 0x08, 0x31, 0x00, 0x22, + 0xe6, 0xf7, 0x88, 0xfe, 0x01, 0x20, 0x00, 0xe0, 0x28, 0x46, 0x0b, 0xb0, + 0xbd, 0xe8, 0xf0, 0x8f, 0xfb, 0x41, 0x86, 0x00, 0xe0, 0xa6, 0x85, 0x00, + 0xc3, 0x26, 0x86, 0x00, 0x14, 0x26, 0x00, 0x00, 0x1f, 0xb5, 0x02, 0x23, + 0x03, 0x93, 0x0e, 0x23, 0x04, 0x46, 0xc0, 0xf8, 0x4c, 0x38, 0x38, 0x21, + 0x40, 0x68, 0xe3, 0xf3, 0x89, 0xf4, 0xc4, 0xf8, 0x50, 0x08, 0xd0, 0xb1, + 0xd4, 0xf8, 0x4c, 0x28, 0x00, 0x21, 0x92, 0x00, 0xde, 0xf3, 0x38, 0xf6, + 0x60, 0x68, 0xe8, 0x21, 0xe3, 0xf3, 0x7c, 0xf4, 0xc4, 0xf8, 0x48, 0x08, + 0x68, 0xb1, 0x00, 0x21, 0xe8, 0x22, 0xde, 0xf3, 0x2d, 0xf6, 0x01, 0x23, + 0x00, 0x93, 0x60, 0x68, 0xd4, 0xf8, 0x48, 0x18, 0x03, 0xaa, 0xb4, 0x23, + 0xdf, 0xf3, 0x70, 0xf4, 0x01, 0xe0, 0x4f, 0xf0, 0xff, 0x30, 0x04, 0xb0, + 0x10, 0xbd, 0x00, 0x00, 0x83, 0x68, 0x0b, 0x4a, 0x5a, 0x62, 0x00, 0x23, + 0x80, 0xf8, 0x86, 0x30, 0x03, 0x23, 0xa0, 0xf8, 0x8c, 0x30, 0x02, 0x23, + 0xa0, 0xf8, 0x8e, 0x30, 0x07, 0x23, 0xa0, 0xf8, 0x88, 0x30, 0x04, 0x23, + 0xa0, 0xf8, 0x8a, 0x30, 0x42, 0xf6, 0x01, 0x33, 0xa0, 0xf8, 0x9c, 0x30, + 0x70, 0x47, 0x00, 0xbf, 0x64, 0xa8, 0xe7, 0xbe, 0x70, 0xb5, 0x04, 0x69, + 0x05, 0x46, 0x20, 0x6e, 0x08, 0xb1, 0xe9, 0xf7, 0xe7, 0xfc, 0x20, 0x46, + 0xff, 0xf7, 0x18, 0xfe, 0xa6, 0x6f, 0x70, 0x6a, 0x18, 0xb1, 0x03, 0xf0, + 0xbf, 0xff, 0x00, 0x23, 0x73, 0x62, 0x60, 0x6f, 0x03, 0xf0, 0xe0, 0xfd, + 0x20, 0x6f, 0x05, 0xf0, 0x88, 0xf9, 0x61, 0x6e, 0x29, 0xb1, 0x20, 0x68, + 0xa2, 0x6e, 0xe3, 0xf3, 0x3f, 0xf4, 0x00, 0x23, 0x63, 0x66, 0x20, 0x6e, + 0x18, 0xb1, 0x03, 0xf0, 0x4f, 0xf8, 0x00, 0x23, 0x23, 0x66, 0x20, 0x46, + 0xe6, 0xf7, 0x2a, 0xfe, 0x28, 0x46, 0xff, 0xf7, 0x8b, 0xfe, 0x00, 0x20, + 0x70, 0xbd, 0x00, 0x00, 0xc3, 0x6e, 0x4f, 0xf4, 0x80, 0x32, 0x10, 0xb5, + 0xc3, 0xf8, 0x60, 0x21, 0xd3, 0xf8, 0x60, 0x11, 0xd3, 0xf8, 0x64, 0x41, + 0xc3, 0xf8, 0x60, 0x21, 0xd3, 0xf8, 0x60, 0x11, 0x19, 0x49, 0xc3, 0xf8, + 0x64, 0x11, 0xc3, 0xf8, 0x60, 0x21, 0xd3, 0xf8, 0x60, 0x01, 0xd3, 0xf8, + 0x64, 0x01, 0x88, 0x42, 0x23, 0xd1, 0xc3, 0xf8, 0x60, 0x21, 0xd3, 0xf8, + 0x60, 0x11, 0x13, 0x49, 0xc3, 0xf8, 0x64, 0x11, 0xc3, 0xf8, 0x60, 0x21, + 0xd3, 0xf8, 0x60, 0x01, 0xd3, 0xf8, 0x64, 0x01, 0x88, 0x42, 0x4f, 0xf0, + 0x00, 0x00, 0x15, 0xd1, 0xc3, 0xf8, 0x60, 0x21, 0xd3, 0xf8, 0x60, 0x21, + 0xc3, 0xf8, 0x64, 0x41, 0xc3, 0xf8, 0x8c, 0x01, 0xd3, 0xf8, 0x20, 0x31, + 0xb3, 0xf1, 0x04, 0x2f, 0x07, 0xd0, 0x07, 0x48, 0x1b, 0x1a, 0x58, 0x42, + 0x40, 0xeb, 0x03, 0x00, 0x10, 0xbd, 0x00, 0x20, 0x10, 0xbd, 0x01, 0x20, + 0x10, 0xbd, 0x00, 0xbf, 0xaa, 0x55, 0x55, 0xaa, 0x55, 0xaa, 0xaa, 0x55, + 0x00, 0x04, 0x00, 0x84, 0x2d, 0xe9, 0xf0, 0x4f, 0x04, 0x69, 0x9b, 0x46, + 0xe3, 0x63, 0xe3, 0x6f, 0x97, 0xb0, 0xdd, 0xf8, 0x84, 0xa0, 0xa3, 0x67, + 0x9d, 0xf8, 0x80, 0x30, 0xa0, 0x60, 0x23, 0x71, 0x05, 0x46, 0xc4, 0xf8, + 0x00, 0xa0, 0x20, 0x46, 0x16, 0x46, 0x0f, 0x46, 0xff, 0xf7, 0x5a, 0xff, + 0x24, 0x9b, 0x30, 0x46, 0x00, 0x93, 0x04, 0xf1, 0x64, 0x03, 0x01, 0x93, + 0x04, 0xf1, 0x68, 0x03, 0x02, 0x93, 0x51, 0x46, 0x22, 0x9a, 0x23, 0x9b, + 0x03, 0xf0, 0x60, 0xf9, 0x20, 0x66, 0x00, 0x28, 0x00, 0xf0, 0xcf, 0x81, + 0xd4, 0xf8, 0x64, 0x80, 0x81, 0x49, 0x40, 0x46, 0xdf, 0xf3, 0x28, 0xf2, + 0x20, 0xb1, 0x00, 0x21, 0x0a, 0x46, 0xdf, 0xf3, 0xe3, 0xf0, 0x87, 0xb2, + 0x40, 0x46, 0x7d, 0x49, 0xdf, 0xf3, 0x1e, 0xf2, 0x48, 0xb1, 0x00, 0x21, + 0x0a, 0x46, 0xdf, 0xf3, 0xd9, 0xf0, 0x4f, 0xf6, 0xff, 0x73, 0x80, 0xb2, + 0x98, 0x42, 0x18, 0xbf, 0x06, 0x46, 0x38, 0x46, 0x31, 0x46, 0xfe, 0xf7, + 0x6f, 0xfa, 0x00, 0x28, 0x00, 0xf0, 0xaf, 0x81, 0x40, 0xf6, 0x12, 0x01, + 0x00, 0x22, 0xa4, 0xf8, 0x40, 0x70, 0xa4, 0xf8, 0x42, 0x60, 0x20, 0x6e, + 0xe7, 0xf3, 0x18, 0xf6, 0xe0, 0x66, 0x20, 0x6e, 0xe7, 0xf3, 0x66, 0xf4, + 0xd4, 0xf8, 0x6c, 0x90, 0x60, 0x64, 0xc5, 0xf8, 0x0c, 0x90, 0x20, 0x46, + 0xff, 0xf7, 0x5c, 0xfd, 0x00, 0x28, 0x00, 0xf0, 0x98, 0x81, 0x20, 0x6e, + 0xe9, 0xf7, 0x6f, 0xfc, 0x20, 0x46, 0x00, 0x21, 0x18, 0xf0, 0x70, 0xdb, + 0x20, 0x46, 0x4f, 0xf0, 0xff, 0x31, 0xe6, 0xf7, 0xf5, 0xfd, 0x20, 0x46, + 0xff, 0xf7, 0x46, 0xff, 0x00, 0x28, 0x00, 0xf0, 0x88, 0x81, 0x40, 0x46, + 0x5d, 0x49, 0xdf, 0xf3, 0xb1, 0xf1, 0xff, 0x28, 0x08, 0xbf, 0x01, 0x20, + 0xa4, 0xf8, 0x4a, 0x00, 0x20, 0x46, 0xff, 0xf7, 0x46, 0xfd, 0x00, 0x28, + 0x00, 0xf0, 0x7b, 0x81, 0x57, 0x49, 0x40, 0x46, 0xdf, 0xf3, 0xa2, 0xf1, + 0x56, 0x49, 0x84, 0xf8, 0x48, 0x00, 0x40, 0x46, 0xdf, 0xf3, 0x9c, 0xf1, + 0x54, 0x49, 0xe0, 0x64, 0x40, 0x46, 0xdf, 0xf3, 0x97, 0xf1, 0x23, 0x6e, + 0x41, 0xf2, 0x6b, 0x02, 0xd9, 0x6a, 0x20, 0x65, 0x91, 0x42, 0x0a, 0xd1, + 0x9b, 0x6a, 0x4e, 0x2b, 0x07, 0xd1, 0xb4, 0xf8, 0x4a, 0x30, 0x40, 0x2b, + 0x03, 0xd9, 0xe3, 0x6c, 0x43, 0xf0, 0x02, 0x03, 0xe3, 0x64, 0xe3, 0x6c, + 0x99, 0x06, 0x04, 0xd5, 0x01, 0x21, 0x20, 0x46, 0x0a, 0x46, 0x19, 0xf0, + 0xe3, 0xde, 0xb4, 0xf8, 0x42, 0x20, 0x01, 0x23, 0xc4, 0xf8, 0x98, 0x30, + 0xb4, 0xf8, 0x40, 0x00, 0x2b, 0x68, 0xa5, 0xf8, 0x82, 0x21, 0x22, 0x6e, + 0xa5, 0xf8, 0x80, 0x01, 0x1a, 0x61, 0x62, 0x6c, 0x9a, 0x60, 0x94, 0xf8, + 0x48, 0x20, 0x83, 0xf8, 0x7c, 0x20, 0x2b, 0x68, 0xe2, 0x6c, 0xb4, 0xf8, + 0x4a, 0x00, 0xc3, 0xf8, 0x80, 0x20, 0x22, 0x6d, 0xa3, 0xf8, 0x7a, 0x00, + 0xc3, 0xf8, 0x84, 0x20, 0xd4, 0xf8, 0x98, 0x20, 0x20, 0x46, 0x5a, 0x62, + 0xa9, 0x68, 0x2a, 0x46, 0x05, 0xf0, 0x42, 0xf8, 0x20, 0x67, 0x00, 0x28, + 0x00, 0xf0, 0x29, 0x81, 0x62, 0x6c, 0x23, 0x6e, 0x08, 0x92, 0xb4, 0xf8, + 0x40, 0x20, 0x06, 0x90, 0xad, 0xf8, 0x30, 0x20, 0x9a, 0x6b, 0xb4, 0xf8, + 0x42, 0x00, 0x0d, 0x92, 0xda, 0x6b, 0x05, 0x93, 0x0e, 0x92, 0x1a, 0x6c, + 0xad, 0xf8, 0x32, 0x00, 0x0f, 0x92, 0x94, 0xf8, 0x48, 0x20, 0x04, 0xa8, + 0x10, 0x92, 0x9a, 0x6a, 0xcd, 0xf8, 0x10, 0xa0, 0x11, 0x92, 0xb4, 0xf8, + 0x4a, 0x20, 0xcd, 0xf8, 0x1c, 0xb0, 0x12, 0x92, 0xda, 0x6a, 0xcd, 0xf8, + 0x2c, 0x80, 0x13, 0x92, 0xe2, 0x6c, 0x14, 0x92, 0x22, 0x6d, 0x15, 0x92, + 0x5a, 0x68, 0xdb, 0x68, 0x09, 0x92, 0x0a, 0x93, 0x03, 0xf0, 0x3a, 0xfc, + 0x60, 0x67, 0x00, 0x28, 0x00, 0xf0, 0xf9, 0x80, 0xb4, 0xf8, 0x42, 0x30, + 0x44, 0xf2, 0x1d, 0x32, 0x93, 0x42, 0x29, 0xd0, 0x0a, 0xd8, 0x44, 0xf2, + 0x16, 0x32, 0x93, 0x42, 0x24, 0xd0, 0x44, 0xf2, 0x1a, 0x32, 0x93, 0x42, + 0x20, 0xd0, 0x44, 0xf2, 0x13, 0x32, 0x0d, 0xe0, 0x44, 0xf2, 0x2a, 0x32, + 0x93, 0x42, 0x19, 0xd0, 0x02, 0xd8, 0x44, 0xf2, 0x21, 0x32, 0x05, 0xe0, + 0x44, 0xf2, 0x2d, 0x32, 0x93, 0x42, 0x11, 0xd0, 0x44, 0xf2, 0x52, 0x32, + 0x93, 0x42, 0x0d, 0xd0, 0x00, 0x26, 0x0c, 0xe0, 0xd1, 0xad, 0x86, 0x00, + 0x48, 0x37, 0x86, 0x00, 0x84, 0xae, 0x86, 0x00, 0xe5, 0xae, 0x86, 0x00, + 0x86, 0x37, 0x86, 0x00, 0x9e, 0x79, 0x86, 0x00, 0x01, 0x26, 0x31, 0x46, + 0x20, 0x46, 0xe6, 0xf7, 0xbd, 0xfc, 0xa3, 0x6f, 0x00, 0x2e, 0x0c, 0xbf, + 0x02, 0x22, 0x01, 0x22, 0x1a, 0x60, 0x5e, 0x60, 0x2b, 0x6b, 0x20, 0x6e, + 0x83, 0xe8, 0x44, 0x00, 0xef, 0x6a, 0xe7, 0xf3, 0x5f, 0xf3, 0xd9, 0xf8, + 0x5c, 0x31, 0x38, 0x60, 0x62, 0x4a, 0x63, 0x65, 0xa3, 0x65, 0x63, 0x6c, + 0x06, 0x21, 0x01, 0xfb, 0x03, 0x23, 0xa7, 0x6f, 0x18, 0x3b, 0xc4, 0xf8, + 0xb8, 0x30, 0x60, 0x6f, 0x49, 0x46, 0x3a, 0x68, 0x43, 0x46, 0x03, 0xf0, + 0x65, 0xfc, 0x78, 0x62, 0x00, 0x28, 0x00, 0xf0, 0xa0, 0x80, 0xa3, 0x6f, + 0x61, 0x6d, 0x58, 0x6a, 0xee, 0xf7, 0x0f, 0xf9, 0xa3, 0x6f, 0x03, 0xf1, + 0x22, 0x02, 0x00, 0x92, 0x03, 0xf1, 0x1c, 0x01, 0x03, 0xf1, 0x1e, 0x02, + 0x58, 0x6a, 0x20, 0x33, 0x03, 0xf0, 0x0f, 0xfc, 0xa7, 0x6f, 0x78, 0x6a, + 0x03, 0xf0, 0x1b, 0xfc, 0x87, 0xf8, 0x28, 0x00, 0xa3, 0x6f, 0x2f, 0x6b, + 0x58, 0x6a, 0x03, 0xf0, 0x14, 0xfc, 0x38, 0x75, 0xa7, 0x6f, 0x78, 0x6a, + 0x03, 0xf0, 0x12, 0xfc, 0xa3, 0x6f, 0xb8, 0x61, 0xda, 0x8b, 0x03, 0x2a, + 0x7b, 0xd1, 0x29, 0x6b, 0x58, 0x6a, 0x08, 0x61, 0x98, 0x8b, 0x4a, 0x81, + 0x08, 0x81, 0x1a, 0x8c, 0x58, 0x8c, 0x8a, 0x81, 0xc8, 0x81, 0x0f, 0x22, + 0x40, 0xf2, 0xff, 0x30, 0x9a, 0x82, 0xd8, 0x82, 0x31, 0x46, 0x28, 0x46, + 0x01, 0x22, 0xff, 0xf7, 0xbf, 0xfc, 0x00, 0x28, 0x67, 0xd0, 0xa2, 0x6f, + 0x2b, 0x68, 0x50, 0x6a, 0x93, 0xf8, 0x99, 0x10, 0xee, 0xf7, 0xd4, 0xf8, + 0x00, 0x21, 0x20, 0x46, 0x18, 0xf0, 0x16, 0xdf, 0x08, 0x21, 0x20, 0x46, + 0xe6, 0xf7, 0x30, 0xfe, 0x20, 0x46, 0x1a, 0xf0, 0x47, 0xda, 0x00, 0x95, + 0x20, 0x6e, 0x31, 0x49, 0x31, 0x4a, 0x00, 0x23, 0xe7, 0xf3, 0x6e, 0xf4, + 0x20, 0x46, 0x00, 0x21, 0x1a, 0xf0, 0x1e, 0xda, 0x20, 0x46, 0xe6, 0xf7, + 0xe9, 0xfb, 0x00, 0x28, 0x47, 0xd0, 0x04, 0xf1, 0xdc, 0x05, 0x29, 0x46, + 0xde, 0xf3, 0x82, 0xf6, 0x28, 0x46, 0xdf, 0xf3, 0x3f, 0xf0, 0x00, 0x28, + 0x3f, 0xd1, 0x28, 0x46, 0xdf, 0xf3, 0x4a, 0xf0, 0x05, 0x46, 0x00, 0x28, + 0x39, 0xd1, 0x20, 0x46, 0x18, 0xf0, 0x4c, 0xd8, 0xa3, 0x68, 0x1b, 0x68, + 0xd3, 0xf8, 0x9c, 0x00, 0x00, 0x28, 0x34, 0xd0, 0x03, 0x78, 0x00, 0x2b, + 0x2f, 0xd0, 0x1e, 0x49, 0x22, 0x46, 0xdf, 0xf3, 0x4b, 0xf1, 0xa3, 0x68, + 0x1c, 0x49, 0x1b, 0x68, 0x22, 0x46, 0xd3, 0xf8, 0x9c, 0x00, 0xdf, 0xf3, + 0x7d, 0xf1, 0xa0, 0x68, 0xff, 0xf7, 0x54, 0xfd, 0xe0, 0x68, 0x00, 0xb3, + 0xa3, 0x68, 0x1b, 0x68, 0xd3, 0xf8, 0x9c, 0x10, 0xe1, 0xf3, 0x70, 0xf1, + 0x1a, 0xe0, 0x0b, 0x25, 0x18, 0xe0, 0x0c, 0x25, 0x16, 0xe0, 0x0d, 0x25, + 0x14, 0xe0, 0x0e, 0x25, 0x12, 0xe0, 0x0f, 0x25, 0x10, 0xe0, 0x19, 0x25, + 0x0e, 0xe0, 0x10, 0x25, 0x0c, 0xe0, 0x11, 0x25, 0x0a, 0xe0, 0x12, 0x25, + 0x08, 0xe0, 0x13, 0x25, 0x06, 0xe0, 0x15, 0x25, 0x04, 0xe0, 0x16, 0x25, + 0x02, 0xe0, 0x1d, 0x46, 0x00, 0xe0, 0x05, 0x46, 0x28, 0x46, 0x17, 0xb0, + 0xbd, 0xe8, 0xf0, 0x8f, 0x34, 0xfe, 0x01, 0x00, 0x69, 0xc1, 0x83, 0x00, + 0x85, 0xc1, 0x83, 0x00, 0x25, 0xc0, 0x83, 0x00, 0x49, 0xc0, 0x83, 0x00, + 0x10, 0xb5, 0x04, 0x46, 0x1b, 0xf0, 0x0a, 0xdf, 0x01, 0x22, 0x01, 0x46, + 0x20, 0x46, 0xbd, 0xe8, 0x10, 0x40, 0x1b, 0xf0, 0x7b, 0x9f, 0x37, 0xb5, + 0x05, 0x46, 0x1b, 0xf0, 0xff, 0xde, 0x00, 0x23, 0xc5, 0xf8, 0x4c, 0x02, + 0x80, 0xf8, 0x48, 0x30, 0x2a, 0x68, 0x04, 0x46, 0x92, 0xf8, 0x2f, 0x10, + 0x28, 0x46, 0x00, 0x91, 0x4e, 0x32, 0x21, 0x46, 0x1a, 0xf0, 0x9e, 0xdc, + 0x38, 0xb1, 0x28, 0x46, 0x21, 0x46, 0x1b, 0xf0, 0x47, 0xdd, 0x4f, 0xf0, + 0xff, 0x30, 0x03, 0xb0, 0x30, 0xbd, 0x28, 0x46, 0x21, 0x46, 0x03, 0xb0, + 0xbd, 0xe8, 0x30, 0x40, 0x1b, 0xf0, 0xe2, 0x9d, 0x37, 0xb5, 0x04, 0x46, + 0x00, 0x28, 0x45, 0xd0, 0xd0, 0xf8, 0x20, 0x11, 0x31, 0xb1, 0x03, 0x68, + 0x98, 0x68, 0xeb, 0xf3, 0x55, 0xf6, 0x00, 0x23, 0xc4, 0xf8, 0x20, 0x31, + 0x23, 0x68, 0x1a, 0x68, 0x92, 0xf8, 0x2f, 0x20, 0x2a, 0xb3, 0xd3, 0xf8, + 0x00, 0x05, 0x01, 0xa9, 0x31, 0xf0, 0x72, 0xdb, 0x12, 0xe0, 0x43, 0x68, + 0x5a, 0x06, 0x0f, 0xd5, 0xd4, 0xf8, 0x2c, 0x51, 0x45, 0x19, 0x07, 0xe0, + 0x0b, 0x68, 0x48, 0x22, 0xc5, 0xf8, 0x10, 0x31, 0x23, 0x68, 0x58, 0x68, + 0xe3, 0xf3, 0x70, 0xf1, 0xd5, 0xf8, 0x10, 0x11, 0x00, 0x29, 0xf3, 0xd1, + 0x01, 0xa8, 0x31, 0xf0, 0x63, 0xdb, 0x00, 0x28, 0xe7, 0xd1, 0x06, 0xe0, + 0x0a, 0x68, 0x58, 0x68, 0xc4, 0xf8, 0x40, 0x21, 0x48, 0x22, 0xe3, 0xf3, + 0x5f, 0xf1, 0xd4, 0xf8, 0x40, 0x11, 0x23, 0x68, 0x00, 0x29, 0xf3, 0xd1, + 0x18, 0x68, 0x06, 0x49, 0x22, 0x46, 0x00, 0xf0, 0x81, 0xda, 0x23, 0x68, + 0x21, 0x46, 0x58, 0x68, 0x4f, 0xf4, 0xa4, 0x72, 0xe3, 0xf3, 0x4e, 0xf1, + 0x3e, 0xbd, 0x00, 0xbf, 0x91, 0xba, 0x86, 0x00, 0x7f, 0xb5, 0x05, 0x46, + 0x4f, 0xf4, 0xa4, 0x71, 0x40, 0x68, 0xe3, 0xf3, 0x33, 0xf1, 0x04, 0x46, + 0x00, 0x28, 0x55, 0xd0, 0x00, 0x21, 0x4f, 0xf4, 0xa4, 0x72, 0xde, 0xf3, + 0xe3, 0xf2, 0x2a, 0x4b, 0x25, 0x60, 0x00, 0x93, 0x29, 0x4b, 0x00, 0x26, + 0x01, 0x93, 0x29, 0x4b, 0x28, 0x68, 0x03, 0x93, 0x28, 0x49, 0x29, 0x4a, + 0x23, 0x46, 0x02, 0x96, 0x00, 0xf0, 0x20, 0xda, 0x2b, 0x6b, 0x1a, 0x68, + 0x02, 0x2a, 0x05, 0xd1, 0x5b, 0x7d, 0x00, 0x2b, 0x0c, 0xbf, 0x16, 0x23, + 0x30, 0x23, 0x00, 0xe0, 0x30, 0x23, 0xa2, 0x19, 0x44, 0x36, 0xb6, 0xf5, + 0x88, 0x7f, 0x13, 0x74, 0xee, 0xd1, 0xa8, 0x68, 0x1e, 0x49, 0x2a, 0x46, + 0x00, 0x23, 0xeb, 0xf3, 0xf9, 0xf5, 0x06, 0x46, 0xc4, 0xf8, 0x20, 0x01, + 0x30, 0xb9, 0x68, 0x68, 0x21, 0x46, 0x4f, 0xf4, 0xa4, 0x72, 0xe3, 0xf3, + 0x0b, 0xf1, 0x1e, 0xe0, 0x4f, 0xf4, 0x96, 0x73, 0xc4, 0xf8, 0x1c, 0x31, + 0x45, 0xf2, 0x73, 0x53, 0xa4, 0xf8, 0x38, 0x31, 0x46, 0x23, 0xa4, 0xf8, + 0x3a, 0x31, 0x12, 0x4b, 0x00, 0x26, 0xc4, 0xf8, 0x40, 0x61, 0x28, 0x46, + 0x8d, 0xe8, 0x28, 0x00, 0x4f, 0xf4, 0x8a, 0x71, 0x0e, 0x4a, 0x0f, 0x4b, + 0x04, 0xf0, 0x90, 0xff, 0xb0, 0x42, 0xc4, 0xf8, 0x2c, 0x01, 0x03, 0xda, + 0x20, 0x46, 0xff, 0xf7, 0x53, 0xff, 0x34, 0x46, 0x20, 0x46, 0x04, 0xb0, + 0x70, 0xbd, 0x00, 0xbf, 0xf9, 0x0c, 0x84, 0x00, 0x65, 0x02, 0x01, 0x00, + 0x7d, 0x0a, 0x84, 0x00, 0x70, 0xe3, 0x85, 0x00, 0x91, 0xba, 0x86, 0x00, + 0x3d, 0x06, 0x84, 0x00, 0xd9, 0x12, 0x84, 0x00, 0xe5, 0x12, 0x84, 0x00, + 0xa5, 0x12, 0x84, 0x00, 0x01, 0x46, 0x20, 0xb1, 0x03, 0x68, 0xb0, 0x22, + 0xd8, 0x68, 0xe3, 0xf3, 0xcd, 0xb0, 0x70, 0x47, 0xf7, 0xb5, 0x06, 0x68, + 0x05, 0x46, 0xb0, 0x21, 0xf0, 0x68, 0xe3, 0xf3, 0xb5, 0xf0, 0x04, 0x46, + 0x00, 0x28, 0x00, 0xf0, 0x87, 0x80, 0x00, 0x21, 0xb0, 0x22, 0xde, 0xf3, + 0x65, 0xf2, 0x04, 0x22, 0x26, 0x60, 0x65, 0x60, 0x00, 0x21, 0xc5, 0xf8, + 0x5c, 0x41, 0x01, 0xa8, 0xde, 0xf3, 0x5c, 0xf2, 0x2b, 0x68, 0x93, 0xf8, + 0x7c, 0x20, 0x58, 0x69, 0x01, 0x2a, 0x06, 0xd9, 0x3a, 0x49, 0xde, 0xf3, + 0x1b, 0xf7, 0x01, 0x46, 0x88, 0xb1, 0x01, 0xa8, 0x09, 0xe0, 0x38, 0x49, + 0xde, 0xf3, 0xe8, 0xf6, 0x09, 0x28, 0x03, 0x46, 0x09, 0xd8, 0x36, 0x49, + 0x01, 0xa8, 0x01, 0xeb, 0x83, 0x01, 0x03, 0x22, 0xde, 0xf3, 0xfa, 0xf2, + 0x00, 0x23, 0x8d, 0xf8, 0x07, 0x30, 0x03, 0x22, 0x01, 0xa9, 0x04, 0xf1, + 0x08, 0x00, 0xde, 0xf3, 0xf1, 0xf2, 0x00, 0x23, 0xe3, 0x72, 0x2b, 0x68, + 0x2d, 0x49, 0x58, 0x69, 0xde, 0xf3, 0xce, 0xf6, 0x33, 0x69, 0x41, 0xf2, + 0x6b, 0x02, 0xd9, 0x6a, 0xe0, 0x60, 0x91, 0x42, 0x0c, 0xd1, 0x9b, 0x6a, + 0x8b, 0x2b, 0x09, 0xd1, 0x02, 0x28, 0x07, 0xd1, 0x01, 0xa8, 0x26, 0x49, + 0x04, 0x22, 0xde, 0xf3, 0xb9, 0xf2, 0x08, 0xb9, 0x03, 0x23, 0xe3, 0x60, + 0x33, 0x69, 0x41, 0xf2, 0x6b, 0x02, 0xd9, 0x6a, 0x91, 0x42, 0x0d, 0xd1, + 0x9b, 0x6a, 0x93, 0x2b, 0x0a, 0xd1, 0x01, 0xa8, 0x1e, 0x49, 0x04, 0x22, + 0xde, 0xf3, 0xa8, 0xf2, 0x20, 0xb9, 0xe3, 0x68, 0x04, 0x2b, 0x01, 0xd1, + 0x06, 0x23, 0xe3, 0x60, 0x28, 0x46, 0x01, 0xa9, 0x21, 0xf0, 0x0e, 0xde, + 0x06, 0x46, 0x50, 0xb9, 0x17, 0x49, 0x01, 0xa8, 0x03, 0x22, 0xde, 0xf3, + 0xb7, 0xf2, 0x28, 0x46, 0x01, 0xa9, 0x8d, 0xf8, 0x07, 0x60, 0x21, 0xf0, + 0x01, 0xde, 0x05, 0xf5, 0xaa, 0x67, 0x01, 0xa9, 0x03, 0x22, 0x00, 0x26, + 0x07, 0xf1, 0x0a, 0x00, 0xde, 0xf3, 0xa8, 0xf2, 0x0e, 0x49, 0x85, 0xf8, + 0x5d, 0x65, 0x07, 0xf1, 0x0e, 0x00, 0x03, 0x22, 0xde, 0xf3, 0xa0, 0xf2, + 0x85, 0xf8, 0x61, 0x65, 0x20, 0x46, 0x01, 0xa9, 0x22, 0xf0, 0x74, 0xda, + 0x20, 0x46, 0xfe, 0xbd, 0xb3, 0xc4, 0x86, 0x00, 0xb9, 0xc4, 0x86, 0x00, + 0xce, 0x02, 0x86, 0x00, 0xbc, 0xc4, 0x86, 0x00, 0xc3, 0xc4, 0x86, 0x00, + 0x71, 0xc2, 0x86, 0x00, 0xc6, 0xc4, 0x86, 0x00, 0xca, 0xc4, 0x86, 0x00, + 0x30, 0xb5, 0x2c, 0x21, 0x85, 0xb0, 0x05, 0x46, 0x40, 0x68, 0xe3, 0xf3, + 0x11, 0xf0, 0x04, 0x46, 0xb8, 0xb1, 0x00, 0x21, 0x2c, 0x22, 0xde, 0xf3, + 0xc3, 0xf1, 0x08, 0x23, 0xa3, 0x61, 0x0a, 0x4b, 0x25, 0x60, 0x00, 0x93, + 0x00, 0x23, 0x01, 0x93, 0x02, 0x93, 0x03, 0x93, 0x07, 0x4a, 0x23, 0x46, + 0x28, 0x68, 0x07, 0x49, 0x00, 0xf0, 0x00, 0xd9, 0x2a, 0x68, 0x01, 0x23, + 0x82, 0xf8, 0x96, 0x30, 0x23, 0x71, 0x20, 0x46, 0x05, 0xb0, 0x30, 0xbd, + 0x05, 0x0b, 0x85, 0x00, 0x91, 0xe6, 0x86, 0x00, 0x64, 0xc7, 0x01, 0x00, + 0x38, 0xb5, 0x04, 0x46, 0x00, 0x28, 0x28, 0xd0, 0x03, 0x68, 0x14, 0x49, + 0x18, 0x68, 0x22, 0x46, 0x00, 0xf0, 0x20, 0xd9, 0x63, 0x69, 0x05, 0xe0, + 0x1d, 0x68, 0x59, 0x68, 0x20, 0x46, 0x2c, 0xf0, 0x03, 0xde, 0x2b, 0x46, + 0x00, 0x2b, 0xf7, 0xd1, 0x23, 0x69, 0x05, 0xe0, 0x1d, 0x68, 0x59, 0x68, + 0x20, 0x46, 0x2c, 0xf0, 0xf9, 0xdd, 0x2b, 0x46, 0x00, 0x2b, 0xf7, 0xd1, + 0xa1, 0x6a, 0x21, 0xb1, 0x23, 0x68, 0x90, 0x22, 0x58, 0x68, 0xe2, 0xf3, + 0xd9, 0xf7, 0x23, 0x68, 0x21, 0x46, 0x58, 0x68, 0x2c, 0x22, 0xbd, 0xe8, + 0x38, 0x40, 0xe2, 0xf3, 0xd1, 0xb7, 0x38, 0xbd, 0x91, 0xe6, 0x86, 0x00, + 0x2d, 0xe9, 0xf8, 0x43, 0x05, 0x46, 0x88, 0x46, 0xe7, 0xf3, 0xca, 0xf1, + 0x00, 0x21, 0x28, 0x46, 0xe7, 0xf3, 0x5c, 0xf2, 0x04, 0x46, 0x28, 0x46, + 0x6e, 0x69, 0xaf, 0x69, 0xe8, 0xf7, 0x84, 0xfe, 0x0a, 0x2e, 0x81, 0x46, + 0x16, 0xd9, 0x0f, 0x2e, 0x16, 0xd0, 0x28, 0x46, 0xe9, 0xf7, 0x91, 0xf8, + 0x14, 0x2e, 0x05, 0x46, 0x03, 0xd9, 0xa3, 0x68, 0x23, 0xf0, 0x08, 0x03, + 0xa3, 0x60, 0xa3, 0x68, 0x14, 0x2e, 0x43, 0xf0, 0x01, 0x03, 0xa3, 0x60, + 0x14, 0xd9, 0xa3, 0x68, 0x43, 0xf0, 0x08, 0x03, 0xa3, 0x60, 0x0f, 0xe0, + 0x02, 0x2e, 0x0f, 0xd9, 0x28, 0x46, 0xe9, 0xf7, 0x55, 0xf8, 0xd4, 0xf8, + 0xa4, 0x30, 0x05, 0x46, 0x23, 0xf0, 0xff, 0x03, 0x43, 0xf0, 0x02, 0x03, + 0xc4, 0xf8, 0xa4, 0x30, 0x02, 0x23, 0x03, 0xe0, 0x01, 0x23, 0x01, 0xe0, + 0x10, 0x4d, 0x30, 0x23, 0xa2, 0x68, 0xd2, 0x07, 0x07, 0xd4, 0x07, 0xf0, + 0x18, 0x02, 0x08, 0x2a, 0x0c, 0xbf, 0xb5, 0xfb, 0xf3, 0xf5, 0x4f, 0xf4, + 0xe1, 0x15, 0x07, 0xf0, 0x03, 0x07, 0x00, 0x26, 0x0b, 0xe0, 0x04, 0xf5, + 0x40, 0x73, 0xb8, 0xf1, 0x00, 0x0f, 0x05, 0xd0, 0x30, 0x02, 0x18, 0x18, + 0x49, 0x46, 0x2a, 0x46, 0x00, 0x23, 0xc0, 0x47, 0x01, 0x36, 0xbe, 0x42, + 0xf1, 0xdb, 0xbd, 0xe8, 0xf8, 0x83, 0x00, 0xbf, 0x00, 0xc6, 0x3e, 0x05, + 0x2d, 0xe9, 0xf0, 0x41, 0x16, 0x46, 0x98, 0x46, 0x04, 0x46, 0x0d, 0x46, + 0xe7, 0xf3, 0x2c, 0xf0, 0x00, 0x21, 0x07, 0x46, 0x20, 0x46, 0xe7, 0xf3, + 0xf9, 0xf1, 0x00, 0x22, 0x13, 0x46, 0x11, 0x49, 0x01, 0xeb, 0x02, 0x0e, + 0xde, 0xf8, 0x04, 0xe0, 0xbe, 0xf1, 0x00, 0x0f, 0x0d, 0xd1, 0x0c, 0x22, + 0x53, 0x43, 0xca, 0x18, 0xce, 0x50, 0x43, 0x6a, 0x55, 0x60, 0x1e, 0x43, + 0x0a, 0x4b, 0xc2, 0xf8, 0x08, 0x80, 0x1e, 0x60, 0x46, 0x62, 0x01, 0x25, + 0x04, 0xe0, 0x01, 0x33, 0x0c, 0x32, 0x05, 0x2b, 0xe5, 0xd1, 0x00, 0x25, + 0x20, 0x46, 0x39, 0x46, 0xe7, 0xf3, 0xd8, 0xf1, 0x28, 0x46, 0xbd, 0xe8, + 0xf0, 0x81, 0x00, 0xbf, 0x3c, 0x26, 0x00, 0x00, 0x78, 0x26, 0x00, 0x00, + 0x43, 0x69, 0x14, 0x2b, 0x01, 0xdd, 0x02, 0xf0, 0x1f, 0xbd, 0x70, 0x47, + 0x13, 0x4b, 0x13, 0xb5, 0x13, 0x60, 0x13, 0x46, 0x01, 0xe0, 0x11, 0x4c, + 0x1c, 0x60, 0x04, 0x33, 0xad, 0xf1, 0x7c, 0x04, 0xa3, 0x42, 0xf8, 0xd3, + 0x03, 0x30, 0x20, 0xf0, 0x03, 0x00, 0x0d, 0x4b, 0x09, 0x1a, 0x0d, 0x4c, + 0x19, 0x60, 0x00, 0x23, 0x23, 0x60, 0x0c, 0x4c, 0x08, 0x39, 0x23, 0x60, + 0x0b, 0x4c, 0x80, 0xe8, 0x0a, 0x00, 0x23, 0x60, 0x0a, 0x4c, 0x22, 0x60, + 0x0a, 0x4c, 0x02, 0xf5, 0xa0, 0x52, 0x22, 0x60, 0x09, 0x4a, 0x13, 0x60, + 0x09, 0x4b, 0x58, 0x60, 0x1c, 0xbd, 0x00, 0xbf, 0x4b, 0x41, 0x54, 0x53, + 0xc8, 0x26, 0x00, 0x00, 0x88, 0x26, 0x00, 0x00, 0xa4, 0x26, 0x00, 0x00, + 0xcc, 0x26, 0x00, 0x00, 0xf4, 0x07, 0x02, 0x00, 0xf8, 0x07, 0x02, 0x00, + 0x90, 0x26, 0x00, 0x00, 0xc0, 0x26, 0x00, 0x00, 0x1f, 0xb5, 0xe8, 0x20, + 0x00, 0x21, 0xe2, 0xf3, 0x81, 0xf2, 0x0c, 0x4c, 0x20, 0x60, 0xa0, 0xb1, + 0x00, 0x21, 0xe8, 0x22, 0xde, 0xf3, 0x94, 0xf0, 0x04, 0xaa, 0x01, 0x23, + 0x42, 0xf8, 0x04, 0x3d, 0x00, 0x23, 0x00, 0x93, 0x06, 0x4b, 0x21, 0x68, + 0x18, 0x68, 0x40, 0xf2, 0x3c, 0x73, 0xde, 0xf3, 0xd3, 0xf6, 0x20, 0x68, + 0x0e, 0x21, 0xde, 0xf3, 0x19, 0xf7, 0x1f, 0xbd, 0xbc, 0x26, 0x00, 0x00, + 0x20, 0x08, 0x02, 0x00, 0xb1, 0xf5, 0xe0, 0x6f, 0x73, 0xb5, 0x04, 0x46, + 0x0e, 0x46, 0x15, 0x46, 0x06, 0xd1, 0x03, 0x69, 0x00, 0x91, 0x00, 0x21, + 0x01, 0x91, 0x1e, 0x68, 0x0a, 0x46, 0x0c, 0xe0, 0x0d, 0x4b, 0x00, 0x22, + 0x18, 0x68, 0xe7, 0xf3, 0x49, 0xf1, 0x01, 0x46, 0x80, 0xb1, 0x23, 0x69, + 0x00, 0x22, 0x00, 0x96, 0x01, 0x92, 0x1e, 0x68, 0x20, 0x46, 0x2b, 0x46, + 0xb0, 0x47, 0x38, 0xb1, 0x06, 0x4b, 0xa0, 0x61, 0x1a, 0x68, 0x65, 0x61, + 0x22, 0x62, 0x1c, 0x60, 0x00, 0x20, 0x01, 0xe0, 0x4f, 0xf0, 0xff, 0x30, + 0x7c, 0xbd, 0x00, 0xbf, 0x8c, 0x26, 0x00, 0x00, 0x1c, 0x08, 0x02, 0x00, + 0x2d, 0xe9, 0xf8, 0x43, 0x10, 0x20, 0x0c, 0x46, 0x00, 0x21, 0x91, 0x46, + 0x98, 0x46, 0xe2, 0xf3, 0x2d, 0xf2, 0x05, 0x46, 0x00, 0xb3, 0x12, 0x4e, + 0x30, 0x68, 0xe6, 0xf3, 0x5f, 0xf7, 0x09, 0x9b, 0x07, 0x46, 0x23, 0xb9, + 0x30, 0x68, 0x21, 0x46, 0x4a, 0x46, 0xe7, 0xf3, 0x17, 0xf1, 0x30, 0x68, + 0xe6, 0xf3, 0xd0, 0xf7, 0x01, 0x23, 0x83, 0x40, 0xeb, 0x60, 0x08, 0x9b, + 0xc5, 0xf8, 0x04, 0x80, 0xab, 0x60, 0x08, 0x4b, 0x30, 0x68, 0x1a, 0x68, + 0x39, 0x46, 0x2a, 0x60, 0x1d, 0x60, 0xe7, 0xf3, 0x17, 0xf1, 0x00, 0x20, + 0xbd, 0xe8, 0xf8, 0x83, 0x6f, 0xf0, 0x1a, 0x00, 0xbd, 0xe8, 0xf8, 0x83, + 0x8c, 0x26, 0x00, 0x00, 0x98, 0x26, 0x00, 0x00, 0x07, 0xb5, 0x00, 0x21, + 0xe7, 0xf3, 0x08, 0xf1, 0x07, 0x4b, 0x4f, 0xf4, 0x00, 0x61, 0x18, 0x60, + 0x06, 0x4b, 0x00, 0xf5, 0x70, 0x60, 0x18, 0x60, 0x00, 0x20, 0x02, 0x46, + 0x04, 0x4b, 0x00, 0x90, 0x01, 0x90, 0xff, 0xf7, 0xb9, 0xff, 0x0e, 0xbd, + 0x9c, 0x26, 0x00, 0x00, 0xf0, 0x07, 0x02, 0x00, 0x6d, 0x60, 0x80, 0x00, + 0x13, 0xb5, 0x22, 0x4c, 0x22, 0x4b, 0x00, 0x21, 0x1c, 0x22, 0x20, 0x46, + 0x01, 0x93, 0xdd, 0xf3, 0xf9, 0xf7, 0x01, 0x23, 0x23, 0x60, 0x1f, 0x4b, + 0x1b, 0x68, 0x43, 0xf8, 0x04, 0x4c, 0x00, 0xf0, 0x83, 0xf9, 0xad, 0xf5, + 0x9e, 0x51, 0x3c, 0x39, 0x0a, 0x46, 0x1b, 0x48, 0xff, 0xf7, 0x10, 0xff, + 0xe2, 0xf3, 0x8a, 0xf3, 0x00, 0xf0, 0x7e, 0xf8, 0x00, 0x20, 0x02, 0xf0, + 0xb7, 0xf9, 0x17, 0x4b, 0x17, 0x4c, 0x18, 0x60, 0x02, 0xf0, 0xac, 0xfb, + 0x20, 0x60, 0xff, 0xf7, 0xbf, 0xff, 0x20, 0x68, 0x00, 0xf0, 0xfa, 0xf8, + 0xe8, 0xf7, 0x86, 0xfc, 0x20, 0x68, 0x00, 0xf0, 0xe1, 0xf8, 0x00, 0x22, + 0x10, 0x48, 0x11, 0x49, 0xe2, 0xf3, 0x28, 0xf5, 0x00, 0x22, 0x10, 0x48, + 0x10, 0x49, 0xe2, 0xf3, 0x23, 0xf5, 0x10, 0x49, 0x00, 0x22, 0x10, 0x48, + 0xe2, 0xf3, 0x1e, 0xf5, 0x20, 0x68, 0xff, 0xf7, 0xe1, 0xfe, 0xff, 0xf7, + 0x1f, 0xff, 0x20, 0x68, 0x1c, 0xbd, 0x00, 0xbf, 0xfc, 0x07, 0x02, 0x00, + 0xad, 0xde, 0xad, 0xde, 0xe4, 0xfe, 0x01, 0x00, 0xe8, 0x35, 0x03, 0x00, + 0x20, 0x08, 0x02, 0x00, 0x8c, 0x26, 0x00, 0x00, 0xd8, 0x1f, 0x86, 0x00, + 0x7d, 0xc5, 0x00, 0x00, 0xdb, 0x1f, 0x86, 0x00, 0x65, 0x65, 0x80, 0x00, + 0x8d, 0x60, 0x80, 0x00, 0xde, 0x1f, 0x86, 0x00, 0x70, 0xb5, 0x1c, 0x4c, + 0xa6, 0x68, 0x00, 0x2e, 0x33, 0xd1, 0x12, 0x09, 0x22, 0x60, 0xa3, 0x81, + 0x02, 0xf5, 0x61, 0x42, 0x4f, 0xf4, 0xe1, 0x33, 0x92, 0xfb, 0xf3, 0xf5, + 0xa0, 0x60, 0x61, 0x60, 0x20, 0x46, 0x03, 0x21, 0x80, 0x22, 0xe2, 0xf3, + 0xcb, 0xf4, 0x20, 0x46, 0x31, 0x46, 0xea, 0xb2, 0xe2, 0xf3, 0xc6, 0xf4, + 0x20, 0x46, 0x01, 0x21, 0x2a, 0x12, 0xe2, 0xf3, 0xc1, 0xf4, 0x03, 0x21, + 0x20, 0x46, 0x0a, 0x46, 0xe2, 0xf3, 0xbc, 0xf4, 0x01, 0x21, 0x20, 0x46, + 0x0a, 0x46, 0xe2, 0xf3, 0xb7, 0xf4, 0x20, 0x46, 0x04, 0x21, 0x08, 0x22, + 0xe2, 0xf3, 0xb2, 0xf4, 0x20, 0x46, 0x02, 0x21, 0x01, 0x22, 0xe2, 0xf3, + 0xad, 0xf4, 0x4f, 0xf4, 0x7a, 0x70, 0xbd, 0xe8, 0x70, 0x40, 0xe2, 0xf3, + 0xf7, 0xb2, 0x70, 0xbd, 0x24, 0x08, 0x02, 0x00, 0x38, 0xb5, 0xa4, 0x20, + 0x00, 0x21, 0xe2, 0xf3, 0x49, 0xf1, 0x13, 0x4c, 0x20, 0x60, 0x00, 0xb3, + 0x00, 0x21, 0xa4, 0x22, 0xdd, 0xf3, 0x5c, 0xf7, 0x4f, 0xf4, 0x80, 0x60, + 0x00, 0x21, 0x25, 0x68, 0xe2, 0xf3, 0x3c, 0xf1, 0xa8, 0x60, 0x20, 0x68, + 0x85, 0x68, 0x2d, 0xb9, 0xe2, 0xf3, 0x9c, 0xf0, 0x25, 0x60, 0x4f, 0xf0, + 0xff, 0x30, 0x38, 0xbd, 0x4f, 0xf4, 0x80, 0x62, 0xc2, 0x60, 0x45, 0x61, + 0x00, 0x21, 0x28, 0x46, 0xdd, 0xf3, 0x44, 0xf7, 0x22, 0x68, 0x04, 0x4b, + 0x00, 0x20, 0x1a, 0x60, 0x38, 0xbd, 0x4f, 0xf0, 0xff, 0x30, 0x38, 0xbd, + 0x34, 0x08, 0x02, 0x00, 0xd4, 0x26, 0x00, 0x00, 0x70, 0xb5, 0x1b, 0x4d, + 0x04, 0x46, 0x2b, 0x68, 0x33, 0xb9, 0x1a, 0x4e, 0x33, 0x68, 0x0b, 0xb9, + 0xff, 0xf7, 0xc6, 0xff, 0x33, 0x68, 0x2b, 0x60, 0x28, 0x68, 0x17, 0x4b, + 0x58, 0x61, 0x30, 0xb3, 0x00, 0x23, 0x03, 0x60, 0xc0, 0xf8, 0x9c, 0x30, + 0x43, 0x60, 0x23, 0x6c, 0x0e, 0x3b, 0x01, 0x2b, 0x03, 0xd9, 0x20, 0x46, + 0x11, 0x49, 0xff, 0xf7, 0xa5, 0xfd, 0x11, 0x4b, 0x9a, 0x68, 0x12, 0xb1, + 0x2a, 0x68, 0xc2, 0xf8, 0x9c, 0x30, 0x00, 0x24, 0x07, 0xe0, 0xd2, 0xf8, + 0x9c, 0x00, 0x18, 0xb1, 0x93, 0x68, 0x19, 0x5d, 0xe2, 0xf3, 0x52, 0xf4, + 0x01, 0x34, 0x2a, 0x68, 0x13, 0x69, 0x9c, 0x42, 0xf3, 0xd3, 0x08, 0x48, + 0x08, 0x49, 0xe2, 0xf3, 0x5d, 0xf4, 0x01, 0x4b, 0x18, 0x68, 0x70, 0xbd, + 0xd4, 0x26, 0x00, 0x00, 0x34, 0x08, 0x02, 0x00, 0xfc, 0x07, 0x02, 0x00, + 0xf9, 0x40, 0x02, 0x00, 0x24, 0x08, 0x02, 0x00, 0xbd, 0x21, 0x86, 0x00, + 0xa5, 0x68, 0x80, 0x00, 0x10, 0xb5, 0x40, 0x22, 0x00, 0x23, 0x06, 0x49, + 0x04, 0x46, 0xff, 0xf7, 0xd5, 0xfd, 0x05, 0x4b, 0x00, 0x22, 0x20, 0x46, + 0x9a, 0x60, 0xbd, 0xe8, 0x10, 0x40, 0xff, 0xf7, 0xab, 0xbf, 0x00, 0xbf, + 0xa9, 0x69, 0x80, 0x00, 0x24, 0x08, 0x02, 0x00, 0x2d, 0xe9, 0xf0, 0x41, + 0x04, 0x46, 0x00, 0xf0, 0xd5, 0xf8, 0x2a, 0x48, 0xe8, 0xf7, 0x00, 0xf8, + 0x20, 0x46, 0xe8, 0xf7, 0xf3, 0xfb, 0x28, 0x4b, 0x28, 0x4a, 0xc3, 0x18, + 0xb3, 0xfb, 0xf2, 0xf3, 0x27, 0x4a, 0x20, 0x46, 0x13, 0x60, 0xe8, 0xf7, + 0x06, 0xfe, 0x00, 0xf5, 0x78, 0x70, 0x07, 0x30, 0x24, 0x4b, 0x4f, 0xf4, + 0x7a, 0x75, 0xb0, 0xfb, 0xf5, 0xf0, 0x18, 0x60, 0x23, 0x6a, 0x22, 0x49, + 0x00, 0x2b, 0x40, 0xf2, 0xff, 0x33, 0xc8, 0xbf, 0x6f, 0xf0, 0x7f, 0x43, + 0xb3, 0xfb, 0xf0, 0xf0, 0x1e, 0x4b, 0x20, 0x22, 0x18, 0x60, 0x00, 0x23, + 0x20, 0x46, 0xff, 0xf7, 0x99, 0xfd, 0x00, 0x20, 0x1b, 0x49, 0xde, 0xf3, + 0x47, 0xf3, 0x1b, 0x4f, 0x06, 0x46, 0x38, 0x60, 0xf8, 0xb1, 0x20, 0x46, + 0xe8, 0xf7, 0xc4, 0xfb, 0xb6, 0xfb, 0xf0, 0xf8, 0xa8, 0xf1, 0x02, 0x08, + 0xb8, 0xf1, 0x00, 0x0f, 0x15, 0xdd, 0x15, 0x4e, 0x00, 0x21, 0x34, 0x22, + 0x30, 0x46, 0xdd, 0xf3, 0x97, 0xf6, 0x13, 0x4b, 0x74, 0x60, 0xb3, 0x60, + 0x30, 0x46, 0x05, 0xfb, 0x08, 0xf1, 0x01, 0x22, 0xe1, 0xf3, 0x68, 0xf7, + 0x28, 0xb1, 0x39, 0x68, 0x20, 0x46, 0xbd, 0xe8, 0xf0, 0x41, 0xe0, 0xf3, + 0x71, 0xb2, 0xbd, 0xe8, 0xf0, 0x81, 0x00, 0xbf, 0x79, 0xc7, 0x00, 0x00, + 0x3f, 0x42, 0x0f, 0x00, 0x40, 0x42, 0x0f, 0x00, 0xd0, 0x25, 0x00, 0x00, + 0xc8, 0x25, 0x00, 0x00, 0x01, 0x67, 0x80, 0x00, 0xcc, 0x25, 0x00, 0x00, + 0x1e, 0xc9, 0x01, 0x00, 0xe8, 0x26, 0x00, 0x00, 0x3c, 0x08, 0x02, 0x00, + 0xe5, 0x66, 0x80, 0x00, 0x0d, 0x4b, 0x00, 0x21, 0x1a, 0x68, 0x42, 0xf0, + 0x10, 0x02, 0x1a, 0x60, 0x1a, 0x68, 0x22, 0xf4, 0x00, 0x72, 0x1a, 0x60, + 0x09, 0x4a, 0x13, 0x68, 0x43, 0xf0, 0x80, 0x73, 0x43, 0xf4, 0x80, 0x33, + 0x13, 0x60, 0x07, 0x4b, 0x07, 0x22, 0x1a, 0x60, 0x43, 0xf8, 0x04, 0x1c, + 0x59, 0x68, 0x5a, 0x60, 0x04, 0x4b, 0x20, 0x22, 0x1a, 0x60, 0x70, 0x47, + 0x14, 0xed, 0x00, 0xe0, 0xfc, 0xed, 0x00, 0xe0, 0x24, 0x10, 0x00, 0xe0, + 0x00, 0xe4, 0x00, 0xe0, 0x2d, 0xe9, 0xf8, 0x43, 0x04, 0x46, 0x1e, 0x46, + 0x90, 0x46, 0x0d, 0x46, 0xe6, 0xf3, 0x9c, 0xf6, 0x20, 0x46, 0xe6, 0xf3, + 0x5d, 0xf5, 0x41, 0x46, 0x32, 0x46, 0x07, 0x46, 0x20, 0x46, 0xe6, 0xf3, + 0x17, 0xf7, 0x20, 0x46, 0xe6, 0xf3, 0xd0, 0xf5, 0x40, 0xf6, 0x2a, 0x01, + 0x06, 0x46, 0x00, 0x22, 0x20, 0x46, 0xe6, 0xf3, 0x0d, 0xf7, 0x4f, 0xf0, + 0x01, 0x08, 0x81, 0x46, 0x85, 0xb1, 0x08, 0xfa, 0x06, 0xf5, 0x83, 0x69, + 0x33, 0xea, 0x05, 0x05, 0x02, 0xd1, 0x40, 0x46, 0xe7, 0xf7, 0x0c, 0xff, + 0x01, 0x36, 0x01, 0x20, 0xb0, 0x40, 0xe7, 0xf7, 0xe9, 0xfe, 0xc9, 0xf8, + 0x18, 0x50, 0x0e, 0xe0, 0x70, 0x1c, 0x08, 0xfa, 0x06, 0xf6, 0x08, 0xfa, + 0x00, 0xf0, 0xe7, 0xf7, 0xfd, 0xfe, 0x40, 0x46, 0xe7, 0xf7, 0xdc, 0xfe, + 0xd9, 0xf8, 0x18, 0x30, 0x1e, 0x43, 0xc9, 0xf8, 0x18, 0x60, 0x20, 0x46, + 0x39, 0x46, 0xbd, 0xe8, 0xf8, 0x43, 0xe6, 0xf3, 0xf5, 0xb6, 0x00, 0x00, + 0x2d, 0xe9, 0xf8, 0x43, 0x04, 0x46, 0xe6, 0xf3, 0x59, 0xf6, 0x20, 0x46, + 0x40, 0xf6, 0x0e, 0x01, 0x00, 0x22, 0xe6, 0xf3, 0xd7, 0xf6, 0x05, 0x46, + 0x00, 0x28, 0x2f, 0xd0, 0x07, 0x68, 0xd0, 0xf8, 0x00, 0x80, 0x20, 0x46, + 0xe6, 0xf3, 0x20, 0xf5, 0x04, 0x28, 0x06, 0x46, 0x05, 0xd8, 0x25, 0xd1, + 0x08, 0xf4, 0xe0, 0x28, 0xb8, 0xf5, 0x40, 0x3f, 0x20, 0xd1, 0x00, 0x20, + 0x44, 0x49, 0xde, 0xf3, 0x7f, 0xf2, 0xd8, 0xb9, 0x07, 0xf0, 0xf0, 0x07, + 0x3f, 0x09, 0x0f, 0xe0, 0x01, 0x3f, 0x07, 0x2e, 0x2f, 0x61, 0x08, 0xd9, + 0x0c, 0x2e, 0x06, 0xd0, 0x2b, 0x6c, 0x03, 0xf4, 0x40, 0x63, 0xb3, 0xf5, + 0x40, 0x6f, 0x00, 0xd0, 0x10, 0xb1, 0x3b, 0x4b, 0x01, 0x20, 0x6b, 0x61, + 0x00, 0x2f, 0xed, 0xd1, 0xd5, 0xf8, 0xe8, 0x31, 0x23, 0xf0, 0x10, 0x03, + 0xc5, 0xf8, 0xe8, 0x31, 0x00, 0x22, 0x40, 0xf6, 0x2a, 0x01, 0x20, 0x46, + 0xe6, 0xf3, 0x9e, 0xf6, 0x33, 0x4d, 0x40, 0xf2, 0xdd, 0x56, 0x28, 0x60, + 0x20, 0x46, 0xe6, 0xf3, 0xe9, 0xf4, 0x31, 0x4b, 0x18, 0x60, 0x2b, 0x68, + 0x1a, 0x68, 0x42, 0xf0, 0x80, 0x72, 0x1a, 0x60, 0x1a, 0x68, 0x42, 0xf0, + 0x02, 0x02, 0x1a, 0x60, 0x00, 0x22, 0xc3, 0xf8, 0xe0, 0x21, 0x02, 0xe0, + 0x0a, 0x20, 0xe2, 0xf3, 0x33, 0xf1, 0x2b, 0x68, 0xd3, 0xf8, 0xe0, 0x31, + 0x9b, 0x03, 0x01, 0xd4, 0x01, 0x3e, 0xf5, 0xd1, 0x00, 0x21, 0x0b, 0x46, + 0x20, 0x46, 0x4f, 0xf4, 0x00, 0x62, 0xff, 0xf7, 0x4f, 0xff, 0x00, 0x21, + 0x0b, 0x46, 0x20, 0x46, 0x40, 0xf6, 0x12, 0x02, 0xff, 0xf7, 0x48, 0xff, + 0x00, 0x21, 0x0b, 0x46, 0x20, 0x46, 0x40, 0xf6, 0x29, 0x02, 0xff, 0xf7, + 0x41, 0xff, 0x20, 0x46, 0x01, 0x21, 0xe8, 0xf7, 0x77, 0xfa, 0x00, 0x20, + 0x18, 0x49, 0xde, 0xf3, 0x1f, 0xf2, 0xf0, 0xb1, 0x20, 0x46, 0xe6, 0xf3, + 0x9d, 0xf4, 0x40, 0xf6, 0x2a, 0x01, 0x06, 0x46, 0x00, 0x22, 0x20, 0x46, + 0xe6, 0xf3, 0x56, 0xf6, 0xd0, 0xf8, 0x14, 0x90, 0x07, 0x46, 0xd0, 0xf8, + 0x98, 0x80, 0x20, 0x46, 0xe6, 0xf3, 0x8e, 0xf4, 0x01, 0x23, 0x83, 0x40, + 0x43, 0xea, 0x09, 0x03, 0x7b, 0x61, 0x48, 0xf0, 0x01, 0x03, 0xc7, 0xf8, + 0x98, 0x30, 0x20, 0x46, 0x31, 0x46, 0xe6, 0xf3, 0x53, 0xf6, 0x2b, 0x68, + 0x1a, 0x6a, 0x42, 0xf0, 0x03, 0x02, 0x1a, 0x62, 0xbd, 0xe8, 0xf8, 0x83, + 0x29, 0xc9, 0x01, 0x00, 0xff, 0x7f, 0x01, 0x21, 0x70, 0x08, 0x02, 0x00, + 0x74, 0x08, 0x02, 0x00, 0x1e, 0xc9, 0x01, 0x00, 0x10, 0xb5, 0x84, 0x69, + 0xa0, 0x68, 0xfc, 0xf7, 0x83, 0xfd, 0xe0, 0x68, 0xe8, 0xf7, 0x1b, 0xfc, + 0x00, 0x20, 0x10, 0xbd, 0x10, 0xb5, 0x84, 0x69, 0x00, 0x21, 0x34, 0x22, + 0x04, 0xf1, 0x1c, 0x00, 0xdd, 0xf3, 0x40, 0xf5, 0x03, 0x4b, 0xa0, 0x68, + 0x63, 0x62, 0x24, 0x62, 0xeb, 0xf7, 0xea, 0xf8, 0x00, 0x20, 0x10, 0xbd, + 0x05, 0xaa, 0x80, 0x00, 0x2d, 0xe9, 0xf3, 0x47, 0x25, 0x4d, 0x99, 0x46, + 0x2b, 0x68, 0x06, 0x46, 0x07, 0x2b, 0x0f, 0x46, 0x92, 0x46, 0x3d, 0xdc, + 0x01, 0xf0, 0xfe, 0xfe, 0x50, 0x21, 0x80, 0x46, 0xe2, 0xf3, 0x6e, 0xf3, + 0x04, 0x46, 0x00, 0x28, 0x37, 0xd0, 0x00, 0x21, 0x50, 0x22, 0xdd, 0xf3, + 0x1f, 0xf5, 0x2b, 0x68, 0xa4, 0xf8, 0x14, 0x90, 0x84, 0xe8, 0x48, 0x00, + 0x27, 0x61, 0xc4, 0xf8, 0x0c, 0x80, 0x20, 0x46, 0x41, 0xf2, 0xe4, 0x41, + 0x4a, 0x46, 0x43, 0x46, 0x8d, 0xe8, 0x80, 0x04, 0xfc, 0xf7, 0xea, 0xfb, + 0xa0, 0x60, 0xf8, 0xb1, 0x00, 0x20, 0x0a, 0x99, 0x0b, 0x9a, 0x11, 0x4b, + 0x8d, 0xe8, 0x40, 0x04, 0xff, 0xf7, 0xb4, 0xfc, 0x18, 0xb1, 0xa0, 0x68, + 0xfc, 0xf7, 0x36, 0xfd, 0x10, 0xe0, 0xa0, 0x68, 0xe4, 0xf3, 0x00, 0xf7, + 0x0b, 0x49, 0xa0, 0x61, 0x2a, 0x68, 0x30, 0x46, 0xdd, 0xf3, 0x4a, 0xf5, + 0x09, 0x48, 0x31, 0x46, 0xeb, 0xf7, 0xc4, 0xf8, 0x2b, 0x68, 0x01, 0x33, + 0x2b, 0x60, 0x02, 0xe0, 0x00, 0x24, 0x00, 0xe0, 0x04, 0x46, 0x20, 0x46, + 0xbd, 0xe8, 0xfc, 0x87, 0x78, 0x08, 0x02, 0x00, 0x31, 0xaa, 0x80, 0x00, + 0xe8, 0x8d, 0x02, 0x00, 0xc8, 0x8d, 0x02, 0x00, 0x01, 0x46, 0x80, 0x68, + 0x50, 0x22, 0xe2, 0xf3, 0x33, 0xb3, 0x00, 0x00, 0x2d, 0xe9, 0xf0, 0x41, + 0xdf, 0xf8, 0x68, 0x80, 0x1f, 0x46, 0x98, 0xf8, 0x00, 0x30, 0x05, 0x46, + 0x07, 0x2b, 0x14, 0x46, 0x21, 0xd8, 0x38, 0x46, 0x4c, 0x21, 0xe2, 0xf3, + 0x13, 0xf3, 0x06, 0x46, 0xe0, 0xb1, 0x00, 0x21, 0x4c, 0x22, 0xdd, 0xf3, + 0xc5, 0xf4, 0x98, 0xf8, 0x00, 0x30, 0xb4, 0x60, 0x86, 0xf8, 0x44, 0x30, + 0x01, 0x33, 0x88, 0xf8, 0x00, 0x30, 0x02, 0x23, 0x86, 0xe8, 0xa0, 0x00, + 0xb3, 0x64, 0x38, 0x46, 0x08, 0x21, 0xe2, 0xf3, 0xfd, 0xf2, 0x04, 0x46, + 0x30, 0x64, 0x40, 0xb1, 0x00, 0x21, 0x08, 0x22, 0xdd, 0xf3, 0xae, 0xf4, + 0x00, 0xe0, 0x00, 0x26, 0x30, 0x46, 0xbd, 0xe8, 0xf0, 0x81, 0x31, 0x46, + 0x4c, 0x22, 0xe2, 0xf3, 0xfd, 0xf2, 0x26, 0x46, 0xf6, 0xe7, 0x00, 0xbf, + 0x7c, 0x08, 0x02, 0x00, 0xc2, 0x6b, 0x1a, 0xb1, 0x00, 0x23, 0x53, 0x62, + 0x82, 0x6b, 0x53, 0x62, 0xc0, 0x68, 0xff, 0xf7, 0xb7, 0xbf, 0x00, 0x00, + 0x2d, 0xe9, 0xf0, 0x4f, 0xd1, 0xf8, 0xfc, 0x30, 0x91, 0xb0, 0x0b, 0x93, + 0x03, 0xf5, 0x60, 0x63, 0x04, 0x46, 0x09, 0x93, 0x3c, 0xe1, 0x0e, 0x22, + 0x00, 0x23, 0x20, 0x46, 0x0b, 0xa9, 0xdb, 0xf3, 0xc9, 0xf6, 0x0f, 0x28, + 0x06, 0x46, 0x00, 0xf0, 0x3b, 0x81, 0x00, 0x22, 0x20, 0x46, 0x0b, 0xa9, + 0x13, 0x46, 0xdb, 0xf3, 0xbf, 0xf6, 0x10, 0xf0, 0x0e, 0x0f, 0x40, 0xf0, + 0x2e, 0x81, 0x9a, 0x4b, 0x00, 0xf4, 0xf8, 0x77, 0x33, 0x40, 0x40, 0xf2, + 0x3b, 0x42, 0x1b, 0x0a, 0x3f, 0x09, 0xb2, 0xeb, 0x16, 0x5f, 0x04, 0xd1, + 0x40, 0xf6, 0xff, 0x72, 0x93, 0x42, 0x00, 0xf0, 0x19, 0x81, 0x00, 0xf4, + 0x78, 0x52, 0x51, 0x0a, 0x08, 0x91, 0x00, 0x2a, 0x00, 0xf0, 0x12, 0x81, + 0x00, 0xf4, 0xf8, 0x2b, 0x00, 0xf4, 0x78, 0x02, 0xd2, 0x0c, 0x4f, 0xea, + 0x9b, 0x3b, 0x07, 0x92, 0x12, 0xeb, 0x0b, 0x02, 0x19, 0xd1, 0x40, 0xf2, + 0x67, 0x31, 0x8b, 0x42, 0x40, 0xf0, 0x02, 0x81, 0x0c, 0xab, 0x01, 0x93, + 0x0d, 0xab, 0x02, 0x93, 0x0e, 0xab, 0x03, 0x93, 0x0f, 0xab, 0x04, 0x93, + 0x20, 0x46, 0x0b, 0xa9, 0x13, 0x46, 0x00, 0x92, 0xdb, 0xf3, 0x24, 0xf6, + 0x00, 0x28, 0x00, 0xf0, 0xf1, 0x80, 0x0c, 0x9b, 0xc4, 0xf8, 0x54, 0x33, + 0xec, 0xe0, 0xd4, 0xf8, 0xcc, 0x50, 0x04, 0xeb, 0x85, 0x02, 0xc2, 0xf8, + 0xd4, 0x62, 0xc2, 0xf8, 0x14, 0x03, 0x05, 0xf1, 0x34, 0x02, 0x44, 0xf8, + 0x22, 0x30, 0x00, 0x26, 0x0b, 0xe0, 0x01, 0x22, 0x20, 0x46, 0x0b, 0xa9, + 0x13, 0x46, 0xdb, 0xf3, 0x6b, 0xf6, 0x00, 0xf0, 0x0e, 0x00, 0x02, 0x28, + 0x40, 0xf0, 0xd9, 0x80, 0x01, 0x36, 0xbe, 0x42, 0xf1, 0xd1, 0x00, 0x27, + 0x3a, 0x46, 0x0c, 0xae, 0x0d, 0xf1, 0x34, 0x08, 0x0d, 0xf1, 0x38, 0x09, + 0x0d, 0xf1, 0x3c, 0x0a, 0x20, 0x46, 0x0b, 0xa9, 0x3b, 0x46, 0x00, 0x97, + 0x01, 0x96, 0xcd, 0xf8, 0x08, 0x80, 0xcd, 0xf8, 0x0c, 0x90, 0xcd, 0xf8, + 0x10, 0xa0, 0xdb, 0xf3, 0xeb, 0xf5, 0x02, 0x46, 0xc0, 0xb9, 0x40, 0x23, + 0x8d, 0xe8, 0x48, 0x03, 0x20, 0x46, 0x0b, 0xa9, 0x13, 0x46, 0xcd, 0xf8, + 0x10, 0xa0, 0xdb, 0xf3, 0xdf, 0xf5, 0x60, 0xb9, 0x0d, 0x9b, 0x00, 0x2b, + 0x40, 0xf0, 0xaf, 0x80, 0x0f, 0x9f, 0x00, 0x2f, 0x40, 0xf0, 0xab, 0x80, + 0x0e, 0x9b, 0xb3, 0xf5, 0x80, 0x5f, 0x01, 0xd0, 0xa5, 0xe0, 0x01, 0x27, + 0x0c, 0x9a, 0x05, 0xf1, 0x44, 0x03, 0x44, 0xf8, 0x23, 0x20, 0x0e, 0x9a, + 0x05, 0xf1, 0x74, 0x03, 0x44, 0xf8, 0x23, 0x20, 0x01, 0x26, 0x0c, 0xab, + 0x01, 0x93, 0x0d, 0xab, 0x02, 0x93, 0x0e, 0xab, 0x03, 0x93, 0x0f, 0xab, + 0x00, 0x22, 0x04, 0x93, 0x20, 0x46, 0x0b, 0xa9, 0x33, 0x46, 0x00, 0x92, + 0xdb, 0xf3, 0xb6, 0xf5, 0x70, 0xb1, 0x01, 0x2e, 0x0c, 0xd1, 0x0e, 0x9b, + 0xb3, 0xf5, 0x80, 0x5f, 0x08, 0xd1, 0x0c, 0x99, 0x05, 0xf1, 0x64, 0x02, + 0x44, 0xf8, 0x22, 0x10, 0x05, 0xf1, 0x84, 0x02, 0x44, 0xf8, 0x22, 0x30, + 0x01, 0x36, 0x00, 0x28, 0xdd, 0xd1, 0x01, 0x26, 0x19, 0xe0, 0x43, 0x46, + 0x00, 0xe0, 0x00, 0x23, 0x00, 0x22, 0x00, 0x92, 0x0c, 0xaa, 0x01, 0x92, + 0x0d, 0xaa, 0x02, 0x92, 0x0e, 0xaa, 0x03, 0x92, 0x0f, 0xaa, 0x04, 0x92, + 0x20, 0x46, 0x0b, 0xa9, 0x32, 0x46, 0x03, 0xf1, 0x01, 0x08, 0xdb, 0xf3, + 0x8d, 0xf5, 0x00, 0x28, 0xe9, 0xd1, 0xb8, 0xf1, 0x00, 0x0f, 0x5c, 0xd0, + 0x01, 0x36, 0x08, 0x9a, 0x96, 0x42, 0xe4, 0xd1, 0x00, 0x26, 0x1f, 0xe0, + 0xc0, 0x23, 0x00, 0x93, 0x0c, 0xab, 0x01, 0x93, 0x0d, 0xab, 0x02, 0x93, + 0x0e, 0xab, 0x03, 0x93, 0x0f, 0xab, 0x04, 0x93, 0x20, 0x46, 0x0b, 0xa9, + 0x32, 0x46, 0x00, 0x23, 0xdb, 0xf3, 0x72, 0xf5, 0x00, 0x28, 0x44, 0xd0, + 0x0f, 0x9b, 0x00, 0x2b, 0x41, 0xd1, 0x0e, 0x9b, 0xb3, 0xf5, 0x80, 0x5f, + 0x3d, 0xd1, 0x26, 0xb9, 0x0c, 0x9a, 0x04, 0xeb, 0x85, 0x03, 0xc3, 0xf8, + 0x94, 0x22, 0x01, 0x36, 0x5e, 0x45, 0xdd, 0xd1, 0x00, 0x26, 0x24, 0xe0, + 0x80, 0x23, 0x00, 0x93, 0x0c, 0xab, 0x01, 0x93, 0x0d, 0xab, 0x02, 0x93, + 0x0e, 0xab, 0x03, 0x93, 0x0f, 0xab, 0x04, 0x93, 0x08, 0x9b, 0x20, 0x46, + 0x01, 0x2b, 0x0c, 0xbf, 0x32, 0x46, 0x72, 0x1c, 0x0b, 0xa9, 0x00, 0x23, + 0xdb, 0xf3, 0x4a, 0xf5, 0xe8, 0xb1, 0x0f, 0x9b, 0xdb, 0xb9, 0x0e, 0x9b, + 0xb3, 0xf5, 0x80, 0x5f, 0x17, 0xd1, 0xbb, 0xf1, 0x00, 0x0f, 0x05, 0xd1, + 0x26, 0xb9, 0x0c, 0x9a, 0x04, 0xeb, 0x85, 0x03, 0xc3, 0xf8, 0x94, 0x22, + 0x01, 0x36, 0x07, 0x99, 0x8e, 0x42, 0xd7, 0xd1, 0x27, 0xb9, 0xd4, 0xf8, + 0xcc, 0x30, 0x01, 0x33, 0xc4, 0xf8, 0xcc, 0x30, 0x0b, 0x9b, 0x09, 0x9a, + 0x93, 0x42, 0xff, 0xf4, 0xbe, 0xae, 0x00, 0x23, 0xc4, 0xf8, 0xcc, 0x30, + 0x11, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, 0x00, 0xbf, 0x00, 0xff, 0x0f, 0x00, + 0x82, 0x60, 0x41, 0x60, 0x01, 0x60, 0x70, 0x47, 0x0e, 0xb4, 0xf3, 0xb5, + 0x81, 0x68, 0x04, 0x46, 0x01, 0x29, 0x45, 0xd9, 0x08, 0xab, 0x40, 0x68, + 0x07, 0x9a, 0x01, 0x93, 0xdd, 0xf3, 0x66, 0xf4, 0x43, 0x1c, 0x06, 0x46, + 0x03, 0xd0, 0xa3, 0x68, 0x02, 0x3b, 0x98, 0x42, 0x02, 0xdd, 0x00, 0x20, + 0xa0, 0x60, 0x36, 0xe0, 0x60, 0x68, 0x3d, 0x21, 0xdd, 0xf3, 0x86, 0xf3, + 0x40, 0xb3, 0x67, 0x68, 0x25, 0x68, 0xc7, 0x1b, 0x21, 0xe0, 0x28, 0x46, + 0x3a, 0x46, 0xdd, 0xf3, 0x99, 0xf2, 0xb0, 0xb9, 0xeb, 0x5d, 0x3d, 0x2b, + 0x13, 0xd1, 0x28, 0x46, 0xdd, 0xf3, 0xa2, 0xf3, 0x62, 0x68, 0x47, 0x1c, + 0x73, 0x1c, 0xdb, 0x1b, 0x52, 0x1b, 0xe9, 0x19, 0xd2, 0x18, 0x28, 0x46, + 0xdd, 0xf3, 0xda, 0xf2, 0x63, 0x68, 0xdb, 0x1b, 0x63, 0x60, 0xa3, 0x68, + 0xdf, 0x19, 0xa7, 0x60, 0x08, 0xe0, 0x2b, 0x46, 0x13, 0xf8, 0x01, 0x2b, + 0x1d, 0x46, 0x00, 0x2a, 0xfa, 0xd1, 0x61, 0x68, 0x8d, 0x42, 0xda, 0xd3, + 0xa3, 0x68, 0x70, 0x1c, 0x1b, 0x1a, 0xa3, 0x60, 0x63, 0x68, 0x1b, 0x18, + 0x63, 0x60, 0x00, 0xe0, 0x00, 0x20, 0xbd, 0xe8, 0xfc, 0x40, 0x03, 0xb0, + 0x70, 0x47, 0x2d, 0xe9, 0xf0, 0x41, 0x55, 0x1a, 0x01, 0x2d, 0x0c, 0x46, + 0x1f, 0x46, 0x06, 0x9e, 0x0e, 0xdd, 0x29, 0x46, 0xe2, 0xf3, 0x28, 0xf1, + 0x80, 0x46, 0x70, 0xb1, 0x21, 0x46, 0x2a, 0x46, 0xdd, 0xf3, 0x76, 0xf2, + 0xc7, 0xf8, 0x00, 0x80, 0x00, 0x20, 0x35, 0x60, 0xbd, 0xe8, 0xf0, 0x81, + 0x00, 0x20, 0x18, 0x60, 0x30, 0x60, 0xbd, 0xe8, 0xf0, 0x81, 0x6f, 0xf0, + 0x1a, 0x00, 0xbd, 0xe8, 0xf0, 0x81, 0x00, 0x00, 0x2d, 0xe9, 0xf0, 0x4f, + 0xa7, 0xb0, 0x0e, 0x91, 0x4f, 0xf4, 0x80, 0x51, 0x0d, 0x90, 0x0f, 0x92, + 0x10, 0x93, 0xe2, 0xf3, 0x07, 0xf1, 0x09, 0x90, 0x00, 0x28, 0x01, 0xf0, + 0xdf, 0x80, 0x23, 0xa8, 0x09, 0x99, 0x4f, 0xf4, 0x80, 0x52, 0xff, 0xf7, + 0x75, 0xff, 0x4f, 0xf4, 0x80, 0x52, 0x09, 0x98, 0x00, 0x21, 0xdd, 0xf3, + 0xaf, 0xf2, 0x00, 0x23, 0x4f, 0xf0, 0xff, 0x32, 0x8d, 0xf8, 0x4c, 0x30, + 0x07, 0x92, 0x0b, 0x93, 0x08, 0x93, 0x01, 0xf0, 0x94, 0xb8, 0x0e, 0x9b, + 0x01, 0x22, 0x53, 0xf8, 0x04, 0x5b, 0x0c, 0x92, 0x0e, 0x93, 0x00, 0x23, + 0x0a, 0x93, 0x0c, 0x9a, 0x15, 0xf8, 0x03, 0xb0, 0x42, 0xb1, 0x0b, 0xf1, + 0xff, 0x32, 0xd2, 0xb2, 0x5f, 0x1c, 0xfd, 0x2a, 0x0d, 0xd8, 0xee, 0x5d, + 0x9f, 0x1c, 0x0b, 0xe0, 0x0b, 0xf1, 0xff, 0x32, 0xd2, 0xb2, 0xfd, 0x2a, + 0x96, 0xbf, 0x5e, 0x46, 0x0c, 0x9e, 0x4f, 0xf0, 0x80, 0x0b, 0x5f, 0x1c, + 0x00, 0xe0, 0x00, 0x26, 0xbb, 0x19, 0xb3, 0xf5, 0x60, 0x7f, 0x81, 0xf2, + 0x6b, 0x80, 0xbb, 0xf1, 0x20, 0x0f, 0x28, 0xd0, 0x07, 0xd8, 0xbb, 0xf1, + 0x15, 0x0f, 0x0d, 0xd0, 0xbb, 0xf1, 0x1b, 0x0f, 0x41, 0xf0, 0x5a, 0x80, + 0x5f, 0xe0, 0xbb, 0xf1, 0x22, 0x0f, 0x33, 0xd0, 0x2e, 0xd3, 0xbb, 0xf1, + 0x80, 0x0f, 0x41, 0xf0, 0x51, 0x80, 0x5c, 0xe0, 0xeb, 0x19, 0x5a, 0x78, + 0xeb, 0x5d, 0x12, 0x02, 0xd3, 0x18, 0x07, 0x2b, 0x0f, 0xdd, 0xbc, 0x1c, + 0x2c, 0x19, 0x83, 0x49, 0x22, 0x46, 0x23, 0xa8, 0xff, 0xf7, 0x20, 0xff, + 0x20, 0x46, 0xdd, 0xf3, 0xe9, 0xf2, 0xfa, 0x1c, 0x12, 0x18, 0x7f, 0x49, + 0x23, 0xa8, 0xaa, 0x18, 0x0e, 0xe0, 0xec, 0x19, 0x62, 0x78, 0xeb, 0x5d, + 0x12, 0x02, 0xd2, 0x18, 0x7b, 0x49, 0x23, 0xa8, 0xff, 0xf7, 0x0e, 0xff, + 0xe3, 0x78, 0xa2, 0x78, 0x79, 0x49, 0x1b, 0x02, 0x23, 0xa8, 0x9a, 0x18, + 0xff, 0xf7, 0x06, 0xff, 0x01, 0xf0, 0x26, 0xb8, 0xeb, 0x5d, 0x0a, 0x93, + 0x01, 0xf0, 0x22, 0xb8, 0x0a, 0x9a, 0x0c, 0x2a, 0x00, 0xf0, 0xef, 0x87, + 0x9d, 0xf8, 0x4c, 0x30, 0x00, 0x2b, 0x41, 0xf0, 0x19, 0x80, 0xeb, 0x5d, + 0x04, 0x2b, 0x41, 0xf0, 0x15, 0x80, 0x07, 0xf1, 0x02, 0x08, 0x05, 0xeb, + 0x08, 0x04, 0x20, 0x46, 0xdd, 0xf3, 0xb4, 0xf6, 0x00, 0x28, 0x41, 0xf0, + 0x0b, 0x80, 0x15, 0xf8, 0x08, 0x30, 0xd8, 0x07, 0x01, 0xf1, 0x06, 0x80, + 0x20, 0x46, 0x13, 0xa9, 0xdd, 0xf3, 0xf0, 0xf4, 0x07, 0x9b, 0x01, 0x33, + 0x40, 0xf0, 0xfe, 0x87, 0xeb, 0x19, 0x9a, 0x79, 0xdb, 0x79, 0x12, 0x02, + 0xbf, 0xe3, 0xeb, 0x19, 0xda, 0x79, 0x23, 0xa8, 0x9b, 0x79, 0x5e, 0x49, + 0xaf, 0xe0, 0xeb, 0x5d, 0xec, 0x19, 0x82, 0x2b, 0x00, 0xf2, 0xee, 0x87, + 0xdf, 0xe8, 0x13, 0xf0, 0x9b, 0x00, 0xba, 0x00, 0x30, 0x01, 0xeb, 0x01, + 0xab, 0x02, 0xe7, 0x01, 0xac, 0x01, 0xb7, 0x01, 0x3c, 0x01, 0xbf, 0x02, + 0xd3, 0x02, 0xe4, 0x02, 0xe9, 0x02, 0xec, 0x07, 0x50, 0x02, 0xdc, 0x01, + 0xec, 0x07, 0x00, 0x03, 0x1b, 0x03, 0x9f, 0x00, 0x38, 0x03, 0x3c, 0x03, + 0x4a, 0x03, 0x4e, 0x03, 0xf5, 0x00, 0x98, 0x03, 0xec, 0x07, 0x63, 0x01, + 0xb7, 0x03, 0x69, 0x01, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xbf, 0x03, + 0xd0, 0x03, 0xd3, 0x03, 0x24, 0x04, 0x06, 0x05, 0xec, 0x07, 0xec, 0x07, + 0xd6, 0x05, 0x93, 0x00, 0x8b, 0x00, 0x83, 0x00, 0x90, 0x06, 0x97, 0x06, + 0x9e, 0x06, 0xa5, 0x06, 0xec, 0x07, 0xf4, 0x02, 0x5f, 0x01, 0xec, 0x07, + 0xec, 0x07, 0xfc, 0x00, 0xb8, 0x07, 0xac, 0x06, 0xec, 0x07, 0xec, 0x07, + 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, + 0x6f, 0x01, 0xd5, 0x06, 0xe7, 0x06, 0x05, 0x07, 0x23, 0x07, 0x41, 0x07, + 0x5f, 0x07, 0x7d, 0x07, 0x9a, 0x07, 0xa1, 0x07, 0xec, 0x07, 0x74, 0x01, + 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, + 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, + 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, + 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, + 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, + 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, + 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, + 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, + 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, 0xec, 0x07, + 0xa8, 0x07, 0x4f, 0xea, 0x96, 0x0a, 0x5f, 0xfa, 0x8a, 0xfa, 0x4f, 0xf0, + 0x00, 0x08, 0x00, 0xf0, 0xc7, 0xbd, 0x4f, 0xea, 0x56, 0x09, 0x5f, 0xfa, + 0x89, 0xf9, 0x4f, 0xf0, 0x00, 0x08, 0x00, 0xf0, 0x93, 0xbd, 0x4f, 0xea, + 0x56, 0x09, 0x5f, 0xfa, 0x89, 0xf9, 0x4f, 0xf0, 0x00, 0x08, 0x00, 0xf0, + 0x7a, 0xbd, 0x23, 0xa8, 0x0c, 0x49, 0x00, 0xf0, 0x1b, 0xbf, 0xe3, 0x78, + 0x22, 0x79, 0x1b, 0x04, 0x43, 0xea, 0x02, 0x63, 0x62, 0x78, 0x09, 0x49, + 0x13, 0x43, 0xa2, 0x78, 0x23, 0xa8, 0x43, 0xea, 0x02, 0x22, 0x15, 0xe7, + 0xcc, 0x8e, 0x02, 0x00, 0x36, 0x91, 0x02, 0x00, 0x8a, 0x8e, 0x02, 0x00, + 0x2d, 0x92, 0x02, 0x00, 0xee, 0x94, 0x02, 0x00, 0x65, 0x90, 0x02, 0x00, + 0x01, 0x8e, 0x02, 0x00, 0xa2, 0x78, 0x63, 0x78, 0x12, 0x02, 0xd2, 0x18, + 0x9f, 0x49, 0x23, 0xa8, 0xff, 0xf7, 0x08, 0xfe, 0x22, 0x79, 0xe3, 0x78, + 0x12, 0x02, 0x23, 0xa8, 0x9c, 0x49, 0xd2, 0x18, 0xff, 0xf7, 0x00, 0xfe, + 0x06, 0x2e, 0x40, 0xf2, 0x1f, 0x87, 0xa2, 0x79, 0x63, 0x79, 0x12, 0x02, + 0x23, 0xa8, 0x98, 0x49, 0xd2, 0x18, 0xff, 0xf7, 0xf5, 0xfd, 0x08, 0x2e, + 0x40, 0xf2, 0x14, 0x87, 0x23, 0x7a, 0xe2, 0x79, 0x1b, 0x02, 0x23, 0xa8, + 0x93, 0x49, 0x9a, 0x18, 0xff, 0xf7, 0xea, 0xfd, 0x0a, 0x2e, 0x40, 0xf2, + 0x09, 0x87, 0x07, 0xf1, 0x0a, 0x08, 0x07, 0xf1, 0x09, 0x04, 0x15, 0xf8, + 0x08, 0x20, 0x2b, 0x5d, 0x12, 0x02, 0xd2, 0x18, 0x23, 0xa8, 0x8c, 0x49, + 0xff, 0xf7, 0xda, 0xfd, 0x15, 0xf8, 0x08, 0x30, 0x2a, 0x5d, 0x1b, 0x02, + 0x70, 0xe0, 0xa3, 0x78, 0x62, 0x78, 0x1b, 0x02, 0x9a, 0x18, 0x07, 0x92, + 0x00, 0xf0, 0xf0, 0xbe, 0x85, 0x4b, 0x06, 0x22, 0xb6, 0xfb, 0xf2, 0xf2, + 0x1a, 0x70, 0x4f, 0xf0, 0x00, 0x08, 0x99, 0x46, 0x24, 0xe0, 0x43, 0x46, + 0x10, 0x21, 0x81, 0x4a, 0x1b, 0xa8, 0xdd, 0xf3, 0x3f, 0xf1, 0x43, 0x46, + 0x10, 0x21, 0x7f, 0x4a, 0x1f, 0xa8, 0xdd, 0xf3, 0x39, 0xf1, 0x63, 0x78, + 0xa2, 0x78, 0x1b, 0xa9, 0x43, 0xea, 0x02, 0x22, 0x23, 0xa8, 0xff, 0xf7, + 0xb1, 0xfd, 0x63, 0x79, 0xa2, 0x79, 0x1b, 0x04, 0x43, 0xea, 0x02, 0x63, + 0xe2, 0x78, 0x23, 0xa8, 0x13, 0x43, 0x22, 0x79, 0x1f, 0xa9, 0x43, 0xea, + 0x02, 0x22, 0xff, 0xf7, 0xa3, 0xfd, 0x08, 0xf1, 0x01, 0x08, 0x06, 0x34, + 0x99, 0xf8, 0x00, 0x30, 0x98, 0x45, 0xd6, 0xdb, 0x00, 0xf0, 0xbc, 0xbe, + 0x02, 0x2e, 0x03, 0xd1, 0x23, 0xa8, 0x6d, 0x49, 0x00, 0xf0, 0x84, 0xbe, + 0xa3, 0x78, 0x62, 0x78, 0x1b, 0x02, 0x23, 0xa8, 0x69, 0x49, 0x84, 0xe6, + 0xa2, 0x78, 0x63, 0x78, 0x12, 0x02, 0x04, 0x2e, 0x1a, 0x44, 0x05, 0xd9, + 0x23, 0x79, 0xe1, 0x78, 0x1b, 0x06, 0x09, 0x04, 0x5b, 0x18, 0x1a, 0x43, + 0x23, 0xa8, 0x63, 0x49, 0xff, 0xf7, 0x7e, 0xfd, 0x06, 0x2e, 0x40, 0xf2, + 0x9d, 0x86, 0xeb, 0x19, 0x9a, 0x79, 0x59, 0x79, 0x12, 0x02, 0x08, 0x2e, + 0x0a, 0x44, 0x05, 0xd9, 0x19, 0x7a, 0xdb, 0x79, 0x09, 0x06, 0x1b, 0x04, + 0xc9, 0x18, 0x0a, 0x43, 0x23, 0xa8, 0x5a, 0x49, 0x62, 0xe6, 0x23, 0xa8, + 0x59, 0x49, 0x00, 0xf0, 0x57, 0xbe, 0xa3, 0x78, 0x62, 0x78, 0x1b, 0x02, + 0x23, 0xa8, 0x57, 0x49, 0x57, 0xe6, 0x01, 0x36, 0x00, 0x23, 0xf6, 0xb2, + 0x0c, 0x93, 0x00, 0xf0, 0x7d, 0xbe, 0xa3, 0x78, 0x62, 0x78, 0x23, 0xa8, + 0x52, 0x49, 0x47, 0xe2, 0x49, 0x4b, 0xf2, 0x08, 0x1a, 0x70, 0x4f, 0xf0, + 0x00, 0x08, 0x99, 0x46, 0x2a, 0xe0, 0x43, 0x46, 0x10, 0x21, 0x46, 0x4a, + 0x1f, 0xa8, 0xdd, 0xf3, 0xc9, 0xf0, 0x43, 0x46, 0x10, 0x21, 0x44, 0x4a, + 0x1b, 0xa8, 0xdd, 0xf3, 0xc3, 0xf0, 0xe3, 0x78, 0x22, 0x79, 0x1b, 0x04, + 0x43, 0xea, 0x02, 0x63, 0x62, 0x78, 0x1f, 0xa9, 0x13, 0x43, 0xa2, 0x78, + 0x23, 0xa8, 0x43, 0xea, 0x02, 0x22, 0xff, 0xf7, 0x35, 0xfd, 0xe3, 0x79, + 0x22, 0x7a, 0x1b, 0x04, 0x43, 0xea, 0x02, 0x63, 0x62, 0x79, 0x23, 0xa8, + 0x13, 0x43, 0xa2, 0x79, 0x1b, 0xa9, 0x43, 0xea, 0x02, 0x22, 0xff, 0xf7, + 0x27, 0xfd, 0x08, 0xf1, 0x01, 0x08, 0x08, 0x34, 0x99, 0xf8, 0x00, 0x30, + 0x98, 0x45, 0xd0, 0xdb, 0x00, 0xf0, 0x40, 0xbe, 0x23, 0xa8, 0x36, 0x49, + 0x62, 0x78, 0xff, 0xf7, 0x19, 0xfd, 0x02, 0x2e, 0x40, 0xf2, 0x38, 0x86, + 0x23, 0xa8, 0x33, 0x49, 0x46, 0xe1, 0x00, 0x22, 0x23, 0xa8, 0x32, 0x49, + 0x63, 0x78, 0xff, 0xf7, 0x0d, 0xfd, 0x02, 0x2e, 0x40, 0xf2, 0x2a, 0x86, + 0x01, 0x22, 0x23, 0xa8, 0x2d, 0x49, 0xa3, 0x78, 0xff, 0xf7, 0x04, 0xfd, + 0x03, 0x2e, 0x00, 0xf0, 0x21, 0x86, 0x02, 0x22, 0x23, 0xa8, 0x29, 0x49, + 0xe3, 0x78, 0xff, 0xf7, 0xfb, 0xfc, 0x04, 0x2e, 0x00, 0xf0, 0x18, 0x86, + 0x03, 0x22, 0x23, 0xa8, 0x24, 0x49, 0x23, 0x79, 0xff, 0xf7, 0xf2, 0xfc, + 0x01, 0x22, 0x08, 0x92, 0x00, 0xf0, 0x10, 0xbe, 0x1f, 0x49, 0x62, 0x78, + 0x23, 0xa8, 0xff, 0xf7, 0xe9, 0xfc, 0x23, 0xa8, 0x1d, 0x49, 0x01, 0x22, + 0xa3, 0x78, 0x00, 0xf0, 0xce, 0xbd, 0x23, 0xa8, 0x1b, 0x49, 0x00, 0xf0, + 0xcf, 0xbd, 0xb3, 0x1e, 0x08, 0x2b, 0x00, 0xf2, 0xfd, 0x85, 0xdf, 0xe8, + 0x13, 0xf0, 0x09, 0x00, 0xfb, 0x05, 0xfb, 0x05, 0xfb, 0x05, 0xfb, 0x05, + 0x4c, 0x00, 0x3e, 0x00, 0x38, 0x00, 0x33, 0x00, 0x23, 0xa8, 0x13, 0x49, + 0x00, 0xf0, 0xbc, 0xbd, 0x4e, 0x93, 0x02, 0x00, 0x0f, 0x94, 0x02, 0x00, + 0x58, 0x92, 0x02, 0x00, 0x96, 0x8e, 0x02, 0x00, 0xad, 0x8f, 0x02, 0x00, + 0x7d, 0x08, 0x02, 0x00, 0x34, 0xc9, 0x01, 0x00, 0x3f, 0xc9, 0x01, 0x00, + 0xe2, 0x8f, 0x02, 0x00, 0xd1, 0x93, 0x02, 0x00, 0x0e, 0x8f, 0x02, 0x00, + 0xee, 0x90, 0x02, 0x00, 0xad, 0x8e, 0x02, 0x00, 0x88, 0x8f, 0x02, 0x00, + 0x0d, 0x8e, 0x02, 0x00, 0x46, 0x94, 0x02, 0x00, 0x1b, 0x91, 0x02, 0x00, + 0xd1, 0x94, 0x02, 0x00, 0x86, 0x93, 0x02, 0x00, 0x23, 0xa8, 0x96, 0x49, + 0x62, 0x7a, 0xff, 0xf7, 0xa1, 0xfc, 0xeb, 0x19, 0x23, 0xa8, 0x94, 0x49, + 0x1a, 0x7a, 0xff, 0xf7, 0x9b, 0xfc, 0x07, 0xf1, 0x07, 0x08, 0x92, 0x49, + 0x15, 0xf8, 0x08, 0x20, 0x23, 0xa8, 0xff, 0xf7, 0x93, 0xfc, 0x23, 0xa8, + 0x8f, 0x49, 0x15, 0xf8, 0x08, 0x20, 0xff, 0xf7, 0x8d, 0xfc, 0x4f, 0xf0, + 0x00, 0x08, 0xa2, 0x78, 0x63, 0x78, 0x8c, 0x49, 0x12, 0x02, 0x41, 0x44, + 0x23, 0xa8, 0xd2, 0x18, 0x08, 0xf1, 0x09, 0x08, 0xff, 0xf7, 0x80, 0xfc, + 0x02, 0x34, 0xb8, 0xf1, 0x1b, 0x0f, 0xf0, 0xd1, 0x00, 0xf0, 0x9c, 0xbd, + 0x14, 0x2e, 0x19, 0xd0, 0x17, 0x2e, 0x03, 0xd0, 0x13, 0x2e, 0x40, 0xf0, + 0x95, 0x85, 0x19, 0xe0, 0x05, 0xeb, 0x07, 0x08, 0x80, 0x49, 0x98, 0xf8, + 0x16, 0x20, 0x23, 0xa8, 0xff, 0xf7, 0x6a, 0xfc, 0x7e, 0x49, 0x98, 0xf8, + 0x15, 0x20, 0x23, 0xa8, 0xff, 0xf7, 0x64, 0xfc, 0x23, 0xa8, 0x7c, 0x49, + 0x98, 0xf8, 0x14, 0x20, 0xff, 0xf7, 0x5e, 0xfc, 0xeb, 0x19, 0x23, 0xa8, + 0x79, 0x49, 0xda, 0x7c, 0xff, 0xf7, 0x58, 0xfc, 0xb1, 0x46, 0xa2, 0x46, + 0x4f, 0xf0, 0x00, 0x08, 0x26, 0x46, 0xb2, 0x78, 0x73, 0x78, 0x75, 0x49, + 0x12, 0x02, 0x41, 0x44, 0x23, 0xa8, 0xd2, 0x18, 0x08, 0xf1, 0x09, 0x08, + 0xff, 0xf7, 0x48, 0xfc, 0x02, 0x36, 0xb8, 0xf1, 0x1b, 0x0f, 0xf0, 0xd1, + 0x4e, 0x46, 0x4f, 0xf0, 0x00, 0x08, 0x22, 0x7a, 0xe3, 0x79, 0x6d, 0x49, + 0x12, 0x02, 0x41, 0x44, 0x23, 0xa8, 0xd2, 0x18, 0x08, 0xf1, 0x0b, 0x08, + 0xff, 0xf7, 0x36, 0xfc, 0x02, 0x34, 0xb8, 0xf1, 0x21, 0x0f, 0xf0, 0xd1, + 0x00, 0x24, 0x9a, 0xf8, 0x0e, 0x20, 0x9a, 0xf8, 0x0d, 0x30, 0x65, 0x49, + 0x12, 0x02, 0x09, 0x19, 0x23, 0xa8, 0xd2, 0x18, 0x0b, 0x34, 0xff, 0xf7, + 0x25, 0xfc, 0x21, 0x2c, 0x0a, 0xf1, 0x02, 0x0a, 0xef, 0xd1, 0x00, 0xf0, + 0x41, 0xbd, 0xe1, 0x78, 0x62, 0x78, 0xa3, 0x78, 0x00, 0x91, 0x21, 0x79, + 0x23, 0xa8, 0x01, 0x91, 0x61, 0x79, 0x02, 0x91, 0xa1, 0x79, 0x03, 0x91, + 0xe1, 0x79, 0x04, 0x91, 0x21, 0x7a, 0x05, 0x91, 0x57, 0x49, 0xff, 0xf7, + 0x0d, 0xfc, 0x00, 0xf0, 0x2d, 0xbd, 0xa0, 0x46, 0x43, 0x46, 0x00, 0x24, + 0xb0, 0x46, 0x1e, 0x46, 0x16, 0xf8, 0x01, 0x3f, 0xff, 0x2b, 0x04, 0xd0, + 0x23, 0xa8, 0x51, 0x49, 0x22, 0x46, 0xff, 0xf7, 0xfd, 0xfb, 0x01, 0x34, + 0x04, 0x2c, 0xf3, 0xd1, 0x46, 0x46, 0x00, 0xf0, 0x19, 0xbd, 0x62, 0x78, + 0x23, 0xa8, 0x0a, 0xb1, 0xa3, 0x78, 0x1b, 0xb9, 0x4a, 0x49, 0xff, 0xf7, + 0xef, 0xfb, 0x02, 0xe0, 0x49, 0x49, 0xff, 0xf7, 0xeb, 0xfb, 0xeb, 0x19, + 0x23, 0xa8, 0x48, 0x49, 0xda, 0x78, 0xdd, 0xe4, 0xa3, 0x78, 0x62, 0x78, + 0x23, 0xa8, 0x46, 0x49, 0xd2, 0xe0, 0xe3, 0x78, 0x22, 0x79, 0x1b, 0x04, + 0x43, 0xea, 0x02, 0x63, 0x62, 0x78, 0x23, 0xa8, 0x13, 0x43, 0x42, 0x49, + 0xa2, 0x78, 0xb4, 0xe5, 0x23, 0xa8, 0x41, 0x49, 0x62, 0x78, 0xff, 0xf7, + 0xd1, 0xfb, 0x02, 0x2e, 0x40, 0xf2, 0xf0, 0x84, 0x3e, 0x49, 0x23, 0xa8, + 0xa2, 0x78, 0xc1, 0xe4, 0x7c, 0x1c, 0x2a, 0x5d, 0x3c, 0x49, 0x02, 0xf0, + 0x0f, 0x02, 0x23, 0xa8, 0xff, 0xf7, 0xc2, 0xfb, 0x2a, 0x5d, 0x3a, 0x49, + 0x12, 0x09, 0xbc, 0x1c, 0x23, 0xa8, 0xff, 0xf7, 0xbb, 0xfb, 0x2a, 0x5d, + 0x37, 0x49, 0x02, 0xf0, 0x07, 0x02, 0x23, 0xa8, 0xff, 0xf7, 0xb4, 0xfb, + 0x2a, 0x5d, 0x23, 0xa8, 0xd2, 0x08, 0x34, 0x49, 0x19, 0xe0, 0x7c, 0x1c, + 0x2a, 0x5d, 0x33, 0x49, 0x02, 0xf0, 0x0f, 0x02, 0x23, 0xa8, 0xff, 0xf7, + 0xa7, 0xfb, 0x2a, 0x5d, 0x30, 0x49, 0x12, 0x09, 0xbc, 0x1c, 0x23, 0xa8, + 0xff, 0xf7, 0xa0, 0xfb, 0x2a, 0x5d, 0x2e, 0x49, 0x02, 0xf0, 0x07, 0x02, + 0x23, 0xa8, 0xff, 0xf7, 0x99, 0xfb, 0x2a, 0x5d, 0x2b, 0x49, 0xd2, 0x08, + 0x23, 0xa8, 0x02, 0xf0, 0x03, 0x02, 0x89, 0xe4, 0x23, 0xa8, 0x29, 0x49, + 0x00, 0xf0, 0x7e, 0xbc, 0x28, 0x49, 0x62, 0x78, 0x23, 0xa8, 0xff, 0xf7, + 0x89, 0xfb, 0x27, 0x49, 0xa2, 0x78, 0x23, 0xa8, 0xff, 0xf7, 0x84, 0xfb, + 0x23, 0xa8, 0x25, 0x49, 0xe2, 0x78, 0x77, 0xe4, 0x23, 0xa8, 0x24, 0x49, + 0x00, 0xf0, 0x6c, 0xbc, 0x23, 0xa8, 0x23, 0x49, 0x00, 0xf0, 0x68, 0xbc, + 0x47, 0x93, 0x02, 0x00, 0x86, 0x93, 0x02, 0x00, 0x39, 0x92, 0x02, 0x00, + 0x6f, 0x8e, 0x02, 0x00, 0xbc, 0x90, 0x02, 0x00, 0x60, 0x8e, 0x02, 0x00, + 0x79, 0x8f, 0x02, 0x00, 0xd5, 0x8f, 0x02, 0x00, 0x7d, 0x8e, 0x02, 0x00, + 0x9c, 0x92, 0x02, 0x00, 0x7a, 0x90, 0x02, 0x00, 0x93, 0x93, 0x02, 0x00, + 0xea, 0x93, 0x02, 0x00, 0x23, 0x8e, 0x02, 0x00, 0xb1, 0x94, 0x02, 0x00, + 0xc6, 0x94, 0x02, 0x00, 0xe4, 0x94, 0x02, 0x00, 0xf7, 0x90, 0x02, 0x00, + 0x90, 0x94, 0x02, 0x00, 0x50, 0x94, 0x02, 0x00, 0x70, 0x90, 0x02, 0x00, + 0xf4, 0x8d, 0x02, 0x00, 0xd7, 0x90, 0x02, 0x00, 0x3f, 0x8e, 0x02, 0x00, + 0xe1, 0x93, 0x02, 0x00, 0x2b, 0x94, 0x02, 0x00, 0x01, 0x8f, 0x02, 0x00, + 0x83, 0x94, 0x02, 0x00, 0x5b, 0x94, 0x02, 0x00, 0x9c, 0x94, 0x02, 0x00, + 0x02, 0x91, 0x02, 0x00, 0x3e, 0x93, 0x02, 0x00, 0xe4, 0x90, 0x02, 0x00, + 0xe0, 0x91, 0x02, 0x00, 0x96, 0x8f, 0x02, 0x00, 0x07, 0xf1, 0x01, 0x08, + 0x05, 0xeb, 0x08, 0x04, 0x20, 0x46, 0xdd, 0xf3, 0xf3, 0xf2, 0x00, 0x28, + 0x40, 0xf0, 0x4a, 0x84, 0x15, 0xf8, 0x08, 0x30, 0xd9, 0x07, 0x00, 0xf1, + 0x45, 0x84, 0x20, 0x46, 0x13, 0xa9, 0xdd, 0xf3, 0x2f, 0xf1, 0x07, 0x9b, + 0x01, 0x33, 0x40, 0xf0, 0x3d, 0x84, 0xeb, 0x19, 0x5a, 0x79, 0x9b, 0x79, + 0x12, 0x02, 0xd3, 0x18, 0x07, 0x93, 0x00, 0xf0, 0x35, 0xbc, 0xa2, 0x78, + 0x63, 0x78, 0x8f, 0x49, 0x12, 0x06, 0x23, 0xa8, 0x42, 0xea, 0x03, 0x22, + 0x02, 0xe4, 0x8d, 0x49, 0x62, 0x78, 0x23, 0xa8, 0xff, 0xf7, 0x06, 0xfb, + 0x8b, 0x49, 0xa2, 0x78, 0x23, 0xa8, 0xff, 0xf7, 0x01, 0xfb, 0x23, 0x79, + 0xe2, 0x78, 0x1b, 0x02, 0x23, 0xa8, 0x88, 0x49, 0xff, 0xf7, 0xf1, 0xbb, + 0x23, 0xa8, 0x87, 0x49, 0xe6, 0xe3, 0x94, 0xf8, 0x02, 0x80, 0x63, 0x78, + 0x4f, 0xea, 0x08, 0x28, 0x98, 0x44, 0x1f, 0xfa, 0x88, 0xf8, 0x83, 0x49, + 0x4f, 0xea, 0xd8, 0x22, 0x23, 0xa8, 0xff, 0xf7, 0xe9, 0xfa, 0x08, 0xf4, + 0xe0, 0x62, 0x12, 0x0a, 0x7f, 0x49, 0x23, 0xa8, 0xff, 0xf7, 0xe2, 0xfa, + 0x08, 0xf0, 0xf8, 0x02, 0xd2, 0x08, 0x7d, 0x49, 0x23, 0xa8, 0xff, 0xf7, + 0xdb, 0xfa, 0x08, 0xf0, 0x06, 0x02, 0x52, 0x08, 0x7a, 0x49, 0x23, 0xa8, + 0xff, 0xf7, 0xd4, 0xfa, 0x23, 0xa8, 0x79, 0x49, 0x08, 0xf0, 0x01, 0x02, + 0xff, 0xf7, 0xce, 0xfa, 0x04, 0x2e, 0x40, 0xf2, 0xed, 0x83, 0x23, 0x79, + 0xe4, 0x78, 0x1b, 0x02, 0x1c, 0x19, 0xa4, 0xb2, 0x73, 0x49, 0xe2, 0x0a, + 0x23, 0xa8, 0xff, 0xf7, 0xc1, 0xfa, 0x04, 0xf4, 0xe0, 0x62, 0x71, 0x49, + 0x12, 0x0a, 0x23, 0xa8, 0xff, 0xf7, 0xba, 0xfa, 0x04, 0xf0, 0xf8, 0x02, + 0x6e, 0x49, 0xd2, 0x08, 0x23, 0xa8, 0xff, 0xf7, 0xb3, 0xfa, 0x04, 0xf0, + 0x06, 0x02, 0x6c, 0x49, 0x52, 0x08, 0x23, 0xa8, 0xff, 0xf7, 0xac, 0xfa, + 0x23, 0xa8, 0x6a, 0x49, 0x04, 0xf0, 0x01, 0x02, 0xff, 0xf7, 0x9e, 0xbb, + 0x68, 0x49, 0x62, 0x78, 0x23, 0xa8, 0xff, 0xf7, 0xa1, 0xfa, 0x4f, 0xf0, + 0x00, 0x08, 0x66, 0x49, 0xa2, 0x78, 0x23, 0xa8, 0xff, 0xf7, 0x9a, 0xfa, + 0xcd, 0xf8, 0x00, 0x80, 0x22, 0x79, 0xe3, 0x78, 0x12, 0x02, 0xd3, 0x18, + 0x01, 0x93, 0x02, 0x22, 0x60, 0x49, 0x43, 0x46, 0x23, 0xa8, 0xff, 0xf7, + 0x8d, 0xfa, 0xcd, 0xf8, 0x00, 0x80, 0xa2, 0x79, 0x63, 0x79, 0x12, 0x02, + 0xd3, 0x18, 0x01, 0x93, 0x02, 0x22, 0x01, 0x23, 0x59, 0x49, 0x23, 0xa8, + 0xff, 0xf7, 0x80, 0xfa, 0xcd, 0xf8, 0x00, 0x80, 0x22, 0x7a, 0xe3, 0x79, + 0x12, 0x02, 0xd3, 0x18, 0x02, 0x22, 0x01, 0x93, 0x23, 0xa8, 0x53, 0x49, + 0x13, 0x46, 0xff, 0xf7, 0x73, 0xfa, 0x1e, 0x2e, 0x40, 0xf2, 0x92, 0x83, + 0x50, 0x49, 0x62, 0x7a, 0x23, 0xa8, 0xff, 0xf7, 0x6b, 0xfa, 0x4f, 0x49, + 0xa2, 0x7a, 0x23, 0xa8, 0xff, 0xf7, 0x66, 0xfa, 0x4d, 0x49, 0xe2, 0x7a, + 0x23, 0xa8, 0xff, 0xf7, 0x61, 0xfa, 0x4c, 0x49, 0x22, 0x7b, 0x23, 0xa8, + 0xff, 0xf7, 0x5c, 0xfa, 0xcd, 0xf8, 0x00, 0x80, 0xa2, 0x7b, 0x63, 0x7b, + 0x12, 0x02, 0xd3, 0x18, 0x01, 0x93, 0x42, 0x49, 0x05, 0x22, 0x43, 0x46, + 0x23, 0xa8, 0xff, 0xf7, 0x4f, 0xfa, 0xcd, 0xf8, 0x00, 0x80, 0x22, 0x7c, + 0xe3, 0x7b, 0x12, 0x02, 0xd3, 0x18, 0x01, 0x93, 0x3b, 0x49, 0x05, 0x22, + 0x01, 0x23, 0x23, 0xa8, 0xff, 0xf7, 0x42, 0xfa, 0xcd, 0xf8, 0x00, 0x80, + 0xa2, 0x7c, 0x63, 0x7c, 0x12, 0x02, 0xd3, 0x18, 0x01, 0x93, 0x35, 0x49, + 0x05, 0x22, 0x02, 0x23, 0x23, 0xa8, 0xff, 0xf7, 0x35, 0xfa, 0xcd, 0xf8, + 0x00, 0x80, 0xcd, 0xf8, 0x04, 0x80, 0x22, 0x7d, 0xe3, 0x7c, 0x12, 0x02, + 0xd3, 0x18, 0x02, 0x93, 0x32, 0x49, 0x05, 0x22, 0x6c, 0x23, 0x4f, 0xf0, + 0x01, 0x09, 0x23, 0xa8, 0xff, 0xf7, 0x24, 0xfa, 0xcd, 0xf8, 0x00, 0x90, + 0xcd, 0xf8, 0x04, 0x80, 0xa2, 0x7d, 0x63, 0x7d, 0x12, 0x02, 0xd3, 0x18, + 0x02, 0x93, 0x2a, 0x49, 0x05, 0x22, 0x6c, 0x23, 0x23, 0xa8, 0x4f, 0xf0, + 0x02, 0x0a, 0xff, 0xf7, 0x13, 0xfa, 0xcd, 0xf8, 0x00, 0xa0, 0xcd, 0xf8, + 0x04, 0x80, 0x22, 0x7e, 0xe3, 0x7d, 0x12, 0x02, 0xd3, 0x18, 0x02, 0x93, + 0x21, 0x49, 0x05, 0x22, 0x6c, 0x23, 0x23, 0xa8, 0xff, 0xf7, 0x04, 0xfa, + 0xcd, 0xf8, 0x00, 0x80, 0xcd, 0xf8, 0x04, 0x80, 0xa2, 0x7e, 0x63, 0x7e, + 0x12, 0x02, 0xd3, 0x18, 0x02, 0x93, 0x23, 0xa8, 0x19, 0x49, 0x05, 0x22, + 0x68, 0x23, 0xff, 0xf7, 0xf5, 0xf9, 0xcd, 0xf8, 0x00, 0x90, 0xe0, 0xe0, + 0x71, 0x92, 0x02, 0x00, 0x20, 0x92, 0x02, 0x00, 0xea, 0x91, 0x02, 0x00, + 0x11, 0x92, 0x02, 0x00, 0xc5, 0x93, 0x02, 0x00, 0x73, 0x94, 0x02, 0x00, + 0x1f, 0x8f, 0x02, 0x00, 0x2c, 0x8f, 0x02, 0x00, 0xfd, 0x94, 0x02, 0x00, + 0x30, 0x8e, 0x02, 0x00, 0xe0, 0x92, 0x02, 0x00, 0x1a, 0x95, 0x02, 0x00, + 0x4d, 0x95, 0x02, 0x00, 0x25, 0x91, 0x02, 0x00, 0x64, 0x94, 0x02, 0x00, + 0x6f, 0x8e, 0x02, 0x00, 0xf7, 0x91, 0x02, 0x00, 0x1a, 0x94, 0x02, 0x00, + 0xc4, 0x92, 0x02, 0x00, 0xbb, 0x8f, 0x02, 0x00, 0x7e, 0x92, 0x02, 0x00, + 0xd4, 0x8e, 0x02, 0x00, 0x9b, 0x90, 0x02, 0x00, 0x98, 0x49, 0x62, 0x78, + 0x23, 0xa8, 0xff, 0xf7, 0xbf, 0xf9, 0x4f, 0xf0, 0x01, 0x08, 0x96, 0x49, + 0xa2, 0x78, 0x23, 0xa8, 0xff, 0xf7, 0xb8, 0xf9, 0xcd, 0xf8, 0x00, 0x80, + 0x22, 0x79, 0xe3, 0x78, 0x12, 0x02, 0xd3, 0x18, 0x01, 0x93, 0x02, 0x22, + 0x00, 0x23, 0x90, 0x49, 0x23, 0xa8, 0xff, 0xf7, 0xab, 0xf9, 0xcd, 0xf8, + 0x00, 0x80, 0xa2, 0x79, 0x63, 0x79, 0x12, 0x02, 0xd3, 0x18, 0x01, 0x93, + 0x02, 0x22, 0x8a, 0x49, 0x43, 0x46, 0x23, 0xa8, 0xff, 0xf7, 0x9e, 0xf9, + 0xcd, 0xf8, 0x00, 0x80, 0x22, 0x7a, 0xe3, 0x79, 0x12, 0x02, 0xd3, 0x18, + 0x02, 0x22, 0x01, 0x93, 0x23, 0xa8, 0x83, 0x49, 0x13, 0x46, 0xff, 0xf7, + 0x91, 0xf9, 0x1e, 0x2e, 0x40, 0xf2, 0xb0, 0x82, 0x80, 0x49, 0x62, 0x7a, + 0x23, 0xa8, 0xff, 0xf7, 0x89, 0xf9, 0x7f, 0x49, 0xa2, 0x7a, 0x23, 0xa8, + 0xff, 0xf7, 0x84, 0xf9, 0x7d, 0x49, 0xe2, 0x7a, 0x23, 0xa8, 0xff, 0xf7, + 0x7f, 0xf9, 0x7c, 0x49, 0x22, 0x7b, 0x23, 0xa8, 0xff, 0xf7, 0x7a, 0xf9, + 0xcd, 0xf8, 0x00, 0x80, 0xa2, 0x7b, 0x63, 0x7b, 0x12, 0x02, 0xd3, 0x18, + 0x01, 0x93, 0x72, 0x49, 0x05, 0x22, 0x00, 0x23, 0x23, 0xa8, 0xff, 0xf7, + 0x6d, 0xf9, 0xcd, 0xf8, 0x00, 0x80, 0x22, 0x7c, 0xe3, 0x7b, 0x12, 0x02, + 0xd3, 0x18, 0x01, 0x93, 0x6b, 0x49, 0x05, 0x22, 0x43, 0x46, 0x23, 0xa8, + 0xff, 0xf7, 0x60, 0xf9, 0xcd, 0xf8, 0x00, 0x80, 0xa2, 0x7c, 0x63, 0x7c, + 0x12, 0x02, 0xd3, 0x18, 0x01, 0x93, 0x65, 0x49, 0x05, 0x22, 0x02, 0x23, + 0x4f, 0xf0, 0x00, 0x09, 0x23, 0xa8, 0xff, 0xf7, 0x51, 0xf9, 0xcd, 0xf8, + 0x00, 0x90, 0xcd, 0xf8, 0x04, 0x80, 0x22, 0x7d, 0xe3, 0x7c, 0x12, 0x02, + 0xd3, 0x18, 0x02, 0x93, 0x61, 0x49, 0x05, 0x22, 0x6c, 0x23, 0x23, 0xa8, + 0xff, 0xf7, 0x42, 0xf9, 0xcd, 0xf8, 0x00, 0x80, 0xcd, 0xf8, 0x04, 0x80, + 0xa2, 0x7d, 0x63, 0x7d, 0x12, 0x02, 0xd3, 0x18, 0x02, 0x93, 0x5a, 0x49, + 0x05, 0x22, 0x6c, 0x23, 0x23, 0xa8, 0x4f, 0xf0, 0x02, 0x0a, 0xff, 0xf7, + 0x31, 0xf9, 0xcd, 0xf8, 0x00, 0xa0, 0xcd, 0xf8, 0x04, 0x80, 0x22, 0x7e, + 0xe3, 0x7d, 0x12, 0x02, 0xd3, 0x18, 0x02, 0x93, 0x51, 0x49, 0x05, 0x22, + 0x6c, 0x23, 0x23, 0xa8, 0xff, 0xf7, 0x22, 0xf9, 0xcd, 0xf8, 0x00, 0x90, + 0xcd, 0xf8, 0x04, 0x80, 0xa2, 0x7e, 0x63, 0x7e, 0x12, 0x02, 0xd3, 0x18, + 0x02, 0x93, 0x23, 0xa8, 0x49, 0x49, 0x05, 0x22, 0x68, 0x23, 0xff, 0xf7, + 0x13, 0xf9, 0xcd, 0xf8, 0x00, 0x80, 0xcd, 0xf8, 0x04, 0x80, 0x22, 0x7f, + 0xe3, 0x7e, 0x12, 0x02, 0xd3, 0x18, 0x02, 0x93, 0x05, 0x22, 0x68, 0x23, + 0x23, 0xa8, 0x41, 0x49, 0xff, 0xf7, 0x04, 0xf9, 0xcd, 0xf8, 0x00, 0xa0, + 0xcd, 0xf8, 0x04, 0x80, 0xa3, 0x7f, 0x62, 0x7f, 0x1b, 0x02, 0x9b, 0x18, + 0x02, 0x93, 0x23, 0xa8, 0x3a, 0x49, 0x05, 0x22, 0x68, 0x23, 0xff, 0xf7, + 0xf5, 0xf8, 0x15, 0xe2, 0xa2, 0x78, 0x63, 0x78, 0x12, 0x02, 0xd2, 0x18, + 0x36, 0x49, 0x23, 0xa8, 0xff, 0xf7, 0xec, 0xf8, 0xa2, 0x79, 0x63, 0x79, + 0x12, 0x06, 0x1b, 0x04, 0xd2, 0x18, 0x23, 0x79, 0x23, 0xa8, 0x1b, 0x02, + 0xd2, 0x18, 0xe3, 0x78, 0x30, 0x49, 0xd2, 0x18, 0xff, 0xf7, 0xde, 0xf8, + 0x12, 0x2e, 0x40, 0xf2, 0xfd, 0x81, 0xa2, 0x7a, 0x63, 0x7a, 0x12, 0x06, + 0x1b, 0x04, 0xd2, 0x18, 0x23, 0x7a, 0x2b, 0x49, 0x1b, 0x02, 0xd2, 0x18, + 0xe3, 0x79, 0x23, 0xa8, 0xd2, 0x18, 0xff, 0xf7, 0xcd, 0xf8, 0xa2, 0x7b, + 0x63, 0x7b, 0x12, 0x06, 0x1b, 0x04, 0xd2, 0x18, 0x23, 0x7b, 0x23, 0xa8, + 0x1b, 0x02, 0xd2, 0x18, 0xe3, 0x7a, 0x23, 0x49, 0xd2, 0x18, 0xff, 0xf7, + 0xbf, 0xf8, 0xa2, 0x7c, 0x63, 0x7c, 0x12, 0x06, 0x1b, 0x04, 0xd3, 0x18, + 0x22, 0x7c, 0x12, 0x02, 0x9b, 0x18, 0xe2, 0x7b, 0xbb, 0xe0, 0xa2, 0x78, + 0x63, 0x78, 0x12, 0x02, 0xd3, 0x18, 0x00, 0x93, 0x02, 0x22, 0x43, 0x46, + 0x23, 0xa8, 0x19, 0x49, 0x08, 0xf1, 0x01, 0x08, 0xff, 0xf7, 0xa8, 0xf8, + 0x02, 0x34, 0xc8, 0x45, 0xef, 0xdd, 0xc5, 0xe1, 0xa2, 0x78, 0x63, 0x78, + 0x12, 0x02, 0xd3, 0x18, 0x00, 0x93, 0x05, 0x22, 0x43, 0x46, 0x23, 0xa8, + 0x10, 0x49, 0x08, 0xf1, 0x01, 0x08, 0xff, 0xf7, 0x97, 0xf8, 0x02, 0x34, + 0xc8, 0x45, 0xef, 0xdd, 0xb4, 0xe1, 0x00, 0xbf, 0xae, 0x90, 0x02, 0x00, + 0x04, 0x92, 0x02, 0x00, 0x1a, 0x94, 0x02, 0x00, 0xd2, 0x92, 0x02, 0x00, + 0xc8, 0x8f, 0x02, 0x00, 0x8d, 0x92, 0x02, 0x00, 0xe3, 0x8e, 0x02, 0x00, + 0x9b, 0x90, 0x02, 0x00, 0xd7, 0x94, 0x02, 0x00, 0x38, 0x94, 0x02, 0x00, + 0x63, 0x92, 0x02, 0x00, 0xf2, 0x8e, 0x02, 0x00, 0xbc, 0x8e, 0x02, 0x00, + 0xcd, 0xf8, 0x00, 0x80, 0xa2, 0x78, 0x63, 0x78, 0x12, 0x02, 0xd3, 0x18, + 0x01, 0x93, 0x05, 0x22, 0x6c, 0x23, 0x23, 0xa8, 0xb1, 0x49, 0x08, 0xf1, + 0x01, 0x08, 0xff, 0xf7, 0x69, 0xf8, 0x02, 0x34, 0xd0, 0x45, 0xed, 0xdd, + 0x4f, 0xea, 0x56, 0x09, 0x5f, 0xfa, 0x89, 0xf9, 0x09, 0xf1, 0x01, 0x0c, + 0x09, 0xf1, 0x02, 0x09, 0xbc, 0x44, 0xb9, 0x44, 0x05, 0xeb, 0x09, 0x04, + 0xcd, 0xf8, 0x44, 0xb0, 0x4f, 0xf0, 0x00, 0x08, 0xb3, 0x46, 0x2e, 0x46, + 0x65, 0x46, 0xcd, 0xf8, 0x00, 0x80, 0x22, 0x78, 0xc9, 0xeb, 0x04, 0x03, + 0x5b, 0x5d, 0x12, 0x02, 0xd3, 0x18, 0x01, 0x93, 0x05, 0x22, 0x68, 0x23, + 0x23, 0xa8, 0x9e, 0x49, 0x08, 0xf1, 0x01, 0x08, 0xff, 0xf7, 0x42, 0xf8, + 0x02, 0x34, 0xd0, 0x45, 0xeb, 0xdd, 0x35, 0x46, 0x5e, 0x46, 0xdd, 0xf8, + 0x44, 0xb0, 0x5b, 0xe1, 0xa3, 0x78, 0x62, 0x78, 0x1b, 0x02, 0x23, 0xa8, + 0x96, 0x49, 0xff, 0xf7, 0x2a, 0xb9, 0xa3, 0x78, 0x62, 0x78, 0x1b, 0x02, + 0x23, 0xa8, 0x94, 0x49, 0xff, 0xf7, 0x23, 0xb9, 0xa3, 0x78, 0x62, 0x78, + 0x1b, 0x02, 0x23, 0xa8, 0x91, 0x49, 0xff, 0xf7, 0x1c, 0xb9, 0xa3, 0x78, + 0x62, 0x78, 0x1b, 0x02, 0x23, 0xa8, 0x8f, 0x49, 0xff, 0xf7, 0x15, 0xb9, + 0x22, 0x79, 0xe3, 0x78, 0x12, 0x06, 0x1b, 0x04, 0xd2, 0x18, 0xa3, 0x78, + 0x8b, 0x49, 0x1b, 0x02, 0xd2, 0x18, 0x63, 0x78, 0x23, 0xa8, 0xd2, 0x18, + 0xff, 0xf7, 0x10, 0xf8, 0x22, 0x7a, 0xe3, 0x79, 0x12, 0x06, 0x1b, 0x04, + 0xd2, 0x18, 0xa3, 0x79, 0x23, 0xa8, 0x1b, 0x02, 0xd2, 0x18, 0x63, 0x79, + 0x83, 0x49, 0xd2, 0x18, 0xff, 0xf7, 0x02, 0xf8, 0x22, 0x7b, 0xe3, 0x7a, + 0x12, 0x06, 0x1b, 0x04, 0xd3, 0x18, 0xa2, 0x7a, 0x12, 0x02, 0x9b, 0x18, + 0x62, 0x7a, 0x23, 0xa8, 0x7d, 0x49, 0xff, 0xf7, 0xec, 0xb8, 0xa2, 0x78, + 0x63, 0x78, 0x12, 0x02, 0x23, 0xa8, 0x7b, 0x49, 0xd2, 0x18, 0xfe, 0xf7, + 0xed, 0xff, 0x04, 0x2e, 0x40, 0xf2, 0x0c, 0x81, 0x23, 0x79, 0xe2, 0x78, + 0x1b, 0x02, 0x23, 0xa8, 0x76, 0x49, 0xff, 0xf7, 0xda, 0xb8, 0x22, 0x79, + 0xe3, 0x78, 0x12, 0x06, 0x1b, 0x04, 0xd2, 0x18, 0xa3, 0x78, 0x23, 0xa8, + 0x1b, 0x02, 0xd2, 0x18, 0x63, 0x78, 0x71, 0x49, 0xd2, 0x18, 0xfe, 0xf7, + 0xd5, 0xff, 0x06, 0x2e, 0x40, 0xf2, 0xf4, 0x80, 0x22, 0x7a, 0xe3, 0x79, + 0x12, 0x06, 0x1b, 0x04, 0xd3, 0x18, 0xa2, 0x79, 0x23, 0xa8, 0x12, 0x02, + 0x9b, 0x18, 0x6a, 0x49, 0x62, 0x79, 0xff, 0xf7, 0xbc, 0xb8, 0xdf, 0xf8, + 0xb4, 0x91, 0x4f, 0xf0, 0x01, 0x08, 0xb0, 0x45, 0x80, 0xf2, 0xe0, 0x80, + 0x22, 0x79, 0xe3, 0x78, 0x12, 0x06, 0x1b, 0x04, 0xd2, 0x18, 0xa3, 0x78, + 0x49, 0x46, 0x1b, 0x02, 0xd2, 0x18, 0x63, 0x78, 0x23, 0xa8, 0xd2, 0x18, + 0x08, 0xf1, 0x04, 0x08, 0xfe, 0xf7, 0xae, 0xff, 0x04, 0x34, 0xb8, 0xf1, + 0x19, 0x0f, 0x09, 0xf1, 0x18, 0x09, 0xe6, 0xd1, 0xc8, 0xe0, 0xdf, 0xf8, + 0x7c, 0x91, 0x4f, 0xf0, 0x01, 0x08, 0xb0, 0x45, 0x80, 0xf2, 0xc2, 0x80, + 0x22, 0x79, 0xe3, 0x78, 0x12, 0x06, 0x1b, 0x04, 0xd2, 0x18, 0xa3, 0x78, + 0x49, 0x46, 0x1b, 0x02, 0xd2, 0x18, 0x63, 0x78, 0x23, 0xa8, 0xd2, 0x18, + 0x08, 0xf1, 0x04, 0x08, 0xfe, 0xf7, 0x90, 0xff, 0x04, 0x34, 0xb8, 0xf1, + 0x0d, 0x0f, 0x09, 0xf1, 0x13, 0x09, 0xe6, 0xd1, 0xaa, 0xe0, 0xdf, 0xf8, + 0x44, 0x91, 0x4f, 0xf0, 0x01, 0x08, 0xb0, 0x45, 0x80, 0xf2, 0xa4, 0x80, + 0x22, 0x79, 0xe3, 0x78, 0x12, 0x06, 0x1b, 0x04, 0xd2, 0x18, 0xa3, 0x78, + 0x49, 0x46, 0x1b, 0x02, 0xd2, 0x18, 0x63, 0x78, 0x23, 0xa8, 0xd2, 0x18, + 0x08, 0xf1, 0x04, 0x08, 0xfe, 0xf7, 0x72, 0xff, 0x04, 0x34, 0xb8, 0xf1, + 0x0d, 0x0f, 0x09, 0xf1, 0x14, 0x09, 0xe6, 0xd1, 0x8c, 0xe0, 0xdf, 0xf8, + 0x0c, 0x91, 0x4f, 0xf0, 0x01, 0x08, 0xb0, 0x45, 0x80, 0xf2, 0x86, 0x80, + 0x22, 0x79, 0xe3, 0x78, 0x12, 0x06, 0x1b, 0x04, 0xd2, 0x18, 0xa3, 0x78, + 0x49, 0x46, 0x1b, 0x02, 0xd2, 0x18, 0x63, 0x78, 0x23, 0xa8, 0xd2, 0x18, + 0x08, 0xf1, 0x04, 0x08, 0xfe, 0xf7, 0x54, 0xff, 0x04, 0x34, 0xb8, 0xf1, + 0x0d, 0x0f, 0x09, 0xf1, 0x14, 0x09, 0xe6, 0xd1, 0x6e, 0xe0, 0xdf, 0xf8, + 0xd4, 0x90, 0x4f, 0xf0, 0x01, 0x08, 0xb0, 0x45, 0x68, 0xda, 0x22, 0x79, + 0xe3, 0x78, 0x12, 0x06, 0x1b, 0x04, 0xd2, 0x18, 0xa3, 0x78, 0x49, 0x46, + 0x1b, 0x02, 0xd2, 0x18, 0x63, 0x78, 0x23, 0xa8, 0xd2, 0x18, 0x08, 0xf1, + 0x04, 0x08, 0xfe, 0xf7, 0x37, 0xff, 0x04, 0x34, 0xb8, 0xf1, 0x0d, 0x0f, + 0x09, 0xf1, 0x14, 0x09, 0xe7, 0xd1, 0x51, 0xe0, 0xa3, 0x78, 0x62, 0x78, + 0x1b, 0x02, 0x23, 0xa8, 0x1c, 0x49, 0xff, 0xf7, 0x20, 0xb8, 0xa3, 0x78, + 0x62, 0x78, 0x1b, 0x02, 0x23, 0xa8, 0x1a, 0x49, 0xff, 0xf7, 0x19, 0xb8, + 0x22, 0x79, 0xe3, 0x78, 0x12, 0x06, 0x1b, 0x04, 0xd3, 0x18, 0xa2, 0x78, + 0x64, 0x78, 0x12, 0x02, 0x9b, 0x18, 0x15, 0x49, 0x23, 0xa8, 0x01, 0x22, + 0x1b, 0x19, 0xfe, 0xf7, 0x13, 0xff, 0x33, 0xe0, 0x12, 0x49, 0x23, 0xa8, + 0x62, 0x78, 0xff, 0xf7, 0x05, 0xb8, 0x00, 0x22, 0x0a, 0x92, 0x2b, 0xe0, + 0xf0, 0x92, 0x02, 0x00, 0x45, 0x91, 0x02, 0x00, 0xa5, 0x94, 0x02, 0x00, + 0x17, 0x8e, 0x02, 0x00, 0xb7, 0x92, 0x02, 0x00, 0x63, 0x92, 0x02, 0x00, + 0xf2, 0x8e, 0x02, 0x00, 0x0c, 0x91, 0x02, 0x00, 0x27, 0x95, 0x02, 0x00, + 0x3a, 0x95, 0x02, 0x00, 0x5a, 0x93, 0x02, 0x00, 0x70, 0x93, 0x02, 0x00, + 0xa0, 0x8f, 0x02, 0x00, 0x4c, 0x8e, 0x02, 0x00, 0xb4, 0x93, 0x02, 0x00, + 0x46, 0x92, 0x02, 0x00, 0x50, 0x91, 0x02, 0x00, 0xf0, 0x8f, 0x02, 0x00, + 0x3d, 0x8f, 0x02, 0x00, 0x29, 0x90, 0x02, 0x00, 0x02, 0x93, 0x02, 0x00, + 0x01, 0x23, 0x08, 0x93, 0xbb, 0xf1, 0xff, 0x0f, 0x07, 0xeb, 0x06, 0x03, + 0x7e, 0xf4, 0x77, 0xaf, 0x0b, 0x9a, 0x01, 0x32, 0x0b, 0x92, 0x0b, 0x9b, + 0x0f, 0x9a, 0x93, 0x42, 0x7e, 0xf4, 0x67, 0xaf, 0x07, 0x9b, 0x5a, 0x1c, + 0x04, 0xd0, 0x23, 0xa8, 0x18, 0x49, 0x1a, 0x46, 0xfe, 0xf7, 0xc8, 0xfe, + 0x9d, 0xf8, 0x4c, 0x30, 0x23, 0xb1, 0x23, 0xa8, 0x15, 0x49, 0x13, 0xaa, + 0xfe, 0xf7, 0xc0, 0xfe, 0x00, 0x20, 0x14, 0x49, 0xdc, 0xf3, 0xc0, 0xf6, + 0x30, 0xb9, 0x08, 0x9a, 0x22, 0xb9, 0x23, 0xa8, 0x11, 0x49, 0xff, 0x23, + 0xfe, 0xf7, 0xb4, 0xfe, 0x24, 0x9a, 0x00, 0x23, 0x02, 0xf8, 0x01, 0x3b, + 0x30, 0x9b, 0x09, 0x99, 0x00, 0x93, 0x0d, 0x98, 0x10, 0x9b, 0x24, 0x92, + 0xfe, 0xf7, 0xf9, 0xfe, 0x09, 0x99, 0x04, 0x46, 0x4f, 0xf4, 0x80, 0x52, + 0x0d, 0x98, 0xe1, 0xf3, 0x35, 0xf0, 0x01, 0xe0, 0x6f, 0xf0, 0x01, 0x04, + 0x20, 0x46, 0x27, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, 0x0e, 0x95, 0x02, 0x00, + 0xbb, 0x94, 0x02, 0x00, 0x0e, 0x5d, 0x86, 0x00, 0x1b, 0x91, 0x02, 0x00, + 0x2d, 0xe9, 0xf0, 0x4f, 0x8d, 0xb0, 0x05, 0x92, 0x05, 0x46, 0x0e, 0x46, + 0x06, 0xa8, 0x00, 0x21, 0x14, 0x22, 0x9a, 0x46, 0x0b, 0x91, 0xdc, 0xf3, + 0xc1, 0xf1, 0x63, 0x4b, 0x1c, 0x78, 0x00, 0x2c, 0x40, 0xf0, 0xb6, 0x80, + 0x6b, 0x69, 0x23, 0x2b, 0x0e, 0xdd, 0x1c, 0x22, 0x28, 0x46, 0x21, 0x46, + 0x23, 0x46, 0x00, 0x94, 0xe5, 0xf3, 0xd8, 0xf0, 0x00, 0x28, 0x09, 0xda, + 0x4f, 0xf0, 0x01, 0x09, 0x02, 0x27, 0xcd, 0xf8, 0x10, 0x90, 0x07, 0xe0, + 0x04, 0x27, 0x4f, 0xf0, 0x01, 0x09, 0x02, 0xe0, 0x0c, 0x27, 0x4f, 0xf0, + 0x03, 0x09, 0x04, 0x94, 0x28, 0x46, 0xe5, 0xf3, 0x79, 0xf0, 0x01, 0x28, + 0x83, 0x46, 0x02, 0xd0, 0x02, 0x28, 0x13, 0xd1, 0x05, 0xe0, 0x28, 0x46, + 0x31, 0x46, 0xdc, 0xf3, 0xc9, 0xf0, 0x40, 0x00, 0x0b, 0xe0, 0x28, 0x46, + 0xfa, 0xf7, 0x7c, 0xff, 0x04, 0x46, 0x38, 0xb1, 0xdc, 0xf3, 0x6e, 0xf0, + 0xc3, 0x05, 0x03, 0xd5, 0x20, 0x46, 0xdc, 0xf3, 0x5f, 0xf0, 0x0b, 0x90, + 0x0b, 0x99, 0x00, 0x29, 0x51, 0xd0, 0x30, 0x46, 0xe0, 0xf3, 0xc8, 0xf7, + 0x04, 0x46, 0x00, 0x28, 0x7c, 0xd0, 0xbb, 0xf1, 0x01, 0x0f, 0xdd, 0xf8, + 0x2c, 0x80, 0x03, 0xd0, 0xbb, 0xf1, 0x02, 0x0f, 0x1a, 0xd1, 0x0a, 0xe0, + 0x00, 0x21, 0x02, 0x90, 0x8d, 0xe8, 0x02, 0x01, 0x03, 0x91, 0x28, 0x46, + 0x05, 0x9a, 0x33, 0x46, 0xdc, 0xf3, 0x98, 0xf0, 0x0c, 0xe0, 0x0c, 0xab, + 0x4f, 0xea, 0x58, 0x02, 0x43, 0xf8, 0x04, 0x2d, 0x28, 0x46, 0x01, 0x21, + 0x22, 0x46, 0xdb, 0xf3, 0xf5, 0xf7, 0x0b, 0x9b, 0x5b, 0x00, 0x0b, 0x93, + 0x00, 0x28, 0x4b, 0xd1, 0x22, 0x88, 0x4f, 0xf6, 0xfd, 0x73, 0x01, 0x3a, + 0x92, 0xb2, 0x9a, 0x42, 0x05, 0xd9, 0x30, 0x46, 0x21, 0x46, 0x42, 0x46, + 0xe0, 0xf3, 0xa6, 0xf7, 0x1c, 0xe0, 0x04, 0x9a, 0x1a, 0xb1, 0x04, 0xeb, + 0x47, 0x07, 0x06, 0x97, 0x1b, 0xe0, 0xe3, 0x19, 0x62, 0x88, 0x06, 0x93, + 0xa3, 0x88, 0xa7, 0xf5, 0x80, 0x57, 0x07, 0xeb, 0x12, 0x22, 0x1b, 0x06, + 0x02, 0xeb, 0x13, 0x43, 0xe3, 0x18, 0x07, 0x93, 0xe3, 0x88, 0xdb, 0x19, + 0xe3, 0x18, 0x08, 0x93, 0x23, 0x89, 0xdf, 0x19, 0xe7, 0x19, 0x09, 0x97, + 0x05, 0xe0, 0x88, 0x46, 0x1b, 0x4b, 0x00, 0x24, 0x06, 0x93, 0x4f, 0xf0, + 0x01, 0x09, 0x16, 0x9b, 0x30, 0x46, 0x00, 0x93, 0x06, 0xa9, 0x4a, 0x46, + 0x53, 0x46, 0xfe, 0xf7, 0x59, 0xfe, 0x90, 0xb9, 0x15, 0x49, 0xdc, 0xf3, + 0xbb, 0xf5, 0x38, 0xb1, 0x16, 0x9b, 0x28, 0x46, 0xda, 0xf8, 0x00, 0x10, + 0x1a, 0x68, 0x00, 0xf0, 0x25, 0xfb, 0x06, 0xe0, 0x16, 0x9b, 0x28, 0x46, + 0xda, 0xf8, 0x00, 0x10, 0x1a, 0x68, 0x00, 0xf0, 0x3f, 0xfb, 0x24, 0xb1, + 0x30, 0x46, 0x21, 0x46, 0x42, 0x46, 0xe0, 0xf3, 0x61, 0xf7, 0x07, 0x4a, + 0x01, 0x23, 0x13, 0x70, 0x16, 0x9b, 0x00, 0x20, 0xca, 0xf8, 0x00, 0x00, + 0x18, 0x60, 0x01, 0xe0, 0x6f, 0xf0, 0x1a, 0x00, 0x0d, 0xb0, 0xbd, 0xe8, + 0xf0, 0x8f, 0x00, 0xbf, 0x40, 0x27, 0x00, 0x00, 0xa5, 0x8e, 0x02, 0x00, + 0x4a, 0xc9, 0x01, 0x00, 0x30, 0xb5, 0x19, 0x46, 0x03, 0x9b, 0x04, 0x9c, + 0x43, 0xb1, 0x4c, 0xb1, 0x00, 0x25, 0x1d, 0x60, 0x25, 0x60, 0x03, 0x94, + 0xbd, 0xe8, 0x30, 0x40, 0xff, 0xf7, 0x18, 0xbf, 0x18, 0x46, 0x30, 0xbd, + 0x20, 0x46, 0x30, 0xbd, 0x08, 0x4b, 0x1a, 0x88, 0x8a, 0x42, 0x04, 0xd0, + 0x9a, 0x88, 0x8a, 0x42, 0x06, 0xd1, 0x01, 0x22, 0x00, 0xe0, 0x00, 0x22, + 0x03, 0xeb, 0x82, 0x03, 0x98, 0x78, 0x00, 0xe0, 0xff, 0x20, 0x40, 0xb2, + 0x70, 0x47, 0x00, 0xbf, 0xa8, 0x95, 0x02, 0x00, 0xf8, 0xb5, 0x04, 0x46, + 0x15, 0x46, 0x1f, 0x46, 0x00, 0x2b, 0x7b, 0xd0, 0xe6, 0xf7, 0x24, 0xfe, + 0x06, 0x46, 0x0b, 0xe0, 0xbb, 0x42, 0x08, 0xd1, 0xd5, 0xf8, 0x00, 0x26, + 0xb3, 0x78, 0x02, 0xf0, 0x7c, 0x02, 0xb3, 0xeb, 0x92, 0x0f, 0x07, 0xd1, + 0xf8, 0xbd, 0x0c, 0x36, 0x00, 0x2e, 0x69, 0xd0, 0x33, 0x88, 0x00, 0x2b, + 0xee, 0xd1, 0xf8, 0xbd, 0xd5, 0xf8, 0x18, 0x36, 0x64, 0x20, 0x23, 0xf0, + 0xc0, 0x73, 0xc5, 0xf8, 0x18, 0x36, 0xd5, 0xf8, 0x1c, 0x36, 0x40, 0xf2, + 0xdd, 0x57, 0x23, 0xf0, 0xc0, 0x73, 0xc5, 0xf8, 0x1c, 0x36, 0xe0, 0xf3, + 0x2d, 0xf4, 0x02, 0xe0, 0x0a, 0x20, 0xe0, 0xf3, 0x29, 0xf4, 0xd5, 0xf8, + 0xe0, 0x31, 0x9b, 0x03, 0x01, 0xd5, 0x01, 0x3f, 0xf6, 0xd1, 0x00, 0x23, + 0xc5, 0xf8, 0x60, 0x36, 0x31, 0x79, 0xf3, 0x78, 0xd5, 0xf8, 0x64, 0x26, + 0x09, 0x06, 0x1b, 0x05, 0x01, 0xf0, 0x70, 0x61, 0x03, 0xf4, 0x70, 0x03, + 0x22, 0xf0, 0x7f, 0x62, 0x0b, 0x43, 0x13, 0x43, 0xc5, 0xf8, 0x64, 0x36, + 0x02, 0x23, 0xc5, 0xf8, 0x60, 0x36, 0xd5, 0xf8, 0x64, 0x36, 0x72, 0x79, + 0x23, 0xf0, 0xfe, 0x53, 0x23, 0xf4, 0x78, 0x13, 0x43, 0xea, 0x02, 0x53, + 0x43, 0xf4, 0x80, 0x23, 0xc5, 0xf8, 0x64, 0x36, 0x03, 0x23, 0xc5, 0xf8, + 0x60, 0x36, 0xd5, 0xf8, 0x64, 0x26, 0xb3, 0x68, 0x02, 0xf0, 0x7f, 0x42, + 0x23, 0xf0, 0x7f, 0x43, 0x13, 0x43, 0xc5, 0xf8, 0x64, 0x36, 0x23, 0x6a, + 0x01, 0x2b, 0x05, 0xdd, 0xd5, 0xf8, 0x00, 0x36, 0x43, 0xf4, 0x80, 0x63, + 0xc5, 0xf8, 0x00, 0x36, 0xb2, 0x78, 0xd5, 0xf8, 0x00, 0x16, 0x92, 0x00, + 0x4f, 0xf6, 0x83, 0x73, 0x02, 0xf0, 0x7c, 0x02, 0x0b, 0x40, 0x13, 0x43, + 0x32, 0x88, 0x7f, 0x32, 0xd2, 0x11, 0x01, 0x3a, 0x43, 0xea, 0x02, 0x43, + 0xc5, 0xf8, 0x00, 0x36, 0xf8, 0xbd, 0x00, 0x00, 0x2d, 0xe9, 0xff, 0x41, + 0x03, 0x6a, 0x04, 0x46, 0x04, 0x2b, 0x47, 0x6a, 0x03, 0xdd, 0x07, 0xf0, + 0xf8, 0x67, 0xbf, 0x0d, 0x02, 0xe0, 0x07, 0xf0, 0xf0, 0x77, 0x7f, 0x0d, + 0x20, 0x46, 0xe4, 0xf3, 0x57, 0xf7, 0x00, 0x21, 0x80, 0x46, 0x20, 0x46, + 0xe5, 0xf3, 0x24, 0xf1, 0x00, 0x25, 0x06, 0x46, 0x13, 0xe0, 0x10, 0x21, + 0x68, 0x46, 0x0d, 0x4a, 0x2b, 0x46, 0xdc, 0xf3, 0x6f, 0xf0, 0x00, 0x20, + 0x69, 0x46, 0xdc, 0xf3, 0xef, 0xf4, 0x38, 0xb1, 0x00, 0x21, 0x0a, 0x46, + 0xdc, 0xf3, 0xaa, 0xf3, 0xc6, 0xf8, 0x58, 0x56, 0xc6, 0xf8, 0x5c, 0x06, + 0x01, 0x35, 0xeb, 0xb2, 0xbb, 0x42, 0xe8, 0xd3, 0x20, 0x46, 0x41, 0x46, + 0xe5, 0xf3, 0x06, 0xf1, 0xbd, 0xe8, 0xff, 0x81, 0x63, 0x36, 0x86, 0x00, + 0x2d, 0xe9, 0xff, 0x41, 0x05, 0x46, 0xe4, 0xf3, 0x2b, 0xf7, 0x00, 0x21, + 0x80, 0x46, 0x28, 0x46, 0xe5, 0xf3, 0xf8, 0xf0, 0x2b, 0x6a, 0x07, 0x46, + 0x04, 0x2b, 0x6e, 0x6a, 0x01, 0xdd, 0xf6, 0x0e, 0x02, 0xe0, 0x06, 0xf0, + 0xf0, 0x56, 0x76, 0x0e, 0x00, 0x24, 0x13, 0xe0, 0x10, 0x21, 0x68, 0x46, + 0x0c, 0x4a, 0x23, 0x46, 0xdc, 0xf3, 0x3a, 0xf0, 0x00, 0x20, 0x69, 0x46, + 0xdc, 0xf3, 0xba, 0xf4, 0x38, 0xb1, 0x00, 0x21, 0x0a, 0x46, 0xdc, 0xf3, + 0x75, 0xf3, 0xc7, 0xf8, 0x50, 0x46, 0xc7, 0xf8, 0x54, 0x06, 0x01, 0x34, + 0xb4, 0x42, 0xe9, 0xd1, 0x28, 0x46, 0x41, 0x46, 0xe5, 0xf3, 0xd2, 0xf0, + 0xbd, 0xe8, 0xff, 0x81, 0x5b, 0x36, 0x86, 0x00, 0xf7, 0xb5, 0x05, 0x3a, + 0x06, 0x46, 0x1f, 0x46, 0x06, 0x2a, 0x2e, 0xd8, 0xdf, 0xe8, 0x02, 0xf0, + 0x04, 0x16, 0x0b, 0x0f, 0x08, 0x2d, 0x12, 0x00, 0x04, 0x23, 0x0f, 0x25, + 0x01, 0x24, 0x10, 0xe0, 0x04, 0x23, 0x0f, 0x25, 0x08, 0xe0, 0x03, 0x23, + 0x1f, 0x25, 0x00, 0x24, 0x09, 0xe0, 0x03, 0x23, 0x1f, 0x25, 0x05, 0xe0, + 0x02, 0x23, 0x03, 0x25, 0x11, 0x24, 0x02, 0xe0, 0x04, 0x23, 0x0f, 0x25, + 0x05, 0x24, 0x2f, 0x40, 0xa7, 0x40, 0x00, 0x93, 0x00, 0x21, 0x4f, 0xf4, + 0xcb, 0x62, 0x4f, 0xf0, 0xff, 0x33, 0x30, 0x46, 0xe4, 0xf3, 0xd8, 0xf6, + 0x30, 0x46, 0x00, 0x21, 0x40, 0xf2, 0x5c, 0x62, 0x15, 0xfa, 0x04, 0xf3, + 0x00, 0x97, 0xe4, 0xf3, 0xcf, 0xf6, 0xfe, 0xbd, 0x2d, 0xe9, 0xf0, 0x43, + 0x00, 0x24, 0x85, 0xb0, 0x05, 0x46, 0x02, 0x94, 0x03, 0x94, 0xe4, 0xf3, + 0xbd, 0xf6, 0x21, 0x46, 0x80, 0x46, 0x28, 0x46, 0xe5, 0xf3, 0x8a, 0xf0, + 0x6f, 0x6a, 0x04, 0x46, 0x07, 0xf4, 0xf8, 0x57, 0x3f, 0x0a, 0x03, 0x26, + 0x4b, 0x4b, 0x01, 0x3e, 0x03, 0xeb, 0xc6, 0x02, 0x13, 0xf8, 0x36, 0x30, + 0xc4, 0xf8, 0x20, 0x36, 0x53, 0x68, 0xc4, 0xf8, 0x28, 0x36, 0x00, 0x2e, + 0xf2, 0xd1, 0x1d, 0xe0, 0x08, 0x21, 0x68, 0x46, 0x44, 0x4a, 0x33, 0x46, + 0xdb, 0xf3, 0xc4, 0xf7, 0x00, 0x20, 0x69, 0x46, 0xdc, 0xf3, 0x44, 0xf4, + 0x88, 0xb1, 0x00, 0x21, 0x0a, 0x46, 0xdc, 0xf3, 0xff, 0xf2, 0x2b, 0x6a, + 0x0c, 0x2b, 0x06, 0xdd, 0xb0, 0xf5, 0x80, 0x3f, 0x03, 0xd2, 0xc3, 0xb2, + 0x00, 0x0a, 0x43, 0xea, 0x00, 0x40, 0xc4, 0xf8, 0x20, 0x66, 0xc4, 0xf8, + 0x28, 0x06, 0x01, 0x36, 0xbe, 0x42, 0xdf, 0xd1, 0x4f, 0xf0, 0x03, 0x09, + 0x35, 0x4e, 0x09, 0xf1, 0xff, 0x39, 0x06, 0xeb, 0x09, 0x16, 0xf3, 0x68, + 0x0b, 0xb9, 0x00, 0x23, 0x21, 0xe0, 0x28, 0x46, 0x98, 0x47, 0x00, 0xb3, + 0xf9, 0xe7, 0x01, 0x21, 0x99, 0x40, 0x32, 0x68, 0x11, 0x42, 0x17, 0xd0, + 0xc4, 0xf8, 0x20, 0x36, 0x96, 0xf9, 0x04, 0x20, 0x22, 0xb1, 0x01, 0x2a, + 0x04, 0xd0, 0x01, 0x32, 0x0e, 0xd1, 0x06, 0xe0, 0xb2, 0x68, 0x09, 0xe0, + 0xd4, 0xf8, 0x24, 0x16, 0xb2, 0x68, 0x0a, 0x43, 0x04, 0xe0, 0xd4, 0xf8, + 0x24, 0x26, 0xb1, 0x68, 0x22, 0xea, 0x01, 0x02, 0xc4, 0xf8, 0x24, 0x26, + 0x01, 0x33, 0xbb, 0x42, 0xdf, 0xd1, 0xb9, 0xf1, 0x00, 0x0f, 0xcf, 0xd1, + 0x4e, 0x46, 0x13, 0xe0, 0x08, 0x21, 0x68, 0x46, 0x1c, 0x4a, 0x33, 0x46, + 0xdb, 0xf3, 0x70, 0xf7, 0x00, 0x20, 0x69, 0x46, 0xdc, 0xf3, 0xf0, 0xf3, + 0x38, 0xb1, 0x00, 0x21, 0xc4, 0xf8, 0x20, 0x66, 0x0a, 0x46, 0xdc, 0xf3, + 0xa9, 0xf2, 0xc4, 0xf8, 0x24, 0x06, 0x01, 0x36, 0xbe, 0x42, 0xe9, 0xd1, + 0x02, 0xa9, 0x03, 0xaa, 0x28, 0x46, 0xdf, 0xf3, 0x8f, 0xf5, 0x03, 0x9b, + 0x02, 0x9a, 0xd4, 0xf8, 0x1c, 0x16, 0x13, 0x43, 0x19, 0x43, 0x03, 0x93, + 0xc4, 0xf8, 0x1c, 0x16, 0x23, 0xb1, 0xc4, 0xf8, 0x1c, 0x36, 0x0a, 0xb1, + 0xc4, 0xf8, 0x18, 0x26, 0x4f, 0xf4, 0xfa, 0x60, 0xe0, 0xf3, 0x90, 0xf2, + 0x28, 0x46, 0x41, 0x46, 0xe4, 0xf3, 0xf0, 0xf7, 0x05, 0xb0, 0xbd, 0xe8, + 0xf0, 0x83, 0x00, 0xbf, 0x90, 0x95, 0x02, 0x00, 0x51, 0x36, 0x86, 0x00, + 0x60, 0x95, 0x02, 0x00, 0x56, 0x36, 0x86, 0x00, 0xf8, 0xb5, 0x04, 0x46, + 0x16, 0x46, 0x0f, 0x46, 0xe4, 0xf3, 0x0c, 0xf6, 0x00, 0x21, 0x05, 0x46, + 0x20, 0x46, 0xe4, 0xf3, 0xd9, 0xf7, 0x39, 0x46, 0x02, 0x46, 0x33, 0x46, + 0x20, 0x46, 0xff, 0xf7, 0x15, 0xfe, 0x20, 0x46, 0x29, 0x46, 0xbd, 0xe8, + 0xf8, 0x40, 0xe4, 0xf3, 0xcd, 0xb7, 0x38, 0xb5, 0x04, 0x46, 0xe4, 0xf3, + 0xf7, 0xf5, 0x00, 0x21, 0x05, 0x46, 0x20, 0x46, 0xe4, 0xf3, 0xc4, 0xf7, + 0x23, 0x6a, 0x01, 0x2b, 0x04, 0xd1, 0xd0, 0xf8, 0x00, 0x36, 0x23, 0xf4, + 0x00, 0x73, 0x04, 0xe0, 0x05, 0xdd, 0xd0, 0xf8, 0x00, 0x36, 0x43, 0xf4, + 0x00, 0x73, 0xc0, 0xf8, 0x00, 0x36, 0x20, 0x46, 0x29, 0x46, 0xbd, 0xe8, + 0x38, 0x40, 0xe4, 0xf3, 0xaf, 0xb7, 0x00, 0x00, 0x38, 0xb5, 0x04, 0x46, + 0x0d, 0x46, 0xff, 0xf7, 0xa7, 0xfe, 0x00, 0x22, 0x29, 0x46, 0x20, 0x46, + 0xdf, 0xf3, 0x80, 0xf6, 0x20, 0x46, 0xe4, 0xf3, 0xcf, 0xf5, 0x0b, 0x49, + 0x05, 0x46, 0x00, 0x20, 0xdc, 0xf3, 0x48, 0xf3, 0x4f, 0xf4, 0x00, 0x22, + 0x10, 0xf0, 0x01, 0x03, 0x4f, 0xf0, 0x00, 0x01, 0x20, 0x46, 0x18, 0xbf, + 0x13, 0x46, 0xdf, 0xf3, 0xa1, 0xf5, 0x20, 0x46, 0x29, 0x46, 0xbd, 0xe8, + 0x38, 0x40, 0xe4, 0xf3, 0x8b, 0xb7, 0x00, 0xbf, 0x78, 0x36, 0x86, 0x00, + 0xf8, 0xb5, 0x03, 0x6a, 0x05, 0x46, 0x09, 0x2b, 0x2a, 0xdd, 0xe4, 0xf3, + 0xaf, 0xf5, 0x00, 0x21, 0x06, 0x46, 0x28, 0x46, 0xe4, 0xf3, 0x7c, 0xf7, + 0xd0, 0xf8, 0x08, 0x46, 0x07, 0x46, 0x14, 0xf4, 0x80, 0x74, 0x18, 0xd0, + 0x4f, 0xf0, 0x00, 0x43, 0xc0, 0xf8, 0x6c, 0x36, 0x4f, 0xf4, 0x7a, 0x70, + 0xe0, 0xf3, 0x0a, 0xf2, 0xd7, 0xf8, 0x6c, 0x46, 0x00, 0x23, 0xe4, 0x04, + 0xe4, 0x0c, 0x64, 0x03, 0xc7, 0xf8, 0x6c, 0x36, 0x04, 0xf5, 0x42, 0x44, + 0x07, 0x4b, 0x04, 0xf5, 0xa8, 0x74, 0xb4, 0xfb, 0xf3, 0xf4, 0x64, 0x23, + 0x5c, 0x43, 0x28, 0x46, 0x31, 0x46, 0xe4, 0xf3, 0x59, 0xf7, 0x00, 0xe0, + 0x00, 0x24, 0x20, 0x46, 0xf8, 0xbd, 0x00, 0xbf, 0xa0, 0x86, 0x01, 0x00, + 0xf8, 0xb5, 0x04, 0x46, 0x0d, 0x46, 0x00, 0x20, 0x16, 0x49, 0xdc, 0xf3, + 0xf7, 0xf2, 0x16, 0x49, 0x87, 0xb2, 0x00, 0x20, 0xdc, 0xf3, 0xf2, 0xf2, + 0x40, 0xf2, 0xdc, 0x51, 0x00, 0x2f, 0x18, 0xbf, 0x39, 0x46, 0xc6, 0xb2, + 0x20, 0x46, 0xff, 0xf7, 0x6b, 0xfd, 0x00, 0x28, 0x0c, 0xdb, 0xc7, 0xb2, + 0x29, 0x46, 0x20, 0x46, 0x07, 0x22, 0x3b, 0x46, 0xff, 0xf7, 0x66, 0xfe, + 0x20, 0x46, 0x29, 0x46, 0x08, 0x22, 0x3b, 0x46, 0xff, 0xf7, 0x60, 0xfe, + 0x2e, 0xb1, 0x20, 0x46, 0x29, 0x46, 0x32, 0x46, 0x01, 0x23, 0xe6, 0xf7, + 0xdd, 0xfc, 0x20, 0x46, 0x29, 0x46, 0xbd, 0xe8, 0xf8, 0x40, 0xff, 0xf7, + 0xe7, 0xbd, 0x00, 0xbf, 0x6f, 0x36, 0x86, 0x00, 0xfc, 0xda, 0x01, 0x00, + 0x38, 0xb5, 0x00, 0x21, 0x05, 0x46, 0x10, 0x20, 0xe0, 0xf3, 0x0c, 0xf0, + 0x00, 0x21, 0x04, 0x46, 0x10, 0x22, 0xdb, 0xf3, 0x21, 0xf6, 0x65, 0x60, + 0x20, 0x46, 0x38, 0xbd, 0x38, 0xb5, 0x0c, 0x46, 0x15, 0x46, 0xe4, 0xf3, + 0x73, 0xf6, 0x10, 0x21, 0xe0, 0xf3, 0x5e, 0xf4, 0x48, 0xb1, 0x10, 0x23, + 0x43, 0x60, 0x05, 0x4b, 0xc4, 0x60, 0x1a, 0x68, 0x85, 0x60, 0x02, 0x60, + 0x18, 0x60, 0x00, 0x20, 0x38, 0xbd, 0x6f, 0xf0, 0x1a, 0x00, 0x38, 0xbd, + 0x6c, 0x27, 0x00, 0x00, 0x08, 0xb5, 0x06, 0x4b, 0x1b, 0x68, 0x3b, 0xb9, + 0x05, 0x4b, 0x19, 0x68, 0x21, 0xb1, 0x05, 0x4b, 0x1a, 0x68, 0x0a, 0xb1, + 0xff, 0xf7, 0xdc, 0xff, 0x00, 0x20, 0x08, 0xbd, 0x6c, 0x27, 0x00, 0x00, + 0xe8, 0xfe, 0x01, 0x00, 0xec, 0xfe, 0x01, 0x00, 0x38, 0xb5, 0x0c, 0x46, + 0x15, 0x46, 0xe4, 0xf3, 0x47, 0xf6, 0x10, 0x21, 0xe0, 0xf3, 0x32, 0xf4, + 0x90, 0xb1, 0x10, 0x23, 0x0a, 0x4a, 0x43, 0x60, 0x00, 0x23, 0x03, 0x60, + 0x13, 0x68, 0xc4, 0x60, 0x85, 0x60, 0x1b, 0xb9, 0x10, 0x60, 0x18, 0x46, + 0x38, 0xbd, 0x13, 0x46, 0x1a, 0x68, 0x00, 0x2a, 0xfb, 0xd1, 0x18, 0x60, + 0x10, 0x46, 0x38, 0xbd, 0x6f, 0xf0, 0x1a, 0x00, 0x38, 0xbd, 0x00, 0xbf, + 0x6c, 0x27, 0x00, 0x00, 0x38, 0xb5, 0x0c, 0x46, 0x15, 0x46, 0xe4, 0xf3, + 0x25, 0xf6, 0x10, 0x21, 0xe0, 0xf3, 0x10, 0xf4, 0x48, 0xb1, 0x10, 0x23, + 0x43, 0x60, 0x05, 0x4b, 0xc4, 0x60, 0x1a, 0x68, 0x85, 0x60, 0x02, 0x60, + 0x18, 0x60, 0x00, 0x20, 0x38, 0xbd, 0x6f, 0xf0, 0x1a, 0x00, 0x38, 0xbd, + 0x6c, 0x27, 0x00, 0x00, 0x01, 0x20, 0x70, 0x47, 0x00, 0x20, 0x70, 0x47, + 0x38, 0xb5, 0x41, 0xf2, 0xe4, 0x43, 0x04, 0x46, 0xc3, 0x62, 0x0d, 0x46, + 0x29, 0xb1, 0x08, 0x46, 0x09, 0x49, 0xdc, 0xf3, 0x45, 0xf2, 0xa0, 0x62, + 0x40, 0xb9, 0x00, 0x20, 0x07, 0x49, 0xdc, 0xf3, 0x3f, 0xf2, 0xa0, 0x62, + 0x10, 0xb9, 0x4f, 0xf6, 0xff, 0x73, 0xa3, 0x62, 0x28, 0x46, 0x04, 0x49, + 0xdc, 0xf3, 0x36, 0xf2, 0x20, 0x63, 0x38, 0xbd, 0x54, 0x37, 0x86, 0x00, + 0x5b, 0x37, 0x86, 0x00, 0x86, 0x37, 0x86, 0x00, 0x30, 0xb5, 0x85, 0xb0, + 0x01, 0x90, 0x00, 0x24, 0x04, 0xa8, 0x40, 0xf8, 0x04, 0x4d, 0x01, 0xa9, + 0x04, 0x22, 0xdb, 0xf3, 0x23, 0xf5, 0x01, 0x9d, 0xcd, 0xb1, 0x2b, 0x46, + 0xd3, 0xf8, 0x88, 0x20, 0x12, 0xb1, 0x00, 0x22, 0xc3, 0xf8, 0x88, 0x20, + 0x01, 0x34, 0x04, 0x33, 0x10, 0x2c, 0xf5, 0xd1, 0x03, 0x98, 0xdb, 0xf3, + 0xb1, 0xf4, 0x03, 0x98, 0xe6, 0xf7, 0x4a, 0xfc, 0x05, 0x4b, 0x9d, 0x42, + 0x05, 0xd0, 0x68, 0x6d, 0x29, 0x46, 0x4f, 0xf4, 0x56, 0x72, 0xe0, 0xf3, + 0xc3, 0xf3, 0x05, 0xb0, 0x30, 0xbd, 0x00, 0xbf, 0x88, 0x08, 0x02, 0x00, + 0x2d, 0xe9, 0xf8, 0x43, 0x00, 0x21, 0x04, 0x46, 0x98, 0x46, 0x08, 0x9f, + 0xdd, 0xf8, 0x24, 0x90, 0xe4, 0xf3, 0x4c, 0xf6, 0x05, 0x46, 0x20, 0x46, + 0xe4, 0xf3, 0x88, 0xf4, 0x0a, 0x28, 0xc8, 0xbf, 0xeb, 0x6a, 0x60, 0x61, + 0xc8, 0xbf, 0x63, 0x64, 0x22, 0x28, 0x6b, 0x68, 0xc8, 0xbf, 0xd5, 0xf8, + 0xac, 0x20, 0xa3, 0x61, 0xc8, 0xbf, 0xe2, 0x61, 0xdb, 0x00, 0x04, 0xd5, + 0xd5, 0xf8, 0x04, 0x36, 0x63, 0x62, 0xdb, 0xb2, 0x23, 0x62, 0x4f, 0xf4, + 0xe0, 0x63, 0xa3, 0x60, 0x4f, 0xf0, 0xff, 0x33, 0xe3, 0x60, 0x11, 0x23, + 0x23, 0x61, 0x26, 0x46, 0x00, 0x25, 0x13, 0xe0, 0x29, 0x46, 0xe4, 0xf3, + 0x25, 0xf6, 0x20, 0x46, 0xe4, 0xf3, 0x62, 0xf4, 0xb8, 0xf1, 0x00, 0x0f, + 0x03, 0xd0, 0xd6, 0xf8, 0x10, 0x31, 0x98, 0x45, 0x03, 0xd0, 0xd6, 0xf8, + 0x88, 0x30, 0x99, 0x45, 0x00, 0xd1, 0x3d, 0x60, 0x01, 0x35, 0x04, 0x36, + 0xd4, 0xf8, 0xcc, 0x30, 0x20, 0x46, 0x9d, 0x42, 0xe6, 0xd3, 0x39, 0x68, + 0xe4, 0xf3, 0x0c, 0xf6, 0x01, 0x20, 0xbd, 0xe8, 0xf8, 0x83, 0x00, 0x00, + 0x2d, 0xe9, 0xff, 0x47, 0x0c, 0x9d, 0x92, 0x46, 0xdd, 0xf8, 0x34, 0x90, + 0x88, 0x46, 0x4f, 0xf4, 0x56, 0x72, 0x00, 0x21, 0x04, 0x46, 0x1f, 0x46, + 0x0e, 0x9e, 0x01, 0x2d, 0x08, 0xbf, 0x00, 0x25, 0xdb, 0xf3, 0x06, 0xf5, + 0x11, 0x23, 0x23, 0x61, 0xc4, 0xf8, 0x84, 0x70, 0xc4, 0xf8, 0x58, 0x90, + 0xc4, 0xf8, 0x54, 0xa0, 0x65, 0x60, 0x00, 0x2d, 0x40, 0xf0, 0xb3, 0x80, + 0x20, 0x46, 0x29, 0x46, 0x42, 0x46, 0x4b, 0x46, 0xff, 0xf7, 0x3c, 0xff, + 0x00, 0x28, 0x00, 0xf0, 0xae, 0x80, 0x4f, 0xf0, 0xc0, 0x59, 0xd9, 0xf8, + 0x00, 0x30, 0x20, 0x46, 0x1a, 0x0f, 0x22, 0x60, 0x9a, 0xb2, 0xa2, 0x63, + 0x03, 0xf4, 0x70, 0x22, 0x03, 0xf4, 0x70, 0x03, 0x1b, 0x0d, 0x23, 0x64, + 0x0e, 0x3b, 0x12, 0x0c, 0x01, 0x2b, 0x8c, 0xbf, 0x00, 0x23, 0x01, 0x23, + 0xe2, 0x63, 0x84, 0xf8, 0x48, 0x30, 0x49, 0x46, 0x42, 0x46, 0xfe, 0xf7, + 0x3f, 0xf8, 0xd4, 0xf8, 0xcc, 0x30, 0x00, 0x2b, 0x00, 0xf0, 0x8b, 0x80, + 0x04, 0xab, 0x43, 0xf8, 0x04, 0x5d, 0x8d, 0xe8, 0x88, 0x00, 0x20, 0x46, + 0x49, 0x46, 0x2a, 0x46, 0x2b, 0x46, 0xff, 0xf7, 0x5f, 0xff, 0x00, 0x28, + 0x7f, 0xd0, 0x20, 0x46, 0xff, 0xf7, 0xba, 0xfe, 0x0f, 0x9b, 0x00, 0x96, + 0x01, 0x93, 0x20, 0x46, 0x29, 0x46, 0x3a, 0x46, 0x63, 0x6d, 0xff, 0xf7, + 0xc3, 0xfb, 0x00, 0x28, 0x73, 0xd1, 0x06, 0xb1, 0x36, 0x68, 0x3b, 0x4f, + 0x20, 0x46, 0x31, 0x46, 0xff, 0xf7, 0xfa, 0xfe, 0x3d, 0x78, 0x00, 0x2d, + 0x2f, 0xd1, 0x63, 0x69, 0x13, 0x2b, 0x0b, 0xdd, 0x4f, 0xf4, 0x00, 0x61, + 0x20, 0x46, 0x2a, 0x46, 0xe4, 0xf3, 0x80, 0xf5, 0x03, 0x99, 0x85, 0x65, + 0xc5, 0x65, 0x20, 0x46, 0xe4, 0xf3, 0x8c, 0xf5, 0x20, 0x46, 0x61, 0x6d, + 0xff, 0xf7, 0xbb, 0xfd, 0x20, 0x46, 0x61, 0x6d, 0xff, 0xf7, 0xd6, 0xfd, + 0x30, 0x46, 0x2c, 0x49, 0xdc, 0xf3, 0x2c, 0xf1, 0x02, 0x46, 0x20, 0xb9, + 0x20, 0x46, 0x61, 0x6d, 0xff, 0xf7, 0xf2, 0xfd, 0x02, 0x46, 0x20, 0x46, + 0x61, 0x6d, 0xff, 0xf7, 0x91, 0xfd, 0x20, 0x46, 0x61, 0x6d, 0xff, 0xf7, + 0xd9, 0xfc, 0x20, 0x46, 0x61, 0x6d, 0xff, 0xf7, 0x1b, 0xfe, 0x01, 0x23, + 0x3b, 0x70, 0x63, 0x69, 0x0f, 0x2b, 0x0f, 0xdd, 0x1f, 0x49, 0x30, 0x46, + 0xdc, 0xf3, 0x10, 0xf1, 0x1e, 0x4b, 0x00, 0x21, 0x00, 0x28, 0x08, 0xbf, + 0x18, 0x46, 0x00, 0x90, 0x88, 0x22, 0x20, 0x46, 0x4f, 0xf0, 0xff, 0x33, + 0xe4, 0xf3, 0x8e, 0xf3, 0x30, 0x46, 0x19, 0x49, 0xdc, 0xf3, 0x2c, 0xf1, + 0x38, 0xb1, 0x17, 0x49, 0x30, 0x46, 0xdc, 0xf3, 0xfb, 0xf0, 0x01, 0x46, + 0x20, 0x46, 0xe6, 0xf7, 0x48, 0xfb, 0x63, 0x69, 0x14, 0x2b, 0x17, 0xdd, + 0x00, 0x25, 0x29, 0x46, 0x08, 0x22, 0x2b, 0x46, 0x20, 0x46, 0x00, 0x95, + 0xe4, 0xf3, 0x76, 0xf3, 0x29, 0x46, 0x40, 0xf0, 0x04, 0x03, 0x08, 0x22, + 0x20, 0x46, 0x00, 0x93, 0xe4, 0xf3, 0x6e, 0xf3, 0x06, 0xe0, 0x00, 0x24, + 0x04, 0xe0, 0x1c, 0x46, 0x02, 0xe0, 0x04, 0x46, 0x00, 0xe0, 0x2c, 0x46, + 0x20, 0x46, 0x04, 0xb0, 0xbd, 0xe8, 0xf0, 0x87, 0xe0, 0x0b, 0x02, 0x00, + 0xe2, 0x38, 0x86, 0x00, 0xeb, 0x38, 0x86, 0x00, 0x5a, 0x00, 0x0a, 0x00, + 0xf1, 0x38, 0x86, 0x00, 0x1f, 0xb5, 0x0f, 0x4c, 0x02, 0x46, 0x23, 0x78, + 0xbb, 0xb9, 0x10, 0xb9, 0x03, 0x46, 0x01, 0x46, 0x01, 0xe0, 0x0c, 0x4b, + 0x19, 0x1d, 0x00, 0x20, 0x00, 0x90, 0x01, 0x90, 0x02, 0x93, 0x03, 0x91, + 0x09, 0x48, 0x44, 0xf2, 0x10, 0x71, 0x4f, 0xf0, 0xc0, 0x53, 0xff, 0xf7, + 0x03, 0xff, 0x28, 0xb1, 0x06, 0x4b, 0x20, 0x22, 0x1a, 0x60, 0x01, 0x23, + 0x23, 0x70, 0x03, 0x48, 0x04, 0xb0, 0x10, 0xbd, 0x84, 0x08, 0x02, 0x00, + 0x04, 0x09, 0x02, 0x00, 0x88, 0x08, 0x02, 0x00, 0x74, 0x27, 0x00, 0x00, + 0x2d, 0xe9, 0xff, 0x47, 0x80, 0x46, 0x0f, 0x46, 0x08, 0x46, 0x4f, 0xf4, + 0x56, 0x71, 0x91, 0x46, 0x9a, 0x46, 0x0d, 0x9e, 0x0e, 0x9d, 0xe0, 0xf3, + 0x45, 0xf2, 0x04, 0x46, 0xd8, 0xb1, 0x0c, 0x9b, 0x41, 0x46, 0x01, 0x93, + 0x3a, 0x46, 0x4b, 0x46, 0xcd, 0xf8, 0x00, 0xa0, 0x02, 0x96, 0x03, 0x95, + 0xff, 0xf7, 0xd8, 0xfe, 0x80, 0x46, 0x38, 0xb9, 0x21, 0x46, 0x38, 0x46, + 0x4f, 0xf4, 0x56, 0x72, 0xe0, 0xf3, 0x40, 0xf2, 0x44, 0x46, 0x06, 0xe0, + 0x06, 0xb1, 0x36, 0x68, 0xe6, 0x67, 0x05, 0xb1, 0x2d, 0x68, 0xc4, 0xf8, + 0x80, 0x50, 0x20, 0x46, 0x04, 0xb0, 0xbd, 0xe8, 0xf0, 0x87, 0x00, 0x20, + 0xdc, 0xf3, 0x74, 0xb0, 0x10, 0xb5, 0x0b, 0x49, 0x04, 0x46, 0xff, 0xf7, + 0xf8, 0xff, 0x80, 0xb2, 0x78, 0xb9, 0xe0, 0x6f, 0x07, 0x49, 0xdc, 0xf3, + 0x69, 0xf0, 0x80, 0xb2, 0x48, 0xb9, 0xe0, 0x6f, 0x05, 0x49, 0xdc, 0xf3, + 0x63, 0xf0, 0x4f, 0xf6, 0xff, 0x73, 0x80, 0xb2, 0x00, 0x28, 0x08, 0xbf, + 0x18, 0x46, 0x10, 0xbd, 0x48, 0x37, 0x86, 0x00, 0x4e, 0x37, 0x86, 0x00, + 0x73, 0xb5, 0x00, 0x23, 0xad, 0xf8, 0x06, 0x30, 0x83, 0x69, 0x04, 0x46, + 0x99, 0x00, 0x65, 0xd5, 0x83, 0x68, 0xb3, 0xf5, 0x02, 0x6f, 0x09, 0xd0, + 0x40, 0xf6, 0x04, 0x02, 0x93, 0x42, 0x07, 0xd1, 0xc5, 0x68, 0x0c, 0x2d, + 0x94, 0xbf, 0x00, 0x25, 0x01, 0x25, 0x02, 0xe0, 0x01, 0x25, 0x00, 0xe0, + 0x00, 0x25, 0xed, 0xb2, 0x4d, 0xb9, 0x20, 0x46, 0x4f, 0xf4, 0x00, 0x61, + 0x2a, 0x46, 0xd4, 0xf8, 0xc8, 0x60, 0xe4, 0xf3, 0x77, 0xf4, 0x30, 0xb9, + 0x48, 0xe0, 0xd4, 0xf8, 0x84, 0x00, 0x10, 0xf5, 0x40, 0x50, 0x43, 0xd0, + 0x00, 0x26, 0x63, 0x69, 0x22, 0x2b, 0x4f, 0xf0, 0x00, 0x03, 0xd8, 0xbf, + 0xc0, 0xf8, 0x68, 0x31, 0xc0, 0xf8, 0x64, 0x31, 0xc0, 0xf8, 0x60, 0x31, + 0x63, 0x69, 0x22, 0x2b, 0x03, 0xdc, 0x1d, 0x4b, 0xc0, 0xf8, 0x44, 0x31, + 0x05, 0xe0, 0x01, 0x23, 0xc0, 0xf8, 0x48, 0x31, 0xff, 0x23, 0xc0, 0xf8, + 0x4c, 0x31, 0x63, 0x69, 0x22, 0x2b, 0x4f, 0xf0, 0x00, 0x03, 0x06, 0xdc, + 0xc0, 0xf8, 0x80, 0x31, 0xc0, 0xf8, 0x7c, 0x31, 0xc0, 0xf8, 0x78, 0x31, + 0x03, 0xe0, 0xc0, 0xf8, 0x74, 0x31, 0xc0, 0xf8, 0x70, 0x31, 0x1d, 0xb9, + 0x20, 0x46, 0x31, 0x46, 0xe4, 0xf3, 0x54, 0xf4, 0x20, 0x46, 0x0d, 0xf1, + 0x06, 0x01, 0xff, 0xf7, 0xa9, 0xfd, 0x90, 0xb9, 0xbd, 0xf8, 0x06, 0x00, + 0x80, 0xb1, 0x63, 0x69, 0x20, 0x46, 0x22, 0x2b, 0xd9, 0xbf, 0x4f, 0xf4, + 0x80, 0x21, 0x0a, 0x46, 0x06, 0x49, 0x40, 0x22, 0x00, 0x23, 0xe4, 0xf3, + 0x8f, 0xf2, 0x02, 0xe0, 0x4f, 0xf0, 0xff, 0x30, 0x00, 0xe0, 0x00, 0x20, + 0x7c, 0xbd, 0x00, 0xbf, 0x00, 0x00, 0xfb, 0xbf, 0x40, 0x00, 0x55, 0x55, + 0x2d, 0xe9, 0xff, 0x41, 0x03, 0x68, 0x05, 0x46, 0x70, 0x21, 0xd8, 0x68, + 0xe0, 0xf3, 0x84, 0xf1, 0x04, 0x46, 0x00, 0x28, 0x43, 0xd0, 0x00, 0x21, + 0x70, 0x22, 0xdb, 0xf3, 0x35, 0xf3, 0x04, 0x23, 0x63, 0x60, 0xb4, 0x23, + 0x25, 0x60, 0xa3, 0x81, 0xa0, 0x46, 0x27, 0x46, 0x00, 0x26, 0x0d, 0xe0, + 0x18, 0x22, 0x02, 0xfb, 0x06, 0x42, 0x3c, 0x61, 0xa8, 0x68, 0x1b, 0x49, + 0x10, 0x32, 0x00, 0x23, 0xe8, 0xf3, 0x5e, 0xf6, 0x38, 0x62, 0x18, 0x37, + 0xf0, 0xb1, 0x01, 0x36, 0x63, 0x68, 0x9e, 0x42, 0xee, 0xdb, 0x16, 0x4b, + 0x16, 0x49, 0x00, 0x93, 0x00, 0x23, 0x01, 0x93, 0x02, 0x93, 0x03, 0x93, + 0x28, 0x68, 0x14, 0x4a, 0x23, 0x46, 0xfd, 0xf3, 0x5b, 0xf2, 0x18, 0xe0, + 0xd8, 0xf8, 0x20, 0x10, 0x31, 0xb1, 0x23, 0x68, 0x98, 0x68, 0xe8, 0xf3, + 0x27, 0xf6, 0x00, 0x23, 0xc8, 0xf8, 0x20, 0x30, 0x01, 0x35, 0x08, 0xf1, + 0x18, 0x08, 0x00, 0xe0, 0x05, 0x46, 0x63, 0x68, 0x9d, 0x42, 0xed, 0xdb, + 0x23, 0x68, 0x21, 0x46, 0x58, 0x68, 0x70, 0x22, 0xe0, 0xf3, 0x4e, 0xf1, + 0x00, 0x24, 0x20, 0x46, 0x04, 0xb0, 0xbd, 0xe8, 0xf0, 0x81, 0x00, 0xbf, + 0xf1, 0xd3, 0x00, 0x00, 0x83, 0xd2, 0x00, 0x00, 0xe4, 0xdb, 0x01, 0x00, + 0x09, 0xdc, 0x01, 0x00, 0x70, 0xb5, 0x04, 0x46, 0x00, 0x28, 0x26, 0xd0, + 0x03, 0x68, 0x13, 0x49, 0x18, 0x68, 0x22, 0x46, 0xfd, 0xf3, 0x62, 0xf2, + 0x25, 0x46, 0x00, 0x26, 0x10, 0xe0, 0x29, 0x6a, 0x29, 0xb1, 0x23, 0x68, + 0x98, 0x68, 0xe8, 0xf3, 0xf5, 0xf5, 0x00, 0x23, 0x2b, 0x62, 0xe9, 0x69, + 0x21, 0xb1, 0x23, 0x68, 0x2a, 0x8b, 0x58, 0x68, 0xe0, 0xf3, 0x24, 0xf1, + 0x01, 0x36, 0x18, 0x35, 0x63, 0x68, 0x9e, 0x42, 0xeb, 0xdb, 0x18, 0x22, + 0x5a, 0x43, 0x21, 0x68, 0x10, 0x32, 0x48, 0x68, 0x21, 0x46, 0xbd, 0xe8, + 0x70, 0x40, 0xe0, 0xf3, 0x15, 0xb1, 0x70, 0xbd, 0x08, 0xdc, 0x01, 0x00, + 0x00, 0x20, 0x70, 0x47, 0x10, 0xb5, 0x04, 0x46, 0xa8, 0xb1, 0x09, 0xf0, + 0xb5, 0xdf, 0x0a, 0x49, 0x60, 0x68, 0x22, 0x46, 0xfd, 0xf3, 0x32, 0xf2, + 0xe1, 0x6e, 0x21, 0xb1, 0x63, 0x68, 0x3c, 0x22, 0xd8, 0x68, 0xe0, 0xf3, + 0xff, 0xf0, 0x63, 0x68, 0x21, 0x46, 0xd8, 0x68, 0x70, 0x22, 0xbd, 0xe8, + 0x10, 0x40, 0xe0, 0xf3, 0xf7, 0xb0, 0x10, 0xbd, 0xd5, 0x8d, 0x86, 0x00, + 0x30, 0xb5, 0x70, 0x21, 0x85, 0xb0, 0x05, 0x46, 0x40, 0x68, 0xe0, 0xf3, + 0xdd, 0xf0, 0x04, 0x46, 0x00, 0x28, 0x2f, 0xd0, 0x00, 0x21, 0x70, 0x22, + 0xdb, 0xf3, 0x8e, 0xf2, 0x2b, 0x68, 0x25, 0x60, 0x63, 0x60, 0x68, 0x68, + 0x3c, 0x21, 0xe0, 0xf3, 0xcf, 0xf0, 0xe0, 0x66, 0xf0, 0xb1, 0x00, 0x21, + 0x3c, 0x22, 0xdb, 0xf3, 0x81, 0xf2, 0x11, 0x4b, 0x11, 0x49, 0x00, 0x93, + 0x00, 0x23, 0x01, 0x93, 0x02, 0x93, 0x10, 0x4b, 0x10, 0x4a, 0x03, 0x93, + 0x60, 0x68, 0x23, 0x46, 0xfd, 0xf3, 0xc0, 0xf1, 0x60, 0xb9, 0x01, 0x23, + 0x63, 0x82, 0xa3, 0x82, 0x20, 0x46, 0x29, 0x46, 0xff, 0xf7, 0xb2, 0xff, + 0x00, 0x28, 0x03, 0xdb, 0x20, 0x46, 0x0a, 0xf0, 0x65, 0xd8, 0x03, 0xe0, + 0x20, 0x46, 0xff, 0xf7, 0xab, 0xff, 0x00, 0x24, 0x20, 0x46, 0x05, 0xb0, + 0x30, 0xbd, 0x00, 0xbf, 0x39, 0x0b, 0x83, 0x00, 0x40, 0xe1, 0x85, 0x00, + 0x29, 0x0c, 0x83, 0x00, 0xd5, 0x8d, 0x86, 0x00, 0x10, 0xb5, 0x04, 0x46, + 0x68, 0xb1, 0x03, 0x68, 0x22, 0x46, 0x18, 0x68, 0x05, 0x49, 0xfd, 0xf3, + 0xd1, 0xf1, 0x23, 0x68, 0x21, 0x46, 0x58, 0x68, 0x08, 0x22, 0xbd, 0xe8, + 0x10, 0x40, 0xe0, 0xf3, 0x9d, 0xb0, 0x10, 0xbd, 0xcc, 0xbb, 0x86, 0x00, + 0x7f, 0xb5, 0x05, 0x46, 0x08, 0x21, 0x40, 0x68, 0xe0, 0xf3, 0x84, 0xf0, + 0x04, 0x46, 0x18, 0xb3, 0x00, 0x21, 0x08, 0x22, 0xdb, 0xf3, 0x36, 0xf2, + 0x00, 0x26, 0x04, 0x21, 0x28, 0x46, 0x10, 0x4a, 0x10, 0x4b, 0x00, 0x96, + 0x01, 0x94, 0x01, 0xf0, 0x23, 0xff, 0xb0, 0x42, 0x60, 0x60, 0x0f, 0xdb, + 0x0d, 0x4b, 0x28, 0x68, 0x00, 0x93, 0x0d, 0x4b, 0x0d, 0x49, 0x01, 0x93, + 0x0d, 0x4b, 0x0e, 0x4a, 0x03, 0x93, 0x23, 0x46, 0x02, 0x96, 0xfd, 0xf3, + 0x69, 0xf1, 0x08, 0xb9, 0x25, 0x60, 0x03, 0xe0, 0x20, 0x46, 0xff, 0xf7, + 0xc1, 0xff, 0x00, 0x24, 0x20, 0x46, 0x04, 0xb0, 0x70, 0xbd, 0x00, 0xbf, + 0x0f, 0xdd, 0x00, 0x00, 0xff, 0xe6, 0x00, 0x00, 0x03, 0xdd, 0x00, 0x00, + 0xff, 0xdc, 0x00, 0x00, 0x48, 0xdc, 0x01, 0x00, 0xfb, 0xdc, 0x00, 0x00, + 0xcc, 0xbb, 0x86, 0x00, 0xf8, 0xb5, 0x05, 0x68, 0x04, 0x46, 0x1b, 0x49, + 0x28, 0x68, 0x22, 0x46, 0xfd, 0xf3, 0x80, 0xf1, 0x00, 0x26, 0xb3, 0x01, + 0x03, 0xf5, 0x84, 0x73, 0xe1, 0x58, 0xe7, 0x18, 0x19, 0xb1, 0x68, 0x68, + 0x3a, 0x89, 0xe0, 0xf3, 0x49, 0xf0, 0x79, 0x68, 0x19, 0xb1, 0x68, 0x68, + 0x7a, 0x89, 0xe0, 0xf3, 0x43, 0xf0, 0x01, 0x36, 0x04, 0x2e, 0xec, 0xd1, + 0xd4, 0xf8, 0x0c, 0x12, 0x21, 0xb1, 0x68, 0x68, 0xb4, 0xf8, 0x10, 0x22, + 0xe0, 0xf3, 0x38, 0xf0, 0xd4, 0xf8, 0x1c, 0x12, 0x11, 0xb1, 0xa8, 0x68, + 0xe8, 0xf3, 0xfa, 0xf4, 0xd4, 0xf8, 0x20, 0x12, 0x19, 0xb1, 0x68, 0x68, + 0x04, 0x22, 0xe0, 0xf3, 0x2b, 0xf0, 0x68, 0x68, 0x21, 0x46, 0x4f, 0xf4, + 0x23, 0x72, 0xbd, 0xe8, 0xf8, 0x40, 0xe0, 0xf3, 0x23, 0xb0, 0x00, 0xbf, + 0x54, 0xdc, 0x01, 0x00, 0x2d, 0xe9, 0xf0, 0x41, 0x06, 0x46, 0x0f, 0x46, + 0xc0, 0x68, 0x2c, 0x21, 0x15, 0x46, 0x98, 0x46, 0xe0, 0xf3, 0x06, 0xf0, + 0x04, 0x46, 0xc0, 0xb1, 0x00, 0x21, 0x2c, 0x22, 0xdb, 0xf3, 0xb8, 0xf1, + 0xe5, 0x60, 0x28, 0x46, 0xc4, 0xf8, 0x1c, 0x80, 0xa7, 0x60, 0x26, 0x61, + 0x08, 0x49, 0x22, 0x46, 0x00, 0x23, 0xe8, 0xf3, 0xe9, 0xf4, 0x05, 0x46, + 0xa0, 0x61, 0x30, 0xb9, 0x23, 0x69, 0x21, 0x46, 0xd8, 0x68, 0x2c, 0x22, + 0xdf, 0xf3, 0xfc, 0xf7, 0x2c, 0x46, 0x20, 0x46, 0xbd, 0xe8, 0xf0, 0x81, + 0x3d, 0x66, 0x84, 0x00, 0x10, 0xb5, 0x04, 0x46, 0xe8, 0xf7, 0x43, 0xf8, + 0xa1, 0x69, 0x61, 0xb1, 0x23, 0x7d, 0x23, 0xb1, 0xe0, 0x68, 0xe8, 0xf3, + 0xa1, 0xf4, 0x00, 0x23, 0x23, 0x75, 0xe0, 0x68, 0xa1, 0x69, 0xe8, 0xf3, + 0xad, 0xf4, 0x00, 0x23, 0xa3, 0x61, 0x23, 0x69, 0x21, 0x46, 0xd8, 0x68, + 0x2c, 0x22, 0xdf, 0xf3, 0xdd, 0xf7, 0x00, 0x20, 0x10, 0xbd, 0x00, 0x00, + 0x38, 0xb5, 0x05, 0x68, 0x04, 0x46, 0x22, 0x46, 0x28, 0x68, 0x05, 0x49, + 0xfd, 0xf3, 0xfe, 0xf0, 0x68, 0x68, 0x21, 0x46, 0x50, 0x22, 0xbd, 0xe8, + 0x38, 0x40, 0xdf, 0xf3, 0xcb, 0xb7, 0x00, 0xbf, 0x3c, 0xe4, 0x86, 0x00, + 0x1f, 0xb5, 0x08, 0x4a, 0x03, 0x46, 0x00, 0x92, 0x00, 0x22, 0x01, 0x92, + 0x02, 0x92, 0x03, 0x92, 0x05, 0x49, 0x06, 0x4a, 0x00, 0x68, 0xfd, 0xf3, + 0xaf, 0xf0, 0x00, 0x30, 0x18, 0xbf, 0x01, 0x20, 0x05, 0xb0, 0x00, 0xbd, + 0x01, 0xf3, 0x00, 0x00, 0xc4, 0xdd, 0x01, 0x00, 0x18, 0xdd, 0x01, 0x00, + 0x70, 0xb5, 0xd0, 0xf8, 0xb8, 0x40, 0x0e, 0x46, 0x08, 0x46, 0x00, 0x29, + 0x1f, 0xd0, 0xdb, 0xf3, 0xdf, 0xf1, 0x05, 0x46, 0x90, 0xb9, 0x1a, 0xe0, + 0x20, 0x46, 0x31, 0x46, 0x2a, 0x46, 0xdb, 0xf3, 0xc7, 0xf0, 0x28, 0xb9, + 0x63, 0x5d, 0x3d, 0x2b, 0x02, 0xd1, 0x01, 0x35, 0x60, 0x19, 0x70, 0xbd, + 0x23, 0x46, 0x13, 0xf8, 0x01, 0x2b, 0x1c, 0x46, 0x00, 0x2a, 0xfa, 0xd1, + 0x14, 0xb1, 0x23, 0x78, 0x00, 0x2b, 0xe9, 0xd1, 0x30, 0x46, 0xbd, 0xe8, + 0x70, 0x40, 0xe0, 0xf3, 0x47, 0xb7, 0x70, 0xbd, 0x2d, 0xe9, 0xf3, 0x41, + 0x00, 0xf5, 0x9a, 0x58, 0xb8, 0xf8, 0x18, 0x30, 0x04, 0x46, 0x0e, 0x46, + 0x33, 0xb3, 0x08, 0x46, 0xdb, 0xf3, 0xb4, 0xf1, 0x07, 0x46, 0x17, 0x48, + 0xdb, 0xf3, 0xb0, 0xf1, 0x3f, 0x18, 0xe3, 0x69, 0x10, 0x37, 0xbf, 0xb2, + 0x98, 0x68, 0x39, 0x46, 0xdf, 0xf3, 0x60, 0xf7, 0x05, 0x46, 0xe0, 0xb1, + 0xb8, 0xf8, 0x18, 0x30, 0x10, 0x4a, 0x00, 0x93, 0x39, 0x46, 0x33, 0x46, + 0xdb, 0xf3, 0x52, 0xf1, 0x29, 0x46, 0x20, 0x46, 0xe9, 0xf7, 0xf4, 0xff, + 0xe3, 0x69, 0x80, 0x46, 0x29, 0x46, 0x98, 0x68, 0x3a, 0x46, 0xdf, 0xf3, + 0x5b, 0xf7, 0xb8, 0xf1, 0x00, 0x0f, 0x07, 0xd1, 0x20, 0x46, 0x31, 0x46, + 0x02, 0xb0, 0xbd, 0xe8, 0xf0, 0x41, 0xe9, 0xf7, 0xe3, 0xbf, 0x80, 0x46, + 0x40, 0x46, 0x02, 0xb0, 0xbd, 0xe8, 0xf0, 0x81, 0xdc, 0xde, 0x01, 0x00, + 0xe2, 0xde, 0x01, 0x00, 0x2d, 0xe9, 0xf0, 0x4f, 0x00, 0xf5, 0x9a, 0x59, + 0x1c, 0x46, 0xb9, 0xf8, 0x18, 0x30, 0x85, 0xb0, 0x06, 0x46, 0x88, 0x46, + 0x92, 0x46, 0xd0, 0xf8, 0xb8, 0x70, 0x00, 0x2b, 0x38, 0xd0, 0x08, 0x46, + 0xdb, 0xf3, 0x6e, 0xf1, 0x83, 0x46, 0x25, 0x48, 0xdb, 0xf3, 0x6a, 0xf1, + 0x83, 0x44, 0xf3, 0x69, 0x0b, 0xf1, 0x10, 0x0b, 0x1f, 0xfa, 0x8b, 0xfb, + 0x98, 0x68, 0x59, 0x46, 0xdf, 0xf3, 0x18, 0xf7, 0x05, 0x46, 0x00, 0x28, + 0x33, 0xd0, 0xb9, 0xf8, 0x18, 0x30, 0x59, 0x46, 0x00, 0x93, 0x1c, 0x4a, + 0x43, 0x46, 0xdb, 0xf3, 0x09, 0xf1, 0x30, 0x46, 0x29, 0x46, 0xe9, 0xf7, + 0xb7, 0xff, 0x03, 0x90, 0x68, 0xb1, 0x38, 0x46, 0x29, 0x46, 0xdb, 0xf7, + 0xe7, 0xfc, 0x40, 0xb1, 0x50, 0x45, 0x06, 0xdd, 0x38, 0x46, 0x29, 0x46, + 0x52, 0x46, 0xdb, 0xf3, 0x5d, 0xf5, 0x81, 0x46, 0x00, 0xe0, 0xa1, 0x46, + 0xf3, 0x69, 0x29, 0x46, 0x98, 0x68, 0x5a, 0x46, 0xdf, 0xf3, 0x02, 0xf7, + 0x03, 0x9b, 0x8b, 0xb9, 0x38, 0x46, 0x41, 0x46, 0xdb, 0xf7, 0xd0, 0xfc, + 0x58, 0xb1, 0x50, 0x45, 0x09, 0xdd, 0x38, 0x46, 0x41, 0x46, 0x52, 0x46, + 0x05, 0xb0, 0xbd, 0xe8, 0xf0, 0x4f, 0xdb, 0xf3, 0x43, 0xb5, 0x81, 0x46, + 0x00, 0xe0, 0xa1, 0x46, 0x48, 0x46, 0x05, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, + 0xdc, 0xde, 0x01, 0x00, 0xe2, 0xde, 0x01, 0x00, 0x70, 0xb5, 0x90, 0xf8, + 0xc4, 0x30, 0x01, 0x26, 0x1b, 0x49, 0x9e, 0x40, 0x05, 0x46, 0xe9, 0xf7, + 0x94, 0xff, 0x05, 0xf5, 0x80, 0x54, 0xc0, 0xb2, 0x84, 0xf8, 0x32, 0x00, + 0x01, 0x38, 0xc0, 0xb2, 0x01, 0x3e, 0xfd, 0x28, 0xf6, 0xb2, 0x02, 0xd9, + 0x73, 0x23, 0x84, 0xf8, 0x32, 0x30, 0x94, 0xf8, 0x32, 0x30, 0x28, 0x46, + 0x84, 0xf8, 0x33, 0x30, 0x10, 0x49, 0xe9, 0xf7, 0x7e, 0xff, 0xc0, 0xb2, + 0x84, 0xf8, 0x34, 0x00, 0x05, 0xf5, 0x80, 0x55, 0x08, 0xb1, 0x0f, 0x28, + 0x02, 0xd1, 0x05, 0x23, 0x85, 0xf8, 0x34, 0x30, 0x95, 0xf8, 0x32, 0x20, + 0x95, 0xf8, 0x34, 0x30, 0x46, 0xea, 0x06, 0x16, 0xd3, 0x1a, 0x85, 0xf8, + 0x35, 0x30, 0x00, 0x23, 0x85, 0xf8, 0x36, 0x30, 0x85, 0xf8, 0x38, 0x30, + 0x85, 0xf8, 0x37, 0x60, 0x70, 0xbd, 0x00, 0xbf, 0x01, 0x96, 0x02, 0x00, + 0xdb, 0x95, 0x02, 0x00, 0x38, 0xb5, 0x98, 0x21, 0x05, 0x46, 0x00, 0x68, + 0xdf, 0xf3, 0x90, 0xf6, 0x04, 0x46, 0x00, 0x28, 0x32, 0xd0, 0x00, 0x21, + 0x98, 0x22, 0xdb, 0xf3, 0x41, 0xf0, 0x2b, 0x68, 0xa3, 0x60, 0x6b, 0x68, + 0xe3, 0x60, 0xab, 0x68, 0x23, 0x61, 0xeb, 0x68, 0x63, 0x60, 0x2b, 0x69, + 0x63, 0x61, 0x2b, 0x8c, 0xa3, 0x84, 0x6b, 0x8c, 0xe3, 0x84, 0x6b, 0x6a, + 0xa3, 0x62, 0xab, 0x6a, 0xe3, 0x62, 0xeb, 0x6a, 0x23, 0x63, 0x2b, 0x6b, + 0x63, 0x63, 0x6b, 0x6b, 0x63, 0x64, 0xab, 0x6b, 0xa3, 0x64, 0xeb, 0x6b, + 0xe3, 0x64, 0x2b, 0x6c, 0x23, 0x65, 0x6b, 0x6c, 0x63, 0x65, 0x6b, 0x69, + 0xa3, 0x65, 0xab, 0x69, 0xe3, 0x65, 0x0f, 0x23, 0x23, 0x66, 0x3c, 0x23, + 0x63, 0x66, 0x78, 0x23, 0xa3, 0x66, 0x03, 0x23, 0xe3, 0x66, 0x00, 0x23, + 0x84, 0xf8, 0x94, 0x30, 0x20, 0x46, 0x38, 0xbd, 0x01, 0x46, 0x18, 0xb1, + 0x80, 0x68, 0x98, 0x22, 0xdf, 0xf3, 0x62, 0xb6, 0x70, 0x47, 0x10, 0xb5, + 0xb0, 0xf8, 0xbc, 0x40, 0x0c, 0x80, 0xb0, 0xf8, 0xc0, 0x10, 0x11, 0x80, + 0xb0, 0xf8, 0xc6, 0x20, 0x1a, 0x80, 0x90, 0xf8, 0xc8, 0x20, 0x02, 0x9b, + 0x01, 0x20, 0x1a, 0x80, 0x10, 0xbd, 0x90, 0xf8, 0xd4, 0x00, 0x70, 0x47, + 0xd0, 0xf8, 0xcc, 0x00, 0x70, 0x47, 0x00, 0x00, 0x38, 0xb5, 0x01, 0x21, + 0x04, 0x46, 0xe9, 0xf7, 0xd9, 0xff, 0x20, 0x46, 0xe9, 0xf7, 0xa8, 0xfd, + 0x0f, 0x4d, 0x03, 0x0f, 0x05, 0x40, 0x2d, 0x0b, 0x84, 0xf8, 0xc8, 0x30, + 0x42, 0xf2, 0x64, 0x03, 0x00, 0xf0, 0x0f, 0x00, 0x9d, 0x42, 0xa4, 0xf8, + 0xc6, 0x50, 0x84, 0xf8, 0xc9, 0x00, 0x07, 0xd0, 0x42, 0xf2, 0x66, 0x03, + 0x9d, 0x42, 0x14, 0xbf, 0x4f, 0xf0, 0xff, 0x35, 0x00, 0x25, 0x00, 0xe0, + 0x00, 0x25, 0x20, 0x46, 0x00, 0x21, 0xea, 0xf7, 0xbb, 0xf9, 0x28, 0x46, + 0x38, 0xbd, 0x00, 0xbf, 0x00, 0xf0, 0xff, 0x0f, 0x2d, 0xe9, 0xf0, 0x47, + 0x8a, 0x46, 0x00, 0x21, 0xd0, 0xf8, 0x08, 0x90, 0x04, 0x46, 0x15, 0x46, + 0xc0, 0x68, 0x0a, 0x46, 0x98, 0x46, 0xe3, 0xf3, 0xc5, 0xf6, 0x03, 0x07, + 0x07, 0x46, 0x14, 0xd5, 0x26, 0x68, 0x96, 0xb1, 0x30, 0x46, 0x29, 0x46, + 0x00, 0xf0, 0xaa, 0xfa, 0x00, 0x28, 0x00, 0xf0, 0x5f, 0x81, 0xf3, 0x69, + 0xd6, 0xf8, 0xcc, 0x10, 0x18, 0x69, 0x29, 0xf0, 0xd9, 0xda, 0xd6, 0xf8, + 0xe4, 0x30, 0x01, 0x33, 0xc6, 0xf8, 0xe4, 0x30, 0x59, 0xe1, 0x48, 0x46, + 0x41, 0xf2, 0x88, 0x31, 0xdf, 0xf3, 0xe6, 0xf5, 0x06, 0x46, 0x00, 0x28, + 0x00, 0xf0, 0x51, 0x81, 0x00, 0x21, 0x41, 0xf2, 0x88, 0x32, 0xda, 0xf3, + 0x95, 0xf7, 0x06, 0xf5, 0x92, 0x53, 0x10, 0x33, 0x06, 0xf5, 0x8e, 0x52, + 0x53, 0x63, 0x01, 0x23, 0x86, 0xf8, 0xe1, 0x30, 0xe2, 0x6c, 0x41, 0xf2, + 0x6b, 0x03, 0x9a, 0x42, 0xc6, 0xf8, 0xb0, 0xa0, 0xf4, 0x61, 0x05, 0xd1, + 0x63, 0x6c, 0x93, 0x2b, 0x0c, 0xbf, 0x01, 0x23, 0x18, 0x23, 0x00, 0xe0, + 0x18, 0x23, 0xa6, 0xf8, 0x22, 0x36, 0x64, 0x23, 0x00, 0x21, 0x04, 0x22, + 0x86, 0xf8, 0xe0, 0x30, 0x02, 0x2d, 0x06, 0xf5, 0x90, 0x53, 0xc6, 0xf8, + 0xb8, 0x80, 0x83, 0xf8, 0x38, 0x10, 0x83, 0xf8, 0x39, 0x20, 0x83, 0xf8, + 0x3a, 0x10, 0x83, 0xf8, 0x3b, 0x20, 0x05, 0xd1, 0xff, 0x07, 0x44, 0xbf, + 0x4f, 0xf4, 0x00, 0x53, 0xc6, 0xf8, 0xcc, 0x30, 0xd6, 0xf8, 0xcc, 0x10, + 0x20, 0x69, 0x29, 0xf0, 0x8d, 0xda, 0xd6, 0xf8, 0xb0, 0x30, 0xb3, 0xf8, + 0xe0, 0x73, 0xf3, 0x69, 0xbf, 0xb2, 0xd8, 0x68, 0xe5, 0xf7, 0xef, 0xff, + 0x06, 0xf5, 0x9a, 0x53, 0x18, 0x83, 0xf0, 0x69, 0x07, 0xf0, 0x0f, 0x03, + 0xc6, 0xf8, 0xc0, 0x30, 0x82, 0x4a, 0x83, 0x6a, 0x07, 0xf4, 0x70, 0x61, + 0x9a, 0x18, 0x09, 0x0a, 0x01, 0x2a, 0xc6, 0xf8, 0xbc, 0x10, 0x07, 0xd9, + 0x4a, 0xf6, 0xe6, 0x02, 0x93, 0x42, 0x03, 0xd0, 0x4a, 0xf6, 0xe2, 0x02, + 0x93, 0x42, 0x06, 0xd1, 0xc3, 0x6a, 0x02, 0x3b, 0x01, 0x2b, 0x02, 0xd8, + 0x09, 0x23, 0xc6, 0xf8, 0xc0, 0x30, 0x09, 0x29, 0x07, 0xd1, 0x04, 0x23, + 0xc6, 0xf8, 0xbc, 0x30, 0xd6, 0xf8, 0xc0, 0x30, 0x10, 0x33, 0xc6, 0xf8, + 0xc0, 0x30, 0x01, 0x23, 0x86, 0xf8, 0xc4, 0x30, 0xd6, 0xf8, 0xbc, 0x30, + 0x3f, 0x0b, 0x02, 0x2b, 0xc6, 0xf8, 0xd0, 0x70, 0x07, 0xd9, 0x0a, 0x2b, + 0x00, 0xf2, 0xcc, 0x80, 0x4f, 0xf0, 0x7a, 0x62, 0x9a, 0x40, 0x40, 0xf1, + 0xc7, 0x80, 0x06, 0xf5, 0x80, 0x53, 0x3c, 0x22, 0x5a, 0x61, 0x00, 0x22, + 0x9a, 0x61, 0x4f, 0xf4, 0x00, 0x62, 0xa6, 0xf8, 0xde, 0x20, 0x42, 0xf6, + 0x01, 0x33, 0x41, 0xf6, 0x24, 0x32, 0x02, 0x2d, 0x18, 0xbf, 0x13, 0x46, + 0xa6, 0xf8, 0xda, 0x30, 0x86, 0xf8, 0x00, 0x37, 0x30, 0x46, 0x5e, 0x49, + 0xe9, 0xf7, 0xf4, 0xfd, 0x88, 0xb1, 0x5c, 0x49, 0x30, 0x46, 0xf7, 0x69, + 0xe9, 0xf7, 0x07, 0xfe, 0x59, 0x49, 0x38, 0x67, 0x30, 0x46, 0xf7, 0x69, + 0xe9, 0xf7, 0x01, 0xfe, 0xf3, 0x69, 0x78, 0x67, 0x02, 0x2d, 0x0c, 0xbf, + 0x1a, 0x6f, 0x5a, 0x6f, 0xda, 0x66, 0x06, 0xf5, 0x90, 0x52, 0x0a, 0x23, + 0x93, 0x71, 0x03, 0x23, 0xd3, 0x71, 0x01, 0x22, 0x00, 0x27, 0x86, 0xf8, + 0xe8, 0x20, 0x06, 0xf5, 0x91, 0x52, 0x17, 0x70, 0x06, 0xf5, 0x80, 0x58, + 0x09, 0x22, 0x88, 0xf8, 0x3b, 0x20, 0xf2, 0x69, 0x86, 0xf8, 0xe9, 0x75, + 0x86, 0xf8, 0xee, 0x75, 0x86, 0xf8, 0xf3, 0x75, 0x86, 0xf8, 0xf8, 0x75, + 0x86, 0xf8, 0xfd, 0x75, 0x30, 0x46, 0x82, 0xf8, 0x93, 0x30, 0xff, 0xf7, + 0x3b, 0xfe, 0x06, 0xf5, 0x96, 0x53, 0x4f, 0xf6, 0xce, 0x72, 0x9a, 0x84, + 0x88, 0xf8, 0x39, 0x70, 0x86, 0xf8, 0xf4, 0x70, 0x33, 0x46, 0x7f, 0x22, + 0x01, 0x37, 0x83, 0xf8, 0x2c, 0x26, 0x83, 0xf8, 0x91, 0x26, 0x83, 0xf8, + 0xb2, 0x22, 0x01, 0x33, 0x65, 0x2f, 0xf4, 0xd1, 0x4f, 0xf0, 0xff, 0x33, + 0xa6, 0xf8, 0xfa, 0x36, 0x00, 0x23, 0x86, 0xf8, 0xac, 0x30, 0x30, 0x46, + 0x29, 0x46, 0x01, 0xf0, 0xa1, 0xf9, 0x00, 0x28, 0x56, 0xd0, 0x30, 0x46, + 0xe9, 0xf7, 0x55, 0xfc, 0x30, 0x46, 0xff, 0xf7, 0xaf, 0xfe, 0x05, 0x46, + 0x00, 0x28, 0x4d, 0xd1, 0x2d, 0x49, 0x06, 0x22, 0x30, 0x46, 0xe9, 0xf7, + 0x9b, 0xfd, 0x06, 0xf5, 0x98, 0x57, 0xb8, 0x71, 0x2a, 0x49, 0x01, 0x22, + 0x30, 0x46, 0xe9, 0xf7, 0x93, 0xfd, 0x29, 0x49, 0x38, 0x75, 0x2a, 0x46, + 0x30, 0x46, 0xe9, 0xf7, 0x8d, 0xfd, 0x06, 0xf5, 0x9a, 0x57, 0xb8, 0x76, + 0x25, 0x49, 0x30, 0x46, 0x07, 0x22, 0xe9, 0xf7, 0x85, 0xfd, 0xf8, 0x76, + 0x2a, 0x46, 0x30, 0x46, 0x22, 0x49, 0xe9, 0xf7, 0xa3, 0xfd, 0x73, 0x19, + 0x01, 0x35, 0x03, 0xf5, 0x9a, 0x53, 0x18, 0x2d, 0x18, 0x77, 0xf3, 0xd1, + 0x00, 0x25, 0x2a, 0x46, 0x30, 0x46, 0x1d, 0x49, 0xe9, 0xf7, 0x96, 0xfd, + 0x73, 0x19, 0x01, 0x35, 0x03, 0xf5, 0x9a, 0x53, 0x0e, 0x2d, 0x83, 0xf8, + 0x34, 0x00, 0xf2, 0xd1, 0xd6, 0xf8, 0xe4, 0x30, 0x01, 0x33, 0xc6, 0xf8, + 0xe4, 0x30, 0xf3, 0x69, 0x1a, 0x68, 0xd8, 0x68, 0xc6, 0xf8, 0xb4, 0x20, + 0x26, 0x60, 0xff, 0xf7, 0x9f, 0xfa, 0x06, 0xf1, 0xb8, 0x03, 0xc6, 0xf8, + 0xb8, 0x30, 0x30, 0x46, 0x06, 0xf1, 0xbc, 0x01, 0x1c, 0x22, 0xda, 0xf3, + 0xed, 0xf5, 0x06, 0xe0, 0x31, 0x46, 0xa0, 0x68, 0x41, 0xf2, 0x88, 0x32, + 0xdf, 0xf3, 0xa2, 0xf4, 0x00, 0x26, 0x30, 0x46, 0xbd, 0xe8, 0xf0, 0x87, + 0x1d, 0x57, 0xff, 0xff, 0x0c, 0x96, 0x02, 0x00, 0xb0, 0x95, 0x02, 0x00, + 0xcf, 0x95, 0x02, 0x00, 0xc2, 0x95, 0x02, 0x00, 0xec, 0x95, 0x02, 0x00, + 0xfa, 0x95, 0x02, 0x00, 0xbb, 0x95, 0x02, 0x00, 0x70, 0xb5, 0x04, 0x46, + 0x00, 0x28, 0x32, 0xd0, 0xd0, 0xf8, 0xe4, 0x50, 0x01, 0x3d, 0xc0, 0xf8, + 0xe4, 0x50, 0x00, 0x2d, 0x2b, 0xd1, 0x00, 0xf5, 0x96, 0x56, 0xb1, 0x6a, + 0x21, 0xb1, 0xc3, 0x69, 0x18, 0x69, 0xf4, 0xf7, 0x0f, 0xf8, 0xb5, 0x62, + 0x04, 0xf5, 0x8e, 0x53, 0x00, 0x25, 0x83, 0xf8, 0x3d, 0x50, 0x20, 0x46, + 0xea, 0xf7, 0x82, 0xfe, 0xe2, 0x69, 0x13, 0x68, 0xa3, 0x42, 0x03, 0xd1, + 0xd4, 0xf8, 0xb4, 0x30, 0x13, 0x60, 0x05, 0xe0, 0xd3, 0xf8, 0xb4, 0x20, + 0xa2, 0x42, 0x08, 0xbf, 0xc3, 0xf8, 0xb4, 0x50, 0xe3, 0x6e, 0x0b, 0xb1, + 0x20, 0x46, 0x98, 0x47, 0xe3, 0x69, 0x21, 0x46, 0x98, 0x68, 0x41, 0xf2, + 0x88, 0x32, 0xbd, 0xe8, 0x70, 0x40, 0xdf, 0xf3, 0x57, 0xb4, 0x70, 0xbd, + 0x1f, 0xb5, 0x09, 0x4b, 0x09, 0x49, 0x00, 0x93, 0x00, 0x23, 0x01, 0x93, + 0x02, 0x93, 0x03, 0x93, 0x07, 0x4a, 0x03, 0x68, 0xfc, 0xf3, 0x3e, 0xf5, + 0x00, 0x28, 0x14, 0xbf, 0x4f, 0xf0, 0xff, 0x30, 0x00, 0x20, 0x05, 0xb0, + 0x00, 0xbd, 0x00, 0xbf, 0x19, 0x2b, 0x01, 0x00, 0xd8, 0xe4, 0x01, 0x00, + 0xa4, 0xe5, 0x01, 0x00, 0x01, 0x49, 0x02, 0x68, 0xfc, 0xf3, 0x64, 0xb5, + 0xa4, 0xe5, 0x01, 0x00, 0x00, 0x23, 0xf0, 0xb5, 0x1c, 0x46, 0x07, 0xe0, + 0xcd, 0x18, 0x2f, 0x68, 0xc6, 0x18, 0xc7, 0x50, 0x2d, 0x79, 0x01, 0x34, + 0x35, 0x71, 0x05, 0x33, 0x94, 0x42, 0xf5, 0xd1, 0xf0, 0xbd, 0x00, 0x00, + 0x02, 0x29, 0x38, 0xb5, 0x05, 0x46, 0x0c, 0x46, 0x0a, 0xd0, 0x03, 0x29, + 0x11, 0xd0, 0x01, 0x29, 0x16, 0xd1, 0x06, 0x22, 0x0b, 0x49, 0xe9, 0xf7, + 0x63, 0xfd, 0xeb, 0x69, 0x00, 0x22, 0x05, 0xe0, 0x06, 0x22, 0x09, 0x49, + 0xe9, 0xf7, 0x5c, 0xfd, 0xeb, 0x69, 0x01, 0x22, 0x83, 0xf8, 0x81, 0x20, + 0x38, 0xbd, 0x06, 0x49, 0x06, 0x22, 0xe9, 0xf7, 0x53, 0xfd, 0xeb, 0x69, + 0x83, 0xf8, 0x81, 0x40, 0x38, 0xbd, 0x00, 0xbf, 0x8c, 0xeb, 0x01, 0x00, + 0xe4, 0xed, 0x01, 0x00, 0x16, 0xed, 0x01, 0x00, 0x38, 0xb5, 0xd0, 0xf8, + 0xa8, 0x40, 0x00, 0x23, 0xc4, 0xf8, 0x74, 0x35, 0x94, 0xf8, 0xc1, 0x53, + 0x10, 0x4b, 0x11, 0x4a, 0x4f, 0xf4, 0x20, 0x71, 0x02, 0x2d, 0x14, 0xbf, + 0x15, 0x46, 0x1d, 0x46, 0xc3, 0x69, 0x98, 0x68, 0xdf, 0xf3, 0xda, 0xf3, + 0xc4, 0xf8, 0x74, 0x05, 0x88, 0xb1, 0x80, 0x22, 0x29, 0x46, 0xff, 0xf7, + 0xad, 0xff, 0x94, 0xf8, 0x3a, 0x35, 0x02, 0x2b, 0x08, 0xd1, 0xd4, 0xf8, + 0x74, 0x05, 0x06, 0x49, 0xa0, 0x30, 0x15, 0x22, 0xff, 0xf7, 0xa2, 0xff, + 0x01, 0x20, 0x38, 0xbd, 0x01, 0x20, 0x38, 0xbd, 0x78, 0xa4, 0x02, 0x00, + 0x14, 0xa0, 0x02, 0x00, 0x78, 0xa8, 0x02, 0x00, 0x2d, 0xe9, 0xf0, 0x47, + 0xd0, 0xf8, 0xa8, 0x30, 0x06, 0x46, 0xd3, 0xf8, 0x7c, 0x55, 0xd3, 0xf8, + 0x78, 0x75, 0x00, 0x24, 0x1b, 0xe0, 0x4f, 0xf0, 0x14, 0x08, 0x08, 0xfb, + 0x04, 0xf8, 0x05, 0xeb, 0x08, 0x03, 0x1a, 0x69, 0x5b, 0x68, 0x55, 0xf8, + 0x08, 0xa0, 0x03, 0xfb, 0x02, 0xf9, 0xf3, 0x69, 0x4f, 0xea, 0xd9, 0x09, + 0x98, 0x68, 0x49, 0x46, 0xdf, 0xf3, 0xa0, 0xf3, 0x45, 0xf8, 0x08, 0x00, + 0x40, 0xb1, 0x51, 0x46, 0x4a, 0x46, 0xda, 0xf3, 0xed, 0xf4, 0x01, 0x34, + 0xe4, 0xb2, 0xbc, 0x42, 0xe1, 0xd3, 0x01, 0x20, 0xbd, 0xe8, 0xf0, 0x87, + 0x2d, 0xe9, 0xf0, 0x41, 0x1c, 0x4b, 0xd0, 0xf8, 0xa8, 0x60, 0x1b, 0x68, + 0xc2, 0x69, 0x00, 0x27, 0x14, 0x21, 0x05, 0x46, 0xc6, 0xf8, 0x7c, 0x75, + 0xc6, 0xf8, 0x78, 0x35, 0x90, 0x68, 0x59, 0x43, 0xdf, 0xf3, 0x80, 0xf3, + 0x04, 0x46, 0xc6, 0xf8, 0x7c, 0x05, 0x10, 0xb3, 0xbc, 0x46, 0xb8, 0x46, + 0x14, 0xe0, 0xeb, 0x69, 0x04, 0xeb, 0x0c, 0x07, 0x1b, 0x6d, 0x08, 0xf1, + 0x01, 0x08, 0x13, 0xf4, 0x80, 0x5f, 0x14, 0xbf, 0x0d, 0x4b, 0x0e, 0x4b, + 0x03, 0xeb, 0x0c, 0x0e, 0xbe, 0xe8, 0x0f, 0x00, 0x0f, 0xc7, 0xde, 0xf8, + 0x00, 0x30, 0x0c, 0xf1, 0x14, 0x0c, 0x3b, 0x60, 0xd6, 0xf8, 0x78, 0x35, + 0x98, 0x45, 0xe6, 0xd3, 0x01, 0x21, 0x28, 0x46, 0xff, 0xf7, 0x9e, 0xff, + 0x00, 0x30, 0x18, 0xbf, 0x01, 0x20, 0xbd, 0xe8, 0xf0, 0x81, 0x00, 0xbf, + 0x2c, 0xfb, 0x01, 0x00, 0xb0, 0x9f, 0x02, 0x00, 0x14, 0xa4, 0x02, 0x00, + 0x2d, 0xe9, 0xf0, 0x41, 0x0f, 0x46, 0x86, 0xb0, 0x79, 0x49, 0x04, 0x46, + 0xd0, 0xf8, 0xa8, 0x50, 0xe9, 0xf7, 0x0d, 0xfc, 0x77, 0x49, 0x28, 0x72, + 0x20, 0x46, 0xe9, 0xf7, 0x08, 0xfc, 0x76, 0x49, 0x68, 0x72, 0x20, 0x46, + 0xe9, 0xf7, 0x03, 0xfc, 0x74, 0x49, 0xa4, 0xf8, 0xfc, 0x00, 0x20, 0x46, + 0xe9, 0xf7, 0xfd, 0xfb, 0x72, 0x49, 0xa4, 0xf8, 0xfe, 0x00, 0x20, 0x46, + 0xe9, 0xf7, 0xf7, 0xfb, 0x70, 0x49, 0xa4, 0xf8, 0x00, 0x01, 0x20, 0x46, + 0xe9, 0xf7, 0xd8, 0xfb, 0x38, 0xb1, 0x20, 0x46, 0x6c, 0x49, 0xe9, 0xf7, + 0xec, 0xfb, 0x10, 0xb1, 0x01, 0x23, 0x85, 0xf8, 0xe8, 0x33, 0x95, 0xf8, + 0xe8, 0x33, 0x13, 0xb3, 0x67, 0x49, 0x20, 0x46, 0xe9, 0xf7, 0xe1, 0xfb, + 0x66, 0x49, 0xa4, 0xf8, 0x02, 0x01, 0x20, 0x46, 0xe9, 0xf7, 0xdb, 0xfb, + 0x64, 0x49, 0xa4, 0xf8, 0x04, 0x01, 0x20, 0x46, 0xe9, 0xf7, 0xd5, 0xfb, + 0x62, 0x49, 0xa4, 0xf8, 0x06, 0x01, 0x20, 0x46, 0xe9, 0xf7, 0xcf, 0xfb, + 0x60, 0x49, 0x85, 0xf8, 0x24, 0x05, 0x20, 0x46, 0xe9, 0xf7, 0xc9, 0xfb, + 0x04, 0xf5, 0x80, 0x53, 0x00, 0x22, 0x85, 0xf8, 0x25, 0x05, 0x83, 0xf8, + 0x3b, 0x20, 0x5b, 0x49, 0x20, 0x46, 0xe9, 0xf7, 0xbe, 0xfb, 0x5a, 0x49, + 0xc5, 0xf8, 0x34, 0x04, 0x14, 0x22, 0x20, 0x46, 0xe9, 0xf7, 0xaa, 0xfb, + 0x57, 0x49, 0xa5, 0xf8, 0x3c, 0x04, 0x5a, 0x22, 0x20, 0x46, 0xe9, 0xf7, + 0xa3, 0xfb, 0x55, 0x49, 0x85, 0xf8, 0x54, 0x04, 0x08, 0x22, 0x20, 0x46, + 0xe9, 0xf7, 0x9c, 0xfb, 0x52, 0x49, 0x85, 0xf8, 0x4c, 0x04, 0x03, 0x22, + 0x20, 0x46, 0xe9, 0xf7, 0x95, 0xfb, 0x50, 0x49, 0x85, 0xf8, 0x4d, 0x04, + 0x08, 0x22, 0x20, 0x46, 0xe9, 0xf7, 0x8e, 0xfb, 0x4d, 0x49, 0x85, 0xf8, + 0x4e, 0x04, 0x03, 0x22, 0x20, 0x46, 0xe9, 0xf7, 0x87, 0xfb, 0x4b, 0x49, + 0x85, 0xf8, 0x4f, 0x04, 0x08, 0x22, 0x20, 0x46, 0xe9, 0xf7, 0x80, 0xfb, + 0x48, 0x49, 0x85, 0xf8, 0x50, 0x04, 0x03, 0x22, 0x20, 0x46, 0xe9, 0xf7, + 0x79, 0xfb, 0x46, 0x49, 0x85, 0xf8, 0x51, 0x04, 0x08, 0x22, 0x20, 0x46, + 0xe9, 0xf7, 0x72, 0xfb, 0x03, 0x22, 0x85, 0xf8, 0x52, 0x04, 0x42, 0x49, + 0x20, 0x46, 0xe9, 0xf7, 0x6b, 0xfb, 0x41, 0x49, 0x85, 0xf8, 0x53, 0x04, + 0x20, 0x46, 0xe9, 0xf7, 0x72, 0xfb, 0x3f, 0x49, 0x85, 0xf8, 0x58, 0x04, + 0x02, 0x22, 0x20, 0x46, 0xe9, 0xf7, 0x5e, 0xfb, 0x3c, 0x49, 0x85, 0xf8, + 0xc1, 0x04, 0x20, 0x46, 0xe9, 0xf7, 0x4c, 0xfb, 0x18, 0xb1, 0x20, 0x46, + 0x38, 0x49, 0xe9, 0xf7, 0x60, 0xfb, 0xe8, 0x74, 0x37, 0x49, 0x20, 0x46, + 0xe9, 0xf7, 0x42, 0xfb, 0x28, 0xb1, 0x20, 0x46, 0x34, 0x49, 0xe9, 0xf7, + 0x56, 0xfb, 0x28, 0x75, 0x01, 0xe0, 0x08, 0x23, 0x2b, 0x75, 0x20, 0x46, + 0x31, 0x49, 0xe9, 0xf7, 0x35, 0xfb, 0x28, 0xb1, 0x20, 0x46, 0x2f, 0x49, + 0xe9, 0xf7, 0x49, 0xfb, 0x68, 0x75, 0x01, 0xe0, 0x02, 0x23, 0x6b, 0x75, + 0x20, 0x46, 0x2c, 0x49, 0xe9, 0xf7, 0x28, 0xfb, 0x28, 0xb1, 0x20, 0x46, + 0x29, 0x49, 0xe9, 0xf7, 0x3c, 0xfb, 0xa8, 0x75, 0x01, 0xe0, 0x04, 0x23, + 0xab, 0x75, 0x20, 0x46, 0x26, 0x49, 0xe9, 0xf7, 0x1b, 0xfb, 0x28, 0xb1, + 0x20, 0x46, 0x24, 0x49, 0xe9, 0xf7, 0x2f, 0xfb, 0xe8, 0x75, 0x01, 0xe0, + 0x08, 0x23, 0xeb, 0x75, 0x20, 0x46, 0x21, 0x49, 0xe9, 0xf7, 0x0e, 0xfb, + 0x00, 0x28, 0x3f, 0xd0, 0x20, 0x46, 0x1e, 0x49, 0xe9, 0xf7, 0x21, 0xfb, + 0x28, 0x76, 0x3b, 0xe0, 0x8f, 0x9d, 0x02, 0x00, 0x40, 0x9d, 0x02, 0x00, + 0x78, 0x9a, 0x02, 0x00, 0x7e, 0x9a, 0x02, 0x00, 0x84, 0x9a, 0x02, 0x00, + 0x5c, 0x9b, 0x02, 0x00, 0x35, 0x9a, 0x02, 0x00, 0x1f, 0x99, 0x02, 0x00, + 0x39, 0x97, 0x02, 0x00, 0x00, 0x97, 0x02, 0x00, 0x41, 0x9f, 0x02, 0x00, + 0xd8, 0x99, 0x02, 0x00, 0x19, 0x9e, 0x02, 0x00, 0x97, 0x9e, 0x02, 0x00, + 0xb9, 0x9b, 0x02, 0x00, 0x65, 0x9e, 0x02, 0x00, 0x33, 0x96, 0x02, 0x00, + 0x76, 0x9e, 0x02, 0x00, 0x44, 0x96, 0x02, 0x00, 0x4d, 0x9e, 0x02, 0x00, + 0x5a, 0x9f, 0x02, 0x00, 0xf7, 0x98, 0x02, 0x00, 0x7a, 0x97, 0x02, 0x00, + 0x79, 0x98, 0x02, 0x00, 0x66, 0x98, 0x02, 0x00, 0xd0, 0x9c, 0x02, 0x00, + 0x8f, 0x9e, 0x02, 0x00, 0x87, 0x9e, 0x02, 0x00, 0x03, 0x99, 0x02, 0x00, + 0x02, 0x23, 0x2b, 0x76, 0xb7, 0x49, 0x20, 0x46, 0xe9, 0xf7, 0xdf, 0xfa, + 0xb6, 0x49, 0xa8, 0x72, 0x20, 0x46, 0xe9, 0xf7, 0xda, 0xfa, 0xb5, 0x49, + 0xe8, 0x72, 0x20, 0x46, 0xe9, 0xf7, 0xd5, 0xfa, 0xaa, 0x7a, 0xeb, 0x7a, + 0x28, 0x73, 0x6a, 0x73, 0xab, 0x73, 0xe8, 0x73, 0x2a, 0x74, 0x6b, 0x74, + 0xa8, 0x74, 0xaf, 0x49, 0x20, 0x46, 0xe9, 0xf7, 0xc8, 0xfa, 0xb4, 0xf8, + 0xfc, 0x10, 0x04, 0xf5, 0x98, 0x52, 0x04, 0xf5, 0x9a, 0x53, 0x51, 0x87, + 0x19, 0x80, 0xb4, 0xf8, 0xfe, 0x10, 0x5f, 0xfa, 0x80, 0xf8, 0x91, 0x87, + 0x59, 0x80, 0xb4, 0xf8, 0x00, 0x11, 0x84, 0xf8, 0x1a, 0x81, 0xd1, 0x87, + 0x99, 0x80, 0x20, 0x46, 0xa3, 0x49, 0xe9, 0xf7, 0xb0, 0xfa, 0x00, 0x26, + 0x80, 0xb2, 0xa3, 0x19, 0x00, 0xf0, 0x0f, 0x02, 0x01, 0x36, 0xa8, 0xeb, + 0x42, 0x02, 0x00, 0x09, 0x04, 0x2e, 0x83, 0xf8, 0x1e, 0x21, 0xf4, 0xd1, + 0x20, 0x46, 0x9c, 0x49, 0xe9, 0xf7, 0x9f, 0xfa, 0x00, 0xf0, 0x0f, 0x02, + 0xa3, 0x19, 0x52, 0x00, 0x01, 0x36, 0xc2, 0xeb, 0x08, 0x02, 0x00, 0x09, + 0x0c, 0x2e, 0x83, 0xf8, 0x1e, 0x21, 0xf3, 0xd1, 0x95, 0x49, 0x20, 0x46, + 0xe9, 0xf7, 0x8f, 0xfa, 0x94, 0x49, 0x06, 0x46, 0x20, 0x46, 0xe9, 0xf7, + 0x8a, 0xfa, 0x80, 0xb2, 0x40, 0xea, 0x06, 0x46, 0x6e, 0x60, 0x14, 0x23, + 0x06, 0xf0, 0x0f, 0x01, 0xe2, 0x18, 0x49, 0x00, 0x01, 0x33, 0xc1, 0xeb, + 0x08, 0x01, 0x36, 0x09, 0x1c, 0x2b, 0x82, 0xf8, 0x16, 0x11, 0xf3, 0xd1, + 0x8a, 0x49, 0x20, 0x46, 0xe9, 0xf7, 0x75, 0xfa, 0x89, 0x49, 0x68, 0x83, + 0x20, 0x46, 0xe9, 0xf7, 0x70, 0xfa, 0x88, 0x49, 0x28, 0x77, 0x20, 0x46, + 0xe9, 0xf7, 0x6b, 0xfa, 0x86, 0x49, 0x68, 0x77, 0x20, 0x46, 0xe9, 0xf7, + 0x66, 0xfa, 0x85, 0x49, 0xa8, 0x77, 0x20, 0x46, 0xe9, 0xf7, 0x61, 0xfa, + 0x83, 0x49, 0xe8, 0x77, 0x20, 0x46, 0xe9, 0xf7, 0x5c, 0xfa, 0x82, 0x49, + 0x85, 0xf8, 0x22, 0x00, 0x20, 0x46, 0xe9, 0xf7, 0x56, 0xfa, 0x80, 0x49, + 0x85, 0xf8, 0x21, 0x00, 0x20, 0x46, 0xe9, 0xf7, 0x50, 0xfa, 0x7e, 0x49, + 0x85, 0xf8, 0xe0, 0x04, 0x20, 0x46, 0xe9, 0xf7, 0x4a, 0xfa, 0x01, 0x26, + 0xc5, 0xf8, 0xe4, 0x04, 0x7a, 0x49, 0x01, 0xa8, 0x32, 0x46, 0xda, 0xf3, + 0x87, 0xf3, 0xd4, 0xf8, 0xb8, 0x00, 0x01, 0xa9, 0xda, 0xf3, 0xf6, 0xf7, + 0x30, 0xb1, 0x00, 0x21, 0x0a, 0x46, 0xda, 0xf3, 0xb1, 0xf6, 0xab, 0x19, + 0x83, 0xf8, 0xe7, 0x04, 0x01, 0x36, 0x0f, 0x2e, 0xea, 0xd1, 0x71, 0x49, + 0x20, 0x46, 0xe9, 0xf7, 0x2e, 0xfa, 0x70, 0x49, 0x85, 0xf8, 0xf6, 0x04, + 0x20, 0x46, 0xe9, 0xf7, 0x28, 0xfa, 0x6e, 0x49, 0x85, 0xf8, 0xf7, 0x04, + 0x20, 0x46, 0xe9, 0xf7, 0x22, 0xfa, 0x6c, 0x49, 0x85, 0xf8, 0xf8, 0x04, + 0x20, 0x46, 0xe9, 0xf7, 0x1c, 0xfa, 0x6a, 0x49, 0x85, 0xf8, 0xf9, 0x04, + 0x20, 0x46, 0xe9, 0xf7, 0x16, 0xfa, 0x68, 0x49, 0x85, 0xf8, 0xfa, 0x04, + 0x20, 0x46, 0xe9, 0xf7, 0x10, 0xfa, 0x66, 0x49, 0x85, 0xf8, 0xfb, 0x04, + 0x20, 0x46, 0xe9, 0xf7, 0x0a, 0xfa, 0x64, 0x49, 0x85, 0xf8, 0xfc, 0x04, + 0x20, 0x46, 0xe9, 0xf7, 0x04, 0xfa, 0x62, 0x49, 0x85, 0xf8, 0xfd, 0x04, + 0x20, 0x46, 0xe9, 0xf7, 0xfe, 0xf9, 0x60, 0x49, 0x85, 0xf8, 0xfe, 0x04, + 0x20, 0x46, 0xe9, 0xf7, 0xf8, 0xf9, 0x5e, 0x49, 0x85, 0xf8, 0xff, 0x04, + 0x20, 0x46, 0xe9, 0xf7, 0xf2, 0xf9, 0x5c, 0x49, 0x85, 0xf8, 0x00, 0x05, + 0x20, 0x46, 0xe9, 0xf7, 0xec, 0xf9, 0x5a, 0x49, 0x85, 0xf8, 0x01, 0x05, + 0x20, 0x46, 0xe9, 0xf7, 0xe6, 0xf9, 0x58, 0x49, 0x85, 0xf8, 0x02, 0x05, + 0x20, 0x46, 0xe9, 0xf7, 0xe0, 0xf9, 0x56, 0x49, 0x85, 0xf8, 0x03, 0x05, + 0x20, 0x46, 0xe9, 0xf7, 0xda, 0xf9, 0x54, 0x49, 0x85, 0xf8, 0x04, 0x05, + 0x20, 0x46, 0xe9, 0xf7, 0xd4, 0xf9, 0x52, 0x49, 0x85, 0xf8, 0x05, 0x05, + 0x20, 0x46, 0xe9, 0xf7, 0xce, 0xf9, 0x50, 0x49, 0x85, 0xf8, 0x06, 0x05, + 0x20, 0x46, 0xe9, 0xf7, 0xc8, 0xf9, 0x4e, 0x49, 0x85, 0xf8, 0x07, 0x05, + 0x20, 0x46, 0xe9, 0xf7, 0xc2, 0xf9, 0x4c, 0x49, 0x85, 0xf8, 0x08, 0x05, + 0x20, 0x46, 0xe9, 0xf7, 0xbc, 0xf9, 0x4a, 0x49, 0x85, 0xf8, 0x09, 0x05, + 0x20, 0x46, 0xe9, 0xf7, 0xb6, 0xf9, 0x48, 0x49, 0x85, 0xf8, 0x0a, 0x05, + 0x20, 0x46, 0xe9, 0xf7, 0xb0, 0xf9, 0x46, 0x49, 0x85, 0xf8, 0x0b, 0x05, + 0x20, 0x46, 0xe9, 0xf7, 0xaa, 0xf9, 0x44, 0x49, 0x85, 0xf8, 0x0c, 0x05, + 0x20, 0x46, 0xe9, 0xf7, 0xa4, 0xf9, 0x42, 0x49, 0x85, 0xf8, 0x0d, 0x05, + 0x20, 0x46, 0xe9, 0xf7, 0x9e, 0xf9, 0x40, 0x49, 0xa5, 0xf8, 0x14, 0x05, + 0x20, 0x46, 0xe9, 0xf7, 0x98, 0xf9, 0x4f, 0xf0, 0x00, 0x42, 0xa5, 0xf8, + 0x16, 0x05, 0x3c, 0x49, 0x20, 0x46, 0xe9, 0xf7, 0x83, 0xf9, 0x3b, 0x49, + 0xc5, 0xf8, 0x10, 0x05, 0x20, 0x46, 0xe9, 0xf7, 0x8a, 0xf9, 0x39, 0x49, + 0x85, 0xf8, 0x24, 0x00, 0x20, 0x46, 0xe9, 0xf7, 0x84, 0xf9, 0x37, 0x49, + 0x85, 0xf8, 0x23, 0x00, 0x20, 0x46, 0xe9, 0xf7, 0x7e, 0xf9, 0x35, 0x49, + 0x85, 0xf8, 0x20, 0x00, 0x20, 0x46, 0xe9, 0xf7, 0x78, 0xf9, 0x33, 0x49, + 0x84, 0xf8, 0x26, 0x06, 0x20, 0x46, 0x63, 0xe0, 0x6f, 0x96, 0x02, 0x00, + 0x8a, 0x9c, 0x02, 0x00, 0x2b, 0x9a, 0x02, 0x00, 0x3e, 0x9a, 0x02, 0x00, + 0xe4, 0x99, 0x02, 0x00, 0xc7, 0x9c, 0x02, 0x00, 0x19, 0x96, 0x02, 0x00, + 0x58, 0x97, 0x02, 0x00, 0xe6, 0x9a, 0x02, 0x00, 0x65, 0x96, 0x02, 0x00, + 0x58, 0x9c, 0x02, 0x00, 0x63, 0x9c, 0x02, 0x00, 0x55, 0x96, 0x02, 0x00, + 0x0b, 0x99, 0x02, 0x00, 0x35, 0x99, 0x02, 0x00, 0x12, 0x9b, 0x02, 0x00, + 0x4f, 0x9b, 0x02, 0x00, 0x22, 0x96, 0x02, 0x00, 0x8a, 0x9a, 0x02, 0x00, + 0xef, 0x9b, 0x02, 0x00, 0x0b, 0x9c, 0x02, 0x00, 0xf0, 0x9d, 0x02, 0x00, + 0x5b, 0x9d, 0x02, 0x00, 0x6c, 0x9d, 0x02, 0x00, 0xb0, 0x9e, 0x02, 0x00, + 0xd1, 0x9e, 0x02, 0x00, 0xd4, 0x9a, 0x02, 0x00, 0xf3, 0x9a, 0x02, 0x00, + 0x20, 0x9b, 0x02, 0x00, 0x7d, 0x9d, 0x02, 0x00, 0x6e, 0x9c, 0x02, 0x00, + 0xa0, 0x9d, 0x02, 0x00, 0xb2, 0x9d, 0x02, 0x00, 0xc4, 0x9d, 0x02, 0x00, + 0x04, 0x9f, 0x02, 0x00, 0x16, 0x9f, 0x02, 0x00, 0xa7, 0x96, 0x02, 0x00, + 0xd1, 0x96, 0x02, 0x00, 0xc6, 0x97, 0x02, 0x00, 0xe5, 0x97, 0x02, 0x00, + 0xda, 0x98, 0x02, 0x00, 0x05, 0x97, 0x02, 0x00, 0x6b, 0x97, 0x02, 0x00, + 0x95, 0x99, 0x02, 0x00, 0xa2, 0x97, 0x02, 0x00, 0x24, 0x9e, 0x02, 0x00, + 0x30, 0x9e, 0x02, 0x00, 0xe2, 0x9e, 0x02, 0x00, 0xb8, 0x9c, 0x02, 0x00, + 0xc5, 0x96, 0x02, 0x00, 0xe9, 0xf7, 0x0d, 0xf9, 0xbf, 0x49, 0x85, 0xf8, + 0xc1, 0x03, 0x20, 0x46, 0xe9, 0xf7, 0x07, 0xf9, 0xbd, 0x49, 0x85, 0xf8, + 0xc2, 0x03, 0x20, 0x46, 0xe9, 0xf7, 0x01, 0xf9, 0x85, 0xf8, 0xc3, 0x03, + 0x94, 0xf8, 0x26, 0x16, 0x11, 0xb1, 0x20, 0x46, 0xff, 0xf7, 0x1c, 0xfc, + 0xb7, 0x49, 0x20, 0x46, 0x4f, 0xf0, 0xff, 0x32, 0xe9, 0xf7, 0xe6, 0xf8, + 0x80, 0xb2, 0xa5, 0xf8, 0x62, 0x00, 0x00, 0x04, 0x48, 0xbf, 0x4f, 0xf0, + 0xff, 0x30, 0x4f, 0xf0, 0xff, 0x33, 0x48, 0xbf, 0xa5, 0xf8, 0x62, 0x00, + 0xa5, 0xf8, 0x66, 0x30, 0xa5, 0xf8, 0x68, 0x30, 0x20, 0x46, 0xad, 0x49, + 0xe9, 0xf7, 0xc6, 0xf8, 0x50, 0xb1, 0xab, 0x49, 0x20, 0x46, 0xe9, 0xf7, + 0xda, 0xf8, 0x80, 0xb2, 0x01, 0x04, 0x5c, 0xbf, 0xa5, 0xf8, 0x66, 0x00, + 0xa5, 0xf8, 0x68, 0x00, 0x20, 0x46, 0xa6, 0x49, 0xe9, 0xf7, 0xb6, 0xf8, + 0x40, 0xb1, 0x20, 0x46, 0xa3, 0x49, 0xe9, 0xf7, 0xca, 0xf8, 0x80, 0xb2, + 0x02, 0x04, 0x58, 0xbf, 0xa5, 0xf8, 0x66, 0x00, 0x20, 0x46, 0xa0, 0x49, + 0xe9, 0xf7, 0xa8, 0xf8, 0x40, 0xb1, 0x20, 0x46, 0x9d, 0x49, 0xe9, 0xf7, + 0xbc, 0xf8, 0x80, 0xb2, 0x03, 0x04, 0x58, 0xbf, 0xa5, 0xf8, 0x68, 0x00, + 0x9a, 0x49, 0x4f, 0xf0, 0xff, 0x32, 0x20, 0x46, 0xe9, 0xf7, 0xa4, 0xf8, + 0x4f, 0xf0, 0xff, 0x32, 0xa5, 0xf8, 0xc4, 0x03, 0x96, 0x49, 0x20, 0x46, + 0xe9, 0xf7, 0x9c, 0xf8, 0x95, 0x49, 0xa5, 0xf8, 0xc6, 0x03, 0x20, 0x46, + 0xe9, 0xf7, 0xa3, 0xf8, 0x93, 0x49, 0xa5, 0xf8, 0xc8, 0x03, 0x4f, 0xf4, + 0xcf, 0x72, 0x20, 0x46, 0xe9, 0xf7, 0x8e, 0xf8, 0x90, 0x49, 0xc5, 0xf8, + 0xcc, 0x03, 0x47, 0xf6, 0x9a, 0x62, 0x20, 0x46, 0xe9, 0xf7, 0x86, 0xf8, + 0x8d, 0x49, 0xc5, 0xf8, 0xd0, 0x03, 0x0a, 0x22, 0x20, 0x46, 0xe9, 0xf7, + 0x7f, 0xf8, 0x8b, 0x49, 0xc5, 0xf8, 0xd4, 0x03, 0x08, 0x22, 0x20, 0x46, + 0xe9, 0xf7, 0x78, 0xf8, 0x88, 0x49, 0xc5, 0xf8, 0xd8, 0x03, 0x41, 0xf2, + 0x6e, 0x02, 0x20, 0x46, 0xe9, 0xf7, 0x70, 0xf8, 0x0a, 0x22, 0xc5, 0xf8, + 0xdc, 0x03, 0x84, 0x49, 0x20, 0x46, 0xe9, 0xf7, 0x69, 0xf8, 0x83, 0x49, + 0xc5, 0xf8, 0xe0, 0x03, 0x20, 0x46, 0xe9, 0xf7, 0x70, 0xf8, 0x81, 0x49, + 0xa5, 0xf8, 0xe4, 0x03, 0x20, 0x46, 0xe9, 0xf7, 0x6a, 0xf8, 0x95, 0xf8, + 0xe8, 0x33, 0xa5, 0xf8, 0xe6, 0x03, 0x2b, 0xb1, 0x00, 0xb2, 0x00, 0x28, + 0x02, 0xdd, 0x00, 0x20, 0xa5, 0xf8, 0xe6, 0x03, 0x50, 0x22, 0x79, 0x49, + 0x20, 0x46, 0xe9, 0xf7, 0x4d, 0xf8, 0x78, 0x49, 0x85, 0xf8, 0xea, 0x03, + 0x20, 0x46, 0xe9, 0xf7, 0x54, 0xf8, 0x76, 0x49, 0x85, 0xf8, 0xec, 0x03, + 0x20, 0x46, 0xe9, 0xf7, 0x4e, 0xf8, 0x74, 0x49, 0x85, 0xf8, 0xed, 0x03, + 0x20, 0x46, 0xe9, 0xf7, 0x48, 0xf8, 0x72, 0x49, 0x85, 0xf8, 0xee, 0x03, + 0x4f, 0xf0, 0xff, 0x32, 0x20, 0x46, 0xe9, 0xf7, 0x33, 0xf8, 0x6f, 0x49, + 0x85, 0xf8, 0xf0, 0x03, 0x4f, 0xf0, 0xff, 0x32, 0x20, 0x46, 0xe9, 0xf7, + 0x2b, 0xf8, 0xff, 0x23, 0x85, 0xf8, 0xef, 0x33, 0x85, 0xf8, 0xf1, 0x03, + 0x69, 0x49, 0x4f, 0xf0, 0xff, 0x32, 0x20, 0x46, 0xe9, 0xf7, 0x20, 0xf8, + 0x67, 0x49, 0x85, 0xf8, 0xf2, 0x03, 0x4f, 0xf0, 0xff, 0x32, 0x20, 0x46, + 0xe9, 0xf7, 0x18, 0xf8, 0x64, 0x49, 0x85, 0xf8, 0x59, 0x05, 0x4f, 0xf0, + 0xff, 0x32, 0x20, 0x46, 0xe9, 0xf7, 0x10, 0xf8, 0x61, 0x49, 0x85, 0xf8, + 0x5a, 0x05, 0x4f, 0xf0, 0xff, 0x32, 0x20, 0x46, 0xe9, 0xf7, 0x08, 0xf8, + 0x5e, 0x49, 0x85, 0xf8, 0xf3, 0x03, 0x4f, 0xf0, 0xff, 0x32, 0x20, 0x46, + 0xe9, 0xf7, 0x00, 0xf8, 0x5b, 0x49, 0x85, 0xf8, 0x5b, 0x05, 0x4f, 0xf0, + 0xff, 0x32, 0x20, 0x46, 0xe8, 0xf7, 0xf8, 0xff, 0x58, 0x49, 0x85, 0xf8, + 0x5c, 0x05, 0x4f, 0xf0, 0xff, 0x32, 0x20, 0x46, 0xe8, 0xf7, 0xf0, 0xff, + 0x00, 0x22, 0x85, 0xf8, 0xf4, 0x03, 0x54, 0x49, 0x20, 0x46, 0xe8, 0xf7, + 0xe9, 0xff, 0x53, 0x49, 0x85, 0xf8, 0x09, 0x04, 0x4f, 0xf0, 0xff, 0x32, + 0x20, 0x46, 0xe8, 0xf7, 0xe1, 0xff, 0x50, 0x49, 0x84, 0xf8, 0xda, 0x05, + 0x4f, 0xf0, 0xff, 0x32, 0x20, 0x46, 0xe8, 0xf7, 0xd9, 0xff, 0x4d, 0x49, + 0xa5, 0xf8, 0xf6, 0x03, 0x4f, 0xf0, 0xff, 0x32, 0x20, 0x46, 0xe8, 0xf7, + 0xd1, 0xff, 0x4a, 0x49, 0xa5, 0xf8, 0xf8, 0x03, 0x4f, 0xf0, 0xff, 0x32, + 0x20, 0x46, 0xe8, 0xf7, 0xc9, 0xff, 0x47, 0x49, 0xa5, 0xf8, 0xfa, 0x03, + 0x4f, 0xf0, 0xff, 0x32, 0x20, 0x46, 0xe8, 0xf7, 0xc1, 0xff, 0x44, 0x49, + 0xa5, 0xf8, 0xfc, 0x03, 0x4f, 0xf0, 0xff, 0x32, 0x20, 0x46, 0xe8, 0xf7, + 0xb9, 0xff, 0x41, 0x49, 0xa5, 0xf8, 0xfe, 0x03, 0x4f, 0xf0, 0xff, 0x32, + 0x20, 0x46, 0xe8, 0xf7, 0xb1, 0xff, 0x3e, 0x49, 0xa5, 0xf8, 0x00, 0x04, + 0x4f, 0xf0, 0xff, 0x32, 0x20, 0x46, 0xe8, 0xf7, 0xa9, 0xff, 0x3b, 0x49, + 0xa5, 0xf8, 0x02, 0x04, 0x4f, 0xf0, 0xff, 0x32, 0x20, 0x46, 0xe8, 0xf7, + 0xa1, 0xff, 0x00, 0x22, 0xa5, 0xf8, 0x04, 0x04, 0x36, 0x49, 0x20, 0x46, + 0xe8, 0xf7, 0x9a, 0xff, 0x00, 0x22, 0xa5, 0xf8, 0x5e, 0x05, 0x34, 0x49, + 0x20, 0x46, 0xe8, 0xf7, 0x93, 0xff, 0x00, 0x22, 0xa5, 0xf8, 0x60, 0x05, + 0x31, 0x49, 0x20, 0x46, 0xe8, 0xf7, 0x8c, 0xff, 0x30, 0x49, 0xa5, 0xf8, + 0x62, 0x05, 0x00, 0x22, 0x20, 0x46, 0xe8, 0xf7, 0x85, 0xff, 0x2e, 0x49, + 0xa5, 0xf8, 0x64, 0x05, 0x20, 0x46, 0x59, 0xe0, 0xb9, 0x96, 0x02, 0x00, + 0x00, 0x9d, 0x02, 0x00, 0xfa, 0x99, 0x02, 0x00, 0x28, 0x9f, 0x02, 0x00, + 0xde, 0x9d, 0x02, 0x00, 0xf2, 0x9e, 0x02, 0x00, 0x08, 0x98, 0x02, 0x00, + 0x95, 0x9b, 0x02, 0x00, 0x99, 0x97, 0x02, 0x00, 0xbd, 0x9c, 0x02, 0x00, + 0x01, 0x9e, 0x02, 0x00, 0x5e, 0x9e, 0x02, 0x00, 0x4e, 0x97, 0x02, 0x00, + 0x97, 0x9d, 0x02, 0x00, 0xb5, 0x98, 0x02, 0x00, 0xf3, 0x9c, 0x02, 0x00, + 0xec, 0x99, 0x02, 0x00, 0x15, 0x99, 0x02, 0x00, 0x32, 0x9b, 0x02, 0x00, + 0x9a, 0x96, 0x02, 0x00, 0x30, 0x9c, 0x02, 0x00, 0x78, 0x99, 0x02, 0x00, + 0x60, 0x99, 0x02, 0x00, 0xa5, 0x9e, 0x02, 0x00, 0x1c, 0x9d, 0x02, 0x00, + 0xd8, 0x97, 0x02, 0x00, 0xa4, 0x99, 0x02, 0x00, 0x4a, 0x9c, 0x02, 0x00, + 0x17, 0x97, 0x02, 0x00, 0x1c, 0x98, 0x02, 0x00, 0x9b, 0x9a, 0x02, 0x00, + 0x3b, 0x9b, 0x02, 0x00, 0x59, 0x9a, 0x02, 0x00, 0x25, 0x97, 0x02, 0x00, + 0xd8, 0x9c, 0x02, 0x00, 0x20, 0x9a, 0x02, 0x00, 0x4b, 0x98, 0x02, 0x00, + 0x52, 0x99, 0x02, 0x00, 0x46, 0x99, 0x02, 0x00, 0x58, 0x98, 0x02, 0x00, + 0xe5, 0x9c, 0x02, 0x00, 0x9c, 0x9b, 0x02, 0x00, 0x87, 0x9b, 0x02, 0x00, + 0x30, 0x9d, 0x02, 0x00, 0x8b, 0x96, 0x02, 0x00, 0xe8, 0xf7, 0x31, 0xff, + 0x02, 0x2f, 0x85, 0xf8, 0x06, 0x04, 0x14, 0xd1, 0x20, 0x46, 0xad, 0x49, + 0xe8, 0xf7, 0x10, 0xff, 0x00, 0x28, 0x00, 0xf0, 0xc5, 0x82, 0x2f, 0x46, + 0x00, 0x26, 0x32, 0x46, 0x20, 0x46, 0xa8, 0x49, 0xe8, 0xf7, 0x36, 0xff, + 0x01, 0x36, 0xc7, 0xf8, 0x0c, 0x04, 0x04, 0x37, 0x05, 0x2e, 0xf4, 0xd1, + 0x15, 0xe0, 0x01, 0x2f, 0x13, 0xd1, 0x20, 0x46, 0xa2, 0x49, 0xe8, 0xf7, + 0xf9, 0xfe, 0x00, 0x28, 0x00, 0xf0, 0xae, 0x82, 0x2f, 0x46, 0x00, 0x26, + 0x32, 0x46, 0x20, 0x46, 0x9d, 0x49, 0xe8, 0xf7, 0x1f, 0xff, 0x01, 0x36, + 0xc7, 0xf8, 0x20, 0x04, 0x04, 0x37, 0x05, 0x2e, 0xf4, 0xd1, 0x9a, 0x49, + 0x4f, 0xf0, 0xff, 0x32, 0x20, 0x46, 0xe8, 0xf7, 0xef, 0xfe, 0x98, 0x49, + 0xa5, 0xf8, 0x3e, 0x04, 0x4f, 0xf0, 0xff, 0x32, 0x20, 0x46, 0xe8, 0xf7, + 0xe7, 0xfe, 0x95, 0x49, 0xa5, 0xf8, 0x40, 0x04, 0x4f, 0xf0, 0xff, 0x32, + 0x20, 0x46, 0xe8, 0xf7, 0xdf, 0xfe, 0x92, 0x49, 0xa4, 0xf8, 0xfe, 0x0f, + 0x20, 0x46, 0xe8, 0xf7, 0xcd, 0xfe, 0x30, 0xb1, 0x20, 0x46, 0x8e, 0x49, + 0xe8, 0xf7, 0xe1, 0xfe, 0x04, 0xf5, 0x98, 0x53, 0x58, 0x81, 0x8c, 0x49, + 0x20, 0x46, 0x4f, 0xf0, 0xff, 0x32, 0xe8, 0xf7, 0xcb, 0xfe, 0x04, 0xf5, + 0x9a, 0x53, 0x98, 0x82, 0x88, 0x49, 0x20, 0x46, 0xe8, 0xf7, 0xb8, 0xfe, + 0x30, 0xb1, 0x20, 0x46, 0x85, 0x49, 0xe8, 0xf7, 0xcc, 0xfe, 0x04, 0xf5, + 0x98, 0x53, 0xd8, 0x81, 0x20, 0x46, 0x83, 0x49, 0x00, 0x22, 0xe8, 0xf7, + 0xb7, 0xfe, 0xc0, 0xb2, 0x85, 0xf8, 0x4d, 0x03, 0x58, 0xb1, 0x80, 0x49, + 0x20, 0x46, 0xe8, 0xf7, 0xbc, 0xfe, 0x7f, 0x49, 0xc5, 0xf8, 0x50, 0x03, + 0x20, 0x46, 0xe8, 0xf7, 0xb6, 0xfe, 0xc5, 0xf8, 0x60, 0x03, 0x20, 0x46, + 0x7b, 0x49, 0xe8, 0xf7, 0x97, 0xfe, 0x00, 0x28, 0x37, 0xd0, 0xd4, 0xf8, + 0xb8, 0x00, 0x78, 0x49, 0xda, 0xf7, 0xc6, 0xfb, 0x06, 0x28, 0x30, 0xd1, + 0x75, 0x49, 0x00, 0x22, 0xd4, 0xf8, 0xb8, 0x00, 0xda, 0xf3, 0x3c, 0xf4, + 0x85, 0xf8, 0x95, 0x03, 0x71, 0x49, 0x01, 0x22, 0xd4, 0xf8, 0xb8, 0x00, + 0xda, 0xf3, 0x34, 0xf4, 0x85, 0xf8, 0x97, 0x03, 0x6d, 0x49, 0x02, 0x22, + 0xd4, 0xf8, 0xb8, 0x00, 0xda, 0xf3, 0x2c, 0xf4, 0x85, 0xf8, 0x99, 0x03, + 0x69, 0x49, 0x03, 0x22, 0xd4, 0xf8, 0xb8, 0x00, 0xda, 0xf3, 0x24, 0xf4, + 0x85, 0xf8, 0x96, 0x03, 0x65, 0x49, 0x04, 0x22, 0xd4, 0xf8, 0xb8, 0x00, + 0xda, 0xf3, 0x1c, 0xf4, 0x85, 0xf8, 0x98, 0x03, 0xd4, 0xf8, 0xb8, 0x00, + 0x60, 0x49, 0x05, 0x22, 0xda, 0xf3, 0x14, 0xf4, 0x85, 0xf8, 0x9a, 0x03, + 0x10, 0xe0, 0x01, 0x23, 0x85, 0xf8, 0x95, 0x33, 0x32, 0x23, 0x85, 0xf8, + 0x96, 0x33, 0x40, 0x23, 0x85, 0xf8, 0x97, 0x33, 0x85, 0xf8, 0x98, 0x33, + 0x04, 0x23, 0x85, 0xf8, 0x99, 0x33, 0xff, 0x23, 0x85, 0xf8, 0x9a, 0x33, + 0x55, 0x49, 0x20, 0x46, 0xff, 0x22, 0xe8, 0xf7, 0x53, 0xfe, 0xff, 0x23, + 0xa5, 0xf8, 0x54, 0x03, 0xa5, 0xf8, 0x56, 0x33, 0xa5, 0xf8, 0x58, 0x33, + 0xa5, 0xf8, 0x5a, 0x33, 0x20, 0x46, 0x4f, 0x49, 0xe8, 0xf7, 0x3a, 0xfe, + 0x38, 0xb3, 0xd4, 0xf8, 0xb8, 0x00, 0x4c, 0x49, 0xda, 0xf7, 0x6a, 0xfb, + 0x2f, 0x46, 0x03, 0x28, 0xb4, 0xbf, 0x80, 0x46, 0x4f, 0xf0, 0x03, 0x08, + 0x00, 0x26, 0x07, 0xe0, 0x32, 0x46, 0x20, 0x46, 0x45, 0x49, 0xe8, 0xf7, + 0x57, 0xfe, 0x01, 0x36, 0xa7, 0xf8, 0x54, 0x03, 0x02, 0x37, 0x46, 0x45, + 0xf4, 0xdb, 0x28, 0xea, 0xe8, 0x78, 0x42, 0x46, 0x00, 0x23, 0x08, 0xe0, + 0x05, 0xeb, 0x48, 0x01, 0xb5, 0xf8, 0x56, 0x03, 0xc9, 0x18, 0xa1, 0xf8, + 0x56, 0x03, 0x01, 0x32, 0x02, 0x33, 0x02, 0x2a, 0xf4, 0xdd, 0x01, 0x22, + 0x39, 0x49, 0x20, 0x46, 0xe8, 0xf7, 0x18, 0xfe, 0x38, 0x49, 0x85, 0xf8, + 0x40, 0x03, 0x20, 0x46, 0xe8, 0xf7, 0x1f, 0xfe, 0x01, 0x22, 0x85, 0xf8, + 0x4b, 0x03, 0x35, 0x49, 0x20, 0x46, 0xe8, 0xf7, 0x0b, 0xfe, 0x34, 0x49, + 0x85, 0xf8, 0x41, 0x03, 0x20, 0x46, 0xe8, 0xf7, 0x12, 0xfe, 0x32, 0x49, + 0x85, 0xf8, 0x4c, 0x03, 0x4f, 0xf0, 0xff, 0x32, 0x20, 0x46, 0xe8, 0xf7, + 0xfd, 0xfd, 0x2f, 0x49, 0x85, 0xf8, 0x49, 0x03, 0x4f, 0xf0, 0xff, 0x32, + 0x20, 0x46, 0xe8, 0xf7, 0xf5, 0xfd, 0x2c, 0x49, 0x85, 0xf8, 0x4a, 0x03, + 0x4f, 0xf0, 0xff, 0x32, 0x20, 0x46, 0xe8, 0xf7, 0xed, 0xfd, 0x29, 0x49, + 0x85, 0xf8, 0x5c, 0x03, 0x4f, 0xf0, 0xff, 0x32, 0x20, 0x46, 0xe8, 0xf7, + 0xe5, 0xfd, 0x26, 0x49, 0x85, 0xf8, 0x5d, 0x03, 0x20, 0x46, 0xe8, 0xf7, + 0xd3, 0xfd, 0x00, 0x28, 0x46, 0xd0, 0x01, 0x26, 0x21, 0x49, 0x00, 0x22, + 0x85, 0xf8, 0xbb, 0x64, 0x20, 0x46, 0xe8, 0xf7, 0xf9, 0xfd, 0x1e, 0x49, + 0x85, 0xf8, 0xbc, 0x04, 0x32, 0x46, 0x20, 0x46, 0xe8, 0xf7, 0xf2, 0xfd, + 0x1a, 0x49, 0x85, 0xf8, 0xbd, 0x04, 0x02, 0x22, 0x20, 0x46, 0xe8, 0xf7, + 0xeb, 0xfd, 0x85, 0xf8, 0xbe, 0x04, 0x2f, 0xe0, 0x0f, 0x98, 0x02, 0x00, + 0xac, 0x9b, 0x02, 0x00, 0x31, 0x97, 0x02, 0x00, 0x29, 0x9d, 0x02, 0x00, + 0xa5, 0x9c, 0x02, 0x00, 0x6c, 0x99, 0x02, 0x00, 0xc1, 0x9e, 0x02, 0x00, + 0x80, 0x9c, 0x02, 0x00, 0xb8, 0x97, 0x02, 0x00, 0x1c, 0x9c, 0x02, 0x00, + 0xbd, 0x99, 0x02, 0x00, 0xf7, 0x97, 0x02, 0x00, 0x65, 0x9b, 0x02, 0x00, + 0x4a, 0x9f, 0x02, 0x00, 0x47, 0x9d, 0x02, 0x00, 0xbc, 0x98, 0x02, 0x00, + 0x85, 0x97, 0x02, 0x00, 0xda, 0x9b, 0x02, 0x00, 0xa4, 0x98, 0x02, 0x00, + 0xef, 0x96, 0x02, 0x00, 0x39, 0x9c, 0x02, 0x00, 0xa5, 0x9a, 0x02, 0x00, + 0x38, 0x9f, 0x02, 0x00, 0x85, 0xf8, 0xbb, 0x04, 0xff, 0x22, 0xa1, 0x49, + 0x20, 0x46, 0xe8, 0xf7, 0x8f, 0xfd, 0xff, 0x22, 0x85, 0xf8, 0xbf, 0x04, + 0x9e, 0x49, 0x20, 0x46, 0xe8, 0xf7, 0x88, 0xfd, 0x9d, 0x49, 0x85, 0xf8, + 0xc0, 0x04, 0x20, 0x46, 0xe8, 0xf7, 0x8f, 0xfd, 0x00, 0x22, 0xa5, 0xf8, + 0xc2, 0x04, 0x9a, 0x49, 0x20, 0x46, 0xe8, 0xf7, 0x7b, 0xfd, 0x00, 0x22, + 0x85, 0xf8, 0x18, 0x05, 0x97, 0x49, 0x20, 0x46, 0xe8, 0xf7, 0x74, 0xfd, + 0xc0, 0xb2, 0x85, 0xf8, 0x1a, 0x05, 0xe3, 0x69, 0xdb, 0x68, 0x5b, 0x6c, + 0x03, 0xf0, 0x07, 0x03, 0x05, 0x2b, 0x03, 0xd9, 0x10, 0xb1, 0x00, 0x23, + 0x85, 0xf8, 0x1a, 0x35, 0x8f, 0x49, 0x00, 0x22, 0x20, 0x46, 0xe8, 0xf7, + 0x61, 0xfd, 0x8e, 0x49, 0x85, 0xf8, 0x1c, 0x05, 0x00, 0x22, 0x20, 0x46, + 0xe8, 0xf7, 0x5a, 0xfd, 0x8b, 0x49, 0x85, 0xf8, 0x1d, 0x05, 0x4f, 0xf0, + 0xff, 0x32, 0x20, 0x46, 0xe8, 0xf7, 0x52, 0xfd, 0x88, 0x49, 0x85, 0xf8, + 0x1e, 0x05, 0x00, 0x22, 0x20, 0x46, 0xe8, 0xf7, 0x4b, 0xfd, 0x86, 0x49, + 0x85, 0xf8, 0x95, 0x05, 0x4f, 0xf0, 0xff, 0x32, 0x20, 0x46, 0xe8, 0xf7, + 0x43, 0xfd, 0x83, 0x49, 0xa5, 0xf8, 0x20, 0x05, 0x01, 0x22, 0x20, 0x46, + 0xe8, 0xf7, 0x3c, 0xfd, 0x80, 0x49, 0x85, 0xf8, 0x27, 0x05, 0x4f, 0xf0, + 0xff, 0x32, 0x20, 0x46, 0xe8, 0xf7, 0x34, 0xfd, 0x7d, 0x49, 0xa5, 0xf8, + 0x2a, 0x05, 0x4f, 0xf0, 0xff, 0x32, 0x20, 0x46, 0xe8, 0xf7, 0x2c, 0xfd, + 0x7a, 0x49, 0xa5, 0xf8, 0x2c, 0x05, 0x00, 0x22, 0x20, 0x46, 0xe8, 0xf7, + 0x25, 0xfd, 0x78, 0x49, 0x85, 0xf8, 0x3a, 0x05, 0x00, 0x22, 0x20, 0x46, + 0xe8, 0xf7, 0x1e, 0xfd, 0x75, 0x49, 0x85, 0xf8, 0x3b, 0x05, 0x4f, 0xf0, + 0xff, 0x32, 0x20, 0x46, 0xe8, 0xf7, 0x16, 0xfd, 0x72, 0x49, 0x85, 0xf8, + 0x3c, 0x05, 0x20, 0x46, 0xe8, 0xf7, 0x04, 0xfd, 0x30, 0xb1, 0x20, 0x46, + 0x6e, 0x49, 0xe8, 0xf7, 0x18, 0xfd, 0x85, 0xf8, 0x42, 0x05, 0x02, 0xe0, + 0xff, 0x23, 0x85, 0xf8, 0x42, 0x35, 0x20, 0x46, 0x6a, 0x49, 0xe8, 0xf7, + 0xf5, 0xfc, 0x30, 0xb1, 0x20, 0x46, 0x68, 0x49, 0xe8, 0xf7, 0x09, 0xfd, + 0xa5, 0xf8, 0x44, 0x05, 0x03, 0xe0, 0x4f, 0xf0, 0xff, 0x33, 0xa5, 0xf8, + 0x44, 0x35, 0x64, 0x49, 0x20, 0x46, 0x4f, 0xf0, 0xff, 0x32, 0xe8, 0xf7, + 0xef, 0xfc, 0x62, 0x49, 0xa5, 0xf8, 0x90, 0x05, 0x20, 0x46, 0xe8, 0xf7, + 0xdd, 0xfc, 0x30, 0xb3, 0x01, 0x26, 0x5e, 0x49, 0x00, 0x22, 0x85, 0xf8, + 0x52, 0x65, 0x20, 0x46, 0xe8, 0xf7, 0x04, 0xfd, 0x5a, 0x49, 0x85, 0xf8, + 0x53, 0x05, 0x32, 0x46, 0x20, 0x46, 0xe8, 0xf7, 0xfd, 0xfc, 0x57, 0x49, + 0x85, 0xf8, 0x54, 0x05, 0x02, 0x22, 0x20, 0x46, 0xe8, 0xf7, 0xf6, 0xfc, + 0x53, 0x49, 0x85, 0xf8, 0x55, 0x05, 0x03, 0x22, 0x20, 0x46, 0xe8, 0xf7, + 0xef, 0xfc, 0x50, 0x49, 0x85, 0xf8, 0x56, 0x05, 0x04, 0x22, 0x20, 0x46, + 0xe8, 0xf7, 0xe8, 0xfc, 0x85, 0xf8, 0x57, 0x05, 0x01, 0xe0, 0x85, 0xf8, + 0x52, 0x05, 0x4b, 0x49, 0x4f, 0xf0, 0xff, 0x32, 0x20, 0x46, 0xe8, 0xf7, + 0xb9, 0xfc, 0x49, 0x49, 0x85, 0xf8, 0x58, 0x05, 0x4f, 0xf0, 0xff, 0x32, + 0x20, 0x46, 0xe8, 0xf7, 0xb1, 0xfc, 0x46, 0x49, 0x85, 0xf8, 0x59, 0x05, + 0x4f, 0xf0, 0xff, 0x32, 0x20, 0x46, 0xe8, 0xf7, 0xa9, 0xfc, 0x43, 0x49, + 0x85, 0xf8, 0x5a, 0x05, 0x00, 0x22, 0x20, 0x46, 0xe8, 0xf7, 0xa2, 0xfc, + 0x40, 0x49, 0x85, 0xf8, 0x70, 0x05, 0x00, 0x22, 0x20, 0x46, 0xe8, 0xf7, + 0x9b, 0xfc, 0x03, 0x22, 0x85, 0xf8, 0x80, 0x05, 0x3c, 0x49, 0x20, 0x46, + 0xe8, 0xf7, 0x94, 0xfc, 0x3b, 0x49, 0x85, 0xf8, 0x81, 0x05, 0x20, 0x46, + 0xe8, 0xf7, 0x9b, 0xfc, 0x39, 0x49, 0x85, 0xf8, 0x82, 0x05, 0x20, 0x46, + 0xe8, 0xf7, 0x95, 0xfc, 0x37, 0x49, 0xa5, 0xf8, 0x84, 0x05, 0x20, 0x46, + 0xe8, 0xf7, 0x8f, 0xfc, 0x35, 0x49, 0xa5, 0xf8, 0x86, 0x05, 0x20, 0x46, + 0xe8, 0xf7, 0x89, 0xfc, 0x33, 0x49, 0xa5, 0xf8, 0x88, 0x05, 0x20, 0x46, + 0xe8, 0xf7, 0x83, 0xfc, 0x31, 0x49, 0xa5, 0xf8, 0x8a, 0x05, 0x20, 0x46, + 0xe8, 0xf7, 0x7d, 0xfc, 0x2f, 0x49, 0xc5, 0xf8, 0x8c, 0x05, 0x00, 0x22, + 0x20, 0x46, 0xe8, 0xf7, 0x69, 0xfc, 0x2d, 0x49, 0x85, 0xf8, 0x94, 0x05, + 0x4f, 0xf0, 0xff, 0x32, 0x20, 0x46, 0xe8, 0xf7, 0x61, 0xfc, 0xc0, 0xb2, + 0xa5, 0xf8, 0xc6, 0x05, 0x28, 0x49, 0x20, 0x46, 0x6f, 0xf0, 0x07, 0x02, + 0xe8, 0xf7, 0x58, 0xfc, 0xc0, 0xb2, 0xa5, 0xf8, 0xc8, 0x05, 0x01, 0x20, + 0x06, 0xb0, 0xbd, 0xe8, 0xf0, 0x81, 0x00, 0xbf, 0x8f, 0x9d, 0x02, 0x00, + 0xd6, 0x9d, 0x02, 0x00, 0x3e, 0x97, 0x02, 0x00, 0x64, 0x9a, 0x02, 0x00, + 0xc7, 0x9b, 0x02, 0x00, 0xb6, 0x9a, 0x02, 0x00, 0x0b, 0x9d, 0x02, 0x00, + 0x05, 0x9b, 0x02, 0x00, 0xc7, 0x9a, 0x02, 0x00, 0x26, 0x98, 0x02, 0x00, + 0x79, 0x96, 0x02, 0x00, 0xec, 0x98, 0x02, 0x00, 0x33, 0x98, 0x02, 0x00, + 0x61, 0x97, 0x02, 0x00, 0x3f, 0x98, 0x02, 0x00, 0x09, 0x9a, 0x02, 0x00, + 0x28, 0x99, 0x02, 0x00, 0xe3, 0x96, 0x02, 0x00, 0x6e, 0x98, 0x02, 0x00, + 0x00, 0x9c, 0x02, 0x00, 0x13, 0x9a, 0x02, 0x00, 0x1c, 0x9d, 0x02, 0x00, + 0xd8, 0x97, 0x02, 0x00, 0xb0, 0x99, 0x02, 0x00, 0x0a, 0x9e, 0x02, 0x00, + 0x81, 0x98, 0x02, 0x00, 0xd1, 0x98, 0x02, 0x00, 0x94, 0x9c, 0x02, 0x00, + 0x92, 0x98, 0x02, 0x00, 0x47, 0x9a, 0x02, 0x00, 0x75, 0x9b, 0x02, 0x00, + 0x83, 0x99, 0x02, 0x00, 0x3e, 0x9e, 0x02, 0x00, 0x92, 0x96, 0x02, 0x00, + 0xaf, 0x97, 0x02, 0x00, 0xc3, 0x69, 0x70, 0xb5, 0x04, 0x46, 0x0d, 0x46, + 0x98, 0x68, 0x40, 0xf2, 0xcc, 0x51, 0xde, 0xf3, 0x47, 0xf3, 0xc4, 0xf8, + 0xa8, 0x00, 0x00, 0x28, 0x59, 0xd0, 0x00, 0x21, 0x40, 0xf2, 0xcc, 0x52, + 0xd9, 0xf3, 0xf6, 0xf4, 0xe3, 0x69, 0xd4, 0xf8, 0xa8, 0x60, 0x1a, 0x6d, + 0xd2, 0x03, 0x05, 0xd4, 0x01, 0x22, 0x04, 0xf5, 0x82, 0x51, 0x84, 0xf8, + 0x1a, 0x26, 0x0a, 0x71, 0xd8, 0x68, 0xe4, 0xf7, 0x1a, 0xfc, 0x04, 0xf5, + 0x80, 0x53, 0x98, 0x62, 0x00, 0x23, 0xf3, 0x63, 0x20, 0x4b, 0x20, 0x46, + 0x23, 0x62, 0x20, 0x4b, 0x29, 0x46, 0x63, 0x62, 0x1f, 0x4b, 0xa3, 0x62, + 0x1f, 0x4b, 0xe3, 0x62, 0x1f, 0x4b, 0xa3, 0x67, 0x1f, 0x4b, 0xe3, 0x67, + 0x1f, 0x4b, 0xc4, 0xf8, 0x90, 0x30, 0x1f, 0x4b, 0xc4, 0xf8, 0x84, 0x30, + 0x1e, 0x4b, 0x23, 0x63, 0x1e, 0x4b, 0x63, 0x63, 0x1e, 0x4b, 0xe3, 0x63, + 0x1e, 0x4b, 0x63, 0x64, 0x1e, 0x4b, 0x63, 0x65, 0x1e, 0x4b, 0xa3, 0x65, + 0x1e, 0x4b, 0xc4, 0xf8, 0x8c, 0x30, 0x1e, 0x4b, 0xc4, 0xf8, 0x88, 0x30, + 0x1d, 0x4b, 0xe3, 0x66, 0x1d, 0x4b, 0xc4, 0xf8, 0x9c, 0x30, 0x1d, 0x4b, + 0xc4, 0xf8, 0xa0, 0x30, 0x1c, 0x4b, 0xc4, 0xf8, 0xa4, 0x30, 0xfe, 0xf7, + 0xa7, 0xff, 0x60, 0xb1, 0x20, 0x46, 0xeb, 0xf7, 0x85, 0xfd, 0x20, 0x46, + 0xfe, 0xf7, 0x02, 0xff, 0x28, 0xb1, 0x20, 0x46, 0xfe, 0xf7, 0x5a, 0xff, + 0x00, 0x30, 0x18, 0xbf, 0x01, 0x20, 0x70, 0xbd, 0x55, 0x81, 0x01, 0x00, + 0x1d, 0x2e, 0x01, 0x00, 0x75, 0xb2, 0x01, 0x00, 0x0f, 0x73, 0x01, 0x00, + 0x75, 0x71, 0x01, 0x00, 0xaf, 0x2e, 0x01, 0x00, 0x09, 0x79, 0x01, 0x00, + 0xf1, 0x78, 0x01, 0x00, 0xa1, 0x90, 0x01, 0x00, 0x39, 0x56, 0x01, 0x00, + 0x35, 0x63, 0x01, 0x00, 0x69, 0x53, 0x01, 0x00, 0x8d, 0x37, 0x01, 0x00, + 0xc9, 0x39, 0x01, 0x00, 0x63, 0xb1, 0x01, 0x00, 0xad, 0x2e, 0x01, 0x00, + 0x9d, 0x35, 0x01, 0x00, 0x6b, 0x56, 0x01, 0x00, 0xa5, 0x50, 0x01, 0x00, + 0x31, 0xb1, 0x01, 0x00, 0xf8, 0xb5, 0x05, 0x46, 0x0e, 0x46, 0x00, 0x68, + 0x0c, 0x21, 0x17, 0x46, 0xde, 0xf3, 0xb8, 0xf2, 0x04, 0x46, 0x30, 0xb1, + 0x00, 0x21, 0x0c, 0x22, 0xd9, 0xf3, 0x6a, 0xf4, 0x84, 0xe8, 0xa0, 0x00, + 0xa6, 0x60, 0x20, 0x46, 0xf8, 0xbd, 0x01, 0x46, 0x20, 0xb1, 0x03, 0x68, + 0x0c, 0x22, 0x18, 0x68, 0xde, 0xf3, 0xb6, 0xb2, 0x70, 0x47, 0x00, 0x00, + 0x7f, 0xb5, 0x05, 0x46, 0x88, 0x21, 0x40, 0x68, 0xde, 0xf3, 0x9e, 0xf2, + 0x04, 0x46, 0x00, 0x28, 0x3a, 0xd0, 0x00, 0x21, 0x88, 0x22, 0xd9, 0xf3, + 0x4f, 0xf4, 0x2b, 0x68, 0x25, 0x60, 0x63, 0x60, 0x00, 0x26, 0x04, 0x21, + 0x28, 0x46, 0x1a, 0x4a, 0x1a, 0x4b, 0x00, 0x96, 0x01, 0x94, 0x00, 0xf0, + 0x39, 0xf9, 0xb0, 0x42, 0xa0, 0x60, 0x21, 0xdb, 0x17, 0x4b, 0x02, 0x96, + 0x8d, 0xe8, 0x48, 0x00, 0x03, 0x96, 0x60, 0x68, 0x15, 0x49, 0x16, 0x4a, + 0x23, 0x46, 0xfb, 0xf3, 0x81, 0xf3, 0xa8, 0xb9, 0x1e, 0x22, 0x62, 0x61, + 0x04, 0x22, 0xe2, 0x73, 0x02, 0x22, 0x22, 0x74, 0x0a, 0x22, 0x01, 0x23, + 0x62, 0x74, 0x4f, 0xf6, 0xaf, 0x72, 0x84, 0xf8, 0x20, 0x00, 0xe3, 0x77, + 0x23, 0x73, 0xa3, 0x61, 0xa0, 0x74, 0x60, 0x73, 0xa0, 0x73, 0xa2, 0x83, + 0xa3, 0x77, 0x05, 0xe0, 0x21, 0x46, 0x68, 0x68, 0x88, 0x22, 0xde, 0xf3, + 0x71, 0xf2, 0x00, 0x24, 0x20, 0x46, 0x04, 0xb0, 0x70, 0xbd, 0x00, 0xbf, + 0x51, 0x23, 0x85, 0x00, 0x25, 0x23, 0x85, 0x00, 0x81, 0x14, 0x85, 0x00, + 0xbc, 0x1d, 0x86, 0x00, 0x03, 0xe8, 0x86, 0x00, 0x10, 0xb5, 0x04, 0x46, + 0x60, 0xb1, 0x22, 0x46, 0x06, 0x49, 0x40, 0x68, 0xfb, 0xf3, 0x86, 0xf3, + 0x63, 0x68, 0x21, 0x46, 0xd8, 0x68, 0x88, 0x22, 0xbd, 0xe8, 0x10, 0x40, + 0xde, 0xf3, 0x52, 0xb2, 0x10, 0xbd, 0x00, 0xbf, 0x03, 0xe8, 0x86, 0x00, + 0x2d, 0xe9, 0xf0, 0x43, 0x07, 0x46, 0x85, 0xb0, 0x88, 0x46, 0x10, 0x46, + 0x40, 0xf2, 0xc4, 0x51, 0x15, 0x46, 0x99, 0x46, 0xde, 0xf3, 0x32, 0xf2, + 0x04, 0x46, 0x00, 0x28, 0x76, 0xd0, 0x00, 0x21, 0x40, 0xf2, 0xc4, 0x52, + 0xd9, 0xf3, 0xe2, 0xf3, 0x28, 0x46, 0x1c, 0x21, 0xde, 0xf3, 0x26, 0xf2, + 0x06, 0x46, 0x20, 0x60, 0x38, 0xb9, 0x28, 0x46, 0x21, 0x46, 0x40, 0xf2, + 0xc4, 0x52, 0xde, 0xf3, 0x2d, 0xf2, 0x30, 0x46, 0x62, 0xe0, 0x00, 0x21, + 0x1c, 0x22, 0xd9, 0xf3, 0xcf, 0xf3, 0x23, 0x68, 0x40, 0xf2, 0xc4, 0x52, + 0x1c, 0x60, 0x00, 0x26, 0x62, 0x61, 0x4f, 0xf0, 0xff, 0x32, 0xa2, 0x61, + 0xa7, 0x60, 0xe5, 0x60, 0xc4, 0xf8, 0x04, 0x90, 0x9e, 0x71, 0x14, 0x23, + 0xa4, 0xf8, 0x08, 0x32, 0x28, 0x23, 0xa4, 0xf8, 0x06, 0x32, 0x2d, 0x23, + 0xa4, 0xf8, 0x04, 0x32, 0xfa, 0x23, 0xa4, 0xf8, 0x0a, 0x32, 0x02, 0x23, + 0x84, 0xf8, 0x0c, 0x32, 0x64, 0x23, 0xa4, 0xf8, 0x3e, 0x32, 0x84, 0xf8, + 0x0d, 0x62, 0x40, 0x46, 0x1f, 0x49, 0x22, 0x46, 0x33, 0x46, 0xe6, 0xf3, + 0xe3, 0xf6, 0xc4, 0xf8, 0xf8, 0x01, 0x00, 0xb3, 0x04, 0xf5, 0x10, 0x73, + 0xc4, 0xf8, 0x18, 0x32, 0xc4, 0xf8, 0x14, 0x32, 0x04, 0xf5, 0x3d, 0x73, + 0xc4, 0xf8, 0x24, 0x32, 0xc4, 0xf8, 0x20, 0x32, 0x05, 0x22, 0x16, 0x4b, + 0xc4, 0xf8, 0x1c, 0x22, 0x3c, 0x22, 0xc4, 0xf8, 0x28, 0x22, 0x8d, 0xe8, + 0x48, 0x00, 0x13, 0x4b, 0x02, 0x96, 0x03, 0x93, 0x38, 0x68, 0x12, 0x49, + 0x12, 0x4a, 0x23, 0x46, 0xfb, 0xf3, 0xd2, 0xf2, 0x08, 0xb9, 0x20, 0x68, + 0x12, 0xe0, 0xd4, 0xf8, 0xf8, 0x11, 0x11, 0xb1, 0x40, 0x46, 0xe6, 0xf3, + 0x9d, 0xf6, 0x21, 0x68, 0x19, 0xb1, 0x28, 0x46, 0x1c, 0x22, 0xde, 0xf3, + 0xcf, 0xf1, 0x28, 0x46, 0x21, 0x46, 0x40, 0xf2, 0xc4, 0x52, 0xde, 0xf3, + 0xc9, 0xf1, 0x00, 0x20, 0x05, 0xb0, 0xbd, 0xe8, 0xf0, 0x83, 0x00, 0xbf, + 0xc1, 0x3c, 0x85, 0x00, 0xf5, 0x37, 0x85, 0x00, 0x99, 0xb4, 0x01, 0x00, + 0xd4, 0x1d, 0x86, 0x00, 0xe6, 0xe8, 0x86, 0x00, 0x38, 0xb5, 0x04, 0x68, + 0xdc, 0xb1, 0xd4, 0xf8, 0xf8, 0x11, 0xa5, 0x68, 0x29, 0xb1, 0xa8, 0x68, + 0xe6, 0xf3, 0x78, 0xf6, 0x00, 0x23, 0xc4, 0xf8, 0xf8, 0x31, 0x09, 0x49, + 0x28, 0x68, 0x22, 0x46, 0xfb, 0xf3, 0xd4, 0xf2, 0x21, 0x68, 0x19, 0xb1, + 0x68, 0x68, 0x1c, 0x22, 0xde, 0xf3, 0xa2, 0xf1, 0x68, 0x68, 0x62, 0x69, + 0x21, 0x46, 0xbd, 0xe8, 0x38, 0x40, 0xde, 0xf3, 0x9b, 0xb1, 0x38, 0xbd, + 0xe6, 0xe8, 0x86, 0x00, 0xf8, 0xb5, 0xc3, 0x69, 0x06, 0x46, 0x1b, 0x69, + 0xc0, 0x68, 0xdd, 0x1d, 0x48, 0xbf, 0x03, 0xf1, 0x0e, 0x05, 0xed, 0x10, + 0xed, 0xb2, 0xef, 0x00, 0x07, 0xf5, 0x92, 0x77, 0x39, 0x46, 0xde, 0xf3, + 0x77, 0xf1, 0x04, 0x46, 0xa0, 0xb1, 0x3a, 0x46, 0x00, 0x21, 0xd9, 0xf3, + 0x29, 0xf3, 0x23, 0x46, 0x43, 0xf8, 0x24, 0x6b, 0xe3, 0x61, 0x03, 0xeb, + 0x85, 0x03, 0x03, 0xf5, 0x80, 0x73, 0x04, 0xf5, 0x92, 0x72, 0x23, 0x61, + 0x4f, 0xf4, 0x03, 0x73, 0x84, 0xf8, 0x20, 0x50, 0xe2, 0x60, 0x63, 0x61, + 0x20, 0x46, 0xf8, 0xbd, 0x01, 0x46, 0x40, 0xb1, 0x90, 0xf8, 0x20, 0x20, + 0x03, 0x68, 0xd2, 0x00, 0xd8, 0x68, 0x02, 0xf5, 0x92, 0x72, 0xde, 0xf3, + 0x63, 0xb1, 0x70, 0x47, 0xf0, 0xb5, 0xd0, 0xf8, 0x00, 0x45, 0xa5, 0x69, + 0x0f, 0x2d, 0x11, 0xd8, 0xe7, 0x69, 0x2e, 0x01, 0xb8, 0x19, 0x01, 0x35, + 0xa5, 0x61, 0x43, 0x60, 0x05, 0x9b, 0xba, 0x51, 0x83, 0x60, 0x06, 0x9b, + 0xc3, 0x60, 0x60, 0x69, 0xc3, 0x1c, 0x59, 0x18, 0x21, 0xf0, 0x03, 0x01, + 0x61, 0x61, 0xf0, 0xbd, 0x4f, 0xf0, 0xff, 0x30, 0xf0, 0xbd, 0x00, 0x00, + 0x2d, 0xe9, 0xf0, 0x4f, 0x3b, 0x4d, 0x8d, 0xb0, 0x28, 0x68, 0x3b, 0x49, + 0xd9, 0xf3, 0x82, 0xf7, 0x01, 0x28, 0x61, 0xd0, 0x2b, 0x68, 0xdf, 0xf8, + 0x0c, 0x91, 0x02, 0x93, 0xdf, 0xf8, 0x08, 0x81, 0xd9, 0xf8, 0x00, 0x30, + 0x00, 0x24, 0x03, 0x93, 0xd8, 0xf8, 0x00, 0x30, 0x33, 0x4f, 0x04, 0x93, + 0x23, 0x68, 0x33, 0x4e, 0x05, 0x93, 0x3b, 0x68, 0xdf, 0xf8, 0xf0, 0xa0, + 0x06, 0x93, 0x33, 0x68, 0xdf, 0xf8, 0xec, 0xb0, 0x07, 0x93, 0xda, 0xf8, + 0x00, 0x30, 0xdf, 0xf8, 0xe8, 0xc0, 0x08, 0x93, 0xdb, 0xf8, 0x00, 0x30, + 0x2b, 0x48, 0x09, 0x93, 0x2b, 0x4b, 0x2c, 0x49, 0x1a, 0x68, 0x3c, 0x60, + 0x0a, 0x92, 0xdc, 0xf8, 0x00, 0x20, 0x1c, 0x60, 0x0b, 0x92, 0x29, 0x4a, + 0xcc, 0xf8, 0x00, 0x40, 0x32, 0x60, 0x09, 0x1a, 0x4f, 0xf0, 0xff, 0x32, + 0x01, 0x93, 0xcd, 0xf8, 0x00, 0xc0, 0x2c, 0x60, 0xc8, 0xf8, 0x00, 0x40, + 0xc9, 0xf8, 0x00, 0x40, 0xcb, 0xf8, 0x00, 0x40, 0xca, 0xf8, 0x00, 0x40, + 0xd9, 0xf3, 0x94, 0xf7, 0x1f, 0x4a, 0x01, 0x9b, 0x90, 0x42, 0xdd, 0xf8, + 0x00, 0xc0, 0x28, 0xd1, 0x02, 0x9a, 0x2a, 0x60, 0x03, 0x9a, 0xc9, 0xf8, + 0x00, 0x20, 0x04, 0x9a, 0xc8, 0xf8, 0x00, 0x20, 0x21, 0x68, 0x19, 0x4a, + 0x11, 0x60, 0x05, 0x9a, 0x22, 0x60, 0x06, 0x9a, 0x3a, 0x60, 0x07, 0x9a, + 0x32, 0x60, 0x08, 0x9a, 0xca, 0xf8, 0x00, 0x20, 0x09, 0x9a, 0xcb, 0xf8, + 0x00, 0x20, 0x0a, 0x9a, 0x1a, 0x60, 0x0b, 0x9b, 0xcc, 0xf8, 0x00, 0x30, + 0x10, 0x4a, 0x11, 0x4b, 0xd1, 0x7e, 0x19, 0x77, 0x11, 0x7f, 0x59, 0x77, + 0x51, 0x7f, 0x99, 0x77, 0x92, 0x7f, 0xda, 0x77, 0x0d, 0xb0, 0xbd, 0xe8, + 0xf0, 0x8f, 0xfe, 0xe7, 0xe8, 0xfe, 0x01, 0x00, 0xa4, 0xfd, 0x01, 0x00, + 0x84, 0xc2, 0x00, 0x00, 0x70, 0xc2, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x8c, 0xc2, 0x00, 0x00, 0xec, 0x35, 0x03, 0x00, 0xdd, 0xba, 0xad, 0xbb, + 0xe3, 0x20, 0xbb, 0xde, 0x74, 0xc2, 0x00, 0x00, 0xe8, 0x35, 0x03, 0x00, + 0xfc, 0x07, 0x02, 0x00, 0xec, 0xfe, 0x01, 0x00, 0xe4, 0xfe, 0x01, 0x00, + 0x80, 0xc2, 0x00, 0x00, 0x88, 0xc2, 0x00, 0x00, 0x90, 0xc2, 0x00, 0x00, + 0x70, 0x47, 0x00, 0x00, 0x2d, 0xe9, 0xf0, 0x4f, 0x91, 0xb0, 0xff, 0xf7, + 0x5d, 0xff, 0x6d, 0x4b, 0x1b, 0x68, 0x04, 0x3b, 0x01, 0x2b, 0x03, 0xd8, + 0x6b, 0x4b, 0x18, 0x68, 0xff, 0xf7, 0xf0, 0xff, 0xfb, 0xf7, 0x3e, 0xfa, + 0x00, 0x21, 0x04, 0x46, 0xe2, 0xf3, 0x72, 0xf3, 0x20, 0x46, 0x00, 0x21, + 0xe2, 0xf3, 0x28, 0xf3, 0x28, 0xb1, 0x03, 0x6a, 0x00, 0x2b, 0xbc, 0xbf, + 0x4f, 0xf0, 0x00, 0x43, 0x03, 0x62, 0x0e, 0xa9, 0x08, 0x22, 0xa0, 0x6b, + 0xd9, 0xf3, 0xba, 0xf4, 0x02, 0x46, 0x20, 0x46, 0xd4, 0xf8, 0x3c, 0xb0, + 0x0b, 0x92, 0xe4, 0xf7, 0x58, 0xf9, 0x82, 0x46, 0x20, 0x46, 0xe4, 0xf7, + 0x54, 0xf9, 0x81, 0x46, 0x20, 0x46, 0xe4, 0xf7, 0x50, 0xf9, 0x80, 0x46, + 0x20, 0x46, 0xe4, 0xf7, 0x27, 0xf9, 0x07, 0x46, 0x20, 0x46, 0xe4, 0xf7, + 0x23, 0xf9, 0x06, 0x46, 0x20, 0x46, 0xe4, 0xf7, 0x1f, 0xf9, 0x05, 0x46, + 0x20, 0x46, 0xe3, 0xf7, 0x2d, 0xff, 0x01, 0x46, 0x20, 0x46, 0x0c, 0x91, + 0xe3, 0xf7, 0x28, 0xff, 0x84, 0x46, 0x20, 0x46, 0xcd, 0xf8, 0x34, 0xc0, + 0xe3, 0xf7, 0x22, 0xff, 0x0b, 0x9a, 0x0c, 0x99, 0xdd, 0xf8, 0x34, 0xc0, + 0x02, 0x92, 0x08, 0xf5, 0x42, 0x48, 0x47, 0x4a, 0x05, 0xf5, 0x42, 0x45, + 0x00, 0xf5, 0x42, 0x40, 0x0a, 0xf5, 0x42, 0x4a, 0x09, 0xf5, 0x42, 0x49, + 0x08, 0xf5, 0xa8, 0x78, 0x07, 0xf5, 0x42, 0x47, 0x06, 0xf5, 0x42, 0x46, + 0x05, 0xf5, 0xa8, 0x75, 0x01, 0xf5, 0x42, 0x41, 0x0c, 0xf5, 0x42, 0x4c, + 0x00, 0xf5, 0xa8, 0x70, 0xb8, 0xfb, 0xf2, 0xf8, 0xb5, 0xfb, 0xf2, 0xf5, + 0x0c, 0xf5, 0xa8, 0x7c, 0xb0, 0xfb, 0xf2, 0xf0, 0x0a, 0xf5, 0xa8, 0x7a, + 0x09, 0xf5, 0xa8, 0x79, 0x07, 0xf5, 0xa8, 0x77, 0x06, 0xf5, 0xa8, 0x76, + 0x01, 0xf5, 0xa8, 0x71, 0xb1, 0xfb, 0xf2, 0xf1, 0xdf, 0xf8, 0xe8, 0xe0, + 0xba, 0xfb, 0xf2, 0xfa, 0x02, 0xfb, 0x18, 0x99, 0xb7, 0xfb, 0xf2, 0xf7, + 0x02, 0xfb, 0x15, 0x66, 0x02, 0xfb, 0x10, 0xc2, 0xcd, 0xf8, 0x04, 0xe0, + 0xdf, 0xf8, 0xd0, 0xe0, 0x2a, 0x4b, 0xb2, 0xfb, 0xfe, 0xf2, 0xb9, 0xfb, + 0xfe, 0xf9, 0xb6, 0xfb, 0xfe, 0xf6, 0x08, 0x91, 0x09, 0x92, 0x27, 0x49, + 0x27, 0x4a, 0x28, 0x48, 0x00, 0x93, 0xcd, 0xf8, 0x0c, 0xb0, 0xcd, 0xf8, + 0x10, 0xa0, 0xcd, 0xf8, 0x14, 0x90, 0x06, 0x97, 0x07, 0x96, 0xe6, 0xf7, + 0x7b, 0xfd, 0x23, 0x48, 0x40, 0xf6, 0x0d, 0x01, 0x44, 0xf2, 0xf4, 0x32, + 0xfb, 0xf7, 0x24, 0xf9, 0x38, 0xb1, 0x1f, 0x48, 0x40, 0xf6, 0x29, 0x01, + 0x44, 0xf2, 0xf4, 0x32, 0xfb, 0xf7, 0x1c, 0xf9, 0x20, 0xb9, 0x1c, 0x4a, + 0x1c, 0x4b, 0x1a, 0x4d, 0x1a, 0x60, 0x00, 0xe0, 0x00, 0x25, 0x20, 0x46, + 0xfd, 0xf7, 0xb8, 0xfd, 0x44, 0xf2, 0x18, 0x33, 0x4f, 0xf6, 0xff, 0x72, + 0x90, 0x42, 0x14, 0xbf, 0x02, 0x46, 0x1a, 0x46, 0x40, 0xf6, 0x12, 0x01, + 0x14, 0x48, 0xfb, 0xf7, 0x05, 0xf9, 0x13, 0x49, 0x00, 0x28, 0x18, 0xbf, + 0x00, 0x21, 0x4d, 0xb1, 0x41, 0xb1, 0x0f, 0x4b, 0x28, 0x46, 0x1b, 0x68, + 0x5b, 0x68, 0x98, 0x47, 0x2b, 0x69, 0x28, 0x46, 0x5b, 0x68, 0x98, 0x47, + 0x20, 0x46, 0x11, 0xb0, 0xbd, 0xe8, 0xf0, 0x8f, 0x90, 0xc2, 0x00, 0x00, + 0x8c, 0xc2, 0x00, 0x00, 0x40, 0x42, 0x0f, 0x00, 0xab, 0xff, 0x86, 0x00, + 0xaa, 0xfd, 0x01, 0x00, 0xaf, 0xfd, 0x01, 0x00, 0x90, 0xae, 0x02, 0x00, + 0xf0, 0xfe, 0x01, 0x00, 0x1c, 0xff, 0x01, 0x00, 0xf8, 0x26, 0x00, 0x00, + 0xe4, 0xfd, 0x01, 0x00, 0xbc, 0xba, 0x01, 0x00, 0xa0, 0x86, 0x01, 0x00, + 0x77, 0x6c, 0x25, 0x64, 0x3a, 0x20, 0x42, 0x72, 0x6f, 0x61, 0x64, 0x63, + 0x6f, 0x6d, 0x20, 0x42, 0x43, 0x4d, 0x25, 0x64, 0x20, 0x38, 0x30, 0x32, + 0x2e, 0x31, 0x31, 0x20, 0x57, 0x69, 0x72, 0x65, 0x6c, 0x65, 0x73, 0x73, + 0x20, 0x43, 0x6f, 0x6e, 0x74, 0x72, 0x6f, 0x6c, 0x6c, 0x65, 0x72, 0x20, + 0x25, 0x73, 0x0a, 0x00, 0x25, 0x73, 0x3a, 0x20, 0x42, 0x72, 0x6f, 0x61, + 0x64, 0x63, 0x6f, 0x6d, 0x20, 0x53, 0x44, 0x50, 0x43, 0x4d, 0x44, 0x20, + 0x43, 0x44, 0x43, 0x20, 0x64, 0x72, 0x69, 0x76, 0x65, 0x72, 0x0a, 0x00, + 0x73, 0x64, 0x70, 0x63, 0x6d, 0x64, 0x63, 0x64, 0x63, 0x25, 0x64, 0x00, + 0x72, 0x73, 0x73, 0x69, 0x73, 0x6d, 0x66, 0x32, 0x67, 0x3d, 0x25, 0x64, + 0x00, 0x78, 0x74, 0x61, 0x6c, 0x66, 0x72, 0x65, 0x71, 0x3d, 0x25, 0x64, + 0x00, 0x61, 0x61, 0x32, 0x67, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x62, + 0x77, 0x34, 0x30, 0x70, 0x6f, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x6c, + 0x65, 0x64, 0x62, 0x68, 0x25, 0x64, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, + 0x74, 0x73, 0x73, 0x69, 0x70, 0x6f, 0x73, 0x32, 0x67, 0x3d, 0x30, 0x78, + 0x25, 0x78, 0x00, 0x72, 0x73, 0x73, 0x69, 0x73, 0x61, 0x76, 0x32, 0x67, + 0x3d, 0x25, 0x64, 0x00, 0x6c, 0x65, 0x67, 0x6f, 0x66, 0x64, 0x6d, 0x34, + 0x30, 0x64, 0x75, 0x70, 0x70, 0x6f, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, + 0x70, 0x61, 0x31, 0x68, 0x69, 0x6d, 0x61, 0x78, 0x70, 0x77, 0x72, 0x3d, + 0x25, 0x64, 0x00, 0x6d, 0x61, 0x78, 0x70, 0x32, 0x67, 0x61, 0x30, 0x3d, + 0x30, 0x78, 0x25, 0x78, 0x00, 0x70, 0x61, 0x31, 0x69, 0x74, 0x73, 0x73, + 0x69, 0x74, 0x3d, 0x25, 0x64, 0x00, 0x6d, 0x61, 0x6e, 0x66, 0x69, 0x64, + 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x73, 0x75, 0x62, 0x76, 0x65, 0x6e, + 0x64, 0x69, 0x64, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x20, 0x04, 0xd0, + 0x02, 0x36, 0x43, 0xff, 0xff, 0x62, 0x6f, 0x61, 0x72, 0x64, 0x74, 0x79, + 0x70, 0x65, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x6d, 0x63, 0x73, 0x25, + 0x64, 0x67, 0x70, 0x6f, 0x25, 0x64, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, + 0x6d, 0x61, 0x6e, 0x66, 0x3d, 0x25, 0x73, 0x00, 0x6d, 0x61, 0x78, 0x70, + 0x35, 0x67, 0x6c, 0x61, 0x30, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x6d, + 0x61, 0x78, 0x70, 0x35, 0x67, 0x6c, 0x61, 0x31, 0x3d, 0x30, 0x78, 0x25, + 0x78, 0x00, 0x6f, 0x66, 0x64, 0x6d, 0x35, 0x67, 0x6c, 0x70, 0x6f, 0x3d, + 0x30, 0x78, 0x25, 0x78, 0x00, 0x72, 0x73, 0x73, 0x69, 0x73, 0x6d, 0x63, + 0x35, 0x67, 0x3d, 0x25, 0x64, 0x00, 0x62, 0x6f, 0x61, 0x72, 0x64, 0x66, + 0x6c, 0x61, 0x67, 0x73, 0x32, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x74, + 0x72, 0x69, 0x73, 0x6f, 0x32, 0x67, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, + 0x70, 0x64, 0x65, 0x74, 0x72, 0x61, 0x6e, 0x67, 0x65, 0x32, 0x67, 0x3d, + 0x30, 0x78, 0x25, 0x78, 0x00, 0x6d, 0x63, 0x73, 0x62, 0x77, 0x32, 0x30, + 0x35, 0x67, 0x6c, 0x70, 0x6f, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x00, + 0x00, 0x6d, 0x63, 0x73, 0x62, 0x77, 0x32, 0x30, 0x75, 0x6c, 0x35, 0x67, + 0x6c, 0x70, 0x6f, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x6d, 0x63, 0x73, + 0x62, 0x77, 0x34, 0x30, 0x35, 0x67, 0x6c, 0x70, 0x6f, 0x3d, 0x30, 0x78, + 0x25, 0x78, 0x00, 0x00, 0x00, 0x70, 0x61, 0x31, 0x6c, 0x6f, 0x6d, 0x61, + 0x78, 0x70, 0x77, 0x72, 0x3d, 0x25, 0x64, 0x00, 0x75, 0x73, 0x62, 0x65, + 0x70, 0x6e, 0x75, 0x6d, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x72, 0x78, + 0x70, 0x6f, 0x35, 0x67, 0x3d, 0x25, 0x64, 0x00, 0x6d, 0x63, 0x73, 0x33, + 0x32, 0x70, 0x6f, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x73, 0x75, 0x62, + 0x64, 0x65, 0x76, 0x69, 0x64, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x69, + 0x74, 0x74, 0x35, 0x67, 0x61, 0x30, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, + 0x69, 0x74, 0x74, 0x35, 0x67, 0x61, 0x31, 0x3d, 0x30, 0x78, 0x25, 0x78, + 0x00, 0x70, 0x61, 0x31, 0x6d, 0x61, 0x78, 0x70, 0x77, 0x72, 0x3d, 0x25, + 0x64, 0x00, 0x62, 0x6f, 0x61, 0x72, 0x64, 0x72, 0x65, 0x76, 0x3d, 0x30, + 0x78, 0x25, 0x78, 0x00, 0x6d, 0x63, 0x73, 0x62, 0x77, 0x32, 0x30, 0x32, + 0x67, 0x70, 0x6f, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x00, 0x00, 0x6d, + 0x63, 0x73, 0x62, 0x77, 0x32, 0x30, 0x75, 0x6c, 0x32, 0x67, 0x70, 0x6f, + 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x6d, 0x63, 0x73, 0x62, 0x77, 0x34, + 0x30, 0x32, 0x67, 0x70, 0x6f, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x00, + 0x00, 0x6d, 0x63, 0x73, 0x62, 0x77, 0x32, 0x30, 0x35, 0x67, 0x6d, 0x70, + 0x6f, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x00, 0x00, 0x6d, 0x63, 0x73, + 0x62, 0x77, 0x32, 0x30, 0x75, 0x6c, 0x35, 0x67, 0x6d, 0x70, 0x6f, 0x3d, + 0x30, 0x78, 0x25, 0x78, 0x00, 0x6d, 0x63, 0x73, 0x62, 0x77, 0x34, 0x30, + 0x35, 0x67, 0x6d, 0x70, 0x6f, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x00, + 0x00, 0x73, 0x72, 0x6f, 0x6d, 0x72, 0x65, 0x76, 0x3d, 0x25, 0x64, 0x00, + 0x77, 0x70, 0x73, 0x6c, 0x65, 0x64, 0x3d, 0x25, 0x64, 0x00, 0x70, 0x61, + 0x31, 0x6c, 0x6f, 0x62, 0x30, 0x3d, 0x25, 0x64, 0x00, 0x70, 0x61, 0x31, + 0x6c, 0x6f, 0x62, 0x31, 0x3d, 0x25, 0x64, 0x00, 0x70, 0x61, 0x31, 0x6c, + 0x6f, 0x62, 0x32, 0x3d, 0x25, 0x64, 0x00, 0x70, 0x61, 0x25, 0x64, 0x67, + 0x25, 0x63, 0x77, 0x25, 0x64, 0x61, 0x25, 0x64, 0x3d, 0x30, 0x78, 0x25, + 0x78, 0x00, 0x6d, 0x61, 0x78, 0x70, 0x32, 0x67, 0x61, 0x31, 0x3d, 0x30, + 0x78, 0x25, 0x78, 0x00, 0x70, 0x61, 0x30, 0x62, 0x30, 0x3d, 0x25, 0x64, + 0x00, 0x70, 0x61, 0x30, 0x62, 0x31, 0x3d, 0x25, 0x64, 0x00, 0x70, 0x61, + 0x30, 0x62, 0x32, 0x3d, 0x25, 0x64, 0x00, 0x72, 0x73, 0x73, 0x69, 0x73, + 0x6d, 0x63, 0x32, 0x67, 0x3d, 0x25, 0x64, 0x00, 0x74, 0x72, 0x69, 0x35, + 0x67, 0x68, 0x3d, 0x25, 0x64, 0x00, 0x75, 0x73, 0x62, 0x66, 0x73, 0x3d, + 0x25, 0x64, 0x00, 0x63, 0x63, 0x6b, 0x70, 0x6f, 0x3d, 0x30, 0x78, 0x25, + 0x78, 0x00, 0x74, 0x72, 0x69, 0x35, 0x67, 0x6c, 0x3d, 0x25, 0x64, 0x00, + 0x6f, 0x66, 0x64, 0x6d, 0x35, 0x67, 0x68, 0x70, 0x6f, 0x3d, 0x30, 0x78, + 0x25, 0x78, 0x00, 0x61, 0x67, 0x25, 0x64, 0x3d, 0x30, 0x78, 0x25, 0x78, + 0x00, 0x65, 0x78, 0x74, 0x70, 0x61, 0x67, 0x61, 0x69, 0x6e, 0x35, 0x67, + 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x70, 0x72, 0x6f, 0x64, 0x75, 0x63, + 0x74, 0x6e, 0x61, 0x6d, 0x65, 0x3d, 0x25, 0x73, 0x00, 0x63, 0x64, 0x64, + 0x70, 0x6f, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x6c, 0x65, 0x67, 0x6f, + 0x66, 0x64, 0x6d, 0x62, 0x77, 0x32, 0x30, 0x35, 0x67, 0x6c, 0x70, 0x6f, + 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x00, 0x00, 0x6c, 0x65, 0x67, 0x6f, + 0x66, 0x64, 0x6d, 0x62, 0x77, 0x32, 0x30, 0x75, 0x6c, 0x35, 0x67, 0x6c, + 0x70, 0x6f, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x6c, 0x65, 0x67, 0x6f, + 0x66, 0x64, 0x6d, 0x62, 0x77, 0x32, 0x30, 0x35, 0x67, 0x6d, 0x70, 0x6f, + 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x00, 0x00, 0x6c, 0x65, 0x67, 0x6f, + 0x66, 0x64, 0x6d, 0x62, 0x77, 0x32, 0x30, 0x75, 0x6c, 0x35, 0x67, 0x6d, + 0x70, 0x6f, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x6c, 0x65, 0x67, 0x6f, + 0x66, 0x64, 0x6d, 0x62, 0x77, 0x32, 0x30, 0x35, 0x67, 0x68, 0x70, 0x6f, + 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x00, 0x00, 0x6c, 0x65, 0x67, 0x6f, + 0x66, 0x64, 0x6d, 0x62, 0x77, 0x32, 0x30, 0x75, 0x6c, 0x35, 0x67, 0x68, + 0x70, 0x6f, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x72, 0x78, 0x70, 0x6f, + 0x32, 0x67, 0x3d, 0x25, 0x64, 0x00, 0x72, 0x78, 0x63, 0x68, 0x61, 0x69, + 0x6e, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x69, 0x74, 0x74, 0x32, 0x67, + 0x61, 0x30, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x69, 0x74, 0x74, 0x32, + 0x67, 0x61, 0x31, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x61, 0x6e, 0x74, + 0x73, 0x77, 0x69, 0x74, 0x63, 0x68, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, + 0x74, 0x78, 0x63, 0x68, 0x61, 0x69, 0x6e, 0x3d, 0x30, 0x78, 0x25, 0x78, + 0x00, 0x70, 0x72, 0x6f, 0x64, 0x69, 0x64, 0x3d, 0x30, 0x78, 0x25, 0x78, + 0x00, 0x70, 0x61, 0x30, 0x69, 0x74, 0x73, 0x73, 0x69, 0x74, 0x3d, 0x25, + 0x64, 0x00, 0x63, 0x63, 0x6b, 0x64, 0x69, 0x67, 0x66, 0x69, 0x6c, 0x74, + 0x74, 0x79, 0x70, 0x65, 0x3d, 0x25, 0x64, 0x00, 0x63, 0x68, 0x69, 0x70, + 0x72, 0x65, 0x76, 0x3d, 0x25, 0x64, 0x00, 0x6f, 0x66, 0x64, 0x6d, 0x35, + 0x67, 0x70, 0x6f, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x6c, 0x65, 0x64, + 0x64, 0x63, 0x3d, 0x30, 0x78, 0x25, 0x30, 0x34, 0x78, 0x00, 0x6d, 0x61, + 0x78, 0x70, 0x35, 0x67, 0x68, 0x61, 0x30, 0x3d, 0x30, 0x78, 0x25, 0x78, + 0x00, 0x6d, 0x61, 0x78, 0x70, 0x35, 0x67, 0x68, 0x61, 0x31, 0x3d, 0x30, + 0x78, 0x25, 0x78, 0x00, 0x70, 0x61, 0x31, 0x62, 0x30, 0x3d, 0x25, 0x64, + 0x00, 0x70, 0x61, 0x31, 0x62, 0x31, 0x3d, 0x25, 0x64, 0x00, 0x70, 0x61, + 0x31, 0x62, 0x32, 0x3d, 0x25, 0x64, 0x00, 0x62, 0x77, 0x64, 0x75, 0x70, + 0x70, 0x6f, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x6d, 0x61, 0x78, 0x70, + 0x35, 0x67, 0x61, 0x30, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x6d, 0x61, + 0x78, 0x70, 0x35, 0x67, 0x61, 0x31, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, + 0x61, 0x6e, 0x74, 0x73, 0x77, 0x63, 0x74, 0x6c, 0x35, 0x67, 0x3d, 0x30, + 0x78, 0x25, 0x78, 0x00, 0x6d, 0x63, 0x73, 0x25, 0x64, 0x67, 0x25, 0x63, + 0x70, 0x6f, 0x25, 0x64, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x6d, 0x63, + 0x73, 0x62, 0x77, 0x32, 0x30, 0x35, 0x67, 0x68, 0x70, 0x6f, 0x3d, 0x30, + 0x78, 0x25, 0x78, 0x00, 0x00, 0x00, 0x6d, 0x63, 0x73, 0x62, 0x77, 0x32, + 0x30, 0x75, 0x6c, 0x35, 0x67, 0x68, 0x70, 0x6f, 0x3d, 0x30, 0x78, 0x25, + 0x78, 0x00, 0x6d, 0x63, 0x73, 0x62, 0x77, 0x34, 0x30, 0x35, 0x67, 0x68, + 0x70, 0x6f, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x00, 0x00, 0x74, 0x72, + 0x69, 0x35, 0x67, 0x3d, 0x25, 0x64, 0x00, 0x6f, 0x70, 0x6f, 0x3d, 0x25, + 0x64, 0x00, 0x76, 0x65, 0x6e, 0x64, 0x69, 0x64, 0x3d, 0x30, 0x78, 0x25, + 0x78, 0x00, 0x6c, 0x65, 0x67, 0x6f, 0x66, 0x64, 0x6d, 0x62, 0x77, 0x32, + 0x30, 0x32, 0x67, 0x70, 0x6f, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x00, + 0x6c, 0x65, 0x67, 0x6f, 0x66, 0x64, 0x6d, 0x62, 0x77, 0x32, 0x30, 0x75, + 0x6c, 0x32, 0x67, 0x70, 0x6f, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x70, 0x61, + 0x30, 0x6d, 0x61, 0x78, 0x70, 0x77, 0x72, 0x3d, 0x25, 0x64, 0x00, 0x70, + 0x61, 0x31, 0x68, 0x69, 0x62, 0x30, 0x3d, 0x25, 0x64, 0x00, 0x70, 0x61, + 0x31, 0x68, 0x69, 0x62, 0x31, 0x3d, 0x25, 0x64, 0x00, 0x70, 0x61, 0x31, + 0x68, 0x69, 0x62, 0x32, 0x3d, 0x25, 0x64, 0x00, 0x63, 0x75, 0x73, 0x74, + 0x6f, 0x6d, 0x76, 0x61, 0x72, 0x25, 0x64, 0x3d, 0x30, 0x78, 0x25, 0x78, + 0x00, 0x72, 0x65, 0x67, 0x72, 0x65, 0x76, 0x3d, 0x30, 0x78, 0x25, 0x78, + 0x00, 0x62, 0x6f, 0x61, 0x72, 0x64, 0x66, 0x6c, 0x61, 0x67, 0x73, 0x3d, + 0x30, 0x78, 0x25, 0x78, 0x00, 0x62, 0x78, 0x61, 0x32, 0x67, 0x3d, 0x25, + 0x64, 0x00, 0x6f, 0x65, 0x6d, 0x3d, 0x25, 0x30, 0x32, 0x78, 0x25, 0x30, + 0x32, 0x78, 0x25, 0x30, 0x32, 0x78, 0x25, 0x30, 0x32, 0x78, 0x25, 0x30, + 0x32, 0x78, 0x25, 0x30, 0x32, 0x78, 0x25, 0x30, 0x32, 0x78, 0x25, 0x30, + 0x32, 0x78, 0x00, 0x64, 0x65, 0x76, 0x69, 0x64, 0x3d, 0x30, 0x78, 0x25, + 0x78, 0x00, 0x70, 0x61, 0x25, 0x64, 0x67, 0x77, 0x25, 0x64, 0x61, 0x25, + 0x64, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x72, 0x73, 0x73, 0x69, 0x73, + 0x6d, 0x66, 0x35, 0x67, 0x3d, 0x25, 0x64, 0x00, 0x6f, 0x66, 0x64, 0x6d, + 0x32, 0x67, 0x70, 0x6f, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x61, 0x61, + 0x35, 0x67, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x77, 0x70, 0x73, 0x67, + 0x70, 0x69, 0x6f, 0x3d, 0x25, 0x64, 0x00, 0x62, 0x78, 0x61, 0x35, 0x67, + 0x3d, 0x25, 0x64, 0x00, 0x74, 0x73, 0x73, 0x69, 0x70, 0x6f, 0x73, 0x35, + 0x67, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x61, 0x6e, 0x74, 0x73, 0x77, + 0x63, 0x74, 0x6c, 0x32, 0x67, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x72, + 0x73, 0x73, 0x69, 0x73, 0x61, 0x76, 0x35, 0x67, 0x3d, 0x25, 0x64, 0x00, + 0x6f, 0x66, 0x64, 0x6d, 0x70, 0x6f, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, + 0x74, 0x72, 0x69, 0x32, 0x67, 0x3d, 0x25, 0x64, 0x00, 0x73, 0x74, 0x62, + 0x63, 0x70, 0x6f, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x63, 0x63, 0x6f, + 0x64, 0x65, 0x3d, 0x30, 0x78, 0x30, 0x00, 0x6d, 0x61, 0x63, 0x61, 0x64, + 0x64, 0x72, 0x3d, 0x25, 0x73, 0x00, 0x63, 0x63, 0x6f, 0x64, 0x65, 0x3d, + 0x25, 0x63, 0x25, 0x63, 0x00, 0x63, 0x63, 0x3d, 0x25, 0x64, 0x00, 0x63, + 0x63, 0x6b, 0x32, 0x67, 0x70, 0x6f, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, + 0x63, 0x63, 0x74, 0x6c, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x72, 0x65, + 0x67, 0x77, 0x69, 0x6e, 0x64, 0x6f, 0x77, 0x73, 0x7a, 0x3d, 0x25, 0x64, + 0x00, 0x65, 0x78, 0x74, 0x70, 0x61, 0x67, 0x61, 0x69, 0x6e, 0x32, 0x67, + 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x62, 0x6f, 0x61, 0x72, 0x64, 0x6e, + 0x75, 0x6d, 0x3d, 0x25, 0x64, 0x00, 0x74, 0x72, 0x69, 0x73, 0x6f, 0x35, + 0x67, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x63, 0x63, 0x6b, 0x62, 0x77, + 0x32, 0x30, 0x32, 0x67, 0x70, 0x6f, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, + 0x00, 0x00, 0x63, 0x63, 0x6b, 0x62, 0x77, 0x32, 0x30, 0x75, 0x6c, 0x32, + 0x67, 0x70, 0x6f, 0x3d, 0x30, 0x78, 0x25, 0x78, 0x00, 0x70, 0x64, 0x65, + 0x74, 0x72, 0x61, 0x6e, 0x67, 0x65, 0x35, 0x67, 0x3d, 0x30, 0x78, 0x25, + 0x78, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0xff, 0x00, 0x00, 0x00, + 0x0c, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, + 0xff, 0x00, 0x00, 0x00, 0x0c, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x08, 0x00, 0xff, 0x00, 0x00, 0x00, 0x0e, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x01, 0x00, 0x04, 0x00, + 0x03, 0x00, 0x00, 0x00, 0x01, 0x00, 0x02, 0x00, 0x0a, 0x00, 0x00, 0x00, + 0x02, 0x00, 0x60, 0x00, 0xdc, 0x05, 0x00, 0x00, 0x08, 0x07, 0x17, 0x00, + 0x74, 0x78, 0x70, 0x77, 0x72, 0x62, 0x63, 0x6b, 0x6f, 0x66, 0x00, 0x32, + 0x67, 0x5f, 0x63, 0x67, 0x61, 0x00, 0x72, 0x73, 0x73, 0x69, 0x63, 0x6f, + 0x72, 0x72, 0x6e, 0x6f, 0x72, 0x6d, 0x00, 0x74, 0x73, 0x73, 0x69, 0x6c, + 0x69, 0x6d, 0x75, 0x63, 0x6f, 0x64, 0x00, 0x74, 0x65, 0x6d, 0x70, 0x73, + 0x5f, 0x68, 0x79, 0x73, 0x74, 0x65, 0x72, 0x65, 0x73, 0x69, 0x73, 0x00, + 0x72, 0x73, 0x73, 0x69, 0x63, 0x6f, 0x72, 0x72, 0x61, 0x74, 0x74, 0x65, + 0x6e, 0x00, 0x35, 0x67, 0x5f, 0x63, 0x67, 0x61, 0x00, 0x74, 0x65, 0x6d, + 0x70, 0x74, 0x68, 0x72, 0x65, 0x73, 0x68, 0x00, 0x69, 0x6e, 0x74, 0x65, + 0x72, 0x66, 0x65, 0x72, 0x65, 0x6e, 0x63, 0x65, 0x00, 0x6d, 0x63, 0x73, + 0x32, 0x67, 0x70, 0x6f, 0x31, 0x00, 0x6f, 0x70, 0x65, 0x6e, 0x6c, 0x70, + 0x67, 0x61, 0x69, 0x6e, 0x69, 0x64, 0x78, 0x62, 0x25, 0x64, 0x00, 0x74, + 0x73, 0x73, 0x69, 0x6f, 0x66, 0x66, 0x73, 0x65, 0x74, 0x6d, 0x69, 0x6e, + 0x35, 0x67, 0x6c, 0x00, 0x74, 0x73, 0x73, 0x69, 0x6f, 0x66, 0x66, 0x73, + 0x65, 0x74, 0x6d, 0x69, 0x6e, 0x35, 0x67, 0x6d, 0x00, 0x74, 0x65, 0x6d, + 0x70, 0x73, 0x65, 0x6e, 0x73, 0x65, 0x5f, 0x73, 0x6c, 0x6f, 0x70, 0x65, + 0x00, 0x6d, 0x65, 0x61, 0x73, 0x70, 0x6f, 0x77, 0x65, 0x72, 0x00, 0x72, + 0x73, 0x73, 0x69, 0x73, 0x6d, 0x66, 0x32, 0x67, 0x00, 0x70, 0x6c, 0x6c, + 0x64, 0x6f, 0x75, 0x62, 0x6c, 0x65, 0x72, 0x5f, 0x6d, 0x6f, 0x64, 0x65, + 0x32, 0x67, 0x00, 0x70, 0x61, 0x72, 0x66, 0x70, 0x73, 0x00, 0x65, 0x64, + 0x6f, 0x6e, 0x74, 0x68, 0x64, 0x00, 0x72, 0x66, 0x72, 0x65, 0x67, 0x30, + 0x33, 0x33, 0x5f, 0x63, 0x63, 0x6b, 0x00, 0x6f, 0x70, 0x65, 0x6e, 0x6c, + 0x70, 0x67, 0x61, 0x69, 0x6e, 0x69, 0x64, 0x78, 0x61, 0x31, 0x34, 0x30, + 0x00, 0x65, 0x78, 0x74, 0x70, 0x61, 0x67, 0x61, 0x69, 0x6e, 0x35, 0x67, + 0x00, 0x65, 0x78, 0x74, 0x70, 0x61, 0x67, 0x61, 0x69, 0x6e, 0x32, 0x67, + 0x00, 0x6f, 0x70, 0x65, 0x6e, 0x6c, 0x70, 0x67, 0x61, 0x69, 0x6e, 0x69, + 0x64, 0x78, 0x61, 0x31, 0x34, 0x39, 0x00, 0x74, 0x78, 0x69, 0x71, 0x6c, + 0x6f, 0x70, 0x61, 0x67, 0x32, 0x67, 0x00, 0x6e, 0x6f, 0x69, 0x73, 0x65, + 0x5f, 0x63, 0x61, 0x6c, 0x5f, 0x72, 0x65, 0x66, 0x5f, 0x35, 0x67, 0x00, + 0x70, 0x6d, 0x61, 0x78, 0x00, 0x6f, 0x70, 0x65, 0x6e, 0x6c, 0x70, 0x67, + 0x61, 0x69, 0x6e, 0x69, 0x64, 0x78, 0x61, 0x31, 0x36, 0x35, 0x00, 0x70, + 0x61, 0x63, 0x61, 0x6c, 0x69, 0x64, 0x78, 0x35, 0x67, 0x68, 0x69, 0x31, + 0x00, 0x70, 0x61, 0x63, 0x61, 0x6c, 0x61, 0x74, 0x68, 0x32, 0x67, 0x31, + 0x00, 0x64, 0x61, 0x63, 0x67, 0x63, 0x32, 0x67, 0x00, 0x70, 0x6d, 0x69, + 0x6e, 0x00, 0x70, 0x61, 0x63, 0x61, 0x6c, 0x70, 0x75, 0x6c, 0x73, 0x65, + 0x77, 0x69, 0x64, 0x74, 0x68, 0x00, 0x76, 0x62, 0x61, 0x74, 0x5f, 0x6d, + 0x75, 0x6c, 0x74, 0x00, 0x6d, 0x63, 0x73, 0x32, 0x67, 0x70, 0x6f, 0x30, + 0x00, 0x74, 0x78, 0x67, 0x61, 0x69, 0x6e, 0x74, 0x62, 0x6c, 0x00, 0x6f, + 0x70, 0x65, 0x6e, 0x6c, 0x70, 0x74, 0x65, 0x6d, 0x70, 0x63, 0x6f, 0x72, + 0x72, 0x00, 0x74, 0x73, 0x73, 0x69, 0x6d, 0x61, 0x78, 0x6e, 0x70, 0x74, + 0x00, 0x6e, 0x6f, 0x69, 0x73, 0x65, 0x5f, 0x63, 0x61, 0x6c, 0x5f, 0x65, + 0x6e, 0x61, 0x62, 0x6c, 0x65, 0x5f, 0x35, 0x67, 0x00, 0x74, 0x78, 0x69, + 0x71, 0x6c, 0x6f, 0x74, 0x66, 0x00, 0x6f, 0x70, 0x65, 0x6e, 0x6c, 0x70, + 0x70, 0x77, 0x72, 0x6c, 0x69, 0x6d, 0x00, 0x65, 0x64, 0x6f, 0x66, 0x66, + 0x74, 0x68, 0x64, 0x00, 0x6e, 0x6f, 0x69, 0x73, 0x65, 0x5f, 0x63, 0x61, + 0x6c, 0x5f, 0x64, 0x62, 0x67, 0x00, 0x6f, 0x70, 0x65, 0x6e, 0x6c, 0x70, + 0x67, 0x61, 0x69, 0x6e, 0x69, 0x64, 0x78, 0x61, 0x31, 0x35, 0x33, 0x00, + 0x70, 0x61, 0x63, 0x61, 0x6c, 0x69, 0x64, 0x78, 0x35, 0x67, 0x68, 0x69, + 0x00, 0x6f, 0x70, 0x65, 0x6e, 0x6c, 0x70, 0x67, 0x61, 0x69, 0x6e, 0x69, + 0x64, 0x78, 0x61, 0x31, 0x35, 0x37, 0x00, 0x6e, 0x6f, 0x69, 0x73, 0x65, + 0x5f, 0x63, 0x61, 0x6c, 0x5f, 0x75, 0x70, 0x64, 0x61, 0x74, 0x65, 0x00, + 0x70, 0x61, 0x67, 0x63, 0x32, 0x67, 0x00, 0x73, 0x77, 0x63, 0x74, 0x72, + 0x6c, 0x6d, 0x61, 0x70, 0x5f, 0x32, 0x67, 0x00, 0x70, 0x61, 0x63, 0x61, + 0x6c, 0x61, 0x6c, 0x69, 0x6d, 0x00, 0x69, 0x71, 0x6c, 0x6f, 0x63, 0x61, + 0x6c, 0x70, 0x77, 0x72, 0x32, 0x67, 0x00, 0x70, 0x61, 0x63, 0x61, 0x6c, + 0x70, 0x77, 0x72, 0x32, 0x67, 0x31, 0x00, 0x74, 0x78, 0x67, 0x61, 0x69, + 0x6e, 0x74, 0x62, 0x6c, 0x35, 0x67, 0x00, 0x70, 0x61, 0x63, 0x61, 0x6c, + 0x61, 0x74, 0x68, 0x35, 0x67, 0x68, 0x69, 0x00, 0x70, 0x61, 0x63, 0x61, + 0x6c, 0x61, 0x74, 0x68, 0x35, 0x67, 0x68, 0x69, 0x31, 0x00, 0x76, 0x62, + 0x61, 0x74, 0x73, 0x6d, 0x63, 0x00, 0x61, 0x64, 0x63, 0x72, 0x66, 0x73, + 0x65, 0x71, 0x32, 0x67, 0x00, 0x76, 0x62, 0x61, 0x74, 0x73, 0x6d, 0x66, + 0x00, 0x72, 0x78, 0x67, 0x61, 0x69, 0x6e, 0x62, 0x61, 0x63, 0x6b, 0x6f, + 0x66, 0x66, 0x76, 0x61, 0x6c, 0x00, 0x72, 0x78, 0x67, 0x61, 0x69, 0x6e, + 0x74, 0x65, 0x6d, 0x70, 0x63, 0x6f, 0x72, 0x72, 0x35, 0x67, 0x68, 0x00, + 0x6e, 0x6f, 0x69, 0x73, 0x65, 0x5f, 0x63, 0x61, 0x6c, 0x5f, 0x72, 0x65, + 0x66, 0x5f, 0x32, 0x67, 0x00, 0x76, 0x62, 0x61, 0x74, 0x5f, 0x71, 0x00, + 0x6e, 0x6f, 0x69, 0x73, 0x65, 0x5f, 0x63, 0x61, 0x6c, 0x5f, 0x70, 0x6f, + 0x5f, 0x62, 0x69, 0x61, 0x73, 0x5f, 0x32, 0x67, 0x00, 0x72, 0x66, 0x72, + 0x65, 0x67, 0x30, 0x38, 0x38, 0x00, 0x6f, 0x70, 0x65, 0x6e, 0x6c, 0x70, + 0x67, 0x61, 0x69, 0x6e, 0x69, 0x64, 0x78, 0x61, 0x31, 0x36, 0x31, 0x00, + 0x70, 0x61, 0x63, 0x61, 0x6c, 0x70, 0x77, 0x72, 0x32, 0x67, 0x00, 0x64, + 0x79, 0x6e, 0x70, 0x77, 0x72, 0x6c, 0x69, 0x6d, 0x65, 0x6e, 0x00, 0x74, + 0x65, 0x6d, 0x70, 0x73, 0x61, 0x76, 0x00, 0x74, 0x65, 0x6d, 0x70, 0x63, + 0x6f, 0x72, 0x72, 0x78, 0x00, 0x64, 0x61, 0x63, 0x72, 0x61, 0x74, 0x65, + 0x32, 0x67, 0x00, 0x70, 0x61, 0x30, 0x62, 0x32, 0x5f, 0x6c, 0x6f, 0x00, + 0x74, 0x78, 0x69, 0x71, 0x6c, 0x6f, 0x70, 0x61, 0x70, 0x75, 0x32, 0x67, + 0x00, 0x74, 0x65, 0x6d, 0x70, 0x73, 0x65, 0x6e, 0x73, 0x65, 0x5f, 0x6f, + 0x70, 0x74, 0x69, 0x6f, 0x6e, 0x00, 0x70, 0x61, 0x63, 0x61, 0x6c, 0x61, + 0x74, 0x68, 0x35, 0x67, 0x31, 0x00, 0x70, 0x61, 0x63, 0x61, 0x6c, 0x61, + 0x74, 0x68, 0x35, 0x67, 0x6c, 0x6f, 0x31, 0x00, 0x70, 0x61, 0x63, 0x61, + 0x6c, 0x69, 0x64, 0x78, 0x32, 0x67, 0x31, 0x00, 0x74, 0x78, 0x61, 0x6c, + 0x70, 0x66, 0x62, 0x79, 0x70, 0x32, 0x67, 0x00, 0x70, 0x61, 0x63, 0x61, + 0x6c, 0x69, 0x64, 0x78, 0x32, 0x67, 0x00, 0x75, 0x6e, 0x6d, 0x6f, 0x64, + 0x5f, 0x72, 0x73, 0x73, 0x69, 0x5f, 0x6f, 0x66, 0x66, 0x73, 0x65, 0x74, + 0x00, 0x6f, 0x70, 0x65, 0x6e, 0x6c, 0x70, 0x76, 0x6f, 0x6c, 0x74, 0x63, + 0x6f, 0x72, 0x72, 0x00, 0x70, 0x61, 0x63, 0x61, 0x6c, 0x69, 0x64, 0x78, + 0x35, 0x67, 0x31, 0x00, 0x72, 0x78, 0x67, 0x61, 0x69, 0x6e, 0x74, 0x62, + 0x6c, 0x31, 0x30, 0x30, 0x00, 0x6e, 0x6f, 0x69, 0x73, 0x65, 0x5f, 0x63, + 0x61, 0x6c, 0x5f, 0x6e, 0x66, 0x5f, 0x73, 0x75, 0x62, 0x73, 0x74, 0x72, + 0x61, 0x63, 0x74, 0x5f, 0x76, 0x61, 0x6c, 0x00, 0x74, 0x73, 0x73, 0x69, + 0x74, 0x78, 0x64, 0x65, 0x6c, 0x61, 0x79, 0x00, 0x63, 0x63, 0x6b, 0x32, + 0x67, 0x70, 0x6f, 0x00, 0x63, 0x63, 0x6b, 0x50, 0x77, 0x72, 0x49, 0x64, + 0x78, 0x43, 0x6f, 0x72, 0x72, 0x00, 0x63, 0x63, 0x6b, 0x64, 0x69, 0x67, + 0x66, 0x69, 0x6c, 0x74, 0x74, 0x79, 0x70, 0x65, 0x00, 0x6c, 0x6f, 0x63, + 0x63, 0x6d, 0x6f, 0x64, 0x65, 0x31, 0x00, 0x6c, 0x6f, 0x69, 0x64, 0x61, + 0x63, 0x6d, 0x6f, 0x64, 0x65, 0x35, 0x67, 0x00, 0x70, 0x61, 0x63, 0x61, + 0x6c, 0x61, 0x74, 0x68, 0x35, 0x67, 0x00, 0x72, 0x73, 0x73, 0x69, 0x73, + 0x61, 0x76, 0x32, 0x67, 0x00, 0x70, 0x61, 0x30, 0x62, 0x31, 0x5f, 0x6c, + 0x6f, 0x00, 0x6d, 0x61, 0x78, 0x70, 0x32, 0x67, 0x61, 0x30, 0x00, 0x72, + 0x78, 0x67, 0x61, 0x69, 0x6e, 0x74, 0x65, 0x6d, 0x70, 0x63, 0x6f, 0x72, + 0x72, 0x35, 0x67, 0x6d, 0x00, 0x70, 0x61, 0x63, 0x61, 0x6c, 0x61, 0x74, + 0x68, 0x32, 0x67, 0x00, 0x70, 0x6c, 0x6c, 0x64, 0x6f, 0x75, 0x62, 0x6c, + 0x65, 0x72, 0x5f, 0x65, 0x6e, 0x61, 0x62, 0x6c, 0x65, 0x32, 0x67, 0x00, + 0x70, 0x61, 0x30, 0x62, 0x30, 0x00, 0x70, 0x61, 0x30, 0x62, 0x31, 0x00, + 0x70, 0x61, 0x30, 0x62, 0x32, 0x00, 0x6f, 0x70, 0x65, 0x6e, 0x6c, 0x70, + 0x67, 0x61, 0x69, 0x6e, 0x69, 0x64, 0x78, 0x61, 0x33, 0x36, 0x00, 0x70, + 0x61, 0x63, 0x61, 0x6c, 0x66, 0x63, 0x64, 0x31, 0x00, 0x6e, 0x6f, 0x69, + 0x73, 0x65, 0x5f, 0x63, 0x61, 0x6c, 0x5f, 0x61, 0x64, 0x6a, 0x5f, 0x35, + 0x67, 0x00, 0x69, 0x71, 0x6c, 0x6f, 0x63, 0x61, 0x6c, 0x69, 0x64, 0x78, + 0x32, 0x67, 0x6f, 0x66, 0x66, 0x73, 0x00, 0x69, 0x71, 0x6c, 0x6f, 0x73, + 0x74, 0x31, 0x6f, 0x66, 0x66, 0x32, 0x67, 0x00, 0x6f, 0x70, 0x65, 0x6e, + 0x6c, 0x70, 0x67, 0x61, 0x69, 0x6e, 0x69, 0x64, 0x78, 0x61, 0x31, 0x30, + 0x30, 0x00, 0x72, 0x61, 0x77, 0x74, 0x65, 0x6d, 0x70, 0x73, 0x65, 0x6e, + 0x73, 0x65, 0x00, 0x6f, 0x70, 0x65, 0x6e, 0x6c, 0x70, 0x67, 0x61, 0x69, + 0x6e, 0x69, 0x64, 0x78, 0x61, 0x31, 0x30, 0x34, 0x00, 0x69, 0x71, 0x6c, + 0x6f, 0x63, 0x61, 0x6c, 0x69, 0x64, 0x78, 0x32, 0x67, 0x00, 0x6f, 0x70, + 0x65, 0x6e, 0x6c, 0x70, 0x70, 0x77, 0x72, 0x63, 0x74, 0x72, 0x6c, 0x00, + 0x6f, 0x70, 0x65, 0x6e, 0x6c, 0x70, 0x67, 0x61, 0x69, 0x6e, 0x69, 0x64, + 0x78, 0x61, 0x31, 0x30, 0x38, 0x00, 0x72, 0x66, 0x72, 0x65, 0x67, 0x30, + 0x33, 0x33, 0x00, 0x74, 0x78, 0x5f, 0x74, 0x6f, 0x6e, 0x65, 0x5f, 0x70, + 0x6f, 0x77, 0x65, 0x72, 0x5f, 0x69, 0x6e, 0x64, 0x65, 0x78, 0x00, 0x6f, + 0x70, 0x65, 0x6e, 0x6c, 0x70, 0x72, 0x65, 0x66, 0x70, 0x77, 0x72, 0x00, + 0x70, 0x61, 0x30, 0x62, 0x30, 0x5f, 0x6c, 0x6f, 0x00, 0x6e, 0x6f, 0x69, + 0x73, 0x65, 0x5f, 0x63, 0x61, 0x6c, 0x5f, 0x70, 0x6f, 0x5f, 0x32, 0x67, + 0x00, 0x72, 0x78, 0x67, 0x61, 0x69, 0x6e, 0x74, 0x65, 0x6d, 0x70, 0x63, + 0x6f, 0x72, 0x72, 0x35, 0x67, 0x6c, 0x00, 0x70, 0x61, 0x63, 0x61, 0x6c, + 0x69, 0x64, 0x78, 0x35, 0x67, 0x31, 0x74, 0x68, 0x00, 0x70, 0x61, 0x67, + 0x63, 0x35, 0x67, 0x00, 0x70, 0x61, 0x63, 0x61, 0x6c, 0x69, 0x64, 0x78, + 0x35, 0x67, 0x6c, 0x6f, 0x31, 0x74, 0x68, 0x00, 0x73, 0x77, 0x63, 0x74, + 0x72, 0x6c, 0x6d, 0x61, 0x70, 0x5f, 0x35, 0x67, 0x00, 0x74, 0x73, 0x73, + 0x69, 0x6f, 0x66, 0x66, 0x73, 0x65, 0x74, 0x6d, 0x69, 0x6e, 0x00, 0x73, + 0x70, 0x75, 0x72, 0x61, 0x76, 0x6f, 0x69, 0x64, 0x5f, 0x65, 0x6e, 0x61, + 0x62, 0x6c, 0x65, 0x32, 0x67, 0x00, 0x6e, 0x6f, 0x69, 0x73, 0x65, 0x5f, + 0x63, 0x61, 0x6c, 0x5f, 0x70, 0x6f, 0x5f, 0x62, 0x69, 0x61, 0x73, 0x5f, + 0x35, 0x67, 0x00, 0x6f, 0x70, 0x65, 0x6e, 0x6c, 0x70, 0x67, 0x61, 0x69, + 0x6e, 0x69, 0x64, 0x78, 0x61, 0x34, 0x30, 0x00, 0x6c, 0x6f, 0x67, 0x65, + 0x6e, 0x5f, 0x6d, 0x6f, 0x64, 0x65, 0x00, 0x6f, 0x70, 0x65, 0x6e, 0x6c, + 0x70, 0x67, 0x61, 0x69, 0x6e, 0x69, 0x64, 0x78, 0x61, 0x34, 0x34, 0x00, + 0x6e, 0x6f, 0x69, 0x73, 0x65, 0x5f, 0x63, 0x61, 0x6c, 0x5f, 0x68, 0x69, + 0x67, 0x68, 0x5f, 0x67, 0x61, 0x69, 0x6e, 0x00, 0x72, 0x66, 0x72, 0x65, + 0x67, 0x30, 0x33, 0x38, 0x00, 0x6e, 0x6f, 0x69, 0x73, 0x65, 0x5f, 0x63, + 0x61, 0x6c, 0x5f, 0x61, 0x64, 0x6a, 0x5f, 0x32, 0x67, 0x00, 0x70, 0x61, + 0x63, 0x61, 0x6c, 0x69, 0x64, 0x78, 0x35, 0x67, 0x6c, 0x6f, 0x31, 0x00, + 0x6d, 0x65, 0x61, 0x73, 0x70, 0x6f, 0x77, 0x65, 0x72, 0x31, 0x00, 0x6d, + 0x65, 0x61, 0x73, 0x70, 0x6f, 0x77, 0x65, 0x72, 0x32, 0x00, 0x6f, 0x70, + 0x65, 0x6e, 0x6c, 0x70, 0x67, 0x61, 0x69, 0x6e, 0x69, 0x64, 0x78, 0x61, + 0x31, 0x31, 0x36, 0x00, 0x62, 0x70, 0x68, 0x79, 0x73, 0x63, 0x61, 0x6c, + 0x65, 0x00, 0x72, 0x73, 0x73, 0x69, 0x73, 0x6d, 0x63, 0x32, 0x67, 0x00, + 0x72, 0x78, 0x67, 0x61, 0x69, 0x6e, 0x74, 0x65, 0x6d, 0x70, 0x63, 0x6f, + 0x72, 0x72, 0x32, 0x67, 0x00, 0x6f, 0x66, 0x64, 0x6d, 0x61, 0x6e, 0x61, + 0x6c, 0x6f, 0x67, 0x66, 0x69, 0x6c, 0x74, 0x62, 0x77, 0x32, 0x67, 0x00, + 0x61, 0x61, 0x32, 0x67, 0x00, 0x74, 0x65, 0x6d, 0x70, 0x5f, 0x6d, 0x75, + 0x6c, 0x74, 0x00, 0x6f, 0x66, 0x64, 0x6d, 0x32, 0x67, 0x70, 0x6f, 0x00, + 0x76, 0x62, 0x61, 0x74, 0x73, 0x61, 0x76, 0x00, 0x70, 0x61, 0x63, 0x61, + 0x6c, 0x61, 0x74, 0x68, 0x35, 0x67, 0x6c, 0x6f, 0x00, 0x70, 0x61, 0x63, + 0x61, 0x6c, 0x69, 0x64, 0x78, 0x32, 0x67, 0x31, 0x74, 0x68, 0x00, 0x63, + 0x63, 0x6b, 0x50, 0x77, 0x72, 0x4f, 0x66, 0x66, 0x73, 0x65, 0x74, 0x00, + 0x74, 0x78, 0x70, 0x77, 0x72, 0x69, 0x6e, 0x64, 0x65, 0x78, 0x00, 0x69, + 0x71, 0x6c, 0x6f, 0x63, 0x61, 0x6c, 0x69, 0x64, 0x78, 0x35, 0x67, 0x6f, + 0x66, 0x66, 0x73, 0x00, 0x70, 0x61, 0x63, 0x61, 0x6c, 0x69, 0x64, 0x78, + 0x35, 0x67, 0x6c, 0x6f, 0x00, 0x67, 0x6d, 0x67, 0x63, 0x32, 0x67, 0x00, + 0x70, 0x61, 0x63, 0x61, 0x6c, 0x69, 0x64, 0x78, 0x35, 0x67, 0x68, 0x69, + 0x31, 0x74, 0x68, 0x00, 0x72, 0x78, 0x70, 0x6f, 0x32, 0x67, 0x00, 0x6e, + 0x6f, 0x69, 0x73, 0x65, 0x5f, 0x63, 0x61, 0x6c, 0x5f, 0x65, 0x6e, 0x61, + 0x62, 0x6c, 0x65, 0x5f, 0x32, 0x67, 0x00, 0x6f, 0x70, 0x65, 0x6e, 0x6c, + 0x70, 0x67, 0x61, 0x69, 0x6e, 0x69, 0x64, 0x78, 0x61, 0x35, 0x32, 0x00, + 0x6f, 0x70, 0x65, 0x6e, 0x6c, 0x70, 0x67, 0x61, 0x69, 0x6e, 0x69, 0x64, + 0x78, 0x61, 0x35, 0x36, 0x00, 0x6f, 0x70, 0x65, 0x6e, 0x6c, 0x70, 0x67, + 0x61, 0x69, 0x6e, 0x69, 0x64, 0x78, 0x61, 0x31, 0x31, 0x32, 0x00, 0x74, + 0x72, 0x69, 0x73, 0x6f, 0x32, 0x67, 0x00, 0x76, 0x62, 0x61, 0x74, 0x5f, + 0x61, 0x64, 0x64, 0x00, 0x6f, 0x70, 0x65, 0x6e, 0x6c, 0x70, 0x67, 0x61, + 0x69, 0x6e, 0x69, 0x64, 0x78, 0x61, 0x31, 0x32, 0x30, 0x00, 0x6f, 0x70, + 0x65, 0x6e, 0x6c, 0x70, 0x67, 0x61, 0x69, 0x6e, 0x69, 0x64, 0x78, 0x61, + 0x31, 0x32, 0x34, 0x00, 0x6f, 0x70, 0x65, 0x6e, 0x6c, 0x70, 0x67, 0x61, + 0x69, 0x6e, 0x69, 0x64, 0x78, 0x61, 0x31, 0x32, 0x38, 0x00, 0x74, 0x72, + 0x69, 0x64, 0x78, 0x32, 0x67, 0x00, 0x6f, 0x66, 0x64, 0x6d, 0x64, 0x69, + 0x67, 0x66, 0x69, 0x6c, 0x74, 0x74, 0x79, 0x70, 0x65, 0x32, 0x67, 0x00, + 0x6f, 0x70, 0x65, 0x6e, 0x6c, 0x70, 0x67, 0x61, 0x69, 0x6e, 0x69, 0x64, + 0x78, 0x61, 0x34, 0x38, 0x00, 0x74, 0x65, 0x6d, 0x70, 0x5f, 0x61, 0x64, + 0x64, 0x00, 0x72, 0x78, 0x67, 0x61, 0x69, 0x6e, 0x74, 0x62, 0x6c, 0x77, + 0x6c, 0x62, 0x67, 0x61, 0x00, 0x69, 0x6e, 0x69, 0x74, 0x78, 0x69, 0x64, + 0x78, 0x32, 0x67, 0x00, 0x68, 0x77, 0x5f, 0x69, 0x71, 0x63, 0x61, 0x6c, + 0x5f, 0x65, 0x6e, 0x00, 0x69, 0x71, 0x63, 0x61, 0x6c, 0x5f, 0x73, 0x77, + 0x70, 0x5f, 0x64, 0x69, 0x73, 0x00, 0x6d, 0x75, 0x78, 0x5f, 0x67, 0x61, + 0x69, 0x6e, 0x5f, 0x74, 0x61, 0x62, 0x6c, 0x65, 0x00, 0x74, 0x73, 0x73, + 0x69, 0x6f, 0x66, 0x66, 0x73, 0x65, 0x74, 0x6d, 0x61, 0x78, 0x35, 0x67, + 0x68, 0x00, 0x74, 0x65, 0x6d, 0x70, 0x5f, 0x71, 0x00, 0x74, 0x73, 0x73, + 0x69, 0x6f, 0x66, 0x66, 0x73, 0x65, 0x74, 0x6d, 0x61, 0x78, 0x35, 0x67, + 0x6c, 0x00, 0x74, 0x73, 0x73, 0x69, 0x6f, 0x66, 0x66, 0x73, 0x65, 0x74, + 0x6d, 0x61, 0x78, 0x35, 0x67, 0x6d, 0x00, 0x74, 0x65, 0x6d, 0x70, 0x73, + 0x6d, 0x63, 0x00, 0x74, 0x65, 0x6d, 0x70, 0x73, 0x6d, 0x66, 0x00, 0x74, + 0x73, 0x73, 0x69, 0x6f, 0x66, 0x66, 0x73, 0x65, 0x74, 0x6d, 0x61, 0x78, + 0x00, 0x70, 0x61, 0x63, 0x61, 0x6c, 0x69, 0x64, 0x78, 0x35, 0x67, 0x00, + 0x6f, 0x70, 0x65, 0x6e, 0x6c, 0x70, 0x67, 0x61, 0x69, 0x6e, 0x69, 0x64, + 0x78, 0x61, 0x36, 0x30, 0x00, 0x74, 0x78, 0x61, 0x6c, 0x70, 0x66, 0x62, + 0x79, 0x70, 0x32, 0x67, 0x5f, 0x63, 0x63, 0x6b, 0x00, 0x6f, 0x70, 0x65, + 0x6e, 0x6c, 0x70, 0x67, 0x61, 0x69, 0x6e, 0x69, 0x64, 0x78, 0x61, 0x36, + 0x34, 0x00, 0x66, 0x72, 0x65, 0x71, 0x6f, 0x66, 0x66, 0x73, 0x65, 0x74, + 0x5f, 0x63, 0x6f, 0x72, 0x72, 0x00, 0x6f, 0x66, 0x64, 0x6d, 0x64, 0x69, + 0x67, 0x66, 0x69, 0x6c, 0x74, 0x74, 0x79, 0x70, 0x65, 0x35, 0x67, 0x00, + 0x6f, 0x70, 0x65, 0x6e, 0x6c, 0x70, 0x67, 0x61, 0x69, 0x6e, 0x69, 0x64, + 0x78, 0x61, 0x31, 0x33, 0x32, 0x00, 0x6f, 0x70, 0x65, 0x6e, 0x6c, 0x70, + 0x67, 0x61, 0x69, 0x6e, 0x69, 0x64, 0x78, 0x61, 0x31, 0x33, 0x36, 0x00, + 0x6f, 0x66, 0x64, 0x6d, 0x64, 0x69, 0x67, 0x66, 0x69, 0x6c, 0x74, 0x74, + 0x79, 0x70, 0x65, 0x00, 0x78, 0x74, 0x61, 0x6c, 0x6d, 0x6f, 0x64, 0x65, + 0x00, 0x74, 0x73, 0x73, 0x69, 0x74, 0x69, 0x6d, 0x65, 0x00, 0x6e, 0x6f, + 0x69, 0x73, 0x65, 0x5f, 0x63, 0x61, 0x6c, 0x5f, 0x70, 0x6f, 0x5f, 0x35, + 0x67, 0x00, 0x74, 0x73, 0x73, 0x69, 0x6f, 0x66, 0x66, 0x73, 0x65, 0x74, + 0x6d, 0x69, 0x6e, 0x35, 0x67, 0x68, 0x00, 0x09, 0x0c, 0x12, 0x18, 0x18, + 0x18, 0x09, 0x0c, 0x12, 0x18, 0x18, 0x18, 0x00, 0x00, 0x0c, 0x07, 0x6f, + 0x7a, 0x06, 0x0c, 0x0f, 0x7b, 0x7e, 0x01, 0x05, 0x08, 0x0b, 0x0e, 0x11, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x06, 0x09, + 0x0c, 0x0f, 0x12, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x03, 0x06, 0x09, 0x0c, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0xf8, 0xa6, 0x02, 0x00, 0x60, 0x00, 0x00, 0x00, + 0x12, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x00, 0x00, 0x00, + 0x2e, 0xa9, 0x02, 0x00, 0x26, 0x00, 0x00, 0x00, 0x0e, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0xc0, 0xa9, 0x02, 0x00, + 0x98, 0x00, 0x00, 0x00, 0x0d, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x20, 0x00, 0x00, 0x00, 0x6b, 0x9f, 0x02, 0x00, 0x44, 0x00, 0x00, 0x00, + 0x11, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, + 0x80, 0xae, 0x02, 0x00, 0x10, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x07, 0x00, 0x1f, 0x00, + 0x48, 0x07, 0x00, 0x1f, 0x00, 0x46, 0x07, 0x00, 0x1f, 0x00, 0x44, 0x07, + 0x00, 0x1e, 0x00, 0x43, 0x07, 0x00, 0x1d, 0x00, 0x44, 0x07, 0x00, 0x1c, + 0x00, 0x44, 0x07, 0x00, 0x1b, 0x00, 0x45, 0x07, 0x00, 0x1a, 0x00, 0x46, + 0x07, 0x00, 0x19, 0x00, 0x46, 0x07, 0x00, 0x18, 0x00, 0x47, 0x07, 0x00, + 0x17, 0x00, 0x48, 0x07, 0x00, 0x17, 0x00, 0x46, 0x07, 0x00, 0x16, 0x00, + 0x47, 0x07, 0x00, 0x15, 0x00, 0x48, 0x07, 0x00, 0x15, 0x00, 0x46, 0x07, + 0x00, 0x15, 0x00, 0x44, 0x07, 0x00, 0x15, 0x00, 0x42, 0x07, 0x00, 0x15, + 0x00, 0x40, 0x07, 0x00, 0x15, 0x00, 0x3f, 0x07, 0x00, 0x14, 0x00, 0x40, + 0x07, 0x00, 0x13, 0x00, 0x41, 0x07, 0x00, 0x13, 0x00, 0x40, 0x07, 0x00, + 0x12, 0x00, 0x41, 0x07, 0x00, 0x12, 0x00, 0x40, 0x07, 0x00, 0x11, 0x00, + 0x41, 0x07, 0x00, 0x11, 0x00, 0x40, 0x07, 0x00, 0x10, 0x00, 0x41, 0x07, + 0x00, 0x10, 0x00, 0x40, 0x07, 0x00, 0x10, 0x00, 0x3e, 0x07, 0x00, 0x10, + 0x00, 0x3c, 0x07, 0x00, 0x10, 0x00, 0x3a, 0x07, 0x00, 0x0f, 0x00, 0x3d, + 0x07, 0x00, 0x0f, 0x00, 0x3b, 0x07, 0x00, 0x0e, 0x00, 0x3d, 0x07, 0x00, + 0x0e, 0x00, 0x3c, 0x07, 0x00, 0x0e, 0x00, 0x3a, 0x07, 0x00, 0x0d, 0x00, + 0x3c, 0x07, 0x00, 0x0d, 0x00, 0x3b, 0x07, 0x00, 0x0c, 0x00, 0x3e, 0x07, + 0x00, 0x0c, 0x00, 0x3c, 0x07, 0x00, 0x0c, 0x00, 0x3a, 0x07, 0x00, 0x0b, + 0x00, 0x3e, 0x07, 0x00, 0x0b, 0x00, 0x3c, 0x07, 0x00, 0x0b, 0x00, 0x3b, + 0x07, 0x00, 0x0b, 0x00, 0x39, 0x07, 0x00, 0x0a, 0x00, 0x3d, 0x07, 0x00, + 0x0a, 0x00, 0x3b, 0x07, 0x00, 0x0a, 0x00, 0x39, 0x07, 0x00, 0x09, 0x00, + 0x3e, 0x07, 0x00, 0x09, 0x00, 0x3c, 0x07, 0x00, 0x09, 0x00, 0x3a, 0x07, + 0x00, 0x09, 0x00, 0x39, 0x07, 0x00, 0x08, 0x00, 0x3e, 0x07, 0x00, 0x08, + 0x00, 0x3c, 0x07, 0x00, 0x08, 0x00, 0x3a, 0x07, 0x00, 0x08, 0x00, 0x39, + 0x07, 0x00, 0x08, 0x00, 0x37, 0x07, 0x00, 0x07, 0x00, 0x3d, 0x07, 0x00, + 0x07, 0x00, 0x3c, 0x07, 0x00, 0x07, 0x00, 0x3a, 0x07, 0x00, 0x07, 0x00, + 0x38, 0x07, 0x00, 0x07, 0x00, 0x37, 0x07, 0x00, 0x06, 0x00, 0x3e, 0x07, + 0x00, 0x06, 0x00, 0x3c, 0x07, 0x00, 0x06, 0x00, 0x3a, 0x07, 0x00, 0x06, + 0x00, 0x39, 0x07, 0x00, 0x06, 0x00, 0x37, 0x07, 0x00, 0x06, 0x00, 0x36, + 0x07, 0x00, 0x06, 0x00, 0x34, 0x07, 0x00, 0x05, 0x00, 0x3d, 0x07, 0x00, + 0x05, 0x00, 0x3b, 0x07, 0x00, 0x05, 0x00, 0x39, 0x07, 0x00, 0x05, 0x00, + 0x38, 0x07, 0x00, 0x05, 0x00, 0x36, 0x07, 0x00, 0x05, 0x00, 0x35, 0x07, + 0x00, 0x05, 0x00, 0x33, 0x07, 0x00, 0x04, 0x00, 0x3e, 0x07, 0x00, 0x04, + 0x00, 0x3c, 0x07, 0x00, 0x04, 0x00, 0x3a, 0x07, 0x00, 0x04, 0x00, 0x39, + 0x07, 0x00, 0x04, 0x00, 0x37, 0x07, 0x00, 0x04, 0x00, 0x36, 0x07, 0x00, + 0x04, 0x00, 0x34, 0x07, 0x00, 0x04, 0x00, 0x33, 0x07, 0x00, 0x04, 0x00, + 0x31, 0x07, 0x00, 0x04, 0x00, 0x30, 0x07, 0x00, 0x04, 0x00, 0x2e, 0x07, + 0x00, 0x03, 0x00, 0x3c, 0x07, 0x00, 0x03, 0x00, 0x3a, 0x07, 0x00, 0x03, + 0x00, 0x39, 0x07, 0x00, 0x03, 0x00, 0x37, 0x07, 0x00, 0x03, 0x00, 0x36, + 0x07, 0x00, 0x03, 0x00, 0x34, 0x07, 0x00, 0x03, 0x00, 0x33, 0x07, 0x00, + 0x03, 0x00, 0x31, 0x07, 0x00, 0x03, 0x00, 0x30, 0x07, 0x00, 0x03, 0x00, + 0x2e, 0x07, 0x00, 0x03, 0x00, 0x2d, 0x07, 0x00, 0x03, 0x00, 0x2c, 0x07, + 0x00, 0x03, 0x00, 0x2b, 0x07, 0x00, 0x03, 0x00, 0x29, 0x07, 0x00, 0x02, + 0x00, 0x3d, 0x07, 0x00, 0x02, 0x00, 0x3b, 0x07, 0x00, 0x02, 0x00, 0x39, + 0x07, 0x00, 0x02, 0x00, 0x38, 0x07, 0x00, 0x02, 0x00, 0x36, 0x07, 0x00, + 0x02, 0x00, 0x35, 0x07, 0x00, 0x02, 0x00, 0x33, 0x07, 0x00, 0x02, 0x00, + 0x32, 0x07, 0x00, 0x02, 0x00, 0x30, 0x07, 0x00, 0x02, 0x00, 0x2f, 0x07, + 0x00, 0x02, 0x00, 0x2e, 0x07, 0x00, 0x02, 0x00, 0x2c, 0x07, 0x00, 0x02, + 0x00, 0x2b, 0x07, 0x00, 0x02, 0x00, 0x2a, 0x07, 0x00, 0x02, 0x00, 0x29, + 0x07, 0x00, 0x02, 0x00, 0x27, 0x07, 0x00, 0x02, 0x00, 0x26, 0x07, 0x00, + 0x02, 0x00, 0x25, 0x07, 0x00, 0x02, 0x00, 0x24, 0x07, 0x00, 0x02, 0x00, + 0x23, 0x07, 0x00, 0x02, 0x00, 0x22, 0x07, 0x00, 0x02, 0x00, 0x21, 0x07, + 0x00, 0x02, 0x00, 0x20, 0x07, 0x00, 0x01, 0x00, 0x3f, 0x07, 0x00, 0x01, + 0x00, 0x3d, 0x07, 0x00, 0x01, 0x00, 0x3b, 0x07, 0x00, 0x01, 0x00, 0x39, + 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, + 0xc0, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x05, 0x00, 0x00, 0x00, + 0x02, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, + 0x4a, 0x00, 0x00, 0x00, 0x8a, 0x00, 0x00, 0x00, 0xca, 0x00, 0x00, 0x00, + 0x0a, 0x01, 0x00, 0x00, 0x4a, 0x01, 0x00, 0x00, 0x8a, 0x01, 0x00, 0x00, + 0x8a, 0x05, 0x00, 0x00, 0x8a, 0x09, 0x00, 0x00, 0x8a, 0x0d, 0x00, 0x00, + 0x8a, 0x11, 0x00, 0x00, 0x8a, 0x51, 0x00, 0x00, 0x8a, 0x91, 0x00, 0x00, + 0x8a, 0xd1, 0x00, 0x00, 0x8a, 0x11, 0x01, 0x00, 0x8a, 0x51, 0x01, 0x00, + 0x8a, 0x91, 0x01, 0x00, 0x89, 0x00, 0x00, 0x00, 0x8a, 0xd1, 0x01, 0x00, + 0x8a, 0x11, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x94, 0xa2, 0x02, 0x00, 0x60, 0x00, 0x00, 0x00, 0x12, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x20, 0x00, 0x00, 0x00, 0xe2, 0xa8, 0x02, 0x00, + 0x26, 0x00, 0x00, 0x00, 0x0e, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x10, 0x00, 0x00, 0x00, 0x20, 0xac, 0x02, 0x00, 0x98, 0x00, 0x00, 0x00, + 0x0d, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x00, 0x00, 0x00, + 0x7a, 0xa9, 0x02, 0x00, 0x44, 0x00, 0x00, 0x00, 0x11, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x80, 0xae, 0x02, 0x00, + 0x10, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x08, 0x00, 0x00, 0x00, 0x03, 0x00, 0x13, 0x00, 0x41, 0x03, 0x00, 0x13, + 0x00, 0x40, 0x03, 0x00, 0x12, 0x00, 0x41, 0x03, 0x00, 0x12, 0x00, 0x40, + 0x03, 0x00, 0x11, 0x00, 0x41, 0x03, 0x00, 0x11, 0x00, 0x40, 0x03, 0x00, + 0x10, 0x00, 0x41, 0x03, 0x00, 0x10, 0x00, 0x40, 0x03, 0x00, 0x10, 0x00, + 0x3e, 0x03, 0x00, 0x10, 0x00, 0x3c, 0x03, 0x00, 0x10, 0x00, 0x3a, 0x03, + 0x00, 0x0f, 0x00, 0x3d, 0x03, 0x00, 0x0f, 0x00, 0x3b, 0x03, 0x00, 0x0e, + 0x00, 0x3d, 0x03, 0x00, 0x0e, 0x00, 0x3c, 0x03, 0x00, 0x0e, 0x00, 0x3a, + 0x03, 0x00, 0x0d, 0x00, 0x3c, 0x03, 0x00, 0x0d, 0x00, 0x3b, 0x03, 0x00, + 0x0c, 0x00, 0x3e, 0x03, 0x00, 0x0c, 0x00, 0x3c, 0x03, 0x00, 0x0c, 0x00, + 0x3a, 0x03, 0x00, 0x0b, 0x00, 0x3e, 0x03, 0x00, 0x0b, 0x00, 0x3c, 0x03, + 0x00, 0x0b, 0x00, 0x3b, 0x03, 0x00, 0x0b, 0x00, 0x39, 0x03, 0x00, 0x0a, + 0x00, 0x3d, 0x03, 0x00, 0x0a, 0x00, 0x3b, 0x03, 0x00, 0x0a, 0x00, 0x39, + 0x03, 0x00, 0x09, 0x00, 0x3e, 0x03, 0x00, 0x09, 0x00, 0x3c, 0x03, 0x00, + 0x09, 0x00, 0x3a, 0x03, 0x00, 0x09, 0x00, 0x39, 0x03, 0x00, 0x08, 0x00, + 0x3e, 0x03, 0x00, 0x08, 0x00, 0x3c, 0x03, 0x00, 0x08, 0x00, 0x3a, 0x03, + 0x00, 0x08, 0x00, 0x39, 0x03, 0x00, 0x08, 0x00, 0x37, 0x03, 0x00, 0x07, + 0x00, 0x3d, 0x03, 0x00, 0x07, 0x00, 0x3c, 0x03, 0x00, 0x07, 0x00, 0x3a, + 0x03, 0x00, 0x07, 0x00, 0x38, 0x03, 0x00, 0x07, 0x00, 0x37, 0x03, 0x00, + 0x06, 0x00, 0x3e, 0x03, 0x00, 0x06, 0x00, 0x3c, 0x03, 0x00, 0x06, 0x00, + 0x3a, 0x03, 0x00, 0x06, 0x00, 0x39, 0x03, 0x00, 0x06, 0x00, 0x37, 0x03, + 0x00, 0x06, 0x00, 0x36, 0x03, 0x00, 0x06, 0x00, 0x34, 0x03, 0x00, 0x05, + 0x00, 0x3d, 0x03, 0x00, 0x05, 0x00, 0x3b, 0x03, 0x00, 0x05, 0x00, 0x39, + 0x03, 0x00, 0x05, 0x00, 0x38, 0x03, 0x00, 0x05, 0x00, 0x36, 0x03, 0x00, + 0x05, 0x00, 0x35, 0x03, 0x00, 0x05, 0x00, 0x33, 0x03, 0x00, 0x04, 0x00, + 0x3e, 0x03, 0x00, 0x04, 0x00, 0x3c, 0x03, 0x00, 0x04, 0x00, 0x3a, 0x03, + 0x00, 0x04, 0x00, 0x39, 0x03, 0x00, 0x04, 0x00, 0x37, 0x03, 0x00, 0x04, + 0x00, 0x36, 0x03, 0x00, 0x04, 0x00, 0x34, 0x03, 0x00, 0x04, 0x00, 0x33, + 0x03, 0x00, 0x04, 0x00, 0x31, 0x03, 0x00, 0x04, 0x00, 0x30, 0x03, 0x00, + 0x04, 0x00, 0x2e, 0x03, 0x00, 0x03, 0x00, 0x3c, 0x03, 0x00, 0x03, 0x00, + 0x3a, 0x03, 0x00, 0x03, 0x00, 0x39, 0x03, 0x00, 0x03, 0x00, 0x37, 0x03, + 0x00, 0x03, 0x00, 0x36, 0x03, 0x00, 0x03, 0x00, 0x34, 0x03, 0x00, 0x03, + 0x00, 0x33, 0x03, 0x00, 0x03, 0x00, 0x31, 0x03, 0x00, 0x03, 0x00, 0x30, + 0x03, 0x00, 0x03, 0x00, 0x2e, 0x03, 0x00, 0x03, 0x00, 0x2d, 0x03, 0x00, + 0x03, 0x00, 0x2c, 0x03, 0x00, 0x03, 0x00, 0x2b, 0x03, 0x00, 0x03, 0x00, + 0x29, 0x03, 0x00, 0x02, 0x00, 0x3d, 0x03, 0x00, 0x02, 0x00, 0x3b, 0x03, + 0x00, 0x02, 0x00, 0x39, 0x03, 0x00, 0x02, 0x00, 0x38, 0x03, 0x00, 0x02, + 0x00, 0x36, 0x03, 0x00, 0x02, 0x00, 0x35, 0x03, 0x00, 0x02, 0x00, 0x33, + 0x03, 0x00, 0x02, 0x00, 0x32, 0x03, 0x00, 0x02, 0x00, 0x30, 0x03, 0x00, + 0x02, 0x00, 0x2f, 0x03, 0x00, 0x02, 0x00, 0x2e, 0x03, 0x00, 0x02, 0x00, + 0x2c, 0x03, 0x00, 0x02, 0x00, 0x2b, 0x03, 0x00, 0x02, 0x00, 0x2a, 0x03, + 0x00, 0x02, 0x00, 0x29, 0x03, 0x00, 0x02, 0x00, 0x27, 0x03, 0x00, 0x02, + 0x00, 0x26, 0x03, 0x00, 0x02, 0x00, 0x25, 0x03, 0x00, 0x02, 0x00, 0x24, + 0x03, 0x00, 0x02, 0x00, 0x23, 0x03, 0x00, 0x02, 0x00, 0x22, 0x03, 0x00, + 0x02, 0x00, 0x21, 0x03, 0x00, 0x02, 0x00, 0x20, 0x03, 0x00, 0x01, 0x00, + 0x3f, 0x03, 0x00, 0x01, 0x00, 0x3d, 0x03, 0x00, 0x01, 0x00, 0x3b, 0x03, + 0x00, 0x01, 0x00, 0x39, 0x03, 0x00, 0x01, 0x00, 0x38, 0x03, 0x00, 0x01, + 0x00, 0x36, 0x03, 0x00, 0x01, 0x00, 0x35, 0x03, 0x00, 0x01, 0x00, 0x33, + 0x03, 0x00, 0x01, 0x00, 0x32, 0x03, 0x00, 0x01, 0x00, 0x30, 0x03, 0x00, + 0x01, 0x00, 0x2f, 0x03, 0x00, 0x01, 0x00, 0x2e, 0x03, 0x00, 0x01, 0x00, + 0x2c, 0x03, 0x00, 0x01, 0x00, 0x2b, 0x03, 0x00, 0x01, 0x00, 0x2a, 0x03, + 0x00, 0x01, 0x00, 0x29, 0x03, 0x00, 0x01, 0x00, 0x27, 0x03, 0x00, 0x01, + 0x00, 0x26, 0x03, 0x00, 0x01, 0x00, 0x25, 0x03, 0x00, 0x01, 0x00, 0x24, + 0x03, 0x00, 0x01, 0x00, 0x23, 0x03, 0x00, 0x01, 0x00, 0x22, 0x03, 0x00, + 0x01, 0x00, 0x21, 0x03, 0x00, 0x01, 0x00, 0x20, 0x00, 0x00, 0x00, 0x00, + 0x04, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, + 0xc0, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x05, 0x00, 0x00, 0x00, + 0x45, 0x00, 0x00, 0x00, 0x85, 0x00, 0x00, 0x00, 0xc5, 0x00, 0x00, 0x00, + 0x05, 0x01, 0x00, 0x00, 0x45, 0x01, 0x00, 0x00, 0x85, 0x01, 0x00, 0x00, + 0x85, 0x05, 0x00, 0x00, 0x85, 0x09, 0x00, 0x00, 0x85, 0x0d, 0x00, 0x00, + 0x89, 0x09, 0x00, 0x00, 0x89, 0x0d, 0x00, 0x00, 0x89, 0x11, 0x00, 0x00, + 0x89, 0x51, 0x00, 0x00, 0x89, 0x91, 0x00, 0x00, 0x89, 0xd1, 0x00, 0x00, + 0x89, 0x11, 0x01, 0x00, 0x85, 0x4d, 0x00, 0x00, 0x85, 0x8d, 0x00, 0x00, + 0x85, 0xcd, 0x00, 0x00, 0x89, 0x51, 0x01, 0x00, 0x89, 0x91, 0x01, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0x00, 0x10, 0x00, + 0x39, 0x07, 0x00, 0x10, 0x00, 0x38, 0x07, 0x00, 0x10, 0x00, 0x36, 0x07, + 0x00, 0x10, 0x00, 0x34, 0x07, 0x00, 0x10, 0x00, 0x33, 0x07, 0x00, 0x10, + 0x00, 0x31, 0x07, 0x00, 0x10, 0x00, 0x30, 0x07, 0x00, 0x10, 0x00, 0x2f, + 0x07, 0x00, 0x10, 0x00, 0x2d, 0x07, 0x00, 0x10, 0x00, 0x2c, 0x07, 0x00, + 0x10, 0x00, 0x2b, 0x07, 0x00, 0x10, 0x00, 0x2a, 0x07, 0x00, 0x10, 0x00, + 0x28, 0x07, 0x00, 0x10, 0x00, 0x27, 0x07, 0x00, 0x10, 0x00, 0x26, 0x07, + 0x00, 0x10, 0x00, 0x25, 0x07, 0x00, 0x10, 0x00, 0x24, 0x07, 0x00, 0x10, + 0x00, 0x23, 0x07, 0x00, 0x10, 0x00, 0x22, 0x07, 0x00, 0x10, 0x00, 0x21, + 0x07, 0x00, 0x10, 0x00, 0x20, 0x00, 0x80, 0x00, 0x80, 0x00, 0x80, 0x00, + 0x80, 0x00, 0x80, 0x00, 0x80, 0x00, 0x80, 0x00, 0x80, 0x00, 0x80, 0x00, + 0x81, 0x00, 0x82, 0x00, 0x83, 0x00, 0x84, 0x00, 0x85, 0x00, 0x04, 0x01, + 0x05, 0x01, 0x80, 0x00, 0x80, 0x00, 0x80, 0x00, 0x80, 0x00, 0x80, 0x00, + 0x80, 0x00, 0x80, 0x00, 0x81, 0x00, 0x82, 0x00, 0x83, 0x00, 0x84, 0x00, + 0x85, 0x00, 0x04, 0x01, 0x05, 0x01, 0x06, 0x01, 0x07, 0x01, 0x19, 0x01, + 0x87, 0x01, 0x88, 0x01, 0x89, 0x01, 0x8a, 0x01, 0x8b, 0x01, 0x00, 0x04, + 0x00, 0x04, 0x00, 0x04, 0x00, 0x04, 0x00, 0x04, 0x00, 0x04, 0x00, 0x04, + 0x00, 0x04, 0x00, 0x04, 0x00, 0x04, 0x00, 0x04, 0x01, 0x04, 0x80, 0x04, + 0x82, 0x04, 0x83, 0x04, 0x84, 0x04, 0x00, 0x04, 0x00, 0x04, 0x00, 0x04, + 0x00, 0x04, 0x00, 0x04, 0x00, 0x04, 0x00, 0x04, 0x00, 0x04, 0x00, 0x04, + 0x01, 0x04, 0x80, 0x04, 0x82, 0x04, 0x83, 0x04, 0x84, 0x04, 0x85, 0x04, + 0x86, 0x04, 0x05, 0x05, 0x06, 0x05, 0x07, 0x05, 0x08, 0x05, 0x09, 0x05, + 0x0a, 0x05, 0x09, 0x0c, 0x12, 0x18, 0x18, 0x18, 0x09, 0x0c, 0x12, 0x18, + 0x18, 0x18, 0x00, 0x00, 0x0c, 0x07, 0x6f, 0x7a, 0x06, 0x0c, 0x0f, 0x7b, + 0x7e, 0x01, 0x05, 0x08, 0x0b, 0x0e, 0x11, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x03, 0x06, 0x09, 0x0c, 0x0f, 0x12, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x06, 0x09, 0x0c, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, 0x40, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x48, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, + 0x48, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x30, 0x48, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x40, 0x48, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x50, + 0x48, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x60, 0x48, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x50, 0x50, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x60, + 0x50, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x50, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x80, 0x50, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x90, + 0x50, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xa0, 0x50, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xb0, 0x50, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xc0, + 0x50, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xd0, 0x50, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xe0, 0x50, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xf0, + 0x50, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xe0, 0x58, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x59, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, + 0x59, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x59, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x30, 0x59, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, + 0x59, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x50, 0x59, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x60, 0x59, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x48, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x20, 0x48, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x30, + 0x48, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x48, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x50, 0x48, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x60, + 0x48, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x50, 0x50, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x60, 0x50, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, + 0x50, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x50, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x90, 0x50, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xa0, + 0x50, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xb0, 0x50, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xc0, 0x50, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xd0, + 0x50, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xe0, 0x50, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xf0, 0x50, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, + 0x51, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x51, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x90, 0x51, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, + 0x59, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x30, 0x59, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x40, 0x59, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x50, + 0x59, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x60, 0x59, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xa0, 0x59, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xb0, + 0x59, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, + 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x08, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x30, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, + 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x50, 0x08, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x40, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x50, + 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x60, 0x10, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x70, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, + 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x18, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x80, 0x18, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x90, + 0x18, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xa0, 0x18, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xb0, 0x18, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xc0, + 0x18, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xd0, 0x18, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xe0, 0x18, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xf0, + 0x18, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x19, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x10, 0x19, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, + 0x19, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x30, 0x19, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x40, 0x19, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x50, + 0x19, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x60, 0x19, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x70, 0x19, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, + 0x19, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x10, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, + 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x30, 0x08, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x40, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x50, + 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x10, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x50, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x60, + 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x10, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x90, 0x11, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, + 0x18, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x18, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x90, 0x18, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xa0, + 0x18, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xb0, 0x18, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xc0, 0x18, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xd0, + 0x18, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xe0, 0x18, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xf0, 0x18, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x19, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, 0x19, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x20, 0x19, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x30, + 0x19, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x19, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x50, 0x19, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x60, + 0x19, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x19, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x80, 0x19, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xa0, + 0x19, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xb0, 0x19, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x5f, 0x36, 0x29, 0x1f, 0x5f, 0x36, 0x29, 0x1f, + 0x5f, 0x36, 0x29, 0x1f, 0x5f, 0x36, 0x29, 0x1f, 0x0a, 0x52, 0x54, 0x45, + 0x20, 0x28, 0x25, 0x73, 0x2d, 0x25, 0x73, 0x25, 0x73, 0x25, 0x73, 0x29, + 0x20, 0x25, 0x73, 0x20, 0x6f, 0x6e, 0x20, 0x42, 0x43, 0x4d, 0x25, 0x73, + 0x20, 0x72, 0x25, 0x64, 0x20, 0x40, 0x20, 0x25, 0x64, 0x2e, 0x25, 0x64, + 0x2f, 0x25, 0x64, 0x2e, 0x25, 0x64, 0x2f, 0x25, 0x64, 0x2e, 0x25, 0x64, + 0x4d, 0x48, 0x7a, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x2d, 0xe9, 0xff, 0x41, + 0x07, 0x46, 0x0d, 0x46, 0x08, 0x46, 0xfc, 0x21, 0x16, 0x46, 0x98, 0x46, + 0xdb, 0xf3, 0xf8, 0xf6, 0x04, 0x46, 0x60, 0xb3, 0x00, 0x21, 0xfc, 0x22, + 0xd7, 0xf3, 0xaa, 0xf0, 0x0a, 0x9b, 0x38, 0x46, 0x00, 0x93, 0x04, 0xf1, + 0x64, 0x03, 0x01, 0x93, 0x04, 0xf1, 0x68, 0x03, 0x02, 0x93, 0x29, 0x46, + 0x32, 0x46, 0x43, 0x46, 0xfb, 0xf7, 0x92, 0xfc, 0x20, 0x66, 0xd0, 0xb1, + 0x40, 0xf6, 0x12, 0x01, 0x00, 0x22, 0xe0, 0xf3, 0x73, 0xf1, 0x00, 0x21, + 0x0a, 0x46, 0xe0, 0x66, 0x25, 0x60, 0x20, 0x6e, 0xdf, 0xf3, 0x90, 0xf7, + 0x20, 0x46, 0xf8, 0xf7, 0x2b, 0xf9, 0x20, 0x6e, 0xfb, 0xf7, 0xf6, 0xfa, + 0x28, 0x46, 0x21, 0x46, 0xfc, 0x22, 0xdb, 0xf3, 0xdb, 0xf6, 0x00, 0x20, + 0x02, 0xe0, 0x1e, 0x20, 0x00, 0xe0, 0x0b, 0x20, 0x04, 0xb0, 0xbd, 0xe8, + 0xf0, 0x81, 0x00, 0x00, 0x96, 0x86, 0x00, 0x00, 0x01, 0xbc, 0x60, 0x03, + 0x00, 0x10, 0x4e, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0c, 0x2b, 0x03, 0xa8, + 0x5e, 0x02, 0xf0, 0x00, 0x13, 0x03, 0xa6, 0x5e, 0x02, 0xf0, 0x00, 0x13, + 0x02, 0x82, 0x5e, 0x53, 0x00, 0x00, 0x13, 0x02, 0x85, 0x5e, 0xaf, 0x00, + 0x00, 0x13, 0x03, 0xa3, 0x5e, 0x02, 0xf0, 0x00, 0x13, 0x02, 0x83, 0xc2, + 0x1f, 0x00, 0x00, 0x13, 0x02, 0x86, 0xc0, 0x37, 0x00, 0x00, 0x13, 0x02, + 0x02, 0x00, 0xbf, 0x00, 0x00, 0x10, 0x03, 0xa8, 0x5e, 0x02, 0xf0, 0x00, + 0x13, 0x02, 0x82, 0xde, 0xbb, 0x00, 0x00, 0x13, 0x02, 0x82, 0xde, 0xb3, + 0x00, 0x00, 0x13, 0x02, 0x83, 0x5e, 0xb7, 0x00, 0x00, 0x13, 0x02, 0x84, + 0x5e, 0xb3, 0x00, 0x00, 0x13, 0x02, 0x86, 0x00, 0xc7, 0x00, 0x00, 0x13, + 0x02, 0x84, 0x80, 0xc3, 0x00, 0x00, 0x13, 0x01, 0xbc, 0x63, 0xff, 0x1f, + 0xf0, 0x40, 0x00, 0x00, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x03, 0x5b, 0x5e, + 0x02, 0xf0, 0x00, 0x15, 0x01, 0xbc, 0x60, 0x13, 0x00, 0x10, 0x43, 0x00, + 0x01, 0x5e, 0x02, 0xf0, 0x00, 0x00, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x11, + 0x8f, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x11, 0xa4, 0x02, 0x02, 0x00, 0xbf, + 0x00, 0x00, 0x92, 0x02, 0x04, 0x5e, 0xff, 0x00, 0x00, 0x1d, 0x00, 0x6b, + 0x44, 0x65, 0x57, 0x40, 0x1d, 0x01, 0x84, 0x60, 0x02, 0xf7, 0xf7, 0xbf, + 0x01, 0xbc, 0x60, 0x03, 0x00, 0x0a, 0xac, 0x00, 0x02, 0x5e, 0x02, 0xf0, + 0x0f, 0x39, 0x02, 0x02, 0xde, 0xff, 0x00, 0x00, 0x22, 0x00, 0x6b, 0x44, + 0x65, 0x55, 0xe0, 0x22, 0x01, 0x82, 0xe0, 0x02, 0xf7, 0xf7, 0xbf, 0x03, + 0xbf, 0xde, 0x02, 0xf0, 0x05, 0xce, 0x00, 0x68, 0x2b, 0x67, 0x00, 0x00, + 0x27, 0x02, 0x80, 0xde, 0xff, 0x00, 0x00, 0x92, 0x00, 0x6b, 0x44, 0x65, + 0x5b, 0x20, 0x92, 0x01, 0x84, 0xe0, 0x06, 0xf5, 0x77, 0xab, 0x00, 0x02, + 0x5e, 0x02, 0xf0, 0x11, 0x36, 0x02, 0x04, 0x80, 0xc7, 0x00, 0x00, 0x29, + 0x02, 0x81, 0x80, 0xc7, 0x00, 0x00, 0x2b, 0x01, 0x80, 0x60, 0x02, 0xf7, + 0xf7, 0xbf, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x0a, 0xe0, 0x00, 0x90, 0x2b, + 0xfb, 0x00, 0xd7, 0xa2, 0x00, 0xe0, 0x2b, 0xf6, 0xf4, 0x57, 0xa3, 0x00, + 0x6d, 0x44, 0x6a, 0xf4, 0x60, 0x2f, 0x00, 0xb0, 0x2b, 0xef, 0x00, 0x0a, + 0xf6, 0x01, 0x87, 0x60, 0x02, 0xf7, 0xf7, 0xbf, 0x00, 0x68, 0x2b, 0xd7, + 0x00, 0x00, 0x36, 0x00, 0xe9, 0x44, 0x65, 0x5e, 0xb7, 0xa3, 0x00, 0xe8, + 0xc4, 0x69, 0x5f, 0x37, 0xa2, 0x00, 0x68, 0xde, 0x8b, 0x00, 0x00, 0x36, + 0x00, 0x6d, 0xde, 0x8d, 0x5e, 0xc0, 0x36, 0x01, 0x87, 0x60, 0x06, 0xf7, + 0xf7, 0xbf, 0x02, 0x07, 0xde, 0xff, 0x00, 0x00, 0x3b, 0x00, 0xe8, 0x44, + 0x65, 0x5a, 0xf7, 0xa2, 0x00, 0x6d, 0x5e, 0x89, 0x5a, 0xc0, 0x3b, 0x01, + 0x87, 0xe0, 0x02, 0xf7, 0xf7, 0xbf, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x0a, + 0xd7, 0x00, 0x68, 0x2a, 0xff, 0x00, 0x00, 0x46, 0x00, 0xe8, 0x44, 0x65, + 0x57, 0xf7, 0xa1, 0x00, 0x6d, 0xde, 0x85, 0x57, 0x00, 0x42, 0x00, 0x68, + 0x2b, 0x3b, 0x00, 0x00, 0x46, 0x00, 0xe8, 0x44, 0x65, 0x59, 0xd7, 0xa1, + 0x00, 0x6d, 0xde, 0x85, 0x57, 0x00, 0x44, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x00, 0x46, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x0a, 0xc0, 0x01, 0xbc, 0x60, + 0x03, 0x00, 0x0a, 0xbf, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x0a, 0xce, 0x01, + 0xbc, 0x60, 0x03, 0x00, 0x0a, 0xc6, 0x02, 0x02, 0xde, 0xb3, 0x00, 0x00, + 0x49, 0x02, 0x00, 0x42, 0x03, 0x00, 0x00, 0x49, 0x00, 0x02, 0x5e, 0x02, + 0xf0, 0x0b, 0x22, 0x02, 0x84, 0x5e, 0xb3, 0x00, 0x00, 0x92, 0x00, 0x68, + 0xab, 0x07, 0x00, 0x00, 0x92, 0x02, 0x83, 0xde, 0xb7, 0x00, 0x00, 0x4d, + 0x02, 0x01, 0x80, 0xc7, 0x00, 0x00, 0x68, 0x00, 0xb0, 0x2a, 0xc3, 0x00, + 0x17, 0xa2, 0x02, 0x80, 0x2b, 0xeb, 0x00, 0x00, 0x54, 0x00, 0xb0, 0x2b, + 0x1b, 0x00, 0x17, 0xa1, 0x00, 0x6d, 0xde, 0x85, 0x5c, 0xa0, 0x86, 0x00, + 0x68, 0x5e, 0x87, 0x00, 0x00, 0x54, 0x00, 0x68, 0x2b, 0xff, 0x00, 0x00, + 0x54, 0x00, 0xb0, 0x2b, 0xff, 0x00, 0x17, 0xa2, 0x00, 0x68, 0x2b, 0x03, + 0x00, 0x00, 0x59, 0x00, 0xe8, 0x44, 0x65, 0x58, 0x17, 0xa1, 0x00, 0x6d, + 0xde, 0x86, 0xf4, 0x40, 0x86, 0x00, 0xe0, 0x5e, 0x85, 0x55, 0xb7, 0xa1, + 0x00, 0x6d, 0xde, 0x86, 0xf4, 0x40, 0x86, 0x02, 0x02, 0xde, 0xbb, 0x00, + 0x00, 0x68, 0x00, 0x68, 0x2a, 0xb3, 0x00, 0x00, 0x68, 0x00, 0xe8, 0x44, + 0x65, 0x56, 0x97, 0xa1, 0x00, 0xe0, 0x2a, 0xb3, 0x01, 0x57, 0xa2, 0x00, + 0x6e, 0xde, 0x86, 0xf4, 0x40, 0x62, 0x01, 0x82, 0xe0, 0x02, 0xf5, 0xd7, + 0xae, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x0a, 0xf0, 0x01, 0xbc, 0x60, 0x03, + 0x00, 0x0a, 0xac, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x00, 0x68, 0x00, 0xe8, + 0x2a, 0xb2, 0xf4, 0x37, 0xa1, 0x00, 0x90, 0x2a, 0xb3, 0x00, 0x37, 0xa2, + 0x00, 0x6e, 0x2a, 0xb6, 0xf4, 0x40, 0x66, 0x00, 0xb0, 0x2a, 0xb7, 0x00, + 0x17, 0xa2, 0x00, 0x69, 0xde, 0x86, 0xf4, 0x40, 0x68, 0x03, 0xbf, 0xde, + 0x02, 0xf0, 0x00, 0x86, 0x02, 0x83, 0xde, 0xb7, 0x00, 0x00, 0x7e, 0x02, + 0x88, 0x81, 0xab, 0x00, 0x00, 0x7c, 0x02, 0x03, 0x5e, 0xb7, 0x00, 0x00, + 0x92, 0x02, 0x04, 0x80, 0xc7, 0x00, 0x00, 0x6d, 0x02, 0x00, 0x5e, 0xff, + 0x00, 0x00, 0x7c, 0x02, 0x80, 0x80, 0xbf, 0x00, 0x00, 0x7c, 0x00, 0x68, + 0x2b, 0x3b, 0x00, 0x00, 0x73, 0x02, 0x80, 0x2b, 0xeb, 0x00, 0x00, 0x73, + 0x00, 0xb0, 0x2b, 0x43, 0x00, 0x17, 0xbb, 0x00, 0x6e, 0x2b, 0x1a, 0xf7, + 0x60, 0x92, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x00, 0x7c, 0x02, 0x04, 0xde, + 0xb7, 0x00, 0x00, 0x75, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x00, 0x7c, 0x02, + 0x84, 0x00, 0xc7, 0x00, 0x00, 0x77, 0x02, 0x86, 0x00, 0xc7, 0x00, 0x00, + 0x78, 0x00, 0x68, 0x2b, 0x03, 0x00, 0x00, 0x7c, 0x00, 0xe8, 0x44, 0x65, + 0x56, 0xf7, 0xa1, 0x00, 0x6d, 0xde, 0x85, 0x57, 0xc0, 0x7c, 0x00, 0x6c, + 0xc4, 0x65, 0x57, 0x20, 0x92, 0x02, 0x84, 0x5e, 0xb7, 0x00, 0x00, 0x92, + 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x11, 0x51, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x00, 0x92, 0x01, 0xbc, 0x63, 0xff, 0x1f, 0xf7, 0xa1, 0x00, 0x68, 0x45, + 0x86, 0xf4, 0x20, 0x7c, 0x02, 0x03, 0xc5, 0x73, 0x00, 0x00, 0x86, 0x02, + 0x84, 0x5e, 0xb7, 0x00, 0x00, 0x86, 0x02, 0x01, 0x00, 0xc7, 0x00, 0x00, + 0x92, 0x00, 0x6b, 0x44, 0x65, 0x57, 0x40, 0x92, 0x00, 0x20, 0xe3, 0xfe, + 0x14, 0x60, 0x92, 0x02, 0x82, 0xde, 0xbb, 0x00, 0x00, 0x92, 0x02, 0x88, + 0x81, 0xab, 0x00, 0x00, 0x92, 0x02, 0x82, 0xde, 0xb3, 0x00, 0x00, 0x92, + 0x02, 0x80, 0x80, 0xbf, 0x00, 0x00, 0x92, 0x02, 0x84, 0xde, 0xaf, 0x00, + 0x00, 0x92, 0x02, 0x82, 0x5e, 0xbb, 0x00, 0x00, 0x92, 0x03, 0xa0, 0xde, + 0x02, 0xf0, 0x00, 0x8e, 0x02, 0x00, 0x42, 0x03, 0x00, 0x00, 0x8e, 0x00, + 0x02, 0x5e, 0x02, 0xf0, 0x0b, 0x22, 0x01, 0x83, 0x60, 0x02, 0xf5, 0xb7, + 0xad, 0x01, 0x84, 0xe0, 0x06, 0xf5, 0x77, 0xab, 0x01, 0xbc, 0x60, 0x03, + 0x00, 0x0a, 0xc1, 0x00, 0xb0, 0x44, 0x67, 0x00, 0x0a, 0xc2, 0x01, 0x80, + 0x60, 0x02, 0x0d, 0x90, 0x6c, 0x03, 0x59, 0x5e, 0x02, 0xf0, 0x00, 0x94, + 0x03, 0xd8, 0x5e, 0x02, 0xf0, 0x00, 0x95, 0x03, 0xd8, 0xde, 0x02, 0xf0, + 0x00, 0x96, 0x01, 0xbc, 0x61, 0x83, 0x00, 0x11, 0x29, 0x00, 0xb0, 0x00, + 0x7b, 0x00, 0x11, 0x2b, 0x01, 0xbc, 0x63, 0x03, 0x00, 0x11, 0x23, 0x03, + 0x12, 0x5e, 0x02, 0xf0, 0x0a, 0x9c, 0x03, 0x97, 0x5e, 0x02, 0xf0, 0x0b, + 0x33, 0x02, 0x01, 0x81, 0xb3, 0x00, 0x00, 0xa9, 0x02, 0x85, 0xc5, 0x23, + 0x00, 0x00, 0xa9, 0x02, 0x87, 0x81, 0xb3, 0x00, 0x00, 0xa2, 0x03, 0xa3, + 0xde, 0x02, 0xf0, 0x00, 0xa9, 0x03, 0xa0, 0xde, 0x02, 0xf0, 0x00, 0xa9, + 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0b, 0x22, 0x01, 0x87, 0xe0, 0x04, 0x0d, + 0x80, 0x6c, 0x00, 0xe0, 0x44, 0x64, 0x0d, 0xb7, 0xbd, 0x00, 0x6b, 0x44, + 0x66, 0xf7, 0xa0, 0xa3, 0x01, 0xbc, 0x60, 0x03, 0x01, 0x97, 0x80, 0x01, + 0xbc, 0x60, 0x03, 0x00, 0x37, 0x81, 0x01, 0xbc, 0x60, 0x6b, 0x00, 0x50, + 0x8a, 0x01, 0xbc, 0x60, 0x03, 0x06, 0x37, 0x92, 0x03, 0xbf, 0xde, 0x02, + 0xf0, 0x02, 0xe3, 0x03, 0xd0, 0x5e, 0x02, 0xf0, 0x03, 0x1d, 0x03, 0xd0, + 0xde, 0x02, 0xf0, 0x05, 0x2c, 0x03, 0xd5, 0xde, 0x02, 0xf0, 0x0a, 0x56, + 0x03, 0x91, 0x5e, 0x02, 0xf0, 0x05, 0xa2, 0x03, 0x96, 0xde, 0x02, 0xf0, + 0x0a, 0x51, 0x02, 0x88, 0xc1, 0x73, 0x00, 0x00, 0xca, 0x03, 0xc4, 0x5e, + 0x02, 0xf0, 0x07, 0x1c, 0x03, 0xc7, 0x5e, 0x02, 0xf0, 0x07, 0x42, 0x03, + 0xdc, 0xde, 0x02, 0xf0, 0x11, 0xe4, 0x03, 0xaa, 0x5e, 0x02, 0xf0, 0x07, + 0x85, 0x03, 0x86, 0xde, 0x02, 0xf0, 0x0a, 0x94, 0x02, 0x87, 0xc0, 0x37, + 0x00, 0x0a, 0x94, 0x03, 0x83, 0x5e, 0x02, 0xf0, 0x08, 0xc6, 0x03, 0x91, + 0xde, 0x02, 0xf0, 0x06, 0x24, 0x03, 0xc2, 0xde, 0x02, 0xf0, 0x0a, 0xf8, + 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0f, 0x38, 0x00, 0x02, 0x5e, 0x02, 0xf0, + 0x11, 0x8f, 0x03, 0xd4, 0xde, 0x02, 0xf0, 0x06, 0xb5, 0x03, 0xa3, 0xde, + 0x02, 0xf0, 0x00, 0x02, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0e, 0x69, 0x03, + 0xa2, 0x5e, 0x02, 0xf0, 0x00, 0xc7, 0x03, 0x56, 0x5e, 0x02, 0xf0, 0x00, + 0xc4, 0x01, 0x86, 0x60, 0x06, 0x09, 0x10, 0x48, 0x03, 0x1f, 0x5e, 0x02, + 0xf0, 0x00, 0xc4, 0x00, 0x6a, 0x5e, 0x23, 0x00, 0x00, 0xc3, 0x00, 0xb0, + 0x00, 0x27, 0x00, 0x17, 0x88, 0x00, 0xe8, 0x5e, 0x23, 0x00, 0x37, 0x88, + 0x03, 0xa6, 0x5e, 0x02, 0xf0, 0x01, 0x31, 0x00, 0x02, 0x5e, 0x02, 0xf0, + 0x0f, 0x00, 0x00, 0x28, 0x60, 0x0e, 0x08, 0xe1, 0x52, 0x03, 0xc4, 0xde, + 0x02, 0xf0, 0x0b, 0x6a, 0x00, 0x20, 0xc2, 0x03, 0x00, 0x21, 0x64, 0x03, + 0xbf, 0xde, 0x02, 0xf0, 0x01, 0xaf, 0x03, 0x81, 0x5e, 0x02, 0xf0, 0x00, + 0xcc, 0x03, 0x00, 0xde, 0x02, 0xf0, 0x00, 0xaf, 0x01, 0x88, 0xe0, 0x02, + 0x0b, 0x90, 0x5c, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x03, 0x1a, 0x02, 0x87, + 0x40, 0x63, 0x00, 0x00, 0xce, 0x02, 0x82, 0xc1, 0x07, 0x00, 0x00, 0xcf, + 0x01, 0x86, 0x60, 0x06, 0xf4, 0x30, 0x18, 0x02, 0x86, 0x40, 0x63, 0x00, + 0x00, 0xd1, 0x00, 0xb0, 0x5e, 0x87, 0x00, 0x17, 0xa1, 0x00, 0x02, 0xde, + 0x02, 0xf0, 0x00, 0x00, 0x02, 0x87, 0x40, 0x63, 0x00, 0x00, 0xd4, 0x00, + 0xb0, 0x5e, 0x8b, 0x00, 0x10, 0x19, 0x01, 0x86, 0xe0, 0x06, 0xf4, 0x30, + 0x18, 0x02, 0x81, 0xde, 0xaf, 0x00, 0x00, 0xd9, 0x02, 0x86, 0xc0, 0x63, + 0x00, 0x00, 0xd8, 0x00, 0xb0, 0x5e, 0x87, 0x00, 0x17, 0xa1, 0x00, 0x02, + 0xde, 0x02, 0xf0, 0x00, 0x00, 0x01, 0xbc, 0x60, 0x03, 0x02, 0x80, 0x06, + 0x02, 0x80, 0xde, 0x07, 0x00, 0x00, 0xe5, 0x01, 0xda, 0x60, 0x02, 0xf0, + 0x17, 0x80, 0x02, 0x08, 0x5e, 0x07, 0x00, 0x00, 0xf5, 0x01, 0xbc, 0x60, + 0x03, 0x1e, 0x17, 0xa1, 0x00, 0xe0, 0x5e, 0x02, 0xf4, 0x30, 0x65, 0x01, + 0xbc, 0x60, 0x03, 0x1c, 0x17, 0xa1, 0x00, 0xe0, 0x5e, 0x02, 0xf4, 0x30, + 0x64, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x28, 0x17, 0x03, 0xbf, 0xde, 0x02, + 0xf0, 0x00, 0xfb, 0x01, 0x10, 0x5e, 0x03, 0x00, 0x17, 0xa1, 0x00, 0x88, + 0x5e, 0x87, 0x00, 0x37, 0xa2, 0x00, 0xe0, 0x5e, 0x86, 0xf4, 0x57, 0xa1, + 0x00, 0xe0, 0x01, 0x5a, 0xf4, 0x30, 0x63, 0x02, 0x86, 0x00, 0xc3, 0x00, + 0x00, 0xee, 0x00, 0xb0, 0x56, 0x0b, 0x00, 0x10, 0x62, 0x00, 0xb0, 0x54, + 0x03, 0x00, 0x10, 0x62, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x28, 0x17, 0x03, + 0xbf, 0xde, 0x02, 0xf0, 0x00, 0xfd, 0x00, 0xb0, 0x41, 0x8f, 0x00, 0x10, + 0x62, 0x01, 0x09, 0xde, 0x03, 0x00, 0x17, 0xa1, 0x00, 0x88, 0x5e, 0x87, + 0x00, 0x57, 0xa1, 0x00, 0xe0, 0x5e, 0x85, 0x05, 0x77, 0xa1, 0x00, 0xe0, + 0x5e, 0x87, 0x03, 0xc0, 0x06, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x48, 0x17, + 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x00, 0xfd, 0x01, 0xbc, 0x60, 0x07, 0x02, + 0x17, 0xa1, 0x00, 0xe0, 0x5e, 0x02, 0xf4, 0x30, 0x65, 0x01, 0xbc, 0x60, + 0x07, 0x00, 0x17, 0xa1, 0x00, 0xe0, 0x5e, 0x02, 0xf4, 0x30, 0x64, 0x01, + 0xbc, 0x60, 0x03, 0x18, 0x00, 0x06, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x08, + 0x17, 0x00, 0xb0, 0x5a, 0x03, 0x00, 0x10, 0x62, 0x00, 0xb0, 0x58, 0x03, + 0x00, 0x10, 0x63, 0x01, 0x05, 0x01, 0x43, 0x00, 0x17, 0xa1, 0x00, 0x88, + 0x00, 0x1a, 0xf4, 0x20, 0x06, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, + 0x01, 0xbc, 0x60, 0x03, 0x06, 0x37, 0x92, 0x01, 0xbc, 0x63, 0xff, 0x1f, + 0xf0, 0xc3, 0x01, 0xbc, 0x60, 0x03, 0x18, 0x90, 0xe3, 0x01, 0xbc, 0x63, + 0xff, 0x1f, 0xf0, 0xc5, 0x01, 0xbc, 0x63, 0xff, 0x1f, 0xf0, 0xc6, 0x01, + 0xbc, 0x63, 0xff, 0x1f, 0xf0, 0xc7, 0x00, 0xb0, 0x2c, 0x53, 0x00, 0x10, + 0xe5, 0x00, 0xb0, 0x2c, 0x57, 0x00, 0x10, 0xe6, 0x00, 0xb0, 0x2c, 0x5b, + 0x00, 0x10, 0xe7, 0x02, 0x80, 0xac, 0x3f, 0x00, 0x01, 0x13, 0x01, 0xbc, + 0x60, 0x03, 0x00, 0x10, 0x10, 0x00, 0xb0, 0x40, 0x43, 0x00, 0x18, 0x00, + 0x00, 0xb0, 0x40, 0x47, 0x00, 0x10, 0xe5, 0x01, 0xbc, 0x60, 0x03, 0x00, + 0x30, 0x10, 0x00, 0xb0, 0x40, 0x43, 0x00, 0x18, 0x00, 0x00, 0xb0, 0x40, + 0x47, 0x00, 0x10, 0xe6, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x50, 0x10, 0x00, + 0xb0, 0x40, 0x43, 0x00, 0x18, 0x00, 0x00, 0xb0, 0x40, 0x47, 0x00, 0x10, + 0xe7, 0x01, 0xbc, 0x63, 0xff, 0x1f, 0xf0, 0xc4, 0x00, 0x02, 0xde, 0x02, + 0xf0, 0x00, 0x00, 0x00, 0xe8, 0x40, 0x33, 0x00, 0x97, 0xa1, 0x00, 0xb0, + 0x40, 0x0b, 0x00, 0x17, 0xa3, 0x00, 0x6d, 0x5e, 0x86, 0xf4, 0x61, 0x1a, + 0x00, 0x90, 0x5e, 0x8f, 0x00, 0x37, 0xa3, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x01, 0x1b, 0x00, 0x90, 0x5e, 0x87, 0x00, 0x37, 0xa3, 0x01, 0xbc, 0x60, + 0x1f, 0x14, 0x17, 0xa1, 0x00, 0xe0, 0x5e, 0x8e, 0xf4, 0x37, 0xa3, 0x01, + 0xf0, 0x41, 0x97, 0x00, 0x17, 0xa1, 0x00, 0x6d, 0xde, 0x86, 0xf4, 0x61, + 0x2f, 0x02, 0x87, 0xc1, 0x97, 0x00, 0x01, 0x23, 0x01, 0x38, 0x5a, 0x03, + 0x00, 0x17, 0xa1, 0x01, 0x3c, 0x5a, 0x03, 0x00, 0x17, 0xa2, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x01, 0x25, 0x01, 0x3c, 0x5a, 0x03, 0x00, 0x17, 0xa1, + 0x01, 0x38, 0x5a, 0x07, 0x00, 0x17, 0xa2, 0x00, 0x68, 0x5e, 0x86, 0xf4, + 0x81, 0x2a, 0x00, 0xd8, 0x5e, 0x8b, 0x00, 0x37, 0xa2, 0x00, 0xe1, 0x41, + 0x96, 0xf4, 0x50, 0x65, 0x00, 0xe1, 0xc1, 0x97, 0x00, 0x30, 0x65, 0x03, + 0xbf, 0xde, 0x02, 0xf0, 0x01, 0x1d, 0x00, 0xd8, 0x5e, 0x8b, 0x00, 0x37, + 0xa2, 0x00, 0xe1, 0x41, 0x96, 0xf4, 0x57, 0xa1, 0x00, 0xe1, 0xde, 0x87, + 0x00, 0x37, 0xa1, 0x01, 0xf0, 0x5e, 0x87, 0x00, 0x17, 0xa1, 0x00, 0x6e, + 0xde, 0x86, 0xf4, 0x61, 0x30, 0x01, 0xbc, 0x63, 0xff, 0x1f, 0xf7, 0xa4, + 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x00, 0x20, 0xe3, 0x8e, 0x09, + 0x00, 0x02, 0x03, 0x1e, 0xde, 0x02, 0xf0, 0x01, 0x36, 0x03, 0x9f, 0x5e, + 0x02, 0xf0, 0x01, 0x36, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x01, 0x59, 0x03, + 0xbf, 0xde, 0x02, 0xf0, 0x00, 0x02, 0x02, 0x08, 0x41, 0x1f, 0x00, 0x01, + 0x34, 0x01, 0x81, 0x60, 0x05, 0x61, 0xcb, 0x0e, 0x00, 0x02, 0x5e, 0x02, + 0xf0, 0x0b, 0x22, 0x00, 0xb0, 0x00, 0xab, 0x00, 0x10, 0x86, 0x00, 0xb0, + 0x01, 0x63, 0x00, 0x10, 0x8a, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0d, 0x3b, + 0x01, 0xbc, 0x60, 0x03, 0x04, 0x17, 0x92, 0x00, 0xb0, 0x00, 0x3b, 0x00, + 0x11, 0x1d, 0x01, 0x90, 0x60, 0x06, 0x09, 0x10, 0x48, 0x03, 0xa1, 0xde, + 0x02, 0xf0, 0x01, 0x4c, 0x01, 0x81, 0xe0, 0x06, 0x09, 0x10, 0x48, 0x01, + 0xbc, 0x60, 0x03, 0x00, 0x90, 0x42, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x11, + 0x2d, 0x03, 0x9e, 0xde, 0x02, 0xf0, 0x01, 0x4f, 0x01, 0x84, 0x60, 0x02, + 0xf2, 0x97, 0x94, 0x00, 0xb0, 0x45, 0x17, 0x00, 0x17, 0x8f, 0x00, 0xb0, + 0x5e, 0x17, 0x00, 0x17, 0x90, 0x02, 0x00, 0x44, 0x1f, 0x00, 0x01, 0x4a, + 0x01, 0x85, 0x60, 0x02, 0x09, 0x10, 0x48, 0x01, 0x81, 0x60, 0x07, 0x00, + 0x10, 0x47, 0x01, 0xf0, 0xde, 0x0f, 0x00, 0x37, 0xa1, 0x00, 0xa0, 0x44, + 0xb6, 0xf4, 0x31, 0x45, 0x03, 0x9e, 0xde, 0x02, 0xf0, 0x01, 0x4f, 0x01, + 0xbc, 0x61, 0x37, 0x12, 0xb0, 0x80, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x00, + 0x02, 0x00, 0xa0, 0x44, 0xb4, 0x2a, 0x31, 0x45, 0x01, 0xbc, 0x61, 0x27, + 0x12, 0x70, 0x80, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x00, 0x02, 0x00, 0x20, + 0xe0, 0x82, 0x09, 0x00, 0x02, 0x01, 0x0c, 0xde, 0x53, 0x00, 0x17, 0xa1, + 0x01, 0x88, 0x5e, 0x87, 0x00, 0x10, 0x47, 0x01, 0xbc, 0x60, 0x03, 0x00, + 0x50, 0x42, 0x01, 0x08, 0x41, 0x1f, 0x00, 0x17, 0xa1, 0x01, 0x8c, 0xde, + 0x86, 0xf2, 0x97, 0x94, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x00, 0x02, 0x01, + 0xbc, 0x60, 0x03, 0x00, 0x90, 0x42, 0x00, 0xe0, 0x2f, 0xc3, 0x00, 0x2b, + 0xf0, 0x00, 0xe8, 0x5e, 0x23, 0x00, 0x37, 0x88, 0x00, 0x69, 0xde, 0x23, + 0x00, 0x01, 0x5e, 0x00, 0xe8, 0x00, 0x27, 0x00, 0x37, 0x88, 0x01, 0x86, + 0x60, 0x02, 0x09, 0x10, 0x48, 0x01, 0x85, 0x60, 0x06, 0xf5, 0xb7, 0xad, + 0x00, 0x88, 0x00, 0x9b, 0x00, 0xd1, 0x26, 0x00, 0x90, 0x00, 0x9b, 0x01, + 0x51, 0x28, 0x01, 0xbc, 0x63, 0x03, 0x00, 0x11, 0x24, 0x00, 0x02, 0xde, + 0x02, 0xf0, 0x00, 0x00, 0x00, 0x20, 0xe0, 0x7e, 0x09, 0x00, 0x02, 0x00, + 0x02, 0x5e, 0x02, 0xf0, 0x0f, 0x0a, 0x02, 0x83, 0xc2, 0x1f, 0x00, 0x00, + 0x02, 0x02, 0x02, 0x80, 0xf3, 0x00, 0x01, 0x6e, 0x00, 0xb0, 0x44, 0x67, + 0x00, 0x17, 0xa1, 0x01, 0x7c, 0x5e, 0x86, 0x23, 0x57, 0xa3, 0x02, 0x83, + 0x5e, 0xff, 0x00, 0x01, 0x6d, 0x00, 0xe0, 0x00, 0xfa, 0xf4, 0x68, 0x2f, + 0x01, 0x83, 0x60, 0x06, 0xf7, 0xf7, 0xbf, 0x00, 0x6b, 0xde, 0x8d, 0x05, + 0xe1, 0x72, 0x02, 0x06, 0xd0, 0x03, 0x00, 0x01, 0x76, 0x00, 0xe9, 0x50, + 0x86, 0x23, 0x37, 0xa1, 0x00, 0xe8, 0xd0, 0x8a, 0x23, 0x57, 0xa2, 0x00, + 0x69, 0xde, 0x8b, 0x00, 0x01, 0x76, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0b, + 0x22, 0x01, 0x91, 0x60, 0x16, 0x84, 0xf4, 0x27, 0x00, 0xe0, 0x20, 0xbf, + 0x00, 0x88, 0x2f, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x03, 0x00, 0x02, 0x04, + 0x00, 0xbf, 0x00, 0x01, 0x7c, 0x03, 0x94, 0x5e, 0x02, 0xf0, 0x00, 0x02, + 0x00, 0xa0, 0x42, 0x8f, 0x01, 0xf7, 0x80, 0x00, 0x68, 0x5e, 0x00, 0x2d, + 0xc0, 0x02, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0b, 0x22, 0x03, 0xbf, 0xde, + 0x02, 0xf0, 0x00, 0x13, 0x02, 0x01, 0xc2, 0x8f, 0x00, 0x00, 0x02, 0x01, + 0x14, 0x00, 0x63, 0x00, 0x17, 0xa1, 0x00, 0x68, 0x5e, 0x87, 0x00, 0x60, + 0x02, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0b, 0x22, 0x01, 0x94, 0x60, 0x0f, + 0x00, 0x00, 0x18, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x01, 0x83, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x00, 0x13, 0x01, 0x14, 0x00, 0x63, 0x00, 0x17, 0xa1, + 0x00, 0xb0, 0x5e, 0x87, 0x00, 0x10, 0xa5, 0x01, 0xbc, 0x60, 0x13, 0x11, + 0x10, 0x60, 0x00, 0x68, 0x5e, 0x87, 0x00, 0x01, 0x8a, 0x00, 0xe0, 0x41, + 0x83, 0x06, 0xd0, 0x60, 0x00, 0xe8, 0x5e, 0x87, 0x00, 0x37, 0xa1, 0x03, + 0xbf, 0xde, 0x02, 0xf0, 0x01, 0x86, 0x02, 0x80, 0x50, 0xc3, 0x00, 0x01, + 0x94, 0x01, 0x87, 0x60, 0x04, 0x03, 0x10, 0xa0, 0x00, 0xb0, 0x00, 0x63, + 0x00, 0x10, 0xb4, 0x00, 0xb0, 0x42, 0xd3, 0x00, 0x18, 0x00, 0x00, 0x88, + 0x41, 0x83, 0x00, 0x30, 0xb6, 0x01, 0xbc, 0x60, 0x03, 0x0b, 0x10, 0xb5, + 0x00, 0xb0, 0x00, 0x63, 0x00, 0xb0, 0xb4, 0x03, 0x17, 0xde, 0x02, 0xf0, + 0x01, 0x91, 0x03, 0x97, 0xde, 0x02, 0xf0, 0x01, 0x92, 0x01, 0x80, 0x60, + 0x06, 0x86, 0x14, 0x30, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x00, + 0x20, 0xe0, 0x12, 0x80, 0x41, 0xae, 0x01, 0x87, 0x60, 0x04, 0x03, 0x10, + 0xa0, 0x00, 0xb0, 0x00, 0x63, 0x00, 0x10, 0xb4, 0x01, 0xbc, 0x60, 0x03, + 0x0e, 0x10, 0xb5, 0x00, 0xb0, 0x00, 0x63, 0x00, 0xf0, 0xb4, 0x01, 0xbc, + 0x60, 0x57, 0x04, 0x90, 0xb6, 0x00, 0xb0, 0x00, 0x63, 0x00, 0x10, 0xb4, + 0x01, 0xbc, 0x60, 0x03, 0x02, 0xd0, 0xb5, 0x02, 0x07, 0x50, 0x0b, 0x00, + 0x01, 0xab, 0x01, 0xbc, 0x60, 0x03, 0x03, 0xd0, 0xb5, 0x01, 0x8e, 0x60, + 0x02, 0xf2, 0x97, 0x94, 0x02, 0x04, 0x50, 0x0b, 0x00, 0x01, 0xa4, 0x02, + 0x04, 0xd0, 0x0b, 0x00, 0x01, 0xa4, 0x01, 0x86, 0x60, 0x06, 0xf2, 0x97, + 0x94, 0x00, 0xe0, 0x42, 0xd7, 0x00, 0xd0, 0xb5, 0x00, 0xa0, 0x50, 0x0b, + 0x11, 0x17, 0xa1, 0x00, 0x68, 0xde, 0x87, 0x11, 0x01, 0xaa, 0x01, 0x86, + 0xe0, 0x06, 0xf2, 0x97, 0x94, 0x00, 0xe0, 0x42, 0xd7, 0x00, 0x50, 0xb5, + 0x02, 0x07, 0xd0, 0x0b, 0x00, 0x01, 0xaa, 0x00, 0xe0, 0x42, 0xd7, 0x00, + 0x90, 0xb5, 0x00, 0xb0, 0x42, 0xd7, 0x00, 0x11, 0xe1, 0x00, 0xb0, 0x00, + 0x63, 0x00, 0xb0, 0xb4, 0x03, 0x17, 0xde, 0x02, 0xf0, 0x01, 0xac, 0x03, + 0x97, 0xde, 0x02, 0xf0, 0x01, 0xad, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, + 0x00, 0x00, 0x68, 0x20, 0xdb, 0x00, 0x01, 0xb2, 0x00, 0x6c, 0xc4, 0x65, + 0x06, 0xc0, 0x13, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x08, 0x36, 0x00, 0x68, + 0x20, 0xd3, 0x00, 0x01, 0xb5, 0x00, 0x6c, 0xc4, 0x65, 0x06, 0xa0, 0x13, + 0x01, 0xbc, 0x60, 0x03, 0x00, 0x08, 0x34, 0x00, 0x20, 0xe0, 0xbe, 0x09, + 0x00, 0x02, 0x03, 0x90, 0x5e, 0x02, 0xf0, 0x00, 0x13, 0x03, 0xa2, 0x5e, + 0x02, 0xf0, 0x01, 0xf0, 0x02, 0x02, 0x00, 0xbf, 0x00, 0x01, 0xba, 0x02, + 0x03, 0xc5, 0x73, 0x00, 0x01, 0xe3, 0x00, 0x68, 0x2f, 0x63, 0x00, 0x01, + 0xbe, 0x00, 0xe8, 0x44, 0x65, 0x7b, 0x17, 0xa1, 0x00, 0x6d, 0x5e, 0x85, + 0x7a, 0xe1, 0xe3, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x0b, 0xd8, 0x00, 0x68, + 0x2d, 0x93, 0x00, 0x01, 0xe3, 0x02, 0x82, 0xc1, 0x07, 0x00, 0x01, 0xe3, + 0x02, 0x80, 0x42, 0x03, 0x00, 0x01, 0xe3, 0x02, 0x85, 0xc5, 0x23, 0x00, + 0x01, 0xe3, 0x02, 0x86, 0x40, 0x37, 0x00, 0x01, 0xe3, 0x01, 0x81, 0xe0, + 0x06, 0xf5, 0x77, 0xab, 0x00, 0xb0, 0x2d, 0x97, 0x00, 0x17, 0xa1, 0x01, + 0xbc, 0x60, 0x2f, 0x10, 0x37, 0xa2, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x17, + 0xa3, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x13, 0x1b, 0x00, 0xb0, 0x2d, 0x9b, + 0x00, 0x17, 0xa1, 0x01, 0xbc, 0x60, 0x2f, 0x17, 0x37, 0xa2, 0x01, 0xbc, + 0x60, 0x03, 0x00, 0x17, 0xa3, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x13, 0x29, + 0x01, 0xbc, 0x60, 0x13, 0x1a, 0x17, 0xa1, 0x00, 0x02, 0x5e, 0x02, 0xf0, + 0x00, 0xce, 0x00, 0xb0, 0x40, 0x67, 0x04, 0x17, 0xa2, 0x00, 0x02, 0x5e, + 0x02, 0xf0, 0x00, 0xd4, 0x00, 0xe0, 0x44, 0x67, 0x00, 0xd7, 0xa1, 0x00, + 0x6c, 0xc4, 0x66, 0xf4, 0x21, 0xd1, 0x01, 0xbc, 0x60, 0x13, 0x0e, 0xd7, + 0xa1, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xce, 0x00, 0xa0, 0x40, 0x67, + 0x3f, 0xf7, 0xa2, 0x01, 0xbc, 0x60, 0x13, 0x14, 0xd7, 0xa1, 0x01, 0xbc, + 0x62, 0x03, 0x00, 0x17, 0xa3, 0x00, 0xb0, 0x5e, 0x8a, 0xf4, 0x77, 0xa2, + 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xd4, 0x00, 0xb0, 0x2d, 0x97, 0x00, + 0x17, 0xa1, 0x01, 0xbc, 0x60, 0x2f, 0x0c, 0xf7, 0xa2, 0x01, 0xbc, 0x60, + 0x03, 0x00, 0x17, 0xa3, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x13, 0x1b, 0x00, + 0xb0, 0x2d, 0x9b, 0x00, 0x17, 0xa1, 0x01, 0xbc, 0x60, 0x2f, 0x13, 0x77, + 0xa2, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x17, 0xa3, 0x00, 0x02, 0x5e, 0x02, + 0xf0, 0x13, 0x29, 0x01, 0x81, 0xe0, 0x02, 0xf5, 0x77, 0xab, 0x01, 0xbc, + 0x60, 0x03, 0x00, 0x0b, 0x64, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0e, 0x19, + 0x02, 0x02, 0x00, 0xbf, 0x00, 0x01, 0xef, 0x02, 0x84, 0xde, 0xaf, 0x00, + 0x01, 0xea, 0x02, 0x03, 0x5e, 0xb7, 0x00, 0x01, 0xef, 0x00, 0x02, 0x5e, + 0x02, 0xf0, 0x11, 0x02, 0x02, 0x03, 0x5e, 0xb7, 0x00, 0x01, 0xef, 0x03, + 0xbf, 0xde, 0x02, 0xf0, 0x00, 0x02, 0x02, 0x03, 0x5e, 0xb7, 0x00, 0x01, + 0xed, 0x02, 0x04, 0x80, 0xc7, 0x00, 0x01, 0xef, 0x02, 0x80, 0x5e, 0xff, + 0x00, 0x01, 0xef, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x10, 0xc3, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x00, 0x02, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0f, 0x0a, + 0x02, 0x00, 0x42, 0x1f, 0x00, 0x02, 0x07, 0x00, 0x68, 0x42, 0xf3, 0x00, + 0x01, 0xf3, 0x00, 0x6d, 0x42, 0xf3, 0x00, 0x42, 0x07, 0x01, 0x14, 0x00, + 0x63, 0x00, 0x17, 0xa1, 0x00, 0xb0, 0x5e, 0x87, 0x00, 0x17, 0xa2, 0x03, + 0xa2, 0x5e, 0x02, 0xf0, 0x01, 0xfc, 0x01, 0x83, 0xe0, 0x02, 0x0d, 0x90, + 0x6c, 0x03, 0x14, 0x5e, 0x02, 0xf0, 0x02, 0x09, 0x00, 0x6e, 0xc4, 0x56, + 0x80, 0x62, 0x09, 0x02, 0x81, 0x45, 0x23, 0x00, 0x02, 0x09, 0x00, 0x6e, + 0x5e, 0x87, 0x00, 0x62, 0x07, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x77, 0xa2, + 0x00, 0x88, 0x60, 0x06, 0xf4, 0x57, 0xa3, 0x00, 0x88, 0x5e, 0x8b, 0x01, + 0x00, 0x18, 0x00, 0xe8, 0x5e, 0x8b, 0x00, 0x37, 0xa2, 0x00, 0x20, 0xc2, + 0x8e, 0xf4, 0x62, 0x02, 0x00, 0x6a, 0xde, 0x86, 0xf4, 0x41, 0xfc, 0x03, + 0xbf, 0xde, 0x02, 0xf0, 0x02, 0x07, 0x00, 0x90, 0x00, 0x63, 0x01, 0x01, + 0x65, 0x00, 0x80, 0x85, 0x97, 0x02, 0x17, 0xa1, 0x00, 0xe0, 0x64, 0x82, + 0x0d, 0xa1, 0x66, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0e, 0xc1, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x02, 0x33, 0x01, 0x82, 0x60, 0x02, 0x09, 0x10, 0x48, + 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x00, 0x02, 0x01, 0xbc, 0x60, 0x03, 0x00, + 0x11, 0x15, 0x00, 0xb0, 0x01, 0x7f, 0x00, 0x17, 0xa6, 0x03, 0x1f, 0x5e, + 0x02, 0xf0, 0x02, 0x18, 0x02, 0x03, 0x00, 0xc3, 0x00, 0x02, 0x0e, 0x00, + 0x20, 0xc2, 0x8f, 0x02, 0x02, 0x12, 0x03, 0x25, 0x5e, 0x02, 0xf0, 0x02, + 0x18, 0x00, 0x20, 0xc2, 0x8f, 0x02, 0x02, 0x12, 0x00, 0x68, 0x81, 0x53, + 0xff, 0xe0, 0x13, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x02, 0x14, 0x01, 0x94, + 0x60, 0x13, 0x00, 0x00, 0x18, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x02, 0x33, + 0x03, 0x9e, 0xde, 0x02, 0xf0, 0x02, 0x17, 0x00, 0x68, 0xde, 0x98, 0x0b, + 0xc2, 0x17, 0x02, 0x01, 0x41, 0x1f, 0x00, 0x0c, 0x86, 0x01, 0x85, 0x60, + 0x02, 0x09, 0x10, 0x48, 0x00, 0x68, 0x5e, 0x98, 0x0b, 0xc2, 0x1c, 0x00, + 0x69, 0x5e, 0x9f, 0x00, 0x62, 0x38, 0x02, 0x98, 0x42, 0x8f, 0x00, 0x02, + 0x1c, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x02, 0x38, 0x02, 0x01, 0x41, 0x1f, + 0x00, 0x0c, 0x86, 0x02, 0x04, 0x00, 0xbf, 0x00, 0x02, 0x23, 0x02, 0x18, + 0x42, 0x8f, 0x00, 0x0c, 0x86, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0e, 0xa3, + 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0e, 0xc1, 0x01, 0x94, 0x05, 0x87, 0x00, + 0x00, 0x18, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x02, 0x33, 0x02, 0x00, 0x13, + 0xbb, 0x00, 0x02, 0x2c, 0x02, 0x00, 0x15, 0x6b, 0x00, 0x02, 0x2f, 0x00, + 0xb0, 0x13, 0x47, 0x00, 0x17, 0xa1, 0x00, 0x68, 0xde, 0x84, 0xa7, 0xa2, + 0x2c, 0x00, 0xb0, 0x13, 0x4b, 0x00, 0x17, 0xa1, 0x00, 0x68, 0xde, 0x84, + 0xa7, 0xc2, 0x2c, 0x00, 0xb0, 0x13, 0x4f, 0x00, 0x17, 0xa1, 0x00, 0x68, + 0xde, 0x84, 0xa7, 0xe2, 0x2c, 0x02, 0x9e, 0x13, 0x97, 0x00, 0x02, 0x2f, + 0x02, 0x01, 0xc2, 0x8f, 0x00, 0x02, 0x31, 0x01, 0x94, 0x60, 0x0f, 0x00, + 0x00, 0x18, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x02, 0x33, 0x02, 0x01, 0xc2, + 0x8f, 0x00, 0x02, 0x31, 0x01, 0x80, 0x60, 0x06, 0x0d, 0x90, 0x6c, 0x02, + 0x00, 0xc2, 0x8f, 0x00, 0x0c, 0x86, 0x01, 0x94, 0x60, 0x07, 0x00, 0x00, + 0x18, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x01, 0x83, 0x02, 0x04, 0x00, 0xbf, + 0x00, 0x02, 0x68, 0x02, 0x85, 0x00, 0x63, 0x00, 0x02, 0x68, 0x01, 0x83, + 0xe0, 0x06, 0x0d, 0x90, 0x6c, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x02, 0x68, + 0x01, 0xbc, 0x60, 0x03, 0x18, 0x10, 0x60, 0x01, 0x29, 0x50, 0x0b, 0x00, + 0x17, 0x92, 0x00, 0xb0, 0x01, 0x7b, 0x00, 0x10, 0x65, 0x00, 0x68, 0x00, + 0xeb, 0x00, 0x02, 0x41, 0x00, 0x88, 0x5a, 0x13, 0x01, 0x17, 0xa1, 0x00, + 0xe8, 0x44, 0x66, 0xf4, 0x37, 0xa1, 0x00, 0x6e, 0xde, 0x84, 0x07, 0x42, + 0x41, 0x00, 0xe0, 0x02, 0x9b, 0x00, 0x20, 0xa6, 0x03, 0xbf, 0xde, 0x02, + 0xf0, 0x06, 0xae, 0x01, 0x90, 0x60, 0x12, 0x09, 0x10, 0x48, 0x01, 0x94, + 0x60, 0x1f, 0x00, 0x00, 0x18, 0x01, 0x08, 0x5a, 0x0f, 0x00, 0x17, 0x81, + 0x01, 0x88, 0x5e, 0x06, 0x81, 0x54, 0x0a, 0x01, 0x34, 0x5a, 0x0f, 0x00, + 0x17, 0x80, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xdb, 0x00, 0xb0, 0x01, + 0x7b, 0x00, 0x10, 0x65, 0x00, 0xb0, 0x56, 0x23, 0x00, 0x17, 0xa1, 0x00, + 0xe0, 0x5e, 0x86, 0xa0, 0x97, 0xa1, 0x00, 0xe8, 0x5e, 0x84, 0x00, 0xf4, + 0x03, 0x00, 0xe8, 0x5e, 0x84, 0x00, 0xf4, 0x16, 0x00, 0xb0, 0x5a, 0x03, + 0x00, 0x14, 0x13, 0x00, 0xb0, 0x5a, 0x07, 0x00, 0x14, 0x14, 0x00, 0xb0, + 0x5a, 0x0b, 0x00, 0x14, 0x15, 0x00, 0x68, 0xde, 0x07, 0x00, 0x42, 0x59, + 0x00, 0xe8, 0x00, 0x97, 0x00, 0x57, 0xa1, 0x01, 0xbc, 0x5e, 0x86, 0xf0, + 0x14, 0x1b, 0x01, 0x7c, 0x5e, 0x87, 0x00, 0xf4, 0x1c, 0x00, 0xb0, 0x20, + 0x5f, 0x00, 0x17, 0x81, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0d, 0x3f, 0x00, + 0xb0, 0x01, 0x7b, 0x00, 0x10, 0x65, 0x01, 0x08, 0x5a, 0x0f, 0x00, 0x17, + 0x81, 0x00, 0xb0, 0x5e, 0x87, 0x00, 0x14, 0x1e, 0x03, 0xbf, 0xde, 0x02, + 0xf0, 0x02, 0x5c, 0x00, 0xb0, 0x56, 0x17, 0x00, 0x14, 0x1b, 0x00, 0xb0, + 0x56, 0x1b, 0x00, 0x14, 0x1c, 0x00, 0xb0, 0x54, 0x13, 0x00, 0x14, 0x1e, + 0x00, 0xb0, 0x50, 0x13, 0x00, 0x10, 0x86, 0x00, 0x6d, 0x00, 0xa7, 0x00, + 0x82, 0x62, 0x01, 0x90, 0x01, 0x63, 0x00, 0x10, 0x8a, 0x00, 0xb0, 0x41, + 0x8f, 0x00, 0x10, 0x62, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x11, 0xb1, 0x00, + 0xb0, 0x42, 0x2b, 0x00, 0x14, 0x06, 0x01, 0xbc, 0x60, 0x03, 0x18, 0x17, + 0xa1, 0x00, 0x6d, 0xc1, 0x8c, 0x20, 0x02, 0x65, 0x01, 0xbc, 0x60, 0x03, + 0x02, 0x97, 0xa1, 0x00, 0xe0, 0x5e, 0x84, 0x03, 0x77, 0xa1, 0x00, 0xe0, + 0x5e, 0x86, 0xb0, 0x11, 0x1d, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x02, 0xdd, + 0x02, 0x03, 0x00, 0xc7, 0x00, 0x02, 0x78, 0x02, 0x0c, 0xd0, 0x03, 0x00, + 0x02, 0x78, 0x01, 0x14, 0x00, 0x63, 0x00, 0x17, 0xa1, 0x02, 0x85, 0x00, + 0x63, 0x00, 0x02, 0x78, 0x00, 0x80, 0xde, 0x87, 0x01, 0xf7, 0xa2, 0x01, + 0xbc, 0x60, 0x1b, 0x02, 0x57, 0xa2, 0x00, 0xe0, 0x5e, 0x8a, 0x0d, 0xb0, + 0x65, 0x00, 0xb0, 0x41, 0x97, 0x00, 0x14, 0x32, 0x00, 0x80, 0xde, 0x87, + 0x00, 0xb7, 0xa2, 0x01, 0xbc, 0x60, 0x17, 0x1f, 0xd7, 0xa2, 0x00, 0xe0, + 0x5e, 0x8a, 0x0d, 0xb0, 0x64, 0x00, 0xb0, 0x41, 0x93, 0x00, 0x14, 0x33, + 0x00, 0x68, 0xd8, 0x13, 0x00, 0x02, 0x82, 0x02, 0x00, 0x5a, 0x1b, 0x00, + 0x02, 0x7a, 0x01, 0x80, 0x60, 0x06, 0x84, 0xf4, 0x27, 0x03, 0xbf, 0xde, + 0x02, 0xf0, 0x05, 0xce, 0x02, 0x01, 0xd0, 0x03, 0x00, 0x02, 0x7a, 0x00, + 0xb0, 0x50, 0x9b, 0x00, 0x14, 0x2f, 0x02, 0x81, 0xd0, 0xc7, 0x00, 0x02, + 0xfd, 0x01, 0x0b, 0xd0, 0x03, 0x00, 0x17, 0xa1, 0x01, 0x3c, 0x50, 0x2b, + 0x00, 0x17, 0xa2, 0x01, 0x8c, 0x5e, 0x86, 0xf4, 0x57, 0xa1, 0x01, 0x48, + 0x01, 0x43, 0x00, 0x17, 0xa2, 0x00, 0x68, 0x5e, 0x86, 0xf4, 0x42, 0x82, + 0x01, 0x91, 0x60, 0x12, 0x84, 0xf4, 0x27, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x03, 0x00, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x01, 0x95, 0x00, 0xb0, 0x50, + 0x13, 0x00, 0x10, 0x86, 0x00, 0xb0, 0x50, 0x17, 0x00, 0x10, 0x8a, 0x00, + 0x68, 0x2f, 0xbf, 0x00, 0x02, 0x8d, 0x02, 0x91, 0xd0, 0x17, 0x00, 0x02, + 0x8b, 0x02, 0x91, 0xd0, 0x1b, 0x00, 0x02, 0x8b, 0x02, 0x91, 0xd0, 0x1f, + 0x00, 0x02, 0x8b, 0x02, 0x91, 0xd0, 0x23, 0x00, 0x02, 0x8b, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x02, 0x8d, 0x01, 0x91, 0x60, 0x02, 0x84, 0xf4, 0x27, + 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x03, 0x00, 0x03, 0xa2, 0x5e, 0x02, 0xf0, + 0x02, 0xbc, 0x02, 0x0c, 0xd0, 0x03, 0x00, 0x02, 0xa9, 0x02, 0x03, 0x00, + 0xc7, 0x00, 0x02, 0xa8, 0x00, 0xb0, 0x50, 0xcb, 0x00, 0x10, 0x65, 0x00, + 0x02, 0x5e, 0x02, 0xf0, 0x12, 0x4a, 0x02, 0x03, 0x50, 0xc7, 0x00, 0x02, + 0x96, 0x01, 0xbc, 0x60, 0x23, 0x00, 0x97, 0xa1, 0x00, 0xa8, 0x50, 0x02, + 0xf4, 0x34, 0x00, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x02, 0xad, 0x02, 0x04, + 0x81, 0xab, 0x00, 0x02, 0x98, 0x00, 0x6d, 0x42, 0x46, 0xc0, 0x80, 0x13, + 0x00, 0xb0, 0x5a, 0x13, 0x00, 0x17, 0x80, 0x00, 0x02, 0x5e, 0x02, 0xf0, + 0x00, 0xe5, 0x00, 0xb0, 0x54, 0x0f, 0x00, 0x14, 0x1e, 0x00, 0xb0, 0x5a, + 0x07, 0x00, 0x17, 0xa1, 0x00, 0xb0, 0x5a, 0x13, 0x00, 0x17, 0x80, 0x01, + 0x87, 0x5a, 0x16, 0xf0, 0x17, 0x80, 0x00, 0xb0, 0x41, 0x8f, 0x00, 0x10, + 0x65, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x11, 0xba, 0x00, 0xe0, 0x5e, 0x86, + 0xa0, 0x74, 0x03, 0x02, 0x87, 0x5e, 0x03, 0x00, 0x02, 0xa7, 0x01, 0x09, + 0xde, 0x03, 0x00, 0x17, 0xa3, 0x00, 0xe0, 0x5e, 0x8b, 0x00, 0x77, 0xa2, + 0x00, 0xe0, 0x5e, 0x8a, 0xf4, 0x77, 0xa2, 0x00, 0x88, 0x5e, 0x8b, 0x00, + 0x37, 0xa1, 0x00, 0xe0, 0x5e, 0x86, 0xf4, 0x50, 0x89, 0x03, 0xbf, 0xde, + 0x02, 0xf0, 0x02, 0xad, 0x00, 0x6d, 0x42, 0x4a, 0x84, 0x80, 0x13, 0x01, + 0x06, 0x50, 0x07, 0x00, 0x17, 0xa1, 0x02, 0x8c, 0xd0, 0x03, 0x00, 0x02, + 0xac, 0x00, 0x68, 0x5e, 0x87, 0x00, 0x02, 0xad, 0x01, 0x82, 0xde, 0x86, + 0x86, 0x34, 0x31, 0x01, 0x82, 0x60, 0x02, 0x86, 0x34, 0x31, 0x00, 0x20, + 0xd0, 0x03, 0x04, 0x02, 0xb3, 0x00, 0xb0, 0x50, 0x4f, 0x00, 0x11, 0xf2, + 0x00, 0xb0, 0x50, 0x53, 0x00, 0x11, 0xf3, 0x00, 0xb0, 0x50, 0x57, 0x00, + 0x11, 0xf4, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x91, 0xf0, 0x02, 0x01, 0x01, + 0xb3, 0x00, 0x02, 0xb5, 0x01, 0x87, 0xe0, 0x06, 0xf5, 0x77, 0xab, 0x03, + 0x94, 0x5e, 0x02, 0xf0, 0x02, 0xbc, 0x02, 0x06, 0x50, 0x03, 0x00, 0x02, + 0xb8, 0x02, 0x87, 0xde, 0xaf, 0x00, 0x02, 0xbc, 0x02, 0x81, 0x50, 0x03, + 0x00, 0x05, 0x0d, 0x02, 0x02, 0xd0, 0xc7, 0x00, 0x02, 0xbb, 0x02, 0x08, + 0x50, 0x2b, 0x00, 0x02, 0xbc, 0x02, 0x85, 0xd0, 0x03, 0x00, 0x05, 0x24, + 0x01, 0x90, 0x60, 0x12, 0x86, 0x34, 0x31, 0x03, 0xa2, 0x5e, 0x02, 0xf0, + 0x02, 0xc9, 0x00, 0xb0, 0x50, 0x0f, 0x00, 0x11, 0x16, 0x02, 0x02, 0xd0, + 0xc7, 0x00, 0x02, 0xc1, 0x00, 0xb0, 0x50, 0x5b, 0x00, 0x11, 0x16, 0x02, + 0x82, 0xd0, 0x03, 0x00, 0x02, 0xc9, 0x02, 0x81, 0x47, 0xc3, 0x00, 0x02, + 0xc2, 0x02, 0x80, 0x50, 0x4f, 0x00, 0x02, 0xc7, 0x00, 0x20, 0x47, 0xc7, + 0x3f, 0x82, 0xc9, 0x00, 0x20, 0xc7, 0xdb, 0x00, 0xc2, 0xff, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x02, 0xc9, 0x03, 0xa5, 0x5e, 0x02, 0xf0, 0x02, 0xc9, + 0x02, 0x80, 0xc7, 0xdf, 0x00, 0x02, 0xff, 0x02, 0x88, 0x50, 0xc7, 0x00, + 0x02, 0xe3, 0x01, 0x29, 0x50, 0x0b, 0x00, 0x17, 0x92, 0x02, 0x03, 0x00, + 0xc7, 0x00, 0x02, 0xd6, 0x02, 0x0c, 0xd0, 0x03, 0x00, 0x02, 0xd6, 0x02, + 0x83, 0x50, 0xc7, 0x00, 0x02, 0xd6, 0x00, 0xb0, 0x50, 0xcb, 0x00, 0x10, + 0x65, 0x01, 0x38, 0x5a, 0x13, 0x00, 0x17, 0x80, 0x01, 0x82, 0x5a, 0x17, + 0x00, 0x57, 0x81, 0x01, 0x0e, 0x5a, 0x13, 0x00, 0x17, 0xa1, 0x01, 0x8e, + 0x5e, 0x86, 0xf0, 0x37, 0x81, 0x02, 0x02, 0xd0, 0xc7, 0x00, 0x02, 0xe3, + 0x00, 0xb0, 0x50, 0x1b, 0x00, 0x10, 0x8a, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x02, 0xe3, 0x02, 0x82, 0xd0, 0xc7, 0x00, 0x02, 0xdd, 0x01, 0x38, 0x50, + 0x27, 0x00, 0x17, 0x80, 0x01, 0x08, 0x50, 0x13, 0x00, 0x17, 0x81, 0x01, + 0x02, 0x50, 0x13, 0x00, 0x17, 0xa1, 0x01, 0x82, 0x5e, 0x86, 0xf0, 0x37, + 0x81, 0x00, 0xb0, 0x50, 0x7f, 0x00, 0x10, 0x89, 0x03, 0xbf, 0xde, 0x02, + 0xf0, 0x02, 0xe3, 0x01, 0x38, 0x50, 0x6f, 0x00, 0x17, 0x80, 0x01, 0x08, + 0x50, 0x2b, 0x00, 0x17, 0x81, 0x01, 0x06, 0xd0, 0x07, 0x00, 0x17, 0xa1, + 0x01, 0x82, 0x5e, 0x86, 0xf0, 0x37, 0x81, 0x00, 0xb0, 0x50, 0x1b, 0x00, + 0x10, 0x8a, 0x00, 0xb0, 0x50, 0x83, 0x00, 0x10, 0x89, 0x00, 0x02, 0x5e, + 0x02, 0xf0, 0x00, 0xdb, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0d, 0x32, 0x01, + 0x02, 0x42, 0x1b, 0x00, 0x17, 0x81, 0x01, 0x82, 0x5e, 0x05, 0x02, 0xf7, + 0x81, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0d, 0x3f, 0x00, 0xe0, 0x5e, 0x84, + 0x01, 0x17, 0xa1, 0x01, 0xd9, 0xde, 0x87, 0x00, 0x10, 0x83, 0x02, 0x00, + 0x01, 0xb3, 0x00, 0x02, 0xec, 0x01, 0xe0, 0x01, 0xb7, 0x00, 0x10, 0x83, + 0x01, 0xbc, 0x61, 0x37, 0x03, 0xb7, 0x91, 0x00, 0x68, 0x5e, 0x4b, 0x02, + 0x83, 0x03, 0x02, 0x04, 0x00, 0xbf, 0x00, 0x02, 0xf1, 0x02, 0x87, 0x50, + 0x03, 0x00, 0x02, 0xf1, 0x03, 0x94, 0x5e, 0x02, 0xf0, 0x02, 0xf2, 0x03, + 0x22, 0x5e, 0x02, 0xf0, 0x02, 0xf4, 0x01, 0xbc, 0x61, 0x03, 0x00, 0x30, + 0x80, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x00, 0x02, 0x01, 0xbc, 0x61, 0x33, + 0x03, 0xb7, 0x91, 0x03, 0x2b, 0xde, 0x02, 0xf0, 0x02, 0xfa, 0x00, 0x90, + 0x00, 0x63, 0x00, 0x97, 0xa1, 0x00, 0xe0, 0x64, 0x82, 0xf4, 0x30, 0x65, + 0x00, 0x6e, 0x5a, 0x13, 0x00, 0x22, 0xfa, 0x01, 0x88, 0xe0, 0x06, 0xf2, + 0x37, 0x91, 0x00, 0x68, 0xde, 0x4b, 0x04, 0x82, 0xfc, 0x01, 0xbc, 0x61, + 0xbb, 0x03, 0xb7, 0x91, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x03, 0x03, 0x01, + 0x91, 0x60, 0x0e, 0x84, 0xf4, 0x27, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x03, + 0x00, 0x01, 0x91, 0x60, 0x06, 0x84, 0xf4, 0x27, 0x01, 0xbc, 0x60, 0x03, + 0x00, 0x10, 0xb4, 0x01, 0x81, 0xe0, 0x06, 0x86, 0x34, 0x31, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x05, 0xce, 0x03, 0xc4, 0xde, 0x02, 0xf0, 0x0b, 0x6a, + 0x02, 0x06, 0x50, 0x03, 0x00, 0x03, 0x0b, 0x02, 0x07, 0xde, 0xaf, 0x00, + 0x03, 0x0b, 0x01, 0xbc, 0x61, 0x03, 0x00, 0x37, 0x91, 0x02, 0x07, 0x50, + 0x03, 0x00, 0x03, 0x09, 0x01, 0xbc, 0x62, 0x03, 0x00, 0xf7, 0x91, 0x00, + 0xe0, 0x01, 0x0b, 0x00, 0x20, 0x42, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x03, + 0x0c, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x20, 0x42, 0x00, 0xb0, 0x5e, 0x47, + 0x00, 0x10, 0x80, 0x02, 0x00, 0x01, 0xb3, 0x00, 0x03, 0x12, 0x01, 0x82, + 0x60, 0x06, 0x10, 0x30, 0x81, 0x02, 0x01, 0x81, 0xb3, 0x00, 0x03, 0x12, + 0x01, 0xbc, 0x60, 0x03, 0x05, 0xb7, 0x93, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x06, 0xe0, 0x02, 0x04, 0x00, 0xbf, 0x00, 0x03, 0x19, 0x00, 0xb0, 0x05, + 0x8b, 0x00, 0x10, 0x64, 0x00, 0x6e, 0x45, 0x17, 0x00, 0x00, 0x02, 0x00, + 0x68, 0xde, 0x4b, 0x02, 0x83, 0x18, 0x00, 0xa0, 0x44, 0xb4, 0x2a, 0x31, + 0x45, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x00, 0x02, 0x00, 0x02, 0x5e, 0x02, + 0xf0, 0x0d, 0x4c, 0x00, 0x68, 0xc5, 0x17, 0x00, 0x00, 0x02, 0x03, 0xd0, + 0x5e, 0x02, 0xf0, 0x03, 0x1d, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0d, 0x4c, + 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x00, 0x02, 0x01, 0x83, 0x60, 0x02, 0xf7, + 0xf7, 0xbf, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x90, 0x04, 0x00, 0xa8, 0x41, + 0x23, 0x30, 0x10, 0x48, 0x01, 0xbc, 0x62, 0x0f, 0x00, 0x11, 0xe0, 0x01, + 0x81, 0x60, 0x02, 0xf5, 0xd7, 0xae, 0x02, 0x02, 0x00, 0xbf, 0x00, 0x03, + 0x31, 0x00, 0x68, 0xde, 0x4b, 0x02, 0x03, 0x25, 0x00, 0x02, 0x5e, 0x02, + 0xf0, 0x13, 0x15, 0x00, 0x68, 0xde, 0x4b, 0x06, 0x23, 0x31, 0x02, 0x04, + 0x5e, 0xb3, 0x00, 0x03, 0x31, 0x02, 0x00, 0x45, 0x6f, 0x00, 0x03, 0x31, + 0x00, 0xe8, 0x44, 0x65, 0x56, 0xf7, 0xa1, 0x00, 0xe8, 0x2a, 0xae, 0xf4, + 0x37, 0xa1, 0x00, 0x69, 0x5e, 0x87, 0x08, 0x23, 0x31, 0x01, 0x83, 0xe0, + 0x02, 0x2b, 0x91, 0x5c, 0x02, 0x07, 0x01, 0xab, 0x00, 0x03, 0x2e, 0x01, + 0x80, 0xe0, 0x02, 0x09, 0xd0, 0x4e, 0x01, 0xbc, 0x60, 0x03, 0x18, 0x51, + 0x78, 0x00, 0xb0, 0x45, 0xe3, 0x00, 0x18, 0x00, 0x01, 0x80, 0x60, 0x02, + 0x2f, 0x31, 0x79, 0x01, 0x87, 0xe0, 0x02, 0xf5, 0x77, 0xab, 0x00, 0x68, + 0x81, 0x0b, 0x00, 0x23, 0x34, 0x00, 0xb0, 0x44, 0x67, 0x00, 0x00, 0x43, + 0x01, 0x82, 0xe0, 0x06, 0x09, 0x10, 0x48, 0x01, 0x81, 0x60, 0x02, 0x0d, + 0x90, 0x6c, 0x01, 0x82, 0x60, 0x06, 0x28, 0x91, 0x44, 0x01, 0x88, 0xe0, + 0x02, 0x0b, 0x90, 0x5c, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0f, 0x38, 0x01, + 0x85, 0xe0, 0x02, 0xf7, 0xf7, 0xbf, 0x02, 0x88, 0x42, 0x1b, 0x00, 0x03, + 0x3c, 0x01, 0x85, 0xe0, 0x06, 0xf7, 0xf7, 0xbf, 0x03, 0x5b, 0x5e, 0x02, + 0xf0, 0x03, 0x3e, 0x01, 0xbc, 0x60, 0x13, 0x00, 0x10, 0x43, 0x01, 0xbc, + 0x60, 0x03, 0x00, 0x10, 0x85, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x10, 0xb8, + 0x00, 0x88, 0x50, 0x77, 0x00, 0x90, 0xb9, 0x02, 0x08, 0x50, 0x2b, 0x00, + 0x03, 0x45, 0x01, 0x38, 0x50, 0x73, 0x00, 0x17, 0xa1, 0x01, 0x7c, 0x50, + 0x6e, 0xf4, 0x37, 0xa1, 0x00, 0x88, 0x5e, 0x87, 0x00, 0x90, 0xb9, 0x02, + 0x00, 0x47, 0xa3, 0x00, 0x03, 0x49, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x11, + 0xea, 0x00, 0x90, 0x42, 0xe7, 0x00, 0x91, 0xeb, 0x00, 0xb0, 0x47, 0xa3, + 0x00, 0xd1, 0xe8, 0x02, 0x00, 0x47, 0xb3, 0x00, 0x03, 0x4b, 0x01, 0xb0, + 0xe0, 0x8e, 0x3d, 0x91, 0xec, 0x01, 0xd2, 0xe0, 0x02, 0x10, 0x90, 0x84, + 0x03, 0xa9, 0x5e, 0x02, 0xf0, 0x04, 0x37, 0x01, 0xbc, 0x60, 0x03, 0x00, + 0x10, 0x84, 0x00, 0xe0, 0x01, 0xc3, 0x00, 0x20, 0x70, 0x02, 0x81, 0x81, + 0xb3, 0x00, 0x03, 0x81, 0x03, 0x20, 0xde, 0x02, 0xf0, 0x03, 0x9d, 0x01, + 0x81, 0x60, 0x06, 0xf5, 0xb7, 0xad, 0x00, 0x68, 0xde, 0x4b, 0x04, 0xa3, + 0x64, 0x02, 0x03, 0xde, 0xbb, 0x00, 0x03, 0x56, 0x00, 0xe0, 0x2c, 0x8f, + 0x00, 0x10, 0x65, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x03, 0x57, 0x01, 0xbc, + 0x60, 0x23, 0x01, 0xd0, 0x65, 0x00, 0xa0, 0x5e, 0x7f, 0xfe, 0x10, 0xec, + 0x00, 0xb0, 0x5a, 0x03, 0x00, 0x10, 0xed, 0x00, 0xb0, 0x5a, 0x07, 0x00, + 0x10, 0xee, 0x00, 0xb0, 0x5a, 0x0b, 0x00, 0x10, 0xef, 0x00, 0xb0, 0x5a, + 0x0f, 0x00, 0x10, 0xf0, 0x01, 0xbc, 0x63, 0xff, 0x1e, 0xf0, 0x84, 0x01, + 0xbc, 0x60, 0x03, 0x00, 0x30, 0x85, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x10, + 0xb4, 0x01, 0xbc, 0x60, 0x03, 0x01, 0xd0, 0xa6, 0x01, 0xbc, 0x60, 0x03, + 0x04, 0x50, 0xb5, 0x01, 0xbc, 0x60, 0x23, 0x04, 0xd0, 0xb4, 0x00, 0xe0, + 0x02, 0xaf, 0x00, 0x20, 0xab, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x03, 0xe5, + 0x00, 0x68, 0xde, 0x4b, 0x05, 0x23, 0x6a, 0x01, 0xbc, 0x60, 0x03, 0x00, + 0x10, 0xb4, 0x01, 0xbc, 0x60, 0x07, 0x15, 0xd0, 0xa6, 0x01, 0xbc, 0x60, + 0x03, 0x02, 0xd0, 0xb5, 0x01, 0xbc, 0x60, 0x23, 0x04, 0xd0, 0xb4, 0x03, + 0xbf, 0xde, 0x02, 0xf0, 0x03, 0x74, 0x00, 0x68, 0xde, 0x4b, 0x02, 0x43, + 0x81, 0x02, 0x85, 0xc3, 0x8f, 0x00, 0x03, 0x6d, 0x00, 0xe0, 0x5e, 0x27, + 0x00, 0x37, 0x89, 0x01, 0xda, 0x5e, 0x27, 0x00, 0x10, 0xee, 0x01, 0xbc, + 0x63, 0xff, 0x1f, 0xf0, 0xce, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x10, 0xb4, + 0x01, 0xbc, 0x60, 0x03, 0x00, 0xd0, 0xa6, 0x01, 0xbc, 0x60, 0x03, 0x03, + 0xd0, 0xb5, 0x01, 0xbc, 0x60, 0x23, 0x04, 0xd0, 0xb4, 0x00, 0xe0, 0x01, + 0xd3, 0x00, 0x20, 0x74, 0x01, 0xbc, 0x61, 0xff, 0x1f, 0xf0, 0x84, 0x01, + 0xbc, 0x60, 0x03, 0x00, 0x10, 0x85, 0x01, 0x84, 0x60, 0x07, 0x00, 0x11, + 0xe0, 0x02, 0x82, 0xde, 0xb3, 0x00, 0x04, 0xf4, 0x02, 0x04, 0x5e, 0xb3, + 0x00, 0x04, 0xf4, 0x01, 0x83, 0xe0, 0x06, 0x09, 0x10, 0x48, 0x00, 0xb0, + 0x41, 0x23, 0x00, 0x18, 0x00, 0x01, 0xbc, 0x60, 0x03, 0x06, 0xb7, 0x8e, + 0x01, 0x81, 0xe0, 0x06, 0xf5, 0xd7, 0xae, 0x00, 0xb0, 0x54, 0x13, 0x00, + 0x17, 0xa1, 0x00, 0xe0, 0x5e, 0x84, 0x01, 0x17, 0xa1, 0x00, 0x88, 0x5e, + 0x87, 0x00, 0x70, 0x83, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x04, 0xf4, 0x01, + 0xbc, 0x60, 0x03, 0x1f, 0xf0, 0x84, 0x01, 0x03, 0xde, 0x53, 0x00, 0x17, + 0xa2, 0x02, 0x00, 0x5e, 0xff, 0x00, 0x03, 0x85, 0x01, 0xbc, 0x60, 0x03, + 0x00, 0x37, 0xa2, 0x00, 0x68, 0x2b, 0x67, 0x00, 0x03, 0x87, 0x01, 0xbc, + 0x60, 0x03, 0x00, 0x37, 0xa2, 0x01, 0x86, 0x5e, 0x8a, 0x1c, 0x70, 0xe3, + 0x00, 0x6a, 0xc3, 0x93, 0x00, 0x03, 0x91, 0x00, 0xe8, 0x43, 0x90, 0x00, + 0xd0, 0xe4, 0x02, 0x02, 0x42, 0x1b, 0x00, 0x03, 0x8f, 0x00, 0x90, 0x00, + 0x1b, 0x00, 0x37, 0xa1, 0x00, 0x20, 0x42, 0x1b, 0x00, 0x43, 0x8e, 0x00, + 0xb0, 0x20, 0xaf, 0x00, 0x17, 0xa1, 0x00, 0xe0, 0x43, 0x92, 0xf4, 0x30, + 0xe4, 0x00, 0x69, 0xc3, 0x93, 0x00, 0x03, 0x91, 0x01, 0xbc, 0x60, 0x03, + 0x00, 0x10, 0xe4, 0x00, 0x68, 0x2b, 0x67, 0x00, 0x03, 0x93, 0x00, 0xe0, + 0x43, 0x91, 0x5b, 0xf0, 0xe4, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x10, 0xb4, + 0x01, 0xbc, 0x60, 0x03, 0x00, 0x10, 0xa6, 0x01, 0xbc, 0x60, 0x03, 0x02, + 0x10, 0xb5, 0x01, 0xbc, 0x60, 0x23, 0x04, 0xd0, 0xb4, 0x00, 0x68, 0x5e, + 0x4b, 0x06, 0xa3, 0x9b, 0x00, 0xe0, 0x01, 0xcb, 0x00, 0x20, 0x72, 0x01, + 0xbc, 0x60, 0x03, 0x00, 0x08, 0x37, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x03, + 0xe5, 0x00, 0xe0, 0x01, 0xcf, 0x00, 0x20, 0x73, 0x03, 0xbf, 0xde, 0x02, + 0xf0, 0x03, 0xe5, 0x03, 0x20, 0x5e, 0x02, 0xf0, 0x03, 0xec, 0x01, 0x81, + 0xe0, 0x02, 0x09, 0x10, 0x48, 0x00, 0xe0, 0x01, 0xd7, 0x00, 0x20, 0x75, + 0x03, 0x1e, 0xde, 0x02, 0xf0, 0x03, 0xcc, 0x01, 0xbc, 0x60, 0x03, 0x00, + 0x17, 0xa2, 0x00, 0x6a, 0x5e, 0x23, 0x00, 0x03, 0xa5, 0x01, 0x02, 0x42, + 0x8f, 0x00, 0x17, 0xa2, 0x01, 0x85, 0x5e, 0x8a, 0x09, 0x10, 0x48, 0x01, + 0x80, 0xe0, 0x06, 0x10, 0x30, 0x81, 0x02, 0x84, 0xde, 0x53, 0x00, 0x03, + 0xac, 0x00, 0xb0, 0x00, 0x77, 0x00, 0x17, 0xa1, 0x00, 0xe0, 0x5e, 0x84, + 0x04, 0x37, 0xa1, 0x00, 0x88, 0x5e, 0x87, 0x00, 0x57, 0xa1, 0x00, 0xe0, + 0x5e, 0x87, 0x0d, 0x57, 0xa1, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x03, 0xad, + 0x01, 0xbc, 0x60, 0x03, 0x0d, 0x57, 0xa1, 0x00, 0x68, 0x00, 0x27, 0x00, + 0x03, 0xcc, 0x00, 0xe0, 0x5e, 0x84, 0x01, 0xf7, 0xa1, 0x01, 0xbc, 0x60, + 0x23, 0x01, 0x50, 0x65, 0x00, 0x88, 0x41, 0x97, 0x00, 0x30, 0xb6, 0x01, + 0xbc, 0x60, 0x03, 0x00, 0x10, 0xb4, 0x00, 0x90, 0x5e, 0x87, 0x00, 0x50, + 0xa6, 0x01, 0xbc, 0x60, 0x03, 0x01, 0x10, 0xb5, 0x01, 0xbc, 0x60, 0x23, + 0x00, 0xb0, 0xb4, 0x03, 0x17, 0xde, 0x02, 0xf0, 0x03, 0xb5, 0x03, 0x97, + 0xde, 0x02, 0xf0, 0x03, 0xb6, 0x00, 0x20, 0xde, 0x87, 0x00, 0x43, 0xbf, + 0x00, 0x20, 0xde, 0x87, 0x00, 0x23, 0xbc, 0x01, 0xb8, 0x5e, 0x22, 0xd0, + 0x16, 0x80, 0x01, 0x80, 0x5e, 0x8a, 0xd0, 0x36, 0x81, 0x03, 0xbf, 0xde, + 0x02, 0xf0, 0x03, 0xc5, 0x01, 0xbc, 0x5e, 0x22, 0xd0, 0x16, 0x80, 0x01, + 0x84, 0x5e, 0x8a, 0xd0, 0x36, 0x81, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x03, + 0xc5, 0x00, 0x20, 0xde, 0x87, 0x00, 0x23, 0xc3, 0x01, 0xb8, 0x5e, 0x22, + 0xd0, 0x36, 0x81, 0x01, 0x80, 0x5e, 0x8a, 0xd0, 0x56, 0x82, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x03, 0xc5, 0x01, 0xbc, 0x5e, 0x22, 0xd0, 0x36, 0x81, + 0x01, 0x84, 0x5e, 0x8a, 0xd0, 0x56, 0x82, 0x01, 0x88, 0x60, 0x02, 0xf4, + 0x30, 0xa8, 0x00, 0xb0, 0x5a, 0x03, 0x00, 0x10, 0xb0, 0x00, 0xb0, 0x5a, + 0x07, 0x00, 0x10, 0xb1, 0x02, 0x80, 0x42, 0xa3, 0x00, 0x03, 0xc8, 0x00, + 0xe0, 0x42, 0xa3, 0x00, 0x90, 0xa8, 0x00, 0xb0, 0x5a, 0x0b, 0x00, 0x10, + 0xb0, 0x00, 0xb0, 0x5a, 0x0f, 0x00, 0x10, 0xb1, 0x01, 0x87, 0x60, 0x06, + 0x10, 0x90, 0x84, 0x00, 0xe0, 0x5e, 0x27, 0x00, 0x37, 0x89, 0x01, 0xda, + 0x5e, 0x27, 0x00, 0x10, 0xee, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x10, 0xb4, + 0x01, 0xbc, 0x60, 0x03, 0x03, 0x50, 0xa6, 0x00, 0xb0, 0x00, 0x33, 0x00, + 0x10, 0xb5, 0x02, 0x84, 0xde, 0x53, 0x00, 0x03, 0xd6, 0x00, 0xe0, 0x60, + 0x68, 0x03, 0xb0, 0xa6, 0x00, 0xe0, 0x42, 0x98, 0x04, 0x30, 0xa6, 0x00, + 0xb0, 0x00, 0x37, 0x00, 0x10, 0xb5, 0x01, 0xbc, 0x60, 0x23, 0x04, 0xd0, + 0xb4, 0x01, 0x84, 0x60, 0x06, 0xf2, 0x97, 0x94, 0x01, 0x86, 0x60, 0x02, + 0x09, 0x10, 0x48, 0x03, 0x9e, 0xde, 0x02, 0xf0, 0x03, 0xe0, 0x02, 0x80, + 0x44, 0x1f, 0x00, 0x03, 0xe3, 0x00, 0xb0, 0x5e, 0x3f, 0x00, 0x11, 0x45, + 0x01, 0xbc, 0x60, 0x03, 0x00, 0x17, 0x8f, 0x00, 0xb0, 0x5e, 0x43, 0x00, + 0x17, 0x85, 0x00, 0xb0, 0x5e, 0x0f, 0x00, 0x17, 0x90, 0x03, 0xbf, 0xde, + 0x02, 0xf0, 0x03, 0xe3, 0x00, 0xb0, 0x5e, 0x0f, 0x00, 0x17, 0x85, 0x02, + 0x80, 0x44, 0x1f, 0x00, 0x03, 0xe3, 0x00, 0xa0, 0x44, 0xb6, 0xf0, 0xb1, + 0x45, 0x01, 0xbc, 0x60, 0x03, 0x01, 0x10, 0x42, 0x01, 0x83, 0x60, 0x06, + 0xf2, 0x97, 0x94, 0x01, 0x84, 0x60, 0x07, 0x00, 0x11, 0xe0, 0x03, 0xa0, + 0x5e, 0x02, 0xf0, 0x04, 0xf2, 0x02, 0x06, 0x5e, 0xaf, 0x00, 0x04, 0xf4, + 0x01, 0x86, 0xe0, 0x06, 0xf5, 0x77, 0xab, 0x01, 0xbc, 0x60, 0x03, 0x00, + 0x10, 0x80, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0b, 0x28, 0x03, 0xbf, 0xde, + 0x02, 0xf0, 0x06, 0x24, 0x03, 0xa1, 0x5e, 0x02, 0xf0, 0x04, 0x5e, 0x01, + 0x14, 0x00, 0x63, 0x00, 0x17, 0xa1, 0x00, 0x68, 0xde, 0x87, 0x00, 0xe3, + 0xf1, 0x01, 0x81, 0x60, 0x06, 0x09, 0x10, 0x48, 0x03, 0xbf, 0xde, 0x02, + 0xf0, 0x04, 0x5e, 0x01, 0x81, 0x60, 0x06, 0xf5, 0xd7, 0xae, 0x00, 0x20, + 0x60, 0x0e, 0x86, 0x24, 0x16, 0x01, 0x87, 0x60, 0x04, 0x03, 0x10, 0xa0, + 0x00, 0xb0, 0x00, 0x63, 0x00, 0x10, 0xb4, 0x01, 0xbc, 0x60, 0x03, 0x0b, + 0x10, 0xb5, 0x00, 0xb0, 0x00, 0x63, 0x00, 0xf0, 0xb4, 0x02, 0x03, 0x00, + 0xc7, 0x00, 0x04, 0x04, 0x02, 0x0c, 0xd0, 0x03, 0x00, 0x04, 0x04, 0x02, + 0x80, 0x50, 0xc7, 0x00, 0x03, 0xfc, 0x00, 0xb0, 0x54, 0x13, 0x00, 0x17, + 0xa1, 0x00, 0xe0, 0x5e, 0x86, 0x80, 0x74, 0x1a, 0x00, 0xb0, 0x50, 0x6b, + 0x00, 0x10, 0xe4, 0x00, 0xb0, 0x42, 0x13, 0x02, 0x10, 0x84, 0x02, 0x09, + 0x50, 0x2b, 0x00, 0x04, 0x04, 0x00, 0xb0, 0x42, 0x13, 0x00, 0x30, 0x84, + 0x01, 0xd2, 0xe0, 0x3a, 0xa0, 0x30, 0xe0, 0x02, 0x80, 0x50, 0xc7, 0x00, + 0x04, 0x0a, 0x01, 0xd2, 0xe0, 0x52, 0xa0, 0x30, 0xe0, 0x03, 0xbf, 0xde, + 0x02, 0xf0, 0x04, 0x0a, 0x02, 0x02, 0xd0, 0xc7, 0x00, 0x04, 0x0a, 0x00, + 0xb0, 0x50, 0x5f, 0x00, 0x10, 0xe0, 0x00, 0xb0, 0x50, 0x63, 0x00, 0x10, + 0xe1, 0x00, 0xb0, 0x50, 0x67, 0x00, 0x10, 0xe2, 0x00, 0xb0, 0x50, 0x6b, + 0x00, 0x10, 0xe4, 0x00, 0xb0, 0x42, 0x13, 0x02, 0xf0, 0x84, 0x02, 0x00, + 0x50, 0xc7, 0x00, 0x04, 0x11, 0x00, 0xb0, 0x00, 0x63, 0x00, 0x10, 0xb4, + 0x01, 0xbc, 0x60, 0x03, 0x02, 0x10, 0xb5, 0x00, 0xb0, 0x00, 0x63, 0x04, + 0xd0, 0xb4, 0x01, 0x84, 0x60, 0x07, 0x00, 0x11, 0xe0, 0x01, 0xbc, 0x60, + 0x03, 0x00, 0x17, 0x8e, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x04, 0xf6, 0x00, + 0xe0, 0x01, 0xc7, 0x00, 0x20, 0x71, 0x00, 0xb0, 0x00, 0x63, 0x00, 0x10, + 0xb4, 0x01, 0xbc, 0x60, 0x03, 0x02, 0xd0, 0xb5, 0x00, 0xb0, 0x00, 0x63, + 0x04, 0xd0, 0xb4, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x04, 0x8e, 0x01, 0x85, + 0x60, 0x06, 0xf7, 0xf7, 0xbf, 0x01, 0x03, 0x50, 0x03, 0x00, 0x17, 0xa1, + 0x00, 0xb8, 0x5e, 0x87, 0x00, 0x37, 0xa1, 0x01, 0x87, 0x5e, 0x86, 0x10, + 0x10, 0x80, 0x02, 0x0c, 0xd0, 0x03, 0x00, 0x04, 0x5d, 0x02, 0x03, 0x00, + 0xc7, 0x00, 0x04, 0x2d, 0x00, 0xb0, 0x50, 0xcb, 0x00, 0x10, 0x65, 0x01, + 0xbc, 0x60, 0x03, 0x00, 0x16, 0x85, 0x00, 0xe0, 0x5a, 0x33, 0x00, 0x36, + 0x8c, 0x02, 0x03, 0x50, 0xc7, 0x00, 0x04, 0x22, 0x00, 0xe0, 0x5a, 0x27, + 0x00, 0x36, 0x89, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x04, 0x5e, 0x01, 0xbc, + 0x60, 0x03, 0x00, 0x17, 0xb2, 0x00, 0xb0, 0x5a, 0x0b, 0x00, 0x0b, 0x24, + 0x01, 0x38, 0x5a, 0x13, 0x00, 0x17, 0xa1, 0x01, 0xbc, 0x5a, 0x06, 0xf4, + 0x30, 0xe0, 0x01, 0x3c, 0x5a, 0x13, 0x00, 0x17, 0xa1, 0x01, 0x7c, 0x5a, + 0x06, 0xf4, 0x30, 0xe1, 0x01, 0x81, 0xe0, 0x06, 0x10, 0x90, 0x84, 0x01, + 0x85, 0xe0, 0x07, 0x00, 0x10, 0xe3, 0x01, 0x85, 0xe0, 0x07, 0x00, 0x10, + 0xc3, 0x02, 0x82, 0xd0, 0xc7, 0x00, 0x04, 0x32, 0x03, 0xbf, 0xde, 0x02, + 0xf0, 0x04, 0x35, 0x02, 0x02, 0xd0, 0xc7, 0x00, 0x04, 0x37, 0x00, 0xb0, + 0x2a, 0x4b, 0x00, 0x17, 0xa1, 0x01, 0xb8, 0x50, 0x6e, 0xf4, 0x30, 0xe0, + 0x00, 0xb0, 0x50, 0x73, 0x00, 0x17, 0xa1, 0x01, 0xb8, 0x2a, 0x4e, 0xf4, + 0x30, 0xe1, 0x02, 0x82, 0x42, 0x13, 0x00, 0x04, 0x35, 0x00, 0xb0, 0x50, + 0x7b, 0x00, 0x10, 0xe4, 0x00, 0xb0, 0x42, 0x13, 0x02, 0x10, 0x84, 0x01, + 0x85, 0xe0, 0x06, 0x1c, 0x30, 0xe1, 0x00, 0xb0, 0x42, 0x13, 0x00, 0x70, + 0x84, 0x01, 0x87, 0x60, 0x04, 0x03, 0x10, 0xa0, 0x02, 0x03, 0x00, 0xc7, + 0x00, 0x04, 0x4c, 0x00, 0xb0, 0x50, 0xcb, 0x00, 0x10, 0x65, 0x00, 0x6d, + 0x5e, 0xca, 0xd1, 0xc4, 0x3d, 0x01, 0x85, 0xe0, 0x02, 0x18, 0x70, 0xc3, + 0x00, 0xe0, 0x5e, 0xcb, 0x00, 0x36, 0x8e, 0x01, 0xbc, 0x60, 0x1b, 0x09, + 0xd0, 0x65, 0x00, 0xe0, 0x41, 0x96, 0xf6, 0x50, 0x65, 0x00, 0xb0, 0x50, + 0x97, 0x00, 0x16, 0x80, 0x00, 0x68, 0xde, 0xcb, 0x00, 0x04, 0x44, 0x01, + 0xbc, 0x60, 0x23, 0x01, 0x50, 0xb8, 0x00, 0x68, 0x2c, 0x93, 0x00, 0x24, + 0x4a, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x04, 0x56, 0x00, 0xb0, 0x5e, 0xcb, + 0x00, 0x10, 0xb5, 0x00, 0xb0, 0x00, 0x63, 0x08, 0x70, 0xb4, 0x02, 0x83, + 0x42, 0xd3, 0x00, 0x04, 0x46, 0x01, 0xbc, 0x60, 0x03, 0x01, 0x70, 0xb8, + 0x00, 0x68, 0xac, 0x93, 0x00, 0x24, 0x56, 0x01, 0xbc, 0x60, 0x03, 0x01, + 0x70, 0xb8, 0x02, 0xbc, 0x50, 0x67, 0x00, 0x04, 0x55, 0x03, 0xbf, 0xde, + 0x02, 0xf0, 0x04, 0x54, 0x01, 0x0c, 0xd0, 0x03, 0x00, 0x17, 0xa1, 0x03, + 0xa9, 0x5e, 0x02, 0xf0, 0x04, 0x51, 0x01, 0xbc, 0x60, 0x23, 0x01, 0x50, + 0xb8, 0x00, 0x68, 0x5e, 0x87, 0x00, 0x64, 0x54, 0x03, 0xbf, 0xde, 0x02, + 0xf0, 0x04, 0x56, 0x01, 0xbc, 0x60, 0x03, 0x01, 0x70, 0xb8, 0x00, 0x68, + 0x5e, 0x87, 0x00, 0x44, 0x56, 0x01, 0xbc, 0x60, 0x03, 0x01, 0x70, 0xb8, + 0x01, 0x81, 0xe0, 0x02, 0x17, 0x10, 0xb8, 0x01, 0xbc, 0x60, 0x03, 0x00, + 0xf0, 0xa5, 0x01, 0xbc, 0x60, 0x03, 0x0e, 0x10, 0xb5, 0x00, 0xb0, 0x00, + 0x63, 0x00, 0x10, 0xb4, 0x00, 0xb0, 0x00, 0x63, 0x00, 0xf0, 0xb4, 0x00, + 0xb0, 0x42, 0xd3, 0x00, 0x18, 0x00, 0x01, 0x88, 0x60, 0x08, 0x03, 0x10, + 0xb4, 0x01, 0x81, 0x60, 0x06, 0x0d, 0x90, 0x6c, 0x03, 0xbf, 0xde, 0x02, + 0xf0, 0x04, 0x8e, 0x02, 0x02, 0xd0, 0xc7, 0x00, 0x04, 0x64, 0x00, 0xb0, + 0x50, 0x6f, 0x00, 0x10, 0xe0, 0x00, 0xb0, 0x50, 0x73, 0x00, 0x10, 0xe1, + 0x00, 0xb0, 0x50, 0x77, 0x00, 0x10, 0xe2, 0x02, 0x82, 0x42, 0x13, 0x00, + 0x04, 0x63, 0x00, 0xb0, 0x50, 0x7b, 0x00, 0x10, 0xe4, 0x00, 0xb0, 0x42, + 0x13, 0x02, 0xf0, 0x84, 0x00, 0xe0, 0x5e, 0x9f, 0x00, 0x37, 0xa7, 0x03, + 0xa1, 0x5e, 0x02, 0xf0, 0x04, 0x6d, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x17, + 0xa7, 0x01, 0x87, 0x60, 0x04, 0x03, 0x10, 0xa0, 0x00, 0xb0, 0x00, 0x63, + 0x00, 0x10, 0xb4, 0x01, 0xbc, 0x60, 0x03, 0x0e, 0x10, 0xb5, 0x00, 0xb0, + 0x00, 0x63, 0x00, 0xf0, 0xb4, 0x01, 0x88, 0x60, 0x08, 0x03, 0x10, 0xb4, + 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x04, 0x83, 0x00, 0xb0, 0x01, 0x7b, 0x00, + 0x10, 0x65, 0x00, 0xb0, 0x5a, 0x03, 0x00, 0x10, 0xe5, 0x01, 0xbc, 0x63, + 0xff, 0x1f, 0xf0, 0xc5, 0x00, 0xb0, 0x5a, 0x07, 0x00, 0x10, 0xe6, 0x01, + 0xbc, 0x63, 0xff, 0x1f, 0xf0, 0xc6, 0x00, 0xb0, 0x5a, 0x0b, 0x00, 0x10, + 0xe7, 0x01, 0xbc, 0x63, 0xff, 0x1f, 0xf0, 0xc7, 0x00, 0x68, 0xa0, 0x63, + 0x00, 0x04, 0x76, 0x00, 0xe0, 0x5e, 0x27, 0x00, 0x37, 0x89, 0x00, 0x68, + 0x20, 0x63, 0x00, 0x04, 0x7a, 0x01, 0x85, 0xe0, 0x07, 0x00, 0x10, 0xe3, + 0x01, 0x85, 0xe0, 0x07, 0x00, 0x10, 0xc3, 0x00, 0xb0, 0x42, 0x13, 0x01, + 0x10, 0x84, 0x01, 0xda, 0x5e, 0x27, 0x00, 0x10, 0xee, 0x01, 0x87, 0x60, + 0x06, 0x10, 0x90, 0x84, 0x00, 0xb0, 0x42, 0x13, 0x1c, 0x10, 0x84, 0x01, + 0xbc, 0x60, 0x03, 0x00, 0x10, 0xb4, 0x00, 0xe0, 0x60, 0x68, 0x03, 0xb0, + 0xa6, 0x00, 0xb0, 0x00, 0x97, 0x00, 0x10, 0xb5, 0x01, 0xbc, 0x60, 0x23, + 0x04, 0xd0, 0xb4, 0x01, 0x84, 0x60, 0x07, 0x00, 0x11, 0xe0, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x04, 0xe2, 0x01, 0x08, 0x5e, 0x4b, 0x00, 0x17, 0xa1, + 0x00, 0x68, 0x5e, 0x87, 0x00, 0x24, 0x8e, 0x02, 0x02, 0x50, 0x03, 0x00, + 0x04, 0x8d, 0x02, 0x9e, 0x50, 0x9f, 0x00, 0x04, 0x8a, 0x02, 0x01, 0xd0, + 0x03, 0x00, 0x04, 0x8a, 0x00, 0xe0, 0x5e, 0x27, 0x00, 0x37, 0x89, 0x01, + 0x58, 0x5e, 0x27, 0x00, 0x14, 0x2d, 0x01, 0xda, 0x50, 0xb7, 0x00, 0x10, + 0xee, 0x01, 0x87, 0x60, 0x06, 0x10, 0x90, 0x84, 0x03, 0xbf, 0xde, 0x02, + 0xf0, 0x04, 0x8e, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x14, 0x2d, 0x01, 0x04, + 0xc1, 0x07, 0x00, 0x17, 0xa1, 0x03, 0x22, 0x5e, 0x02, 0xf0, 0x04, 0x91, + 0x01, 0x03, 0xde, 0x53, 0x00, 0x17, 0xa1, 0x00, 0xb0, 0x5e, 0x87, 0x00, + 0x17, 0xa2, 0x02, 0x00, 0x5e, 0xff, 0x00, 0x04, 0x94, 0x01, 0xbc, 0x60, + 0x03, 0x00, 0x37, 0xa2, 0x00, 0x68, 0x2b, 0x67, 0x00, 0x04, 0x96, 0x01, + 0xbc, 0x60, 0x03, 0x00, 0x37, 0xa2, 0x02, 0x88, 0x5e, 0x4b, 0x00, 0x04, + 0x99, 0x00, 0x68, 0x5e, 0x4b, 0x06, 0x84, 0x99, 0x01, 0xbc, 0x60, 0x03, + 0x00, 0x17, 0xa2, 0x01, 0x83, 0xde, 0x86, 0xf2, 0x97, 0x94, 0x01, 0x83, + 0xde, 0x86, 0x84, 0xf4, 0x27, 0x02, 0x81, 0xc2, 0x13, 0x00, 0x04, 0xa0, + 0x01, 0x86, 0x5e, 0x8b, 0x00, 0x10, 0xe3, 0x01, 0x86, 0x60, 0x07, 0x00, + 0x10, 0xc3, 0x01, 0x81, 0xe0, 0x06, 0x10, 0x90, 0x84, 0x03, 0xbf, 0xde, + 0x02, 0xf0, 0x04, 0xa2, 0x01, 0x86, 0x5e, 0x8a, 0x1c, 0x70, 0xe3, 0x01, + 0x86, 0x60, 0x06, 0x18, 0x70, 0xc3, 0x02, 0xb8, 0x47, 0xa7, 0x00, 0x04, + 0xde, 0x02, 0xa0, 0x47, 0xb7, 0x00, 0x04, 0xe0, 0x03, 0xa9, 0x5e, 0x02, + 0xf0, 0x04, 0xaa, 0x01, 0x08, 0x5e, 0x4b, 0x00, 0x17, 0xa1, 0x00, 0x68, + 0x5e, 0x87, 0x00, 0x24, 0xdf, 0x02, 0x1e, 0x50, 0x9f, 0x00, 0x04, 0xaa, + 0x01, 0x85, 0xe0, 0x06, 0x1c, 0x70, 0xe3, 0x01, 0x85, 0xe0, 0x06, 0x18, + 0x70, 0xc3, 0x01, 0x14, 0x00, 0x63, 0x00, 0x17, 0xa1, 0x00, 0x68, 0xde, + 0x87, 0x00, 0x84, 0xb3, 0x00, 0xb0, 0x01, 0x53, 0x00, 0x17, 0xa2, 0x00, + 0x68, 0xde, 0x8b, 0xff, 0xe4, 0xaf, 0x00, 0x68, 0x42, 0x47, 0x00, 0x24, + 0xb0, 0x00, 0x68, 0xde, 0x8a, 0x84, 0xc4, 0xb3, 0x01, 0x85, 0x60, 0x02, + 0x09, 0x10, 0x48, 0x01, 0x86, 0xe0, 0x02, 0x1c, 0x70, 0xe3, 0x01, 0x86, + 0xe0, 0x06, 0x18, 0x70, 0xc3, 0x01, 0x10, 0x50, 0x07, 0x00, 0x17, 0xa6, + 0x00, 0x68, 0x5e, 0x9b, 0x00, 0x04, 0xdf, 0x01, 0xbc, 0x60, 0x03, 0x00, + 0x11, 0xe4, 0x01, 0x3a, 0x50, 0x07, 0x00, 0x17, 0x80, 0x00, 0x88, 0x5e, + 0x03, 0x00, 0x77, 0x80, 0x00, 0xe0, 0x00, 0xae, 0xf0, 0x10, 0x64, 0x00, + 0x68, 0xde, 0x9b, 0x00, 0x44, 0xc4, 0x02, 0x07, 0xd0, 0x03, 0x00, 0x04, + 0xbe, 0x01, 0xbc, 0x60, 0x2b, 0x12, 0xb7, 0xa2, 0x00, 0xe0, 0x5e, 0x00, + 0x0b, 0x37, 0xa3, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0d, 0x8d, 0x01, 0xbc, + 0x60, 0x23, 0x07, 0x97, 0x81, 0x00, 0xe0, 0x41, 0x83, 0x01, 0x70, 0x63, + 0x00, 0xe0, 0x41, 0x8f, 0x00, 0xb0, 0x65, 0x00, 0x02, 0x5e, 0x02, 0xf0, + 0x0d, 0x62, 0x01, 0xbc, 0x60, 0x23, 0x07, 0x50, 0x64, 0x01, 0xbc, 0x60, + 0x47, 0x00, 0x17, 0xa2, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0d, 0xb5, 0x00, + 0x68, 0x5e, 0x9b, 0x00, 0x44, 0xe0, 0x01, 0xa4, 0x60, 0x46, 0xf4, 0x71, + 0xe0, 0x00, 0x68, 0xde, 0x9b, 0x00, 0xc4, 0xd2, 0x01, 0xbc, 0x61, 0x13, + 0x00, 0xb7, 0xa1, 0x02, 0x06, 0x00, 0xf3, 0x00, 0x04, 0xcb, 0x01, 0xbc, + 0x60, 0x13, 0x00, 0xb7, 0xa1, 0x01, 0x92, 0xc2, 0x1a, 0xf4, 0x37, 0xa2, + 0x03, 0x29, 0x5e, 0x02, 0xf0, 0x04, 0xd0, 0x01, 0xbc, 0x60, 0x03, 0x00, + 0x11, 0xee, 0x00, 0x90, 0x42, 0xe7, 0x00, 0x91, 0xef, 0x01, 0x92, 0xe0, + 0x0e, 0xf4, 0x37, 0xa2, 0x00, 0xb0, 0x5e, 0x8b, 0x00, 0x11, 0xec, 0x03, + 0xbf, 0xde, 0x02, 0xf0, 0x04, 0xe0, 0x00, 0x68, 0x5e, 0x9b, 0x00, 0x64, + 0xd7, 0x00, 0x68, 0x5e, 0x9b, 0x00, 0xa4, 0xd7, 0x00, 0xb0, 0x50, 0x2f, + 0x00, 0x11, 0xe2, 0x00, 0xb0, 0x50, 0x33, 0x00, 0x11, 0xe2, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x04, 0xe0, 0x01, 0x87, 0x60, 0x02, 0x3d, 0x11, 0xe8, + 0x00, 0x68, 0xde, 0x9b, 0x00, 0xa4, 0xda, 0x01, 0x87, 0x60, 0x06, 0x3d, + 0x11, 0xe8, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x11, 0xea, 0x00, 0x90, 0x42, + 0xe7, 0x00, 0x91, 0xeb, 0x01, 0x92, 0xc2, 0x1b, 0x00, 0xb7, 0xa2, 0x01, + 0xb8, 0x5e, 0x8a, 0x3d, 0x11, 0xe8, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x04, + 0xe0, 0x01, 0x84, 0x60, 0x07, 0x00, 0x11, 0xe0, 0x01, 0xbc, 0x60, 0x03, + 0x00, 0x11, 0x2d, 0x00, 0xb0, 0x44, 0x83, 0x00, 0x14, 0x2c, 0x03, 0xa3, + 0xde, 0x02, 0xf0, 0x04, 0xf5, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x17, 0x8e, + 0x00, 0x68, 0x5e, 0x4b, 0x05, 0xa4, 0xe6, 0x02, 0x00, 0x50, 0x03, 0x00, + 0x04, 0xef, 0x01, 0x83, 0xe0, 0x06, 0x09, 0x10, 0x48, 0x00, 0xb0, 0x41, + 0x23, 0x00, 0x18, 0x00, 0x01, 0xbc, 0x60, 0x03, 0x04, 0xb7, 0x8e, 0x03, + 0xa9, 0x5e, 0x02, 0xf0, 0x04, 0xf4, 0x00, 0x68, 0x5e, 0x4b, 0x04, 0x24, + 0xf4, 0x01, 0xbc, 0x60, 0x03, 0x06, 0x37, 0x8e, 0x00, 0x68, 0x5e, 0x4b, + 0x05, 0xa4, 0xf4, 0x01, 0xbc, 0x60, 0x03, 0x06, 0xb7, 0x8e, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x04, 0xf4, 0x01, 0x81, 0x60, 0x06, 0xf5, 0x77, 0xab, + 0x00, 0xb0, 0x5e, 0x0f, 0x00, 0x17, 0x85, 0x00, 0x02, 0x5e, 0x02, 0xf0, + 0x0d, 0x4c, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x17, 0x8c, 0x01, 0xbc, 0x60, + 0x03, 0x00, 0x17, 0x8d, 0x03, 0x23, 0xde, 0x02, 0xf0, 0x04, 0xf6, 0x01, + 0x87, 0xe0, 0x06, 0x10, 0x70, 0x83, 0x01, 0x85, 0xe0, 0x02, 0xf5, 0xb7, + 0xad, 0x03, 0x29, 0x5e, 0x02, 0xf0, 0x05, 0x0a, 0x02, 0x03, 0x00, 0xc7, + 0x00, 0x05, 0x05, 0x00, 0xb0, 0x50, 0xcb, 0x00, 0x10, 0x65, 0x02, 0x82, + 0xd0, 0xc7, 0x00, 0x04, 0xfd, 0x00, 0xe0, 0x5a, 0x23, 0x00, 0x36, 0x88, + 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x04, 0xfe, 0x00, 0xe0, 0x5a, 0x27, 0x00, + 0x36, 0x89, 0x00, 0x68, 0x2c, 0x93, 0x00, 0x25, 0x05, 0x00, 0xe0, 0x5e, + 0xcb, 0x00, 0x37, 0xb2, 0x01, 0x0a, 0x5e, 0xcb, 0x00, 0x17, 0xa1, 0x00, + 0xe0, 0x50, 0xca, 0xf4, 0x30, 0x65, 0x00, 0xd0, 0x60, 0x06, 0xf6, 0x57, + 0xa2, 0x00, 0x20, 0x5a, 0x1a, 0xf4, 0x45, 0x05, 0x03, 0xbf, 0xde, 0x02, + 0xf0, 0x04, 0xff, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0f, 0x38, 0x03, 0xd5, + 0xde, 0x02, 0xf0, 0x0a, 0x56, 0x03, 0xd6, 0xde, 0x02, 0xf0, 0x0a, 0x6e, + 0x03, 0x50, 0xde, 0x02, 0xf0, 0x05, 0x05, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x05, 0x2c, 0x02, 0x05, 0x5e, 0xaf, 0x00, 0x05, 0x0c, 0x01, 0x87, 0xe0, + 0x06, 0x26, 0x71, 0x33, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x00, 0x02, 0x01, + 0x90, 0x60, 0x0a, 0x86, 0x34, 0x31, 0x02, 0x82, 0xd0, 0xc7, 0x00, 0x05, + 0x16, 0x01, 0x3c, 0x50, 0x27, 0x00, 0x17, 0x80, 0x01, 0x09, 0x50, 0x2b, + 0x00, 0x17, 0x81, 0x01, 0x07, 0x50, 0x07, 0x00, 0x17, 0xa1, 0x01, 0x82, + 0x5e, 0x86, 0xf0, 0x37, 0x81, 0x00, 0xb0, 0x50, 0x1f, 0x00, 0x10, 0x8a, + 0x00, 0xb0, 0x50, 0x0f, 0x00, 0x11, 0x16, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x05, 0x1c, 0x01, 0x38, 0x50, 0x5f, 0x00, 0x17, 0x80, 0x01, 0x0a, 0x50, + 0x2b, 0x00, 0x17, 0x81, 0x01, 0x07, 0xd0, 0x07, 0x00, 0x17, 0xa1, 0x01, + 0x82, 0x5e, 0x86, 0xf0, 0x37, 0x81, 0x00, 0xb0, 0x50, 0x23, 0x00, 0x10, + 0x8a, 0x00, 0xb0, 0x50, 0x5b, 0x00, 0x11, 0x16, 0x02, 0x03, 0x00, 0xc7, + 0x00, 0x05, 0x21, 0x02, 0x0c, 0xd0, 0x03, 0x00, 0x05, 0x21, 0x02, 0x08, + 0x5e, 0x07, 0x00, 0x05, 0x21, 0x01, 0x38, 0x54, 0x07, 0x00, 0x17, 0x80, + 0x00, 0xb0, 0x54, 0x27, 0x00, 0x10, 0x8a, 0x02, 0x80, 0x50, 0xc7, 0x00, + 0x05, 0x2a, 0x01, 0xbc, 0x60, 0x03, 0x05, 0xb7, 0x92, 0x03, 0xbf, 0xde, + 0x02, 0xf0, 0x02, 0xc1, 0x01, 0x90, 0x60, 0x06, 0x86, 0x34, 0x31, 0x02, + 0x03, 0x00, 0xc7, 0x00, 0x05, 0x0e, 0x02, 0x0c, 0xd0, 0x03, 0x00, 0x05, + 0x0e, 0x00, 0xb0, 0x00, 0x1f, 0x00, 0x17, 0xa1, 0x00, 0xe0, 0x5e, 0x86, + 0x80, 0x74, 0x1a, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x05, 0x0e, 0x01, 0xbc, + 0x60, 0x03, 0x06, 0x37, 0x92, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x02, 0xc1, + 0x02, 0x05, 0x5e, 0xff, 0x00, 0x05, 0x3b, 0x01, 0x85, 0x60, 0x02, 0xf7, + 0xf7, 0xbf, 0x03, 0x2b, 0xde, 0x02, 0xf0, 0x05, 0x3b, 0x02, 0x00, 0x00, + 0xf3, 0x00, 0x05, 0x32, 0x00, 0xe8, 0x00, 0x23, 0x00, 0x51, 0x42, 0x01, + 0xbc, 0x60, 0x0a, 0x28, 0x51, 0x42, 0x03, 0x94, 0x5e, 0x02, 0xf0, 0x05, + 0x37, 0x00, 0xb0, 0x05, 0x8b, 0x00, 0x10, 0x64, 0x00, 0x68, 0x58, 0x03, + 0x00, 0x05, 0x37, 0x00, 0xb0, 0x44, 0x67, 0x00, 0x11, 0x12, 0x00, 0xb0, + 0x58, 0x03, 0x00, 0x11, 0x15, 0x00, 0x68, 0x45, 0x1f, 0x00, 0x05, 0x3b, + 0x03, 0xa2, 0x5e, 0x02, 0xf0, 0x05, 0x3b, 0x01, 0x85, 0xe0, 0x06, 0xf5, + 0x77, 0xab, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0e, 0x7c, 0x02, 0x01, 0xc2, + 0xe3, 0x00, 0x05, 0x65, 0x02, 0x03, 0x00, 0xc7, 0x00, 0x05, 0x40, 0x00, + 0x68, 0x2c, 0x93, 0x00, 0x25, 0x50, 0x00, 0x6e, 0x42, 0x46, 0xf6, 0x45, + 0x50, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x05, 0x42, 0x00, 0x6e, 0x42, 0x47, + 0x00, 0x25, 0x50, 0x02, 0x03, 0x00, 0xc7, 0x00, 0x05, 0x4d, 0x03, 0x55, + 0xde, 0x02, 0xf0, 0x05, 0x42, 0x01, 0x80, 0x60, 0x02, 0x86, 0x14, 0x30, + 0x01, 0x38, 0x50, 0x83, 0x00, 0x17, 0xa1, 0x00, 0xb0, 0x50, 0xcb, 0x00, + 0x10, 0x65, 0x00, 0x6d, 0xda, 0x32, 0xf4, 0x2a, 0x56, 0x00, 0xa8, 0x41, + 0x23, 0x14, 0x10, 0x48, 0x01, 0x14, 0x00, 0x63, 0x00, 0x10, 0x65, 0x00, + 0xe0, 0x41, 0x97, 0x0e, 0xd0, 0x65, 0x00, 0xe0, 0x5a, 0x03, 0x00, 0x36, + 0x80, 0x01, 0xbc, 0x62, 0x1f, 0x00, 0x11, 0xe0, 0x03, 0xbf, 0xde, 0x02, + 0xf0, 0x00, 0x13, 0x01, 0x81, 0xe0, 0x06, 0x86, 0x34, 0x31, 0x01, 0x91, + 0x60, 0x0e, 0x84, 0xf4, 0x27, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x05, 0x65, + 0x01, 0x3c, 0x50, 0x67, 0x00, 0x17, 0xa1, 0x01, 0xac, 0x5e, 0x86, 0x17, + 0x50, 0xba, 0x01, 0xbc, 0x60, 0x03, 0x01, 0x90, 0xb8, 0x02, 0x03, 0x00, + 0xc7, 0x00, 0x05, 0x5f, 0x00, 0x68, 0xac, 0x93, 0x00, 0x25, 0x5a, 0x01, + 0x81, 0xe0, 0x02, 0x17, 0x10, 0xb8, 0x03, 0xd5, 0xde, 0x02, 0xf0, 0x0a, + 0x56, 0x03, 0xd6, 0xde, 0x02, 0xf0, 0x0a, 0x6e, 0x03, 0x50, 0xde, 0x02, + 0xf0, 0x05, 0x56, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x05, 0x65, 0x00, 0xe8, + 0x2c, 0x93, 0x00, 0x2b, 0x24, 0x00, 0xb0, 0x5e, 0xcb, 0x00, 0x10, 0xb5, + 0x00, 0xb0, 0x00, 0x63, 0x08, 0x70, 0xb4, 0x02, 0x83, 0x42, 0xd3, 0x00, + 0x05, 0x5d, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x05, 0x60, 0x01, 0x86, 0xe0, + 0x04, 0x03, 0x10, 0xa0, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x01, 0x8c, 0x03, + 0xd5, 0xde, 0x02, 0xf0, 0x0a, 0x56, 0x03, 0xd6, 0xde, 0x02, 0xf0, 0x0a, + 0x6e, 0x03, 0x50, 0xde, 0x02, 0xf0, 0x05, 0x61, 0x03, 0xbf, 0xde, 0x02, + 0xf0, 0x03, 0x3c, 0x01, 0xbc, 0x60, 0x03, 0x00, 0xf0, 0xa5, 0x01, 0x82, + 0xe0, 0x02, 0x09, 0x10, 0x48, 0x01, 0xbc, 0x62, 0x1f, 0x00, 0x11, 0xe0, + 0x01, 0xbc, 0x60, 0x03, 0x00, 0x11, 0xec, 0x01, 0xbc, 0x60, 0x0f, 0x00, + 0x11, 0xe8, 0x02, 0x85, 0x50, 0x0b, 0x00, 0x05, 0x6c, 0x01, 0x82, 0x60, + 0x02, 0x09, 0x10, 0x48, 0x02, 0x81, 0x81, 0xb3, 0x00, 0x05, 0x73, 0x03, + 0xa0, 0xde, 0x02, 0xf0, 0x05, 0x71, 0x03, 0xd5, 0xde, 0x02, 0xf0, 0x0a, + 0x56, 0x03, 0xd6, 0xde, 0x02, 0xf0, 0x0a, 0x6e, 0x03, 0x20, 0x5e, 0x02, + 0xf0, 0x05, 0x73, 0x01, 0x88, 0x60, 0x02, 0x09, 0x10, 0x48, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x00, 0x13, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x37, 0xa1, + 0x02, 0x00, 0x01, 0xb3, 0x00, 0x05, 0x81, 0x02, 0x04, 0x01, 0xb3, 0x00, + 0x05, 0x80, 0x00, 0xe9, 0x01, 0xbb, 0x00, 0x20, 0x6e, 0x00, 0xe8, 0x81, + 0xbf, 0x00, 0x00, 0x6f, 0x00, 0x68, 0x81, 0xbb, 0x00, 0x05, 0x80, 0x00, + 0x68, 0x81, 0xbf, 0x00, 0x05, 0x80, 0x02, 0x81, 0x81, 0xb3, 0x00, 0x05, + 0x7d, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x00, 0x6c, 0x03, 0xbf, 0xde, 0x02, + 0xf0, 0x05, 0xce, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x00, 0x6c, 0x00, 0x02, + 0x5e, 0x02, 0xf0, 0x0a, 0xe5, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x00, 0x13, + 0x01, 0xbc, 0x60, 0x03, 0x00, 0x17, 0xa1, 0x00, 0x02, 0x5e, 0x02, 0xf0, + 0x0c, 0x70, 0x02, 0x01, 0x01, 0xb3, 0x00, 0x05, 0x84, 0x03, 0xbf, 0xde, + 0x02, 0xf0, 0x00, 0x13, 0x03, 0xa3, 0xde, 0x02, 0xf0, 0x00, 0x13, 0x02, + 0x00, 0x50, 0xc7, 0x00, 0x05, 0x8d, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x10, + 0x80, 0x01, 0x82, 0x60, 0x06, 0x09, 0x10, 0x48, 0x01, 0x80, 0x60, 0x02, + 0x86, 0x34, 0x31, 0x01, 0x04, 0xc1, 0x07, 0x00, 0x17, 0xa1, 0x01, 0x83, + 0xde, 0x86, 0xf2, 0x97, 0x94, 0x00, 0xe0, 0x01, 0xcb, 0x00, 0x20, 0x72, + 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x01, 0xaf, 0x02, 0x01, 0x01, 0xb3, 0x00, + 0x05, 0x8f, 0x01, 0x87, 0xe0, 0x06, 0xf5, 0x77, 0xab, 0x00, 0xb0, 0x01, + 0x0b, 0x00, 0x17, 0xa1, 0x00, 0x6d, 0xde, 0x84, 0x08, 0x05, 0xce, 0x00, + 0xe8, 0x44, 0x64, 0x08, 0x77, 0xa1, 0x00, 0x6e, 0x5e, 0x84, 0x08, 0x25, + 0xce, 0x01, 0x87, 0xe0, 0x06, 0xf5, 0x77, 0xab, 0x02, 0x02, 0x00, 0xbf, + 0x00, 0x05, 0xa1, 0x02, 0x88, 0x81, 0xab, 0x00, 0x05, 0xa1, 0x02, 0x84, + 0x00, 0xc7, 0x00, 0x05, 0xa1, 0x01, 0x29, 0x50, 0x0b, 0x00, 0x17, 0xa1, + 0x00, 0x68, 0xde, 0x87, 0x02, 0x05, 0xa1, 0x02, 0x03, 0xc5, 0x73, 0x00, + 0x05, 0xa0, 0x02, 0x83, 0xde, 0xb3, 0x00, 0x05, 0xa0, 0x02, 0x82, 0xde, + 0xbb, 0x00, 0x05, 0x9d, 0x00, 0x68, 0x2a, 0xff, 0x00, 0x05, 0xa1, 0x00, + 0x6d, 0xde, 0x2f, 0x01, 0xe5, 0xa1, 0x01, 0x82, 0xe0, 0x06, 0xf7, 0xf7, + 0xbf, 0x00, 0xe0, 0x44, 0x65, 0x56, 0x0a, 0xaf, 0x03, 0xbf, 0xde, 0x02, + 0xf0, 0x00, 0x13, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x05, 0xce, 0x02, 0x82, + 0x5e, 0xaf, 0x00, 0x05, 0xb1, 0x01, 0x82, 0x60, 0x06, 0xf5, 0x77, 0xab, + 0x00, 0xb0, 0x44, 0x67, 0x00, 0x08, 0x22, 0x00, 0xb0, 0x01, 0x4b, 0x00, + 0x17, 0xa2, 0x02, 0x08, 0x42, 0x1b, 0x00, 0x05, 0xa8, 0x00, 0xb0, 0x01, + 0x6b, 0x00, 0x17, 0xa2, 0x00, 0x68, 0x5e, 0x8b, 0x00, 0x05, 0xae, 0x00, + 0x90, 0x45, 0x2b, 0x00, 0x97, 0xa1, 0x00, 0x80, 0xde, 0x86, 0xf4, 0x57, + 0xa1, 0x00, 0x6e, 0x20, 0xd2, 0x0d, 0xa5, 0xae, 0x00, 0xb0, 0x41, 0xb7, + 0x00, 0x08, 0x34, 0x00, 0xe0, 0x20, 0xd2, 0x23, 0x28, 0x35, 0x01, 0x85, + 0xe0, 0x02, 0xf5, 0xb7, 0xad, 0x02, 0x05, 0x5e, 0xaf, 0x00, 0x05, 0xb1, + 0x01, 0xbc, 0x61, 0x03, 0x00, 0x11, 0x33, 0x00, 0xe8, 0x44, 0x65, 0x04, + 0x57, 0xa5, 0x00, 0xb0, 0x44, 0x67, 0x00, 0x0b, 0xd8, 0x00, 0x6d, 0x5e, + 0x97, 0x01, 0x00, 0xad, 0x02, 0x02, 0x00, 0xbf, 0x00, 0x05, 0xc0, 0x00, + 0x68, 0xde, 0x4b, 0x06, 0xa5, 0xb7, 0x01, 0x84, 0xe0, 0x02, 0xf7, 0xf7, + 0xbf, 0x00, 0x68, 0xde, 0x4b, 0x04, 0x05, 0xba, 0x02, 0x82, 0xde, 0xb3, + 0x00, 0x05, 0xba, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x0b, 0x10, 0x02, 0x04, + 0x5e, 0xb3, 0x00, 0x05, 0xbd, 0x00, 0x68, 0xde, 0x4b, 0x06, 0x25, 0xbd, + 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x11, 0x2a, 0x00, 0x02, 0x5e, 0x02, 0xf0, + 0x0f, 0x39, 0x03, 0xa3, 0xde, 0x02, 0xf0, 0x05, 0xc0, 0x01, 0x83, 0xe0, + 0x02, 0xf5, 0x97, 0xac, 0x01, 0xbc, 0x60, 0x13, 0x14, 0x97, 0xa1, 0x00, + 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xce, 0x01, 0xbc, 0x63, 0x83, 0x00, 0x17, + 0xa1, 0x00, 0xa0, 0x40, 0x66, 0xf4, 0x37, 0xa2, 0x00, 0x68, 0xde, 0x8a, + 0xf4, 0x25, 0xcc, 0x01, 0xbc, 0x60, 0x13, 0x0e, 0x77, 0xa1, 0x00, 0x02, + 0x5e, 0x02, 0xf0, 0x00, 0xce, 0x00, 0xa0, 0x40, 0x67, 0x3f, 0xf7, 0xa2, + 0x00, 0x98, 0x5e, 0x8b, 0x00, 0x37, 0xa2, 0x00, 0x68, 0x5e, 0x8b, 0x00, + 0x05, 0xcb, 0x00, 0x68, 0xde, 0x8b, 0x0f, 0xe5, 0xcc, 0x01, 0xbc, 0x60, + 0x23, 0x00, 0x10, 0x43, 0x01, 0x82, 0x60, 0x02, 0xf5, 0x77, 0xab, 0x03, + 0xd1, 0x5e, 0x02, 0xf0, 0x00, 0x02, 0x02, 0x00, 0x50, 0xc3, 0x00, 0x06, + 0x1d, 0x03, 0x25, 0xde, 0x02, 0xf0, 0x05, 0xd2, 0x01, 0x83, 0x60, 0x06, + 0x84, 0xf4, 0x27, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x06, 0x04, 0x02, 0x0c, + 0xd0, 0x03, 0x00, 0x06, 0x02, 0x02, 0x03, 0x00, 0xc7, 0x00, 0x05, 0xf1, + 0x01, 0x14, 0x00, 0x63, 0x00, 0x17, 0xa1, 0x00, 0x6d, 0xde, 0x87, 0x00, + 0x86, 0x02, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x17, 0x80, 0x00, 0xb0, 0x50, + 0xcb, 0x00, 0x10, 0x65, 0x00, 0xb0, 0x50, 0xcf, 0x00, 0x10, 0x64, 0x01, + 0x81, 0x60, 0x06, 0x0d, 0x90, 0x6c, 0x01, 0x82, 0x60, 0x06, 0x86, 0x34, + 0x31, 0x00, 0xb0, 0x5a, 0x23, 0x00, 0x17, 0xa1, 0x01, 0xbc, 0x60, 0x03, + 0x00, 0x16, 0x88, 0x01, 0xbc, 0x5a, 0x2a, 0xf4, 0x37, 0xa1, 0x01, 0xbc, + 0x60, 0x03, 0x00, 0x16, 0x8a, 0x00, 0xb0, 0x5e, 0x87, 0x00, 0x14, 0x8f, + 0x00, 0xb0, 0x5a, 0x27, 0x00, 0x17, 0xa1, 0x01, 0xbc, 0x60, 0x03, 0x00, + 0x16, 0x89, 0x01, 0xbc, 0x5a, 0x2e, 0xf4, 0x37, 0xa1, 0x01, 0xbc, 0x60, + 0x03, 0x00, 0x16, 0x8b, 0x00, 0xb0, 0x5e, 0x87, 0x00, 0x14, 0x90, 0x00, + 0xb0, 0x5a, 0x1b, 0x00, 0x14, 0x8d, 0x00, 0xb0, 0x5a, 0x1f, 0x00, 0x14, + 0x8e, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x16, 0x04, 0x00, 0x68, 0xde, 0x03, + 0x00, 0x05, 0xee, 0x02, 0x03, 0x50, 0xc7, 0x00, 0x05, 0xed, 0x01, 0x00, + 0x50, 0x9f, 0x00, 0x17, 0x80, 0x01, 0x80, 0x5e, 0x02, 0x91, 0xb4, 0x8d, + 0x01, 0xbc, 0x5e, 0x02, 0x92, 0x14, 0x90, 0x01, 0xbc, 0x60, 0x03, 0x00, + 0x37, 0x80, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x12, 0x96, 0x00, 0xb0, 0x5e, + 0x03, 0x00, 0x14, 0x8c, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x05, 0xfd, 0x00, + 0x68, 0xc2, 0x47, 0x00, 0x05, 0xf6, 0x01, 0x81, 0xe0, 0x06, 0x86, 0x34, + 0x31, 0x01, 0x91, 0x60, 0x0e, 0x84, 0xf4, 0x27, 0x01, 0xbc, 0x60, 0x03, + 0x00, 0x14, 0x30, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x00, 0x02, 0x00, 0xb0, + 0x50, 0x9f, 0x00, 0x17, 0xa1, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x01, 0x8b, + 0x00, 0xb0, 0x5e, 0x87, 0x00, 0x14, 0x27, 0x01, 0x86, 0xe0, 0x04, 0x03, + 0x10, 0xa0, 0x00, 0xb0, 0x42, 0x83, 0x00, 0x18, 0x00, 0x01, 0x0c, 0xd0, + 0x03, 0x00, 0x17, 0xa1, 0x00, 0x68, 0xde, 0x87, 0x00, 0x65, 0xf1, 0x01, + 0x02, 0x50, 0xc7, 0x00, 0x17, 0xa1, 0x01, 0x80, 0x5e, 0x86, 0x84, 0xf4, + 0x27, 0x01, 0x8a, 0xe0, 0x0e, 0x84, 0xf4, 0x27, 0x00, 0xb0, 0x50, 0xbf, + 0x00, 0x14, 0x26, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x06, 0x04, 0x01, 0x86, + 0xe0, 0x04, 0x03, 0x10, 0xa0, 0x02, 0x00, 0x50, 0x9f, 0x00, 0x06, 0x04, + 0x02, 0x86, 0xc1, 0x07, 0x00, 0x06, 0x18, 0x03, 0x29, 0x5e, 0x02, 0xf0, + 0x06, 0x09, 0x00, 0xb0, 0x52, 0x33, 0x00, 0x14, 0x2d, 0x00, 0xb0, 0x52, + 0x37, 0x00, 0x17, 0xa1, 0x01, 0x9e, 0x5e, 0x86, 0x84, 0xf4, 0x27, 0x00, + 0xb0, 0x50, 0x9f, 0x00, 0x17, 0xa1, 0x01, 0x80, 0xde, 0x86, 0xf4, 0x37, + 0xa1, 0x00, 0xb0, 0x50, 0xbb, 0x00, 0x10, 0x8f, 0x00, 0xb0, 0x50, 0xb7, + 0x00, 0x10, 0x8e, 0x00, 0xb0, 0x50, 0x9b, 0x00, 0x10, 0x8d, 0x01, 0x80, + 0x60, 0x06, 0xf4, 0x30, 0x8c, 0x02, 0x02, 0x50, 0xc7, 0x00, 0x06, 0x17, + 0x00, 0xb0, 0x52, 0x43, 0x00, 0x10, 0x8f, 0x00, 0xb0, 0x52, 0x3f, 0x00, + 0x10, 0x8e, 0x00, 0xb0, 0x52, 0x3b, 0x00, 0x10, 0x8d, 0x01, 0x1a, 0x52, + 0x37, 0x00, 0x17, 0xa1, 0x01, 0x98, 0xde, 0x87, 0x04, 0x37, 0xa1, 0x01, + 0xb8, 0x5e, 0x86, 0x91, 0xb0, 0x8c, 0x01, 0x82, 0x60, 0x02, 0x86, 0x34, + 0x31, 0x01, 0x81, 0x60, 0x02, 0x0d, 0x90, 0x6c, 0x03, 0x25, 0xde, 0x02, + 0xf0, 0x06, 0x1b, 0x01, 0x9c, 0x60, 0x02, 0x84, 0xf4, 0x27, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x06, 0x1f, 0x02, 0x85, 0x50, 0x0b, 0x00, 0x06, 0x1d, + 0x00, 0xa8, 0x50, 0xc7, 0x0d, 0x14, 0x31, 0x01, 0xbc, 0x60, 0x03, 0x00, + 0x14, 0x30, 0x01, 0x81, 0x60, 0x02, 0xf5, 0xd7, 0xae, 0x01, 0x83, 0x60, + 0x02, 0x84, 0xf4, 0x27, 0x01, 0x85, 0xe0, 0x02, 0x09, 0x10, 0x48, 0x01, + 0xbc, 0x60, 0x03, 0x00, 0x14, 0x2e, 0x03, 0xa2, 0x5e, 0x02, 0xf0, 0x01, + 0xaf, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x00, 0x13, 0x03, 0x23, 0xde, 0x02, + 0xf0, 0x06, 0x8f, 0x03, 0xa3, 0x5e, 0x02, 0xf0, 0x06, 0x8f, 0x03, 0xa2, + 0xde, 0x02, 0xf0, 0x06, 0x8f, 0x01, 0x81, 0x60, 0x06, 0xf5, 0x77, 0xab, + 0x03, 0xaa, 0x5e, 0x02, 0xf0, 0x06, 0x8f, 0x01, 0x83, 0xe0, 0x02, 0x09, + 0x10, 0x48, 0x03, 0x51, 0xde, 0x02, 0xf0, 0x06, 0x47, 0x02, 0x04, 0x5e, + 0xb3, 0x00, 0x06, 0x34, 0x01, 0x84, 0x60, 0x02, 0xf5, 0x97, 0xac, 0x01, + 0x83, 0xe0, 0x02, 0x09, 0x10, 0x48, 0x00, 0xb0, 0x2b, 0x57, 0x00, 0x17, + 0xa1, 0x00, 0x6d, 0x2b, 0x06, 0xf4, 0x20, 0x02, 0x00, 0xe0, 0x02, 0x7b, + 0x00, 0x20, 0x9e, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x0a, 0xc1, 0x00, 0x02, + 0x5e, 0x02, 0xf0, 0x11, 0x2d, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x00, 0x02, + 0x02, 0x03, 0xde, 0xb3, 0x00, 0x06, 0x44, 0x01, 0x83, 0xe0, 0x02, 0xf5, + 0x97, 0xac, 0x00, 0xe0, 0x20, 0xe7, 0x00, 0x28, 0x39, 0x02, 0x01, 0x5e, + 0xbb, 0x00, 0x06, 0x44, 0x00, 0xb0, 0x2a, 0x9b, 0x00, 0x17, 0xa1, 0x00, + 0x6d, 0x20, 0xe6, 0xf4, 0x26, 0x3f, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x08, + 0x39, 0x00, 0xe0, 0x02, 0x7f, 0x00, 0x20, 0x9f, 0x03, 0xa9, 0x5e, 0x02, + 0xf0, 0x06, 0x42, 0x01, 0x91, 0x60, 0x1a, 0x84, 0xf4, 0x27, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x03, 0x00, 0x01, 0xbc, 0x63, 0xff, 0x1f, 0xf7, 0xa1, + 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0c, 0x70, 0x03, 0x29, 0x5e, 0x02, 0xf0, + 0x06, 0x44, 0x01, 0x91, 0x60, 0x1a, 0x84, 0xf4, 0x27, 0x03, 0xbf, 0xde, + 0x02, 0xf0, 0x06, 0x44, 0x00, 0xe0, 0x02, 0x6b, 0x00, 0x20, 0x9a, 0x01, + 0x80, 0xe0, 0x06, 0xf5, 0x77, 0xab, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x06, + 0x4c, 0x03, 0x01, 0xde, 0x02, 0xf0, 0x06, 0x4a, 0x00, 0x68, 0x5e, 0x4f, + 0x06, 0x26, 0x4a, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x17, 0xa8, 0x03, 0xa4, + 0x5e, 0x02, 0xf0, 0x06, 0x4c, 0x03, 0xc1, 0xde, 0x02, 0xf0, 0x06, 0x92, + 0x01, 0x84, 0x60, 0x02, 0x09, 0x10, 0x48, 0x02, 0x04, 0x00, 0xbf, 0x00, + 0x06, 0x51, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x11, 0x15, 0x01, 0x14, 0x00, + 0x63, 0x00, 0x17, 0xa1, 0x00, 0xe0, 0x66, 0x02, 0xf4, 0x30, 0x65, 0x00, + 0x02, 0x5e, 0x02, 0xf0, 0x0d, 0x51, 0x01, 0x82, 0x60, 0x02, 0x09, 0x10, + 0x48, 0x03, 0xa9, 0x5e, 0x02, 0xf0, 0x06, 0x6c, 0x00, 0x68, 0x5e, 0x3b, + 0x04, 0xa6, 0x5c, 0x01, 0xf0, 0xde, 0x17, 0x00, 0x37, 0x85, 0x00, 0xa0, + 0x5e, 0x16, 0xf0, 0x97, 0x85, 0x00, 0x68, 0x5e, 0x3b, 0x06, 0x26, 0x5c, + 0x02, 0x01, 0x50, 0x03, 0x00, 0x06, 0x5b, 0x02, 0x87, 0x80, 0xbf, 0x00, + 0x06, 0x5b, 0x01, 0x85, 0xe0, 0x06, 0x09, 0x10, 0x48, 0x02, 0x80, 0xd0, + 0x03, 0x00, 0x06, 0x6c, 0x00, 0xb0, 0x5e, 0x1b, 0x00, 0x17, 0xa3, 0x00, + 0xb0, 0x00, 0x8b, 0x00, 0x17, 0xa4, 0x02, 0x04, 0x00, 0xbf, 0x00, 0x06, + 0x62, 0x00, 0x6e, 0x41, 0x97, 0x30, 0x66, 0x62, 0x01, 0x18, 0x5a, 0x03, + 0x00, 0x17, 0xa3, 0x01, 0x1a, 0x5a, 0x03, 0x00, 0x17, 0xa4, 0x00, 0x68, + 0xc1, 0x83, 0x18, 0x06, 0x65, 0x00, 0xe0, 0x02, 0x93, 0x00, 0x20, 0xa4, + 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x06, 0x67, 0x00, 0x6d, 0x5e, 0x2e, 0xf4, + 0x86, 0x67, 0x01, 0x82, 0xe0, 0x06, 0x86, 0x34, 0x31, 0x00, 0xe0, 0x5e, + 0x33, 0x00, 0x37, 0x8c, 0x00, 0x68, 0xde, 0x32, 0xf4, 0x66, 0x6a, 0x00, + 0xb0, 0x5e, 0x0f, 0x00, 0x17, 0x85, 0x00, 0x6d, 0xde, 0x2e, 0xf4, 0x66, + 0x78, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x06, 0x8a, 0x00, 0xb0, 0x5e, 0x1f, + 0x00, 0x17, 0xa3, 0x00, 0xb0, 0x00, 0x8f, 0x00, 0x17, 0xa4, 0x02, 0x04, + 0x00, 0xbf, 0x00, 0x06, 0x72, 0x00, 0x6e, 0x41, 0x97, 0x30, 0x66, 0x72, + 0x01, 0x1c, 0x5a, 0x03, 0x00, 0x17, 0xa3, 0x01, 0x1e, 0x5a, 0x03, 0x00, + 0x17, 0xa4, 0x00, 0x6d, 0x5e, 0x2e, 0xf4, 0x86, 0x74, 0x01, 0x82, 0xe0, + 0x06, 0x86, 0x34, 0x31, 0x00, 0xe0, 0x5e, 0x37, 0x00, 0x37, 0x8d, 0x00, + 0x68, 0xde, 0x36, 0xf4, 0x66, 0x77, 0x00, 0xb0, 0x5e, 0x0f, 0x00, 0x17, + 0x85, 0x00, 0x6d, 0x5e, 0x2e, 0xf4, 0x66, 0x8a, 0x01, 0x85, 0xe0, 0x02, + 0x09, 0x10, 0x48, 0x03, 0xd1, 0xde, 0x02, 0xf0, 0x06, 0x7a, 0x00, 0x68, + 0x5e, 0x4b, 0x04, 0x86, 0x84, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0d, 0x4c, + 0x00, 0x68, 0x41, 0x83, 0x18, 0x06, 0xae, 0x02, 0x03, 0x00, 0xc7, 0x00, + 0x06, 0x82, 0x02, 0x0c, 0xd0, 0x03, 0x00, 0x06, 0x82, 0x02, 0x83, 0x50, + 0xc7, 0x00, 0x06, 0x82, 0x00, 0x68, 0xde, 0x4b, 0x05, 0xa6, 0x82, 0x03, + 0xbf, 0xde, 0x02, 0xf0, 0x12, 0x14, 0x01, 0x81, 0xe0, 0x06, 0x86, 0x34, + 0x31, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x05, 0xce, 0x00, 0xb0, 0x50, 0x4f, + 0x00, 0x11, 0xf2, 0x00, 0xb0, 0x50, 0x53, 0x00, 0x11, 0xf3, 0x00, 0xb0, + 0x50, 0x57, 0x00, 0x11, 0xf4, 0x01, 0xbc, 0x60, 0x03, 0x01, 0x11, 0xf5, + 0x01, 0xbc, 0x60, 0x03, 0x00, 0x51, 0xf0, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x05, 0xce, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0d, 0x4c, 0x01, 0x81, 0x60, + 0x02, 0x09, 0x10, 0x48, 0x03, 0x29, 0x5e, 0x02, 0xf0, 0x06, 0x8f, 0x02, + 0x83, 0x00, 0xc7, 0x00, 0x12, 0x14, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x05, + 0xce, 0x03, 0xd1, 0xde, 0x02, 0xf0, 0x06, 0x90, 0x03, 0xa5, 0xde, 0x02, + 0xf0, 0x05, 0xce, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x00, 0x13, 0x02, 0x80, + 0x01, 0xb3, 0x00, 0x00, 0x13, 0x02, 0x06, 0x50, 0x03, 0x00, 0x06, 0x99, + 0x00, 0xb0, 0x01, 0x03, 0x00, 0x17, 0xa1, 0x00, 0x6d, 0x81, 0x0a, 0xf4, + 0x26, 0x99, 0x00, 0xe8, 0x44, 0x64, 0x08, 0x77, 0xa1, 0x00, 0x6e, 0x5e, + 0x84, 0x08, 0x26, 0x99, 0x01, 0x87, 0xe0, 0x06, 0xf5, 0x77, 0xab, 0x01, + 0x08, 0x5e, 0x4b, 0x00, 0x17, 0xa1, 0x00, 0x68, 0x5e, 0x87, 0x00, 0x26, + 0x9c, 0x00, 0xb0, 0x5e, 0x0f, 0x00, 0x17, 0x85, 0x00, 0x02, 0x5e, 0x02, + 0xf0, 0x0d, 0x4c, 0x00, 0x68, 0x5e, 0x3b, 0x06, 0x26, 0xa2, 0x01, 0xbc, + 0x60, 0x03, 0x00, 0x17, 0x8c, 0x02, 0x00, 0xd0, 0x03, 0x00, 0x06, 0xa7, + 0x01, 0xbc, 0x60, 0x03, 0x00, 0x17, 0x8d, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x06, 0xa7, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x17, 0x8c, 0x02, 0x03, 0x00, + 0xc7, 0x00, 0x01, 0xaf, 0x02, 0x0c, 0xd0, 0x03, 0x00, 0x01, 0xaf, 0x01, + 0x9c, 0x60, 0x02, 0x84, 0xf4, 0x27, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x01, + 0xaf, 0x00, 0x68, 0x41, 0x83, 0x18, 0x06, 0xad, 0x01, 0x80, 0x60, 0x06, + 0x84, 0xf4, 0x27, 0x03, 0x29, 0x5e, 0x02, 0xf0, 0x05, 0xce, 0x01, 0x82, + 0x60, 0x06, 0x86, 0x34, 0x31, 0x02, 0x83, 0x00, 0xc7, 0x00, 0x12, 0x14, + 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x05, 0xce, 0x00, 0xe0, 0x02, 0x97, 0x00, + 0x20, 0xa5, 0x01, 0x81, 0x60, 0x02, 0x09, 0x10, 0x48, 0x01, 0xbc, 0x60, + 0x03, 0x00, 0x08, 0x18, 0x00, 0xe0, 0x01, 0x7b, 0x00, 0xa0, 0x5e, 0x01, + 0xbc, 0x60, 0x13, 0x10, 0xd7, 0xa1, 0x00, 0x6d, 0x01, 0x7a, 0xf4, 0x20, + 0x13, 0x01, 0xbc, 0x60, 0x13, 0x09, 0x40, 0x5e, 0x03, 0xbf, 0xde, 0x02, + 0xf0, 0x00, 0x13, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0b, 0x22, 0x03, 0x38, + 0xde, 0x02, 0xf0, 0x00, 0x13, 0x03, 0x9e, 0xde, 0x02, 0xf0, 0x00, 0x13, + 0x00, 0xe8, 0x44, 0x4c, 0x00, 0xf7, 0xa1, 0x00, 0xe8, 0x5e, 0x84, 0x01, + 0x17, 0xa1, 0x00, 0x6a, 0xde, 0x84, 0x01, 0x06, 0xbe, 0x00, 0xe8, 0x5e, + 0x84, 0x01, 0x11, 0x87, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x11, 0x88, 0x01, + 0xa5, 0xe0, 0x22, 0x30, 0x11, 0x80, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x11, + 0x13, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x11, 0x14, 0x00, 0xb0, 0x44, 0x67, + 0x00, 0x17, 0xa1, 0x00, 0xb0, 0x44, 0x6b, 0x00, 0x17, 0xa2, 0x00, 0xb0, + 0x5e, 0x87, 0x00, 0x11, 0x04, 0x00, 0xb0, 0x5e, 0x8b, 0x00, 0x11, 0x05, + 0x03, 0xb8, 0xde, 0x02, 0xf0, 0x06, 0xc0, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x00, 0x13, 0x01, 0xbc, 0x60, 0x03, 0x04, 0xb7, 0x92, 0x01, 0xbc, 0x60, + 0x03, 0x04, 0x17, 0xa1, 0x01, 0xbc, 0x63, 0xff, 0x1f, 0xf0, 0xcb, 0x01, + 0xbc, 0x63, 0xff, 0x1f, 0xf0, 0xcc, 0x01, 0xbc, 0x63, 0xff, 0x1f, 0xf0, + 0xcd, 0x01, 0xbc, 0x63, 0xff, 0x1f, 0xf0, 0xce, 0x01, 0xbc, 0x63, 0xff, + 0x1f, 0xf0, 0xcf, 0x01, 0xbc, 0x63, 0xff, 0x1f, 0xf0, 0xd0, 0x00, 0xb0, + 0x52, 0x17, 0x00, 0x10, 0xe8, 0x01, 0xbc, 0x63, 0xff, 0x1f, 0xf0, 0xc8, + 0x00, 0xb0, 0x52, 0x1b, 0x00, 0x10, 0xe9, 0x01, 0xbc, 0x63, 0xff, 0x1f, + 0xf0, 0xc9, 0x00, 0xb0, 0x52, 0x1f, 0x00, 0x10, 0xea, 0x01, 0xbc, 0x63, + 0xff, 0x1f, 0xf0, 0xca, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x10, 0xe4, 0x02, + 0x86, 0x00, 0xc3, 0x00, 0x06, 0xe1, 0x00, 0xb0, 0x54, 0x0f, 0x00, 0x17, + 0xa2, 0x00, 0x69, 0xde, 0x8a, 0x90, 0x86, 0xd9, 0x00, 0xe8, 0x52, 0x12, + 0xf4, 0x50, 0xe4, 0x00, 0x68, 0xa0, 0x5f, 0x00, 0x06, 0xe1, 0x01, 0xbc, + 0x60, 0x03, 0x00, 0x10, 0xe4, 0x00, 0xb0, 0x54, 0x27, 0x00, 0x10, 0xe0, + 0x00, 0xb0, 0x54, 0x2f, 0x00, 0x10, 0xe1, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x06, 0xea, 0x03, 0xa4, 0xde, 0x02, 0xf0, 0x08, 0xc6, 0x03, 0xa9, 0xde, + 0x02, 0xf0, 0x08, 0xc6, 0x01, 0xbc, 0x60, 0x03, 0x01, 0xd7, 0xa1, 0x02, + 0x06, 0x00, 0xc3, 0x00, 0x06, 0xe3, 0x02, 0x80, 0xde, 0x5f, 0x00, 0x06, + 0xe8, 0x00, 0xb0, 0x54, 0x07, 0x00, 0x10, 0xe0, 0x00, 0x68, 0x20, 0x5f, + 0x00, 0x06, 0xe6, 0x01, 0xd2, 0xde, 0x86, 0xa0, 0x30, 0xe0, 0x00, 0xb0, + 0x54, 0x0b, 0x00, 0x10, 0xe1, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x06, 0xea, + 0x01, 0xbc, 0x5e, 0x86, 0x90, 0x10, 0xe0, 0x01, 0xbc, 0x60, 0x1f, 0x00, + 0x10, 0xe1, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x10, 0xe2, 0x00, 0xb0, 0x52, + 0x23, 0x00, 0x10, 0xe5, 0x01, 0xbc, 0x63, 0xff, 0x1f, 0xf0, 0xc5, 0x00, + 0xb0, 0x52, 0x27, 0x00, 0x10, 0xe6, 0x01, 0xbc, 0x63, 0xff, 0x1f, 0xf0, + 0xc6, 0x00, 0xb0, 0x52, 0x2b, 0x00, 0x10, 0xe7, 0x01, 0xbc, 0x63, 0xff, + 0x1f, 0xf0, 0xc7, 0x00, 0xb0, 0x00, 0x47, 0x00, 0x10, 0x86, 0x01, 0x08, + 0x20, 0x5f, 0x00, 0x17, 0x81, 0x01, 0x38, 0x52, 0x03, 0x00, 0x17, 0x80, + 0x01, 0x02, 0xc0, 0x27, 0x00, 0x17, 0xa6, 0x00, 0x02, 0x5e, 0x02, 0xf0, + 0x11, 0xad, 0x00, 0x68, 0x20, 0x5f, 0x00, 0x46, 0xf8, 0x00, 0xb0, 0x54, + 0x07, 0x00, 0x17, 0x80, 0x02, 0x81, 0x81, 0xb3, 0x00, 0x06, 0xfa, 0x00, + 0x02, 0x5e, 0x02, 0xf0, 0x0d, 0x32, 0x00, 0x68, 0x20, 0x5f, 0x00, 0x27, + 0x02, 0x00, 0x68, 0xa0, 0x5f, 0x00, 0x06, 0xfd, 0x02, 0x1a, 0x54, 0x07, + 0x00, 0x07, 0x02, 0x00, 0x68, 0x00, 0xa7, 0x01, 0x07, 0x00, 0x01, 0x03, + 0xc0, 0x27, 0x00, 0x17, 0xa1, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x07, 0x01, + 0x01, 0x06, 0xc0, 0x3b, 0x00, 0x17, 0xa1, 0x01, 0x82, 0x5e, 0x86, 0x10, + 0xd0, 0x86, 0x03, 0xa9, 0xde, 0x02, 0xf0, 0x09, 0x21, 0x00, 0x68, 0x5e, + 0x4f, 0x04, 0x27, 0x14, 0x01, 0xbc, 0x63, 0xff, 0x1f, 0xf0, 0xc3, 0x00, + 0x68, 0x5e, 0x4f, 0x05, 0xa7, 0x0a, 0x01, 0xbc, 0x60, 0x03, 0x1a, 0x90, + 0xe3, 0x01, 0xbc, 0x60, 0x03, 0x06, 0xb7, 0x92, 0x00, 0x68, 0x5e, 0x4f, + 0x05, 0x27, 0x14, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x07, 0x0e, 0x01, 0xbc, + 0x60, 0x03, 0x06, 0x37, 0x92, 0x02, 0x98, 0x44, 0x07, 0x00, 0x09, 0xef, + 0x02, 0x80, 0x46, 0x07, 0x00, 0x09, 0xef, 0x01, 0xbc, 0x60, 0x03, 0x18, + 0x90, 0xe3, 0x00, 0xb0, 0x20, 0x5f, 0x00, 0x17, 0x81, 0x00, 0x02, 0x5e, + 0x02, 0xf0, 0x0d, 0x3f, 0x00, 0xe8, 0x5e, 0x84, 0x00, 0xd7, 0xa1, 0x00, + 0x6a, 0x5e, 0x86, 0x90, 0x87, 0x14, 0x00, 0xe8, 0x52, 0x12, 0xf4, 0x30, + 0xe4, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x07, 0x17, 0x01, 0xbc, 0x60, 0x03, + 0x00, 0x10, 0xe4, 0x03, 0x38, 0xde, 0x02, 0xf0, 0x07, 0x17, 0x01, 0x87, + 0xe0, 0x06, 0x1c, 0x90, 0xe4, 0x01, 0x90, 0x60, 0x0a, 0x09, 0x10, 0x48, + 0x01, 0xbc, 0x61, 0x03, 0x04, 0x37, 0x91, 0x00, 0x68, 0x5e, 0x4f, 0x05, + 0xa9, 0xef, 0x03, 0x83, 0x5e, 0x02, 0xf0, 0x08, 0xc6, 0x03, 0xbf, 0xde, + 0x02, 0xf0, 0x00, 0x02, 0x01, 0x86, 0x60, 0x02, 0xf7, 0xf7, 0xbf, 0x01, + 0x82, 0xe0, 0x02, 0xf5, 0xb7, 0xad, 0x01, 0x85, 0xe0, 0x02, 0xf5, 0xb7, + 0xad, 0x02, 0x04, 0x41, 0x63, 0x00, 0x07, 0x27, 0x01, 0x84, 0x60, 0x02, + 0x0b, 0x10, 0x58, 0x02, 0x05, 0x5e, 0xaf, 0x00, 0x07, 0x23, 0x01, 0x87, + 0xe0, 0x06, 0x26, 0x71, 0x33, 0x02, 0x04, 0x00, 0xbf, 0x00, 0x07, 0x26, + 0x01, 0x85, 0xe0, 0x02, 0xf5, 0x77, 0xab, 0x00, 0x02, 0x5e, 0x02, 0xf0, + 0x0e, 0x7c, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x00, 0x02, 0x02, 0x83, 0xc0, + 0x37, 0x00, 0x07, 0x2f, 0x00, 0x6c, 0xc4, 0x65, 0x6c, 0x07, 0x30, 0x01, + 0xbc, 0x60, 0x1b, 0x1a, 0x77, 0xa1, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, + 0xce, 0x01, 0x80, 0xe0, 0x06, 0x03, 0x37, 0xa2, 0x00, 0x02, 0x5e, 0x02, + 0xf0, 0x00, 0xd4, 0x01, 0x80, 0xe0, 0x02, 0xf4, 0x57, 0xa2, 0x00, 0x02, + 0x5e, 0x02, 0xf0, 0x00, 0xd4, 0x00, 0xe0, 0x44, 0x65, 0x6c, 0x2b, 0x60, + 0x02, 0x85, 0xc5, 0x23, 0x00, 0x07, 0x36, 0x01, 0x84, 0x60, 0x06, 0x0b, + 0x10, 0x58, 0x02, 0x00, 0xde, 0xff, 0x00, 0x07, 0x36, 0x01, 0x80, 0xe0, + 0x02, 0xf7, 0xf7, 0xbf, 0x00, 0x68, 0x2b, 0x67, 0x00, 0x07, 0x36, 0x00, + 0xe0, 0x44, 0x65, 0x5b, 0x0a, 0xd9, 0x02, 0x05, 0x5e, 0xaf, 0x00, 0x07, + 0x38, 0x01, 0xbc, 0x61, 0x03, 0x00, 0x11, 0x33, 0x02, 0x05, 0x80, 0xbf, + 0x00, 0x07, 0x3e, 0x01, 0xbc, 0x60, 0x13, 0x11, 0x57, 0xa1, 0x00, 0x02, + 0x5e, 0x02, 0xf0, 0x00, 0xce, 0x01, 0x96, 0x60, 0x0e, 0x03, 0x30, 0x19, + 0x00, 0xb0, 0x40, 0x67, 0x00, 0x17, 0xa2, 0x00, 0x02, 0x5e, 0x02, 0xf0, + 0x00, 0xd4, 0x02, 0x83, 0xc0, 0x37, 0x00, 0x00, 0x13, 0x00, 0xe0, 0x02, + 0x1f, 0x00, 0x20, 0x87, 0x01, 0x82, 0x60, 0x06, 0x28, 0x91, 0x44, 0x03, + 0xbf, 0xde, 0x02, 0xf0, 0x00, 0x13, 0x02, 0x81, 0x40, 0x13, 0x00, 0x00, + 0x02, 0x02, 0x00, 0x42, 0x03, 0x00, 0x07, 0x45, 0x01, 0x84, 0x60, 0x02, + 0xf5, 0x97, 0xac, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x10, 0x80, 0x03, 0xa3, + 0xde, 0x02, 0xf0, 0x07, 0x48, 0x01, 0x90, 0x60, 0x02, 0x09, 0x10, 0x48, + 0x00, 0xb0, 0x44, 0x67, 0x00, 0x17, 0x9e, 0x00, 0xb0, 0x44, 0x6b, 0x00, + 0x17, 0x9d, 0x00, 0xb0, 0x44, 0x6f, 0x00, 0x17, 0x9c, 0x00, 0xb0, 0x44, + 0x73, 0x00, 0x17, 0x9b, 0x00, 0x68, 0xde, 0x7a, 0x23, 0x27, 0x48, 0x00, + 0xe0, 0x02, 0x23, 0x00, 0x20, 0x88, 0x01, 0x15, 0x40, 0x3b, 0x00, 0x17, + 0x97, 0x00, 0xb0, 0x01, 0x43, 0x00, 0x17, 0xa1, 0x01, 0xc9, 0xde, 0x84, + 0x05, 0x28, 0x05, 0x01, 0xbc, 0x60, 0x03, 0x10, 0x77, 0x95, 0x01, 0x91, + 0xe0, 0x02, 0x0d, 0x90, 0x6c, 0x02, 0x86, 0x40, 0x37, 0x00, 0x07, 0x56, + 0x00, 0xe0, 0x02, 0xbb, 0x00, 0x20, 0xae, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x0a, 0x97, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x14, 0x80, 0x01, 0xbc, 0x60, + 0x03, 0x00, 0x14, 0x81, 0x01, 0xb8, 0x60, 0x0a, 0x04, 0x90, 0x24, 0x01, + 0xbc, 0x60, 0x03, 0x04, 0x08, 0x2a, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x48, + 0x29, 0x01, 0xbc, 0x60, 0x03, 0x00, 0xd0, 0x2a, 0x01, 0xb3, 0x60, 0x07, + 0x00, 0x10, 0x04, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x08, 0x0e, 0x01, 0xbc, + 0x60, 0x03, 0x00, 0x08, 0x0f, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x08, 0x10, + 0x01, 0xbc, 0x60, 0x03, 0x00, 0x08, 0x11, 0x01, 0x83, 0xe0, 0x02, 0xf5, + 0xd7, 0xae, 0x02, 0x87, 0xc0, 0x37, 0x00, 0x0a, 0x93, 0x00, 0x02, 0x5e, + 0x02, 0xf0, 0x11, 0x8f, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0f, 0x38, 0x03, + 0x43, 0x5e, 0x02, 0xf0, 0x07, 0x62, 0x00, 0x6d, 0x40, 0x33, 0x00, 0xcb, + 0x03, 0x00, 0x68, 0x5e, 0x5f, 0x00, 0x47, 0x7a, 0x00, 0x68, 0x5e, 0x5f, + 0x00, 0x27, 0x77, 0x00, 0x68, 0x00, 0xa7, 0x00, 0xc7, 0x6c, 0x00, 0x68, + 0x00, 0xa7, 0x01, 0x07, 0x6c, 0x00, 0x68, 0x80, 0xa7, 0x00, 0xa7, 0x6d, + 0x00, 0xe0, 0x44, 0x66, 0x90, 0x28, 0x36, 0x01, 0xbc, 0x62, 0xc3, 0x00, + 0x17, 0xa1, 0x02, 0x80, 0x52, 0x03, 0x00, 0x07, 0x70, 0x01, 0x96, 0x52, + 0x03, 0x00, 0x17, 0xa1, 0x00, 0x80, 0xde, 0x86, 0x90, 0x37, 0x9a, 0x02, + 0x03, 0x52, 0x03, 0x00, 0x07, 0x75, 0x00, 0xe0, 0x5e, 0x6a, 0x90, 0x37, + 0x9a, 0x02, 0x07, 0xd2, 0x03, 0x00, 0x07, 0x75, 0x00, 0xe8, 0x5e, 0x6b, + 0x00, 0x37, 0x9a, 0x02, 0x9e, 0x5e, 0x6b, 0x00, 0x0b, 0x03, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x07, 0x7f, 0x01, 0x52, 0xd2, 0x03, 0x00, 0x17, 0xa1, + 0x01, 0x85, 0xd2, 0x06, 0xf4, 0x37, 0x9a, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x07, 0x7f, 0x01, 0x3c, 0x52, 0x03, 0x00, 0x17, 0xa1, 0x01, 0xbc, 0x52, + 0x06, 0xf4, 0x37, 0x9a, 0x00, 0x6e, 0x5e, 0x68, 0x0b, 0xab, 0x03, 0x00, + 0x68, 0x2f, 0xbf, 0x00, 0x07, 0x7f, 0x02, 0x8e, 0x52, 0x07, 0x00, 0x0b, + 0x03, 0x02, 0x04, 0xc0, 0x3b, 0x00, 0x07, 0x89, 0x01, 0x81, 0xe0, 0x06, + 0x0d, 0x90, 0x6c, 0x02, 0x87, 0x40, 0x37, 0x00, 0x0a, 0x97, 0x00, 0x02, + 0x5e, 0x02, 0xf0, 0x11, 0x8f, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0f, 0x38, + 0x02, 0x87, 0xc0, 0xaf, 0x00, 0x07, 0x81, 0x02, 0x87, 0xc0, 0xaf, 0x00, + 0x0a, 0x93, 0x01, 0x58, 0x40, 0xaf, 0x00, 0x17, 0x9a, 0x01, 0xbc, 0x60, + 0x3f, 0x1e, 0x17, 0xa1, 0x00, 0x6d, 0xde, 0x6a, 0xf4, 0x2a, 0x93, 0x03, + 0x5b, 0x5e, 0x02, 0xf0, 0x07, 0x8b, 0x01, 0xbc, 0x60, 0x13, 0x00, 0x10, + 0x43, 0x00, 0xb0, 0x41, 0x23, 0x28, 0x10, 0x48, 0x01, 0x80, 0x60, 0x02, + 0xf2, 0x97, 0x94, 0x01, 0x84, 0xe0, 0x02, 0x09, 0x10, 0x48, 0x01, 0x58, + 0x40, 0xaf, 0x00, 0x10, 0x2a, 0x00, 0x68, 0x40, 0xab, 0x00, 0x2a, 0x93, + 0x01, 0xbb, 0x5e, 0x56, 0x00, 0x90, 0x04, 0x02, 0x03, 0x5e, 0x57, 0x00, + 0x07, 0x9a, 0x02, 0x00, 0x47, 0xa3, 0x00, 0x07, 0x97, 0x01, 0xbc, 0x62, + 0x1e, 0x3c, 0x11, 0xe0, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x11, 0xea, 0x00, + 0xb0, 0x5e, 0x6b, 0x00, 0x11, 0xeb, 0x01, 0x98, 0x60, 0x1e, 0x3d, 0x11, + 0xe8, 0x02, 0x00, 0x47, 0xb3, 0x00, 0x07, 0x9a, 0x00, 0xb0, 0x5e, 0x6b, + 0x00, 0x11, 0xef, 0x01, 0xb0, 0xe0, 0xce, 0x3d, 0x91, 0xec, 0x03, 0x83, + 0x5e, 0x02, 0xf0, 0x07, 0x9e, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x11, 0x8f, + 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0f, 0x38, 0x00, 0x6d, 0x40, 0x33, 0x04, + 0xc7, 0x9a, 0x01, 0x83, 0x60, 0x02, 0x0d, 0x90, 0x6c, 0x02, 0x02, 0x00, + 0xf3, 0x00, 0x07, 0xa6, 0x03, 0xaa, 0xde, 0x02, 0xf0, 0x07, 0xa8, 0x02, + 0x80, 0x52, 0x17, 0x00, 0x07, 0xa8, 0x00, 0xe0, 0x41, 0x87, 0x00, 0xb0, + 0x65, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0c, 0x80, 0x02, 0x00, 0xc0, 0x77, + 0x00, 0x07, 0xa6, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x07, 0xa7, 0x03, 0x30, + 0x5e, 0x02, 0xf0, 0x07, 0xa8, 0x01, 0x83, 0x60, 0x06, 0x0d, 0x90, 0x6c, + 0x01, 0xbc, 0x60, 0x03, 0x00, 0x08, 0x02, 0x01, 0x88, 0xe0, 0x0f, 0x00, + 0x08, 0x03, 0x00, 0x6d, 0x40, 0x33, 0x02, 0x08, 0xc0, 0x01, 0x29, 0x52, + 0x0f, 0x00, 0x17, 0x93, 0x01, 0x09, 0x52, 0x0f, 0x00, 0x17, 0xaa, 0x01, + 0x96, 0x60, 0x02, 0xf2, 0x97, 0x94, 0x00, 0xe0, 0x41, 0x87, 0x01, 0xf0, + 0x65, 0x01, 0xbc, 0x60, 0x0f, 0x00, 0x17, 0xa1, 0x00, 0x28, 0xde, 0x86, + 0x90, 0x67, 0xb4, 0x01, 0x86, 0x60, 0x06, 0xf2, 0x97, 0x94, 0x00, 0xe0, + 0x41, 0x97, 0x00, 0x70, 0x65, 0x00, 0xe0, 0x20, 0xab, 0x00, 0xc8, 0x2a, + 0x01, 0x06, 0x5e, 0x53, 0x00, 0x17, 0xa2, 0x00, 0xa0, 0x5e, 0x4f, 0x04, + 0x77, 0xa1, 0x00, 0x68, 0xde, 0x87, 0x04, 0x47, 0xc2, 0x01, 0x86, 0xe0, + 0x06, 0xf2, 0x97, 0x94, 0x00, 0xb8, 0x5e, 0x8b, 0x00, 0x37, 0xa2, 0x00, + 0xb0, 0x5a, 0x03, 0x00, 0x17, 0xa0, 0x02, 0x0a, 0xda, 0x03, 0x00, 0x07, + 0xbc, 0x01, 0x87, 0x60, 0x06, 0xf2, 0x97, 0x94, 0x02, 0x84, 0xc0, 0x3b, + 0x00, 0x07, 0xc2, 0x02, 0x03, 0xda, 0x03, 0x00, 0x07, 0xc2, 0x03, 0xab, + 0x5e, 0x02, 0xf0, 0x07, 0xc0, 0x02, 0x04, 0x41, 0x07, 0x00, 0x07, 0xc2, + 0x01, 0x80, 0x60, 0x05, 0x00, 0x68, 0x03, 0x01, 0x06, 0x5e, 0x53, 0x00, + 0x17, 0xa2, 0x01, 0x82, 0xde, 0x8a, 0x00, 0x90, 0x04, 0x03, 0xaa, 0xde, + 0x02, 0xf0, 0x07, 0xf1, 0x03, 0xab, 0x5e, 0x02, 0xf0, 0x07, 0xdd, 0x02, + 0x87, 0xd2, 0x13, 0x00, 0x07, 0xf1, 0x00, 0xb0, 0x52, 0x13, 0x00, 0x11, + 0x86, 0x01, 0xa5, 0xe0, 0x0a, 0x30, 0x11, 0x80, 0x01, 0x84, 0x60, 0x02, + 0x0d, 0x90, 0x6c, 0x01, 0xbc, 0x63, 0xff, 0x1f, 0xf7, 0x99, 0x00, 0xe0, + 0x41, 0x87, 0x01, 0x70, 0x65, 0x00, 0x68, 0xde, 0xab, 0x00, 0x27, 0xcf, + 0x00, 0xa0, 0x5e, 0x4f, 0xff, 0x77, 0xa1, 0x00, 0x68, 0xde, 0x87, 0x07, + 0x27, 0xdb, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x07, 0xd1, 0x02, 0x84, 0x52, + 0x0f, 0x00, 0x07, 0xdb, 0x02, 0x04, 0xd2, 0x0f, 0x00, 0x07, 0xd4, 0x03, + 0xb1, 0x5e, 0x02, 0xf0, 0x07, 0xda, 0x00, 0xe0, 0x41, 0x87, 0x01, 0x10, + 0x65, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x07, 0xd5, 0x03, 0xb3, 0x5e, 0x02, + 0xf0, 0x07, 0xda, 0x02, 0x00, 0x80, 0xf3, 0x00, 0x07, 0xdb, 0x02, 0x00, + 0x52, 0x17, 0x00, 0x07, 0xdb, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0c, 0x80, + 0x02, 0x00, 0xc0, 0x77, 0x00, 0x07, 0xdb, 0x01, 0x29, 0x40, 0x77, 0x00, + 0x17, 0x99, 0x01, 0x84, 0x60, 0x06, 0x0d, 0x90, 0x6c, 0x02, 0x00, 0x52, + 0x17, 0x00, 0x07, 0xf1, 0x03, 0x31, 0x5e, 0x02, 0xf0, 0x07, 0xf1, 0x01, + 0x86, 0x60, 0x02, 0x30, 0x11, 0x80, 0x01, 0x80, 0xe0, 0x01, 0x61, 0xcb, + 0x0e, 0x02, 0x00, 0x52, 0x17, 0x00, 0x07, 0xe1, 0x02, 0x02, 0xab, 0x47, + 0x00, 0x07, 0xec, 0x00, 0x68, 0xde, 0x5f, 0x00, 0x07, 0xec, 0x00, 0xb0, + 0x2b, 0xaf, 0x00, 0x17, 0xa1, 0x00, 0x68, 0x2a, 0xb3, 0x00, 0x07, 0xec, + 0x00, 0xb0, 0x2b, 0xab, 0x00, 0x17, 0xa2, 0x00, 0x6d, 0xaa, 0xb2, 0xf4, + 0x47, 0xec, 0x00, 0x68, 0xde, 0xab, 0x00, 0x47, 0xe8, 0x01, 0x84, 0xe0, + 0x06, 0xf7, 0xf7, 0xbf, 0x00, 0x68, 0xde, 0x4f, 0x02, 0x87, 0xec, 0x00, + 0x02, 0x5e, 0x02, 0xf0, 0x13, 0x15, 0x02, 0x06, 0xde, 0xff, 0x00, 0x07, + 0xec, 0x00, 0xe0, 0x2b, 0xdf, 0x00, 0x2a, 0xf7, 0x00, 0x68, 0xde, 0x5f, + 0x00, 0x07, 0xef, 0x00, 0x68, 0xde, 0xab, 0x00, 0x47, 0xef, 0x01, 0x80, + 0xe0, 0x05, 0x61, 0xcb, 0x0e, 0x00, 0x68, 0x2b, 0x67, 0x00, 0x07, 0xf1, + 0x01, 0x80, 0xe0, 0x06, 0xf7, 0xf7, 0xbf, 0x02, 0x07, 0x52, 0x0f, 0x00, + 0x08, 0x71, 0x02, 0x80, 0x47, 0xa3, 0x00, 0x08, 0x6e, 0x02, 0x80, 0x47, + 0xb3, 0x00, 0x08, 0x6e, 0x00, 0xe0, 0x20, 0xab, 0x00, 0x88, 0x2a, 0x00, + 0xe8, 0x20, 0xa7, 0x00, 0x88, 0x29, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x11, + 0xe4, 0x01, 0xbc, 0x63, 0xff, 0x1f, 0xf7, 0xa5, 0x01, 0xbc, 0x60, 0x03, + 0x03, 0xd1, 0xe1, 0x02, 0x06, 0x5e, 0x53, 0x00, 0x07, 0xfb, 0x01, 0xbc, + 0x60, 0x03, 0x04, 0x91, 0xe1, 0x02, 0x06, 0xde, 0x53, 0x00, 0x07, 0xff, + 0x00, 0xe0, 0x47, 0x87, 0x00, 0x51, 0xe1, 0x02, 0x07, 0xd2, 0x0f, 0x00, + 0x07, 0xff, 0x00, 0xe0, 0x47, 0x87, 0x00, 0x91, 0xe1, 0x00, 0x6d, 0x40, + 0x33, 0x02, 0xc8, 0xc0, 0x00, 0x68, 0x5e, 0x4f, 0x05, 0x88, 0x02, 0x00, + 0x68, 0xde, 0xab, 0x00, 0x48, 0x71, 0x03, 0xab, 0x5e, 0x02, 0xf0, 0x08, + 0x05, 0x02, 0x00, 0x52, 0x17, 0x00, 0x08, 0x71, 0x02, 0x05, 0x80, 0xf3, + 0x00, 0x08, 0x10, 0x00, 0xe0, 0x41, 0x87, 0x01, 0x10, 0x65, 0x02, 0x02, + 0x00, 0xf3, 0x00, 0x08, 0x09, 0x02, 0x04, 0xd2, 0x0f, 0x00, 0x08, 0x09, + 0x00, 0xe0, 0x41, 0x87, 0x00, 0xb0, 0x65, 0x00, 0x02, 0x5e, 0x02, 0xf0, + 0x0c, 0x80, 0x02, 0x00, 0xc0, 0x77, 0x00, 0x08, 0x0d, 0x01, 0x29, 0x40, + 0x77, 0x00, 0x17, 0xa5, 0x00, 0xe0, 0x5e, 0x97, 0x00, 0x97, 0xa5, 0x00, + 0x68, 0xde, 0x97, 0xff, 0xe8, 0x10, 0x02, 0x80, 0x52, 0x17, 0x00, 0x08, + 0x71, 0x02, 0x07, 0x00, 0xbf, 0x00, 0x08, 0x71, 0x01, 0xbc, 0x60, 0x1f, + 0x14, 0x17, 0xa2, 0x00, 0x90, 0x47, 0x87, 0x00, 0x30, 0x65, 0x00, 0xe0, + 0x41, 0x96, 0xf4, 0x50, 0x65, 0x00, 0xe0, 0x47, 0x87, 0x01, 0x08, 0x20, + 0x03, 0x83, 0x5e, 0x02, 0xf0, 0x08, 0x18, 0x00, 0x02, 0x5e, 0x02, 0xf0, + 0x11, 0x8f, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0f, 0x38, 0x00, 0x6d, 0x40, + 0x31, 0x04, 0x08, 0x14, 0x00, 0x6d, 0x40, 0x31, 0x04, 0x08, 0xc0, 0x01, + 0xbc, 0x60, 0x0b, 0x1d, 0x57, 0xa1, 0x00, 0x68, 0xde, 0x97, 0xff, 0xe8, + 0x28, 0x01, 0x0f, 0x5a, 0x07, 0x00, 0x17, 0xa5, 0x03, 0x1e, 0xde, 0x02, + 0xf0, 0x08, 0x28, 0x02, 0x00, 0x52, 0x17, 0x00, 0x08, 0x28, 0x03, 0x2c, + 0x5e, 0x02, 0xf0, 0x08, 0x71, 0x00, 0x68, 0x5e, 0x67, 0xff, 0xe8, 0x28, + 0x00, 0xe0, 0x5e, 0x67, 0x00, 0x97, 0x99, 0x00, 0xe0, 0x5e, 0x66, 0xf4, + 0x30, 0x64, 0x01, 0x2a, 0x58, 0x03, 0x00, 0x17, 0x99, 0x01, 0x00, 0xde, + 0x97, 0x00, 0x17, 0xa5, 0x00, 0xe0, 0x5e, 0x66, 0xf4, 0xb7, 0x99, 0x00, + 0xe0, 0x5e, 0x67, 0x00, 0x37, 0x99, 0x01, 0x15, 0x58, 0x03, 0x00, 0x17, + 0xa6, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x08, 0x38, 0x00, 0xe0, 0x5e, 0x96, + 0xf4, 0x30, 0x64, 0x01, 0x2a, 0x58, 0x03, 0x00, 0x17, 0x99, 0x02, 0x05, + 0x80, 0xf3, 0x00, 0x08, 0x37, 0x01, 0x82, 0xe0, 0x02, 0xf3, 0x37, 0x99, + 0x02, 0x00, 0x52, 0x17, 0x00, 0x08, 0x37, 0x01, 0x16, 0xd8, 0x03, 0x00, + 0x17, 0xa6, 0x01, 0x0f, 0x5a, 0x07, 0x00, 0x17, 0xa4, 0x01, 0x0c, 0xd8, + 0x03, 0x00, 0x17, 0xa1, 0x00, 0x68, 0xde, 0x92, 0xf4, 0x28, 0x33, 0x00, + 0xe0, 0x5e, 0x67, 0x02, 0x17, 0x99, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x08, + 0x3c, 0x01, 0x0d, 0xd8, 0x03, 0x00, 0x17, 0xa1, 0x00, 0x68, 0xde, 0x92, + 0xf4, 0x28, 0x71, 0x00, 0xe0, 0x5e, 0x67, 0x04, 0x17, 0x99, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x08, 0x3c, 0x01, 0x10, 0x58, 0x03, 0x00, 0x17, 0xa6, + 0x00, 0x68, 0xde, 0x9b, 0x00, 0xc8, 0x3c, 0x01, 0x81, 0xda, 0x03, 0x00, + 0x17, 0xa1, 0x00, 0xb8, 0x5e, 0x86, 0xc0, 0x17, 0xa1, 0x02, 0x81, 0xde, + 0x87, 0x00, 0x08, 0x71, 0x00, 0x88, 0x5e, 0x67, 0x00, 0x77, 0x80, 0x00, + 0xe0, 0x00, 0xae, 0xf0, 0x10, 0x64, 0x01, 0xaa, 0xde, 0x65, 0x00, 0x48, + 0x02, 0x00, 0x68, 0xde, 0x9b, 0x00, 0x48, 0x56, 0x02, 0x07, 0x81, 0x87, + 0x00, 0x08, 0x49, 0x00, 0x6d, 0xde, 0x03, 0x0c, 0x08, 0x49, 0x02, 0x85, + 0x52, 0x0f, 0x00, 0x08, 0x49, 0x02, 0x98, 0x52, 0x3b, 0x00, 0x08, 0x49, + 0x01, 0x81, 0xe0, 0x05, 0x00, 0x68, 0x03, 0x00, 0xe0, 0x5e, 0x00, 0x0b, + 0x37, 0xa3, 0x00, 0xe0, 0x5e, 0x8f, 0x00, 0x97, 0xa3, 0x00, 0xe0, 0x41, + 0x87, 0x00, 0x77, 0xa2, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0d, 0x8d, 0x00, + 0xe8, 0x20, 0xa7, 0x01, 0x08, 0x29, 0x01, 0xbc, 0x60, 0x23, 0x07, 0x97, + 0x81, 0x00, 0x88, 0x5e, 0x97, 0x00, 0x77, 0xa1, 0x00, 0xe8, 0x5e, 0x86, + 0xf4, 0xb0, 0x63, 0x01, 0xbc, 0x60, 0x07, 0x0e, 0x17, 0xa1, 0x00, 0xe0, + 0x41, 0x8e, 0xf4, 0x30, 0x63, 0x00, 0xb0, 0x56, 0x17, 0x00, 0x17, 0xa1, + 0x00, 0xb0, 0x56, 0x1b, 0x00, 0x17, 0xa2, 0x00, 0x68, 0xde, 0x86, 0xd0, + 0x48, 0x71, 0x00, 0x68, 0xde, 0x8a, 0xd0, 0x68, 0x71, 0x00, 0x02, 0x5e, + 0x02, 0xf0, 0x0d, 0x62, 0x01, 0xbc, 0x60, 0x23, 0x07, 0x50, 0x64, 0x01, + 0xbc, 0x62, 0x4f, 0x00, 0x17, 0xa2, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0d, + 0xb5, 0x00, 0x68, 0x5e, 0x9b, 0x00, 0x48, 0x6e, 0x01, 0xbc, 0x62, 0x1e, + 0xf4, 0x71, 0xe0, 0x00, 0x68, 0xde, 0x9b, 0x00, 0xc8, 0x61, 0x01, 0xbc, + 0x61, 0x13, 0x00, 0xb7, 0xa1, 0x02, 0x06, 0x00, 0xf3, 0x00, 0x08, 0x5d, + 0x01, 0xbc, 0x60, 0x13, 0x00, 0xb7, 0xa1, 0x01, 0xbc, 0x60, 0x03, 0x00, + 0x11, 0xee, 0x00, 0xb0, 0x5e, 0x6b, 0x00, 0x11, 0xef, 0x01, 0x92, 0xe0, + 0x0e, 0xf4, 0x31, 0xec, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x08, 0x6e, 0x00, + 0x68, 0x5e, 0x9b, 0x00, 0x68, 0x63, 0x00, 0x68, 0xde, 0x9b, 0x00, 0xa8, + 0x6e, 0x01, 0x98, 0x60, 0x06, 0x3d, 0x11, 0xe8, 0x00, 0xe0, 0x20, 0xab, + 0x00, 0x88, 0x2a, 0x00, 0xe8, 0x20, 0xa7, 0x00, 0x88, 0x29, 0x01, 0xbc, + 0x60, 0x03, 0x00, 0x11, 0xea, 0x00, 0x68, 0xde, 0x5f, 0x00, 0x48, 0x69, + 0x00, 0xb0, 0x5e, 0x6b, 0x00, 0x11, 0xeb, 0x01, 0x92, 0xde, 0x5e, 0x3d, + 0x11, 0xe8, 0x01, 0x87, 0x60, 0x02, 0x3d, 0x11, 0xe8, 0x00, 0x68, 0xde, + 0x9b, 0x00, 0xa8, 0x6d, 0x01, 0x87, 0x60, 0x06, 0x3d, 0x11, 0xe8, 0x01, + 0x98, 0x60, 0x16, 0x3d, 0x11, 0xe8, 0x01, 0x81, 0xe0, 0x05, 0x00, 0x48, + 0x02, 0x01, 0xaa, 0xde, 0x65, 0x00, 0x48, 0x02, 0x03, 0xbf, 0xde, 0x02, + 0xf0, 0x08, 0x76, 0x01, 0xbc, 0x62, 0x0f, 0x00, 0x11, 0xe0, 0x01, 0xbc, + 0x60, 0x03, 0x00, 0x11, 0xe4, 0x01, 0x81, 0xe0, 0x01, 0x00, 0x68, 0x03, + 0x01, 0xbc, 0x60, 0x0f, 0x00, 0x11, 0xe8, 0x01, 0xbc, 0x60, 0x03, 0x00, + 0x11, 0xec, 0x02, 0x00, 0x20, 0x0f, 0x00, 0x08, 0x7d, 0x00, 0xe0, 0x20, + 0xa6, 0xf3, 0x48, 0x29, 0x00, 0xb0, 0x20, 0xab, 0x00, 0x10, 0x25, 0x00, + 0xe8, 0x20, 0xa6, 0x04, 0xa8, 0x29, 0x00, 0x6a, 0xa0, 0xa7, 0x01, 0xc8, + 0x7d, 0x01, 0xb8, 0x60, 0x06, 0x04, 0x90, 0x24, 0x01, 0x82, 0xe0, 0x06, + 0xf2, 0x97, 0x94, 0x01, 0x88, 0x60, 0x0a, 0x00, 0x90, 0x04, 0x01, 0xbc, + 0x60, 0x03, 0x18, 0x77, 0x95, 0x03, 0xa0, 0xde, 0x02, 0xf0, 0x08, 0x8a, + 0x00, 0x68, 0x5e, 0x4f, 0x06, 0xa8, 0x8f, 0x01, 0x38, 0x52, 0x03, 0x00, + 0x17, 0x80, 0x00, 0xb0, 0x5e, 0x5f, 0x00, 0x17, 0x81, 0x02, 0x03, 0xde, + 0xb7, 0x00, 0x08, 0x89, 0x00, 0x68, 0x5e, 0x07, 0x00, 0x08, 0x88, 0x01, + 0xbc, 0x60, 0x03, 0x01, 0x77, 0x80, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x37, + 0x81, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x08, 0x89, 0x01, 0xbc, 0x60, 0x03, + 0x01, 0x57, 0x80, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xdb, 0x00, 0x68, + 0xde, 0xab, 0x00, 0x48, 0x8f, 0x00, 0xa0, 0x5e, 0x4f, 0x04, 0x77, 0xa1, + 0x00, 0x68, 0x5e, 0x87, 0x00, 0x4a, 0x3f, 0x00, 0x68, 0x5e, 0x87, 0x04, + 0x4a, 0x3f, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0c, 0x06, 0x03, 0x86, 0xde, + 0x02, 0xf0, 0x0a, 0x94, 0x02, 0x87, 0xc0, 0x37, 0x00, 0x0a, 0x93, 0x00, + 0x02, 0x5e, 0x02, 0xf0, 0x11, 0x8f, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0f, + 0x38, 0x03, 0x03, 0x5e, 0x02, 0xf0, 0x08, 0x8f, 0x03, 0xa9, 0xde, 0x02, + 0xf0, 0x08, 0x9b, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x11, 0x8f, 0x00, 0x02, + 0x5e, 0x02, 0xf0, 0x0f, 0x38, 0x02, 0x07, 0x40, 0x37, 0x00, 0x08, 0x95, + 0x03, 0x86, 0xde, 0x02, 0xf0, 0x0a, 0x94, 0x02, 0x87, 0xc0, 0x37, 0x00, + 0x0a, 0x93, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0c, 0x7d, 0x00, 0x6e, 0x40, + 0x30, 0x02, 0x08, 0xc6, 0x03, 0x01, 0xde, 0x02, 0xf0, 0x08, 0xc6, 0x00, + 0x68, 0xde, 0xab, 0x00, 0x08, 0xad, 0x03, 0x2b, 0x5e, 0x02, 0xf0, 0x08, + 0xa1, 0x00, 0xe0, 0x02, 0x2b, 0x00, 0x20, 0x8a, 0x03, 0xbf, 0xde, 0x02, + 0xf0, 0x08, 0xa5, 0x02, 0x80, 0x52, 0x17, 0x00, 0x08, 0xa4, 0x00, 0xe0, + 0x02, 0x43, 0x00, 0x20, 0x90, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x08, 0xa5, + 0x00, 0xe0, 0x02, 0x57, 0x00, 0x20, 0x95, 0x00, 0x68, 0x5e, 0x4f, 0x04, + 0x0b, 0x75, 0x00, 0x68, 0x5e, 0x4f, 0x02, 0x8b, 0x75, 0x00, 0x68, 0x5e, + 0x4f, 0x02, 0x09, 0xf6, 0x00, 0x68, 0x5e, 0x4f, 0x04, 0x8a, 0x38, 0x00, + 0x68, 0x5e, 0x4f, 0x05, 0x0b, 0xf7, 0x00, 0x68, 0x5e, 0x4f, 0x06, 0x0b, + 0xf7, 0x00, 0x68, 0x5e, 0x4f, 0x06, 0x8c, 0x00, 0x03, 0xbf, 0xde, 0x02, + 0xf0, 0x0c, 0x06, 0x00, 0x68, 0xde, 0xab, 0x00, 0x28, 0xbe, 0x03, 0x2b, + 0x5e, 0x02, 0xf0, 0x08, 0xb1, 0x00, 0xe0, 0x02, 0x2f, 0x00, 0x20, 0x8b, + 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x08, 0xb5, 0x02, 0x80, 0x52, 0x17, 0x00, + 0x08, 0xb4, 0x00, 0xe0, 0x02, 0x47, 0x00, 0x20, 0x91, 0x03, 0xbf, 0xde, + 0x02, 0xf0, 0x08, 0xb5, 0x00, 0xe0, 0x02, 0x5b, 0x00, 0x20, 0x96, 0x00, + 0x68, 0x5e, 0x4f, 0x06, 0xa9, 0xca, 0x00, 0x68, 0x5e, 0x4f, 0x04, 0x2c, + 0x1e, 0x00, 0x68, 0x5e, 0x4f, 0x04, 0xac, 0x1e, 0x00, 0x68, 0x5e, 0x4f, + 0x05, 0xaa, 0x45, 0x00, 0x68, 0x5e, 0x4f, 0x06, 0x29, 0xca, 0x00, 0x68, + 0x5e, 0x4f, 0x05, 0x2b, 0xf5, 0x00, 0xa0, 0x5e, 0x4f, 0xff, 0x77, 0xa1, + 0x00, 0x68, 0x5e, 0x87, 0x07, 0x2c, 0x11, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x09, 0xef, 0x00, 0xe0, 0x02, 0x13, 0x00, 0x20, 0x84, 0x03, 0xbf, 0xde, + 0x02, 0xf0, 0x09, 0xf3, 0x00, 0xe0, 0x02, 0x0f, 0x00, 0x20, 0x83, 0x01, + 0xbc, 0x60, 0x03, 0x00, 0x11, 0xec, 0x01, 0xbc, 0x60, 0x0f, 0x00, 0x11, + 0xe8, 0x02, 0x84, 0xc0, 0x3b, 0x00, 0x08, 0x71, 0x01, 0x84, 0xe0, 0x06, + 0x09, 0x10, 0x48, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x08, 0x71, 0x02, 0x00, + 0xc0, 0x93, 0x00, 0x00, 0x02, 0x03, 0xa3, 0x5e, 0x02, 0xf0, 0x08, 0xca, + 0x03, 0xc3, 0x5e, 0x02, 0xf0, 0x08, 0xc9, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x0a, 0xff, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x11, 0x8f, 0x00, 0x02, 0x5e, + 0x02, 0xf0, 0x0f, 0x38, 0x02, 0x07, 0xc0, 0xaf, 0x00, 0x08, 0xce, 0x02, + 0x07, 0x40, 0x37, 0x00, 0x08, 0xca, 0x01, 0x07, 0xc0, 0xaf, 0x00, 0x17, + 0xa1, 0x00, 0xb8, 0x5e, 0x87, 0x00, 0x37, 0xa1, 0x01, 0x82, 0x5e, 0x86, + 0x0d, 0x90, 0x6c, 0x00, 0xb0, 0x44, 0x7f, 0x00, 0x08, 0x04, 0x01, 0x83, + 0x60, 0x02, 0x09, 0x10, 0x48, 0x02, 0x87, 0xc0, 0x37, 0x00, 0x0a, 0x93, + 0x03, 0x86, 0xde, 0x02, 0xf0, 0x0a, 0x94, 0x00, 0x02, 0x5e, 0x02, 0xf0, + 0x11, 0x8f, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0f, 0x38, 0x03, 0x43, 0x5e, + 0x02, 0xf0, 0x08, 0xd3, 0x02, 0x87, 0xc0, 0x37, 0x00, 0x0a, 0x93, 0x02, + 0x00, 0x81, 0xb3, 0x00, 0x08, 0xf1, 0x01, 0x80, 0x60, 0x06, 0xf2, 0x97, + 0x94, 0x03, 0x01, 0xde, 0x02, 0xf0, 0x08, 0xf1, 0x01, 0x38, 0x52, 0x03, + 0x00, 0x17, 0x80, 0x00, 0xb0, 0x5e, 0x5f, 0x00, 0x17, 0xa4, 0x00, 0x02, + 0x5e, 0x02, 0xf0, 0x13, 0x08, 0x01, 0xbc, 0x60, 0x2f, 0x06, 0x57, 0xa4, + 0x00, 0xe0, 0x5e, 0x86, 0xf4, 0x90, 0x65, 0x00, 0xe0, 0x5a, 0x03, 0x00, + 0x36, 0x80, 0x03, 0xb0, 0x5e, 0x02, 0xf0, 0x08, 0xe5, 0x00, 0xe0, 0x02, + 0x07, 0x00, 0x20, 0x81, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x08, 0xe6, 0x00, + 0xe0, 0x02, 0x03, 0x00, 0x20, 0x80, 0x02, 0x84, 0x81, 0xb3, 0x00, 0x08, + 0xeb, 0x01, 0x84, 0xe0, 0x04, 0x0d, 0x80, 0x6c, 0x01, 0xbc, 0x60, 0x03, + 0x00, 0x00, 0x6e, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x00, 0x6f, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x08, 0xf0, 0x00, 0xe8, 0x52, 0x3a, 0xf7, 0xb7, 0xa1, + 0x00, 0xe8, 0x5e, 0x87, 0x02, 0x17, 0xa1, 0x00, 0x90, 0x5e, 0x87, 0x00, + 0x97, 0xa1, 0x00, 0xe1, 0x01, 0xba, 0xf4, 0x20, 0x6e, 0x00, 0xe0, 0x81, + 0xbf, 0x00, 0x00, 0x6f, 0x00, 0xb0, 0x52, 0x3b, 0x00, 0x17, 0xbd, 0x03, + 0x01, 0xde, 0x02, 0xf0, 0x09, 0x07, 0x02, 0x80, 0x81, 0xb3, 0x00, 0x08, + 0xf4, 0x03, 0x30, 0x5e, 0x02, 0xf0, 0x09, 0x07, 0x01, 0xbc, 0x60, 0x1b, + 0x1f, 0x50, 0x65, 0x00, 0xe0, 0x41, 0x94, 0xdf, 0x30, 0x65, 0x01, 0x2d, + 0x40, 0x6b, 0x00, 0x17, 0xa2, 0x00, 0x88, 0x5e, 0x8b, 0x01, 0x37, 0xa2, + 0x01, 0x38, 0x40, 0x2b, 0x00, 0x16, 0x80, 0x02, 0x88, 0x40, 0x27, 0x00, + 0x08, 0xfb, 0x01, 0x84, 0x60, 0x06, 0xd0, 0x16, 0x80, 0x00, 0xb0, 0x5a, + 0x02, 0xf4, 0x56, 0x80, 0x02, 0x05, 0xc0, 0x27, 0x00, 0x08, 0xfe, 0x01, + 0x87, 0xe0, 0x06, 0xd0, 0x16, 0x80, 0x01, 0xbc, 0x60, 0x1b, 0x0d, 0xd7, + 0xa1, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xce, 0x00, 0xb0, 0x40, 0x67, + 0x00, 0x16, 0x81, 0x01, 0xbc, 0x60, 0x1b, 0x0d, 0xf7, 0xa1, 0x00, 0x02, + 0x5e, 0x02, 0xf0, 0x00, 0xce, 0x00, 0xb0, 0x40, 0x67, 0x00, 0x16, 0x82, + 0x00, 0xe0, 0x1b, 0xe7, 0x00, 0x66, 0xf9, 0x00, 0x69, 0x1b, 0xe7, 0x01, + 0x89, 0x07, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x06, 0xf9, 0x02, 0x00, 0x81, + 0xb3, 0x00, 0x09, 0x09, 0x02, 0x05, 0x01, 0xb3, 0x00, 0x0b, 0x03, 0x02, + 0x80, 0x20, 0x0f, 0x00, 0x09, 0x0b, 0x00, 0x6e, 0x40, 0x30, 0x02, 0x09, + 0xc5, 0x03, 0x81, 0xde, 0x02, 0xf0, 0x09, 0x15, 0x00, 0xe0, 0x02, 0x17, + 0x00, 0x20, 0x85, 0x03, 0xa9, 0xde, 0x02, 0xf0, 0x09, 0x11, 0x01, 0x84, + 0xe0, 0x06, 0x09, 0x10, 0x48, 0x01, 0x80, 0xe0, 0x02, 0x09, 0x10, 0x48, + 0x01, 0x84, 0xe0, 0x02, 0xf7, 0xf7, 0xbf, 0x03, 0x86, 0xde, 0x02, 0xf0, + 0x0a, 0x94, 0x01, 0x80, 0x60, 0x05, 0x00, 0x48, 0x02, 0x01, 0x80, 0x60, + 0x06, 0xf2, 0x97, 0x94, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x09, 0x93, 0x01, + 0x83, 0x60, 0x02, 0xf7, 0xf7, 0xbf, 0x03, 0x86, 0xde, 0x02, 0xf0, 0x0a, + 0x94, 0x03, 0x2b, 0x5e, 0x02, 0xf0, 0x09, 0x3b, 0x03, 0xa9, 0xde, 0x02, + 0xf0, 0x09, 0x1e, 0x00, 0x68, 0xde, 0xab, 0x00, 0x49, 0x3b, 0x00, 0xb0, + 0x52, 0x3b, 0x00, 0x17, 0x9f, 0x00, 0xb0, 0x52, 0x3b, 0x00, 0x17, 0xbe, + 0x01, 0xbc, 0x60, 0x03, 0x00, 0x28, 0x0e, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x09, 0x3b, 0x02, 0x87, 0x5e, 0x53, 0x00, 0x09, 0x48, 0x03, 0xa0, 0xde, + 0x02, 0xf0, 0x09, 0x2a, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x06, 0xc6, 0x01, + 0x82, 0xe0, 0x06, 0x0d, 0x90, 0x6c, 0x01, 0x90, 0x60, 0x0a, 0x09, 0x10, + 0x48, 0x00, 0xb0, 0x52, 0x3b, 0x00, 0x17, 0x9f, 0x00, 0xb0, 0x52, 0x3b, + 0x00, 0x17, 0xbe, 0x01, 0x9e, 0x5e, 0x83, 0x00, 0xb0, 0xeb, 0x01, 0x06, + 0x52, 0x0f, 0x00, 0x17, 0xa1, 0x00, 0xb8, 0x5e, 0x87, 0x00, 0x37, 0xa1, + 0x01, 0x82, 0xde, 0x86, 0xf5, 0x77, 0xab, 0x01, 0xbc, 0x61, 0x03, 0x00, + 0x30, 0x80, 0x00, 0xe8, 0x52, 0x3a, 0xf3, 0xf7, 0xa2, 0x00, 0x6b, 0xd2, + 0x3a, 0xf3, 0xe9, 0x2d, 0x00, 0xe8, 0x5e, 0x7e, 0x91, 0xd7, 0xa2, 0x00, + 0x90, 0x5e, 0x8b, 0x00, 0x97, 0xa1, 0x01, 0xbc, 0x60, 0x23, 0x01, 0xd0, + 0x64, 0x00, 0x6b, 0x52, 0x3a, 0xf3, 0xe9, 0x38, 0x01, 0x18, 0x5e, 0x87, + 0x00, 0x17, 0xa2, 0x01, 0x0a, 0x5e, 0x87, 0x00, 0x17, 0xa3, 0x00, 0x88, + 0x60, 0x06, 0xf4, 0x57, 0xa2, 0x00, 0xe0, 0x41, 0x92, 0xf4, 0x70, 0x64, + 0x00, 0xb0, 0x58, 0x02, 0xf4, 0x56, 0x00, 0x00, 0x6b, 0xde, 0xfa, 0x91, + 0xc9, 0x3b, 0x00, 0xb0, 0x52, 0x3b, 0x00, 0x17, 0xbe, 0x03, 0xbf, 0xde, + 0x02, 0xf0, 0x09, 0x3b, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x11, 0xff, 0x00, + 0xb0, 0x20, 0x3b, 0x00, 0x28, 0x0e, 0x00, 0xb0, 0x52, 0x3b, 0x00, 0x17, + 0x9f, 0x03, 0x20, 0xde, 0x02, 0xf0, 0x09, 0x48, 0x02, 0x07, 0x5e, 0x53, + 0x00, 0x09, 0x3f, 0x01, 0x80, 0xe0, 0x02, 0x09, 0x10, 0x48, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x09, 0x48, 0x00, 0x68, 0xde, 0x5f, 0x00, 0x09, 0x45, + 0x02, 0x1a, 0x54, 0x07, 0x00, 0x09, 0x43, 0x01, 0x03, 0xc0, 0x27, 0x00, + 0x17, 0xa1, 0x01, 0x82, 0x5e, 0x86, 0x10, 0xd0, 0x86, 0x01, 0x02, 0xc0, + 0x27, 0x00, 0x17, 0xa1, 0x00, 0xe0, 0x42, 0x2a, 0xf4, 0x30, 0x8a, 0x01, + 0x80, 0xe0, 0x05, 0x00, 0x48, 0x02, 0x03, 0xa9, 0xde, 0x02, 0xf0, 0x09, + 0x48, 0x00, 0xb0, 0x5e, 0x47, 0x00, 0x10, 0x80, 0x01, 0x08, 0x5e, 0x4f, + 0x00, 0x17, 0xa1, 0x00, 0x68, 0x5e, 0x87, 0x00, 0x29, 0x67, 0x03, 0xab, + 0x5e, 0x02, 0xf0, 0x09, 0x6b, 0x02, 0x00, 0x52, 0x17, 0x00, 0x09, 0x59, + 0x00, 0x68, 0xde, 0xab, 0x00, 0x49, 0x4e, 0x00, 0xe0, 0x02, 0x53, 0x00, + 0x20, 0x94, 0x02, 0x86, 0x5e, 0x53, 0x00, 0x09, 0x93, 0x02, 0x84, 0x52, + 0x0f, 0x00, 0x0b, 0x03, 0x02, 0x84, 0xd2, 0x0f, 0x00, 0x09, 0x53, 0x03, + 0xac, 0x5e, 0x02, 0xf0, 0x09, 0x57, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x09, + 0x60, 0x03, 0x2c, 0x5e, 0x02, 0xf0, 0x09, 0x60, 0x00, 0x68, 0x5e, 0x4f, + 0x04, 0x09, 0x57, 0x01, 0x06, 0xd2, 0x0f, 0x00, 0x17, 0xa1, 0x01, 0x84, + 0x5e, 0x86, 0xf2, 0x97, 0x94, 0x00, 0x68, 0x5e, 0x4f, 0x02, 0x09, 0x93, + 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x09, 0x83, 0x03, 0x1e, 0xde, 0x02, 0xf0, + 0x09, 0x5d, 0x03, 0x31, 0x5e, 0x02, 0xf0, 0x09, 0x5d, 0x00, 0x68, 0xde, + 0xab, 0x00, 0x49, 0x5d, 0x01, 0x84, 0x60, 0x02, 0xf2, 0x97, 0x94, 0x00, + 0x68, 0xde, 0xab, 0x00, 0x49, 0x62, 0x00, 0xe0, 0x02, 0x3f, 0x00, 0x20, + 0x8f, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x09, 0x65, 0x00, 0x68, 0x5e, 0xab, + 0x00, 0x49, 0x65, 0x02, 0x80, 0x52, 0x2f, 0x00, 0x09, 0x93, 0x02, 0x02, + 0x41, 0x07, 0x00, 0x09, 0x65, 0x00, 0x68, 0x5e, 0x4f, 0x04, 0x09, 0x93, + 0x00, 0x68, 0x5e, 0x4f, 0x02, 0x89, 0x93, 0x02, 0x04, 0x41, 0x07, 0x00, + 0x0b, 0x03, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x09, 0x93, 0x03, 0x2b, 0x5e, + 0x02, 0xf0, 0x09, 0x93, 0x00, 0x68, 0x5e, 0x4f, 0x05, 0xa9, 0x83, 0x00, + 0x68, 0x5e, 0x4f, 0x05, 0x29, 0x83, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x09, + 0x93, 0x00, 0x68, 0xde, 0xab, 0x00, 0x49, 0x73, 0x01, 0xbc, 0x60, 0x03, + 0x00, 0x0a, 0xbb, 0x01, 0x82, 0x60, 0x02, 0xf5, 0xd7, 0xae, 0x02, 0x80, + 0x5e, 0xff, 0x00, 0x09, 0x71, 0x00, 0x68, 0x2b, 0x67, 0x00, 0x09, 0x73, + 0x00, 0xe0, 0x44, 0x65, 0x5b, 0x0a, 0xd9, 0x00, 0x68, 0x2b, 0x83, 0xff, + 0xc9, 0x73, 0x00, 0xe0, 0x2b, 0x83, 0x00, 0x2a, 0xe0, 0x02, 0x06, 0x5e, + 0x53, 0x00, 0x09, 0x76, 0x00, 0xe0, 0x02, 0x63, 0x00, 0x20, 0x98, 0x03, + 0xbf, 0xde, 0x02, 0xf0, 0x09, 0x93, 0x03, 0x23, 0xde, 0x02, 0xf0, 0x09, + 0x7e, 0x01, 0x29, 0x50, 0x0b, 0x00, 0x17, 0xa3, 0x00, 0x68, 0xde, 0x8f, + 0x05, 0x29, 0x7e, 0x01, 0x87, 0xe0, 0x02, 0x10, 0x70, 0x83, 0x01, 0x84, + 0x60, 0x02, 0x09, 0x10, 0x48, 0x00, 0xb0, 0x5e, 0x87, 0x00, 0x17, 0xa1, + 0x00, 0x6e, 0xe0, 0x03, 0x00, 0x29, 0x7d, 0x03, 0xd1, 0xde, 0x02, 0xf0, + 0x09, 0x7e, 0x00, 0x68, 0xde, 0xab, 0x00, 0x49, 0x80, 0x00, 0xe0, 0x02, + 0x27, 0x00, 0x20, 0x89, 0x00, 0x68, 0x5e, 0x4f, 0x00, 0x09, 0x93, 0x00, + 0x68, 0x5e, 0x4f, 0x01, 0x09, 0x93, 0x00, 0x68, 0x5e, 0x4f, 0x05, 0x89, + 0x93, 0x02, 0x80, 0x47, 0xc7, 0x00, 0x09, 0xc3, 0x03, 0x29, 0xde, 0x02, + 0xf0, 0x09, 0x89, 0x01, 0x02, 0xde, 0xaf, 0x00, 0x17, 0xa1, 0x01, 0x06, + 0x52, 0x0f, 0x00, 0x17, 0xa2, 0x00, 0x38, 0x5e, 0x86, 0xf4, 0x49, 0x93, + 0x01, 0x82, 0xde, 0x8a, 0xf5, 0x77, 0xab, 0x00, 0xb0, 0x52, 0x23, 0x00, + 0x11, 0xf2, 0x00, 0xb0, 0x52, 0x27, 0x00, 0x11, 0xf3, 0x00, 0xb0, 0x52, + 0x2b, 0x00, 0x11, 0xf4, 0x01, 0x06, 0x52, 0x0f, 0x00, 0x17, 0xa1, 0x00, + 0xe0, 0x5e, 0x87, 0x00, 0x31, 0xf5, 0x00, 0xb0, 0x00, 0x5b, 0x00, 0x11, + 0xf0, 0x00, 0xb0, 0x47, 0xc3, 0x00, 0x18, 0x00, 0x01, 0x34, 0xc7, 0xc7, + 0x00, 0x17, 0xa1, 0x00, 0x6e, 0xde, 0x84, 0x02, 0xa9, 0x93, 0x01, 0xbc, + 0x60, 0x03, 0x08, 0x10, 0x42, 0x02, 0x83, 0xc1, 0x07, 0x00, 0x09, 0x95, + 0x02, 0x80, 0x5e, 0x53, 0x00, 0x0b, 0x03, 0x00, 0xb0, 0x40, 0x33, 0x00, + 0x17, 0xa1, 0x01, 0x08, 0xa0, 0x0f, 0x00, 0x17, 0xa2, 0x00, 0x68, 0x5e, + 0x8b, 0x00, 0x69, 0x9d, 0x00, 0xe8, 0x40, 0x31, 0x05, 0x57, 0xa1, 0x02, + 0x81, 0x20, 0x0f, 0x00, 0x09, 0x9d, 0x00, 0xb0, 0x20, 0xab, 0x00, 0x17, + 0xa1, 0x02, 0x80, 0xa0, 0x0f, 0x00, 0x09, 0x9d, 0x00, 0xb0, 0x5e, 0x63, + 0x00, 0x17, 0xa1, 0x00, 0x6e, 0x5e, 0x84, 0x02, 0x09, 0xc5, 0x00, 0xb0, + 0x5e, 0x87, 0x00, 0x07, 0xfa, 0x01, 0x81, 0x60, 0x01, 0x00, 0x48, 0x02, + 0x02, 0x02, 0xc0, 0x13, 0x00, 0x09, 0xa3, 0x00, 0xe0, 0x5e, 0x84, 0x03, + 0x47, 0xfa, 0x01, 0x81, 0x60, 0x05, 0x00, 0x48, 0x02, 0x02, 0x01, 0x20, + 0x0f, 0x00, 0x09, 0xbe, 0x01, 0x03, 0x5e, 0x53, 0x00, 0x17, 0xa1, 0x01, + 0x87, 0xde, 0x85, 0x00, 0x48, 0x02, 0x03, 0x86, 0xde, 0x02, 0xf0, 0x0a, + 0x94, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x11, 0x8f, 0x00, 0x02, 0x5e, 0x02, + 0xf0, 0x0f, 0x38, 0x03, 0x85, 0x5e, 0x02, 0xf0, 0x09, 0xa6, 0x01, 0x8e, + 0x60, 0x02, 0x3d, 0x11, 0xe8, 0x01, 0x07, 0xc7, 0x83, 0x00, 0x17, 0xa1, + 0x01, 0x82, 0x5e, 0x85, 0x00, 0x48, 0x02, 0x02, 0x01, 0xa0, 0x0f, 0x00, + 0x09, 0xb0, 0x01, 0x03, 0xc7, 0x97, 0x00, 0x17, 0xa1, 0x01, 0x82, 0x5e, + 0x85, 0x00, 0x68, 0x03, 0x00, 0xb0, 0x20, 0x4b, 0x00, 0x17, 0xa1, 0x01, + 0x8e, 0x5e, 0x85, 0x00, 0x68, 0x03, 0x02, 0x07, 0xc0, 0xaf, 0x00, 0x0c, + 0x61, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x11, 0xec, 0x01, 0xbc, 0x60, 0x0f, + 0x00, 0x11, 0xe8, 0x01, 0x84, 0x60, 0x05, 0x00, 0x68, 0x03, 0x00, 0xb0, + 0x40, 0x27, 0x00, 0x07, 0xfc, 0x00, 0xb0, 0x40, 0x2b, 0x00, 0x07, 0xfd, + 0x00, 0xb0, 0x40, 0x6b, 0x00, 0x07, 0xfe, 0x00, 0xb0, 0x40, 0x6f, 0x00, + 0x07, 0xff, 0x01, 0x84, 0x60, 0x05, 0x00, 0x68, 0x03, 0x00, 0x02, 0x5e, + 0x02, 0xf0, 0x0c, 0x7d, 0x01, 0xbc, 0x63, 0xff, 0x1f, 0xd7, 0xa8, 0x00, + 0x02, 0x5e, 0x02, 0xf0, 0x0d, 0x51, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0c, + 0x61, 0x01, 0xa8, 0x60, 0x0a, 0x00, 0x90, 0x04, 0x02, 0x01, 0x20, 0x0f, + 0x00, 0x11, 0xea, 0x00, 0xa8, 0x40, 0x13, 0x00, 0x50, 0x04, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x06, 0x24, 0x00, 0xe0, 0x02, 0x87, 0x00, 0x20, 0xa1, + 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x09, 0xc6, 0x00, 0xe0, 0x02, 0x0b, 0x00, + 0x20, 0x82, 0x03, 0xa9, 0xde, 0x02, 0xf0, 0x0b, 0x03, 0x01, 0x84, 0x60, + 0x06, 0x09, 0x10, 0x48, 0x01, 0x84, 0xe0, 0x06, 0x09, 0x10, 0x48, 0x03, + 0xbf, 0xde, 0x02, 0xf0, 0x0b, 0x03, 0x03, 0x2b, 0x5e, 0x02, 0xf0, 0x09, + 0xe7, 0x00, 0x68, 0xde, 0x4f, 0x06, 0xa9, 0xce, 0x00, 0xe0, 0x02, 0x3b, + 0x00, 0x20, 0x8e, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x09, 0xcf, 0x00, 0xe0, + 0x02, 0x37, 0x00, 0x20, 0x8d, 0x03, 0x23, 0xde, 0x02, 0xf0, 0x09, 0xef, + 0x00, 0x68, 0xde, 0x4e, 0xf1, 0xc9, 0xef, 0x01, 0x87, 0xe0, 0x02, 0x10, + 0x70, 0x83, 0x01, 0x84, 0x60, 0x02, 0x09, 0x10, 0x48, 0x00, 0xb0, 0x5e, + 0x87, 0x00, 0x17, 0xa1, 0x00, 0x6e, 0xe0, 0x03, 0x00, 0x29, 0xd5, 0x03, + 0xd1, 0xde, 0x02, 0xf0, 0x09, 0xd6, 0x00, 0x68, 0x5e, 0x4f, 0x06, 0x29, + 0xe5, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x08, 0x39, 0x03, 0x29, 0x5e, 0x02, + 0xf0, 0x09, 0xdb, 0x02, 0x03, 0xde, 0xb3, 0x00, 0x09, 0xdc, 0x01, 0x91, + 0x60, 0x1a, 0x84, 0xf4, 0x27, 0x01, 0x83, 0xe0, 0x02, 0xf5, 0x97, 0xac, + 0x02, 0x02, 0x00, 0xbf, 0x00, 0x09, 0xe4, 0x02, 0x03, 0x45, 0x6f, 0x00, + 0x09, 0xdf, 0x01, 0x85, 0xe0, 0x06, 0x2b, 0x71, 0x5b, 0x02, 0x04, 0x5e, + 0xb3, 0x00, 0x09, 0xe4, 0x01, 0x87, 0xe0, 0x02, 0x10, 0x70, 0x83, 0x01, + 0x83, 0xe0, 0x02, 0x09, 0x10, 0x48, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x11, + 0x2e, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x09, 0xef, 0x02, 0x05, 0x50, 0x0b, + 0x00, 0x09, 0xef, 0x01, 0x82, 0x60, 0x06, 0x09, 0x10, 0x48, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x09, 0xef, 0x02, 0x87, 0x00, 0xc3, 0x00, 0x09, 0xec, + 0x00, 0x68, 0xde, 0x4f, 0x06, 0xa9, 0xec, 0x00, 0x68, 0xd2, 0x13, 0x00, + 0x09, 0xec, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x11, 0x83, 0x01, 0xbc, 0x60, + 0x03, 0x00, 0x11, 0x82, 0x00, 0x68, 0xde, 0x4f, 0x06, 0x29, 0xef, 0x00, + 0xe0, 0x02, 0x4f, 0x00, 0x20, 0x93, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x09, + 0xef, 0x03, 0xab, 0x5e, 0x02, 0xf0, 0x09, 0xf1, 0x02, 0x04, 0x41, 0x07, + 0x00, 0x09, 0xf4, 0x02, 0x83, 0x41, 0x07, 0x00, 0x08, 0xc6, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x09, 0xf4, 0x02, 0x84, 0x41, 0x07, 0x00, 0x08, 0xc6, + 0x01, 0x80, 0x60, 0x06, 0xf2, 0x97, 0x94, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x08, 0xc6, 0x03, 0x9f, 0x5e, 0x02, 0xf0, 0x09, 0xf9, 0x03, 0x9e, 0xde, + 0x02, 0xf0, 0x0c, 0x06, 0x02, 0x03, 0x5e, 0x53, 0x00, 0x0c, 0x06, 0x02, + 0x04, 0x81, 0x43, 0x00, 0x09, 0xfd, 0x01, 0x00, 0x01, 0x63, 0x00, 0x17, + 0xa1, 0x01, 0x02, 0xc0, 0x27, 0x00, 0x17, 0xa2, 0x00, 0x38, 0xde, 0x86, + 0xf4, 0x49, 0xf3, 0x03, 0xab, 0x5e, 0x02, 0xf0, 0x09, 0xff, 0x02, 0x00, + 0x52, 0x17, 0x00, 0x09, 0xf3, 0x02, 0x80, 0x52, 0x2f, 0x00, 0x0a, 0x01, + 0x03, 0x33, 0x5e, 0x02, 0xf0, 0x0c, 0x06, 0x02, 0x3c, 0x52, 0x3f, 0x00, + 0x0a, 0x12, 0x01, 0x3c, 0x52, 0x3f, 0x00, 0x17, 0xa1, 0x00, 0x68, 0xde, + 0x84, 0x04, 0x8a, 0x32, 0x01, 0xbc, 0x60, 0x03, 0x16, 0x10, 0x64, 0x01, + 0xbc, 0x60, 0x1f, 0x16, 0x10, 0x65, 0x00, 0x68, 0x5e, 0x87, 0x00, 0x2a, + 0x0e, 0x00, 0xb0, 0x5a, 0x03, 0x00, 0x17, 0xa2, 0x00, 0x68, 0xde, 0x8a, + 0xc0, 0x0a, 0x32, 0x00, 0xe0, 0x41, 0x97, 0x00, 0x30, 0x65, 0x00, 0xe0, + 0x41, 0x93, 0x00, 0x30, 0x64, 0x00, 0xe8, 0x5e, 0x87, 0x00, 0x57, 0xa1, + 0x00, 0x6a, 0x5e, 0x87, 0x00, 0x2a, 0x07, 0x00, 0x68, 0x5e, 0x87, 0x00, + 0x0a, 0x13, 0x01, 0x38, 0x5a, 0x03, 0x00, 0x17, 0xa1, 0x01, 0x38, 0x58, + 0x03, 0x00, 0x17, 0xa2, 0x00, 0x68, 0xde, 0x86, 0xf4, 0x4a, 0x32, 0x03, + 0xbf, 0xde, 0x02, 0xf0, 0x0a, 0x13, 0x02, 0x85, 0xc1, 0x07, 0x00, 0x0c, + 0x06, 0x01, 0xbc, 0x60, 0x1f, 0x15, 0xf0, 0x65, 0x01, 0xbc, 0x60, 0x03, + 0x05, 0xb7, 0xa4, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x01, 0x15, 0x02, 0x80, + 0x00, 0xc3, 0x00, 0x0a, 0x32, 0x01, 0xbc, 0x60, 0x13, 0x10, 0xd7, 0xa6, + 0x00, 0xe0, 0x01, 0x7f, 0x00, 0xb7, 0xa5, 0x00, 0x6d, 0x5e, 0x96, 0xf4, + 0xca, 0x1b, 0x01, 0xbc, 0x60, 0x13, 0x09, 0x57, 0xa5, 0x00, 0x68, 0x5e, + 0x94, 0x0b, 0xca, 0x36, 0x00, 0xb0, 0x01, 0x7b, 0x00, 0x10, 0x65, 0x00, + 0xb0, 0x52, 0x27, 0x00, 0x17, 0xa2, 0x00, 0xb0, 0x52, 0x2b, 0x00, 0x17, + 0xa3, 0x00, 0x68, 0x41, 0x94, 0x0b, 0xea, 0x26, 0x00, 0x68, 0xde, 0x8e, + 0xd0, 0x4a, 0x22, 0x00, 0x68, 0x5e, 0x8a, 0xd0, 0x2a, 0x32, 0x00, 0xe0, + 0x41, 0x97, 0x00, 0xb0, 0x65, 0x00, 0x6d, 0x41, 0x96, 0xf4, 0xca, 0x1f, + 0x01, 0xbc, 0x60, 0x13, 0x09, 0x50, 0x65, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x0a, 0x1f, 0x00, 0xe0, 0x02, 0x8b, 0x00, 0x20, 0xa2, 0x00, 0xb0, 0x01, + 0x7f, 0x00, 0x10, 0x65, 0x00, 0xb0, 0x52, 0x23, 0x00, 0x16, 0x80, 0x00, + 0xb0, 0x52, 0x27, 0x00, 0x16, 0x81, 0x00, 0xb0, 0x52, 0x2b, 0x00, 0x16, + 0x82, 0x01, 0xbc, 0x52, 0x02, 0xf2, 0xf7, 0xa1, 0x01, 0xa9, 0x5e, 0x02, + 0xf4, 0x36, 0x83, 0x00, 0x90, 0x44, 0x67, 0x01, 0x16, 0x84, 0x02, 0x02, + 0x81, 0xab, 0x00, 0x0a, 0x30, 0x00, 0x68, 0xde, 0x93, 0x05, 0xaa, 0x31, + 0x01, 0x84, 0x60, 0x06, 0xd0, 0x96, 0x84, 0x00, 0xb0, 0x5e, 0x97, 0x00, + 0x00, 0x5f, 0x02, 0x07, 0x81, 0xab, 0x00, 0x0a, 0x34, 0x01, 0x80, 0x60, + 0x06, 0xf2, 0x97, 0x94, 0x03, 0xab, 0x5e, 0x02, 0xf0, 0x06, 0xde, 0x03, + 0xbf, 0xde, 0x02, 0xf0, 0x08, 0xc6, 0x00, 0xe0, 0x02, 0x8f, 0x00, 0x20, + 0xa3, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x09, 0xf3, 0x03, 0x9e, 0xde, 0x02, + 0xf0, 0x0c, 0x06, 0x03, 0xab, 0x5e, 0x02, 0xf0, 0x0a, 0x3b, 0x02, 0x00, + 0x52, 0x17, 0x00, 0x09, 0xf3, 0x03, 0x33, 0x5e, 0x02, 0xf0, 0x0c, 0x06, + 0x01, 0x84, 0x60, 0x06, 0xf2, 0x97, 0x94, 0x03, 0xab, 0x5e, 0x02, 0xf0, + 0x06, 0xde, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x08, 0xc6, 0x03, 0x83, 0x5e, + 0x02, 0xf0, 0x0a, 0x42, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x11, 0x8f, 0x00, + 0x6d, 0x40, 0x33, 0x03, 0x8a, 0x3f, 0x00, 0x6d, 0x40, 0x33, 0x03, 0x89, + 0xf3, 0x03, 0x2b, 0x5e, 0x02, 0xf0, 0x0c, 0x0a, 0x03, 0xbf, 0xde, 0x02, + 0xf0, 0x06, 0xde, 0x03, 0x2b, 0x5e, 0x02, 0xf0, 0x0a, 0x48, 0x00, 0xe0, + 0x02, 0x33, 0x00, 0x20, 0x8c, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x06, 0xe0, + 0x00, 0xe0, 0x02, 0x4b, 0x00, 0x20, 0x92, 0x01, 0x03, 0xc0, 0x27, 0x00, + 0x17, 0x81, 0x01, 0x82, 0x5e, 0x05, 0x02, 0xf7, 0x81, 0x00, 0x02, 0x5e, + 0x02, 0xf0, 0x0d, 0x3f, 0x00, 0x88, 0x00, 0x23, 0x00, 0x37, 0xa2, 0x00, + 0xe0, 0x5e, 0x88, 0x00, 0xf7, 0xa2, 0x00, 0xe0, 0x5e, 0x86, 0xf4, 0x51, + 0x89, 0x01, 0x86, 0xe0, 0x06, 0x30, 0x11, 0x80, 0x03, 0xbf, 0xde, 0x02, + 0xf0, 0x09, 0xef, 0x03, 0xa2, 0xde, 0x02, 0xf0, 0x00, 0xae, 0x03, 0xa3, + 0xde, 0x02, 0xf0, 0x0a, 0x6e, 0x00, 0xe0, 0x01, 0xff, 0x00, 0x20, 0x7f, + 0x01, 0xbc, 0x60, 0x03, 0x00, 0x17, 0xa3, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x0a, 0x70, 0x01, 0x87, 0x60, 0x04, 0x03, 0x10, 0xa0, 0x01, 0xbc, 0x60, + 0x03, 0x00, 0x51, 0xe4, 0x00, 0xb0, 0x47, 0x93, 0x00, 0x18, 0x00, 0x01, + 0xbc, 0x60, 0x03, 0x02, 0x90, 0x04, 0x01, 0xbc, 0x62, 0x0f, 0x00, 0x11, + 0xe0, 0x01, 0xbc, 0x60, 0x0f, 0x01, 0x31, 0xe8, 0x00, 0xb0, 0x47, 0xa3, + 0x00, 0x18, 0x00, 0x01, 0xbc, 0x60, 0x0f, 0x00, 0x11, 0xe8, 0x01, 0xbc, + 0x60, 0x03, 0x01, 0x31, 0xec, 0x00, 0xb0, 0x47, 0xb3, 0x00, 0x18, 0x00, + 0x01, 0xbc, 0x60, 0x03, 0x00, 0x11, 0xec, 0x01, 0x84, 0x60, 0x06, 0x09, + 0x10, 0x48, 0x00, 0x20, 0x60, 0x1e, 0x09, 0x0a, 0x65, 0x00, 0xe0, 0x01, + 0xfb, 0x00, 0x20, 0x7e, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0a, 0x76, 0x01, + 0xbc, 0x60, 0x03, 0x0e, 0xd7, 0xa1, 0x01, 0x14, 0x00, 0x63, 0x00, 0x17, + 0xa2, 0x00, 0xe0, 0x5e, 0x86, 0xf4, 0x50, 0x65, 0x00, 0xe0, 0x5a, 0x03, + 0x00, 0x36, 0x80, 0x02, 0x03, 0x00, 0xc7, 0x00, 0x0a, 0x6b, 0x03, 0xa9, + 0x5e, 0x02, 0xf0, 0x0a, 0x70, 0x02, 0x91, 0x50, 0x9f, 0x00, 0x0a, 0x6f, + 0x01, 0x91, 0x60, 0x1a, 0x84, 0xf4, 0x27, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x0a, 0x6f, 0x00, 0xe0, 0x01, 0xff, 0x00, 0x20, 0x7f, 0x01, 0xbc, 0x60, + 0x03, 0x00, 0x37, 0xa3, 0x03, 0x23, 0xde, 0x02, 0xf0, 0x0a, 0x76, 0x01, + 0x83, 0xe0, 0x02, 0x09, 0x10, 0x48, 0x01, 0x84, 0x60, 0x02, 0xf5, 0x97, + 0xac, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x17, 0x8e, 0x01, 0x87, 0xe0, 0x02, + 0x10, 0x70, 0x83, 0x01, 0x82, 0x60, 0x02, 0x09, 0x10, 0x48, 0x03, 0xd0, + 0xde, 0x02, 0xf0, 0x0a, 0x77, 0x03, 0xd0, 0x5e, 0x02, 0xf0, 0x0a, 0x78, + 0x01, 0x82, 0xe0, 0x02, 0x09, 0x10, 0x48, 0x03, 0xd5, 0xde, 0x02, 0xf0, + 0x0a, 0x7a, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x10, 0xb4, 0x01, 0xbc, 0x60, + 0x03, 0x00, 0xf7, 0xa1, 0x00, 0x68, 0x00, 0xa7, 0x00, 0x0a, 0x7e, 0x01, + 0x85, 0x42, 0x1a, 0xf4, 0x37, 0xa1, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, + 0xce, 0x00, 0xb0, 0x40, 0x67, 0x00, 0x17, 0xa5, 0x01, 0xbc, 0x63, 0xff, + 0x1f, 0xf7, 0xa2, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xd4, 0x00, 0x88, + 0x60, 0x07, 0x01, 0x57, 0xa4, 0x00, 0xb8, 0x5e, 0x86, 0xf4, 0x97, 0xa1, + 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xd4, 0x02, 0x83, 0xc2, 0x1f, 0x00, + 0x0a, 0x85, 0x00, 0xe0, 0x44, 0x67, 0x01, 0x17, 0xa1, 0x02, 0x04, 0x45, + 0x23, 0x00, 0x0a, 0x8a, 0x00, 0x6b, 0x44, 0x66, 0xf4, 0x2a, 0x87, 0x00, + 0x02, 0x5e, 0x02, 0xf0, 0x11, 0x76, 0x00, 0x68, 0x5e, 0x8f, 0x00, 0x00, + 0x02, 0x00, 0x68, 0x01, 0xb3, 0x00, 0x0a, 0x8e, 0x01, 0xbc, 0x60, 0x03, + 0x00, 0x04, 0xee, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0a, 0x91, 0x00, 0x20, + 0xe0, 0x1e, 0x09, 0x0a, 0x91, 0x00, 0xb0, 0x5e, 0x97, 0x00, 0x14, 0x2e, + 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x03, 0x00, 0x00, 0xa8, 0x41, 0x23, 0x00, + 0xf0, 0x48, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x00, 0x02, 0x01, 0x83, 0x60, + 0x02, 0x09, 0x10, 0x48, 0x01, 0xbc, 0x60, 0x07, 0x00, 0x10, 0x42, 0x00, + 0x6e, 0x40, 0x30, 0x02, 0x0a, 0x97, 0x00, 0xe0, 0x02, 0x77, 0x00, 0x20, + 0x9d, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x12, 0xbc, 0x03, 0xa3, 0x5e, 0x02, + 0xf0, 0x08, 0xc6, 0x03, 0xc6, 0xde, 0x02, 0xf0, 0x0a, 0x9a, 0x01, 0x84, + 0xe0, 0x06, 0x09, 0x10, 0x48, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0b, 0x03, + 0x00, 0x68, 0x20, 0xdf, 0x00, 0x0a, 0xa2, 0x00, 0xe8, 0x44, 0x65, 0x06, + 0xf7, 0xa1, 0x01, 0xbc, 0x60, 0x9f, 0x02, 0x17, 0xa2, 0x00, 0x6d, 0x5e, + 0x86, 0xf4, 0x4a, 0xa2, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x08, 0x37, 0x00, + 0x02, 0x5e, 0x02, 0xf0, 0x0b, 0x22, 0x00, 0x20, 0xe1, 0x02, 0x09, 0x00, + 0x9b, 0x00, 0x20, 0x62, 0x8a, 0x09, 0x0a, 0xa6, 0x00, 0x02, 0x5e, 0x02, + 0xf0, 0x11, 0x8f, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x00, 0x9b, 0x02, 0x84, + 0x45, 0x23, 0x00, 0x00, 0x9b, 0x03, 0x91, 0x5e, 0x02, 0xf0, 0x00, 0x9b, + 0x03, 0x96, 0xde, 0x02, 0xf0, 0x00, 0x9b, 0x03, 0x96, 0x5e, 0x02, 0xf0, + 0x00, 0x9b, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0b, 0x22, 0x01, 0xbc, 0x60, + 0x03, 0x00, 0x60, 0x20, 0x00, 0x68, 0x01, 0x73, 0x00, 0x0a, 0xbc, 0x00, + 0x02, 0x5e, 0x02, 0xf0, 0x01, 0x00, 0x00, 0xb0, 0x44, 0x67, 0x00, 0x08, + 0x37, 0x00, 0xb0, 0x01, 0x73, 0x00, 0x10, 0xe4, 0x01, 0xbc, 0x60, 0x03, + 0x00, 0x00, 0x06, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x00, 0x5c, 0x01, 0xbc, + 0x60, 0x03, 0x01, 0xd7, 0x82, 0x01, 0xd2, 0xde, 0x08, 0x75, 0x70, 0xe0, + 0x00, 0xb0, 0x0e, 0xb3, 0x00, 0x10, 0xe1, 0x00, 0xb0, 0x00, 0x47, 0x00, + 0x10, 0x86, 0x00, 0xb0, 0x0e, 0xcf, 0x00, 0x10, 0x8a, 0x01, 0xbc, 0x60, + 0x03, 0x00, 0x37, 0x81, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0d, 0x32, 0x01, + 0x90, 0x60, 0x0a, 0x09, 0x10, 0x48, 0x01, 0xbc, 0x61, 0x03, 0x00, 0x30, + 0x80, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x00, 0x02, 0x01, 0xbc, 0x60, 0x03, + 0x00, 0x30, 0x42, 0x01, 0x87, 0xe0, 0x02, 0x24, 0x71, 0x23, 0x00, 0x02, + 0x5e, 0x02, 0xf0, 0x10, 0x92, 0x01, 0xbc, 0x60, 0x03, 0x06, 0x77, 0x80, + 0x00, 0x68, 0x0d, 0xef, 0x00, 0x0a, 0xc3, 0x00, 0xb0, 0x0d, 0xef, 0x00, + 0x17, 0x81, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0d, 0xe9, 0x03, 0x97, 0x5e, + 0x02, 0xf0, 0x0b, 0x33, 0x03, 0x12, 0x5e, 0x02, 0xf0, 0x0a, 0xc3, 0x01, + 0xbc, 0x60, 0x03, 0x00, 0x40, 0x20, 0x01, 0xbc, 0x61, 0x83, 0x00, 0x11, + 0x25, 0x00, 0xb0, 0x00, 0x7b, 0x00, 0x11, 0x27, 0x01, 0xbc, 0x60, 0x07, + 0x02, 0x57, 0x80, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0d, 0xe4, 0x00, 0xb0, + 0x5e, 0x07, 0x00, 0x0b, 0x2f, 0x01, 0xbc, 0x60, 0x07, 0x02, 0x77, 0x80, + 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0d, 0xe4, 0x00, 0xb0, 0x5e, 0x07, 0x00, + 0x0b, 0x30, 0x01, 0xbc, 0x60, 0x13, 0x09, 0x97, 0xa1, 0x00, 0x02, 0x5e, + 0x02, 0xf0, 0x00, 0xce, 0x00, 0xb0, 0x40, 0x67, 0x00, 0x0b, 0x62, 0x01, + 0xbc, 0x60, 0x13, 0x09, 0x40, 0x5e, 0x01, 0xbc, 0x60, 0x13, 0x09, 0x40, + 0x5f, 0x01, 0x80, 0xe0, 0x06, 0xf5, 0xd7, 0xae, 0x01, 0x07, 0xc1, 0x07, + 0x00, 0x17, 0xa1, 0x01, 0x80, 0x5e, 0x86, 0xf5, 0x77, 0xab, 0x01, 0xbc, + 0x60, 0x0f, 0x00, 0x11, 0xe8, 0x01, 0xbc, 0x62, 0x0f, 0x00, 0x11, 0xe0, + 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0a, 0xe5, 0x01, 0xbc, 0x61, 0xcf, 0x0c, + 0x10, 0x5c, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x10, 0x5d, 0x01, 0xbc, 0x61, + 0xcf, 0x01, 0xf0, 0x5e, 0x01, 0xbc, 0x60, 0x3b, 0x0a, 0xf0, 0x5f, 0x00, + 0x02, 0x5e, 0x02, 0xf0, 0x10, 0x56, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x08, + 0x34, 0x02, 0x03, 0x00, 0xc7, 0x00, 0x00, 0x13, 0x01, 0xbc, 0x60, 0x03, + 0x00, 0x06, 0x02, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x06, 0x07, 0x01, 0xbc, + 0x60, 0x03, 0x00, 0x06, 0x0c, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x06, 0x11, + 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x00, 0x13, 0x01, 0xbc, 0x60, 0x03, 0x00, + 0x10, 0x48, 0x01, 0x85, 0xe0, 0x02, 0xf5, 0xb7, 0xad, 0x01, 0xbc, 0x63, + 0xff, 0x1f, 0xf0, 0x54, 0x01, 0xbc, 0x63, 0xff, 0x1f, 0xf0, 0x55, 0x01, + 0xbc, 0x63, 0xbf, 0x1f, 0xf0, 0x56, 0x01, 0xbc, 0x63, 0xff, 0x0f, 0xf0, + 0x57, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x12, 0xbc, 0x01, 0x87, 0xe0, 0x06, + 0x24, 0x71, 0x23, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x10, 0x54, 0x01, 0xbc, + 0x60, 0x03, 0x00, 0x10, 0x55, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x10, 0x56, + 0x01, 0xbc, 0x60, 0x03, 0x00, 0x10, 0x57, 0x01, 0xbc, 0x60, 0x0f, 0x00, + 0x20, 0x17, 0x01, 0x06, 0xc1, 0x07, 0x00, 0x17, 0xa1, 0x01, 0x82, 0x5e, + 0x84, 0x02, 0xe0, 0x17, 0x01, 0x07, 0x41, 0x07, 0x00, 0x17, 0xa1, 0x00, + 0xb8, 0x5e, 0x87, 0x00, 0x37, 0xa1, 0x01, 0x80, 0xde, 0x87, 0x00, 0x00, + 0x16, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x02, 0x85, 0xc0, 0x37, + 0x00, 0x00, 0x02, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x11, 0x8f, 0x00, 0x02, + 0x5e, 0x02, 0xf0, 0x0f, 0x38, 0x02, 0x86, 0x40, 0x37, 0x00, 0x0a, 0xf8, + 0x00, 0xe0, 0x02, 0x1b, 0x00, 0x20, 0x86, 0x03, 0x86, 0xde, 0x02, 0xf0, + 0x0a, 0x94, 0x02, 0x87, 0xc0, 0x37, 0x00, 0x0a, 0x94, 0x01, 0x58, 0x60, + 0x03, 0x00, 0x10, 0x2a, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x90, 0x04, 0x00, + 0xb0, 0x40, 0x13, 0x00, 0x17, 0xa1, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x00, + 0x13, 0x01, 0xb8, 0x60, 0x0a, 0x04, 0x90, 0x24, 0x03, 0xaa, 0x5e, 0x02, + 0xf0, 0x0b, 0x06, 0x01, 0x58, 0x60, 0x03, 0x00, 0x10, 0x2a, 0x01, 0xbc, + 0x60, 0x03, 0x02, 0x90, 0x04, 0x00, 0xb0, 0x40, 0x13, 0x00, 0x18, 0x00, + 0x01, 0x83, 0x60, 0x02, 0x09, 0x10, 0x48, 0x01, 0xbc, 0x60, 0x03, 0x00, + 0x51, 0xe4, 0x00, 0xb0, 0x47, 0x93, 0x00, 0x18, 0x00, 0x01, 0xbc, 0x62, + 0x0f, 0x00, 0x11, 0xe0, 0x01, 0x80, 0x60, 0x01, 0x00, 0x68, 0x03, 0x00, + 0x02, 0x5e, 0x02, 0xf0, 0x0f, 0x38, 0x03, 0x85, 0x5e, 0x02, 0xf0, 0x0b, + 0x0d, 0x01, 0xbc, 0x62, 0x0f, 0x00, 0x11, 0xe0, 0x01, 0xbc, 0x60, 0x0f, + 0x01, 0x31, 0xe8, 0x00, 0xb0, 0x47, 0xa3, 0x00, 0x18, 0x00, 0x01, 0xbc, + 0x60, 0x0f, 0x00, 0x11, 0xe8, 0x01, 0xbc, 0x60, 0x03, 0x01, 0x57, 0xa1, + 0x00, 0xe8, 0x5e, 0x87, 0x00, 0x37, 0xa1, 0x00, 0x68, 0xde, 0x87, 0x00, + 0x0b, 0x14, 0x01, 0xbc, 0x60, 0x03, 0x02, 0x90, 0x04, 0x00, 0xb0, 0x40, + 0x13, 0x00, 0x18, 0x00, 0x01, 0xbc, 0x60, 0x03, 0x01, 0x31, 0xec, 0x00, + 0xb0, 0x47, 0xb3, 0x00, 0x18, 0x00, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x11, + 0xec, 0x03, 0x24, 0xde, 0x02, 0xf0, 0x06, 0x24, 0x01, 0x86, 0x60, 0x06, + 0xf5, 0x77, 0xab, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0b, 0x22, 0x01, 0x80, + 0x60, 0x06, 0x10, 0x30, 0x81, 0x00, 0xb0, 0x5e, 0x87, 0x00, 0x17, 0xa1, + 0x01, 0x80, 0x60, 0x02, 0x10, 0x30, 0x81, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x06, 0x24, 0x01, 0xbc, 0x61, 0x03, 0x00, 0x10, 0x80, 0x00, 0xb0, 0x42, + 0x03, 0x00, 0x18, 0x00, 0x00, 0x6e, 0xe0, 0x03, 0x00, 0x2b, 0x25, 0x03, + 0x50, 0x5e, 0x02, 0xf0, 0x0b, 0x28, 0x00, 0x01, 0x5e, 0x02, 0xf0, 0x00, + 0x00, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x03, 0x1d, 0x01, 0x84, 0x60, 0x02, + 0xf5, 0x97, 0xac, 0x00, 0xa8, 0x41, 0x23, 0x04, 0xf0, 0x48, 0x01, 0x82, + 0x60, 0x02, 0x09, 0x10, 0x48, 0x02, 0x06, 0xde, 0xaf, 0x00, 0x0b, 0x2e, + 0x03, 0xd5, 0xde, 0x02, 0xf0, 0x0b, 0x2e, 0x03, 0x50, 0xde, 0x02, 0xf0, + 0x0b, 0x2c, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x10, 0xb4, 0x02, 0x84, 0xc7, + 0x83, 0x00, 0x0b, 0x31, 0x01, 0xbc, 0x60, 0x0b, 0x00, 0x11, 0xe0, 0x01, + 0x8e, 0x60, 0x02, 0xf5, 0x77, 0xab, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, + 0x00, 0x03, 0xa2, 0xde, 0x02, 0xf0, 0x00, 0x9b, 0x02, 0xbc, 0x42, 0x87, + 0x00, 0x0b, 0x3a, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x37, 0xa4, 0x01, 0xbc, + 0x60, 0x03, 0x1f, 0xf7, 0xa3, 0x01, 0x14, 0x00, 0x63, 0x00, 0x17, 0xa2, + 0x00, 0x88, 0x60, 0x06, 0xf4, 0x57, 0xa2, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x0b, 0x3f, 0x00, 0x88, 0x60, 0x07, 0x01, 0x17, 0xa4, 0x01, 0xbc, 0x63, + 0xff, 0x00, 0x17, 0xa3, 0x01, 0x14, 0x00, 0x63, 0x00, 0x17, 0xa2, 0x00, + 0xe0, 0x5e, 0x8b, 0x01, 0x17, 0xa2, 0x00, 0x88, 0x60, 0x06, 0xf4, 0x57, + 0xa2, 0x01, 0xbc, 0x60, 0x13, 0x11, 0x10, 0x65, 0x01, 0xbc, 0x60, 0x1b, + 0x02, 0x50, 0x64, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x17, 0xa5, 0x00, 0x20, + 0xc2, 0x86, 0xf4, 0x8b, 0x49, 0x00, 0xe0, 0x41, 0x97, 0x06, 0xd0, 0x65, + 0x00, 0xe0, 0x41, 0x93, 0x01, 0xf0, 0x64, 0x00, 0xe0, 0x5e, 0x97, 0x00, + 0x37, 0xa5, 0x00, 0x88, 0x5e, 0x93, 0x00, 0x37, 0xa4, 0x00, 0x20, 0x5e, + 0x92, 0xf4, 0x6b, 0x68, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0b, 0x42, 0x00, + 0x68, 0xde, 0x92, 0xf4, 0x4b, 0x4e, 0x00, 0x68, 0x00, 0x83, 0x00, 0x6b, + 0x4e, 0x03, 0xa0, 0xde, 0x02, 0xf0, 0x0b, 0x4e, 0x00, 0x20, 0xc1, 0x23, + 0x16, 0x0b, 0x43, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0b, 0x22, 0x00, 0x6d, + 0xde, 0x93, 0x20, 0x0b, 0x64, 0x02, 0x03, 0x00, 0xc7, 0x00, 0x0b, 0x58, + 0x00, 0x6d, 0xde, 0x97, 0x00, 0x8b, 0x58, 0x01, 0xbc, 0x60, 0x03, 0x00, + 0x16, 0x08, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x16, 0x09, 0x01, 0xbc, 0x60, + 0x03, 0x00, 0x16, 0x0a, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x16, 0x0b, 0x01, + 0xbc, 0x60, 0x03, 0x00, 0x16, 0x0c, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x16, + 0x0d, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x16, 0x0e, 0x02, 0x00, 0x5a, 0xc3, + 0x00, 0x0b, 0x63, 0x02, 0x3c, 0x5a, 0x9f, 0x00, 0x0b, 0x63, 0x00, 0x68, + 0x00, 0x83, 0x00, 0x6b, 0x63, 0x03, 0x85, 0xde, 0x02, 0xf0, 0x00, 0x9b, + 0x03, 0x85, 0x5e, 0x02, 0xf0, 0x00, 0x9b, 0x03, 0xa2, 0xde, 0x02, 0xf0, + 0x00, 0x9b, 0x03, 0xa3, 0xde, 0x02, 0xf0, 0x00, 0x9b, 0x03, 0x97, 0xde, + 0x02, 0xf0, 0x00, 0x9b, 0x00, 0xb0, 0x41, 0x97, 0x00, 0x10, 0x60, 0x01, + 0x91, 0x60, 0x0a, 0x84, 0xf4, 0x27, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x03, + 0x00, 0x01, 0x80, 0x60, 0x02, 0xd6, 0x16, 0xb0, 0x00, 0xb0, 0x5e, 0x93, + 0x00, 0x10, 0xa1, 0x01, 0x83, 0x60, 0x02, 0xf7, 0xf7, 0xbf, 0x01, 0xbc, + 0x60, 0x03, 0x00, 0x30, 0x43, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0b, 0x43, + 0x00, 0x68, 0x80, 0x83, 0x00, 0x60, 0x9b, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x0a, 0xc4, 0x02, 0x83, 0xc2, 0x1f, 0x00, 0x00, 0x02, 0x00, 0xb0, 0x5e, + 0x87, 0x00, 0x17, 0xa1, 0x03, 0xd0, 0xde, 0x02, 0xf0, 0x05, 0x2c, 0x01, + 0xbc, 0x60, 0x03, 0x04, 0x10, 0x42, 0x03, 0x9e, 0xde, 0x02, 0xf0, 0x00, + 0x13, 0x00, 0xb0, 0x5e, 0x3f, 0x00, 0x11, 0x45, 0x01, 0xbc, 0x60, 0x03, + 0x00, 0x17, 0x8f, 0x00, 0xb0, 0x5e, 0x43, 0x00, 0x17, 0x85, 0x00, 0xb0, + 0x5e, 0x0f, 0x00, 0x17, 0x90, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0b, 0x22, + 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x00, 0x13, 0x00, 0x6d, 0x40, 0x33, 0x05, + 0x89, 0xf4, 0x03, 0xac, 0x5e, 0x02, 0xf0, 0x0b, 0x7a, 0x00, 0x68, 0x5e, + 0x4f, 0x02, 0x8b, 0xb1, 0x00, 0xe0, 0x02, 0x67, 0x00, 0x20, 0x99, 0x03, + 0xbf, 0xde, 0x02, 0xf0, 0x0b, 0xb1, 0x00, 0x68, 0x5e, 0x4f, 0x02, 0x8b, + 0xb0, 0x00, 0xe0, 0x02, 0x5f, 0x00, 0x20, 0x97, 0x01, 0x85, 0x60, 0x02, + 0xf5, 0xb7, 0xad, 0x01, 0x82, 0x60, 0x02, 0xf5, 0xd7, 0xae, 0x01, 0xbc, + 0x60, 0x03, 0x00, 0x0a, 0xbb, 0x03, 0x9f, 0x5e, 0x02, 0xf0, 0x0b, 0xf3, + 0x03, 0x9e, 0xde, 0x02, 0xf0, 0x0b, 0x8f, 0x03, 0x21, 0xde, 0x02, 0xf0, + 0x0b, 0x8f, 0x00, 0xe0, 0x02, 0x6f, 0x00, 0x20, 0x9b, 0x00, 0x02, 0x5e, + 0x02, 0xf0, 0x0b, 0x22, 0x01, 0x86, 0x60, 0x02, 0x09, 0x10, 0x48, 0x01, + 0x80, 0x60, 0x02, 0x09, 0x10, 0x48, 0x01, 0x81, 0xe0, 0x02, 0x09, 0x10, + 0x48, 0x01, 0xbc, 0x60, 0x03, 0x02, 0x10, 0x42, 0x02, 0x80, 0x44, 0x1f, + 0x00, 0x0b, 0x8e, 0x00, 0xb0, 0x5e, 0x3f, 0x00, 0x11, 0x45, 0x01, 0xbc, + 0x60, 0x03, 0x00, 0x17, 0x8f, 0x00, 0xb0, 0x5e, 0x43, 0x00, 0x17, 0x85, + 0x00, 0xb0, 0x5e, 0x0f, 0x00, 0x17, 0x90, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x0b, 0x8f, 0x00, 0xa0, 0x44, 0xb6, 0xf0, 0x71, 0x45, 0x03, 0x9f, 0x5e, + 0x02, 0xf0, 0x0b, 0xf3, 0x02, 0x82, 0x00, 0xc3, 0x00, 0x0b, 0xb0, 0x03, + 0x33, 0x5e, 0x02, 0xf0, 0x0b, 0xb0, 0x00, 0xb0, 0x00, 0x73, 0x00, 0x17, + 0xa1, 0x00, 0xe0, 0x5e, 0x86, 0xb0, 0x17, 0xa1, 0x00, 0xe1, 0x5e, 0x7a, + 0xf4, 0x37, 0x9e, 0x00, 0xe1, 0xde, 0x77, 0x00, 0x17, 0x9d, 0x00, 0xe1, + 0xde, 0x73, 0x00, 0x17, 0x9c, 0x00, 0xe0, 0xde, 0x6f, 0x00, 0x17, 0x9b, + 0x03, 0x9e, 0xde, 0x02, 0xf0, 0x0b, 0xa0, 0x00, 0x6e, 0x5e, 0x6e, 0x92, + 0x4b, 0xf3, 0x00, 0x6d, 0x5e, 0x6e, 0x92, 0x4b, 0xa0, 0x00, 0x6e, 0x5e, + 0x72, 0x92, 0x2b, 0xf3, 0x00, 0x6d, 0x5e, 0x72, 0x92, 0x2b, 0xa0, 0x00, + 0x6e, 0x5e, 0x76, 0x92, 0x0b, 0xf3, 0x00, 0x6d, 0x5e, 0x76, 0x92, 0x0b, + 0xa0, 0x00, 0x6d, 0xde, 0x7a, 0x91, 0xeb, 0xf3, 0x00, 0xb0, 0x44, 0x67, + 0x00, 0x08, 0x33, 0x00, 0xb0, 0x44, 0x6b, 0x00, 0x08, 0x32, 0x00, 0xb0, + 0x44, 0x6f, 0x00, 0x08, 0x31, 0x00, 0xb0, 0x44, 0x73, 0x00, 0x08, 0x30, + 0x00, 0x68, 0xa0, 0xce, 0x23, 0x2b, 0xa0, 0x00, 0xe9, 0x20, 0xce, 0xf3, + 0xd7, 0x9e, 0x00, 0xe9, 0xa0, 0xca, 0xf3, 0xb7, 0x9d, 0x00, 0xe9, 0xa0, + 0xc6, 0xf3, 0x97, 0x9c, 0x00, 0xe8, 0xa0, 0xc2, 0xf3, 0x77, 0x9b, 0x00, + 0xe1, 0x5e, 0x7a, 0x91, 0xf7, 0xa1, 0x00, 0xb0, 0x5e, 0x87, 0x00, 0x11, + 0x19, 0x00, 0xe1, 0xde, 0x76, 0x92, 0x11, 0x1a, 0x00, 0xe1, 0xde, 0x72, + 0x92, 0x31, 0x1b, 0x00, 0xe0, 0xde, 0x6e, 0x92, 0x51, 0x1c, 0x00, 0x68, + 0xde, 0x86, 0x23, 0x2b, 0xa9, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x0b, 0xf0, + 0x03, 0x1e, 0xde, 0x02, 0xf0, 0x0b, 0xf3, 0x00, 0x68, 0x5e, 0x4f, 0x02, + 0x8b, 0xf3, 0x01, 0xbc, 0x60, 0x1f, 0x16, 0xb0, 0x65, 0x01, 0xbc, 0x60, + 0x03, 0x00, 0x97, 0xa4, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x01, 0x15, 0x00, + 0x68, 0xde, 0x93, 0x00, 0x8b, 0xe0, 0x02, 0x85, 0x00, 0xc3, 0x00, 0x0b, + 0xe0, 0x02, 0x07, 0xc1, 0x97, 0x00, 0x0b, 0xbb, 0x01, 0x3c, 0x5a, 0x0f, + 0x00, 0x17, 0xa2, 0x01, 0xbc, 0x5a, 0x12, 0xf4, 0x57, 0xa2, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x0b, 0xbc, 0x00, 0xb0, 0x5a, 0x0f, 0x00, 0x17, 0xa2, + 0x01, 0xbc, 0x60, 0x03, 0x00, 0x11, 0x32, 0x03, 0x2c, 0x5e, 0x02, 0xf0, + 0x0b, 0xc2, 0x02, 0x80, 0x44, 0x1f, 0x00, 0x0b, 0xe0, 0x00, 0xb0, 0x5e, + 0x8b, 0x00, 0x11, 0x86, 0x01, 0xa5, 0xe0, 0x0e, 0x30, 0x11, 0x80, 0x03, + 0xbf, 0xde, 0x02, 0xf0, 0x0b, 0xe0, 0x03, 0x33, 0x5e, 0x02, 0xf0, 0x0b, + 0xd9, 0x02, 0x9b, 0x40, 0x2f, 0x00, 0x0b, 0xd9, 0x02, 0x00, 0x44, 0x07, + 0x00, 0x0b, 0xd3, 0x02, 0x00, 0xc4, 0x07, 0x00, 0x0b, 0xcd, 0x02, 0x81, + 0x44, 0x07, 0x00, 0x0b, 0xe0, 0x01, 0x82, 0xe0, 0x07, 0x01, 0x90, 0x10, + 0x00, 0xb0, 0x52, 0x2f, 0x00, 0x10, 0x11, 0x00, 0xb0, 0x52, 0x33, 0x00, + 0x10, 0x11, 0x00, 0xb0, 0x52, 0x37, 0x00, 0x10, 0x11, 0x00, 0xb0, 0x5e, + 0x8b, 0x00, 0x11, 0x0f, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0b, 0xe0, 0x01, + 0x82, 0xe0, 0x07, 0x01, 0x30, 0x10, 0x00, 0xb0, 0x52, 0x2f, 0x00, 0x10, + 0x11, 0x00, 0xb0, 0x52, 0x33, 0x00, 0x10, 0x11, 0x00, 0xb0, 0x52, 0x37, + 0x00, 0x10, 0x11, 0x00, 0xb0, 0x5e, 0x8b, 0x00, 0x11, 0x0d, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x0b, 0xe0, 0x01, 0x82, 0xe0, 0x07, 0x00, 0xd0, 0x10, + 0x00, 0xb0, 0x52, 0x2f, 0x00, 0x10, 0x11, 0x00, 0xb0, 0x52, 0x33, 0x00, + 0x10, 0x11, 0x00, 0xb0, 0x52, 0x37, 0x00, 0x10, 0x11, 0x00, 0xb0, 0x5e, + 0x8b, 0x00, 0x11, 0x0b, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0b, 0xe0, 0x03, + 0x33, 0xde, 0x02, 0xf0, 0x0b, 0xdc, 0x00, 0xb0, 0x5e, 0x8b, 0x00, 0x11, + 0x0b, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0b, 0xe0, 0x03, 0x34, 0x5e, 0x02, + 0xf0, 0x0b, 0xdf, 0x00, 0xb0, 0x5e, 0x8b, 0x00, 0x11, 0x0d, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x0b, 0xe0, 0x00, 0xb0, 0x5e, 0x8b, 0x00, 0x11, 0x0f, + 0x03, 0x1e, 0xde, 0x02, 0xf0, 0x0b, 0xf3, 0x03, 0x9f, 0x5e, 0x02, 0xf0, + 0x0b, 0xf3, 0x00, 0x68, 0x5e, 0x4f, 0x02, 0x8b, 0xf3, 0x03, 0x33, 0x5e, + 0x02, 0xf0, 0x0b, 0xf3, 0x01, 0xbc, 0x60, 0x1f, 0x16, 0xb0, 0x65, 0x01, + 0xbc, 0x60, 0x03, 0x00, 0xb7, 0xa4, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x01, + 0x15, 0x00, 0x68, 0xde, 0x93, 0x00, 0xab, 0xf3, 0x02, 0x07, 0xc1, 0x97, + 0x00, 0x0b, 0xec, 0x01, 0x3c, 0x5a, 0x07, 0x00, 0x17, 0x88, 0x01, 0x3c, + 0x5a, 0x0b, 0x00, 0x17, 0xa1, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0b, 0xee, + 0x01, 0x38, 0x5a, 0x07, 0x00, 0x17, 0x88, 0x01, 0x38, 0x5a, 0x0b, 0x00, + 0x17, 0xa1, 0x01, 0x84, 0x5e, 0x86, 0xf2, 0x97, 0x94, 0x01, 0x87, 0xde, + 0x86, 0x24, 0x91, 0x24, 0x02, 0x06, 0x80, 0xf3, 0x00, 0x0b, 0xf3, 0x01, + 0x84, 0x60, 0x02, 0xf2, 0x97, 0x94, 0x01, 0x87, 0xe0, 0x02, 0x24, 0x91, + 0x24, 0x03, 0xab, 0x5e, 0x02, 0xf0, 0x06, 0xde, 0x03, 0xbf, 0xde, 0x02, + 0xf0, 0x08, 0xc6, 0x03, 0x2b, 0x5e, 0x02, 0xf0, 0x09, 0xf3, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x06, 0xde, 0x03, 0xab, 0x5e, 0x02, 0xf0, 0x0b, 0xfa, + 0x03, 0x2c, 0x5e, 0x02, 0xf0, 0x09, 0xf3, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x0c, 0x0a, 0x00, 0xb0, 0x52, 0x23, 0x00, 0x11, 0xf2, 0x00, 0xb0, 0x52, + 0x27, 0x00, 0x11, 0xf3, 0x00, 0xb0, 0x52, 0x2b, 0x00, 0x11, 0xf4, 0x01, + 0xbc, 0x60, 0x03, 0x00, 0x91, 0xf5, 0x00, 0xb0, 0x00, 0x5b, 0x00, 0x11, + 0xf0, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x06, 0xde, 0x01, 0x38, 0x52, 0x3f, + 0x00, 0x17, 0xa1, 0x02, 0x06, 0x5e, 0x53, 0x00, 0x0c, 0x03, 0x01, 0x38, + 0x52, 0x4b, 0x00, 0x17, 0xa1, 0x00, 0x68, 0xde, 0x87, 0x00, 0x8c, 0x06, + 0x03, 0xab, 0x5e, 0x02, 0xf0, 0x06, 0xde, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x08, 0xc6, 0x00, 0x68, 0xde, 0x4f, 0x02, 0x0c, 0x09, 0x02, 0x07, 0x81, + 0xab, 0x00, 0x0c, 0x09, 0x01, 0x80, 0x60, 0x06, 0xf2, 0x97, 0x94, 0x03, + 0xab, 0x5e, 0x02, 0xf0, 0x06, 0xde, 0x02, 0x00, 0x00, 0xf3, 0x00, 0x0c, + 0x0f, 0x02, 0x06, 0xde, 0x53, 0x00, 0x0c, 0x0f, 0x01, 0x18, 0x5e, 0x83, + 0x00, 0x17, 0xa1, 0x00, 0x68, 0xde, 0x87, 0x00, 0xac, 0x0f, 0x01, 0xbc, + 0x60, 0x0b, 0x02, 0x51, 0x42, 0x02, 0x00, 0x52, 0x17, 0x00, 0x09, 0xf3, + 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x08, 0xc6, 0x01, 0xbc, 0x60, 0x03, 0x00, + 0x11, 0x83, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x11, 0x82, 0x03, 0x2c, 0x5e, + 0x02, 0xf0, 0x0c, 0x16, 0x01, 0x99, 0xe0, 0x06, 0x20, 0x11, 0x00, 0x03, + 0xbf, 0xde, 0x02, 0xf0, 0x0c, 0x1a, 0x01, 0x19, 0x40, 0x2f, 0x00, 0x17, + 0xa1, 0x00, 0x68, 0x5e, 0x87, 0x00, 0x09, 0xef, 0x01, 0x99, 0xde, 0x86, + 0x20, 0x11, 0x00, 0x03, 0x31, 0x5e, 0x02, 0xf0, 0x09, 0xef, 0x00, 0xa0, + 0x5e, 0x3b, 0x00, 0x97, 0xa2, 0x00, 0x20, 0x5e, 0x4e, 0xf4, 0x49, 0xef, + 0x01, 0x84, 0x60, 0x02, 0x09, 0x10, 0x48, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x09, 0xef, 0x03, 0x2b, 0x5e, 0x02, 0xf0, 0x09, 0xef, 0x00, 0x68, 0xde, + 0x4f, 0x04, 0x2c, 0x23, 0x00, 0xb0, 0x52, 0x33, 0x00, 0x17, 0x9f, 0x00, + 0xb0, 0x52, 0x2f, 0x00, 0x10, 0xeb, 0x02, 0x81, 0x52, 0x2f, 0x00, 0x06, + 0xc6, 0x00, 0xe0, 0x02, 0xab, 0x00, 0x20, 0xaa, 0x02, 0x81, 0x52, 0x2f, + 0x00, 0x09, 0xcf, 0x03, 0x29, 0x5e, 0x02, 0xf0, 0x0c, 0x29, 0x02, 0x03, + 0xde, 0xb3, 0x00, 0x0c, 0x29, 0x01, 0x91, 0x60, 0x1a, 0x84, 0xf4, 0x27, + 0x01, 0x83, 0xe0, 0x02, 0xf5, 0x97, 0xac, 0x02, 0x08, 0x52, 0x2f, 0x00, + 0x06, 0xde, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x08, 0xc6, 0x01, 0xbc, 0x60, + 0x03, 0x00, 0x10, 0x67, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x10, 0x46, 0x01, + 0x80, 0xe0, 0x06, 0x09, 0x30, 0x49, 0x02, 0x82, 0xc1, 0x1f, 0x00, 0x0c, + 0x33, 0x01, 0xbc, 0x60, 0x2f, 0x1f, 0xf0, 0x65, 0x01, 0xbc, 0x60, 0x03, + 0x00, 0x16, 0x80, 0x00, 0xe8, 0x41, 0x97, 0x00, 0x30, 0x65, 0x00, 0x69, + 0xc1, 0x97, 0x00, 0x0c, 0x30, 0x01, 0xbc, 0x60, 0x0b, 0x00, 0x17, 0x94, + 0x01, 0xbc, 0x60, 0x03, 0x00, 0x17, 0xab, 0x01, 0xbc, 0x60, 0x03, 0x00, + 0x17, 0xac, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x17, 0xad, 0x01, 0xbc, 0x60, + 0x03, 0x00, 0x17, 0xae, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x17, 0xbf, 0x01, + 0xbc, 0x60, 0x03, 0x00, 0x20, 0x20, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x17, + 0xa1, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xce, 0x01, 0x38, 0x40, 0x67, + 0x00, 0x00, 0x28, 0x01, 0x1c, 0x40, 0x67, 0x00, 0x00, 0x29, 0x01, 0xbc, + 0x60, 0x03, 0x00, 0x50, 0x49, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x17, 0xa7, + 0x01, 0xbc, 0x60, 0x03, 0x00, 0x17, 0xa8, 0x01, 0xbc, 0x60, 0x03, 0x00, + 0x17, 0xa9, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x17, 0xac, 0x01, 0xbc, 0x60, + 0x03, 0x00, 0x17, 0xad, 0x01, 0x82, 0xe0, 0x06, 0x0f, 0x10, 0x78, 0x02, + 0x06, 0xc1, 0xe3, 0x00, 0x0c, 0x45, 0x00, 0x68, 0x80, 0xa7, 0x00, 0x0c, + 0x48, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0c, 0x49, 0x00, 0x68, 0x80, 0xa7, + 0x00, 0x8c, 0x49, 0x01, 0xbc, 0x60, 0x0b, 0x1a, 0xe0, 0x00, 0x01, 0xbc, + 0x60, 0x07, 0x06, 0xc0, 0x01, 0x01, 0xbc, 0x63, 0x1b, 0x01, 0xe0, 0x02, + 0x01, 0xbc, 0x62, 0xcf, 0x0f, 0x60, 0x03, 0x01, 0xbc, 0x60, 0x03, 0x00, + 0x00, 0x04, 0x01, 0xbc, 0x60, 0x53, 0x0d, 0x80, 0x05, 0x01, 0xbc, 0x60, + 0x1f, 0x14, 0x10, 0x61, 0x01, 0xbc, 0x60, 0x13, 0x17, 0xd0, 0x60, 0x01, + 0xbc, 0x60, 0x03, 0x00, 0x08, 0x28, 0x00, 0xb0, 0x5e, 0x0f, 0x00, 0x17, + 0x85, 0x00, 0xa0, 0x44, 0xb6, 0xf0, 0x71, 0x45, 0x02, 0x87, 0x41, 0xd7, + 0x00, 0x0c, 0x54, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x0b, 0xef, 0x01, 0xbc, + 0x60, 0x03, 0x00, 0x10, 0x7d, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x10, 0x7c, + 0x01, 0xbc, 0x60, 0x63, 0x00, 0x10, 0x7b, 0x01, 0xbc, 0x60, 0x03, 0x00, + 0x10, 0x7a, 0x01, 0xac, 0x60, 0x7f, 0x00, 0x10, 0x75, 0x01, 0xbc, 0x63, + 0x47, 0x08, 0x97, 0xa1, 0x00, 0x68, 0xc1, 0xda, 0xf4, 0x2c, 0x60, 0x01, + 0x1a, 0x41, 0xdf, 0x00, 0x17, 0xa1, 0x00, 0x68, 0xde, 0x87, 0x01, 0x6c, + 0x60, 0x01, 0xbc, 0x63, 0x7b, 0x15, 0xab, 0xef, 0x03, 0xbf, 0xde, 0x02, + 0xf0, 0x0a, 0xab, 0x01, 0x88, 0x5e, 0x5c, 0xff, 0x87, 0xfc, 0x01, 0xbc, + 0x60, 0x1f, 0x1f, 0x50, 0x07, 0x01, 0xbc, 0x60, 0x03, 0x01, 0x90, 0x08, + 0x01, 0x88, 0x60, 0x06, 0x00, 0x90, 0x04, 0x03, 0x86, 0xde, 0x02, 0xf0, + 0x0a, 0x94, 0x03, 0x05, 0xde, 0x02, 0xf0, 0x0c, 0x65, 0x03, 0x86, 0xde, + 0x02, 0xf0, 0x0a, 0x94, 0x03, 0x85, 0xde, 0x02, 0xf0, 0x0c, 0x67, 0x00, + 0xb0, 0x5e, 0x87, 0x00, 0x17, 0xa1, 0x00, 0x6e, 0xe0, 0x03, 0x00, 0x2c, + 0x6b, 0x03, 0x86, 0xde, 0x02, 0xf0, 0x0a, 0x94, 0x00, 0x6e, 0xc0, 0x14, + 0x6f, 0x2c, 0x6e, 0x01, 0xbc, 0x60, 0x07, 0x00, 0x10, 0x42, 0x02, 0x07, + 0xc0, 0xaf, 0x00, 0x07, 0x85, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, + 0x03, 0x21, 0x5e, 0x02, 0xf0, 0x0c, 0x74, 0x00, 0xe0, 0x20, 0x62, 0xf4, + 0x28, 0x18, 0x00, 0xb0, 0x20, 0x63, 0x00, 0x17, 0x8b, 0x03, 0xbf, 0xde, + 0x02, 0xf0, 0x0c, 0x7c, 0x02, 0x81, 0x50, 0xc7, 0x00, 0x0c, 0x79, 0x01, + 0x1c, 0x50, 0x9f, 0x00, 0x17, 0x8b, 0x00, 0xe0, 0x5e, 0x2e, 0xf4, 0x37, + 0x8b, 0x01, 0x9c, 0x5e, 0x2e, 0x84, 0xf4, 0x27, 0x03, 0xbf, 0xde, 0x02, + 0xf0, 0x0c, 0x7c, 0x01, 0x1e, 0x50, 0x9f, 0x00, 0x17, 0x8b, 0x00, 0xe0, + 0x5e, 0x2e, 0xf4, 0x37, 0x8b, 0x01, 0x9e, 0x5e, 0x2e, 0x84, 0xf4, 0x27, + 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x01, 0x07, 0x40, 0x27, 0x00, + 0x08, 0x27, 0x00, 0xe0, 0x20, 0x9f, 0x00, 0x28, 0x27, 0x00, 0x02, 0xde, + 0x02, 0xf0, 0x00, 0x00, 0x00, 0xb0, 0x5a, 0x03, 0x00, 0x10, 0x1f, 0x00, + 0xb0, 0x5a, 0x07, 0x00, 0x10, 0x20, 0x00, 0xb0, 0x5a, 0x0b, 0x00, 0x10, + 0x21, 0x01, 0x80, 0x60, 0x07, 0x00, 0x10, 0x1d, 0x02, 0x80, 0x40, 0x77, + 0x00, 0x0c, 0x84, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x01, 0x87, + 0xe0, 0x02, 0xf5, 0x77, 0xab, 0x03, 0x91, 0x5e, 0x02, 0xf0, 0x00, 0x02, + 0x00, 0x20, 0xe3, 0xfe, 0x09, 0x00, 0x02, 0x02, 0x81, 0x5e, 0x53, 0x00, + 0x0c, 0x92, 0x02, 0x83, 0x41, 0x1f, 0x00, 0x0c, 0x8c, 0x02, 0x81, 0xde, + 0x53, 0x00, 0x0c, 0x98, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x11, 0x51, 0x01, + 0xbc, 0x60, 0x03, 0x00, 0x11, 0x52, 0x01, 0xbc, 0x62, 0x03, 0x00, 0x11, + 0x53, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x51, 0x50, 0x01, 0x89, 0x60, 0x06, + 0xf2, 0x97, 0x94, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x00, 0x02, 0x02, 0x80, + 0xc5, 0x43, 0x00, 0x00, 0x02, 0x01, 0xf0, 0xc5, 0x47, 0x00, 0x11, 0x56, + 0x01, 0x07, 0xc5, 0x47, 0x00, 0x17, 0xa1, 0x01, 0xf0, 0xc5, 0x4a, 0xf4, + 0x31, 0x55, 0x01, 0x89, 0x60, 0x0a, 0xf2, 0x97, 0x94, 0x01, 0xbc, 0x60, + 0x03, 0x08, 0x10, 0x47, 0x03, 0x92, 0xde, 0x02, 0xf0, 0x00, 0x02, 0x00, + 0x68, 0xc0, 0x17, 0x00, 0x00, 0x02, 0x02, 0x04, 0xc1, 0x07, 0x00, 0x00, + 0x02, 0x03, 0x9e, 0xde, 0x02, 0xf0, 0x0c, 0xa0, 0x03, 0xb8, 0xde, 0x02, + 0xf0, 0x00, 0x02, 0x00, 0xb0, 0x01, 0x7f, 0x00, 0x17, 0xa1, 0x00, 0x68, + 0xde, 0x84, 0x0b, 0xc0, 0x02, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0c, 0xa2, + 0x02, 0x03, 0xde, 0x53, 0x00, 0x00, 0x02, 0x00, 0x68, 0xde, 0x23, 0x00, + 0x0c, 0xa3, 0x02, 0x84, 0x5e, 0x53, 0x00, 0x00, 0x02, 0x02, 0x87, 0xc4, + 0x93, 0x00, 0x00, 0x02, 0x02, 0x82, 0xde, 0xbb, 0x00, 0x0c, 0xa6, 0x00, + 0x68, 0x2a, 0xff, 0x00, 0x0c, 0xa9, 0x00, 0x68, 0x2b, 0x87, 0xff, 0xe0, + 0x02, 0x00, 0xb0, 0x2a, 0xef, 0x00, 0x17, 0xa1, 0x00, 0x6d, 0xde, 0x85, + 0x55, 0xc0, 0x02, 0x00, 0xb0, 0x01, 0x2b, 0x00, 0x17, 0xa3, 0x02, 0x82, + 0xde, 0xbb, 0x00, 0x0c, 0xac, 0x00, 0x68, 0x2a, 0xff, 0x00, 0x0c, 0xad, + 0x00, 0xe0, 0x5e, 0x8d, 0x5c, 0x37, 0xa3, 0x00, 0xb0, 0x44, 0x0b, 0x00, + 0x17, 0xa1, 0x00, 0xb0, 0x44, 0x0f, 0x00, 0x17, 0xa2, 0x00, 0xe9, 0x5e, + 0x86, 0x23, 0x37, 0xa1, 0x00, 0xe8, 0xde, 0x8a, 0x23, 0x57, 0xa2, 0x00, + 0xe9, 0x5e, 0x86, 0xf4, 0x66, 0xe5, 0x00, 0xe8, 0xde, 0x8b, 0x00, 0x08, + 0x14, 0x00, 0xb0, 0x44, 0x1f, 0x00, 0x18, 0x00, 0x00, 0x88, 0x44, 0x23, + 0x01, 0x57, 0xa3, 0x00, 0x90, 0x44, 0x23, 0x00, 0xd7, 0xa4, 0x00, 0x6e, + 0x5e, 0x8a, 0xf4, 0x8a, 0xd7, 0x00, 0x6d, 0xaf, 0xc3, 0x00, 0x2c, 0xcd, + 0x00, 0x68, 0x81, 0x6f, 0x00, 0x0c, 0xbb, 0x00, 0x68, 0x5e, 0x23, 0x00, + 0x2c, 0xcd, 0x00, 0x68, 0x00, 0x27, 0x00, 0x2c, 0xcd, 0x00, 0xe8, 0x5e, + 0x23, 0x00, 0x37, 0xa1, 0x00, 0x69, 0xde, 0x87, 0x00, 0x0c, 0xbe, 0x00, + 0xe0, 0x5e, 0x84, 0x01, 0x37, 0xa1, 0x01, 0x3c, 0x01, 0x6f, 0x00, 0x17, + 0xa5, 0x00, 0x68, 0xde, 0x97, 0x00, 0x0c, 0xc5, 0x01, 0x38, 0x01, 0x6f, + 0x00, 0x17, 0xa5, 0x00, 0x68, 0x5e, 0x97, 0x00, 0x0c, 0xc9, 0x00, 0xe8, + 0x5e, 0x97, 0x00, 0x37, 0xa1, 0x00, 0x68, 0x5e, 0x87, 0x00, 0x0c, 0xcd, + 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0c, 0xc9, 0x00, 0xe8, 0x5e, 0x97, 0x00, + 0x37, 0xa5, 0x00, 0x80, 0xde, 0x94, 0x01, 0x37, 0xa5, 0x00, 0xe0, 0x5e, + 0x86, 0x0d, 0xb7, 0xa1, 0x00, 0x68, 0x5e, 0x87, 0x00, 0x0c, 0xcd, 0x00, + 0xe1, 0x1b, 0x96, 0xf4, 0x66, 0xe5, 0x00, 0xe0, 0xa0, 0x52, 0xf4, 0x88, + 0x14, 0x00, 0xe8, 0x5e, 0x87, 0x00, 0x37, 0xa1, 0x00, 0x6a, 0x5e, 0x87, + 0x00, 0x0c, 0xc9, 0x01, 0xbc, 0x61, 0x03, 0x00, 0x11, 0x23, 0x00, 0x69, + 0x20, 0x53, 0x00, 0x0c, 0xd1, 0x01, 0x80, 0xe0, 0x06, 0xf2, 0x97, 0x94, + 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0c, 0xd3, 0x01, 0x80, 0xe0, 0x02, 0xf2, + 0x97, 0x94, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x00, 0x02, 0x00, 0x68, 0x41, + 0x27, 0x00, 0x0c, 0xdd, 0x02, 0x84, 0x45, 0x23, 0x00, 0x0c, 0xd4, 0x00, + 0xb0, 0x44, 0x67, 0x00, 0x17, 0xa1, 0x00, 0xe8, 0x44, 0x66, 0xf4, 0x37, + 0xa2, 0x00, 0x6d, 0x5e, 0x8b, 0x00, 0x4c, 0xd6, 0x03, 0x92, 0xde, 0x02, + 0xf0, 0x0a, 0xd7, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x10, 0x96, 0x00, 0x02, + 0x5e, 0x02, 0xf0, 0x0d, 0xf4, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0d, 0xef, + 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0d, 0xff, 0x01, 0xbc, 0x60, 0x0f, 0x00, + 0x11, 0xe8, 0x03, 0x1e, 0xde, 0x02, 0xf0, 0x0c, 0xe4, 0x01, 0xbc, 0x60, + 0x03, 0x00, 0x10, 0x5c, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x90, 0x5d, 0x01, + 0xbc, 0x60, 0x53, 0x04, 0x10, 0x5e, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x10, + 0x5f, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0c, 0xe8, 0x01, 0xbc, 0x60, 0x0b, + 0x00, 0x10, 0x5c, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x90, 0x5d, 0x01, 0xbc, + 0x60, 0x43, 0x04, 0x10, 0x5e, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x10, 0x5f, + 0x01, 0xbc, 0x60, 0x03, 0x00, 0x80, 0x20, 0x02, 0x85, 0x00, 0xbf, 0x00, + 0x0d, 0x23, 0x00, 0xb0, 0x1b, 0x97, 0x00, 0x11, 0x51, 0x00, 0xb0, 0x20, + 0x53, 0x00, 0x11, 0x52, 0x00, 0x6e, 0x1b, 0x96, 0x2a, 0x8c, 0xf0, 0x00, + 0x68, 0xa0, 0x53, 0x00, 0x0c, 0xf0, 0x00, 0xe0, 0x1b, 0x96, 0x23, 0x28, + 0x15, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0c, 0xf2, 0x00, 0xb0, 0x44, 0x67, + 0x00, 0x08, 0x15, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x31, 0x50, 0x01, 0xbc, + 0x60, 0x03, 0x0c, 0x90, 0x40, 0x00, 0x00, 0xde, 0x02, 0xf0, 0x00, 0x00, + 0x00, 0x68, 0xc1, 0x03, 0x00, 0x0c, 0xf7, 0x02, 0x80, 0x45, 0x43, 0x00, + 0x0c, 0xf2, 0x00, 0x6b, 0x44, 0x65, 0x02, 0xac, 0xf2, 0x01, 0xbc, 0x60, + 0x03, 0x00, 0x11, 0x50, 0x02, 0x84, 0x45, 0x43, 0x00, 0x0c, 0xf8, 0x00, + 0xb0, 0x44, 0x67, 0x00, 0x17, 0xa1, 0x00, 0x68, 0x5e, 0x86, 0x23, 0x2c, + 0xfa, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x40, 0x20, 0x00, 0xe9, 0x1b, 0x96, + 0x2a, 0x37, 0xa1, 0x00, 0xe8, 0xa0, 0x52, 0x2a, 0x57, 0xa2, 0x00, 0xe1, + 0x44, 0x66, 0xf4, 0x31, 0x19, 0x00, 0xe1, 0xc4, 0x6a, 0xf4, 0x51, 0x1a, + 0x00, 0xe1, 0xc4, 0x6f, 0x00, 0x11, 0x1b, 0x00, 0xe0, 0xc4, 0x73, 0x00, + 0x11, 0x1c, 0x00, 0xb0, 0x44, 0x1f, 0x00, 0x18, 0x00, 0x00, 0x88, 0x44, + 0x23, 0x01, 0x57, 0xa3, 0x00, 0x90, 0x44, 0x23, 0x00, 0xd7, 0xa4, 0x00, + 0xb0, 0x44, 0x0b, 0x00, 0x17, 0xa1, 0x00, 0xb0, 0x44, 0x0f, 0x00, 0x17, + 0xa2, 0x00, 0xe9, 0x5e, 0x86, 0x23, 0x37, 0xa1, 0x00, 0xe8, 0xde, 0x8a, + 0x23, 0x57, 0xa2, 0x00, 0x69, 0xde, 0x8b, 0x00, 0x0d, 0x11, 0x00, 0xe1, + 0x44, 0x0a, 0xf4, 0x71, 0x02, 0x00, 0xe0, 0xc4, 0x0e, 0xf4, 0x91, 0x03, + 0x00, 0xe0, 0x2a, 0xef, 0x00, 0x2a, 0xbb, 0x00, 0xe8, 0x5e, 0x23, 0x00, + 0x37, 0x88, 0x00, 0x69, 0xde, 0x23, 0x00, 0x0d, 0x05, 0x00, 0xe8, 0x00, + 0x27, 0x00, 0x37, 0x88, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0d, 0x05, 0x01, + 0x86, 0x60, 0x02, 0x20, 0x11, 0x00, 0x02, 0x00, 0xde, 0x53, 0x00, 0x0d, + 0x25, 0x01, 0x80, 0xe0, 0x02, 0xf2, 0x97, 0x94, 0x00, 0x02, 0x5e, 0x02, + 0xf0, 0x0d, 0xf2, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x10, 0x40, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x0d, 0x18, 0x02, 0x00, 0x80, 0xc3, 0x00, 0x0d, 0x1c, + 0x00, 0xe0, 0x44, 0x64, 0x09, 0x57, 0xa1, 0x00, 0xe8, 0x5e, 0x86, 0x21, + 0x37, 0xa1, 0x00, 0x6c, 0xc4, 0x66, 0xf4, 0x2d, 0x1a, 0x03, 0xbf, 0xde, + 0x02, 0xf0, 0x0d, 0x25, 0x00, 0xe8, 0x01, 0x2a, 0x21, 0x26, 0xe5, 0x01, + 0xbc, 0x60, 0x03, 0x00, 0x08, 0x14, 0x00, 0xb0, 0x1b, 0x97, 0x00, 0x11, + 0x51, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x11, 0x52, 0x01, 0xbc, 0x60, 0x03, + 0x00, 0x31, 0x50, 0x02, 0x80, 0x45, 0x43, 0x00, 0x0d, 0x21, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x0c, 0xfc, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x10, 0x40, + 0x00, 0xb0, 0x01, 0x2b, 0x00, 0x11, 0x09, 0x00, 0x68, 0xaa, 0xdf, 0x00, + 0x0d, 0x27, 0x00, 0x00, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x03, 0x56, 0x5e, + 0x02, 0xf0, 0x0d, 0x29, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x01, 0x59, 0x00, + 0xb0, 0x01, 0x2f, 0x00, 0x11, 0x09, 0x01, 0xbc, 0x61, 0xcf, 0x0c, 0x10, + 0x5c, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x10, 0x5d, 0x01, 0xbc, 0x61, 0xcf, + 0x01, 0xf0, 0x5e, 0x01, 0xbc, 0x60, 0x3b, 0x0a, 0xf0, 0x5f, 0x00, 0x02, + 0x5e, 0x02, 0xf0, 0x0d, 0xfb, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0e, 0x04, + 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0d, 0xf8, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x0a, 0xd7, 0x01, 0x88, 0x5e, 0x06, 0x10, 0xd0, 0x86, 0x01, 0x02, 0x5e, + 0x07, 0x00, 0x17, 0xa1, 0x01, 0x82, 0x5e, 0x86, 0x10, 0xd0, 0x86, 0x01, + 0xbc, 0x60, 0x03, 0x06, 0x77, 0x80, 0x00, 0xb0, 0x0d, 0xef, 0x00, 0x17, + 0x81, 0x02, 0x88, 0x42, 0x1b, 0x00, 0x0d, 0x39, 0x00, 0xb0, 0x0d, 0xeb, + 0x00, 0x17, 0x81, 0x00, 0x68, 0x5e, 0x07, 0x00, 0x0d, 0x3b, 0x00, 0x02, + 0x5e, 0x02, 0xf0, 0x0d, 0xe9, 0x02, 0x0b, 0x42, 0x1b, 0x00, 0x0d, 0x3d, + 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0d, 0x3e, 0x01, 0x8b, 0x20, 0x9e, 0x10, + 0xd0, 0x86, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x00, 0xb0, 0x54, + 0x13, 0x00, 0x17, 0xa1, 0x02, 0x00, 0xde, 0x07, 0x00, 0x0d, 0x46, 0x00, + 0xb0, 0x41, 0x8b, 0x00, 0x10, 0x65, 0x01, 0xbc, 0x60, 0x03, 0x01, 0xd7, + 0xa1, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x11, 0xba, 0x00, 0xe0, 0x5e, 0x84, + 0x00, 0xf7, 0xa1, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0d, 0x4b, 0x02, 0x04, + 0x80, 0xf3, 0x00, 0x0d, 0x4b, 0x02, 0x02, 0x5e, 0x07, 0x00, 0x0d, 0x4b, + 0x02, 0x80, 0x5e, 0x07, 0x00, 0x0d, 0x4b, 0x00, 0x90, 0x00, 0x1b, 0x00, + 0x37, 0xa2, 0x00, 0xe8, 0x54, 0x12, 0xf4, 0x57, 0xa1, 0x00, 0x02, 0xde, + 0x02, 0xf0, 0x00, 0x00, 0x02, 0x04, 0x00, 0xbf, 0x00, 0x0d, 0x4f, 0x00, + 0x02, 0x5e, 0x02, 0xf0, 0x0e, 0xf2, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0d, + 0x50, 0x00, 0xa0, 0x44, 0xb6, 0xf0, 0xb1, 0x45, 0x00, 0x02, 0xde, 0x02, + 0xf0, 0x00, 0x00, 0x02, 0x00, 0x00, 0xbf, 0x00, 0x0d, 0x61, 0x00, 0x68, + 0xac, 0x07, 0x00, 0x0d, 0x61, 0x00, 0xe0, 0x5e, 0xa3, 0x00, 0x37, 0xa8, + 0x00, 0x6d, 0x5e, 0xa0, 0x05, 0xcd, 0x61, 0x00, 0xb0, 0x2c, 0xb3, 0x00, + 0x17, 0xa1, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xce, 0x00, 0xb0, 0x40, + 0x67, 0x00, 0x17, 0xa2, 0x00, 0x68, 0xde, 0xa3, 0xff, 0xed, 0x5e, 0x00, + 0xb0, 0x5e, 0x89, 0x65, 0xb7, 0xa2, 0x00, 0x6d, 0x00, 0xa7, 0x00, 0x8d, + 0x5d, 0x00, 0x6d, 0xa0, 0x9f, 0x00, 0x4d, 0x5f, 0x03, 0xbf, 0xde, 0x02, + 0xf0, 0x0d, 0x5e, 0x00, 0x68, 0xa0, 0x9f, 0x00, 0x0d, 0x5f, 0x00, 0xb8, + 0x5e, 0x89, 0x65, 0xb7, 0xa2, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xd4, + 0x01, 0xbc, 0x60, 0x03, 0x00, 0x17, 0xa8, 0x00, 0x02, 0xde, 0x02, 0xf0, + 0x00, 0x00, 0x00, 0xd8, 0x5a, 0x03, 0x01, 0x17, 0xa2, 0x01, 0xb8, 0x5a, + 0x06, 0xf4, 0x57, 0xa2, 0x00, 0xb0, 0x56, 0x03, 0x00, 0x08, 0x3c, 0x00, + 0xb0, 0x56, 0x07, 0x00, 0x08, 0x3d, 0x00, 0xb0, 0x56, 0x0b, 0x00, 0x08, + 0x3e, 0x00, 0xb0, 0x56, 0x0f, 0x00, 0x08, 0x3f, 0x00, 0xb0, 0x56, 0x13, + 0x00, 0x08, 0x40, 0x00, 0xe0, 0x56, 0x12, 0xf4, 0x48, 0x41, 0x00, 0xb0, + 0x5a, 0x03, 0x00, 0x08, 0x3a, 0x01, 0x38, 0x5e, 0x8b, 0x00, 0x08, 0x3b, + 0x00, 0xb0, 0x21, 0x07, 0x00, 0x17, 0xa4, 0x01, 0xbc, 0x60, 0x03, 0x00, + 0x17, 0xa2, 0x00, 0xb0, 0x41, 0x93, 0x00, 0x10, 0x65, 0x00, 0xb8, 0x5e, + 0x92, 0xd0, 0x17, 0xa4, 0x00, 0xe0, 0x5e, 0x06, 0xf4, 0x50, 0x63, 0x00, + 0xf0, 0x5e, 0x93, 0x00, 0x17, 0xa3, 0x00, 0xf0, 0x5e, 0x93, 0x00, 0x77, + 0xa4, 0x00, 0xe0, 0x5e, 0x8b, 0x00, 0x37, 0xa2, 0x00, 0xb8, 0x5e, 0x92, + 0xf4, 0x77, 0xa4, 0x00, 0xe0, 0x41, 0x92, 0xf4, 0x50, 0x65, 0x00, 0xe0, + 0x56, 0x02, 0xf4, 0x95, 0x80, 0x00, 0xb0, 0x56, 0x03, 0x00, 0x17, 0xa4, + 0x00, 0x6e, 0xde, 0x8b, 0x00, 0xad, 0x6f, 0x00, 0xb8, 0x5e, 0x92, 0xc0, + 0xd7, 0xa2, 0x00, 0xd8, 0x5e, 0x8b, 0x00, 0x37, 0xa2, 0x00, 0xe0, 0x20, + 0xf2, 0xf4, 0x48, 0x3c, 0x00, 0xb0, 0x20, 0xf3, 0x00, 0x17, 0xa4, 0x00, + 0xb8, 0x5e, 0x92, 0xc0, 0xf7, 0xa2, 0x00, 0xd8, 0x5e, 0x8b, 0x00, 0x37, + 0xa2, 0x00, 0xe0, 0x20, 0xf6, 0xf4, 0x48, 0x3d, 0x00, 0xd8, 0x20, 0xf7, + 0x00, 0x37, 0xa2, 0x00, 0xe0, 0x20, 0xfa, 0xf4, 0x48, 0x3e, 0x00, 0xd8, + 0x20, 0xfb, 0x00, 0x37, 0xa2, 0x00, 0xe0, 0x20, 0xfe, 0xf4, 0x48, 0x3f, + 0x00, 0xd8, 0x20, 0xff, 0x00, 0x37, 0xa2, 0x00, 0xe0, 0x21, 0x02, 0xf4, + 0x48, 0x40, 0x00, 0xd8, 0x21, 0x03, 0x00, 0x37, 0xa2, 0x00, 0xe0, 0x21, + 0x06, 0xf4, 0x48, 0x41, 0x00, 0xb0, 0x21, 0x07, 0x00, 0x17, 0xa2, 0x00, + 0xb8, 0x5e, 0x8a, 0xc0, 0x17, 0xa2, 0x00, 0x90, 0x5e, 0x8b, 0x00, 0x37, + 0xa2, 0x01, 0xbc, 0x5e, 0x89, 0x07, 0x68, 0x3b, 0x00, 0x02, 0xde, 0x02, + 0xf0, 0x00, 0x00, 0x01, 0x80, 0x60, 0x06, 0x3c, 0x91, 0xe4, 0x01, 0x87, + 0x60, 0x06, 0x3c, 0xd1, 0xe6, 0x01, 0xa8, 0x60, 0x02, 0x3c, 0xd1, 0xe6, + 0x01, 0x8b, 0x60, 0x02, 0x3c, 0xd1, 0xe6, 0x00, 0xb0, 0x5e, 0x8f, 0x00, + 0x10, 0x63, 0x00, 0xb0, 0x56, 0x03, 0x00, 0x11, 0xe7, 0x00, 0xb0, 0x56, + 0x07, 0x00, 0x11, 0xe7, 0x00, 0xb0, 0x56, 0x0b, 0x00, 0x11, 0xe7, 0x00, + 0xb0, 0x56, 0x0f, 0x00, 0x11, 0xe7, 0x01, 0xa9, 0x60, 0x42, 0x3c, 0x91, + 0xe4, 0x01, 0xa8, 0x60, 0x02, 0x3c, 0xd1, 0xe6, 0x01, 0x8b, 0x60, 0x06, + 0x3c, 0xd1, 0xe6, 0x00, 0xb0, 0x5e, 0x8b, 0x00, 0x10, 0x63, 0x01, 0xbc, + 0x60, 0x03, 0x00, 0x57, 0xa1, 0x02, 0x04, 0x56, 0x03, 0x00, 0x0d, 0x9d, + 0x01, 0xbc, 0x60, 0x03, 0x01, 0x17, 0xa1, 0x00, 0xe0, 0x41, 0x8e, 0xf4, + 0x30, 0x63, 0x00, 0xb0, 0x56, 0x03, 0x00, 0x11, 0xe7, 0x00, 0xb0, 0x56, + 0x07, 0x00, 0x11, 0xe7, 0x00, 0xb0, 0x56, 0x0b, 0x00, 0x11, 0xe7, 0x00, + 0xb0, 0x5e, 0x8b, 0x00, 0x10, 0x63, 0x01, 0xbc, 0x60, 0x03, 0x00, 0xb7, + 0xa1, 0x02, 0x04, 0xd6, 0x03, 0x00, 0x0d, 0xa7, 0x01, 0xbc, 0x60, 0x03, + 0x01, 0x17, 0xa1, 0x02, 0x06, 0x5e, 0x53, 0x00, 0x0d, 0xa7, 0x01, 0xbc, + 0x60, 0x03, 0x01, 0x97, 0xa1, 0x00, 0xe0, 0x41, 0x8e, 0xf4, 0x30, 0x63, + 0x00, 0xb0, 0x56, 0x03, 0x00, 0x11, 0xe7, 0x00, 0xb0, 0x56, 0x07, 0x00, + 0x11, 0xe7, 0x00, 0xb0, 0x56, 0x0b, 0x00, 0x11, 0xe7, 0x01, 0xbc, 0x60, + 0x03, 0x00, 0x17, 0xa1, 0x02, 0x06, 0xde, 0x53, 0x00, 0x0d, 0xb2, 0x00, + 0xb0, 0x5e, 0x8b, 0x00, 0x10, 0x63, 0x02, 0x06, 0x5e, 0x53, 0x00, 0x0d, + 0xb1, 0x00, 0xa0, 0x56, 0x3f, 0x01, 0xf7, 0xa1, 0x03, 0xbf, 0xde, 0x02, + 0xf0, 0x0d, 0xb2, 0x00, 0xa0, 0x56, 0x33, 0x01, 0xf7, 0xa1, 0x00, 0xb0, + 0x5e, 0x87, 0x00, 0x11, 0xe7, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x11, 0xe7, + 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x00, 0x68, 0x5e, 0x9b, 0x00, + 0xcd, 0xcf, 0x01, 0xbc, 0x60, 0x07, 0x02, 0x11, 0xe3, 0x00, 0x68, 0xde, + 0x9b, 0x00, 0x4d, 0xc2, 0x00, 0xe8, 0x47, 0x87, 0x01, 0x11, 0xe1, 0x01, + 0xbc, 0x60, 0x03, 0x00, 0x11, 0xe2, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x11, + 0xe2, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x11, 0xe2, 0x01, 0xbc, 0x60, 0x03, + 0x00, 0x11, 0xe2, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x11, 0xe2, 0x01, 0xbc, + 0x60, 0x03, 0x00, 0x11, 0xe2, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x11, 0xe2, + 0x01, 0xbc, 0x60, 0x03, 0x00, 0x11, 0xe2, 0x00, 0xb0, 0x61, 0x42, 0xf4, + 0x51, 0xe0, 0x00, 0xb0, 0x58, 0x03, 0x00, 0x11, 0xe2, 0x00, 0xb0, 0x58, + 0x07, 0x00, 0x11, 0xe2, 0x00, 0xb0, 0x58, 0x0b, 0x00, 0x11, 0xe2, 0x00, + 0xb0, 0x58, 0x0f, 0x00, 0x11, 0xe2, 0x00, 0xb0, 0x58, 0x13, 0x00, 0x11, + 0xe2, 0x00, 0xb0, 0x58, 0x17, 0x00, 0x11, 0xe2, 0x00, 0xb0, 0x58, 0x1b, + 0x00, 0x11, 0xe2, 0x00, 0xb0, 0x58, 0x1f, 0x00, 0x11, 0xe2, 0x00, 0xb0, + 0x5e, 0x9b, 0x00, 0x17, 0xa4, 0x00, 0x68, 0xde, 0x9b, 0x00, 0xad, 0xcd, + 0x01, 0xbc, 0x60, 0x03, 0x00, 0x77, 0xa4, 0x01, 0x92, 0xde, 0x93, 0x02, + 0x17, 0xa3, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x01, 0xbc, 0x60, + 0x07, 0x00, 0x11, 0xe3, 0x00, 0xb0, 0x58, 0x03, 0x00, 0x11, 0xe2, 0x00, + 0xb0, 0x58, 0x07, 0x00, 0x11, 0xe2, 0x00, 0xb0, 0x58, 0x0b, 0x00, 0x11, + 0xe2, 0x00, 0xb0, 0x58, 0x0f, 0x00, 0x11, 0xe2, 0x00, 0xb0, 0x58, 0x13, + 0x00, 0x11, 0xe2, 0x00, 0xb0, 0x58, 0x17, 0x00, 0x11, 0xe2, 0x00, 0xb0, + 0x58, 0x1b, 0x00, 0x11, 0xe2, 0x00, 0xb0, 0x58, 0x1f, 0x00, 0x11, 0xe2, + 0x00, 0xe0, 0x01, 0x46, 0xf0, 0x10, 0x64, 0x01, 0xbc, 0x60, 0x07, 0x00, + 0x31, 0xe3, 0x00, 0xb0, 0x58, 0x03, 0x00, 0x11, 0xe2, 0x00, 0xb0, 0x58, + 0x07, 0x00, 0x11, 0xe2, 0x00, 0xb0, 0x58, 0x0b, 0x00, 0x11, 0xe2, 0x00, + 0xb0, 0x58, 0x0f, 0x00, 0x11, 0xe2, 0x00, 0xb0, 0x58, 0x13, 0x00, 0x11, + 0xe2, 0x00, 0xb0, 0x58, 0x17, 0x00, 0x11, 0xe2, 0x00, 0xb0, 0x58, 0x1b, + 0x00, 0x11, 0xe2, 0x00, 0xb0, 0x58, 0x1f, 0x00, 0x11, 0xe2, 0x01, 0x92, + 0xe0, 0x1b, 0x00, 0x17, 0xa3, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, + 0x02, 0x87, 0x40, 0xc3, 0x00, 0x0d, 0xe4, 0x01, 0x86, 0x60, 0x06, 0xf0, + 0x10, 0x30, 0x02, 0x86, 0x40, 0xc3, 0x00, 0x0d, 0xe6, 0x00, 0xb0, 0x40, + 0xc7, 0x00, 0x17, 0x81, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x02, + 0x87, 0x40, 0xc3, 0x00, 0x0d, 0xe9, 0x00, 0xb0, 0x5e, 0x07, 0x00, 0x10, + 0x31, 0x01, 0x86, 0xe0, 0x06, 0xf0, 0x10, 0x30, 0x00, 0x02, 0xde, 0x02, + 0xf0, 0x00, 0x00, 0x00, 0x68, 0x00, 0xa7, 0x01, 0x12, 0xf8, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x0e, 0x03, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0d, 0xf2, + 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0e, 0x04, 0x00, 0x02, 0xde, 0x02, 0xf0, + 0x00, 0x00, 0x00, 0x68, 0x00, 0xa7, 0x01, 0x12, 0xc1, 0x00, 0x02, 0xde, + 0x02, 0xf0, 0x00, 0x00, 0x01, 0x81, 0x60, 0x06, 0x09, 0x30, 0x49, 0x00, + 0x68, 0x00, 0xa7, 0x00, 0x8d, 0xf7, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0e, + 0x14, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x00, 0x02, 0x5e, 0x02, + 0xf0, 0x0e, 0x14, 0x01, 0x81, 0x60, 0x02, 0x09, 0x30, 0x49, 0x00, 0x02, + 0xde, 0x02, 0xf0, 0x00, 0x00, 0x01, 0x88, 0xe0, 0x0e, 0x09, 0x30, 0x49, + 0x00, 0xb0, 0x41, 0x27, 0x00, 0x18, 0x00, 0x00, 0xb0, 0x00, 0x2b, 0x00, + 0x10, 0x02, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x01, 0xbc, 0x60, + 0x03, 0x00, 0x10, 0x02, 0x01, 0x82, 0xe0, 0x02, 0x0f, 0x10, 0x78, 0x01, + 0xbc, 0x60, 0x03, 0x00, 0x10, 0x49, 0x00, 0xb0, 0x41, 0x27, 0x00, 0x18, + 0x00, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x00, 0x68, 0x00, 0xa7, + 0x01, 0x0e, 0x05, 0x02, 0x80, 0xde, 0x53, 0x00, 0x0e, 0x0b, 0x01, 0xbc, + 0x60, 0x13, 0x07, 0x77, 0xa1, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xce, + 0x01, 0x90, 0x60, 0x02, 0x03, 0x37, 0xa2, 0x00, 0x02, 0x5e, 0x02, 0xf0, + 0x00, 0xd4, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x01, 0xbc, 0x60, + 0x13, 0x07, 0x97, 0xa1, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xce, 0x01, + 0x90, 0x60, 0x1e, 0x03, 0x37, 0xa2, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, + 0xd4, 0x01, 0xbc, 0x60, 0x13, 0x07, 0x77, 0xa1, 0x00, 0x02, 0x5e, 0x02, + 0xf0, 0x00, 0xce, 0x01, 0x90, 0x60, 0x1e, 0x03, 0x37, 0xa2, 0x00, 0x02, + 0x5e, 0x02, 0xf0, 0x00, 0xd4, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, + 0x01, 0x00, 0xde, 0x53, 0x00, 0x17, 0xa6, 0x01, 0x81, 0xde, 0x9a, 0x09, + 0x30, 0x49, 0x00, 0xb0, 0x41, 0x27, 0x00, 0x18, 0x00, 0x00, 0x02, 0xde, + 0x02, 0xf0, 0x00, 0x00, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x00, + 0xb0, 0x44, 0x67, 0x00, 0x17, 0xa2, 0x01, 0x7d, 0x5e, 0x8a, 0x23, 0x57, + 0xa3, 0x00, 0xb0, 0x1c, 0x77, 0x00, 0x17, 0xa1, 0x00, 0xb8, 0x5e, 0x84, + 0xe3, 0xd7, 0xa2, 0x02, 0x5a, 0x5e, 0x8b, 0x00, 0x0e, 0x21, 0x01, 0x80, + 0xe0, 0x06, 0xf4, 0x27, 0x1e, 0x01, 0x82, 0x5e, 0x86, 0xf2, 0x97, 0x94, + 0x00, 0xb0, 0x5e, 0x8f, 0x00, 0x07, 0x1b, 0x02, 0x00, 0x1c, 0x7b, 0x00, + 0x0e, 0x68, 0x00, 0xe8, 0x5e, 0x8c, 0xe3, 0x77, 0xa2, 0x00, 0x6d, 0x5e, + 0x88, 0xe3, 0x8e, 0x68, 0x00, 0xe0, 0x44, 0x67, 0x02, 0x87, 0x21, 0x02, + 0x85, 0xc5, 0x23, 0x00, 0x0e, 0x65, 0x00, 0x20, 0xe3, 0xfe, 0x09, 0x0e, + 0x65, 0x01, 0xbc, 0x60, 0x13, 0x09, 0x97, 0xa1, 0x00, 0x02, 0x5e, 0x02, + 0xf0, 0x00, 0xce, 0x00, 0x68, 0xc0, 0x67, 0x00, 0x0e, 0x65, 0x01, 0xbc, + 0x60, 0x13, 0x16, 0x17, 0xa1, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xce, + 0x00, 0x68, 0xc0, 0x67, 0x00, 0x0e, 0x65, 0x01, 0xbc, 0x60, 0x13, 0x09, + 0xd7, 0xa1, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xce, 0x00, 0x68, 0xc0, + 0x67, 0x00, 0x0e, 0x65, 0x01, 0xbc, 0x63, 0xff, 0x1f, 0xf7, 0xa1, 0x00, + 0x68, 0xde, 0x86, 0x2c, 0x2e, 0x65, 0x02, 0x00, 0x9c, 0x7b, 0x00, 0x0e, + 0x59, 0x01, 0x80, 0xe0, 0x00, 0xe3, 0xc7, 0x1e, 0x01, 0xbc, 0x60, 0x23, + 0x0f, 0x57, 0xa1, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xce, 0x00, 0xb0, + 0x40, 0x67, 0x00, 0x77, 0xa4, 0x00, 0xb0, 0x5e, 0x93, 0x00, 0x17, 0xa2, + 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xd4, 0x01, 0xbc, 0x60, 0x1b, 0x1b, + 0x57, 0xa1, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xce, 0x01, 0x81, 0xe0, + 0x06, 0x03, 0x37, 0xa2, 0x01, 0x86, 0xe0, 0x06, 0xf4, 0x57, 0xa2, 0x00, + 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xd4, 0x01, 0xbc, 0x60, 0x17, 0x14, 0xd7, + 0xa1, 0x01, 0xbc, 0x60, 0x03, 0x00, 0xb7, 0xa2, 0x00, 0x02, 0x5e, 0x02, + 0xf0, 0x00, 0xd4, 0x01, 0xbc, 0x60, 0x17, 0x14, 0x57, 0xa1, 0x01, 0xbc, + 0x60, 0x03, 0x18, 0x77, 0xa2, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xd4, + 0x01, 0xbc, 0x60, 0x17, 0x14, 0xb7, 0xa1, 0x01, 0xbc, 0x60, 0x03, 0x00, + 0xf7, 0xa2, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xd4, 0x01, 0xbc, 0x60, + 0x17, 0x10, 0x77, 0xa1, 0x01, 0xbc, 0x60, 0x0f, 0x04, 0x17, 0xa2, 0x00, + 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xd4, 0x01, 0xbc, 0x60, 0x17, 0x10, 0x97, + 0xa1, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x17, 0xa2, 0x00, 0x02, 0x5e, 0x02, + 0xf0, 0x00, 0xd4, 0x01, 0xbc, 0x60, 0x17, 0x10, 0xb7, 0xa1, 0x01, 0xbc, + 0x60, 0x0b, 0x00, 0x17, 0xa2, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xd4, + 0x01, 0xbc, 0x60, 0x17, 0x10, 0xd7, 0xa1, 0x01, 0xbc, 0x60, 0x03, 0x00, + 0x17, 0xa2, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xd4, 0x01, 0xbc, 0x60, + 0x17, 0x10, 0x17, 0xa1, 0x01, 0xbc, 0x60, 0x0b, 0x00, 0x37, 0xa2, 0x00, + 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xd4, 0x01, 0xbc, 0x60, 0x23, 0x0f, 0x57, + 0xa1, 0x00, 0xa8, 0x5e, 0x93, 0x00, 0x77, 0xa2, 0x00, 0x02, 0x5e, 0x02, + 0xf0, 0x00, 0xd4, 0x01, 0xbc, 0x60, 0x17, 0x10, 0x17, 0xa1, 0x00, 0x02, + 0x5e, 0x02, 0xf0, 0x00, 0xce, 0x02, 0x00, 0x40, 0x67, 0x00, 0x0e, 0x5e, + 0x00, 0x6c, 0xc4, 0x64, 0xe4, 0x2e, 0x25, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x0e, 0x65, 0x01, 0xbc, 0x60, 0x17, 0x12, 0x77, 0xa1, 0x00, 0x02, 0x5e, + 0x02, 0xf0, 0x00, 0xce, 0x00, 0x68, 0xc0, 0x67, 0x1f, 0xee, 0x65, 0x01, + 0x80, 0x60, 0x00, 0xe3, 0xc7, 0x1e, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x90, + 0x43, 0x01, 0x80, 0x60, 0x00, 0xe3, 0xc7, 0x1e, 0x01, 0x82, 0x60, 0x02, + 0xf2, 0x97, 0x94, 0x01, 0x80, 0xe0, 0x04, 0xe3, 0xc7, 0x1e, 0x01, 0xbc, + 0x60, 0x03, 0x00, 0x07, 0x1a, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0e, 0x68, + 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x02, 0x01, 0xc1, 0x1f, 0x00, + 0x0e, 0x7b, 0x02, 0x85, 0x5e, 0xaf, 0x00, 0x0e, 0x6e, 0x01, 0x85, 0x60, + 0x06, 0xf5, 0x77, 0xab, 0x00, 0xb0, 0x44, 0x67, 0x00, 0x08, 0x24, 0x00, + 0xb0, 0x44, 0x6b, 0x00, 0x08, 0x25, 0x00, 0xe9, 0x44, 0x65, 0x04, 0x97, + 0xa1, 0x00, 0xe8, 0xc4, 0x69, 0x04, 0xb7, 0xa2, 0x00, 0xd0, 0x5e, 0x87, + 0x00, 0x77, 0xa1, 0x01, 0xe1, 0xde, 0x8a, 0xf4, 0x37, 0xa2, 0x00, 0xe9, + 0x5e, 0x86, 0x26, 0x97, 0xa1, 0x00, 0xe8, 0xde, 0x8a, 0x26, 0xb7, 0xa2, + 0x00, 0x69, 0x5e, 0x8b, 0x00, 0x0e, 0x7b, 0x01, 0xbc, 0x61, 0x03, 0x00, + 0x11, 0x33, 0x00, 0xe1, 0x44, 0xda, 0xf4, 0x31, 0x36, 0x00, 0xe1, 0x44, + 0xde, 0xf4, 0x51, 0x37, 0x01, 0x85, 0x60, 0x02, 0xf5, 0x77, 0xab, 0x01, + 0xbc, 0x60, 0x03, 0x01, 0x10, 0x47, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x50, + 0x43, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x00, 0xb0, 0x45, 0x1f, + 0x00, 0x17, 0x81, 0x00, 0xb0, 0x05, 0xb7, 0x00, 0x17, 0xa6, 0x01, 0xbc, + 0x60, 0x07, 0x04, 0x10, 0x64, 0x01, 0xbc, 0x60, 0x13, 0x11, 0x10, 0x65, + 0x01, 0xbc, 0x60, 0x03, 0x00, 0x17, 0xa1, 0x02, 0x05, 0xde, 0xaf, 0x00, + 0x0e, 0x94, 0x00, 0xb0, 0x58, 0x0f, 0x00, 0x17, 0x80, 0x00, 0x68, 0x5e, + 0x84, 0x2c, 0x2e, 0x9c, 0x02, 0x00, 0x5e, 0x9b, 0x00, 0x0e, 0x94, 0x02, + 0x80, 0xda, 0x03, 0x00, 0x0e, 0x8a, 0x01, 0x18, 0x58, 0x1f, 0x00, 0x17, + 0x82, 0x00, 0xe0, 0x5e, 0x0b, 0x00, 0x37, 0x82, 0x01, 0x98, 0x5e, 0x0a, + 0xc0, 0xf6, 0x07, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0e, 0x8d, 0x01, 0x1a, + 0x58, 0x1f, 0x00, 0x17, 0x82, 0x00, 0xe0, 0x5e, 0x0b, 0x00, 0x37, 0x82, + 0x01, 0x9a, 0x5e, 0x0a, 0xc0, 0xf6, 0x07, 0x01, 0xf0, 0xde, 0x03, 0x00, + 0x37, 0x80, 0x00, 0xa0, 0x5e, 0x02, 0xc0, 0x57, 0x80, 0x00, 0xb0, 0x5e, + 0x03, 0x00, 0x16, 0x03, 0x00, 0xa0, 0x44, 0xb6, 0xf0, 0x17, 0x82, 0x00, + 0xb0, 0x5e, 0x0b, 0x00, 0x16, 0x05, 0x00, 0xe0, 0x5e, 0x0a, 0xc0, 0x96, + 0x06, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0e, 0x9c, 0x00, 0xb0, 0x58, 0x13, + 0x00, 0x17, 0x82, 0x00, 0xe8, 0x5e, 0x06, 0xf0, 0x57, 0xa5, 0x00, 0x6a, + 0xde, 0x97, 0x00, 0x0e, 0x9a, 0x00, 0xe8, 0x58, 0x16, 0xf4, 0xb6, 0x05, + 0x00, 0x69, 0xd8, 0x17, 0x00, 0x0e, 0x9a, 0x01, 0xbc, 0x60, 0x03, 0x00, + 0x16, 0x05, 0x00, 0xb0, 0x58, 0x17, 0x00, 0x17, 0xa5, 0x00, 0xe0, 0x58, + 0x12, 0xf4, 0xb6, 0x06, 0x00, 0xe0, 0x41, 0x93, 0x02, 0x10, 0x64, 0x00, + 0xe0, 0x41, 0x97, 0x06, 0xd0, 0x65, 0x00, 0xe0, 0x5e, 0x87, 0x00, 0x37, + 0xa1, 0x00, 0x90, 0x5e, 0x9b, 0x00, 0x37, 0xa6, 0x00, 0x68, 0xde, 0x87, + 0x00, 0x8e, 0x81, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x11, 0x47, 0x00, 0x02, + 0xde, 0x02, 0xf0, 0x00, 0x00, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x01, 0x6c, + 0x01, 0xbc, 0x60, 0x03, 0x00, 0x01, 0x6d, 0x01, 0xbc, 0x60, 0x07, 0x0a, + 0x10, 0x64, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x77, 0xa1, 0x00, 0xb0, 0x42, + 0x8f, 0x00, 0x17, 0x80, 0x00, 0xa0, 0x5e, 0x03, 0x01, 0xf7, 0x80, 0x00, + 0xb0, 0x5e, 0x03, 0x00, 0x01, 0x6e, 0x01, 0xbc, 0x63, 0xff, 0x1f, 0xf7, + 0xa2, 0x00, 0x68, 0xde, 0x03, 0x00, 0x0e, 0xad, 0x01, 0xbc, 0x60, 0x03, + 0x00, 0x17, 0xa2, 0x00, 0x88, 0x60, 0x06, 0xf4, 0x37, 0x81, 0x00, 0x20, + 0x05, 0xba, 0xf0, 0x2e, 0xb2, 0x00, 0x68, 0xde, 0x8a, 0xc0, 0xce, 0xb2, + 0x00, 0xe0, 0x05, 0xb3, 0x00, 0x21, 0x6c, 0x00, 0xb0, 0x05, 0xb6, 0xf0, + 0x21, 0x6d, 0x00, 0x68, 0x5e, 0x03, 0x00, 0x0e, 0xb6, 0x00, 0x20, 0x5e, + 0x06, 0xf0, 0x0e, 0xbc, 0x00, 0x6e, 0xde, 0x8a, 0xc0, 0xce, 0xbc, 0x03, + 0xbf, 0xde, 0x02, 0xf0, 0x0e, 0xb7, 0x00, 0x6d, 0xde, 0x8a, 0xc0, 0xce, + 0xbc, 0x00, 0xb0, 0x5e, 0x87, 0x00, 0x17, 0xa3, 0x00, 0xb0, 0x41, 0x93, + 0x00, 0x01, 0x66, 0x00, 0xb0, 0x58, 0x1b, 0x00, 0x17, 0xa2, 0x01, 0xbc, + 0x60, 0x03, 0x00, 0x01, 0x6c, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x01, 0x6d, + 0x00, 0xe8, 0x41, 0x93, 0x02, 0x10, 0x64, 0x00, 0xe8, 0x5e, 0x87, 0x00, + 0x37, 0xa1, 0x00, 0x69, 0xde, 0x87, 0x00, 0x0e, 0xad, 0x00, 0xb0, 0x5e, + 0x8f, 0x00, 0x01, 0x65, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x00, + 0xb0, 0x05, 0x9b, 0x00, 0x10, 0x64, 0x00, 0x6e, 0x58, 0x1b, 0x00, 0x2e, + 0xc5, 0x00, 0xe0, 0x58, 0x1b, 0x00, 0x31, 0x45, 0x03, 0xbf, 0xde, 0x02, + 0xf0, 0x0e, 0xc6, 0x00, 0xe8, 0x58, 0x1b, 0x00, 0x31, 0x45, 0x00, 0xb0, + 0x05, 0x9b, 0x00, 0x01, 0x62, 0x00, 0xb0, 0x05, 0x97, 0x00, 0x01, 0x61, + 0x00, 0xb0, 0x58, 0x0f, 0x00, 0x17, 0x85, 0x00, 0xb0, 0x58, 0x07, 0x00, + 0x17, 0x83, 0x00, 0xb0, 0x58, 0x0b, 0x00, 0x17, 0x84, 0x01, 0x18, 0x58, + 0x1f, 0x00, 0x17, 0x8c, 0x01, 0x1a, 0x58, 0x1f, 0x00, 0x17, 0x8d, 0x00, + 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x00, 0xb0, 0x05, 0x97, 0x00, 0x17, + 0x80, 0x00, 0x68, 0x5e, 0x00, 0x2c, 0x2e, 0xf1, 0x01, 0xbc, 0x60, 0x03, + 0x00, 0x11, 0x12, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x11, 0x15, 0x00, 0xb0, + 0x05, 0x9b, 0x00, 0x10, 0x64, 0x02, 0x00, 0x45, 0x23, 0x00, 0x0e, 0xdb, + 0x00, 0xb0, 0x45, 0x1f, 0x00, 0x17, 0x81, 0x00, 0xe8, 0x05, 0x92, 0xf0, + 0x37, 0x80, 0x00, 0x6a, 0xde, 0x03, 0x00, 0x0e, 0xd9, 0x00, 0xb0, 0x5e, + 0x03, 0x00, 0x11, 0x45, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0e, 0xdc, 0x01, + 0xbc, 0x60, 0x03, 0x00, 0x31, 0x45, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0e, + 0xdc, 0x00, 0xb0, 0x05, 0x93, 0x00, 0x11, 0x45, 0x00, 0xb0, 0x05, 0x83, + 0x00, 0x01, 0x69, 0x00, 0xb0, 0x05, 0x8b, 0x00, 0x01, 0x6a, 0x00, 0xb0, + 0x05, 0x8f, 0x00, 0x01, 0x6b, 0x00, 0xb0, 0x05, 0x87, 0x00, 0x01, 0x68, + 0x00, 0xb0, 0x05, 0xab, 0x00, 0x10, 0x65, 0x02, 0x84, 0x5a, 0x1f, 0x00, + 0x0e, 0xe5, 0x00, 0xb0, 0x5e, 0x17, 0x00, 0x16, 0x83, 0x01, 0x98, 0x5e, + 0x32, 0xd0, 0xf6, 0x87, 0x01, 0x9a, 0x5e, 0x36, 0xd0, 0xf6, 0x87, 0x01, + 0x84, 0x60, 0x02, 0xd0, 0xf6, 0x87, 0x00, 0xb0, 0x05, 0x93, 0x00, 0x01, + 0x60, 0x00, 0xb0, 0x05, 0x9b, 0x00, 0x01, 0x62, 0x00, 0xb0, 0x05, 0x9f, + 0x00, 0x01, 0x63, 0x00, 0xb0, 0x05, 0x97, 0x00, 0x01, 0x61, 0x00, 0xb0, + 0x05, 0x8b, 0x00, 0x10, 0x64, 0x00, 0xb0, 0x58, 0x0f, 0x00, 0x17, 0x85, + 0x00, 0xb0, 0x58, 0x07, 0x00, 0x17, 0x83, 0x00, 0xb0, 0x58, 0x0b, 0x00, + 0x17, 0x84, 0x01, 0x98, 0x58, 0x1e, 0xf1, 0x97, 0x8c, 0x01, 0x9a, 0x58, + 0x1e, 0xf1, 0xb7, 0x8d, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0e, 0xf1, 0x00, + 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x00, 0xb0, 0x05, 0x8b, 0x00, 0x10, + 0x64, 0x00, 0x6e, 0x41, 0x93, 0x2a, 0x0e, 0xfe, 0x00, 0xa0, 0x44, 0xb6, + 0xf0, 0xb7, 0xa1, 0x00, 0xb0, 0x5e, 0x87, 0x00, 0x16, 0x05, 0x00, 0xe0, + 0x58, 0x12, 0xf4, 0x36, 0x06, 0x02, 0x00, 0x00, 0xf3, 0x00, 0x0e, 0xfb, + 0x00, 0x6d, 0x41, 0x93, 0x28, 0x0e, 0xfb, 0x02, 0x00, 0xde, 0xaf, 0x00, + 0x0e, 0xfb, 0x01, 0xbc, 0x60, 0x0b, 0x02, 0x51, 0x42, 0x00, 0xb0, 0x5e, + 0x87, 0x00, 0x01, 0x6f, 0x02, 0x01, 0x5e, 0xaf, 0x00, 0x0e, 0xfe, 0x00, + 0xb0, 0x5e, 0x17, 0x00, 0x16, 0x03, 0x01, 0x81, 0x60, 0x02, 0xf5, 0x77, + 0xab, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x02, 0x01, 0x45, 0x23, + 0x00, 0x0f, 0x09, 0x02, 0x87, 0xc4, 0x93, 0x00, 0x0f, 0x09, 0x01, 0x82, + 0x60, 0x02, 0xf5, 0xd7, 0xae, 0x02, 0x01, 0x2c, 0x3b, 0x00, 0x0f, 0x06, + 0x00, 0xe0, 0x2c, 0x43, 0x00, 0x2b, 0x10, 0x01, 0x81, 0x60, 0x01, 0x61, + 0xcb, 0x0e, 0x02, 0x05, 0x5e, 0xb7, 0x00, 0x0f, 0x09, 0x00, 0xe0, 0x2a, + 0xef, 0x00, 0x2a, 0xbb, 0x01, 0x85, 0x60, 0x02, 0xf5, 0xb7, 0xad, 0x00, + 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x02, 0x02, 0x00, 0xbf, 0x00, 0x0f, + 0x17, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0f, 0x39, 0x02, 0x02, 0xde, 0xb3, + 0x00, 0x0f, 0x0f, 0x00, 0x20, 0x42, 0x8f, 0x00, 0x0c, 0x86, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x00, 0x02, 0x02, 0x88, 0x81, 0xab, 0x00, 0x0f, 0x17, + 0x02, 0x84, 0x5e, 0xff, 0x00, 0x0f, 0x0d, 0x02, 0x84, 0x5e, 0xb3, 0x00, + 0x0f, 0x0d, 0x02, 0x82, 0xde, 0xff, 0x00, 0x0f, 0x0d, 0x02, 0x82, 0x2b, + 0x47, 0x00, 0x0f, 0x15, 0x00, 0x68, 0x2a, 0xb3, 0x00, 0x0f, 0x17, 0x02, + 0x84, 0xde, 0xaf, 0x00, 0x0f, 0x0d, 0x02, 0x83, 0x5e, 0xb7, 0x00, 0x0f, + 0x0d, 0x00, 0xb0, 0x5e, 0x87, 0x00, 0x17, 0xa1, 0x00, 0x02, 0xde, 0x02, + 0xf0, 0x00, 0x00, 0x01, 0x82, 0xe0, 0x02, 0xf5, 0x97, 0xac, 0x02, 0x03, + 0xde, 0xff, 0x00, 0x0f, 0x21, 0x02, 0x84, 0x45, 0x23, 0x00, 0x0f, 0x21, + 0x02, 0x01, 0x2b, 0x47, 0x00, 0x0f, 0x21, 0x01, 0x80, 0xe0, 0x06, 0xf2, + 0x97, 0x94, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0e, 0x14, 0x01, 0x80, 0xe0, + 0x02, 0xf2, 0x97, 0x94, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0e, 0x14, 0x01, + 0x80, 0xe0, 0x02, 0xf2, 0x97, 0x94, 0x02, 0x84, 0x00, 0xc7, 0x00, 0x0d, + 0xed, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0d, 0xef, 0x02, 0x04, 0x00, 0xc7, + 0x00, 0x0f, 0x2b, 0x02, 0x84, 0xc5, 0x6f, 0x00, 0x0f, 0x37, 0x02, 0x84, + 0x45, 0x23, 0x00, 0x0f, 0x28, 0x02, 0x00, 0x42, 0x03, 0x00, 0x0f, 0x37, + 0x00, 0x68, 0x5e, 0x4b, 0x04, 0xaf, 0x37, 0x00, 0x68, 0x5e, 0x4b, 0x06, + 0xaf, 0x37, 0x00, 0x68, 0x5e, 0x4b, 0x06, 0x2f, 0x37, 0x01, 0x82, 0xe0, + 0x06, 0xf5, 0x97, 0xac, 0x02, 0x84, 0x45, 0x23, 0x00, 0x0f, 0x2e, 0x03, + 0x23, 0xde, 0x02, 0xf0, 0x0f, 0x2f, 0x01, 0x83, 0xe0, 0x06, 0xf5, 0x97, + 0xac, 0x01, 0x80, 0xe0, 0x06, 0xf2, 0x97, 0x94, 0x02, 0x84, 0x00, 0xc7, + 0x00, 0x0d, 0xed, 0x00, 0xb0, 0x2a, 0xef, 0x00, 0x17, 0xa2, 0x00, 0x6d, + 0xde, 0x89, 0x55, 0xcd, 0xed, 0x02, 0x87, 0x2b, 0x47, 0x00, 0x0d, 0xef, + 0x02, 0x00, 0x5e, 0xff, 0x00, 0x0d, 0xed, 0x02, 0x87, 0xab, 0x47, 0x00, + 0x0d, 0xef, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0d, 0xed, 0x00, 0x02, 0xde, + 0x02, 0xf0, 0x00, 0x00, 0x02, 0x02, 0x00, 0xbf, 0x00, 0x10, 0x4a, 0x00, + 0x68, 0x2b, 0x03, 0x00, 0x0f, 0x3e, 0x00, 0xe8, 0x44, 0x65, 0x58, 0x17, + 0xa1, 0x01, 0xbc, 0x63, 0xf7, 0x1d, 0x17, 0xa2, 0x00, 0x6d, 0x5e, 0x86, + 0xf4, 0x4f, 0x3e, 0x00, 0xe8, 0x44, 0x66, 0xf4, 0x4a, 0xc0, 0x00, 0x6c, + 0xc4, 0x65, 0x57, 0x2f, 0x40, 0x00, 0xe8, 0x44, 0x67, 0x00, 0x2a, 0xb9, + 0x02, 0x80, 0x45, 0x6f, 0x00, 0x0f, 0x77, 0x02, 0x03, 0xde, 0xb7, 0x00, + 0x10, 0x4a, 0x01, 0x83, 0xe0, 0x02, 0xf5, 0xb7, 0xad, 0x02, 0x02, 0xde, + 0xb3, 0x00, 0x0f, 0x46, 0x01, 0x83, 0x60, 0x06, 0x2b, 0x91, 0x5c, 0x00, + 0x02, 0x5e, 0x02, 0xf0, 0x0f, 0x19, 0x02, 0x83, 0x5e, 0xbb, 0x00, 0x0f, + 0x49, 0x00, 0xe8, 0x45, 0x89, 0x5b, 0xb7, 0xa1, 0x00, 0x6e, 0x5e, 0x85, + 0x55, 0x6f, 0x5e, 0x02, 0x04, 0xde, 0xb7, 0x00, 0x0f, 0x5a, 0x00, 0xe0, + 0x2b, 0xaf, 0x00, 0x2a, 0xeb, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x0a, 0xed, + 0x00, 0xb0, 0x2b, 0xaf, 0x00, 0x17, 0xa2, 0x02, 0x04, 0xde, 0xff, 0x00, + 0x0f, 0x50, 0x00, 0x6d, 0x5e, 0x89, 0x5d, 0x8f, 0x50, 0x01, 0x84, 0xe0, + 0x02, 0xf7, 0xf7, 0xbf, 0x02, 0x06, 0xde, 0xff, 0x00, 0x0f, 0x5a, 0x00, + 0xe0, 0x2b, 0xdf, 0x02, 0x0a, 0xf7, 0x00, 0xb0, 0x44, 0x67, 0x00, 0x0b, + 0x02, 0x01, 0x18, 0x2b, 0xdf, 0x00, 0x17, 0xa1, 0x01, 0x1a, 0x2b, 0xdf, + 0x00, 0x17, 0xa2, 0x00, 0x6e, 0x5e, 0x87, 0x00, 0x0f, 0x58, 0x00, 0x6d, + 0xde, 0x89, 0x5f, 0x0f, 0x58, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0f, 0x5a, + 0x01, 0xbc, 0x60, 0x03, 0x00, 0x0a, 0xf7, 0x01, 0x86, 0xe0, 0x02, 0xf7, + 0xf7, 0xbf, 0x02, 0x02, 0x5e, 0xff, 0x00, 0x10, 0x4a, 0x00, 0x68, 0xab, + 0x03, 0x00, 0x10, 0x4a, 0x00, 0xb0, 0x2a, 0xdf, 0x00, 0x0a, 0xc0, 0x00, + 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x01, 0x82, 0xe0, 0x02, 0xf7, 0xf7, + 0xbf, 0x02, 0x02, 0x5e, 0xff, 0x00, 0x0f, 0x6b, 0x02, 0x06, 0x00, 0xc7, + 0x00, 0x0f, 0x64, 0x02, 0x80, 0x2b, 0xeb, 0x00, 0x0f, 0x64, 0x00, 0xb0, + 0x2b, 0x43, 0x00, 0x17, 0xbb, 0x00, 0x6e, 0x2b, 0x1a, 0xf7, 0x70, 0x4a, + 0x02, 0x02, 0x5e, 0xff, 0x00, 0x0f, 0x6b, 0x00, 0xe8, 0x45, 0x89, 0x5b, + 0xb7, 0xa1, 0x00, 0x6d, 0xde, 0x85, 0x61, 0x0f, 0x69, 0x00, 0xe8, 0x44, + 0x65, 0x61, 0x37, 0xa1, 0x00, 0x6d, 0x5e, 0x85, 0x61, 0x4f, 0x6b, 0x00, + 0xb0, 0x44, 0x67, 0x00, 0x0a, 0xc0, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, + 0x00, 0x02, 0x04, 0xde, 0xb7, 0x00, 0x0f, 0x71, 0x00, 0xe8, 0x44, 0x65, + 0x56, 0x8a, 0xbc, 0x00, 0xe0, 0x2b, 0xb7, 0x00, 0x2a, 0xed, 0x00, 0xb0, + 0x2b, 0xbb, 0x00, 0x17, 0xa1, 0x00, 0x6d, 0x2b, 0xb6, 0xf4, 0x2f, 0x71, + 0x01, 0xbc, 0x60, 0x03, 0x00, 0x0a, 0xeb, 0x00, 0x68, 0xab, 0x0f, 0x00, + 0xaf, 0x74, 0x00, 0xb0, 0x44, 0x67, 0x00, 0x0a, 0xf5, 0x00, 0xb0, 0x44, + 0x6b, 0x00, 0x0a, 0xf9, 0x00, 0x68, 0xab, 0x0f, 0x01, 0x2f, 0x76, 0x00, + 0xb0, 0x44, 0x67, 0x00, 0x0b, 0x11, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, + 0x00, 0x02, 0x03, 0xde, 0xb7, 0x00, 0x0f, 0x7e, 0x02, 0x82, 0xde, 0xb3, + 0x00, 0x10, 0x4a, 0x02, 0x03, 0xc5, 0x73, 0x00, 0x10, 0x3c, 0x00, 0xe8, + 0x44, 0x65, 0x56, 0xf7, 0xa1, 0x00, 0x6d, 0x5e, 0x85, 0x56, 0x70, 0x4a, + 0x01, 0x83, 0x60, 0x06, 0xf5, 0xd7, 0xae, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x10, 0x4a, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x0a, 0xdd, 0x00, 0x6d, 0x45, + 0x87, 0x1f, 0x4f, 0x81, 0x00, 0xb0, 0x45, 0x87, 0x00, 0x0a, 0xdd, 0x00, + 0xe0, 0x44, 0x65, 0x5b, 0xb7, 0xbb, 0x00, 0xe8, 0x5e, 0xee, 0x2c, 0x2a, + 0xb7, 0x01, 0x83, 0x60, 0x02, 0xf5, 0xd7, 0xae, 0x01, 0x83, 0xe0, 0x06, + 0xf5, 0xb7, 0xad, 0x01, 0x84, 0xe0, 0x02, 0xf5, 0xb7, 0xad, 0x01, 0x82, + 0x60, 0x02, 0xf7, 0xf7, 0xbf, 0x01, 0x84, 0x60, 0x02, 0xf5, 0xb7, 0xad, + 0x01, 0x01, 0x45, 0x6f, 0x00, 0x17, 0xa1, 0x01, 0x87, 0x5e, 0x86, 0xf5, + 0x77, 0xab, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x0b, 0x0b, 0x00, 0xe8, 0x44, + 0x65, 0x56, 0xf7, 0xa1, 0x00, 0x6d, 0x5e, 0x85, 0x5e, 0x8f, 0x8b, 0x00, + 0x6d, 0x5e, 0x85, 0x56, 0x6f, 0x8f, 0x00, 0xe0, 0x2b, 0x7b, 0x00, 0x2a, + 0xde, 0x00, 0xb0, 0x2a, 0xab, 0x00, 0x17, 0xb3, 0x01, 0xbc, 0x60, 0x03, + 0x00, 0x11, 0x78, 0x00, 0xb0, 0x45, 0xe3, 0x00, 0x18, 0x00, 0x00, 0xb0, + 0x45, 0xe7, 0x00, 0x0a, 0xca, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x31, 0x78, + 0x00, 0xb0, 0x45, 0xe3, 0x00, 0x18, 0x00, 0x00, 0xb0, 0x45, 0xe7, 0x00, + 0x0a, 0xcb, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x51, 0x78, 0x00, 0xb0, 0x45, + 0xe3, 0x00, 0x18, 0x00, 0x00, 0xb0, 0x45, 0xe7, 0x00, 0x0a, 0xcc, 0x01, + 0x84, 0x60, 0x00, 0x06, 0x00, 0x30, 0x02, 0x07, 0xab, 0x33, 0x00, 0x0f, + 0x9c, 0x01, 0x84, 0x60, 0x04, 0x06, 0x00, 0x30, 0x00, 0xb0, 0x2b, 0x2b, + 0x00, 0x17, 0xbb, 0x01, 0x2a, 0x5e, 0xef, 0x00, 0x0a, 0xc3, 0x01, 0xbc, + 0x60, 0x13, 0x1c, 0x57, 0xbb, 0x02, 0x1e, 0x2b, 0x2b, 0x00, 0x0f, 0xa3, + 0x01, 0x1e, 0x2b, 0x2b, 0x00, 0x17, 0xa6, 0x00, 0x80, 0xde, 0x9a, 0xf7, + 0x77, 0xbb, 0x00, 0xb0, 0x41, 0xb7, 0x00, 0x17, 0xb3, 0x00, 0x6e, 0x2b, + 0x0f, 0x01, 0xef, 0xa7, 0x00, 0x88, 0x60, 0x05, 0x58, 0x77, 0xbb, 0x00, + 0x20, 0xde, 0xed, 0x5d, 0x0f, 0xaa, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0f, + 0xad, 0x00, 0xe8, 0x2b, 0x0f, 0x02, 0x17, 0xbb, 0x00, 0x88, 0x60, 0x06, + 0xf7, 0x77, 0xbb, 0x00, 0x20, 0x5e, 0xed, 0x5d, 0x2f, 0xad, 0x01, 0x84, + 0x60, 0x06, 0xf5, 0xb7, 0xad, 0x02, 0x04, 0x80, 0xc3, 0x00, 0x0f, 0xad, + 0x01, 0x84, 0xe0, 0x05, 0x61, 0x6b, 0x0b, 0x00, 0x6e, 0x2b, 0x0f, 0x01, + 0xef, 0xb1, 0x00, 0x88, 0x60, 0x05, 0x58, 0x77, 0xbb, 0x00, 0x20, 0xde, + 0xed, 0x5b, 0x4f, 0xb4, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0f, 0xb5, 0x00, + 0xe8, 0x2b, 0x0f, 0x02, 0x17, 0xbb, 0x00, 0x88, 0x60, 0x06, 0xf7, 0x77, + 0xbb, 0x00, 0x20, 0x5e, 0xed, 0x5b, 0x6f, 0xb5, 0x01, 0x84, 0x60, 0x05, + 0x61, 0x6b, 0x0b, 0x00, 0x68, 0xab, 0x0f, 0x00, 0xaf, 0xbf, 0x02, 0x07, + 0x5e, 0xff, 0x00, 0x0f, 0xbf, 0x01, 0x2c, 0x2b, 0x33, 0x00, 0x17, 0xa3, + 0x00, 0x6d, 0xde, 0x8d, 0x60, 0xef, 0xbf, 0x00, 0x68, 0x5e, 0x8f, 0x00, + 0x0f, 0xbf, 0x02, 0x80, 0xab, 0x2f, 0x00, 0x0f, 0xbd, 0x01, 0x83, 0x60, + 0x05, 0x61, 0x6b, 0x0b, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0f, 0xbf, 0x00, + 0xb0, 0x2b, 0xf3, 0x00, 0x0a, 0xf6, 0x00, 0xb0, 0x44, 0x6b, 0x00, 0x0a, + 0xfd, 0x02, 0x81, 0xab, 0xeb, 0x00, 0x0f, 0xcc, 0x00, 0x68, 0xab, 0x0f, + 0x01, 0x2f, 0xcc, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x0a, 0xe0, 0x00, 0x68, + 0x2c, 0x47, 0x00, 0x0f, 0xcc, 0x00, 0xe8, 0x44, 0x65, 0x62, 0x37, 0xa1, + 0x00, 0x6d, 0x5e, 0x85, 0x62, 0x4f, 0xc9, 0x00, 0xb0, 0x2c, 0x4b, 0x00, + 0x17, 0xa2, 0x00, 0xe0, 0x5e, 0x89, 0x62, 0x77, 0xa2, 0x00, 0x6d, 0xde, + 0x86, 0xf4, 0x4f, 0xcb, 0x02, 0x00, 0xac, 0x3b, 0x00, 0x0f, 0xcc, 0x01, + 0x85, 0x60, 0x05, 0x61, 0x6b, 0x0b, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x0f, + 0xcc, 0x01, 0x80, 0xe0, 0x01, 0x61, 0xcb, 0x0e, 0x00, 0x68, 0xab, 0x0f, + 0x01, 0x0f, 0xcf, 0x00, 0xb0, 0x2a, 0xdf, 0x00, 0x0a, 0xd7, 0x01, 0x87, + 0xe0, 0x06, 0xf7, 0xf7, 0xbf, 0x02, 0x07, 0xde, 0xff, 0x00, 0x0f, 0xd1, + 0x01, 0x81, 0xe0, 0x05, 0x61, 0x6b, 0x0b, 0x00, 0x68, 0x2b, 0x0f, 0x00, + 0x2f, 0xd5, 0x00, 0x68, 0x2b, 0x0f, 0x01, 0xef, 0xd5, 0x00, 0x68, 0x2b, + 0x0f, 0x03, 0x0f, 0xd5, 0x00, 0x68, 0xab, 0x0f, 0x00, 0x8f, 0xda, 0x01, + 0x82, 0x60, 0x06, 0xf7, 0xf7, 0xbf, 0x00, 0xb0, 0x2a, 0xdf, 0x00, 0x0a, + 0xbf, 0x00, 0x68, 0xab, 0x0f, 0x00, 0x8f, 0xda, 0x01, 0x1a, 0x2b, 0x2f, + 0x00, 0x0a, 0xc6, 0x00, 0xb0, 0x2a, 0xdf, 0x00, 0x0a, 0xce, 0x02, 0x02, + 0xde, 0xbb, 0x00, 0x0f, 0xe0, 0x02, 0x84, 0xde, 0xff, 0x00, 0x0f, 0xdd, + 0x02, 0x06, 0xde, 0xff, 0x00, 0x0f, 0xe0, 0x00, 0xb0, 0x2b, 0xaf, 0x00, + 0x17, 0xa1, 0x00, 0x6d, 0xde, 0x85, 0x5d, 0x8f, 0xe0, 0x01, 0x82, 0xe0, + 0x05, 0x61, 0x6b, 0x0b, 0x00, 0xe0, 0x5e, 0xcd, 0x55, 0x77, 0xb3, 0x01, + 0x82, 0x60, 0x02, 0xf5, 0xd7, 0xae, 0x00, 0xb0, 0x2c, 0x43, 0x00, 0x17, + 0xa1, 0x00, 0xb0, 0x2a, 0xef, 0x00, 0x17, 0xa2, 0x00, 0x6d, 0x5e, 0x89, + 0x55, 0xcf, 0xe7, 0x02, 0x85, 0x5e, 0xb7, 0x00, 0x0f, 0xf0, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x0f, 0xe9, 0x00, 0x6d, 0x5e, 0x85, 0x60, 0xaf, 0xf2, + 0x02, 0x81, 0x2c, 0x3b, 0x00, 0x0f, 0xf0, 0x00, 0xb0, 0x44, 0x0b, 0x00, + 0x17, 0xa3, 0x00, 0xb0, 0x44, 0x0f, 0x00, 0x17, 0xa2, 0x00, 0xe9, 0x5e, + 0x8e, 0x23, 0x37, 0xa3, 0x00, 0xe8, 0xde, 0x8a, 0x23, 0x57, 0xa2, 0x00, + 0x69, 0x5e, 0x8b, 0x00, 0x0f, 0xf2, 0x00, 0x68, 0xde, 0x8b, 0x00, 0x0f, + 0xf2, 0x00, 0x6e, 0x5e, 0x8e, 0xf6, 0x6f, 0xf2, 0x01, 0x82, 0x60, 0x06, + 0xf5, 0xd7, 0xae, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x11, 0x51, 0x01, 0xbc, + 0x60, 0x13, 0x1c, 0x57, 0xbb, 0x01, 0x2c, 0x2b, 0x33, 0x00, 0x17, 0xa2, + 0x00, 0x80, 0xde, 0x8a, 0xf7, 0x77, 0xbb, 0x00, 0xb0, 0x41, 0xb7, 0x00, + 0x17, 0xa2, 0x00, 0x68, 0x2b, 0x0f, 0x00, 0x4f, 0xfb, 0x00, 0x68, 0x2b, + 0x0f, 0x02, 0x4f, 0xfb, 0x00, 0x68, 0x2b, 0x0f, 0x02, 0x6f, 0xfb, 0x00, + 0x68, 0x2b, 0x0f, 0x00, 0x6f, 0xfb, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x10, + 0x09, 0x01, 0x84, 0xe0, 0x06, 0xf5, 0xb7, 0xad, 0x00, 0x68, 0x5e, 0x8b, + 0x00, 0x10, 0x02, 0x00, 0xb0, 0x5e, 0x8b, 0x00, 0x0a, 0xac, 0x01, 0x82, + 0xe0, 0x06, 0xf5, 0xd7, 0xae, 0x00, 0xe0, 0x2b, 0xc3, 0x00, 0x2a, 0xf0, + 0x00, 0x6e, 0x5e, 0x89, 0x60, 0xd0, 0x02, 0x01, 0x82, 0x60, 0x05, 0x61, + 0x6b, 0x0b, 0x00, 0xe8, 0x44, 0x65, 0x56, 0xf7, 0xa1, 0x00, 0xb0, 0x44, + 0x6b, 0x00, 0x17, 0xa2, 0x00, 0xb0, 0x44, 0x67, 0x00, 0x17, 0xa3, 0x00, + 0x68, 0xde, 0x8a, 0x23, 0x50, 0x02, 0x00, 0xe9, 0x5e, 0x8e, 0xf4, 0x2a, + 0xb4, 0x00, 0xe8, 0xde, 0x8b, 0x00, 0x0a, 0xb5, 0x01, 0x84, 0x60, 0x02, + 0xf7, 0xf7, 0xbf, 0x02, 0x82, 0xde, 0xb3, 0x00, 0x10, 0x4a, 0x02, 0x03, + 0xc5, 0x73, 0x00, 0x10, 0x3c, 0x00, 0xb0, 0x2a, 0xc3, 0x00, 0x17, 0xa2, + 0x00, 0xb0, 0x2a, 0xcb, 0x00, 0x17, 0xa3, 0x00, 0x68, 0xab, 0x0f, 0x00, + 0x90, 0x16, 0x02, 0x80, 0x2b, 0xeb, 0x00, 0x10, 0x16, 0x00, 0xb0, 0x2b, + 0x1b, 0x00, 0x17, 0xa1, 0x00, 0x6d, 0x5e, 0x85, 0x59, 0x30, 0x12, 0x01, + 0x80, 0xe0, 0x05, 0x61, 0x6b, 0x0b, 0x00, 0x68, 0x5e, 0x87, 0x00, 0x10, + 0x16, 0x00, 0x68, 0x2b, 0xff, 0x00, 0x10, 0x16, 0x00, 0xb0, 0x2b, 0xff, + 0x00, 0x17, 0xa2, 0x00, 0xb0, 0x2c, 0x03, 0x00, 0x17, 0xa3, 0x00, 0x68, + 0x5e, 0x8f, 0x00, 0x10, 0x1c, 0x00, 0x68, 0x2b, 0x03, 0x00, 0x10, 0x1c, + 0x00, 0xe8, 0x44, 0x65, 0x58, 0x17, 0xa1, 0x00, 0xe0, 0x5e, 0x8e, 0xf4, + 0x57, 0xa2, 0x00, 0x6d, 0x5e, 0x86, 0xf4, 0x50, 0x1c, 0x01, 0x81, 0x60, + 0x05, 0x61, 0x6b, 0x0b, 0x02, 0x81, 0xab, 0x47, 0x00, 0x10, 0x21, 0x02, + 0x00, 0x5e, 0xff, 0x00, 0x10, 0x21, 0x02, 0x04, 0x45, 0x23, 0x00, 0x10, + 0x21, 0x03, 0xa0, 0xde, 0x02, 0xf0, 0x10, 0x21, 0x01, 0x83, 0xe0, 0x05, + 0x61, 0x6b, 0x0b, 0x02, 0x80, 0x80, 0xbf, 0x00, 0x10, 0x4a, 0x02, 0x82, + 0x5e, 0xbb, 0x00, 0x10, 0x4a, 0x02, 0x82, 0x2b, 0xeb, 0x00, 0x10, 0x36, + 0x02, 0x81, 0xac, 0x2f, 0x00, 0x10, 0x36, 0x02, 0x80, 0xac, 0x2f, 0x00, + 0x10, 0x36, 0x02, 0x81, 0x2c, 0x2f, 0x00, 0x10, 0x36, 0x02, 0x82, 0x2c, + 0x2f, 0x00, 0x10, 0x36, 0x02, 0x88, 0x81, 0xab, 0x00, 0x10, 0x36, 0x02, + 0x82, 0xac, 0x2f, 0x00, 0x10, 0x2f, 0x02, 0x80, 0x2b, 0x2f, 0x00, 0x10, + 0x36, 0x02, 0x83, 0x2c, 0x2f, 0x00, 0x10, 0x2f, 0x02, 0x85, 0x2c, 0x2f, + 0x00, 0x10, 0x2f, 0x02, 0x84, 0x2c, 0x2f, 0x00, 0x10, 0x36, 0x02, 0x84, + 0xac, 0x2f, 0x00, 0x10, 0x36, 0x02, 0x83, 0xac, 0x2f, 0x00, 0x10, 0x36, + 0x02, 0x83, 0x5e, 0xb7, 0x00, 0x10, 0x35, 0x02, 0x04, 0xde, 0xaf, 0x00, + 0x10, 0x35, 0x02, 0x81, 0xde, 0xbb, 0x00, 0x10, 0x35, 0x01, 0x84, 0xe0, + 0x02, 0xf5, 0x77, 0xab, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x11, 0x3a, 0x03, + 0xbf, 0xde, 0x02, 0xf0, 0x10, 0x4a, 0x01, 0x83, 0xe0, 0x02, 0x2b, 0x91, + 0x5c, 0x02, 0x07, 0x01, 0xab, 0x00, 0x10, 0x39, 0x01, 0x80, 0xe0, 0x02, + 0x09, 0xd0, 0x4e, 0x01, 0xbc, 0x60, 0x03, 0x18, 0x51, 0x78, 0x00, 0xb0, + 0x45, 0xe3, 0x00, 0x18, 0x00, 0x01, 0x80, 0x60, 0x02, 0x2f, 0x31, 0x79, + 0x00, 0xe8, 0x44, 0x65, 0x56, 0xf7, 0xa1, 0x00, 0x6d, 0x5e, 0x85, 0x55, + 0x70, 0x4a, 0x02, 0x81, 0x01, 0xab, 0x00, 0x10, 0x42, 0x02, 0x00, 0x81, + 0xab, 0x00, 0x10, 0x44, 0x02, 0x84, 0x2c, 0x2f, 0x00, 0x10, 0x44, 0x02, + 0x80, 0xac, 0x2f, 0x00, 0x10, 0x44, 0x01, 0x83, 0x60, 0x02, 0x2b, 0x91, + 0x5c, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x10, 0x4a, 0x01, 0x83, 0x60, 0x02, + 0x2b, 0x91, 0x5c, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0f, 0x24, 0x02, 0x83, + 0x5e, 0xb7, 0x00, 0x10, 0x4a, 0x01, 0x84, 0xe0, 0x06, 0xf5, 0x77, 0xab, + 0x00, 0xe0, 0x2b, 0x3f, 0x00, 0x2a, 0xcf, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x11, 0x22, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x01, 0x84, 0xe0, + 0x02, 0xf5, 0xb7, 0xad, 0x01, 0x83, 0x60, 0x02, 0xf5, 0xd7, 0xae, 0x01, + 0x82, 0xe0, 0x02, 0xf5, 0xd7, 0xae, 0x01, 0x82, 0xe0, 0x02, 0xf7, 0xf7, + 0xbf, 0x01, 0x84, 0xe0, 0x02, 0xf7, 0xf7, 0xbf, 0x01, 0xbc, 0x60, 0x03, + 0x00, 0x0a, 0xd9, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x0a, 0xce, 0x01, 0xbc, + 0x60, 0x03, 0x00, 0x0a, 0xc6, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x0a, 0xf0, + 0x01, 0x87, 0x60, 0x01, 0x60, 0x2b, 0x01, 0x00, 0x02, 0xde, 0x02, 0xf0, + 0x00, 0x00, 0x02, 0x02, 0x00, 0xbf, 0x00, 0x10, 0x82, 0x02, 0x83, 0xde, + 0xff, 0x00, 0x10, 0x91, 0x01, 0x83, 0xe0, 0x06, 0xf7, 0xf7, 0xbf, 0x01, + 0xbc, 0x60, 0x03, 0x02, 0x11, 0x5d, 0x00, 0xb0, 0x2a, 0xaf, 0x00, 0x11, + 0x5e, 0x01, 0x85, 0x60, 0x06, 0x0b, 0x70, 0x5b, 0x01, 0x85, 0x60, 0x06, + 0x0b, 0xf0, 0x5f, 0x02, 0x80, 0x45, 0x6b, 0x00, 0x10, 0x63, 0x01, 0x8b, + 0x60, 0x02, 0x2b, 0x91, 0x5c, 0x01, 0xbc, 0x60, 0x03, 0x18, 0x51, 0x78, + 0x00, 0xb0, 0x45, 0xe3, 0x00, 0x18, 0x00, 0x01, 0x80, 0x60, 0x02, 0x2f, + 0x31, 0x79, 0x01, 0x88, 0x60, 0x0e, 0x2b, 0x51, 0x5a, 0x01, 0xbc, 0x60, + 0x03, 0x00, 0x37, 0xa3, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x11, 0x6c, 0x00, + 0x68, 0x2a, 0xd3, 0x00, 0x10, 0x68, 0x01, 0x84, 0x60, 0x06, 0xf7, 0xf7, + 0xbf, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x0a, 0xb4, 0x00, 0x02, 0x5e, 0x02, + 0xf0, 0x10, 0x4b, 0x00, 0xe8, 0x44, 0x69, 0x60, 0x97, 0xa1, 0x00, 0x6e, + 0xde, 0x87, 0x00, 0x30, 0x70, 0x00, 0xb0, 0x2b, 0xef, 0x00, 0x0a, 0xf6, + 0x01, 0xbc, 0x60, 0x03, 0x00, 0x0a, 0xf5, 0x00, 0x68, 0x2b, 0x03, 0x00, + 0x10, 0x70, 0x00, 0xb0, 0x44, 0x67, 0x00, 0x0a, 0xbf, 0x00, 0xe8, 0x44, + 0x65, 0x56, 0x0a, 0xc0, 0x02, 0x80, 0x80, 0xbf, 0x00, 0x10, 0x76, 0x02, + 0x81, 0xde, 0xbb, 0x00, 0x10, 0x7d, 0x02, 0x00, 0x45, 0x6f, 0x00, 0x10, + 0x76, 0x02, 0x83, 0xc5, 0x73, 0x00, 0x10, 0x76, 0x01, 0xbc, 0x63, 0xff, + 0x1f, 0xf7, 0xa1, 0x00, 0x68, 0xc5, 0x86, 0xf4, 0x30, 0x7d, 0x01, 0x8b, + 0x60, 0x0e, 0x2b, 0x91, 0x5c, 0x01, 0xbc, 0x60, 0x03, 0x18, 0x51, 0x78, + 0x00, 0xb0, 0x45, 0xe3, 0x00, 0x18, 0x00, 0x01, 0x8b, 0x2b, 0x46, 0x2f, + 0x31, 0x79, 0x01, 0x83, 0xe0, 0x02, 0xf5, 0xb7, 0xad, 0x01, 0x84, 0xe0, + 0x02, 0xf5, 0x77, 0xab, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x11, 0x2d, 0x01, + 0x83, 0x60, 0x02, 0x2b, 0x91, 0x5c, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0f, + 0x24, 0x01, 0x83, 0xe0, 0x06, 0xf5, 0xb7, 0xad, 0x01, 0x84, 0xe0, 0x06, + 0xf5, 0x77, 0xab, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x11, 0x2d, 0x01, 0x8d, + 0x60, 0x02, 0x0b, 0xf0, 0x5f, 0x01, 0x88, 0x60, 0x0e, 0x2b, 0x51, 0x5a, + 0x02, 0x81, 0x81, 0xab, 0x00, 0x10, 0x8a, 0x01, 0x8b, 0x60, 0x06, 0x2b, + 0x91, 0x5c, 0x01, 0xbc, 0x60, 0x03, 0x18, 0x51, 0x78, 0x00, 0xb0, 0x45, + 0xe3, 0x00, 0x18, 0x00, 0x01, 0x80, 0x60, 0x02, 0x2f, 0x31, 0x79, 0x03, + 0xbf, 0xde, 0x02, 0xf0, 0x10, 0x8e, 0x01, 0x8b, 0x60, 0x02, 0x2b, 0x91, + 0x5c, 0x01, 0xbc, 0x60, 0x03, 0x18, 0x51, 0x78, 0x00, 0xb0, 0x45, 0xe3, + 0x00, 0x18, 0x00, 0x01, 0x80, 0x60, 0x02, 0x2f, 0x31, 0x79, 0x01, 0x83, + 0xe0, 0x02, 0xf5, 0xb7, 0xad, 0x01, 0x84, 0xe0, 0x02, 0xf5, 0x77, 0xab, + 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x10, 0x4b, 0x00, 0x02, 0xde, 0x02, 0xf0, + 0x00, 0x00, 0x00, 0xb0, 0x44, 0x6b, 0x00, 0x0b, 0x04, 0x02, 0x02, 0xde, + 0xb3, 0x00, 0x10, 0x96, 0x01, 0x83, 0x60, 0x06, 0x2b, 0x91, 0x5c, 0x00, + 0x02, 0x5e, 0x02, 0xf0, 0x0f, 0x19, 0x02, 0x02, 0x00, 0xbf, 0x00, 0x10, + 0xa6, 0x01, 0x83, 0xe0, 0x02, 0xf7, 0xf7, 0xbf, 0x02, 0x03, 0xc5, 0x73, + 0x00, 0x10, 0x9f, 0x02, 0x00, 0x80, 0xbf, 0x00, 0x10, 0x9f, 0x01, 0x8b, + 0x60, 0x0e, 0x2b, 0x91, 0x5c, 0x01, 0xbc, 0x60, 0x03, 0x18, 0x51, 0x78, + 0x00, 0xb0, 0x45, 0xe3, 0x00, 0x18, 0x00, 0x01, 0x8b, 0x2b, 0x46, 0x2f, + 0x31, 0x79, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x10, 0xa3, 0x01, 0x8b, 0x60, + 0x02, 0x2b, 0x91, 0x5c, 0x01, 0xbc, 0x60, 0x03, 0x18, 0x51, 0x78, 0x00, + 0xb0, 0x45, 0xe3, 0x00, 0x18, 0x00, 0x01, 0x80, 0x60, 0x02, 0x2f, 0x31, + 0x79, 0x01, 0x82, 0xe0, 0x02, 0xf5, 0x97, 0xac, 0x01, 0xbc, 0x60, 0x03, + 0x00, 0x17, 0xa3, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x11, 0x6c, 0x00, 0x02, + 0xde, 0x02, 0xf0, 0x00, 0x00, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x70, 0x10, + 0x01, 0xbc, 0x63, 0xff, 0x1f, 0xf0, 0xc5, 0x01, 0xbc, 0x63, 0xff, 0x1f, + 0xf0, 0xcb, 0x00, 0xb0, 0x40, 0x47, 0x00, 0x10, 0xe5, 0x00, 0xb0, 0x40, + 0x47, 0x00, 0x10, 0xeb, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x90, 0x10, 0x01, + 0xbc, 0x63, 0xff, 0x1f, 0xf0, 0xc6, 0x01, 0xbc, 0x63, 0xff, 0x1f, 0xf0, + 0xcc, 0x00, 0xb0, 0x40, 0x47, 0x00, 0x10, 0xe6, 0x00, 0xb0, 0x40, 0x47, + 0x00, 0x10, 0xec, 0x01, 0xbc, 0x60, 0x03, 0x00, 0xb0, 0x10, 0x01, 0xbc, + 0x63, 0xff, 0x1f, 0xf0, 0xc7, 0x01, 0xbc, 0x63, 0xff, 0x1f, 0xf0, 0xcd, + 0x00, 0xb0, 0x40, 0x47, 0x00, 0x10, 0xe7, 0x00, 0xb0, 0x40, 0x47, 0x00, + 0x10, 0xed, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x10, 0x10, 0x00, 0xb0, 0x40, + 0x43, 0x00, 0x18, 0x00, 0x01, 0xbc, 0x63, 0xff, 0x1f, 0xf0, 0xc8, 0x00, + 0xb0, 0x40, 0x47, 0x00, 0x10, 0xe8, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x30, + 0x10, 0x00, 0xb0, 0x40, 0x43, 0x00, 0x18, 0x00, 0x01, 0xbc, 0x63, 0xff, + 0x1f, 0xf0, 0xc9, 0x00, 0xb0, 0x40, 0x47, 0x00, 0x10, 0xe9, 0x01, 0xbc, + 0x60, 0x03, 0x00, 0x50, 0x10, 0x00, 0xb0, 0x40, 0x43, 0x00, 0x18, 0x00, + 0x01, 0xbc, 0x63, 0xff, 0x1f, 0xf0, 0xca, 0x00, 0xb0, 0x40, 0x47, 0x00, + 0x10, 0xea, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x01, 0xbc, 0x60, + 0x03, 0x00, 0x37, 0xa2, 0x00, 0x20, 0xe3, 0xfe, 0x09, 0x11, 0x01, 0x00, + 0x20, 0xe0, 0x42, 0x0d, 0x91, 0x01, 0x02, 0x80, 0x42, 0x03, 0x00, 0x11, + 0x01, 0x02, 0x84, 0x45, 0x23, 0x00, 0x11, 0x01, 0x03, 0x91, 0x5e, 0x02, + 0xf0, 0x11, 0x01, 0x00, 0x68, 0xab, 0x67, 0x00, 0x11, 0x01, 0x02, 0x82, + 0xde, 0xff, 0x00, 0x11, 0x01, 0x02, 0x80, 0x5e, 0xff, 0x00, 0x11, 0x36, + 0x02, 0x01, 0x80, 0xc7, 0x00, 0x11, 0x2d, 0x02, 0x82, 0xde, 0xb3, 0x00, + 0x11, 0x01, 0x02, 0x04, 0x80, 0xc7, 0x00, 0x10, 0xee, 0x00, 0x68, 0x5e, + 0x8b, 0x00, 0x10, 0xda, 0x00, 0xb0, 0x2b, 0x9b, 0x00, 0x17, 0xa1, 0x00, + 0x6e, 0xab, 0x82, 0xf4, 0x30, 0xda, 0x02, 0x03, 0xc5, 0x73, 0x00, 0x10, + 0xee, 0x00, 0x68, 0x2a, 0xb3, 0x00, 0x10, 0xd9, 0x00, 0x68, 0x2a, 0xd3, + 0x00, 0x10, 0xda, 0x00, 0xe8, 0x44, 0x65, 0x56, 0x97, 0xa1, 0x00, 0xe8, + 0x2a, 0xb2, 0xf4, 0x37, 0xa1, 0x00, 0x6a, 0xde, 0x85, 0x55, 0xb0, 0xee, + 0x00, 0x6a, 0xde, 0x85, 0x5b, 0x10, 0xee, 0x00, 0x68, 0x2a, 0xff, 0x00, + 0x10, 0xee, 0x02, 0x03, 0xde, 0x53, 0x00, 0x10, 0xdd, 0x00, 0xb0, 0x2b, + 0x9f, 0x00, 0x0a, 0xad, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x11, 0x2d, 0x01, + 0xbc, 0x60, 0x03, 0x02, 0x57, 0x92, 0x01, 0xbc, 0x63, 0xff, 0x1f, 0xf0, + 0xc3, 0x01, 0xbc, 0x60, 0x03, 0x09, 0x10, 0xe3, 0x01, 0x86, 0x5e, 0x8a, + 0x1c, 0x70, 0xe3, 0x01, 0x84, 0x60, 0x06, 0x1c, 0x70, 0xe3, 0x00, 0x68, + 0x2b, 0x07, 0x00, 0x10, 0xe4, 0x01, 0x85, 0xe0, 0x06, 0x1c, 0x70, 0xe3, + 0x01, 0xbc, 0x60, 0x03, 0x03, 0x97, 0x82, 0x00, 0x02, 0x5e, 0x02, 0xf0, + 0x11, 0x0b, 0x01, 0xbc, 0x63, 0xff, 0x1f, 0xf0, 0xc4, 0x00, 0xb0, 0x54, + 0x13, 0x00, 0x10, 0xe4, 0x00, 0xe0, 0x43, 0x91, 0x5b, 0xf0, 0xe4, 0x00, + 0x02, 0x5e, 0x02, 0xf0, 0x10, 0xa7, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x10, + 0xee, 0x01, 0xbc, 0x63, 0xff, 0x1f, 0xf0, 0xce, 0x00, 0xe0, 0x2b, 0x07, + 0x00, 0x2a, 0xc1, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x10, 0xfb, 0x02, 0x83, + 0x5e, 0xb7, 0x00, 0x11, 0x01, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x01, 0x00, + 0x00, 0xb0, 0x5e, 0xcf, 0x00, 0x10, 0xe4, 0x00, 0x68, 0x2a, 0xb3, 0x00, + 0x10, 0xf8, 0x00, 0xb0, 0x2a, 0xf3, 0x00, 0x10, 0xe4, 0x02, 0x80, 0x45, + 0x6f, 0x00, 0x10, 0xf8, 0x00, 0xe8, 0x44, 0x65, 0x56, 0x97, 0xa1, 0x00, + 0xe8, 0x2a, 0xb2, 0xf4, 0x37, 0xa1, 0x00, 0x69, 0x5e, 0x87, 0x00, 0x10, + 0xf8, 0x00, 0xe0, 0x5e, 0x85, 0x57, 0x90, 0xe4, 0x01, 0xbc, 0x60, 0x03, + 0x01, 0xd7, 0x82, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x11, 0x0b, 0x03, 0xbf, + 0xde, 0x02, 0xf0, 0x10, 0xfb, 0x00, 0xb0, 0x00, 0x47, 0x00, 0x10, 0x86, + 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x11, 0xad, 0x00, 0x02, 0x5e, 0x02, 0xf0, + 0x0d, 0x32, 0x01, 0x90, 0x60, 0x0a, 0x09, 0x10, 0x48, 0x01, 0x84, 0x60, + 0x06, 0xf5, 0x97, 0xac, 0x01, 0xbc, 0x61, 0x33, 0x00, 0x70, 0x80, 0x00, + 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x02, 0x80, 0x5e, 0xff, 0x00, 0x11, + 0x06, 0x02, 0x81, 0xde, 0xbb, 0x00, 0x11, 0x06, 0x02, 0x01, 0x80, 0xc7, + 0x00, 0x11, 0x2d, 0x02, 0x04, 0x80, 0xc7, 0x00, 0x11, 0x2d, 0x01, 0x80, + 0x60, 0x02, 0xf7, 0xf7, 0xbf, 0x02, 0x80, 0xc2, 0x8f, 0x00, 0x11, 0x2e, + 0x02, 0x01, 0xde, 0xbb, 0x00, 0x11, 0x2e, 0x01, 0xbc, 0x60, 0x03, 0x00, + 0x17, 0xa2, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x10, 0xc4, 0x01, 0xbc, 0x63, + 0xff, 0x1f, 0xf0, 0xc0, 0x01, 0xbc, 0x63, 0xff, 0x1f, 0xf0, 0xc1, 0x02, + 0x85, 0xde, 0xff, 0x00, 0x11, 0x1b, 0x00, 0x68, 0x5e, 0x4b, 0x06, 0x31, + 0x14, 0x00, 0xb0, 0x2b, 0x4f, 0x00, 0x17, 0xa1, 0x00, 0x6d, 0xab, 0x06, + 0xf4, 0x31, 0x1b, 0x01, 0xbc, 0x60, 0x03, 0x01, 0x37, 0x80, 0x00, 0xb0, + 0x2b, 0x53, 0x00, 0x17, 0xa1, 0x00, 0x6d, 0x2b, 0x06, 0xf4, 0x31, 0x16, + 0x02, 0x81, 0x2b, 0xeb, 0x00, 0x11, 0x16, 0x01, 0xbc, 0x60, 0x03, 0x01, + 0x77, 0x80, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x37, 0x81, 0x00, 0x02, 0x5e, + 0x02, 0xf0, 0x00, 0xdb, 0x01, 0xd2, 0xde, 0x0a, 0xa0, 0x30, 0xe0, 0x00, + 0xb0, 0x54, 0x0b, 0x00, 0x10, 0xe1, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x11, + 0x21, 0x02, 0x80, 0xab, 0xeb, 0x00, 0x11, 0x14, 0x01, 0xbc, 0x60, 0x03, + 0x01, 0x57, 0x80, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x17, 0x81, 0x00, 0x02, + 0x5e, 0x02, 0xf0, 0x00, 0xdb, 0x00, 0xb0, 0x54, 0x07, 0x00, 0x10, 0xe0, + 0x00, 0x88, 0x5e, 0x0b, 0x00, 0x70, 0xe1, 0x00, 0x02, 0xde, 0x02, 0xf0, + 0x00, 0x00, 0x00, 0x68, 0x2b, 0x0b, 0x00, 0x11, 0x2d, 0x02, 0x04, 0xde, + 0xaf, 0x00, 0x11, 0x2d, 0x00, 0xe8, 0x44, 0x65, 0x58, 0x57, 0xa4, 0x00, + 0x6e, 0x5e, 0x91, 0x55, 0xb1, 0x2d, 0x00, 0x88, 0x5e, 0x93, 0x00, 0x37, + 0xa4, 0x00, 0x6d, 0x5e, 0x91, 0x55, 0xb1, 0x2d, 0x00, 0x02, 0x5e, 0x02, + 0xf0, 0x11, 0x61, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x11, 0x3a, 0x00, 0xe8, + 0x44, 0x65, 0x58, 0x57, 0xa4, 0x00, 0x88, 0x5e, 0x93, 0x00, 0x37, 0xa4, + 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x11, 0x61, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x11, 0x3a, 0x02, 0x84, 0xde, 0xaf, 0x00, 0x11, 0x31, 0x01, 0x81, 0xe0, + 0x02, 0xf5, 0xd7, 0xae, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x11, 0x3a, 0x00, + 0x68, 0x2b, 0x7f, 0x00, 0x11, 0x36, 0x00, 0xe0, 0x44, 0x65, 0x5b, 0xea, + 0xd9, 0x00, 0x68, 0x2b, 0x83, 0x00, 0x11, 0x35, 0x00, 0xe0, 0x44, 0x65, + 0x5b, 0x0a, 0xd9, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x01, 0x80, + 0x60, 0x06, 0xf7, 0xf7, 0xbf, 0x00, 0x68, 0x2b, 0x0b, 0x00, 0x11, 0x3a, + 0x00, 0xe8, 0x44, 0x65, 0x58, 0x57, 0xa4, 0x00, 0x02, 0x5e, 0x02, 0xf0, + 0x11, 0x61, 0x01, 0x84, 0x60, 0x02, 0xf5, 0x97, 0xac, 0x01, 0xbc, 0x60, + 0x03, 0x00, 0x0a, 0xc2, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x0a, 0xd9, 0x01, + 0xbc, 0x60, 0x03, 0x00, 0x0a, 0xc1, 0x01, 0x04, 0xde, 0xaf, 0x00, 0x17, + 0xa1, 0x01, 0x83, 0x5e, 0x86, 0xf5, 0xb7, 0xad, 0x02, 0x84, 0xde, 0xaf, + 0x00, 0x11, 0x43, 0x01, 0x80, 0x60, 0x06, 0x0d, 0x90, 0x6c, 0x00, 0x02, + 0xde, 0x02, 0xf0, 0x00, 0x00, 0x00, 0xb0, 0x2a, 0xa7, 0x00, 0x17, 0xa3, + 0x02, 0x04, 0x00, 0xc3, 0x00, 0x11, 0x46, 0x00, 0xb0, 0x2a, 0xc7, 0x00, + 0x17, 0xa3, 0x02, 0x02, 0xde, 0xbb, 0x00, 0x11, 0x48, 0x00, 0xb0, 0x2a, + 0xa3, 0x00, 0x17, 0xa3, 0x00, 0xe0, 0x44, 0x66, 0xf4, 0x6a, 0xb9, 0x00, + 0xb0, 0x44, 0x67, 0x00, 0x0b, 0x09, 0x01, 0x83, 0xe0, 0x02, 0x2b, 0x91, + 0x5c, 0x02, 0x07, 0x01, 0xab, 0x00, 0x11, 0x4d, 0x01, 0x80, 0xe0, 0x02, + 0x09, 0xd0, 0x4e, 0x01, 0xbc, 0x60, 0x03, 0x18, 0x51, 0x78, 0x00, 0xb0, + 0x45, 0xe3, 0x00, 0x18, 0x00, 0x01, 0x80, 0x60, 0x02, 0x2f, 0x31, 0x79, + 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x02, 0x02, 0xde, 0xb3, 0x00, + 0x11, 0x54, 0x01, 0x83, 0x60, 0x06, 0x2b, 0x91, 0x5c, 0x00, 0x02, 0x5e, + 0x02, 0xf0, 0x0f, 0x19, 0x02, 0x03, 0xc5, 0x73, 0x00, 0x11, 0x59, 0x02, + 0x84, 0xde, 0xaf, 0x00, 0x11, 0x59, 0x02, 0x81, 0xde, 0xbb, 0x00, 0x11, + 0x59, 0x02, 0x80, 0x5e, 0xff, 0x00, 0x11, 0x59, 0x02, 0x03, 0x5e, 0xb7, + 0x00, 0x11, 0x60, 0x01, 0x8b, 0x60, 0x0e, 0x2b, 0x91, 0x5c, 0x01, 0xbc, + 0x60, 0x03, 0x18, 0x51, 0x78, 0x00, 0xb0, 0x45, 0xe3, 0x00, 0x18, 0x00, + 0x01, 0x8b, 0x2b, 0x46, 0x2f, 0x31, 0x79, 0x01, 0x83, 0x60, 0x06, 0xf5, + 0xb7, 0xad, 0x01, 0x84, 0xe0, 0x02, 0xf5, 0x77, 0xab, 0x01, 0xbc, 0x60, + 0x03, 0x00, 0x0a, 0xc1, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x00, + 0x68, 0x2b, 0x73, 0x00, 0x11, 0x63, 0x00, 0xb0, 0x2b, 0x73, 0x00, 0x17, + 0xa4, 0x00, 0x6d, 0x5e, 0x91, 0x56, 0x11, 0x65, 0x00, 0xb0, 0x2a, 0xc3, + 0x00, 0x17, 0xa4, 0x00, 0x88, 0x2b, 0x1f, 0x00, 0x37, 0xa5, 0x00, 0xe8, + 0x2b, 0x22, 0xf4, 0xaa, 0xc8, 0x00, 0x88, 0x5e, 0x93, 0x00, 0x37, 0xa4, + 0x00, 0xe0, 0x2b, 0x22, 0xf4, 0x8a, 0xc8, 0x00, 0x90, 0x2b, 0x23, 0x00, + 0xaa, 0xc7, 0x00, 0xb0, 0x2b, 0x1f, 0x00, 0x0a, 0xad, 0x00, 0x02, 0xde, + 0x02, 0xf0, 0x00, 0x00, 0x02, 0x03, 0x2c, 0x3f, 0x00, 0x11, 0x75, 0x02, + 0x87, 0x41, 0xd7, 0x00, 0x11, 0x6d, 0x01, 0xbc, 0x60, 0x63, 0x00, 0x10, + 0x7b, 0x01, 0xbc, 0x60, 0x07, 0x00, 0x10, 0x7a, 0x01, 0xac, 0x60, 0x7f, + 0x1c, 0x10, 0x75, 0x02, 0x87, 0x41, 0xd7, 0x00, 0x11, 0x71, 0x01, 0x84, + 0x5e, 0x8e, 0x0e, 0xd0, 0x76, 0x01, 0xac, 0x60, 0xbf, 0x1c, 0x10, 0x75, + 0x02, 0x87, 0x41, 0xd7, 0x00, 0x11, 0x74, 0x00, 0x02, 0xde, 0x02, 0xf0, + 0x00, 0x00, 0x02, 0x86, 0x41, 0x07, 0x00, 0x11, 0x76, 0x01, 0xbc, 0x60, + 0x13, 0x09, 0x17, 0xa1, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xce, 0x01, + 0x87, 0x60, 0x06, 0x03, 0x37, 0xa2, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, + 0xd4, 0x00, 0xb0, 0x5e, 0x87, 0x00, 0x17, 0xa1, 0x00, 0xb0, 0x5e, 0x87, + 0x00, 0x17, 0xa1, 0x00, 0xb0, 0x5e, 0x87, 0x00, 0x17, 0xa1, 0x01, 0x87, + 0x60, 0x02, 0xf4, 0x57, 0xa2, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xd4, + 0x01, 0xbc, 0x60, 0x13, 0x09, 0x57, 0xa1, 0x00, 0x02, 0x5e, 0x02, 0xf0, + 0x00, 0xce, 0x01, 0x80, 0x60, 0x06, 0x03, 0x37, 0xa2, 0x00, 0x02, 0x5e, + 0x02, 0xf0, 0x00, 0xd4, 0x00, 0xe0, 0x02, 0xb3, 0x00, 0x20, 0xac, 0x01, + 0x80, 0x60, 0x02, 0xf4, 0x57, 0xa2, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, + 0xd4, 0x01, 0xbc, 0x60, 0x27, 0x08, 0x57, 0xa1, 0x00, 0x02, 0x5e, 0x02, + 0xf0, 0x00, 0xce, 0x00, 0x68, 0xc0, 0x67, 0x01, 0xf1, 0x8e, 0x01, 0xbc, + 0x60, 0x03, 0x00, 0x17, 0xa2, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xd4, + 0x01, 0xbc, 0x60, 0x03, 0x01, 0xf7, 0xa2, 0x00, 0x02, 0x5e, 0x02, 0xf0, + 0x00, 0xd4, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x03, 0x90, 0x5e, + 0x02, 0xf0, 0x11, 0xa2, 0x03, 0x87, 0x5e, 0x02, 0xf0, 0x11, 0xa2, 0x03, + 0x90, 0xde, 0x02, 0xf0, 0x11, 0xa2, 0x02, 0x04, 0x45, 0x23, 0x00, 0x11, + 0x99, 0x02, 0x83, 0xc2, 0x1f, 0x00, 0x11, 0xa2, 0x00, 0x68, 0xa0, 0xb3, + 0x00, 0x11, 0x96, 0x00, 0xb0, 0x44, 0x67, 0x00, 0x08, 0x2c, 0x00, 0xe8, + 0x44, 0x65, 0x05, 0x97, 0xa1, 0x00, 0x6e, 0x5e, 0x87, 0x7d, 0x11, 0x9d, + 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x11, 0xa3, 0x02, 0x86, 0xc0, 0x37, 0x00, + 0x11, 0xa2, 0x00, 0xe0, 0x44, 0x67, 0x00, 0xd7, 0xa1, 0x02, 0x06, 0x40, + 0x37, 0x00, 0x11, 0xa2, 0x00, 0x6c, 0xc4, 0x66, 0xf4, 0x31, 0x9b, 0x00, + 0x02, 0x5e, 0x02, 0xf0, 0x0b, 0x22, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x11, + 0x76, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x08, 0x2c, 0x00, 0x02, 0x5e, 0x02, + 0xf0, 0x0a, 0xe5, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x00, 0x13, 0x01, 0xbc, + 0x60, 0x03, 0x00, 0x08, 0x2c, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, + 0x02, 0x80, 0x42, 0x03, 0x00, 0x11, 0xac, 0x02, 0x85, 0x45, 0x23, 0x00, + 0x11, 0xab, 0x02, 0x85, 0xde, 0xb7, 0x00, 0x11, 0xa9, 0x01, 0x85, 0xe0, + 0x06, 0xf5, 0xb7, 0xad, 0x00, 0xe0, 0x44, 0x6b, 0x00, 0x2b, 0x20, 0x00, + 0x6c, 0xc4, 0x69, 0x64, 0x11, 0xac, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x11, + 0x76, 0x01, 0x85, 0xe0, 0x02, 0xf5, 0xb7, 0xad, 0x00, 0x02, 0xde, 0x02, + 0xf0, 0x00, 0x00, 0x01, 0x0c, 0x81, 0x43, 0x00, 0x17, 0xa1, 0x01, 0xbc, + 0x60, 0x03, 0x00, 0x50, 0x8a, 0x00, 0x68, 0x5e, 0x07, 0x00, 0x11, 0xb1, + 0x00, 0x68, 0x5e, 0x87, 0x00, 0x11, 0xb1, 0x00, 0x68, 0x5e, 0x07, 0x00, + 0x11, 0xb9, 0x01, 0x90, 0x42, 0x2a, 0xa1, 0x30, 0x8a, 0x00, 0x68, 0x5e, + 0x07, 0x00, 0x31, 0xb9, 0x01, 0x90, 0x42, 0x2a, 0xa0, 0x10, 0x8a, 0x01, + 0x09, 0xde, 0x03, 0x00, 0x17, 0xa2, 0x01, 0x8f, 0x5e, 0x8a, 0x11, 0x50, + 0x8a, 0x00, 0x68, 0x5e, 0x8b, 0x00, 0x11, 0xb9, 0x01, 0x91, 0xe0, 0x0e, + 0x11, 0x50, 0x8a, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x01, 0x09, + 0xde, 0x03, 0x00, 0x17, 0xa4, 0x00, 0xe0, 0x5a, 0x06, 0xf4, 0x97, 0xa5, + 0x00, 0x90, 0x5e, 0x96, 0xf4, 0x97, 0xa5, 0x02, 0x03, 0xde, 0x03, 0x00, + 0x11, 0xc1, 0x02, 0x82, 0xde, 0x03, 0x00, 0x11, 0xc1, 0x01, 0xbc, 0x61, + 0xef, 0x08, 0x57, 0xa6, 0x00, 0x80, 0xde, 0x96, 0xf4, 0xd7, 0xa5, 0x01, + 0x16, 0xde, 0x87, 0x00, 0x17, 0xa3, 0x00, 0x88, 0x5e, 0x87, 0x00, 0x77, + 0xa1, 0x00, 0xe1, 0x5e, 0x87, 0x02, 0xd7, 0xa1, 0x00, 0xe0, 0xde, 0x8f, + 0x00, 0x17, 0xa3, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x17, 0xa2, 0x02, 0x0e, + 0x5e, 0x03, 0x00, 0x11, 0xc8, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x37, 0xa2, + 0x00, 0x90, 0x5e, 0x96, 0xf4, 0x57, 0xa5, 0x00, 0x80, 0xde, 0x96, 0xf4, + 0x37, 0xa1, 0x00, 0xe1, 0x41, 0xb7, 0xff, 0xf7, 0xa6, 0x00, 0xe1, 0xde, + 0x87, 0x01, 0xf7, 0xa1, 0x00, 0x80, 0xde, 0x96, 0xf4, 0x77, 0xa3, 0x00, + 0xe1, 0xde, 0x86, 0x0d, 0xb7, 0xa1, 0x00, 0xe0, 0xde, 0x8f, 0x00, 0x17, + 0xa3, 0x01, 0x7a, 0x5e, 0x86, 0xf4, 0x77, 0xa1, 0x00, 0x88, 0x5e, 0x86, + 0xf4, 0x57, 0xa1, 0x00, 0xb0, 0x5e, 0x87, 0x00, 0x17, 0xa2, 0x02, 0x87, + 0xde, 0x03, 0x00, 0x11, 0xd5, 0x00, 0x88, 0x5e, 0x87, 0x00, 0x57, 0xa1, + 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x11, 0xe2, 0x02, 0x87, 0x5e, 0x03, 0x00, + 0x11, 0xdc, 0x01, 0xbc, 0x63, 0x9b, 0x0c, 0xd7, 0xa5, 0x00, 0x80, 0xde, + 0x86, 0xf4, 0xb7, 0xa1, 0x00, 0xe1, 0x41, 0xb7, 0xff, 0xf7, 0xa5, 0x00, + 0xe0, 0xde, 0x87, 0x00, 0x17, 0xa1, 0x00, 0x88, 0x5e, 0x87, 0x00, 0x57, + 0xa1, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x11, 0xe2, 0x00, 0x88, 0x5e, 0x87, + 0x00, 0x57, 0xa1, 0x01, 0xbc, 0x63, 0x9b, 0x0c, 0xf7, 0xa5, 0x00, 0x80, + 0xde, 0x86, 0xf4, 0xb7, 0xa1, 0x01, 0xbc, 0x62, 0x03, 0x00, 0x17, 0xa5, + 0x00, 0xe1, 0x41, 0xb6, 0xf4, 0xb7, 0xa5, 0x00, 0xe0, 0xde, 0x87, 0x00, + 0x17, 0xa1, 0x00, 0xe0, 0x5e, 0x84, 0x00, 0xd7, 0xa1, 0x00, 0x02, 0xde, + 0x02, 0xf0, 0x00, 0x00, 0x02, 0x00, 0x20, 0x0f, 0x00, 0x00, 0x13, 0x02, + 0x82, 0xde, 0x53, 0x00, 0x11, 0xea, 0x01, 0x88, 0x60, 0x02, 0x04, 0x90, + 0x24, 0x00, 0xe0, 0x20, 0xaa, 0xf3, 0x08, 0x2a, 0x00, 0xe8, 0x20, 0xa6, + 0xf3, 0x08, 0x29, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x09, 0x93, 0x01, 0xb8, + 0x60, 0x16, 0x04, 0x90, 0x24, 0x01, 0xbc, 0x60, 0x03, 0x01, 0xd0, 0x25, + 0x03, 0x05, 0x5e, 0x02, 0xf0, 0x11, 0xfc, 0x02, 0x87, 0xc0, 0x37, 0x00, + 0x0a, 0x93, 0x03, 0x86, 0xde, 0x02, 0xf0, 0x0a, 0x94, 0x00, 0x02, 0x5e, + 0x02, 0xf0, 0x0f, 0x38, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x11, 0x8f, 0x03, + 0x5c, 0xde, 0x02, 0xf0, 0x11, 0xec, 0x00, 0xd8, 0x40, 0x9b, 0x01, 0x17, + 0xa1, 0x00, 0xe0, 0x5e, 0x87, 0x02, 0x37, 0x98, 0x00, 0xa8, 0x5e, 0x63, + 0x00, 0x77, 0x98, 0x01, 0x02, 0xde, 0x53, 0x00, 0x17, 0xa1, 0x01, 0x82, + 0xe0, 0x02, 0xf2, 0x97, 0x94, 0x01, 0x88, 0xde, 0x85, 0x00, 0x68, 0x03, + 0x00, 0x6e, 0xa0, 0xa6, 0xf3, 0x11, 0xfc, 0x00, 0xe8, 0x5e, 0x63, 0x01, + 0xd0, 0x25, 0x01, 0xb8, 0x60, 0x06, 0x04, 0x90, 0x24, 0x03, 0xbf, 0xde, + 0x02, 0xf0, 0x00, 0x02, 0x01, 0x81, 0x60, 0x05, 0x00, 0x68, 0x03, 0x01, + 0xb8, 0x60, 0x0a, 0x04, 0x90, 0x24, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x00, + 0x02, 0x02, 0x28, 0x5e, 0x87, 0x00, 0x12, 0x12, 0x00, 0xb0, 0x41, 0x93, + 0x00, 0x17, 0xa4, 0x00, 0xe0, 0x41, 0x93, 0x00, 0x70, 0x64, 0x01, 0x0a, + 0x5e, 0x87, 0x00, 0x17, 0xa2, 0x00, 0xe8, 0x41, 0x92, 0xf4, 0x50, 0x63, + 0x01, 0x18, 0x5e, 0x87, 0x00, 0x17, 0xa1, 0x00, 0xe8, 0x60, 0x42, 0xf4, + 0x37, 0xa2, 0x00, 0x88, 0x56, 0x02, 0xf4, 0x36, 0x00, 0x00, 0x68, 0x41, + 0x8e, 0xf4, 0x92, 0x0e, 0x00, 0xe8, 0x41, 0x8f, 0x00, 0x30, 0x63, 0x00, + 0xe8, 0x41, 0x93, 0x00, 0x30, 0x64, 0x00, 0x68, 0x5e, 0x8b, 0x02, 0x12, + 0x06, 0x00, 0x90, 0x56, 0x02, 0xf4, 0x57, 0xa3, 0x00, 0xb0, 0x58, 0x06, + 0xf4, 0x76, 0x01, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x12, 0x06, 0x00, 0x68, + 0x41, 0x92, 0xf4, 0x92, 0x12, 0x00, 0xe8, 0x41, 0x93, 0x00, 0x30, 0x64, + 0x01, 0xbc, 0x60, 0x03, 0x00, 0x16, 0x00, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x12, 0x0e, 0x00, 0xb0, 0x5e, 0x87, 0x00, 0x17, 0xa1, 0x00, 0x02, 0xde, + 0x02, 0xf0, 0x00, 0x00, 0x01, 0x80, 0x60, 0x02, 0x86, 0x14, 0x30, 0x00, + 0xb0, 0x50, 0xcb, 0x00, 0x10, 0x65, 0x01, 0x38, 0x50, 0x83, 0x00, 0x17, + 0xa1, 0x00, 0x68, 0xde, 0x3b, 0x06, 0x32, 0x1a, 0x00, 0xe0, 0x5a, 0x33, + 0x00, 0x36, 0x8c, 0x00, 0x6e, 0xda, 0x32, 0xf4, 0x20, 0x13, 0x00, 0xb0, + 0x5a, 0x0b, 0x00, 0x17, 0xa2, 0x00, 0xe0, 0x01, 0xf7, 0x00, 0x20, 0x7d, + 0x00, 0xe0, 0x01, 0xd2, 0xf4, 0x40, 0x74, 0x01, 0xbc, 0x63, 0xff, 0x1f, + 0xf7, 0xa3, 0x00, 0xb0, 0x50, 0xcf, 0x00, 0x10, 0x64, 0x00, 0x6e, 0xda, + 0x32, 0xf4, 0x32, 0x21, 0x00, 0xb0, 0x5a, 0x37, 0x00, 0x17, 0xa3, 0x00, + 0xb0, 0x58, 0x13, 0x00, 0x17, 0x82, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x16, + 0x04, 0x01, 0xbc, 0x60, 0x1b, 0x09, 0xd7, 0xb6, 0x01, 0x02, 0xd0, 0xc7, + 0x00, 0x17, 0xa1, 0x00, 0xe0, 0x41, 0x96, 0xf4, 0x30, 0x65, 0x00, 0xe0, + 0x50, 0xcb, 0x00, 0xd0, 0x64, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x17, 0xb4, + 0x01, 0xbc, 0x60, 0x03, 0x00, 0x17, 0x80, 0x01, 0xbc, 0x60, 0x03, 0x00, + 0x37, 0x81, 0x01, 0x87, 0x60, 0x04, 0x03, 0x10, 0xa0, 0x00, 0x90, 0x52, + 0x33, 0x00, 0x97, 0xa4, 0x00, 0xe0, 0x41, 0x87, 0x01, 0xb7, 0xb5, 0x00, + 0x68, 0x5e, 0xd2, 0xf0, 0x52, 0x48, 0x00, 0xe0, 0x5e, 0xda, 0xf6, 0x90, + 0x63, 0x00, 0x20, 0xd8, 0x02, 0xf0, 0x32, 0x3c, 0x02, 0x02, 0x50, 0xc7, + 0x00, 0x12, 0x42, 0x00, 0x90, 0x56, 0x03, 0x00, 0x97, 0xa1, 0x00, 0xe8, + 0x5e, 0x86, 0xf4, 0x97, 0xa1, 0x01, 0x9e, 0x60, 0x02, 0xf4, 0x37, 0xa1, + 0x00, 0x6d, 0xde, 0x87, 0x08, 0x12, 0x42, 0x01, 0x0a, 0x5e, 0x87, 0x00, + 0x17, 0xa2, 0x01, 0xda, 0x60, 0x02, 0xf4, 0x37, 0xa1, 0x00, 0xe0, 0x5e, + 0xd6, 0xf4, 0x50, 0x63, 0x00, 0x88, 0x60, 0x06, 0xf4, 0x37, 0xa1, 0x00, + 0x20, 0x56, 0x02, 0xf4, 0x32, 0x42, 0x00, 0xb0, 0x58, 0x02, 0xf0, 0x36, + 0x00, 0x00, 0xe0, 0x5a, 0x2b, 0x00, 0x36, 0x8a, 0x00, 0x6a, 0xde, 0xd2, + 0xf4, 0x72, 0x3e, 0x00, 0x68, 0xde, 0xd2, 0xf0, 0x12, 0x43, 0x00, 0xe0, + 0x5e, 0x03, 0x00, 0x37, 0x80, 0x00, 0x68, 0x5e, 0x03, 0x00, 0x32, 0x43, + 0x01, 0x86, 0xe0, 0x04, 0x03, 0x10, 0xa0, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x12, 0x43, 0x00, 0x6a, 0xde, 0xd2, 0xf4, 0x72, 0x3e, 0x00, 0xe0, 0x5e, + 0xd3, 0x00, 0x37, 0xb4, 0x00, 0xd0, 0x5e, 0x07, 0x00, 0x37, 0x81, 0x02, + 0x98, 0x5e, 0xd3, 0x00, 0x12, 0x2d, 0x00, 0xe0, 0x41, 0x93, 0x00, 0x30, + 0x64, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x12, 0x2d, 0x00, 0x68, 0x5e, 0x03, + 0x00, 0x00, 0x13, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x05, 0xd7, 0x02, 0x82, + 0xd0, 0xc7, 0x00, 0x12, 0x52, 0x00, 0xb0, 0x2a, 0x4f, 0x00, 0x17, 0xa1, + 0x01, 0xb8, 0x2a, 0x4a, 0xf4, 0x36, 0x84, 0x01, 0x02, 0x50, 0x13, 0x00, + 0x16, 0x85, 0x01, 0x3c, 0x50, 0x83, 0x00, 0x17, 0xa1, 0x00, 0xb0, 0x50, + 0xa7, 0x00, 0x17, 0xa4, 0x00, 0x6d, 0x5a, 0x32, 0xf4, 0x32, 0x5b, 0x01, + 0x82, 0xe0, 0x06, 0x86, 0x34, 0x31, 0x02, 0x88, 0x50, 0x2b, 0x00, 0x12, + 0x57, 0x00, 0xb0, 0x5a, 0x33, 0x00, 0x17, 0xa1, 0x01, 0x9e, 0x5e, 0x86, + 0x84, 0xf4, 0x27, 0x01, 0x83, 0x60, 0x06, 0x86, 0x34, 0x31, 0x00, 0x02, + 0xde, 0x02, 0xf0, 0x00, 0x00, 0x00, 0xb0, 0x50, 0x73, 0x00, 0x17, 0xa1, + 0x01, 0xb8, 0x50, 0x6e, 0xf4, 0x36, 0x84, 0x01, 0x06, 0xd0, 0x07, 0x00, + 0x16, 0x85, 0x00, 0xb0, 0x50, 0xab, 0x00, 0x17, 0xa4, 0x00, 0xd0, 0x60, + 0x06, 0xc0, 0x97, 0x80, 0x00, 0xe0, 0x41, 0x97, 0x00, 0xd7, 0xb5, 0x01, + 0x0a, 0x58, 0x13, 0x00, 0x17, 0xa1, 0x00, 0xe0, 0x5e, 0xd6, 0xf4, 0x37, + 0xb5, 0x00, 0xb0, 0x58, 0x0f, 0x00, 0x10, 0x63, 0x01, 0x16, 0x56, 0x03, + 0x00, 0x17, 0x81, 0x00, 0x68, 0xd8, 0x13, 0x00, 0x12, 0x70, 0x01, 0x14, + 0x00, 0x63, 0x00, 0x17, 0xa1, 0x00, 0x68, 0xde, 0x87, 0x00, 0x12, 0x66, + 0x00, 0x88, 0x01, 0x3b, 0x01, 0x16, 0x80, 0x03, 0xbf, 0xde, 0x02, 0xf0, + 0x12, 0x6b, 0x00, 0x68, 0xde, 0x87, 0x00, 0x72, 0x69, 0x00, 0xa0, 0x01, + 0x3b, 0xe0, 0x16, 0x80, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x12, 0x6b, 0x00, + 0xe0, 0x5e, 0x87, 0x09, 0x70, 0x62, 0x00, 0x88, 0x54, 0x03, 0x01, 0x16, + 0x80, 0x00, 0xe8, 0x5a, 0x03, 0x30, 0x16, 0x80, 0x01, 0xbc, 0x60, 0x03, + 0x00, 0x16, 0x81, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x16, 0x82, 0x01, 0xbc, + 0x60, 0x03, 0x00, 0x16, 0x83, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x12, 0x75, + 0x00, 0xe0, 0x41, 0x8e, 0xc0, 0x90, 0x63, 0x00, 0x6e, 0xc1, 0x8e, 0xc0, + 0x32, 0x75, 0x00, 0xe8, 0x41, 0x8e, 0xc0, 0x30, 0x63, 0x00, 0xe8, 0x58, + 0x03, 0x00, 0x37, 0xa1, 0x00, 0xe0, 0x41, 0x8e, 0xf4, 0x30, 0x63, 0x01, + 0x38, 0x50, 0xa3, 0x00, 0x17, 0xa5, 0x00, 0x68, 0x58, 0x13, 0x03, 0xf2, + 0x90, 0x00, 0x68, 0x41, 0x8e, 0xc0, 0x52, 0x90, 0x00, 0x6d, 0xda, 0x0a, + 0xf4, 0xb2, 0x90, 0x01, 0x16, 0x56, 0x03, 0x00, 0x17, 0xa1, 0x00, 0x68, + 0xde, 0x86, 0xf0, 0x32, 0x90, 0x01, 0x58, 0x56, 0x03, 0x00, 0x17, 0xa1, + 0x00, 0xe0, 0x5e, 0x87, 0x0d, 0xd7, 0xa2, 0x00, 0xb0, 0x5e, 0xd7, 0x00, + 0x10, 0x62, 0x00, 0x20, 0xde, 0x02, 0xa0, 0x12, 0x87, 0x00, 0xe0, 0x5e, + 0x86, 0xd0, 0x37, 0xa3, 0x00, 0xe0, 0x5e, 0x8e, 0xd0, 0x77, 0xa3, 0x00, + 0x6d, 0x5a, 0x02, 0xf4, 0x52, 0x90, 0x00, 0x6e, 0x5e, 0x8e, 0xf4, 0x92, + 0x90, 0x00, 0xe8, 0x60, 0x02, 0xf4, 0x36, 0x83, 0x00, 0xb0, 0x5e, 0x8f, + 0x00, 0x16, 0x81, 0x00, 0xa0, 0x5a, 0x0f, 0x00, 0x76, 0x83, 0x00, 0xe0, + 0x5a, 0x0b, 0x00, 0x36, 0x82, 0x00, 0xe8, 0x5a, 0x02, 0xf4, 0x56, 0x80, + 0x00, 0xd0, 0x5e, 0x03, 0x00, 0x37, 0x80, 0x00, 0xe0, 0x58, 0x13, 0x00, + 0x36, 0x04, 0x00, 0xe0, 0x41, 0x8f, 0x00, 0x30, 0x63, 0x02, 0x98, 0x58, + 0x13, 0x00, 0x12, 0x8d, 0x00, 0xe0, 0x5e, 0xd7, 0x00, 0x37, 0xb5, 0x00, + 0x6e, 0xc1, 0x8e, 0xc0, 0x32, 0x76, 0x00, 0xb0, 0x58, 0x03, 0x00, 0x10, + 0x63, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x12, 0x76, 0x00, 0xb0, 0x58, 0x13, + 0x00, 0x17, 0xa1, 0x00, 0x68, 0xda, 0x37, 0x00, 0x12, 0x93, 0x00, 0xb0, + 0x5e, 0x87, 0x00, 0x16, 0x8d, 0x00, 0x6d, 0xde, 0x86, 0xd1, 0xb2, 0x95, + 0x00, 0xb0, 0x5e, 0x87, 0x00, 0x16, 0x8d, 0x00, 0x02, 0xde, 0x02, 0xf0, + 0x00, 0x00, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x17, 0xa1, 0x01, 0x87, 0x60, + 0x04, 0x03, 0x10, 0xa0, 0x01, 0xbc, 0x60, 0x03, 0x09, 0x90, 0xb5, 0x00, + 0xb0, 0x00, 0x63, 0x00, 0xf0, 0xb4, 0x01, 0xbc, 0x60, 0x57, 0x04, 0x90, + 0xb6, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x90, 0xb5, 0x00, 0xb0, 0x00, 0x63, + 0x00, 0xb0, 0xb4, 0x00, 0xb0, 0x42, 0xd3, 0x00, 0x18, 0x00, 0x03, 0x17, + 0xde, 0x02, 0xf0, 0x12, 0x9e, 0x03, 0x97, 0xde, 0x02, 0xf0, 0x12, 0x9f, + 0x00, 0xb0, 0x2a, 0x4b, 0x00, 0x14, 0x2f, 0x01, 0x8e, 0xe0, 0x0c, 0x03, + 0x10, 0xa0, 0x00, 0x6d, 0xde, 0x02, 0xd1, 0xb2, 0xa5, 0x00, 0xe8, 0x5a, + 0x36, 0xf0, 0x16, 0x8d, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x12, 0xa7, 0x01, + 0xbc, 0x60, 0x03, 0x00, 0x16, 0x8c, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x16, + 0x8d, 0x00, 0x6e, 0x5a, 0x3a, 0xf0, 0x12, 0xaa, 0x01, 0xbc, 0x60, 0x03, + 0x00, 0x16, 0x8e, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x12, 0xab, 0x00, 0xe8, + 0x5a, 0x3a, 0xf0, 0x16, 0x8e, 0x00, 0xb0, 0x58, 0x07, 0x00, 0x17, 0xa1, + 0x00, 0xe0, 0x58, 0x0e, 0xf0, 0x16, 0x03, 0x00, 0x6e, 0xd8, 0x0e, 0xf4, + 0x32, 0xb1, 0x00, 0xe8, 0x5e, 0x86, 0xc0, 0x17, 0xa1, 0x00, 0xe8, 0x58, + 0x0e, 0xf4, 0x36, 0x03, 0x00, 0xe8, 0x58, 0x0f, 0x00, 0x36, 0x03, 0x01, + 0x18, 0x5e, 0x03, 0x00, 0x17, 0xa1, 0x00, 0x6d, 0xde, 0x03, 0x02, 0x12, + 0xb9, 0x00, 0xe8, 0x60, 0x42, 0xf4, 0x37, 0xa2, 0x00, 0x90, 0x5a, 0x1a, + 0xf4, 0x36, 0x86, 0x00, 0x88, 0x5a, 0x1e, 0xf4, 0x57, 0xa2, 0x00, 0x90, + 0x5a, 0x1e, 0xf4, 0x36, 0x87, 0x00, 0xb0, 0x5a, 0x1a, 0xf4, 0x56, 0x86, + 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x12, 0xbb, 0x00, 0x90, 0x5a, 0x1e, 0xf4, + 0x36, 0x86, 0x01, 0xbc, 0x60, 0x03, 0x00, 0x16, 0x87, 0x00, 0x02, 0xde, + 0x02, 0xf0, 0x00, 0x00, 0x01, 0x58, 0x60, 0x03, 0x00, 0x10, 0x2a, 0x01, + 0xb8, 0x60, 0x0a, 0x04, 0x90, 0x24, 0x01, 0xbc, 0x60, 0x03, 0x02, 0x90, + 0x04, 0x01, 0x89, 0xe0, 0x02, 0x0d, 0x90, 0x6c, 0x00, 0x02, 0xde, 0x02, + 0xf0, 0x00, 0x00, 0x02, 0x00, 0xde, 0x53, 0x00, 0x12, 0xe6, 0x01, 0xbc, + 0x60, 0x13, 0x09, 0xb7, 0xa1, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xce, + 0x01, 0xa5, 0x60, 0x02, 0x03, 0x37, 0xa2, 0x01, 0x99, 0xe0, 0x02, 0xf4, + 0x57, 0xa2, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xd4, 0x01, 0xbc, 0x60, + 0x13, 0x09, 0x97, 0xa1, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xce, 0x01, + 0xa4, 0x60, 0x7e, 0x03, 0x37, 0xa2, 0x01, 0x99, 0xe0, 0x3e, 0xf4, 0x57, + 0xa2, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xd4, 0x01, 0xbc, 0x60, 0x13, + 0x16, 0xf7, 0xa1, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xce, 0x01, 0xb4, + 0x60, 0x02, 0x03, 0x37, 0xa2, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xd4, + 0x01, 0xbc, 0x60, 0x13, 0x16, 0x37, 0xa1, 0x00, 0x02, 0x5e, 0x02, 0xf0, + 0x00, 0xce, 0x01, 0x86, 0xe0, 0x02, 0x03, 0x37, 0xa2, 0x01, 0x85, 0x60, + 0x02, 0xf4, 0x57, 0xa2, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xd4, 0x01, + 0xbc, 0x60, 0x13, 0x16, 0x17, 0xa1, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, + 0xce, 0x01, 0x81, 0xe0, 0x06, 0x03, 0x37, 0xa2, 0x01, 0x85, 0xe0, 0x06, + 0xf4, 0x57, 0xa2, 0x01, 0x83, 0x60, 0x06, 0xf4, 0x57, 0xa2, 0x00, 0x02, + 0x5e, 0x02, 0xf0, 0x00, 0xd4, 0x01, 0xbc, 0x60, 0x13, 0x1f, 0x57, 0xa1, + 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xce, 0x01, 0x81, 0xe0, 0x02, 0x03, + 0x37, 0xa2, 0x02, 0x86, 0x00, 0xc7, 0x00, 0x12, 0xe0, 0x01, 0x81, 0xe0, + 0x06, 0x03, 0x37, 0xa2, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xd4, 0x01, + 0xbc, 0x60, 0x13, 0x1f, 0x37, 0xa1, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, + 0xce, 0x01, 0x81, 0xe0, 0x06, 0x03, 0x37, 0xa2, 0x00, 0x02, 0x5e, 0x02, + 0xf0, 0x00, 0xd4, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x01, 0xbc, + 0x60, 0x13, 0x09, 0x97, 0xa1, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xce, + 0x01, 0xa4, 0x60, 0x02, 0x03, 0x37, 0xa2, 0x01, 0x99, 0xe0, 0x02, 0xf4, + 0x57, 0xa2, 0x01, 0x88, 0x60, 0x02, 0xf4, 0x57, 0xa2, 0x00, 0x02, 0x5e, + 0x02, 0xf0, 0x00, 0xd4, 0x01, 0xbc, 0x60, 0x13, 0x16, 0x17, 0xa1, 0x00, + 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xce, 0x01, 0x81, 0xe0, 0x02, 0x03, 0x37, + 0xa2, 0x01, 0x85, 0xe0, 0x02, 0xf4, 0x57, 0xa2, 0x01, 0x83, 0x60, 0x02, + 0xf4, 0x57, 0xa2, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xd4, 0x02, 0x06, + 0x00, 0xc7, 0x00, 0x12, 0xf7, 0x01, 0xbc, 0x60, 0x13, 0x1f, 0x37, 0xa1, + 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xce, 0x01, 0x81, 0xe0, 0x02, 0x03, + 0x37, 0xa2, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xd4, 0x00, 0x02, 0xde, + 0x02, 0xf0, 0x00, 0x00, 0x02, 0x00, 0xde, 0x53, 0x00, 0x12, 0xe6, 0x01, + 0xbc, 0x60, 0x13, 0x09, 0xb7, 0xa1, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, + 0xce, 0x01, 0x87, 0x60, 0x02, 0x03, 0x37, 0xa2, 0x01, 0x81, 0xe0, 0x02, + 0xf4, 0x57, 0xa2, 0x01, 0x88, 0x60, 0x06, 0xf4, 0x57, 0xa2, 0x00, 0x02, + 0x5e, 0x02, 0xf0, 0x00, 0xd4, 0x01, 0xbc, 0x60, 0x13, 0x09, 0x97, 0xa1, + 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xce, 0x02, 0x04, 0x00, 0xc7, 0x00, + 0x13, 0x04, 0x01, 0x88, 0x60, 0x0e, 0x03, 0x37, 0xa2, 0x03, 0xbf, 0xde, + 0x02, 0xf0, 0x13, 0x06, 0x01, 0x86, 0x60, 0x06, 0x03, 0x37, 0xa2, 0x01, + 0x81, 0xe0, 0x06, 0xf4, 0x57, 0xa2, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, + 0xd4, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x12, 0xdb, 0x00, 0x68, 0xde, 0x93, + 0x00, 0x13, 0x0c, 0x00, 0xe0, 0x5e, 0x03, 0x00, 0x57, 0xa2, 0x01, 0x09, + 0x5e, 0x8b, 0x00, 0x17, 0xa1, 0x03, 0xbf, 0xde, 0x02, 0xf0, 0x13, 0x14, + 0x00, 0x68, 0xde, 0x93, 0x00, 0x33, 0x10, 0x01, 0x10, 0x5e, 0x03, 0x00, + 0x17, 0xa2, 0x00, 0xe0, 0x5e, 0x8b, 0x00, 0x97, 0xa1, 0x03, 0xbf, 0xde, + 0x02, 0xf0, 0x13, 0x14, 0x01, 0x30, 0x5e, 0x03, 0x00, 0x17, 0xa2, 0x00, + 0xe0, 0x5e, 0x8b, 0x01, 0x97, 0xa1, 0x00, 0x6d, 0x5e, 0x87, 0x05, 0x93, + 0x14, 0x01, 0xbc, 0x60, 0x03, 0x05, 0x97, 0xa1, 0x00, 0x02, 0xde, 0x02, + 0xf0, 0x00, 0x00, 0x00, 0x68, 0x2b, 0xe3, 0x00, 0x13, 0x1a, 0x00, 0xb0, + 0x2c, 0x0b, 0x00, 0x17, 0xa1, 0x00, 0xe0, 0x5e, 0x85, 0x60, 0x77, 0xa1, + 0x00, 0x6b, 0xde, 0x86, 0x23, 0x33, 0x1a, 0x01, 0x86, 0xe0, 0x06, 0xf7, + 0xf7, 0xbf, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x00, 0xb0, 0x5e, + 0x8f, 0x00, 0x10, 0x64, 0x00, 0xb0, 0x5e, 0x87, 0x00, 0x17, 0xa3, 0x00, + 0xb0, 0x5e, 0x8b, 0x00, 0x10, 0x65, 0x00, 0xb0, 0x5a, 0x03, 0x00, 0x17, + 0xa1, 0x00, 0x68, 0x41, 0x93, 0x00, 0x13, 0x23, 0x00, 0x02, 0x5e, 0x02, + 0xf0, 0x00, 0xce, 0x00, 0xb0, 0x40, 0x67, 0x00, 0x16, 0x01, 0x00, 0xe0, + 0x41, 0x93, 0x00, 0x50, 0x64, 0x00, 0xb0, 0x5a, 0x07, 0x00, 0x17, 0xa2, + 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x00, 0xd4, 0x00, 0xe0, 0x41, 0x97, 0x00, + 0x50, 0x65, 0x00, 0xe8, 0x5e, 0x8f, 0x00, 0x37, 0xa3, 0x00, 0x68, 0xde, + 0x8f, 0x00, 0x13, 0x1e, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, 0x00, 0x00, + 0xb0, 0x5e, 0x8f, 0x00, 0x10, 0x64, 0x00, 0xb0, 0x5e, 0x87, 0x00, 0x17, + 0xa3, 0x00, 0xb0, 0x5e, 0x8b, 0x00, 0x10, 0x65, 0x00, 0xb0, 0x5a, 0x03, + 0x00, 0x17, 0x80, 0x00, 0x68, 0x41, 0x93, 0x00, 0x13, 0x31, 0x00, 0x02, + 0x5e, 0x02, 0xf0, 0x0d, 0xe4, 0x00, 0xb0, 0x5e, 0x07, 0x00, 0x16, 0x01, + 0x00, 0xe0, 0x41, 0x93, 0x00, 0x50, 0x64, 0x00, 0xb0, 0x5a, 0x07, 0x00, + 0x17, 0x81, 0x00, 0x02, 0x5e, 0x02, 0xf0, 0x0d, 0xe9, 0x00, 0xe0, 0x41, + 0x97, 0x00, 0x50, 0x65, 0x00, 0xe8, 0x5e, 0x8f, 0x00, 0x37, 0xa3, 0x00, + 0x68, 0xde, 0x8f, 0x00, 0x13, 0x2c, 0x00, 0x02, 0xde, 0x02, 0xf0, 0x00, + 0x00, 0x02, 0x02, 0x00, 0xbf, 0x00, 0x01, 0xba, 0x02, 0x03, 0xc5, 0x73, + 0x00, 0x01, 0xe3, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0xd2, 0x58, 0x82, 0x92 +}; + +const unsigned int bcmf_firmware_image_len = sizeof(bcmf_firmware_image); diff --git a/drivers/wireless/ieee80211/Kconfig b/drivers/wireless/ieee80211/Kconfig index ec3952c129..a38f67daf8 100644 --- a/drivers/wireless/ieee80211/Kconfig +++ b/drivers/wireless/ieee80211/Kconfig @@ -8,6 +8,11 @@ if DRIVERS_IEEE80211 config IEEE80211_BROADCOM_FULLMAC bool +config IEEE80211_BROADCOM_BCM43362 + bool "Broadcom 43362 chip support" + depends on IEEE80211_BROADCOM_FULLMAC + default n + config IEEE80211_BROADCOM_FULLMAC_SDIO bool "Broadcom FullMAC driver on SDIO bus" depends on ARCH_HAVE_SDIO diff --git a/drivers/wireless/ieee80211/Make.defs b/drivers/wireless/ieee80211/Make.defs index 99c4a4446f..b18d123546 100644 --- a/drivers/wireless/ieee80211/Make.defs +++ b/drivers/wireless/ieee80211/Make.defs @@ -42,9 +42,14 @@ ifeq ($(CONFIG_DRIVERS_IEEE80211),y) ifeq ($(CONFIG_IEEE80211_BROADCOM_FULLMAC_SDIO),y) CSRCS += bcmf_sdio.c + CSRCS += bcmf_core.c CSRCS += mmc_sdio.c endif +ifeq ($(CONFIG_IEEE80211_BROADCOM_BCM43362),y) +CSRCS += bcmf_chip_43362.c +endif + # Include IEEE 802.11 build support DEPPATH += --dep-path wireless$(DELIM)ieee80211 diff --git a/drivers/wireless/ieee80211/bcm43362_constants.h b/drivers/wireless/ieee80211/bcm43362_constants.h new file mode 100644 index 0000000000..929bdf4042 --- /dev/null +++ b/drivers/wireless/ieee80211/bcm43362_constants.h @@ -0,0 +1,164 @@ +/* + * Copyright (c) 2015 Broadcom + * 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 of Broadcom nor the names of other contributors to this + * software may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * 4. This software may not be used as a standalone product, and may only be used as + * incorporated in your product or device that incorporates Broadcom wireless connectivity + * products and solely for the purpose of enabling the functionalities of such Broadcom products. + * + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + * ANY WARRANTIES OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + * WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT, ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER 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 BCM43362_CONSTANTS_H_ +#define BCM43362_CONSTANTS_H_ + +/****************************************************** + * Architecture Constants + ******************************************************/ + +/* General chip stats */ +#define CHIP_RAM_SIZE 0x3C000 + +/* Backplane architecture */ +#define CHIPCOMMON_BASE_ADDRESS 0x18000000 /* Chipcommon core register region */ +#define DOT11MAC_BASE_ADDRESS 0x18001000 /* dot11mac core register region */ +#define SDIO_BASE_ADDRESS 0x18002000 /* SDIOD Device core register region */ +#define WLAN_ARMCM3_BASE_ADDRESS 0x18003000 /* ARMCM3 core register region */ +#define SOCSRAM_BASE_ADDRESS 0x18004000 /* SOCSRAM core register region */ +#define BACKPLANE_ADDRESS_MASK 0x7FFF + +#define CHIP_STA_INTERFACE 0 +#define CHIP_AP_INTERFACE 1 +#define CHIP_P2P_INTERFACE 2 + +/* Maximum value of bus data credit difference */ +#define CHIP_MAX_BUS_DATA_CREDIT_DIFF 7 + +/* Chipcommon registers */ +#define CHIPCOMMON_GPIO_CONTROL ((uint32_t) (CHIPCOMMON_BASE_ADDRESS + 0x6C) ) + +/****************************************************** + * SDIO Constants + ******************************************************/ +/* CurrentSdiodProgGuide r23 */ + +/* Base registers */ +#define SDIO_CORE ((uint32_t) (SDIO_BASE_ADDRESS + 0x00) ) +#define SDIO_INT_STATUS ((uint32_t) (SDIO_BASE_ADDRESS + 0x20) ) +#define SDIO_TO_SB_MAILBOX ((uint32_t) (SDIO_BASE_ADDRESS + 0x40) ) +#define SDIO_TO_SB_MAILBOX_DATA ((uint32_t) (SDIO_BASE_ADDRESS + 0x48) ) +#define SDIO_TO_HOST_MAILBOX_DATA ((uint32_t) (SDIO_BASE_ADDRESS + 0x4C) ) +#define SDIO_TO_SB_MAIL_BOX ((uint32_t) (SDIO_BASE_ADDRESS + 0x40) ) +#define SDIO_INT_HOST_MASK ((uint32_t) (SDIO_BASE_ADDRESS + 0x24) ) +#define SDIO_FUNCTION_INT_MASK ((uint32_t) (SDIO_BASE_ADDRESS + 0x34) ) + +/* SDIO Function 0 (SDIO Bus) register addresses */ + +/* SDIO Device CCCR offsets */ +/* TODO: What does CIS/CCCR stand for? */ +/* CCCR accesses do not require backpane clock */ +#define SDIOD_CCCR_UHS_I ( (uint32_t) 0x14 ) /* UHS-I Support */ +#define SDIOD_CCCR_DRIVE ( (uint32_t) 0x15 ) /* Drive Strength */ +#define SDIOD_CCCR_INTEXT ( (uint32_t) 0x16 ) /* Interrupt Extension */ +#define SDIOD_SEP_INT_CTL ( (uint32_t) 0xF2 ) /* Separate Interrupt Control*/ +#define SDIOD_CCCR_F1INFO ( (uint32_t) 0x100 ) /* Function 1 (Backplane) Info */ +#define SDIOD_CCCR_F1HP ( (uint32_t) 0x102 ) /* Function 1 (Backplane) High Power */ +#define SDIOD_CCCR_F1CISPTR_0 ( (uint32_t) 0x109 ) /* Function 1 (Backplane) CIS Base Address Pointer Register 0 (LSB) */ +#define SDIOD_CCCR_F1CISPTR_1 ( (uint32_t) 0x10A ) /* Function 1 (Backplane) CIS Base Address Pointer Register 1 */ +#define SDIOD_CCCR_F1CISPTR_2 ( (uint32_t) 0x10B ) /* Function 1 (Backplane) CIS Base Address Pointer Register 2 (MSB - only bit 1 valid) */ +#define SDIOD_CCCR_F1BLKSIZE_0 ( (uint32_t) 0x110 ) /* Function 1 (Backplane) SDIO Block Size Register 0 (LSB) */ +#define SDIOD_CCCR_F1BLKSIZE_1 ( (uint32_t) 0x111 ) /* Function 1 (Backplane) SDIO Block Size Register 1 (MSB) */ +#define SDIOD_CCCR_F2INFO ( (uint32_t) 0x200 ) /* Function 2 (WLAN Data FIFO) Info */ +#define SDIOD_CCCR_F2HP ( (uint32_t) 0x202 ) /* Function 2 (WLAN Data FIFO) High Power */ +#define SDIOD_CCCR_F2CISPTR_0 ( (uint32_t) 0x209 ) /* Function 2 (WLAN Data FIFO) CIS Base Address Pointer Register 0 (LSB) */ +#define SDIOD_CCCR_F2CISPTR_1 ( (uint32_t) 0x20A ) /* Function 2 (WLAN Data FIFO) CIS Base Address Pointer Register 1 */ +#define SDIOD_CCCR_F2CISPTR_2 ( (uint32_t) 0x20B ) /* Function 2 (WLAN Data FIFO) CIS Base Address Pointer Register 2 (MSB - only bit 1 valid) */ +#define SDIOD_CCCR_F2BLKSIZE_0 ( (uint32_t) 0x210 ) /* Function 2 (WLAN Data FIFO) SDIO Block Size Register 0 (LSB) */ +#define SDIOD_CCCR_F2BLKSIZE_1 ( (uint32_t) 0x211 ) /* Function 2 (WLAN Data FIFO) SDIO Block Size Register 1 (MSB) */ +#define SDIOD_CCCR_F3INFO ( (uint32_t) 0x300 ) /* Function 3 (Bluetooth Data FIFO) Info */ +#define SDIOD_CCCR_F3HP ( (uint32_t) 0x302 ) /* Function 3 (Bluetooth Data FIFO) High Power */ +#define SDIOD_CCCR_F3CISPTR_0 ( (uint32_t) 0x309 ) /* Function 3 (Bluetooth Data FIFO) CIS Base Address Pointer Register 0 (LSB) */ +#define SDIOD_CCCR_F3CISPTR_1 ( (uint32_t) 0x30A ) /* Function 3 (Bluetooth Data FIFO) CIS Base Address Pointer Register 1 */ +#define SDIOD_CCCR_F3CISPTR_2 ( (uint32_t) 0x30B ) /* Function 3 (Bluetooth Data FIFO) CIS Base Address Pointer Register 2 (MSB - only bit 1 valid) */ +#define SDIOD_CCCR_F3BLKSIZE_0 ( (uint32_t) 0x310 ) /* Function 3 (Bluetooth Data FIFO) SDIO Block Size Register 0 (LSB) */ +#define SDIOD_CCCR_F3BLKSIZE_1 ( (uint32_t) 0x311 ) /* Function 3 (Bluetooth Data FIFO) SDIO Block Size Register 1 (MSB) */ + + +/* SDIO Function 1 (Backplane) register addresses */ +/* Addresses 0x00000000 - 0x0000FFFF are directly access the backplane + * throught the backplane window. Addresses above 0x0000FFFF are + * registers relating to backplane access, and do not require a backpane + * clock to access them + */ +#define SDIO_GPIO_SELECT ( (uint32_t) 0x10005 ) +#define SDIO_GPIO_OUTPUT ( (uint32_t) 0x10006 ) +#define SDIO_GPIO_ENABLE ( (uint32_t) 0x10007 ) +#define SDIO_FUNCTION2_WATERMARK ( (uint32_t) 0x10008 ) +#define SDIO_DEVICE_CONTROL ( (uint32_t) 0x10009 ) +#define SDIO_BACKPLANE_ADDRESS_LOW ( (uint32_t) 0x1000A ) +#define SDIO_BACKPLANE_ADDRESS_MID ( (uint32_t) 0x1000B ) +#define SDIO_BACKPLANE_ADDRESS_HIGH ( (uint32_t) 0x1000C ) +#define SDIO_FRAME_CONTROL ( (uint32_t) 0x1000D ) +#define SDIO_CHIP_CLOCK_CSR ( (uint32_t) 0x1000E ) +#define SDIO_PULL_UP ( (uint32_t) 0x1000F ) +#define SDIO_READ_FRAME_BC_LOW ( (uint32_t) 0x1001B ) +#define SDIO_READ_FRAME_BC_HIGH ( (uint32_t) 0x1001C ) + +#define I_HMB_SW_MASK ( (uint32_t) 0x000000F0 ) +#define I_HMB_FRAME_IND ( 1<<6 ) +#define FRAME_AVAILABLE_MASK I_HMB_SW_MASK + +/****************************************************** + * Bit Masks + ******************************************************/ + +/* SDIO_FRAME_CONTROL Bits */ +#define SFC_RF_TERM ( (uint32_t) (1 << 0) ) /* Read Frame Terminate */ +#define SFC_WF_TERM ( (uint32_t) (1 << 1) ) /* Write Frame Terminate */ +#define SFC_CRC4WOOS ( (uint32_t) (1 << 2) ) /* HW reports CRC error for write out of sync */ +#define SFC_ABORTALL ( (uint32_t) (1 << 3) ) /* Abort cancels all in-progress frames */ + +/* SDIO_TO_SB_MAIL_BOX bits corresponding to intstatus bits */ +#define SMB_NAK ( (uint32_t) (1 << 0) ) /* To SB Mailbox Frame NAK */ +#define SMB_INT_ACK ( (uint32_t) (1 << 1) ) /* To SB Mailbox Host Interrupt ACK */ +#define SMB_USE_OOB ( (uint32_t) (1 << 2) ) /* To SB Mailbox Use OOB Wakeup */ +#define SMB_DEV_INT ( (uint32_t) (1 << 3) ) /* To SB Mailbox Miscellaneous Interrupt */ + + +#define WL_CHANSPEC_BAND_MASK (0xf000) +#define WL_CHANSPEC_BAND_5G (0x1000) +#define WL_CHANSPEC_BAND_2G (0x2000) +#define WL_CHANSPEC_CTL_SB_MASK (0x0300) +#define WL_CHANSPEC_CTL_SB_LOWER (0x0100) +#define WL_CHANSPEC_CTL_SB_UPPER (0x0200) +#define WL_CHANSPEC_CTL_SB_NONE (0x0300) +#define WL_CHANSPEC_BW_MASK (0x0C00) +#define WL_CHANSPEC_BW_10 (0x0400) +#define WL_CHANSPEC_BW_20 (0x0800) +#define WL_CHANSPEC_BW_40 (0x0C00) + +#endif /* ifndef BCM43362_CONSTANTS_H_ */ diff --git a/drivers/wireless/ieee80211/bcmf_chip_43362.c b/drivers/wireless/ieee80211/bcmf_chip_43362.c new file mode 100644 index 0000000000..0c940ffae5 --- /dev/null +++ b/drivers/wireless/ieee80211/bcmf_chip_43362.c @@ -0,0 +1,28 @@ +#include "bcmf_chip_43362.h" +#include "bcm43362_constants.h" + +#include +#include +#include "bcmf_sdio_core.h" + +#define WRAPPER_REGISTER_OFFSET (0x100000) + +uint32_t bcmf_43362_get_core_base_address(unsigned int core) +{ + switch (core) + { + case CHIPCOMMON_CORE_ID: + return CHIPCOMMON_BASE_ADDRESS; + case DOT11MAC_CORE_ID: + return DOT11MAC_BASE_ADDRESS; + case SDIOD_CORE_ID: + return SDIO_BASE_ADDRESS; + case WLAN_ARMCM3_CORE_ID: + return WLAN_ARMCM3_BASE_ADDRESS + WRAPPER_REGISTER_OFFSET; + case SOCSRAM_CORE_ID: + return SOCSRAM_BASE_ADDRESS + WRAPPER_REGISTER_OFFSET; + default: + _err("Invalid core id %d\n", core); + } + return 0; +} diff --git a/drivers/wireless/ieee80211/bcmf_chip_43362.h b/drivers/wireless/ieee80211/bcmf_chip_43362.h new file mode 100644 index 0000000000..08f6918f62 --- /dev/null +++ b/drivers/wireless/ieee80211/bcmf_chip_43362.h @@ -0,0 +1,8 @@ +#ifndef __DRIVERS_WIRELESS_IEEE80211_BCM_CHIP_43362_H +#define __DRIVERS_WIRELESS_IEEE80211_BCM_CHIP_43362_H + +#include + +uint32_t bcmf_43362_get_core_base_address(unsigned int core); + +#endif /* __DRIVERS_WIRELESS_IEEE80211_BCM_CHIP_43362_H */ diff --git a/drivers/wireless/ieee80211/bcmf_core.c b/drivers/wireless/ieee80211/bcmf_core.c new file mode 100644 index 0000000000..0da0e2131c --- /dev/null +++ b/drivers/wireless/ieee80211/bcmf_core.c @@ -0,0 +1,390 @@ +/**************************************************************************** + * drivers/wireless/ieee80211/bcmf_core.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Simon Piriou + * + * 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 "bcmf_core.h" +#include "bcmf_sdio.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Agent registers (common for every core) */ +#define BCMA_IOCTL 0x0408 /* IO control */ +#define BCMA_IOST 0x0500 /* IO status */ +#define BCMA_RESET_CTL 0x0800 /* Reset control */ +#define BCMA_RESET_ST 0x0804 + +#define BCMA_IOCTL_CLK 0x0001 +#define BCMA_IOCTL_FGC 0x0002 +#define BCMA_IOCTL_CORE_BITS 0x3FFC +#define BCMA_IOCTL_PME_EN 0x4000 +#define BCMA_IOCTL_BIST_EN 0x8000 + +#define BCMA_IOST_CORE_BITS 0x0FFF +#define BCMA_IOST_DMA64 0x1000 +#define BCMA_IOST_GATED_CLK 0x2000 +#define BCMA_IOST_BIST_ERROR 0x4000 +#define BCMA_IOST_BIST_DONE 0x8000 + +#define BCMA_RESET_CTL_RESET 0x0001 + +/* Transfer size properties */ +#define BCMF_UPLOAD_TRANSFER_SIZE (64 * 256) + +// TODO move in chip configuration data +#define CHIP_RAM_SIZE 0x3C000 + +extern const char bcmf_nvram_image[]; +extern const unsigned int bcmf_nvram_image_len; + +extern const uint8_t bcmf_firmware_image[]; +extern const unsigned int bcmf_firmware_image_len; + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static int bcmf_core_set_backplane_window(FAR struct bcmf_dev_s *priv, + uint32_t address); + +static int bcmf_upload_binary(FAR struct bcmf_dev_s *priv, + uint32_t address, uint8_t *buf, + unsigned int len); + +static int bcmf_upload_nvram(FAR struct bcmf_dev_s *priv); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +int bcmf_core_set_backplane_window(FAR struct bcmf_dev_s *priv, uint32_t address) +{ + int ret; + int i; + + address &= ~SBSDIO_SB_OFT_ADDR_MASK; + + for (i = 1; i < 4; i++) + { + uint8_t addr_part = (address >> (8*i)) & 0xff; + uint8_t cur_addr_part = (priv->backplane_current_addr >> (8*i)) & 0xff; + + if (addr_part != cur_addr_part) + { + /* Update current backplane base address */ + + ret = bcmf_write_reg(priv, 1, SBSDIO_FUNC1_SBADDRLOW+i-1, + addr_part); + + if (ret != OK) + { + return ret; + } + + priv->backplane_current_addr &= ~(0xff << (8*i)); + priv->backplane_current_addr |= addr_part << (8*i); + } + } + + return OK; +} + +int bcmf_upload_binary(FAR struct bcmf_dev_s *priv, uint32_t address, + uint8_t *buf, unsigned int len) +{ + unsigned int size; + + while (len > 0) + { + /* Set the backplane window to include the start address */ + + int ret = bcmf_core_set_backplane_window(priv, address); + if (ret != OK) + { + return ret; + } + + if (len > BCMF_UPLOAD_TRANSFER_SIZE) + { + size = BCMF_UPLOAD_TRANSFER_SIZE; + } + else + { + size = len; + } + + /* Transfer firmware data */ + + ret = bcmf_transfer_bytes(priv, true, 1, + address & SBSDIO_SB_OFT_ADDR_MASK, buf, size); + if (ret != OK) + { + _err("transfer failed %d %x %d\n", ret, address, size); + return ret; + } + + len -= size; + address += size; + buf += size; + } + return OK; +} + +int bcmf_upload_nvram(FAR struct bcmf_dev_s *priv) +{ + int ret; + uint32_t nvram_sz; + uint32_t token; + + /* Round up the size of the image */ + + nvram_sz = (bcmf_nvram_image_len + 63) & (-64); + + _info("nvram size is %d %d bytes\n", nvram_sz, bcmf_nvram_image_len); + + /* Write image */ + + ret = bcmf_upload_binary(priv, CHIP_RAM_SIZE - 4 - nvram_sz, + (uint8_t*)bcmf_nvram_image, bcmf_nvram_image_len); + if ( ret != OK) + { + return ret; + } + + /* generate length token */ + + token = nvram_sz / 4; + token = (~token << 16) | (token & 0x0000FFFF); + + /* Write the length token to the last word */ + + ret = bcmf_write_sbreg(priv, CHIP_RAM_SIZE - 4, (uint8_t*)&token, 4); + if ( ret != OK) + { + return ret; + } + + return OK; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: bcmf_read_sbreg + ****************************************************************************/ + +int bcmf_read_sbreg(FAR struct bcmf_dev_s *priv, uint32_t address, + uint8_t *reg, unsigned int len) +{ + int ret = bcmf_core_set_backplane_window(priv, address); + if (ret != OK) + { + return ret; + } + + return bcmf_transfer_bytes(priv, false, 1, + address & SBSDIO_SB_OFT_ADDR_MASK, reg, len); +} + +/**************************************************************************** + * Name: bcmf_write_sbreg + ****************************************************************************/ + +int bcmf_write_sbreg(FAR struct bcmf_dev_s *priv, uint32_t address, + uint8_t *reg, unsigned int len) +{ + + int ret = bcmf_core_set_backplane_window(priv, address); + if (ret != OK) + { + return ret; + } + + return bcmf_transfer_bytes(priv, true, 1, address & SBSDIO_SB_OFT_ADDR_MASK, + reg, len); +} + +/**************************************************************************** + * Name: bcmf_core_upload_firmware + ****************************************************************************/ + +int bcmf_core_upload_firmware(FAR struct bcmf_dev_s *priv) +{ + int ret; + + _info("upload firmware\n"); + + /* Disable ARMCM3 core and reset SOCRAM core + * to set device in firmware upload mode */ + + bcmf_core_disable(priv, WLAN_ARMCM3_CORE_ID); + bcmf_core_reset(priv, SOCSRAM_CORE_ID); + + up_mdelay(50); + + /* Flash chip firmware */ + + _info("firmware size is %d bytes\n", bcmf_firmware_image_len); + ret = bcmf_upload_binary(priv, 0, (uint8_t*)bcmf_firmware_image, + bcmf_firmware_image_len); + + if (ret != OK) + { + _err("Failed to upload firmware\n"); + return ret; + } + + /* Flash NVRAM configuration file */ + + _info("upload nvram configuration\n"); + ret = bcmf_upload_nvram(priv); + if (ret != OK) + { + _err("Failed to upload nvram\n"); + return ret; + } + + /* Firmware upload done, restart ARMCM3 core */ + + up_mdelay(10); + bcmf_core_reset(priv, WLAN_ARMCM3_CORE_ID); + + /* Check ARMCM3 core is running */ + + up_mdelay(10); + if (!bcmf_core_isup(priv, WLAN_ARMCM3_CORE_ID)) + { + _err("Cannot start ARMCM3 core\n"); + return -ETIMEDOUT; + } + + return OK; +} + +bool bcmf_core_isup(FAR struct bcmf_dev_s *priv, unsigned int core) +{ + uint32_t value = 0; + uint32_t base = priv->get_core_base_address(core); + + bcmf_read_sbregw(priv, base + BCMA_IOCTL, &value); + + if ((value & (BCMA_IOCTL_FGC | BCMA_IOCTL_CLK)) != BCMA_IOCTL_CLK) + { + return false; + } + + bcmf_read_sbregw(priv, base + BCMA_RESET_CTL, &value); + + return (value & BCMA_RESET_CTL_RESET) == 0; +} + +void bcmf_core_disable(FAR struct bcmf_dev_s *priv, unsigned int core) +{ + uint8_t value; + uint32_t base = priv->get_core_base_address(core); + + /* Check if core is already in reset state */ + + bcmf_read_sbregb(priv, base + BCMA_RESET_CTL, &value); + + if ((value & BCMA_RESET_CTL_RESET) != 0) + { + /* Core already disabled */ + + return; + } + + /* Ensure no backplane operation is pending */ + + up_mdelay(10); + + /* Set core in reset state */ + + bcmf_write_sbregb(priv, base + BCMA_RESET_CTL, BCMA_RESET_CTL_RESET); + up_udelay(1); + + /* Write 0 to the IO control and read it back */ + + bcmf_write_sbregb(priv, base + BCMA_IOCTL, 0); + bcmf_read_sbregb(priv, base + BCMA_IOCTL, &value); + up_udelay(10); +} + +void bcmf_core_reset(FAR struct bcmf_dev_s *priv, unsigned int core) +{ + uint32_t value; + uint32_t base = priv->get_core_base_address(core); + + /* Put core in reset state */ + + bcmf_core_disable(priv, core); + + /* Run initialization sequence */ + + bcmf_write_sbregb(priv, base + BCMA_IOCTL, BCMA_IOCTL_FGC | BCMA_IOCTL_CLK); + bcmf_read_sbregw(priv, base + BCMA_IOCTL, &value); + + bcmf_write_sbregb(priv, base + BCMA_RESET_CTL, 0); + bcmf_read_sbregw(priv, base + BCMA_RESET_CTL, &value); + + up_udelay(1); + + bcmf_write_sbregb(priv, base + BCMA_IOCTL, BCMA_IOCTL_CLK); + bcmf_read_sbregw(priv, base + BCMA_IOCTL, &value); + + up_udelay(1); +} diff --git a/drivers/wireless/ieee80211/bcmf_core.h b/drivers/wireless/ieee80211/bcmf_core.h new file mode 100644 index 0000000000..9200423979 --- /dev/null +++ b/drivers/wireless/ieee80211/bcmf_core.h @@ -0,0 +1,83 @@ +/**************************************************************************** + * drivers/wireless/ieee80211/bcmf_core.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Simon Piriou + * + * 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 __DRIVERS_WIRELESS_IEEE80211_BCMF_CORE_H +#define __DRIVERS_WIRELESS_IEEE80211_BCMF_CORE_H + +#include +#include + +#include "bcmf_driver.h" + + +int bcmf_read_sbreg(FAR struct bcmf_dev_s *priv, uint32_t address, + uint8_t *reg, unsigned int len); + +int bcmf_write_sbreg(FAR struct bcmf_dev_s *priv, uint32_t address, + uint8_t *reg, unsigned int len); + +bool bcmf_core_isup(FAR struct bcmf_dev_s *priv, unsigned int core); + +void bcmf_core_disable(FAR struct bcmf_dev_s *priv, unsigned int core); + +void bcmf_core_reset(FAR struct bcmf_dev_s *priv, unsigned int core); + +int bcmf_core_upload_firmware(FAR struct bcmf_dev_s *priv); + +static inline int bcmf_read_sbregb(FAR struct bcmf_dev_s *priv, + uint32_t address, uint8_t *reg) +{ + return bcmf_read_sbreg(priv, address, reg, 1); +} + +static inline int bcmf_read_sbregw(FAR struct bcmf_dev_s *priv, + uint32_t address, uint32_t *reg) +{ + return bcmf_read_sbreg(priv, address, (uint8_t*)reg, 4); +} + +static inline int bcmf_write_sbregb(FAR struct bcmf_dev_s *priv, + uint32_t address, uint8_t reg) +{ + return bcmf_write_sbreg(priv, address, ®, 1); +} + +static inline int bcmf_write_sbregw(FAR struct bcmf_dev_s *priv, + uint32_t address, uint32_t reg) +{ + return bcmf_write_sbreg(priv, address, (uint8_t*)®, 4); +} + +#endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_CORE_H */ diff --git a/drivers/wireless/ieee80211/bcmf_driver.h b/drivers/wireless/ieee80211/bcmf_driver.h new file mode 100644 index 0000000000..0156e9021d --- /dev/null +++ b/drivers/wireless/ieee80211/bcmf_driver.h @@ -0,0 +1,54 @@ +/**************************************************************************** + * drivers/wireless/ieee80211/bcmf_driver.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Simon Piriou + * + * 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 __DRIVERS_WIRELESS_IEEE80211_BCMF_DRIVER_H +#define __DRIVERS_WIRELESS_IEEE80211_BCMF_DRIVER_H + +#include + +/* This structure contains the unique state of the Broadcom FullMAC driver */ + +struct bcmf_dev_s +{ + FAR struct sdio_dev_s *sdio_dev; /* The SDIO device bound to this instance */ + int minor; /* Device minor number */ + + uint32_t backplane_current_addr; /* Current function 1 backplane base addr */ + + uint32_t (*get_core_base_address)(unsigned int core); /* Get chip specific + base address for evey cores */ +}; + +#endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_DRIVER_H */ diff --git a/drivers/wireless/ieee80211/bcmf_sdio.c b/drivers/wireless/ieee80211/bcmf_sdio.c index 317102fc30..5fecd45cb4 100644 --- a/drivers/wireless/ieee80211/bcmf_sdio.c +++ b/drivers/wireless/ieee80211/bcmf_sdio.c @@ -54,7 +54,8 @@ #include #include -#include "chip_constants.h" +#include "bcmf_sdio.h" +#include "bcmf_core.h" /**************************************************************************** * Pre-processor Definitions @@ -64,66 +65,20 @@ #define BCMF_DEVICE_START_DELAY_MS 10 #define BCMF_CLOCK_SETUP_DELAY_MS 500 -/* Agent registers (common for every core) */ -#define BCMA_IOCTL 0x0408 /* IO control */ -#define BCMA_IOST 0x0500 /* IO status */ -#define BCMA_RESET_CTL 0x0800 /* Reset control */ -#define BCMA_RESET_ST 0x0804 - -#define BCMA_IOCTL_CLK 0x0001 -#define BCMA_IOCTL_FGC 0x0002 -#define BCMA_IOCTL_CORE_BITS 0x3FFC -#define BCMA_IOCTL_PME_EN 0x4000 -#define BCMA_IOCTL_BIST_EN 0x8000 - -#define BCMA_IOST_CORE_BITS 0x0FFF -#define BCMA_IOST_DMA64 0x1000 -#define BCMA_IOST_GATED_CLK 0x2000 -#define BCMA_IOST_BIST_ERROR 0x4000 -#define BCMA_IOST_BIST_DONE 0x8000 - -#define BCMA_RESET_CTL_RESET 0x0001 - /**************************************************************************** * Private Types ****************************************************************************/ -/* This structure contains the unique state of the Broadcom FullMAC driver */ - -struct bcmf_dev_s -{ - FAR struct sdio_dev_s *sdio_dev; /* The SDIO device bound to this instance */ - int minor; /* Device minor number */ - - uint32_t backplane_current_addr; /* Current function 1 backplane base addr */ -}; - /**************************************************************************** * Private Function Prototypes ****************************************************************************/ -static int bcmf_transfer_bytes(FAR struct bcmf_dev_s *priv, bool write, - uint8_t function, uint32_t address, - uint8_t *buf, unsigned int len); - -static int bcmf_read_reg(FAR struct bcmf_dev_s *priv, uint8_t function, - uint32_t address, uint8_t *reg); - -static int bcmf_write_reg(FAR struct bcmf_dev_s *priv, uint8_t function, - uint32_t address, uint8_t reg); - -static int bcmf_read_sbreg(FAR struct bcmf_dev_s *priv, uint32_t address, - uint32_t *reg); - -static int bcmf_write_sbreg(FAR struct bcmf_dev_s *priv, uint32_t address, - uint32_t reg); - static int bcmf_probe(FAR struct bcmf_dev_s *priv); static int bcmf_hwinitialize(FAR struct bcmf_dev_s *priv); static void bcmf_hwuninitialize(FAR struct bcmf_dev_s *priv); static int bcmf_chipinitialize(FAR struct bcmf_dev_s *priv); -static int bcmf_set_backplane_window(FAR struct bcmf_dev_s *priv, uint32_t addr); +static int bcmf_oob_irq(int irq, FAR void *context, FAR void *arg); /**************************************************************************** * Private Data @@ -133,80 +88,10 @@ static int bcmf_set_backplane_window(FAR struct bcmf_dev_s *priv, uint32_t addr * Private Functions ****************************************************************************/ -/**************************************************************************** - * Name: bcmf_transfer_bytes - ****************************************************************************/ - -int bcmf_transfer_bytes(FAR struct bcmf_dev_s *priv, bool write, - uint8_t function, uint32_t address, - uint8_t *buf, unsigned int len) -{ - /* Use rw_io_direct method if len is 1 */ - - if (len == 1) - { - return sdio_io_rw_direct(priv->sdio_dev, write, - function, address, *buf, buf); - } - - return sdio_io_rw_extended(priv->sdio_dev, write, - function, address, true, buf, len, 1); - - // return -EINVAL; -} - -/**************************************************************************** - * Name: bcmf_read_reg - ****************************************************************************/ - -int bcmf_read_reg(FAR struct bcmf_dev_s *priv, uint8_t function, - uint32_t address, uint8_t *reg) -{ - return bcmf_transfer_bytes(priv, false, function, address, reg, 1); -} - -/**************************************************************************** - * Name: bcmf_write_reg - ****************************************************************************/ - -int bcmf_write_reg(FAR struct bcmf_dev_s *priv, uint8_t function, - uint32_t address, uint8_t reg) -{ - return bcmf_transfer_bytes(priv, true, function, address, ®, 1); -} - -/**************************************************************************** - * Name: bcmf_read_sbreg - ****************************************************************************/ - -int bcmf_read_sbreg(FAR struct bcmf_dev_s *priv, uint32_t address, - uint32_t *reg) -{ - int ret = bcmf_set_backplane_window(priv, address); - if (ret != OK) - { - return ret; - } - - return bcmf_transfer_bytes(priv, false, 1, address, (uint8_t*)reg, 4); -} - -/**************************************************************************** - * Name: bcmf_write_sbreg - ****************************************************************************/ - -int bcmf_write_sbreg(FAR struct bcmf_dev_s *priv, uint32_t address, - uint32_t reg) +int bcmf_oob_irq(int irq, FAR void *context, FAR void *arg) { - - int ret = bcmf_set_backplane_window(priv, address); - if (ret != OK) - { - return ret; - } - - return bcmf_transfer_bytes(priv, true, 1, address, - (uint8_t*)®, 4); + /* TODO */ + return OK; } /**************************************************************************** @@ -217,7 +102,6 @@ int bcmf_probe(FAR struct bcmf_dev_s *priv) { int ret; uint8_t value; - int loops; /* Probe sdio card compatible device */ @@ -227,14 +111,6 @@ int bcmf_probe(FAR struct bcmf_dev_s *priv) goto exit_error; } - /* Enable bus FN1 */ - - ret = sdio_enable_function(priv->sdio_dev, 1); - if (ret != OK) - { - goto exit_error; - } - /* Set FN0 / FN1 / FN2 default block size */ ret = sdio_set_blocksize(priv->sdio_dev, 0, 64); @@ -257,8 +133,6 @@ int bcmf_probe(FAR struct bcmf_dev_s *priv) /* Enable device interrupts for FN0, FN1 and FN2 */ - // ret = sdio_io_rw_direct(priv->sdio_dev, true, 0, SDIO_CCCR_INTEN, - // (1 << 0) | (1 << 1) | (1 << 2), NULL); ret = bcmf_write_reg(priv, 0, SDIO_CCCR_INTEN, (1 << 0) | (1 << 1) | (1 << 2)); if (ret != OK) @@ -266,41 +140,20 @@ int bcmf_probe(FAR struct bcmf_dev_s *priv) goto exit_error; } - /* Default device clock speed is up to 25 Mhz * We could set EHS bit to operate at a clock rate up to 50 Mhz */ SDIO_CLOCK(priv->sdio_dev, CLOCK_SD_TRANSFER_4BIT); up_mdelay(BCMF_CLOCK_SETUP_DELAY_MS); - /* Wait for function 1 to be ready */ - - loops = 10; - while (--loops > 0) - { - up_mdelay(1); - - // ret = sdio_io_rw_direct(priv->sdio_dev, false, 0, SDIO_CCCR_IORDY, 0, &value); - ret = bcmf_read_reg(priv, 0, SDIO_CCCR_IORDY, &value); - if (ret != OK) - { - return ret; - } - - if (value & (1 << 1)) - { - /* Function 1 is ready */ - break; - } - } + /* Enable bus FN1 */ - if (loops <= 0) + ret = sdio_enable_function(priv->sdio_dev, 1); + if (ret != OK) { - return -ETIMEDOUT; + goto exit_error; } - _info("sdio fn1 ready\n"); - return OK; exit_error: @@ -313,14 +166,15 @@ exit_error: * Name: bcmf_businitialize ****************************************************************************/ - int bcmf_businitialize(FAR struct bcmf_dev_s *priv) +int bcmf_businitialize(FAR struct bcmf_dev_s *priv) { int ret; int loops; + uint8_t value; /* Send Active Low-Power clock request */ - ret = bcmf_write_reg(priv, 1, SDIO_CHIP_CLOCK_CSR, + ret = bcmf_write_reg(priv, 1, SBSDIO_FUNC1_CHIPCLKCSR, SBSDIO_FORCE_HW_CLKREQ_OFF | SBSDIO_ALP_AVAIL_REQ | SBSDIO_FORCE_ALP); @@ -333,10 +187,8 @@ exit_error: loops = 10; while (--loops > 0) { - uint8_t value; - up_mdelay(10); - ret = bcmf_read_reg(priv, 1, SDIO_CHIP_CLOCK_CSR, &value); + ret = bcmf_read_reg(priv, 1, SBSDIO_FUNC1_CHIPCLKCSR, &value); if (ret != OK) { @@ -358,7 +210,7 @@ exit_error: /* Clear Active Low-Power clock request */ - ret = bcmf_write_reg(priv, 1, SDIO_CHIP_CLOCK_CSR, 0); + ret = bcmf_write_reg(priv, 1, SBSDIO_FUNC1_CHIPCLKCSR, 0); if (ret != OK) { return ret; @@ -366,7 +218,7 @@ exit_error: /* Disable pull-ups on SDIO cmd, d0-2 lines */ - ret = bcmf_write_reg(priv, 1, SDIO_PULL_UP, 0); + ret = bcmf_write_reg(priv, 1, SBSDIO_FUNC1_SDIOPULLUP, 0); if (ret != OK) { return ret; @@ -380,41 +232,87 @@ exit_error: return ret; } - // /* Enable function 2 */ + /* Upload firmware */ + + ret = bcmf_core_upload_firmware(priv); + if (ret != OK) + { + return ret; + } + + /* Enable FN2 (frame transfers) */ - // ret = sdio_enable_function(priv->sdio_dev, 2); - // if (ret != OK) - // { - // goto exit_error; - // } + ret = sdio_enable_function(priv->sdio_dev, 2); + if (ret != OK) + { + return ret; + } - // /* Enable out-of-band interrupt signal */ + /* Configure gpio interrupt pin */ - // ret = sdio_io_rw_direct(priv->sdio_dev, true, 0, SDIOD_SEP_INT_CTL, - // SEP_INTR_CTL_MASK | SEP_INTR_CTL_EN | SEP_INTR_CTL_POL, NULL); - // if (ret != OK) - // { - // return ret; - // } + bcmf_board_setup_oob_irq(priv->minor, bcmf_oob_irq, (void*)priv); - // /* Enable function 2 interrupt */ + /* Enable function 2 interrupt */ - // ret = sdio_enable_interrupt(priv->sdio_dev, 0); - // if (ret != OK) - // { - // return ret; - // } - // ret = sdio_enable_interrupt(priv->sdio_dev, 2); - // if (ret != OK) - // { - // return ret; - // } + ret = sdio_enable_interrupt(priv->sdio_dev, 0); + if (ret != OK) + { + return ret; + } + ret = sdio_enable_interrupt(priv->sdio_dev, 2); + if (ret != OK) + { + return ret; + } - // bcmf_board_setup_oob_irq(priv->minor, bcmf_oob_irq, (void*)priv); + /* Redirect, configure and enable io for out-of-band interrupt signal */ - /* Upload firmware */ + ret = sdio_io_rw_direct(priv->sdio_dev, true, 0, SDIO_CCCR_BRCM_SEPINT, + SDIO_SEPINT_MASK | SDIO_SEPINT_OE | SDIO_SEPINT_ACT_HI, NULL); + if (ret != OK) + { + return ret; + } + + _info("wait high throughput clock\n"); + + /* Wait for High Troughput clock to be sure function 2 is running */ + + loops = 10; + while (--loops > 0) + { + up_mdelay(10); + ret = bcmf_read_reg(priv, 1, SBSDIO_FUNC1_CHIPCLKCSR, &value); + + if (ret != OK) + { + return ret; + } - _info("upload firmware\n"); + if (value & SBSDIO_HT_AVAIL) + { + /* High Throughput clock is ready */ + break; + } + } + + if (loops <= 0) + { + _err("HT clock not ready\n"); + return -ETIMEDOUT; + } + + /* FN2 successfully enabled, set core and enable interrupts */ + + bcmf_write_sbregw(priv, + CORE_BUS_REG(priv->get_core_base_address(SDIOD_CORE_ID), + hostintmask), I_HMB_SW_MASK); + + bcmf_write_sbregb(priv, + CORE_BUS_REG(priv->get_core_base_address(SDIOD_CORE_ID), + funcintmask), 2); + + bcmf_write_reg(priv, 1, SBSDIO_WATERMARK, 8); return OK; } @@ -467,6 +365,76 @@ void bcmf_hwuninitialize(FAR struct bcmf_dev_s *priv) * Public Functions ****************************************************************************/ +/**************************************************************************** + * Name: bcmf_transfer_bytes + ****************************************************************************/ + +int bcmf_transfer_bytes(FAR struct bcmf_dev_s *priv, bool write, + uint8_t function, uint32_t address, + uint8_t *buf, unsigned int len) +{ + /* Use rw_io_direct method if len is 1 */ + + if (len == 1) + { + if (write) + { + return sdio_io_rw_direct(priv->sdio_dev, write, + function, address, *buf, NULL); + } + return sdio_io_rw_direct(priv->sdio_dev, write, + function, address, 0, buf); + } + + /* Find best block size / count values for transfer */ + + unsigned int blocklen; + unsigned int nblocks; + + if (len == 64 || len > 0 && len % 64 == 0) + { + blocklen = 64; + nblocks = len / 64; + } + else if (len > 20) + { + // FIXME + blocklen = 64; + nblocks = (len+63) / 64; + } + else + { + blocklen = len; + nblocks = 0; + } + // _info("try extended %d %d %d\n", len, blocklen, nblocks); + return sdio_io_rw_extended(priv->sdio_dev, write, + function, address, true, buf, blocklen, nblocks); + + // return -EINVAL; +} + +/**************************************************************************** + * Name: bcmf_read_reg + ****************************************************************************/ + +int bcmf_read_reg(FAR struct bcmf_dev_s *priv, uint8_t function, + uint32_t address, uint8_t *reg) +{ + *reg = 0; + return bcmf_transfer_bytes(priv, false, function, address, reg, 1); +} + +/**************************************************************************** + * Name: bcmf_write_reg + ****************************************************************************/ + +int bcmf_write_reg(FAR struct bcmf_dev_s *priv, uint8_t function, + uint32_t address, uint8_t reg) +{ + return bcmf_transfer_bytes(priv, true, function, address, ®, 1); +} + /**************************************************************************** * Name: bcmf_sdio_initialize ****************************************************************************/ @@ -511,7 +479,7 @@ int bcmf_sdio_initialize(int minor, FAR struct sdio_dev_s *dev) goto exit_uninit_hw; } - /* Initialize device */ + /* Initialize device bus */ ret = bcmf_businitialize(priv); @@ -520,7 +488,12 @@ int bcmf_sdio_initialize(int minor, FAR struct sdio_dev_s *dev) goto exit_uninit_hw; } - /* TODO Create a wlan device name and register network driver here */ + /* FIXME wait for the chip to be ready to receive commands */ + + up_mdelay(100); + + /* Device is up and running + TODO Create a wlan device name and register network driver here */ return OK; @@ -537,7 +510,7 @@ int bcmf_chipinitialize(FAR struct bcmf_dev_s *priv) int ret; uint32_t value = 0; - ret = bcmf_read_sbreg(priv, CHIPCOMMON_BASE_ADDRESS, &value); + ret = bcmf_read_sbregw(priv, SI_ENUM_BASE, &value); if (ret != OK) { return ret; @@ -547,8 +520,9 @@ int bcmf_chipinitialize(FAR struct bcmf_dev_s *priv) int chipid = value & 0xffff; switch (chipid) { - case BCM_43362_CHIP_ID: - _info("bcm43362 chip detected !!\n"); + case SDIO_DEVICE_ID_BROADCOM_43362: + _info("bcm43362 chip detected\n"); + priv->get_core_base_address = bcmf_43362_get_core_base_address; break; default: _err("chip 0x%x is not supported\n", chipid); @@ -556,36 +530,3 @@ int bcmf_chipinitialize(FAR struct bcmf_dev_s *priv) } return OK; } - -int bcmf_set_backplane_window(FAR struct bcmf_dev_s *priv, uint32_t address) -{ - int ret; - int i; - - address &= ~BACKPLANE_ADDRESS_MASK; - - for (i = 1; i < 4; i++) - { - uint8_t addr_part = (address >> (8*i)) & 0xff; - uint8_t cur_addr_part = (priv->backplane_current_addr >> (8*i)) & 0xff; - - if (addr_part != cur_addr_part) - { - /* Update current backplane base address */ - - ret = bcmf_write_reg(priv, 1, SDIO_BACKPLANE_ADDRESS_LOW+i-1, - addr_part); - - if (ret != OK) - { - return ret; - } - - priv->backplane_current_addr &= ~(0xff << (8*i)); - priv->backplane_current_addr |= addr_part << (8*i); - _info("update %d %08x\n", i, priv->backplane_current_addr); - } - } - - return OK; -} diff --git a/drivers/wireless/ieee80211/bcmf_sdio.h b/drivers/wireless/ieee80211/bcmf_sdio.h new file mode 100644 index 0000000000..614f62ab21 --- /dev/null +++ b/drivers/wireless/ieee80211/bcmf_sdio.h @@ -0,0 +1,21 @@ +#ifndef __DRIVERS_WIRELESS_IEEE80211_BCMF_SDIO_H +#define __DRIVERS_WIRELESS_IEEE80211_BCMF_SDIO_H + +#include "bcmf_sdio_regs.h" +#include "bcmf_sdio_core.h" + +#include "bcmf_driver.h" +#include +#include + +int bcmf_transfer_bytes(FAR struct bcmf_dev_s *priv, bool write, + uint8_t function, uint32_t address, + uint8_t *buf, unsigned int len); + +int bcmf_read_reg(FAR struct bcmf_dev_s *priv, uint8_t function, + uint32_t address, uint8_t *reg); + +int bcmf_write_reg(FAR struct bcmf_dev_s *priv, uint8_t function, + uint32_t address, uint8_t reg); + +#endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_SDIO_H */ \ No newline at end of file diff --git a/drivers/wireless/ieee80211/bcmf_sdio_core.h b/drivers/wireless/ieee80211/bcmf_sdio_core.h new file mode 100644 index 0000000000..a3aca72108 --- /dev/null +++ b/drivers/wireless/ieee80211/bcmf_sdio_core.h @@ -0,0 +1,214 @@ +/* + * Copyright (c) 2011 Broadcom Corporation + * + * Permission to use, copy, modify, and/or distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY + * SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION + * OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF OR IN + * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + */ + +#ifndef BCMF_SDIO_CHIP_H_ +#define BCMF_SDIO_CHIP_H_ + +#include + +#ifndef PAD +#define _PADLINE(line) pad ## line +#define _XSTR(line) _PADLINE(line) +#define PAD _XSTR(__LINE__) +#endif + +/* SDIO device ID */ +#define SDIO_DEVICE_ID_BROADCOM_43143 43143 +#define SDIO_DEVICE_ID_BROADCOM_43241 0x4324 +#define SDIO_DEVICE_ID_BROADCOM_4329 0x4329 +#define SDIO_DEVICE_ID_BROADCOM_4330 0x4330 +#define SDIO_DEVICE_ID_BROADCOM_4334 0x4334 +#define SDIO_DEVICE_ID_BROADCOM_4335_4339 0x4335 +#define SDIO_DEVICE_ID_BROADCOM_43362 43362 + +/* + * Core reg address translation. + * Both macro's returns a 32 bits byte address on the backplane bus. + */ +#define CORE_CC_REG(base, field) \ + (base + offsetof(struct chipcregs, field)) +#define CORE_BUS_REG(base, field) \ + (base + offsetof(struct sdpcmd_regs, field)) +#define CORE_SB(base, field) \ + (base + offsetof(struct sbconfig, field)) + +#define BRCMF_MAX_CORENUM 6 +#define SI_ENUM_BASE 0x18000000 /* Enumeration space base */ + +/* Target state register description */ + +#define SSB_TMSLOW_RESET 0x00000001 /* Reset */ +#define SSB_TMSLOW_REJECT 0x00000002 /* Reject (Standard Backplane) */ +#define SSB_TMSLOW_REJECT_23 0x00000004 /* Reject (Backplane rev 2.3) */ +#define SSB_TMSLOW_CLOCK 0x00010000 /* Clock Enable */ +#define SSB_TMSLOW_FGC 0x00020000 /* Force Gated Clocks On */ +#define SSB_TMSLOW_PE 0x40000000 /* Power Management Enable */ +#define SSB_TMSLOW_BE 0x80000000 /* BIST Enable */ + +#define I_HMB_SW_MASK ( (uint32_t) 0x000000F0 ) + +enum { + CHIPCOMMON_CORE_ID, + DOT11MAC_CORE_ID, + SDIOD_CORE_ID, + WLAN_ARMCM3_CORE_ID, + SOCSRAM_CORE_ID +}; + +struct chip_core_info { + uint16_t id; + uint16_t rev; + uint32_t base; + uint32_t wrapbase; + uint32_t caps; + uint32_t cib; +}; + +struct sbconfig { + uint8_t PAD[0xf00]; + uint32_t PAD[2]; + uint32_t sbipsflag; /* initiator port ocp slave flag */ + uint32_t PAD[3]; + uint32_t sbtpsflag; /* target port ocp slave flag */ + uint32_t PAD[11]; + uint32_t sbtmerrloga; /* (sonics >= 2.3) */ + uint32_t PAD; + uint32_t sbtmerrlog; /* (sonics >= 2.3) */ + uint32_t PAD[3]; + uint32_t sbadmatch3; /* address match3 */ + uint32_t PAD; + uint32_t sbadmatch2; /* address match2 */ + uint32_t PAD; + uint32_t sbadmatch1; /* address match1 */ + uint32_t PAD[7]; + uint32_t sbimstate; /* initiator agent state */ + uint32_t sbintvec; /* interrupt mask */ + uint32_t sbtmstatelow; /* target state */ + uint32_t sbtmstatehigh; /* target state */ + uint32_t sbbwa0; /* bandwidth allocation table0 */ + uint32_t PAD; + uint32_t sbimconfiglow; /* initiator configuration */ + uint32_t sbimconfighigh; /* initiator configuration */ + uint32_t sbadmatch0; /* address match0 */ + uint32_t PAD; + uint32_t sbtmconfiglow; /* target configuration */ + uint32_t sbtmconfighigh; /* target configuration */ + uint32_t sbbconfig; /* broadcast configuration */ + uint32_t PAD; + uint32_t sbbstate; /* broadcast state */ + uint32_t PAD[3]; + uint32_t sbactcnfg; /* activate configuration */ + uint32_t PAD[3]; + uint32_t sbflagst; /* current sbflags */ + uint32_t PAD[3]; + uint32_t sbidlow; /* identification */ + uint32_t sbidhigh; /* identification */ +}; + +/* sdio core registers */ +struct sdpcmd_regs { + uint32_t corecontrol; /* 0x00, rev8 */ + uint32_t corestatus; /* rev8 */ + uint32_t PAD[1]; + uint32_t biststatus; /* rev8 */ + + /* PCMCIA access */ + uint16_t pcmciamesportaladdr; /* 0x010, rev8 */ + uint16_t PAD[1]; + uint16_t pcmciamesportalmask; /* rev8 */ + uint16_t PAD[1]; + uint16_t pcmciawrframebc; /* rev8 */ + uint16_t PAD[1]; + uint16_t pcmciaunderflowtimer; /* rev8 */ + uint16_t PAD[1]; + + /* interrupt */ + uint32_t intstatus; /* 0x020, rev8 */ + uint32_t hostintmask; /* rev8 */ + uint32_t intmask; /* rev8 */ + uint32_t sbintstatus; /* rev8 */ + uint32_t sbintmask; /* rev8 */ + uint32_t funcintmask; /* rev4 */ + uint32_t PAD[2]; + uint32_t tosbmailbox; /* 0x040, rev8 */ + uint32_t tohostmailbox; /* rev8 */ + uint32_t tosbmailboxdata; /* rev8 */ + uint32_t tohostmailboxdata; /* rev8 */ + + /* synchronized access to registers in SDIO clock domain */ + uint32_t sdioaccess; /* 0x050, rev8 */ + uint32_t PAD[3]; + + /* PCMCIA frame control */ + uint8_t pcmciaframectrl; /* 0x060, rev8 */ + uint8_t PAD[3]; + uint8_t pcmciawatermark; /* rev8 */ + uint8_t PAD[155]; + + /* interrupt batching control */ + uint32_t intrcvlazy; /* 0x100, rev8 */ + uint32_t PAD[3]; + + /* counters */ + uint32_t cmd52rd; /* 0x110, rev8 */ + uint32_t cmd52wr; /* rev8 */ + uint32_t cmd53rd; /* rev8 */ + uint32_t cmd53wr; /* rev8 */ + uint32_t abort; /* rev8 */ + uint32_t datacrcerror; /* rev8 */ + uint32_t rdoutofsync; /* rev8 */ + uint32_t wroutofsync; /* rev8 */ + uint32_t writebusy; /* rev8 */ + uint32_t readwait; /* rev8 */ + uint32_t readterm; /* rev8 */ + uint32_t writeterm; /* rev8 */ + uint32_t PAD[40]; + uint32_t clockctlstatus; /* rev8 */ + uint32_t PAD[7]; + + uint32_t PAD[128]; /* DMA engines */ + + /* SDIO/PCMCIA CIS region */ + char cis[512]; /* 0x400-0x5ff, rev6 */ + + /* PCMCIA function control registers */ + char pcmciafcr[256]; /* 0x600-6ff, rev6 */ + uint16_t PAD[55]; + + /* PCMCIA backplane access */ + uint16_t backplanecsr; /* 0x76E, rev6 */ + uint16_t backplaneaddr0; /* rev6 */ + uint16_t backplaneaddr1; /* rev6 */ + uint16_t backplaneaddr2; /* rev6 */ + uint16_t backplaneaddr3; /* rev6 */ + uint16_t backplanedata0; /* rev6 */ + uint16_t backplanedata1; /* rev6 */ + uint16_t backplanedata2; /* rev6 */ + uint16_t backplanedata3; /* rev6 */ + uint16_t PAD[31]; + + /* sprom "size" & "blank" info */ + uint16_t spromstatus; /* 0x7BE, rev2 */ + uint32_t PAD[464]; + + uint16_t PAD[0x80]; +}; + +#ifdef CONFIG_IEEE80211_BROADCOM_BCM43362 +#include "bcmf_chip_43362.h" +#endif + +#endif /* _BCMF_SDIO_CHIP_H_ */ diff --git a/drivers/wireless/ieee80211/bcmf_sdio_regs.h b/drivers/wireless/ieee80211/bcmf_sdio_regs.h new file mode 100644 index 0000000000..bdc117accb --- /dev/null +++ b/drivers/wireless/ieee80211/bcmf_sdio_regs.h @@ -0,0 +1,167 @@ +/* + * Copyright (c) 2010 Broadcom Corporation + * + * Permission to use, copy, modify, and/or distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY + * SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION + * OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF OR IN + * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + */ + +#ifndef _BRCM_SDH_H_ +#define _BRCM_SDH_H_ + +#define SDIO_FUNC_0 0 +#define SDIO_FUNC_1 1 +#define SDIO_FUNC_2 2 + +#define SDIOD_FBR_SIZE 0x100 + +/* io_en */ +#define SDIO_FUNC_ENABLE_1 0x02 +#define SDIO_FUNC_ENABLE_2 0x04 + +/* io_rdys */ +#define SDIO_FUNC_READY_1 0x02 +#define SDIO_FUNC_READY_2 0x04 + +/* intr_status */ +#define INTR_STATUS_FUNC1 0x2 +#define INTR_STATUS_FUNC2 0x4 + +/* Maximum number of I/O funcs */ +#define SDIOD_MAX_IOFUNCS 7 + +/* mask of register map */ +#define REG_F0_REG_MASK 0x7FF +#define REG_F1_MISC_MASK 0x1FFFF + +/* as of sdiod rev 0, supports 3 functions */ +#define SBSDIO_NUM_FUNCTION 3 + +/* function 0 vendor specific CCCR registers */ +#define SDIO_CCCR_BRCM_CARDCAP 0xf0 +#define SDIO_CCCR_BRCM_CARDCAP_CMD14_SUPPORT 0x02 +#define SDIO_CCCR_BRCM_CARDCAP_CMD14_EXT 0x04 +#define SDIO_CCCR_BRCM_CARDCAP_CMD_NODEC 0x08 +#define SDIO_CCCR_BRCM_CARDCTRL 0xf1 +#define SDIO_CCCR_BRCM_CARDCTRL_WLANRESET 0x02 +#define SDIO_CCCR_BRCM_SEPINT 0xf2 + +#define SDIO_SEPINT_MASK 0x01 +#define SDIO_SEPINT_OE 0x02 +#define SDIO_SEPINT_ACT_HI 0x04 + +/* function 1 miscellaneous registers */ + +/* sprom command and status */ +#define SBSDIO_SPROM_CS 0x10000 +/* sprom info register */ +#define SBSDIO_SPROM_INFO 0x10001 +/* sprom indirect access data byte 0 */ +#define SBSDIO_SPROM_DATA_LOW 0x10002 +/* sprom indirect access data byte 1 */ +#define SBSDIO_SPROM_DATA_HIGH 0x10003 +/* sprom indirect access addr byte 0 */ +#define SBSDIO_SPROM_ADDR_LOW 0x10004 +/* sprom indirect access addr byte 0 */ +#define SBSDIO_SPROM_ADDR_HIGH 0x10005 +/* xtal_pu (gpio) output */ +#define SBSDIO_CHIP_CTRL_DATA 0x10006 +/* xtal_pu (gpio) enable */ +#define SBSDIO_CHIP_CTRL_EN 0x10007 +/* rev < 7, watermark for sdio device */ +#define SBSDIO_WATERMARK 0x10008 +/* control busy signal generation */ +#define SBSDIO_DEVICE_CTL 0x10009 + +/* SB Address Window Low (b15) */ +#define SBSDIO_FUNC1_SBADDRLOW 0x1000A +/* SB Address Window Mid (b23:b16) */ +#define SBSDIO_FUNC1_SBADDRMID 0x1000B +/* SB Address Window High (b31:b24) */ +#define SBSDIO_FUNC1_SBADDRHIGH 0x1000C +/* Frame Control (frame term/abort) */ +#define SBSDIO_FUNC1_FRAMECTRL 0x1000D +/* ChipClockCSR (ALP/HT ctl/status) */ +#define SBSDIO_FUNC1_CHIPCLKCSR 0x1000E +/* Force ALP request to backplane */ +#define SBSDIO_FORCE_ALP 0x01 +/* Force HT request to backplane */ +#define SBSDIO_FORCE_HT 0x02 +/* Force ILP request to backplane */ +#define SBSDIO_FORCE_ILP 0x04 +/* Make ALP ready (power up xtal) */ +#define SBSDIO_ALP_AVAIL_REQ 0x08 +/* Make HT ready (power up PLL) */ +#define SBSDIO_HT_AVAIL_REQ 0x10 +/* Squelch clock requests from HW */ +#define SBSDIO_FORCE_HW_CLKREQ_OFF 0x20 +/* Status: ALP is ready */ +#define SBSDIO_ALP_AVAIL 0x40 +/* Status: HT is ready */ +#define SBSDIO_HT_AVAIL 0x80 +/* SdioPullUp (on cmd, d0-d2) */ +#define SBSDIO_FUNC1_SDIOPULLUP 0x1000F +/* Write Frame Byte Count Low */ +#define SBSDIO_FUNC1_WFRAMEBCLO 0x10019 +/* Write Frame Byte Count High */ +#define SBSDIO_FUNC1_WFRAMEBCHI 0x1001A +/* Read Frame Byte Count Low */ +#define SBSDIO_FUNC1_RFRAMEBCLO 0x1001B +/* Read Frame Byte Count High */ +#define SBSDIO_FUNC1_RFRAMEBCHI 0x1001C +/* MesBusyCtl (rev 11) */ +#define SBSDIO_FUNC1_MESBUSYCTRL 0x1001D +/* Sdio Core Rev 12 */ +#define SBSDIO_FUNC1_WAKEUPCTRL 0x1001E +#define SBSDIO_FUNC1_WCTRL_ALPWAIT_MASK 0x1 +#define SBSDIO_FUNC1_WCTRL_ALPWAIT_SHIFT 0 +#define SBSDIO_FUNC1_WCTRL_HTWAIT_MASK 0x2 +#define SBSDIO_FUNC1_WCTRL_HTWAIT_SHIFT 1 +#define SBSDIO_FUNC1_SLEEPCSR 0x1001F +#define SBSDIO_FUNC1_SLEEPCSR_KSO_MASK 0x1 +#define SBSDIO_FUNC1_SLEEPCSR_KSO_SHIFT 0 +#define SBSDIO_FUNC1_SLEEPCSR_KSO_EN 1 +#define SBSDIO_FUNC1_SLEEPCSR_DEVON_MASK 0x2 +#define SBSDIO_FUNC1_SLEEPCSR_DEVON_SHIFT 1 + +#define SBSDIO_AVBITS (SBSDIO_HT_AVAIL | SBSDIO_ALP_AVAIL) +#define SBSDIO_ALPAV(regval) ((regval) & SBSDIO_AVBITS) +#define SBSDIO_HTAV(regval) (((regval) & SBSDIO_AVBITS) == SBSDIO_AVBITS) +#define SBSDIO_ALPONLY(regval) (SBSDIO_ALPAV(regval) && !SBSDIO_HTAV(regval)) +#define SBSDIO_CLKAV(regval, alponly) \ + (SBSDIO_ALPAV(regval) && (alponly ? 1 : SBSDIO_HTAV(regval))) + +#define SBSDIO_FUNC1_MISC_REG_START 0x10000 /* f1 misc register start */ +#define SBSDIO_FUNC1_MISC_REG_LIMIT 0x1001F /* f1 misc register end */ + +/* function 1 OCP space */ + +/* sb offset addr is <= 15 bits, 32k */ +#define SBSDIO_SB_OFT_ADDR_MASK 0x07FFF +#define SBSDIO_SB_OFT_ADDR_LIMIT 0x08000 +/* with b15, maps to 32-bit SB access */ +#define SBSDIO_SB_ACCESS_2_4B_FLAG 0x08000 + +/* valid bits in SBSDIO_FUNC1_SBADDRxxx regs */ + +#define SBSDIO_SBADDRLOW_MASK 0x80 /* Valid bits in SBADDRLOW */ +#define SBSDIO_SBADDRMID_MASK 0xff /* Valid bits in SBADDRMID */ +#define SBSDIO_SBADDRHIGH_MASK 0xffU /* Valid bits in SBADDRHIGH */ +/* Address bits from SBADDR regs */ +#define SBSDIO_SBWINDOW_MASK 0xffff8000 + +/* Packet alignment for most efficient SDIO (can change based on platform) */ +#define BRCMF_SDALIGN (1 << 6) + +/* watchdog polling interval in ms */ +#define BRCMF_WD_POLL_MS 10 + +#endif /* _BRCM_SDH_H_ */ diff --git a/drivers/wireless/ieee80211/chip_constants.h b/drivers/wireless/ieee80211/chip_constants.h deleted file mode 100644 index b3f9f94c48..0000000000 --- a/drivers/wireless/ieee80211/chip_constants.h +++ /dev/null @@ -1,421 +0,0 @@ -/* - * Copyright (c) 2015 Broadcom - * 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 of Broadcom nor the names of other contributors to this - * software may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * 4. This software may not be used as a standalone product, and may only be used as - * incorporated in your product or device that incorporates Broadcom wireless connectivity - * products and solely for the purpose of enabling the functionalities of such Broadcom products. - * - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND - * ANY WARRANTIES OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED - * WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT, ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER 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 INCLUDED_CHIP_CONSTANTS_H_ -#define INCLUDED_CHIP_CONSTANTS_H_ - -// #include "wwd_wlioctl.h" - -#ifdef __cplusplus -extern "C" { -#endif - -/****************************************************** - * Chip Constants - ******************************************************/ - -#define BCM_43362_CHIP_ID 43362 - -/****************************************************** - * Architecture Constants - ******************************************************/ - -/* General chip stats */ -#define CHIP_RAM_SIZE 0x3C000 - -/* Backplane architecture */ -#define CHIPCOMMON_BASE_ADDRESS 0x18000000 /* Chipcommon core register region */ -#define DOT11MAC_BASE_ADDRESS 0x18001000 /* dot11mac core register region */ -#define SDIO_BASE_ADDRESS 0x18002000 /* SDIOD Device core register region */ -#define WLAN_ARMCM3_BASE_ADDRESS 0x18003000 /* ARMCM3 core register region */ -#define SOCSRAM_BASE_ADDRESS 0x18004000 /* SOCSRAM core register region */ -#define BACKPLANE_ADDRESS_MASK 0x7FFF - -#define CHIP_STA_INTERFACE 0 -#define CHIP_AP_INTERFACE 1 -#define CHIP_P2P_INTERFACE 2 - -/* Maximum value of bus data credit difference */ -#define CHIP_MAX_BUS_DATA_CREDIT_DIFF 7 - -/* Chipcommon registers */ -#define CHIPCOMMON_GPIO_CONTROL ((uint32_t) (CHIPCOMMON_BASE_ADDRESS + 0x6C) ) - -/****************************************************** - * SDIO Constants - ******************************************************/ -/* CurrentSdiodProgGuide r23 */ - -/* Base registers */ -#define SDIO_CORE ((uint32_t) (SDIO_BASE_ADDRESS + 0x00) ) -#define SDIO_INT_STATUS ((uint32_t) (SDIO_BASE_ADDRESS + 0x20) ) -#define SDIO_TO_SB_MAILBOX ((uint32_t) (SDIO_BASE_ADDRESS + 0x40) ) -#define SDIO_TO_SB_MAILBOX_DATA ((uint32_t) (SDIO_BASE_ADDRESS + 0x48) ) -#define SDIO_TO_HOST_MAILBOX_DATA ((uint32_t) (SDIO_BASE_ADDRESS + 0x4C) ) -#define SDIO_TO_SB_MAIL_BOX ((uint32_t) (SDIO_BASE_ADDRESS + 0x40) ) -#define SDIO_INT_HOST_MASK ((uint32_t) (SDIO_BASE_ADDRESS + 0x24) ) -#define SDIO_FUNCTION_INT_MASK ((uint32_t) (SDIO_BASE_ADDRESS + 0x34) ) - -/* SDIO Function 0 (SDIO Bus) register addresses */ - -/* SDIO Device CCCR offsets */ -/* TODO: What does CIS/CCCR stand for? */ -/* CCCR accesses do not require backpane clock */ -#define SDIOD_CCCR_REV ( (uint32_t) 0x00 ) /* CCCR/SDIO Revision */ -#define SDIOD_CCCR_SDREV ( (uint32_t) 0x01 ) /* SD Revision */ -#define SDIOD_CCCR_IOEN ( (uint32_t) 0x02 ) /* I/O Enable */ -#define SDIOD_CCCR_IORDY ( (uint32_t) 0x03 ) /* I/O Ready */ -#define SDIOD_CCCR_INTEN ( (uint32_t) 0x04 ) /* Interrupt Enable */ -#define SDIOD_CCCR_INTPEND ( (uint32_t) 0x05 ) /* Interrupt Pending */ -#define SDIOD_CCCR_IOABORT ( (uint32_t) 0x06 ) /* I/O Abort */ -#define SDIOD_CCCR_BICTRL ( (uint32_t) 0x07 ) /* Bus Interface control */ -#define SDIOD_CCCR_CAPABLITIES ( (uint32_t) 0x08 ) /* Card Capabilities */ -#define SDIOD_CCCR_CISPTR_0 ( (uint32_t) 0x09 ) /* Common CIS Base Address Pointer Register 0 (LSB) */ -#define SDIOD_CCCR_CISPTR_1 ( (uint32_t) 0x0A ) /* Common CIS Base Address Pointer Register 1 */ -#define SDIOD_CCCR_CISPTR_2 ( (uint32_t) 0x0B ) /* Common CIS Base Address Pointer Register 2 (MSB - only bit 1 valid)*/ -#define SDIOD_CCCR_BUSSUSP ( (uint32_t) 0x0C ) /* */ -#define SDIOD_CCCR_FUNCSEL ( (uint32_t) 0x0D ) /* */ -#define SDIOD_CCCR_EXECFLAGS ( (uint32_t) 0x0E ) /* */ -#define SDIOD_CCCR_RDYFLAGS ( (uint32_t) 0x0F ) /* */ -#define SDIOD_CCCR_BLKSIZE_0 ( (uint32_t) 0x10 ) /* Function 0 (Bus) SDIO Block Size Register 0 (LSB) */ -#define SDIOD_CCCR_BLKSIZE_1 ( (uint32_t) 0x11 ) /* Function 0 (Bus) SDIO Block Size Register 1 (MSB) */ -#define SDIOD_CCCR_POWER_CONTROL ( (uint32_t) 0x12 ) /* Power Control */ -#define SDIOD_CCCR_SPEED_CONTROL ( (uint32_t) 0x13 ) /* Bus Speed Select (control device entry into high-speed clocking mode) */ -#define SDIOD_CCCR_UHS_I ( (uint32_t) 0x14 ) /* UHS-I Support */ -#define SDIOD_CCCR_DRIVE ( (uint32_t) 0x15 ) /* Drive Strength */ -#define SDIOD_CCCR_INTEXT ( (uint32_t) 0x16 ) /* Interrupt Extension */ -#define SDIOD_SEP_INT_CTL ( (uint32_t) 0xF2 ) /* Separate Interrupt Control*/ -#define SDIOD_CCCR_F1INFO ( (uint32_t) 0x100 ) /* Function 1 (Backplane) Info */ -#define SDIOD_CCCR_F1HP ( (uint32_t) 0x102 ) /* Function 1 (Backplane) High Power */ -#define SDIOD_CCCR_F1CISPTR_0 ( (uint32_t) 0x109 ) /* Function 1 (Backplane) CIS Base Address Pointer Register 0 (LSB) */ -#define SDIOD_CCCR_F1CISPTR_1 ( (uint32_t) 0x10A ) /* Function 1 (Backplane) CIS Base Address Pointer Register 1 */ -#define SDIOD_CCCR_F1CISPTR_2 ( (uint32_t) 0x10B ) /* Function 1 (Backplane) CIS Base Address Pointer Register 2 (MSB - only bit 1 valid) */ -#define SDIOD_CCCR_F1BLKSIZE_0 ( (uint32_t) 0x110 ) /* Function 1 (Backplane) SDIO Block Size Register 0 (LSB) */ -#define SDIOD_CCCR_F1BLKSIZE_1 ( (uint32_t) 0x111 ) /* Function 1 (Backplane) SDIO Block Size Register 1 (MSB) */ -#define SDIOD_CCCR_F2INFO ( (uint32_t) 0x200 ) /* Function 2 (WLAN Data FIFO) Info */ -#define SDIOD_CCCR_F2HP ( (uint32_t) 0x202 ) /* Function 2 (WLAN Data FIFO) High Power */ -#define SDIOD_CCCR_F2CISPTR_0 ( (uint32_t) 0x209 ) /* Function 2 (WLAN Data FIFO) CIS Base Address Pointer Register 0 (LSB) */ -#define SDIOD_CCCR_F2CISPTR_1 ( (uint32_t) 0x20A ) /* Function 2 (WLAN Data FIFO) CIS Base Address Pointer Register 1 */ -#define SDIOD_CCCR_F2CISPTR_2 ( (uint32_t) 0x20B ) /* Function 2 (WLAN Data FIFO) CIS Base Address Pointer Register 2 (MSB - only bit 1 valid) */ -#define SDIOD_CCCR_F2BLKSIZE_0 ( (uint32_t) 0x210 ) /* Function 2 (WLAN Data FIFO) SDIO Block Size Register 0 (LSB) */ -#define SDIOD_CCCR_F2BLKSIZE_1 ( (uint32_t) 0x211 ) /* Function 2 (WLAN Data FIFO) SDIO Block Size Register 1 (MSB) */ -#define SDIOD_CCCR_F3INFO ( (uint32_t) 0x300 ) /* Function 3 (Bluetooth Data FIFO) Info */ -#define SDIOD_CCCR_F3HP ( (uint32_t) 0x302 ) /* Function 3 (Bluetooth Data FIFO) High Power */ -#define SDIOD_CCCR_F3CISPTR_0 ( (uint32_t) 0x309 ) /* Function 3 (Bluetooth Data FIFO) CIS Base Address Pointer Register 0 (LSB) */ -#define SDIOD_CCCR_F3CISPTR_1 ( (uint32_t) 0x30A ) /* Function 3 (Bluetooth Data FIFO) CIS Base Address Pointer Register 1 */ -#define SDIOD_CCCR_F3CISPTR_2 ( (uint32_t) 0x30B ) /* Function 3 (Bluetooth Data FIFO) CIS Base Address Pointer Register 2 (MSB - only bit 1 valid) */ -#define SDIOD_CCCR_F3BLKSIZE_0 ( (uint32_t) 0x310 ) /* Function 3 (Bluetooth Data FIFO) SDIO Block Size Register 0 (LSB) */ -#define SDIOD_CCCR_F3BLKSIZE_1 ( (uint32_t) 0x311 ) /* Function 3 (Bluetooth Data FIFO) SDIO Block Size Register 1 (MSB) */ - - -/* SDIO Function 1 (Backplane) register addresses */ -/* Addresses 0x00000000 - 0x0000FFFF are directly access the backplane - * throught the backplane window. Addresses above 0x0000FFFF are - * registers relating to backplane access, and do not require a backpane - * clock to access them - */ -#define SDIO_GPIO_SELECT ( (uint32_t) 0x10005 ) -#define SDIO_GPIO_OUTPUT ( (uint32_t) 0x10006 ) -#define SDIO_GPIO_ENABLE ( (uint32_t) 0x10007 ) -#define SDIO_FUNCTION2_WATERMARK ( (uint32_t) 0x10008 ) -#define SDIO_DEVICE_CONTROL ( (uint32_t) 0x10009 ) -#define SDIO_BACKPLANE_ADDRESS_LOW ( (uint32_t) 0x1000A ) -#define SDIO_BACKPLANE_ADDRESS_MID ( (uint32_t) 0x1000B ) -#define SDIO_BACKPLANE_ADDRESS_HIGH ( (uint32_t) 0x1000C ) -#define SDIO_FRAME_CONTROL ( (uint32_t) 0x1000D ) -#define SDIO_CHIP_CLOCK_CSR ( (uint32_t) 0x1000E ) -#define SDIO_PULL_UP ( (uint32_t) 0x1000F ) -#define SDIO_READ_FRAME_BC_LOW ( (uint32_t) 0x1001B ) -#define SDIO_READ_FRAME_BC_HIGH ( (uint32_t) 0x1001C ) - -#define I_HMB_SW_MASK ( (uint32_t) 0x000000F0 ) -#define I_HMB_FRAME_IND ( 1<<6 ) -#define FRAME_AVAILABLE_MASK I_HMB_SW_MASK - - -/****************************************************** - * SPI Constants - ******************************************************/ -/* GSPI v1 */ -#define SPI_FRAME_CONTROL ( (uint32_t) 0x1000D ) - -/* Register addresses */ -#define SPI_BUS_CONTROL ( (uint32_t) 0x0000 ) -#define SPI_RESPONSE_DELAY ( (uint32_t) 0x0001 ) -#define SPI_STATUS_ENABLE ( (uint32_t) 0x0002 ) -#define SPI_RESET_BP ( (uint32_t) 0x0003 ) /* (corerev >= 1) */ -#define SPI_INTERRUPT_REGISTER ( (uint32_t) 0x0004 ) /* 16 bits - Interrupt status */ -#define SPI_INTERRUPT_ENABLE_REGISTER ( (uint32_t) 0x0006 ) /* 16 bits - Interrupt mask */ -#define SPI_STATUS_REGISTER ( (uint32_t) 0x0008 ) /* 32 bits */ -#define SPI_FUNCTION1_INFO ( (uint32_t) 0x000C ) /* 16 bits */ -#define SPI_FUNCTION2_INFO ( (uint32_t) 0x000E ) /* 16 bits */ -#define SPI_FUNCTION3_INFO ( (uint32_t) 0x0010 ) /* 16 bits */ -#define SPI_READ_TEST_REGISTER ( (uint32_t) 0x0014 ) /* 32 bits */ -#define SPI_RESP_DELAY_F0 ( (uint32_t) 0x001c ) /* 8 bits (corerev >= 3) */ -#define SPI_RESP_DELAY_F1 ( (uint32_t) 0x001d ) /* 8 bits (corerev >= 3) */ -#define SPI_RESP_DELAY_F2 ( (uint32_t) 0x001e ) /* 8 bits (corerev >= 3) */ -#define SPI_RESP_DELAY_F3 ( (uint32_t) 0x001f ) /* 8 bits (corerev >= 3) */ - -/****************************************************** - * Bit Masks - ******************************************************/ - -/* SDIOD_CCCR_REV Bits */ -#define SDIO_REV_SDIOID_MASK ( (uint32_t) 0xF0 ) /* SDIO spec revision number */ -#define SDIO_REV_CCCRID_MASK ( (uint32_t) 0x0F ) /* CCCR format version number */ - -/* SDIOD_CCCR_SDREV Bits */ -#define SD_REV_PHY_MASK ( (uint32_t) 0x0F ) /* SD format version number */ - -/* SDIOD_CCCR_IOEN Bits */ -#define SDIO_FUNC_ENABLE_1 ( (uint32_t) 0x02 ) /* function 1 I/O enable */ -#define SDIO_FUNC_ENABLE_2 ( (uint32_t) 0x04 ) /* function 2 I/O enable */ -#define SDIO_FUNC_ENABLE_3 ( (uint32_t) 0x08 ) /* function 3 I/O enable */ - -/* SDIOD_CCCR_IORDY Bits */ -#define SDIO_FUNC_READY_1 ( (uint32_t) 0x02 ) /* function 1 I/O ready */ -#define SDIO_FUNC_READY_2 ( (uint32_t) 0x04 ) /* function 2 I/O ready */ -#define SDIO_FUNC_READY_3 ( (uint32_t) 0x08 ) /* function 3 I/O ready */ - -/* SDIOD_CCCR_INTEN Bits */ -#define INTR_CTL_MASTER_EN ( (uint32_t) 0x01 ) /* interrupt enable master */ -#define INTR_CTL_FUNC1_EN ( (uint32_t) 0x02 ) /* interrupt enable for function 1 */ -#define INTR_CTL_FUNC2_EN ( (uint32_t) 0x04 ) /* interrupt enable for function 2 */ - -/* SDIOD_SEP_INT_CTL Bits */ -#define SEP_INTR_CTL_MASK ( (uint32_t) 0x01 ) /* out-of-band interrupt mask */ -#define SEP_INTR_CTL_EN ( (uint32_t) 0x02 ) /* out-of-band interrupt output enable */ -#define SEP_INTR_CTL_POL ( (uint32_t) 0x04 ) /* out-of-band interrupt polarity */ - -/* SDIOD_CCCR_INTPEND Bits */ -#define INTR_STATUS_FUNC1 ( (uint32_t) 0x02 ) /* interrupt pending for function 1 */ -#define INTR_STATUS_FUNC2 ( (uint32_t) 0x04 ) /* interrupt pending for function 2 */ -#define INTR_STATUS_FUNC3 ( (uint32_t) 0x08 ) /* interrupt pending for function 3 */ - -/* SDIOD_CCCR_IOABORT Bits */ -#define IO_ABORT_RESET_ALL ( (uint32_t) 0x08 ) /* I/O card reset */ -#define IO_ABORT_FUNC_MASK ( (uint32_t) 0x07 ) /* abort selction: function x */ - -/* SDIOD_CCCR_BICTRL Bits */ -#define BUS_CARD_DETECT_DIS ( (uint32_t) 0x80 ) /* Card Detect disable */ -#define BUS_SPI_CONT_INTR_CAP ( (uint32_t) 0x40 ) /* support continuous SPI interrupt */ -#define BUS_SPI_CONT_INTR_EN ( (uint32_t) 0x20 ) /* continuous SPI interrupt enable */ -#define BUS_SD_DATA_WIDTH_MASK ( (uint32_t) 0x03 ) /* bus width mask */ -#define BUS_SD_DATA_WIDTH_4BIT ( (uint32_t) 0x02 ) /* bus width 4-bit mode */ -#define BUS_SD_DATA_WIDTH_1BIT ( (uint32_t) 0x00 ) /* bus width 1-bit mode */ - -/* SDIOD_CCCR_CAPABLITIES Bits */ -#define SDIO_CAP_4BLS ( (uint32_t) 0x80 ) /* 4-bit support for low speed card */ -#define SDIO_CAP_LSC ( (uint32_t) 0x40 ) /* low speed card */ -#define SDIO_CAP_E4MI ( (uint32_t) 0x20 ) /* enable interrupt between block of data in 4-bit mode */ -#define SDIO_CAP_S4MI ( (uint32_t) 0x10 ) /* support interrupt between block of data in 4-bit mode */ -#define SDIO_CAP_SBS ( (uint32_t) 0x08 ) /* support suspend/resume */ -#define SDIO_CAP_SRW ( (uint32_t) 0x04 ) /* support read wait */ -#define SDIO_CAP_SMB ( (uint32_t) 0x02 ) /* support multi-block transfer */ -#define SDIO_CAP_SDC ( (uint32_t) 0x01 ) /* Support Direct commands during multi-byte transfer */ - -/* SDIOD_CCCR_POWER_CONTROL Bits */ -#define SDIO_POWER_SMPC ( (uint32_t) 0x01 ) /* supports master power control (RO) */ -#define SDIO_POWER_EMPC ( (uint32_t) 0x02 ) /* enable master power control (allow > 200mA) (RW) */ - -/* SDIOD_CCCR_SPEED_CONTROL Bits */ -#define SDIO_SPEED_SHS ( (uint32_t) 0x01 ) /* supports high-speed [clocking] mode (RO) */ -#define SDIO_SPEED_EHS ( (uint32_t) 0x02 ) /* enable high-speed [clocking] mode (RW) */ - - - -/* GSPI */ -#define SPI_READ_TEST_REGISTER_VALUE ( (uint32_t) 0xFEEDBEAD ) -#define SPI_READ_TEST_REG_LSB ( ( ( SPI_READ_TEST_REGISTER_VALUE ) ) & 0xff ) -#define SPI_READ_TEST_REG_LSB_SFT1 ( ( ( SPI_READ_TEST_REGISTER_VALUE << 1 ) ) & 0xff ) -#define SPI_READ_TEST_REG_LSB_SFT2 ( ( ( SPI_READ_TEST_REGISTER_VALUE << 1 ) + 1 ) & 0xff ) -#define SPI_READ_TEST_REG_LSB_SFT3 ( ( ( SPI_READ_TEST_REGISTER_VALUE +1 ) << 1 ) & 0xff ) - - -/* SPI_BUS_CONTROL Bits */ -#define WORD_LENGTH_32 ( (uint32_t) 0x01 ) /* 0/1 16/32 bit word length */ -#define ENDIAN_BIG ( (uint32_t) 0x02 ) /* 0/1 Little/Big Endian */ -#define CLOCK_PHASE ( (uint32_t) 0x04 ) /* 0/1 clock phase delay */ -#define CLOCK_POLARITY ( (uint32_t) 0x08 ) /* 0/1 Idle state clock polarity is low/high */ -#define HIGH_SPEED_MODE ( (uint32_t) 0x10 ) /* 1/0 High Speed mode / Normal mode */ -#define INTR_POLARITY_HIGH ( (uint32_t) 0x20 ) /* 1/0 Interrupt active polarity is high/low */ -#define WAKE_UP ( (uint32_t) 0x80 ) /* 0/1 Wake-up command from Host to WLAN */ - -/* SPI_RESPONSE_DELAY Bit mask */ -#define RESPONSE_DELAY_MASK 0xFF /* Configurable rd response delay in multiples of 8 bits */ - -/* SPI_STATUS_ENABLE Bits */ -#define STATUS_ENABLE ( (uint32_t) 0x01 ) /* 1/0 Status sent/not sent to host after read/write */ -#define INTR_WITH_STATUS ( (uint32_t) 0x02 ) /* 0/1 Do-not / do-interrupt if status is sent */ -#define RESP_DELAY_ALL ( (uint32_t) 0x04 ) /* Applicability of resp delay to F1 or all func's read */ -#define DWORD_PKT_LEN_EN ( (uint32_t) 0x08 ) /* Packet len denoted in dwords instead of bytes */ -#define CMD_ERR_CHK_EN ( (uint32_t) 0x20 ) /* Command error check enable */ -#define DATA_ERR_CHK_EN ( (uint32_t) 0x40 ) /* Data error check enable */ - - - -/* SPI_RESET_BP Bits*/ -#define RESET_ON_WLAN_BP_RESET ( (uint32_t) 0x04 ) /* enable reset for WLAN backplane */ -#define RESET_ON_BT_BP_RESET ( (uint32_t) 0x08 ) /* enable reset for BT backplane */ -#define RESET_SPI ( (uint32_t) 0x80 ) /* reset the above enabled logic */ - - - -/* SPI_INTERRUPT_REGISTER and SPI_INTERRUPT_ENABLE_REGISTER Bits */ -#define DATA_UNAVAILABLE ( (uint32_t) 0x0001 ) /* Requested data not available; Clear by writing a "1" */ -#define F2_F3_FIFO_RD_UNDERFLOW ( (uint32_t) 0x0002 ) -#define F2_F3_FIFO_WR_OVERFLOW ( (uint32_t) 0x0004 ) -#define COMMAND_ERROR ( (uint32_t) 0x0008 ) /* Cleared by writing 1 */ -#define DATA_ERROR ( (uint32_t) 0x0010 ) /* Cleared by writing 1 */ -#define F2_PACKET_AVAILABLE ( (uint32_t) 0x0020 ) -#define F3_PACKET_AVAILABLE ( (uint32_t) 0x0040 ) -#define F1_OVERFLOW ( (uint32_t) 0x0080 ) /* Due to last write. Bkplane has pending write requests */ -#define MISC_INTR0 ( (uint32_t) 0x0100 ) -#define MISC_INTR1 ( (uint32_t) 0x0200 ) -#define MISC_INTR2 ( (uint32_t) 0x0400 ) -#define MISC_INTR3 ( (uint32_t) 0x0800 ) -#define MISC_INTR4 ( (uint32_t) 0x1000 ) -#define F1_INTR ( (uint32_t) 0x2000 ) -#define F2_INTR ( (uint32_t) 0x4000 ) -#define F3_INTR ( (uint32_t) 0x8000 ) - - - - -/* SPI_STATUS_REGISTER Bits */ -#define STATUS_DATA_NOT_AVAILABLE ( (uint32_t) 0x00000001 ) -#define STATUS_UNDERFLOW ( (uint32_t) 0x00000002 ) -#define STATUS_OVERFLOW ( (uint32_t) 0x00000004 ) -#define STATUS_F2_INTR ( (uint32_t) 0x00000008 ) -#define STATUS_F3_INTR ( (uint32_t) 0x00000010 ) -#define STATUS_F2_RX_READY ( (uint32_t) 0x00000020 ) -#define STATUS_F3_RX_READY ( (uint32_t) 0x00000040 ) -#define STATUS_HOST_CMD_DATA_ERR ( (uint32_t) 0x00000080 ) -#define STATUS_F2_PKT_AVAILABLE ( (uint32_t) 0x00000100 ) -#define STATUS_F2_PKT_LEN_MASK ( (uint32_t) 0x000FFE00 ) -#define STATUS_F2_PKT_LEN_SHIFT ( (uint32_t) 9 ) -#define STATUS_F3_PKT_AVAILABLE ( (uint32_t) 0x00100000 ) -#define STATUS_F3_PKT_LEN_MASK ( (uint32_t) 0xFFE00000 ) -#define STATUS_F3_PKT_LEN_SHIFT ( (uint32_t) 21 ) - - - - - -/* SDIO_CHIP_CLOCK_CSR Bits */ -#define SBSDIO_FORCE_ALP ( (uint32_t) 0x01 ) /* Force ALP request to backplane */ -#define SBSDIO_FORCE_HT ( (uint32_t) 0x02 ) /* Force HT request to backplane */ -#define SBSDIO_FORCE_ILP ( (uint32_t) 0x04 ) /* Force ILP request to backplane */ -#define SBSDIO_ALP_AVAIL_REQ ( (uint32_t) 0x08 ) /* Make ALP ready (power up xtal) */ -#define SBSDIO_HT_AVAIL_REQ ( (uint32_t) 0x10 ) /* Make HT ready (power up PLL) */ -#define SBSDIO_FORCE_HW_CLKREQ_OFF ( (uint32_t) 0x20 ) /* Squelch clock requests from HW */ -#define SBSDIO_ALP_AVAIL ( (uint32_t) 0x40 ) /* Status: ALP is ready */ -#define SBSDIO_HT_AVAIL ( (uint32_t) 0x80 ) /* Status: HT is ready */ -#define SBSDIO_Rev8_HT_AVAIL ( (uint32_t) 0x40 ) -#define SBSDIO_Rev8_ALP_AVAIL ( (uint32_t) 0x80 ) - - -/* SDIO_FRAME_CONTROL Bits */ -#define SFC_RF_TERM ( (uint32_t) (1 << 0) ) /* Read Frame Terminate */ -#define SFC_WF_TERM ( (uint32_t) (1 << 1) ) /* Write Frame Terminate */ -#define SFC_CRC4WOOS ( (uint32_t) (1 << 2) ) /* HW reports CRC error for write out of sync */ -#define SFC_ABORTALL ( (uint32_t) (1 << 3) ) /* Abort cancels all in-progress frames */ - -/* SDIO_TO_SB_MAIL_BOX bits corresponding to intstatus bits */ -#define SMB_NAK ( (uint32_t) (1 << 0) ) /* To SB Mailbox Frame NAK */ -#define SMB_INT_ACK ( (uint32_t) (1 << 1) ) /* To SB Mailbox Host Interrupt ACK */ -#define SMB_USE_OOB ( (uint32_t) (1 << 2) ) /* To SB Mailbox Use OOB Wakeup */ -#define SMB_DEV_INT ( (uint32_t) (1 << 3) ) /* To SB Mailbox Miscellaneous Interrupt */ - - -#define WL_CHANSPEC_BAND_MASK (0xf000) -#define WL_CHANSPEC_BAND_5G (0x1000) -#define WL_CHANSPEC_BAND_2G (0x2000) -#define WL_CHANSPEC_CTL_SB_MASK (0x0300) -#define WL_CHANSPEC_CTL_SB_LOWER (0x0100) -#define WL_CHANSPEC_CTL_SB_UPPER (0x0200) -#define WL_CHANSPEC_CTL_SB_NONE (0x0300) -#define WL_CHANSPEC_BW_MASK (0x0C00) -#define WL_CHANSPEC_BW_10 (0x0400) -#define WL_CHANSPEC_BW_20 (0x0800) -#define WL_CHANSPEC_BW_40 (0x0C00) - - -// /* CIS accesses require backpane clock */ -// -// -// #define CHIP_HAS_BSSID_CNT_IN_ASSOC_PARAMS -// #define CHIP_FIRMWARE_SUPPORTS_PM_LIMIT_IOVAR -// -// struct ether_addr; -// struct wl_join_scan_params; -// -// typedef struct wl_assoc_params -// { -// struct ether_addr bssid; -// #ifdef CHIP_HAS_BSSID_CNT_IN_ASSOC_PARAMS -// uint16_t bssid_cnt; -// #endif /* ifdef CHIP_HAS_BSSID_CNT_IN_ASSOC_PARAMS */ -// uint32_t chanspec_num; -// chanspec_t chanspec_list[1]; -// } wl_assoc_params_t; -// #define WL_ASSOC_PARAMS_FIXED_SIZE (sizeof(wl_assoc_params_t) - sizeof(wl_chanspec_t)) -// typedef wl_assoc_params_t wl_reassoc_params_t; -// #define WL_REASSOC_PARAMS_FIXED_SIZE WL_ASSOC_PARAMS_FIXED_SIZE -// typedef wl_assoc_params_t wl_join_assoc_params_t; -// #define WL_JOIN_ASSOC_PARAMS_FIXED_SIZE WL_ASSOC_PARAMS_FIXED_SIZE -// typedef struct wl_join_params -// { -// wlc_ssid_t ssid; -// struct wl_assoc_params params; -// } wl_join_params_t; -// #define WL_JOIN_PARAMS_FIXED_SIZE (sizeof(wl_join_params_t) - sizeof(wl_chanspec_t)) -// -// /* extended join params */ -// typedef struct wl_extjoin_params -// { -// wlc_ssid_t ssid; /* {0, ""}: wildcard scan */ -// struct wl_join_scan_params scan_params; -// wl_join_assoc_params_t assoc_params; /* optional field, but it must include the fixed portion of the wl_join_assoc_params_t struct when it does present. */ -// } wl_extjoin_params_t; -// #define WL_EXTJOIN_PARAMS_FIXED_SIZE (sizeof(wl_extjoin_params_t) - sizeof(chanspec_t)) -// -// typedef wl_cnt_ver_six_t wiced_counters_t; - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif /* ifndef INCLUDED_CHIP_CONSTANTS_H_ */ diff --git a/drivers/wireless/ieee80211/mmc_sdio.c b/drivers/wireless/ieee80211/mmc_sdio.c index 6085afce89..947c71a956 100644 --- a/drivers/wireless/ieee80211/mmc_sdio.c +++ b/drivers/wireless/ieee80211/mmc_sdio.c @@ -78,7 +78,14 @@ int sdio_io_rw_direct(FAR struct sdio_dev_s *dev, bool write, /* Setup CMD52 argument */ - arg.cmd52.write_data = inb; + if (write) + { + arg.cmd52.write_data = inb; + } + else + { + arg.cmd52.write_data = 0; + } arg.cmd52.register_address = address & 0x1ffff; arg.cmd52.raw_flag = (write && outb); arg.cmd52.function_number = function & 7; @@ -128,18 +135,18 @@ int sdio_io_rw_extended(FAR struct sdio_dev_s *dev, bool write, /* Setup CMD53 argument */ - arg.cmd53.byte_block_count = blocklen; arg.cmd53.register_address = address & 0x1ffff; arg.cmd53.op_code = inc_addr; arg.cmd53.function_number = function & 7; arg.cmd53.rw_flag = write; - if (nblocks <= 1 && blocklen < 512) + if (nblocks == 0 && blocklen < 512) { /* Use byte mode */ - _info("byte mode\n"); + // _info("byte mode\n"); arg.cmd53.block_mode = 0; + arg.cmd53.byte_block_count = blocklen; nblocks = 1; } else @@ -147,6 +154,7 @@ int sdio_io_rw_extended(FAR struct sdio_dev_s *dev, bool write, /* Use block mode */ arg.cmd53.block_mode = 1; + arg.cmd53.byte_block_count = nblocks; } /* Send CMD53 command */ @@ -157,6 +165,7 @@ int sdio_io_rw_extended(FAR struct sdio_dev_s *dev, bool write, if (write) { + // _info("prep write %d %d\n", blocklen, nblocks); sdio_sendcmdpoll(dev, SDIO_ACMD53, (uint32_t)arg.value); ret = SDIO_RECVR5(dev, SDIO_ACMD53, (uint32_t*)&resp); @@ -165,7 +174,7 @@ int sdio_io_rw_extended(FAR struct sdio_dev_s *dev, bool write, } else { - _info("prep read %d\n", blocklen * nblocks); + // _info("prep read %d\n", blocklen * nblocks); SDIO_RECVSETUP(dev, buf, blocklen * nblocks); SDIO_SENDCMD(dev, SDIO_ACMD53, (uint32_t)arg.value); diff --git a/include/nuttx/wireless/ieee80211/bcmf_board.h b/include/nuttx/wireless/ieee80211/bcmf_board.h index 7ae0c21dc2..c4aa396432 100644 --- a/include/nuttx/wireless/ieee80211/bcmf_board.h +++ b/include/nuttx/wireless/ieee80211/bcmf_board.h @@ -102,6 +102,22 @@ void bcmf_board_power(int minor, bool power); void bcmf_board_reset(int minor, bool reset); +/************************************************************************************ + * Function: bcmf_board_setup_oob_irq + * + * Description: + * Board specific function called from Broadcom FullMAC driver + * that must be implemented to use WLAN chip interrupt signal + * + * Parameters: + * minor - zero based minor device number which is unique + * for each wlan device. + * func - WLAN chip callback function that must be called on gpio event + * arg - WLAN chip internal structure that must be passed to callback + ************************************************************************************/ + +void bcmf_board_setup_oob_irq(int minor, xcpt_t func, void *arg); + #undef EXTERN #ifdef __cplusplus } diff --git a/include/nuttx/wireless/ieee80211/mmc_sdio.h b/include/nuttx/wireless/ieee80211/mmc_sdio.h index 39e7154f9e..d460f0ad35 100644 --- a/include/nuttx/wireless/ieee80211/mmc_sdio.h +++ b/include/nuttx/wireless/ieee80211/mmc_sdio.h @@ -12,6 +12,8 @@ int sdio_set_blocksize(FAR struct sdio_dev_s *dev, uint8_t function, int sdio_enable_function(FAR struct sdio_dev_s *dev, uint8_t function); +int sdio_enable_interrupt(FAR struct sdio_dev_s *dev, uint8_t function); + int sdio_sendcmdpoll(FAR struct sdio_dev_s *dev, uint32_t cmd, uint32_t arg); int sdio_io_rw_direct(FAR struct sdio_dev_s *dev, bool write, -- GitLab From 72bffeddccc3c8dbf8fe11edd2e49474f32d3ead Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 5 Apr 2017 14:31:44 -0600 Subject: [PATCH 352/990] 6loWPAN: Fixes another HC06 indexing problem. --- net/sixlowpan/sixlowpan_hc06.c | 17 ++++++++++------- 1 file changed, 10 insertions(+), 7 deletions(-) diff --git a/net/sixlowpan/sixlowpan_hc06.c b/net/sixlowpan/sixlowpan_hc06.c index 0b9d5153b0..9ad3101d1c 100644 --- a/net/sixlowpan/sixlowpan_hc06.c +++ b/net/sixlowpan/sixlowpan_hc06.c @@ -819,7 +819,7 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, } /**************************************************************************** - * Name: sixlowpan_hc06_initialize + * Name: sixlowpan_uncompresshdr_hc06 * * Description: * Uncompress HC06 (i.e., IPHC and LOWPAN_UDP) headers and put them in @@ -849,26 +849,29 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, FAR uint8_t *payptr) { FAR struct ipv6_hdr_s *ipv6 = IPv6BUF(ieee); - FAR uint8_t *iphc = payptr + g_frame_hdrlen; + FAR uint8_t *iphc; uint8_t iphc0; uint8_t iphc1; uint8_t tmp; - /* At least two byte will be used for the encoding */ - - g_hc06ptr = payptr + g_frame_hdrlen + 2; + /* payptr points to IPHC. At least two byte will be used for the encoding. */ + iphc = payptr; iphc0 = iphc[0]; iphc1 = iphc[1]; - ninfo("payptr=%p g_frame_hdrlen=%u iphc[%p]=%02x:%02x:%02x g_hc06ptr=%p\n", + /* g_hc96ptr points to just after the 2-byte minimum IPHC */ + + g_hc06ptr = payptr + 2; + + ninfo("payptr=%p g_frame_hdrlen=%u iphc=%02x:%02x:%02x g_hc06ptr=%p\n", payptr, g_frame_hdrlen, iphc, iphc[0], iphc[1], iphc[2], g_hc06ptr); /* Another if the CID flag is set */ if (iphc1 & SIXLOWPAN_IPHC_CID) { - ninfo("IPHC: CID flag set. Increase header by one\n"); + ninfo("CID flag set. Increase header by one\n"); g_hc06ptr++; } -- GitLab From d0aa22fb8086986f4975d739d699caba21fd10d8 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 5 Apr 2017 17:26:12 -0600 Subject: [PATCH 353/990] 6loWPAN: Costmetic changes. --- include/nuttx/net/sixlowpan.h | 53 ++++++++++++++------------- net/sixlowpan/sixlowpan_hc06.c | 66 +++++++++++++++++----------------- 2 files changed, 61 insertions(+), 58 deletions(-) diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index 5f73d9cdb1..0211d17ce6 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -94,37 +94,40 @@ /* IPHC encoding * - * Values of fields within the IPHC encoding first byte (C stands for - * compressed and I for inline) + * Values of fields within the IPHC encoding first byte + * (Using MS-to-LS bit numbering of the draft RFC) */ - -#define SIXLOWPAN_IPHC_FL_C 0x10 -#define SIXLOWPAN_IPHC_TC_C 0x08 -#define SIXLOWPAN_IPHC_NH_C 0x04 -#define SIXLOWPAN_IPHC_TTL_1 0x01 -#define SIXLOWPAN_IPHC_TTL_64 0x02 -#define SIXLOWPAN_IPHC_TTL_255 0x03 -#define SIXLOWPAN_IPHC_TTL_I 0x00 + /* Bits 0-2: 011 */ +#define SIXLOWPAN_IPHC_TC_MASK 0x18 /* Bits 3-4: Traffic Class, Flow Label */ +# define SIXLOWPAN_IPHC_TC_00 0x00 /* ECN+DSCP+4-bit Pad+Flow Label (4 bytes) */ +# define SIXLOWPAN_IPHC_TC_01 0x08 /* ECN+2-bit Pad+ Flow Label (3 bytes), DSCP is elided. */ +# define SIXLOWPAN_IPHC_TC_10 0x10 /* ECN+DSCP (1 byte), Flow Label is elided */ +# define SIXLOWPAN_IPHC_TC_11 0x11 /* Traffic Class and Flow Label are elided */ +#define SIXLOWPAN_IPHC_NH 0x04 /* Bit 5: Next Header Compressed */ +#define SIXLOWPAN_IPHC_HLIM_MASK 0x03 /* Bits 6-7: Hop Limit */ +# define SIXLOWPAN_IPHC_HLIM_INLINE 0x00 /* Carried in-line */ +# define SIXLOWPAN_IPHC_HLIM_1 0x01 /* Compressed hop limit of 1 */ +# define SIXLOWPAN_IPHC_HLIM_64 0x02 /* Compressed hop limit of 64 */ +# define SIXLOWPAN_IPHC_HLIM_255 0x03 /* Compressed hop limit of 255 */ /* Values of fields within the IPHC encoding second byte */ -#define SIXLOWPAN_IPHC_CID 0x80 - -#define SIXLOWPAN_IPHC_SAC 0x40 -#define SIXLOWPAN_IPHC_SAM_00 0x00 -#define SIXLOWPAN_IPHC_SAM_01 0x10 -#define SIXLOWPAN_IPHC_SAM_10 0x20 -#define SIXLOWPAN_IPHC_SAM_11 0x30 +#define SIXLOWPAN_IPHC_CID 0x80 /* Bit 8: Context identifier extension */ +#define SIXLOWPAN_IPHC_SAC 0x40 /* Bit 9: Source address compression */ +#define SIXLOWPAN_IPHC_SAM_MASK 0x30 /* Bits 10-11: Source address mode */ +# define SIXLOWPAN_IPHC_SAM_128 0x00 /* 128-bits */ +# define SIXLOWPAN_IPHC_SAM_64 0x10 /* 64-bits */ +# define SIXLOWPAN_IPHC_SAM_16 0x20 /* 16-bits */ +# define SIXLOWPAN_IPHC_SAM_0 0x30 /* 0-bits */ +#define SIXLOWPAN_IPHC_M 0x08 /* Bit 12: Multicast compression */ +#define SIXLOWPAN_IPHC_DAC 0x04 /* Bit 13: Destination address compression */ +#define SIXLOWPAN_IPHC_DAM_MASK 0x03 /* Bits 14-15: Destination address mode */ +# define SIXLOWPAN_IPHC_DAM_128 0x00 /* 128-bits */ +# define SIXLOWPAN_IPHC_DAM_64 0x01 /* 64-bits */ +# define SIXLOWPAN_IPHC_DAM_16 0x02 /* 16-bits */ +# define SIXLOWPAN_IPHC_DAM_0 0x03 /* 0-bits */ #define SIXLOWPAN_IPHC_SAM_BIT 4 - -#define SIXLOWPAN_IPHC_M 0x08 -#define SIXLOWPAN_IPHC_DAC 0x04 -#define SIXLOWPAN_IPHC_DAM_00 0x00 -#define SIXLOWPAN_IPHC_DAM_01 0x01 -#define SIXLOWPAN_IPHC_DAM_10 0x02 -#define SIXLOWPAN_IPHC_DAM_11 0x03 - #define SIXLOWPAN_IPHC_DAM_BIT 0 /* Link local context number */ diff --git a/net/sixlowpan/sixlowpan_hc06.c b/net/sixlowpan/sixlowpan_hc06.c index 9ad3101d1c..2c345f7818 100644 --- a/net/sixlowpan/sixlowpan_hc06.c +++ b/net/sixlowpan/sixlowpan_hc06.c @@ -508,12 +508,12 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, { /* Flow label can be compressed */ - iphc0 |= SIXLOWPAN_IPHC_FL_C; + iphc0 |= SIXLOWPAN_IPHC_TC_10; if (((ipv6->vtc & 0x0f) == 0) && ((ipv6->tcf & 0xf0) == 0)) { /* Compress (elide) all */ - iphc0 |= SIXLOWPAN_IPHC_TC_C; + iphc0 |= SIXLOWPAN_IPHC_TC_01; } else { @@ -531,7 +531,7 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, { /* Compress only traffic class */ - iphc0 |= SIXLOWPAN_IPHC_TC_C; + iphc0 |= SIXLOWPAN_IPHC_TC_01; *g_hc06ptr = (tmp & 0xc0) | (ipv6->tcf & 0x0f); memcpy(g_hc06ptr + 1, &ipv6->flow, 2); g_hc06ptr += 3; @@ -556,11 +556,11 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, #if CONFIG_NET_UDP || UIP_CONF_ROUTER if (ipv6->proto == IP_PROTO_UDP) { - iphc0 |= SIXLOWPAN_IPHC_NH_C; + iphc0 |= SIXLOWPAN_IPHC_NH; } #endif /* CONFIG_NET_UDP */ - if ((iphc0 & SIXLOWPAN_IPHC_NH_C) == 0) + if ((iphc0 & SIXLOWPAN_IPHC_NH) == 0) { *g_hc06ptr = ipv6->proto; g_hc06ptr += 1; @@ -577,15 +577,15 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, switch (ipv6->ttl) { case 1: - iphc0 |= SIXLOWPAN_IPHC_TTL_1; + iphc0 |= SIXLOWPAN_IPHC_HLIM_1; break; case 64: - iphc0 |= SIXLOWPAN_IPHC_TTL_64; + iphc0 |= SIXLOWPAN_IPHC_HLIM_64; break; case 255: - iphc0 |= SIXLOWPAN_IPHC_TTL_255; + iphc0 |= SIXLOWPAN_IPHC_HLIM_255; break; default: @@ -601,7 +601,7 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, ninfo("Compressing unspecified. Setting SAC\n"); iphc1 |= SIXLOWPAN_IPHC_SAC; - iphc1 |= SIXLOWPAN_IPHC_SAM_00; + iphc1 |= SIXLOWPAN_IPHC_SAM_128; } else if ((addrcontext = find_addrcontext_byprefix(ipv6->srcipaddr)) != NULL) { @@ -613,7 +613,7 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, iphc1 |= SIXLOWPAN_IPHC_CID | SIXLOWPAN_IPHC_SAC; iphc[2] |= addrcontext->number << 4; - /* Compession compare with this nodes address (source) */ + /* Compression compare with this nodes address (source) */ iphc1 |= compress_addr_64(ipv6->srcipaddr, &ieee->i_nodeaddr, SIXLOWPAN_IPHC_SAM_BIT); @@ -631,7 +631,7 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, { /* Send the full address => SAC = 0, SAM = 00 */ - iphc1 |= SIXLOWPAN_IPHC_SAM_00; /* 128-bits */ + iphc1 |= SIXLOWPAN_IPHC_SAM_128; /* 128-bits */ memcpy(g_hc06ptr, ipv6->srcipaddr, 16); g_hc06ptr += 16; } @@ -645,7 +645,7 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, iphc1 |= SIXLOWPAN_IPHC_M; if (SIXLOWPAN_IS_MCASTADDR_COMPRESSABLE8(ipv6->destipaddr)) { - iphc1 |= SIXLOWPAN_IPHC_DAM_11; + iphc1 |= SIXLOWPAN_IPHC_DAM_0; /* Use last byte */ @@ -656,7 +656,7 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, { FAR uint8_t *iptr = (FAR uint8_t *)ipv6->destipaddr; - iphc1 |= SIXLOWPAN_IPHC_DAM_10; + iphc1 |= SIXLOWPAN_IPHC_DAM_16; /* Second byte + the last three */ @@ -668,7 +668,7 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, { FAR uint8_t *iptr = (FAR uint8_t *)ipv6->destipaddr; - iphc1 |= SIXLOWPAN_IPHC_DAM_01; + iphc1 |= SIXLOWPAN_IPHC_DAM_64; /* Second byte + the last five */ @@ -678,7 +678,7 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, } else { - iphc1 |= SIXLOWPAN_IPHC_DAM_00; + iphc1 |= SIXLOWPAN_IPHC_DAM_128; /* Full address */ @@ -715,7 +715,7 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, { /* Send the full address */ - iphc1 |= SIXLOWPAN_IPHC_DAM_00; /* 128-bits */ + iphc1 |= SIXLOWPAN_IPHC_DAM_128; /* 128-bits */ memcpy(g_hc06ptr, ipv6->destipaddr, 16); g_hc06ptr += 16; } @@ -865,7 +865,7 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, g_hc06ptr = payptr + 2; ninfo("payptr=%p g_frame_hdrlen=%u iphc=%02x:%02x:%02x g_hc06ptr=%p\n", - payptr, g_frame_hdrlen, iphc, iphc[0], iphc[1], iphc[2], g_hc06ptr); + payptr, g_frame_hdrlen, iphc[0], iphc[1], iphc[2], g_hc06ptr); /* Another if the CID flag is set */ @@ -877,11 +877,11 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, /* Traffic class and flow label */ - if ((iphc0 & SIXLOWPAN_IPHC_FL_C) == 0) + if ((iphc0 & SIXLOWPAN_IPHC_TC_10) == 0) { /* Flow label are carried inline */ - if ((iphc0 & SIXLOWPAN_IPHC_TC_C) == 0) + if ((iphc0 & SIXLOWPAN_IPHC_TC_01) == 0) { /* Traffic class is carried inline */ @@ -916,7 +916,7 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, /* Version is always 6! */ /* Version and flow label are compressed */ - if ((iphc0 & SIXLOWPAN_IPHC_TC_C) == 0) + if ((iphc0 & SIXLOWPAN_IPHC_TC_01) == 0) { /* Traffic class is inline */ @@ -937,7 +937,7 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, /* Next Header */ - if ((iphc0 & SIXLOWPAN_IPHC_NH_C) == 0) + if ((iphc0 & SIXLOWPAN_IPHC_NH) == 0) { /* Next header is carried inline */ @@ -948,19 +948,19 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, /* Hop limit */ - if ((iphc0 & 0x03) != SIXLOWPAN_IPHC_TTL_I) + if ((iphc0 & SIXLOWPAN_IPHC_HLIM_MASK) != SIXLOWPAN_IPHC_HLIM_INLINE) { - ipv6->ttl = g_ttl_values[iphc0 & 0x03]; + ipv6->ttl = g_ttl_values[iphc0 & SIXLOWPAN_IPHC_HLIM_MASK]; } else { - ipv6->ttl = *g_hc06ptr; + ipv6->ttl = *g_hc06ptr; g_hc06ptr += 1; } /* Put the source address compression mode SAM in the tmp var */ - tmp = ((iphc1 & SIXLOWPAN_IPHC_SAM_11) >> SIXLOWPAN_IPHC_SAM_BIT) & 0x03; + tmp = ((iphc1 & SIXLOWPAN_IPHC_SAM_MASK) >> SIXLOWPAN_IPHC_SAM_BIT) & 0x03; /* Address context based compression */ @@ -996,9 +996,9 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, } /* Destination address */ - /* put the destination address compression mode into tmp */ + /* Put the destination address compression mode into tmp */ - tmp = ((iphc1 & SIXLOWPAN_IPHC_DAM_11) >> SIXLOWPAN_IPHC_DAM_BIT) & 0x03; + tmp = ((iphc1 & SIXLOWPAN_IPHC_DAM_MASK) >> SIXLOWPAN_IPHC_DAM_BIT) & 0x03; /* Multicast compression */ @@ -1012,12 +1012,12 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, } else { - /* non-address context based multicast compression + /* Non-address context based multicast compression * - * DAM_00: 128 bits - * DAM_01: 48 bits FFXX::00XX:XXXX:XXXX - * DAM_10: 32 bits FFXX::00XX:XXXX - * DAM_11: 8 bits FF02::00XX + * DAM 00: 128 bits + * DAM 01: 48 bits FFXX::00XX:XXXX:XXXX + * DAM 0: 32 bits FFXX::00XX:XXXX + * DAM 11: 8 bits FF02::00XX */ uint8_t prefix[] = { 0xff, 0x02 }; @@ -1066,7 +1066,7 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, /* Next header processing - continued */ - if ((iphc0 & SIXLOWPAN_IPHC_NH_C)) + if ((iphc0 & SIXLOWPAN_IPHC_NH)) { FAR struct udp_hdr_s *udp = UDPIPv6BUF(ieee); -- GitLab From 18518eae061d36c078594f47a8a0a9a62a5d9239 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 5 Apr 2017 18:14:13 -0600 Subject: [PATCH 354/990] 6loWPAN: Fix another HC06 indexing problem. --- net/sixlowpan/sixlowpan_hc06.c | 29 ++++++++++++++++------------- 1 file changed, 16 insertions(+), 13 deletions(-) diff --git a/net/sixlowpan/sixlowpan_hc06.c b/net/sixlowpan/sixlowpan_hc06.c index 2c345f7818..9e51f88c17 100644 --- a/net/sixlowpan/sixlowpan_hc06.c +++ b/net/sixlowpan/sixlowpan_hc06.c @@ -458,9 +458,7 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, uint8_t iphc1; uint8_t tmp; - g_hc06ptr = fptr + 2; - ninfo("fptr=%p g_frame_hdrlen=%u iphc=%p g_hc06ptr=%p\n", - fptr, g_frame_hdrlen, iphc, g_hc06ptr); + ninfo("fptr=%p g_frame_hdrlen=%u iphc=%p\n", fptr, g_frame_hdrlen, iphc); /* As we copy some bit-length fields, in the IPHC encoding bytes, * we sometimes use |= @@ -472,6 +470,10 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, iphc1 = 0; iphc[2] = 0; /* Might not be used - but needs to be cleared */ + /* Point to just after the two IPHC bytes we have committed to */ + + g_hc06ptr = iphc + 2; + /* Address handling needs to be made first since it might cause an extra * byte with [ SCI | DCI ] */ @@ -527,7 +529,7 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, { /* Flow label cannot be compressed */ - if (((ipv6->vtc & 0x0f) == 0) && ((ipv6->tcf & 0xF0) == 0)) + if (((ipv6->vtc & 0x0f) == 0) && ((ipv6->tcf & 0xf0) == 0)) { /* Compress only traffic class */ @@ -617,9 +619,10 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, iphc1 |= compress_addr_64(ipv6->srcipaddr, &ieee->i_nodeaddr, SIXLOWPAN_IPHC_SAM_BIT); - - /* No address context found for this address */ } + + /* No address context found for this address */ + else if (net_is_addr_linklocal(ipv6->srcipaddr) && ipv6->destipaddr[1] == 0 && ipv6->destipaddr[2] == 0 && ipv6->destipaddr[3] == 0) @@ -869,7 +872,7 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, /* Another if the CID flag is set */ - if (iphc1 & SIXLOWPAN_IPHC_CID) + if ((iphc1 & SIXLOWPAN_IPHC_CID) != 0) { ninfo("CID flag set. Increase header by one\n"); g_hc06ptr++; @@ -964,7 +967,7 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, /* Address context based compression */ - if (iphc1 & SIXLOWPAN_IPHC_SAC) + if ((iphc1 & SIXLOWPAN_IPHC_SAC) != 0) { FAR struct sixlowpan_addrcontext_s *addrcontext; uint8_t sci = (iphc1 & SIXLOWPAN_IPHC_CID) ? iphc[2] >> 4 : 0; @@ -1002,11 +1005,11 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, /* Multicast compression */ - if (iphc1 & SIXLOWPAN_IPHC_M) + if ((iphc1 & SIXLOWPAN_IPHC_M) != 0) { /* Address context based multicast compression */ - if (iphc1 & SIXLOWPAN_IPHC_DAC) + if ((iphc1 & SIXLOWPAN_IPHC_DAC) != 0) { /* TODO: implement this */ } @@ -1035,10 +1038,10 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, /* no multicast */ /* Context based */ - if (iphc1 & SIXLOWPAN_IPHC_DAC) + if ((iphc1 & SIXLOWPAN_IPHC_DAC) != 0) { FAR struct sixlowpan_addrcontext_s *addrcontext; - uint8_t dci = (iphc1 & SIXLOWPAN_IPHC_CID) ? iphc[2] & 0x0f : 0; + uint8_t dci = ((iphc1 & SIXLOWPAN_IPHC_CID) != 0) ? iphc[2] & 0x0f : 0; addrcontext = find_addrcontext_bynumber(dci); @@ -1066,7 +1069,7 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, /* Next header processing - continued */ - if ((iphc0 & SIXLOWPAN_IPHC_NH)) + if ((iphc0 & SIXLOWPAN_IPHC_NH) != 0) { FAR struct udp_hdr_s *udp = UDPIPv6BUF(ieee); -- GitLab From 0de787b558adfb5be454fb038fbc3838bfe2df2b Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Wed, 5 Apr 2017 18:28:54 -0600 Subject: [PATCH 355/990] Document set [{+|-}{e|x|xe|ex}] [ ] --- Documentation/NuttShell.html | 53 ++++++++++++++++++++++++++++++++++-- 1 file changed, 50 insertions(+), 3 deletions(-) diff --git a/Documentation/NuttShell.html b/Documentation/NuttShell.html index 987f8a7177..af8eeba20b 100644 --- a/Documentation/NuttShell.html +++ b/Documentation/NuttShell.html @@ -8,7 +8,7 @@

NuttShell (NSH)

-

Last Updated: February 5, 2017

+

Last Updated: April 5, 2017

@@ -2708,11 +2708,13 @@ nsh>

Command Syntax:

    -set <name> <value>
    +set [{+|-}{e|x|xe|ex}] [<name> <value>]
     

Synopsis. - Set the environment variable <name> to the string <value>. + Set the environment variable <name> to the string <value> and or set NSH + parser control options. For example, + For example,

    @@ -2724,6 +2726,51 @@ foovalue
     nsh>
     
+

+ Set the 'exit on error control' and/or 'print a trace' of commands when parsing + scripts in NSH. The settinngs are in effect from the point of exection, until + they are changed again, or in the case of the init script, the settings are + returned to the default settings when it exits. Included child scripts will run + with the parents settings and changes made in the child script will effect the + parent on return. +

+

+ Use 'set -e' to enable and 'set +e' to disable (ignore) the exit condition on commands. + The default is -e. Errors cause script to exit. +

+

+ Use 'set -x' to enable and 'set +x' to disable (silence) printing a trace of the script + commands as they are ececuted. + The default is +x. No printing of a trace of script commands as they are executed. + +

+ + Example 1 - no exit on command not found +
    +    set +e
    +    notacommand
    +
+ + Example 2 - will exit on command not found +
    +    set -e
    +    notacommand
    +
+ + Example 3 - will exit on command not found, and print a trace of the script commmands +
    +    set -ex
    +
+ + Example 4 - will exit on command not found, and print a trace of the script commmands + and set foobar to foovalue. +
    +    set -ex foobar foovalue
    +    nsh> echo $foobar
    +    foovalue
    +
+ +
-- GitLab From f5b6ae627dbefa85457e9adcf5f9c19ab19301eb Mon Sep 17 00:00:00 2001 From: Masayuki Ishikawa Date: Thu, 6 Apr 2017 17:12:13 +0900 Subject: [PATCH 356/990] EFM32 I2C: Fix timeout calculation --- arch/arm/src/efm32/efm32_i2c.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/arch/arm/src/efm32/efm32_i2c.c b/arch/arm/src/efm32/efm32_i2c.c index 59ad3aa2f8..a52cd05ead 100644 --- a/arch/arm/src/efm32/efm32_i2c.c +++ b/arch/arm/src/efm32/efm32_i2c.c @@ -553,7 +553,7 @@ static inline int efm32_i2c_sem_waitdone(FAR struct efm32_i2c_priv_s *priv) #ifdef CONFIG_EFM32_I2C_DYNTIMEO abstime.tv_nsec += 1000 * efm32_i2c_tousecs(priv->msgc, priv->msgv); - if (abstime.tv_nsec > 1000 * 1000 * 1000) + if (abstime.tv_nsec >= 1000 * 1000 * 1000) { abstime.tv_sec++; abstime.tv_nsec -= 1000 * 1000 * 1000; @@ -561,7 +561,7 @@ static inline int efm32_i2c_sem_waitdone(FAR struct efm32_i2c_priv_s *priv) #elif CONFIG_EFM32_I2CTIMEOMS > 0 abstime.tv_nsec += CONFIG_EFM32_I2CTIMEOMS * 1000 * 1000; - if (abstime.tv_nsec > 1000 * 1000 * 1000) + if (abstime.tv_nsec >= 1000 * 1000 * 1000) { abstime.tv_sec++; abstime.tv_nsec -= 1000 * 1000 * 1000; -- GitLab From 1fa300f01159382c078ead269028278a7a2e024c Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 6 Apr 2017 08:32:18 -0600 Subject: [PATCH 357/990] 6loWPAN: Fix uncompressing of IPv6 encoded packet. --- net/sixlowpan/sixlowpan_input.c | 13 +++++++++++-- 1 file changed, 11 insertions(+), 2 deletions(-) diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index 03a78f3684..257e7b48c9 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -462,12 +462,21 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, if (hc1[RIME_HC1_DISPATCH] == SIXLOWPAN_DISPATCH_IPV6) { - ninfo("IPV6 Dispatch\n"); + FAR struct ipv6_hdr_s *ipv6 = IPv6BUF(&ieee->i_dev); + + ninfo("IPv6 Dispatch\n"); g_frame_hdrlen += SIXLOWPAN_IPV6_HDR_LEN; + /* payptr was set up to begin just after the IPHC bytes. However, + * those bytes are not present for the case of IPv6 dispatch. Just + * reset back to the begnning of the buffer. + */ + + payptr = iob->io_data; + /* Put uncompressed IP header in d_buf. */ - memcpy(ieee->i_dev.d_buf, payptr + g_frame_hdrlen, IPv6_HDRLEN); + memcpy(ipv6, payptr + g_frame_hdrlen, IPv6_HDRLEN); /* Update g_uncomp_hdrlen and g_frame_hdrlen. */ -- GitLab From 95941b49084e5e30194a6debdac9c60bbf3e596e Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Thu, 6 Apr 2017 08:35:33 -0600 Subject: [PATCH 358/990] STM32: Fix SYSCFG_CFGR1_I2C_PBXFMP_SHIFT value --- arch/arm/src/stm32/chip/stm32f30xxx_syscfg.h | 2 +- arch/arm/src/stm32/chip/stm32f33xxx_syscfg.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/arch/arm/src/stm32/chip/stm32f30xxx_syscfg.h b/arch/arm/src/stm32/chip/stm32f30xxx_syscfg.h index 1f19e74dcc..a4bf5d184c 100644 --- a/arch/arm/src/stm32/chip/stm32f30xxx_syscfg.h +++ b/arch/arm/src/stm32/chip/stm32f30xxx_syscfg.h @@ -94,7 +94,7 @@ #define SYSCFG_CFGR1_DAC1_DMARMP (1 << 13) /* Bit 13: DAC channel DMA remap */ #define SYSCFG_CFGR1_TIM7_DMARMP (1 << 14) /* Bit 14: TIM7 DMA remap */ #define SYSCFG_CFGR1_DAC2_DMARMP (1 << 14) /* Bit 14: DAC channel2 DMA remap */ -#define SYSCFG_CFGR1_I2C_PBXFMP_SHIFT (0) /* Bits 16-19: Fast Mode Plus (FM+) driving capability */ +#define SYSCFG_CFGR1_I2C_PBXFMP_SHIFT (16) /* Bits 16-19: Fast Mode Plus (FM+) driving capability */ #define SYSCFG_CFGR1_I2C_PBXFMP_MASK (15 << SYSCFG_CFGR1_I2C_PBXFMP_SHIFT) #define SYSCFG_CFGR1_I2C1_FMP (1 << 20) /* Bit 20: I2C1 fast mode Plus driving capability */ #define SYSCFG_CFGR1_I2C2_FMP (1 << 21) /* Bit 21: I2C2 fast mode Plus driving capability */ diff --git a/arch/arm/src/stm32/chip/stm32f33xxx_syscfg.h b/arch/arm/src/stm32/chip/stm32f33xxx_syscfg.h index 6e83d0b611..d675d00f7b 100644 --- a/arch/arm/src/stm32/chip/stm32f33xxx_syscfg.h +++ b/arch/arm/src/stm32/chip/stm32f33xxx_syscfg.h @@ -96,7 +96,7 @@ #define SYSCFG_CFGR1_TIM7_DMARMP (1 << 14) /* Bit 14: TIM7 DMA remap */ #define SYSCFG_CFGR1_DAC2CH2_DMARMP (1 << 14) /* Bit 14: DAC channel2 DMA remap */ #define SYSCFG_CFGR1_DAC2CH1_DMARMP (1 << 15) /* Bit 14: DAC channel1 DMA remap */ -#define SYSCFG_CFGR1_I2C_PBXFMP_SHIFT (0) /* Bits 16-19: Fast Mode Plus (FM+) driving capability */ +#define SYSCFG_CFGR1_I2C_PBXFMP_SHIFT (16) /* Bits 16-19: Fast Mode Plus (FM+) driving capability */ #define SYSCFG_CFGR1_I2C_PBXFMP_MASK (15 << SYSCFG_CFGR1_I2C_PBXFMP_SHIFT) #define SYSCFG_CFGR1_I2C1_FMP (1 << 20) /* Bit 20: I2C1 fast mode Plus driving capability */ #define SYSCFG_CFGR1_I2C2_FMP (1 << 21) /* Bit 21: I2C2 fast mode Plus driving capability */ -- GitLab From e180522854970106801c93135aa4d4742df4fc7d Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Thu, 6 Apr 2017 08:41:41 -0600 Subject: [PATCH 359/990] stm32f7: serial: add interface to get uart_dev_t by USART number, stm32_serial_get_uart --- arch/arm/src/stm32f7/stm32_serial.c | 38 +++++++++++++++++++++++++++++ arch/arm/src/stm32f7/stm32_uart.h | 11 +++++++++ 2 files changed, 49 insertions(+) diff --git a/arch/arm/src/stm32f7/stm32_serial.c b/arch/arm/src/stm32f7/stm32_serial.c index b839aad8f4..eb554c314e 100644 --- a/arch/arm/src/stm32f7/stm32_serial.c +++ b/arch/arm/src/stm32f7/stm32_serial.c @@ -228,6 +228,10 @@ struct up_dev_s uint16_t ie; /* Saved interrupt mask bits value */ uint16_t sr; /* Saved status bits */ + /* Has been initialized and HW is setup. */ + + bool initialized; + /* If termios are supported, then the following fields may vary at * runtime. */ @@ -1460,6 +1464,11 @@ static int up_setup(struct uart_dev_s *dev) /* Set up the cached interrupt enables value */ priv->ie = 0; + + /* Mark device as initialized. */ + + priv->initialized = true; + return OK; } @@ -1539,6 +1548,10 @@ static void up_shutdown(struct uart_dev_s *dev) struct up_dev_s *priv = (struct up_dev_s *)dev->priv; uint32_t regval; + /* Mark device as uninitialized. */ + + priv->initialized = false; + /* Disable all interrupts */ up_disableusartint(priv, NULL); @@ -2529,6 +2542,31 @@ static int up_pm_prepare(struct pm_callback_s *cb, int domain, #ifdef USE_SERIALDRIVER +/**************************************************************************** + * Name: stm32_serial_get_uart + * + * Description: + * Get serial driver structure for STM32 USART + * + ****************************************************************************/ + +FAR uart_dev_t *stm32_serial_get_uart(int uart_num) +{ + int uart_idx = uart_num - 1; + + if (uart_idx < 0 || uart_idx >= STM32_NSERIAL || !uart_devs[uart_idx]) + { + return NULL; + } + + if (!uart_devs[uart_idx]->initialized) + { + return NULL; + } + + return &uart_devs[uart_idx]->dev; +} + /**************************************************************************** * Name: up_earlyserialinit * diff --git a/arch/arm/src/stm32f7/stm32_uart.h b/arch/arm/src/stm32f7/stm32_uart.h index d250eb7761..496d7e9ea4 100644 --- a/arch/arm/src/stm32f7/stm32_uart.h +++ b/arch/arm/src/stm32f7/stm32_uart.h @@ -41,6 +41,7 @@ ************************************************************************************/ #include +#include #include "chip/stm32_uart.h" @@ -319,6 +320,16 @@ extern "C" * Public Functions ************************************************************************************/ +/************************************************************************************ + * Name: stm32_serial_get_uart + * + * Description: + * Get serial driver structure for STM32 USART + * + ************************************************************************************/ + +FAR uart_dev_t *stm32_serial_get_uart(int uart_num); + /************************************************************************************ * Name: stm32_serial_dma_poll * -- GitLab From dabf45f10077cc40496a0d8f58cede2047ec1544 Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Thu, 6 Apr 2017 08:44:53 -0600 Subject: [PATCH 360/990] STM32F7: default CONFIG_STM32F7_DMACAPABLE to 'n'. STM32F7 does not have CCM RAM but DTCM, so this option does not need to enabled. DTCM RAM is DMA-able through CPU AHBS bus. --- arch/arm/src/stm32f7/Kconfig | 3 +-- arch/arm/src/stm32f7/stm32_ethernet.c | 4 ++-- arch/arm/src/stm32f7/stm32_serial.c | 3 +-- 3 files changed, 4 insertions(+), 6 deletions(-) diff --git a/arch/arm/src/stm32f7/Kconfig b/arch/arm/src/stm32f7/Kconfig index e727aef24a..f5815f4d91 100644 --- a/arch/arm/src/stm32f7/Kconfig +++ b/arch/arm/src/stm32f7/Kconfig @@ -1884,8 +1884,7 @@ config STM32F7_DTCM_PROCFS config STM32F7_DMACAPABLE bool "Workaround non-DMA capable memory" depends on ARCH_DMA - default y if !STM32F7_CCMEXCLUDE - default n if STM32F7_CCMEXCLUDE + default n ---help--- This option enables the DMA interface stm32_dmacapable that can be used to check if it is possible to do DMA from the selected address. diff --git a/arch/arm/src/stm32f7/stm32_ethernet.c b/arch/arm/src/stm32f7/stm32_ethernet.c index 480c395c79..961b21bf26 100644 --- a/arch/arm/src/stm32f7/stm32_ethernet.c +++ b/arch/arm/src/stm32f7/stm32_ethernet.c @@ -635,8 +635,8 @@ struct stm32_ethmac_s * 1. Be a multiple of the D-Cache line size. This requirement is assured * by the definition of RXDMA buffer size above. * 2. Be aligned a D-Cache line boundaries, and - * 3. Be positioned in DMA-able memory (*NOT* DTCM memory). This must - * be managed by logic in the linker script file. + * 3. Be positioned in DMA-able memory. This must be managed by logic + * in the linker script file. * * These DMA buffers are defined sequentially here to best assure optimal * packing of the buffers. diff --git a/arch/arm/src/stm32f7/stm32_serial.c b/arch/arm/src/stm32f7/stm32_serial.c index eb554c314e..18f56600df 100644 --- a/arch/arm/src/stm32f7/stm32_serial.c +++ b/arch/arm/src/stm32f7/stm32_serial.c @@ -383,8 +383,7 @@ static const struct uart_ops_s g_uart_dma_ops = * 1. Be a multiple of the D-Cache line size. This requirement is assured * by the definition of RXDMA buffer size above. * 2. Be aligned a D-Cache line boundaries, and - * 3. Be positioned in DMA-able memory (*NOT* DTCM memory). This must - * be managed by logic in the linker script file. + * 3. Be positioned in DMA-able memory. * * These DMA buffers are defined sequentially here to best assure optimal * packing of the buffers. -- GitLab From e2702cbe4eacfe2d94f7d704cd954ce4684af5c2 Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Thu, 6 Apr 2017 08:46:24 -0600 Subject: [PATCH 361/990] STM32F7: fix UART7 and UART8 IFLOWCONTROL options --- arch/arm/src/stm32f7/stm32_serial.c | 8 ++++---- drivers/serial/Kconfig | 2 +- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/arch/arm/src/stm32f7/stm32_serial.c b/arch/arm/src/stm32f7/stm32_serial.c index 18f56600df..1ea4bce7dc 100644 --- a/arch/arm/src/stm32f7/stm32_serial.c +++ b/arch/arm/src/stm32f7/stm32_serial.c @@ -882,11 +882,11 @@ static struct up_dev_s g_uart7priv = .usartbase = STM32_UART7_BASE, .tx_gpio = GPIO_UART7_TX, .rx_gpio = GPIO_UART7_RX, -#if defined(CONFIG_SERIAL_OFLOWCONTROL) && defined(CONFIG_USART7_OFLOWCONTROL) +#if defined(CONFIG_SERIAL_OFLOWCONTROL) && defined(CONFIG_UART7_OFLOWCONTROL) .oflow = true, .cts_gpio = GPIO_UART7_CTS, #endif -#if defined(CONFIG_SERIAL_IFLOWCONTROL) && defined(CONFIG_USART7_IFLOWCONTROL) +#if defined(CONFIG_SERIAL_IFLOWCONTROL) && defined(CONFIG_UART7_IFLOWCONTROL) .iflow = true, .rts_gpio = GPIO_UART7_RTS, #endif @@ -943,11 +943,11 @@ static struct up_dev_s g_uart8priv = .usartbase = STM32_UART8_BASE, .tx_gpio = GPIO_UART8_TX, .rx_gpio = GPIO_UART8_RX, -#if defined(CONFIG_SERIAL_OFLOWCONTROL) && defined(CONFIG_USART8_OFLOWCONTROL) +#if defined(CONFIG_SERIAL_OFLOWCONTROL) && defined(CONFIG_UART8_OFLOWCONTROL) .oflow = true, .cts_gpio = GPIO_UART8_CTS, #endif -#if defined(CONFIG_SERIAL_IFLOWCONTROL) && defined(CONFIG_USART8_IFLOWCONTROL) +#if defined(CONFIG_SERIAL_IFLOWCONTROL) && defined(CONFIG_UART8_IFLOWCONTROL) .iflow = true, .rts_gpio = GPIO_UART8_RTS, #endif diff --git a/drivers/serial/Kconfig b/drivers/serial/Kconfig index 53ef72c3cb..a6d8c2f120 100644 --- a/drivers/serial/Kconfig +++ b/drivers/serial/Kconfig @@ -1577,7 +1577,7 @@ config USART6_2STOP 1=Two stop bits config USART6_IFLOWCONTROL - bool "UART6 RTS flow control" + bool "USART6 RTS flow control" default n select SERIAL_IFLOWCONTROL ---help--- -- GitLab From 0aa52d98a2dbc4601f217d77e74c0cae2a69d770 Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Thu, 6 Apr 2017 08:47:45 -0600 Subject: [PATCH 362/990] STM32F7: add warning for RXDMA + IFLOWCONTROL combination Combination of RXDMA + IFLOWCONTROL does not work as one might expect. Since RXDMA uses circular DMA-buffer, DMA will always keep reading new data from USART peripheral even if DMA buffer underruns. Thus this combination only does following: RTS is asserted on USART setup and deasserted on shutdown and does not perform actual RTS flow-control. Data loss can be demonstrated by doing long up_mdelay inside irq critical section and feeding data to RXDMA+IFLOWCONTROL UART. --- arch/arm/src/stm32f7/stm32_serial.c | 40 +++++++++++++++++++++++++++++ 1 file changed, 40 insertions(+) diff --git a/arch/arm/src/stm32f7/stm32_serial.c b/arch/arm/src/stm32f7/stm32_serial.c index 1ea4bce7dc..ec97ec7096 100644 --- a/arch/arm/src/stm32f7/stm32_serial.c +++ b/arch/arm/src/stm32f7/stm32_serial.c @@ -218,6 +218,46 @@ #ifdef USE_SERIALDRIVER #ifdef HAVE_UART +/* Warnings for potentially unsafe configuration combinations. */ + +/* Combination of RXDMA + IFLOWCONTROL does not work as one might expect. + * Since RXDMA uses circular DMA-buffer, DMA will always keep reading new + * data from USART peripheral even if DMA buffer underruns. Thus this + * combination only does following: RTS is asserted on USART setup and + * deasserted on shutdown and does not perform actual RTS flow-control. + */ + +#if defined(CONFIG_USART1_RXDMA) && defined(CONFIG_USART1_IFLOWCONTROL) +# warning "RXDMA and IFLOWCONTROL both enabled for USART1. \ + This combination can lead to data loss." +#endif + +#if defined(CONFIG_USART2_RXDMA) && defined(CONFIG_USART2_IFLOWCONTROL) +# warning "RXDMA and IFLOWCONTROL both enabled for USART2. \ + This combination can lead to data loss." +#endif + +#if defined(CONFIG_USART3_RXDMA) && defined(CONFIG_USART3_IFLOWCONTROL) +# warning "RXDMA and IFLOWCONTROL both enabled for USART3. \ + This combination can lead to data loss." +#endif + +#if defined(CONFIG_USART6_RXDMA) && defined(CONFIG_USART6_IFLOWCONTROL) +# warning "RXDMA and IFLOWCONTROL both enabled for USART6. \ + This combination can lead to data loss." +#endif + +#if defined(CONFIG_UART7_RXDMA) && defined(CONFIG_UART7_IFLOWCONTROL) +# warning "RXDMA and IFLOWCONTROL both enabled for UART7. \ + This combination can lead to data loss." +#endif + +#if defined(CONFIG_UART8_RXDMA) && defined(CONFIG_UART8_IFLOWCONTROL) +# warning "RXDMA and IFLOWCONTROL both enabled for UART8. \ + This combination can lead to data loss." +#endif + + /**************************************************************************** * Private Types ****************************************************************************/ -- GitLab From 869e3b5b73391d8a6359f54de97635dbe212f88b Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 6 Apr 2017 09:36:57 -0600 Subject: [PATCH 363/990] sim/sixlowpan: Now support apps/examples/udpblaster too. --- configs/sim/README.txt | 6 ++++++ configs/sim/sixlowpan/defconfig | 36 ++++++++++++++++++++++++++++++++- 2 files changed, 41 insertions(+), 1 deletion(-) diff --git a/configs/sim/README.txt b/configs/sim/README.txt index 7fa886b5bd..816ed00743 100644 --- a/configs/sim/README.txt +++ b/configs/sim/README.txt @@ -813,6 +813,12 @@ sixlowpan 6loWPAN stack. It enables networking with 6loWPAN support and uses only a IEEE802.15.4 MAC loopback network device to supported testing. + This configuration includes apps/examples/nettest and apps/examples/udpblaster. + Neither are truly functional. The only intent of this configuration + is to verify that the 6loWPAN stack correctly encodes IEEE802.15.4 + packets on output to the loopback device and correct decodes the + returned packet. + touchscreen This configuration uses the simple touchscreen test at diff --git a/configs/sim/sixlowpan/defconfig b/configs/sim/sixlowpan/defconfig index 8a5d9f766d..ac4d9e35de 100644 --- a/configs/sim/sixlowpan/defconfig +++ b/configs/sim/sixlowpan/defconfig @@ -525,6 +525,10 @@ CONFIG_NETDEV_PHY_IOCTL=y # CONFIG_NET_IPv4 is not set CONFIG_NET_IPv6=y CONFIG_NET_IPv6_NCONF_ENTRIES=8 + +# +# 6LoWPAN Configuration +# CONFIG_NET_6LOWPAN_FRAG=y CONFIG_NET_6LOWPAN_FRAMELEN=127 # CONFIG_NET_6LOWPAN_COMPRESSION_IPv6 is not set @@ -882,6 +886,7 @@ CONFIG_EXAMPLES_NETTEST_IPv6=y # # Target IPv6 address # + # # Client IPv6 address # @@ -922,7 +927,36 @@ CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_TIFF is not set # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_UDP is not set -# CONFIG_EXAMPLES_UDPBLASTER is not set +CONFIG_EXAMPLES_UDPBLASTER=y +CONFIG_EXAMPLES_UDPBLASTER_STACKSIZE=8192 +CONFIG_EXAMPLES_UDPBLASTER_PRIORITY=100 +CONFIG_EXAMPLES_UDPBLASTER_HOSTRATE=800000 +CONFIG_EXAMPLES_UDPBLASTER_IPv6=y +# CONFIG_EXAMPLES_UDPBLASTER_INIT is not set + +# +# Target IPv6 address +# +CONFIG_EXAMPLES_UDPBLASTER_TARGETIPv6_1=0xfe80 +CONFIG_EXAMPLES_UDPBLASTER_TARGETIPv6_2=0x0000 +CONFIG_EXAMPLES_UDPBLASTER_TARGETIPv6_3=0x0000 +CONFIG_EXAMPLES_UDPBLASTER_TARGETIPv6_4=0x0000 +CONFIG_EXAMPLES_UDPBLASTER_TARGETIPv6_5=0x0000 +CONFIG_EXAMPLES_UDPBLASTER_TARGETIPv6_6=0x00ff +CONFIG_EXAMPLES_UDPBLASTER_TARGETIPv6_7=0xfe00 +CONFIG_EXAMPLES_UDPBLASTER_TARGETIPv6_8=0xa9cd + +# +# Router IPv6 address +# +CONFIG_EXAMPLES_UDPBLASTER_HOSTIPv6_1=0xfe80 +CONFIG_EXAMPLES_UDPBLASTER_HOSTIPv6_2=0x0000 +CONFIG_EXAMPLES_UDPBLASTER_HOSTIPv6_3=0x0000 +CONFIG_EXAMPLES_UDPBLASTER_HOSTIPv6_4=0x0000 +CONFIG_EXAMPLES_UDPBLASTER_HOSTIPv6_5=0x0000 +CONFIG_EXAMPLES_UDPBLASTER_HOSTIPv6_6=0x00ff +CONFIG_EXAMPLES_UDPBLASTER_HOSTIPv6_7=0xfe00 +CONFIG_EXAMPLES_UDPBLASTER_HOSTIPv6_8=0x1034 # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set -- GitLab From 571f3d952e5d3944830ac37a427f4a4ff13ff702 Mon Sep 17 00:00:00 2001 From: Frank Benkert Date: Thu, 6 Apr 2017 09:43:07 -0600 Subject: [PATCH 364/990] SAMV7: Watchdog: fix Forbidden Window Value According the Datasheet the WDD Value is the lower bound of a so called Forbidden Window and to disable this we have to set the WDD Value greater than or equal to the WDV Value. This seems to be a bug in the datasheet. It looks like we have to set it to a greater value than the WDV to realy disable this Thing. When triggering the Watchdog faster than the (very slow) clock source of the Watchdog fires, this Forbidden Window Feature resets the System if WDD equals to WDV. This Changeset disables the Forbidden Window by setting the WDD Value to the Maximum (0xfff) Value possible. --- arch/arm/src/samv7/sam_wdt.c | 15 ++++++++++++++- 1 file changed, 14 insertions(+), 1 deletion(-) diff --git a/arch/arm/src/samv7/sam_wdt.c b/arch/arm/src/samv7/sam_wdt.c index e662146077..c3921df2fd 100644 --- a/arch/arm/src/samv7/sam_wdt.c +++ b/arch/arm/src/samv7/sam_wdt.c @@ -495,9 +495,22 @@ static int sam_settimeout(FAR struct watchdog_lowerhalf_s *lower, * NOTE: The Watchdog Mode Register (WDT_MR) can be written only once. Only * a processor reset resets it. Writing the WDT_MR register reloads the * timer with the newly programmed mode parameters. + * + * NOTE: The WDD Value is the lower bound of a so called Forbidden Window + * (see Datasheet for further Informations). To disable this Forbidden + * Window we have to set the WDD Value greater than or equal to WDV + * (according the Datasheet). + * + * When setting the WDD Value equal to WDV we have to wait at least one clock + * pulse of the (very slow) watchdog clock source between two resets (or the + * configuration and the first reset) of the watchdog. + * + * On fast systems this can lead to a direct hit of the WDD boundary and + * thus to a reset of the system. This is why we program the WDD Value toi + * 0xfff to truly disable this Forbidden Window Feature. */ - regval = WDT_MR_WDV(reload) | WDT_MR_WDD(reload); + regval = WDT_MR_WDV(reload) | WDT_MR_WDD(0xfff); #ifdef CONFIG_SAMV7_WDT_INTERRUPT /* Generate an interrupt whent he watchdog timer expires */ -- GitLab From ac8ddf4eb1bd91b6f87aeabd3cd1e8b252e5add9 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 6 Apr 2017 09:46:04 -0600 Subject: [PATCH 365/990] SAMv7: In review of last patch, change literal 0xfff to WDT_MR_WDD_MAX for portability. --- arch/arm/src/samv7/sam_wdt.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/arch/arm/src/samv7/sam_wdt.c b/arch/arm/src/samv7/sam_wdt.c index c3921df2fd..4ce21303c3 100644 --- a/arch/arm/src/samv7/sam_wdt.c +++ b/arch/arm/src/samv7/sam_wdt.c @@ -507,10 +507,10 @@ static int sam_settimeout(FAR struct watchdog_lowerhalf_s *lower, * * On fast systems this can lead to a direct hit of the WDD boundary and * thus to a reset of the system. This is why we program the WDD Value toi - * 0xfff to truly disable this Forbidden Window Feature. + * WDT_MR_WDD_MAX to truly disable this Forbidden Window Feature. */ - regval = WDT_MR_WDV(reload) | WDT_MR_WDD(0xfff); + regval = WDT_MR_WDV(reload) | WDT_MR_WDD(WDT_MR_WDD_MAX); #ifdef CONFIG_SAMV7_WDT_INTERRUPT /* Generate an interrupt whent he watchdog timer expires */ -- GitLab From e3b3e57e560ef39c26ce498ab29181288816ffaf Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Thu, 6 Apr 2017 09:53:11 -0600 Subject: [PATCH 366/990] RTC: add interface for check if RTC time has been set New interface allows checking if RTC time has been set. This allows to application to detect if RTC has valid time (after reset) or should application attempt to get real time by other means (for example, by launching ntpclient or GPS). --- arch/arm/src/kinetis/kinetis_rtc_lowerhalf.c | 1 + arch/arm/src/stm32/Kconfig | 7 ++- arch/arm/src/stm32/stm32_rcc.c | 2 +- arch/arm/src/stm32/stm32_rtc.h | 5 ++ arch/arm/src/stm32/stm32_rtc_lowerhalf.c | 23 +++++++++ arch/arm/src/stm32/stm32_rtcc.c | 13 ++++- arch/arm/src/stm32/stm32f40xxx_rtcc.c | 15 ++++-- arch/arm/src/stm32f7/Kconfig | 7 ++- arch/arm/src/stm32f7/stm32_rtc.c | 25 ++++++---- arch/arm/src/stm32f7/stm32_rtc.h | 5 ++ arch/arm/src/stm32f7/stm32_rtc_lowerhalf.c | 23 +++++++++ arch/arm/src/stm32l4/stm32l4_rtc.h | 13 +++++ arch/arm/src/stm32l4/stm32l4_rtc_lowerhalf.c | 25 +++++++++- arch/arm/src/stm32l4/stm32l4_rtcc.c | 51 +++++++++++++++----- drivers/timers/rtc.c | 20 +++++++- include/nuttx/timers/rtc.h | 21 ++++++-- 16 files changed, 220 insertions(+), 36 deletions(-) diff --git a/arch/arm/src/kinetis/kinetis_rtc_lowerhalf.c b/arch/arm/src/kinetis/kinetis_rtc_lowerhalf.c index 961a212b6a..b56fc5d44a 100644 --- a/arch/arm/src/kinetis/kinetis_rtc_lowerhalf.c +++ b/arch/arm/src/kinetis/kinetis_rtc_lowerhalf.c @@ -121,6 +121,7 @@ static const struct rtc_ops_s g_rtc_ops = { .rdtime = kinetis_rdtime, .settime = kinetis_settime, + .havesettime = NULL, #ifdef CONFIG_RTC_ALARM .setalarm = kinetis_setalarm, .setrelative = kinetis_setrelative, diff --git a/arch/arm/src/stm32/Kconfig b/arch/arm/src/stm32/Kconfig index 6927a3c054..86b5b71435 100644 --- a/arch/arm/src/stm32/Kconfig +++ b/arch/arm/src/stm32/Kconfig @@ -6334,10 +6334,15 @@ config RTC_MAGIC_REG depends on RTC && !STM32_HAVE_RTC_COUNTER config RTC_MAGIC - hex "Value used as Magic to determine if RTC is set already" + hex "Value used as Magic to determine if RTC is already setup" default 0xfacefeee depends on RTC && !STM32_HAVE_RTC_COUNTER +config RTC_MAGIC_TIME_SET + hex "Value used as Magic to determine if RTC is setup and have time set" + default 0xfacefeef + depends on RTC && !STM32_HAVE_RTC_COUNTER + choice prompt "RTC clock source" default RTC_LSECLOCK diff --git a/arch/arm/src/stm32/stm32_rcc.c b/arch/arm/src/stm32/stm32_rcc.c index 3cb57ae6a0..be152ff8d8 100644 --- a/arch/arm/src/stm32/stm32_rcc.c +++ b/arch/arm/src/stm32/stm32_rcc.c @@ -131,7 +131,7 @@ static inline void rcc_resetbkp(void) stm32_pwr_initbkp(false); regval = getreg32(RTC_MAGIC_REG); - if (regval != RTC_MAGIC) + if (regval != RTC_MAGIC && regval != RTC_MAGIC_TIME_SET) { stm32_pwr_enablebkp(true); diff --git a/arch/arm/src/stm32/stm32_rtc.h b/arch/arm/src/stm32/stm32_rtc.h index 119e5e54df..d228a3c458 100644 --- a/arch/arm/src/stm32/stm32_rtc.h +++ b/arch/arm/src/stm32/stm32_rtc.h @@ -83,11 +83,16 @@ # define CONFIG_RTC_MAGIC (0xfacefeee) #endif +#if !defined(CONFIG_RTC_MAGIC_TIME_SET) +# define CONFIG_RTC_MAGIC_TIME_SET (CONFIG_RTC_MAGIC + 1) +#endif + #if !defined(CONFIG_RTC_MAGIC_REG) # define CONFIG_RTC_MAGIC_REG (0) #endif #define RTC_MAGIC CONFIG_RTC_MAGIC +#define RTC_MAGIC_TIME_SET CONFIG_RTC_MAGIC_TIME_SET #define RTC_MAGIC_REG STM32_RTC_BKR(CONFIG_RTC_MAGIC_REG) /**************************************************************************** diff --git a/arch/arm/src/stm32/stm32_rtc_lowerhalf.c b/arch/arm/src/stm32/stm32_rtc_lowerhalf.c index feaa3f5395..548b7fa81b 100644 --- a/arch/arm/src/stm32/stm32_rtc_lowerhalf.c +++ b/arch/arm/src/stm32/stm32_rtc_lowerhalf.c @@ -49,6 +49,8 @@ #include #include +#include "up_arch.h" + #include "chip.h" #include "stm32_rtc.h" @@ -111,6 +113,7 @@ static int stm32_rdtime(FAR struct rtc_lowerhalf_s *lower, FAR struct rtc_time *rtctime); static int stm32_settime(FAR struct rtc_lowerhalf_s *lower, FAR const struct rtc_time *rtctime); +static bool stm32_havesettime(FAR struct rtc_lowerhalf_s *lower); #ifdef CONFIG_RTC_ALARM static int stm32_setalarm(FAR struct rtc_lowerhalf_s *lower, @@ -130,6 +133,7 @@ static const struct rtc_ops_s g_rtc_ops = { .rdtime = stm32_rdtime, .settime = stm32_settime, + .havesettime = stm32_havesettime, #ifdef CONFIG_RTC_ALARM .setalarm = stm32_setalarm, .setrelative = stm32_setrelative, @@ -345,6 +349,25 @@ static int stm32_settime(FAR struct rtc_lowerhalf_s *lower, #endif } +/**************************************************************************** + * Name: stm32_havesettime + * + * Description: + * Implements the havesettime() method of the RTC driver interface + * + * Input Parameters: + * lower - A reference to RTC lower half driver state structure + * + * Returned Value: + * Returns true if RTC date-time have been previously set. + * + ****************************************************************************/ + +static bool stm32_havesettime(FAR struct rtc_lowerhalf_s *lower) +{ + return getreg32(RTC_MAGIC_REG) == RTC_MAGIC_TIME_SET; +} + /**************************************************************************** * Name: stm32_setalarm * diff --git a/arch/arm/src/stm32/stm32_rtcc.c b/arch/arm/src/stm32/stm32_rtcc.c index b715585496..b1347fd9e7 100644 --- a/arch/arm/src/stm32/stm32_rtcc.c +++ b/arch/arm/src/stm32/stm32_rtcc.c @@ -600,7 +600,7 @@ int up_rtc_initialize(void) stm32_pwr_enablebkp(true); - if (regval != RTC_MAGIC) + if (regval != RTC_MAGIC && regval != RTC_MAGIC_TIME_SET) { /* Some boards do not have the external 32khz oscillator installed, for those * boards we must fallback to the crummy internal RC clock or the external high @@ -712,7 +712,7 @@ int up_rtc_initialize(void) * has been writing to to back-up date register DR0. */ - if (regval != RTC_MAGIC) + if (regval != RTC_MAGIC && regval != RTC_MAGIC_TIME_SET) { rtcinfo("Do setup\n"); @@ -1004,6 +1004,15 @@ int stm32_rtc_setdatetime(FAR const struct tm *tp) ret = rtc_synchwait(); } + /* Remember that the RTC is initialized and had its time set. */ + + if (getreg32(RTC_MAGIC_REG) != RTC_MAGIC_TIME_SET) + { + stm32_pwr_enablebkp(true); + putreg32(RTC_MAGIC_TIME_SET, RTC_MAGIC_REG); + stm32_pwr_enablebkp(false); + } + /* Re-enable the write protection for RTC registers */ rtc_wprlock(); diff --git a/arch/arm/src/stm32/stm32f40xxx_rtcc.c b/arch/arm/src/stm32/stm32f40xxx_rtcc.c index 4e8cfc773b..5702904131 100644 --- a/arch/arm/src/stm32/stm32f40xxx_rtcc.c +++ b/arch/arm/src/stm32/stm32f40xxx_rtcc.c @@ -894,7 +894,7 @@ int up_rtc_initialize(void) stm32_pwr_enablebkp(true); - if (regval != RTC_MAGIC) + if (regval != RTC_MAGIC && regval != RTC_MAGIC_TIME_SET) { /* Some boards do not have the external 32khz oscillator installed, * for those boards we must fallback to the crummy internal RC clock @@ -1011,7 +1011,7 @@ int up_rtc_initialize(void) * has been writing to to back-up date register DR0. */ - if (regval != RTC_MAGIC) + if (regval != RTC_MAGIC && regval != RTC_MAGIC_TIME_SET) { rtcinfo("Do setup\n"); @@ -1287,6 +1287,15 @@ int stm32_rtc_setdatetime(FAR const struct tm *tp) ret = rtc_synchwait(); } + /* Remember that the RTC is initialized and had its time set. */ + + if (getreg32(RTC_MAGIC_REG) != RTC_MAGIC_TIME_SET) + { + stm32_pwr_enablebkp(true); + putreg32(RTC_MAGIC_TIME_SET, RTC_MAGIC_REG); + stm32_pwr_enablebkp(false); + } + /* Re-enable the write protection for RTC registers */ rtc_wprlock(); @@ -1362,7 +1371,7 @@ int stm32_rtc_setalarm(FAR struct alm_setalarm_s *alminfo) (rtc_bin2bcd(alminfo->as_time.tm_min) << RTC_ALRMR_MNU_SHIFT) | (rtc_bin2bcd(alminfo->as_time.tm_hour) << RTC_ALRMR_HU_SHIFT) | (rtc_bin2bcd(alminfo->as_time.tm_mday) << RTC_ALRMR_DU_SHIFT); - + /* Set the alarm in hardware and enable interrupts from the RTC */ switch (alminfo->as_id) diff --git a/arch/arm/src/stm32f7/Kconfig b/arch/arm/src/stm32f7/Kconfig index f5815f4d91..d8eabdcd4b 100644 --- a/arch/arm/src/stm32f7/Kconfig +++ b/arch/arm/src/stm32f7/Kconfig @@ -1832,10 +1832,15 @@ config RTC_MAGIC_REG depends on RTC && !STM32F7_HAVE_RTC_COUNTER config RTC_MAGIC - hex "Value used as Magic to determine if RTC is set already" + hex "Value used as Magic to determine if RTC is already setup" default 0xfacefeee depends on RTC && !STM32F7_HAVE_RTC_COUNTER +config RTC_MAGIC_TIME_SET + hex "Value used as Magic to determine if RTC is setup and have time set" + default 0xfacefeef + depends on RTC && !STM32F7_HAVE_RTC_COUNTER + choice prompt "RTC clock source" default STM32F7_RTC_LSECLOCK diff --git a/arch/arm/src/stm32f7/stm32_rtc.c b/arch/arm/src/stm32f7/stm32_rtc.c index 2840fac8a5..4583dfaf1e 100644 --- a/arch/arm/src/stm32f7/stm32_rtc.c +++ b/arch/arm/src/stm32f7/stm32_rtc.c @@ -856,9 +856,13 @@ int up_rtc_initialize(void) regval = getreg32(RTC_MAGIC_REG); + /* Enable write access to the backup domain (RTC registers, RTC + * backup data registers and backup SRAM). + */ + stm32_pwr_enablebkp(true); - if (regval != RTC_MAGIC) + if (regval != RTC_MAGIC && regval != RTC_MAGIC_TIME_SET) { /* Issue the Backup domain Reset Per Section 5.3.20 DocID028270 Rev 2 * The LSEON, LSEBYP, RTCSEL and RTCEN bits in the RCC backup domain @@ -949,8 +953,6 @@ int up_rtc_initialize(void) } } - stm32_pwr_enablebkp(false); - /* Loop, attempting to initialize/resume the RTC. This loop is necessary * because it seems that occasionally it takes longer to initialize the * RTC (the actual failure is in rtc_synchwait()). @@ -988,7 +990,7 @@ int up_rtc_initialize(void) * has been writing to to back-up date register DR0. */ - if (regval != RTC_MAGIC) + if (regval != RTC_MAGIC && regval != RTC_MAGIC_TIME_SET) { rtcinfo("Do setup\n"); @@ -996,12 +998,6 @@ int up_rtc_initialize(void) ret = rtc_setup(); - /* Enable write access to the backup domain (RTC registers, RTC - * backup data registers and backup SRAM). - */ - - stm32_pwr_enablebkp(true); - /* Remember that the RTC is initialized */ putreg32(RTC_MAGIC, RTC_MAGIC_REG); @@ -1297,6 +1293,15 @@ int stm32_rtc_setdatetime(FAR const struct tm *tp) ret = rtc_synchwait(); } + /* Remember that the RTC is initialized and had its time set. */ + + if (getreg32(RTC_MAGIC_REG) != RTC_MAGIC_TIME_SET) + { + stm32_pwr_enablebkp(true); + putreg32(RTC_MAGIC_TIME_SET, RTC_MAGIC_REG); + stm32_pwr_enablebkp(false); + } + /* Re-enable the write protection for RTC registers */ rtc_wprlock(); diff --git a/arch/arm/src/stm32f7/stm32_rtc.h b/arch/arm/src/stm32f7/stm32_rtc.h index f784f8acd3..a46361a55d 100644 --- a/arch/arm/src/stm32f7/stm32_rtc.h +++ b/arch/arm/src/stm32f7/stm32_rtc.h @@ -66,11 +66,16 @@ # define CONFIG_RTC_MAGIC (0xfacefeee) #endif +#if !defined(CONFIG_RTC_MAGIC_TIME_SET) +# define CONFIG_RTC_MAGIC_TIME_SET (CONFIG_RTC_MAGIC + 1) +#endif + #if !defined(CONFIG_RTC_MAGIC_REG) # define CONFIG_RTC_MAGIC_REG (0) #endif #define RTC_MAGIC CONFIG_RTC_MAGIC +#define RTC_MAGIC_TIME_SET CONFIG_RTC_MAGIC_TIME_SET #define RTC_MAGIC_REG STM32_RTC_BKR(CONFIG_RTC_MAGIC_REG) /**************************************************************************** diff --git a/arch/arm/src/stm32f7/stm32_rtc_lowerhalf.c b/arch/arm/src/stm32f7/stm32_rtc_lowerhalf.c index 1b20b44eda..25868c58b8 100644 --- a/arch/arm/src/stm32f7/stm32_rtc_lowerhalf.c +++ b/arch/arm/src/stm32f7/stm32_rtc_lowerhalf.c @@ -50,6 +50,8 @@ #include #include +#include "up_arch.h" + #include "chip.h" #include "stm32_rtc.h" @@ -106,6 +108,7 @@ static int stm32_rdtime(FAR struct rtc_lowerhalf_s *lower, FAR struct rtc_time *rtctime); static int stm32_settime(FAR struct rtc_lowerhalf_s *lower, FAR const struct rtc_time *rtctime); +static bool stm32_havesettime(FAR struct rtc_lowerhalf_s *lower); #ifdef CONFIG_RTC_ALARM static int stm32_setalarm(FAR struct rtc_lowerhalf_s *lower, @@ -125,6 +128,7 @@ static const struct rtc_ops_s g_rtc_ops = { .rdtime = stm32_rdtime, .settime = stm32_settime, + .havesettime = stm32_havesettime, #ifdef CONFIG_RTC_ALARM .setalarm = stm32_setalarm, .setrelative = stm32_setrelative, @@ -314,6 +318,25 @@ static int stm32_settime(FAR struct rtc_lowerhalf_s *lower, #endif } +/**************************************************************************** + * Name: stm32_havesettime + * + * Description: + * Implements the havesettime() method of the RTC driver interface + * + * Input Parameters: + * lower - A reference to RTC lower half driver state structure + * + * Returned Value: + * Returns true if RTC date-time have been previously set. + * + ****************************************************************************/ + +static bool stm32_havesettime(FAR struct rtc_lowerhalf_s *lower) +{ + return getreg32(RTC_MAGIC_REG) == RTC_MAGIC_TIME_SET; +} + /**************************************************************************** * Name: stm32_setalarm * diff --git a/arch/arm/src/stm32l4/stm32l4_rtc.h b/arch/arm/src/stm32l4/stm32l4_rtc.h index 404f8325ad..18e7f6031b 100644 --- a/arch/arm/src/stm32l4/stm32l4_rtc.h +++ b/arch/arm/src/stm32l4/stm32l4_rtc.h @@ -171,6 +171,19 @@ struct tm; int stm32l4_rtc_setdatetime(FAR const struct tm *tp); #endif +/**************************************************************************** + * Name: stm32l4_rtc_setdatetime + * + * Description: + * Check if RTC time has been set. + * + * Returned Value: + * Returns true if RTC date-time have been previously set. + * + ****************************************************************************/ + +bool stm32l4_rtc_havesettime(void); + #ifdef CONFIG_RTC_ALARM /**************************************************************************** * Name: stm32l4_rtc_setalarm diff --git a/arch/arm/src/stm32l4/stm32l4_rtc_lowerhalf.c b/arch/arm/src/stm32l4/stm32l4_rtc_lowerhalf.c index 437faf54f1..5ab212dd86 100644 --- a/arch/arm/src/stm32l4/stm32l4_rtc_lowerhalf.c +++ b/arch/arm/src/stm32l4/stm32l4_rtc_lowerhalf.c @@ -107,6 +107,7 @@ static int stm32l4_rdtime(FAR struct rtc_lowerhalf_s *lower, FAR struct rtc_time *rtctime); static int stm32l4_settime(FAR struct rtc_lowerhalf_s *lower, FAR const struct rtc_time *rtctime); +static bool stm32l4_havesettime(FAR struct rtc_lowerhalf_s *lower); #ifdef CONFIG_RTC_ALARM static int stm32l4_setalarm(FAR struct rtc_lowerhalf_s *lower, @@ -127,6 +128,7 @@ static const struct rtc_ops_s g_rtc_ops = { .rdtime = stm32l4_rdtime, .settime = stm32l4_settime, + .havesettime = stm32l4_havesettime, #ifdef CONFIG_RTC_ALARM .setalarm = stm32l4_setalarm, .setrelative = stm32l4_setrelative, @@ -235,7 +237,7 @@ static int stm32l4_rdtime(FAR struct rtc_lowerhalf_s *lower, ret = up_rtc_getdatetime((FAR struct tm *)rtctime); sem_post(&priv->devsem); - + return ret; } @@ -273,12 +275,31 @@ static int stm32l4_settime(FAR struct rtc_lowerhalf_s *lower, */ ret = stm32l4_rtc_setdatetime((FAR const struct tm *)rtctime); - + sem_post(&priv->devsem); return ret; } +/**************************************************************************** + * Name: stm32l4_havesettime + * + * Description: + * Implements the havesettime() method of the RTC driver interface + * + * Input Parameters: + * lower - A reference to RTC lower half driver state structure + * + * Returned Value: + * Returns true if RTC date-time have been previously set. + * + ****************************************************************************/ + +static bool stm32l4_havesettime(FAR struct rtc_lowerhalf_s *lower) +{ + return stm32l4_rtc_havesettime(); +} + /**************************************************************************** * Name: stm32l4_setalarm * diff --git a/arch/arm/src/stm32l4/stm32l4_rtcc.c b/arch/arm/src/stm32l4/stm32l4_rtcc.c index a0221240f7..84a1f9eab6 100644 --- a/arch/arm/src/stm32l4/stm32l4_rtcc.c +++ b/arch/arm/src/stm32l4/stm32l4_rtcc.c @@ -87,6 +87,10 @@ # define CONFIG_RTC_MAGIC (0xfacefeee) #endif +#if !defined(CONFIG_RTC_MAGIC_TIME_SET) +# define CONFIG_RTC_MAGIC_TIME_SET (CONFIG_RTC_MAGIC + 1) +#endif + #if !defined(CONFIG_RTC_MAGIC_REG) # define CONFIG_RTC_MAGIC_REG (0) #endif @@ -185,7 +189,7 @@ static void rtc_dumpregs(FAR const char *msg) rtcinfo(" ISR: %08x\n", getreg32(STM32L4_RTC_ISR)); rtcinfo(" PRER: %08x\n", getreg32(STM32L4_RTC_PRER)); rtcinfo(" WUTR: %08x\n", getreg32(STM32L4_RTC_WUTR)); - + rtcinfo(" ALRMAR: %08x\n", getreg32(STM32L4_RTC_ALRMAR)); rtcinfo(" ALRMBR: %08x\n", getreg32(STM32L4_RTC_ALRMBR)); rtcinfo(" SHIFTR: %08x\n", getreg32(STM32L4_RTC_SHIFTR)); @@ -693,12 +697,12 @@ static int rtchw_set_alrmar(rtc_alarmreg_t alarmreg) modifyreg32(STM32L4_RTC_CR, (RTC_CR_ALRAE | RTC_CR_ALRAIE), 0); /* Ensure Alarm A flag reset; this is edge triggered */ - + isr = getreg32(STM32L4_RTC_ISR) & ~RTC_ISR_ALRAF; putreg32(isr, STM32L4_RTC_ISR); /* Wait for Alarm A to be writable */ - + ret = rtchw_check_alrawf(); if (ret != OK) { @@ -739,12 +743,12 @@ static int rtchw_set_alrmbr(rtc_alarmreg_t alarmreg) modifyreg32(STM32L4_RTC_CR, (RTC_CR_ALRBE | RTC_CR_ALRBIE), 0); /* Ensure Alarm B flag reset; this is edge triggered */ - + isr = getreg32(STM32L4_RTC_ISR) & ~RTC_ISR_ALRBF; putreg32(isr, STM32L4_RTC_ISR); /* Wait for Alarm B to be writable */ - + ret = rtchw_check_alrbwf(); if (ret != OK) { @@ -865,7 +869,7 @@ int up_rtc_initialize(void) init_stat = rtc_is_inits(); - if(!init_stat) + if (!init_stat) { /* Enable write access to the backup domain (RTC registers, RTC * backup data registers and backup SRAM). @@ -951,11 +955,11 @@ int up_rtc_initialize(void) (void)ret; /* Exit Initialization mode */ - + rtc_exitinit(); /* Enable the write protection for RTC registers */ - + rtc_wprlock(); /* Disable write access to the backup domain (RTC registers, RTC backup @@ -978,11 +982,11 @@ int up_rtc_initialize(void) //rtc_wprunlock(); rtc_resume(); - + /* Enable the write protection for RTC registers */ - + //rtc_wprlock(); - + /* Disable write access to the backup domain (RTC registers, RTC backup * data registers and backup SRAM). */ @@ -1210,6 +1214,15 @@ int stm32l4_rtc_setdatetime(FAR const struct tm *tp) ret = rtc_synchwait(); } + /* Remember that the RTC is initialized and had its time set. */ + + if (getreg32(CONFIG_RTC_MAGIC_REG) != CONFIG_RTC_MAGIC_TIME_SET) + { + stm32l4_pwr_enablebkp(true); + putreg32(CONFIG_RTC_MAGIC_TIME_SET, CONFIG_RTC_MAGIC_REG); + stm32l4_pwr_enablebkp(false); + } + /* Re-enable the write protection for RTC registers */ rtc_wprlock(); @@ -1217,6 +1230,22 @@ int stm32l4_rtc_setdatetime(FAR const struct tm *tp) return ret; } +/************************************************************************************ + * Name: stm32l4_rtc_setdatetime + * + * Description: + * Check if RTC time has been set. + * + * Returned Value: + * Returns true if RTC date-time have been previously set. + * + ************************************************************************************/ + +bool stm32l4_rtc_havesettime(void) +{ + return getreg32(CONFIG_RTC_MAGIC_REG) == CONFIG_RTC_MAGIC_TIME_SET; +} + /************************************************************************************ * Name: up_rtc_settime * diff --git a/drivers/timers/rtc.c b/drivers/timers/rtc.c index 0b467fde2f..990cec845f 100644 --- a/drivers/timers/rtc.c +++ b/drivers/timers/rtc.c @@ -332,7 +332,7 @@ static int rtc_ioctl(FAR struct file *filep, int cmd, unsigned long arg) /* RTC_SET_TIME sets the RTC's time * - * Argument: A read-only reference to a struct rtc_time containing the + * Argument: A read-only reference to a struct rtc_time containing * the new time to be set. */ @@ -348,6 +348,24 @@ static int rtc_ioctl(FAR struct file *filep, int cmd, unsigned long arg) } break; + /* RTC_HAVE_SET_TIME checks if RTC's time had been set + * + * Argument: A writable reference to a bool to receive true/false return + * value of the check. + */ + + case RTC_HAVE_SET_TIME: + { + FAR bool *have_set_time = (FAR bool *)((uintptr_t)arg); + + if (ops->havesettime) + { + *have_set_time = ops->havesettime(upper->lower); + ret = OK; + } + } + break; + #ifdef CONFIG_RTC_ALARM /* RTC_SET_ALARM sets the alarm time. * diff --git a/include/nuttx/timers/rtc.h b/include/nuttx/timers/rtc.h index d2345a4dc1..33b761ed0e 100644 --- a/include/nuttx/timers/rtc.h +++ b/include/nuttx/timers/rtc.h @@ -145,13 +145,22 @@ #define RTC_SET_TIME _RTCIOC(0x0002) + +/* RTC_HAVE_SET_TIME checks if RTC's time had been set + * + * Argument: A writable reference to a bool to receive true/false return value + * of the check. + */ + +#define RTC_HAVE_SET_TIME _RTCIOC(0x0003) + /* RTC_SET_ALARM sets the alarm time (for RTCs that support alarms). * * Argument: A read-only reference to a struct rtc_setalarm_s containing the * new alarm time to be set. */ -#define RTC_SET_ALARM _RTCIOC(0x0003) +#define RTC_SET_ALARM _RTCIOC(0x0004) /* RTC_SET_RELATIVE sets the alarm time relative to the current time. * @@ -159,14 +168,14 @@ * new relative alarm time to be set. */ -#define RTC_SET_RELATIVE _RTCIOC(0x0004) +#define RTC_SET_RELATIVE _RTCIOC(0x0005) /* RTC_SET_RELATIVE cancel the alarm. * * Argument: An ALARM ID value that indicates which alarm should be canceled. */ -#define RTC_CANCEL_ALARM _RTCIOC(0x0005) +#define RTC_CANCEL_ALARM _RTCIOC(0x0006) /* Architecture-specific RTC IOCTLS should begin at RTC_USER_IOCBASE. For * example: @@ -176,7 +185,7 @@ * etc. */ -#define RTC_USER_IOCBASE 0x0006 +#define RTC_USER_IOCBASE 0x0007 /**************************************************************************** * Public Types @@ -291,6 +300,10 @@ struct rtc_ops_s CODE int (*settime)(FAR struct rtc_lowerhalf_s *lower, FAR const struct rtc_time *rtctime); + /* havesettime checks if RTC time have been set */ + + CODE bool (*havesettime)(FAR struct rtc_lowerhalf_s *lower); + #ifdef CONFIG_RTC_ALARM /* setalarm sets up a new alarm. */ -- GitLab From 50170a6108541ce5d868382fccf4e7a8653fca6c Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 6 Apr 2017 11:57:43 -0600 Subject: [PATCH 367/990] 6loWPAN: Fixes for UDP packet transfers. --- net/sixlowpan/sixlowpan_internal.h | 7 +++++-- net/sixlowpan/sixlowpan_send.c | 6 ++++-- net/sixlowpan/sixlowpan_tcpsend.c | 3 ++- net/sixlowpan/sixlowpan_udpsend.c | 20 +++++++------------- 4 files changed, 18 insertions(+), 18 deletions(-) diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index 8f3e52dfd3..d6a795c554 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -446,6 +446,7 @@ extern struct rimeaddr_s g_pktaddrs[PACKETBUF_NUM_ADDRS]; struct net_driver_s; /* Forward reference */ struct ieee802154_driver_s; /* Forward reference */ +struct devif_callback_s; /* Forward reference */ struct ipv6_hdr_s; /* Forward reference */ struct rimeaddr_s; /* Forward reference */ struct iob_s; /* Forward reference */ @@ -466,7 +467,8 @@ struct iob_s; /* Forward reference */ * * Input Parameters: * dev - The IEEE802.15.4 MAC network driver interface. - * destip - IPv6 plus TCP or UDP headers. + * list - Head of callback list for send interrupt + * ipv6hdr - IPv6 plus TCP or UDP headers. * buf - Data to send * buflen - Length of data to send * raddr - The MAC address of the destination @@ -484,7 +486,8 @@ struct iob_s; /* Forward reference */ ****************************************************************************/ int sixlowpan_send(FAR struct net_driver_s *dev, - FAR const struct ipv6_hdr_s *destip, FAR const void *buf, + FAR struct devif_callback_s **list, + FAR const struct ipv6_hdr_s *ipv6hdr, FAR const void *buf, size_t buflen, FAR const struct rimeaddr_s *raddr, uint16_t timeout); diff --git a/net/sixlowpan/sixlowpan_send.c b/net/sixlowpan/sixlowpan_send.c index 98cc577f5f..d078a8534e 100644 --- a/net/sixlowpan/sixlowpan_send.c +++ b/net/sixlowpan/sixlowpan_send.c @@ -237,6 +237,7 @@ end_wait: * * Input Parameters: * dev - The IEEE802.15.4 MAC network driver interface. + * list - Head of callback list for send interrupt * ipv6hdr - IPv6 header followed by TCP or UDP header. * buf - Data to send * len - Length of data to send @@ -255,6 +256,7 @@ end_wait: ****************************************************************************/ int sixlowpan_send(FAR struct net_driver_s *dev, + FAR struct devif_callback_s **list, FAR const struct ipv6_hdr_s *ipv6hdr, FAR const void *buf, size_t len, FAR const struct rimeaddr_s *destmac, uint16_t timeout) @@ -283,7 +285,7 @@ int sixlowpan_send(FAR struct net_driver_s *dev, * device related events, no connect-related events. */ - sinfo.s_cb = devif_callback_alloc(dev, NULL); + sinfo.s_cb = devif_callback_alloc(dev, list); if (sinfo.s_cb != NULL) { int ret; @@ -312,7 +314,7 @@ int sixlowpan_send(FAR struct net_driver_s *dev, /* Make sure that no further interrupts are processed */ - devif_dev_callback_free(dev, sinfo.s_cb); + devif_conn_callback_free(dev, sinfo.s_cb, list); } } diff --git a/net/sixlowpan/sixlowpan_tcpsend.c b/net/sixlowpan/sixlowpan_tcpsend.c index 1ad8068a31..a34bfe0666 100644 --- a/net/sixlowpan/sixlowpan_tcpsend.c +++ b/net/sixlowpan/sixlowpan_tcpsend.c @@ -327,7 +327,8 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, timeout = 0; #endif - ret = sixlowpan_send(dev, (FAR const struct ipv6_hdr_s *)&ipv6tcp, + ret = sixlowpan_send(dev, &conn->list, + (FAR const struct ipv6_hdr_s *)&ipv6tcp, buf, buflen, &destmac, timeout); if (ret < 0) { diff --git a/net/sixlowpan/sixlowpan_udpsend.c b/net/sixlowpan/sixlowpan_udpsend.c index 717df424a2..f8f62e528b 100644 --- a/net/sixlowpan/sixlowpan_udpsend.c +++ b/net/sixlowpan/sixlowpan_udpsend.c @@ -191,8 +191,9 @@ ssize_t psock_6lowpan_udp_sendto(FAR struct socket *psock, if (to6->sin6_family != AF_INET6 || tolen < sizeof(struct sockaddr_in6)) { - nerr("ERROR: Invalid destination address\n"); - return (ssize_t)-EAFNOSUPPORT; + nerr("ERROR: Invalid destination address: sin6_family=%u tolen = %u\n", + to6->sin6_family, tolen); + return (ssize_t)-EPROTOTYPE; } /* Get the underlying UDP "connection" structure */ @@ -200,14 +201,6 @@ ssize_t psock_6lowpan_udp_sendto(FAR struct socket *psock, conn = (FAR struct udp_conn_s *)psock->s_conn; DEBUGASSERT(conn != NULL); - /* Ignore if not IPv6 domain */ - - if (conn->domain != PF_INET6) - { - nwarn("WARNING: Not IPv6\n"); - return (ssize_t)-EPROTOTYPE; - } - /* Route outgoing message to the correct device */ #ifdef CONFIG_NETDEV_MULTINIC @@ -264,8 +257,8 @@ ssize_t psock_6lowpan_udp_sendto(FAR struct socket *psock, /* Copy the source and destination addresses */ - net_ipv6addr_hdrcopy(ipv6udp.ipv6.srcipaddr, to6->sin6_addr.in6_u.u6_addr16); - net_ipv6addr_hdrcopy(ipv6udp.ipv6.destipaddr, conn->u.ipv6.raddr); + net_ipv6addr_hdrcopy(ipv6udp.ipv6.destipaddr, to6->sin6_addr.in6_u.u6_addr16); + net_ipv6addr_hdrcopy(ipv6udp.ipv6.srcipaddr, conn->u.ipv6.laddr); ninfo("IPv6 length: %d\n", ((int)ipv6udp.ipv6.len[0] << 8) + ipv6udp.ipv6.len[1]); @@ -315,7 +308,8 @@ ssize_t psock_6lowpan_udp_sendto(FAR struct socket *psock, timeout = 0; #endif - ret = sixlowpan_send(dev, (FAR const struct ipv6_hdr_s *)&ipv6udp, + ret = sixlowpan_send(dev, &conn->list, + (FAR const struct ipv6_hdr_s *)&ipv6udp, buf, buflen, &destmac, timeout); if (ret < 0) { -- GitLab From 27c65c3f229cf3bbeec83180d32e6df16fccc54d Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 6 Apr 2017 15:58:00 -0600 Subject: [PATCH 368/990] 6loWPAN: Add network IOCTL support to set the node address --- net/netdev/netdev_ioctl.c | 82 +++++++++++++++++++++++++++++++++++---- 1 file changed, 74 insertions(+), 8 deletions(-) diff --git a/net/netdev/netdev_ioctl.c b/net/netdev/netdev_ioctl.c index a9a70191fd..413a5d10fc 100644 --- a/net/netdev/netdev_ioctl.c +++ b/net/netdev/netdev_ioctl.c @@ -59,6 +59,10 @@ #include #include +#ifdef CONFIG_NET_6LOWPAN +# include +#endif + #ifdef CONFIG_NET_IGMP # include # include @@ -702,16 +706,47 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, /* MAC address operations only make sense if Ethernet is supported */ -#ifdef CONFIG_NET_ETHERNET +#if defined(CONFIG_NET_ETHERNET) || defined(CONFIG_NET_6LOWPAN) case SIOCGIFHWADDR: /* Get hardware address */ { dev = netdev_ifrdev(req); if (dev) { - req->ifr_hwaddr.sa_family = AF_INETX; - memcpy(req->ifr_hwaddr.sa_data, - dev->d_mac.ether_addr_octet, IFHWADDRLEN); - ret = OK; +#ifdef CONFIG_NET_ETHERNET +#ifdef CONFIG_NET_MULTILINK + if (dev->d_lltype == NET_LL_ETHERNET) +#else + if (true) +#endif + { + req->ifr_hwaddr.sa_family = AF_INETX; + memcpy(req->ifr_hwaddr.sa_data, + dev->d_mac.ether_addr_octet, IFHWADDRLEN); + ret = OK; + } + else +#endif + +#ifdef CONFIG_NET_6LOWPAN +#ifdef CONFIG_NET_MULTILINK + if (dev->d_lltype == NET_LL_IEEE802154) +#else + if (true) +#endif + { + FAR struct ieee802154_driver_s *ieee = + (FAR struct ieee802154_driver_s *)dev; + + req->ifr_hwaddr.sa_family = AF_INETX; + memcpy(req->ifr_hwaddr.sa_data, ieee->i_nodeaddr.u8, + CONFIG_NET_6LOWPAN_RIMEADDR_SIZE); + ret = OK; + } + else +#endif + { + nerr("Unsupported link layer\n"); + } } } break; @@ -721,9 +756,40 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, dev = netdev_ifrdev(req); if (dev) { - memcpy(dev->d_mac.ether_addr_octet, - req->ifr_hwaddr.sa_data, IFHWADDRLEN); - ret = OK; +#ifdef CONFIG_NET_ETHERNET +#ifdef CONFIG_NET_MULTILINK + if (dev->d_lltype == NET_LL_ETHERNET) +#else + if (true) +#endif + { + memcpy(dev->d_mac.ether_addr_octet, + req->ifr_hwaddr.sa_data, IFHWADDRLEN); + ret = OK; + } + else +#endif + +#ifdef CONFIG_NET_6LOWPAN +#ifdef CONFIG_NET_MULTILINK + if (dev->d_lltype == NET_LL_IEEE802154) +#else + if (true) +#endif + { + FAR struct ieee802154_driver_s *ieee = + (FAR struct ieee802154_driver_s *)dev; + + req->ifr_hwaddr.sa_family = AF_INETX; + memcpy(ieee->i_nodeaddr.u8, req->ifr_hwaddr.sa_data, + CONFIG_NET_6LOWPAN_RIMEADDR_SIZE); + ret = OK; + } + else +#endif + { + nerr("Unsupported link layer\n"); + } } } break; -- GitLab From 494d9968266373bc5749179527e2eb253e90abae Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 6 Apr 2017 17:56:22 -0600 Subject: [PATCH 369/990] 6loWPAN: Fix a few UDP-related issues. --- net/sixlowpan/sixlowpan_framelist.c | 2 +- net/sixlowpan/sixlowpan_hc1.c | 18 +++++---- net/sixlowpan/sixlowpan_internal.h | 16 ++++++++ net/sixlowpan/sixlowpan_send.c | 62 ++++++++++++++++++++++++++--- 4 files changed, 84 insertions(+), 14 deletions(-) diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c index bd4dd2e8eb..8995048b00 100644 --- a/net/sixlowpan/sixlowpan_framelist.c +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -146,7 +146,7 @@ static void sixlowpan_compress_ipv6hdr(FAR struct ieee802154_driver_s *ieee, * * Input Parameters: * ieee - The IEEE802.15.4 MAC driver instance - * ipv6hdr - IPv6 header followed by TCP or UDP header. + * ipv6hdr - IPv6 header followed by TCP, UDP, or ICMPv6 header. * buf - Beginning of the packet packet to send (with IPv6 + protocol * headers) * buflen - Length of data to send (include IPv6 and protocol headers) diff --git a/net/sixlowpan/sixlowpan_hc1.c b/net/sixlowpan/sixlowpan_hc1.c index a7040d5bcb..6626501363 100644 --- a/net/sixlowpan/sixlowpan_hc1.c +++ b/net/sixlowpan/sixlowpan_hc1.c @@ -116,7 +116,8 @@ * * Input Parmeters: * ieee - A reference to the IEE802.15.4 network device state - * ipv6 - The IPv6 header to be compressed + * ipv6 - The IPv6 header followd by TCP, UDP, or ICMPv6 header to be + * compressed * destmac - L2 destination address, needed to compress the IP * destination field * fptr - Pointer to frame to be compressed. @@ -189,7 +190,8 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, #if CONFIG_NET_UDP case IP_PROTO_UDP: { - FAR struct udp_hdr_s *udp = UDPIPv6BUF(&ieee->i_dev); + FAR struct udp_hdr_s *udp = + &(((FAR struct ipv6udp_hdr_s *)ipv6)->udp); /* Try to compress UDP header (we do only full compression). * This is feasible if both src and dest ports are between @@ -199,10 +201,10 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, ninfo("local/remote port %u/%u\n", udp->srcport, udp->destport); - if (htons(udp->srcport) >= CONFIG_NET_6LOWPAN_MINPORT && - htons(udp->srcport) < (CONFIG_NET_6LOWPAN_MINPORT + 16) && - htons(udp->destport) >= CONFIG_NET_6LOWPAN_MINPORT && - htons(udp->destport) < (CONFIG_NET_6LOWPAN_MINPORT + 16)) + if (ntohs(udp->srcport) >= CONFIG_NET_6LOWPAN_MINPORT && + ntohs(udp->srcport) < (CONFIG_NET_6LOWPAN_MINPORT + 16) && + ntohs(udp->destport) >= CONFIG_NET_6LOWPAN_MINPORT && + ntohs(udp->destport) < (CONFIG_NET_6LOWPAN_MINPORT + 16)) { FAR uint8_t *hcudp = fptr + g_frame_hdrlen; @@ -215,8 +217,8 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, hcudp[RIME_HC1_HC_UDP_UDP_ENCODING] = 0xe0; hcudp[RIME_HC1_HC_UDP_TTL] = ipv6->ttl; hcudp[RIME_HC1_HC_UDP_PORTS] = - (uint8_t)((htons(udp->srcport) - CONFIG_NET_6LOWPAN_MINPORT) << 4) + - (uint8_t)((htons(udp->destport) - CONFIG_NET_6LOWPAN_MINPORT)); + (uint8_t)((ntohs(udp->srcport) - CONFIG_NET_6LOWPAN_MINPORT) << 4) + + (uint8_t)((ntohs(udp->destport) - CONFIG_NET_6LOWPAN_MINPORT)); memcpy(&hcudp[RIME_HC1_HC_UDP_CHKSUM], &udp->udpchksum, 2); diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index d6a795c554..23bff8ad98 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -327,6 +327,22 @@ struct ipv6icmp_hdr_s struct icmpv6_iphdr_s icmp; }; +/* IPv6 + TCP or UDP or ICMPv6 header */ + +union ipv6_hdr_u +{ + struct ipv6_hdr_s ipv6; +#ifdef CONFIG_NET_TCP + struct ipv6tcp_hdr_s ipv6tcp; +#endif +#ifdef CONFIG_NET_UDP + struct ipv6udp_hdr_s ipv6udp; +#endif +#ifdef CONFIG_NET_ICMPv6 + struct ipv6icmp_hdr_s ipv6icmp +#endif +}; + /* IEEE802.15.4 Frame Definitions *******************************************/ /* The IEEE 802.15.4 frame has a number of constant/fixed fields that can be * counted to make frame construction and max payload calculations easier. diff --git a/net/sixlowpan/sixlowpan_send.c b/net/sixlowpan/sixlowpan_send.c index d078a8534e..cf15cac28b 100644 --- a/net/sixlowpan/sixlowpan_send.c +++ b/net/sixlowpan/sixlowpan_send.c @@ -39,6 +39,7 @@ #include +#include #include #include #include @@ -82,10 +83,10 @@ struct sixlowpan_send_s int s_result; /* The result of the transfer */ uint16_t s_timeout; /* Send timeout in deciseconds */ systime_t s_time; /* Last send time for determining timeout */ - FAR const struct ipv6_hdr_s *s_ipv6hdr; /* IPv6 header, followed by UDP or TCP header. */ FAR const struct rimeaddr_s *s_destmac; /* Destination MAC address */ FAR const void *s_buf; /* Data to send */ size_t s_len; /* Length of data in buf */ + FAR const union ipv6_hdr_u s_ipv6hdr; /* IPv6 header, followed by UDP, TCP, or ICMPv6 header. */ }; /**************************************************************************** @@ -176,12 +177,12 @@ static uint16_t send_interrupt(FAR struct net_driver_s *dev, { DEBUGASSERT((flags & WPAN_POLL) != 0); - /* Transfer the frame listto the IEEE802.15.4 MAC device */ + /* Transfer the frame list to the IEEE802.15.4 MAC device */ sinfo->s_result = sixlowpan_queue_frames((FAR struct ieee802154_driver_s *)dev, - sinfo->s_ipv6hdr, sinfo->s_buf, sinfo->s_len, - sinfo->s_destmac); + &sinfo->s_ipv6hdr.ipv6, sinfo->s_buf, + sinfo->s_len, sinfo->s_destmac); flags &= ~WPAN_POLL; neighbor_reachable(dev); @@ -217,6 +218,56 @@ end_wait: return flags; } +/**************************************************************************** + * Name: sixlowpan_ipv6_copy + * + * Description: + * Make a copy of the IPv6 + {TCP, UDP, ICMPv6} header structure. + * + * Input Parameters: + * ipv6hdr - IPv6 header followed by TCP or UDP header. + * sinfo - Send state structure reference + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void sixlowpan_ipv6_copy(FAR const struct ipv6_hdr_s *ipv6hdr, + FAR struct sixlowpan_send_s *sinfo) +{ + size_t structsize; + + switch (ipv6hdr->proto) + { +#ifdef CONFIG_NET_TCP + case IP_PROTO_TCP: + structsize = sizeof(struct ipv6tcp_hdr_s); + break; +#endif + +#ifdef CONFIG_NET_UDP + case IP_PROTO_UDP: + structsize = sizeof(struct ipv6udp_hdr_s); + break; +#endif + +#ifdef CONFIG_NET_ICMPv6 + case IP_PROTO_ICMP6: + structsize = sizeof(struct ipv6icmp_hdr_s); + break; +#endif + + default: + nwarn("WARNING: Unrecognized proto: %u\n", ipv6hdr->proto); + structsize = sizeof(struct ipv6_hdr_s); + break; + } + + memcpy((FAR void *)&sinfo->s_ipv6hdr, (FAR const void *)ipv6hdr, + structsize); +} + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -271,11 +322,12 @@ int sixlowpan_send(FAR struct net_driver_s *dev, sinfo.s_result = -EBUSY; sinfo.s_timeout = timeout; sinfo.s_time = clock_systimer(); - sinfo.s_ipv6hdr = ipv6hdr; sinfo.s_destmac = destmac; sinfo.s_buf = buf; sinfo.s_len = len; + sixlowpan_ipv6_copy(ipv6hdr, &sinfo); + net_lock(); if (len > 0) { -- GitLab From 58d0c1f22851cb8196e4de3f12f9302c0a969487 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 6 Apr 2017 18:11:04 -0600 Subject: [PATCH 370/990] 6loWPAN: Back out part of the last commit. That included two fixes for a problem. One that didn't work and is unnecessary and one that is necessary. The commit removes the former. --- net/sixlowpan/sixlowpan_internal.h | 16 -------- net/sixlowpan/sixlowpan_send.c | 60 ++---------------------------- 2 files changed, 4 insertions(+), 72 deletions(-) diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index 23bff8ad98..d6a795c554 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -327,22 +327,6 @@ struct ipv6icmp_hdr_s struct icmpv6_iphdr_s icmp; }; -/* IPv6 + TCP or UDP or ICMPv6 header */ - -union ipv6_hdr_u -{ - struct ipv6_hdr_s ipv6; -#ifdef CONFIG_NET_TCP - struct ipv6tcp_hdr_s ipv6tcp; -#endif -#ifdef CONFIG_NET_UDP - struct ipv6udp_hdr_s ipv6udp; -#endif -#ifdef CONFIG_NET_ICMPv6 - struct ipv6icmp_hdr_s ipv6icmp -#endif -}; - /* IEEE802.15.4 Frame Definitions *******************************************/ /* The IEEE 802.15.4 frame has a number of constant/fixed fields that can be * counted to make frame construction and max payload calculations easier. diff --git a/net/sixlowpan/sixlowpan_send.c b/net/sixlowpan/sixlowpan_send.c index cf15cac28b..8338a41347 100644 --- a/net/sixlowpan/sixlowpan_send.c +++ b/net/sixlowpan/sixlowpan_send.c @@ -39,7 +39,6 @@ #include -#include #include #include #include @@ -83,10 +82,10 @@ struct sixlowpan_send_s int s_result; /* The result of the transfer */ uint16_t s_timeout; /* Send timeout in deciseconds */ systime_t s_time; /* Last send time for determining timeout */ + FAR const struct ipv6_hdr_s *s_ipv6hdr; /* IPv6 header, followed by UDP or TCP header. */ FAR const struct rimeaddr_s *s_destmac; /* Destination MAC address */ FAR const void *s_buf; /* Data to send */ size_t s_len; /* Length of data in buf */ - FAR const union ipv6_hdr_u s_ipv6hdr; /* IPv6 header, followed by UDP, TCP, or ICMPv6 header. */ }; /**************************************************************************** @@ -181,8 +180,8 @@ static uint16_t send_interrupt(FAR struct net_driver_s *dev, sinfo->s_result = sixlowpan_queue_frames((FAR struct ieee802154_driver_s *)dev, - &sinfo->s_ipv6hdr.ipv6, sinfo->s_buf, - sinfo->s_len, sinfo->s_destmac); + sinfo->s_ipv6hdr, sinfo->s_buf, sinfo->s_len, + sinfo->s_destmac); flags &= ~WPAN_POLL; neighbor_reachable(dev); @@ -218,56 +217,6 @@ end_wait: return flags; } -/**************************************************************************** - * Name: sixlowpan_ipv6_copy - * - * Description: - * Make a copy of the IPv6 + {TCP, UDP, ICMPv6} header structure. - * - * Input Parameters: - * ipv6hdr - IPv6 header followed by TCP or UDP header. - * sinfo - Send state structure reference - * - * Returned Value: - * None - * - ****************************************************************************/ - -static void sixlowpan_ipv6_copy(FAR const struct ipv6_hdr_s *ipv6hdr, - FAR struct sixlowpan_send_s *sinfo) -{ - size_t structsize; - - switch (ipv6hdr->proto) - { -#ifdef CONFIG_NET_TCP - case IP_PROTO_TCP: - structsize = sizeof(struct ipv6tcp_hdr_s); - break; -#endif - -#ifdef CONFIG_NET_UDP - case IP_PROTO_UDP: - structsize = sizeof(struct ipv6udp_hdr_s); - break; -#endif - -#ifdef CONFIG_NET_ICMPv6 - case IP_PROTO_ICMP6: - structsize = sizeof(struct ipv6icmp_hdr_s); - break; -#endif - - default: - nwarn("WARNING: Unrecognized proto: %u\n", ipv6hdr->proto); - structsize = sizeof(struct ipv6_hdr_s); - break; - } - - memcpy((FAR void *)&sinfo->s_ipv6hdr, (FAR const void *)ipv6hdr, - structsize); -} - /**************************************************************************** * Public Functions ****************************************************************************/ @@ -322,12 +271,11 @@ int sixlowpan_send(FAR struct net_driver_s *dev, sinfo.s_result = -EBUSY; sinfo.s_timeout = timeout; sinfo.s_time = clock_systimer(); + sinfo.s_ipv6hdr = ipv6hdr; sinfo.s_destmac = destmac; sinfo.s_buf = buf; sinfo.s_len = len; - sixlowpan_ipv6_copy(ipv6hdr, &sinfo); - net_lock(); if (len > 0) { -- GitLab From 3465f6be535cdc5517bf049ad3b7cfe7c915d282 Mon Sep 17 00:00:00 2001 From: Bob Ryan Date: Thu, 6 Apr 2017 17:41:07 -0700 Subject: [PATCH 371/990] Disable serial console on stm32f103-minimum usbnsh example project config. Devices enumerate after this change. --- configs/stm32f103-minimum/usbnsh/defconfig | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/configs/stm32f103-minimum/usbnsh/defconfig b/configs/stm32f103-minimum/usbnsh/defconfig index e5319a27eb..312a2e8505 100644 --- a/configs/stm32f103-minimum/usbnsh/defconfig +++ b/configs/stm32f103-minimum/usbnsh/defconfig @@ -744,7 +744,7 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y # CONFIG_SENSORS is not set CONFIG_SERIAL=y CONFIG_SERIAL_REMOVABLE=y -CONFIG_SERIAL_CONSOLE=y +# CONFIG_SERIAL_CONSOLE is not set # CONFIG_16550_UART is not set # CONFIG_UART_SERIALDRIVER is not set # CONFIG_UART0_SERIALDRIVER is not set @@ -774,9 +774,9 @@ CONFIG_STANDARD_SERIAL=y # CONFIG_SERIAL_OFLOWCONTROL is not set # CONFIG_SERIAL_DMA is not set CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y -CONFIG_USART1_SERIAL_CONSOLE=y +# CONFIG_USART1_SERIAL_CONSOLE is not set # CONFIG_OTHER_SERIAL_CONSOLE is not set -# CONFIG_NO_SERIAL_CONSOLE is not set +CONFIG_NO_SERIAL_CONSOLE=y # # USART1 Configuration -- GitLab From 7bb26d26150d2540d97d6e8a146309866d278ad5 Mon Sep 17 00:00:00 2001 From: Mark Schulte Date: Fri, 7 Apr 2017 07:03:00 -0600 Subject: [PATCH 372/990] pthreads: Adding rwlock implementation Adding an implementation for read/write locks into the pthread library. These locks are writer priority, such that if any writers come in they are given priority for writing. --- include/pthread.h | 43 +++++++- libc/pthread/Make.defs | 4 + libc/pthread/pthread_rwlock.c | 127 ++++++++++++++++++++++++ libc/pthread/pthread_rwlock_rdlock.c | 143 +++++++++++++++++++++++++++ libc/pthread/pthread_rwlock_wrlock.c | 133 +++++++++++++++++++++++++ sched/Kconfig | 6 ++ 6 files changed, 454 insertions(+), 2 deletions(-) create mode 100644 libc/pthread/pthread_rwlock.c create mode 100644 libc/pthread/pthread_rwlock_rdlock.c create mode 100644 libc/pthread/pthread_rwlock_wrlock.c diff --git a/include/pthread.h b/include/pthread.h index af6ef51e23..cfa054cfca 100644 --- a/include/pthread.h +++ b/include/pthread.h @@ -337,6 +337,28 @@ typedef struct pthread_barrier_s pthread_barrier_t; typedef bool pthread_once_t; #define __PTHREAD_ONCE_T_DEFINED 1 +#ifdef CONFIG_PTHREAD_RWLOCK +struct pthread_rwlock_s +{ + pthread_mutex_t lock; + pthread_cond_t cv; + unsigned int num_readers; + unsigned int num_writers; +}; + +typedef struct pthread_rwlock_s pthread_rwlock_t; + +typedef int pthread_rwlockattr_t; + +#define PTHREAD_RWLOCK_INITIALIZER {PTHREAD_MUTEX_INITIALIZER, \ + PTHREAD_COND_INITIALIZER, \ + 0, 0} + +#define PTHREAD_MUTEX_INITIALIZER {NULL, SEM_INITIALIZER(1), -1, \ + __PTHREAD_MUTEX_DEFAULT_FLAGS, \ + PTHREAD_MUTEX_DEFAULT, 0} +#endif + #ifdef CONFIG_PTHREAD_CLEANUP /* This type describes the pthread cleanup callback (non-standard) */ @@ -539,8 +561,8 @@ int pthread_barrierattr_setpshared(FAR pthread_barrierattr_t *attr, int pthread_barrier_destroy(FAR pthread_barrier_t *barrier); int pthread_barrier_init(FAR pthread_barrier_t *barrier, - FAR const pthread_barrierattr_t *attr, - unsigned int count); + FAR const pthread_barrierattr_t *attr, + unsigned int count); int pthread_barrier_wait(FAR pthread_barrier_t *barrier); /* Pthread initialization */ @@ -548,6 +570,23 @@ int pthread_barrier_wait(FAR pthread_barrier_t *barrier); int pthread_once(FAR pthread_once_t *once_control, CODE void (*init_routine)(void)); +/* Pthread rwlock */ + +#ifdef CONFIG_PTHREAD_RWLOCK +int pthread_rwlock_destroy(FAR pthread_rwlock_t *rw_lock); +int pthread_rwlock_init(FAR pthread_rwlock_t *rw_lock, + FAR const pthread_rwlockattr_t *attr); +int pthread_rwlock_rdlock(pthread_rwlock_t *lock); +int pthread_rwlock_timedrdlock(FAR pthread_rwlock_t *lock, + FAR const struct timespec *abstime); +int pthread_rwlock_tryrdlock(FAR pthread_rwlock_t *lock); +int pthread_rwlock_wrlock(FAR pthread_rwlock_t *lock); +int pthread_rwlock_timedwrlock(FAR pthread_rwlock_t *lock, + FAR const struct timespec *abstime); +int pthread_rwlock_trywrlock(FAR pthread_rwlock_t *lock); +int pthread_rwlock_unlock(FAR pthread_rwlock_t *lock); +#endif /* CONFIG_PTHREAD_RWLOCK */ + /* Pthread signal management APIs */ int pthread_kill(pthread_t thread, int sig); diff --git a/libc/pthread/Make.defs b/libc/pthread/Make.defs index b8be2927d2..1f6cacb88e 100644 --- a/libc/pthread/Make.defs +++ b/libc/pthread/Make.defs @@ -53,6 +53,10 @@ CSRCS += pthread_mutexattr_setrobust.c pthread_mutexattr_getrobust.c CSRCS += pthread_setcancelstate.c pthread_setcanceltype.c CSRCS += pthread_testcancel.c +ifeq ($(CONFIG_PTHREAD_RWLOCK),y) +CSRCS += pthread_rwlock.c pthread_rwlock_rdlock.c pthread_rwlock_wrlock.c +endif + ifeq ($(CONFIG_SMP),y) CSRCS += pthread_attr_getaffinity.c pthread_attr_setaffinity.c endif diff --git a/libc/pthread/pthread_rwlock.c b/libc/pthread/pthread_rwlock.c new file mode 100644 index 0000000000..3f902089b0 --- /dev/null +++ b/libc/pthread/pthread_rwlock.c @@ -0,0 +1,127 @@ +/**************************************************************************** + * libc/pthread/pthread_rwlock.c + * + * Copyright (C) 2017 Mark Schulte. All rights reserved. + * Author: Mark Schulte + * + * 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 + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +int pthread_rwlock_init(FAR pthread_rwlock_t *lock, + FAR const pthread_rwlockattr_t *attr) +{ + int err; + + if (attr != NULL) + { + return -ENOSYS; + } + + lock->num_readers = 0; + lock->num_writers = 0; + + err = pthread_cond_init(&lock->cv, NULL); + if (err != 0) + { + return err; + } + + err = pthread_mutex_init(&lock->lock, NULL); + if (err != 0) + { + pthread_cond_destroy(&lock->cv); + return err; + } + + return err; +} + +int pthread_rwlock_destroy(FAR pthread_rwlock_t *lock) +{ + int cond_err = pthread_cond_destroy(&lock->cv); + int mutex_err = pthread_mutex_destroy(&lock->lock); + + if (mutex_err) + { + return mutex_err; + } + + return cond_err; +} + +int pthread_rwlock_unlock(FAR pthread_rwlock_t *rw_lock) +{ + int err; + + err = pthread_mutex_lock(&rw_lock->lock); + if (err != 0) + { + return err; + } + + if (rw_lock->num_readers > 0) + { + rw_lock->num_readers--; + + if (rw_lock->num_readers == 0) + { + err = pthread_cond_broadcast(&rw_lock->cv); + } + } + else if (rw_lock->num_writers > 0) + { + rw_lock->num_writers--; + + err = pthread_cond_broadcast(&rw_lock->cv); + } + else + { + err = EINVAL; + } + + pthread_mutex_unlock(&rw_lock->lock); + return err; +} diff --git a/libc/pthread/pthread_rwlock_rdlock.c b/libc/pthread/pthread_rwlock_rdlock.c new file mode 100644 index 0000000000..6270d2bbe4 --- /dev/null +++ b/libc/pthread/pthread_rwlock_rdlock.c @@ -0,0 +1,143 @@ +/**************************************************************************** + * libc/pthread/pthread_rwlockread.c + * + * Copyright (C) 2017 Mark Schulte. All rights reserved. + * Author: Mark Schulte + * + * 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 + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static int tryrdlock(FAR pthread_rwlock_t *rw_lock) +{ + int err; + + if (rw_lock->num_writers > 0) + { + err = EBUSY; + } + else if (rw_lock->num_readers == UINT_MAX) + { + err = EAGAIN; + } + else + { + rw_lock->num_readers++; + err = OK; + } + + return err; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: pthread_rwlock_rdlock + * + * Description: + * Locks a read/write lock for reading + * + * Parameters: + * None + * + * Return Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +int pthread_rwlock_tryrdlock(FAR pthread_rwlock_t *rw_lock) +{ + int err = pthread_mutex_trylock(&rw_lock->lock); + + if (err != 0) + { + return err; + } + + err = tryrdlock(rw_lock); + + pthread_mutex_unlock(&rw_lock->lock); + return err; +} + +int pthread_rwlock_timedrdlock(FAR pthread_rwlock_t *rw_lock, + FAR const struct timespec *ts) +{ + int err = pthread_mutex_lock(&rw_lock->lock); + + if (err != 0) + { + return err; + } + + while ((err = tryrdlock(rw_lock)) == EBUSY) + { + if (ts != NULL) + { + err = pthread_cond_timedwait(&rw_lock->cv, &rw_lock->lock, ts); + } + else + { + err = pthread_cond_wait(&rw_lock->cv, &rw_lock->lock); + } + + if (err != 0) + { + break; + } + } + + pthread_mutex_unlock(&rw_lock->lock); + return err; +} + +int pthread_rwlock_rdlock(FAR pthread_rwlock_t * rw_lock) +{ + return pthread_rwlock_timedrdlock(rw_lock, NULL); +} diff --git a/libc/pthread/pthread_rwlock_wrlock.c b/libc/pthread/pthread_rwlock_wrlock.c new file mode 100644 index 0000000000..dc2d155021 --- /dev/null +++ b/libc/pthread/pthread_rwlock_wrlock.c @@ -0,0 +1,133 @@ +/**************************************************************************** + * libc/pthread/pthread_rwlockwrite.c + * + * Copyright (C) 2017 Mark Schulte. All rights reserved. + * Author: Mark Schulte + * + * 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 + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: pthread_rwlock_rdlock + * + * Description: + * Locks a read/write lock for reading + * + * Parameters: + * None + * + * Return Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +int pthread_rwlock_trywrlock(FAR pthread_rwlock_t *rw_lock) +{ + int err = pthread_mutex_trylock(&rw_lock->lock); + + if (err != 0) + { + return err; + } + + if (rw_lock->num_readers > 0 || rw_lock->num_writers > 0) + { + err = EBUSY; + } + else + { + rw_lock->num_writers++; + } + + pthread_mutex_unlock(&rw_lock->lock); + return err; +} + +int pthread_rwlock_timedwrlock(FAR pthread_rwlock_t *rw_lock, + FAR const struct timespec *ts) +{ + int err = pthread_mutex_lock(&rw_lock->lock); + int num_writers_current; + + if (err != 0) + { + return err; + } + + num_writers_current = rw_lock->num_writers++; + if (num_writers_current == 0) + { + goto exit_with_mutex; + } + + while (rw_lock->num_writers != num_writers_current) + { + if (ts != NULL) + { + err = pthread_cond_timedwait(&rw_lock->cv, &rw_lock->lock, ts); + } + else + { + err = pthread_cond_wait(&rw_lock->cv, &rw_lock->lock); + } + + if (err != 0) + { + break; + } + } + +exit_with_mutex: + pthread_mutex_unlock(&rw_lock->lock); + return err; +} + +int pthread_rwlock_wrlock(FAR pthread_rwlock_t *rw_lock) +{ + return pthread_rwlock_timedwrlock(rw_lock, NULL); +} diff --git a/sched/Kconfig b/sched/Kconfig index 50613fb44d..02096b268d 100644 --- a/sched/Kconfig +++ b/sched/Kconfig @@ -573,6 +573,12 @@ config PTHREAD_MUTEX_DEFAULT_UNSAFE endchoice # Default NORMAL mutex robustness +config PTHREAD_RWLOCK + bool "Enable pthread rwlock API" + default n + ---help--- + Add supports for the rwlock interfaces + config NPTHREAD_KEYS int "Maximum number of pthread keys" default 4 -- GitLab From b631dc886f3d1533b70d38385e42fabc9fde93fe Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 7 Apr 2017 07:34:22 -0600 Subject: [PATCH 373/990] Remove CONFIG_PTHREAD_RWLOCK. Rwlock interfaces built unconditionally. --- include/pthread.h | 4 ---- libc/pthread/Make.defs | 3 --- sched/Kconfig | 6 ------ 3 files changed, 13 deletions(-) diff --git a/include/pthread.h b/include/pthread.h index cfa054cfca..be555fed75 100644 --- a/include/pthread.h +++ b/include/pthread.h @@ -337,7 +337,6 @@ typedef struct pthread_barrier_s pthread_barrier_t; typedef bool pthread_once_t; #define __PTHREAD_ONCE_T_DEFINED 1 -#ifdef CONFIG_PTHREAD_RWLOCK struct pthread_rwlock_s { pthread_mutex_t lock; @@ -357,7 +356,6 @@ typedef int pthread_rwlockattr_t; #define PTHREAD_MUTEX_INITIALIZER {NULL, SEM_INITIALIZER(1), -1, \ __PTHREAD_MUTEX_DEFAULT_FLAGS, \ PTHREAD_MUTEX_DEFAULT, 0} -#endif #ifdef CONFIG_PTHREAD_CLEANUP /* This type describes the pthread cleanup callback (non-standard) */ @@ -572,7 +570,6 @@ int pthread_once(FAR pthread_once_t *once_control, /* Pthread rwlock */ -#ifdef CONFIG_PTHREAD_RWLOCK int pthread_rwlock_destroy(FAR pthread_rwlock_t *rw_lock); int pthread_rwlock_init(FAR pthread_rwlock_t *rw_lock, FAR const pthread_rwlockattr_t *attr); @@ -585,7 +582,6 @@ int pthread_rwlock_timedwrlock(FAR pthread_rwlock_t *lock, FAR const struct timespec *abstime); int pthread_rwlock_trywrlock(FAR pthread_rwlock_t *lock); int pthread_rwlock_unlock(FAR pthread_rwlock_t *lock); -#endif /* CONFIG_PTHREAD_RWLOCK */ /* Pthread signal management APIs */ diff --git a/libc/pthread/Make.defs b/libc/pthread/Make.defs index 1f6cacb88e..291dfdfd4e 100644 --- a/libc/pthread/Make.defs +++ b/libc/pthread/Make.defs @@ -52,10 +52,7 @@ CSRCS += pthread_mutexattr_settype.c pthread_mutexattr_gettype.c CSRCS += pthread_mutexattr_setrobust.c pthread_mutexattr_getrobust.c CSRCS += pthread_setcancelstate.c pthread_setcanceltype.c CSRCS += pthread_testcancel.c - -ifeq ($(CONFIG_PTHREAD_RWLOCK),y) CSRCS += pthread_rwlock.c pthread_rwlock_rdlock.c pthread_rwlock_wrlock.c -endif ifeq ($(CONFIG_SMP),y) CSRCS += pthread_attr_getaffinity.c pthread_attr_setaffinity.c diff --git a/sched/Kconfig b/sched/Kconfig index 02096b268d..50613fb44d 100644 --- a/sched/Kconfig +++ b/sched/Kconfig @@ -573,12 +573,6 @@ config PTHREAD_MUTEX_DEFAULT_UNSAFE endchoice # Default NORMAL mutex robustness -config PTHREAD_RWLOCK - bool "Enable pthread rwlock API" - default n - ---help--- - Add supports for the rwlock interfaces - config NPTHREAD_KEYS int "Maximum number of pthread keys" default 4 -- GitLab From 19f19e31ebac2ed592f38c3a707878c6ac649e70 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 7 Apr 2017 08:13:18 -0600 Subject: [PATCH 374/990] 6loWPAN: Correct some list handling logic. --- net/sixlowpan/sixlowpan_framelist.c | 1 + wireless/ieee802154/mac802154_loopback.c | 16 +++++++++------- 2 files changed, 10 insertions(+), 7 deletions(-) diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c index 8995048b00..6aca006934 100644 --- a/net/sixlowpan/sixlowpan_framelist.c +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -425,6 +425,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, /* Add the next frame to the tail of the IOB queue */ qtail->io_flink = iob; + qtail = iob; /* Keep track of the total amount of data queue */ diff --git a/wireless/ieee802154/mac802154_loopback.c b/wireless/ieee802154/mac802154_loopback.c index 1f8dc4e8c3..9cb9f09641 100644 --- a/wireless/ieee802154/mac802154_loopback.c +++ b/wireless/ieee802154/mac802154_loopback.c @@ -185,23 +185,25 @@ static int lo_txpoll(FAR struct net_driver_s *dev) /* Find the tail of the IOB queue */ for (tail = NULL, iob = head; - iob != NULL; - tail = iob, iob = iob->io_flink); + iob != NULL; + tail = iob, iob = iob->io_flink); /* Loop while there frames to be sent, i.e., while the IOB list is not * emtpy. Sending, of course, just means relaying back through the network * for this driver. */ - while (!FRAME_IOB_EMPTY(&priv->lo_ieee)) + while (head != NULL) { /* Remove the IOB from the queue */ - FRAME_IOB_REMOVE(&priv->lo_ieee, iob); + iob = head; + head = iob->io_flink; + iob->io_flink = NULL; /* Is the queue now empty? */ - if (FRAME_IOB_EMPTY(&priv->lo_ieee)) + if (head == NULL) { tail = NULL; } @@ -239,8 +241,8 @@ static int lo_txpoll(FAR struct net_driver_s *dev) /* Find the new tail of the IOB queue */ for (tail = iob, iob = iob->io_flink; - iob != NULL; - tail = iob, iob = iob->io_flink); + iob != NULL; + tail = iob, iob = iob->io_flink); } priv->lo_txdone = true; -- GitLab From 47647eac8ffab8e66f32c8dfc079f17a731bfea0 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 7 Apr 2017 09:49:10 -0600 Subject: [PATCH 375/990] 6loWPAN: Correct some fragmentation handling --- net/sixlowpan/sixlowpan_framelist.c | 156 ++++++++++++++++++++++------ net/sixlowpan/sixlowpan_globals.c | 9 -- net/sixlowpan/sixlowpan_input.c | 30 +++--- net/sixlowpan/sixlowpan_internal.h | 9 -- 4 files changed, 139 insertions(+), 65 deletions(-) diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c index 6aca006934..994b7bfc7b 100644 --- a/net/sixlowpan/sixlowpan_framelist.c +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -101,17 +101,15 @@ * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ * * Input Parameters: - * ieee - Pointer to IEEE802.15.4 MAC driver structure. - * destip - Pointer to the IPv6 header to "compress" - * fptr - Pointer to the beginning of the frame under construction + * ipv6hdr - Pointer to the IPv6 header to "compress" + * fptr - Pointer to the beginning of the frame under construction * * Returned Value: * None * ****************************************************************************/ -static void sixlowpan_compress_ipv6hdr(FAR struct ieee802154_driver_s *ieee, - FAR const struct ipv6_hdr_s *destip, +static void sixlowpan_compress_ipv6hdr(FAR const struct ipv6_hdr_s *ipv6hdr, FAR uint8_t *fptr) { /* Indicate the IPv6 dispatch and length */ @@ -121,11 +119,93 @@ static void sixlowpan_compress_ipv6hdr(FAR struct ieee802154_driver_s *ieee, /* Copy the IPv6 header and adjust pointers */ - memcpy(&fptr[g_frame_hdrlen] , destip, IPv6_HDRLEN); + memcpy(&fptr[g_frame_hdrlen] , ipv6hdr, IPv6_HDRLEN); g_frame_hdrlen += IPv6_HDRLEN; g_uncomp_hdrlen += IPv6_HDRLEN; } +/**************************************************************************** + * Name: sixlowpan_copy_protohdr + * + * Description: + * The IPv6 header should have already been processed (as reflected in the + * g_uncomphdrlen). But we probably still need to copy the following + * protocol header. + * + * Input Parameters: + * ipv6hdr - Pointer to the IPv6 header to "compress" + * fptr - Pointer to the beginning of the frame under construction + * + * Returned Value: + * None. But g_frame_hdrlen and g_uncomp_hdrlen updated. + * + ****************************************************************************/ + +static void sixlowpan_copy_protohdr(FAR const struct ipv6_hdr_s *ipv6hdr, + FAR uint8_t *fptr) +{ + uint16_t combined; + uint16_t protosize; + uint16_t copysize; + + /* What is the total size of the IPv6 + protocol header? */ + + switch (ipv6hdr->proto) + { +#ifdef CONFIG_NET_TCP + case IP_PROTO_TCP: + combined = sizeof(struct ipv6tcp_hdr_s); + protosize = sizeof(struct tcp_hdr_s); + break; +#endif + +#ifdef CONFIG_NET_UDP + case IP_PROTO_UDP: + combined = sizeof(struct ipv6udp_hdr_s); + protosize = sizeof(struct udp_hdr_s); + break; +#endif + +#ifdef CONFIG_NET_ICMPv6 + case IP_PROTO_ICMP6: + combined = sizeof(struct ipv6icmp_hdr_s); + protosize = sizeof(struct icmpv6_hdr_s); + break; +#endif + + default: + nwarn("WARNING: Unrecognized proto: %u\n", ipv6hdr->proto); + combined = sizeof(struct ipv6_hdr_s); + protosize = 0; + break; + } + + /* Copy the remaining protocol header. */ + + if (g_uncomp_hdrlen > IPv6_HDRLEN) + { + nwarn("WARNING: Protocol header not copied: " + "g_uncomp_hdren=%u IPv6_HDRLEN=%u\n", + g_uncomp_hdrlen, IPv6_HDRLEN); + return; + } + + copysize = combined - g_uncomp_hdrlen; + if (copysize != protosize) + { + nwarn("WARNING: Protocol header size mismatch: " + "g_uncomp_hdren=%u copysize=%u protosize=%u\n", + g_uncomp_hdrlen, copysize, protosize); + return; + } + + memcpy(fptr + g_frame_hdrlen, (FAR uint8_t *)ipv6hdr + g_uncomp_hdrlen, + copysize); + + g_frame_hdrlen += copysize; + g_uncomp_hdrlen += copysize; +} + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -172,6 +252,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, FAR uint8_t *fptr; int framer_hdrlen; struct rimeaddr_s bcastmac; + uint16_t paysize; #ifdef CONFIG_NET_6LOWPAN_FRAG uint16_t outlen = 0; #endif @@ -267,7 +348,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, { /* Small.. use IPv6 dispatch (no compression) */ - sixlowpan_compress_ipv6hdr(ieee, destip, fptr); + sixlowpan_compress_ipv6hdr(destip, fptr); } ninfo("Header of length %d\n", g_frame_hdrlen); @@ -276,9 +357,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, /* Check if we need to fragment the packet into several frames */ - if ((int)buflen - (int)g_uncomp_hdrlen > - (int)CONFIG_NET_6LOWPAN_MAXPAYLOAD - framer_hdrlen - - (int)g_frame_hdrlen) + if (buflen > (CONFIG_NET_6LOWPAN_MAXPAYLOAD - g_frame_hdrlen)) { #ifdef CONFIG_NET_6LOWPAN_FRAG /* ieee->i_framelist will hold the generated frames; frames will be @@ -295,7 +374,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, * The following fragments contain only the fragn dispatch. */ - ninfo("Fragmentation sending packet length %d\n", buflen); + ninfo("Sending fragmented packet length %d\n", buflen); /* Create 1st Fragment */ /* Add the frame header using the pre-allocated IOB. */ @@ -325,25 +404,28 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, PUTINT16(fptr, RIME_FRAG_DISPATCH_SIZE, ((SIXLOWPAN_DISPATCH_FRAG1 << 8) | buflen)); + PUTINT16(fptr, RIME_FRAG_TAG, ieee->i_dgramtag); ieee->i_dgramtag++; - /* Copy payload and enqueue */ + g_frame_hdrlen += SIXLOWPAN_FRAG1_HDR_LEN; + + /* Copy protocol header that follows the IPv6 header */ - g_frame_hdrlen += SIXLOWPAN_FRAG1_HDR_LEN; - g_rime_payloadlen = - (CONFIG_NET_6LOWPAN_MAXPAYLOAD - framer_hdrlen - g_frame_hdrlen) & 0xf8; + sixlowpan_copy_protohdr(destip, fptr); + + /* Copy payload and enqueue */ - memcpy(fptr + g_frame_hdrlen, - (FAR uint8_t *)destip + g_uncomp_hdrlen, g_rime_payloadlen); - iob->io_len += g_rime_payloadlen + g_frame_hdrlen; + paysize = (CONFIG_NET_6LOWPAN_MAXPAYLOAD - g_frame_hdrlen) & 0xf8; + memcpy(fptr + g_frame_hdrlen, buf, paysize); /* Set outlen to what we already sent from the IP payload */ - outlen = g_rime_payloadlen + g_uncomp_hdrlen; + iob->io_len = paysize + g_frame_hdrlen; + outlen = paysize; ninfo("First fragment: length %d, tag %d\n", - g_rime_payloadlen, ieee->i_dgramtag); + paysize, ieee->i_dgramtag); sixlowpan_dumpbuffer("Outgoing frame", (FAR const uint8_t *)iob->io_data, iob->io_len); @@ -394,30 +476,33 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, PUTINT16(fptr, RIME_FRAG_TAG, ieee->i_dgramtag); fptr[RIME_FRAG_OFFSET] = outlen >> 3; + /* Copy protocol header that follows the IPv6 header */ + + sixlowpan_copy_protohdr(destip, fptr); + /* Copy payload and enqueue */ + /* Check for the last fragment */ - if (buflen - outlen < g_rime_payloadlen) + if (buflen - outlen < paysize) { - /* Last fragment */ + /* Last fragment, truncate to the correct length */ - g_rime_payloadlen = buflen - outlen; + paysize = buflen - outlen; } else { - g_rime_payloadlen = - (CONFIG_NET_6LOWPAN_MAXPAYLOAD - framer_hdrlen - g_frame_hdrlen) & 0xf8; + paysize = (CONFIG_NET_6LOWPAN_MAXPAYLOAD - g_frame_hdrlen) & 0xf8; } - memcpy(fptr + g_frame_hdrlen, (FAR uint8_t *)destip + outlen, - g_rime_payloadlen); - iob->io_len = g_rime_payloadlen + g_frame_hdrlen; + memcpy(fptr + g_frame_hdrlen, buf + outlen, paysize); /* Set outlen to what we already sent from the IP payload */ - outlen += (g_rime_payloadlen + g_uncomp_hdrlen); + iob->io_len = paysize + g_frame_hdrlen; + outlen += paysize; - ninfo("sixlowpan output: fragment offset %d, length %d, tag %d\n", - outlen >> 3, g_rime_payloadlen, ieee->i_dgramtag); + ninfo("Fragment offset %d, length %d, tag %d\n", + outlen >> 3, paysize, ieee->i_dgramtag); sixlowpan_dumpbuffer("Outgoing frame", (FAR const uint8_t *)iob->io_data, iob->io_len); @@ -453,11 +538,14 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, DEBUGASSERT(verify == framer_hdrlen); UNUSED(verify); + /* Copy protocol header that follows the IPv6 header */ + + sixlowpan_copy_protohdr(destip, fptr); + /* Copy the payload and queue */ - memcpy(fptr + g_frame_hdrlen, (FAR uint8_t *)destip + g_uncomp_hdrlen, - buflen - g_uncomp_hdrlen); - iob->io_len = buflen - g_uncomp_hdrlen + g_frame_hdrlen; + memcpy(fptr + g_frame_hdrlen, buf, buflen); + iob->io_len = buflen + g_frame_hdrlen; ninfo("Non-fragmented: length %d\n", iob->io_len); sixlowpan_dumpbuffer("Outgoing frame", diff --git a/net/sixlowpan/sixlowpan_globals.c b/net/sixlowpan/sixlowpan_globals.c index 8f48ade9f2..aac17f7eb9 100644 --- a/net/sixlowpan/sixlowpan_globals.c +++ b/net/sixlowpan/sixlowpan_globals.c @@ -54,15 +54,6 @@ * during that processing */ -/* The length of the payload in the Rime buffer. - * - * The payload is what comes after the compressed or uncompressed headers - * (can be the IP payload if the IP header only is compressed or the UDP - * payload if the UDP header is also compressed) - */ - -uint8_t g_rime_payloadlen; - /* g_uncomp_hdrlen is the length of the headers before compression (if HC2 * is used this includes the UDP header in addition to the IP header). */ diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index 257e7b48c9..95bb7c1cee 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -213,6 +213,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, FAR uint8_t *hc1; /* Convenience pointer to HC1 data */ uint16_t fragsize = 0; /* Size of the IP packet (read from fragment) */ + uint16_t paysize; /* Size of the data payload */ uint8_t fragoffset = 0; /* Offset of the fragment in the IP packet */ int reqsize; /* Required buffer size */ int hdrsize; /* Size of the IEEE802.15.4 header */ @@ -282,12 +283,12 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, fragtag = GETINT16(payptr, RIME_FRAG_TAG); fragsize = GETINT16(payptr, RIME_FRAG_DISPATCH_SIZE) & 0x07ff; - ninfo("FRAGN: size %d, tag %d, offset %d\n", + ninfo("FRAGN: size=%d tag=%d offset=%d\n", fragsize, fragtag, fragoffset); g_frame_hdrlen += SIXLOWPAN_FRAGN_HDR_LEN; - ninfo("FRAGN: i_accumlen %d g_rime_payloadlen %d fragsize %d\n", + ninfo("FRAGN: i_accumlen=%d paysize=%u fragsize=%u\n", ieee->i_accumlen, iob->io_len - g_frame_hdrlen, fragsize); /* Indicate that this frame is a another fragment for reassembly */ @@ -501,28 +502,28 @@ copypayload: * and g_frame_hdrlen are non-zerio, fragoffset is. */ - g_rime_payloadlen = iob->io_len - g_frame_hdrlen; - if (g_rime_payloadlen > CONFIG_NET_6LOWPAN_MTU) + paysize = iob->io_len - g_frame_hdrlen; + if (paysize > CONFIG_NET_6LOWPAN_MTU) { nwarn("WARNING: Packet dropped due to payload (%u) > packet buffer (%u)\n", - g_rime_payloadlen, CONFIG_NET_6LOWPAN_MTU); + paysize, CONFIG_NET_6LOWPAN_MTU); return OK; } /* Sanity-check size of incoming packet to avoid buffer overflow */ - reqsize = g_uncomp_hdrlen + (uint16_t) (fragoffset << 3) + g_rime_payloadlen; + reqsize = g_uncomp_hdrlen + (uint16_t) (fragoffset << 3) + paysize; if (reqsize > CONFIG_NET_6LOWPAN_MTU) { ninfo("Required buffer size: %d+%d+%d=%d Available: %d\n", - g_uncomp_hdrlen, (int)(fragoffset << 3), g_rime_payloadlen, + g_uncomp_hdrlen, (int)(fragoffset << 3), paysize, reqsize, CONFIG_NET_6LOWPAN_MTU); return -ENOMEM; } memcpy((FAR uint8_t *)ieee->i_dev.d_buf + g_uncomp_hdrlen + (int)(fragoffset << 3), payptr + g_frame_hdrlen, - g_rime_payloadlen); + paysize); #ifdef CONFIG_NET_6LOWPAN_FRAG /* Update ieee->i_accumlen if the frame is a fragment, ieee->i_pktlen @@ -548,15 +549,14 @@ copypayload: } else { - ieee->i_accumlen += g_rime_payloadlen; + ieee->i_accumlen += paysize; } - ninfo("i_accumlen %d, g_rime_payloadlen %d\n", - ieee->i_accumlen, g_rime_payloadlen); + ninfo("i_accumlen %d, paysize %d\n", ieee->i_accumlen, paysize); } else { - ieee->i_pktlen = g_rime_payloadlen + g_uncomp_hdrlen; + ieee->i_pktlen = paysize + g_uncomp_hdrlen; } /* If we have a full IP packet in sixlowpan_buf, deliver it to @@ -580,7 +580,7 @@ copypayload: #else /* Deliver the packet to the IP stack */ - ieee->i_dev.d_len = g_rime_payloadlen + g_uncomp_hdrlen; + ieee->i_dev.d_len = paysize + g_uncomp_hdrlen; return INPUT_COMPLETE; #endif /* CONFIG_NET_6LOWPAN_FRAG */ } @@ -706,6 +706,10 @@ int sixlowpan_input(FAR struct ieee802154_driver_s *ieee) ret = sixlowpan_frame_process(ieee, iob); + /* Free the IOB the held the consumed frame */ + + iob_free(iob); + /* Was the frame successfully processed? Is the packet in d_buf fully * reassembled? */ diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index d6a795c554..bd366c884e 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -409,15 +409,6 @@ struct frame802154_s extern FAR uint8_t *g_rimeptr; -/* The length of the payload in the Rime buffer. - * - * The payload is what comes after the compressed or uncompressed headers - * (can be the IP payload if the IP header only is compressed or the UDP - * payload if the UDP header is also compressed) - */ - -extern uint8_t g_rime_payloadlen; - /* g_uncomp_hdrlen is the length of the headers before compression (if HC2 * is used this includes the UDP header in addition to the IP header). */ -- GitLab From f264e6aec261c6f4996ba2ea2a990f13302eb750 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 7 Apr 2017 15:27:53 -0600 Subject: [PATCH 376/990] 6loWPAN: Fixes for fragmented packets. Change fixes some things, breaks other. Lots more to do. --- include/nuttx/net/sixlowpan.h | 8 +- net/sixlowpan/sixlowpan_framelist.c | 65 ++++++----- net/sixlowpan/sixlowpan_input.c | 168 +++++++++++++--------------- net/sixlowpan/sixlowpan_tcpsend.c | 7 +- 4 files changed, 127 insertions(+), 121 deletions(-) diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index 0211d17ce6..04b69da604 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -80,7 +80,7 @@ #define SIXLOWPAN_DISPATCH_FRAG1 0xc0 /* 11000xxx */ #define SIXLOWPAN_DISPATCH_FRAGN 0xe0 /* 11100xxx */ -#define SIXLOWPAN_DISPATCH_FRAG_MASK 0xf1 /* 11111000 */ +#define SIXLOWPAN_DISPATCH_FRAG_MASK 0xf8 /* 11111000 */ /* HC1 encoding */ @@ -398,6 +398,12 @@ struct ieee802154_driver_s uint16_t i_reasstag; + /* i_boffset. Offset to the beginning of data in d_buf. As each fragment + * is received, data is placed at an appriate offset added to this. + */ + + uint16_t i_boffset; + /* The source MAC address of the fragments being merged */ struct rimeaddr_s i_fragsrc; diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c index 994b7bfc7b..8d8900460f 100644 --- a/net/sixlowpan/sixlowpan_framelist.c +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -202,8 +202,8 @@ static void sixlowpan_copy_protohdr(FAR const struct ipv6_hdr_s *ipv6hdr, memcpy(fptr + g_frame_hdrlen, (FAR uint8_t *)ipv6hdr + g_uncomp_hdrlen, copysize); - g_frame_hdrlen += copysize; - g_uncomp_hdrlen += copysize; + g_frame_hdrlen += copysize; + g_uncomp_hdrlen += copysize; } /**************************************************************************** @@ -252,6 +252,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, FAR uint8_t *fptr; int framer_hdrlen; struct rimeaddr_s bcastmac; + uint16_t pktlen; uint16_t paysize; #ifdef CONFIG_NET_6LOWPAN_FRAG uint16_t outlen = 0; @@ -365,6 +366,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, */ FAR struct iob_s *qtail; + FAR uint8_t *frame1; int verify; /* The outbound IPv6 packet is too large to fit into a single 15.4 @@ -383,7 +385,9 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, DEBUGASSERT(verify == framer_hdrlen); UNUSED(verify); - /* Move HC1/HC06/IPv6 header */ + /* Move HC1/HC06/IPv6 header to make space for the FRAG1 header at the + * beginning of the frame. + */ memmove(fptr + SIXLOWPAN_FRAG1_HDR_LEN, fptr, g_frame_hdrlen); @@ -402,11 +406,10 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, * bytes for all subsequent headers. */ + pktlen = buflen + g_uncomp_hdrlen; PUTINT16(fptr, RIME_FRAG_DISPATCH_SIZE, - ((SIXLOWPAN_DISPATCH_FRAG1 << 8) | buflen)); - + ((SIXLOWPAN_DISPATCH_FRAG1 << 8) | pktlen)); PUTINT16(fptr, RIME_FRAG_TAG, ieee->i_dgramtag); - ieee->i_dgramtag++; g_frame_hdrlen += SIXLOWPAN_FRAG1_HDR_LEN; @@ -414,9 +417,11 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, sixlowpan_copy_protohdr(destip, fptr); - /* Copy payload and enqueue */ + /* Copy payload and enqueue. NOTE that the size is a multiple of eight + * bytes. + */ - paysize = (CONFIG_NET_6LOWPAN_MAXPAYLOAD - g_frame_hdrlen) & 0xf8; + paysize = (CONFIG_NET_6LOWPAN_MAXPAYLOAD - g_frame_hdrlen) & ~7; memcpy(fptr + g_frame_hdrlen, buf, paysize); /* Set outlen to what we already sent from the IP payload */ @@ -440,10 +445,11 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, /* Create following fragments */ - g_frame_hdrlen = SIXLOWPAN_FRAGN_HDR_LEN; - + frame1 = iob->io_data; while (outlen < buflen) { + uint16_t fragn_hdrlen; + /* Allocate an IOB to hold the next fragment, waiting if * necessary. */ @@ -459,49 +465,44 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, iob->io_pktlen = 0; fptr = iob->io_data; - /* Add the frame header */ - - verify = sixlowpan_framecreate(ieee, iob, ieee->i_panid); - DEBUGASSERT(verify == framer_hdrlen); - UNUSED(verify); - - /* Move HC1/HC06/IPv6 header */ + /* Copy the frame header from first frame, into the correct + * location after the FRAGN header. + */ - memmove(fptr + SIXLOWPAN_FRAGN_HDR_LEN, fptr, g_frame_hdrlen); + memmove(fptr + SIXLOWPAN_FRAGN_HDR_LEN, + frame1 + SIXLOWPAN_FRAG1_HDR_LEN, + framer_hdrlen); + fragn_hdrlen = framer_hdrlen; - /* Setup up the fragment header */ + /* Setup up the FRAGN header at the beginning of the frame */ PUTINT16(fptr, RIME_FRAG_DISPATCH_SIZE, - ((SIXLOWPAN_DISPATCH_FRAGN << 8) | buflen)); + ((SIXLOWPAN_DISPATCH_FRAGN << 8) | pktlen)); PUTINT16(fptr, RIME_FRAG_TAG, ieee->i_dgramtag); fptr[RIME_FRAG_OFFSET] = outlen >> 3; - /* Copy protocol header that follows the IPv6 header */ - - sixlowpan_copy_protohdr(destip, fptr); + fragn_hdrlen += SIXLOWPAN_FRAGN_HDR_LEN; /* Copy payload and enqueue */ /* Check for the last fragment */ + paysize = (CONFIG_NET_6LOWPAN_MAXPAYLOAD - fragn_hdrlen) & + SIXLOWPAN_DISPATCH_FRAG_MASK; if (buflen - outlen < paysize) { /* Last fragment, truncate to the correct length */ paysize = buflen - outlen; } - else - { - paysize = (CONFIG_NET_6LOWPAN_MAXPAYLOAD - g_frame_hdrlen) & 0xf8; - } - memcpy(fptr + g_frame_hdrlen, buf + outlen, paysize); + memcpy(fptr + fragn_hdrlen, buf + outlen, paysize); /* Set outlen to what we already sent from the IP payload */ - iob->io_len = paysize + g_frame_hdrlen; + iob->io_len = paysize + fragn_hdrlen; outlen += paysize; - ninfo("Fragment offset %d, length %d, tag %d\n", + ninfo("Fragment offset=%d, paysize=%d, i_dgramtag=%d\n", outlen >> 3, paysize, ieee->i_dgramtag); sixlowpan_dumpbuffer("Outgoing frame", (FAR const uint8_t *)iob->io_data, @@ -516,6 +517,10 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, ieee->i_framelist->io_pktlen += iob->io_len; } + + /* Update the datagram TAG value */ + + ieee->i_dgramtag++; #else nerr("ERROR: Packet too large: %d\n", buflen); nerr(" Cannot to be sent without fragmentation support\n"); diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index 95bb7c1cee..7144d36e8b 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -111,12 +111,26 @@ int sixlowpan_recv_hdrlen(FAR const uint8_t *fptr) { - uint16_t hdrlen; + uint16_t hdrlen = 0; uint8_t addrmode; + uint8_t tmp; + + /* Check for a fragment header preceding the IEEE802.15.4 FCF */ + + tmp = *fptr & SIXLOWPAN_DISPATCH_FRAG_MASK; + if (tmp == SIXLOWPAN_DISPATCH_FRAG1) + { + hdrlen += SIXLOWPAN_FRAG1_HDR_LEN; + } + else if (tmp == SIXLOWPAN_DISPATCH_FRAGN) + { + hdrlen += SIXLOWPAN_FRAGN_HDR_LEN; + } /* Minimum header: 2 byte FCF + 1 byte sequence number */ - hdrlen = 3; + fptr += hdrlen; + hdrlen += 3; /* Account for destination address size */ @@ -209,9 +223,7 @@ int sixlowpan_recv_hdrlen(FAR const uint8_t *fptr) static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, FAR struct iob_s *iob) { - FAR uint8_t *payptr; /* Pointer to the frame payload */ FAR uint8_t *hc1; /* Convenience pointer to HC1 data */ - uint16_t fragsize = 0; /* Size of the IP packet (read from fragment) */ uint16_t paysize; /* Size of the data payload */ uint8_t fragoffset = 0; /* Offset of the fragment in the IP packet */ @@ -221,12 +233,13 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, #ifdef CONFIG_NET_6LOWPAN_FRAG bool isfrag = false; bool isfirstfrag = false; - bool islastfrag = false; uint16_t fragtag = 0; /* Tag of the fragment */ systime_t elapsed; /* Elapsed time */ #endif /* CONFIG_NET_6LOWPAN_FRAG */ - /* Get a pointer to the payload following the IEEE802.15.4 frame header. */ + /* Get a pointer to the payload following the IEEE802.15.4 frame header(s). + * This size includes both fragmentation and FCF headers. + */ hdrsize = sixlowpan_recv_hdrlen(iob->io_data); if (hdrsize < 0) @@ -242,16 +255,13 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, g_uncomp_hdrlen = 0; g_frame_hdrlen = hdrsize; - /* Payload starts after the IEEE802.15.4 header */ - - payptr = &iob->io_data[hdrsize]; - #ifdef CONFIG_NET_6LOWPAN_FRAG /* Since we don't support the mesh and broadcast header, the first header - * we look for is the fragmentation header + * we look for is the fragmentation header. NOTE that g_frame_hdrlen + * already includes the fragementation header, if presetn. */ - switch ((GETINT16(payptr, RIME_FRAG_DISPATCH_SIZE) & 0xf800) >> 8) + switch ((GETINT16(iob->io_data, RIME_FRAG_DISPATCH_SIZE) & 0xf800) >> 8) { /* First fragment of new reassembly */ @@ -259,15 +269,12 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, { /* Set up for the reassembly */ - fragoffset = 0; - fragsize = GETINT16(payptr, RIME_FRAG_DISPATCH_SIZE) & 0x07ff; - fragtag = GETINT16(payptr, RIME_FRAG_TAG); + fragsize = GETINT16(iob->io_data, RIME_FRAG_DISPATCH_SIZE) & 0x07ff; + fragtag = GETINT16(iob->io_data, RIME_FRAG_TAG); - ninfo("FRAG1: size %d, tag %d, offset %d\n", + ninfo("FRAG1: fragsize=%d fragtag=%d fragoffset=%d\n", fragsize, fragtag, fragoffset); - g_frame_hdrlen += SIXLOWPAN_FRAG1_HDR_LEN; - /* Indicate the first fragment of the reassembly */ isfirstfrag = true; @@ -279,32 +286,18 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, { /* Set offset, tag, size. Offset is in units of 8 bytes. */ - fragoffset = payptr[RIME_FRAG_OFFSET]; - fragtag = GETINT16(payptr, RIME_FRAG_TAG); - fragsize = GETINT16(payptr, RIME_FRAG_DISPATCH_SIZE) & 0x07ff; + fragoffset = iob->io_data[RIME_FRAG_OFFSET]; + fragtag = GETINT16(iob->io_data, RIME_FRAG_TAG); + fragsize = GETINT16(iob->io_data, RIME_FRAG_DISPATCH_SIZE) & 0x07ff; - ninfo("FRAGN: size=%d tag=%d offset=%d\n", + ninfo("FRAGN: fragsize=%d fragtag=%d fragoffset=%d\n", fragsize, fragtag, fragoffset); - - g_frame_hdrlen += SIXLOWPAN_FRAGN_HDR_LEN; - ninfo("FRAGN: i_accumlen=%d paysize=%u fragsize=%u\n", ieee->i_accumlen, iob->io_len - g_frame_hdrlen, fragsize); /* Indicate that this frame is a another fragment for reassembly */ isfrag = true; - - /* Check if it is the last fragement to be processed. - * - * If this is the last fragment, we may shave off any extrenous - * bytes at the end. We must be liberal in what we accept. - */ - - if (ieee->i_accumlen + iob->io_len - g_frame_hdrlen >= fragsize) - { - islastfrag = true; - } } break; @@ -393,6 +386,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, * compression dispatch logic. */ + g_uncomp_hdrlen = ieee->i_boffset; goto copypayload; } } @@ -413,29 +407,22 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, return OK; } - /* Start reassembly if we received a non-zero length, first fragment */ + /* Drop the packet if it cannot fit into the d_buf */ - if (fragsize > 0) + if (fragsize > CONFIG_NET_6LOWPAN_MTU) { - /* Drop the packet if it cannot fit into the d_buf */ - - if (fragsize > CONFIG_NET_6LOWPAN_MTU) - { - nwarn("WARNING: Reassembled packet size exeeds CONFIG_NET_6LOWPAN_MTU\n"); - return OK; - } - - /* Set up for the reassembly */ + nwarn("WARNING: Reassembled packet size exeeds CONFIG_NET_6LOWPAN_MTU\n"); + return OK; + } - ieee->i_pktlen = fragsize; - ieee->i_reasstag = fragtag; - ieee->i_time = clock_systimer(); + ieee->i_pktlen = fragsize; + ieee->i_reasstag = fragtag; + ieee->i_time = clock_systimer(); - ninfo("Starting reassembly: i_pktlen %d, i_pktlen %d\n", - ieee->i_pktlen, ieee->i_reasstag); + ninfo("Starting reassembly: i_pktlen %u, i_reasstag %d\n", + ieee->i_pktlen, ieee->i_reasstag); - rimeaddr_copy(&ieee->i_fragsrc, &g_pktaddrs[PACKETBUF_ADDR_SENDER]); - } + rimeaddr_copy(&ieee->i_fragsrc, &g_pktaddrs[PACKETBUF_ADDR_SENDER]); } #endif /* CONFIG_NET_6LOWPAN_FRAG */ @@ -446,7 +433,13 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 if ((hc1[RIME_HC1_DISPATCH] & SIXLOWPAN_DISPATCH_IPHC_MASK) == SIXLOWPAN_DISPATCH_IPHC) { + FAR uint8_t *payptr; + ninfo("IPHC Dispatch\n"); + + /* Payload starts after the IEEE802.15.4 header(s) */ + + payptr = &iob->io_data[g_frame_hdrlen]; sixlowpan_uncompresshdr_hc06(ieee, fragsize, iob, payptr); } else @@ -455,7 +448,13 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC1 if (hc1[RIME_HC1_DISPATCH] == SIXLOWPAN_DISPATCH_HC1) { + FAR uint8_t *payptr; + ninfo("HC1 Dispatch\n"); + + /* Payload starts after the IEEE802.15.4 header(s) */ + + payptr = &iob->io_data[g_frame_hdrlen]; sixlowpan_uncompresshdr_hc1(ieee, fragsize, iob, payptr); } else @@ -468,16 +467,9 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, ninfo("IPv6 Dispatch\n"); g_frame_hdrlen += SIXLOWPAN_IPV6_HDR_LEN; - /* payptr was set up to begin just after the IPHC bytes. However, - * those bytes are not present for the case of IPv6 dispatch. Just - * reset back to the begnning of the buffer. - */ - - payptr = iob->io_data; - /* Put uncompressed IP header in d_buf. */ - memcpy(ipv6, payptr + g_frame_hdrlen, IPv6_HDRLEN); + memcpy(ipv6, iob->io_data + g_frame_hdrlen, IPv6_HDRLEN); /* Update g_uncomp_hdrlen and g_frame_hdrlen. */ @@ -493,6 +485,18 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, } #ifdef CONFIG_NET_6LOWPAN_FRAG + /* Non-fragmented and FRAG1 frames pass through here. Remember the + * offset from the beginning of d_buf where be begin placing the data + * payload. + */ + + if (isfirstfrag) + { + ieee->i_boffset = g_uncomp_hdrlen; + } + + /* We branch to here on all good FRAGN frames */ + copypayload: #endif /* CONFIG_NET_6LOWPAN_FRAG */ @@ -512,17 +516,17 @@ copypayload: /* Sanity-check size of incoming packet to avoid buffer overflow */ - reqsize = g_uncomp_hdrlen + (uint16_t) (fragoffset << 3) + paysize; + reqsize = g_uncomp_hdrlen + (fragoffset << 3) + paysize; if (reqsize > CONFIG_NET_6LOWPAN_MTU) { - ninfo("Required buffer size: %d+%d+%d=%d Available: %d\n", - g_uncomp_hdrlen, (int)(fragoffset << 3), paysize, + ninfo("Required buffer size: %u+%u+%u=%u Available=%u\n", + g_uncomp_hdrlen, (fragoffset << 3), paysize, reqsize, CONFIG_NET_6LOWPAN_MTU); return -ENOMEM; } - memcpy((FAR uint8_t *)ieee->i_dev.d_buf + g_uncomp_hdrlen + - (int)(fragoffset << 3), payptr + g_frame_hdrlen, + memcpy(ieee->i_dev.d_buf + g_uncomp_hdrlen + (fragoffset << 3), + iob->io_data + g_frame_hdrlen, paysize); #ifdef CONFIG_NET_6LOWPAN_FRAG @@ -532,27 +536,13 @@ copypayload: if (isfrag) { - /* Add the size of the header only for the first fragment. */ - - if (isfirstfrag) - { - ieee->i_accumlen += g_uncomp_hdrlen; - } - - /* For the last fragment, we are OK if there is extraneous bytes at the - * end of the packet. + /* Check if it is the last fragment to be processed. + * + * If this is the last fragment, we may shave off any extrenous + * bytes at the end. We must be liberal in what we accept. */ - if (islastfrag) - { - ieee->i_accumlen = fragsize; - } - else - { - ieee->i_accumlen += paysize; - } - - ninfo("i_accumlen %d, paysize %d\n", ieee->i_accumlen, paysize); + ieee->i_accumlen = g_uncomp_hdrlen + (fragoffset << 3) + paysize; } else { @@ -563,10 +553,10 @@ copypayload: * the IP stack */ - ninfo("sixlowpan_init i_accumlen %d, ieee->i_pktlen %d\n", - ieee->i_accumlen, ieee->i_pktlen); + ninfo("i_accumlen=%d i_pktlen=%d paysize=%d\n", + ieee->i_accumlen, ieee->i_pktlen, paysize); - if (ieee->i_accumlen == 0 || ieee->i_accumlen == ieee->i_pktlen) + if (ieee->i_accumlen == 0 || ieee->i_accumlen >= ieee->i_pktlen) { ninfo("IP packet ready (length %d)\n", ieee->i_pktlen); diff --git a/net/sixlowpan/sixlowpan_tcpsend.c b/net/sixlowpan/sixlowpan_tcpsend.c index a34bfe0666..a1a4a5847b 100644 --- a/net/sixlowpan/sixlowpan_tcpsend.c +++ b/net/sixlowpan/sixlowpan_tcpsend.c @@ -403,6 +403,8 @@ void sixlowpan_tcp_send(FAR struct net_driver_s *dev) else { struct rimeaddr_s destmac; + FAR uint8_t *buf; + size_t buflen; /* Get the Rime MAC address of the destination. This assumes an * encoding of the MAC address in the IPv6 address. @@ -412,9 +414,12 @@ void sixlowpan_tcp_send(FAR struct net_driver_s *dev) /* Convert the outgoing packet into a frame list. */ + buf = dev->d_buf + sizeof(struct ipv6_hdr_s); + buflen = dev->d_len - sizeof(struct ipv6_hdr_s); + (void)sixlowpan_queue_frames( (FAR struct ieee802154_driver_s *)dev, ipv6hdr, - dev->d_buf, dev->d_len, &destmac); + buf, buflen, &destmac); } } -- GitLab From 2b1ca79b4b2549f63df9b1c77138e9ef1c848ee4 Mon Sep 17 00:00:00 2001 From: Mark Schulte Date: Fri, 7 Apr 2017 15:45:24 -0600 Subject: [PATCH 377/990] pthread rwlock bugfixes --- include/pthread.h | 1 + libc/pthread/pthread_rwlock.c | 9 +++++---- libc/pthread/pthread_rwlock_rdlock.c | 2 +- libc/pthread/pthread_rwlock_wrlock.c | 27 +++++++++++++++++++++------ 4 files changed, 28 insertions(+), 11 deletions(-) diff --git a/include/pthread.h b/include/pthread.h index be555fed75..a75cd9e901 100644 --- a/include/pthread.h +++ b/include/pthread.h @@ -343,6 +343,7 @@ struct pthread_rwlock_s pthread_cond_t cv; unsigned int num_readers; unsigned int num_writers; + bool write_in_progress; }; typedef struct pthread_rwlock_s pthread_rwlock_t; diff --git a/libc/pthread/pthread_rwlock.c b/libc/pthread/pthread_rwlock.c index 3f902089b0..b40b655b26 100644 --- a/libc/pthread/pthread_rwlock.c +++ b/libc/pthread/pthread_rwlock.c @@ -60,8 +60,9 @@ int pthread_rwlock_init(FAR pthread_rwlock_t *lock, return -ENOSYS; } - lock->num_readers = 0; - lock->num_writers = 0; + lock->num_readers = 0; + lock->num_writers = 0; + lock->write_in_progress = false; err = pthread_cond_init(&lock->cv, NULL); if (err != 0) @@ -111,9 +112,9 @@ int pthread_rwlock_unlock(FAR pthread_rwlock_t *rw_lock) err = pthread_cond_broadcast(&rw_lock->cv); } } - else if (rw_lock->num_writers > 0) + else if (rw_lock->write_in_progress) { - rw_lock->num_writers--; + rw_lock->write_in_progress = false; err = pthread_cond_broadcast(&rw_lock->cv); } diff --git a/libc/pthread/pthread_rwlock_rdlock.c b/libc/pthread/pthread_rwlock_rdlock.c index 6270d2bbe4..9fd461a758 100644 --- a/libc/pthread/pthread_rwlock_rdlock.c +++ b/libc/pthread/pthread_rwlock_rdlock.c @@ -54,7 +54,7 @@ static int tryrdlock(FAR pthread_rwlock_t *rw_lock) { int err; - if (rw_lock->num_writers > 0) + if (rw_lock->num_writers > 0 || rw_lock->write_in_progress) { err = EBUSY; } diff --git a/libc/pthread/pthread_rwlock_wrlock.c b/libc/pthread/pthread_rwlock_wrlock.c index dc2d155021..ecda4cb25b 100644 --- a/libc/pthread/pthread_rwlock_wrlock.c +++ b/libc/pthread/pthread_rwlock_wrlock.c @@ -75,13 +75,13 @@ int pthread_rwlock_trywrlock(FAR pthread_rwlock_t *rw_lock) return err; } - if (rw_lock->num_readers > 0 || rw_lock->num_writers > 0) + if (rw_lock->num_readers > 0 || rw_lock->write_in_progress) { err = EBUSY; } else { - rw_lock->num_writers++; + rw_lock->write_in_progress = true; } pthread_mutex_unlock(&rw_lock->lock); @@ -92,20 +92,21 @@ int pthread_rwlock_timedwrlock(FAR pthread_rwlock_t *rw_lock, FAR const struct timespec *ts) { int err = pthread_mutex_lock(&rw_lock->lock); - int num_writers_current; if (err != 0) { return err; } - num_writers_current = rw_lock->num_writers++; - if (num_writers_current == 0) + if (rw_lock->num_writers == UINT_MAX) { + err = EAGAIN; goto exit_with_mutex; } - while (rw_lock->num_writers != num_writers_current) + rw_lock->num_writers++; + + while (rw_lock->write_in_progress || rw_lock->num_readers > 0) { if (ts != NULL) { @@ -122,6 +123,20 @@ int pthread_rwlock_timedwrlock(FAR pthread_rwlock_t *rw_lock, } } + if (err == 0) + { + rw_lock->write_in_progress = true; + } + + else + { + /* In case of error, notify any blocked readers. */ + + (void) pthread_cond_broadcast(&rw_lock->cv); + } + + rw_lock->num_writers--; + exit_with_mutex: pthread_mutex_unlock(&rw_lock->lock); return err; -- GitLab From 60f018625896740015f334d7a7ba42cfaa8364c8 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 7 Apr 2017 17:04:57 -0600 Subject: [PATCH 378/990] 6loWPAN: Add calculation of TCP header size. It is not a constant. --- net/sixlowpan/sixlowpan_framelist.c | 18 +++++++--- net/sixlowpan/sixlowpan_input.c | 13 +++++-- net/sixlowpan/sixlowpan_tcpsend.c | 53 +++++++++++++++++++++-------- 3 files changed, 63 insertions(+), 21 deletions(-) diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c index 8d8900460f..552f394b78 100644 --- a/net/sixlowpan/sixlowpan_framelist.c +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -154,29 +154,37 @@ static void sixlowpan_copy_protohdr(FAR const struct ipv6_hdr_s *ipv6hdr, { #ifdef CONFIG_NET_TCP case IP_PROTO_TCP: - combined = sizeof(struct ipv6tcp_hdr_s); - protosize = sizeof(struct tcp_hdr_s); + { + FAR struct tcp_hdr_s *tcp = &((FAR struct ipv6tcp_hdr_s *)ipv6hdr)->tcp; + + /* The TCP header length is encoded in the top 4 bits of the + * tcpoffset field (in units of 32-bit words). + */ + + protosize = ((uint16_t)tcp->tcpoffset >> 4) << 2; + combined = sizeof(struct ipv6_hdr_s) + protosize; + } break; #endif #ifdef CONFIG_NET_UDP case IP_PROTO_UDP: - combined = sizeof(struct ipv6udp_hdr_s); protosize = sizeof(struct udp_hdr_s); + combined = sizeof(struct ipv6udp_hdr_s); break; #endif #ifdef CONFIG_NET_ICMPv6 case IP_PROTO_ICMP6: - combined = sizeof(struct ipv6icmp_hdr_s); protosize = sizeof(struct icmpv6_hdr_s); + combined = sizeof(struct ipv6icmp_hdr_s); break; #endif default: nwarn("WARNING: Unrecognized proto: %u\n", ipv6hdr->proto); - combined = sizeof(struct ipv6_hdr_s); protosize = 0; + combined = sizeof(struct ipv6_hdr_s); break; } diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index 7144d36e8b..6098a58251 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -86,6 +86,7 @@ /* Buffer access helpers */ #define IPv6BUF(dev) ((FAR struct ipv6_hdr_s *)((dev)->d_buf)) +#define TCPBUF(dev) ((FAR struct tcp_hdr_s *)&(dev)->d_buf[IPv6_HDRLEN]) /**************************************************************************** * Private Functions @@ -728,7 +729,7 @@ int sixlowpan_input(FAR struct ieee802154_driver_s *ieee) * layer protocol header. */ - ipv6hdr = (FAR struct ipv6_hdr_s *)(ieee->i_dev.d_buf); + ipv6hdr = IPv6BUF(&ieee->i_dev); /* Get the Rime MAC address of the destination. This * assumes an encoding of the MAC address in the IPv6 @@ -743,7 +744,15 @@ int sixlowpan_input(FAR struct ieee802154_driver_s *ieee) if (ipv6hdr->proto != IP_PROTO_TCP) { - hdrlen = IPv6_HDRLEN + TCP_HDRLEN; + FAR struct tcp_hdr_s *tcp = TCPBUF(&ieee->i_dev); + uint16_t tcplen; + + /* The TCP header length is encoded in the top 4 bits + * of the tcpoffset field (in units of 32-bit words). + */ + + tcplen = ((uint16_t)tcp->tcpoffset >> 4) << 2; + hdrlen = IPv6_HDRLEN + tcplen; } else if (ipv6hdr->proto != IP_PROTO_UDP) { diff --git a/net/sixlowpan/sixlowpan_tcpsend.c b/net/sixlowpan/sixlowpan_tcpsend.c index a1a4a5847b..3ee39e72ed 100644 --- a/net/sixlowpan/sixlowpan_tcpsend.c +++ b/net/sixlowpan/sixlowpan_tcpsend.c @@ -88,6 +88,7 @@ static uint16_t sixlowpan_tcp_chksum(FAR struct ipv6tcp_hdr_s *ipv6tcp, FAR const uint8_t *buf, uint16_t buflen) { uint16_t upperlen; + uint16_t tcplen; uint16_t sum; /* The length reported in the IPv6 header is the length of the payload @@ -115,9 +116,14 @@ static uint16_t sixlowpan_tcp_chksum(FAR struct ipv6tcp_hdr_s *ipv6tcp, sum = chksum(sum, (FAR uint8_t *)ipv6tcp->ipv6.srcipaddr, 2 * sizeof(net_ipv6addr_t)); - /* Sum the TCP header */ + /* Sum the TCP header + * + * The TCP header length is encoded in the top 4 bits of the tcpoffset + * field (in units of 32-bit words). + */ - sum = chksum(sum, (FAR uint8_t *)&ipv6tcp->tcp, TCP_HDRLEN); + tcplen = ((uint16_t)ipv6tcp->tcp.tcpoffset >> 4) << 2; + sum = chksum(sum, (FAR uint8_t *)&ipv6tcp->tcp, tcplen); /* Sum payload data. */ @@ -383,43 +389,62 @@ void sixlowpan_tcp_send(FAR struct net_driver_s *dev) if (dev != NULL && dev->d_len > 0) { - FAR struct ipv6_hdr_s *ipv6hdr; + FAR struct ipv6tcp_hdr_s *ipv6hdr; /* The IPv6 header followed by a TCP headers should lie at the * beginning of d_buf since there is no link layer protocol header * and the TCP state machine should only response with TCP packets. */ - ipv6hdr = (FAR struct ipv6_hdr_s *)(dev->d_buf); + ipv6hdr = (FAR struct ipv6tcp_hdr_s *)(dev->d_buf); /* The TCP data payload should follow the IPv6 header plus the * protocol header. */ - if (ipv6hdr->proto != IP_PROTO_TCP) + if (ipv6hdr->ipv6.proto != IP_PROTO_TCP) { - nwarn("WARNING: Expected TCP protoype: %u\n", ipv6hdr->proto); + nwarn("WARNING: Expected TCP protoype: %u vs %s\n", + ipv6hdr->ipv6.proto, IP_PROTO_TCP); } else { struct rimeaddr_s destmac; FAR uint8_t *buf; - size_t buflen; + uint16_t hdrlen; + uint16_t buflen; /* Get the Rime MAC address of the destination. This assumes an * encoding of the MAC address in the IPv6 address. */ - sixlowpan_rimefromip(ipv6hdr->destipaddr, &destmac); + sixlowpan_rimefromip(ipv6hdr->ipv6.destipaddr, &destmac); + + /* Get the IPv6 + TCP combined header length. The size of the TCP + * header is encoded in the top 4 bits of the tcpoffset field (in + * units of 32-bit words). + */ + + hdrlen = IPv6_HDRLEN + (((uint16_t)ipv6hdr->tcp.tcpoffset >> 4) << 2); + + /* Drop the packet if the buffer length is less than this. */ - /* Convert the outgoing packet into a frame list. */ + if (hdrlen > dev->d_len) + { + nwarn("WARNING: Dropping small TCP packet: %u < %u\n", + buflen, hdrlen); + } + else + { + /* Convert the outgoing packet into a frame list. */ - buf = dev->d_buf + sizeof(struct ipv6_hdr_s); - buflen = dev->d_len - sizeof(struct ipv6_hdr_s); + buf = dev->d_buf + hdrlen; + buflen = dev->d_len - hdrlen; - (void)sixlowpan_queue_frames( - (FAR struct ieee802154_driver_s *)dev, ipv6hdr, - buf, buflen, &destmac); + (void)sixlowpan_queue_frames( + (FAR struct ieee802154_driver_s *)dev, &ipv6hdr->ipv6, + buf, buflen, &destmac); + } } } -- GitLab From ee6700dbc7556a3ca7c2f2c00cd6554ce713f700 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 8 Apr 2017 07:30:20 -0600 Subject: [PATCH 379/990] Update README's and some comments. --- Documentation/README.html | 4 +++- README.txt | 2 ++ include/nuttx/net/sixlowpan.h | 26 ++++++++++++++++++-------- net/sixlowpan/README.txt | 30 ++++++++++++++++++++++++++++++ 4 files changed, 53 insertions(+), 9 deletions(-) create mode 100644 net/sixlowpan/README.txt diff --git a/Documentation/README.html b/Documentation/README.html index 01a27ce644..8cc093715d 100644 --- a/Documentation/README.html +++ b/Documentation/README.html @@ -8,7 +8,7 @@

NuttX README Files

-

Last Updated: March 23, 2017

+

Last Updated: April 8, 2017

@@ -362,6 +362,8 @@ nuttx/ | | `- README.txt | `- README.txt |- net/ + | |- sixlowpan/ + | | `- README.txt | `- README.txt |- syscall/ | `- README.txt diff --git a/README.txt b/README.txt index 5d3721f4c5..af17a2334d 100644 --- a/README.txt +++ b/README.txt @@ -1750,6 +1750,8 @@ nuttx/ | | `- README.txt | `- README.txt |- net/ + | |- sixlowpan + | | `- README.txt | `- README.txt |- syscall/ | `- README.txt diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index 04b69da604..dfc8a13a76 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -376,28 +376,38 @@ struct ieee802154_driver_s /* i_dgramtag. Datagram tag to be put in the header of the set of * fragments. It is used by the recipient to match fragments of the * same payload. + * + * This is the sender's copy of the tag. It is incremented after each + * fragmented packet is sent so that it will be unique to that + * sequence fragmentation. Its value is then persistent, the values of + * other fragmentatin variables are valid on during a single + * fragmentation sequence (while i_accumlen > 0) */ uint16_t i_dgramtag; + /* i_reasstag. Each frame in the reassembly has a tag. That tag must + * match the reassembly tag in the fragments being merged. + * + * This is the same tag as i_dgramtag but is saved on the receiving + * side to match all of the fragments of the packet. + */ + + uint16_t i_reasstag; + /* i_pktlen. The total length of the IPv6 packet to be re-assembled in - * d_buf. + * d_buf. Used to determine when the re-assembly is complete. */ uint16_t i_pktlen; /* The current accumulated length of the packet being received in d_buf. - * Included IPv6 and protocol headers. + * Included IPv6 and protocol headers. Currently used only to determine + * there is a fragmentation sequence in progress. */ uint16_t i_accumlen; - /* i_reasstag. Each frame in the reassembly has a tag. That tag must - * match the reassembly tag in the fragments being merged. - */ - - uint16_t i_reasstag; - /* i_boffset. Offset to the beginning of data in d_buf. As each fragment * is received, data is placed at an appriate offset added to this. */ diff --git a/net/sixlowpan/README.txt b/net/sixlowpan/README.txt new file mode 100644 index 0000000000..b9968c318b --- /dev/null +++ b/net/sixlowpan/README.txt @@ -0,0 +1,30 @@ +Optimal 6loWPAN Configuration: + +1. Link local IP addresses: + + 128 112 96 80 64 48 32 16 + fe80 0000 0000 0000 xxxx xxxx xxxx xxxx + +2. MAC-based IP addresses: + + 128 112 96 80 64 48 32 16 + ---- ---- ---- ---- ---- ---- ---- ---- + xxxx xxxx xxxx xxxx xxxx 00ff fe00 MMMM 2-byte Rime address IEEE 48-bit MAC + fe80 0000 0000 0000 NNNN NNNN NNNN NNNN 8-byte Rime address IEEE EUI-64 + + Where MMM is the 2-byte rime address XOR 0x0200. For example, the MAC + address of 0xabcd would be 0xa9cd. And NNNN NNNN NNNN NNNN is the 8-byte + rime address address XOR 02000 0000 0000 0000 + +3. MAC based link-local addresses + + 128 112 96 80 64 48 32 16 + ---- ---- ---- ---- ---- ---- ---- ---- + fe80 0000 0000 0000 0000 00ff fe00 MMMM 2-byte Rime address IEEE 48-bit MAC + fe80 0000 0000 0000 NNNN NNNN NNNN NNNN 8-byte Rime address IEEE EUI-64 + +4. Compressable port numbers in the rangs 0xf0b0-0xf0bf + +5. IOBs: Must be big enough to hold one IEEE802.15.4 frame (CONFIG_NET_6LOWPAN_FRAMELEN, + typically 127). There must be enough IOBs to decompose the largest IPv6 + packet (CONFIG_NET_6LOWPAN_MTU, default 1294, plus per frame overhead). \ No newline at end of file -- GitLab From a35845bd095194b7ce9030a72feb8b82bea131fc Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 8 Apr 2017 07:48:37 -0600 Subject: [PATCH 380/990] Restore TCP_HDRLEN to MSS calculation. Also add to UDP MSS calculation where it never appearred. Add some missing MSS and RDVWNDO definitinos for 6loWOPAN. --- include/nuttx/net/netconfig.h | 91 +++++++++++++++++------------------ 1 file changed, 45 insertions(+), 46 deletions(-) diff --git a/include/nuttx/net/netconfig.h b/include/nuttx/net/netconfig.h index 9bbd0e9929..99f00e3856 100644 --- a/include/nuttx/net/netconfig.h +++ b/include/nuttx/net/netconfig.h @@ -295,16 +295,13 @@ #endif /* The UDP maximum packet size. This is should not be to set to more - * than NET_DEV_MTU(d) - NET_LL_HDRLEN(dev) - IPv*_HDRLEN. - * - * REVISIT: It is unclear to me if the UDP_HDRLEN should subtracted - * or not. + * than NET_DEV_MTU(d) - NET_LL_HDRLEN(dev) - UDP_HDRLEN - IPv*_HDRLEN. */ -#define UDP_MSS(d,h) (NET_DEV_MTU(d) - NET_LL_HDRLEN(d) (h)) +#define UDP_MSS(d,h) (NET_DEV_MTU(d) - NET_LL_HDRLEN(d) - UDP_HDRLEN (h)) #ifdef CONFIG_NET_ETHERNET -# define ETH_UDP_MSS(h) (CONFIG_NET_ETH_MTU - ETH_HDRLEN - (h)) +# define ETH_UDP_MSS(h) (CONFIG_NET_ETH_MTU - ETH_HDRLEN - UDP_HDRLEN - (h)) # ifndef CONFIG_NET_MULTILINK # define __MIN_UDP_MSS(h) ETH_UDP_MSS(h) # define __MAX_UDP_MSS(h) ETH_UDP_MSS(h) @@ -312,7 +309,7 @@ #endif #ifdef CONFIG_NET_6LOWPAN -# define IEEE802154_UDP_MSS(h) (CONFIG_NET_6LOWPAN_MAXPAYLOAD - (h)) +# define IEEE802154_UDP_MSS(h) (CONFIG_NET_6LOWPAN_MAXPAYLOAD - UDP_HDRLEN - (h)) # ifndef CONFIG_NET_MULTILINK # define __MIN_UDP_MSS(h) IEEE802154_UDP_MSS(h) # define __MAX_UDP_MSS(h) IEEE802154_UDP_MSS(h) @@ -320,7 +317,7 @@ #endif #ifdef CONFIG_NET_LOOPBACK -# define LO_UDP_MSS(h) (NET_LO_MTU - (h)) +# define LO_UDP_MSS(h) (NET_LO_MTU - UDP_HDRLEN - (h)) # ifndef CONFIG_NET_MULTILINK # define __MIN_UDP_MSS(h) LO_UDP_MSS(h) # define __MAX_UDP_MSS(h) LO_UDP_MSS(h) @@ -328,7 +325,7 @@ #endif #ifdef CONFIG_NET_SLIP -# define SLIP_UDP_MSS(h) (CONFIG_NET_SLIP_MTU - (h)) +# define SLIP_UDP_MSS(h) (CONFIG_NET_SLIP_MTU - UDP_HDRLEN - (h)) # ifndef CONFIG_NET_MULTILINK # define __MIN_UDP_MSS(h) SLIP_UDP_MSS(h) # define __MAX_UDP_MSS(h) SLIP_UDP_MSS(h) @@ -383,27 +380,25 @@ # endif #endif -/* NOTE: MSS calcuation excludes the UDP_HDRLEN. */ - #ifdef CONFIG_NET_IPv4 -# define UDP_IPv4_MSS(d) UDP_MSS(d,IPv4_HDRLEN) -# define ETH_IPv4_UDP_MSS ETH_UDP_MSS(IPv4_HDRLEN) -# define SLIP_IPv4_UDP_MSS SLIP_UDP_MSS(IPv4_HDRLEN) +# define UDP_IPv4_MSS(d) UDP_MSS(d,IPv4_HDRLEN) +# define ETH_IPv4_UDP_MSS ETH_UDP_MSS(IPv4_HDRLEN) +# define SLIP_IPv4_UDP_MSS SLIP_UDP_MSS(IPv4_HDRLEN) -# define MIN_IPv4_UDP_MSS __MIN_UDP_MSS(IPv4_HDRLEN) -# define MIN_UDP_MSS __MIN_UDP_MSS(IPv4_HDRLEN) +# define MIN_IPv4_UDP_MSS __MIN_UDP_MSS(IPv4_HDRLEN) +# define MIN_UDP_MSS __MIN_UDP_MSS(IPv4_HDRLEN) # undef MAX_UDP_MSS -# define MAX_IPv4_UDP_MSS __MAX_UDP_MSS(IPv4_HDRLEN) -# define MAX_UDP_MSS __MAX_UDP_MSS(IPv4_HDRLEN) +# define MAX_IPv4_UDP_MSS __MAX_UDP_MSS(IPv4_HDRLEN) +# define MAX_UDP_MSS __MAX_UDP_MSS(IPv4_HDRLEN) #endif /* If IPv6 is support, it will have the smaller MSS */ #ifdef CONFIG_NET_IPv6 # undef MIN_UDP_MSS -# define MIN_IPv6_UDP_MSS __MIN_UDP_MSS(IPv6_HDRLEN) -# define MIN_UDP_MSS __MIN_UDP_MSS(IPv6_HDRLEN) +# define MIN_IPv6_UDP_MSS __MIN_UDP_MSS(IPv6_HDRLEN) +# define MIN_UDP_MSS __MIN_UDP_MSS(IPv6_HDRLEN) #endif /* TCP configuration options */ @@ -473,17 +468,15 @@ * may support a different UDP MSS value. Here we arbitrarily select * the minimum MSS for that case. * - * REVISIT: It is unclear to me if the TCP_HDRLEN should subtracted - * or not. + * REVISIT: TCP_HDRLEN is not really a constant! */ -#define TCP_MSS(d,h) (NET_DEV_MTU(d) - NET_LL_HDRLEN(d) - (h)) -#define LO_TCP_MSS(h) (NET_LO_MTU - (h)) +#define TCP_MSS(d,h) (NET_DEV_MTU(d) - NET_LL_HDRLEN(d) - TCP_HDRLEN - (h)) /* Get the smallest and largest MSS */ #ifdef CONFIG_NET_ETHERNET -# define ETH_TCP_MSS(h) (CONFIG_NET_ETH_MTU - ETH_HDRLEN - (h)) +# define ETH_TCP_MSS(h) (CONFIG_NET_ETH_MTU - ETH_HDRLEN - TCP_HDRLEN - (h)) # ifndef CONFIG_NET_MULTILINK # define __MIN_TCP_MSS(h) ETH_TCP_MSS(h) # define __MAX_TCP_MSS(h) ETH_TCP_MSS(h) @@ -491,7 +484,7 @@ #endif #ifdef CONFIG_NET_6LOWPAN -# define IEEE802154_TCP_MSS(h) CONFIG_NET_6LOWPAN_MAXPAYLOAD +# define IEEE802154_TCP_MSS(h) (CONFIG_NET_6LOWPAN_MAXPAYLOAD - TCP_HDRLEN - (h)) # ifndef CONFIG_NET_MULTILINK # define __MIN_TCP_MSS(h) IEEE802154_TCP_MSS(h) # define __MAX_TCP_MSS(h) IEEE802154_TCP_MSS(h) @@ -499,7 +492,7 @@ #endif #ifdef CONFIG_NET_LOOPBACK -# define LO_TCP_MSS(h) (NET_LO_MTU - (h)) +# define LO_TCP_MSS(h) (NET_LO_MTU - TCP_HDRLEN - (h)) # ifndef CONFIG_NET_MULTILINK # define __MIN_TCP_MSS(h) LO_TCP_MSS(h) # define __MAX_TCP_MSS(h) LO_TCP_MSS(h) @@ -507,7 +500,7 @@ #endif #ifdef CONFIG_NET_SLIP -# define SLIP_TCP_MSS(h) (CONFIG_NET_SLIP_MTU - (h)) +# define SLIP_TCP_MSS(h) (CONFIG_NET_SLIP_MTU - TCP_HDRLEN - (h)) # ifndef CONFIG_NET_MULTILINK # define __MIN_TCP_MSS(h) SLIP_TCP_MSS(h) # define __MAX_TCP_MSS(h) SLIP_TCP_MSS(h) @@ -568,26 +561,26 @@ */ #ifdef CONFIG_NET_IPv6 -# define TCP_IPv6_MSS(d) TCP_MSS(d,IPv6_HDRLEN) -# define ETH_IPv6_TCP_MSS ETH_TCP_MSS(IPv6_HDRLEN) -# define SLIP_IPv6_TCP_MSS SLIP_TCP_MSS(IPv6_HDRLEN) -# define MAX_TCP_MSS __MAX_TCP_MSS(IPv6_HDRLEN) +# define TCP_IPv6_MSS(d) TCP_MSS(d,IPv6_HDRLEN) +# define ETH_IPv6_TCP_MSS ETH_TCP_MSS(IPv6_HDRLEN) +# define SLIP_IPv6_TCP_MSS SLIP_TCP_MSS(IPv6_HDRLEN) +# define MAX_TCP_MSS __MAX_TCP_MSS(IPv6_HDRLEN) #endif #ifdef CONFIG_NET_IPv4 -# define TCP_IPv4_MSS(d) TCP_MSS(d,IPv4_HDRLEN) -# define ETH_IPv4_TCP_MSS ETH_TCP_MSS(IPv4_HDRLEN) -# define SLIP_IPv4_TCP_MSS SLIP_TCP_MSS(IPv4_HDRLEN) -# define MIN_TCP_MSS __MIN_TCP_MSS(IPv4_HDRLEN) +# define TCP_IPv4_MSS(d) TCP_MSS(d,IPv4_HDRLEN) +# define ETH_IPv4_TCP_MSS ETH_TCP_MSS(IPv4_HDRLEN) +# define SLIP_IPv4_TCP_MSS SLIP_TCP_MSS(IPv4_HDRLEN) +# define MIN_TCP_MSS __MIN_TCP_MSS(IPv4_HDRLEN) # undef MAX_TCP_MSS -# define MAX_TCP_MSS __MAX_TCP_MSS(IPv4_HDRLEN) +# define MAX_TCP_MSS __MAX_TCP_MSS(IPv4_HDRLEN) #endif /* If IPv6 is supported, it will have the smaller MSS */ #ifdef CONFIG_NET_IPv6 # undef MIN_TCP_MSS -# define MIN_TCP_MSS __MIN_TCP_MSS(IPv6_HDRLEN) +# define MIN_TCP_MSS __MIN_TCP_MSS(IPv6_HDRLEN) #endif /* The size of the advertised receiver's window. @@ -614,22 +607,28 @@ #endif #if defined(CONFIG_NET_MULTILINK) - /* We are supporting multiple network devices using different link layer - * protocols. Get the size of the receive window from the device structure. - */ + /* We are supporting multiple network devices using different link layer + * protocols. Get the size of the receive window from the device + * structure. + */ # define NET_DEV_RCVWNDO(d) ((d)->d_recvwndo) -#elif defined(CONFIG_NET_SLIP) - /* Only SLIP.. use the configured SLIP receive window size */ - -# define NET_DEV_RCVWNDO(d) CONFIG_NET_SLIP_TCP_RECVWNDO - #elif defined(CONFIG_NET_ETHERNET) /* Only Ethernet.. use the configured SLIP receive window size */ # define NET_DEV_RCVWNDO(d) CONFIG_NET_ETH_TCP_RECVWNDO +#elif defined(CONFIG_NET_6LOWPAN) + /* Only 6loWPAN.. use the configured 6loWPAN receive window size */ + +# define NET_DEV_RCVWNDO(d) CONFIG_NET_6LOWPAN_TCP_RECVWNDO + +#elif defined(CONFIG_NET_SLIP) + /* Only SLIP.. use the configured SLIP receive window size */ + +# define NET_DEV_RCVWNDO(d) CONFIG_NET_SLIP_TCP_RECVWNDO + #else /* if defined(CONFIG_NET_LOOPBACK) */ /* Only loal loopback.. use the fixed loopback receive window size */ -- GitLab From dea251783a8cdc12cdeb27655dd159e56a416176 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 8 Apr 2017 08:14:11 -0600 Subject: [PATCH 381/990] pthread.h: Remove duplicate, possible erroneous definitino of PTHREAD_MUTEX_INITIALIZER that crept in with some recent changes. --- include/pthread.h | 4 ---- 1 file changed, 4 deletions(-) diff --git a/include/pthread.h b/include/pthread.h index a75cd9e901..225a7ef8b0 100644 --- a/include/pthread.h +++ b/include/pthread.h @@ -354,10 +354,6 @@ typedef int pthread_rwlockattr_t; PTHREAD_COND_INITIALIZER, \ 0, 0} -#define PTHREAD_MUTEX_INITIALIZER {NULL, SEM_INITIALIZER(1), -1, \ - __PTHREAD_MUTEX_DEFAULT_FLAGS, \ - PTHREAD_MUTEX_DEFAULT, 0} - #ifdef CONFIG_PTHREAD_CLEANUP /* This type describes the pthread cleanup callback (non-standard) */ -- GitLab From fe722e44b98818440e57433cd59d7d0bc0747778 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 8 Apr 2017 08:14:42 -0600 Subject: [PATCH 382/990] 6loWPAN: Fix a faulty assumption about relationship between some sizes and offsets. --- arch/sim/src/up_initialize.c | 2 +- net/sixlowpan/sixlowpan_framelist.c | 34 +++++------------------------ 2 files changed, 6 insertions(+), 30 deletions(-) diff --git a/arch/sim/src/up_initialize.c b/arch/sim/src/up_initialize.c index fa8468196e..5b3f1c0e9f 100644 --- a/arch/sim/src/up_initialize.c +++ b/arch/sim/src/up_initialize.c @@ -187,7 +187,7 @@ void up_initialize(void) * separately. */ - syslog(LOG_INFO, "SIM: Initializing"); + syslog(LOG_INFO, "SIM: Initializing\n"); #endif #ifdef CONFIG_PM diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c index 552f394b78..7b36219205 100644 --- a/net/sixlowpan/sixlowpan_framelist.c +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -144,9 +144,7 @@ static void sixlowpan_compress_ipv6hdr(FAR const struct ipv6_hdr_s *ipv6hdr, static void sixlowpan_copy_protohdr(FAR const struct ipv6_hdr_s *ipv6hdr, FAR uint8_t *fptr) { - uint16_t combined; uint16_t protosize; - uint16_t copysize; /* What is the total size of the IPv6 + protocol header? */ @@ -162,7 +160,6 @@ static void sixlowpan_copy_protohdr(FAR const struct ipv6_hdr_s *ipv6hdr, */ protosize = ((uint16_t)tcp->tcpoffset >> 4) << 2; - combined = sizeof(struct ipv6_hdr_s) + protosize; } break; #endif @@ -170,48 +167,27 @@ static void sixlowpan_copy_protohdr(FAR const struct ipv6_hdr_s *ipv6hdr, #ifdef CONFIG_NET_UDP case IP_PROTO_UDP: protosize = sizeof(struct udp_hdr_s); - combined = sizeof(struct ipv6udp_hdr_s); break; #endif #ifdef CONFIG_NET_ICMPv6 case IP_PROTO_ICMP6: protosize = sizeof(struct icmpv6_hdr_s); - combined = sizeof(struct ipv6icmp_hdr_s); break; #endif default: nwarn("WARNING: Unrecognized proto: %u\n", ipv6hdr->proto); - protosize = 0; - combined = sizeof(struct ipv6_hdr_s); - break; + return; } - /* Copy the remaining protocol header. */ - - if (g_uncomp_hdrlen > IPv6_HDRLEN) - { - nwarn("WARNING: Protocol header not copied: " - "g_uncomp_hdren=%u IPv6_HDRLEN=%u\n", - g_uncomp_hdrlen, IPv6_HDRLEN); - return; - } - - copysize = combined - g_uncomp_hdrlen; - if (copysize != protosize) - { - nwarn("WARNING: Protocol header size mismatch: " - "g_uncomp_hdren=%u copysize=%u protosize=%u\n", - g_uncomp_hdrlen, copysize, protosize); - return; - } + /* Copy the protocol header. */ memcpy(fptr + g_frame_hdrlen, (FAR uint8_t *)ipv6hdr + g_uncomp_hdrlen, - copysize); + protosize); - g_frame_hdrlen += copysize; - g_uncomp_hdrlen += copysize; + g_frame_hdrlen += protosize; + g_uncomp_hdrlen += protosize; } /**************************************************************************** -- GitLab From 143b8f9591f39ecc0f1b61cad0c6387fc688de55 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 8 Apr 2017 09:34:30 -0600 Subject: [PATCH 383/990] 6loWPAN: Fix more frame offsets. Reorder some logic that was appropriate only for IPv6 dispatch. --- net/sixlowpan/sixlowpan_framelist.c | 35 +++------------------------- net/sixlowpan/sixlowpan_hc06.c | 18 +++++++-------- net/sixlowpan/sixlowpan_hc1.c | 8 +++---- net/sixlowpan/sixlowpan_input.c | 36 ++++++++++++----------------- net/sixlowpan/sixlowpan_internal.h | 8 +++---- 5 files changed, 35 insertions(+), 70 deletions(-) diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c index 7b36219205..d8b751e8a7 100644 --- a/net/sixlowpan/sixlowpan_framelist.c +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -112,6 +112,8 @@ static void sixlowpan_compress_ipv6hdr(FAR const struct ipv6_hdr_s *ipv6hdr, FAR uint8_t *fptr) { + uint16_t protosize; + /* Indicate the IPv6 dispatch and length */ fptr[g_frame_hdrlen] = SIXLOWPAN_DISPATCH_IPV6; @@ -122,31 +124,8 @@ static void sixlowpan_compress_ipv6hdr(FAR const struct ipv6_hdr_s *ipv6hdr, memcpy(&fptr[g_frame_hdrlen] , ipv6hdr, IPv6_HDRLEN); g_frame_hdrlen += IPv6_HDRLEN; g_uncomp_hdrlen += IPv6_HDRLEN; -} - -/**************************************************************************** - * Name: sixlowpan_copy_protohdr - * - * Description: - * The IPv6 header should have already been processed (as reflected in the - * g_uncomphdrlen). But we probably still need to copy the following - * protocol header. - * - * Input Parameters: - * ipv6hdr - Pointer to the IPv6 header to "compress" - * fptr - Pointer to the beginning of the frame under construction - * - * Returned Value: - * None. But g_frame_hdrlen and g_uncomp_hdrlen updated. - * - ****************************************************************************/ -static void sixlowpan_copy_protohdr(FAR const struct ipv6_hdr_s *ipv6hdr, - FAR uint8_t *fptr) -{ - uint16_t protosize; - - /* What is the total size of the IPv6 + protocol header? */ + /* Copy the following protocol header, */ switch (ipv6hdr->proto) { @@ -397,10 +376,6 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, g_frame_hdrlen += SIXLOWPAN_FRAG1_HDR_LEN; - /* Copy protocol header that follows the IPv6 header */ - - sixlowpan_copy_protohdr(destip, fptr); - /* Copy payload and enqueue. NOTE that the size is a multiple of eight * bytes. */ @@ -527,10 +502,6 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, DEBUGASSERT(verify == framer_hdrlen); UNUSED(verify); - /* Copy protocol header that follows the IPv6 header */ - - sixlowpan_copy_protohdr(destip, fptr); - /* Copy the payload and queue */ memcpy(fptr + g_frame_hdrlen, buf, buflen); diff --git a/net/sixlowpan/sixlowpan_hc06.c b/net/sixlowpan/sixlowpan_hc06.c index 9e51f88c17..d449f82936 100644 --- a/net/sixlowpan/sixlowpan_hc06.c +++ b/net/sixlowpan/sixlowpan_hc06.c @@ -440,7 +440,7 @@ void sixlowpan_hc06_initialize(void) * ipv6 - The IPv6 header to be compressed * destmac - L2 destination address, needed to compress the IP * destination field - * fptr - Pointer to frame data payload. + * fptr - Pointer to frame to be compressed. * * Returned Value: * None @@ -840,7 +840,7 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, * inferred from the L2 length), non 0 if the packet is a first * fragment. * iob - Pointer to the IOB containing the received frame. - * payptr - Pointer to the frame data payload. + * fptr - Pointer to frame to be compressed. * * Returned Value: * None @@ -849,7 +849,7 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, uint16_t iplen, FAR struct iob_s *iob, - FAR uint8_t *payptr) + FAR uint8_t *fptr) { FAR struct ipv6_hdr_s *ipv6 = IPv6BUF(ieee); FAR uint8_t *iphc; @@ -857,18 +857,18 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, uint8_t iphc1; uint8_t tmp; - /* payptr points to IPHC. At least two byte will be used for the encoding. */ + /* iphc points to IPHC. At least two byte will be used for the encoding. */ - iphc = payptr; + iphc = fptr + g_frame_hdrlen; iphc0 = iphc[0]; iphc1 = iphc[1]; /* g_hc96ptr points to just after the 2-byte minimum IPHC */ - g_hc06ptr = payptr + 2; + g_hc06ptr = iphc + 2; - ninfo("payptr=%p g_frame_hdrlen=%u iphc=%02x:%02x:%02x g_hc06ptr=%p\n", - payptr, g_frame_hdrlen, iphc[0], iphc[1], iphc[2], g_hc06ptr); + ninfo("fptr=%p g_frame_hdrlen=%u iphc=%02x:%02x:%02x g_hc06ptr=%p\n", + fptr, g_frame_hdrlen, iphc[0], iphc[1], iphc[2], g_hc06ptr); /* Another if the CID flag is set */ @@ -1171,7 +1171,7 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, } } - g_frame_hdrlen = g_hc06ptr - payptr; + g_frame_hdrlen = g_hc06ptr - fptr; /* IP length field. */ diff --git a/net/sixlowpan/sixlowpan_hc1.c b/net/sixlowpan/sixlowpan_hc1.c index 6626501363..9f657a12dc 100644 --- a/net/sixlowpan/sixlowpan_hc1.c +++ b/net/sixlowpan/sixlowpan_hc1.c @@ -258,7 +258,7 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, * inferred from the L2 length), non 0 if the packet is a 1st * fragment. * iob - Pointer to the IOB containing the received frame. - * payptr - Pointer to the frame data payload. + * fptr - Pointer to frame to be uncompressed. * * Returned Value: * Zero (OK) is returned on success, on failure a negater errno value is @@ -268,10 +268,10 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, int sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, uint16_t iplen, FAR struct iob_s *iob, - FAR uint8_t *payptr) + FAR uint8_t *fptr) { FAR struct ipv6_hdr_s *ipv6 = IPv6BUF(&ieee->i_dev); - FAR uint8_t *hc1 = payptr + g_frame_hdrlen; + FAR uint8_t *hc1 = fptr + g_frame_hdrlen; /* Format the IPv6 header in the device d_buf */ /* Set version, traffic clase, and flow label */ @@ -312,7 +312,7 @@ int sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, case SIXLOWPAN_HC1_NH_UDP: { FAR struct udp_hdr_s *udp = UDPIPv6BUF(&ieee->i_dev); - FAR uint8_t *hcudp = payptr + g_frame_hdrlen; + FAR uint8_t *hcudp = fptr + g_frame_hdrlen; ipv6->proto = IP_PROTO_UDP; if ((hcudp[RIME_HC1_HC_UDP_HC1_ENCODING] & 0x01) != 0) diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index 6098a58251..e491394c7b 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -224,6 +224,7 @@ int sixlowpan_recv_hdrlen(FAR const uint8_t *fptr) static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, FAR struct iob_s *iob) { + FAR uint8_t *fptr; /* Convenience pointer to beginning of the frame */ FAR uint8_t *hc1; /* Convenience pointer to HC1 data */ uint16_t fragsize = 0; /* Size of the IP packet (read from fragment) */ uint16_t paysize; /* Size of the data payload */ @@ -242,7 +243,8 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, * This size includes both fragmentation and FCF headers. */ - hdrsize = sixlowpan_recv_hdrlen(iob->io_data); + fptr = iob->io_data; + hdrsize = sixlowpan_recv_hdrlen(fptr); if (hdrsize < 0) { nwarn("Invalid IEEE802.15.2 header: %d\n", hdrsize); @@ -262,7 +264,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, * already includes the fragementation header, if presetn. */ - switch ((GETINT16(iob->io_data, RIME_FRAG_DISPATCH_SIZE) & 0xf800) >> 8) + switch ((GETINT16(fptr, RIME_FRAG_DISPATCH_SIZE) & 0xf800) >> 8) { /* First fragment of new reassembly */ @@ -270,8 +272,8 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, { /* Set up for the reassembly */ - fragsize = GETINT16(iob->io_data, RIME_FRAG_DISPATCH_SIZE) & 0x07ff; - fragtag = GETINT16(iob->io_data, RIME_FRAG_TAG); + fragsize = GETINT16(fptr, RIME_FRAG_DISPATCH_SIZE) & 0x07ff; + fragtag = GETINT16(fptr, RIME_FRAG_TAG); ninfo("FRAG1: fragsize=%d fragtag=%d fragoffset=%d\n", fragsize, fragtag, fragoffset); @@ -287,9 +289,9 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, { /* Set offset, tag, size. Offset is in units of 8 bytes. */ - fragoffset = iob->io_data[RIME_FRAG_OFFSET]; - fragtag = GETINT16(iob->io_data, RIME_FRAG_TAG); - fragsize = GETINT16(iob->io_data, RIME_FRAG_DISPATCH_SIZE) & 0x07ff; + fragoffset = fptr[RIME_FRAG_OFFSET]; + fragtag = GETINT16(fptr, RIME_FRAG_TAG); + fragsize = GETINT16(fptr, RIME_FRAG_DISPATCH_SIZE) & 0x07ff; ninfo("FRAGN: fragsize=%d fragtag=%d fragoffset=%d\n", fragsize, fragtag, fragoffset); @@ -429,19 +431,16 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, /* Process next dispatch and headers */ - hc1 = &iob->io_data[g_frame_hdrlen]; + hc1 = fptr + g_frame_hdrlen; #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 if ((hc1[RIME_HC1_DISPATCH] & SIXLOWPAN_DISPATCH_IPHC_MASK) == SIXLOWPAN_DISPATCH_IPHC) { - FAR uint8_t *payptr; - ninfo("IPHC Dispatch\n"); /* Payload starts after the IEEE802.15.4 header(s) */ - payptr = &iob->io_data[g_frame_hdrlen]; - sixlowpan_uncompresshdr_hc06(ieee, fragsize, iob, payptr); + sixlowpan_uncompresshdr_hc06(ieee, fragsize, iob, fptr); } else #endif /* CONFIG_NET_6LOWPAN_COMPRESSION_HC06 */ @@ -449,14 +448,11 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC1 if (hc1[RIME_HC1_DISPATCH] == SIXLOWPAN_DISPATCH_HC1) { - FAR uint8_t *payptr; - ninfo("HC1 Dispatch\n"); /* Payload starts after the IEEE802.15.4 header(s) */ - payptr = &iob->io_data[g_frame_hdrlen]; - sixlowpan_uncompresshdr_hc1(ieee, fragsize, iob, payptr); + sixlowpan_uncompresshdr_hc1(ieee, fragsize, iob, fptr); } else #endif /* CONFIG_NET_6LOWPAN_COMPRESSION_HC1 */ @@ -470,7 +466,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, /* Put uncompressed IP header in d_buf. */ - memcpy(ipv6, iob->io_data + g_frame_hdrlen, IPv6_HDRLEN); + memcpy(ipv6, fptr + g_frame_hdrlen, IPv6_HDRLEN); /* Update g_uncomp_hdrlen and g_frame_hdrlen. */ @@ -527,8 +523,7 @@ copypayload: } memcpy(ieee->i_dev.d_buf + g_uncomp_hdrlen + (fragoffset << 3), - iob->io_data + g_frame_hdrlen, - paysize); + fptr + g_frame_hdrlen, paysize); #ifdef CONFIG_NET_6LOWPAN_FRAG /* Update ieee->i_accumlen if the frame is a fragment, ieee->i_pktlen @@ -690,8 +685,7 @@ int sixlowpan_input(FAR struct ieee802154_driver_s *ieee) FRAME_IOB_REMOVE(ieee, iob); DEBUGASSERT(iob != NULL); - sixlowpan_dumpbuffer("Incoming frame", - (FAR const uint8_t *)iob->io_data, iob->io_len); + sixlowpan_dumpbuffer("Incoming frame", iob->io_data, iob->io_len); /* Process the frame, decompressing it into the packet buffer */ diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index bd366c884e..0f04a068b2 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -641,7 +641,7 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, * inferred from the L2 length), non 0 if the packet is a first * fragment. * iob - Pointer to the IOB containing the received frame. - * payptr - Pointer to the frame data payload. + * fptr - Pointer to frame to be uncompressed. * * Returned Value: * None @@ -651,7 +651,7 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, uint16_t iplen, FAR struct iob_s *iob, - FAR uint8_t *payptr); + FAR uint8_t *fptr); #endif /**************************************************************************** @@ -701,7 +701,7 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, * inferred from the L2 length), non 0 if the packet is a first * fragment. * iob - Pointer to the IOB containing the received frame. - * payptr - Pointer to the frame data payload. + * fptr - Pointer to frame to be uncompressed. * * Returned Value: * None @@ -711,7 +711,7 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC1 int sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, uint16_t ip_len, FAR struct iob_s *iob, - FAR uint8_t *payptr); + FAR uint8_t *fptr); #endif /**************************************************************************** -- GitLab From 3f51180ccab2de01fcd10e1e14f1c74332afc190 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 8 Apr 2017 10:18:44 -0600 Subject: [PATCH 384/990] 6loWPAN: Fix breakage in IPv6 dispatch caused by fixes to HC1 dispatch; Move some standard definitions from internal header file to include/nuttx/net/sixlowpan.h. Update a README. --- include/nuttx/net/sixlowpan.h | 143 ++++++++++++++++++++++++++++- net/sixlowpan/README.txt | 47 +++++++++- net/sixlowpan/sixlowpan_input.c | 106 +++++++++++++++++---- net/sixlowpan/sixlowpan_internal.h | 139 ---------------------------- 4 files changed, 273 insertions(+), 162 deletions(-) diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index dfc8a13a76..a98cfa457c 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -63,6 +63,83 @@ * Pre-processor Definitions ****************************************************************************/ +/* Frame format definitions *************************************************/ +/* Fragment header. + * + * The fragment header is used when the payload is too large to fit in a + * single IEEE 802.15.4 frame. The fragment header contains three fields: + * Datagram size, datagram tag and datagram offset. + * + * 1. Datagram size describes the total (un-fragmented) payload. + * 2. Datagram tag identifies the set of fragments and is used to match + * fragments of the same payload. + * 3. Datagram offset identifies the fragment’s offset within the un- + * fragmented payload. + * + * The fragment header length is 4 bytes for the first header and 5 + * bytes for all subsequent headers. + */ + +#define RIME_FRAG_DISPATCH_SIZE 0 /* 16 bit */ +#define RIME_FRAG_TAG 2 /* 16 bit */ +#define RIME_FRAG_OFFSET 4 /* 8 bit */ + +/* Define the Rime buffer as a byte array */ + +#define RIME_HC1_DISPATCH 0 /* 8 bit */ +#define RIME_HC1_ENCODING 1 /* 8 bit */ +#define RIME_HC1_TTL 2 /* 8 bit */ + +#define RIME_HC1_HC_UDP_DISPATCH 0 /* 8 bit */ +#define RIME_HC1_HC_UDP_HC1_ENCODING 1 /* 8 bit */ +#define RIME_HC1_HC_UDP_UDP_ENCODING 2 /* 8 bit */ +#define RIME_HC1_HC_UDP_TTL 3 /* 8 bit */ +#define RIME_HC1_HC_UDP_PORTS 4 /* 8 bit */ +#define RIME_HC1_HC_UDP_CHKSUM 5 /* 16 bit */ + +/* These are some definitions of element values used in the FCF. See the + * IEEE802.15.4 spec for details. + */ + +#define FRAME802154_FRAMETYPE_SHIFT (0) /* Bits 0-2: Frame type */ +#define FRAME802154_FRAMETYPE_MASK (7 << FRAME802154_FRAMETYPE_SHIFT) +#define FRAME802154_SECENABLED_SHIFT (3) /* Bit 3: Security enabled */ +#define FRAME802154_FRAMEPENDING_SHIFT (4) /* Bit 4: Frame pending */ +#define FRAME802154_ACKREQUEST_SHIFT (5) /* Bit 5: ACK request */ +#define FRAME802154_PANIDCOMP_SHIFT (6) /* Bit 6: PANID compression */ + /* Bits 7-9: Reserved */ +#define FRAME802154_DSTADDR_SHIFT (2) /* Bits 10-11: Dest address mode */ +#define FRAME802154_DSTADDR_MASK (3 << FRAME802154_DSTADDR_SHIFT) +#define FRAME802154_VERSION_SHIFT (4) /* Bit 12-13: Frame version */ +#define FRAME802154_VERSION_MASK (3 << FRAME802154_VERSION_SHIFT) +#define FRAME802154_SRCADDR_SHIFT (6) /* Bits 14-15: Source address mode */ +#define FRAME802154_SRCADDR_MASK (3 << FRAME802154_SRCADDR_SHIFT) + +/* Unshifted values for use in struct frame802154_fcf_s */ + +#define FRAME802154_BEACONFRAME (0) +#define FRAME802154_DATAFRAME (1) +#define FRAME802154_ACKFRAME (2) +#define FRAME802154_CMDFRAME (3) + +#define FRAME802154_BEACONREQ (7) + +#define FRAME802154_IEEERESERVED (0) +#define FRAME802154_NOADDR (0) /* Only valid for ACK or Beacon frames */ +#define FRAME802154_SHORTADDRMODE (2) +#define FRAME802154_LONGADDRMODE (3) + +#define FRAME802154_NOBEACONS 0x0f + +#define FRAME802154_BROADCASTADDR 0xffff +#define FRAME802154_BROADCASTPANDID 0xffff + +#define FRAME802154_IEEE802154_2003 (0) +#define FRAME802154_IEEE802154_2006 (1) + +#define FRAME802154_SECURITY_LEVEL_NONE (0) +#define FRAME802154_SECURITY_LEVEL_128 (3) + /* Min and Max compressible UDP ports - HC06 */ #define SIXLOWPAN_UDP_4_BIT_PORT_MIN 0xf0b0 @@ -171,9 +248,71 @@ #define SIXLOWPAN_MAC_STDFRAME 127 -/* Frame buffer helper macros. +/* Address compressibility test macros **************************************/ + +/* Check whether we can compress the IID in address 'a' to 16 bits. This is + * used for unicast addresses only, and is true if the address is on the + * format ::0000:00ff:fe00:XXXX + * + * NOTE: we currently assume 64-bits prefixes + */ + +/* Check whether we can compress the IID in address 'a' to 16 bits. This is + * used for unicast addresses only, and is true if the address is on the + * format ::0000:00ff:fe00:XXXX. + * + * NOTE: we currently assume 64-bits prefixes. Big-endian, network order is + * assumed. + */ + +#define SIXLOWPAN_IS_IID_16BIT_COMPRESSABLE(a) \ + ((((a)[4]) == 0x0000) && (((a)[5]) == HTONS(0x00ff)) && \ + (((a)[6]) == 0xfe00)) + +/* Check whether the 9-bit group-id of the compressed multicast address is + * known. It is true if the 9-bit group is the all nodes or all routers + * group. Parameter 'a' is typed uint8_t * + */ + +#define SIXLOWPAN_IS_MCASTADDR_DECOMPRESSABLE(a) \ + (((*a & 0x01) == 0) && \ + ((*(a + 1) == 0x01) || (*(a + 1) == 0x02))) + +/* Check whether the 112-bit group-id of the multicast address is mappable + * to a 9-bit group-id. It is true if the group is the all nodes or all + * routers group: * - * The IEEE802.15.4 MAC driver structures includes a list of IOB + * XXXX:0000:0000:0000:0000:0000:0000:0001 All nodes address + * XXXX:0000:0000:0000:0000:0000:0000:0002 All routers address + */ + +#define SIXLOWPAN_IS_MCASTADDR_COMPRESSABLE(a) \ + ((a)[1] == 0 && (a)[2] == 0 && (a)[3] == 0 && \ + (a)[4] == 0 && (a)[5] == 0 && (a)[6] == 0 && \ + ((a)[7] == HTONS(0x0001) || (a)[7] == HTONS(0x0002))) + +/* FFXX:0000:0000:0000:0000:00XX:XXXX:XXXX */ + +#define SIXLOWPAN_IS_MCASTADDR_COMPRESSABLE48(a) \ + ((a)[1] == 0 && (a)[2] == 0 && (a)[3] == 0 && \ + (a)[4] == 0 && (((a)[5] & HTONS(0xff00)) == 0)) + +/* FFXX:0000:0000:0000:0000:0000:00XX:XXXX */ + +#define SIXLOWPAN_IS_MCASTADDR_COMPRESSABLE32(a) \ + ((a)[1] == 0 && (a)[2] == 0 && (a)[3] == 0 && \ + (a)[4] == 0 && (a)[5] == 0 && ((a)[6] & HTONS(0xff00)) == 0) + +/* FF02:0000:0000:0000:0000:0000:0000:00XX */ + +#define SIXLOWPAN_IS_MCASTADDR_COMPRESSABLE8(a) \ + ((((a)[0] & HTONS(0x00ff)) == HTONS(0x0002)) && \ + (a)[1] == 0 && (a)[2] == 0 && (a)[3] == 0 && \ + (a)[4] == 0 && (a)[5] == 0 && (a)[6] == 0 && \ + (((a)[7] & HTONS(0xff00)) == 0x0000)) + +/* Frame buffer helper macros ***********************************************/ +/* The IEEE802.15.4 MAC driver structures includes a list of IOB * structures, i_framelist, containing frames to be sent by the driver or * that were received by the driver. The IOB structure is defined in * include/nuttx/net/iob.h. The length of data in the IOB is provided by diff --git a/net/sixlowpan/README.txt b/net/sixlowpan/README.txt index b9968c318b..643735dd86 100644 --- a/net/sixlowpan/README.txt +++ b/net/sixlowpan/README.txt @@ -1,4 +1,5 @@ -Optimal 6loWPAN Configuration: +Optimal 6loWPAN Configuration +----------------------------- 1. Link local IP addresses: @@ -27,4 +28,46 @@ Optimal 6loWPAN Configuration: 5. IOBs: Must be big enough to hold one IEEE802.15.4 frame (CONFIG_NET_6LOWPAN_FRAMELEN, typically 127). There must be enough IOBs to decompose the largest IPv6 - packet (CONFIG_NET_6LOWPAN_MTU, default 1294, plus per frame overhead). \ No newline at end of file + packet (CONFIG_NET_6LOWPAN_MTU, default 1294, plus per frame overhead). + +Fragmentation Headers +--------------------- +A fragment header is placed at the beginning of the outgoing packet when the +payload is too large to fit in a single IEEE 802.15.4 frame. The fragment +header contains three fields: Datagram size, datagram tag and datagram +offset. + +1. Datagram size describes the total (un-fragmented) payload. +2. Datagram tag identifies the set of fragments and is used to match + fragments of the same payload. +3. Datagram offset identifies the fragment’s offset within the un- + fragmented payload (in units of 8 bytes). + +The length of the fragment header length is four bytes for the first header +(FRAG1) and five bytes for all subsequent headers (FRAGN). For example, +this is a HC1 compressed first frame of a packet + + c50e 000b ### 4-byte FRAG1 header + 01 08 01 0000 3412 ### 7-byte FCF header + 42 ### SIXLOWPAN_DISPATCH_HC1 + fb ### RIME_HC1_HC_UDP_HC1_ENCODING + e0 ### RIME_HC1_HC_UDP_UDP_ENCODING + 00 ### RIME_HC1_HC_UDP_TTL + 10 ### RIME_HC1_HC_UDP_PORTS + 0000 ### RIME_HC1_HC_UDP_CHKSUM + 4f4e452064617920 48656e6e792d7065 6e6e792077617320 7069636b696e6720 ### 80 byte payload + 757020636f726e20 696e207468652063 6f726e7961726420 7768656e2d2d7768 + 61636b212d2d736f 6d657468696e6720 g + +This is the second frame of the same transfer: + + e50e 000b 0a ### 5 byte FRAGN header + 01 08 01 0000 3412 ### 7-byte FCF header + 6869742068657220 75706f6e20746865 20686561642e2027 476f6f646e657373 ### 88 byte payload + 2067726163696f75 73206d6521272073 6169642048656e6e 792d70656e6e793b + 202774686520736b 79277320612d676f 696e6720746f2066 + +The payload length is encoded in the LS 11-bits of the first 16-bit value: +In this example the payload size is 0x050e or 1,294. The tag is 0x000b. In +the second frame, the fifth byte contains the offset 0x0a which is 10 << 3 = +80 bytes, the size of the payload on the first packet. diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index e491394c7b..b19fa8ffba 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -190,6 +190,91 @@ int sixlowpan_recv_hdrlen(FAR const uint8_t *fptr) return 0; } +/**************************************************************************** + * Name: sixlowpan_compress_ipv6hdr + * + * Description: + * IPv6 dispatch "compression" function. Packets "Compression" when only + * IPv6 dispatch is used + * + * There is no compression in this case, all fields are sent + * inline. We just add the IPv6 dispatch byte before the packet. + * + * 0 1 2 3 + * 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + * | IPv6 Dsp | IPv6 header and payload ... + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + * + * Input Parameters: + * ieee - The IEEE802.15.4 MAC network driver interface. + * fptr - Pointer to the beginning of the frame under construction + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void sixlowpan_uncompress_ipv6hdr(FAR struct ieee802154_driver_s *ieee, + FAR uint8_t *fptr) +{ + FAR struct ipv6_hdr_s *ipv6 = IPv6BUF(&ieee->i_dev); + uint16_t protosize; + + /* Put uncompressed IPv6 header in d_buf. */ + + g_frame_hdrlen += SIXLOWPAN_IPV6_HDR_LEN; + memcpy(ipv6, fptr + g_frame_hdrlen, IPv6_HDRLEN); + + /* Update g_uncomp_hdrlen and g_frame_hdrlen. */ + + g_frame_hdrlen += IPv6_HDRLEN; + g_uncomp_hdrlen += IPv6_HDRLEN; + + /* Copy the following protocol header, */ + + switch (ipv6->proto) + { +#ifdef CONFIG_NET_TCP + case IP_PROTO_TCP: + { + FAR struct tcp_hdr_s *tcp = &((FAR struct ipv6tcp_hdr_s *)ipv6)->tcp; + + /* The TCP header length is encoded in the top 4 bits of the + * tcpoffset field (in units of 32-bit words). + */ + + protosize = ((uint16_t)tcp->tcpoffset >> 4) << 2; + } + break; +#endif + +#ifdef CONFIG_NET_UDP + case IP_PROTO_UDP: + protosize = sizeof(struct udp_hdr_s); + break; +#endif + +#ifdef CONFIG_NET_ICMPv6 + case IP_PROTO_ICMP6: + protosize = sizeof(struct icmpv6_hdr_s); + break; +#endif + + default: + nwarn("WARNING: Unrecognized proto: %u\n", ipv6->proto); + return; + } + + /* Copy the protocol header. */ + + memcpy((FAR uint8_t *)ipv6 + g_uncomp_hdrlen, fptr + g_frame_hdrlen, + protosize); + + g_frame_hdrlen += protosize; + g_uncomp_hdrlen += protosize; +} + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -437,9 +522,6 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, if ((hc1[RIME_HC1_DISPATCH] & SIXLOWPAN_DISPATCH_IPHC_MASK) == SIXLOWPAN_DISPATCH_IPHC) { ninfo("IPHC Dispatch\n"); - - /* Payload starts after the IEEE802.15.4 header(s) */ - sixlowpan_uncompresshdr_hc06(ieee, fragsize, iob, fptr); } else @@ -449,29 +531,15 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, if (hc1[RIME_HC1_DISPATCH] == SIXLOWPAN_DISPATCH_HC1) { ninfo("HC1 Dispatch\n"); - - /* Payload starts after the IEEE802.15.4 header(s) */ - - sixlowpan_uncompresshdr_hc1(ieee, fragsize, iob, fptr); + sixlowpan_uncompresshdr_hc1(ieee, fragsize, iob, fptr); } else #endif /* CONFIG_NET_6LOWPAN_COMPRESSION_HC1 */ if (hc1[RIME_HC1_DISPATCH] == SIXLOWPAN_DISPATCH_IPV6) { - FAR struct ipv6_hdr_s *ipv6 = IPv6BUF(&ieee->i_dev); - ninfo("IPv6 Dispatch\n"); - g_frame_hdrlen += SIXLOWPAN_IPV6_HDR_LEN; - - /* Put uncompressed IP header in d_buf. */ - - memcpy(ipv6, fptr + g_frame_hdrlen, IPv6_HDRLEN); - - /* Update g_uncomp_hdrlen and g_frame_hdrlen. */ - - g_frame_hdrlen += IPv6_HDRLEN; - g_uncomp_hdrlen += IPv6_HDRLEN; + sixlowpan_uncompress_ipv6hdr(ieee, fptr); } else { diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index 0f04a068b2..5445686373 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -84,82 +84,6 @@ /* Pointers in the Rime buffer */ -/* Fragment header. - * - * The fragment header is used when the payload is too large to fit in a - * single IEEE 802.15.4 frame. The fragment header contains three fields: - * Datagram size, datagram tag and datagram offset. - * - * 1. Datagram size describes the total (un-fragmented) payload. - * 2. Datagram tag identifies the set of fragments and is used to match - * fragments of the same payload. - * 3. Datagram offset identifies the fragment’s offset within the un- - * fragmented payload. - * - * The fragment header length is 4 bytes for the first header and 5 - * bytes for all subsequent headers. - */ - -#define RIME_FRAG_DISPATCH_SIZE 0 /* 16 bit */ -#define RIME_FRAG_TAG 2 /* 16 bit */ -#define RIME_FRAG_OFFSET 4 /* 8 bit */ - -/* Define the Rime buffer as a byte array */ - -#define RIME_HC1_DISPATCH 0 /* 8 bit */ -#define RIME_HC1_ENCODING 1 /* 8 bit */ -#define RIME_HC1_TTL 2 /* 8 bit */ - -#define RIME_HC1_HC_UDP_DISPATCH 0 /* 8 bit */ -#define RIME_HC1_HC_UDP_HC1_ENCODING 1 /* 8 bit */ -#define RIME_HC1_HC_UDP_UDP_ENCODING 2 /* 8 bit */ -#define RIME_HC1_HC_UDP_TTL 3 /* 8 bit */ -#define RIME_HC1_HC_UDP_PORTS 4 /* 8 bit */ -#define RIME_HC1_HC_UDP_CHKSUM 5 /* 16 bit */ - -/* These are some definitions of element values used in the FCF. See the - * IEEE802.15.4 spec for details. - */ - -#define FRAME802154_FRAMETYPE_SHIFT (0) /* Bits 0-2: Frame type */ -#define FRAME802154_FRAMETYPE_MASK (7 << FRAME802154_FRAMETYPE_SHIFT) -#define FRAME802154_SECENABLED_SHIFT (3) /* Bit 3: Security enabled */ -#define FRAME802154_FRAMEPENDING_SHIFT (4) /* Bit 4: Frame pending */ -#define FRAME802154_ACKREQUEST_SHIFT (5) /* Bit 5: ACK request */ -#define FRAME802154_PANIDCOMP_SHIFT (6) /* Bit 6: PANID compression */ - /* Bits 7-9: Reserved */ -#define FRAME802154_DSTADDR_SHIFT (2) /* Bits 10-11: Dest address mode */ -#define FRAME802154_DSTADDR_MASK (3 << FRAME802154_DSTADDR_SHIFT) -#define FRAME802154_VERSION_SHIFT (4) /* Bit 12-13: Frame version */ -#define FRAME802154_VERSION_MASK (3 << FRAME802154_VERSION_SHIFT) -#define FRAME802154_SRCADDR_SHIFT (6) /* Bits 14-15: Source address mode */ -#define FRAME802154_SRCADDR_MASK (3 << FRAME802154_SRCADDR_SHIFT) - -/* Unshifted values for use in struct frame802154_fcf_s */ - -#define FRAME802154_BEACONFRAME (0) -#define FRAME802154_DATAFRAME (1) -#define FRAME802154_ACKFRAME (2) -#define FRAME802154_CMDFRAME (3) - -#define FRAME802154_BEACONREQ (7) - -#define FRAME802154_IEEERESERVED (0) -#define FRAME802154_NOADDR (0) /* Only valid for ACK or Beacon frames */ -#define FRAME802154_SHORTADDRMODE (2) -#define FRAME802154_LONGADDRMODE (3) - -#define FRAME802154_NOBEACONS 0x0f - -#define FRAME802154_BROADCASTADDR 0xffff -#define FRAME802154_BROADCASTPANDID 0xffff - -#define FRAME802154_IEEE802154_2003 (0) -#define FRAME802154_IEEE802154_2006 (1) - -#define FRAME802154_SECURITY_LEVEL_NONE (0) -#define FRAME802154_SECURITY_LEVEL_128 (3) - /* Packet buffer Definitions */ #define PACKETBUF_ATTR_PACKET_TYPE_DATA 0 @@ -215,69 +139,6 @@ #define PACKETBUF_NUM_ADDRS 4 -/* Address compressibility test macros **************************************/ - -/* Check whether we can compress the IID in address 'a' to 16 bits. This is - * used for unicast addresses only, and is true if the address is on the - * format ::0000:00ff:fe00:XXXX - * - * NOTE: we currently assume 64-bits prefixes - */ - -/* Check whether we can compress the IID in address 'a' to 16 bits. This is - * used for unicast addresses only, and is true if the address is on the - * format ::0000:00ff:fe00:XXXX. - * - * NOTE: we currently assume 64-bits prefixes. Big-endian, network order is - * assumed. - */ - -#define SIXLOWPAN_IS_IID_16BIT_COMPRESSABLE(a) \ - ((((a)[4]) == 0x0000) && (((a)[5]) == HTONS(0x00ff)) && \ - (((a)[6]) == 0xfe00)) - -/* Check whether the 9-bit group-id of the compressed multicast address is - * known. It is true if the 9-bit group is the all nodes or all routers - * group. Parameter 'a' is typed uint8_t * - */ - -#define SIXLOWPAN_IS_MCASTADDR_DECOMPRESSABLE(a) \ - (((*a & 0x01) == 0) && \ - ((*(a + 1) == 0x01) || (*(a + 1) == 0x02))) - -/* Check whether the 112-bit group-id of the multicast address is mappable - * to a 9-bit group-id. It is true if the group is the all nodes or all - * routers group: - * - * XXXX:0000:0000:0000:0000:0000:0000:0001 All nodes address - * XXXX:0000:0000:0000:0000:0000:0000:0002 All routers address - */ - -#define SIXLOWPAN_IS_MCASTADDR_COMPRESSABLE(a) \ - ((a)[1] == 0 && (a)[2] == 0 && (a)[3] == 0 && \ - (a)[4] == 0 && (a)[5] == 0 && (a)[6] == 0 && \ - ((a)[7] == HTONS(0x0001) || (a)[7] == HTONS(0x0002))) - -/* FFXX:0000:0000:0000:0000:00XX:XXXX:XXXX */ - -#define SIXLOWPAN_IS_MCASTADDR_COMPRESSABLE48(a) \ - ((a)[1] == 0 && (a)[2] == 0 && (a)[3] == 0 && \ - (a)[4] == 0 && (((a)[5] & HTONS(0xff00)) == 0)) - -/* FFXX:0000:0000:0000:0000:0000:00XX:XXXX */ - -#define SIXLOWPAN_IS_MCASTADDR_COMPRESSABLE32(a) \ - ((a)[1] == 0 && (a)[2] == 0 && (a)[3] == 0 && \ - (a)[4] == 0 && (a)[5] == 0 && ((a)[6] & HTONS(0xff00)) == 0) - -/* FF02:0000:0000:0000:0000:0000:0000:00XX */ - -#define SIXLOWPAN_IS_MCASTADDR_COMPRESSABLE8(a) \ - ((((a)[0] & HTONS(0x00ff)) == HTONS(0x0002)) && \ - (a)[1] == 0 && (a)[2] == 0 && (a)[3] == 0 && \ - (a)[4] == 0 && (a)[5] == 0 && (a)[6] == 0 && \ - (((a)[7] & HTONS(0xff00)) == 0x0000)) - /* General helper macros ****************************************************/ #define GETINT16(ptr,index) \ -- GitLab From 35ca7331084bd79f1e2fcb5b05eb3b82af9a287d Mon Sep 17 00:00:00 2001 From: Mark Schulte Date: Sat, 8 Apr 2017 12:34:08 -0600 Subject: [PATCH 385/990] pthread.h: Fix rwlock initializer --- configs/sim/sixlowpan/defconfig | 2 +- include/nuttx/net/sixlowpan.h | 13 ++- include/pthread.h | 2 +- net/netdev/netdev_ioctl.c | 4 +- net/procfs/netdev_statistics.c | 30 +++--- net/sixlowpan/Kconfig | 11 ++- net/sixlowpan/sixlowpan_framer.c | 20 ++-- net/sixlowpan/sixlowpan_internal.h | 6 +- net/sixlowpan/sixlowpan_utils.c | 24 ++--- wireless/ieee802154/mac802154_loopback.c | 113 +++++++++++++---------- 10 files changed, 122 insertions(+), 103 deletions(-) diff --git a/configs/sim/sixlowpan/defconfig b/configs/sim/sixlowpan/defconfig index ac4d9e35de..0c6809ad43 100644 --- a/configs/sim/sixlowpan/defconfig +++ b/configs/sim/sixlowpan/defconfig @@ -539,7 +539,7 @@ CONFIG_NET_6LOWPAN_MAXADDRCONTEXT=1 CONFIG_NET_6LOWPAN_MAXADDRCONTEXT_PREFIX_0_0=0xaa CONFIG_NET_6LOWPAN_MAXADDRCONTEXT_PREFIX_0_1=0xaa # CONFIG_NET_6LOWPAN_MAXADDRCONTEXT_PREINIT_1 is not set -CONFIG_NET_6LOWPAN_RIMEADDR_SIZE=2 +# CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED is not set CONFIG_NET_6LOWPAN_MAXAGE=20 CONFIG_NET_6LOWPAN_MAX_MACTRANSMITS=4 CONFIG_NET_6LOWPAN_MAXPAYLOAD=102 diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index a98cfa457c..e2f3eaf1f7 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -63,6 +63,17 @@ * Pre-processor Definitions ****************************************************************************/ +/* By default, a 2-byte Rime address is used for the IEEE802.15.4 MAC + * device's link layer address. If CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED + * is selected, then an 8-byte Rime address will be used. + */ + +#ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED +# define NET_6LOWPAN_RIMEADDR_SIZE 8 +#else +# define NET_6LOWPAN_RIMEADDR_SIZE 2 +#endif + /* Frame format definitions *************************************************/ /* Fragment header. * @@ -374,7 +385,7 @@ struct rimeaddr_s { - uint8_t u8[CONFIG_NET_6LOWPAN_RIMEADDR_SIZE]; + uint8_t u8[NET_6LOWPAN_RIMEADDR_SIZE]; }; /* The device structure for IEEE802.15.4 MAC network device differs from the diff --git a/include/pthread.h b/include/pthread.h index 225a7ef8b0..e70ad06e5b 100644 --- a/include/pthread.h +++ b/include/pthread.h @@ -352,7 +352,7 @@ typedef int pthread_rwlockattr_t; #define PTHREAD_RWLOCK_INITIALIZER {PTHREAD_MUTEX_INITIALIZER, \ PTHREAD_COND_INITIALIZER, \ - 0, 0} + 0, 0, false} #ifdef CONFIG_PTHREAD_CLEANUP /* This type describes the pthread cleanup callback (non-standard) */ diff --git a/net/netdev/netdev_ioctl.c b/net/netdev/netdev_ioctl.c index 413a5d10fc..1a845774fc 100644 --- a/net/netdev/netdev_ioctl.c +++ b/net/netdev/netdev_ioctl.c @@ -739,7 +739,7 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, req->ifr_hwaddr.sa_family = AF_INETX; memcpy(req->ifr_hwaddr.sa_data, ieee->i_nodeaddr.u8, - CONFIG_NET_6LOWPAN_RIMEADDR_SIZE); + NET_6LOWPAN_RIMEADDR_SIZE); ret = OK; } else @@ -782,7 +782,7 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, req->ifr_hwaddr.sa_family = AF_INETX; memcpy(ieee->i_nodeaddr.u8, req->ifr_hwaddr.sa_data, - CONFIG_NET_6LOWPAN_RIMEADDR_SIZE); + NET_6LOWPAN_RIMEADDR_SIZE); ret = OK; } else diff --git a/net/procfs/netdev_statistics.c b/net/procfs/netdev_statistics.c index d7673507b7..b2b83da801 100644 --- a/net/procfs/netdev_statistics.c +++ b/net/procfs/netdev_statistics.c @@ -151,12 +151,7 @@ static int netprocfs_linklayer(FAR struct netprocfs_file_s *netfile) { ieee = (FAR struct ieee802154_driver_s *)dev; -#if CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 2 - len += snprintf(&netfile->line[len], NET_LINELEN - len, - "%s\tLink encap:6loWPAN HWaddr %02x:%02x", - dev->d_ifname, - ieee->i_nodeaddr.u8[0], ieee->i_nodeaddr.u8[1]); -#else /* CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 8 */ +#ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED len += snprintf(&netfile->line[len], NET_LINELEN - len, "%s\tLink encap:6loWPAN HWaddr " "%02x:%02x:%02x:%02x:%02x:%02x:%02x:%02x", @@ -165,6 +160,11 @@ static int netprocfs_linklayer(FAR struct netprocfs_file_s *netfile) ieee->i_nodeaddr.u8[2], ieee->i_nodeaddr.u8[3], ieee->i_nodeaddr.u8[4], ieee->i_nodeaddr.u8[5], ieee->i_nodeaddr.u8[6], ieee->i_nodeaddr.u8[7]); +#else + len += snprintf(&netfile->line[len], NET_LINELEN - len, + "%s\tLink encap:6loWPAN HWaddr %02x:%02x", + dev->d_ifname, + ieee->i_nodeaddr.u8[0], ieee->i_nodeaddr.u8[1]); #endif } break; @@ -215,22 +215,22 @@ static int netprocfs_linklayer(FAR struct netprocfs_file_s *netfile) #elif defined(CONFIG_NET_6LOWPAN) ieee = (FAR struct ieee802154_driver_s *)dev; -#if CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 2 - len += snprintf(&netfile->line[len], NET_LINELEN - len, - "%s\tLink encap:6loWPAN HWaddr %02x:%02x at %s", - dev->d_ifname, - ieee->i_nodeaddr.u8[0], ieee->i_nodeaddr.u8[1], - status); -#else /* CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 8 */ +#ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED len += snprintf(&netfile->line[len], NET_LINELEN - len, "%s\tLink encap:6loWPAN HWaddr " - "%02x:%02x:%02x:%02x:%02x:%02x:%02x:%02x at %s", + "%02x:%02x:%02x:%02x:%02x:%02x:%02x:%02x at %s\n", dev->d_ifname, ieee->i_nodeaddr.u8[0], ieee->i_nodeaddr.u8[1], ieee->i_nodeaddr.u8[2], ieee->i_nodeaddr.u8[3], ieee->i_nodeaddr.u8[4], ieee->i_nodeaddr.u8[5], ieee->i_nodeaddr.u8[6], ieee->i_nodeaddr.u8[7], status); +#else + len += snprintf(&netfile->line[len], NET_LINELEN - len, + "%s\tLink encap:6loWPAN HWaddr %02x:%02x at %s\n", + dev->d_ifname, + ieee->i_nodeaddr.u8[0], ieee->i_nodeaddr.u8[1], + status); #endif #elif defined(CONFIG_NET_LOOPBACK) len += snprintf(&netfile->line[len], NET_LINELEN - len, @@ -443,7 +443,7 @@ static int netprocfs_txstatistics_header(FAR struct netprocfs_file_s *netfile) DEBUGASSERT(netfile != NULL); return snprintf(netfile->line, NET_LINELEN, "\tTX: %-8s %-8s %-8s %-8s\n", - "Queued", "Sent", "Erorts", "Timeouts"); + "Queued", "Sent", "Errors", "Timeouts"); } #endif /* CONFIG_NETDEV_STATISTICS */ diff --git a/net/sixlowpan/Kconfig b/net/sixlowpan/Kconfig index 02d17a42f1..a5eed25dd7 100644 --- a/net/sixlowpan/Kconfig +++ b/net/sixlowpan/Kconfig @@ -133,12 +133,13 @@ config NET_6LOWPAN_MAXADDRCONTEXT_PREFIX_2_1 endif # NET_6LOWPAN_MAXADDRCONTEXT_PREINIT_0 endif # NET_6LOWPAN_COMPRESSION_HC06 -config NET_6LOWPAN_RIMEADDR_SIZE - int "Rime address size" - default 2 - range 2 8 +config NET_6LOWPAN_RIMEADDR_EXTENDED + int "Extended Rime address" + default n ---help--- - Only the values 2 and 8 are supported + By default, a 2-byte Rime address is used for the IEEE802.15.4 MAC + device's link layer address. If this option is selected, then an + 8-byte Rime address will be used. config NET_6LOWPAN_MAXAGE int "Packet reassembly timeout" diff --git a/net/sixlowpan/sixlowpan_framer.c b/net/sixlowpan/sixlowpan_framer.c index b0953db648..746d6dc113 100644 --- a/net/sixlowpan/sixlowpan_framer.c +++ b/net/sixlowpan/sixlowpan_framer.c @@ -125,11 +125,7 @@ static inline uint8_t sixlowpan_addrlen(uint8_t addrmode) static bool sixlowpan_addrnull(FAR uint8_t *addr) { -#if CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 2 - int i = 2; -#else - int i = 8; -#endif + int i = NET_6LOWPAN_RIMEADDR_SIZE; while (i-- > 0) { @@ -354,10 +350,10 @@ static void sixlowpan_setup_params(FAR struct ieee802154_driver_s *ieee, /* Use short address mode if so configured */ -#if CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 2 - params->fcf.dest_addr_mode = FRAME802154_SHORTADDRMODE; -#else +#ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED params->fcf.dest_addr_mode = FRAME802154_LONGADDRMODE; +#else + params->fcf.dest_addr_mode = FRAME802154_SHORTADDRMODE; #endif } @@ -543,14 +539,14 @@ int sixlowpan_framecreate(FAR struct ieee802154_driver_s *ieee, wlinfo("Frame type: %02x hdrlen: %d\n", params.fcf.frame_type, hdrlen); -#if CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 2 - wlinfo("Dest address: %02x:%02x\n", - params.dest_addr[0], params.dest_addr[1]); -#else +#ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED wlinfo("Dest address: %02x:%02x:%02x:%02x:%02x:%02x:%02x:%02x\n", params.dest_addr[0], params.dest_addr[1], params.dest_addr[2], params.dest_addr[3], params.dest_addr[4], params.dest_addr[5], params.dest_addr[6], params.dest_addr[7]); +#else + wlinfo("Dest address: %02x:%02x\n", + params.dest_addr[0], params.dest_addr[1]); #endif return hdrlen; diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index 5445686373..da104f89be 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -74,13 +74,13 @@ /* Rime addres macros */ /* Copy a Rime address */ -#define rimeaddr_copy(dest,src) \ - memcpy(dest, src, CONFIG_NET_6LOWPAN_RIMEADDR_SIZE) +#define rimeaddr_copy(dest,src) \ + memcpy(dest, src, NET_6LOWPAN_RIMEADDR_SIZE) /* Compare two Rime addresses */ #define rimeaddr_cmp(addr1,addr2) \ - (memcmp(addr1, addr2, CONFIG_NET_6LOWPAN_RIMEADDR_SIZE) == 0) + (memcmp(addr1, addr2, NET_6LOWPAN_RIMEADDR_SIZE) == 0) /* Pointers in the Rime buffer */ diff --git a/net/sixlowpan/sixlowpan_utils.c b/net/sixlowpan/sixlowpan_utils.c index fc322ec38e..dcda6be652 100644 --- a/net/sixlowpan/sixlowpan_utils.c +++ b/net/sixlowpan/sixlowpan_utils.c @@ -88,14 +88,14 @@ void sixlowpan_ipfromrime(FAR const struct rimeaddr_s *rime, memset(ipaddr, 0, sizeof(net_ipv6addr_t)); ipaddr[0] = HTONS(0xfe80); -#if CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 2 +#ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED + memcpy(&ipaddr[4], rime, NET_6LOWPAN_RIMEADDR_SIZE); + ipaddr[4] ^= HTONS(0x0200); +#else ipaddr[5] = HTONS(0x00ff); ipaddr[6] = HTONS(0xfe00); - memcpy(&ipaddr[7], rime, CONFIG_NET_6LOWPAN_RIMEADDR_SIZE); + memcpy(&ipaddr[7], rime, NET_6LOWPAN_RIMEADDR_SIZE); ipaddr[7] ^= HTONS(0x0200); -#else - memcpy(&ipaddr[4], rime, CONFIG_NET_6LOWPAN_RIMEADDR_SIZE); - ipaddr[4] ^= HTONS(0x0200); #endif } @@ -119,10 +119,10 @@ void sixlowpan_rimefromip(const net_ipv6addr_t ipaddr, DEBUGASSERT(ipaddr[0] == HTONS(0xfe80)); -#if CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 2 - memcpy(rime, &ipaddr[7], CONFIG_NET_6LOWPAN_RIMEADDR_SIZE); +#ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED + memcpy(rime, &ipaddr[4], NET_6LOWPAN_RIMEADDR_SIZE); #else - memcpy(rime, &ipaddr[4], CONFIG_NET_6LOWPAN_RIMEADDR_SIZE); + memcpy(rime, &ipaddr[7], NET_6LOWPAN_RIMEADDR_SIZE); #endif rime->u8[0] ^= 0x02; } @@ -145,14 +145,14 @@ bool sixlowpan_ismacbased(const net_ipv6addr_t ipaddr, { FAR const uint8_t *rimeptr = rime->u8; -#if CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 2 - return (ipaddr[5] == HTONS(0x00ff) && ipaddr[6] == HTONS(0xfe00) && - ipaddr[7] == htons((GETINT16(rimeptr, 0) ^ 0x0200))); -#else /* CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 8 */ +#ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED return (ipaddr[4] == htons((GETINT16(rimeptr, 0) ^ 0x0200)) && ipaddr[5] == GETINT16(rimeptr, 2) && ipaddr[6] == GETINT16(rimeptr, 4) && ipaddr[7] == GETINT16(rimeptr, 6)); +#else + return (ipaddr[5] == HTONS(0x00ff) && ipaddr[6] == HTONS(0xfe00) && + ipaddr[7] == htons((GETINT16(rimeptr, 0) ^ 0x0200))); #endif } diff --git a/wireless/ieee802154/mac802154_loopback.c b/wireless/ieee802154/mac802154_loopback.c index 9cb9f09641..994289642b 100644 --- a/wireless/ieee802154/mac802154_loopback.c +++ b/wireless/ieee802154/mac802154_loopback.c @@ -195,57 +195,68 @@ static int lo_txpoll(FAR struct net_driver_s *dev) while (head != NULL) { - /* Remove the IOB from the queue */ + /* Increment statistics */ - iob = head; - head = iob->io_flink; - iob->io_flink = NULL; + NETDEV_RXPACKETS(&priv->lo_ieee.i_dev); - /* Is the queue now empty? */ + /* Remove the IOB from the queue */ - if (head == NULL) - { - tail = NULL; - } + iob = head; + head = iob->io_flink; + iob->io_flink = NULL; - /* Return the next frame to the network */ + /* Is the queue now empty? */ - iob->io_flink = NULL; - priv->lo_ieee.i_framelist = iob; + if (head == NULL) + { + tail = NULL; + } + + /* Return the next frame to the network */ + + iob->io_flink = NULL; + priv->lo_ieee.i_framelist = iob; + + ninfo("Send frame %p to the network. Length=%u\n", iob, iob->io_len); + ret = sixlowpan_input(&priv->lo_ieee); + + /* Increment statistics */ + + NETDEV_TXPACKETS(&priv->lo_ieee.i_dev); - ninfo("Send frame %p to the network. Length=%u\n", iob, iob->io_len); - ret = sixlowpan_input(&priv->lo_ieee); - if (ret < 0) - { - nerr("ERROR: sixlowpan_input returned %d\n", ret); - } + if (ret < 0) + { + nerr("ERROR: sixlowpan_input returned %d\n", ret); + NETDEV_TXERRORS(&priv->lo_ieee.i_dev); + NETDEV_ERRORS(&priv->lo_ieee.i_dev); + } - /* What if the network responds with more frames to send? */ + /* What if the network responds with more frames to send? */ - if (priv->lo_ieee.i_framelist != NULL) - { - /* Append the new list to the tail of the queue */ + if (priv->lo_ieee.i_framelist != NULL) + { + /* Append the new list to the tail of the queue */ - iob = priv->lo_ieee.i_framelist; - priv->lo_ieee.i_framelist = NULL; + iob = priv->lo_ieee.i_framelist; + priv->lo_ieee.i_framelist = NULL; - if (tail == NULL) - { - head = iob; - } - else - { - tail->io_flink = iob; - } + if (tail == NULL) + { + head = iob; + } + else + { + tail->io_flink = iob; + } - /* Find the new tail of the IOB queue */ + /* Find the new tail of the IOB queue */ - for (tail = iob, iob = iob->io_flink; - iob != NULL; - tail = iob, iob = iob->io_flink); - } + for (tail = iob, iob = iob->io_flink; + iob != NULL; + tail = iob, iob = iob->io_flink); + } - priv->lo_txdone = true; + priv->lo_txdone = true; } return 0; @@ -352,17 +363,17 @@ static int lo_ifup(FAR struct net_driver_s *dev) dev->d_ipv6addr[3], dev->d_ipv6addr[4], dev->d_ipv6addr[5], dev->d_ipv6addr[6], dev->d_ipv6addr[7]); -#if CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 2 - ninfo(" Node: %02x:%02x PANID=%04x\n", - priv->lo_ieee.i_nodeaddr.u8[0], priv->lo_ieee.i_nodeaddr.u8[1], - priv->lo_ieee.i_panid); -#else /* CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 8 */ +#ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED ninfo(" Node: %02x:%02x:%02x:%02x:%02x:%02x:%02x:%02x PANID=%04x\n", priv->lo_ieee.i_nodeaddr.u8[0], priv->lo_ieee.i_nodeaddr.u8[1], priv->lo_ieee.i_nodeaddr.u8[2], priv->lo_ieee.i_nodeaddr.u8[3], priv->lo_ieee.i_nodeaddr.u8[4], priv->lo_ieee.i_nodeaddr.u8[5], priv->lo_ieee.i_nodeaddr.u8[6], priv->lo_ieee.i_nodeaddr.u8[7], priv->lo_ieee.i_panid); +#else + ninfo(" Node: %02x:%02x PANID=%04x\n", + priv->lo_ieee.i_nodeaddr.u8[0], priv->lo_ieee.i_nodeaddr.u8[1], + priv->lo_ieee.i_panid); #endif /* Set and activate a timer process */ @@ -508,12 +519,12 @@ static int lo_txavail(FAR struct net_driver_s *dev) #if defined(CONFIG_NET_IGMP) || defined(CONFIG_NET_ICMPv6) static int lo_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) { -#if CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 2 - ninfo("MAC: %02x:%02x\n", - mac[0], mac[1]); -#else /* CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 8 */ +#ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED ninfo("MAC: %02x:%02x:%02x:%02x:%02x:%02x:%02x:%02x\n", mac[0], mac[1], mac[2], mac[3], mac[4], mac[5], mac[6], mac[7]); +#else + ninfo("MAC: %02x:%02x\n", + mac[0], mac[1]); #endif /* There is no multicast support in the loopback driver */ @@ -543,12 +554,12 @@ static int lo_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) #ifdef CONFIG_NET_IGMP static int lo_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) { -#if CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 2 - ninfo("MAC: %02x:%02x\n", - mac[0], mac[1]); -#else /* CONFIG_NET_6LOWPAN_RIMEADDR_SIZE == 8 */ +#ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED ninfo("MAC: %02x:%02x:%02x:%02x:%02x:%02x:%02x:%02x\n", mac[0], mac[1], mac[2], mac[3], mac[4], mac[5], mac[6], mac[7]); +#else + ninfo("MAC: %02x:%02x\n", + mac[0], mac[1]); #endif /* There is no multicast support in the loopback driver */ -- GitLab From 83660ac30e7f64b529977b61e183c1e5005bda8d Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 8 Apr 2017 13:27:03 -0600 Subject: [PATCH 386/990] Add configuration/build support for an IEEE802.15.4 network device. --- wireless/ieee802154/Kconfig | 34 +++++++++++++++++++++++++++++++++- wireless/ieee802154/Make.defs | 4 ++++ 2 files changed, 37 insertions(+), 1 deletion(-) diff --git a/wireless/ieee802154/Kconfig b/wireless/ieee802154/Kconfig index b46aada66d..64b9e66e91 100644 --- a/wireless/ieee802154/Kconfig +++ b/wireless/ieee802154/Kconfig @@ -37,13 +37,45 @@ config IEEE802154_DEV Enables a device driver to expose ieee802.15.4 radio controls to user space as IOCTLs. +config IEEE802154_NETDEV + bool "IEEE802154 6loWPAN Network Device" + default n + depends on NET_6LOWPAN && NET_IPv6 + select ARCH_HAVE_NETDEV_STATISTICS + ---help--- + Add support for the IEEE802.15.4 6loWPAN network device built on + the common IEEE802.15.4 MAC. + +if IEEE802154_NETDEV + +choice + prompt "Work queue" + default IEEE802154_NETDEV_LPWORK if SCHED_LPWORK + default IEEE802154_NETDEV_HPWORK if !SCHED_LPWORK && SCHED_HPWORK + depends on SCHED_WORKQUEUE + ---help--- + Work queue support is required to use the IEEE802.15.4 network + driver. If the low priority work queue is available, then it shoul + be used by the loopback driver. + +config IEEE802154_NETDEV_HPWORK + bool "High priority" + depends on SCHED_HPWORK + +config IEEE802154_NETDEV_LPWORK + bool "Low priority" + depends on SCHED_LPWORK + +endchoice # Work queue +endif # IEEE802154_NETDEV + config IEEE802154_LOOPBACK bool "IEEE802154 6loWPAN Loopback" default n depends on NET_6LOWPAN && NET_IPv6 select ARCH_HAVE_NETDEV_STATISTICS ---help--- - Add support for the IEEE802154 6loWPAN Loopback test device. + Add support for the IEEE802.15.4 6loWPAN Loopback test device. if IEEE802154_LOOPBACK diff --git a/wireless/ieee802154/Make.defs b/wireless/ieee802154/Make.defs index bb2531e3e7..fc4db543bf 100644 --- a/wireless/ieee802154/Make.defs +++ b/wireless/ieee802154/Make.defs @@ -53,6 +53,10 @@ ifeq ($(CONFIG_IEEE802154_DEV),y) CSRCS += radio802154_device.c endif +ifeq ($(CONFIG_IEEE802154_NETDEV),y) +CSRCS += mac802154_netdev.c +endif + ifeq ($(CONFIG_IEEE802154_LOOPBACK),y) CSRCS += mac802154_loopback.c endif -- GitLab From 8b8ddd05c28a3ba25e8ae2f7fb19330bfb89bdf0 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 8 Apr 2017 13:30:30 -0600 Subject: [PATCH 387/990] Fix some old-style interrupt handling logic in drivers/net/skeleton.c --- drivers/net/skeleton.c | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/drivers/net/skeleton.c b/drivers/net/skeleton.c index d354ab8130..9a8d4e8eed 100644 --- a/drivers/net/skeleton.c +++ b/drivers/net/skeleton.c @@ -136,6 +136,10 @@ struct skel_driver_s /* A single packet buffer per device is used here. There might be multiple * packet buffers in a more complex, pipelined design. + * + * NOTE that if CONFIG_skeleton_NINTERFACES were greater than 1, you would + * need a minimum on one packetbuffer per instance. Much better to be + * allocated dynamically. */ static uint8_t g_pktbuf[MAX_NET_DEV_MTU + CONFIG_NET_GUARDSIZE]; @@ -557,7 +561,9 @@ static void skel_interrupt_work(FAR void *arg) static int skel_interrupt(int irq, FAR void *context, FAR void *arg) { - FAR struct skel_driver_s *priv = &g_skel[0]; + FAR struct skel_driver_s *priv = (FAR struct skel_driver_s *)arg; + + DEBUGASSERT(priv != NULL); /* Disable further Ethernet interrupts. Because Ethernet interrupts are * also disabled if the TX timeout event occurs, there can be no race @@ -1101,7 +1107,7 @@ int skel_initialize(int intf) /* Attach the IRQ to the driver */ - if (irq_attach(CONFIG_skeleton_IRQ, skel_interrupt, NULL)) + if (irq_attach(CONFIG_skeleton_IRQ, skel_interrupt, priv)) { /* We could not attach the ISR to the interrupt */ -- GitLab From a1aca89d6115301f153de280b3587184ed248079 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 8 Apr 2017 13:55:23 -0600 Subject: [PATCH 388/990] drivers/net/skeleton.c: Use more common 'Name:' vs. 'Function:' --- drivers/net/skeleton.c | 38 +++++++++++++++++++------------------- 1 file changed, 19 insertions(+), 19 deletions(-) diff --git a/drivers/net/skeleton.c b/drivers/net/skeleton.c index 9a8d4e8eed..bb1a543ff9 100644 --- a/drivers/net/skeleton.c +++ b/drivers/net/skeleton.c @@ -196,7 +196,7 @@ static void skel_ipv6multicast(FAR struct skel_driver_s *priv); ****************************************************************************/ /**************************************************************************** - * Function: skel_transmit + * Name: skel_transmit * * Description: * Start hardware transmission. Called either from the txdone interrupt @@ -237,7 +237,7 @@ static int skel_transmit(FAR struct skel_driver_s *priv) } /**************************************************************************** - * Function: skel_txpoll + * Name: skel_txpoll * * Description: * The transmitter is available, check if the network has any outgoing @@ -309,7 +309,7 @@ static int skel_txpoll(FAR struct net_driver_s *dev) } /**************************************************************************** - * Function: skel_receive + * Name: skel_receive * * Description: * An interrupt was received indicating the availability of a new RX packet @@ -451,7 +451,7 @@ static void skel_receive(FAR struct skel_driver_s *priv) } /**************************************************************************** - * Function: skel_txdone + * Name: skel_txdone * * Description: * An interrupt was received indicating that the last TX packet(s) is done @@ -491,7 +491,7 @@ static void skel_txdone(FAR struct skel_driver_s *priv) } /**************************************************************************** - * Function: skel_interrupt_work + * Name: skel_interrupt_work * * Description: * Perform interrupt related work from the worker thread @@ -543,7 +543,7 @@ static void skel_interrupt_work(FAR void *arg) } /**************************************************************************** - * Function: skel_interrupt + * Name: skel_interrupt * * Description: * Hardware interrupt handler @@ -590,7 +590,7 @@ static int skel_interrupt(int irq, FAR void *context, FAR void *arg) } /**************************************************************************** - * Function: skel_txtimeout_work + * Name: skel_txtimeout_work * * Description: * Perform TX timeout related work from the worker thread @@ -631,7 +631,7 @@ static void skel_txtimeout_work(FAR void *arg) } /**************************************************************************** - * Function: skel_txtimeout_expiry + * Name: skel_txtimeout_expiry * * Description: * Our TX watchdog timed out. Called from the timer interrupt handler. @@ -666,7 +666,7 @@ static void skel_txtimeout_expiry(int argc, wdparm_t arg, ...) } /**************************************************************************** - * Function: skel_poll_process + * Name: skel_poll_process * * Description: * Perform the periodic poll. This may be called either from watchdog @@ -687,7 +687,7 @@ static inline void skel_poll_process(FAR struct skel_driver_s *priv) } /**************************************************************************** - * Function: skel_poll_work + * Name: skel_poll_work * * Description: * Perform periodic polling from the worker thread @@ -736,7 +736,7 @@ static void skel_poll_work(FAR void *arg) } /**************************************************************************** - * Function: skel_poll_expiry + * Name: skel_poll_expiry * * Description: * Periodic timer handler. Called from the timer interrupt handler. @@ -763,7 +763,7 @@ static void skel_poll_expiry(int argc, wdparm_t arg, ...) } /**************************************************************************** - * Function: skel_ifup + * Name: skel_ifup * * Description: * NuttX Callback: Bring up the Ethernet interface when an IP address is @@ -818,7 +818,7 @@ static int skel_ifup(FAR struct net_driver_s *dev) } /**************************************************************************** - * Function: skel_ifdown + * Name: skel_ifdown * * Description: * NuttX Callback: Stop the interface. @@ -861,7 +861,7 @@ static int skel_ifdown(FAR struct net_driver_s *dev) } /**************************************************************************** - * Function: skel_txavail_work + * Name: skel_txavail_work * * Description: * Perform an out-of-cycle poll on the worker thread. @@ -904,7 +904,7 @@ static void skel_txavail_work(FAR void *arg) } /**************************************************************************** - * Function: skel_txavail + * Name: skel_txavail * * Description: * Driver callback invoked when new TX data is available. This is a @@ -942,7 +942,7 @@ static int skel_txavail(FAR struct net_driver_s *dev) } /**************************************************************************** - * Function: skel_addmac + * Name: skel_addmac * * Description: * NuttX Callback: Add the specified MAC address to the hardware multicast @@ -971,7 +971,7 @@ static int skel_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) #endif /**************************************************************************** - * Function: skel_rmmac + * Name: skel_rmmac * * Description: * NuttX Callback: Remove the specified MAC address from the hardware multicast @@ -1000,7 +1000,7 @@ static int skel_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) #endif /**************************************************************************** - * Function: skel_ipv6multicast + * Name: skel_ipv6multicast * * Description: * Configure the IPv6 multicast MAC address. @@ -1078,7 +1078,7 @@ static void skel_ipv6multicast(FAR struct skel_driver_s *priv) ****************************************************************************/ /**************************************************************************** - * Function: skel_initialize + * Name: skel_initialize * * Description: * Initialize the Ethernet controller and driver -- GitLab From 11bd9afe5329de69d567df85a7a538e82ae764b9 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 8 Apr 2017 14:21:20 -0600 Subject: [PATCH 389/990] wireless/ieee802154: Add a partial implementation of the IEEE802.15.4 network driver. This is very incomplete on the initial commit. --- wireless/ieee802154/mac802154_loopback.c | 2 +- wireless/ieee802154/mac802154_netdev.c | 1365 ++++++++++++++++++++++ 2 files changed, 1366 insertions(+), 1 deletion(-) create mode 100644 wireless/ieee802154/mac802154_netdev.c diff --git a/wireless/ieee802154/mac802154_loopback.c b/wireless/ieee802154/mac802154_loopback.c index 994289642b..71255f0d60 100644 --- a/wireless/ieee802154/mac802154_loopback.c +++ b/wireless/ieee802154/mac802154_loopback.c @@ -603,7 +603,7 @@ int ieee8021514_loopback(void) memset(priv, 0, sizeof(struct lo_driver_s)); - dev = &priv->lo_ieee.i_dev; + dev = &priv->lo_ieee.i_dev; dev->d_ifup = lo_ifup; /* I/F up (new IP address) callback */ dev->d_ifdown = lo_ifdown; /* I/F down callback */ dev->d_txavail = lo_txavail; /* New TX data callback */ diff --git a/wireless/ieee802154/mac802154_netdev.c b/wireless/ieee802154/mac802154_netdev.c new file mode 100644 index 0000000000..807320811c --- /dev/null +++ b/wireless/ieee802154/mac802154_netdev.c @@ -0,0 +1,1365 @@ +/**************************************************************************** + * wireless/ieee802154/mac802154_netdev.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#ifdef CONFIG_NET_6LOWPAN + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* If processing is not done at the interrupt level, then work queue support + * is required. + */ + +#if !defined(CONFIG_SCHED_WORKQUEUE) +# error Work queue support is required in this configuration (CONFIG_SCHED_WORKQUEUE) +#else + + /* Use the selected work queue */ + +# if defined(CONFIG_IEEE802154_NETDEV_HPWORK) +# define ETHWORK HPWORK +# elif defined(CONFIG_IEEE802154_NETDEV_LPWORK) +# define ETHWORK LPWORK +# else +# error Neither CONFIG_IEEE802154_NETDEV_HPWORK nor CONFIG_IEEE802154_NETDEV_LPWORK defined +# endif +#endif + +/* CONFIG_IEEE802154_NETDEV_NINTERFACES determines the number of physical interfaces + * that will be supported. + */ + +#ifndef CONFIG_IEEE802154_NETDEV_NINTERFACES +# define CONFIG_IEEE802154_NETDEV_NINTERFACES 1 +#endif + +/* TX poll delay = 1 seconds. CLK_TCK is the number of clock ticks per second */ + +#define skeleton_WDDELAY (1*CLK_TCK) + +/* TX timeout = 1 minute */ + +#define skeleton_TXTIMEOUT (60*CLK_TCK) + +/* This is a helper pointer for accessing the contents of the Ethernet header */ + +#define BUF ((struct eth_hdr_s *)priv->m8_dev.d_buf) + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/* The mac802154_driver_s encapsulates all state information for a single hardware + * interface + */ + +struct mac802154_driver_s +{ + /* This holds the information visible to the NuttX network */ + + struct ieee802154_driver_s m8_dev; /* Interface understood by the network */ + struct ieee802154_mac_s m8_mac; /* Interface understood by the MAC */ + + /* For internal use by this driver */ + + bool m8_bifup; /* true:ifup false:ifdown */ + WDOG_ID m8_txpoll; /* TX poll timer */ + WDOG_ID m8_txtimeout; /* TX timeout timer */ + struct work_s m8_irqwork; /* For deferring interupt work to the work queue */ + struct work_s m8_pollwork; /* For deferring poll work to the work queue */ +}; + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +struct ieee802154_radio_s; /* Forware reference */ + + +{ + + struct ieee802154_macops_s ops; + struct ieee802154_maccb_s cbs; +}; + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* A single packet buffer per device is used here. There might be multiple + * packet buffers in a more complex, pipelined design. + */ + +static uint8_t g_pktbuf[MAX_NET_DEV_MTU + CONFIG_NET_GUARDSIZE]; + +/* Driver state structure */ + +static struct mac802154_driver_s g_skel[CONFIG_IEEE802154_NETDEV_NINTERFACES]; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* IEE802.15.4 MAC callback functions ***************************************/ +/* Asynchronous confirmations to requests */ + +static void mac802154_conf_data(FAR struct ieee802154_mac_s *mac, + FAR struct ieee802154_data_conf_s *conf); +static void mac802154_conf_purge(FAR struct ieee802154_mac_s *mac, + uint8_t handle, int status); +static void mac802154_conf_associate(FAR struct ieee802154_mac_s *mac, + uint16_t saddr, int status); +static void mac802154_conf_disassociate(FAR struct ieee802154_mac_s *mac, +static void mac802154_conf_get(FAR struct ieee802154_mac_s *mac, int status, + int attribute, FAR uint8_t *value, int valuelen); +static void mac802154_conf_gts(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *characteristics, int status); +static void mac802154_conf_reset(FAR struct ieee802154_mac_s *mac, + int status); +static void mac802154_conf_rxenable(FAR struct ieee802154_mac_s *mac, + int status); +static void mac802154_conf_scan(FAR struct ieee802154_mac_s *mac, + int status, uint8_t type, uint32_t unscanned, int rsltsize, + FAR uint8_t *edlist, FAR uint8_t *pandescs); +static void mac802154_conf_set(FAR struct ieee802154_mac_s *mac, int status, + int attribute); +static void mac802154_conf_start(FAR struct ieee802154_mac_s *mac, + int status); +static void mac802154_conf_poll(FAR struct ieee802154_mac_s *mac, + int status); + + /* Asynchronous event indications, replied to synchronously with responses */ + +static void mac802154_ind_data(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *buf, int len); +static void mac802154_ind_associate(FAR struct ieee802154_mac_s *mac, + uint16_t clipanid, FAR uint8_t *clieaddr); +static void mac802154_ind_disassociate(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *eadr, uint8_t reason); +static void mac802154_ind_beaconnotify(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *bsn, FAR struct ieee802154_pan_desc_s *pandesc, + FAR uint8_t *sdu, int sdulen); +static void mac802154_ind_gts(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *devaddr, FAR uint8_t *characteristics); +static void mac802154_ind_orphan(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *orphanaddr); +static void mac802154_ind_commstatus(FAR struct ieee802154_mac_s *mac, + uint16_t panid, FAR uint8_t *src, FAR uint8_t *dst, + int status); +static void mac802154_ind_syncloss(FAR struct ieee802154_mac_s *mac, + int reason); + +/* Network interface support ************************************************/ +/* Common TX logic */ + +static int mac802154_transmit(FAR struct mac802154_driver_s *priv); +static int mac802154_txpoll(FAR struct net_driver_s *dev); + +/* Frame transfer */ + +static void mac802154_receive(FAR struct mac802154_driver_s *priv); +static void mac802154_txdone(FAR struct mac802154_driver_s *priv); + +static void mac802154_transfer_work(FAR void *arg); +static int mac802154_transfer(int irq, FAR void *context, FAR void *arg); + +/* Watchdog timer expirations */ + +static void mac802154_txtimeout_work(FAR void *arg); +static void mac802154_txtimeout_expiry(int argc, wdparm_t arg, ...); + +static void mac802154_poll_work(FAR void *arg); +static void mac802154_poll_expiry(int argc, wdparm_t arg, ...); + +/* NuttX callback functions */ + +static int mac802154_ifup(FAR struct net_driver_s *dev); +static int mac802154_ifdown(FAR struct net_driver_s *dev); + +static void mac802154_txavail_work(FAR void *arg); +static int mac802154_txavail(FAR struct net_driver_s *dev); + +#if defined(CONFIG_NET_IGMP) || defined(CONFIG_NET_ICMPv6) +static int mac802154_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac); +#ifdef CONFIG_NET_IGMP +static int mac802154_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac); +#endif +#ifdef CONFIG_NET_ICMPv6 +static void mac802154_ipv6multicast(FAR struct mac802154_driver_s *priv); +#endif +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: mac802154_conf_data + * + * Description: + * Data frame was received by remote device + * + ****************************************************************************/ + +static void mac802154_conf_data(FAR struct ieee802154_mac_s *mac, + FAR struct ieee802154_data_conf_s *conf) +{ +} + +/**************************************************************************** + * Name: mac802154_conf_purge + * + * Description: + * Data frame was purged + * + ****************************************************************************/ + +static void mac802154_conf_purge(FAR struct ieee802154_mac_s *mac, + uint8_t handle, int status) +{ +} + +/**************************************************************************** + * Name: mac802154_conf_associate + * + * Description: + * Association request completed + * + ****************************************************************************/ + +static void mac802154_conf_associate(FAR struct ieee802154_mac_s *mac, + uint16_t saddr, int status) +{ +} + +/**************************************************************************** + * Name: mac802154_conf_disassociate + * + * Description: + * Disassociation request completed + * + ****************************************************************************/ + +static void mac802154_conf_disassociate(FAR struct ieee802154_mac_s *mac, +{ +} + +/**************************************************************************** + * Name: mac802154_conf_get + * + * Description: + * PIvoata returned + * + ****************************************************************************/ + +static void mac802154_conf_get(FAR struct ieee802154_mac_s *mac, int status, + int attribute, FAR uint8_t *value, + int valuelen) +{ +} + +/**************************************************************************** + * Name: mac802154_conf_gts + * + * Description: + * GTvoanagement completed + * + ****************************************************************************/ + +static void mac802154_conf_gts(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *characteristics, int status) +{ +} + +/**************************************************************************** + * Name: mac802154_conf_reset + * + * Description: + * MAveset completed + * + ****************************************************************************/ + +static void mac802154_conf_reset(FAR struct ieee802154_mac_s *mac, + int status) +{ +} + +/**************************************************************************** + * Name: mac802154_conf_rxenable + * + * Description: + * + ****************************************************************************/ + +static void mac802154_conf_rxenable(FAR struct ieee802154_mac_s *mac, + int status) +{ +} + +/**************************************************************************** + * Name: mac802154_conf_scan + * + * Description: + * + ****************************************************************************/ + +static void mac802154_conf_scan(FAR struct ieee802154_mac_s *mac, + int status, uint8_t type, + uint32_t unscanned, int rsltsize, + FAR uint8_t *edlist, FAR uint8_t *pandescs) +{ +} + +/**************************************************************************** + * Name: mac802154_conf_set + * + * Description: + * + ****************************************************************************/ + +static void mac802154_conf_set(FAR struct ieee802154_mac_s *mac, int status, + int attribute) +{ +} + +/**************************************************************************** + * Name: mac802154_conf_start + * + * Description: + * + ****************************************************************************/ + +static void mac802154_conf_start(FAR struct ieee802154_mac_s *mac, + int status) +{ +} + +/**************************************************************************** + * Name: mac802154_conf_poll + * + * Description: + * + ****************************************************************************/ + +static void mac802154_conf_poll(FAR struct ieee802154_mac_s *mac, + int status) +{ +} + +/**************************************************************************** + * Name: mac802154_ind_data + * + * Description: + * Data frame received + * + ****************************************************************************/ + +static void mac802154_ind_data(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *buf, int len) +{ +} + +/**************************************************************************** + * Name: mac802154_ind_associate + * + * Description: + * Association request received + * + ****************************************************************************/ + +static void mac802154_ind_associate(FAR struct ieee802154_mac_s *mac, + uint16_t clipanid, + FAR uint8_t *clieaddr) +{ +} + +/**************************************************************************** + * Name: mac802154_ind_disassociate + * + * Description: + * Disassociation request received + * + ****************************************************************************/ + +static void mac802154_ind_disassociate(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *eadr, uint8_t reason) +{ +} + +/**************************************************************************** + * Name: mac802154_ind_beaconnotify + * + * Description: + * Beacon notification + * + ****************************************************************************/ + +static void mac802154_ind_beaconnotify(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *bsn, + FAR struct ieee802154_pan_desc_s *pandesc, + FAR uint8_t *sdu, int sdulen) +{ +} + +/**************************************************************************** + * Name: mac802154_ind_gts + * + * Description: + * GTS management request received + * + ****************************************************************************/ + +static void mac802154_ind_gts(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *devaddr, + FAR uint8_t *characteristics) +{ +} + +/**************************************************************************** + * Name: mac802154_ind_orphan + * + * Description: + * Orphan device detected + * + ****************************************************************************/ + +static void mac802154_ind_orphan(FAR struct ieee802154_mac_s *mac, + FAR uint8_t *orphanaddr) +{ +} + +/**************************************************************************** + * Name: mac802154_ind_commstatus + * + * Description: + * + ****************************************************************************/ + +static void mac802154_ind_commstatus(FAR struct ieee802154_mac_s *mac, + uint16_t panid, FAR uint8_t *src, + FAR uint8_t *dst, int status) +{ +} + +/**************************************************************************** + * Name: mac802154_ind_syncloss + * + * Description: + * + ****************************************************************************/ + +static void mac802154_ind_syncloss(FAR struct ieee802154_mac_s *mac, + int reason) +{ +} + +/**************************************************************************** + * Name: mac802154_transmit + * + * Description: + * Start hardware transmission. Called either from the txdone interrupt + * handling or from watchdog based polling. + * + * Parameters: + * priv - Reference to the driver state structure + * + * Returned Value: + * OK on success; a negated errno on failure + * + * Assumptions: + * May or may not be called from an interrupt handler. In either case, + * the network is locked. + * + ****************************************************************************/ + +static int mac802154_transmit(FAR struct mac802154_driver_s *priv) +{ + /* Verify that the hardware is ready to send another packet. If we get + * here, then we are committed to sending a packet; Higher level logic + * must have assured that there is no transmission in progress. + */ + + /* Increment statistics */ + + NETDEV_TXPACKETS(priv->m8_dev); + + /* Send the packet: address=priv->m8_dev.d_buf, length=priv->m8_dev.d_len */ + + /* Enable Tx interrupts */ + + /* Setup the TX timeout watchdog (perhaps restarting the timer) */ + + (void)wd_start(priv->m8_txtimeout, skeleton_TXTIMEOUT, + mac802154_txtimeout_expiry, 1, (wdparm_t)priv); + return OK; +} + +/**************************************************************************** + * Name: mac802154_txpoll + * + * Description: + * The transmitter is available, check if the network has any outgoing + * packets ready to send. This is a callback from devif_poll(). + * devif_poll() may be called: + * + * 1. When the preceding TX packet send is complete, + * 2. When the preceding TX packet send timesout and the interface is reset + * 3. During normal TX polling + * + * Parameters: + * dev - Reference to the NuttX driver state structure + * + * Returned Value: + * OK on success; a negated errno on failure + * + * Assumptions: + * May or may not be called from an interrupt handler. In either case, + * the network is locked. + * + ****************************************************************************/ + +static int mac802154_txpoll(FAR struct net_driver_s *dev) +{ + FAR struct mac802154_driver_s *priv = (FAR struct mac802154_driver_s *)dev->d_private; + + /* If the polling resulted in data that should be sent out, the field + * i_framelist will set to a new, outgoing list of frames. + */ + + if (priv->m8_dev.i_framelist != NULL) + { + /* And send the packet */ + + mac802154_transmit(priv); + } + + /* If zero is returned, the polling will continue until all connections have + * been examined. + */ + + return 0; +} + +/**************************************************************************** + * Name: mac802154_receive + * + * Description: + * An interrupt was received indicating the availability of a new RX packet + * + * Parameters: + * priv - Reference to the driver state structure + * + * Returned Value: + * None + * + * Assumptions: + * The network is locked. + * + ****************************************************************************/ + +static void mac802154_receive(FAR struct mac802154_driver_s *priv) +{ + FAR struct iob_s *iob; + FAR struct iob_s *fptr; + + /* Allocate an IOB to hold the frame */ + + net_lock(); + iob = iob_alloc(false); + if (iob == NULL) + { + nerr("ERROR: Failed to allocate an IOB\n") + return; + } + + /* Copy the frame data into the IOB. + * REVISIT: Can a copy be avoided? + */ + + fptr = iob->io_data; +#warning Missing logic + + /* Transfer the frame to the network logic */ + + priv->m8_dev.framelist = iob; + sixlowpan_input(&priv->m8_dev); + + /* If the above function invocation resulted in data that should be sent + * out, the field i_framelist will set to a new, outgoing list of frames. + */ + + if (priv->m8_dev.i_framelist != NULL) + { + /* And send the packet */ + + mac802154_transmit(priv); + } +} + +/**************************************************************************** + * Name: mac802154_txdone + * + * Description: + * An interrupt was received indicating that the last TX packet(s) is done + * + * Parameters: + * priv - Reference to the driver state structure + * + * Returned Value: + * None + * + * Assumptions: + * The network is locked. + * + ****************************************************************************/ + +static void mac802154_txdone(FAR struct mac802154_driver_s *priv) +{ + int delay; + + /* Check for errors and update statistics */ + + NETDEV_TXDONE(priv->m8_dev); + + /* Check if there are pending transmissions */ + + /* If no further transmissions are pending, then cancel the TX timeout and + * disable further Tx interrupts. + */ + + wd_cancel(priv->m8_txtimeout); + + /* And disable further TX interrupts. */ + + /* In any event, poll the network for new TX data */ + + (void)devif_poll(&priv->m8_dev, mac802154_txpoll); +} + +/**************************************************************************** + * Name: mac802154_transfer_work + * + * Description: + * Perform interrupt related work from the worker thread + * + * Parameters: + * arg - The argument passed when work_queue() was called. + * + * Returned Value: + * OK on success + * + * Assumptions: + * The network is locked. + * + ****************************************************************************/ + +static void mac802154_transfer_work(FAR void *arg) +{ + FAR struct mac802154_driver_s *priv = (FAR struct mac802154_driver_s *)arg; + + /* Lock the network and serialize driver operations if necessary. + * NOTE: Serialization is only required in the case where the driver work + * is performed on an LP worker thread and where more than one LP worker + * thread has been configured. + */ + + net_lock(); + + /* Process pending Ethernet interrupts */ + + /* Get and clear interrupt status bits */ + + /* Handle interrupts according to status bit settings */ + + /* Check if we received an incoming packet, if so, call mac802154_receive() */ + + mac802154_receive(priv); + + /* Check if a packet transmission just completed. If so, call mac802154_txdone. + * This may disable further Tx interrupts if there are no pending + * transmissions. + */ + + mac802154_txdone(priv); + net_unlock(); + + /* Re-enable Ethernet interrupts */ + + up_enable_irq(CONFIG_IEEE802154_NETDEV_IRQ); +} + +/**************************************************************************** + * Name: mac802154_transfer + * + * Description: + * Hardware interrupt handler + * + * Parameters: + * irq - Number of the IRQ that generated the interrupt + * context - Interrupt register state save info (architecture-specific) + * + * Returned Value: + * OK on success + * + * Assumptions: + * + ****************************************************************************/ + +static int mac802154_transfer(int irq, FAR void *context, FAR void *arg) +{ + FAR struct mac802154_driver_s *priv = &g_skel[0]; + + /* Disable further Ethernet interrupts. Because Ethernet interrupts are + * also disabled if the TX timeout event occurs, there can be no race + * condition here. + */ + + up_disable_irq(CONFIG_IEEE802154_NETDEV_IRQ); + + /* TODO: Determine if a TX transfer just completed */ + + { + /* If a TX transfer just completed, then cancel the TX timeout so + * there will be no race condition between any subsequent timeout + * expiration and the deferred interrupt processing. + */ + + wd_cancel(priv->m8_txtimeout); + } + + /* Schedule to perform the interrupt processing on the worker thread. */ + + work_queue(ETHWORK, &priv->m8_irqwork, mac802154_transfer_work, priv, 0); + return OK; +} + +/**************************************************************************** + * Name: mac802154_txtimeout_work + * + * Description: + * Perform TX timeout related work from the worker thread + * + * Parameters: + * arg - The argument passed when work_queue() as called. + * + * Returned Value: + * OK on success + * + * Assumptions: + * The network is locked. + * + ****************************************************************************/ + +static void mac802154_txtimeout_work(FAR void *arg) +{ + FAR struct mac802154_driver_s *priv = (FAR struct mac802154_driver_s *)arg; + + /* Lock the network and serialize driver operations if necessary. + * NOTE: Serialization is only required in the case where the driver work + * is performed on an LP worker thread and where more than one LP worker + * thread has been configured. + */ + + net_lock(); + + /* Increment statistics and dump debug info */ + + NETDEV_TXTIMEOUTS(priv->m8_dev); + + /* Then reset the hardware */ + + /* Then poll the network for new XMIT data */ + + (void)devif_poll(&priv->m8_dev, mac802154_txpoll); + net_unlock(); +} + +/**************************************************************************** + * Name: mac802154_txtimeout_expiry + * + * Description: + * Our TX watchdog timed out. Called from the timer interrupt handler. + * The last TX never completed. Reset the hardware and start again. + * + * Parameters: + * argc - The number of available arguments + * arg - The first argument + * + * Returned Value: + * None + * + * Assumptions: + * Global interrupts are disabled by the watchdog logic. + * + ****************************************************************************/ + +static void mac802154_txtimeout_expiry(int argc, wdparm_t arg, ...) +{ + FAR struct mac802154_driver_s *priv = (FAR struct mac802154_driver_s *)arg; + + /* Disable further Ethernet interrupts. This will prevent some race + * conditions with interrupt work. There is still a potential race + * condition with interrupt work that is already queued and in progress. + */ + + up_disable_irq(CONFIG_IEEE802154_NETDEV_IRQ); + + /* Schedule to perform the TX timeout processing on the worker thread. */ + + work_queue(ETHWORK, &priv->m8_irqwork, mac802154_txtimeout_work, priv, 0); +} + +/**************************************************************************** + * Name: mac802154_poll_process + * + * Description: + * Perform the periodic poll. This may be called either from watchdog + * timer logic or from the worker thread, depending upon the configuration. + * + * Parameters: + * priv - Reference to the driver state structure + * + * Returned Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +static inline void mac802154_poll_process(FAR struct mac802154_driver_s *priv) +{ +} + +/**************************************************************************** + * Name: mac802154_poll_work + * + * Description: + * Perform periodic polling from the worker thread + * + * Parameters: + * arg - The argument passed when work_queue() as called. + * + * Returned Value: + * OK on success + * + * Assumptions: + * The network is locked. + * + ****************************************************************************/ + +static void mac802154_poll_work(FAR void *arg) +{ + FAR struct mac802154_driver_s *priv = (FAR struct mac802154_driver_s *)arg; + + /* Lock the network and serialize driver operations if necessary. + * NOTE: Serialization is only required in the case where the driver work + * is performed on an LP worker thread and where more than one LP worker + * thread has been configured. + */ + + net_lock(); + + /* Perform the poll */ + + /* Check if there is room in the send another TX packet. We cannot perform + * the TX poll if he are unable to accept another packet for transmission. + */ + + /* If so, update TCP timing states and poll the network for new XMIT data. + * Hmmm.. might be bug here. Does this mean if there is a transmit in + * progress, we will missing TCP time state updates? + */ + + (void)devif_timer(&priv->m8_dev, mac802154_txpoll); + + /* Setup the watchdog poll timer again */ + + (void)wd_start(priv->m8_txpoll, skeleton_WDDELAY, mac802154_poll_expiry, 1, + (wdparm_t)priv); + net_unlock(); +} + +/**************************************************************************** + * Name: mac802154_poll_expiry + * + * Description: + * Periodic timer handler. Called from the timer interrupt handler. + * + * Parameters: + * argc - The number of available arguments + * arg - The first argument + * + * Returned Value: + * None + * + * Assumptions: + * Global interrupts are disabled by the watchdog logic. + * + ****************************************************************************/ + +static void mac802154_poll_expiry(int argc, wdparm_t arg, ...) +{ + FAR struct mac802154_driver_s *priv = (FAR struct mac802154_driver_s *)arg; + + /* Schedule to perform the interrupt processing on the worker thread. */ + + work_queue(ETHWORK, &priv->m8_pollwork, mac802154_poll_work, priv, 0); +} + +/**************************************************************************** + * Name: mac802154_ifup + * + * Description: + * NuttX Callback: Bring up the Ethernet interface when an IP address is + * provided + * + * Parameters: + * dev - Reference to the NuttX driver state structure + * + * Returned Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +static int mac802154_ifup(FAR struct net_driver_s *dev) +{ + FAR struct mac802154_driver_s *priv = (FAR struct mac802154_driver_s *)dev->d_private; + +#ifdef CONFIG_NET_IPv4 + ninfo("Bringing up: %d.%d.%d.%d\n", + dev->d_ipaddr & 0xff, (dev->d_ipaddr >> 8) & 0xff, + (dev->d_ipaddr >> 16) & 0xff, dev->d_ipaddr >> 24); +#endif +#ifdef CONFIG_NET_IPv6 + ninfo("Bringing up: %04x:%04x:%04x:%04x:%04x:%04x:%04x:%04x\n", + dev->d_ipv6addr[0], dev->d_ipv6addr[1], dev->d_ipv6addr[2], + dev->d_ipv6addr[3], dev->d_ipv6addr[4], dev->d_ipv6addr[5], + dev->d_ipv6addr[6], dev->d_ipv6addr[7]); +#endif + + /* Initialize PHYs, the Ethernet interface, and setup up Ethernet interrupts */ + + /* Instantiate the MAC address from priv->m8_dev.d_mac.ether_addr_octet */ + +#ifdef CONFIG_NET_ICMPv6 + /* Set up IPv6 multicast address filtering */ + + mac802154_ipv6multicast(priv); +#endif + + /* Set and activate a timer process */ + + (void)wd_start(priv->m8_txpoll, skeleton_WDDELAY, mac802154_poll_expiry, 1, + (wdparm_t)priv); + + /* Enable the Ethernet interrupt */ + + priv->m8_bifup = true; + up_enable_irq(CONFIG_IEEE802154_NETDEV_IRQ); + return OK; +} + +/**************************************************************************** + * Name: mac802154_ifdown + * + * Description: + * NuttX Callback: Stop the interface. + * + * Parameters: + * dev - Reference to the NuttX driver state structure + * + * Returned Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +static int mac802154_ifdown(FAR struct net_driver_s *dev) +{ + FAR struct mac802154_driver_s *priv = (FAR struct mac802154_driver_s *)dev->d_private; + irqstate_t flags; + + /* Disable the Ethernet interrupt */ + + flags = enter_critical_section(); + up_disable_irq(CONFIG_IEEE802154_NETDEV_IRQ); + + /* Cancel the TX poll timer and TX timeout timers */ + + wd_cancel(priv->m8_txpoll); + wd_cancel(priv->m8_txtimeout); + + /* Put the EMAC in its reset, non-operational state. This should be + * a known configuration that will guarantee the mac802154_ifup() always + * successfully brings the interface back up. + */ + + /* Mark the device "down" */ + + priv->m8_bifup = false; + leave_critical_section(flags); + return OK; +} + +/**************************************************************************** + * Name: mac802154_txavail_work + * + * Description: + * Perform an out-of-cycle poll on the worker thread. + * + * Parameters: + * arg - Reference to the NuttX driver state structure (cast to void*) + * + * Returned Value: + * None + * + * Assumptions: + * Called on the higher priority worker thread. + * + ****************************************************************************/ + +static void mac802154_txavail_work(FAR void *arg) +{ + FAR struct mac802154_driver_s *priv = (FAR struct mac802154_driver_s *)arg; + + /* Lock the network and serialize driver operations if necessary. + * NOTE: Serialization is only required in the case where the driver work + * is performed on an LP worker thread and where more than one LP worker + * thread has been configured. + */ + + net_lock(); + + /* Ignore the notification if the interface is not yet up */ + + if (priv->m8_bifup) + { + /* Check if there is room in the hardware to hold another outgoing packet. */ + + /* If so, then poll the network for new XMIT data */ + + (void)devif_poll(&priv->m8_dev, mac802154_txpoll); + } + + net_unlock(); +} + +/**************************************************************************** + * Name: mac802154_txavail + * + * Description: + * Driver callback invoked when new TX data is available. This is a + * stimulus perform an out-of-cycle poll and, thereby, reduce the TX + * latency. + * + * Parameters: + * dev - Reference to the NuttX driver state structure + * + * Returned Value: + * None + * + * Assumptions: + * Called in normal user mode + * + ****************************************************************************/ + +static int mac802154_txavail(FAR struct net_driver_s *dev) +{ + FAR struct mac802154_driver_s *priv = (FAR struct mac802154_driver_s *)dev->d_private; + + /* Is our single work structure available? It may not be if there are + * pending interrupt actions and we will have to ignore the Tx + * availability action. + */ + + if (work_available(&priv->m8_pollwork)) + { + /* Schedule to serialize the poll on the worker thread. */ + + work_queue(ETHWORK, &priv->m8_pollwork, mac802154_txavail_work, priv, 0); + } + + return OK; +} + +/**************************************************************************** + * Name: mac802154_addmac + * + * Description: + * NuttX Callback: Add the specified MAC address to the hardware multicast + * address filtering + * + * Parameters: + * dev - Reference to the NuttX driver state structure + * mac - The MAC address to be added + * + * Returned Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +#if defined(CONFIG_NET_IGMP) || defined(CONFIG_NET_ICMPv6) +static int mac802154_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) +{ + FAR struct mac802154_driver_s *priv = (FAR struct mac802154_driver_s *)dev->d_private; + + /* Add the MAC address to the hardware multicast routing table */ + + return OK; +} +#endif + +/**************************************************************************** + * Name: mac802154_rmmac + * + * Description: + * NuttX Callback: Remove the specified MAC address from the hardware multicast + * address filtering + * + * Parameters: + * dev - Reference to the NuttX driver state structure + * mac - The MAC address to be removed + * + * Returned Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +#ifdef CONFIG_NET_IGMP +static int mac802154_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) +{ + FAR struct mac802154_driver_s *priv = (FAR struct mac802154_driver_s *)dev->d_private; + + /* Add the MAC address to the hardware multicast routing table */ + + return OK; +} +#endif + +/**************************************************************************** + * Name: mac802154_ipv6multicast + * + * Description: + * Configure the IPv6 multicast MAC address. + * + * Parameters: + * priv - A reference to the private driver state structure + * + * Returned Value: + * OK on success; Negated errno on failure. + * + * Assumptions: + * + ****************************************************************************/ + +#ifdef CONFIG_NET_ICMPv6 +static void mac802154_ipv6multicast(FAR struct mac802154_driver_s *priv) +{ + FAR struct net_driver_s *dev; + uint16_t tmp16; + uint8_t mac[6]; + + /* For ICMPv6, we need to add the IPv6 multicast address + * + * For IPv6 multicast addresses, the Ethernet MAC is derived by + * the four low-order octets OR'ed with the MAC 33:33:00:00:00:00, + * so for example the IPv6 address FF02:DEAD:BEEF::1:3 would map + * to the Ethernet MAC address 33:33:00:01:00:03. + * + * NOTES: This appears correct for the ICMPv6 Router Solicitation + * Message, but the ICMPv6 Neighbor Solicitation message seems to + * use 33:33:ff:01:00:03. + */ + + mac[0] = 0x33; + mac[1] = 0x33; + + dev = &priv->dev; + tmp16 = dev->d_ipv6addr[6]; + mac[2] = 0xff; + mac[3] = tmp16 >> 8; + + tmp16 = dev->d_ipv6addr[7]; + mac[4] = tmp16 & 0xff; + mac[5] = tmp16 >> 8; + + ninfo("IPv6 Multicast: %02x:%02x:%02x:%02x:%02x:%02x\n", + mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]); + + (void)mac802154_addmac(dev, mac); + +#ifdef CONFIG_NET_ICMPv6_AUTOCONF + /* Add the IPv6 all link-local nodes Ethernet address. This is the + * address that we expect to receive ICMPv6 Router Advertisement + * packets. + */ + + (void)mac802154_addmac(dev, g_ipv6_ethallnodes.ether_addr_octet); + +#endif /* CONFIG_NET_ICMPv6_AUTOCONF */ + +#ifdef CONFIG_NET_ICMPv6_ROUTER + /* Add the IPv6 all link-local routers Ethernet address. This is the + * address that we expect to receive ICMPv6 Router Solicitation + * packets. + */ + + (void)mac802154_addmac(dev, g_ipv6_ethallrouters.ether_addr_octet); + +#endif /* CONFIG_NET_ICMPv6_ROUTER */ +} +#endif /* CONFIG_NET_ICMPv6 */ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: mac802154_initialize + * + * Description: + * Initialize the Ethernet controller and driver + * + * Parameters: + * intf - In the case where there are multiple EMACs, this value + * identifies which EMAC is to be initialized. + * + * Returned Value: + * OK on success; Negated errno on failure. + * + * Assumptions: + * + ****************************************************************************/ + +int mac802154_initialize(FAR struct ieee802154_radio_s *radio) +{ + FAR struct mac802154_driver_s *priv; + FAR struct ieee802154_driver_s *ieee; + FAR struct net_driver_s *dev; + FAR uint8_t *pktbuf; + + DEBUGASSERT(radio != NULL); + + /* Get the interface structure associated with this interface number. */ + + priv = (FAR struct mac802154_driver_s *) + kmm_zalloc(sizeof(struct mac802154_driver_s)); + + if (priv == NULL) + { + nerr("ERROR: Failed to allocate the device structure\n"); + return -ENOMEM; + } + + /* Allocate a packet buffer (not used by this driver, but need by the + * upper networking layer) + */ + + pktbuf = (FAR uint8_t *)kmm_malloc(CONFIG_NET_6LOWPAN_MTU + CONFIG_NET_GUARDSIZE); + if (pktbuf == NULL + { + nerr("ERROR: Failed to allocate the packet buffer\n"); + kmm_free(priv); + return -ENOMEM; + } + + /* Initialize the driver structure */ + + ieee = &priv->m8_dev; + dev = &ieee->i_dev; + + dev->d_buf = pktbuf; /* Single packet buffer */ + dev->d_ifup = mac802154_ifup; /* I/F up (new IP address) callback */ + dev->d_ifdown = mac802154_ifdown; /* I/F down callback */ + dev->d_txavail = mac802154_txavail; /* New TX data callback */ +#ifdef CONFIG_NET_IGMP + dev->d_addmac = mac802154_addmac; /* Add multicast MAC address */ + dev->d_rmmac = mac802154_rmmac; /* Remove multicast MAC address */ +#endif + dev->d_private = (FAR void *)priv; /* Used to recover private state from dev */ + + /* Create a watchdog for timing polling for and timing of transmisstions */ + + priv->m8_txpoll = wd_create(); /* Create periodic poll timer */ + priv->m8_txtimeout = wd_create(); /* Create TX timeout timer */ + + DEBUGASSERT(priv->m8_txpoll != NULL && priv->m8_txtimeout != NULL); + + /* Put the interface in the down state. */ + + mac802154_ifdown(dev); + + /* Register the device with the OS so that socket IOCTLs can be performed */ + + (void)netdev_register(&priv->m8_dev, NET_LL_IEEE802154); + return OK; +} + +#endif /* CONFIG_NET && CONFIG_NET_skeleton */ -- GitLab From 51cd421ce720d78094354c788fdd12f4513192dd Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 8 Apr 2017 19:11:57 -0600 Subject: [PATCH 390/990] Ieee802.15.4 MAC network driver. A little more logic (but still only partial). Add interface definitions to header file. --- configs/clicker2-stm32/src/stm32_mrf24j40.c | 25 +++++-- .../wireless/ieee802154/ieee802154_mac.h | 30 ++++++-- wireless/ieee802154/mac802154.c | 6 +- wireless/ieee802154/mac802154_netdev.c | 70 +++++++++++-------- 4 files changed, 86 insertions(+), 45 deletions(-) diff --git a/configs/clicker2-stm32/src/stm32_mrf24j40.c b/configs/clicker2-stm32/src/stm32_mrf24j40.c index 17eb70ea96..8f6868f59e 100644 --- a/configs/clicker2-stm32/src/stm32_mrf24j40.c +++ b/configs/clicker2-stm32/src/stm32_mrf24j40.c @@ -264,20 +264,33 @@ static int stm32_mrf24j40_devsetup(FAR struct stm32_priv_s *priv) wlerr("ERROR: Failed to initialize IEEE802.15.4 MAC\n"); return -ENODEV; } -#endif -#if defined(CONFIG_IEEE802154_MAC_DEV) - /* If want to call these APIs from userspace, you have to wrap your mac - * in a character device via mac802154_device.c. +#if defined(CONFIG_IEEE802154_NETDEV) + /* Use the IEEE802.15.4 MAC interface instance to create a 6loWPAN + * network interface by wrapping the MAC intrface instance in a + * network device driver via mac802154dev_register(). + */ + + ret = mac802154netdev_register(mac); + if (ret < 0) + { + wlerr("ERROR: Failed to register the MAC network driver wpan%d: %d\n", + 0, ret); + return ret; + } +#elif defined(CONFIG_IEEE802154_MAC_DEV) + /* If want to call these APIs from userspace, you have to wrap the MAC + * interface in a character device viamac802154dev_register(). */ ret = mac802154dev_register(mac, 0); if (ret < 0) { - wlerr("ERROR: Failed to register the MAC character driver ieee%d: %d\n", + wlerr("ERROR: Failed to register the MAC character driver /dev/ieee%d: %d\n", 0, ret); return ret; } +#endif #elif defined(CONFIG_IEEE802154_DEV) /* Register a character driver to access the IEEE 802.15.4 radio from * user-space @@ -290,7 +303,7 @@ static int stm32_mrf24j40_devsetup(FAR struct stm32_priv_s *priv) RADIO_DEVNAME, ret); return ret; } -#endif +#endif /* CONFIG_IEEE802154_MAC */ return OK; } diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index 1299fe9856..55830d70fc 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -918,11 +918,11 @@ struct ieee802154_maccb_s CODE void (*ind_syncloss)(FAR struct ieee802154_mac_s *mac, int reason); }; -struct ieee802154_radio_s; /* Forware reference */ +struct ieee802154_radio_s; /* Forward reference */ struct ieee802154_mac_s { - struct ieee802154_radio_s *radio; + FAR struct ieee802154_radio_s *radio; struct ieee802154_macops_s ops; struct ieee802154_maccb_s cbs; }; @@ -947,9 +947,9 @@ extern "C" * * The returned MAC structure should be passed to either the next highest * layer in the network stack, or registered with a mac802154dev character - * driver. In either of these scenarios, the next highest layer should - * register a set of callbacks with the MAC layer by setting the mac->cbs - * member. + * or network drivers. In any of these scenarios, the next highest layer + * should register a set of callbacks with the MAC layer by setting the + * mac->cbs member. * * NOTE: This API does not create any device accessible to userspace. If you * want to call these APIs from userspace, you have to wrap your mac in a @@ -975,7 +975,7 @@ FAR struct ieee802154_mac_s * * user-space * * Input Parameters: - * mac - Pointer to the mac layer struct to be registerd. + * mac - Pointer to the mac layer struct to be registered. * minor - The device minor number. The IEEE802.15.4 MAC character device * will be registered as /dev/ieeeN where N is the minor number * @@ -987,6 +987,24 @@ FAR struct ieee802154_mac_s * int mac802154dev_register(FAR struct ieee802154_mac_s *mac, int minor); +/**************************************************************************** + * Name: mac802154netdev_register + * + * Description: + * Register a network driver to access the IEEE 802.15.4 MAC layer from + * a socket using 6loWPAN + * + * Input Parameters: + * mac - Pointer to the mac layer struct to be registered. + * + * Returned Values: + * Zero (OK) is returned on success. Otherwise a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +int mac802154netdev_register(FAR struct ieee802154_mac_s *mac); + #undef EXTERN #ifdef __cplusplus } diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index 8e4a3b8055..f291d76199 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -518,9 +518,9 @@ static int mac802154_rsp_orphan(FAR struct ieee802154_mac_s *mac, * * The returned MAC structure should be passed to either the next highest * layer in the network stack, or registered with a mac802154dev character - * driver. In either of these scenarios, the next highest layer should - * register a set of callbacks with the MAC layer by setting the mac->cbs - * member. + * or network drivers. In any of these scenarios, the next highest layer + * should register a set of callbacks with the MAC layer by setting the + * mac->cbs member. * * NOTE: This API does not create any device accessible to userspace. If you * want to call these APIs from userspace, you have to wrap your mac in a diff --git a/wireless/ieee802154/mac802154_netdev.c b/wireless/ieee802154/mac802154_netdev.c index 807320811c..f3367b82a2 100644 --- a/wireless/ieee802154/mac802154_netdev.c +++ b/wireless/ieee802154/mac802154_netdev.c @@ -117,8 +117,8 @@ struct mac802154_driver_s { /* This holds the information visible to the NuttX network */ - struct ieee802154_driver_s m8_dev; /* Interface understood by the network */ - struct ieee802154_mac_s m8_mac; /* Interface understood by the MAC */ + struct ieee802154_driver_s m8_dev; /* Interface understood by the network */ + FAR struct ieee802154_mac_s *m8_mac; /* Contained MAC interface */ /* For internal use by this driver */ @@ -129,19 +129,6 @@ struct mac802154_driver_s struct work_s m8_pollwork; /* For deferring poll work to the work queue */ }; -/**************************************************************************** - * Private Data - ****************************************************************************/ - -struct ieee802154_radio_s; /* Forware reference */ - - -{ - - struct ieee802154_macops_s ops; - struct ieee802154_maccb_s cbs; -}; - /**************************************************************************** * Private Data ****************************************************************************/ @@ -1282,26 +1269,25 @@ static void mac802154_ipv6multicast(FAR struct mac802154_driver_s *priv) ****************************************************************************/ /**************************************************************************** - * Name: mac802154_initialize + * Name: mac802154netdev_register * * Description: - * Initialize the Ethernet controller and driver - * - * Parameters: - * intf - In the case where there are multiple EMACs, this value - * identifies which EMAC is to be initialized. + * Register a network driver to access the IEEE 802.15.4 MAC layer from + * a socket using 6loWPAN * - * Returned Value: - * OK on success; Negated errno on failure. + * Input Parameters: + * mac - Pointer to the mac layer struct to be registered. * - * Assumptions: + * Returned Values: + * Zero (OK) is returned on success. Otherwise a negated errno value is + * returned to indicate the nature of the failure. * ****************************************************************************/ -int mac802154_initialize(FAR struct ieee802154_radio_s *radio) +int mac802154netdev_register(FAR struct ieee802154_mac_s *mac); { FAR struct mac802154_driver_s *priv; - FAR struct ieee802154_driver_s *ieee; + FAR truct ieee802154_maccb_s *macb; FAR struct net_driver_s *dev; FAR uint8_t *pktbuf; @@ -1332,9 +1318,7 @@ int mac802154_initialize(FAR struct ieee802154_radio_s *radio) /* Initialize the driver structure */ - ieee = &priv->m8_dev; - dev = &ieee->i_dev; - + dev = &ieee->m8_dev.i_dev; dev->d_buf = pktbuf; /* Single packet buffer */ dev->d_ifup = mac802154_ifup; /* I/F up (new IP address) callback */ dev->d_ifdown = mac802154_ifdown; /* I/F down callback */ @@ -1347,11 +1331,37 @@ int mac802154_initialize(FAR struct ieee802154_radio_s *radio) /* Create a watchdog for timing polling for and timing of transmisstions */ - priv->m8_txpoll = wd_create(); /* Create periodic poll timer */ + priv->m8_mac = mac; /* Save the MAC interface instance */ + priv->m8_txpoll = wd_create(); /* Create periodic poll timer */ priv->m8_txtimeout = wd_create(); /* Create TX timeout timer */ DEBUGASSERT(priv->m8_txpoll != NULL && priv->m8_txtimeout != NULL); + /* Initialize the MAC callbacks */ + + maccb = &mac->cbs; + maccb->cb_context = priv; + maccb->conf_data = mac802154_conf_data; + maccb->conf_purge = mac802154_conf_purge; + maccb->conf_associate = mac802154_conf_associate; + maccb->conf_disassociate = mac802154_conf_disassociate; + maccb->conf_get = mac802154_conf_get; + maccb->conf_gts = mac802154_conf_gts; + maccb->conf_reset = mac802154_conf_reset; + maccb->conf_rxenable = mac802154_conf_rxenable; + maccb->conf_scan = mac802154_conf_scan; + maccb->conf_set = mac802154_conf_set; + maccb->conf_start = mac802154_conf_start; + maccb->conf_poll = mac802154_conf_poll; + maccb->ind_data = mac802154_ind_data; + maccb->ind_associate = mac802154_ind_associate; + maccb->ind_disassociate = mac802154_ind_disassociate; + maccb->ind_beaconnotify = mac802154_ind_beaconnotify; + maccb->ind_gts = mac802154_ind_gts; + maccb->ind_orphan = mac802154_ind_orphan; + maccb->ind_commstatus = mac802154_ind_commstatus; + maccb->ind_syncloss = mac802154_ind_syncloss; + /* Put the interface in the down state. */ mac802154_ifdown(dev); -- GitLab From 5a0636d8bce3ed39669cdcfad58ccbf53e8e5bb4 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 9 Apr 2017 05:49:30 -0600 Subject: [PATCH 391/990] Trivial change to spacing --- wireless/ieee802154/mac802154_loopback.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/wireless/ieee802154/mac802154_loopback.c b/wireless/ieee802154/mac802154_loopback.c index 994289642b..71255f0d60 100644 --- a/wireless/ieee802154/mac802154_loopback.c +++ b/wireless/ieee802154/mac802154_loopback.c @@ -603,7 +603,7 @@ int ieee8021514_loopback(void) memset(priv, 0, sizeof(struct lo_driver_s)); - dev = &priv->lo_ieee.i_dev; + dev = &priv->lo_ieee.i_dev; dev->d_ifup = lo_ifup; /* I/F up (new IP address) callback */ dev->d_ifdown = lo_ifdown; /* I/F down callback */ dev->d_txavail = lo_txavail; /* New TX data callback */ -- GitLab From af1a9db4f6b2374d4be437c39bd3b9b7264dd3c7 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 9 Apr 2017 06:15:55 -0600 Subject: [PATCH 392/990] Some trivial addtions to the still fragmentary IEEE802.15.4 MAC network driver. --- wireless/ieee802154/mac802154_netdev.c | 84 +++++++++++++++++++++++++- 1 file changed, 82 insertions(+), 2 deletions(-) diff --git a/wireless/ieee802154/mac802154_netdev.c b/wireless/ieee802154/mac802154_netdev.c index f3367b82a2..1f5f2335e1 100644 --- a/wireless/ieee802154/mac802154_netdev.c +++ b/wireless/ieee802154/mac802154_netdev.c @@ -109,8 +109,8 @@ * Private Types ****************************************************************************/ -/* The mac802154_driver_s encapsulates all state information for a single hardware - * interface +/* The mac802154_driver_s encapsulates all state information for a single + * IEEE802.15.4 MAC interface. */ struct mac802154_driver_s @@ -251,6 +251,10 @@ static void mac802154_ipv6multicast(FAR struct mac802154_driver_s *priv); static void mac802154_conf_data(FAR struct ieee802154_mac_s *mac, FAR struct ieee802154_data_conf_s *conf) { + FAR struct mac802154_driver_s *priv; + + DEBUGASSERT(mac != NULL && mac->cb_context); + priv = (FAR struct mac802154_driver_s *)mac->cb_context; } /**************************************************************************** @@ -264,6 +268,10 @@ static void mac802154_conf_data(FAR struct ieee802154_mac_s *mac, static void mac802154_conf_purge(FAR struct ieee802154_mac_s *mac, uint8_t handle, int status) { + FAR struct mac802154_driver_s *priv; + + DEBUGASSERT(mac != NULL && mac->cb_context); + priv = (FAR struct mac802154_driver_s *)mac->cb_context; } /**************************************************************************** @@ -277,6 +285,10 @@ static void mac802154_conf_purge(FAR struct ieee802154_mac_s *mac, static void mac802154_conf_associate(FAR struct ieee802154_mac_s *mac, uint16_t saddr, int status) { + FAR struct mac802154_driver_s *priv; + + DEBUGASSERT(mac != NULL && mac->cb_context); + priv = (FAR struct mac802154_driver_s *)mac->cb_context; } /**************************************************************************** @@ -289,6 +301,10 @@ static void mac802154_conf_associate(FAR struct ieee802154_mac_s *mac, static void mac802154_conf_disassociate(FAR struct ieee802154_mac_s *mac, { + FAR struct mac802154_driver_s *priv; + + DEBUGASSERT(mac != NULL && mac->cb_context); + priv = (FAR struct mac802154_driver_s *)mac->cb_context; } /**************************************************************************** @@ -303,6 +319,10 @@ static void mac802154_conf_get(FAR struct ieee802154_mac_s *mac, int status, int attribute, FAR uint8_t *value, int valuelen) { + FAR struct mac802154_driver_s *priv; + + DEBUGASSERT(mac != NULL && mac->cb_context); + priv = (FAR struct mac802154_driver_s *)mac->cb_context; } /**************************************************************************** @@ -316,6 +336,10 @@ static void mac802154_conf_get(FAR struct ieee802154_mac_s *mac, int status, static void mac802154_conf_gts(FAR struct ieee802154_mac_s *mac, FAR uint8_t *characteristics, int status) { + FAR struct mac802154_driver_s *priv; + + DEBUGASSERT(mac != NULL && mac->cb_context); + priv = (FAR struct mac802154_driver_s *)mac->cb_context; } /**************************************************************************** @@ -329,6 +353,10 @@ static void mac802154_conf_gts(FAR struct ieee802154_mac_s *mac, static void mac802154_conf_reset(FAR struct ieee802154_mac_s *mac, int status) { + FAR struct mac802154_driver_s *priv; + + DEBUGASSERT(mac != NULL && mac->cb_context); + priv = (FAR struct mac802154_driver_s *)mac->cb_context; } /**************************************************************************** @@ -341,6 +369,10 @@ static void mac802154_conf_reset(FAR struct ieee802154_mac_s *mac, static void mac802154_conf_rxenable(FAR struct ieee802154_mac_s *mac, int status) { + FAR struct mac802154_driver_s *priv; + + DEBUGASSERT(mac != NULL && mac->cb_context); + priv = (FAR struct mac802154_driver_s *)mac->cb_context; } /**************************************************************************** @@ -355,6 +387,10 @@ static void mac802154_conf_scan(FAR struct ieee802154_mac_s *mac, uint32_t unscanned, int rsltsize, FAR uint8_t *edlist, FAR uint8_t *pandescs) { + FAR struct mac802154_driver_s *priv; + + DEBUGASSERT(mac != NULL && mac->cb_context); + priv = (FAR struct mac802154_driver_s *)mac->cb_context; } /**************************************************************************** @@ -367,6 +403,10 @@ static void mac802154_conf_scan(FAR struct ieee802154_mac_s *mac, static void mac802154_conf_set(FAR struct ieee802154_mac_s *mac, int status, int attribute) { + FAR struct mac802154_driver_s *priv; + + DEBUGASSERT(mac != NULL && mac->cb_context); + priv = (FAR struct mac802154_driver_s *)mac->cb_context; } /**************************************************************************** @@ -379,6 +419,10 @@ static void mac802154_conf_set(FAR struct ieee802154_mac_s *mac, int status, static void mac802154_conf_start(FAR struct ieee802154_mac_s *mac, int status) { + FAR struct mac802154_driver_s *priv; + + DEBUGASSERT(mac != NULL && mac->cb_context); + priv = (FAR struct mac802154_driver_s *)mac->cb_context; } /**************************************************************************** @@ -391,6 +435,10 @@ static void mac802154_conf_start(FAR struct ieee802154_mac_s *mac, static void mac802154_conf_poll(FAR struct ieee802154_mac_s *mac, int status) { + FAR struct mac802154_driver_s *priv; + + DEBUGASSERT(mac != NULL && mac->cb_context); + priv = (FAR struct mac802154_driver_s *)mac->cb_context; } /**************************************************************************** @@ -404,6 +452,10 @@ static void mac802154_conf_poll(FAR struct ieee802154_mac_s *mac, static void mac802154_ind_data(FAR struct ieee802154_mac_s *mac, FAR uint8_t *buf, int len) { + FAR struct mac802154_driver_s *priv; + + DEBUGASSERT(mac != NULL && mac->cb_context); + priv = (FAR struct mac802154_driver_s *)mac->cb_context; } /**************************************************************************** @@ -418,6 +470,10 @@ static void mac802154_ind_associate(FAR struct ieee802154_mac_s *mac, uint16_t clipanid, FAR uint8_t *clieaddr) { + FAR struct mac802154_driver_s *priv; + + DEBUGASSERT(mac != NULL && mac->cb_context); + priv = (FAR struct mac802154_driver_s *)mac->cb_context; } /**************************************************************************** @@ -431,6 +487,10 @@ static void mac802154_ind_associate(FAR struct ieee802154_mac_s *mac, static void mac802154_ind_disassociate(FAR struct ieee802154_mac_s *mac, FAR uint8_t *eadr, uint8_t reason) { + FAR struct mac802154_driver_s *priv; + + DEBUGASSERT(mac != NULL && mac->cb_context); + priv = (FAR struct mac802154_driver_s *)mac->cb_context; } /**************************************************************************** @@ -446,6 +506,10 @@ static void mac802154_ind_beaconnotify(FAR struct ieee802154_mac_s *mac, FAR struct ieee802154_pan_desc_s *pandesc, FAR uint8_t *sdu, int sdulen) { + FAR struct mac802154_driver_s *priv; + + DEBUGASSERT(mac != NULL && mac->cb_context); + priv = (FAR struct mac802154_driver_s *)mac->cb_context; } /**************************************************************************** @@ -460,6 +524,10 @@ static void mac802154_ind_gts(FAR struct ieee802154_mac_s *mac, FAR uint8_t *devaddr, FAR uint8_t *characteristics) { + FAR struct mac802154_driver_s *priv; + + DEBUGASSERT(mac != NULL && mac->cb_context); + priv = (FAR struct mac802154_driver_s *)mac->cb_context; } /**************************************************************************** @@ -473,6 +541,10 @@ static void mac802154_ind_gts(FAR struct ieee802154_mac_s *mac, static void mac802154_ind_orphan(FAR struct ieee802154_mac_s *mac, FAR uint8_t *orphanaddr) { + FAR struct mac802154_driver_s *priv; + + DEBUGASSERT(mac != NULL && mac->cb_context); + priv = (FAR struct mac802154_driver_s *)mac->cb_context; } /**************************************************************************** @@ -486,6 +558,10 @@ static void mac802154_ind_commstatus(FAR struct ieee802154_mac_s *mac, uint16_t panid, FAR uint8_t *src, FAR uint8_t *dst, int status) { + FAR struct mac802154_driver_s *priv; + + DEBUGASSERT(mac != NULL && mac->cb_context); + priv = (FAR struct mac802154_driver_s *)mac->cb_context; } /**************************************************************************** @@ -498,6 +574,10 @@ static void mac802154_ind_commstatus(FAR struct ieee802154_mac_s *mac, static void mac802154_ind_syncloss(FAR struct ieee802154_mac_s *mac, int reason) { + FAR struct mac802154_driver_s *priv; + + DEBUGASSERT(mac != NULL && mac->cb_context); + priv = (FAR struct mac802154_driver_s *)mac->cb_context; } /**************************************************************************** -- GitLab From f9e402018bb922b11af957c4cb606f54f5e91c55 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 9 Apr 2017 07:22:49 -0600 Subject: [PATCH 393/990] Buttons: Change return value of board_buttons() and the type of btn_buttonset_t to uint32_t so that more than 8 buttons can be supported. --- configs/avr32dev1/src/avr32_buttons.c | 4 ++-- configs/bambino-200e/src/lpc43_buttons.c | 4 ++-- configs/clicker2-stm32/src/stm32_buttons.c | 4 ++-- configs/cloudctrl/src/stm32_buttons.c | 4 ++-- configs/demo9s12ne64/src/m9s12_buttons.c | 2 +- configs/dk-tm4c129x/src/tm4c_buttons.c | 4 ++-- configs/ea3131/src/lpc31_buttons.c | 14 +------------- configs/ea3152/src/lpc31_buttons.c | 14 +------------- configs/ez80f910200zco/src/ez80_buttons.c | 2 +- configs/fire-stm32v2/src/stm32_buttons.c | 4 ++-- configs/freedom-k64f/src/k64_buttons.c | 4 ++-- configs/freedom-k66f/src/k66_buttons.c | 4 ++-- configs/hymini-stm32v/src/stm32_buttons.c | 4 ++-- configs/kwikstik-k40/src/k40_buttons.c | 2 +- configs/launchxl-tms57004/src/tms570_buttons.c | 2 +- configs/lincoln60/src/lpc17_buttons.c | 4 ++-- configs/lpc4330-xplorer/src/lpc43_buttons.c | 4 ++-- configs/lpc4357-evb/src/lpc43_buttons.c | 4 ++-- configs/ne64badge/src/m9s12_buttons.c | 4 ++-- configs/nucleo-144/src/stm32_buttons.c | 2 +- configs/nucleo-f303re/src/stm32_buttons.c | 2 +- configs/nucleo-f4x1re/src/stm32_buttons.c | 2 +- configs/nucleo-l476rg/src/stm32_buttons.c | 2 +- .../olimex-efm32g880f128-stk/src/efm32_buttons.c | 4 ++-- configs/olimex-lpc1766stk/src/lpc17_buttons.c | 4 ++-- configs/olimex-stm32-e407/src/stm32_buttons.c | 4 ++-- configs/olimex-stm32-h405/src/stm32_buttons.c | 4 ++-- configs/olimex-stm32-h407/src/stm32_buttons.c | 4 ++-- configs/olimex-stm32-p207/src/stm32_buttons.c | 4 ++-- configs/olimex-stm32-p407/src/stm32_buttons.c | 4 ++-- configs/olimex-strp711/src/str71_buttons.c | 4 ++-- configs/olimexino-stm32/src/stm32_buttons.c | 2 +- configs/open1788/src/lpc17_buttons.c | 4 ++-- configs/pcduino-a10/src/a1x_buttons.c | 2 +- configs/photon/src/stm32_buttons.c | 2 +- configs/pic32mz-starterkit/src/pic32mz_buttons.c | 4 ++-- configs/sam3u-ek/src/sam_buttons.c | 4 ++-- configs/sam4e-ek/src/sam_buttons.c | 4 ++-- configs/sam4l-xplained/src/sam_buttons.c | 6 +----- configs/sam4s-xplained-pro/src/sam_buttons.c | 2 +- configs/sam4s-xplained/src/sam_buttons.c | 2 +- configs/sama5d2-xult/src/sam_buttons.c | 2 +- configs/sama5d3-xplained/src/sam_buttons.c | 2 +- configs/sama5d3x-ek/src/sam_buttons.c | 2 +- configs/sama5d4-ek/src/sam_buttons.c | 2 +- configs/samd20-xplained/src/sam_buttons.c | 2 +- configs/samd21-xplained/src/sam_buttons.c | 2 +- configs/same70-xplained/src/sam_buttons.c | 2 +- configs/saml21-xplained/src/sam_buttons.c | 2 +- configs/samv71-xult/src/sam_buttons.c | 4 ++-- configs/shenzhou/src/stm32_buttons.c | 4 ++-- configs/skp16c26/src/m16c_buttons.c | 4 ++-- configs/spark/src/stm32_buttons.c | 2 +- configs/stm3210e-eval/src/stm32_buttons.c | 4 ++-- configs/stm3220g-eval/src/stm32_buttons.c | 4 ++-- configs/stm3240g-eval/src/stm32_buttons.c | 4 ++-- configs/stm32butterfly2/src/stm32_buttons.c | 4 ++-- configs/stm32f103-minimum/src/stm32_buttons.c | 4 ++-- configs/stm32f3discovery/src/stm32_buttons.c | 4 ++-- configs/stm32f429i-disco/src/stm32_buttons.c | 4 ++-- configs/stm32f4discovery/src/stm32_buttons.c | 4 ++-- configs/stm32f746g-disco/src/stm32_buttons.c | 2 +- configs/stm32l476-mdk/src/stm32_buttons.c | 4 ++-- configs/stm32l476vg-disco/src/stm32_buttons.c | 4 ++-- configs/stm32ldiscovery/src/stm32_buttons.c | 4 ++-- configs/stm32vldiscovery/src/stm32_buttons.c | 4 ++-- configs/sure-pic32mx/src/pic32mx_buttons.c | 4 ++-- configs/tm4c123g-launchpad/src/tm4c_buttons.c | 4 ++-- configs/tm4c1294-launchpad/src/tm4c_buttons.c | 4 ++-- configs/twr-k60n512/src/k60_buttons.c | 4 ++-- configs/ubw32/src/pic32_buttons.c | 4 ++-- configs/viewtool-stm32f107/src/stm32_buttons.c | 4 ++-- configs/xmc4500-relax/src/xmc4_buttons.c | 2 +- configs/zkit-arm-1769/src/lpc17_buttons.c | 4 ++-- include/nuttx/board.h | 2 +- include/nuttx/input/buttons.h | 2 +- net/sixlowpan/sixlowpan_internal.h | 4 ++-- 77 files changed, 125 insertions(+), 153 deletions(-) diff --git a/configs/avr32dev1/src/avr32_buttons.c b/configs/avr32dev1/src/avr32_buttons.c index 72191bb585..427a19d835 100644 --- a/configs/avr32dev1/src/avr32_buttons.c +++ b/configs/avr32dev1/src/avr32_buttons.c @@ -126,9 +126,9 @@ void board_button_initialize(void) * ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t retval; + uint32_t retval; retval = at32uc3_gpioread(PINMUX_GPIO_BUTTON1) ? 0 : BUTTON1; retval |= at32uc3_gpioread(PINMUX_GPIO_BUTTON2) ? 0 : BUTTON2; diff --git a/configs/bambino-200e/src/lpc43_buttons.c b/configs/bambino-200e/src/lpc43_buttons.c index 8aaeac3c95..8f96dafd27 100644 --- a/configs/bambino-200e/src/lpc43_buttons.c +++ b/configs/bambino-200e/src/lpc43_buttons.c @@ -120,9 +120,9 @@ void board_button_initialize(void) * ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; int i; /* Check that state of each key */ diff --git a/configs/clicker2-stm32/src/stm32_buttons.c b/configs/clicker2-stm32/src/stm32_buttons.c index 14da26b964..922007dcf6 100644 --- a/configs/clicker2-stm32/src/stm32_buttons.c +++ b/configs/clicker2-stm32/src/stm32_buttons.c @@ -79,9 +79,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; /* Check that state of each key. A low value will be sensed when the * button is pressed. diff --git a/configs/cloudctrl/src/stm32_buttons.c b/configs/cloudctrl/src/stm32_buttons.c index b62dbeb719..6603ce1d07 100644 --- a/configs/cloudctrl/src/stm32_buttons.c +++ b/configs/cloudctrl/src/stm32_buttons.c @@ -104,9 +104,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; int i; /* Check that state of each key */ diff --git a/configs/demo9s12ne64/src/m9s12_buttons.c b/configs/demo9s12ne64/src/m9s12_buttons.c index 2452139174..addf4af171 100644 --- a/configs/demo9s12ne64/src/m9s12_buttons.c +++ b/configs/demo9s12ne64/src/m9s12_buttons.c @@ -77,7 +77,7 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { return 0; } diff --git a/configs/dk-tm4c129x/src/tm4c_buttons.c b/configs/dk-tm4c129x/src/tm4c_buttons.c index f5b65bee71..7ef91a768b 100644 --- a/configs/dk-tm4c129x/src/tm4c_buttons.c +++ b/configs/dk-tm4c129x/src/tm4c_buttons.c @@ -103,9 +103,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; int i; /* Check that state of each key */ diff --git a/configs/ea3131/src/lpc31_buttons.c b/configs/ea3131/src/lpc31_buttons.c index de80fdf1bc..8b0822e649 100644 --- a/configs/ea3131/src/lpc31_buttons.c +++ b/configs/ea3131/src/lpc31_buttons.c @@ -49,18 +49,6 @@ #ifdef CONFIG_ARCH_BUTTONS -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - /**************************************************************************** * Public Functions ****************************************************************************/ @@ -77,7 +65,7 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { return 0; } diff --git a/configs/ea3152/src/lpc31_buttons.c b/configs/ea3152/src/lpc31_buttons.c index 28b349abb0..577692c1a1 100644 --- a/configs/ea3152/src/lpc31_buttons.c +++ b/configs/ea3152/src/lpc31_buttons.c @@ -49,18 +49,6 @@ #ifdef CONFIG_ARCH_BUTTONS -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - /**************************************************************************** * Public Functions ****************************************************************************/ @@ -77,7 +65,7 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { return 0; } diff --git a/configs/ez80f910200zco/src/ez80_buttons.c b/configs/ez80f910200zco/src/ez80_buttons.c index 6bc2aa9462..ee76218d0d 100644 --- a/configs/ez80f910200zco/src/ez80_buttons.c +++ b/configs/ez80f910200zco/src/ez80_buttons.c @@ -168,7 +168,7 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { return inp(EZ80_PB_DDR) & 7; } diff --git a/configs/fire-stm32v2/src/stm32_buttons.c b/configs/fire-stm32v2/src/stm32_buttons.c index d2dd07cd8e..5c041230f9 100644 --- a/configs/fire-stm32v2/src/stm32_buttons.c +++ b/configs/fire-stm32v2/src/stm32_buttons.c @@ -91,9 +91,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; /* Check that state of each key. A LOW value means that the key is pressed, */ diff --git a/configs/freedom-k64f/src/k64_buttons.c b/configs/freedom-k64f/src/k64_buttons.c index 0c9f22e8c8..d6f6ea44d6 100644 --- a/configs/freedom-k64f/src/k64_buttons.c +++ b/configs/freedom-k64f/src/k64_buttons.c @@ -92,9 +92,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; if (kinetis_gpioread(GPIO_SW2)) { diff --git a/configs/freedom-k66f/src/k66_buttons.c b/configs/freedom-k66f/src/k66_buttons.c index de70f31dc5..ce63345c85 100644 --- a/configs/freedom-k66f/src/k66_buttons.c +++ b/configs/freedom-k66f/src/k66_buttons.c @@ -96,9 +96,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; if (kinetis_gpioread(GPIO_SW2)) { diff --git a/configs/hymini-stm32v/src/stm32_buttons.c b/configs/hymini-stm32v/src/stm32_buttons.c index d92be06ab9..757f159af7 100644 --- a/configs/hymini-stm32v/src/stm32_buttons.c +++ b/configs/hymini-stm32v/src/stm32_buttons.c @@ -79,9 +79,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; bool pinValue; /* Check that state of each key */ diff --git a/configs/kwikstik-k40/src/k40_buttons.c b/configs/kwikstik-k40/src/k40_buttons.c index 7057ab1bd8..35f673d0ea 100644 --- a/configs/kwikstik-k40/src/k40_buttons.c +++ b/configs/kwikstik-k40/src/k40_buttons.c @@ -74,7 +74,7 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { /* The KwikStik-K40 board has no standard GPIO contact buttons */ diff --git a/configs/launchxl-tms57004/src/tms570_buttons.c b/configs/launchxl-tms57004/src/tms570_buttons.c index c0f307d2fe..3ee9e0eb31 100644 --- a/configs/launchxl-tms57004/src/tms570_buttons.c +++ b/configs/launchxl-tms57004/src/tms570_buttons.c @@ -159,7 +159,7 @@ void board_button_initialize(void) * ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { return tms570_gioread(GIO_BUTTON) ? BUTTON_GIOA7_BIT : 0; } diff --git a/configs/lincoln60/src/lpc17_buttons.c b/configs/lincoln60/src/lpc17_buttons.c index bcee2e34f0..48ea429826 100644 --- a/configs/lincoln60/src/lpc17_buttons.c +++ b/configs/lincoln60/src/lpc17_buttons.c @@ -127,9 +127,9 @@ void board_button_initialize(void) * ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; int i; /* Check that state of each key */ diff --git a/configs/lpc4330-xplorer/src/lpc43_buttons.c b/configs/lpc4330-xplorer/src/lpc43_buttons.c index 0d0f5db695..9e09ce07dc 100644 --- a/configs/lpc4330-xplorer/src/lpc43_buttons.c +++ b/configs/lpc4330-xplorer/src/lpc43_buttons.c @@ -126,9 +126,9 @@ void board_button_initialize(void) * ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; int i; /* Check that state of each key */ diff --git a/configs/lpc4357-evb/src/lpc43_buttons.c b/configs/lpc4357-evb/src/lpc43_buttons.c index c62229d35c..2ed5097495 100644 --- a/configs/lpc4357-evb/src/lpc43_buttons.c +++ b/configs/lpc4357-evb/src/lpc43_buttons.c @@ -129,10 +129,10 @@ void board_button_initialize(void) * ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { #if 0 /* Not yet implemented */ - uint8_t ret = 0; + uint32_t ret = 0; int i; /* Check that state of each key */ diff --git a/configs/ne64badge/src/m9s12_buttons.c b/configs/ne64badge/src/m9s12_buttons.c index 522d402c49..964b7114b5 100644 --- a/configs/ne64badge/src/m9s12_buttons.c +++ b/configs/ne64badge/src/m9s12_buttons.c @@ -94,9 +94,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; if (hcs12_gpioread(NE64BADGE_BUTTON1)) { diff --git a/configs/nucleo-144/src/stm32_buttons.c b/configs/nucleo-144/src/stm32_buttons.c index ea520e8473..5d47aa30bd 100644 --- a/configs/nucleo-144/src/stm32_buttons.c +++ b/configs/nucleo-144/src/stm32_buttons.c @@ -77,7 +77,7 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { return stm32_gpioread(GPIO_BTN_USER) ? 1 : 0; } diff --git a/configs/nucleo-f303re/src/stm32_buttons.c b/configs/nucleo-f303re/src/stm32_buttons.c index 65b046b819..8ae6081f48 100644 --- a/configs/nucleo-f303re/src/stm32_buttons.c +++ b/configs/nucleo-f303re/src/stm32_buttons.c @@ -88,7 +88,7 @@ void board_button_initialize(void) * ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { /* Check the state of the USER button. A LOW value means that the key is * pressed. diff --git a/configs/nucleo-f4x1re/src/stm32_buttons.c b/configs/nucleo-f4x1re/src/stm32_buttons.c index ab019d2a5c..30fd294fc5 100644 --- a/configs/nucleo-f4x1re/src/stm32_buttons.c +++ b/configs/nucleo-f4x1re/src/stm32_buttons.c @@ -78,7 +78,7 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { /* Check that state of each USER button. A LOW value means that the key is * pressed. diff --git a/configs/nucleo-l476rg/src/stm32_buttons.c b/configs/nucleo-l476rg/src/stm32_buttons.c index 7da458ffb3..55f99e8192 100644 --- a/configs/nucleo-l476rg/src/stm32_buttons.c +++ b/configs/nucleo-l476rg/src/stm32_buttons.c @@ -78,7 +78,7 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { /* Check that state of each USER button. A LOW value means that the key is * pressed. diff --git a/configs/olimex-efm32g880f128-stk/src/efm32_buttons.c b/configs/olimex-efm32g880f128-stk/src/efm32_buttons.c index e2bcba1a58..9637b12555 100644 --- a/configs/olimex-efm32g880f128-stk/src/efm32_buttons.c +++ b/configs/olimex-efm32g880f128-stk/src/efm32_buttons.c @@ -125,9 +125,9 @@ void board_button_initialize(void) * ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret; + uint32_t ret; int i; /* Check each button */ diff --git a/configs/olimex-lpc1766stk/src/lpc17_buttons.c b/configs/olimex-lpc1766stk/src/lpc17_buttons.c index 37326a8277..179a678584 100644 --- a/configs/olimex-lpc1766stk/src/lpc17_buttons.c +++ b/configs/olimex-lpc1766stk/src/lpc17_buttons.c @@ -130,9 +130,9 @@ void board_button_initialize(void) * ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; int i; /* Check that state of each key */ diff --git a/configs/olimex-stm32-e407/src/stm32_buttons.c b/configs/olimex-stm32-e407/src/stm32_buttons.c index 870b1ff8a9..c57c54f42d 100644 --- a/configs/olimex-stm32-e407/src/stm32_buttons.c +++ b/configs/olimex-stm32-e407/src/stm32_buttons.c @@ -96,9 +96,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; /* Check that state of each key */ diff --git a/configs/olimex-stm32-h405/src/stm32_buttons.c b/configs/olimex-stm32-h405/src/stm32_buttons.c index c3b6aa92fe..e7bd98cf23 100644 --- a/configs/olimex-stm32-h405/src/stm32_buttons.c +++ b/configs/olimex-stm32-h405/src/stm32_buttons.c @@ -96,9 +96,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; /* Check that state of each key */ diff --git a/configs/olimex-stm32-h407/src/stm32_buttons.c b/configs/olimex-stm32-h407/src/stm32_buttons.c index ed33810dd4..976157d117 100644 --- a/configs/olimex-stm32-h407/src/stm32_buttons.c +++ b/configs/olimex-stm32-h407/src/stm32_buttons.c @@ -96,9 +96,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; /* Check that state of each key */ diff --git a/configs/olimex-stm32-p207/src/stm32_buttons.c b/configs/olimex-stm32-p207/src/stm32_buttons.c index 0002098298..9400b7456c 100644 --- a/configs/olimex-stm32-p207/src/stm32_buttons.c +++ b/configs/olimex-stm32-p207/src/stm32_buttons.c @@ -102,9 +102,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; /* Check that state of each key */ diff --git a/configs/olimex-stm32-p407/src/stm32_buttons.c b/configs/olimex-stm32-p407/src/stm32_buttons.c index 6add698e0f..3d98c9eab7 100644 --- a/configs/olimex-stm32-p407/src/stm32_buttons.c +++ b/configs/olimex-stm32-p407/src/stm32_buttons.c @@ -104,9 +104,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; /* Check that state of each key */ diff --git a/configs/olimex-strp711/src/str71_buttons.c b/configs/olimex-strp711/src/str71_buttons.c index 98537be388..ec1b18b4d4 100644 --- a/configs/olimex-strp711/src/str71_buttons.c +++ b/configs/olimex-strp711/src/str71_buttons.c @@ -112,9 +112,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; if ((getreg16(STR71X_GPIO0_PD) & STR71X_WAKEUPBUTTON_GPIO0) != 0) { diff --git a/configs/olimexino-stm32/src/stm32_buttons.c b/configs/olimexino-stm32/src/stm32_buttons.c index 971bdb79f2..cc6ea25509 100644 --- a/configs/olimexino-stm32/src/stm32_buttons.c +++ b/configs/olimexino-stm32/src/stm32_buttons.c @@ -102,7 +102,7 @@ void board_button_initialize(void) * ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { return stm32_gpioread(BUTTON_BOOT0n) ? 0 : BUTTON_BOOT0_MASK; } diff --git a/configs/open1788/src/lpc17_buttons.c b/configs/open1788/src/lpc17_buttons.c index e7a7cf8851..f2e2fb5f27 100644 --- a/configs/open1788/src/lpc17_buttons.c +++ b/configs/open1788/src/lpc17_buttons.c @@ -149,9 +149,9 @@ void board_button_initialize(void) * ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; int i; /* Check that state of each key */ diff --git a/configs/pcduino-a10/src/a1x_buttons.c b/configs/pcduino-a10/src/a1x_buttons.c index a690ae866d..c7d1089135 100644 --- a/configs/pcduino-a10/src/a1x_buttons.c +++ b/configs/pcduino-a10/src/a1x_buttons.c @@ -84,7 +84,7 @@ void board_button_initialize(void) * ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { # warning Missing logic } diff --git a/configs/photon/src/stm32_buttons.c b/configs/photon/src/stm32_buttons.c index 7c695dd5ef..7a9297eb6b 100644 --- a/configs/photon/src/stm32_buttons.c +++ b/configs/photon/src/stm32_buttons.c @@ -66,7 +66,7 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { /* Check the state of the only button */ diff --git a/configs/pic32mz-starterkit/src/pic32mz_buttons.c b/configs/pic32mz-starterkit/src/pic32mz_buttons.c index a51ca05f08..206be294c3 100644 --- a/configs/pic32mz-starterkit/src/pic32mz_buttons.c +++ b/configs/pic32mz-starterkit/src/pic32mz_buttons.c @@ -105,9 +105,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; int i; /* Check that state of each key */ diff --git a/configs/sam3u-ek/src/sam_buttons.c b/configs/sam3u-ek/src/sam_buttons.c index 520f05e1a5..107c7036a6 100644 --- a/configs/sam3u-ek/src/sam_buttons.c +++ b/configs/sam3u-ek/src/sam_buttons.c @@ -133,9 +133,9 @@ void board_button_initialize(void) * ************************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t retval; + uint32_t retval; retval = sam_gpioread(GPIO_BUTTON1) ? 0 : BUTTON1; retval |= sam_gpioread(GPIO_BUTTON2) ? 0 : BUTTON2; diff --git a/configs/sam4e-ek/src/sam_buttons.c b/configs/sam4e-ek/src/sam_buttons.c index d9fbabeb6d..53626290b7 100644 --- a/configs/sam4e-ek/src/sam_buttons.c +++ b/configs/sam4e-ek/src/sam_buttons.c @@ -135,9 +135,9 @@ void board_button_initialize(void) * ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t retval; + uint32_t retval; retval = sam_gpioread(GPIO_SCROLLUP) ? 0 : BUTTON_SCROLLUP; retval |= sam_gpioread(GPIO_SCROLLDWN) ? 0 : BUTTON_SCROLLDOWN; diff --git a/configs/sam4l-xplained/src/sam_buttons.c b/configs/sam4l-xplained/src/sam_buttons.c index 619f7d658b..8d306bb311 100644 --- a/configs/sam4l-xplained/src/sam_buttons.c +++ b/configs/sam4l-xplained/src/sam_buttons.c @@ -53,10 +53,6 @@ #ifdef CONFIG_ARCH_BUTTONS -/**************************************************************************** - * Private Functions - ****************************************************************************/ - /**************************************************************************** * Public Functions ****************************************************************************/ @@ -88,7 +84,7 @@ void board_button_initialize(void) * ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { return sam_gpioread(GPIO_SW0) ? 0 : BUTTON_SW0_BIT; } diff --git a/configs/sam4s-xplained-pro/src/sam_buttons.c b/configs/sam4s-xplained-pro/src/sam_buttons.c index daae49b89e..3b9b4fe359 100644 --- a/configs/sam4s-xplained-pro/src/sam_buttons.c +++ b/configs/sam4s-xplained-pro/src/sam_buttons.c @@ -86,7 +86,7 @@ void board_button_initialize(void) * ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { return sam_gpioread(GPIO_SW0) ? 0 : BUTTON_SW0_BIT; } diff --git a/configs/sam4s-xplained/src/sam_buttons.c b/configs/sam4s-xplained/src/sam_buttons.c index 940f97edae..314e8e1818 100644 --- a/configs/sam4s-xplained/src/sam_buttons.c +++ b/configs/sam4s-xplained/src/sam_buttons.c @@ -85,7 +85,7 @@ void board_button_initialize(void) * ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { return sam_gpioread(GPIO_BP2) ? 0 : BUTTON_BP2_BIT; } diff --git a/configs/sama5d2-xult/src/sam_buttons.c b/configs/sama5d2-xult/src/sam_buttons.c index c93fa6b904..0939ddaa11 100644 --- a/configs/sama5d2-xult/src/sam_buttons.c +++ b/configs/sama5d2-xult/src/sam_buttons.c @@ -96,7 +96,7 @@ void board_button_initialize(void) * ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { return sam_pioread(PIO_BTN_USER) ? 0 : BUTTON_USER_BIT; } diff --git a/configs/sama5d3-xplained/src/sam_buttons.c b/configs/sama5d3-xplained/src/sam_buttons.c index b7fd824556..43794b374d 100644 --- a/configs/sama5d3-xplained/src/sam_buttons.c +++ b/configs/sama5d3-xplained/src/sam_buttons.c @@ -100,7 +100,7 @@ void board_button_initialize(void) * ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { return sam_pioread(PIO_USER) ? 0 : BUTTON_USER_BIT; } diff --git a/configs/sama5d3x-ek/src/sam_buttons.c b/configs/sama5d3x-ek/src/sam_buttons.c index 5b7ccc9b90..dbdaa310f6 100644 --- a/configs/sama5d3x-ek/src/sam_buttons.c +++ b/configs/sama5d3x-ek/src/sam_buttons.c @@ -100,7 +100,7 @@ void board_button_initialize(void) * ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { return sam_pioread(PIO_USER1) ? 0 : BUTTON_USER1_BIT; } diff --git a/configs/sama5d4-ek/src/sam_buttons.c b/configs/sama5d4-ek/src/sam_buttons.c index 5696d96de5..4ccae619f6 100644 --- a/configs/sama5d4-ek/src/sam_buttons.c +++ b/configs/sama5d4-ek/src/sam_buttons.c @@ -96,7 +96,7 @@ void board_button_initialize(void) * ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { return sam_pioread(PIO_BTN_USER) ? 0 : BUTTON_USER_BIT; } diff --git a/configs/samd20-xplained/src/sam_buttons.c b/configs/samd20-xplained/src/sam_buttons.c index 88c24aced7..fc8f14bd0c 100644 --- a/configs/samd20-xplained/src/sam_buttons.c +++ b/configs/samd20-xplained/src/sam_buttons.c @@ -85,7 +85,7 @@ void board_button_initialize(void) * ************************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { return sam_portread(PORT_SW0) ? 0 : BUTTON_SW0_BIT; } diff --git a/configs/samd21-xplained/src/sam_buttons.c b/configs/samd21-xplained/src/sam_buttons.c index aa19ddc008..e4c31aa941 100644 --- a/configs/samd21-xplained/src/sam_buttons.c +++ b/configs/samd21-xplained/src/sam_buttons.c @@ -85,7 +85,7 @@ void board_button_initialize(void) * ************************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { return sam_portread(PORT_SW0) ? 0 : BUTTON_SW0_BIT; } diff --git a/configs/same70-xplained/src/sam_buttons.c b/configs/same70-xplained/src/sam_buttons.c index 669a6d3bfe..7e66905c8a 100644 --- a/configs/same70-xplained/src/sam_buttons.c +++ b/configs/same70-xplained/src/sam_buttons.c @@ -147,7 +147,7 @@ void board_button_initialize(void) * ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { return sam_gpioread(GPIO_SW0) ? 0 : BUTTON_SW0_BIT; } diff --git a/configs/saml21-xplained/src/sam_buttons.c b/configs/saml21-xplained/src/sam_buttons.c index 437c4d7ec8..909fa58a7a 100644 --- a/configs/saml21-xplained/src/sam_buttons.c +++ b/configs/saml21-xplained/src/sam_buttons.c @@ -85,7 +85,7 @@ void board_button_initialize(void) * ************************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { return sam_portread(PORT_SW0) ? 0 : BUTTON_SW0_BIT; } diff --git a/configs/samv71-xult/src/sam_buttons.c b/configs/samv71-xult/src/sam_buttons.c index 7c9a98b52c..1a06c84034 100644 --- a/configs/samv71-xult/src/sam_buttons.c +++ b/configs/samv71-xult/src/sam_buttons.c @@ -163,9 +163,9 @@ void board_button_initialize(void) * ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t retval; + uint32_t retval; retval = sam_gpioread(GPIO_SW0) ? 0 : BUTTON_SW0_BIT; retval |= sam_gpioread(GPIO_SW1) ? 0 : BUTTON_SW1_BIT; diff --git a/configs/shenzhou/src/stm32_buttons.c b/configs/shenzhou/src/stm32_buttons.c index 515cad297f..139d517956 100644 --- a/configs/shenzhou/src/stm32_buttons.c +++ b/configs/shenzhou/src/stm32_buttons.c @@ -96,9 +96,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; int i; /* Check that state of each key */ diff --git a/configs/skp16c26/src/m16c_buttons.c b/configs/skp16c26/src/m16c_buttons.c index 4841fefe82..78832b9c59 100644 --- a/configs/skp16c26/src/m16c_buttons.c +++ b/configs/skp16c26/src/m16c_buttons.c @@ -89,9 +89,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t swset = 0; + uint32_t swset = 0; uint8_t regval = getreg8(M16C_P8); if (SW_PRESSED(regval, SW1_BIT)) diff --git a/configs/spark/src/stm32_buttons.c b/configs/spark/src/stm32_buttons.c index e41463d6c9..3ab2f3c854 100644 --- a/configs/spark/src/stm32_buttons.c +++ b/configs/spark/src/stm32_buttons.c @@ -80,7 +80,7 @@ void board_button_initialize(void) * N.B The return state in true logic, the button polarity is dealt here in ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { return stm32_gpioread(GPIO_BTN)==0 ? BUTTON_USER_BIT : 0; } diff --git a/configs/stm3210e-eval/src/stm32_buttons.c b/configs/stm3210e-eval/src/stm32_buttons.c index 043535444c..b9f4822814 100644 --- a/configs/stm3210e-eval/src/stm32_buttons.c +++ b/configs/stm3210e-eval/src/stm32_buttons.c @@ -108,9 +108,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; int i; /* Check that state of each key */ diff --git a/configs/stm3220g-eval/src/stm32_buttons.c b/configs/stm3220g-eval/src/stm32_buttons.c index 115fea249e..669b460b03 100644 --- a/configs/stm3220g-eval/src/stm32_buttons.c +++ b/configs/stm3220g-eval/src/stm32_buttons.c @@ -96,9 +96,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; int i; /* Check that state of each key */ diff --git a/configs/stm3240g-eval/src/stm32_buttons.c b/configs/stm3240g-eval/src/stm32_buttons.c index a20c03f16a..4682ffb1a9 100644 --- a/configs/stm3240g-eval/src/stm32_buttons.c +++ b/configs/stm3240g-eval/src/stm32_buttons.c @@ -104,9 +104,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; int i; /* Check that state of each key */ diff --git a/configs/stm32butterfly2/src/stm32_buttons.c b/configs/stm32butterfly2/src/stm32_buttons.c index 85e7a0751c..612776adc5 100644 --- a/configs/stm32butterfly2/src/stm32_buttons.c +++ b/configs/stm32butterfly2/src/stm32_buttons.c @@ -92,9 +92,9 @@ void board_button_initialize(void) * Reads keys ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t rv = 0; + uint32_t rv = 0; int i; for (i = 0; i != NUM_BUTTONS; ++i) diff --git a/configs/stm32f103-minimum/src/stm32_buttons.c b/configs/stm32f103-minimum/src/stm32_buttons.c index ebca1469f1..6891b3db0a 100644 --- a/configs/stm32f103-minimum/src/stm32_buttons.c +++ b/configs/stm32f103-minimum/src/stm32_buttons.c @@ -104,9 +104,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; int i; /* Check that state of each key */ diff --git a/configs/stm32f3discovery/src/stm32_buttons.c b/configs/stm32f3discovery/src/stm32_buttons.c index f89fd207a3..a0ecada6a5 100644 --- a/configs/stm32f3discovery/src/stm32_buttons.c +++ b/configs/stm32f3discovery/src/stm32_buttons.c @@ -96,9 +96,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; int i; /* Check that state of each key */ diff --git a/configs/stm32f429i-disco/src/stm32_buttons.c b/configs/stm32f429i-disco/src/stm32_buttons.c index a6ffed5433..d2e9ba2e09 100644 --- a/configs/stm32f429i-disco/src/stm32_buttons.c +++ b/configs/stm32f429i-disco/src/stm32_buttons.c @@ -96,9 +96,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; int i; /* Check that state of each key */ diff --git a/configs/stm32f4discovery/src/stm32_buttons.c b/configs/stm32f4discovery/src/stm32_buttons.c index 449001f13a..2d86ea80cf 100644 --- a/configs/stm32f4discovery/src/stm32_buttons.c +++ b/configs/stm32f4discovery/src/stm32_buttons.c @@ -96,9 +96,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; int i; /* Check that state of each key */ diff --git a/configs/stm32f746g-disco/src/stm32_buttons.c b/configs/stm32f746g-disco/src/stm32_buttons.c index ec08616aa6..b8a46a8dac 100644 --- a/configs/stm32f746g-disco/src/stm32_buttons.c +++ b/configs/stm32f746g-disco/src/stm32_buttons.c @@ -77,7 +77,7 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { return stm32_gpioread(GPIO_BTN_USER) ? 1 : 0; } diff --git a/configs/stm32l476-mdk/src/stm32_buttons.c b/configs/stm32l476-mdk/src/stm32_buttons.c index 955cba926d..7debe3c597 100644 --- a/configs/stm32l476-mdk/src/stm32_buttons.c +++ b/configs/stm32l476-mdk/src/stm32_buttons.c @@ -103,9 +103,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; int i; /* Check that state of each key */ diff --git a/configs/stm32l476vg-disco/src/stm32_buttons.c b/configs/stm32l476vg-disco/src/stm32_buttons.c index 1d85b27875..f3c4d50c9c 100644 --- a/configs/stm32l476vg-disco/src/stm32_buttons.c +++ b/configs/stm32l476vg-disco/src/stm32_buttons.c @@ -261,9 +261,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; int i; /* Check that state of each key */ diff --git a/configs/stm32ldiscovery/src/stm32_buttons.c b/configs/stm32ldiscovery/src/stm32_buttons.c index f599b0c851..f766017d15 100644 --- a/configs/stm32ldiscovery/src/stm32_buttons.c +++ b/configs/stm32ldiscovery/src/stm32_buttons.c @@ -96,9 +96,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; int i; /* Check that state of each key */ diff --git a/configs/stm32vldiscovery/src/stm32_buttons.c b/configs/stm32vldiscovery/src/stm32_buttons.c index 259cfee756..9784b19d77 100644 --- a/configs/stm32vldiscovery/src/stm32_buttons.c +++ b/configs/stm32vldiscovery/src/stm32_buttons.c @@ -75,9 +75,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; ret = (stm32_gpioread(g_buttons[i]) == false ? 1 : 0); diff --git a/configs/sure-pic32mx/src/pic32mx_buttons.c b/configs/sure-pic32mx/src/pic32mx_buttons.c index 6c378dd0a6..bf5ca03429 100644 --- a/configs/sure-pic32mx/src/pic32mx_buttons.c +++ b/configs/sure-pic32mx/src/pic32mx_buttons.c @@ -157,9 +157,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; int id; /* Configure input pins */ diff --git a/configs/tm4c123g-launchpad/src/tm4c_buttons.c b/configs/tm4c123g-launchpad/src/tm4c_buttons.c index a61c7e9c78..96370046f4 100644 --- a/configs/tm4c123g-launchpad/src/tm4c_buttons.c +++ b/configs/tm4c123g-launchpad/src/tm4c_buttons.c @@ -118,9 +118,9 @@ void board_button_initialize(void) * ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; /* Check that state of each key. A LOW value means that the key is * pressed. diff --git a/configs/tm4c1294-launchpad/src/tm4c_buttons.c b/configs/tm4c1294-launchpad/src/tm4c_buttons.c index 17d83c81f3..5b72e5bb29 100644 --- a/configs/tm4c1294-launchpad/src/tm4c_buttons.c +++ b/configs/tm4c1294-launchpad/src/tm4c_buttons.c @@ -102,9 +102,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; int i; /* Check that state of each key */ diff --git a/configs/twr-k60n512/src/k60_buttons.c b/configs/twr-k60n512/src/k60_buttons.c index a952f64828..d9206f2c71 100644 --- a/configs/twr-k60n512/src/k60_buttons.c +++ b/configs/twr-k60n512/src/k60_buttons.c @@ -94,9 +94,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; if (kinetis_gpioread(GPIO_SW1)) { diff --git a/configs/ubw32/src/pic32_buttons.c b/configs/ubw32/src/pic32_buttons.c index f612e1eea4..69b1deeb44 100644 --- a/configs/ubw32/src/pic32_buttons.c +++ b/configs/ubw32/src/pic32_buttons.c @@ -132,9 +132,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; int id; /* Configure input pins */ diff --git a/configs/viewtool-stm32f107/src/stm32_buttons.c b/configs/viewtool-stm32f107/src/stm32_buttons.c index 9039e72e09..9e39a2d72c 100644 --- a/configs/viewtool-stm32f107/src/stm32_buttons.c +++ b/configs/viewtool-stm32f107/src/stm32_buttons.c @@ -96,9 +96,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; int i; /* Check that state of each key */ diff --git a/configs/xmc4500-relax/src/xmc4_buttons.c b/configs/xmc4500-relax/src/xmc4_buttons.c index 24f9e05a20..881467f11c 100644 --- a/configs/xmc4500-relax/src/xmc4_buttons.c +++ b/configs/xmc4500-relax/src/xmc4_buttons.c @@ -59,7 +59,7 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { #warning Missing logic return 0; diff --git a/configs/zkit-arm-1769/src/lpc17_buttons.c b/configs/zkit-arm-1769/src/lpc17_buttons.c index 6c98465032..ffa7646686 100644 --- a/configs/zkit-arm-1769/src/lpc17_buttons.c +++ b/configs/zkit-arm-1769/src/lpc17_buttons.c @@ -109,9 +109,9 @@ void board_button_initialize(void) * Name: board_buttons ****************************************************************************/ -uint8_t board_buttons(void) +uint32_t board_buttons(void) { - uint8_t ret = 0; + uint32_t ret = 0; bool released; int i; diff --git a/include/nuttx/board.h b/include/nuttx/board.h index 0525499021..310a973c34 100644 --- a/include/nuttx/board.h +++ b/include/nuttx/board.h @@ -593,7 +593,7 @@ void board_button_initialize(void); ****************************************************************************/ #ifdef CONFIG_ARCH_BUTTONS -uint8_t board_buttons(void); +uint32_t board_buttons(void); #endif /**************************************************************************** diff --git a/include/nuttx/input/buttons.h b/include/nuttx/input/buttons.h index 3012ba9857..13ba28c3aa 100644 --- a/include/nuttx/input/buttons.h +++ b/include/nuttx/input/buttons.h @@ -96,7 +96,7 @@ * from the button driver. */ -typedef uint8_t btn_buttonset_t; +typedef uint32_t btn_buttonset_t; /* A reference to this structure is provided with the BTNIOC_POLLEVENTS IOCTL * command and describes the conditions under which the client would like diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index da104f89be..be29abc8ca 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -92,7 +92,7 @@ #define PACKETBUF_ATTR_PACKET_TYPE_STREAM_END 3 #define PACKETBUF_ATTR_PACKET_TYPE_TIMESTAMP 4 -/* Packet buffer attributes (indices into i_pktattr) */ +/* Packet buffer attributes (indices into g_pktattrs) */ #define PACKETBUF_ATTR_NONE 0 @@ -130,7 +130,7 @@ #define PACKETBUF_NUM_ATTRS 24 -/* Addresses (indices into i_pktaddr) */ +/* Addresses (indices into g_pktaddrs) */ #define PACKETBUF_ADDR_SENDER 0 #define PACKETBUF_ADDR_RECEIVER 1 -- GitLab From 55b32430e16a6f8727f196650ef7b46689a7ad01 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 9 Apr 2017 07:48:40 -0600 Subject: [PATCH 394/990] Fix photon/nsh/defconfig, was turning on non-existent LED support when the configuration was refreshed. --- configs/photon/nsh/defconfig | 35 ++++++++++++++++++++++++++++------- 1 file changed, 28 insertions(+), 7 deletions(-) diff --git a/configs/photon/nsh/defconfig b/configs/photon/nsh/defconfig index f11b644af3..c82bde94e9 100644 --- a/configs/photon/nsh/defconfig +++ b/configs/photon/nsh/defconfig @@ -90,6 +90,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -101,7 +102,7 @@ CONFIG_ARCH_CHIP_STM32=y # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -371,9 +372,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -387,7 +392,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -401,6 +409,7 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set # CONFIG_STM32_OTGFS is not set # CONFIG_STM32_OTGHS is not set # CONFIG_STM32_PWR is not set @@ -436,6 +445,7 @@ CONFIG_STM32_IWDG=y # # Alternate Pin Mapping # +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -569,6 +579,11 @@ CONFIG_ARCH_BOARD="photon" # # Common Board Options # +CONFIG_ARCH_HAVE_LEDS=y +# CONFIG_ARCH_LEDS is not set +CONFIG_ARCH_HAVE_BUTTONS=y +# CONFIG_ARCH_BUTTONS is not set +CONFIG_ARCH_HAVE_IRQBUTTONS=y # # Board-Specific Options @@ -638,6 +653,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -755,6 +772,7 @@ CONFIG_WATCHDOG_DEVPATH="/dev/watchdog0" # # LED Support # +# CONFIG_USERLED is not set # CONFIG_RGBLED is not set # CONFIG_PCA9635PW is not set # CONFIG_NCP5623C is not set @@ -818,6 +836,7 @@ CONFIG_USART1_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -1042,10 +1061,6 @@ CONFIG_HAVE_CXXINITIALIZE=y # Application Configuration # -# -# NxWidgets/NxWM -# - # # Built-In Applications # @@ -1058,6 +1073,7 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # # Examples # +# CONFIG_EXAMPLES_BUTTONS is not set # CONFIG_EXAMPLES_CCTYPE is not set # CONFIG_EXAMPLES_CHAT is not set # CONFIG_EXAMPLES_CONFIGDATA is not set @@ -1072,6 +1088,7 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_IGMP is not set # CONFIG_EXAMPLES_JSON is not set # CONFIG_EXAMPLES_KEYPADTEST is not set +# CONFIG_EXAMPLES_LEDS is not set # CONFIG_EXAMPLES_MEDIA is not set # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set @@ -1106,9 +1123,9 @@ CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_TIFF is not set # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_USBSERIAL is not set -# CONFIG_EXAMPLES_USBTERM is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1249,6 +1266,10 @@ CONFIG_NSH_ARCHINIT=y # CONFIG_NSH_LOGIN is not set # CONFIG_NSH_CONSOLE_LOGIN is not set +# +# NxWidgets/NxWM +# + # # Platform-specific Support # -- GitLab From 2bfb284989383a52615e2c14198a1af6367e14ce Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 9 Apr 2017 09:19:25 -0600 Subject: [PATCH 395/990] Add support for NuttX controlled LEDS and for board_initialize. Separate initialize logic to stm32_bringup.c so that in initialization can occur either through board_initialize() or through board_app_initialize(). Same as with most other newer board configurations. --- configs/photon/include/board.h | 33 +++++ configs/photon/src/Makefile | 16 ++- configs/photon/src/photon.h | 15 ++ configs/photon/src/stm32_appinit.c | 83 ++--------- configs/photon/src/stm32_autoleds.c | 116 +++++++++++++++ configs/photon/src/stm32_boot.c | 28 ++++ configs/photon/src/stm32_bringup.c | 132 ++++++++++++++++++ configs/photon/src/stm32_usb.c | 12 -- .../src/{stm32_leds.c => stm32_userleds.c} | 6 +- configs/photon/src/stm32_wdt.c | 5 - configs/photon/src/stm32_wlan.c | 17 ++- configs/same70-xplained/src/sam_autoleds.c | 2 +- 12 files changed, 362 insertions(+), 103 deletions(-) create mode 100644 configs/photon/src/stm32_autoleds.c create mode 100644 configs/photon/src/stm32_bringup.c rename configs/photon/src/{stm32_leds.c => stm32_userleds.c} (97%) diff --git a/configs/photon/include/board.h b/configs/photon/include/board.h index 8c2fc655e3..96115ca57f 100644 --- a/configs/photon/include/board.h +++ b/configs/photon/include/board.h @@ -152,11 +152,44 @@ #undef BOARD_ENABLE_USBOTG_HSULPI /* LED definitions ******************************************************************/ +/* LEDs + * + * A single LED is available driven by PA13. + */ + +/* LED index values for use with board_userled() */ #define BOARD_LED1 0 #define BOARD_NLEDS 1 + +/* LED bits for use with board_userled_all() */ + #define BOARD_LED1_BIT (1 << BOARD_LED1) +/* These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is + * defined. In that case, the usage by the board port is defined in + * include/board.h and src/sam_autoleds.c. The LEDs are used to encode + * OS-related events as follows: + * + * ------------------- ---------------------------- ------ + * SYMBOL Meaning LED + * ------------------- ---------------------------- ------ */ + +#define LED_STARTED 0 /* NuttX has been started OFF */ +#define LED_HEAPALLOCATE 0 /* Heap has been allocated OFF */ +#define LED_IRQSENABLED 0 /* Interrupts enabled OFF */ +#define LED_STACKCREATED 1 /* Idle stack created ON */ +#define LED_INIRQ 2 /* In an interrupt N/C */ +#define LED_SIGNAL 2 /* In a signal handler N/C */ +#define LED_ASSERTION 2 /* An assertion failed N/C */ +#define LED_PANIC 3 /* The system has crashed FLASH */ +#undef LED_IDLE /* MCU is is sleep mode Not used */ + +/* Thus if LED is statically on, NuttX has successfully booted and is, + * apparently, running normally. If LED is flashing at approximately + * 2Hz, then a fatal error has been detected and the system has halted. + */ + /* Button definitions ***************************************************************/ #define BOARD_BUTTON1 0 diff --git a/configs/photon/src/Makefile b/configs/photon/src/Makefile index 5d9501759c..23f31b4489 100644 --- a/configs/photon/src/Makefile +++ b/configs/photon/src/Makefile @@ -35,18 +35,24 @@ -include $(TOPDIR)/Make.defs ASRCS = -CSRCS = stm32_boot.c +CSRCS = stm32_boot.c stm32_bringup.c ifeq ($(CONFIG_PHOTON_DFU_BOOTLOADER),y) CSRCS += dfu_signature.c endif +ifeq ($(CONFIG_LIB_BOARDCTL),y) +CSRCS += stm32_appinit.c +endif + ifeq ($(CONFIG_BUTTONS),y) CSRCS += stm32_buttons.c endif -ifeq ($(CONFIG_USERLED),y) -CSRCS += stm32_leds.c +ifeq ($(CONFIG_ARCH_LEDS),y) +CSRCS += stm32_autoleds.c +else +CSRCS += stm32_userleds.c endif ifeq ($(CONFIG_PHOTON_WDG),y) @@ -61,8 +67,4 @@ ifeq ($(CONFIG_STM32_OTGHS),y) CSRCS += stm32_usb.c endif -ifeq ($(CONFIG_NSH_LIBRARY),y) -CSRCS += stm32_appinit.c -endif - include $(TOPDIR)/configs/Board.mk diff --git a/configs/photon/src/photon.h b/configs/photon/src/photon.h index 4e0f312b6c..5628d1b69c 100644 --- a/configs/photon/src/photon.h +++ b/configs/photon/src/photon.h @@ -89,6 +89,21 @@ * Public Functions ****************************************************************************/ +/**************************************************************************** + * Name: stm32_bringup + * + * Description: + * Called either by board_intialize() if CONFIG_BOARD_INITIALIZE or by + * board_app_initialize if CONFIG_LIB_BOARDCTL is selected. This function + * initializes and configures all on-board features appropriate for the + * selected configuration. + * + ****************************************************************************/ + +#if defined(CONFIG_LIB_BOARDCTL) || defined(CONFIG_BOARD_INITIALIZE) +int stm32_bringup(void); +#endif + /**************************************************************************** * Name: photon_watchdog_initialize() * diff --git a/configs/photon/src/stm32_appinit.c b/configs/photon/src/stm32_appinit.c index dc2899789f..946dfbe8e2 100644 --- a/configs/photon/src/stm32_appinit.c +++ b/configs/photon/src/stm32_appinit.c @@ -2,7 +2,7 @@ * config/photon/src/stm32_appinit.c * * Copyright (C) 2017 Gregory Nutt. All rights reserved. - * Author: Simon Piriou + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -38,23 +38,14 @@ ****************************************************************************/ #include -#include -#include -#include +#include + +#include #include "photon.h" -#include "stm32_wdg.h" -#include -#include -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -#ifndef OK -# define OK 0 -#endif +#ifdef CONFIG_LIB_BOARDCTL /**************************************************************************** * Public Functions @@ -87,65 +78,13 @@ int board_app_initialize(uintptr_t arg) { - int ret = OK; - -#ifdef CONFIG_USERLED -#ifdef CONFIG_USERLED_LOWER - /* Register the LED driver */ - - ret = userled_lower_initialize("/dev/userleds"); - if (ret != OK) - { - syslog(LOG_ERR, "ERROR: userled_lower_initialize() failed: %d\n", ret); - return ret; - } -#else - board_userled_initialize(); -#endif /* CONFIG_USERLED_LOWER */ -#endif /* CONFIG_USERLED */ - -#ifdef CONFIG_BUTTONS -#ifdef CONFIG_BUTTONS_LOWER - /* Register the BUTTON driver */ +#ifndef CONFIG_BOARD_INITIALIZE + /* Perform board initialization */ - ret = btn_lower_initialize("/dev/buttons"); - if (ret != OK) - { - syslog(LOG_ERR, "ERROR: btn_lower_initialize() failed: %d\n", ret); - return ret; - } + return stm32_bringup(); #else - board_button_initialize(); -#endif /* CONFIG_BUTTONS_LOWER */ -#endif /* CONFIG_BUTTONS */ - -#ifdef CONFIG_STM32_IWDG - stm32_iwdginitialize("/dev/watchdog0", STM32_LSI_FREQUENCY); -#endif - -#ifdef CONFIG_PHOTON_WDG - - /* Start WDG kicker thread */ - - ret = photon_watchdog_initialize(); - if (ret != OK) - { - syslog(LOG_ERR, "Failed to start watchdog thread: %d\n", ret); - return ret; - } + return OK; #endif - -#ifdef CONFIG_PHOTON_WLAN - - /* Initialize wlan driver and hardware */ - - ret = photon_wlan_initialize(); - if (ret != OK) - { - syslog(LOG_ERR, "Failed to initialize wlan: %d\n", ret); - return ret; - } -#endif - - return ret; } + +#endif /* CONFIG_LIB_BOARDCTL */ diff --git a/configs/photon/src/stm32_autoleds.c b/configs/photon/src/stm32_autoleds.c new file mode 100644 index 0000000000..a490fa5432 --- /dev/null +++ b/configs/photon/src/stm32_autoleds.c @@ -0,0 +1,116 @@ +/**************************************************************************** + * configs/photon/src/stm32_autoleds.c + * + * 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. + * + ****************************************************************************/ + +/* LEDs + * + * A single LED is available driven by PA13. + * + * These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is + * defined. In that case, the usage by the board port is defined in + * include/board.h and src/sam_autoleds.c. The LEDs are used to encode + * OS-related events as follows: + * + * ------------------- ----------------------- ------ + * SYMBOL Meaning LED + * ------------------- ----------------------- ------ + * LED_STARTED NuttX has been started OFF + * LED_HEAPALLOCATE Heap has been allocated OFF + * LED_IRQSENABLED Interrupts enabled OFF + * LED_STACKCREATED Idle stack created ON + * LED_INIRQ In an interrupt N/C + * LED_SIGNAL In a signal handler N/C + * LED_ASSERTION An assertion failed N/C + * LED_PANIC The system has crashed FLASH + * + * Thus is LED is statically on, NuttX has successfully booted and is, + * apparently, running normally. If LED is flashing at approximately + * 2Hz, then a fatal error has been detected and the system has halted. + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include + +#include "stm32_gpio.h" +#include "photon.h" + +#ifdef CONFIG_ARCH_LEDS + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_autoled_initialize + ****************************************************************************/ + +void board_autoled_initialize(void) +{ + /* Configure Photon LED gpio as output */ + + stm32_configgpio(GPIO_LED1); +} + +/**************************************************************************** + * Name: board_autoled_on + ****************************************************************************/ + +void board_autoled_on(int led) +{ + if (led == 1 || led == 3) + { + stm32_gpiowrite(GPIO_LED1, true); + } +} + +/**************************************************************************** + * Name: board_autoled_off + ****************************************************************************/ + +void board_autoled_off(int led) +{ + if (led == 3) + { + stm32_gpiowrite(GPIO_LED1, false); + } +} + +#endif /* CONFIG_ARCH_LEDS */ diff --git a/configs/photon/src/stm32_boot.c b/configs/photon/src/stm32_boot.c index c9dfe28729..5adc28f31c 100644 --- a/configs/photon/src/stm32_boot.c +++ b/configs/photon/src/stm32_boot.c @@ -73,4 +73,32 @@ void stm32_boardinitialize(void) stm32_usbinitialize(); } #endif + +#ifdef CONFIG_ARCH_LEDS + /* Configure on-board LEDs if LED support has been selected. */ + + board_autoled_initialize(); +#endif +} + +/**************************************************************************** + * Name: board_initialize + * + * Description: + * If CONFIG_BOARD_INITIALIZE is selected, then an additional + * initialization call will be performed in the boot-up sequence to a + * function called board_initialize(). board_initialize() will be + * called immediately after up_intitialize() is called and just before the + * initial application is started. This additional initialization phase + * may be used, for example, to initialize board-specific device drivers. + * + ****************************************************************************/ + +#ifdef CONFIG_BOARD_INITIALIZE +void board_initialize(void) +{ + /* Perform board initialization */ + + (void)stm32_bringup(); } +#endif /* CONFIG_BOARD_INITIALIZE */ diff --git a/configs/photon/src/stm32_bringup.c b/configs/photon/src/stm32_bringup.c new file mode 100644 index 0000000000..d83e0493ed --- /dev/null +++ b/configs/photon/src/stm32_bringup.c @@ -0,0 +1,132 @@ +/**************************************************************************** + * config/photon/src/stm32_bringup.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Simon Piriou + * + * 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 "photon.h" +#include "stm32_wdg.h" + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_bringup + * + * Description: + * Called either by board_intialize() if CONFIG_BOARD_INITIALIZE or by + * board_app_initialize if CONFIG_LIB_BOARDCTL is selected. This function + * initializes and configures all on-board features appropriate for the + * selected configuration. + * + ****************************************************************************/ + +int stm32_bringup(void) +{ + int ret = OK; + +#ifdef CONFIG_USERLED +#ifdef CONFIG_USERLED_LOWER + /* Register the LED driver */ + + ret = userled_lower_initialize("/dev/userleds"); + if (ret != OK) + { + syslog(LOG_ERR, "ERROR: userled_lower_initialize() failed: %d\n", ret); + return ret; + } +#else + board_userled_initialize(); +#endif /* CONFIG_USERLED_LOWER */ +#endif /* CONFIG_USERLED */ + +#ifdef CONFIG_BUTTONS +#ifdef CONFIG_BUTTONS_LOWER + /* Register the BUTTON driver */ + + ret = btn_lower_initialize("/dev/buttons"); + if (ret != OK) + { + syslog(LOG_ERR, "ERROR: btn_lower_initialize() failed: %d\n", ret); + return ret; + } +#else + board_button_initialize(); +#endif /* CONFIG_BUTTONS_LOWER */ +#endif /* CONFIG_BUTTONS */ + +#ifdef CONFIG_STM32_IWDG + stm32_iwdginitialize("/dev/watchdog0", STM32_LSI_FREQUENCY); +#endif + +#ifdef CONFIG_PHOTON_WDG + + /* Start WDG kicker thread */ + + ret = photon_watchdog_initialize(); + if (ret != OK) + { + syslog(LOG_ERR, "Failed to start watchdog thread: %d\n", ret); + return ret; + } +#endif + +#ifdef CONFIG_PHOTON_WLAN + + /* Initialize wlan driver and hardware */ + + ret = photon_wlan_initialize(); + if (ret != OK) + { + syslog(LOG_ERR, "Failed to initialize wlan: %d\n", ret); + return ret; + } +#endif + + return ret; +} diff --git a/configs/photon/src/stm32_usb.c b/configs/photon/src/stm32_usb.c index 5dc24d5ed8..6f361a2c3f 100644 --- a/configs/photon/src/stm32_usb.c +++ b/configs/photon/src/stm32_usb.c @@ -43,18 +43,6 @@ #include #include -/************************************************************************************ - * Pre-processor Definitions - ************************************************************************************/ - -/************************************************************************************ - * Private Data - ************************************************************************************/ - -/************************************************************************************ - * Private Functions - ************************************************************************************/ - /************************************************************************************ * Public Functions ************************************************************************************/ diff --git a/configs/photon/src/stm32_leds.c b/configs/photon/src/stm32_userleds.c similarity index 97% rename from configs/photon/src/stm32_leds.c rename to configs/photon/src/stm32_userleds.c index 076df40ad6..8c7366f8a9 100644 --- a/configs/photon/src/stm32_leds.c +++ b/configs/photon/src/stm32_userleds.c @@ -1,5 +1,5 @@ /**************************************************************************** - * configs/photon/src/stm32_leds.c + * configs/photon/src/stm32_userleds.c * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Simon Piriou @@ -45,6 +45,8 @@ #include "stm32_gpio.h" +#ifndef CONFIG_ARCH_LEDS + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -80,3 +82,5 @@ void board_userled_all(uint8_t ledset) { stm32_gpiowrite(GPIO_LED1, !!(ledset & BOARD_LED1_BIT)); } + +#endif /* !CONFIG_ARCH_LEDS */ diff --git a/configs/photon/src/stm32_wdt.c b/configs/photon/src/stm32_wdt.c index 1df96707c6..8ea352925c 100644 --- a/configs/photon/src/stm32_wdt.c +++ b/configs/photon/src/stm32_wdt.c @@ -53,11 +53,6 @@ #include #include -/************************************************************************************ - * Pre-processor Definitions - ************************************************************************************/ -/* Configuration *******************************************************************/ - /************************************************************************************ * Public Functions ************************************************************************************/ diff --git a/configs/photon/src/stm32_wlan.c b/configs/photon/src/stm32_wlan.c index a0b19e4e0f..068561d63a 100644 --- a/configs/photon/src/stm32_wlan.c +++ b/configs/photon/src/stm32_wlan.c @@ -38,16 +38,19 @@ ****************************************************************************/ #include + #include -#include #include #include -#include "photon.h" + +#include #include "stm32_gpio.h" #include "stm32_sdio.h" +#include "photon.h" + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -105,25 +108,29 @@ int photon_wlan_initialize() struct sdio_dev_s *sdio_dev; /* Initialize sdio interface */ - _info("Initializing SDIO slot %d\n", SDIO_WLAN0_SLOTNO); + + wlinfo("Initializing SDIO slot %d\n", SDIO_WLAN0_SLOTNO); sdio_dev = sdio_initialize(SDIO_WLAN0_SLOTNO); if (!sdio_dev) { - _err("ERROR: Failed to initialize SDIO with slot %d\n", + wlerr("ERROR: Failed to initialize SDIO with slot %d\n", SDIO_WLAN0_SLOTNO); return ERROR; } /* Bind the SDIO interface to the bcmf driver */ + ret = bcmf_sdio_initialize(SDIO_WLAN0_MINOR, sdio_dev); if (ret != OK) { - _err("ERROR: Failed to bind SDIO to bcmf driver\n"); + wlerr("ERROR: Failed to bind SDIO to bcmf driver\n"); + /* FIXME deinitialize sdio device */ return ERROR; } + return OK; } diff --git a/configs/same70-xplained/src/sam_autoleds.c b/configs/same70-xplained/src/sam_autoleds.c index 64fd6b663c..51e5272a19 100644 --- a/configs/same70-xplained/src/sam_autoleds.c +++ b/configs/same70-xplained/src/sam_autoleds.c @@ -1,5 +1,5 @@ /**************************************************************************** - * configs/same70-xplained/include/sam_autoleds.c + * configs/same70-xplained/src/sam_autoleds.c * * Copyright (C) 2015 Gregory Nutt. All rights reserved. * Author: Gregory Nutt -- GitLab From dedc3c15d44232684089a7ae5313b3787c2b98d0 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 9 Apr 2017 09:19:25 -0600 Subject: [PATCH 396/990] Add support for NuttX controlled LEDS and for board_initialize. Separate initialize logic to stm32_bringup.c so that in initialization can occur either through board_initialize() or through board_app_initialize(). Same as with most other newer board configurations. --- configs/photon/include/board.h | 33 +++++ configs/photon/src/Makefile | 16 ++- configs/photon/src/photon.h | 15 ++ configs/photon/src/stm32_appinit.c | 83 ++--------- configs/photon/src/stm32_autoleds.c | 116 +++++++++++++++ configs/photon/src/stm32_boot.c | 28 ++++ configs/photon/src/stm32_bringup.c | 132 ++++++++++++++++++ configs/photon/src/stm32_usb.c | 12 -- .../src/{stm32_leds.c => stm32_userleds.c} | 6 +- configs/photon/src/stm32_wdt.c | 5 - configs/photon/src/stm32_wlan.c | 17 ++- configs/same70-xplained/src/sam_autoleds.c | 2 +- 12 files changed, 362 insertions(+), 103 deletions(-) create mode 100644 configs/photon/src/stm32_autoleds.c create mode 100644 configs/photon/src/stm32_bringup.c rename configs/photon/src/{stm32_leds.c => stm32_userleds.c} (97%) diff --git a/configs/photon/include/board.h b/configs/photon/include/board.h index 8c2fc655e3..96115ca57f 100644 --- a/configs/photon/include/board.h +++ b/configs/photon/include/board.h @@ -152,11 +152,44 @@ #undef BOARD_ENABLE_USBOTG_HSULPI /* LED definitions ******************************************************************/ +/* LEDs + * + * A single LED is available driven by PA13. + */ + +/* LED index values for use with board_userled() */ #define BOARD_LED1 0 #define BOARD_NLEDS 1 + +/* LED bits for use with board_userled_all() */ + #define BOARD_LED1_BIT (1 << BOARD_LED1) +/* These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is + * defined. In that case, the usage by the board port is defined in + * include/board.h and src/sam_autoleds.c. The LEDs are used to encode + * OS-related events as follows: + * + * ------------------- ---------------------------- ------ + * SYMBOL Meaning LED + * ------------------- ---------------------------- ------ */ + +#define LED_STARTED 0 /* NuttX has been started OFF */ +#define LED_HEAPALLOCATE 0 /* Heap has been allocated OFF */ +#define LED_IRQSENABLED 0 /* Interrupts enabled OFF */ +#define LED_STACKCREATED 1 /* Idle stack created ON */ +#define LED_INIRQ 2 /* In an interrupt N/C */ +#define LED_SIGNAL 2 /* In a signal handler N/C */ +#define LED_ASSERTION 2 /* An assertion failed N/C */ +#define LED_PANIC 3 /* The system has crashed FLASH */ +#undef LED_IDLE /* MCU is is sleep mode Not used */ + +/* Thus if LED is statically on, NuttX has successfully booted and is, + * apparently, running normally. If LED is flashing at approximately + * 2Hz, then a fatal error has been detected and the system has halted. + */ + /* Button definitions ***************************************************************/ #define BOARD_BUTTON1 0 diff --git a/configs/photon/src/Makefile b/configs/photon/src/Makefile index 5d9501759c..23f31b4489 100644 --- a/configs/photon/src/Makefile +++ b/configs/photon/src/Makefile @@ -35,18 +35,24 @@ -include $(TOPDIR)/Make.defs ASRCS = -CSRCS = stm32_boot.c +CSRCS = stm32_boot.c stm32_bringup.c ifeq ($(CONFIG_PHOTON_DFU_BOOTLOADER),y) CSRCS += dfu_signature.c endif +ifeq ($(CONFIG_LIB_BOARDCTL),y) +CSRCS += stm32_appinit.c +endif + ifeq ($(CONFIG_BUTTONS),y) CSRCS += stm32_buttons.c endif -ifeq ($(CONFIG_USERLED),y) -CSRCS += stm32_leds.c +ifeq ($(CONFIG_ARCH_LEDS),y) +CSRCS += stm32_autoleds.c +else +CSRCS += stm32_userleds.c endif ifeq ($(CONFIG_PHOTON_WDG),y) @@ -61,8 +67,4 @@ ifeq ($(CONFIG_STM32_OTGHS),y) CSRCS += stm32_usb.c endif -ifeq ($(CONFIG_NSH_LIBRARY),y) -CSRCS += stm32_appinit.c -endif - include $(TOPDIR)/configs/Board.mk diff --git a/configs/photon/src/photon.h b/configs/photon/src/photon.h index 4e0f312b6c..5628d1b69c 100644 --- a/configs/photon/src/photon.h +++ b/configs/photon/src/photon.h @@ -89,6 +89,21 @@ * Public Functions ****************************************************************************/ +/**************************************************************************** + * Name: stm32_bringup + * + * Description: + * Called either by board_intialize() if CONFIG_BOARD_INITIALIZE or by + * board_app_initialize if CONFIG_LIB_BOARDCTL is selected. This function + * initializes and configures all on-board features appropriate for the + * selected configuration. + * + ****************************************************************************/ + +#if defined(CONFIG_LIB_BOARDCTL) || defined(CONFIG_BOARD_INITIALIZE) +int stm32_bringup(void); +#endif + /**************************************************************************** * Name: photon_watchdog_initialize() * diff --git a/configs/photon/src/stm32_appinit.c b/configs/photon/src/stm32_appinit.c index dc2899789f..946dfbe8e2 100644 --- a/configs/photon/src/stm32_appinit.c +++ b/configs/photon/src/stm32_appinit.c @@ -2,7 +2,7 @@ * config/photon/src/stm32_appinit.c * * Copyright (C) 2017 Gregory Nutt. All rights reserved. - * Author: Simon Piriou + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -38,23 +38,14 @@ ****************************************************************************/ #include -#include -#include -#include +#include + +#include #include "photon.h" -#include "stm32_wdg.h" -#include -#include -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -#ifndef OK -# define OK 0 -#endif +#ifdef CONFIG_LIB_BOARDCTL /**************************************************************************** * Public Functions @@ -87,65 +78,13 @@ int board_app_initialize(uintptr_t arg) { - int ret = OK; - -#ifdef CONFIG_USERLED -#ifdef CONFIG_USERLED_LOWER - /* Register the LED driver */ - - ret = userled_lower_initialize("/dev/userleds"); - if (ret != OK) - { - syslog(LOG_ERR, "ERROR: userled_lower_initialize() failed: %d\n", ret); - return ret; - } -#else - board_userled_initialize(); -#endif /* CONFIG_USERLED_LOWER */ -#endif /* CONFIG_USERLED */ - -#ifdef CONFIG_BUTTONS -#ifdef CONFIG_BUTTONS_LOWER - /* Register the BUTTON driver */ +#ifndef CONFIG_BOARD_INITIALIZE + /* Perform board initialization */ - ret = btn_lower_initialize("/dev/buttons"); - if (ret != OK) - { - syslog(LOG_ERR, "ERROR: btn_lower_initialize() failed: %d\n", ret); - return ret; - } + return stm32_bringup(); #else - board_button_initialize(); -#endif /* CONFIG_BUTTONS_LOWER */ -#endif /* CONFIG_BUTTONS */ - -#ifdef CONFIG_STM32_IWDG - stm32_iwdginitialize("/dev/watchdog0", STM32_LSI_FREQUENCY); -#endif - -#ifdef CONFIG_PHOTON_WDG - - /* Start WDG kicker thread */ - - ret = photon_watchdog_initialize(); - if (ret != OK) - { - syslog(LOG_ERR, "Failed to start watchdog thread: %d\n", ret); - return ret; - } + return OK; #endif - -#ifdef CONFIG_PHOTON_WLAN - - /* Initialize wlan driver and hardware */ - - ret = photon_wlan_initialize(); - if (ret != OK) - { - syslog(LOG_ERR, "Failed to initialize wlan: %d\n", ret); - return ret; - } -#endif - - return ret; } + +#endif /* CONFIG_LIB_BOARDCTL */ diff --git a/configs/photon/src/stm32_autoleds.c b/configs/photon/src/stm32_autoleds.c new file mode 100644 index 0000000000..a490fa5432 --- /dev/null +++ b/configs/photon/src/stm32_autoleds.c @@ -0,0 +1,116 @@ +/**************************************************************************** + * configs/photon/src/stm32_autoleds.c + * + * 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. + * + ****************************************************************************/ + +/* LEDs + * + * A single LED is available driven by PA13. + * + * These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is + * defined. In that case, the usage by the board port is defined in + * include/board.h and src/sam_autoleds.c. The LEDs are used to encode + * OS-related events as follows: + * + * ------------------- ----------------------- ------ + * SYMBOL Meaning LED + * ------------------- ----------------------- ------ + * LED_STARTED NuttX has been started OFF + * LED_HEAPALLOCATE Heap has been allocated OFF + * LED_IRQSENABLED Interrupts enabled OFF + * LED_STACKCREATED Idle stack created ON + * LED_INIRQ In an interrupt N/C + * LED_SIGNAL In a signal handler N/C + * LED_ASSERTION An assertion failed N/C + * LED_PANIC The system has crashed FLASH + * + * Thus is LED is statically on, NuttX has successfully booted and is, + * apparently, running normally. If LED is flashing at approximately + * 2Hz, then a fatal error has been detected and the system has halted. + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include + +#include "stm32_gpio.h" +#include "photon.h" + +#ifdef CONFIG_ARCH_LEDS + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_autoled_initialize + ****************************************************************************/ + +void board_autoled_initialize(void) +{ + /* Configure Photon LED gpio as output */ + + stm32_configgpio(GPIO_LED1); +} + +/**************************************************************************** + * Name: board_autoled_on + ****************************************************************************/ + +void board_autoled_on(int led) +{ + if (led == 1 || led == 3) + { + stm32_gpiowrite(GPIO_LED1, true); + } +} + +/**************************************************************************** + * Name: board_autoled_off + ****************************************************************************/ + +void board_autoled_off(int led) +{ + if (led == 3) + { + stm32_gpiowrite(GPIO_LED1, false); + } +} + +#endif /* CONFIG_ARCH_LEDS */ diff --git a/configs/photon/src/stm32_boot.c b/configs/photon/src/stm32_boot.c index c9dfe28729..5adc28f31c 100644 --- a/configs/photon/src/stm32_boot.c +++ b/configs/photon/src/stm32_boot.c @@ -73,4 +73,32 @@ void stm32_boardinitialize(void) stm32_usbinitialize(); } #endif + +#ifdef CONFIG_ARCH_LEDS + /* Configure on-board LEDs if LED support has been selected. */ + + board_autoled_initialize(); +#endif +} + +/**************************************************************************** + * Name: board_initialize + * + * Description: + * If CONFIG_BOARD_INITIALIZE is selected, then an additional + * initialization call will be performed in the boot-up sequence to a + * function called board_initialize(). board_initialize() will be + * called immediately after up_intitialize() is called and just before the + * initial application is started. This additional initialization phase + * may be used, for example, to initialize board-specific device drivers. + * + ****************************************************************************/ + +#ifdef CONFIG_BOARD_INITIALIZE +void board_initialize(void) +{ + /* Perform board initialization */ + + (void)stm32_bringup(); } +#endif /* CONFIG_BOARD_INITIALIZE */ diff --git a/configs/photon/src/stm32_bringup.c b/configs/photon/src/stm32_bringup.c new file mode 100644 index 0000000000..d83e0493ed --- /dev/null +++ b/configs/photon/src/stm32_bringup.c @@ -0,0 +1,132 @@ +/**************************************************************************** + * config/photon/src/stm32_bringup.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Simon Piriou + * + * 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 "photon.h" +#include "stm32_wdg.h" + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_bringup + * + * Description: + * Called either by board_intialize() if CONFIG_BOARD_INITIALIZE or by + * board_app_initialize if CONFIG_LIB_BOARDCTL is selected. This function + * initializes and configures all on-board features appropriate for the + * selected configuration. + * + ****************************************************************************/ + +int stm32_bringup(void) +{ + int ret = OK; + +#ifdef CONFIG_USERLED +#ifdef CONFIG_USERLED_LOWER + /* Register the LED driver */ + + ret = userled_lower_initialize("/dev/userleds"); + if (ret != OK) + { + syslog(LOG_ERR, "ERROR: userled_lower_initialize() failed: %d\n", ret); + return ret; + } +#else + board_userled_initialize(); +#endif /* CONFIG_USERLED_LOWER */ +#endif /* CONFIG_USERLED */ + +#ifdef CONFIG_BUTTONS +#ifdef CONFIG_BUTTONS_LOWER + /* Register the BUTTON driver */ + + ret = btn_lower_initialize("/dev/buttons"); + if (ret != OK) + { + syslog(LOG_ERR, "ERROR: btn_lower_initialize() failed: %d\n", ret); + return ret; + } +#else + board_button_initialize(); +#endif /* CONFIG_BUTTONS_LOWER */ +#endif /* CONFIG_BUTTONS */ + +#ifdef CONFIG_STM32_IWDG + stm32_iwdginitialize("/dev/watchdog0", STM32_LSI_FREQUENCY); +#endif + +#ifdef CONFIG_PHOTON_WDG + + /* Start WDG kicker thread */ + + ret = photon_watchdog_initialize(); + if (ret != OK) + { + syslog(LOG_ERR, "Failed to start watchdog thread: %d\n", ret); + return ret; + } +#endif + +#ifdef CONFIG_PHOTON_WLAN + + /* Initialize wlan driver and hardware */ + + ret = photon_wlan_initialize(); + if (ret != OK) + { + syslog(LOG_ERR, "Failed to initialize wlan: %d\n", ret); + return ret; + } +#endif + + return ret; +} diff --git a/configs/photon/src/stm32_usb.c b/configs/photon/src/stm32_usb.c index 5dc24d5ed8..6f361a2c3f 100644 --- a/configs/photon/src/stm32_usb.c +++ b/configs/photon/src/stm32_usb.c @@ -43,18 +43,6 @@ #include #include -/************************************************************************************ - * Pre-processor Definitions - ************************************************************************************/ - -/************************************************************************************ - * Private Data - ************************************************************************************/ - -/************************************************************************************ - * Private Functions - ************************************************************************************/ - /************************************************************************************ * Public Functions ************************************************************************************/ diff --git a/configs/photon/src/stm32_leds.c b/configs/photon/src/stm32_userleds.c similarity index 97% rename from configs/photon/src/stm32_leds.c rename to configs/photon/src/stm32_userleds.c index 076df40ad6..8c7366f8a9 100644 --- a/configs/photon/src/stm32_leds.c +++ b/configs/photon/src/stm32_userleds.c @@ -1,5 +1,5 @@ /**************************************************************************** - * configs/photon/src/stm32_leds.c + * configs/photon/src/stm32_userleds.c * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Simon Piriou @@ -45,6 +45,8 @@ #include "stm32_gpio.h" +#ifndef CONFIG_ARCH_LEDS + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -80,3 +82,5 @@ void board_userled_all(uint8_t ledset) { stm32_gpiowrite(GPIO_LED1, !!(ledset & BOARD_LED1_BIT)); } + +#endif /* !CONFIG_ARCH_LEDS */ diff --git a/configs/photon/src/stm32_wdt.c b/configs/photon/src/stm32_wdt.c index 1df96707c6..8ea352925c 100644 --- a/configs/photon/src/stm32_wdt.c +++ b/configs/photon/src/stm32_wdt.c @@ -53,11 +53,6 @@ #include #include -/************************************************************************************ - * Pre-processor Definitions - ************************************************************************************/ -/* Configuration *******************************************************************/ - /************************************************************************************ * Public Functions ************************************************************************************/ diff --git a/configs/photon/src/stm32_wlan.c b/configs/photon/src/stm32_wlan.c index a0b19e4e0f..068561d63a 100644 --- a/configs/photon/src/stm32_wlan.c +++ b/configs/photon/src/stm32_wlan.c @@ -38,16 +38,19 @@ ****************************************************************************/ #include + #include -#include #include #include -#include "photon.h" + +#include #include "stm32_gpio.h" #include "stm32_sdio.h" +#include "photon.h" + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -105,25 +108,29 @@ int photon_wlan_initialize() struct sdio_dev_s *sdio_dev; /* Initialize sdio interface */ - _info("Initializing SDIO slot %d\n", SDIO_WLAN0_SLOTNO); + + wlinfo("Initializing SDIO slot %d\n", SDIO_WLAN0_SLOTNO); sdio_dev = sdio_initialize(SDIO_WLAN0_SLOTNO); if (!sdio_dev) { - _err("ERROR: Failed to initialize SDIO with slot %d\n", + wlerr("ERROR: Failed to initialize SDIO with slot %d\n", SDIO_WLAN0_SLOTNO); return ERROR; } /* Bind the SDIO interface to the bcmf driver */ + ret = bcmf_sdio_initialize(SDIO_WLAN0_MINOR, sdio_dev); if (ret != OK) { - _err("ERROR: Failed to bind SDIO to bcmf driver\n"); + wlerr("ERROR: Failed to bind SDIO to bcmf driver\n"); + /* FIXME deinitialize sdio device */ return ERROR; } + return OK; } diff --git a/configs/same70-xplained/src/sam_autoleds.c b/configs/same70-xplained/src/sam_autoleds.c index 64fd6b663c..51e5272a19 100644 --- a/configs/same70-xplained/src/sam_autoleds.c +++ b/configs/same70-xplained/src/sam_autoleds.c @@ -1,5 +1,5 @@ /**************************************************************************** - * configs/same70-xplained/include/sam_autoleds.c + * configs/same70-xplained/src/sam_autoleds.c * * Copyright (C) 2015 Gregory Nutt. All rights reserved. * Author: Gregory Nutt -- GitLab From f3b10eb073c06b2cd426ccc340d5fedb064d1cc6 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 9 Apr 2017 11:06:21 -0600 Subject: [PATCH 397/990] net procfs: Some long lines were being generated that cause buffer-related problems and corrupted output --- net/procfs/netdev_statistics.c | 40 +++++++++++++++++++++++++++++----- 1 file changed, 34 insertions(+), 6 deletions(-) diff --git a/net/procfs/netdev_statistics.c b/net/procfs/netdev_statistics.c index b2b83da801..f4927eab2f 100644 --- a/net/procfs/netdev_statistics.c +++ b/net/procfs/netdev_statistics.c @@ -62,7 +62,9 @@ static int netprocfs_linklayer(FAR struct netprocfs_file_s *netfile); static int netprocfs_ipaddresses(FAR struct netprocfs_file_s *netfile); - +#ifdef CONFIG_NET_IPv6 +static int netprocfs_dripaddress(FAR struct netprocfs_file_s *netfile); +#endif #ifdef CONFIG_NETDEV_STATISTICS static int netprocfs_rxstatistics_header(FAR struct netprocfs_file_s *netfile); static int netprocfs_rxstatistics(FAR struct netprocfs_file_s *netfile); @@ -83,6 +85,9 @@ static const linegen_t g_linegen[] = { netprocfs_linklayer, netprocfs_ipaddresses +#ifdef CONFIG_NET_IPv6 + , netprocfs_dripaddress +#endif #ifdef CONFIG_NETDEV_STATISTICS , netprocfs_rxstatistics_header, netprocfs_rxstatistics, @@ -292,7 +297,7 @@ static int netprocfs_ipaddresses(FAR struct netprocfs_file_s *netfile) addr.s_addr = dev->d_netmask; len += snprintf(&netfile->line[len], NET_LINELEN - len, - "Mask:%s\n", inet_ntoa(addr)); + "Mask:%s\n\n", inet_ntoa(addr)); #endif #ifdef CONFIG_NET_IPv6 @@ -307,19 +312,42 @@ static int netprocfs_ipaddresses(FAR struct netprocfs_file_s *netfile) len += snprintf(&netfile->line[len], NET_LINELEN - len, "\tinet6 addr:%s/%d\n", addrstr, preflen); } +#endif - /* REVISIT: Show the IPv6 default router address */ + return len; +} + +/**************************************************************************** + * Name: netprocfs_dripaddress + ****************************************************************************/ + +#ifdef CONFIG_NET_IPv6 +static int netprocfs_dripaddress(FAR struct netprocfs_file_s *netfile) +{ + FAR struct net_driver_s *dev; + char addrstr[INET6_ADDRSTRLEN]; + uint8_t preflen; + int len = 0; + + DEBUGASSERT(netfile != NULL && netfile->dev != NULL); + dev = netfile->dev; + + /* Convert the 128 network mask to a human friendly prefix length */ + + preflen = net_ipv6_mask2pref(dev->d_ipv6netmask); + + + /* Show the IPv6 default router address */ if (inet_ntop(AF_INET6, dev->d_ipv6draddr, addrstr, INET6_ADDRSTRLEN)) { len += snprintf(&netfile->line[len], NET_LINELEN - len, - "\tinet6 DRaddr:%s/%d\n", addrstr, preflen); + "\tinet6 DRaddr:%s/%d\n\n", addrstr, preflen); } -#endif - len += snprintf(&netfile->line[len], NET_LINELEN - len, "\n"); return len; } +#endif /**************************************************************************** * Name: netprocfs_rxstatistics_header -- GitLab From ebd2416f9d5d76b793ffcdbf56c47fce815b021a Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 9 Apr 2017 11:47:57 -0600 Subject: [PATCH 398/990] stm32 COMP: Logic in stm32_comp.h must be configured on CONFIG_STM32_COMP or otherwise it causes an error via #error on every platform without COMP support. --- arch/arm/src/stm32/stm32_comp.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/arch/arm/src/stm32/stm32_comp.h b/arch/arm/src/stm32/stm32_comp.h index 16a0ad6971..ab28cac186 100644 --- a/arch/arm/src/stm32/stm32_comp.h +++ b/arch/arm/src/stm32/stm32_comp.h @@ -44,6 +44,8 @@ #include "chip.h" +#ifdef CONFIG_STM32_COMP + #if defined(CONFIG_STM32_STM32F30XX) # error "COMP support for STM32F30XX not implemented yet" #elif defined(CONFIG_STM32_STM32F33XX) @@ -211,4 +213,5 @@ FAR struct comp_dev_s* stm32_compinitialize(int intf); #endif #endif /* __ASSEMBLY__ */ +#endif /* CONFIG_STM23_COMP */ #endif /* __ARCH_ARM_SRC_STM32_STM32_COMP_H */ -- GitLab From de2c368249f74d719917f002cf696dc0738fd60f Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 9 Apr 2017 12:13:47 -0600 Subject: [PATCH 399/990] Eliminate a warning about garbage at the end of the line. --- configs/tm4c123g-launchpad/src/tm4c_ssi.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/configs/tm4c123g-launchpad/src/tm4c_ssi.c b/configs/tm4c123g-launchpad/src/tm4c_ssi.c index 7b295f76aa..ce8ce7021c 100644 --- a/configs/tm4c123g-launchpad/src/tm4c_ssi.c +++ b/configs/tm4c123g-launchpad/src/tm4c_ssi.c @@ -59,7 +59,7 @@ * Pre-processor Definitions ************************************************************************************/ -#ifdef CONFIG_DEBUG_SPI_INFO) +#ifdef CONFIG_DEBUG_SPI_INFO # define ssi_dumpgpio(m) tiva_dumpgpio(SDCCS_GPIO, m) #else # define ssi_dumpgpio(m) -- GitLab From 5104eb530f4e48cccb65e71064a9fa8e73ec0a00 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 9 Apr 2017 13:46:27 -0600 Subject: [PATCH 400/990] Photon: Add logic to automatically mount the procfs file system on startup. Fix some LED-related configuration conflicts. --- configs/photon/src/stm32_bringup.c | 23 +++++++++++++++++++---- 1 file changed, 19 insertions(+), 4 deletions(-) diff --git a/configs/photon/src/stm32_bringup.c b/configs/photon/src/stm32_bringup.c index d83e0493ed..d55f3bc291 100644 --- a/configs/photon/src/stm32_bringup.c +++ b/configs/photon/src/stm32_bringup.c @@ -40,6 +40,7 @@ #include #include +#include #include #include @@ -70,7 +71,17 @@ int stm32_bringup(void) { int ret = OK; -#ifdef CONFIG_USERLED +#ifdef CONFIG_FS_PROCFS + /* Mount the procfs file system */ + + ret = mount(NULL, "/proc", "procfs", 0, NULL); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: Failed to mount procfs at /proc: %d\n", ret); + } +#endif + +#if defined(CONFIG_USERLED) && !defined(CONFIG_ARCH_LEDS) #ifdef CONFIG_USERLED_LOWER /* Register the LED driver */ @@ -81,9 +92,11 @@ int stm32_bringup(void) return ret; } #else + /* Enable USER LED support for some other purpose */ + board_userled_initialize(); #endif /* CONFIG_USERLED_LOWER */ -#endif /* CONFIG_USERLED */ +#endif /* CONFIG_USERLED && !CONFIG_ARCH_LEDS */ #ifdef CONFIG_BUTTONS #ifdef CONFIG_BUTTONS_LOWER @@ -96,16 +109,19 @@ int stm32_bringup(void) return ret; } #else + /* Enable BUTTON support for some other purpose */ + board_button_initialize(); #endif /* CONFIG_BUTTONS_LOWER */ #endif /* CONFIG_BUTTONS */ #ifdef CONFIG_STM32_IWDG + /* Initialize the watchdog timer */ + stm32_iwdginitialize("/dev/watchdog0", STM32_LSI_FREQUENCY); #endif #ifdef CONFIG_PHOTON_WDG - /* Start WDG kicker thread */ ret = photon_watchdog_initialize(); @@ -117,7 +133,6 @@ int stm32_bringup(void) #endif #ifdef CONFIG_PHOTON_WLAN - /* Initialize wlan driver and hardware */ ret = photon_wlan_initialize(); -- GitLab From 77f980e676c11c1cb2303d28d73f4c5f5dcfd682 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 9 Apr 2017 14:44:49 -0600 Subject: [PATCH 401/990] Buttons: Correct some comments left after last button-related change: 32- vs 8-bit bit set. --- configs/avr32dev1/src/avr32_buttons.c | 2 +- configs/clicker2-stm32/src/stm32_buttons.c | 2 +- configs/cloudctrl/src/stm32_buttons.c | 2 +- configs/dk-tm4c129x/src/tm4c_buttons.c | 2 +- configs/fire-stm32v2/src/stm32_buttons.c | 2 +- configs/freedom-k64f/src/k64_buttons.c | 2 +- configs/freedom-k66f/src/k66_buttons.c | 2 +- configs/hymini-stm32v/src/stm32_buttons.c | 2 +- configs/kwikstik-k40/src/k40_buttons.c | 2 +- configs/launchxl-tms57004/src/tms570_buttons.c | 2 +- configs/nucleo-144/src/stm32_buttons.c | 2 +- configs/nucleo-f303re/src/stm32_buttons.c | 2 +- configs/nucleo-f4x1re/src/stm32_buttons.c | 2 +- configs/nucleo-l476rg/src/stm32_buttons.c | 2 +- configs/olimex-efm32g880f128-stk/src/efm32_buttons.c | 2 +- configs/olimex-stm32-e407/src/stm32_buttons.c | 2 +- configs/olimex-stm32-h405/src/stm32_buttons.c | 2 +- configs/olimex-stm32-h407/src/stm32_buttons.c | 2 +- configs/olimex-stm32-p207/src/stm32_buttons.c | 2 +- configs/olimex-stm32-p407/src/stm32_buttons.c | 2 +- configs/olimexino-stm32/src/stm32_buttons.c | 4 ++-- configs/pcduino-a10/src/a1x_buttons.c | 2 +- configs/pic32mz-starterkit/src/pic32mz_buttons.c | 2 +- configs/sam3u-ek/src/sam_buttons.c | 2 +- configs/sam4e-ek/src/sam_buttons.c | 2 +- configs/sam4l-xplained/src/sam_buttons.c | 2 +- configs/sam4s-xplained-pro/src/sam_buttons.c | 2 +- configs/sam4s-xplained/src/sam_buttons.c | 2 +- configs/sama5d2-xult/src/sam_buttons.c | 2 +- configs/sama5d3-xplained/src/sam_buttons.c | 2 +- configs/sama5d3x-ek/src/sam_buttons.c | 2 +- configs/sama5d4-ek/src/sam_buttons.c | 2 +- configs/samd20-xplained/src/sam_buttons.c | 2 +- configs/samd21-xplained/src/sam_buttons.c | 2 +- configs/same70-xplained/src/sam_buttons.c | 2 +- configs/saml21-xplained/src/sam_buttons.c | 2 +- configs/samv71-xult/src/sam_buttons.c | 2 +- configs/shenzhou/src/stm32_buttons.c | 2 +- configs/spark/src/stm32_buttons.c | 2 +- configs/stm3210e-eval/src/stm32_buttons.c | 2 +- configs/stm3220g-eval/src/stm32_buttons.c | 2 +- configs/stm3240g-eval/src/stm32_buttons.c | 2 +- configs/stm32f103-minimum/src/stm32_buttons.c | 2 +- configs/stm32f3discovery/src/stm32_buttons.c | 2 +- configs/stm32f429i-disco/src/stm32_buttons.c | 2 +- configs/stm32f4discovery/src/stm32_buttons.c | 2 +- configs/stm32f746g-disco/src/stm32_buttons.c | 2 +- configs/stm32l476-mdk/src/stm32_buttons.c | 2 +- configs/stm32l476vg-disco/src/stm32_buttons.c | 2 +- configs/stm32ldiscovery/src/stm32_buttons.c | 2 +- configs/stm32vldiscovery/src/stm32_buttons.c | 2 +- configs/sure-pic32mx/src/pic32mx_buttons.c | 2 +- configs/tm4c123g-launchpad/src/tm4c_buttons.c | 2 +- configs/twr-k60n512/src/k60_buttons.c | 2 +- configs/ubw32/src/pic32_buttons.c | 2 +- configs/viewtool-stm32f107/src/stm32_buttons.c | 2 +- configs/zkit-arm-1769/src/lpc17_buttons.c | 2 +- include/nuttx/board.h | 2 +- 58 files changed, 59 insertions(+), 59 deletions(-) diff --git a/configs/avr32dev1/src/avr32_buttons.c b/configs/avr32dev1/src/avr32_buttons.c index 427a19d835..4514a800a5 100644 --- a/configs/avr32dev1/src/avr32_buttons.c +++ b/configs/avr32dev1/src/avr32_buttons.c @@ -120,7 +120,7 @@ void board_button_initialize(void) * Description: * After board_button_initialize() has been called, board_buttons() may be * called to collect the state of all buttons. board_buttons() returns an - * 8-bit bit set with each bit associated with a button. See the BUTTON* + * 32-bit bit set with each bit associated with a button. See the BUTTON* * definitions in the board.h header file for the meaning of each bit in * the returned value. * diff --git a/configs/clicker2-stm32/src/stm32_buttons.c b/configs/clicker2-stm32/src/stm32_buttons.c index 922007dcf6..00a571c817 100644 --- a/configs/clicker2-stm32/src/stm32_buttons.c +++ b/configs/clicker2-stm32/src/stm32_buttons.c @@ -110,7 +110,7 @@ uint32_t board_buttons(void) * handlers. * * After board_button_initialize() has been called, board_buttons() may be called to - * collect the state of all buttons. board_buttons() returns an 8-bit bit set + * collect the state of all buttons. board_buttons() returns an 32-bit bit set * with each bit associated with a button. See the BUTTON_*_BIT * definitions in board.h for the meaning of each bit. * diff --git a/configs/cloudctrl/src/stm32_buttons.c b/configs/cloudctrl/src/stm32_buttons.c index 6603ce1d07..574e6a1581 100644 --- a/configs/cloudctrl/src/stm32_buttons.c +++ b/configs/cloudctrl/src/stm32_buttons.c @@ -145,7 +145,7 @@ uint32_t board_buttons(void) * * After board_button_initialize() has been called, board_buttons() may be * called to collect the state of all buttons. board_buttons() returns an - * 8-bit bit set with each bit associated with a button. See the + * 32-bit bit set with each bit associated with a button. See the * BUTTON_*_BIT and JOYSTICK_*_BIT definitions in board.h for the meaning * of each bit. * diff --git a/configs/dk-tm4c129x/src/tm4c_buttons.c b/configs/dk-tm4c129x/src/tm4c_buttons.c index 7ef91a768b..7a85cda8e8 100644 --- a/configs/dk-tm4c129x/src/tm4c_buttons.c +++ b/configs/dk-tm4c129x/src/tm4c_buttons.c @@ -137,7 +137,7 @@ uint32_t board_buttons(void) * handlers. * * After board_button_initialize() has been called, board_buttons() may be called to - * collect the state of all buttons. board_buttons() returns an 8-bit bit set + * collect the state of all buttons. board_buttons() returns an 32-bit bit set * with each bit associated with a button. See the BUTTON_*_BIT and JOYSTICK_*_BIT * definitions in board.h for the meaning of each bit. * diff --git a/configs/fire-stm32v2/src/stm32_buttons.c b/configs/fire-stm32v2/src/stm32_buttons.c index 5c041230f9..d1fcbda183 100644 --- a/configs/fire-stm32v2/src/stm32_buttons.c +++ b/configs/fire-stm32v2/src/stm32_buttons.c @@ -121,7 +121,7 @@ uint32_t board_buttons(void) * * After board_button_initialize() has been called, board_buttons() may be * called to collect the state of all buttons. board_buttons() returns an - * 8-bit bit set with each bit associated with a button. See the + * 32-bit bit set with each bit associated with a button. See the * BUTTON_*_BIT and JOYSTICK_*_BIT definitions in board.h for the meaning * of each bit. * diff --git a/configs/freedom-k64f/src/k64_buttons.c b/configs/freedom-k64f/src/k64_buttons.c index d6f6ea44d6..53caa760b8 100644 --- a/configs/freedom-k64f/src/k64_buttons.c +++ b/configs/freedom-k64f/src/k64_buttons.c @@ -120,7 +120,7 @@ uint32_t board_buttons(void) * * After board_button_initialize() has been called, board_buttons() may * be called to collect the state of all buttons. board_buttons() returns - * an 8-bit bit set with each bit associated with a button. See the + * an 32-bit bit set with each bit associated with a button. See the * BUTTON_*_BIT and JOYSTICK_*_BIT definitions in board.h for the meaning * of each bit. * diff --git a/configs/freedom-k66f/src/k66_buttons.c b/configs/freedom-k66f/src/k66_buttons.c index ce63345c85..b186d40b41 100644 --- a/configs/freedom-k66f/src/k66_buttons.c +++ b/configs/freedom-k66f/src/k66_buttons.c @@ -124,7 +124,7 @@ uint32_t board_buttons(void) * * After board_button_initialize() has been called, board_buttons() may * be called to collect the state of all buttons. board_buttons() returns - * an 8-bit bit set with each bit associated with a button. See the + * an 32-bit bit set with each bit associated with a button. See the * BUTTON_*_BIT and JOYSTICK_*_BIT definitions in board.h for the meaning * of each bit. * diff --git a/configs/hymini-stm32v/src/stm32_buttons.c b/configs/hymini-stm32v/src/stm32_buttons.c index 757f159af7..4dac6fc8f4 100644 --- a/configs/hymini-stm32v/src/stm32_buttons.c +++ b/configs/hymini-stm32v/src/stm32_buttons.c @@ -120,7 +120,7 @@ uint32_t board_buttons(void) * * After board_button_initialize() has been called, board_buttons() may be * called to collect the state of all buttons. board_buttons() returns an - * 8-bit bit set with each bit associated with a button. See the + * 32-bit bit set with each bit associated with a button. See the * BUTTON_*_BIT and JOYSTICK_*_BIT definitions in board.h for the meaning * of each bit. * diff --git a/configs/kwikstik-k40/src/k40_buttons.c b/configs/kwikstik-k40/src/k40_buttons.c index 35f673d0ea..c66c2d858c 100644 --- a/configs/kwikstik-k40/src/k40_buttons.c +++ b/configs/kwikstik-k40/src/k40_buttons.c @@ -92,7 +92,7 @@ uint32_t board_buttons(void) * * After board_button_initialize() has been called, board_buttons() may be * called to collect the state of all buttons. board_buttons() returns an - * 8-bit bit set with each bit associated with a button. See the + * 32-bit bit set with each bit associated with a button. See the * BUTTON_*_BIT and JOYSTICK_*_BIT definitions in board.h for the meaning * of each bit. * diff --git a/configs/launchxl-tms57004/src/tms570_buttons.c b/configs/launchxl-tms57004/src/tms570_buttons.c index 3ee9e0eb31..d84de8f63a 100644 --- a/configs/launchxl-tms57004/src/tms570_buttons.c +++ b/configs/launchxl-tms57004/src/tms570_buttons.c @@ -154,7 +154,7 @@ void board_button_initialize(void) * Description: * After board_button_initialize() has been called, board_buttons() may be * called to collect the state of all buttons. board_buttons() returns an - * 8-bit bit set with each bit associated with a button. See the BUTTON* + * 32-bit bit set with each bit associated with a button. See the BUTTON* * definitions above for the meaning of each bit in the returned value. * ****************************************************************************/ diff --git a/configs/nucleo-144/src/stm32_buttons.c b/configs/nucleo-144/src/stm32_buttons.c index 5d47aa30bd..a8783b4e20 100644 --- a/configs/nucleo-144/src/stm32_buttons.c +++ b/configs/nucleo-144/src/stm32_buttons.c @@ -92,7 +92,7 @@ uint32_t board_buttons(void) * handlers. * * After board_button_initialize() has been called, board_buttons() may be called to - * collect the state of all buttons. board_buttons() returns an 8-bit bit set + * collect the state of all buttons. board_buttons() returns an 32-bit bit set * with each bit associated with a button. See the BUTTON_*_BIT * definitions in board.h for the meaning of each bit. * diff --git a/configs/nucleo-f303re/src/stm32_buttons.c b/configs/nucleo-f303re/src/stm32_buttons.c index 8ae6081f48..e40db64c28 100644 --- a/configs/nucleo-f303re/src/stm32_buttons.c +++ b/configs/nucleo-f303re/src/stm32_buttons.c @@ -83,7 +83,7 @@ void board_button_initialize(void) * Description: * After board_button_initialize() has been called, board_buttons() may be * called to collect the state of all buttons. board_buttons() returns an - * 8-bit unsigned integer with each bit associated with a button. See the + * 32-bit unsigned integer with each bit associated with a button. See the * BUTTON_*_BIT definitions in board.h for the meaning of each bit. * ****************************************************************************/ diff --git a/configs/nucleo-f4x1re/src/stm32_buttons.c b/configs/nucleo-f4x1re/src/stm32_buttons.c index 30fd294fc5..fe18b0b216 100644 --- a/configs/nucleo-f4x1re/src/stm32_buttons.c +++ b/configs/nucleo-f4x1re/src/stm32_buttons.c @@ -98,7 +98,7 @@ uint32_t board_buttons(void) * handlers. * * After board_button_initialize() has been called, board_buttons() may be called to - * collect the state of all buttons. board_buttons() returns an 8-bit bit set + * collect the state of all buttons. board_buttons() returns an 32-bit bit set * with each bit associated with a button. See the BUTTON_*_BIT * definitions in board.h for the meaning of each bit. * diff --git a/configs/nucleo-l476rg/src/stm32_buttons.c b/configs/nucleo-l476rg/src/stm32_buttons.c index 55f99e8192..456795c304 100644 --- a/configs/nucleo-l476rg/src/stm32_buttons.c +++ b/configs/nucleo-l476rg/src/stm32_buttons.c @@ -98,7 +98,7 @@ uint32_t board_buttons(void) * handlers. * * After board_button_initialize() has been called, board_buttons() may be called to - * collect the state of all buttons. board_buttons() returns an 8-bit bit set + * collect the state of all buttons. board_buttons() returns an 32-bit bit set * with each bit associated with a button. See the BUTTON_*_BIT * definitions in board.h for the meaning of each bit. * diff --git a/configs/olimex-efm32g880f128-stk/src/efm32_buttons.c b/configs/olimex-efm32g880f128-stk/src/efm32_buttons.c index 9637b12555..2863a332c1 100644 --- a/configs/olimex-efm32g880f128-stk/src/efm32_buttons.c +++ b/configs/olimex-efm32g880f128-stk/src/efm32_buttons.c @@ -120,7 +120,7 @@ void board_button_initialize(void) * Description: * After board_button_initialize() has been called, board_buttons() may be * called to collect the state of all buttons. board_buttons() returns an - * 8-bit bit set with each bit associated with a button. See the BUTTON* + * 32-bit bit set with each bit associated with a button. See the BUTTON* * definitions above for the meaning of each bit in the returned value. * ****************************************************************************/ diff --git a/configs/olimex-stm32-e407/src/stm32_buttons.c b/configs/olimex-stm32-e407/src/stm32_buttons.c index c57c54f42d..e52d296079 100644 --- a/configs/olimex-stm32-e407/src/stm32_buttons.c +++ b/configs/olimex-stm32-e407/src/stm32_buttons.c @@ -121,7 +121,7 @@ uint32_t board_buttons(void) * * After board_button_initialize() has been called, board_buttons() may be * called to collect the state of all buttons. board_buttons() returns an - * 8-bit bit set with each bit associated with a button. See the BUTTON_*_BIT + * 32-bit bit set with each bit associated with a button. See the BUTTON_*_BIT * definitions in board.h for the meaning of each bit. * * board_button_irq() may be called to register an interrupt handler that diff --git a/configs/olimex-stm32-h405/src/stm32_buttons.c b/configs/olimex-stm32-h405/src/stm32_buttons.c index e7bd98cf23..abcac85c80 100644 --- a/configs/olimex-stm32-h405/src/stm32_buttons.c +++ b/configs/olimex-stm32-h405/src/stm32_buttons.c @@ -120,7 +120,7 @@ uint32_t board_buttons(void) * handlers. * * After board_button_initialize() has been called, board_buttons() may be called to - * collect the state of all buttons. board_buttons() returns an 8-bit bit set + * collect the state of all buttons. board_buttons() returns an 32-bit bit set * with each bit associated with a button. See the BUTTON_*_BIT * definitions in board.h for the meaning of each bit. * diff --git a/configs/olimex-stm32-h407/src/stm32_buttons.c b/configs/olimex-stm32-h407/src/stm32_buttons.c index 976157d117..1155069e5e 100644 --- a/configs/olimex-stm32-h407/src/stm32_buttons.c +++ b/configs/olimex-stm32-h407/src/stm32_buttons.c @@ -121,7 +121,7 @@ uint32_t board_buttons(void) * * After board_button_initialize() has been called, board_buttons() may be * called to collect the state of all buttons. board_buttons() returns an - * 8-bit bit set with each bit associated with a button. See the BUTTON_*_BIT + * 32-bit bit set with each bit associated with a button. See the BUTTON_*_BIT * definitions in board.h for the meaning of each bit. * * board_button_irq() may be called to register an interrupt handler that diff --git a/configs/olimex-stm32-p207/src/stm32_buttons.c b/configs/olimex-stm32-p207/src/stm32_buttons.c index 9400b7456c..bde278810b 100644 --- a/configs/olimex-stm32-p207/src/stm32_buttons.c +++ b/configs/olimex-stm32-p207/src/stm32_buttons.c @@ -156,7 +156,7 @@ uint32_t board_buttons(void) * handlers. * * After board_button_initialize() has been called, board_buttons() may be called to - * collect the state of all buttons. board_buttons() returns an 8-bit bit set + * collect the state of all buttons. board_buttons() returns an 32-bit bit set * with each bit associated with a button. See the BUTTON_*_BIT * definitions in board.h for the meaning of each bit. * diff --git a/configs/olimex-stm32-p407/src/stm32_buttons.c b/configs/olimex-stm32-p407/src/stm32_buttons.c index 3d98c9eab7..a7bf89714d 100644 --- a/configs/olimex-stm32-p407/src/stm32_buttons.c +++ b/configs/olimex-stm32-p407/src/stm32_buttons.c @@ -158,7 +158,7 @@ uint32_t board_buttons(void) * handlers. * * After board_button_initialize() has been called, board_buttons() may be called to - * collect the state of all buttons. board_buttons() returns an 8-bit bit set + * collect the state of all buttons. board_buttons() returns an 32-bit bit set * with each bit associated with a button. See the BUTTON_*_BIT * definitions in board.h for the meaning of each bit. * diff --git a/configs/olimexino-stm32/src/stm32_buttons.c b/configs/olimexino-stm32/src/stm32_buttons.c index cc6ea25509..092383cade 100644 --- a/configs/olimexino-stm32/src/stm32_buttons.c +++ b/configs/olimexino-stm32/src/stm32_buttons.c @@ -63,7 +63,7 @@ * * After board_button_initialize() has been called, board_buttons() may be * called to collect the state of all buttons. board_buttons() returns an - * 8-bit bit set with each bit associated with a button. + * 32-bit bit set with each bit associated with a button. * See the BUTTON_*_BIT definitions in board.h for the meaning of each bit. * * board_button_irq() may be called to register an interrupt handler that @@ -97,7 +97,7 @@ void board_button_initialize(void) * * After board_button_initialize() has been called, board_buttons() may be * called to collect the state of all buttons. board_buttons() returns an - * 8-bit bit set with each bit associated with a button. + * 32-bit bit set with each bit associated with a button. * See the BUTTON_*_BIT definitions in board.h for the meaning of each bit. * ****************************************************************************/ diff --git a/configs/pcduino-a10/src/a1x_buttons.c b/configs/pcduino-a10/src/a1x_buttons.c index c7d1089135..4d4feccc0f 100644 --- a/configs/pcduino-a10/src/a1x_buttons.c +++ b/configs/pcduino-a10/src/a1x_buttons.c @@ -78,7 +78,7 @@ void board_button_initialize(void) * * Description: * After board_button_initialize() has been called, board_buttons() may be called to - * collect the state of all buttons. board_buttons() returns an 8-bit bit set + * collect the state of all buttons. board_buttons() returns an 32-bit bit set * with each bit associated with a button. See the BUTTON* definitions * above for the meaning of each bit in the returned value. * diff --git a/configs/pic32mz-starterkit/src/pic32mz_buttons.c b/configs/pic32mz-starterkit/src/pic32mz_buttons.c index 206be294c3..639844a953 100644 --- a/configs/pic32mz-starterkit/src/pic32mz_buttons.c +++ b/configs/pic32mz-starterkit/src/pic32mz_buttons.c @@ -140,7 +140,7 @@ uint32_t board_buttons(void) * * After board_button_initialize() has been called, board_buttons() may be * called to collect the state of all buttons. board_buttons() returns an - * 8-bit bit set with each bit associated with a button. See the + * 32-bit bit set with each bit associated with a button. See the * BUTTON_*_BIT definitions in board.h for the meaning of each bit. * * board_button_irq() may be called to register an interrupt handler that diff --git a/configs/sam3u-ek/src/sam_buttons.c b/configs/sam3u-ek/src/sam_buttons.c index 107c7036a6..19a00d97ec 100644 --- a/configs/sam3u-ek/src/sam_buttons.c +++ b/configs/sam3u-ek/src/sam_buttons.c @@ -127,7 +127,7 @@ void board_button_initialize(void) * * Description: * After board_button_initialize() has been called, board_buttons() may be called to collect - * the state of all buttons. board_buttons() returns an 8-bit bit set with each bit + * the state of all buttons. board_buttons() returns an 32-bit bit set with each bit * associated with a button. See the BUTTON* definitions above for the meaning of * each bit in the returned value. * diff --git a/configs/sam4e-ek/src/sam_buttons.c b/configs/sam4e-ek/src/sam_buttons.c index 53626290b7..ed3690782a 100644 --- a/configs/sam4e-ek/src/sam_buttons.c +++ b/configs/sam4e-ek/src/sam_buttons.c @@ -130,7 +130,7 @@ void board_button_initialize(void) * Description: * After board_button_initialize() has been called, board_buttons() may be * called to collect the state of all buttons. board_buttons() returns an - * 8-bit bit set with each bit associated with a button. See the BUTTON* + * 32-bit bit set with each bit associated with a button. See the BUTTON* * definitions above for the meaning of each bit in the returned value. * ****************************************************************************/ diff --git a/configs/sam4l-xplained/src/sam_buttons.c b/configs/sam4l-xplained/src/sam_buttons.c index 8d306bb311..78949a1cde 100644 --- a/configs/sam4l-xplained/src/sam_buttons.c +++ b/configs/sam4l-xplained/src/sam_buttons.c @@ -79,7 +79,7 @@ void board_button_initialize(void) * Description: * After board_button_initialize() has been called, board_buttons() may be * called to collect the state of all buttons. board_buttons() returns an - * 8-bit bit set with each bit associated with a button. See the BUTTON* + * 32-bit bit set with each bit associated with a button. See the BUTTON* * definitions above for the meaning of each bit in the returned value. * ****************************************************************************/ diff --git a/configs/sam4s-xplained-pro/src/sam_buttons.c b/configs/sam4s-xplained-pro/src/sam_buttons.c index 3b9b4fe359..f19f29894e 100644 --- a/configs/sam4s-xplained-pro/src/sam_buttons.c +++ b/configs/sam4s-xplained-pro/src/sam_buttons.c @@ -81,7 +81,7 @@ void board_button_initialize(void) * Description: * After board_button_initialize() has been called, board_buttons() may be * called to collect the state of all buttons. board_buttons() returns an - * 8-bit bit set with each bit associated with a button. See the BUTTON* + * 32-bit bit set with each bit associated with a button. See the BUTTON* * definitions above for the meaning of each bit in the returned value. * ****************************************************************************/ diff --git a/configs/sam4s-xplained/src/sam_buttons.c b/configs/sam4s-xplained/src/sam_buttons.c index 314e8e1818..5b979a1aa9 100644 --- a/configs/sam4s-xplained/src/sam_buttons.c +++ b/configs/sam4s-xplained/src/sam_buttons.c @@ -80,7 +80,7 @@ void board_button_initialize(void) * Description: * After board_button_initialize() has been called, board_buttons() may be * called to collect the state of all buttons. board_buttons() returns an - * 8-bit bit set with each bit associated with a button. See the BUTTON* + * 32-bit bit set with each bit associated with a button. See the BUTTON* * definitions above for the meaning of each bit in the returned value. * ****************************************************************************/ diff --git a/configs/sama5d2-xult/src/sam_buttons.c b/configs/sama5d2-xult/src/sam_buttons.c index 0939ddaa11..56548f3480 100644 --- a/configs/sama5d2-xult/src/sam_buttons.c +++ b/configs/sama5d2-xult/src/sam_buttons.c @@ -91,7 +91,7 @@ void board_button_initialize(void) * Description: * After board_button_initialize() has been called, board_buttons() may be * called to collect the state of all buttons. board_buttons() returns an - * 8-bit bit set with each bit associated with a button. See the BUTTON* + * 32-bit bit set with each bit associated with a button. See the BUTTON* * definitions above for the meaning of each bit in the returned value. * ****************************************************************************/ diff --git a/configs/sama5d3-xplained/src/sam_buttons.c b/configs/sama5d3-xplained/src/sam_buttons.c index 43794b374d..768b7b5db7 100644 --- a/configs/sama5d3-xplained/src/sam_buttons.c +++ b/configs/sama5d3-xplained/src/sam_buttons.c @@ -95,7 +95,7 @@ void board_button_initialize(void) * Description: * After board_button_initialize() has been called, board_buttons() may be * called to collect the state of all buttons. board_buttons() returns an - * 8-bit bit set with each bit associated with a button. See the BUTTON* + * 32-bit bit set with each bit associated with a button. See the BUTTON* * definitions above for the meaning of each bit in the returned value. * ****************************************************************************/ diff --git a/configs/sama5d3x-ek/src/sam_buttons.c b/configs/sama5d3x-ek/src/sam_buttons.c index dbdaa310f6..e76fcd2a0a 100644 --- a/configs/sama5d3x-ek/src/sam_buttons.c +++ b/configs/sama5d3x-ek/src/sam_buttons.c @@ -95,7 +95,7 @@ void board_button_initialize(void) * Description: * After board_button_initialize() has been called, board_buttons() may be * called to collect the state of all buttons. board_buttons() returns an - * 8-bit bit set with each bit associated with a button. See the BUTTON* + * 32-bit bit set with each bit associated with a button. See the BUTTON* * definitions above for the meaning of each bit in the returned value. * ****************************************************************************/ diff --git a/configs/sama5d4-ek/src/sam_buttons.c b/configs/sama5d4-ek/src/sam_buttons.c index 4ccae619f6..90dff73b16 100644 --- a/configs/sama5d4-ek/src/sam_buttons.c +++ b/configs/sama5d4-ek/src/sam_buttons.c @@ -91,7 +91,7 @@ void board_button_initialize(void) * Description: * After board_button_initialize() has been called, board_buttons() may be * called to collect the state of all buttons. board_buttons() returns an - * 8-bit bit set with each bit associated with a button. See the BUTTON* + * 32-bit bit set with each bit associated with a button. See the BUTTON* * definitions above for the meaning of each bit in the returned value. * ****************************************************************************/ diff --git a/configs/samd20-xplained/src/sam_buttons.c b/configs/samd20-xplained/src/sam_buttons.c index fc8f14bd0c..334bf8b403 100644 --- a/configs/samd20-xplained/src/sam_buttons.c +++ b/configs/samd20-xplained/src/sam_buttons.c @@ -79,7 +79,7 @@ void board_button_initialize(void) * * Description: * After board_button_initialize() has been called, board_buttons() may be called to collect - * the state of all buttons. board_buttons() returns an 8-bit bit set with each bit + * the state of all buttons. board_buttons() returns an 32-bit bit set with each bit * associated with a button. See the BUTTON* definitions above for the meaning of * each bit in the returned value. * diff --git a/configs/samd21-xplained/src/sam_buttons.c b/configs/samd21-xplained/src/sam_buttons.c index e4c31aa941..8e1789d1c9 100644 --- a/configs/samd21-xplained/src/sam_buttons.c +++ b/configs/samd21-xplained/src/sam_buttons.c @@ -79,7 +79,7 @@ void board_button_initialize(void) * * Description: * After board_button_initialize() has been called, board_buttons() may be called to collect - * the state of all buttons. board_buttons() returns an 8-bit bit set with each bit + * the state of all buttons. board_buttons() returns an 32-bit bit set with each bit * associated with a button. See the BUTTON* definitions above for the meaning of * each bit in the returned value. * diff --git a/configs/same70-xplained/src/sam_buttons.c b/configs/same70-xplained/src/sam_buttons.c index 7e66905c8a..ab7dfeb8cf 100644 --- a/configs/same70-xplained/src/sam_buttons.c +++ b/configs/same70-xplained/src/sam_buttons.c @@ -142,7 +142,7 @@ void board_button_initialize(void) * Description: * After board_button_initialize() has been called, board_buttons() may be * called to collect the state of all buttons. board_buttons() returns an - * 8-bit bit set with each bit associated with a button. See the BUTTON* + * 32-bit bit set with each bit associated with a button. See the BUTTON* * definitions above for the meaning of each bit in the returned value. * ****************************************************************************/ diff --git a/configs/saml21-xplained/src/sam_buttons.c b/configs/saml21-xplained/src/sam_buttons.c index 909fa58a7a..407b24bb4d 100644 --- a/configs/saml21-xplained/src/sam_buttons.c +++ b/configs/saml21-xplained/src/sam_buttons.c @@ -79,7 +79,7 @@ void board_button_initialize(void) * * Description: * After board_button_initialize() has been called, board_buttons() may be called to collect - * the state of all buttons. board_buttons() returns an 8-bit bit set with each bit + * the state of all buttons. board_buttons() returns an 32-bit bit set with each bit * associated with a button. See the BUTTON* definitions above for the meaning of * each bit in the returned value. * diff --git a/configs/samv71-xult/src/sam_buttons.c b/configs/samv71-xult/src/sam_buttons.c index 1a06c84034..adcd280d73 100644 --- a/configs/samv71-xult/src/sam_buttons.c +++ b/configs/samv71-xult/src/sam_buttons.c @@ -158,7 +158,7 @@ void board_button_initialize(void) * Description: * After board_button_initialize() has been called, board_buttons() may be * called to collect the state of all buttons. board_buttons() returns an - * 8-bit bit set with each bit associated with a button. See the BUTTON* + * 32-bit bit set with each bit associated with a button. See the BUTTON* * definitions above for the meaning of each bit in the returned value. * ****************************************************************************/ diff --git a/configs/shenzhou/src/stm32_buttons.c b/configs/shenzhou/src/stm32_buttons.c index 139d517956..57053359b8 100644 --- a/configs/shenzhou/src/stm32_buttons.c +++ b/configs/shenzhou/src/stm32_buttons.c @@ -136,7 +136,7 @@ uint32_t board_buttons(void) * handlers. * * After board_button_initialize() has been called, board_buttons() may be called to - * collect the state of all buttons. board_buttons() returns an 8-bit bit set + * collect the state of all buttons. board_buttons() returns an 32-bit bit set * with each bit associated with a button. See the BUTTON_*_BIT and JOYSTICK_*_BIT * definitions in board.h for the meaning of each bit. * diff --git a/configs/spark/src/stm32_buttons.c b/configs/spark/src/stm32_buttons.c index 3ab2f3c854..3534eeeb6a 100644 --- a/configs/spark/src/stm32_buttons.c +++ b/configs/spark/src/stm32_buttons.c @@ -95,7 +95,7 @@ uint32_t board_buttons(void) * handlers. * * After board_button_initialize() has been called, board_buttons() may be called to - * collect the state of all buttons. board_buttons() returns an 8-bit bit set + * collect the state of all buttons. board_buttons() returns an 32-bit bit set * with each bit associated with a button. See the BUTTON_*_BIT * definitions in board.h for the meaning of each bit. * diff --git a/configs/stm3210e-eval/src/stm32_buttons.c b/configs/stm3210e-eval/src/stm32_buttons.c index b9f4822814..f6a8575881 100644 --- a/configs/stm3210e-eval/src/stm32_buttons.c +++ b/configs/stm3210e-eval/src/stm32_buttons.c @@ -148,7 +148,7 @@ uint32_t board_buttons(void) * handlers. * * After board_button_initialize() has been called, board_buttons() may be called to - * collect the state of all buttons. board_buttons() returns an 8-bit bit set + * collect the state of all buttons. board_buttons() returns an 32-bit bit set * with each bit associated with a button. See the BUTTON_*_BIT and JOYSTICK_*_BIT * definitions in board.h for the meaning of each bit. * diff --git a/configs/stm3220g-eval/src/stm32_buttons.c b/configs/stm3220g-eval/src/stm32_buttons.c index 669b460b03..9bec8f3c10 100644 --- a/configs/stm3220g-eval/src/stm32_buttons.c +++ b/configs/stm3220g-eval/src/stm32_buttons.c @@ -136,7 +136,7 @@ uint32_t board_buttons(void) * handlers. * * After board_button_initialize() has been called, board_buttons() may be called to - * collect the state of all buttons. board_buttons() returns an 8-bit bit set + * collect the state of all buttons. board_buttons() returns an 32-bit bit set * with each bit associated with a button. See the BUTTON_*_BIT * definitions in board.h for the meaning of each bit. * diff --git a/configs/stm3240g-eval/src/stm32_buttons.c b/configs/stm3240g-eval/src/stm32_buttons.c index 4682ffb1a9..c543a0b6ac 100644 --- a/configs/stm3240g-eval/src/stm32_buttons.c +++ b/configs/stm3240g-eval/src/stm32_buttons.c @@ -144,7 +144,7 @@ uint32_t board_buttons(void) * handlers. * * After board_button_initialize() has been called, board_buttons() may be called to - * collect the state of all buttons. board_buttons() returns an 8-bit bit set + * collect the state of all buttons. board_buttons() returns an 32-bit bit set * with each bit associated with a button. See the BUTTON_*_BIT * definitions in board.h for the meaning of each bit. * diff --git a/configs/stm32f103-minimum/src/stm32_buttons.c b/configs/stm32f103-minimum/src/stm32_buttons.c index 6891b3db0a..154f24225e 100644 --- a/configs/stm32f103-minimum/src/stm32_buttons.c +++ b/configs/stm32f103-minimum/src/stm32_buttons.c @@ -140,7 +140,7 @@ uint32_t board_buttons(void) * * After board_button_initialize() has been called, board_buttons() may be * called to collect the state of all buttons. board_buttons() returns - * an 8-bit bit set with each bit associated with a button. See the + * an 32-bit bit set with each bit associated with a button. See the * BUTTON_*_BIT definitions in board.h for the meaning of each bit. * * board_button_irq() may be called to register an interrupt handler that diff --git a/configs/stm32f3discovery/src/stm32_buttons.c b/configs/stm32f3discovery/src/stm32_buttons.c index a0ecada6a5..a17912bdbd 100644 --- a/configs/stm32f3discovery/src/stm32_buttons.c +++ b/configs/stm32f3discovery/src/stm32_buttons.c @@ -131,7 +131,7 @@ uint32_t board_buttons(void) * handlers. * * After board_button_initialize() has been called, board_buttons() may be called to - * collect the state of all buttons. board_buttons() returns an 8-bit bit set + * collect the state of all buttons. board_buttons() returns an 32-bit bit set * with each bit associated with a button. See the BUTTON_*_BIT * definitions in board.h for the meaning of each bit. * diff --git a/configs/stm32f429i-disco/src/stm32_buttons.c b/configs/stm32f429i-disco/src/stm32_buttons.c index d2e9ba2e09..c5ce618d0c 100644 --- a/configs/stm32f429i-disco/src/stm32_buttons.c +++ b/configs/stm32f429i-disco/src/stm32_buttons.c @@ -131,7 +131,7 @@ uint32_t board_buttons(void) * handlers. * * After board_button_initialize() has been called, board_buttons() may be called to - * collect the state of all buttons. board_buttons() returns an 8-bit bit set + * collect the state of all buttons. board_buttons() returns an 32-bit bit set * with each bit associated with a button. See the BUTTON_*_BIT * definitions in board.h for the meaning of each bit. * diff --git a/configs/stm32f4discovery/src/stm32_buttons.c b/configs/stm32f4discovery/src/stm32_buttons.c index 2d86ea80cf..2b805075e0 100644 --- a/configs/stm32f4discovery/src/stm32_buttons.c +++ b/configs/stm32f4discovery/src/stm32_buttons.c @@ -131,7 +131,7 @@ uint32_t board_buttons(void) * handlers. * * After board_button_initialize() has been called, board_buttons() may be called to - * collect the state of all buttons. board_buttons() returns an 8-bit bit set + * collect the state of all buttons. board_buttons() returns an 32-bit bit set * with each bit associated with a button. See the BUTTON_*_BIT * definitions in board.h for the meaning of each bit. * diff --git a/configs/stm32f746g-disco/src/stm32_buttons.c b/configs/stm32f746g-disco/src/stm32_buttons.c index b8a46a8dac..42faf1d90f 100644 --- a/configs/stm32f746g-disco/src/stm32_buttons.c +++ b/configs/stm32f746g-disco/src/stm32_buttons.c @@ -92,7 +92,7 @@ uint32_t board_buttons(void) * handlers. * * After board_button_initialize() has been called, board_buttons() may be called to - * collect the state of all buttons. board_buttons() returns an 8-bit bit set + * collect the state of all buttons. board_buttons() returns an 32-bit bit set * with each bit associated with a button. See the BUTTON_*_BIT * definitions in board.h for the meaning of each bit. * diff --git a/configs/stm32l476-mdk/src/stm32_buttons.c b/configs/stm32l476-mdk/src/stm32_buttons.c index 7debe3c597..58e9079153 100644 --- a/configs/stm32l476-mdk/src/stm32_buttons.c +++ b/configs/stm32l476-mdk/src/stm32_buttons.c @@ -138,7 +138,7 @@ uint32_t board_buttons(void) * * After board_button_initialize() has been called, board_buttons() may be * called to collect the state of all buttons. board_buttons() returns an - * 8-bit bit set with each bit associated with a button. See the + * 32-bit bit set with each bit associated with a button. See the * BUTTON_*_BIT definitions in board.h for the meaning of each bit. * * board_button_irq() may be called to register an interrupt handler that diff --git a/configs/stm32l476vg-disco/src/stm32_buttons.c b/configs/stm32l476vg-disco/src/stm32_buttons.c index f3c4d50c9c..18b984d2c1 100644 --- a/configs/stm32l476vg-disco/src/stm32_buttons.c +++ b/configs/stm32l476vg-disco/src/stm32_buttons.c @@ -306,7 +306,7 @@ uint32_t board_buttons(void) * handlers. * * After board_button_initialize() has been called, board_buttons() may be called to - * collect the state of all buttons. board_buttons() returns an 8-bit bit set + * collect the state of all buttons. board_buttons() returns an 32-bit bit set * with each bit associated with a button. See the BUTTON_*_BIT * definitions in board.h for the meaning of each bit. * diff --git a/configs/stm32ldiscovery/src/stm32_buttons.c b/configs/stm32ldiscovery/src/stm32_buttons.c index f766017d15..d985c9f4d3 100644 --- a/configs/stm32ldiscovery/src/stm32_buttons.c +++ b/configs/stm32ldiscovery/src/stm32_buttons.c @@ -131,7 +131,7 @@ uint32_t board_buttons(void) * handlers. * * After board_button_initialize() has been called, board_buttons() may be called to - * collect the state of all buttons. board_buttons() returns an 8-bit bit set + * collect the state of all buttons. board_buttons() returns an 32-bit bit set * with each bit associated with a button. See the BUTTON_*_BIT * definitions in board.h for the meaning of each bit. * diff --git a/configs/stm32vldiscovery/src/stm32_buttons.c b/configs/stm32vldiscovery/src/stm32_buttons.c index 9784b19d77..95d9f1590c 100644 --- a/configs/stm32vldiscovery/src/stm32_buttons.c +++ b/configs/stm32vldiscovery/src/stm32_buttons.c @@ -94,7 +94,7 @@ uint32_t board_buttons(void) * handlers. * * After board_button_initialize() has been called, board_buttons() may be called to - * collect the state of all buttons. board_buttons() returns an 8-bit bit set + * collect the state of all buttons. board_buttons() returns an 32-bit bit set * with each bit associated with a button. See the BUTTON_*_BIT and JOYSTICK_*_BIT * definitions in board.h for the meaning of each bit. * diff --git a/configs/sure-pic32mx/src/pic32mx_buttons.c b/configs/sure-pic32mx/src/pic32mx_buttons.c index bf5ca03429..e2ee0ac219 100644 --- a/configs/sure-pic32mx/src/pic32mx_buttons.c +++ b/configs/sure-pic32mx/src/pic32mx_buttons.c @@ -185,7 +185,7 @@ uint32_t board_buttons(void) * handlers. * * After board_button_initialize() has been called, board_buttons() may be called to - * collect the state of all buttons. board_buttons() returns an 8-bit bit set + * collect the state of all buttons. board_buttons() returns an 32-bit bit set * with each bit associated with a button. See the BUTTON_*_BIT and JOYSTICK_*_BIT * definitions in board.h for the meaning of each bit. * diff --git a/configs/tm4c123g-launchpad/src/tm4c_buttons.c b/configs/tm4c123g-launchpad/src/tm4c_buttons.c index 96370046f4..24eb21ea04 100644 --- a/configs/tm4c123g-launchpad/src/tm4c_buttons.c +++ b/configs/tm4c123g-launchpad/src/tm4c_buttons.c @@ -113,7 +113,7 @@ void board_button_initialize(void) * Description: * After board_button_initialize() has been called, board_buttons() may be * called to collect the state of all buttons. board_buttons() returns an - * 8-bit bit set with each bit associated with a button. See the BUTTON* + * 32-bit bit set with each bit associated with a button. See the BUTTON* * definitions above for the meaning of each bit in the returned value. * ****************************************************************************/ diff --git a/configs/twr-k60n512/src/k60_buttons.c b/configs/twr-k60n512/src/k60_buttons.c index d9206f2c71..99bee75910 100644 --- a/configs/twr-k60n512/src/k60_buttons.c +++ b/configs/twr-k60n512/src/k60_buttons.c @@ -121,7 +121,7 @@ uint32_t board_buttons(void) * handlers. * * After board_button_initialize() has been called, board_buttons() may be called to - * collect the state of all buttons. board_buttons() returns an 8-bit bit set + * collect the state of all buttons. board_buttons() returns an 32-bit bit set * with each bit associated with a button. See the BUTTON_*_BIT and JOYSTICK_*_BIT * definitions in board.h for the meaning of each bit. * diff --git a/configs/ubw32/src/pic32_buttons.c b/configs/ubw32/src/pic32_buttons.c index 69b1deeb44..469167f137 100644 --- a/configs/ubw32/src/pic32_buttons.c +++ b/configs/ubw32/src/pic32_buttons.c @@ -160,7 +160,7 @@ uint32_t board_buttons(void) * handlers. * * After board_button_initialize() has been called, board_buttons() may be called to - * collect the state of all buttons. board_buttons() returns an 8-bit bit set + * collect the state of all buttons. board_buttons() returns an 32-bit bit set * with each bit associated with a button. See the BUTTON_*_BIT definitions in * board.h for the meaning of each bit. * diff --git a/configs/viewtool-stm32f107/src/stm32_buttons.c b/configs/viewtool-stm32f107/src/stm32_buttons.c index 9e39a2d72c..086a321755 100644 --- a/configs/viewtool-stm32f107/src/stm32_buttons.c +++ b/configs/viewtool-stm32f107/src/stm32_buttons.c @@ -132,7 +132,7 @@ uint32_t board_buttons(void) * handlers. * * After board_button_initialize() has been called, board_buttons() may be called to - * collect the state of all buttons. board_buttons() returns an 8-bit bit set + * collect the state of all buttons. board_buttons() returns an 32-bit bit set * with each bit associated with a button. See the BUTTON_*_BIT and JOYSTICK_*_BIT * definitions in board.h for the meaning of each bit. * diff --git a/configs/zkit-arm-1769/src/lpc17_buttons.c b/configs/zkit-arm-1769/src/lpc17_buttons.c index ffa7646686..e93f27734f 100644 --- a/configs/zkit-arm-1769/src/lpc17_buttons.c +++ b/configs/zkit-arm-1769/src/lpc17_buttons.c @@ -142,7 +142,7 @@ uint32_t board_buttons(void) * handlers. * * After board_button_initialize() has been called, board_buttons() may be called to - * collect the state of all buttons. board_buttons() returns an 8-bit bit set + * collect the state of all buttons. board_buttons() returns an 32-bit bit set * with each bit associated with a button. See the BUTTON_*_BIT and JOYSTICK_*_BIT * definitions in board.h for the meaning of each bit. * diff --git a/include/nuttx/board.h b/include/nuttx/board.h index 310a973c34..c00d09ce3c 100644 --- a/include/nuttx/board.h +++ b/include/nuttx/board.h @@ -581,7 +581,7 @@ void board_button_initialize(void); * Description: * After board_button_initialize() has been called, board_buttons() may be * called to collect the state of all buttons. board_buttons() returns an - * 8-bit bit set with each bit associated with a button. A bit set to + * 32-bit bit set with each bit associated with a button. A bit set to * "1" means that the button is depressed; a bit set to "0" means that * the button is released. The correspondence of the each button bit * and physical buttons is board-specific. -- GitLab From 755e9312b51f8a03f38d9287e1e2bfbae285cfbe Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Mon, 10 Apr 2017 07:18:16 -0600 Subject: [PATCH 402/990] pthread: use cancel cleanup handlers in rwlock --- libc/pthread/pthread_rwlock_rdlock.c | 17 ++++++++++++++++- libc/pthread/pthread_rwlock_wrlock.c | 27 +++++++++++++++++++++++---- 2 files changed, 39 insertions(+), 5 deletions(-) diff --git a/libc/pthread/pthread_rwlock_rdlock.c b/libc/pthread/pthread_rwlock_rdlock.c index 9fd461a758..19979f79bb 100644 --- a/libc/pthread/pthread_rwlock_rdlock.c +++ b/libc/pthread/pthread_rwlock_rdlock.c @@ -1,5 +1,5 @@ /**************************************************************************** - * libc/pthread/pthread_rwlockread.c + * libc/pthread/pthread_rwlock_rdlock.c * * Copyright (C) 2017 Mark Schulte. All rights reserved. * Author: Mark Schulte @@ -50,6 +50,15 @@ * Private Functions ****************************************************************************/ +#ifdef CONFIG_PTHREAD_CLEANUP +static void rdlock_cleanup(FAR void *arg) +{ + FAR pthread_rwlock_t *rw_lock = (FAR pthread_rwlock_t *)arg; + + pthread_mutex_unlock(&rw_lock->lock); +} +#endif + static int tryrdlock(FAR pthread_rwlock_t *rw_lock) { int err; @@ -116,6 +125,9 @@ int pthread_rwlock_timedrdlock(FAR pthread_rwlock_t *rw_lock, return err; } +#ifdef CONFIG_PTHREAD_CLEANUP + pthread_cleanup_push(&rdlock_cleanup, rw_lock); +#endif while ((err = tryrdlock(rw_lock)) == EBUSY) { if (ts != NULL) @@ -132,6 +144,9 @@ int pthread_rwlock_timedrdlock(FAR pthread_rwlock_t *rw_lock, break; } } +#ifdef CONFIG_PTHREAD_CLEANUP + pthread_cleanup_pop(0); +#endif pthread_mutex_unlock(&rw_lock->lock); return err; diff --git a/libc/pthread/pthread_rwlock_wrlock.c b/libc/pthread/pthread_rwlock_wrlock.c index ecda4cb25b..fcda35cb4f 100644 --- a/libc/pthread/pthread_rwlock_wrlock.c +++ b/libc/pthread/pthread_rwlock_wrlock.c @@ -1,5 +1,5 @@ /**************************************************************************** - * libc/pthread/pthread_rwlockwrite.c + * libc/pthread/pthread_rwlock_wrlock.c * * Copyright (C) 2017 Mark Schulte. All rights reserved. * Author: Mark Schulte @@ -46,15 +46,29 @@ #include +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +#ifdef CONFIG_PTHREAD_CLEANUP +static void wrlock_cleanup(FAR void *arg) +{ + FAR pthread_rwlock_t *rw_lock = (FAR pthread_rwlock_t *)arg; + + rw_lock->num_writers--; + pthread_mutex_unlock(&rw_lock->lock); +} +#endif + /**************************************************************************** * Public Functions ****************************************************************************/ /**************************************************************************** - * Name: pthread_rwlock_rdlock + * Name: pthread_rwlock_wrlock * * Description: - * Locks a read/write lock for reading + * Locks a read/write lock for writing * * Parameters: * None @@ -106,6 +120,9 @@ int pthread_rwlock_timedwrlock(FAR pthread_rwlock_t *rw_lock, rw_lock->num_writers++; +#ifdef CONFIG_PTHREAD_CLEANUP + pthread_cleanup_push(&wrlock_cleanup, rw_lock); +#endif while (rw_lock->write_in_progress || rw_lock->num_readers > 0) { if (ts != NULL) @@ -122,12 +139,14 @@ int pthread_rwlock_timedwrlock(FAR pthread_rwlock_t *rw_lock, break; } } +#ifdef CONFIG_PTHREAD_CLEANUP + pthread_cleanup_pop(0); +#endif if (err == 0) { rw_lock->write_in_progress = true; } - else { /* In case of error, notify any blocked readers. */ -- GitLab From b51b72b2dba6dc7350cddfa40ca93203ebbc6932 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 10 Apr 2017 08:11:16 -0600 Subject: [PATCH 403/990] pthreads: Re-order some operations so that mutexes are placed in the inconsistent state BEFORE the clean-up callbacks are called. --- sched/Kconfig | 4 ++-- sched/pthread/pthread_cancel.c | 12 ++++++------ sched/pthread/pthread_exit.c | 12 ++++++------ sched/pthread/pthread_mutexconsistent.c | 4 +++- 4 files changed, 17 insertions(+), 15 deletions(-) diff --git a/sched/Kconfig b/sched/Kconfig index 50613fb44d..6cefe0e121 100644 --- a/sched/Kconfig +++ b/sched/Kconfig @@ -601,8 +601,6 @@ config PTHREAD_CLEANUP_STACKSIZE 8 for a CPU with 32-bit addressing and 4 for a CPU with 16-bit addressing. -endmenu # Pthread Options - config CANCELLATION_POINTS bool "Cancellation points" default n @@ -611,6 +609,8 @@ config CANCELLATION_POINTS cancellation points will also used with the () task_delete() API even if pthreads are not enabled. +endmenu # Pthread Options + menu "Performance Monitoring" config SCHED_CPULOAD diff --git a/sched/pthread/pthread_cancel.c b/sched/pthread/pthread_cancel.c index e2cad60ebb..f68d272e03 100644 --- a/sched/pthread/pthread_cancel.c +++ b/sched/pthread/pthread_cancel.c @@ -145,6 +145,12 @@ int pthread_cancel(pthread_t thread) pthread_exit(PTHREAD_CANCELED); } +#ifndef CONFIG_PTHREAD_MUTEX_UNSAFE + /* Recover any mutexes still held by the canceled thread */ + + pthread_mutex_inconsistent(tcb); +#endif + #ifdef CONFIG_PTHREAD_CLEANUP /* Perform any stack pthread clean-up callbacks. * @@ -162,12 +168,6 @@ int pthread_cancel(pthread_t thread) (void)pthread_completejoin((pid_t)thread, PTHREAD_CANCELED); -#ifndef CONFIG_PTHREAD_MUTEX_UNSAFE - /* Recover any mutexes still held by the canceled thread */ - - pthread_mutex_inconsistent(tcb); -#endif - /* Then let task_terminate do the real work */ return task_terminate((pid_t)thread, false); diff --git a/sched/pthread/pthread_exit.c b/sched/pthread/pthread_exit.c index bcc8e79c85..4929db94cb 100644 --- a/sched/pthread/pthread_exit.c +++ b/sched/pthread/pthread_exit.c @@ -105,6 +105,12 @@ void pthread_exit(FAR void *exit_value) tcb->cpcount = 0; #endif +#ifndef CONFIG_PTHREAD_MUTEX_UNSAFE + /* Recover any mutexes still held by the canceled thread */ + + pthread_mutex_inconsistent((FAR struct pthread_tcb_s *)tcb); +#endif + #ifdef CONFIG_PTHREAD_CLEANUP /* Perform any stack pthread clean-up callbacks */ @@ -123,12 +129,6 @@ void pthread_exit(FAR void *exit_value) exit(EXIT_FAILURE); } -#ifndef CONFIG_PTHREAD_MUTEX_UNSAFE - /* Recover any mutexes still held by the canceled thread */ - - pthread_mutex_inconsistent((FAR struct pthread_tcb_s *)tcb); -#endif - /* Perform common task termination logic. This will get called again later * through logic kicked off by _exit(). However, we need to call it before * calling _exit() in order certain operations if this is the last thread diff --git a/sched/pthread/pthread_mutexconsistent.c b/sched/pthread/pthread_mutexconsistent.c index 77d9bede3e..e374083021 100644 --- a/sched/pthread/pthread_mutexconsistent.c +++ b/sched/pthread/pthread_mutexconsistent.c @@ -119,7 +119,6 @@ int pthread_mutex_consistent(FAR pthread_mutex_t *mutex) /* The thread associated with the PID no longer exists */ mutex->pid = -1; - mutex->flags &= _PTHREAD_MFLAGS_ROBUST; #ifdef CONFIG_PTHREAD_MUTEX_TYPES mutex->nlocks = 0; #endif @@ -132,6 +131,9 @@ int pthread_mutex_consistent(FAR pthread_mutex_t *mutex) } } + /* Clear the inconsistent flag in any case */ + + mutex->flags &= _PTHREAD_MFLAGS_ROBUST; sched_unlock(); ret = OK; } -- GitLab From 84849cfc5ec7b74bab3c7a21b2babed14c89e37d Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 10 Apr 2017 08:44:08 -0600 Subject: [PATCH 404/990] examples/ostest: pthread rwlock cleanup handlers must call pthread_consistent, not pthread_mutex_unlock() on cancellation if robust mutexes are enabled. --- libc/pthread/pthread_rwlock_rdlock.c | 13 ++++++++++++- libc/pthread/pthread_rwlock_wrlock.c | 14 +++++++++++++- 2 files changed, 25 insertions(+), 2 deletions(-) diff --git a/libc/pthread/pthread_rwlock_rdlock.c b/libc/pthread/pthread_rwlock_rdlock.c index 19979f79bb..29dcf7daae 100644 --- a/libc/pthread/pthread_rwlock_rdlock.c +++ b/libc/pthread/pthread_rwlock_rdlock.c @@ -55,7 +55,18 @@ static void rdlock_cleanup(FAR void *arg) { FAR pthread_rwlock_t *rw_lock = (FAR pthread_rwlock_t *)arg; - pthread_mutex_unlock(&rw_lock->lock); +#ifndef CONFIG_PTHREAD_MUTEX_UNSAFE + /* Check if this is a robust mutex in an inconsistent state */ + + if ((rw_lock->lock.flags & _PTHREAD_MFLAGS_INCONSISTENT) != 0) + { + (void)pthread_mutex_consistent(&rw_lock->lock); + } + else +#endif + { + (void)pthread_mutex_unlock(&rw_lock->lock); + } } #endif diff --git a/libc/pthread/pthread_rwlock_wrlock.c b/libc/pthread/pthread_rwlock_wrlock.c index fcda35cb4f..93a6a23858 100644 --- a/libc/pthread/pthread_rwlock_wrlock.c +++ b/libc/pthread/pthread_rwlock_wrlock.c @@ -56,7 +56,19 @@ static void wrlock_cleanup(FAR void *arg) FAR pthread_rwlock_t *rw_lock = (FAR pthread_rwlock_t *)arg; rw_lock->num_writers--; - pthread_mutex_unlock(&rw_lock->lock); + +#ifndef CONFIG_PTHREAD_MUTEX_UNSAFE + /* Check if this is a robust mutex in an inconsistent state */ + + if ((rw_lock->lock.flags & _PTHREAD_MFLAGS_INCONSISTENT) != 0) + { + (void)pthread_mutex_consistent(&rw_lock->lock); + } + else +#endif + { + (void)pthread_mutex_unlock(&rw_lock->lock); + } } #endif -- GitLab From 948332ca343f596acf7af0b434812a2bb7f90079 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 10 Apr 2017 09:51:03 -0600 Subject: [PATCH 405/990] pthreads: Backed most of last pthread changes. Found the 'real' root poblem. A one like error in pthread_mutex.c. --- libc/pthread/pthread_rwlock_rdlock.c | 13 +------------ libc/pthread/pthread_rwlock_wrlock.c | 14 +------------- sched/pthread/pthread_cancel.c | 12 ++++++------ sched/pthread/pthread_exit.c | 12 ++++++------ sched/pthread/pthread_mutex.c | 6 ++++-- 5 files changed, 18 insertions(+), 39 deletions(-) diff --git a/libc/pthread/pthread_rwlock_rdlock.c b/libc/pthread/pthread_rwlock_rdlock.c index 29dcf7daae..4eadfedccb 100644 --- a/libc/pthread/pthread_rwlock_rdlock.c +++ b/libc/pthread/pthread_rwlock_rdlock.c @@ -55,18 +55,7 @@ static void rdlock_cleanup(FAR void *arg) { FAR pthread_rwlock_t *rw_lock = (FAR pthread_rwlock_t *)arg; -#ifndef CONFIG_PTHREAD_MUTEX_UNSAFE - /* Check if this is a robust mutex in an inconsistent state */ - - if ((rw_lock->lock.flags & _PTHREAD_MFLAGS_INCONSISTENT) != 0) - { - (void)pthread_mutex_consistent(&rw_lock->lock); - } - else -#endif - { - (void)pthread_mutex_unlock(&rw_lock->lock); - } + (void)pthread_mutex_unlock(&rw_lock->lock); } #endif diff --git a/libc/pthread/pthread_rwlock_wrlock.c b/libc/pthread/pthread_rwlock_wrlock.c index 93a6a23858..c9f4f3a7c5 100644 --- a/libc/pthread/pthread_rwlock_wrlock.c +++ b/libc/pthread/pthread_rwlock_wrlock.c @@ -56,19 +56,7 @@ static void wrlock_cleanup(FAR void *arg) FAR pthread_rwlock_t *rw_lock = (FAR pthread_rwlock_t *)arg; rw_lock->num_writers--; - -#ifndef CONFIG_PTHREAD_MUTEX_UNSAFE - /* Check if this is a robust mutex in an inconsistent state */ - - if ((rw_lock->lock.flags & _PTHREAD_MFLAGS_INCONSISTENT) != 0) - { - (void)pthread_mutex_consistent(&rw_lock->lock); - } - else -#endif - { - (void)pthread_mutex_unlock(&rw_lock->lock); - } + (void)pthread_mutex_unlock(&rw_lock->lock); } #endif diff --git a/sched/pthread/pthread_cancel.c b/sched/pthread/pthread_cancel.c index f68d272e03..e2cad60ebb 100644 --- a/sched/pthread/pthread_cancel.c +++ b/sched/pthread/pthread_cancel.c @@ -145,12 +145,6 @@ int pthread_cancel(pthread_t thread) pthread_exit(PTHREAD_CANCELED); } -#ifndef CONFIG_PTHREAD_MUTEX_UNSAFE - /* Recover any mutexes still held by the canceled thread */ - - pthread_mutex_inconsistent(tcb); -#endif - #ifdef CONFIG_PTHREAD_CLEANUP /* Perform any stack pthread clean-up callbacks. * @@ -168,6 +162,12 @@ int pthread_cancel(pthread_t thread) (void)pthread_completejoin((pid_t)thread, PTHREAD_CANCELED); +#ifndef CONFIG_PTHREAD_MUTEX_UNSAFE + /* Recover any mutexes still held by the canceled thread */ + + pthread_mutex_inconsistent(tcb); +#endif + /* Then let task_terminate do the real work */ return task_terminate((pid_t)thread, false); diff --git a/sched/pthread/pthread_exit.c b/sched/pthread/pthread_exit.c index 4929db94cb..bcc8e79c85 100644 --- a/sched/pthread/pthread_exit.c +++ b/sched/pthread/pthread_exit.c @@ -105,12 +105,6 @@ void pthread_exit(FAR void *exit_value) tcb->cpcount = 0; #endif -#ifndef CONFIG_PTHREAD_MUTEX_UNSAFE - /* Recover any mutexes still held by the canceled thread */ - - pthread_mutex_inconsistent((FAR struct pthread_tcb_s *)tcb); -#endif - #ifdef CONFIG_PTHREAD_CLEANUP /* Perform any stack pthread clean-up callbacks */ @@ -129,6 +123,12 @@ void pthread_exit(FAR void *exit_value) exit(EXIT_FAILURE); } +#ifndef CONFIG_PTHREAD_MUTEX_UNSAFE + /* Recover any mutexes still held by the canceled thread */ + + pthread_mutex_inconsistent((FAR struct pthread_tcb_s *)tcb); +#endif + /* Perform common task termination logic. This will get called again later * through logic kicked off by _exit(). However, we need to call it before * calling _exit() in order certain operations if this is the last thread diff --git a/sched/pthread/pthread_mutex.c b/sched/pthread/pthread_mutex.c index f11a5b01f6..afd296407e 100644 --- a/sched/pthread/pthread_mutex.c +++ b/sched/pthread/pthread_mutex.c @@ -125,10 +125,12 @@ int pthread_mutex_take(FAR struct pthread_mutex_s *mutex, bool intr) } else { - /* Take semaphore underlying the mutex */ + /* Take semaphore underlying the mutex. pthread_takesemaphore + * returns zero on success and a positive errno value on failue. + */ ret = pthread_takesemaphore(&mutex->sem, intr); - if (ret < OK) + if (ret != OK) { ret = get_errno(); } -- GitLab From 6935d44405284ee9d680a79b8669143dd96faca3 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 10 Apr 2017 09:58:34 -0600 Subject: [PATCH 406/990] Update TODO list --- TODO | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/TODO b/TODO index d19ac0f067..8998fb1a46 100644 --- a/TODO +++ b/TODO @@ -1,4 +1,4 @@ -NuttX TODO List (Last updated March 26, 2017) +NuttX TODO List (Last updated April 10, 2017) ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ This file summarizes known NuttX bugs, limitations, inconsistencies with @@ -108,9 +108,10 @@ o Task/Scheduler (sched/) 2. They run in supervisor mode (if applicable), and 3. They do not obey any setup of PIC or address environments. Do they need to? - 4. In the case of task_delete() and pthread_cancel(), these - callbacks will run on the thread of execution and address - context of the caller of task. That is very bad! + 4. In the case of task_delete() and pthread_cancel() without + defferred cancellation, these callbacks will run on the + thread of execution and address context of the caller of + task_delete() or pthread_cancel(). That is very bad! The fix for all of these issues it to have the callbacks run on the caller's thread as is currently done with -- GitLab From c36bf090f09c50be36022a4678e4ce4d8f9eb7ee Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 10 Apr 2017 10:10:41 -0600 Subject: [PATCH 407/990] pthread: Minor logic fix in pthread_mutex_consistent. Updat some comments. --- sched/pthread/pthread_mutexconsistent.c | 28 ++++++++++++++++++------- 1 file changed, 21 insertions(+), 7 deletions(-) diff --git a/sched/pthread/pthread_mutexconsistent.c b/sched/pthread/pthread_mutexconsistent.c index e374083021..dac4fcf043 100644 --- a/sched/pthread/pthread_mutexconsistent.c +++ b/sched/pthread/pthread_mutexconsistent.c @@ -104,13 +104,14 @@ int pthread_mutex_consistent(FAR pthread_mutex_t *mutex) DEBUGASSERT(mutex->pid != 0); /* < 0: available, >0 owned, ==0 error */ if (mutex->pid >= 0) { - /* No.. Verify that the PID still exists. We may be destroying - * the mutex after cancelling a pthread and the mutex may have - * been in a bad state owned by the dead pthread. NOTE: The - * folling is unspecified behavior (see pthread_mutex_consistent()). + /* No.. Verify that the thread associated with the PID still + * exists. We may be destroying the mutex after cancelling a + * pthread and the mutex may have been in a bad state owned by + * the dead pthread. NOTE: The following is unspecified behavior + * (see pthread_mutex_consistent()). * * If the holding thread is still valid, then we should be able to - * map its PID to the underlying TCB. That is what sched_gettcb() + * map its PID to the underlying TCB. That is what sched_gettcb() * does. */ @@ -119,6 +120,7 @@ int pthread_mutex_consistent(FAR pthread_mutex_t *mutex) /* The thread associated with the PID no longer exists */ mutex->pid = -1; + mutex->flags &= _PTHREAD_MFLAGS_ROBUST; #ifdef CONFIG_PTHREAD_MUTEX_TYPES mutex->nlocks = 0; #endif @@ -129,11 +131,23 @@ int pthread_mutex_consistent(FAR pthread_mutex_t *mutex) status = sem_reset((FAR sem_t *)&mutex->sem, 1); ret = (status != OK) ? get_errno() : OK; } + + /* Otherwise the mutex is held by some active thread. Let's not + * touch anything! + */ } + else + { + /* There is no holder of the mutex. Just make sure the + * inconsistent flag is cleared and the number of locks is zero. + */ - /* Clear the inconsistent flag in any case */ + mutex->flags &= _PTHREAD_MFLAGS_ROBUST; +#ifdef CONFIG_PTHREAD_MUTEX_TYPES + mutex->nlocks = 0; +#endif + } - mutex->flags &= _PTHREAD_MFLAGS_ROBUST; sched_unlock(); ret = OK; } -- GitLab From c08ba10d325c0d01c5985cd613ab3cc9404e19b6 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 10 Apr 2017 14:56:23 -0600 Subject: [PATCH 408/990] include/: Add some definitions needed by apps/wireless/wapi --- include/nuttx/wireless/wireless.h | 20 ++++++++++++++++++-- sched/pthread/pthread_cancel.c | 6 +++--- 2 files changed, 21 insertions(+), 5 deletions(-) diff --git a/include/nuttx/wireless/wireless.h b/include/nuttx/wireless/wireless.h index 6ab0b0b3d1..74908e7350 100644 --- a/include/nuttx/wireless/wireless.h +++ b/include/nuttx/wireless/wireless.h @@ -203,6 +203,22 @@ #define IW_ESSID_MAX_SIZE 32 +/* Modes of operation */ + +#define IW_MODE_AUTO 0 /* Let the driver decides */ +#define IW_MODE_ADHOC 1 /* Single cell network */ +#define IW_MODE_INFRA 2 /* Multi cell network, roaming, ... */ +#define IW_MODE_MASTER 3 /* Synchronisation master or Access Point */ +#define IW_MODE_REPEAT 4 /* Wireless Repeater (forwarder) */ +#define IW_MODE_SECOND 5 /* Secondary master/repeater (backup) */ +#define IW_MODE_MONITOR 6 /* Passive monitor (listen only) */ +#define IW_MODE_MESH 7 /* Mesh (IEEE 802.11s) network */ + +/* Frequency flags */ + +#define IW_FREQ_AUTO 0x00 /* Let the driver decides */ +#define IW_FREQ_FIXED 0x01 /* Force a specific value */ + /************************************************************************************ * Public Types ************************************************************************************/ @@ -303,8 +319,8 @@ union iwreq_data struct iwreq { - char ifrn_name[IFNAMSIZ]; /* Interface name, e.g. "eth0" */ - union iwreq_data u; /* Data payload */ + char ifrn_name[IFNAMSIZ]; /* Interface name, e.g. "eth0" */ + union iwreq_data u; /* Data payload */ }; #endif /* CONFIG_DRIVERS_WIRELESS */ diff --git a/sched/pthread/pthread_cancel.c b/sched/pthread/pthread_cancel.c index e2cad60ebb..20e6f838b7 100644 --- a/sched/pthread/pthread_cancel.c +++ b/sched/pthread/pthread_cancel.c @@ -150,9 +150,9 @@ int pthread_cancel(pthread_t thread) * * REVISIT: In this case, the clean-up callback will execute on the * thread of the caller of pthread cancel, not on the thread of - * the thread-to-be-canceled. Is that an issue? Presumably they - * are both within the same group and within the same process address - * space. + * the thread-to-be-canceled. This is a problem when deferred + * cancellation is not supported because, for example, the clean-up + * function will be unable to unlock its own mutexes. */ pthread_cleanup_popall(tcb); -- GitLab From 4f35f196b1617b543f24aedc945b9907f7f28b28 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 10 Apr 2017 16:14:12 -0600 Subject: [PATCH 409/990] included/nuttx/wireless/wireless.h: Fix/add a few things needed by apps/wireless/wapi --- include/nuttx/wireless/wireless.h | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/include/nuttx/wireless/wireless.h b/include/nuttx/wireless/wireless.h index 74908e7350..362b991d18 100644 --- a/include/nuttx/wireless/wireless.h +++ b/include/nuttx/wireless/wireless.h @@ -313,13 +313,22 @@ union iwreq_data struct iw_point data; /* Other large parameters */ }; +/* A Wireless Event. */ + +struct iw_event +{ + uint16_t len; /* Real length of ata */ + uint16_t cmd; /* Wireless IOCTL command*/ + union iwreq_data u; /* Fixed IOCTL payload */ +}; + /* This is the structure used to exchange data in wireless IOCTLs. This structure * is the same as 'struct ifreq', but defined for use with wireless IOCTLs. */ struct iwreq { - char ifrn_name[IFNAMSIZ]; /* Interface name, e.g. "eth0" */ + char ifr_name[IFNAMSIZ]; /* Interface name, e.g. "eth0" */ union iwreq_data u; /* Data payload */ }; -- GitLab From e9a8dc7c6ecf9d3b642cb968c757b9c102bc7422 Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Tue, 11 Apr 2017 06:39:27 -0600 Subject: [PATCH 410/990] STM32F7: serial: disallow broken configuration combination of CONFIG_STM32F7_FLOWCONTROL_BROKEN=y and CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS not set. --- arch/arm/src/stm32f7/Kconfig | 2 +- arch/arm/src/stm32f7/stm32_serial.c | 63 +++++++++++++++++------------ 2 files changed, 39 insertions(+), 26 deletions(-) diff --git a/arch/arm/src/stm32f7/Kconfig b/arch/arm/src/stm32f7/Kconfig index d8eabdcd4b..2c21fadf61 100644 --- a/arch/arm/src/stm32f7/Kconfig +++ b/arch/arm/src/stm32f7/Kconfig @@ -1634,7 +1634,7 @@ config SERIAL_DISABLE_REORDERING config STM32F7_FLOWCONTROL_BROKEN bool "Use Software UART RTS flow control" - depends on STM32F7_USART + depends on STM32F7_USART && SERIAL_IFLOWCONTROL_WATERMARKS default n ---help--- Enable UART RTS flow control using Software. Because STM diff --git a/arch/arm/src/stm32f7/stm32_serial.c b/arch/arm/src/stm32f7/stm32_serial.c index ec97ec7096..ea67ddb4db 100644 --- a/arch/arm/src/stm32f7/stm32_serial.c +++ b/arch/arm/src/stm32f7/stm32_serial.c @@ -220,43 +220,56 @@ /* Warnings for potentially unsafe configuration combinations. */ +#if defined(CONFIG_STM32F7_FLOWCONTROL_BROKEN) && \ + !defined(CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS) +# error "CONFIG_STM32F7_FLOWCONTROL_BROKEN requires \ + CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS to be enabled." +#endif + +#ifndef CONFIG_STM32F7_FLOWCONTROL_BROKEN /* Combination of RXDMA + IFLOWCONTROL does not work as one might expect. * Since RXDMA uses circular DMA-buffer, DMA will always keep reading new * data from USART peripheral even if DMA buffer underruns. Thus this * combination only does following: RTS is asserted on USART setup and * deasserted on shutdown and does not perform actual RTS flow-control. + * + * With SW flow-control, RTS is asserted before UART receive buffer fully + * fills, thus preventing data loss if application is slow to process data + * from serial device node. However, if RxDMA interrupt is blocked for too + * long, data loss is still possible as SW flow-control would also be + * blocked. */ -#if defined(CONFIG_USART1_RXDMA) && defined(CONFIG_USART1_IFLOWCONTROL) -# warning "RXDMA and IFLOWCONTROL both enabled for USART1. \ - This combination can lead to data loss." -#endif - -#if defined(CONFIG_USART2_RXDMA) && defined(CONFIG_USART2_IFLOWCONTROL) -# warning "RXDMA and IFLOWCONTROL both enabled for USART2. \ - This combination can lead to data loss." -#endif +# if defined(CONFIG_USART1_RXDMA) && defined(CONFIG_USART1_IFLOWCONTROL) +# warning "RXDMA and IFLOWCONTROL both enabled for USART1. \ + This combination can lead to data loss." +# endif -#if defined(CONFIG_USART3_RXDMA) && defined(CONFIG_USART3_IFLOWCONTROL) -# warning "RXDMA and IFLOWCONTROL both enabled for USART3. \ - This combination can lead to data loss." -#endif +# if defined(CONFIG_USART2_RXDMA) && defined(CONFIG_USART2_IFLOWCONTROL) +# warning "RXDMA and IFLOWCONTROL both enabled for USART2. \ + This combination can lead to data loss." +# endif -#if defined(CONFIG_USART6_RXDMA) && defined(CONFIG_USART6_IFLOWCONTROL) -# warning "RXDMA and IFLOWCONTROL both enabled for USART6. \ - This combination can lead to data loss." -#endif +# if defined(CONFIG_USART3_RXDMA) && defined(CONFIG_USART3_IFLOWCONTROL) +# warning "RXDMA and IFLOWCONTROL both enabled for USART3. \ + This combination can lead to data loss." +# endif -#if defined(CONFIG_UART7_RXDMA) && defined(CONFIG_UART7_IFLOWCONTROL) -# warning "RXDMA and IFLOWCONTROL both enabled for UART7. \ - This combination can lead to data loss." -#endif +# if defined(CONFIG_USART6_RXDMA) && defined(CONFIG_USART6_IFLOWCONTROL) +# warning "RXDMA and IFLOWCONTROL both enabled for USART6. \ + This combination can lead to data loss." +# endif -#if defined(CONFIG_UART8_RXDMA) && defined(CONFIG_UART8_IFLOWCONTROL) -# warning "RXDMA and IFLOWCONTROL both enabled for UART8. \ - This combination can lead to data loss." -#endif +# if defined(CONFIG_UART7_RXDMA) && defined(CONFIG_UART7_IFLOWCONTROL) +# warning "RXDMA and IFLOWCONTROL both enabled for UART7. \ + This combination can lead to data loss." +# endif +# if defined(CONFIG_UART8_RXDMA) && defined(CONFIG_UART8_IFLOWCONTROL) +# warning "RXDMA and IFLOWCONTROL both enabled for UART8. \ + This combination can lead to data loss." +# endif +#endif /* CONFIG_STM32F7_FLOWCONTROL_BROKEN */ /**************************************************************************** * Private Types -- GitLab From 4c99a6aeec03e3b83f34cc90a968a9a1937ed526 Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Tue, 11 Apr 2017 06:40:44 -0600 Subject: [PATCH 411/990] STM32F7: serial: do not stop processing input in SW flow-control mode --- arch/arm/src/stm32f7/stm32_serial.c | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/arch/arm/src/stm32f7/stm32_serial.c b/arch/arm/src/stm32f7/stm32_serial.c index ea67ddb4db..5c2b8b74bc 100644 --- a/arch/arm/src/stm32f7/stm32_serial.c +++ b/arch/arm/src/stm32f7/stm32_serial.c @@ -2224,6 +2224,22 @@ static bool up_rxflowcontrol(struct uart_dev_s *dev, /* Assert/de-assert nRTS set it high resume/stop sending */ stm32_gpiowrite(priv->rts_gpio, upper); + + if (upper) + { + /* With heavy Rx traffic, RXNE might be set and data pending. + * Returning 'true' in such case would cause RXNE left unhandled + * and causing interrupt storm. Sending end might be also be slow + * to react on nRTS, and returning 'true' here would prevent + * processing that data. + * + * Therefore, return 'false' so input data is still being processed + * until sending end reacts on nRTS signal and stops sending more. + */ + + return false; + } + return upper; } -- GitLab From a58823c4493255ad30348bc8d9b0d212f1930440 Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Tue, 11 Apr 2017 06:45:45 -0600 Subject: [PATCH 412/990] STM32XX: Fix Pending Register definition --- arch/arm/src/stm32/chip/stm32_exti.h | 6 +++--- arch/arm/src/stm32f7/chip/stm32_exti.h | 6 +++--- arch/arm/src/stm32l4/chip/stm32l4_exti.h | 12 ++++++------ 3 files changed, 12 insertions(+), 12 deletions(-) diff --git a/arch/arm/src/stm32/chip/stm32_exti.h b/arch/arm/src/stm32/chip/stm32_exti.h index 791bed1f17..e18b60cf71 100644 --- a/arch/arm/src/stm32/chip/stm32_exti.h +++ b/arch/arm/src/stm32/chip/stm32_exti.h @@ -188,9 +188,9 @@ /* Pending register */ -#define EXTI_IMR_BIT(n) STM32_EXTI_BIT(n) /* 1=Selected trigger request occurred */ -#define EXTI_IMR_SHIFT (0) /* Bits 0-X: Pending bit for all lines */ -#define EXTI_IMR_MASK STM32_EXTI_MASK +#define EXTI_PR_BIT(n) STM32_EXTI_BIT(n) /* 1=Selected trigger request occurred */ +#define EXTI_PR_SHIFT (0) /* Bits 0-X: Pending bit for all lines */ +#define EXTI_PR_MASK STM32_EXTI_MASK /* Compatibility Definitions ********************************************************/ diff --git a/arch/arm/src/stm32f7/chip/stm32_exti.h b/arch/arm/src/stm32f7/chip/stm32_exti.h index 288f51b228..8663d2f08e 100644 --- a/arch/arm/src/stm32f7/chip/stm32_exti.h +++ b/arch/arm/src/stm32f7/chip/stm32_exti.h @@ -125,9 +125,9 @@ /* Pending register */ -#define EXTI_IMR_BIT(n) STM32_EXTI_BIT(n) /* 1=Selected trigger request occurred */ -#define EXTI_IMR_SHIFT (0) /* Bits 0-X: Pending bit for all lines */ -#define EXTI_IMR_MASK STM32_EXTI_MASK +#define EXTI_PR_BIT(n) STM32_EXTI_BIT(n) /* 1=Selected trigger request occurred */ +#define EXTI_PR_SHIFT (0) /* Bits 0-X: Pending bit for all lines */ +#define EXTI_PR_MASK STM32_EXTI_MASK #endif /* CONFIG_STM32F7_STM32F74XX || CONFIG_STM32F7_STM32F75XX || CONFIG_STM32F7_STM32F76XX || CONFIG_STM32F7_STM32F77XX */ #endif /* __ARCH_ARM_SRC_STM32F7_CHIP_STM32_EXTI_H */ diff --git a/arch/arm/src/stm32l4/chip/stm32l4_exti.h b/arch/arm/src/stm32l4/chip/stm32l4_exti.h index 1fb1628a7a..f9f087a051 100644 --- a/arch/arm/src/stm32l4/chip/stm32l4_exti.h +++ b/arch/arm/src/stm32l4/chip/stm32l4_exti.h @@ -167,13 +167,13 @@ /* Pending register */ -#define EXTI_IMR1_BIT(n) STM32L4_EXTI1_BIT(n) /* 1=Selected trigger request occurred */ -#define EXTI_IMR1_SHIFT (0) /* Bits 0-X: Pending bit for all lines */ -#define EXTI_IMR1_MASK STM32L4_EXTI1_MASK +#define EXTI_PR1_BIT(n) STM32L4_EXTI1_BIT(n) /* 1=Selected trigger request occurred */ +#define EXTI_PR1_SHIFT (0) /* Bits 0-X: Pending bit for all lines */ +#define EXTI_PR1_MASK STM32L4_EXTI1_MASK -#define EXTI_IMR2_BIT(n) STM32L4_EXTI2_BIT(n) /* 1=Selected trigger request occurred */ -#define EXTI_IMR2_SHIFT (0) /* Bits 0-X: Pending bit for all lines */ -#define EXTI_IMR2_MASK STM32L4_EXTI2_MASK +#define EXTI_PR2_BIT(n) STM32L4_EXTI2_BIT(n) /* 1=Selected trigger request occurred */ +#define EXTI_PR2_SHIFT (0) /* Bits 0-X: Pending bit for all lines */ +#define EXTI_PR2_MASK STM32L4_EXTI2_MASK #endif /* __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4_EXTI_H */ -- GitLab From 3fb730040b9327aa951c3bd6c5edf34fc5f7d9a7 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 11 Apr 2017 10:23:46 -0600 Subject: [PATCH 413/990] include/nuttx/wireless/wireless.h: Add a few more definitions needed by apps/wireless/wapi --- include/nuttx/wireless/wireless.h | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/include/nuttx/wireless/wireless.h b/include/nuttx/wireless/wireless.h index 362b991d18..044315be7b 100644 --- a/include/nuttx/wireless/wireless.h +++ b/include/nuttx/wireless/wireless.h @@ -213,11 +213,17 @@ #define IW_MODE_SECOND 5 /* Secondary master/repeater (backup) */ #define IW_MODE_MONITOR 6 /* Passive monitor (listen only) */ #define IW_MODE_MESH 7 /* Mesh (IEEE 802.11s) network */ +#define IW_MODE_NFLAGS 8 /* Frequency flags */ #define IW_FREQ_AUTO 0x00 /* Let the driver decides */ #define IW_FREQ_FIXED 0x01 /* Force a specific value */ +#define IW_FREQ_NFLAGS 2 + +/* Scan-related */ + +#define IW_SCAN_MAX_DATA 4096 /* Maximum size of returned data */ /************************************************************************************ * Public Types -- GitLab From b4747286b19d3b15193b2a5e8a0fe48fa0a8638c Mon Sep 17 00:00:00 2001 From: "Juha Niskanen (Haltian)" Date: Tue, 11 Apr 2017 11:03:25 -0600 Subject: [PATCH 414/990] Add logic to disable cancellation points within the OS. This is useful when an internal OS function that is NOT a cancellation point calls an OS function which is a cancellation point. In that case, irrecoverable states may occur if the cancellation is within the OS. --- sched/pthread/pthread.h | 8 +++ sched/pthread/pthread_condtimedwait.c | 7 ++- sched/pthread/pthread_condwait.c | 11 +++- sched/pthread/pthread_mutex.c | 83 +++++++++++++++++++++++---- 4 files changed, 96 insertions(+), 13 deletions(-) diff --git a/sched/pthread/pthread.h b/sched/pthread/pthread.h index b4e87d9533..69e08e1445 100644 --- a/sched/pthread/pthread.h +++ b/sched/pthread/pthread.h @@ -121,6 +121,14 @@ void pthread_mutex_inconsistent(FAR struct pthread_tcb_s *tcb); # define pthread_mutex_give(m) pthread_givesemaphore(&(m)->sem) #endif +#ifdef CONFIG_CANCELLATION_POINTS +uint16_t pthread_disable_cancel(void); +void pthread_enable_cancel(uint16_t oldstate); +#else +# define pthread_disable_cancel() (0) +# define pthread_enable_cancel(s) UNUSED(s) +#endif + #ifdef CONFIG_PTHREAD_MUTEX_TYPES int pthread_mutexattr_verifytype(int type); #endif diff --git a/sched/pthread/pthread_condtimedwait.c b/sched/pthread/pthread_condtimedwait.c index 4ed8c5aed6..22ce470770 100644 --- a/sched/pthread/pthread_condtimedwait.c +++ b/sched/pthread/pthread_condtimedwait.c @@ -167,9 +167,10 @@ int pthread_cond_timedwait(FAR pthread_cond_t *cond, FAR pthread_mutex_t *mutex, FAR const struct timespec *abstime) { FAR struct tcb_s *rtcb = this_task(); + irqstate_t flags; + uint16_t oldstate; int ticks; int mypid = (int)getpid(); - irqstate_t flags; int ret = OK; int status; @@ -316,7 +317,11 @@ int pthread_cond_timedwait(FAR pthread_cond_t *cond, FAR pthread_mutex_t *mutex, /* Reacquire the mutex (retaining the ret). */ sinfo("Re-locking...\n"); + + oldstate = pthread_disable_cancel(); status = pthread_mutex_take(mutex, false); + pthread_enable_cancel(oldstate); + if (status == OK) { mutex->pid = mypid; diff --git a/sched/pthread/pthread_condwait.c b/sched/pthread/pthread_condwait.c index 9bcba234a5..91138215fa 100644 --- a/sched/pthread/pthread_condwait.c +++ b/sched/pthread/pthread_condwait.c @@ -95,6 +95,8 @@ int pthread_cond_wait(FAR pthread_cond_t *cond, FAR pthread_mutex_t *mutex) } else { + uint16_t oldstate; + /* Give up the mutex */ sinfo("Give up mutex / take cond\n"); @@ -117,12 +119,17 @@ int pthread_cond_wait(FAR pthread_cond_t *cond, FAR pthread_mutex_t *mutex) /* Reacquire the mutex. * - * REVISIT: When cancellation points are enabled, we will almost - * certainly hold the mutex when the pthread is canceled. + * When cancellation points are enabled, we need to + * hold the mutex when the pthread is canceled and + * cleanup handlers, if any, are entered. */ sinfo("Reacquire mutex...\n"); + + oldstate = pthread_disable_cancel(); status = pthread_mutex_take(mutex, false); + pthread_enable_cancel(oldstate); + if (ret == OK) { /* Report the first failure that occurs */ diff --git a/sched/pthread/pthread_mutex.c b/sched/pthread/pthread_mutex.c index afd296407e..45c4ffd3fa 100644 --- a/sched/pthread/pthread_mutex.c +++ b/sched/pthread/pthread_mutex.c @@ -95,8 +95,8 @@ static void pthread_mutex_add(FAR struct pthread_mutex_s *mutex) * mutex to the list of mutexes held by this thread. * * Parameters: - * mutex - The mux to be locked - * intr - false: ignore EINTR errors when locking; true tread EINTR as + * mutex - The mutex to be locked + * intr - false: ignore EINTR errors when locking; true treat EINTR as * other errors by returning the errno value * * Return Value: @@ -126,15 +126,11 @@ int pthread_mutex_take(FAR struct pthread_mutex_s *mutex, bool intr) else { /* Take semaphore underlying the mutex. pthread_takesemaphore - * returns zero on success and a positive errno value on failue. + * returns zero on success and a positive errno value on failure. */ ret = pthread_takesemaphore(&mutex->sem, intr); - if (ret != OK) - { - ret = get_errno(); - } - else + if (ret == OK) { /* Check if the holder of the mutex has terminated without * releasing. In that case, the state of the mutex is @@ -169,8 +165,8 @@ int pthread_mutex_take(FAR struct pthread_mutex_s *mutex, bool intr) * mutex to the list of mutexes held by this thread. * * Parameters: - * mutex - The mux to be locked - * intr - false: ignore EINTR errors when locking; true tread EINTR as + * mutex - The mutex to be locked + * intr - false: ignore EINTR errors when locking; true treat EINTR as * other errors by returning the errno value * * Return Value: @@ -283,3 +279,70 @@ int pthread_mutex_give(FAR struct pthread_mutex_s *mutex) return ret; } +/**************************************************************************** + * Name: pthread_disable_cancel() and pthread_enable_cancel() + * + * Description: + * Temporarily disable cancellation and return old cancel state, which + * can later be restored. This is useful when a cancellation point + * function is called from within the OS by a non-cancellation point: + * In certain such cases, we need to defer the cancellation to prevent + * bad things from happening. + * + * Parameters: + * saved cancel flags for pthread_enable_cancel() + * + * Return Value: + * old cancel flags for pthread_disable_cancel() + * + ****************************************************************************/ + +#ifdef CONFIG_CANCELLATION_POINTS +uint16_t pthread_disable_cancel(void) +{ + FAR struct pthread_tcb_s *tcb = (FAR struct pthread_tcb_s *)this_task(); + irqstate_t flags; + uint16_t old; + + /* We need perform the following operations from within a critical section + * because it can compete with interrupt level activity. + */ + + flags = enter_critical_section(); + old = tcb->cmn.flags & (TCB_FLAG_CANCEL_PENDING | TCB_FLAG_NONCANCELABLE); + tcb->cmn.flags &= ~(TCB_FLAG_CANCEL_PENDING | TCB_FLAG_NONCANCELABLE); + leave_critical_section(flags); + return old; +} + +void pthread_enable_cancel(uint16_t cancelflags) +{ + FAR struct pthread_tcb_s *tcb = (FAR struct pthread_tcb_s *)this_task(); + irqstate_t flags; + + /* We need perform the following operations from within a critical section + * because it can compete with interrupt level activity. + */ + + flags = enter_critical_section(); + tcb->cmn.flags |= cancelflags; + + /* What should we do if there is a pending cancellation? + * + * If the thread is executing with deferred cancellation, we need do + * nothing more; the cancellation cannot occur until the next + * cancellation point. + * + * However, if the thread is executing in asynchronous cancellation mode, + * then we need to terminate now by simply calling pthread_exit(). + */ + + if ((tcb->cmn.flags & TCB_FLAG_CANCEL_DEFERRED) == 0 && + (tcb->cmn.flags & TCB_FLAG_CANCEL_PENDING) != 0) + { + pthread_exit(NULL); + } + + leave_critical_section(flags); +} +#endif /* CONFIG_CANCELLATION_POINTS */ -- GitLab From 6560db912bd45027a9ad1606e7340001f4087d96 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 11 Apr 2017 12:41:30 -0600 Subject: [PATCH 415/990] Add more definitions needed by apps/examples/wapi --- include/nuttx/net/arp.h | 1 + include/nuttx/wireless/wireless.h | 39 ++++++++++++++++++++++--------- 2 files changed, 29 insertions(+), 11 deletions(-) diff --git a/include/nuttx/net/arp.h b/include/nuttx/net/arp.h index 4a33994a1b..477240a5d6 100644 --- a/include/nuttx/net/arp.h +++ b/include/nuttx/net/arp.h @@ -69,6 +69,7 @@ */ #define ARPHRD_ETHER 1 /* Ethernet */ +#define ARPHRD_IEEE80211    801 /* IEEE 802.11 */ #define ARPHRD_IEEE802154 804 /* IEEE 802.15.4 */ /**************************************************************************** diff --git a/include/nuttx/wireless/wireless.h b/include/nuttx/wireless/wireless.h index 044315be7b..bd9f93ba8f 100644 --- a/include/nuttx/wireless/wireless.h +++ b/include/nuttx/wireless/wireless.h @@ -217,10 +217,19 @@ /* Frequency flags */ -#define IW_FREQ_AUTO 0x00 /* Let the driver decides */ -#define IW_FREQ_FIXED 0x01 /* Force a specific value */ +#define IW_FREQ_AUTO 0 /* Let the driver decides */ +#define IW_FREQ_FIXED 1 /* Force a specific value */ #define IW_FREQ_NFLAGS 2 +#define IW_MAX_FREQUENCIES 32 /* Max. frequencies in struct iw_range */ + +/* Transmit Power flags available */ + +#define IW_TXPOW_DBM 0 /* Value is in dBm */ +#define IW_TXPOW_MWATT 1 /* Value is in mW */ +#define IW_TXPOW_RELATIVE 2 /* Value is in arbitrary units */ +#define IW_TXPOW_NFLAGS 3 + /* Scan-related */ #define IW_SCAN_MAX_DATA 4096 /* Maximum size of returned data */ @@ -318,15 +327,6 @@ union iwreq_data struct iw_param param; /* Other small parameters */ struct iw_point data; /* Other large parameters */ }; - -/* A Wireless Event. */ - -struct iw_event -{ - uint16_t len; /* Real length of ata */ - uint16_t cmd; /* Wireless IOCTL command*/ - union iwreq_data u; /* Fixed IOCTL payload */ -}; /* This is the structure used to exchange data in wireless IOCTLs. This structure * is the same as 'struct ifreq', but defined for use with wireless IOCTLs. @@ -338,5 +338,22 @@ struct iwreq union iwreq_data u; /* Data payload */ }; +/* Range of parameters (currently only frequencies) */ + +struct iw_range +{ + uint8_t num_frequency; /* Number of frequencies in the freq[] list */ + struct iw_freq freq[IW_MAX_FREQUENCIES]; +}; + +/* A Wireless Event. */ + +struct iw_event +{ + uint16_t len; /* Real length of ata */ + uint16_t cmd; /* Wireless IOCTL command*/ + union iwreq_data u; /* Fixed IOCTL payload */ +}; + #endif /* CONFIG_DRIVERS_WIRELESS */ #endif /* __INCLUDE_NUTTX_WIRELESS_H */ -- GitLab From dced088ff53dae4c8005f445e71a555c0c72d1b4 Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Tue, 11 Apr 2017 13:07:11 -0600 Subject: [PATCH 416/990] Fix LLVM libc++ undefined reference to __cxa_guard_* --- libxx/Makefile | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/libxx/Makefile b/libxx/Makefile index 766bd5d62d..9f5ba9c9ac 100644 --- a/libxx/Makefile +++ b/libxx/Makefile @@ -50,13 +50,19 @@ endif ifeq (,$(findstring y,$(CONFIG_UCLIBCXX) $(CONFIG_LIBCXX))) CXXSRCS += libxx_delete.cxx libxx_deletea.cxx libxx_new.cxx libxx_newa.cxx -CXXSRCS += libxx_stdthrow.cxx libxx_cxa_guard.cxx +CXXSRCS += libxx_stdthrow.cxx else ifeq (,$(findstring y,$(CONFIG_UCLIBCXX_EXCEPTION) $(CONFIG_LIBCXX_EXCEPTION))) CXXSRCS += libxx_stdthrow.cxx endif endif +# uClibc++ doesn't need this file + +ifneq ($(CONFIG_UCLIBCXX),y) +CXXSRCS += libxx_cxa_guard.cxx +endif + # Paths DEPPATH = --dep-path . -- GitLab From eab139a5390d0f8da61d47970978233ae0cfe8d1 Mon Sep 17 00:00:00 2001 From: Ritajina Date: Wed, 12 Apr 2017 06:41:08 -0600 Subject: [PATCH 417/990] libc/netdb: in dns_query_callback, ret != -EADDRNOTAVAIL condition consumes error returns including EAGAIN in this case, dns query retransmission doesn't work --- libc/netdb/lib_dnsquery.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libc/netdb/lib_dnsquery.c b/libc/netdb/lib_dnsquery.c index 21ed201ba8..3602a5c8dd 100644 --- a/libc/netdb/lib_dnsquery.c +++ b/libc/netdb/lib_dnsquery.c @@ -494,7 +494,7 @@ static int dns_query_callback(FAR void *arg, FAR struct sockaddr *addr, nerr("ERROR: IPv4 dns_recv_response failed: %d\n", ret); - if (ret != -EADDRNOTAVAIL) + if (ret == -EADDRNOTAVAIL) { /* The IPv4 address is not available. Return zero to * continue the tranversal with the next nameserver @@ -575,7 +575,7 @@ static int dns_query_callback(FAR void *arg, FAR struct sockaddr *addr, nerr("ERROR: IPv6 dns_recv_response failed: %d\n", ret); - if (ret != -EADDRNOTAVAIL) + if (ret == -EADDRNOTAVAIL) { /* The IPv6 address is not available. Return zero to * continue the tranversal with the next nameserver -- GitLab From d9b1b3f824f29b80e28f66382058769cf372a157 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 12 Apr 2017 07:28:11 -0600 Subject: [PATCH 418/990] Update TODO list --- TODO | 45 +++++++++++++++++++++++++++++++++++++++++++-- 1 file changed, 43 insertions(+), 2 deletions(-) diff --git a/TODO b/TODO index 8998fb1a46..93db26ced4 100644 --- a/TODO +++ b/TODO @@ -1,4 +1,4 @@ -NuttX TODO List (Last updated April 10, 2017) +NuttX TODO List (Last updated April 12, 2017) ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ This file summarizes known NuttX bugs, limitations, inconsistencies with @@ -9,7 +9,7 @@ issues related to each board port. nuttx/: - (10) Task/Scheduler (sched/) + (11) Task/Scheduler (sched/) (1) SMP (1) Memory Management (mm/) (0) Power Management (drivers/pm) @@ -186,6 +186,47 @@ o Task/Scheduler (sched/) Priority: Low. Things are just the way that we want them for the way that NuttX is used today. + Title: INTERNAL VERSIONS OF USER FUNCTIONS + Description: The internal NuttX logic uses the same interfaces as does + the application. That sometime produces a problem because + there is "overloaded" functionality in those user interfaces + that are not desireable. + + For example, having cancellation points hidden inside of the + OS can cause non-cancellation point interfaces to behave + strangely. There was a change recently in pthread_cond_wait() + and pthread_cond_timedwait() recently to effectively disable + the cancellation point behavior of sem_init(). This was + accomplished with two functions: pthread_disable_cancel() + and pthread_enable_cancel() + + Here is another issue:  Internal OS functions should not set + errno and should never have to look at the errno value to + determine the cause of the failure.  The errno is provided + for compatibility with POSIX application interface + requirements and really doesn't need to be used within the + OS. + + Both of these could be fixed if there were special internal + versions these functions.  For example, there could be a an + nx_sem_wait() that does all of the same things as sem_wait() + was does not create a cancellation point and does not set + the errno value on failures. + + Everything inside the OS would use nx_sem_wait(). + Applications would call sem_wait() which would just be a + wrapper around nx_sem_wait() that adds the cancellation point + and that sets the errno value on failures. + + Changes like that could clean up some of this internal + craziness.  The condition variable change described above is + really a "bandaid" to handle the case that sem_wait() is a + cancellation point. + Status: Open + Priority: Low. Things are working OK the way they are. But the design + could be improved and made a little more efficient with this + change. + o SMP ^^^ -- GitLab From dc2890904df0cb7a1d0e4c1b2a029ddc8697f953 Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Wed, 12 Apr 2017 10:25:51 -0600 Subject: [PATCH 419/990] STM32L4 DMA: Correct bad channel definition. --- arch/arm/src/stm32l4/chip/stm32l4x6xx_dma.h | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/arch/arm/src/stm32l4/chip/stm32l4x6xx_dma.h b/arch/arm/src/stm32l4/chip/stm32l4x6xx_dma.h index ab63195d2f..6e7afac9af 100644 --- a/arch/arm/src/stm32l4/chip/stm32l4x6xx_dma.h +++ b/arch/arm/src/stm32l4/chip/stm32l4x6xx_dma.h @@ -306,7 +306,12 @@ #define STM32L4_DMA2_CHAN6 (12) #define STM32L4_DMA2_CHAN7 (13) -#define DMACHAN_SETTING(chan, sel) ( ( ( (sel) & 0xff) << 8) | ( (chan) & 0xff) ) +/* DMA Channel settings include a channel and an alternative function. + * Channel is in bits 0..7 + * Request number is in bits 8..15 + */ + +#define DMACHAN_SETTING(chan, req) ((((req) & 0xff) << 8) | ((chan) & 0xff)) #define DMACHAN_SETTING_CHANNEL_MASK 0x00FF #define DMACHAN_SETTING_CHANNEL_SHIFT (0) #define DMACHAN_SETTING_FUNCTION_MASK 0xFF00 @@ -384,7 +389,7 @@ #define DMACHAN_SPI1_RX_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN2, 1) #define DMACHAN_SPI1_RX_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN3, 4) -#define DMACHAN_SPI1_TX_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN3, 0) +#define DMACHAN_SPI1_TX_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN3, 1) #define DMACHAN_SPI1_TX_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN4, 4) #define DMACHAN_SPI2_RX DMACHAN_SETTING(STM32L4_DMA1_CHAN4, 1) -- GitLab From 1a9403313ee597868ed6754081c3770d75312c7e Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Wed, 12 Apr 2017 20:33:32 -0700 Subject: [PATCH 420/990] Adds USB host support to stm32f411-disco board. --- configs/stm32f411e-disco/Kconfig | 11 + configs/stm32f411e-disco/src/Makefile | 6 +- configs/stm32f411e-disco/src/stm32_boot.c | 17 +- configs/stm32f411e-disco/src/stm32_bringup.c | 123 ++++++ configs/stm32f411e-disco/src/stm32_usb.c | 352 ++++++++++++++++++ .../stm32f411e-disco/src/stm32f411e-disco.h | 81 +++- 6 files changed, 574 insertions(+), 16 deletions(-) create mode 100644 configs/stm32f411e-disco/src/stm32_bringup.c create mode 100644 configs/stm32f411e-disco/src/stm32_usb.c diff --git a/configs/stm32f411e-disco/Kconfig b/configs/stm32f411e-disco/Kconfig index c898319183..205dc95fa2 100644 --- a/configs/stm32f411e-disco/Kconfig +++ b/configs/stm32f411e-disco/Kconfig @@ -5,4 +5,15 @@ if ARCH_BOARD_STM32F411E_DISCO +config STM32F411DISCO_USBHOST_STACKSIZE + int "USB host waiter stack size" + default 1024 + depends on USBHOST + +config STM32F411DISCO_USBHOST_PRIO + int "USB host waiter task priority" + default 100 + depends on USBHOST + + endif diff --git a/configs/stm32f411e-disco/src/Makefile b/configs/stm32f411e-disco/src/Makefile index 2ee3b64016..3635386d27 100644 --- a/configs/stm32f411e-disco/src/Makefile +++ b/configs/stm32f411e-disco/src/Makefile @@ -36,10 +36,14 @@ -include $(TOPDIR)/Make.defs ASRCS = -CSRCS = stm32_boot.c +CSRCS = stm32_boot.c stm32_bringup.c ifeq ($(CONFIG_NSH_LIBRARY),y) CSRCS += stm32_appinit.c endif +ifeq ($(CONFIG_STM32_OTGFS),y) +CSRCS += stm32_usb.c +endif + include $(TOPDIR)/configs/Board.mk diff --git a/configs/stm32f411e-disco/src/stm32_boot.c b/configs/stm32f411e-disco/src/stm32_boot.c index dec40d4b70..6de88de6a9 100644 --- a/configs/stm32f411e-disco/src/stm32_boot.c +++ b/configs/stm32f411e-disco/src/stm32_boot.c @@ -80,10 +80,9 @@ void stm32_boardinitialize(void) stm32_spidev_initialize(); #endif -#if defined(CONFIG_USBDEV) && defined(CONFIG_STM32_USB) - /* Initialize USB is 1) USBDEV is selected, 2) the USB controller is not - * disabled, and 3) the weak function stm32_usbinitialize() has been brought - * into the build. +#ifdef CONFIG_STM32_OTGFS + /* Initialize USB if the 1) OTG FS controller is in the configuration and 2) + * disabled. Presumably either CONFIG_USBDEV or CONFIG_USBHOST is also selected. */ stm32_usbinitialize(); @@ -106,14 +105,8 @@ void stm32_boardinitialize(void) #ifdef CONFIG_BOARD_INITIALIZE void board_initialize(void) { -#if defined(CONFIG_NSH_LIBRARY) && !defined(CONFIG_LIB_BOARDCTL) - /* Perform NSH initialization here instead of from the NSH. This - * alternative NSH initialization is necessary when NSH is ran in user-space - * but the initialization function must run in kernel space. - */ - - board_app_initialize(0); -#endif + /* Perform board-specific initialization */ + (void)stm32_bringup(); } #endif diff --git a/configs/stm32f411e-disco/src/stm32_bringup.c b/configs/stm32f411e-disco/src/stm32_bringup.c new file mode 100644 index 0000000000..be0d587123 --- /dev/null +++ b/configs/stm32f411e-disco/src/stm32_bringup.c @@ -0,0 +1,123 @@ +/**************************************************************************** + * config/stm32f4discovery/src/stm32_bringup.c + * + * Copyright (C) 2012, 2014-2016 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#ifdef CONFIG_USBMONITOR +# include +#endif + +#include + +#include "stm32.h" + +#ifdef CONFIG_STM32_OTGFS +# include "stm32_usbhost.h" +#endif + +#include "stm32f411e-disco.h" + +/* Conditional logic in stm32f4discover.h will determine if certain features + * are supported. Tests for these features need to be made after including + * stm32f4discovery.h. + */ + +#ifdef HAVE_RTC_DRIVER +# include +# include "stm32_rtc.h" +#endif + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_bringup + * + * Description: + * Perform architecture-specific initialization + * + * CONFIG_BOARD_INITIALIZE=y : + * Called from board_initialize(). + * + * CONFIG_BOARD_INITIALIZE=n && CONFIG_LIB_BOARDCTL=y : + * Called from the NSH library + * + ****************************************************************************/ + +int stm32_bringup(void) +{ + int ret = OK; + +#ifdef HAVE_USBHOST + /* Initialize USB host operation. stm32_usbhost_initialize() starts a thread + * will monitor for USB connection and disconnection events. + */ + + ret = stm32_usbhost_initialize(); + if (ret != OK) + { + uerr("ERROR: Failed to initialize USB host: %d\n", ret); + return ret; + } +#endif + +#ifdef CONFIG_FS_PROCFS + /* Mount the procfs file system */ + + ret = mount(NULL, STM32_PROCFS_MOUNTPOINT, "procfs", 0, NULL); + if (ret < 0) + { + serr("ERROR: Failed to mount procfs at %s: %d\n", + STM32_PROCFS_MOUNTPOINT, ret); + } +#endif + + return ret; +} diff --git a/configs/stm32f411e-disco/src/stm32_usb.c b/configs/stm32f411e-disco/src/stm32_usb.c new file mode 100644 index 0000000000..cd0a5afee1 --- /dev/null +++ b/configs/stm32f411e-disco/src/stm32_usb.c @@ -0,0 +1,352 @@ +/************************************************************************************ + * configs/stm32f411e-disco/src/stm32_usb.c + * + * Copyright (C) 2012-2013, 2015, 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Copyright (C) 2017 Brian Webb. All rights reserved. + * Author: Brian Webb + * + * 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 + +#include "up_arch.h" +#include "stm32.h" +#include "stm32_otgfs.h" +#include "stm32f411e-disco.h" + +#ifdef CONFIG_STM32_OTGFS + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +#if defined(CONFIG_USBDEV) || defined(CONFIG_USBHOST) +# define HAVE_USB 1 +#else +# warning "CONFIG_STM32_OTGFS is enabled but neither CONFIG_USBDEV nor CONFIG_USBHOST" +# undef HAVE_USB +#endif + +#ifndef CONFIG_STM32F411DISCO_USBHOST_PRIO +# define CONFIG_STM32F411DISCO_USBHOST_PRIO 100 +#endif + +#ifndef CONFIG_STM32F411DISCO_USBHOST_STACKSIZE +# define CONFIG_STM32F411DISCO_USBHOST_STACKSIZE 1024 +#endif + +/************************************************************************************ + * Private Data + ************************************************************************************/ + +#ifdef CONFIG_USBHOST +static struct usbhost_connection_s *g_usbconn; +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: usbhost_waiter + * + * Description: + * Wait for USB devices to be connected. + * + ************************************************************************************/ + +#ifdef CONFIG_USBHOST +static int usbhost_waiter(int argc, char *argv[]) +{ + struct usbhost_hubport_s *hport; + + uinfo("Running\n"); + for (;;) + { + /* Wait for the device to change state */ + + DEBUGVERIFY(CONN_WAIT(g_usbconn, &hport)); + uinfo("%s\n", hport->connected ? "connected" : "disconnected"); + + /* Did we just become connected? */ + + if (hport->connected) + { + /* Yes.. enumerate the newly connected device */ + + (void)CONN_ENUMERATE(g_usbconn, hport); + } + } + + /* Keep the compiler from complaining */ + + return 0; +} +#endif + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_usbinitialize + * + * Description: + * Called from stm32_usbinitialize very early in inialization to setup USB-related + * GPIO pins for the STM32F411 Discovery board. + * + ************************************************************************************/ + +void stm32_usbinitialize(void) +{ + /* The OTG FS has an internal soft pull-up. No GPIO configuration is required */ + + /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */ + +#ifdef CONFIG_STM32_OTGFS + stm32_configgpio(GPIO_OTGFS_VBUS); + stm32_configgpio(GPIO_OTGFS_PWRON); + stm32_configgpio(GPIO_OTGFS_OVER); +#endif +} + +/*********************************************************************************** + * Name: stm32_usbhost_initialize + * + * Description: + * Called at application startup time to initialize the USB host functionality. + * This function will start a thread that will monitor for device + * connection/disconnection events. + * + ***********************************************************************************/ + +#ifdef CONFIG_USBHOST +int stm32_usbhost_initialize(void) +{ + int pid; +#if defined(CONFIG_USBHOST_HUB) || defined(CONFIG_USBHOST_MSC) || \ + defined(CONFIG_USBHOST_HIDKBD) || defined(CONFIG_USBHOST_HIDMOUSE) || \ + defined(CONFIG_USBHOST_XBOXCONTROLLER) + int ret; +#endif + + /* First, register all of the class drivers needed to support the drivers + * that we care about: + */ + + uinfo("Register class drivers\n"); + +#ifdef CONFIG_USBHOST_HUB + /* Initialize USB hub class support */ + + ret = usbhost_hub_initialize(); + if (ret < 0) + { + uerr("ERROR: usbhost_hub_initialize failed: %d\n", ret); + } +#endif + +#ifdef CONFIG_USBHOST_MSC + /* Register the USB mass storage class class */ + + ret = usbhost_msc_initialize(); + if (ret != OK) + { + uerr("ERROR: Failed to register the mass storage class: %d\n", ret); + } +#endif + +#ifdef CONFIG_USBHOST_CDCACM + /* Register the CDC/ACM serial class */ + + ret = usbhost_cdcacm_initialize(); + if (ret != OK) + { + uerr("ERROR: Failed to register the CDC/ACM serial class: %d\n", ret); + } +#endif + +#ifdef CONFIG_USBHOST_HIDKBD + /* Initialize the HID keyboard class */ + + ret = usbhost_kbdinit(); + if (ret != OK) + { + uerr("ERROR: Failed to register the HID keyboard class\n"); + } +#endif + +#ifdef CONFIG_USBHOST_HIDMOUSE + /* Initialize the HID mouse class */ + + ret = usbhost_mouse_init(); + if (ret != OK) + { + uerr("ERROR: Failed to register the HID mouse class\n"); + } +#endif + +#ifdef CONFIG_USBHOST_XBOXCONTROLLER + /* Initialize the HID mouse class */ + + ret = usbhost_xboxcontroller_init(); + if (ret != OK) + { + uerr("ERROR: Failed to register the XBox Controller class\n"); + } +#endif + + /* Then get an instance of the USB host interface */ + + uinfo("Initialize USB host\n"); + g_usbconn = stm32_otgfshost_initialize(0); + if (g_usbconn) + { + /* Start a thread to handle device connection. */ + + uinfo("Start usbhost_waiter\n"); + + pid = task_create("usbhost", CONFIG_STM32F411DISCO_USBHOST_PRIO, + CONFIG_STM32F411DISCO_USBHOST_STACKSIZE, + (main_t)usbhost_waiter, (FAR char * const *)NULL); + return pid < 0 ? -ENOEXEC : OK; + } + + return -ENODEV; +} +#endif + +/*********************************************************************************** + * Name: stm32_usbhost_vbusdrive + * + * Description: + * Enable/disable driving of VBUS 5V output. This function must be provided be + * each platform that implements the STM32 OTG FS host interface + * + * "On-chip 5 V VBUS generation is not supported. For this reason, a charge pump + * or, if 5 V are available on the application board, a basic power switch, must + * be added externally to drive the 5 V VBUS line. The external charge pump can + * be driven by any GPIO output. When the application decides to power on VBUS + * using the chosen GPIO, it must also set the port power bit in the host port + * control and status register (PPWR bit in OTG_FS_HPRT). + * + * "The application uses this field to control power to this port, and the core + * clears this bit on an overcurrent condition." + * + * Input Parameters: + * iface - For future growth to handle multiple USB host interface. Should be zero. + * enable - true: enable VBUS power; false: disable VBUS power + * + * Returned Value: + * None + * + ***********************************************************************************/ + +#ifdef CONFIG_USBHOST +void stm32_usbhost_vbusdrive(int iface, bool enable) +{ + DEBUGASSERT(iface == 0); + + if (enable) + { + /* Enable the Power Switch by driving the enable pin low */ + + stm32_gpiowrite(GPIO_OTGFS_PWRON, false); + } + else + { + /* Disable the Power Switch by driving the enable pin high */ + + stm32_gpiowrite(GPIO_OTGFS_PWRON, true); + } +} +#endif + +/************************************************************************************ + * Name: stm32_setup_overcurrent + * + * Description: + * Setup to receive an interrupt-level callback if an overcurrent condition is + * detected. + * + * Input Parameter: + * handler - New overcurrent interrupt handler + * arg - The argument provided for the interrupt handler + * + * Returned value: + * Zero (OK) is returned on success. Otherwise, a negated errno value is returned + * to indicate the nature of the failure. + * + ************************************************************************************/ + +#ifdef CONFIG_USBHOST +int stm32_setup_overcurrent(xcpt_t handler, void *arg) +{ + return stm32_gpiosetevent(GPIO_OTGFS_OVER, true, true, true, handler, arg); +} +#endif + +/************************************************************************************ + * Name: stm32_usbsuspend + * + * Description: + * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is + * used. This function is called whenever the USB enters or leaves suspend mode. + * This is an opportunity for the board logic to shutdown clocks, power, etc. + * while the USB is suspended. + * + ************************************************************************************/ + +#ifdef CONFIG_USBDEV +void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) +{ + uinfo("resume: %d\n", resume); +} +#endif + +#endif /* CONFIG_STM32_OTGFS */ diff --git a/configs/stm32f411e-disco/src/stm32f411e-disco.h b/configs/stm32f411e-disco/src/stm32f411e-disco.h index 5425f291bd..e679b03a4e 100644 --- a/configs/stm32f411e-disco/src/stm32f411e-disco.h +++ b/configs/stm32f411e-disco/src/stm32f411e-disco.h @@ -85,6 +85,48 @@ #define GPIO_SPI1_SCK_OFF (GPIO_INPUT | GPIO_PULLDOWN | \ GPIO_PORTA | GPIO_PIN5) +/* Assume that we have everything */ + +#define HAVE_USBDEV 1 +#define HAVE_USBHOST 1 +#define HAVE_USBMONITOR 1 +#define HAVE_SDIO 1 +#define HAVE_RTC_DRIVER 1 +#define HAVE_ELF 1 +#define HAVE_NETMONITOR 1 + +/* USB OTG FS + * + * PA9 OTG_FS_VBUS VBUS sensing (also connected to the green LED) + * PC0 OTG_FS_PowerSwitchOn + * PD5 OTG_FS_Overcurrent + */ + +#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|\ + GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN9) +#define GPIO_OTGFS_PWRON (GPIO_OUTPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|\ + GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN0) + +#ifdef CONFIG_USBHOST +# define GPIO_OTGFS_OVER (GPIO_INPUT|GPIO_EXTI|GPIO_FLOAT|\ + GPIO_SPEED_100MHz|GPIO_PUSHPULL|\ + GPIO_PORTD|GPIO_PIN5) + +#else +# define GPIO_OTGFS_OVER (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|\ + GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN5) +#endif + +/* procfs File System */ + +#ifdef CONFIG_FS_PROCFS +# ifdef CONFIG_NSH_PROC_MOUNTPOINT +# define STM32_PROCFS_MOUNTPOINT CONFIG_NSH_PROC_MOUNTPOINT +# else +# define STM32_PROCFS_MOUNTPOINT "/proc" +# endif +#endif + /************************************************************************************ * Public Data ************************************************************************************/ @@ -112,14 +154,47 @@ extern struct spi_dev_s *g_spi2; void stm32_spidev_initialize(void); -/************************************************************************************ +/**************************************************************************** * Name: stm32_usbinitialize * * Description: - * Called to setup USB-related GPIO pins. + * Called from stm32_usbinitialize very early in initialization to setup + * USB-related GPIO pins for the STM32F4Discovery board. * - ************************************************************************************/ + ****************************************************************************/ +#ifdef CONFIG_STM32_OTGFS void stm32_usbinitialize(void); +#endif + +/**************************************************************************** + * Name: stm32_usbhost_initialize + * + * Description: + * Called at application startup time to initialize the USB host + * functionality. This function will start a thread that will monitor for + * device connection/disconnection events. + * + ****************************************************************************/ + +#if defined(CONFIG_STM32_OTGFS) && defined(CONFIG_USBHOST) +int stm32_usbhost_initialize(void); +#endif + +/**************************************************************************** + * Name: stm32_bringup + * + * Description: + * Perform architecture-specific initialization + * + * CONFIG_BOARD_INITIALIZE=y : + * Called from board_initialize(). + * + * CONFIG_BOARD_INITIALIZE=y && CONFIG_LIB_BOARDCTL=y : + * Called from the NSH library + * + ****************************************************************************/ + +int stm32_bringup(void); #endif /* __CONFIGS_STM32F411E_DISCO_SRC_STM32F411E_DISCO_H */ -- GitLab From 7e293b28eeafae0be9e711e53317f9607d5c1d9c Mon Sep 17 00:00:00 2001 From: Thomas Keh Date: Thu, 13 Apr 2017 13:07:03 +0200 Subject: [PATCH 421/990] TUN driver: Implement TAP (OSI layer 2) mode. Enable by setting the IFF_TAP flag instead of the IFF_TUN flag in ifr_flags. --- drivers/net/tun.c | 17 ++++++++++++++++- net/netdev/netdev_register.c | 2 +- 2 files changed, 17 insertions(+), 2 deletions(-) diff --git a/drivers/net/tun.c b/drivers/net/tun.c index 4763087162..65d60e9fe0 100644 --- a/drivers/net/tun.c +++ b/drivers/net/tun.c @@ -1159,7 +1159,7 @@ static int tun_ioctl(FAR struct file *filep, int cmd, unsigned long arg) int intf; FAR struct ifreq *ifr = (FAR struct ifreq *)arg; - if (!ifr || (ifr->ifr_flags & IFF_MASK) != IFF_TUN) + if (!ifr || ((ifr->ifr_flags & IFF_MASK) != IFF_TUN && (ifr->ifr_flags & IFF_MASK) != IFF_TAP)) { return -EINVAL; } @@ -1191,6 +1191,21 @@ static int tun_ioctl(FAR struct file *filep, int cmd, unsigned long arg) priv = filep->f_priv; strncpy(ifr->ifr_name, priv->dev.d_ifname, IFNAMSIZ); + if ((ifr->ifr_flags & IFF_MASK) == IFF_TAP) + { + /* TAP device -> handling raw Ethernet packets + * -> set appropriate Ethernet header length + */ + priv->dev.d_llhdrlen = ETH_HDRLEN; + } + else if ((ifr->ifr_flags & IFF_MASK) == IFF_TUN) + { + /* TUN device -> handling an application data stream + * -> no header + */ + priv->dev.d_llhdrlen = 0; + } + tundev_unlock(tun); return OK; diff --git a/net/netdev/netdev_register.c b/net/netdev/netdev_register.c index 737d51195b..a3de997c85 100644 --- a/net/netdev/netdev_register.c +++ b/net/netdev/netdev_register.c @@ -251,7 +251,7 @@ int netdev_register(FAR struct net_driver_s *dev, enum net_lltype_e lltype) #ifdef CONFIG_NET_TUN case NET_LL_TUN: /* Virtual Network Device (TUN) */ - dev->d_llhdrlen = 0; + dev->d_llhdrlen = 0; /* this will be overwritten by tun_ioctl if used as a TAP (layer 2) device */ dev->d_mtu = CONFIG_NET_TUN_MTU; #ifdef CONFIG_NET_TCP dev->d_recvwndo = CONFIG_NET_TUN_TCP_RECVWNDO; -- GitLab From ad9321b7b75f434de7a203b29e83ed3da66ac4d3 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 13 Apr 2017 06:16:03 -0600 Subject: [PATCH 422/990] Trivial changes from review of last PR --- drivers/net/tun.c | 11 ++++++++++- net/netdev/netdev_register.c | 3 ++- 2 files changed, 12 insertions(+), 2 deletions(-) diff --git a/drivers/net/tun.c b/drivers/net/tun.c index 65d60e9fe0..968a9e2122 100644 --- a/drivers/net/tun.c +++ b/drivers/net/tun.c @@ -1159,7 +1159,12 @@ static int tun_ioctl(FAR struct file *filep, int cmd, unsigned long arg) int intf; FAR struct ifreq *ifr = (FAR struct ifreq *)arg; - if (!ifr || ((ifr->ifr_flags & IFF_MASK) != IFF_TUN && (ifr->ifr_flags & IFF_MASK) != IFF_TAP)) +#ifdef CONFIG_NET_MULTILINK + if (!ifr || ((ifr->ifr_flags & IFF_MASK) != IFF_TUN && + (ifr->ifr_flags & IFF_MASK) != IFF_TAP)) +#else + if (!ifr || (ifr->ifr_flags & IFF_MASK) != IFF_TUN) +#endif { return -EINVAL; } @@ -1191,11 +1196,13 @@ static int tun_ioctl(FAR struct file *filep, int cmd, unsigned long arg) priv = filep->f_priv; strncpy(ifr->ifr_name, priv->dev.d_ifname, IFNAMSIZ); +#ifdef CONFIG_NET_MULTILINK if ((ifr->ifr_flags & IFF_MASK) == IFF_TAP) { /* TAP device -> handling raw Ethernet packets * -> set appropriate Ethernet header length */ + priv->dev.d_llhdrlen = ETH_HDRLEN; } else if ((ifr->ifr_flags & IFF_MASK) == IFF_TUN) @@ -1203,8 +1210,10 @@ static int tun_ioctl(FAR struct file *filep, int cmd, unsigned long arg) /* TUN device -> handling an application data stream * -> no header */ + priv->dev.d_llhdrlen = 0; } +#endif tundev_unlock(tun); diff --git a/net/netdev/netdev_register.c b/net/netdev/netdev_register.c index a3de997c85..01a61b5b8e 100644 --- a/net/netdev/netdev_register.c +++ b/net/netdev/netdev_register.c @@ -251,7 +251,8 @@ int netdev_register(FAR struct net_driver_s *dev, enum net_lltype_e lltype) #ifdef CONFIG_NET_TUN case NET_LL_TUN: /* Virtual Network Device (TUN) */ - dev->d_llhdrlen = 0; /* this will be overwritten by tun_ioctl if used as a TAP (layer 2) device */ + dev->d_llhdrlen = 0; /* This will be overwritten by tun_ioctl + * if used as a TAP (layer 2) device */ dev->d_mtu = CONFIG_NET_TUN_MTU; #ifdef CONFIG_NET_TCP dev->d_recvwndo = CONFIG_NET_TUN_TCP_RECVWNDO; -- GitLab From 39b62c6b46780fd7f1d383a63c1edf74002659f8 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 13 Apr 2017 06:50:33 -0600 Subject: [PATCH 423/990] Changes from review of last PR --- configs/nucleo-f4x1re/src/stm32_appinit.c | 6 --- configs/nucleo-l476rg/src/stm32_appinit.c | 6 --- configs/stm32f411e-disco/Kconfig | 1 - configs/stm32f411e-disco/src/Makefile | 2 +- configs/stm32f411e-disco/src/stm32_appinit.c | 10 ++-- configs/stm32f411e-disco/src/stm32_boot.c | 11 +++-- configs/stm32f411e-disco/src/stm32_bringup.c | 31 ++----------- configs/stm32f411e-disco/src/stm32_usb.c | 7 +-- .../stm32f411e-disco/src/stm32f411e-disco.h | 46 ++++++++----------- configs/stm32l476-mdk/src/stm32_appinit.c | 6 --- configs/stm32l476vg-disco/src/stm32_appinit.c | 18 +++----- 11 files changed, 42 insertions(+), 102 deletions(-) diff --git a/configs/nucleo-f4x1re/src/stm32_appinit.c b/configs/nucleo-f4x1re/src/stm32_appinit.c index 5845ad169f..a76eba4b59 100644 --- a/configs/nucleo-f4x1re/src/stm32_appinit.c +++ b/configs/nucleo-f4x1re/src/stm32_appinit.c @@ -102,12 +102,6 @@ int board_app_initialize(uintptr_t arg) { int ret = OK; - /* Configure CPU load estimation */ - -#ifdef CONFIG_SCHED_INSTRUMENTATION - cpuload_initialize_once(); -#endif - #ifdef HAVE_MMCSD /* First, get an instance of the SDIO interface */ diff --git a/configs/nucleo-l476rg/src/stm32_appinit.c b/configs/nucleo-l476rg/src/stm32_appinit.c index ceaa3a76f5..f66fcdb1ec 100644 --- a/configs/nucleo-l476rg/src/stm32_appinit.c +++ b/configs/nucleo-l476rg/src/stm32_appinit.c @@ -120,12 +120,6 @@ int board_app_initialize(uintptr_t arg) (void)ret; -#ifdef CONFIG_SCHED_INSTRUMENTATION - /* Configure CPU load estimation */ - - cpuload_initialize_once(); -#endif - #ifdef HAVE_PROC /* Mount the proc filesystem */ diff --git a/configs/stm32f411e-disco/Kconfig b/configs/stm32f411e-disco/Kconfig index 205dc95fa2..4e51f7f5dd 100644 --- a/configs/stm32f411e-disco/Kconfig +++ b/configs/stm32f411e-disco/Kconfig @@ -15,5 +15,4 @@ config STM32F411DISCO_USBHOST_PRIO default 100 depends on USBHOST - endif diff --git a/configs/stm32f411e-disco/src/Makefile b/configs/stm32f411e-disco/src/Makefile index 3635386d27..7cc95d6a5d 100644 --- a/configs/stm32f411e-disco/src/Makefile +++ b/configs/stm32f411e-disco/src/Makefile @@ -1,7 +1,7 @@ ############################################################################ # configs/stm32f411e-disco/src/Makefile # -# Copyright (C) 2016 Gregory Nutt. All rights reserved. +# Copyright (C) 2016-2017 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without diff --git a/configs/stm32f411e-disco/src/stm32_appinit.c b/configs/stm32f411e-disco/src/stm32_appinit.c index 9228ec0366..984a3d9ab4 100644 --- a/configs/stm32f411e-disco/src/stm32_appinit.c +++ b/configs/stm32f411e-disco/src/stm32_appinit.c @@ -84,11 +84,11 @@ int board_app_initialize(uintptr_t arg) { -#ifdef CONFIG_SCHED_INSTRUMENTATION - /* Configure CPU load estimation */ - - cpuload_initialize_once(); -#endif +#ifndef CONFIG_BOARD_INITIALIZE + /* Perform board-specific initialization */ + return stm32_bringup(); +#else return OK; +#endif } diff --git a/configs/stm32f411e-disco/src/stm32_boot.c b/configs/stm32f411e-disco/src/stm32_boot.c index 6de88de6a9..208f9b9a75 100644 --- a/configs/stm32f411e-disco/src/stm32_boot.c +++ b/configs/stm32f411e-disco/src/stm32_boot.c @@ -72,17 +72,18 @@ void stm32_boardinitialize(void) board_autoled_initialize(); #endif -#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || defined(CONFIG_STM32_SPI3) - /* Configure SPI chip selects if 1) SP2 is not disabled, and 2) the weak function - * stm32_spidev_initialize() has been brought into the link. +#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || \ + defined(CONFIG_STM32_SPI3) + /* Configure SPI chip selects if 1) SP2 is not disabled, and 2) the + * weak function stm32_spidev_initialize() has been brought into the link. */ stm32_spidev_initialize(); #endif #ifdef CONFIG_STM32_OTGFS - /* Initialize USB if the 1) OTG FS controller is in the configuration and 2) - * disabled. Presumably either CONFIG_USBDEV or CONFIG_USBHOST is also selected. + /* Initialize USB if the OTG FS controller is in the configuration. + * Presumably either CONFIG_USBDEV or CONFIG_USBHOST is also selected. */ stm32_usbinitialize(); diff --git a/configs/stm32f411e-disco/src/stm32_bringup.c b/configs/stm32f411e-disco/src/stm32_bringup.c index be0d587123..22c0ef501d 100644 --- a/configs/stm32f411e-disco/src/stm32_bringup.c +++ b/configs/stm32f411e-disco/src/stm32_bringup.c @@ -1,7 +1,7 @@ /**************************************************************************** - * config/stm32f4discovery/src/stm32_bringup.c + * config/stm32f411e-disco/src/stm32_bringup.c * - * Copyright (C) 2012, 2014-2016 Gregory Nutt. All rights reserved. + * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -40,16 +40,7 @@ #include #include -#include -#include #include -#include - -#ifdef CONFIG_USBMONITOR -# include -#endif - -#include #include "stm32.h" @@ -59,20 +50,6 @@ #include "stm32f411e-disco.h" -/* Conditional logic in stm32f4discover.h will determine if certain features - * are supported. Tests for these features need to be made after including - * stm32f4discovery.h. - */ - -#ifdef HAVE_RTC_DRIVER -# include -# include "stm32_rtc.h" -#endif - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - /**************************************************************************** * Public Functions ****************************************************************************/ @@ -95,7 +72,7 @@ int stm32_bringup(void) { int ret = OK; -#ifdef HAVE_USBHOST +#if defined(CONFIG_STM32_OTGFS) && defined(CONFIG_USBHOST) /* Initialize USB host operation. stm32_usbhost_initialize() starts a thread * will monitor for USB connection and disconnection events. */ @@ -114,7 +91,7 @@ int stm32_bringup(void) ret = mount(NULL, STM32_PROCFS_MOUNTPOINT, "procfs", 0, NULL); if (ret < 0) { - serr("ERROR: Failed to mount procfs at %s: %d\n", + ferr("ERROR: Failed to mount procfs at %s: %d\n", STM32_PROCFS_MOUNTPOINT, ret); } #endif diff --git a/configs/stm32f411e-disco/src/stm32_usb.c b/configs/stm32f411e-disco/src/stm32_usb.c index cd0a5afee1..95cc3da81d 100644 --- a/configs/stm32f411e-disco/src/stm32_usb.c +++ b/configs/stm32f411e-disco/src/stm32_usb.c @@ -1,7 +1,7 @@ /************************************************************************************ * configs/stm32f411e-disco/src/stm32_usb.c * - * Copyright (C) 2012-2013, 2015, 2017 Gregory Nutt. All rights reserved. + * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Copyright (C) 2017 Brian Webb. All rights reserved. @@ -65,11 +65,8 @@ * Pre-processor Definitions ************************************************************************************/ -#if defined(CONFIG_USBDEV) || defined(CONFIG_USBHOST) -# define HAVE_USB 1 -#else +#if !defined(CONFIG_USBDEV) && !defined(CONFIG_USBHOST) # warning "CONFIG_STM32_OTGFS is enabled but neither CONFIG_USBDEV nor CONFIG_USBHOST" -# undef HAVE_USB #endif #ifndef CONFIG_STM32F411DISCO_USBHOST_PRIO diff --git a/configs/stm32f411e-disco/src/stm32f411e-disco.h b/configs/stm32f411e-disco/src/stm32f411e-disco.h index e679b03a4e..1d78f4c6b3 100644 --- a/configs/stm32f411e-disco/src/stm32f411e-disco.h +++ b/configs/stm32f411e-disco/src/stm32f411e-disco.h @@ -1,4 +1,4 @@ -/************************************************************************************ +/**************************************************************************** * configs/stm32f411e-disco/src/stm32f411e-disco.h * * Copyright (C) 2016 Gregory Nutt. All rights reserved. @@ -32,28 +32,28 @@ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * - ************************************************************************************/ + ****************************************************************************/ #ifndef __CONFIGS_STM32F411E_DISCO_SRC_STM32F411E_DISCO_H #define __CONFIGS_STM32F411E_DISCO_SRC_STM32F411E_DISCO_H -/************************************************************************************ +/**************************************************************************** * Included Files - ************************************************************************************/ + ****************************************************************************/ #include #include #include -/************************************************************************************ +/**************************************************************************** * Pre-processor Definitions - ************************************************************************************/ -/* Configuration ********************************************************************/ + ****************************************************************************/ +/* Configuration ************************************************************/ -/* LED. User LD2: the green LED is a user LED connected to Arduino signal D13 - * corresponding to MCU I/O PA5 (pin 21) or PB13 (pin 34) depending on the STM32 - * target. +/* LED. User LD2: the green LED is a user LED connected to Arduino signal + * D13 corresponding to MCU I/O PA5 (pin 21) or PB13 (pin 34) depending on + * the STM32 target. * * - When the I/O is HIGH value, the LED is on. * - When the I/O is LOW, the LED is off. @@ -85,16 +85,6 @@ #define GPIO_SPI1_SCK_OFF (GPIO_INPUT | GPIO_PULLDOWN | \ GPIO_PORTA | GPIO_PIN5) -/* Assume that we have everything */ - -#define HAVE_USBDEV 1 -#define HAVE_USBHOST 1 -#define HAVE_USBMONITOR 1 -#define HAVE_SDIO 1 -#define HAVE_RTC_DRIVER 1 -#define HAVE_ELF 1 -#define HAVE_NETMONITOR 1 - /* USB OTG FS * * PA9 OTG_FS_VBUS VBUS sensing (also connected to the green LED) @@ -127,9 +117,9 @@ # endif #endif -/************************************************************************************ +/**************************************************************************** * Public Data - ************************************************************************************/ + ****************************************************************************/ /* Global driver instances */ @@ -140,17 +130,17 @@ extern struct spi_dev_s *g_spi1; extern struct spi_dev_s *g_spi2; #endif -/************************************************************************************ +/**************************************************************************** * Public Functions - ************************************************************************************/ + ****************************************************************************/ -/************************************************************************************ +/**************************************************************************** * Name: stm32_spidev_initialize * * Description: * Called to configure SPI chip select GPIO pins. * - ************************************************************************************/ + ****************************************************************************/ void stm32_spidev_initialize(void); @@ -158,7 +148,7 @@ void stm32_spidev_initialize(void); * Name: stm32_usbinitialize * * Description: - * Called from stm32_usbinitialize very early in initialization to setup + * Called from stm32_boardinitialize very early in initialization to setup * USB-related GPIO pins for the STM32F4Discovery board. * ****************************************************************************/ @@ -172,7 +162,7 @@ void stm32_usbinitialize(void); * * Description: * Called at application startup time to initialize the USB host - * functionality. This function will start a thread that will monitor for + * functionality. This function will start a thread that will monitor for * device connection/disconnection events. * ****************************************************************************/ diff --git a/configs/stm32l476-mdk/src/stm32_appinit.c b/configs/stm32l476-mdk/src/stm32_appinit.c index 99a42e0a4a..2633d47302 100644 --- a/configs/stm32l476-mdk/src/stm32_appinit.c +++ b/configs/stm32l476-mdk/src/stm32_appinit.c @@ -113,12 +113,6 @@ int board_app_initialize(uintptr_t arg) (void)ret; -#ifdef CONFIG_SCHED_INSTRUMENTATION - /* Configure CPU load estimation */ - - cpuload_initialize_once(); -#endif - #ifdef HAVE_PROC /* mount the proc filesystem */ diff --git a/configs/stm32l476vg-disco/src/stm32_appinit.c b/configs/stm32l476vg-disco/src/stm32_appinit.c index 4cccfd5039..40b204e59e 100644 --- a/configs/stm32l476vg-disco/src/stm32_appinit.c +++ b/configs/stm32l476vg-disco/src/stm32_appinit.c @@ -140,12 +140,6 @@ FAR struct mtd_dev_s *mtd_temp; int ret; (void)ret; - -#ifdef CONFIG_SCHED_INSTRUMENTATION - /* Configure CPU load estimation */ - - cpuload_initialize_once(); -#endif #ifdef HAVE_PROC /* mount the proc filesystem */ @@ -208,7 +202,7 @@ FAR struct mtd_dev_s *mtd_temp; return ret; } g_mtd_fs = mtd_temp; - + #ifdef CONFIG_MTD_PARTITION { FAR struct mtd_geometry_s geo; @@ -342,7 +336,7 @@ int board_ioctl(unsigned int cmd, uintptr_t arg) * 6 = CONFIG_N25QXXX_DUMMIES; * 0xeb = N25QXXX_FAST_READ_QUADIO; */ - + meminfo.flags = QSPIMEM_READ | QSPIMEM_QUADIO; meminfo.addrlen = 3; meminfo.dummies = 6; //CONFIG_N25QXXX_DUMMIES; @@ -350,17 +344,17 @@ int board_ioctl(unsigned int cmd, uintptr_t arg) meminfo.addr = 0; meminfo.buflen = 0; meminfo.buffer = NULL; - + stm32l4_qspi_enter_memorymapped(g_qspi, &meminfo, 80000000); } break; - + case BIOC_EXIT_MEMMAP: stm32l4_qspi_exit_memorymapped(g_qspi); break; - + #endif - + default: return -EINVAL; break; -- GitLab From 015ae22f28256aabfe13087236aa21e06ca548ec Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 13 Apr 2017 07:35:48 -0600 Subject: [PATCH 424/990] ieee802.15.4 radio: Add data structure definitions for Radio IOCTLs. --- .../wireless/ieee802154/ieee802154_radio.h | 73 +++++++++++++++++-- 1 file changed, 66 insertions(+), 7 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_radio.h b/include/nuttx/wireless/ieee802154/ieee802154_radio.h index 0f8b7b187e..79ad5ec6dd 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_radio.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_radio.h @@ -43,9 +43,15 @@ ****************************************************************************/ #include + #include #include #include + +#ifdef CONFIG_NET_6LOWPAN +# include +#endif + #include /**************************************************************************** @@ -97,6 +103,59 @@ * Public Types ****************************************************************************/ +/* Structures used with IEEE802.15.4 radio interface operations *************/ + +struct ieee802154_cca_s +{ + uint8_t use_ed : 1; /* CCA using ED */ + uint8_t use_cs : 1; /* CCA using carrier sense */ + uint8_t edth; /* Energy detection threshold for CCA */ + uint8_t csth; /* Carrier sense threshold for CCA */ +}; + +struct ieee802154_packet_s +{ + uint8_t len; + uint8_t data[127]; + uint8_t lqi; + uint8_t rssi; +}; + +/* IOCTL command data argument **********************************************/ + +/* A pointer to this structure is passed as the argument of each IOCTL + * command. + */ + +union ieee802154_radioarg_u +{ + uint8_t channel; /* PHY802154IOC_GET/SET_CHAN */ + uint16_t panid; /* PHY802154IOC_GET/SET_PANID */ + uint16_t saddr; /* PHY802154IOC_GET/SET_SADDR */ + uint16_t laddr; /* PHY802154IOC_GET/SET_EADDR */ + bool promisc; /* PHY802154IOC_GET/SET_EADDR */ + bool devmode; /* PHY802154IOC_GET/SET_DEVMODE */ + int32_t txpwr; /* PHY802154IOC_GET/SET_TXPWR */ + bool energy /* PHY802154IOC_ENERGYDETECT */ + struct ieee802154_cca_s cca; /* PHY802154IOC_GET/SET_CCA */ +}; + +#ifdef CONFIG_NET_6LOWPAN +/* For the case of network IOCTLs, the network IOCTL to the MAC network + * driver will include a device name like "wpan0" as the destination of + * the IOCTL command. The MAC layer will forward only the payload union + * to the radio IOCTL method. + */ + +struct ieee802154_netradio_s +{ + char ifr_name[IFNAMSIZ]; /* Interface name, e.g. "wpan0" */ + union ieee802154_radioarg_u /* Data payload */ +}; +#endif + +/* IEEE802.15.4 Radio Interface Operations **********************************/ + struct ieee802154_cca_s { uint8_t use_ed : 1; /* CCA using ED */ @@ -105,12 +164,12 @@ struct ieee802154_cca_s uint8_t csth; /* Carrier sense threshold for CCA */ }; -struct ieee802154_packet_s -{ - uint8_t len; - uint8_t data[127]; - uint8_t lqi; - uint8_t rssi; +struct ieee802154_packet_s +{ + uint8_t len; + uint8_t data[127]; + uint8_t lqi; + uint8_t rssi; }; struct ieee802154_radio_s; @@ -163,7 +222,7 @@ struct ieee802154_radioops_s CODE int (*transmit)(FAR struct ieee802154_radio_s *dev, FAR struct ieee802154_packet_s *packet); - /*TODO beacon/sf order*/ + /* TODO beacon/sf order */ }; struct ieee802154_radio_s -- GitLab From 241da3ec49fb7d05a1384ba6a9f9b49a255eb24e Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 13 Apr 2017 08:14:58 -0600 Subject: [PATCH 425/990] ieee802.15.4 MAC: Add data structure definitions for MAC IOCTLs. --- .../wireless/ieee802154/ieee802154_mac.h | 143 +++++++++++++++++- 1 file changed, 142 insertions(+), 1 deletion(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index 55830d70fc..db06acd083 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -51,6 +51,10 @@ #include #include +#ifdef CONFIG_NET_6LOWPAN +# include +#endif + #include /**************************************************************************** @@ -181,6 +185,10 @@ /* IEEE 802.15.4 MAC PIB Attribut Defaults */ +/* Definitions used by IOCTL calls */ + +#define MAX_ORPHAN_ADDR 32 /* REVISIT */ + // TODO: Add macros /**************************************************************************** @@ -740,7 +748,140 @@ struct ieee802154_beaconnotify_ind_s (sizeof(struct ieee802154_beaconnotify_ind_s) \ - IEEE802154_MAX_BEACON_PAYLOAD_LENGTH + (n)) -/* Operations */ +/* IOCTL data arguments *****************************************************/ + +/* Data returned with MAC802154IOC_MLME_ASSOC_RESPONSE */ + +struct ieee802154_assocresp_s +{ + uint8_t eadr; + uint16_t saddr; + int status; +}; + +/* Data provided to MAC802154IOC_MLME_GET_REQUEST */ + +struct ieee802154_getreq_s +{ + enum ieee802154_pib_attr_e attr; +}; + +/* Data provided to MAC802154IOC_MLME_GTS_REQUEST */ + +struct ieee802154_gtsreq_s +{ + uint8_t characteristics; +}; + +/* Data returned with MAC802154IOC_MLME_ORPHAN_RESPONSE */ + +struct ieee802154_orphanresp_s +{ + uint8_t orphanaddr[MAX_ORPHAN_ADDR]; + uint16_t saddr; + bool associated; +}; + +/* Data provided with MAC802154IOC_MLME_RESET_REQUEST */ + +struct ieee802154_resetreq_s +{ + bool setdefaults; +}; + +/* Data provided with MAC802154IOC_MLME_RXENABLE_REQUEST */ + +struct ieee802154_rxenabreq_s +{ + bool deferrable; + int ontime; + int duration; +}; + +/* Data provided with MAC802154IOC_MLME_SCAN_REQUEST */ + +struct ieee802154_scanreq_s +{ + uint8_t type; + uint32_t channels; + int duration; +}; + +/* Data provided with MAC802154IOC_MLME_SET_REQUEST */ + +struct ieee802154_setreq_s +{ + FAR uint8_t *value; + int valuelen; + int attribute; +}; + +/* Data provided with MAC802154IOC_MLME_START_REQUEST */ + +struct ieee802154_startreq_s +{ + int channel; + uint16_t panid; + uint8_t bo; + uint8_t fo; + bool coord; + bool batext; + bool realign; +}; + +/* Data provided with MAC802154IOC_MLME_SYNC_REQUEST */ + +struct ieee802154_syncreq_s +{ + int channel; + bool track; +}; + +/* Data provided with MAC802154IOC_MLME_POLL_REQUEST */ + +struct ieee802154_pollreq_s +{ + FAR uint8_t *coordaddr; +}; + +/* A pointer to this structure is passed as the argument of each IOCTL + * command. + */ + +union ieee802154_macarg_u +{ + struct ieee802154_assoc_req_s assocreq; /* MAC802154IOC_MLME_ASSOC_REQUEST */ + struct ieee802154_assocresp_s assocresp: /* MAC802154IOC_MLME_ASSOC_RESPONSE */ + struct ieee802154_disassoc_req_s disassocreq; /* MAC802154IOC_MLME_DISASSOC_REQUEST */ + struct ieee802154_mlmereq_s getreq; /* MAC802154IOC_MLME_GET_REQUEST */ + struct ieee802154_gtsreq_s gtsreq; /* MAC802154IOC_MLME_GTS_REQUEST */ + struct ieee802154_orphanresp_s orphanresp; /* MAC802154IOC_MLME_ORPHAN_RESPONSE */ + struct ieee802154_resetreq_s resetreq; /* MAC802154IOC_MLME_RESET_REQUEST */ + struct ieee802154_rxenabreq_s rxenabreq; /* MAC802154IOC_MLME_RXENABLE_REQUEST */ + struct ieee802154_scanreq_s scanreq; /* MAC802154IOC_MLME_SCAN_REQUEST */ + struct ieee802154_setreq_s setreq; /* MAC802154IOC_MLME_SET_REQUEST */ + struct ieee802154_startreq_s startreq; /* MAC802154IOC_MLME_START_REQUEST */ + struct ieee802154_syncreq_s syncreq; /* MAC802154IOC_MLME_SYNC_REQUEST */ + struct ieee802154_pollreq_s pollreq; /* MAC802154IOC_MLME_POLL_REQUEST */ + /* To be determined */ /* MAC802154IOC_MLME_DPS_REQUEST */ + /* To be determined */ /* MAC802154IOC_MLME_SOUNDING_REQUEST */ + /* To be determined */ /* MAC802154IOC_MLME_CALIBRATE_REQUEST */ +}; + +#ifdef CONFIG_NET_6LOWPAN +/* For the case of network IOCTLs, the network IOCTL to the MAC network + * driver will include a device name like "wpan0" as the destination of + * the IOCTL command. + */ + +struct ieee802154_netmac_s +{ + char ifr_name[IFNAMSIZ]; /* Interface name, e.g. "wpan0" */ + union ieee802154_macarg_u u; /* Data payload */ +}; +#endif + +/* MAC Interface Operations *************************************************/ struct ieee802154_mac_s; /* Forward reference */ -- GitLab From 32962fa6e39ef0f4d755530567335b59795fd42e Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 13 Apr 2017 08:17:34 -0600 Subject: [PATCH 426/990] Add missing field name --- include/nuttx/wireless/ieee802154/ieee802154_radio.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_radio.h b/include/nuttx/wireless/ieee802154/ieee802154_radio.h index 79ad5ec6dd..cbd014b0b1 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_radio.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_radio.h @@ -149,8 +149,8 @@ union ieee802154_radioarg_u struct ieee802154_netradio_s { - char ifr_name[IFNAMSIZ]; /* Interface name, e.g. "wpan0" */ - union ieee802154_radioarg_u /* Data payload */ + char ifr_name[IFNAMSIZ]; /* Interface name, e.g. "wpan0" */ + union ieee802154_radioarg_u u; /* Data payload */ }; #endif -- GitLab From 8288f53d4ea0184150459ca6d3ccfabcb7b43f0b Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 13 Apr 2017 09:13:16 -0600 Subject: [PATCH 427/990] ieee802154 radio: Implement IOCTL decode and dispatch in all radio drivers. --- drivers/wireless/ieee802154/at86rf23x.c | 73 ++++++++++++++++++- drivers/wireless/ieee802154/mrf24j40.c | 73 ++++++++++++++++++- .../wireless/ieee802154/ieee802154_radio.h | 20 ++--- 3 files changed, 155 insertions(+), 11 deletions(-) diff --git a/drivers/wireless/ieee802154/at86rf23x.c b/drivers/wireless/ieee802154/at86rf23x.c index 7b6193c0aa..ceebfe79f9 100644 --- a/drivers/wireless/ieee802154/at86rf23x.c +++ b/drivers/wireless/ieee802154/at86rf23x.c @@ -1154,10 +1154,81 @@ static int at86rf23x_getcca(FAR struct ieee802154_radio_s *ieee, static int at86rf23x_ioctl(FAR struct ieee802154_radio_s *ieee, int cmd, unsigned long arg) { - FAR struct at86rf23x_dev_s *dev = (FAR struct at86rf23x_dev_s *)ieee; + FAR struct at86rf23x_dev_s *dev = + (FAR struct at86rf23x_dev_s *)ieee; + FAR union ieee802154_radioarg_u *u; = + (FAR union ieee802154_radioarg_u *)((uintptr_t)arg) switch (cmd) { + case PHY802154IOC_SET_CHAN: + ret = at86rf23x_setchannel(ieee, u.channel); + break; + + case PHY802154IOC_GET_CHAN: + ret = at86rf23x_getchannel(ieee, &u.channel); + break; + + case PHY802154IOC_SET_PANID: + ret = at86rf23x_setpanid(ieee, u.panid); + break; + + case PHY802154IOC_GET_PANID: + ret = at86rf23x_getpanid(ieee, &u.panid); + break; + + case PHY802154IOC_SET_SADDR: + ret = at86rf23x_setsaddr(ieee, u.saddr); + break; + + case PHY802154IOC_GET_SADDR: + ret = at86rf23x_getsaddr(ieee, &u.saddr); + break; + + case PHY802154IOC_SET_EADDR: + ret = at86rf23x_seteaddr(ieee, u.eaddr); + break; + + case PHY802154IOC_GET_EADDR: + ret = at86rf23x_geteaddr(ieee, u.eaddr); + break; + + case PHY802154IOC_SET_PROMISC: + ret = at86rf23x_setpromisc(ieee, u.promisc); + break; + + case PHY802154IOC_GET_PROMISC: + ret = at86rf23x_getpromisc(ieee, &u.promisc); + break; + + case PHY802154IOC_SET_DEVMODE: + ret = at86rf23x_setdevmode(ieee, u.devmode); + break; + + case PHY802154IOC_GET_DEVMODE: + ret = at86rf23x_getdevmode(ieee, &u.devmode); + break; + + case PHY802154IOC_SET_TXPWR: + ret = at86rf23x_settxpower(ieee, u.txpwr); + break; + + case PHY802154IOC_GET_TXPWR: + ret = at86rf23x_gettxpower(ieee, &u.txpwr); + break; + + case PHY802154IOC_SET_CCA: + ret = at86rf23x_setcca(ieee, &u.cca); + break; + + case PHY802154IOC_GET_CCA: + ret = at86rf23x_getcca(ieee, &u.cca); + break; + + case PHY802154IOC_ENERGYDETECT: + ret = at86rf23x_energydetect(ieee, &u.energy); + break; + case 1000: return at86rf23x_regdump(dev); diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c index 9ede37739e..1f3f68bf98 100644 --- a/drivers/wireless/ieee802154/mrf24j40.c +++ b/drivers/wireless/ieee802154/mrf24j40.c @@ -991,10 +991,81 @@ static int mrf24j40_regdump(FAR struct mrf24j40_radio_s *dev) static int mrf24j40_ioctl(FAR struct ieee802154_radio_s *ieee, int cmd, unsigned long arg) { - FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; + FAR struct mrf24j40_radio_s *dev = + (FAR struct mrf24j40_radio_s *)ieee; + FAR union ieee802154_radioarg_u *u; = + (FAR union ieee802154_radioarg_u *)((uintptr_t)arg) switch(cmd) { + case PHY802154IOC_SET_CHAN: + ret = mrf24j40_setchannel(ieee, u.channel); + break; + + case PHY802154IOC_GET_CHAN: + ret = mrf24j40_getchannel(ieee, &u.channel); + break; + + case PHY802154IOC_SET_PANID: + ret = mrf24j40_setpanid(ieee, u.panid); + break; + + case PHY802154IOC_GET_PANID: + ret = mrf24j40_getpanid(ieee, &u.panid); + break; + + case PHY802154IOC_SET_SADDR: + ret = mrf24j40_setsaddr(ieee, u.saddr); + break; + + case PHY802154IOC_GET_SADDR: + ret = mrf24j40_getsaddr(ieee, &u.saddr); + break; + + case PHY802154IOC_SET_EADDR: + ret = mrf24j40_seteaddr(ieee, u.eaddr); + break; + + case PHY802154IOC_GET_EADDR: + ret = mrf24j40_geteaddr(ieee, u.eaddr); + break; + + case PHY802154IOC_SET_PROMISC: + ret = mrf24j40_setpromisc(ieee, u.promisc); + break; + + case PHY802154IOC_GET_PROMISC: + ret = mrf24j40_getpromisc(ieee, &u.promisc); + break; + + case PHY802154IOC_SET_DEVMODE: + ret = mrf24j40_setdevmode(ieee, u.devmode); + break; + + case PHY802154IOC_GET_DEVMODE: + ret = mrf24j40_getdevmode(ieee, &u.devmode); + break; + + case PHY802154IOC_SET_TXPWR: + ret = mrf24j40_settxpower(ieee, u.txpwr); + break; + + case PHY802154IOC_GET_TXPWR: + ret = mrf24j40_gettxpower(ieee, &u.txpwr); + break; + + case PHY802154IOC_SET_CCA: + ret = mrf24j40_setcca(ieee, &u.cca); + break; + + case PHY802154IOC_GET_CCA: + ret = mrf24j40_getcca(ieee, &u.cca); + break; + + case PHY802154IOC_ENERGYDETECT: + ret = mrf24j40_energydetect(ieee, &u.energy); + break; + case 1000: return mrf24j40_regdump(dev); diff --git a/include/nuttx/wireless/ieee802154/ieee802154_radio.h b/include/nuttx/wireless/ieee802154/ieee802154_radio.h index cbd014b0b1..af44f96445 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_radio.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_radio.h @@ -99,6 +99,8 @@ #define PHY802154IOC_ENERGYDETECT _PHY802154IOC(0x0011) +#define EADDR_SIZE 8 /* REVISIT */ + /**************************************************************************** * Public Types ****************************************************************************/ @@ -129,15 +131,15 @@ struct ieee802154_packet_s union ieee802154_radioarg_u { - uint8_t channel; /* PHY802154IOC_GET/SET_CHAN */ - uint16_t panid; /* PHY802154IOC_GET/SET_PANID */ - uint16_t saddr; /* PHY802154IOC_GET/SET_SADDR */ - uint16_t laddr; /* PHY802154IOC_GET/SET_EADDR */ - bool promisc; /* PHY802154IOC_GET/SET_EADDR */ - bool devmode; /* PHY802154IOC_GET/SET_DEVMODE */ - int32_t txpwr; /* PHY802154IOC_GET/SET_TXPWR */ - bool energy /* PHY802154IOC_ENERGYDETECT */ - struct ieee802154_cca_s cca; /* PHY802154IOC_GET/SET_CCA */ + uint8_t channel; /* PHY802154IOC_GET/SET_CHAN */ + uint16_t panid; /* PHY802154IOC_GET/SET_PANID */ + uint16_t saddr; /* PHY802154IOC_GET/SET_SADDR */ + uint8_t eaddr[EADDR_SIZE]; /* PHY802154IOC_GET/SET_EADDR */ + bool promisc; /* PHY802154IOC_GET/SET_EADDR */ + uint8_t devmode; /* PHY802154IOC_GET/SET_DEVMODE */ + int32_t txpwr; /* PHY802154IOC_GET/SET_TXPWR */ + bool energy /* PHY802154IOC_ENERGYDETECT */ + struct ieee802154_cca_s cca; /* PHY802154IOC_GET/SET_CCA */ }; #ifdef CONFIG_NET_6LOWPAN -- GitLab From 55c95442e17d968d62cc275ba9d57c7f2a8feb77 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 13 Apr 2017 09:53:38 -0600 Subject: [PATCH 428/990] drivers/net/skeleton.c: Add support for IOCTL handling. --- drivers/net/skeleton.c | 45 ++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 45 insertions(+) diff --git a/drivers/net/skeleton.c b/drivers/net/skeleton.c index bb1a543ff9..94380212f6 100644 --- a/drivers/net/skeleton.c +++ b/drivers/net/skeleton.c @@ -190,6 +190,9 @@ static int skel_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac); static void skel_ipv6multicast(FAR struct skel_driver_s *priv); #endif #endif +#ifdef CONFIG_NETDEV_IOCTL +static int skel_ioctl(FAR struct net_driver_s *dev, int cmd, long arg); +#endif /**************************************************************************** * Private Functions @@ -1073,6 +1076,45 @@ static void skel_ipv6multicast(FAR struct skel_driver_s *priv) } #endif /* CONFIG_NET_ICMPv6 */ +/**************************************************************************** + * Name: skel_ioctl + * + * Description: + * Handle network IOCTL commands directed to this device. + * + * Parameters: + * dev - Reference to the NuttX driver state structure + * cmd - The IOCTL command + * arg - The argument for the IOCTL command + * + * Returned Value: + * OK on success; Negated errno on failure. + * + * Assumptions: + * + ****************************************************************************/ + +#ifdef CONFIG_NETDEV_IOCTL +static int skel_ioctl(FAR struct net_driver_s *dev, int cmd, long arg) +{ + FAR struct skel_driver_s *priv = (FAR struct skel_driver_s *)dev->d_private; + int ret; + + /* Decode and dispatch the driver-specific IOCTL command */ + + switch (cmd) + { + /* Add cases here to support the IOCTL commands */ + + default: + nerr("ERROR: Unrecognized IOCTL command: %d\n", command); + return -ENOTTY; /* Special return value for this case */ + } + + return OK; +} +#endif + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -1124,6 +1166,9 @@ int skel_initialize(int intf) #ifdef CONFIG_NET_IGMP priv->sk_dev.d_addmac = skel_addmac; /* Add multicast MAC address */ priv->sk_dev.d_rmmac = skel_rmmac; /* Remove multicast MAC address */ +#endif +#ifdef CONFIG_NETDEV_IOCTL + priv->sk_dev.d_ioctl = skel_ioctl; /* Handle network IOCTL commands */ #endif priv->sk_dev.d_private = (FAR void *)g_skel; /* Used to recover private state from dev */ -- GitLab From fae1df31dca3203a367fd0a522a326106d279cf7 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 13 Apr 2017 10:18:57 -0600 Subject: [PATCH 429/990] ieee802.15.4 netdev: Add IOCTL support. --- .../wireless/ieee802154/ieee802154_mac.h | 5 ++ wireless/ieee802154/mac802154_netdev.c | 69 +++++++++++++++++++ 2 files changed, 74 insertions(+) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index db06acd083..acfcdac6db 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -959,6 +959,11 @@ struct ieee802154_macops_s CODE int (*rsp_orphan)(FAR struct ieee802154_mac_s *mac, FAR uint8_t *orphanaddr, uint16_t saddr, bool associated); + + /* IOCTL support */ + + CODE int (*ioctl)(FAR struct ieee802154_mac_s *mac, int cmd, + unsigned long arg); }; /* Notifications */ diff --git a/wireless/ieee802154/mac802154_netdev.c b/wireless/ieee802154/mac802154_netdev.c index 1f5f2335e1..f5b0aed51c 100644 --- a/wireless/ieee802154/mac802154_netdev.c +++ b/wireless/ieee802154/mac802154_netdev.c @@ -235,6 +235,9 @@ static int mac802154_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac static void mac802154_ipv6multicast(FAR struct mac802154_driver_s *priv); #endif #endif +#ifdef CONFIG_NETDEV_IOCTL +static int mac802154_ioctl(FAR struct net_driver_s *dev, int cmd, long arg); +#endif /**************************************************************************** * Private Functions @@ -1344,6 +1347,69 @@ static void mac802154_ipv6multicast(FAR struct mac802154_driver_s *priv) } #endif /* CONFIG_NET_ICMPv6 */ +/**************************************************************************** + * Name: mac802154_ioctl + * + * Description: + * Handle network IOCTL commands directed to this device. + * + * Parameters: + * dev - Reference to the NuttX driver state structure + * cmd - The IOCTL command + * arg - The argument for the IOCTL command + * + * Returned Value: + * OK on success; Negated errno on failure. + * + * Assumptions: + * + ****************************************************************************/ + +#ifdef CONFIG_NETDEV_IOCTL +static int mac802154_ioctl(FAR struct net_driver_s *dev, int cmd, long arg) +{ + FAR struct mac802154_driver_s *priv = (FAR struct mac802154_driver_s *)dev->d_private; + int ret = -EINVAL; + + /* Check for IOCTLs aimed at the IEEE802.15.4 MAC layer */ + + if (_MAC802154IOCVALID(cmd)) + { + FAR struct ieee802154_netmac_s *netmac = + (FAR struct ieee802154_netmac_s *)arg; + + if (netmac != NULL) + { + unsigned long macarg = (unsigned int)((uintptr_t)&netmac->u); + ret = priv->m8_mac.macops.ioctl(priv->m8_mac, cmd, macarg); + } + } + + /* No, check for IOCTLs aimed at the IEEE802.15.4 radio layer */ + + else if (_PHY802154IOCVALID(cmd)) + { + FAR struct ieee802154_netradio_s *netradio = + (FAR struct ieee802154_netradio_s *)arg; + + if (netradio != NULL) + { + unsigned long radioarg = (unsigned int)((uintptr_t)&netradio->u); + ret = priv->m8_mac.macops.ioctl(priv->m8_mac, cmd, radioarg); + } + } + + /* Okay, we have no idea what this command is.. just give to the + * IEEE802.15.4 MAC layer without modification. + */ + + else + { + ret = priv->m8_mac.macops.ioctl(priv->m8_mac, cmd, arg); + } +} +#endif + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -1406,6 +1472,9 @@ int mac802154netdev_register(FAR struct ieee802154_mac_s *mac); #ifdef CONFIG_NET_IGMP dev->d_addmac = mac802154_addmac; /* Add multicast MAC address */ dev->d_rmmac = mac802154_rmmac; /* Remove multicast MAC address */ +#endif + #ifdef CONFIG_NETDEV_IOCTL + dev->d_ioctl = mac802154_ioctl; /* Handle network IOCTL commands */ #endif dev->d_private = (FAR void *)priv; /* Used to recover private state from dev */ -- GitLab From 6b8a8bda355dc2a711efa5cfeab6654718b4f04e Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 13 Apr 2017 11:14:02 -0600 Subject: [PATCH 430/990] ieee802.15.4 radio: Remove interface methods that duplicate IOCTL commands. --- drivers/wireless/ieee802154/at86rf23x.c | 61 ++++++++----------- drivers/wireless/ieee802154/mrf24j40.c | 18 ++---- .../wireless/ieee802154/ieee802154_radio.h | 39 ------------ 3 files changed, 30 insertions(+), 88 deletions(-) diff --git a/drivers/wireless/ieee802154/at86rf23x.c b/drivers/wireless/ieee802154/at86rf23x.c index ceebfe79f9..e3429c4d1f 100644 --- a/drivers/wireless/ieee802154/at86rf23x.c +++ b/drivers/wireless/ieee802154/at86rf23x.c @@ -148,7 +148,7 @@ static void at86rf23x_irqwork_tx(FAR struct at86rf23x_dev_s *dev); static void at86rf23x_irqworker(FAR void *arg); static int at86rf23x_interrupt(int irq, FAR void *context, FAR void *arg); -/* Driver operations */ +/* IOCTL helpers */ static int at86rf23x_setchannel(FAR struct ieee802154_radio_s *ieee, uint8_t chan); @@ -182,10 +182,13 @@ static int at86rf23x_setcca(FAR struct ieee802154_radio_s *ieee, FAR struct ieee802154_cca_s *cca); static int at86rf23x_getcca(FAR struct ieee802154_radio_s *ieee, FAR struct ieee802154_cca_s *cca); -static int at86rf23x_ioctl(FAR struct ieee802154_radio_s *ieee, int cmd, - unsigned long arg); static int at86rf23x_energydetect(FAR struct ieee802154_radio_s *ieee, FAR uint8_t *energy); + +/* Driver operations */ + +static int at86rf23x_ioctl(FAR struct ieee802154_radio_s *ieee, int cmd, + unsigned long arg); static int at86rf23x_rxenable(FAR struct ieee802154_radio_s *ieee, bool state, FAR struct ieee802154_packet_s *packet); static int at86rf23x_transmit(FAR struct ieee802154_radio_s *ieee, @@ -206,24 +209,7 @@ static struct at86rf23x_dev_s g_at86rf23x_devices[1]; static const struct ieee802154_radioops_s at86rf23x_devops = { - .setchannel = at86rf23x_setchannel, - .getchannel = at86rf23x_getchannel, - .setpanid = at86rf23x_setpanid, - .getpanid = at86rf23x_getpanid, - .setsaddr = at86rf23x_setsaddr, - .getsaddr = at86rf23x_getsaddr, - .seteaddr = at86rf23x_seteaddr, - .geteaddr = at86rf23x_geteaddr, - .setpromisc = at86rf23x_setpromisc, - .getpromisc = at86rf23x_getpromisc, - .setdevmode = at86rf23x_setdevmode, - .getdevmode = at86rf23x_getdevmode, - .settxpower = at86rf23x_settxpower, - .gettxpower = at86rf23x_gettxpower, - .setcca = at86rf23x_setcca, - .getcca = at86rf23x_getcca, .ioctl = at86rf23x_ioctl, - .energydetect = at86rf23x_energydetect, .rxenable = at86rf23x_rxenable, .transmit = at86rf23x_transmit }; @@ -1143,6 +1129,24 @@ static int at86rf23x_getcca(FAR struct ieee802154_radio_s *ieee, return ERROR; } +/**************************************************************************** + * Name: at86rf23x_energydetect + * + * Description: + * Perform energy detection scan. TODO: Need to implement. + * + ****************************************************************************/ + +static int at86rf23x_energydetect(FAR struct ieee802154_radio_s *ieee, + FAR uint8_t *energy) +{ +#warning at86rf23x_energydetect not implemented. + + /* Not yet implemented */ + + return ERROR; +} + /**************************************************************************** * Name: at86rf23x_ioctl * @@ -1237,23 +1241,6 @@ static int at86rf23x_ioctl(FAR struct ieee802154_radio_s *ieee, int cmd, } } -/**************************************************************************** - * Name: at86rf23x_energydetect - * - * Description: - * Perform energy detection scan. TODO: Need to implement. - * - ****************************************************************************/ -static int at86rf23x_energydetect(FAR struct ieee802154_radio_s *ieee, - FAR uint8_t *energy) -{ -#warning at86rf23x_energydetect not implemented. - - /* Not yet implemented */ - - return ERROR; -} - /**************************************************************************** * Name: at86rf23x_initialize * diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c index 1f3f68bf98..263de68eeb 100644 --- a/drivers/wireless/ieee802154/mrf24j40.c +++ b/drivers/wireless/ieee802154/mrf24j40.c @@ -140,7 +140,7 @@ static void mrf24j40_irqwork_tx(FAR struct mrf24j40_radio_s *dev); static void mrf24j40_irqworker(FAR void *arg); static int mrf24j40_interrupt(int irq, FAR void *context, FAR void *arg); -/* Driver operations */ +/* IOCTL helpers */ static int mrf24j40_setchannel(FAR struct ieee802154_radio_s *ieee, uint8_t chan); @@ -174,10 +174,13 @@ static int mrf24j40_setcca(FAR struct ieee802154_radio_s *ieee, FAR struct ieee802154_cca_s *cca); static int mrf24j40_getcca(FAR struct ieee802154_radio_s *ieee, FAR struct ieee802154_cca_s *cca); -static int mrf24j40_ioctl(FAR struct ieee802154_radio_s *ieee, int cmd, - unsigned long arg); static int mrf24j40_energydetect(FAR struct ieee802154_radio_s *ieee, FAR uint8_t *energy); + +/* Driver operations */ + +static int mrf24j40_ioctl(FAR struct ieee802154_radio_s *ieee, int cmd, + unsigned long arg); static int mrf24j40_rxenable(FAR struct ieee802154_radio_s *ieee, bool state, FAR struct ieee802154_packet_s *packet); static int mrf24j40_transmit(FAR struct ieee802154_radio_s *ieee, @@ -198,16 +201,7 @@ static struct mrf24j40_radio_s g_mrf24j40_devices[1]; static const struct ieee802154_radioops_s mrf24j40_devops = { - mrf24j40_setchannel, mrf24j40_getchannel, - mrf24j40_setpanid , mrf24j40_getpanid, - mrf24j40_setsaddr , mrf24j40_getsaddr, - mrf24j40_seteaddr , mrf24j40_geteaddr, - mrf24j40_setpromisc, mrf24j40_getpromisc, - mrf24j40_setdevmode, mrf24j40_getdevmode, - mrf24j40_settxpower, mrf24j40_gettxpower, - mrf24j40_setcca , mrf24j40_getcca, mrf24j40_ioctl, - mrf24j40_energydetect, mrf24j40_rxenable, mrf24j40_transmit }; diff --git a/include/nuttx/wireless/ieee802154/ieee802154_radio.h b/include/nuttx/wireless/ieee802154/ieee802154_radio.h index af44f96445..5bee1e3d52 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_radio.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_radio.h @@ -178,47 +178,8 @@ struct ieee802154_radio_s; struct ieee802154_radioops_s { - CODE int (*setchannel)(FAR struct ieee802154_radio_s *dev, - uint8_t channel); - CODE int (*getchannel)(FAR struct ieee802154_radio_s *dev, - FAR uint8_t *channel); - - CODE int (*setpanid)(FAR struct ieee802154_radio_s *dev, uint16_t panid); - CODE int (*getpanid)(FAR struct ieee802154_radio_s *dev, - FAR uint16_t *panid); - - CODE int (*setsaddr)(FAR struct ieee802154_radio_s *dev, uint16_t saddr); - CODE int (*getsaddr)(FAR struct ieee802154_radio_s *dev, - FAR uint16_t *saddr); - - CODE int (*seteaddr)(FAR struct ieee802154_radio_s *dev, - FAR uint8_t *laddr); - CODE int (*geteaddr)(FAR struct ieee802154_radio_s *dev, - FAR uint8_t *laddr); - - CODE int (*setpromisc)(FAR struct ieee802154_radio_s *dev, bool promisc); - CODE int (*getpromisc)(FAR struct ieee802154_radio_s *dev, - FAR bool *promisc); - - CODE int (*setdevmode)(FAR struct ieee802154_radio_s *dev, - uint8_t devmode); - CODE int (*getdevmode)(FAR struct ieee802154_radio_s *dev, - FAR uint8_t *devmode); - - CODE int (*settxpower)(FAR struct ieee802154_radio_s *dev, - int32_t txpwr); /* unit = 1 mBm = 1/100 dBm */ - CODE int (*gettxpower)(FAR struct ieee802154_radio_s *dev, - FAR int32_t *txpwr); - - CODE int (*setcca)(FAR struct ieee802154_radio_s *dev, - FAR struct ieee802154_cca_s *cca); - CODE int (*getcca)(FAR struct ieee802154_radio_s *dev, - FAR struct ieee802154_cca_s *cca); - CODE int (*ioctl)(FAR struct ieee802154_radio_s *ieee, int cmd, unsigned long arg); - CODE int (*energydetect)(FAR struct ieee802154_radio_s *dev, - FAR uint8_t *energy); CODE int (*rxenable)(FAR struct ieee802154_radio_s *dev, bool state, FAR struct ieee802154_packet_s *packet); CODE int (*transmit)(FAR struct ieee802154_radio_s *dev, -- GitLab From c1ddae5c5ea2f0546161cf584f539e2150813df1 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 13 Apr 2017 12:17:36 -0600 Subject: [PATCH 431/990] ieee802.15.4: de-couple MAC driver interface. Now works more like other drivers. --- .../wireless/ieee802154/ieee802154_mac.h | 22 +- wireless/ieee802154/mac802154.c | 78 +++++- wireless/ieee802154/mac802154_device.c | 13 +- wireless/ieee802154/mac802154_netdev.c | 226 +++++++++++------- 4 files changed, 236 insertions(+), 103 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index acfcdac6db..5dbed05ea7 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -883,7 +883,8 @@ struct ieee802154_netmac_s /* MAC Interface Operations *************************************************/ -struct ieee802154_mac_s; /* Forward reference */ +struct ieee802154_mac_s; /* Forward reference */ +struct ieee802154_maccb_s; /* Forward reference */ struct ieee802154_macops_s { @@ -960,6 +961,11 @@ struct ieee802154_macops_s FAR uint8_t *orphanaddr, uint16_t saddr, bool associated); + /* Bind callbacks to the IEEE802.15.4 MAC */ + + CODE int (*bind)(FAR struct ieee802154_mac_s *mac, + FAR const struct ieee802154_maccb_s *cb); + /* IOCTL support */ CODE int (*ioctl)(FAR struct ieee802154_mac_s *mac, int cmd, @@ -970,10 +976,6 @@ struct ieee802154_macops_s struct ieee802154_maccb_s { - /* Context arg for handling callback */ - - FAR void *cb_context; - /* Asynchronous confirmations to requests */ /* Data frame was received by remote device */ @@ -1064,13 +1066,13 @@ struct ieee802154_maccb_s CODE void (*ind_syncloss)(FAR struct ieee802154_mac_s *mac, int reason); }; -struct ieee802154_radio_s; /* Forward reference */ - struct ieee802154_mac_s { - FAR struct ieee802154_radio_s *radio; + /* Publicly visiable part of the MAC interface */ + struct ieee802154_macops_s ops; - struct ieee802154_maccb_s cbs; + + /* MAC private data may follow */ }; #ifdef __cplusplus @@ -1085,6 +1087,8 @@ extern "C" * Public Function Prototypes ****************************************************************************/ +struct ieee802154_radio_s; /* Forward reference */ + /**************************************************************************** * Name: mac802154_create * diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index f291d76199..a1bf265534 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -61,7 +61,9 @@ struct ieee802154_privmac_s { - struct ieee802154_mac_s pubmac; /* This MUST be the first member */ + struct ieee802154_mac_s pubmac; /* This MUST be the first member */ + FAR struct ieee802154_radio_s *radio; /* Contained IEEE802.15.4 radio dev */ + FAR const struct ieee802154_maccb_s *cb; /* Contained MAC callbacks */ /* MIB attributes, grouped to save memory */ /* 0x40 */ uint8_t macAckWaitDuration : 1; /* 55 or 120(true) */ @@ -143,6 +145,10 @@ static int mac802154_rsp_associate(FAR struct ieee802154_mac_s *mac, static int mac802154_rsp_orphan(FAR struct ieee802154_mac_s *mac, FAR uint8_t *orphanaddr, uint16_t saddr, bool associated); +static int mac802154_bind(FAR struct ieee802154_mac_s *mac, + FAR struct ieee802154_maccb_s *cb); +static int mac802154_ioctl(FAR struct ieee802154_mac_s *mac, int cmd, + unsigned long arg); /**************************************************************************** * Private Data @@ -502,10 +508,76 @@ static int mac802154_rsp_orphan(FAR struct ieee802154_mac_s *mac, FAR uint8_t *orphanaddr, uint16_t saddr, bool associated) { - FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } +/**************************************************************************** + * Name: mac802154_bind + * + * Description: + * Bind the MAC callback table to the MAC state. + * + * Parameters: + * mac - Reference to the MAC driver state structure + * cb - MAC callback operations + * + * Returned Value: + * OK on success; Negated errno on failure. + * + ****************************************************************************/ + +static int mac802154_bind(FAR struct ieee802154_mac_s *mac, + FAR const struct ieee802154_maccb_s *cb) +{ + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; + + priv->cb = cb; + return OK; +} + +/**************************************************************************** + * Name: mac802154_ioctl + * + * Description: + * Handle MAC and radio IOCTL commands directed to the MAC. + * + * Parameters: + * mac - Reference to the MAC driver state structure + * cmd - The IOCTL command + * arg - The argument for the IOCTL command + * + * Returned Value: + * OK on success; Negated errno on failure. + * + ****************************************************************************/ + +static int mac802154_ioctl(FAR struct ieee802154_mac_s *mac, int cmd, + unsigned long arg) +{ + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; + int ret = -EINVAL; + + /* Check for IOCTLs aimed at the IEEE802.15.4 MAC layer */ + + if (_MAC802154IOCVALID(cmd)) + { + /* Handle the MAC IOCTL command */ +#warning Missing logic + } + + /* No, other IOCTLs must be aimed at the IEEE802.15.4 radio layer */ + + else + { + ret = priv->radio->ioctl(priv->radio, cmd, arg); + } +} +#endif + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -552,7 +624,7 @@ FAR struct ieee802154_mac_s * /* Initialize fields */ - mac->pubmac.radio = radiodev; + mac->radio = radiodev; mac->pubmac.ops = mac802154ops; mac802154_defaultmib(mac); diff --git a/wireless/ieee802154/mac802154_device.c b/wireless/ieee802154/mac802154_device.c index d2bc248980..83e33f8cf3 100644 --- a/wireless/ieee802154/mac802154_device.c +++ b/wireless/ieee802154/mac802154_device.c @@ -494,9 +494,10 @@ void mac802154dev_conf_data(FAR struct ieee802154_mac_s *mac, /* Get the dev from the callback context. This should have been set when * the char driver was registered. + * + * REVISIT: See mac802154_netdev.c */ - - dev = mac->cbs.cb_context; +#warning Missing logic /* Get exclusive access to the driver structure */ @@ -554,7 +555,13 @@ int mac802154dev_register(FAR struct ieee802154_mac_s *mac, int minor) dev->md_mac = mac; sem_init(&dev->md_exclsem, 0, 1); /* Allow the device to be opened once * before blocking */ - + + /* Initialize the callbacks and bind them to the radio + * + * REVISIT: See mac802154_netdev.c + */ +#warning Missing logic + /* Create the character device name */ snprintf(devname, DEVNAME_FMTLEN, DEVNAME_FMT, minor); diff --git a/wireless/ieee802154/mac802154_netdev.c b/wireless/ieee802154/mac802154_netdev.c index f5b0aed51c..6dd798f24b 100644 --- a/wireless/ieee802154/mac802154_netdev.c +++ b/wireless/ieee802154/mac802154_netdev.c @@ -103,12 +103,22 @@ /* This is a helper pointer for accessing the contents of the Ethernet header */ -#define BUF ((struct eth_hdr_s *)priv->m8_dev.d_buf) +#define BUF ((struct eth_hdr_s *)priv->md_dev.d_buf) /**************************************************************************** * Private Types ****************************************************************************/ +/* This is our private version of the MAC callback stucture */ + +struct mac802154_callback_s +{ + /* This holds the information visible to the MAC layer */ + + struct ieee802154_maccb_s mc_cb; /* Interface understood by the MAC layer */ + FAR struct mac802154_driver_s *mc_priv; /* Our priv data */ +}; + /* The mac802154_driver_s encapsulates all state information for a single * IEEE802.15.4 MAC interface. */ @@ -117,16 +127,17 @@ struct mac802154_driver_s { /* This holds the information visible to the NuttX network */ - struct ieee802154_driver_s m8_dev; /* Interface understood by the network */ - FAR struct ieee802154_mac_s *m8_mac; /* Contained MAC interface */ + struct ieee802154_driver_s md_dev; /* Interface understood by the network */ + FAR struct ieee802154_mac_s *md_mac; /* Contained MAC interface */ + struct mac802154_callback_s md_cb; /* Callback information */ /* For internal use by this driver */ - bool m8_bifup; /* true:ifup false:ifdown */ - WDOG_ID m8_txpoll; /* TX poll timer */ - WDOG_ID m8_txtimeout; /* TX timeout timer */ - struct work_s m8_irqwork; /* For deferring interupt work to the work queue */ - struct work_s m8_pollwork; /* For deferring poll work to the work queue */ + bool md_bifup; /* true:ifup false:ifdown */ + WDOG_ID md_txpoll; /* TX poll timer */ + WDOG_ID md_txtimeout; /* TX timeout timer */ + struct work_s md_irqwork; /* For deferring interupt work to the work queue */ + struct work_s md_pollwork; /* For deferring poll work to the work queue */ }; /**************************************************************************** @@ -254,10 +265,11 @@ static int mac802154_ioctl(FAR struct net_driver_s *dev, int cmd, long arg); static void mac802154_conf_data(FAR struct ieee802154_mac_s *mac, FAR struct ieee802154_data_conf_s *conf) { + FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; FAR struct mac802154_driver_s *priv; - DEBUGASSERT(mac != NULL && mac->cb_context); - priv = (FAR struct mac802154_driver_s *)mac->cb_context; + DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); + priv = cb->mc_priv; } /**************************************************************************** @@ -271,10 +283,11 @@ static void mac802154_conf_data(FAR struct ieee802154_mac_s *mac, static void mac802154_conf_purge(FAR struct ieee802154_mac_s *mac, uint8_t handle, int status) { + FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; FAR struct mac802154_driver_s *priv; - DEBUGASSERT(mac != NULL && mac->cb_context); - priv = (FAR struct mac802154_driver_s *)mac->cb_context; + DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); + priv = cb->mc_priv; } /**************************************************************************** @@ -288,10 +301,11 @@ static void mac802154_conf_purge(FAR struct ieee802154_mac_s *mac, static void mac802154_conf_associate(FAR struct ieee802154_mac_s *mac, uint16_t saddr, int status) { + FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; FAR struct mac802154_driver_s *priv; - DEBUGASSERT(mac != NULL && mac->cb_context); - priv = (FAR struct mac802154_driver_s *)mac->cb_context; + DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); + priv = cb->mc_priv; } /**************************************************************************** @@ -304,10 +318,11 @@ static void mac802154_conf_associate(FAR struct ieee802154_mac_s *mac, static void mac802154_conf_disassociate(FAR struct ieee802154_mac_s *mac, { + FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; FAR struct mac802154_driver_s *priv; - DEBUGASSERT(mac != NULL && mac->cb_context); - priv = (FAR struct mac802154_driver_s *)mac->cb_context; + DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); + priv = cb->mc_priv; } /**************************************************************************** @@ -322,10 +337,11 @@ static void mac802154_conf_get(FAR struct ieee802154_mac_s *mac, int status, int attribute, FAR uint8_t *value, int valuelen) { + FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; FAR struct mac802154_driver_s *priv; - DEBUGASSERT(mac != NULL && mac->cb_context); - priv = (FAR struct mac802154_driver_s *)mac->cb_context; + DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); + priv = cb->mc_priv; } /**************************************************************************** @@ -339,10 +355,11 @@ static void mac802154_conf_get(FAR struct ieee802154_mac_s *mac, int status, static void mac802154_conf_gts(FAR struct ieee802154_mac_s *mac, FAR uint8_t *characteristics, int status) { + FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; FAR struct mac802154_driver_s *priv; - DEBUGASSERT(mac != NULL && mac->cb_context); - priv = (FAR struct mac802154_driver_s *)mac->cb_context; + DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); + priv = cb->mc_priv; } /**************************************************************************** @@ -356,10 +373,11 @@ static void mac802154_conf_gts(FAR struct ieee802154_mac_s *mac, static void mac802154_conf_reset(FAR struct ieee802154_mac_s *mac, int status) { + FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; FAR struct mac802154_driver_s *priv; - DEBUGASSERT(mac != NULL && mac->cb_context); - priv = (FAR struct mac802154_driver_s *)mac->cb_context; + DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); + priv = cb->mc_priv; } /**************************************************************************** @@ -372,10 +390,11 @@ static void mac802154_conf_reset(FAR struct ieee802154_mac_s *mac, static void mac802154_conf_rxenable(FAR struct ieee802154_mac_s *mac, int status) { + FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; FAR struct mac802154_driver_s *priv; - DEBUGASSERT(mac != NULL && mac->cb_context); - priv = (FAR struct mac802154_driver_s *)mac->cb_context; + DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); + priv = cb->mc_priv; } /**************************************************************************** @@ -390,10 +409,11 @@ static void mac802154_conf_scan(FAR struct ieee802154_mac_s *mac, uint32_t unscanned, int rsltsize, FAR uint8_t *edlist, FAR uint8_t *pandescs) { + FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; FAR struct mac802154_driver_s *priv; - DEBUGASSERT(mac != NULL && mac->cb_context); - priv = (FAR struct mac802154_driver_s *)mac->cb_context; + DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); + priv = cb->mc_priv; } /**************************************************************************** @@ -406,10 +426,11 @@ static void mac802154_conf_scan(FAR struct ieee802154_mac_s *mac, static void mac802154_conf_set(FAR struct ieee802154_mac_s *mac, int status, int attribute) { + FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; FAR struct mac802154_driver_s *priv; - DEBUGASSERT(mac != NULL && mac->cb_context); - priv = (FAR struct mac802154_driver_s *)mac->cb_context; + DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); + priv = cb->mc_priv; } /**************************************************************************** @@ -422,10 +443,11 @@ static void mac802154_conf_set(FAR struct ieee802154_mac_s *mac, int status, static void mac802154_conf_start(FAR struct ieee802154_mac_s *mac, int status) { + FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; FAR struct mac802154_driver_s *priv; - DEBUGASSERT(mac != NULL && mac->cb_context); - priv = (FAR struct mac802154_driver_s *)mac->cb_context; + DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); + priv = cb->mc_priv; } /**************************************************************************** @@ -438,10 +460,11 @@ static void mac802154_conf_start(FAR struct ieee802154_mac_s *mac, static void mac802154_conf_poll(FAR struct ieee802154_mac_s *mac, int status) { + FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; FAR struct mac802154_driver_s *priv; - DEBUGASSERT(mac != NULL && mac->cb_context); - priv = (FAR struct mac802154_driver_s *)mac->cb_context; + DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); + priv = cb->mc_priv; } /**************************************************************************** @@ -455,10 +478,11 @@ static void mac802154_conf_poll(FAR struct ieee802154_mac_s *mac, static void mac802154_ind_data(FAR struct ieee802154_mac_s *mac, FAR uint8_t *buf, int len) { + FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; FAR struct mac802154_driver_s *priv; - DEBUGASSERT(mac != NULL && mac->cb_context); - priv = (FAR struct mac802154_driver_s *)mac->cb_context; + DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); + priv = cb->mc_priv; } /**************************************************************************** @@ -473,10 +497,11 @@ static void mac802154_ind_associate(FAR struct ieee802154_mac_s *mac, uint16_t clipanid, FAR uint8_t *clieaddr) { + FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; FAR struct mac802154_driver_s *priv; - DEBUGASSERT(mac != NULL && mac->cb_context); - priv = (FAR struct mac802154_driver_s *)mac->cb_context; + DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); + priv = cb->mc_priv; } /**************************************************************************** @@ -490,10 +515,11 @@ static void mac802154_ind_associate(FAR struct ieee802154_mac_s *mac, static void mac802154_ind_disassociate(FAR struct ieee802154_mac_s *mac, FAR uint8_t *eadr, uint8_t reason) { + FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; FAR struct mac802154_driver_s *priv; - DEBUGASSERT(mac != NULL && mac->cb_context); - priv = (FAR struct mac802154_driver_s *)mac->cb_context; + DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); + priv = cb->mc_priv; } /**************************************************************************** @@ -509,10 +535,11 @@ static void mac802154_ind_beaconnotify(FAR struct ieee802154_mac_s *mac, FAR struct ieee802154_pan_desc_s *pandesc, FAR uint8_t *sdu, int sdulen) { + FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; FAR struct mac802154_driver_s *priv; - DEBUGASSERT(mac != NULL && mac->cb_context); - priv = (FAR struct mac802154_driver_s *)mac->cb_context; + DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); + priv = cb->mc_priv; } /**************************************************************************** @@ -527,10 +554,11 @@ static void mac802154_ind_gts(FAR struct ieee802154_mac_s *mac, FAR uint8_t *devaddr, FAR uint8_t *characteristics) { + FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; FAR struct mac802154_driver_s *priv; - DEBUGASSERT(mac != NULL && mac->cb_context); - priv = (FAR struct mac802154_driver_s *)mac->cb_context; + DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); + priv = cb->mc_priv; } /**************************************************************************** @@ -544,10 +572,11 @@ static void mac802154_ind_gts(FAR struct ieee802154_mac_s *mac, static void mac802154_ind_orphan(FAR struct ieee802154_mac_s *mac, FAR uint8_t *orphanaddr) { + FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; FAR struct mac802154_driver_s *priv; - DEBUGASSERT(mac != NULL && mac->cb_context); - priv = (FAR struct mac802154_driver_s *)mac->cb_context; + DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); + priv = cb->mc_priv; } /**************************************************************************** @@ -561,10 +590,11 @@ static void mac802154_ind_commstatus(FAR struct ieee802154_mac_s *mac, uint16_t panid, FAR uint8_t *src, FAR uint8_t *dst, int status) { + FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; FAR struct mac802154_driver_s *priv; - DEBUGASSERT(mac != NULL && mac->cb_context); - priv = (FAR struct mac802154_driver_s *)mac->cb_context; + DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); + priv = cb->mc_priv; } /**************************************************************************** @@ -577,10 +607,11 @@ static void mac802154_ind_commstatus(FAR struct ieee802154_mac_s *mac, static void mac802154_ind_syncloss(FAR struct ieee802154_mac_s *mac, int reason) { + FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; FAR struct mac802154_driver_s *priv; - DEBUGASSERT(mac != NULL && mac->cb_context); - priv = (FAR struct mac802154_driver_s *)mac->cb_context; + DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); + priv = cb->mc_priv; } /**************************************************************************** @@ -611,15 +642,15 @@ static int mac802154_transmit(FAR struct mac802154_driver_s *priv) /* Increment statistics */ - NETDEV_TXPACKETS(priv->m8_dev); + NETDEV_TXPACKETS(priv->md_dev); - /* Send the packet: address=priv->m8_dev.d_buf, length=priv->m8_dev.d_len */ + /* Send the packet: address=priv->md_dev.d_buf, length=priv->md_dev.d_len */ /* Enable Tx interrupts */ /* Setup the TX timeout watchdog (perhaps restarting the timer) */ - (void)wd_start(priv->m8_txtimeout, skeleton_TXTIMEOUT, + (void)wd_start(priv->md_txtimeout, skeleton_TXTIMEOUT, mac802154_txtimeout_expiry, 1, (wdparm_t)priv); return OK; } @@ -656,7 +687,7 @@ static int mac802154_txpoll(FAR struct net_driver_s *dev) * i_framelist will set to a new, outgoing list of frames. */ - if (priv->m8_dev.i_framelist != NULL) + if (priv->md_dev.i_framelist != NULL) { /* And send the packet */ @@ -711,14 +742,14 @@ static void mac802154_receive(FAR struct mac802154_driver_s *priv) /* Transfer the frame to the network logic */ - priv->m8_dev.framelist = iob; - sixlowpan_input(&priv->m8_dev); + priv->md_dev.framelist = iob; + sixlowpan_input(&priv->md_dev); /* If the above function invocation resulted in data that should be sent * out, the field i_framelist will set to a new, outgoing list of frames. */ - if (priv->m8_dev.i_framelist != NULL) + if (priv->md_dev.i_framelist != NULL) { /* And send the packet */ @@ -749,7 +780,7 @@ static void mac802154_txdone(FAR struct mac802154_driver_s *priv) /* Check for errors and update statistics */ - NETDEV_TXDONE(priv->m8_dev); + NETDEV_TXDONE(priv->md_dev); /* Check if there are pending transmissions */ @@ -757,13 +788,13 @@ static void mac802154_txdone(FAR struct mac802154_driver_s *priv) * disable further Tx interrupts. */ - wd_cancel(priv->m8_txtimeout); + wd_cancel(priv->md_txtimeout); /* And disable further TX interrupts. */ /* In any event, poll the network for new TX data */ - (void)devif_poll(&priv->m8_dev, mac802154_txpoll); + (void)devif_poll(&priv->md_dev, mac802154_txpoll); } /**************************************************************************** @@ -854,12 +885,12 @@ static int mac802154_transfer(int irq, FAR void *context, FAR void *arg) * expiration and the deferred interrupt processing. */ - wd_cancel(priv->m8_txtimeout); + wd_cancel(priv->md_txtimeout); } /* Schedule to perform the interrupt processing on the worker thread. */ - work_queue(ETHWORK, &priv->m8_irqwork, mac802154_transfer_work, priv, 0); + work_queue(ETHWORK, &priv->md_irqwork, mac802154_transfer_work, priv, 0); return OK; } @@ -894,13 +925,13 @@ static void mac802154_txtimeout_work(FAR void *arg) /* Increment statistics and dump debug info */ - NETDEV_TXTIMEOUTS(priv->m8_dev); + NETDEV_TXTIMEOUTS(priv->md_dev); /* Then reset the hardware */ /* Then poll the network for new XMIT data */ - (void)devif_poll(&priv->m8_dev, mac802154_txpoll); + (void)devif_poll(&priv->md_dev, mac802154_txpoll); net_unlock(); } @@ -936,7 +967,7 @@ static void mac802154_txtimeout_expiry(int argc, wdparm_t arg, ...) /* Schedule to perform the TX timeout processing on the worker thread. */ - work_queue(ETHWORK, &priv->m8_irqwork, mac802154_txtimeout_work, priv, 0); + work_queue(ETHWORK, &priv->md_irqwork, mac802154_txtimeout_work, priv, 0); } /**************************************************************************** @@ -1000,11 +1031,11 @@ static void mac802154_poll_work(FAR void *arg) * progress, we will missing TCP time state updates? */ - (void)devif_timer(&priv->m8_dev, mac802154_txpoll); + (void)devif_timer(&priv->md_dev, mac802154_txpoll); /* Setup the watchdog poll timer again */ - (void)wd_start(priv->m8_txpoll, skeleton_WDDELAY, mac802154_poll_expiry, 1, + (void)wd_start(priv->md_txpoll, skeleton_WDDELAY, mac802154_poll_expiry, 1, (wdparm_t)priv); net_unlock(); } @@ -1033,7 +1064,7 @@ static void mac802154_poll_expiry(int argc, wdparm_t arg, ...) /* Schedule to perform the interrupt processing on the worker thread. */ - work_queue(ETHWORK, &priv->m8_pollwork, mac802154_poll_work, priv, 0); + work_queue(ETHWORK, &priv->md_pollwork, mac802154_poll_work, priv, 0); } /**************************************************************************** @@ -1071,7 +1102,7 @@ static int mac802154_ifup(FAR struct net_driver_s *dev) /* Initialize PHYs, the Ethernet interface, and setup up Ethernet interrupts */ - /* Instantiate the MAC address from priv->m8_dev.d_mac.ether_addr_octet */ + /* Instantiate the MAC address from priv->md_dev.d_mac.ether_addr_octet */ #ifdef CONFIG_NET_ICMPv6 /* Set up IPv6 multicast address filtering */ @@ -1081,12 +1112,12 @@ static int mac802154_ifup(FAR struct net_driver_s *dev) /* Set and activate a timer process */ - (void)wd_start(priv->m8_txpoll, skeleton_WDDELAY, mac802154_poll_expiry, 1, + (void)wd_start(priv->md_txpoll, skeleton_WDDELAY, mac802154_poll_expiry, 1, (wdparm_t)priv); /* Enable the Ethernet interrupt */ - priv->m8_bifup = true; + priv->md_bifup = true; up_enable_irq(CONFIG_IEEE802154_NETDEV_IRQ); return OK; } @@ -1119,8 +1150,8 @@ static int mac802154_ifdown(FAR struct net_driver_s *dev) /* Cancel the TX poll timer and TX timeout timers */ - wd_cancel(priv->m8_txpoll); - wd_cancel(priv->m8_txtimeout); + wd_cancel(priv->md_txpoll); + wd_cancel(priv->md_txtimeout); /* Put the EMAC in its reset, non-operational state. This should be * a known configuration that will guarantee the mac802154_ifup() always @@ -1129,7 +1160,7 @@ static int mac802154_ifdown(FAR struct net_driver_s *dev) /* Mark the device "down" */ - priv->m8_bifup = false; + priv->md_bifup = false; leave_critical_section(flags); return OK; } @@ -1165,13 +1196,13 @@ static void mac802154_txavail_work(FAR void *arg) /* Ignore the notification if the interface is not yet up */ - if (priv->m8_bifup) + if (priv->md_bifup) { /* Check if there is room in the hardware to hold another outgoing packet. */ /* If so, then poll the network for new XMIT data */ - (void)devif_poll(&priv->m8_dev, mac802154_txpoll); + (void)devif_poll(&priv->md_dev, mac802154_txpoll); } net_unlock(); @@ -1205,11 +1236,11 @@ static int mac802154_txavail(FAR struct net_driver_s *dev) * availability action. */ - if (work_available(&priv->m8_pollwork)) + if (work_available(&priv->md_pollwork)) { /* Schedule to serialize the poll on the worker thread. */ - work_queue(ETHWORK, &priv->m8_pollwork, mac802154_txavail_work, priv, 0); + work_queue(ETHWORK, &priv->md_pollwork, mac802154_txavail_work, priv, 0); } return OK; @@ -1381,7 +1412,7 @@ static int mac802154_ioctl(FAR struct net_driver_s *dev, int cmd, long arg) if (netmac != NULL) { unsigned long macarg = (unsigned int)((uintptr_t)&netmac->u); - ret = priv->m8_mac.macops.ioctl(priv->m8_mac, cmd, macarg); + ret = priv->md_mac.macops.ioctl(priv->md_mac, cmd, macarg); } } @@ -1395,7 +1426,7 @@ static int mac802154_ioctl(FAR struct net_driver_s *dev, int cmd, long arg) if (netradio != NULL) { unsigned long radioarg = (unsigned int)((uintptr_t)&netradio->u); - ret = priv->m8_mac.macops.ioctl(priv->m8_mac, cmd, radioarg); + ret = priv->md_mac.macops.ioctl(priv->md_mac, cmd, radioarg); } } @@ -1405,7 +1436,7 @@ static int mac802154_ioctl(FAR struct net_driver_s *dev, int cmd, long arg) else { - ret = priv->m8_mac.macops.ioctl(priv->m8_mac, cmd, arg); + ret = priv->md_mac.macops.ioctl(priv->md_mac, cmd, arg); } } #endif @@ -1433,9 +1464,9 @@ static int mac802154_ioctl(FAR struct net_driver_s *dev, int cmd, long arg) int mac802154netdev_register(FAR struct ieee802154_mac_s *mac); { FAR struct mac802154_driver_s *priv; - FAR truct ieee802154_maccb_s *macb; FAR struct net_driver_s *dev; FAR uint8_t *pktbuf; + int ret; DEBUGASSERT(radio != NULL); @@ -1464,7 +1495,7 @@ int mac802154netdev_register(FAR struct ieee802154_mac_s *mac); /* Initialize the driver structure */ - dev = &ieee->m8_dev.i_dev; + dev = &ieee->md_dev.i_dev; dev->d_buf = pktbuf; /* Single packet buffer */ dev->d_ifup = mac802154_ifup; /* I/F up (new IP address) callback */ dev->d_ifdown = mac802154_ifdown; /* I/F down callback */ @@ -1480,16 +1511,17 @@ int mac802154netdev_register(FAR struct ieee802154_mac_s *mac); /* Create a watchdog for timing polling for and timing of transmisstions */ - priv->m8_mac = mac; /* Save the MAC interface instance */ - priv->m8_txpoll = wd_create(); /* Create periodic poll timer */ - priv->m8_txtimeout = wd_create(); /* Create TX timeout timer */ + priv->md_mac = mac; /* Save the MAC interface instance */ + priv->md_txpoll = wd_create(); /* Create periodic poll timer */ + priv->md_txtimeout = wd_create(); /* Create TX timeout timer */ - DEBUGASSERT(priv->m8_txpoll != NULL && priv->m8_txtimeout != NULL); + DEBUGASSERT(priv->md_txpoll != NULL && priv->md_txtimeout != NULL); /* Initialize the MAC callbacks */ - maccb = &mac->cbs; - maccb->cb_context = priv; + priv->md_cb.mc_priv = priv; + + maccb = &priv->md_cb.mc_cb; maccb->conf_data = mac802154_conf_data; maccb->conf_purge = mac802154_conf_purge; maccb->conf_associate = mac802154_conf_associate; @@ -1511,13 +1543,31 @@ int mac802154netdev_register(FAR struct ieee802154_mac_s *mac); maccb->ind_commstatus = mac802154_ind_commstatus; maccb->ind_syncloss = mac802154_ind_syncloss; + /* Bind the callback structure */ + + ret = mac->ops->bind(mac, *priv->md_cb.mc_cb); + if (ret < 0) + { + nerr("ERROR: Failed to bind the MAC callbacks: %d\n", ret); + + /* Release wdog timers */ + + wd_delete(priv->md_txpoll); + wd_delete(priv->md_txtimeout); + + /* Free memory and return the error */ + kmm_free(pktbuf); + kmm_free(priv); + return ret + } + /* Put the interface in the down state. */ mac802154_ifdown(dev); /* Register the device with the OS so that socket IOCTLs can be performed */ - (void)netdev_register(&priv->m8_dev, NET_LL_IEEE802154); + (void)netdev_register(&priv->md_dev, NET_LL_IEEE802154); return OK; } -- GitLab From 150036eb8b33427af8b505c67914bb0404761bcc Mon Sep 17 00:00:00 2001 From: Nobutaka Toyoshima Date: Fri, 14 Apr 2017 14:29:47 +0900 Subject: [PATCH 432/990] sched: Fix tg_flags check with GROUP_FLAG_NOCLDWAIT Jira: PDFW15IS-208 Signed-off-by: Masayuki Ishikawa --- sched/sched/sched_waitid.c | 2 +- sched/sched/sched_waitpid.c | 2 +- sched/task/task_reparent.c | 8 ++++---- sched/task/task_setup.c | 2 +- 4 files changed, 7 insertions(+), 7 deletions(-) diff --git a/sched/sched/sched_waitid.c b/sched/sched/sched_waitid.c index dd3dd86211..82471ce38d 100644 --- a/sched/sched/sched_waitid.c +++ b/sched/sched/sched_waitid.c @@ -204,7 +204,7 @@ int waitid(idtype_t idtype, id_t id, FAR siginfo_t *info, int options) #ifdef CONFIG_SCHED_CHILD_STATUS /* Does this task retain child status? */ - retains = ((rtcb->group->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0); + retains = ((rtcb->group->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0); if (rtcb->group->tg_children == NULL && retains) { diff --git a/sched/sched/sched_waitpid.c b/sched/sched/sched_waitpid.c index aca86d093f..6d2bc82680 100644 --- a/sched/sched/sched_waitpid.c +++ b/sched/sched/sched_waitpid.c @@ -346,7 +346,7 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options) #ifdef CONFIG_SCHED_CHILD_STATUS /* Does this task retain child status? */ - retains = ((rtcb->group->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0); + retains = ((rtcb->group->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0); if (rtcb->group->tg_children == NULL && retains) { diff --git a/sched/task/task_reparent.c b/sched/task/task_reparent.c index b7fe508bad..075a391940 100644 --- a/sched/task/task_reparent.c +++ b/sched/task/task_reparent.c @@ -163,7 +163,7 @@ int task_reparent(pid_t ppid, pid_t chpid) { /* Has the new parent's task group supressed child exit status? */ - if ((pgrp->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0) + if ((pgrp->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0) { /* No.. Add the child status entry to the new parent's task group */ @@ -186,7 +186,7 @@ int task_reparent(pid_t ppid, pid_t chpid) * suppressed child exit status. */ - ret = ((ogrp->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0) ? -ENOENT : OK; + ret = ((ogrp->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0) ? -ENOENT : OK; } #else /* CONFIG_SCHED_CHILD_STATUS */ @@ -276,7 +276,7 @@ int task_reparent(pid_t ppid, pid_t chpid) { /* Has the new parent's task group supressed child exit status? */ - if ((ptcb->group->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0) + if ((ptcb->group->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0) { /* No.. Add the child status entry to the new parent's task group */ @@ -299,7 +299,7 @@ int task_reparent(pid_t ppid, pid_t chpid) * suppressed child exit status. */ - ret = ((otcb->group->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0) ? -ENOENT : OK; + ret = ((otcb->group->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0) ? -ENOENT : OK; } #else /* CONFIG_SCHED_CHILD_STATUS */ diff --git a/sched/task/task_setup.c b/sched/task/task_setup.c index b3f89abb67..6c591a16c8 100644 --- a/sched/task/task_setup.c +++ b/sched/task/task_setup.c @@ -237,7 +237,7 @@ static inline void task_saveparent(FAR struct tcb_s *tcb, uint8_t ttype) * the SA_NOCLDWAIT flag with sigaction(). */ - if ((rtcb->group->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0) + if ((rtcb->group->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0) { FAR struct child_status_s *child; -- GitLab From c3e0ec369f3867094e405d119d3dab496fb62ed6 Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Fri, 14 Apr 2017 08:06:01 -0600 Subject: [PATCH 433/990] Add basic support for STM32F0 --- arch/arm/include/stm32f0/chip.h | 145 + arch/arm/include/stm32f0/irq.h | 142 + arch/arm/src/stm32f0/Kconfig | 1560 ++++++++++ arch/arm/src/stm32f0/Make.defs | 99 + arch/arm/src/stm32f0/chip.h | 58 + arch/arm/src/stm32f0/chip/stm32f05xr_pinmap.h | 126 + .../src/stm32f0/chip/stm32f05xxx_memorymap.h | 156 + arch/arm/src/stm32f0/chip/stm32f0_adc.h | 194 ++ arch/arm/src/stm32f0/chip/stm32f0_can.h | 468 +++ arch/arm/src/stm32f0/chip/stm32f0_comp.h | 137 + arch/arm/src/stm32f0/chip/stm32f0_crc.h | 89 + arch/arm/src/stm32f0/chip/stm32f0_crs.h | 114 + arch/arm/src/stm32f0/chip/stm32f0_dac.h | 217 ++ arch/arm/src/stm32f0/chip/stm32f0_dma.h | 455 +++ arch/arm/src/stm32f0/chip/stm32f0_exti.h | 130 + arch/arm/src/stm32f0/chip/stm32f0_gpio.h | 332 +++ arch/arm/src/stm32f0/chip/stm32f0_i2c.h | 237 ++ arch/arm/src/stm32f0/chip/stm32f0_memorymap.h | 52 + arch/arm/src/stm32f0/chip/stm32f0_pwr.h | 97 + arch/arm/src/stm32f0/chip/stm32f0_rcc.h | 347 +++ arch/arm/src/stm32f0/chip/stm32f0_rtcc.h | 329 +++ arch/arm/src/stm32f0/chip/stm32f0_spi.h | 252 ++ arch/arm/src/stm32f0/chip/stm32f0_syscfg.h | 390 +++ arch/arm/src/stm32f0/chip/stm32f0_tim.h | 51 + arch/arm/src/stm32f0/chip/stm32f0_uart.h | 357 +++ arch/arm/src/stm32f0/chip/stm32f0_usbdev.h | 262 ++ arch/arm/src/stm32f0/chip/stm32f0_wdt.h | 141 + arch/arm/src/stm32f0/stm32f0_clockconfig.c | 112 + arch/arm/src/stm32f0/stm32f0_clockconfig.h | 76 + arch/arm/src/stm32f0/stm32f0_gpio.c | 427 +++ arch/arm/src/stm32f0/stm32f0_gpio.h | 378 +++ arch/arm/src/stm32f0/stm32f0_idle.c | 110 + arch/arm/src/stm32f0/stm32f0_irq.c | 340 +++ arch/arm/src/stm32f0/stm32f0_lowputc.c | 366 +++ arch/arm/src/stm32f0/stm32f0_lowputc.h | 79 + arch/arm/src/stm32f0/stm32f0_rcc.h | 50 + arch/arm/src/stm32f0/stm32f0_serial.c | 2560 +++++++++++++++++ arch/arm/src/stm32f0/stm32f0_serial.h | 82 + arch/arm/src/stm32f0/stm32f0_start.c | 170 ++ arch/arm/src/stm32f0/stm32f0_timerisr.c | 164 ++ arch/arm/src/stm32f0/stm32f0_uart.h | 433 +++ 41 files changed, 12284 insertions(+) create mode 100644 arch/arm/include/stm32f0/chip.h create mode 100644 arch/arm/include/stm32f0/irq.h create mode 100644 arch/arm/src/stm32f0/Kconfig create mode 100644 arch/arm/src/stm32f0/Make.defs create mode 100644 arch/arm/src/stm32f0/chip.h create mode 100644 arch/arm/src/stm32f0/chip/stm32f05xr_pinmap.h create mode 100644 arch/arm/src/stm32f0/chip/stm32f05xxx_memorymap.h create mode 100644 arch/arm/src/stm32f0/chip/stm32f0_adc.h create mode 100644 arch/arm/src/stm32f0/chip/stm32f0_can.h create mode 100644 arch/arm/src/stm32f0/chip/stm32f0_comp.h create mode 100644 arch/arm/src/stm32f0/chip/stm32f0_crc.h create mode 100644 arch/arm/src/stm32f0/chip/stm32f0_crs.h create mode 100644 arch/arm/src/stm32f0/chip/stm32f0_dac.h create mode 100644 arch/arm/src/stm32f0/chip/stm32f0_dma.h create mode 100644 arch/arm/src/stm32f0/chip/stm32f0_exti.h create mode 100644 arch/arm/src/stm32f0/chip/stm32f0_gpio.h create mode 100644 arch/arm/src/stm32f0/chip/stm32f0_i2c.h create mode 100644 arch/arm/src/stm32f0/chip/stm32f0_memorymap.h create mode 100644 arch/arm/src/stm32f0/chip/stm32f0_pwr.h create mode 100644 arch/arm/src/stm32f0/chip/stm32f0_rcc.h create mode 100644 arch/arm/src/stm32f0/chip/stm32f0_rtcc.h create mode 100644 arch/arm/src/stm32f0/chip/stm32f0_spi.h create mode 100644 arch/arm/src/stm32f0/chip/stm32f0_syscfg.h create mode 100644 arch/arm/src/stm32f0/chip/stm32f0_tim.h create mode 100644 arch/arm/src/stm32f0/chip/stm32f0_uart.h create mode 100644 arch/arm/src/stm32f0/chip/stm32f0_usbdev.h create mode 100644 arch/arm/src/stm32f0/chip/stm32f0_wdt.h create mode 100644 arch/arm/src/stm32f0/stm32f0_clockconfig.c create mode 100644 arch/arm/src/stm32f0/stm32f0_clockconfig.h create mode 100644 arch/arm/src/stm32f0/stm32f0_gpio.c create mode 100644 arch/arm/src/stm32f0/stm32f0_gpio.h create mode 100644 arch/arm/src/stm32f0/stm32f0_idle.c create mode 100644 arch/arm/src/stm32f0/stm32f0_irq.c create mode 100644 arch/arm/src/stm32f0/stm32f0_lowputc.c create mode 100644 arch/arm/src/stm32f0/stm32f0_lowputc.h create mode 100644 arch/arm/src/stm32f0/stm32f0_rcc.h create mode 100644 arch/arm/src/stm32f0/stm32f0_serial.c create mode 100644 arch/arm/src/stm32f0/stm32f0_serial.h create mode 100644 arch/arm/src/stm32f0/stm32f0_start.c create mode 100644 arch/arm/src/stm32f0/stm32f0_timerisr.c create mode 100644 arch/arm/src/stm32f0/stm32f0_uart.h diff --git a/arch/arm/include/stm32f0/chip.h b/arch/arm/include/stm32f0/chip.h new file mode 100644 index 0000000000..e8c2363680 --- /dev/null +++ b/arch/arm/include/stm32f0/chip.h @@ -0,0 +1,145 @@ +/************************************************************************************ + * arch/arm/include/stm32f0/chip.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_INCLUDE_STM32F0_CHIP_H +#define __ARCH_ARM_INCLUDE_STM32F0_CHIP_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Get customizations for each supported chip */ + +#if defined(CONFIG_ARCH_CHIP_STM32F051R8) +# define STM32F051x 1 /* STM32F051x family */ +# define STM32F0_FLASH_SIZE (64*1024) /* 64Kb */ +# define STM32F0_SRAM_SIZE (8*1024) /* 8Kb */ +# define STM32F0_CPUSRAM_SIZE (8*1024) +# undef STM32F0_HAVE_BANK0 /* No AHB SRAM bank 0 */ +# undef STM32F0_HAVE_BANK1 /* No AHB SRAM bank 1 */ +# define STM32F0_NETHCONTROLLERS 0 /* No Ethernet controller */ +# define STM32F0_NUSBHOST 0 /* No USB host controller */ +# define STM32F0_NUSBOTG 0 /* No USB OTG controller */ +# define STM32F0_NUSBDEV 1 /* One USB device controller */ +# define STM32F0_NUSART 2 /* Two USARTs module */ +# define STM32F0_NPORTS 6 /* 6 GPIO ports, GPIOA-F */ +# define STM32F0_NCAN 1 /* One CAN controller */ +# define STM32F0_NI2C 2 /* Two I2C module */ +# define STM32F0_NI2S 1 /* One I2S module */ +# define STM32F0_NDAC 1 /* One DAC module */ +# define STM32F0_NSPI 2 /* Two DAC module */ +#else +# error "Unsupported STM32F0xx chip" +#endif + +/* NVIC priority levels *************************************************************/ +/* Each priority field holds a priority value, 0-31. The lower the value, the greater + * the priority of the corresponding interrupt. The processor implements only + * bits[7:6] of each field, bits[5:0] read as zero and ignore writes. + */ + +#define NVIC_SYSH_PRIORITY_MIN 0xc0 /* All bits[7:6] set is minimum priority */ +#define NVIC_SYSH_PRIORITY_DEFAULT 0x80 /* Midpoint is the default */ +#define NVIC_SYSH_PRIORITY_MAX 0x00 /* Zero is maximum priority */ +#define NVIC_SYSH_PRIORITY_STEP 0x40 /* Two bits of interrupt priority used */ + +/* If CONFIG_ARMV7M_USEBASEPRI is selected, then interrupts will be disabled + * by setting the BASEPRI register to NVIC_SYSH_DISABLE_PRIORITY so that most + * interrupts will not have execution priority. SVCall must have execution + * priority in all cases. + * + * In the normal cases, interrupts are not nest-able and all interrupts run + * at an execution priority between NVIC_SYSH_PRIORITY_MIN and + * NVIC_SYSH_PRIORITY_MAX (with NVIC_SYSH_PRIORITY_MAX reserved for SVCall). + * + * If, in addition, CONFIG_ARCH_HIPRI_INTERRUPT is defined, then special + * high priority interrupts are supported. These are not "nested" in the + * normal sense of the word. These high priority interrupts can interrupt + * normal processing but execute outside of OS (although they can "get back + * into the game" via a PendSV interrupt). + * + * In the normal course of things, interrupts must occasionally be disabled + * using the up_irq_save() inline function to prevent contention in use of + * resources that may be shared between interrupt level and non-interrupt + * level logic. Now the question arises, if CONFIG_ARCH_HIPRI_INTERRUPT, + * do we disable all interrupts (except SVCall), or do we only disable the + * "normal" interrupts. Since the high priority interrupts cannot interact + * with the OS, you may want to permit the high priority interrupts even if + * interrupts are disabled. The setting CONFIG_ARCH_INT_DISABLEALL can be + * used to select either behavior: + * + * ----------------------------+--------------+---------------------------- + * CONFIG_ARCH_HIPRI_INTERRUPT | NO | YES + * ----------------------------+--------------+--------------+------------- + * CONFIG_ARCH_INT_DISABLEALL | N/A | YES | NO + * ----------------------------+--------------+--------------+------------- + * | | | SVCall + * | SVCall | SVCall | HIGH + * Disable here and below --------> MAXNORMAL ---> HIGH --------> MAXNORMAL + * | | MAXNORMAL | + * ----------------------------+--------------+--------------+------------- + */ + +#if defined(CONFIG_ARCH_HIPRI_INTERRUPT) && defined(CONFIG_ARCH_INT_DISABLEALL) +# define NVIC_SYSH_MAXNORMAL_PRIORITY (NVIC_SYSH_PRIORITY_MAX + 2*NVIC_SYSH_PRIORITY_STEP) +# define NVIC_SYSH_HIGH_PRIORITY (NVIC_SYSH_PRIORITY_MAX + NVIC_SYSH_PRIORITY_STEP) +# define NVIC_SYSH_DISABLE_PRIORITY NVIC_SYSH_HIGH_PRIORITY +# define NVIC_SYSH_SVCALL_PRIORITY NVIC_SYSH_PRIORITY_MAX +#else +# define NVIC_SYSH_MAXNORMAL_PRIORITY (NVIC_SYSH_PRIORITY_MAX + NVIC_SYSH_PRIORITY_STEP) +# define NVIC_SYSH_HIGH_PRIORITY NVIC_SYSH_PRIORITY_MAX +# define NVIC_SYSH_DISABLE_PRIORITY NVIC_SYSH_MAXNORMAL_PRIORITY +# define NVIC_SYSH_SVCALL_PRIORITY NVIC_SYSH_PRIORITY_MAX +#endif + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +#endif /* __ARCH_ARM_INCLUDE_STM32F0_CHIP_H */ diff --git a/arch/arm/include/stm32f0/irq.h b/arch/arm/include/stm32f0/irq.h new file mode 100644 index 0000000000..4d3fd84d8d --- /dev/null +++ b/arch/arm/include/stm32f0/irq.h @@ -0,0 +1,142 @@ +/**************************************************************************** + * arch/arm/include/stm32f0/irq.h + * + * 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. + * + ****************************************************************************/ + +/* This file should never be included directed but, rather, only indirectly + * through nuttx/irq.h + */ + +#ifndef __ARCH_ARM_INCLUDE_STM32F0_IRQ_H +#define __ARCH_ARM_INCLUDE_STM32F0_IRQ_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#ifndef __ASSEMBLY__ +# include +#endif +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ +/* IRQ numbers. The IRQ number corresponds vector number and hence map + * directly to bits in the NVIC. This does, however, waste several words of + * memory in the IRQ to handle mapping tables. + */ + +/* Common Processor Exceptions (vectors 0-15) */ + +#define STM32F0_IRQ_RESERVED (0) /* Reserved vector (only used with CONFIG_DEBUG_FEATURES) */ + /* Vector 0: Reset stack pointer value */ + /* Vector 1: Reset (not handler as an IRQ) */ +#define STM32F0_IRQ_NMI (2) /* Vector 2: Non-Maskable Interrupt (NMI) */ +#define STM32F0_IRQ_HARDFAULT (3) /* Vector 3: Hard fault */ + /* Vectors 4-10: Reserved */ +#define STM32F0_IRQ_SVCALL (11) /* Vector 11: SVC call */ + /* Vector 12-13: Reserved */ +#define STM32F0_IRQ_PENDSV (14) /* Vector 14: Pendable system service request */ +#define STM32F0_IRQ_SYSTICK (15) /* Vector 15: System tick */ + +/* External interrupts (vectors >= 16) */ + +#define STM32F0_IRQ_EXTINT (16) /* Vector number of the first external interrupt */ + +#define STM32F0_IRQ_WWDG (16) /* Vector 16: WWDG */ +#define STM32F0_IRQ_PVD_VDDIO2 (17) /* Vector 17: PVD_VDDIO2 */ +#define STM32F0_IRQ_RTC (18) /* Vector 18: RTC */ +#define STM32F0_IRQ_FLASH (19) /* Vector 19: FLASH */ +#define STM32F0_IRQ_RCC_CRS (20) /* Vector 20: RCC and CRS */ +#define STM32F0_IRQ_EXTI0_1 (21) /* Vector 21: EXTI0_1 */ +#define STM32F0_IRQ_EXTI2_3 (22) /* Vector 22: EXTI2_3 */ +#define STM32F0_IRQ_EXTI4_15 (23) /* Vector 23: EXTI4_15 */ +#define STM32F0_IRQ_TSC (24) /* Vector 24: TSC */ +#define STM32F0_IRQ_DMA_CH1 (25) /* Vector 25: DMA_CH1 */ +#define STM32F0_IRQ_DMA_CH23 (26) /* Vector 26: DMA_CH2_3 and DMA2_CH1_2 */ +#define STM32F0_IRQ_DMA_CH4567 (27) /* Vector 27: DMA_CH4_5_6_7 and DMA2_CH3_4_5 */ +#define STM32F0_IRQ_ADC_COMP (28) /* Vector 28: ADC_COMP */ +#define STM32F0_IRQ_TIM1_BRK (29) /* Vector 29: TIM1_BRK_UP_TRG_COM */ +#define STM32F0_IRQ_TIM1_CC (30) /* Vector 30: TIM1_CC */ +#define STM32F0_IRQ_TIM2 (31) /* Vector 31: TIM2 */ +#define STM32F0_IRQ_TIM3 (32) /* Vector 32: TIM3 */ +#define STM32F0_IRQ_TIM6_DAC (33) /* Vector 33: TIM6 and DAC */ +#define STM32F0_IRQ_TIM7 (34) /* Vector 34: TIM7 */ +#define STM32F0_IRQ_TIM14 (35) /* Vector 35: TIM14 */ +#define STM32F0_IRQ_TIM15 (36) /* Vector 36: TIM15 */ +#define STM32F0_IRQ_TIM16 (37) /* Vector 37: TIM16 */ +#define STM32F0_IRQ_TIM17 (38) /* Vector 38: TIM17 */ +#define STM32F0_IRQ_I2C1 (39) /* Vector 39: I2C1 */ +#define STM32F0_IRQ_I2C2 (40) /* Vector 40: I2C2 */ +#define STM32F0_IRQ_SPI1 (41) /* Vector 41: SPI1 */ +#define STM32F0_IRQ_SPI2 (42) /* Vector 42: SPI2 */ +#define STM32F0_IRQ_USART1 (43) /* Vector 43: USART1 */ +#define STM32F0_IRQ_USART2 (44) /* Vector 44: USART2 */ +#define STM32F0_IRQ_USART345678 (45) /* Vector 45: USART3_4_5_6_7_8 */ +#define STM32F0_IRQ_CEC_CAN (46) /* Vector 46: HDMI CEC and CAN */ +#define STM32F0_IRQ_USB (47) /* Vector 47: USB */ + +#define NR_VECTORS (64) /* 64 vectors */ +#define NR_IRQS (48) /* 64 interrupts but 48 IRQ numbers */ + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +#ifndef __ASSEMBLY__ +typedef void (*vic_vector_t)(uint32_t *regs); + +/**************************************************************************** + * Inline functions + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +#ifdef __cplusplus +extern "C" +{ +#endif + +#ifdef __cplusplus +} +#endif +#endif /* __ASSEMBLY__ */ + +#endif /* __ARCH_ARM_INCLUDE_STM32F0_IRQ_H */ diff --git a/arch/arm/src/stm32f0/Kconfig b/arch/arm/src/stm32f0/Kconfig new file mode 100644 index 0000000000..08e7f6c85c --- /dev/null +++ b/arch/arm/src/stm32f0/Kconfig @@ -0,0 +1,1560 @@ +# +# For a description of the syntax of this configuration file, +# see the file kconfig-language.txt in the NuttX tools repository. +# + +comment "STM32F0xx Configuration Options" + +choice + prompt "ST STM32F0XX Chip Selection" + default ARCH_CHIP_STM32F051R8 + depends on ARCH_CHIP_STM32F0 + +config ARCH_CHIP_STM32F030C6 + bool "STM32F030C6" + select STM32F0_STM32F03X + select STM32F0_VALUELINE + +config ARCH_CHIP_STM32F030C8 + bool "STM32F030C8" + select STM32F0_STM32F03X + select STM32F0_VALUELINE + +config ARCH_CHIP_STM32F030CC + bool "STM32F030CC" + select STM32F0_STM32F03X + select STM32F0_VALUELINE + +config ARCH_CHIP_STM32F030F4 + bool "STM32F030F4" + select STM32F0_STM32F03X + select STM32F0_VALUELINE + +config ARCH_CHIP_STM32F030K6 + bool "STM32F030K6" + select STM32F0_STM32F03X + select STM32F0_VALUELINE + +config ARCH_CHIP_STM32F030R8 + bool "STM32F030R8" + select STM32F0_STM32F03X + select STM32F0_VALUELINE + +config ARCH_CHIP_STM32F030RC + bool "STM32F030RC" + select STM32F0_STM32F03X + select STM32F0_VALUELINE + +config ARCH_CHIP_STM32F031C4 + bool "STM32F031C4" + select STM32F0_STM32F03X + select STM32F0_ACCESSLINE + +config ARCH_CHIP_STM32F031C6 + bool "STM32F031C6" + select STM32F0_STM32F03X + select STM32F0_ACCESSLINE + +config ARCH_CHIP_STM32F031E6 + bool "STM32F031E6" + select STM32F0_STM32F03X + select STM32F0_ACCESSLINE + +config ARCH_CHIP_STM32F031F4 + bool "STM32F031F4" + select STM32F0_STM32F03X + select STM32F0_ACCESSLINE + +config ARCH_CHIP_STM32F031F6 + bool "STM32F031F6" + select STM32F0_STM32F03X + select STM32F0_ACCESSLINE + +config ARCH_CHIP_STM32F031G4 + bool "STM32F031G4" + select STM32F0_STM32F03X + select STM32F0_ACCESSLINE + +config ARCH_CHIP_STM32F031G6 + bool "STM32F031G6" + select STM32F0_STM32F03X + select STM32F0_ACCESSLINE + +config ARCH_CHIP_STM32F031K4 + bool "STM32F031K4" + select STM32F0_STM32F03X + select STM32F0_ACCESSLINE + +config ARCH_CHIP_STM32F031K6 + bool "STM32F031K6" + select STM32F0_STM32F03X + select STM32F0_ACCESSLINE + +config ARCH_CHIP_STM32F038C6 + bool "STM32F038C6" + select STM32F0_STM32F03X + select STM32F0_LOWVOLTLINE + +config ARCH_CHIP_STM32F038E6 + bool "STM32F038E6" + select STM32F0_STM32F03X + select STM32F0_LOWVOLTLINE + +config ARCH_CHIP_STM32F038F6 + bool "STM32F038F6" + select STM32F0_STM32F03X + select STM32F0_LOWVOLTLINE + +config ARCH_CHIP_STM32F038G6 + bool "STM32F038G6" + select STM32F0_STM32F03X + select STM32F0_LOWVOLTLINE + +config ARCH_CHIP_STM32F038K6 + bool "STM32F038K6" + select STM32F0_STM32F03X + select STM32F0_LOWVOLTLINE + +config ARCH_CHIP_STM32F042C4 + bool "STM32F042C4" + select STM32F0_STM32F04X + select STM32F0_USBLINE + +config ARCH_CHIP_STM32F042C6 + bool "STM32F042C6" + select STM32F0_STM32F04X + select STM32F0_USBLINE + +config ARCH_CHIP_STM32F042F4 + bool "STM32F042F4" + select STM32F0_STM32F04X + select STM32F0_USBLINE + +config ARCH_CHIP_STM32F042F6 + bool "STM32F042F6" + select STM32F0_STM32F04X + select STM32F0_USBLINE + +config ARCH_CHIP_STM32F042G4 + bool "STM32F042G4" + select STM32F0_STM32F04X + select STM32F0_USBLINE + +config ARCH_CHIP_STM32F042G6 + bool "STM32F042G6" + select STM32F0_STM32F04X + select STM32F0_USBLINE + +config ARCH_CHIP_STM32F042K4 + bool "STM32F042K4" + select STM32F0_STM32F04X + select STM32F0_USBLINE + +config ARCH_CHIP_STM32F042K6 + bool "STM32F042K6" + select STM32F0_STM32F04X + select STM32F0_USBLINE + +config ARCH_CHIP_STM32F042T6 + bool "STM32F042T6" + select STM32F0_STM32F04X + select STM32F0_USBLINE + +config ARCH_CHIP_STM32F048C6 + bool "STM32F048C6" + select STM32F0_STM32F04X + select STM32F0_LOWVOLTLINE + +config ARCH_CHIP_STM32F048G6 + bool "STM32F048G6" + select STM32F0_STM32F04X + select STM32F0_LOWVOLTLINE + +config ARCH_CHIP_STM32F048T6 + bool "STM32F048T6" + select STM32F0_STM32F04X + select STM32F0_LOWVOLTLINE + +config ARCH_CHIP_STM32F051C4 + bool "STM32F051C4" + select STM32F0_STM32F05X + select STM32F0_ACCESSLINE + +config ARCH_CHIP_STM32F051C6 + bool "STM32F051C6" + select STM32F0_STM32F05X + select STM32F0_ACCESSLINE + +config ARCH_CHIP_STM32F051C8 + bool "STM32F051C8" + select STM32F0_STM32F05X + select STM32F0_ACCESSLINE + +config ARCH_CHIP_STM32F051K4 + bool "STM32F051K4" + select STM32F0_STM32F05X + select STM32F0_ACCESSLINE + +config ARCH_CHIP_STM32F051K6 + bool "STM32F051K6" + select STM32F0_STM32F05X + select STM32F0_ACCESSLINE + +config ARCH_CHIP_STM32F051K8 + bool "STM32F051K8" + select STM32F0_STM32F05X + select STM32F0_ACCESSLINE + +config ARCH_CHIP_STM32F051R4 + bool "STM32F051R4" + select STM32F0_STM32F05X + select STM32F0_ACCESSLINE + +config ARCH_CHIP_STM32F051R6 + bool "STM32F051R6" + select STM32F0_STM32F05X + select STM32F0_ACCESSLINE + +config ARCH_CHIP_STM32F051R8 + bool "STM32F051R8" + select STM32F0_STM32F05X + select STM32F0_ACCESSLINE + +config ARCH_CHIP_STM32F051T8 + bool "STM32F051T8" + select STM32F0_STM32F05X + select STM32F0_ACCESSLINE + +config ARCH_CHIP_STM32F058C8 + bool "STM32F058C8" + select STM32F0_STM32F05X + select STM32F0_LOWVOLTLINE + +config ARCH_CHIP_STM32F058R8 + bool "STM32F058R8" + select STM32F0_STM32F05X + select STM32F0_LOWVOLTLINE + +config ARCH_CHIP_STM32F058T8 + bool "STM32F058T8" + select STM32F0_STM32F05X + select STM32F0_LOWVOLTLINE + +config ARCH_CHIP_STM32F070C6 + bool "STM32F070C6" + select STM32F0_STM32F07X + select STM32F0_VALUELINE + +config ARCH_CHIP_STM32F070CB + bool "STM32F070CB" + select STM32F0_STM32F07X + select STM32F0_VALUELINE + +config ARCH_CHIP_STM32F070F6 + bool "STM32F070F6" + select STM32F0_STM32F07X + select STM32F0_VALUELINE + +config ARCH_CHIP_STM32F070RB + bool "STM32F070RB" + select STM32F0_STM32F07X + select STM32F0_VALUELINE + +config ARCH_CHIP_STM32F071C8 + bool "STM32F071C8" + select STM32F0_STM32F07X + select STM32F0_ACCESSLINE + +config ARCH_CHIP_STM32F071CB + bool "STM32F071CB" + select STM32F0_STM32F07X + select STM32F0_ACCESSLINE + +config ARCH_CHIP_STM32F071RB + bool "STM32F071RB" + select STM32F0_STM32F07X + select STM32F0_ACCESSLINE + +config ARCH_CHIP_STM32F071V8 + bool "STM32F071V8" + select STM32F0_STM32F07X + select STM32F0_ACCESSLINE + +config ARCH_CHIP_STM32F071VB + bool "STM32F071VB" + select STM32F0_STM32F07X + select STM32F0_ACCESSLINE + +config ARCH_CHIP_STM32F072C8 + bool "STM32F072C8" + select STM32F0_STM32F07X + select STM32F0_USBLINE + +config ARCH_CHIP_STM32F072CB + bool "STM32F072CB" + select STM32F0_STM32F07X + select STM32F0_USBLINE + +config ARCH_CHIP_STM32F072R8 + bool "STM32F072R8" + select STM32F0_STM32F07X + select STM32F0_USBLINE + +config ARCH_CHIP_STM32F072RB + bool "STM32F072RB" + select STM32F0_STM32F07X + select STM32F0_USBLINE + +config ARCH_CHIP_STM32F072V8 + bool "STM32F072V8" + select STM32F0_STM32F07X + select STM32F0_USBLINE + +config ARCH_CHIP_STM32F072VB + bool "STM32F072VB" + select STM32F0_STM32F07X + select STM32F0_USBLINE + +config ARCH_CHIP_STM32F078CB + bool "STM32F078CB" + select STM32F0_STM32F07X + select STM32F0_LOWVOLTLINE + +config ARCH_CHIP_STM32F078RB + bool "STM32F078RB" + select STM32F0_STM32F07X + select STM32F0_LOWVOLTLINE + +config ARCH_CHIP_STM32F078VB + bool "STM32F078VB" + select STM32F0_STM32F07X + select STM32F0_LOWVOLTLINE + +config ARCH_CHIP_STM32F091CB + bool "STM32F091CB" + select STM32F0_STM32F09X + select STM32F0_ACCESSLINE + +config ARCH_CHIP_STM32F091CC + bool "STM32F091CC" + select STM32F0_STM32F09X + select STM32F0_ACCESSLINE + +config ARCH_CHIP_STM32F091RB + bool "STM32F091RB" + select STM32F0_STM32F09X + select STM32F0_ACCESSLINE + +config ARCH_CHIP_STM32F091RC + bool "STM32F091RC" + select STM32F0_STM32F09X + select STM32F0_ACCESSLINE + +config ARCH_CHIP_STM32F091VB + bool "STM32F091VB" + select STM32F0_STM32F09X + select STM32F0_ACCESSLINE + +config ARCH_CHIP_STM32F091VC + bool "STM32F091VC" + select STM32F0_STM32F09X + select STM32F0_ACCESSLINE + +config ARCH_CHIP_STM32F098CC + bool "STM32F098CC" + select STM32F0_STM32F09X + select STM32F0_LOWVOLTLINE + +config ARCH_CHIP_STM32F098RC + bool "STM32F098RC" + select STM32F0_STM32F09X + select STM32F0_LOWVOLTLINE + +config ARCH_CHIP_STM32F098VC + bool "STM32F098VC" + select STM32F0_STM32F09X + select STM32F0_LOWVOLTLINE + +endchoice + +config ARCH_FAMILY_STM32F0XX + bool + +choice + prompt "Override Flash Size Designator" + default STM32F0_FLASH_CONFIG_DEFAULT + depends on ARCH_CHIP_STM32 + ---help--- + STM32F series parts numbering (sans the package type) ends with a number or letter + that designates the FLASH size. + + Designator Size in KiB + 4 16 + 6 32 + 8 64 + B 128 + C 256 + D 384 + E 512 + F 768 + G 1024 + I 2048 + + This configuration option defaults to using the configuration based on that designator + or the default smaller size if there is no last character designator is present in the + STM32 Chip Selection. + + Examples: + If the STM32F407VE is chosen, the Flash configuration would be 'E', if a variant of + the part with a 2048 KiB Flash is released in the future one could simply select + the 'I' designator here. + + If an STM32F42xxx or Series parts is chosen the default Flash configuration will be 'G' + and can be set herein to 'I' to choose the larger FLASH part. + +config STM32F0_FLASH_CONFIG_DEFAULT + bool "Default" + +config STM32F0_FLASH_CONFIG_4 + bool "4 16KiB" + +config STM32F0_FLASH_CONFIG_6 + bool "6 32KiB" + +config STM32F0_FLASH_CONFIG_8 + bool "8 64KiB" + +config STM32F0_FLASH_CONFIG_B + bool "B 128KiB" + +config STM32F0_FLASH_CONFIG_C + bool "C 256KiB" + +config STM32F0_FLASH_CONFIG_D + bool "D 384KiB" + +config STM32F0_FLASH_CONFIG_E + bool "E 512KiB" + +config STM32F0_FLASH_CONFIG_F + bool "F 768KiB" + +config STM32F0_FLASH_CONFIG_G + bool "G 1024KiB" + +config STM32F0_FLASH_CONFIG_I + bool "I 2048KiB" + +endchoice + +config STM32F0_STM32F03X + bool + default n + +config STM32F0_STM32F04X + bool + default n + +config STM32F0_STM32F05X + bool + default n + +config STM32F0_STM32F07X + bool + default n + +config STM32F0_STM32F09X + bool + default n + +config STM32F0_VALUELINE + bool + default n + select STM32F0_HAVE_USART3 + select STM32F0_HAVE_USART4 + select STM32F0_HAVE_USART5 + select STM32F0_HAVE_TIM1 + select STM32F0_HAVE_TIM5 + select STM32F0_HAVE_TIM6 + select STM32F0_HAVE_TIM7 + select STM32F0_HAVE_TIM12 + select STM32F0_HAVE_TIM13 + select STM32F0_HAVE_TIM14 + select STM32F0_HAVE_TIM15 + select STM32F0_HAVE_TIM16 + select STM32F0_HAVE_TIM17 + select STM32F0_HAVE_SPI2 if STM32F0_HIGHDENSITY + select STM32F0_HAVE_SPI3 if STM32F0_HIGHDENSITY + +config STM32F0_ACCESSLINE + bool + default n + select STM32F0_HAVE_OTGFS + select STM32F0_HAVE_USART3 + select STM32F0_HAVE_USART4 + select STM32F0_HAVE_USART5 + select STM32F0_HAVE_TIM1 + select STM32F0_HAVE_TIM5 + select STM32F0_HAVE_TIM6 + select STM32F0_HAVE_TIM7 + select STM32F0_HAVE_ADC2 + select STM32F0_HAVE_CAN1 + select STM32F0_HAVE_CAN2 + select STM32F0_HAVE_ETHMAC + select STM32F0_HAVE_SPI2 + select STM32F0_HAVE_SPI3 + +config STM32F0_LOWVOLTLINE + bool + default n + select STM32F0_HAVE_OTGFS + select STM32F0_HAVE_USART3 + select STM32F0_HAVE_USART4 + select STM32F0_HAVE_USART5 + select STM32F0_HAVE_TIM1 + select STM32F0_HAVE_TIM5 + select STM32F0_HAVE_TIM6 + select STM32F0_HAVE_TIM7 + select STM32F0_HAVE_ADC2 + select STM32F0_HAVE_CAN1 + select STM32F0_HAVE_CAN2 + select STM32F0_HAVE_ETHMAC + select STM32F0_HAVE_SPI2 + select STM32F0_HAVE_SPI3 + +config STM32F0_USBLINE + bool + default n + select STM32F0_HAVE_USBDEV + select STM32F0_HAVE_FSMC + select STM32F0_HAVE_USART3 + select STM32F0_HAVE_SPI2 + +config STM32F0_DFU + bool "DFU bootloader" + default n + depends on !STM32F0_VALUELINE + ---help--- + Configure and position code for use with the STMicro DFU bootloader. Do + not select this option if you will load code using JTAG/SWM. + + +choice + prompt "SysTick clock source" + default STM32F0_SYSTICK_CORECLK + +config STM32F0_SYSTICK_CORECLK + bool "Cortex-M0 core clock" + +config STM32F0_SYSTICK_CORECLK_DIV16 + bool "Cortex-M0 core clock divided by 16" + +endchoice + + +menu "STM32 Peripheral Support" + +# These "hidden" settings determine is a peripheral option is available for the +# selection MCU + +config STM32F0_HAVE_CCM + bool + default n + +config STM32F0_HAVE_USBDEV + bool + default n + +config STM32F0_HAVE_OTGFS + bool + default n + +config STM32F0_HAVE_FSMC + bool + default n + +config STM32F0_HAVE_HRTIM1 + bool + default n + +config STM32F0_HAVE_LTDC + bool + default n + +config STM32F0_HAVE_USART3 + bool + default n + +config STM32F0_HAVE_USART4 + bool + default n + +config STM32F0_HAVE_USART5 + bool + default n + +config STM32F0_HAVE_USART6 + bool + default n + +config STM32F0_HAVE_USART7 + bool + default n + +config STM32F0_HAVE_USART8 + bool + default n + +config STM32F0_HAVE_TIM1 + bool + default n + +config STM32F0_HAVE_TIM2 + bool + default n + +config STM32F0_HAVE_TIM3 + bool + default n + +config STM32F0_HAVE_TIM4 + bool + default n + +config STM32F0_HAVE_TIM5 + bool + default n + +config STM32F0_HAVE_TIM6 + bool + default n + +config STM32F0_HAVE_TIM7 + bool + default n + +config STM32F0_HAVE_TIM8 + bool + default n + +config STM32F0_HAVE_TIM9 + bool + default n + +config STM32F0_HAVE_TIM10 + bool + default n + +config STM32F0_HAVE_TIM11 + bool + default n + +config STM32F0_HAVE_TIM12 + bool + default n + +config STM32F0_HAVE_TIM13 + bool + default n + +config STM32F0_HAVE_TIM14 + bool + default n + +config STM32F0_HAVE_TIM15 + bool + default n + +config STM32F0_HAVE_TIM16 + bool + default n + +config STM32F0_HAVE_TIM17 + bool + default n + +config STM32F0_HAVE_TSC + bool + default n + +config STM32F0_HAVE_ADC2 + bool + default n + +config STM32F0_HAVE_ADC3 + bool + default n + +config STM32F0_HAVE_ADC4 + bool + default n + +config STM32F0_HAVE_ADC1_DMA + bool + default n + +config STM32F0_HAVE_ADC2_DMA + bool + default n + +config STM32F0_HAVE_ADC3_DMA + bool + default n + +config STM32F0_HAVE_ADC4_DMA + bool + default n + +config STM32F0_HAVE_SDADC1 + bool + default n + +config STM32F0_HAVE_SDADC2 + bool + default n + +config STM32F0_HAVE_SDADC3 + bool + default n + +config STM32F0_HAVE_SDADC1_DMA + bool + default n + +config STM32F0_HAVE_SDADC2_DMA + bool + default n + +config STM32F0_HAVE_SDADC3_DMA + bool + default n + +config STM32F0_HAVE_CAN1 + bool + default n + +config STM32F0_HAVE_CAN2 + bool + default n + +config STM32F0_HAVE_COMP1 + bool + default n + +config STM32F0_HAVE_COMP2 + bool + default n + +config STM32F0_HAVE_COMP3 + bool + default n + +config STM32F0_HAVE_COMP4 + bool + default n + +config STM32F0_HAVE_COMP5 + bool + default n + +config STM32F0_HAVE_COMP6 + bool + default n + +config STM32F0_HAVE_COMP7 + bool + default n + +config STM32F0_HAVE_DAC1 + bool + default n + +config STM32F0_HAVE_DAC2 + bool + default n + +config STM32F0_HAVE_RNG + bool + default n + +config STM32F0_HAVE_ETHMAC + bool + default n + +config STM32F0_HAVE_I2C2 + bool + default n + +config STM32F0_HAVE_I2C3 + bool + default n + +config STM32F0_HAVE_SPI2 + bool + default n + +config STM32F0_HAVE_SPI3 + bool + default n + +config STM32F0_HAVE_SPI4 + bool + default n + +config STM32F0_HAVE_SPI5 + bool + default n + +config STM32F0_HAVE_SPI6 + bool + default n + +config STM32F0_HAVE_SAIPLL + bool + default n + +config STM32F0_HAVE_I2SPLL + bool + default n + +config STM32F0_HAVE_OPAMP1 + bool + default n + +config STM32F0_HAVE_OPAMP2 + bool + default n + +config STM32F0_HAVE_OPAMP3 + bool + default n + +config STM32F0_HAVE_OPAMP4 + bool + default n + +# These are the peripheral selections proper + +config STM32F0_ADC1 + bool "ADC1" + default n + select STM32F0_ADC + +config STM32F0_ADC2 + bool "ADC2" + default n + select STM32F0_ADC + depends on STM32F0_HAVE_ADC2 + +config STM32F0_ADC3 + bool "ADC3" + default n + select STM32F0_ADC + depends on STM32F0_HAVE_ADC3 + +config STM32F0_ADC4 + bool "ADC4" + default n + select STM32F0_ADC + depends on STM32F0_HAVE_ADC4 + +config STM32F0_SDADC1 + bool "SDADC1" + default n + select STM32F0_SDADC + depends on STM32F0_HAVE_SDADC1 + +config STM32F0_SDADC2 + bool "SDADC2" + default n + select STM32F0_SDADC + depends on STM32F0_HAVE_SDADC2 + +config STM32F0_SDADC3 + bool "SDADC3" + default n + select STM32F0_SDADC + depends on STM32F0_HAVE_SDADC3 + +config STM32F0_COMP + bool "COMP" + default n + +config STM32F0_COMP1 + bool "COMP1" + default n + depends on STM32F0_HAVE_COMP1 + +config STM32F0_COMP2 + bool "COMP2" + default n + depends on STM32F0_HAVE_COMP2 + +config STM32F0_COMP3 + bool "COMP3" + default n + depends on STM32F0_HAVE_COMP3 + +config STM32F0_COMP4 + bool "COMP4" + default n + depends on STM32F0_HAVE_COMP4 + +config STM32F0_COMP5 + bool "COMP5" + default n + depends on STM32F0_HAVE_COMP5 + +config STM32F0_COMP6 + bool "COMP6" + default n + depends on STM32F0_HAVE_COMP6 + +config STM32F0_COMP7 + bool "COMP7" + default n + depends on STM32F0_HAVE_COMP6 + +config STM32F0_BKP + bool "BKP" + default n + +config STM32F0_BKPSRAM + bool "Enable BKP RAM Domain" + default n + +config STM32F0_CAN1 + bool "CAN1" + default n + select CAN + select STM32F0_CAN + depends on STM32F0_HAVE_CAN1 + +config STM32F0_CAN2 + bool "CAN2" + default n + select CAN + select STM32F0_CAN + depends on STM32F0_HAVE_CAN2 + +config STM32F0_CEC + bool "CEC" + default n + depends on STM32F0_VALUELINE + +config STM32F0_CRC + bool "CRC" + default n + +config STM32F0_CRYP + bool "CRYP" + default n + depends on STM32F0_STM32F207 || STM32F0_STM32F40XX + +config STM32F0_DMA1 + bool "DMA1" + default n + select ARCH_DMA + +config STM32F0_DMA2 + bool "DMA2" + default n + select ARCH_DMA + depends on !STM32F0_VALUELINE || (STM32F0_VALUELINE && STM32F0_HIGHDENSITY) + +config STM32F0_DAC1 + bool "DAC1" + default n + depends on STM32F0_HAVE_DAC1 + select STM32F0_DAC + +config STM32F0_DAC2 + bool "DAC2" + default n + depends on STM32F0_HAVE_DAC2 + select STM32F0_DAC + +config STM32F0_FSMC + bool "FSMC" + default n + depends on STM32F0_HAVE_FSMC + +config STM32F0_HASH + bool "HASH" + default n + depends on STM32F0_STM32F207 || STM32F0_STM32F40XX + +config STM32F0_HRTIM1 + bool "HRTIM1" + default n + depends on STM32F0_HAVE_HRTIM1 + +config STM32F0_I2C1 + bool "I2C1" + default n + select STM32F0_I2C + +config STM32F0_I2C2 + bool "I2C2" + default n + depends on STM32F0_HAVE_I2C2 + select STM32F0_I2C + +config STM32F0_I2C3 + bool "I2C3" + default n + depends on STM32F0_HAVE_I2C3 + select STM32F0_I2C + +config STM32F0_PWR + bool "PWR" + default n + +config STM32F0_RNG + bool "RNG" + default n + depends on STM32F0_HAVE_RNG + select ARCH_HAVE_RNG + +config STM32F0_SDIO + bool "SDIO" + default n + depends on !STM32F0_CONNECTIVITYLINE && !STM32F0_VALUELINE + select ARCH_HAVE_SDIO + select ARCH_HAVE_SDIOWAIT_WRCOMPLETE + select SDIO_PREFLIGHT + +config STM32F0_SPI1 + bool "SPI1" + default n + select SPI + select STM32F0_SPI + +config STM32F0_SPI2 + bool "SPI2" + default n + depends on STM32F0_HAVE_SPI2 + select SPI + select STM32F0_SPI + +config STM32F0_SPI3 + bool "SPI3" + default n + depends on STM32F0_HAVE_SPI3 + select SPI + select STM32F0_SPI + +config STM32F0_SPI4 + bool "SPI4" + default n + depends on STM32F0_HAVE_SPI4 + select SPI + select STM32F0_SPI + +config STM32F0_SPI5 + bool "SPI5" + default n + depends on STM32F0_HAVE_SPI5 + select SPI + select STM32F0_SPI + +config STM32F0_SPI6 + bool "SPI6" + default n + depends on STM32F0_HAVE_SPI6 + select SPI + select STM32F0_SPI + +config STM32F0_SYSCFG + bool "SYSCFG" + default y + +config STM32F0_TIM1 + bool "TIM1" + default n + depends on STM32F0_HAVE_TIM1 + +config STM32F0_TIM2 + bool "TIM2" + default n + +config STM32F0_TIM3 + bool "TIM3" + default n + depends on STM32F0_HAVE_TIM3 + +config STM32F0_TIM4 + bool "TIM4" + default n + depends on STM32F0_HAVE_TIM4 + +config STM32F0_TIM5 + bool "TIM5" + default n + depends on STM32F0_HAVE_TIM5 + +config STM32F0_TIM6 + bool "TIM6" + default n + depends on STM32F0_HAVE_TIM6 + +config STM32F0_TIM7 + bool "TIM7" + default n + depends on STM32F0_HAVE_TIM7 + +config STM32F0_TIM8 + bool "TIM8" + default n + depends on STM32F0_HAVE_TIM8 + +config STM32F0_TIM9 + bool "TIM9" + default n + depends on STM32F0_HAVE_TIM9 + +config STM32F0_TIM10 + bool "TIM10" + default n + depends on STM32F0_HAVE_TIM10 + +config STM32F0_TIM11 + bool "TIM11" + default n + depends on STM32F0_HAVE_TIM11 + +config STM32F0_TIM12 + bool "TIM12" + default n + depends on STM32F0_HAVE_TIM12 + +config STM32F0_TIM13 + bool "TIM13" + default n + depends on STM32F0_HAVE_TIM13 + +config STM32F0_TIM14 + bool "TIM14" + default n + depends on STM32F0_HAVE_TIM14 + +config STM32F0_TIM15 + bool "TIM15" + default n + depends on STM32F0_HAVE_TIM15 + +config STM32F0_TIM16 + bool "TIM16" + default n + depends on STM32F0_HAVE_TIM16 + +config STM32F0_TIM17 + bool "TIM17" + default n + depends on STM32F0_HAVE_TIM17 + +config STM32F0_TSC + bool "TSC" + default n + depends on STM32F0_HAVE_TSC + +config STM32F0_USART1 + bool "USART1" + default n + select STM32F0_USART + +config STM32F0_USART2 + bool "USART2" + default n + select STM32F0_USART + +config STM32F0_USART3 + bool "USART3" + default n + depends on STM32F0_HAVE_USART3 + select STM32F0_USART + +config STM32F0_USART4 + bool "USART4" + default n + depends on STM32F0_HAVE_USART4 + select STM32F0_USART + +config STM32F0_USART5 + bool "USART5" + default n + depends on STM32F0_HAVE_USART5 + select STM32F0_USART + +config STM32F0_USART6 + bool "USART6" + default n + depends on STM32F0_HAVE_USART6 + select STM32F0_USART + +config STM32F0_USART7 + bool "USART7" + default n + depends on STM32F0_HAVE_USART7 + select STM32F0_USART + +config STM32F0_USART8 + bool "USART8" + default n + depends on STM32F0_HAVE_USART8 + select STM32F0_USART + +config STM32F0_USB + bool "USB Device" + default n + depends on STM32F0_HAVE_USBDEV + select USBDEV + +config STM32F0_IWDG + bool "IWDG" + default n + select WATCHDOG + +config STM32F0_WWDG + bool "WWDG" + default n + select WATCHDOG + +endmenu + +config STM32F0_ADC + bool + +config STM32F0_SDADC + bool + +config STM32F0_DAC + bool + +config STM32F0_SPI + bool + +config STM32F0_I2C + bool + +config STM32F0_CAN + bool + +config STM32F0_USART + bool + +config STM32F0_SERIALDRIVER + bool + +config STM32F0_1WIREDRIVER + bool + +menu "U[S]ART Configuration" + depends on STM32F0_USART + +comment "U[S]ART Device Configuration" + +choice + prompt "USART1 Driver Configuration" + default STM32F0_USART1_SERIALDRIVER + depends on STM32F0_USART1 + +config STM32F0_USART1_SERIALDRIVER + bool "Standard serial driver" + select USART1_SERIALDRIVER + select ARCH_HAVE_SERIAL_TERMIOS + select STM32F0_SERIALDRIVER + +config STM32F0_USART1_1WIREDRIVER + bool "1-Wire driver" + select STM32F0_1WIREDRIVER + +endchoice # USART1 Driver Configuration + +if STM32F0_USART1_SERIALDRIVER + +config USART1_RS485 + bool "RS-485 on USART1" + default n + ---help--- + Enable RS-485 interface on USART1. Your board config will have to + provide GPIO_USART1_RS485_DIR pin definition. + +config USART1_RS485_DIR_POLARITY + int "USART1 RS-485 DIR pin polarity" + default 1 + range 0 1 + depends on USART1_RS485 + ---help--- + Polarity of DIR pin for RS-485 on USART1. Set to state on DIR pin which + enables TX (0 - low / nTXEN, 1 - high / TXEN). + +endif # STM32F0_USART1_SERIALDRIVER + + +choice + prompt "USART2 Driver Configuration" + default STM32F0_USART2_SERIALDRIVER + depends on STM32F0_USART2 + +config STM32F0_USART2_SERIALDRIVER + bool "Standard serial driver" + select USART2_SERIALDRIVER + select ARCH_HAVE_SERIAL_TERMIOS + select STM32F0_SERIALDRIVER + +config STM32F0_USART2_1WIREDRIVER + bool "1-Wire driver" + select STM32F0_1WIREDRIVER + +endchoice # USART2 Driver Configuration + +if STM32F0_USART2_SERIALDRIVER + +config USART2_RS485 + bool "RS-485 on USART2" + default n + ---help--- + Enable RS-485 interface on USART2. Your board config will have to + provide GPIO_USART2_RS485_DIR pin definition. + +config USART2_RS485_DIR_POLARITY + int "USART2 RS-485 DIR pin polarity" + default 1 + range 0 1 + depends on USART2_RS485 + ---help--- + Polarity of DIR pin for RS-485 on USART2. Set to state on DIR pin which + enables TX (0 - low / nTXEN, 1 - high / TXEN). + +endif # STM32F0_USART2_SERIALDRIVER + + +choice + prompt "USART3 Driver Configuration" + default STM32F0_USART3_SERIALDRIVER + depends on STM32F0_USART3 + +config STM32F0_USART3_SERIALDRIVER + bool "Standard serial driver" + select USART3_SERIALDRIVER + select ARCH_HAVE_SERIAL_TERMIOS + select STM32F0_SERIALDRIVER + +config STM32F0_USART3_1WIREDRIVER + bool "1-Wire driver" + select STM32F0_1WIREDRIVER + +endchoice # USART3 Driver Configuration + +if STM32F0_USART3_SERIALDRIVER + +config USART3_RS485 + bool "RS-485 on USART3" + default n + ---help--- + Enable RS-485 interface on USART3. Your board config will have to + provide GPIO_USART3_RS485_DIR pin definition. + +config USART3_RS485_DIR_POLARITY + int "USART3 RS-485 DIR pin polarity" + default 1 + range 0 1 + depends on USART3_RS485 + ---help--- + Polarity of DIR pin for RS-485 on USART3. Set to state on DIR pin which + enables TX (0 - low / nTXEN, 1 - high / TXEN). + +endif # STM32F0_USART3_SERIALDRIVER + + +choice + prompt "USART4 Driver Configuration" + default STM32F0_USART4_SERIALDRIVER + depends on STM32F0_USART4 + +config STM32F0_USART4_SERIALDRIVER + bool "Standard serial driver" + select USART4_SERIALDRIVER + select ARCH_HAVE_SERIAL_TERMIOS + select STM32F0_SERIALDRIVER + +config STM32F0_USART4_1WIREDRIVER + bool "1-Wire driver" + select STM32F0_1WIREDRIVER + +endchoice # USART4 Driver Configuration + +if STM32F0_USART4_SERIALDRIVER + +config USART4_RS485 + bool "RS-485 on USART4" + default n + ---help--- + Enable RS-485 interface on USART4. Your board config will have to + provide GPIO_USART4_RS485_DIR pin definition. + +config USART4_RS485_DIR_POLARITY + int "USART4 RS-485 DIR pin polarity" + default 1 + range 0 1 + depends on USART4_RS485 + ---help--- + Polarity of DIR pin for RS-485 on USART4. Set to state on DIR pin which + enables TX (0 - low / nTXEN, 1 - high / TXEN). + +endif # STM32F0_USART4_SERIALDRIVER + + +choice + prompt "USART5 Driver Configuration" + default STM32F0_USART5_SERIALDRIVER + depends on STM32F0_USART5 + +config STM32F0_USART5_SERIALDRIVER + bool "Standard serial driver" + select USART5_SERIALDRIVER + select ARCH_HAVE_SERIAL_TERMIOS + select STM32F0_SERIALDRIVER + +config STM32F0_USART5_1WIREDRIVER + bool "1-Wire driver" + select STM32F0_1WIREDRIVER + +endchoice # USART5 Driver Configuration + +if STM32F0_USART5_SERIALDRIVER + +config USART5_RS485 + bool "RS-485 on USART5" + default n + ---help--- + Enable RS-485 interface on USART5. Your board config will have to + provide GPIO_USART5_RS485_DIR pin definition. + +config USART5_RS485_DIR_POLARITY + int "USART5 RS-485 DIR pin polarity" + default 1 + range 0 1 + depends on USART5_RS485 + ---help--- + Polarity of DIR pin for RS-485 on USART5. Set to state on DIR pin which + enables TX (0 - low / nTXEN, 1 - high / TXEN). + +endif # STM32F0_USART5_SERIALDRIVER + + +choice + prompt "USART6 Driver Configuration" + default STM32F0_USART6_SERIALDRIVER + depends on STM32F0_USART6 + +config STM32F0_USART6_SERIALDRIVER + bool "Standard serial driver" + select USART6_SERIALDRIVER + select ARCH_HAVE_SERIAL_TERMIOS + select STM32F0_SERIALDRIVER + +config STM32F0_USART6_1WIREDRIVER + bool "1-Wire driver" + select STM32F0_1WIREDRIVER + +endchoice # USART6 Driver Configuration + +if STM32F0_USART6_SERIALDRIVER + +config USART6_RS485 + bool "RS-485 on USART6" + default n + ---help--- + Enable RS-485 interface on USART6. Your board config will have to + provide GPIO_USART6_RS485_DIR pin definition. + +config USART6_RS485_DIR_POLARITY + int "USART6 RS-485 DIR pin polarity" + default 1 + range 0 1 + depends on USART6_RS485 + ---help--- + Polarity of DIR pin for RS-485 on USART6. Set to state on DIR pin which + enables TX (0 - low / nTXEN, 1 - high / TXEN). + +endif # STM32F0_USART6_SERIALDRIVER + + +choice + prompt "USART7 Driver Configuration" + default STM32F0_USART7_SERIALDRIVER + depends on STM32F0_USART7 + +config STM32F0_USART7_SERIALDRIVER + bool "Standard serial driver" + select USART7_SERIALDRIVER + select ARCH_HAVE_SERIAL_TERMIOS + select STM32F0_SERIALDRIVER + +config STM32F0_USART7_1WIREDRIVER + bool "1-Wire driver" + select STM32F0_1WIREDRIVER + +endchoice # USART7 Driver Configuration + +if STM32F0_USART7_SERIALDRIVER + +config USART7_RS485 + bool "RS-485 on USART7" + default n + ---help--- + Enable RS-485 interface on USART7. Your board config will have to + provide GPIO_USART7_RS485_DIR pin definition. + +config USART7_RS485_DIR_POLARITY + int "USART7 RS-485 DIR pin polarity" + default 1 + range 0 1 + depends on USART7_RS485 + ---help--- + Polarity of DIR pin for RS-485 on USART7. Set to state on DIR pin which + enables TX (0 - low / nTXEN, 1 - high / TXEN). + +endif # STM32F0_USART7_SERIALDRIVER + + +choice + prompt "USART8 Driver Configuration" + default STM32F0_USART8_SERIALDRIVER + depends on STM32F0_USART8 + +config STM32F0_USART8_SERIALDRIVER + bool "Standard serial driver" + select USART8_SERIALDRIVER + select ARCH_HAVE_SERIAL_TERMIOS + select STM32F0_SERIALDRIVER + +config STM32F0_USART8_1WIREDRIVER + bool "1-Wire driver" + select STM32F0_1WIREDRIVER + +endchoice # USART8 Driver Configuration + +if STM32F0_USART8_SERIALDRIVER + +config USART8_RS485 + bool "RS-485 on USART8" + default n + ---help--- + Enable RS-485 interface on USART8. Your board config will have to + provide GPIO_USART8_RS485_DIR pin definition. + +config USART8_RS485_DIR_POLARITY + int "USART8 RS-485 DIR pin polarity" + default 1 + range 0 1 + depends on USART8_RS485 + ---help--- + Polarity of DIR pin for RS-485 on USART8. Set to state on DIR pin which + enables TX (0 - low / nTXEN, 1 - high / TXEN). + +endif # STM32F0_USART8_SERIALDRIVER + +endmenu diff --git a/arch/arm/src/stm32f0/Make.defs b/arch/arm/src/stm32f0/Make.defs new file mode 100644 index 0000000000..6a42cddc97 --- /dev/null +++ b/arch/arm/src/stm32f0/Make.defs @@ -0,0 +1,99 @@ +############################################################################ +# arch/arm/src/stm32f0/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. +# +############################################################################ + +HEAD_ASRC = + +CMN_ASRCS = up_exception.S up_saveusercontext.S up_fullcontextrestore.S +CMN_ASRCS += up_switchcontext.S vfork.S + +CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copyfullstate.c +CMN_CSRCS += up_createstack.c up_mdelay.c up_udelay.c up_exit.c +CMN_CSRCS += up_initialize.c up_initialstate.c up_interruptcontext.c +CMN_CSRCS += up_puts.c up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c +CMN_CSRCS += up_releasepending.c up_releasestack.c up_reprioritizertr.c +CMN_CSRCS += up_schedulesigaction.c up_sigdeliver.c up_stackframe.c +CMN_CSRCS += up_systemreset.c up_unblocktask.c up_usestack.c up_doirq.c +CMN_CSRCS += up_hardfault.c up_svcall.c up_vectors.c up_vfork.c + +ifeq ($(CONFIG_BUILD_PROTECTED),y) +CMN_CSRCS += up_task_start.c up_pthread_start.c +ifneq ($(CONFIG_DISABLE_SIGNALS),y) +CMN_CSRCS += up_signal_dispatch.c +CMN_UASRCS += up_signal_handler.S +endif +endif + +ifeq ($(CONFIG_STACK_COLORATION),y) +CMN_CSRCS += up_checkstack.c +endif + +ifeq ($(CONFIG_DEBUG_FEATURES),y) +CMN_CSRCS += up_dumpnvic.c +endif + +CHIP_ASRCS = +CHIP_CSRCS = stm32f0_clockconfig.c stm32f0_gpio.c stm32f0_idle.c +CHIP_CSRCS += stm32f0_irq.c stm32f0_lowputc.c stm32f0_serial.c +CHIP_CSRCS += stm32f0_start.c + +# Configuration-dependent STM32F0xx files + +ifneq ($(CONFIG_SCHED_TICKLESS),y) +CHIP_CSRCS += stm32f0_timerisr.c +endif + +ifeq ($(CONFIG_BUILD_PROTECTED),y) +CHIP_CSRCS += stm32f0_userspace.c +endif + +ifeq ($(CONFIG_STM32F0_GPIOIRQ),y) +CHIP_CSRCS += stm32f0_gpioint.c +endif + +ifeq ($(CONFIG_ARCH_IRQPRIO),y) +CHIP_CSRCS += stm32f0_irqprio.c +endif + +ifeq ($(CONFIG_STM32F0_SPI0),y) +CHIP_CSRCS += stm32f0_spi.c +else +ifeq ($(CONFIG_STM32F0_SPI1),y) +CHIP_CSRCS += stm32f0_spi.c +endif +endif + +ifeq ($(CONFIG_PWM),y) +CHIP_CSRCS += stm32f0_pwm.c +endif diff --git a/arch/arm/src/stm32f0/chip.h b/arch/arm/src/stm32f0/chip.h new file mode 100644 index 0000000000..5bf33a0e23 --- /dev/null +++ b/arch/arm/src/stm32f0/chip.h @@ -0,0 +1,58 @@ +/************************************************************************************ + * arch/arm/src/stm32f0/chip.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_H +#define __ARCH_ARM_SRC_STM32F0_CHIP_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include "nvic.h" + +/* Include the chip capabilities file */ + +#include + +#define ARMV6M_PERIPHERAL_INTERRUPTS 32 + +/* Include the memory map file. Other chip hardware files should then include + * this file for the proper setup. + */ + +#include "chip/stm32f0_memorymap.h" + +#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_H */ diff --git a/arch/arm/src/stm32f0/chip/stm32f05xr_pinmap.h b/arch/arm/src/stm32f0/chip/stm32f05xr_pinmap.h new file mode 100644 index 0000000000..29ee3e5f01 --- /dev/null +++ b/arch/arm/src/stm32f0/chip/stm32f05xr_pinmap.h @@ -0,0 +1,126 @@ +/************************************************************************************ + * arch/arm/src/stm32f0/chip/stm32f0_pinmap.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_PINMMAP_H +#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_PINMMAP_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include "stm32f0_gpio.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* ADC */ + +#define GPIO_ADC_IN0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN0) +#define GPIO_ADC_IN1 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN1) +#define GPIO_ADC_IN2 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN2) +#define GPIO_ADC_IN3 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN3) +#define GPIO_ADC_IN4 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN4) +#define GPIO_ADC_IN5 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN5) +#define GPIO_ADC_IN6 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN6) +#define GPIO_ADC_IN7 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN7) +#define GPIO_ADC_IN8 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN0) +#define GPIO_ADC_IN9 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN1) +#define GPIO_ADC_IN10 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN0) +#define GPIO_ADC_IN11 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN1) +#define GPIO_ADC_IN12 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN2) +#define GPIO_ADC_IN13 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN3) +#define GPIO_ADC_IN14 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN4) +#define GPIO_ADC_IN15 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN5) + +/* TIMERS */ + +/* TODO: Define TIMx pins here */ + +/* USART */ + +#if defined(CONFIG_STM32F0_USART1_REMAP) +# define GPIO_USART1_TX (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN6) +# define GPIO_USART1_RX (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN7) +#else +# define GPIO_USART1_TX (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN9) +# define GPIO_USART1_RX (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN10) +#endif +#define GPIO_USART1_CTS (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN11) +#define GPIO_USART1_RTS (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN12) +#define GPIO_USART1_CK (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN8) + +#define GPIO_USART2_CTS (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN0) +#define GPIO_USART2_RTS (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN1) +#define GPIO_USART2_TX (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN2) +#define GPIO_USART2_RX (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN3) +#define GPIO_USART2_CK (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN4) + +/* SPI */ + +#if defined(CONFIG_STM32F0_SPI1_REMAP) +# define GPIO_SPI1_NSS (GPIO_ALT|GPIO_AF0 |GPIO_PORTA|GPIO_PIN15) +# define GPIO_SPI1_SCK (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN3) +# define GPIO_SPI1_MISO (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN4) +# define GPIO_SPI1_MOSI (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN5) +#else +# define GPIO_SPI1_NSS (GPIO_ALT|GPIO_AF0 |GPIO_PORTA|GPIO_PIN4) +# define GPIO_SPI1_SCK (GPIO_ALT|GPIO_AF0 |GPIO_PORTA|GPIO_PIN5) +# define GPIO_SPI1_MISO (GPIO_ALT|GPIO_AF0 |GPIO_PORTA|GPIO_PIN6) +# define GPIO_SPI1_MOSI (GPIO_ALT|GPIO_AF0 |GPIO_PORTA|GPIO_PIN7) +#endif + +#define GPIO_SPI2_NSS (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN12) +#define GPIO_SPI2_SCK (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN13) +#define GPIO_SPI2_MISO (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN14) +#define GPIO_SPI2_MOSI (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN15) + +/* I2C */ + +#if defined(CONFIG_STM32F0_I2C1_REMAP) +# define GPIO_I2C1_SCL (GPIO_ALT|GPIO_AF1 |GPIO_PORTB|GPIO_PIN8) +# define GPIO_I2C1_SDA (GPIO_ALT|GPIO_AF1 |GPIO_PORTB|GPIO_PIN9) +#else +# define GPIO_I2C1_SCL (GPIO_ALT|GPIO_AF1 |GPIO_PORTB|GPIO_PIN6) +# define GPIO_I2C1_SDA (GPIO_ALT|GPIO_AF1 |GPIO_PORTB|GPIO_PIN7) +#endif +#define GPIO_I2C1_SMBA (GPIO_ALT|GPIO_AF3 |GPIO_PORTB|GPIO_PIN5) + +#define GPIO_I2C2_SCL (GPIO_ALT|GPIO_AF1 |GPIO_PORTB|GPIO_PIN10) +#define GPIO_I2C2_SDA (GPIO_ALT|GPIO_AF1 |GPIO_PORTB|GPIO_PIN11) + +#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_PINMMAP_H */ diff --git a/arch/arm/src/stm32f0/chip/stm32f05xxx_memorymap.h b/arch/arm/src/stm32f0/chip/stm32f05xxx_memorymap.h new file mode 100644 index 0000000000..0c0ad1a40d --- /dev/null +++ b/arch/arm/src/stm32f0/chip/stm32f05xxx_memorymap.h @@ -0,0 +1,156 @@ +/************************************************************************************ + * arch/arm/src/stm32f0/chip/stm32f05xxx_memorymap.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F05XXX_MEMORYMAP_H +#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F05XXX_MEMORYMAP_H + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* STM32F050XXX Address Blocks *******************************************************/ + +#define STM32F0_CODE_BASE 0x00000000 /* 0x00000000-0x1fffffff: 512Mb code block */ +#define STM32F0_SRAM_BASE 0x20000000 /* 0x20000000-0x3fffffff: 512Mb sram block */ +#define STM32F0_PERIPH_BASE 0x40000000 /* 0x40000000-0x5fffffff: 512Mb peripheral block */ + /* 0x60000000-0xdfffffff: Reserved */ +#define STM32F0_CORTEX_BASE 0xe0000000 /* 0xe0000000-0xffffffff: 512Mb Cortex-M4 block */ + +#define STM32F0_REGION_MASK 0xf0000000 +#define STM32F0_IS_SRAM(a) ((((uint32_t)(a)) & STM32F0_REGION_MASK) == STM32F0_SRAM_BASE) + +/* Code Base Addresses **************************************************************/ + +#define STM32F0_BOOT_BASE 0x00000000 /* 0x00000000-0x000fffff: Aliased boot memory */ + /* 0x00100000-0x07ffffff: Reserved */ +#define STM32F0_FLASH_BASE 0x08000000 /* 0x08000000-0x080fffff: FLASH memory */ + /* 0x08100000-0x0fffffff: Reserved */ +#define STM32F0_CCMRAM_BASE 0x10000000 /* 0x10000000-0x1000ffff: 64Kb CCM data RAM */ + /* 0x10010000-0x1ffeffff: Reserved */ +#define STM32F0_SYSMEM_BASE 0x1fffd800 /* 0x1fff0000-0x1fff7a0f: System memory */ + /* 0x1fff7a10-0x1fff7fff: Reserved */ +#define STM32F0_OPTION_BASE 0x1ffff800 /* 0x1fffc000-0x1fffc007: Option bytes */ + /* 0x1fffc008-0x1fffffff: Reserved */ + +/* System Memory Addresses **********************************************************/ + +#define STM32F0_SYSMEM_UID 0x1ffff7ac /* The 96-bit unique device identifier */ +#define STM32F0_SYSMEM_FSIZE 0x1ffff7cc /* This bitfield indicates the size of + * the device Flash memory expressed in + * Kbytes. Example: 0x040 corresponds + * to 64 Kbytes + */ + +/* Peripheral Base Addresses ********************************************************/ + +#define STM32F0_APB1_BASE 0x40000000 /* 0x40000000-0x40009fff: APB1 */ + /* 0x4000a000-0x4000ffff: Reserved */ +#define STM32F0_APB2_BASE 0x40010000 /* 0x40010000-0x40006bff: APB2 */ + /* 0x40016c00-0x4001ffff: Reserved */ +#define STM32F0_AHB1_BASE 0x40020000 /* 0x40020000-0x400243ff: APB1 */ + /* 0x40024400-0x4007ffff: Reserved */ +#define STM32F0_AHB2_BASE 0x48000000 /* 0x48000000-0x480017ff: AHB2 */ + /* 0x48001800-0x4fffFfff: Reserved */ +#define STM32F0_AHB3_BASE 0x50000000 /* 0x50000000-0x500007ff: AHB3 */ + +/* APB1 Base Addresses **************************************************************/ + +#define STM32F0_TIM2_BASE 0x40000000 /* 0x40000000-0x400003ff TIM2 */ +#define STM32F0_TIM3_BASE 0x40000400 /* 0x40000400-0x400007ff TIM3 */ +#define STM32F0_TIM6_BASE 0x40001000 /* 0x40001000-0x400013ff TIM6 */ +#define STM32F0_TIM7_BASE 0x40001400 /* 0x40001400-0x400017ff TIM7 */ +#define STM32F0_TIM14_BASE 0x40002000 /* 0x40002000-0x400023ff TIM14 */ +#define STM32F0_RTC_BASE 0x40002800 /* 0x40002800-0x40002bff RTC */ +#define STM32F0_WWDG_BASE 0x40002c00 /* 0x40002c00-0x40002fff WWDG */ +#define STM32F0_IWDG_BASE 0x40003000 /* 0x40003000-0x400033ff IWDG */ +#define STM32F0_SPI2_BASE 0x40003800 /* 0x40003800-0x40003bff SPI2, or */ +#define STM32F0_I2S2_BASE 0x40003800 /* 0x40003800-0x40003bff I2S2 */ +#define STM32F0_USART2_BASE 0x40004400 /* 0x40004400-0x400047ff USART2 */ +#define STM32F0_USART3_BASE 0x40004800 /* 0x40004800-0x40004bff USART3 */ +#define STM32F0_USART4_BASE 0x40004c00 /* 0x40004c00-0x40004fff USART4 */ +#define STM32F0_USART5_BASE 0x40005000 /* 0x40005000-0x400053ff USART5 */ +#define STM32F0_I2C1_BASE 0x40005400 /* 0x40005400-0x400057ff I2C1 */ +#define STM32F0_I2C2_BASE 0x40005800 /* 0x40005800-0x40005bff I2C2 */ +#define STM32F0_USB_BASE 0x40005c00 /* 0x40005c00-0x40005fff USB device FS */ +#define STM32F0_USBRAM_BASE 0x40006000 /* 0x40006000-0x400063ff USB SRAM 512B */ +#define STM32F0_CAN_BASE 0x40006400 /* 0x40006400-0x400067ff bxCAN */ +#define STM32F0_CRS_BASE 0x40006c00 /* 0x40006c00-0x40006fff CRS */ +#define STM32F0_PWR_BASE 0x40007000 /* 0x40007000-0x400073ff PWR */ +#define STM32F0_DAC_BASE 0x40007400 /* 0x40007400-0x400077ff DAC */ +#define STM32F0_CEC_BASE 0x40007800 /* 0x40007800-0x40007bff HDMI CEC */ + +/* APB2 Base Addresses **************************************************************/ + +#define STM32F0_SYSCFG_BASE 0x40010000 /* 0x40010000-0x400103ff SYSCFG + COMP + OPAMP */ +#define STM32F0_EXTI_BASE 0x40010400 /* 0x40010400-0x400107ff EXTI */ +#define STM32F0_USART6_BASE 0x40011400 /* 0x40011400-0x400117ff USART6 */ +#define STM32F0_USART7_BASE 0x40011800 /* 0x40011800-0x40011bff USART7 */ +#define STM32F0_USART8_BASE 0x40011c00 /* 0x40011c00-0x40011fff USART8 */ +#define STM32F0_ADC_BASE 0x40012400 /* 0x40012400-0x400127ff ADC */ +#define STM32F0_TIM1_BASE 0x40012c00 /* 0x40012c00-0x40012fff TIM1 */ +#define STM32F0_SPI1_BASE 0x40013000 /* 0x40013000-0x400133ff SPI1 */ +#define STM32F0_USART1_BASE 0x40013800 /* 0x40013800-0x40013bff USART1 */ +#define STM32F0_TIM15_BASE 0x40014000 /* 0x40014000-0x400143ff TIM15 */ +#define STM32F0_TIM16_BASE 0x40014400 /* 0x40014400-0x400147ff TIM16 */ +#define STM32F0_TIM17_BASE 0x40014800 /* 0x40014800-0x40014bff TIM17 */ +#define STM32F0_DBGMCU_BASE 0x40015800 /* 0x40015800-0x40015bff DBGMCU */ + +/* AHB1 Base Addresses **************************************************************/ + +#define STM32F0_DMA1_BASE 0x40020000 /* 0x40020000-0x400203ff: DMA1 */ +#define STM32F0_DMA2_BASE 0x40020400 /* 0x40020400-0x400207ff: DMA2 */ +#define STM32F0_RCC_BASE 0x40021000 /* 0x40021000-0x400213ff: Reset and Clock control RCC */ +#define STM32F0_FLASHIF_BASE 0x40022000 /* 0x40022000-0x400223ff: Flash memory interface */ +#define STM32F0_CRC_BASE 0x40023000 /* 0x40023000-0x400233ff: CRC */ +#define STM32F0_TSC_BASE 0x40024000 /* 0x40024000-0x400243ff: TSC */ + +/* AHB2 Base Addresses **************************************************************/ + +#define STM32F0_GPIOA_BASE 0x48000000 /* 0x48000000-0x480003ff: GPIO Port A */ +#define STM32F0_GPIOB_BASE 0x48000400 /* 0x48000400-0x480007ff: GPIO Port B */ +#define STM32F0_GPIOC_BASE 0x48000800 /* 0x48000800-0x48000bff: GPIO Port C */ +#define STM32F0_GPIOD_BASE 0X48000C00 /* 0x48000c00-0x48000fff: GPIO Port D */ +#define STM32F0_GPIOE_BASE 0x48001000 /* 0x48001000-0x480013ff: GPIO Port E */ +#define STM32F0_GPIOF_BASE 0x48001400 /* 0x48001400-0x480017ff: GPIO Port F */ + +/* Cortex-M4 Base Addresses *********************************************************/ +/* Other registers -- see armv7-m/nvic.h for standard Cortex-M4 registers in this + * address range + */ + +#define STM32F0_SCS_BASE 0xe000e000 +#define STM32F0_DEBUGMCU_BASE 0xe0042000 + +#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F30XXX_MEMORYMAP_H */ diff --git a/arch/arm/src/stm32f0/chip/stm32f0_adc.h b/arch/arm/src/stm32f0/chip/stm32f0_adc.h new file mode 100644 index 0000000000..a516e99b20 --- /dev/null +++ b/arch/arm/src/stm32f0/chip/stm32f0_adc.h @@ -0,0 +1,194 @@ +/******************************************************************************** + * arch/arm/src/stm32f0/chip/stm32f0_adc.h + * + * 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. + * + ********************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_ADC_H +#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_ADC_H + +/******************************************************************************** + * Included Files + ********************************************************************************/ + +#include + +#include "chip.h" + +/******************************************************************************** + * Pre-processor Definitions + ********************************************************************************/ + +/* Register Offsets *********************************************************************************/ + +#define STM32F0_ADC_ISR_OFFSET 0x0000 /* ADC interrupt and status register */ +#define STM32F0_ADC_IER_OFFSET 0x0004 /* ADC interrupt enable register */ +#define STM32F0_ADC_CR_OFFSET 0x0008 /* ADC control register */ +#define STM32F0_ADC_CFGR1_OFFSET 0x000c /* ADC configuration register 1 */ +#define STM32F0_ADC_CFGR2_OFFSET 0x0010 /* ADC configuration register 2 */ +#define STM32F0_ADC_SMPR_OFFSET 0x0014 /* ADC sample time register */ +#define STM32F0_ADC_TR_OFFSET 0x0020 /* ADC watchdog threshold register */ +#define STM32F0_ADC_CHSELR_OFFSET 0x0028 /* ADC channel selection register */ +#define STM32F0_ADC_DR_OFFSET 0x0040 /* ADC regular data register */ +#define STM32F0_ADC_CCR_OFFSET 0x0308 /* ADC common configuration register */ + +/* Register Addresses *******************************************************************************/ + +#define STM32F0_ADC_ISR (STM32F0_ADC_BASE+STM32F0_ADC_ISR_OFFSET) +#define STM32F0_ADC_IER (STM32F0_ADC_BASE+STM32F0_ADC_IER_OFFSET) +#define STM32F0_ADC_CR (STM32F0_ADC_BASE+STM32F0_ADC_CR_OFFSET) +#define STM32F0_ADC_CFGR1 (STM32F0_ADC_BASE+STM32F0_ADC_CFGR1_OFFSET) +#define STM32F0_ADC_CFGR2 (STM32F0_ADC_BASE+STM32F0_ADC_CFGR2_OFFSET) +#define STM32F0_ADC_SMPR (STM32F0_ADC_BASE+STM32F0_ADC_SMPR_OFFSET) +#define STM32F0_ADC_TR (STM32F0_ADC_BASE+STM32F0_ADC_TR_OFFSET) +#define STM32F0_ADC_CHSELR (STM32F0_ADC_BASE+STM32F0_ADC_CHSELR_OFFSET) +#define STM32F0_ADC_DR (STM32F0_ADC_BASE+STM32F0_ADC_DR_OFFSET) +#define STM32F0_ADC_CCR (STM32F0_ADC_BASE+STM32F0_ADC_CCR_OFFSET) + +/* Register Bitfield Definitions ************************************************/ + +/* ADC interrupt and status register (ISR) and ADC interrupt enable register (IER) */ + +#define ADC_INT_ARDY (1 << 0) /* Bit 0: ADC ready */ +#define ADC_INT_EOSMP (1 << 1) /* Bit 1: End of sampling flag */ +#define ADC_INT_EOC (1 << 2) /* Bit 2: End of conversion */ +#define ADC_INT_EOS (1 << 3) /* Bit 3: End of regular sequence flag */ +#define ADC_INT_OVR (1 << 4) /* Bit 4: Overrun */ +#define ADC_INT_AWD (1 << 7) /* Bit 7: Analog watchdog flag */ + +/* ADC control register */ + +#define ADC_CR_ADEN (1 << 0) /* Bit 0: ADC enable control */ +#define ADC_CR_ADDIS (1 << 1) /* Bit 1: ADC disable command */ +#define ADC_CR_ADSTART (1 << 2) /* Bit 2: ADC start of regular conversion */ +#define ADC_CR_ADSTP (1 << 4) /* Bit 4: ADC stop of regular conversion command */ +#define ADC_CR_ADCAL (1 << 31) /* Bit 31: ADC calibration */ + +/* ADC configuration register 1 */ + +#define ADC_CFGR1_DMAEN (1 << 0) /* Bit 0: Direct memory access enable */ +#define ADC_CFGR1_DMACFG (1 << 1) /* Bit 1: Direct memory access configuration */ +#define ADC_CFGR1_SCANDIR (1 << 2) /* Bit 2: Scan sequence direction */ +#define ADC_CFGR1_RES_SHIFT (3) /* Bits 3-4: Data resolution */ +#define ADC_CFGR1_RES_MASK (3 << ADC_CFGR1_RES_SHIFT) +# define ADC_CFGR1_RES_12BIT (0 << ADC_CFGR1_RES_SHIFT) /* 15 ADCCLK clyes */ +# define ADC_CFGR1_RES_10BIT (1 << ADC_CFGR1_RES_SHIFT) /* 13 ADCCLK clyes */ +# define ADC_CFGR1_RES_8BIT (2 << ADC_CFGR1_RES_SHIFT) /* 11 ADCCLK clyes */ +# define ADC_CFGR1_RES_6BIT (3 << ADC_CFGR1_RES_SHIFT) /* 9 ADCCLK clyes */ +#define ADC_CFGR1_ALIGN (1 << 5) /* Bit 5: Data Alignment */ +#define ADC_CFGR1_EXTSEL_SHIFT (6) /* Bits 6-8: External trigger selection */ +#define ADC_CFGR1_EXTSEL_MASK (7 << ADC_CFGR1_EXTSEL_SHIFT) +# define ADC12_CFGR1_EXTSEL_TRG0 (0 << ADC_CFGR1_EXTSEL_SHIFT) +# define ADC12_CFGR1_EXTSEL_TRG1 (1 << ADC_CFGR1_EXTSEL_SHIFT) +# define ADC12_CFGR1_EXTSEL_TRG2 (2 << ADC_CFGR1_EXTSEL_SHIFT) +# define ADC12_CFGR1_EXTSEL_TRG3 (3 << ADC_CFGR1_EXTSEL_SHIFT) +# define ADC12_CFGR1_EXTSEL_TRG4 (4 << ADC_CFGR1_EXTSEL_SHIFT) +# define ADC12_CFGR1_EXTSEL_TRG5 (5 << ADC_CFGR1_EXTSEL_SHIFT) +# define ADC12_CFGR1_EXTSEL_TRG6 (6 << ADC_CFGR1_EXTSEL_SHIFT) +# define ADC12_CFGR1_EXTSEL_TRG7 (7 << ADC_CFGR1_EXTSEL_SHIFT) +#define ADC_CFGR1_EXTEN_SHIFT (10) /* Bits 10-11: External trigger/polarity selection regular channels */ +#define ADC_CFGR1_EXTEN_MASK (3 << ADC_CFGR1_EXTEN_SHIFT) +# define ADC_CFGR1_EXTEN_NONE (0 << ADC_CFGR1_EXTEN_SHIFT) /* Trigger detection disabled */ +# define ADC_CFGR1_EXTEN_RISING (1 << ADC_CFGR1_EXTEN_SHIFT) /* Trigger detection on the rising edge */ +# define ADC_CFGR1_EXTEN_FALLING (2 << ADC_CFGR1_EXTEN_SHIFT) /* Trigger detection on the falling edge */ +# define ADC_CFGR1_EXTEN_BOTH (3 << ADC_CFGR1_EXTEN_SHIFT) /* Trigger detection on both edges */ +#define ADC_CFGR1_OVRMOD (1 << 12) /* Bit 12: Overrun Mode */ +#define ADC_CFGR1_CONT (1 << 13) /* Bit 13: Continuous mode for regular conversions */ +#define ADC_CFGR1_WAIT (1 << 14) /* Bit 14: Wait convertion mode */ +#define ADC_CFGR1_AUTOFF (1 << 15) /* Bit 15: Auto-off mode */ +#define ADC_CFGR1_DISCEN (1 << 16) /* Bit 16: Discontinuous mode on regular channels */ +#define ADC_CFGR1_AWDSGL (1 << 22) /* Bit 22: Enable watchdog on single/all channels */ +#define ADC_CFGR1_AWDEN (1 << 23) /* Bit 23: Analog watchdog enable */ +#define ADC_CFGR1_AWDCH_SHIFT (26) /* Bits 26-30: Analog watchdog 1 channel select bits */ +#define ADC_CFGR1_AWDCH_MASK (31 << ADC_CFGR1_AWDCH_SHIFT) +# define ADC_CFGR1_AWDCH_DISABLED (0 << ADC_CFGR1_AWDCH_SHIFT) + +/* ADC configuration register 2 */ + +#define ADC_CFGR2_CKMODE_SHIFT (30) /* Bits 30-31: ADC clock mode */ +#define ADC_CFGR2_CKMODE_MASK (3 << ADC_CFGR2_CKMODE_SHIFT) +# define ADC_CFGR2_CKMODE_ADCCLK (0 << ADC_CFGR2_CKMODE_SHIFT) /* 00: ADCCLK (Asynchronous) generated at product level */ +# define ADC_CFGR2_CKMODE_PCLKd2 (1 << ADC_CFGR2_CKMODE_SHIFT) /* 01: PCLK/2 (Synchronous clock mode) */ +# define ADC_CFGR2_CKMODE_PCLKd4 (2 << ADC_CFGR2_CKMODE_SHIFT) /* 10: PCLK/4 (Synchronous clock mode) */ + +/* ADC sample time register */ + +#define ADC_SMPR_SMP_SHIFT (0) /* Bits 0-2: Sampling time selection */ +#define ADC_SMPR_SMP_MASK (7 << ADC_SMPR_SMP_SHIFT) +#define ADC_SMPR_SMP_1p5 (0 << ADC_SMPR_SMP_SHIFT) /* 000: 1.5 cycles */ +#define ADC_SMPR_SMP_7p5 (1 << ADC_SMPR_SMP_SHIFT) /* 001: 7.5 cycles */ +#define ADC_SMPR_SMP_13p5 (2 << ADC_SMPR_SMP_SHIFT) /* 010: 13.5 cycles */ +#define ADC_SMPR_SMP_28p5 (3 << ADC_SMPR_SMP_SHIFT) /* 011: 28.5 cycles */ +#define ADC_SMPR_SMP_41p5 (4 << ADC_SMPR_SMP_SHIFT) /* 100: 41.5 cycles */ +#define ADC_SMPR_SMP_55p5 (5 << ADC_SMPR_SMP_SHIFT) /* 101: 55.5 cycles */ +#define ADC_SMPR_SMP_71p5 (6 << ADC_SMPR_SMP_SHIFT) /* 110: 71.5 cycles */ +#define ADC_SMPR_SMP_239p5 (7 << ADC_SMPR_SMP_SHIFT) /* 111: 239.5 cycles */ + +/* ADC watchdog threshold register */ + +#define ADC_TR_LT_SHIFT (0) /* Bits 0-11: Analog watchdog lower threshold */ +#define ADC_TR_LT_MASK (0x0fff << ADC_TR_LT_SHIFT) +#define ADC_TR_HT_SHIFT (16) /* Bits 16-27: Analog watchdog higher threshold */ +#define ADC_TR_HT_MASK (0x0fff << ADC_TR_HT_SHIFT) + +/* ADC channel selection register */ + +#define ADC_CHSELR_CHSEL0 (1 << 0) /* Select channel 0 */ +#define ADC_CHSELR_CHSEL1 (1 << 1) /* Select channel 1 */ +#define ADC_CHSELR_CHSEL2 (1 << 2) /* Select channel 2 */ +#define ADC_CHSELR_CHSEL3 (1 << 3) /* Select channel 3 */ +#define ADC_CHSELR_CHSEL4 (1 << 4) /* Select channel 4 */ +#define ADC_CHSELR_CHSEL5 (1 << 5) /* Select channel 5 */ +#define ADC_CHSELR_CHSEL6 (1 << 6) /* Select channel 6 */ +#define ADC_CHSELR_CHSEL7 (1 << 7) /* Select channel 7 */ +#define ADC_CHSELR_CHSEL8 (1 << 8) /* Select channel 8 */ +#define ADC_CHSELR_CHSEL9 (1 << 9) /* Select channel 9 */ +#define ADC_CHSELR_CHSEL10 (1 << 10) /* Select channel 10 */ +#define ADC_CHSELR_CHSEL11 (1 << 11) /* Select channel 11 */ +#define ADC_CHSELR_CHSEL12 (1 << 12) /* Select channel 12 */ +#define ADC_CHSELR_CHSEL13 (1 << 13) /* Select channel 13 */ +#define ADC_CHSELR_CHSEL14 (1 << 14) /* Select channel 14 */ +#define ADC_CHSELR_CHSEL15 (1 << 15) /* Select channel 15 */ +#define ADC_CHSELR_CHSEL16 (1 << 16) /* Select channel 16 */ +#define ADC_CHSELR_CHSEL17 (1 << 17) /* Select channel 17 */ +#define ADC_CHSELR_CHSEL18 (1 << 18) /* Select channel 18 */ + +#define ADC_DR_RDATA_SHIFT (0) +#define ADC_DR_RDATA_MASK (0xffff << ADC_DR_RDATA_SHIFT) + +/* Common configuration register */ + +#define ADC_CCR_VREFEN (1 << 22) /* Bit 22: VREFINT enable */ +#define ADC_CCR_TSEN (1 << 23) /* Bit 23: Temperature sensor enable */ +#define ADC_CCR_VBATEN (1 << 24) /* Bit 22: VBAT enable */ + +#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_ADC_H */ diff --git a/arch/arm/src/stm32f0/chip/stm32f0_can.h b/arch/arm/src/stm32f0/chip/stm32f0_can.h new file mode 100644 index 0000000000..97fb9e7ad0 --- /dev/null +++ b/arch/arm/src/stm32f0/chip/stm32f0_can.h @@ -0,0 +1,468 @@ +/************************************************************************************ + * arch/arm/src/stm32f0/chip/stm32f0_can.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_CAN_H +#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_CAN_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include "chip.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* 3 TX mailboxes */ + +#define CAN_TXMBOX1 0 +#define CAN_TXMBOX2 1 +#define CAN_TXMBOX3 2 + +/* 2 RX mailboxes */ + +#define CAN_RXMBOX1 0 +#define CAN_RXMBOX2 1 + +/* Number of filters depends on silicon */ + +#define CAN_NFILTERS 14 + +/* Register Offsets *****************************************************************/ + +/* CAN control and status registers */ + +#define STM32F0_CAN_MCR_OFFSET 0x0000 /* CAN master control register */ +#define STM32F0_CAN_MSR_OFFSET 0x0004 /* CAN master status register */ +#define STM32F0_CAN_TSR_OFFSET 0x0008 /* CAN transmit status register */ + +#define STM32F0_CAN_RFR_OFFSET(m) (0x000c+((m)<<2)) +#define STM32F0_CAN_RF0R_OFFSET 0x000c /* CAN receive FIFO 0 register */ +#define STM32F0_CAN_RF1R_OFFSET 0x0010 /* CAN receive FIFO 1 register */ + +#define STM32F0_CAN_IER_OFFSET 0x0014 /* CAN interrupt enable register */ +#define STM32F0_CAN_ESR_OFFSET 0x0018 /* CAN error status register */ +#define STM32F0_CAN_BTR_OFFSET 0x001c /* CAN bit timing register */ + +/* CAN mailbox registers (3 TX and 2 RX) */ + +#define STM32F0_CAN_TIR_OFFSET(m) (0x0180+((m)<<4)) +#define STM32F0_CAN_TI0R_OFFSET 0x0180 /* TX mailbox identifier register 0 */ +#define STM32F0_CAN_TI1R_OFFSET 0x0190 /* TX mailbox identifier register 1 */ +#define STM32F0_CAN_TI2R_OFFSET 0x01a0 /* TX mailbox identifier register 2 */ + +#define STM32F0_CAN_TDTR_OFFSET(m) (0x0184+((m)<<4)) +#define STM32F0_CAN_TDT0R_OFFSET 0x0184 /* Mailbox data length control and time stamp register 0 */ +#define STM32F0_CAN_TDT1R_OFFSET 0x0194 /* Mailbox data length control and time stamp register 1 */ +#define STM32F0_CAN_TDT2R_OFFSET 0x01a4 /* Mailbox data length control and time stamp register 2 */ + +#define STM32F0_CAN_TDLR_OFFSET(m) (0x0188+((m)<<4)) +#define STM32F0_CAN_TDL0R_OFFSET 0x0188 /* Mailbox data low register 0 */ +#define STM32F0_CAN_TDL1R_OFFSET 0x0198 /* Mailbox data low register 1 */ +#define STM32F0_CAN_TDL2R_OFFSET 0x01a8 /* Mailbox data low register 2 */ + +#define STM32F0_CAN_TDHR_OFFSET(m) (0x018c+((m)<<4)) +#define STM32F0_CAN_TDH0R_OFFSET 0x018c /* Mailbox data high register 0 */ +#define STM32F0_CAN_TDH1R_OFFSET 0x019c /* Mailbox data high register 1 */ +#define STM32F0_CAN_TDH2R_OFFSET 0x01ac /* Mailbox data high register 2 */ + +#define STM32F0_CAN_RIR_OFFSET(m) (0x01b0+((m)<<4)) +#define STM32F0_CAN_RI0R_OFFSET 0x01b0 /* Rx FIFO mailbox identifier register 0 */ +#define STM32F0_CAN_RI1R_OFFSET 0x01c0 /* Rx FIFO mailbox identifier register 1 */ + +#define STM32F0_CAN_RDTR_OFFSET(m) (0x01b4+((m)<<4)) +#define STM32F0_CAN_RDT0R_OFFSET 0x01b4 /* Rx FIFO mailbox data length control and time stamp register 0 */ +#define STM32F0_CAN_RDT1R_OFFSET 0x01c4 /* Rx FIFO mailbox data length control and time stamp register 1 */ + +#define STM32F0_CAN_RDLR_OFFSET(m) (0x01b8+((m)<<4)) +#define STM32F0_CAN_RDL0R_OFFSET 0x01b8 /* Receive FIFO mailbox data low register 0 */ +#define STM32F0_CAN_RDL1R_OFFSET 0x01c8 /* Receive FIFO mailbox data low register 1 */ + +#define STM32F0_CAN_RDHR_OFFSET(m) (0x01bc+((m)<<4)) +#define STM32F0_CAN_RDH0R_OFFSET 0x01bc /* Receive FIFO mailbox data high register 0 */ +#define STM32F0_CAN_RDH1R_OFFSET 0x01cc /* Receive FIFO mailbox data high register 1 */ + +/* CAN filter registers */ + +#define STM32F0_CAN_FMR_OFFSET 0x0200 /* CAN filter master register */ +#define STM32F0_CAN_FM1R_OFFSET 0x0204 /* CAN filter mode register */ +#define STM32F0_CAN_FS1R_OFFSET 0x020c /* CAN filter scale register */ +#define STM32F0_CAN_FFA1R_OFFSET 0x0214 /* CAN filter FIFO assignment register */ +#define STM32F0_CAN_FA1R_OFFSET 0x021c /* CAN filter activation register */ + +/* There are 14 or 28 filter banks (depending) on the device. + * Each filter bank is composed of two 32-bit registers, CAN_FiR: + * F0R1 Offset 0x240 + * F0R2 Offset 0x244 + * F1R1 Offset 0x248 + * F1R2 Offset 0x24c + * ... + */ + +#define STM32F0_CAN_FIR_OFFSET(f,i) (0x240+((f)<<3)+(((i)-1)<<2)) + +/* Register Addresses ***************************************************************/ + +#if STM32F0_NCAN > 0 +# define STM32F0_CAN1_MCR (STM32F0_CAN1_BASE+STM32F0_CAN_MCR_OFFSET) +# define STM32F0_CAN1_MSR (STM32F0_CAN1_BASE+STM32F0_CAN_MSR_OFFSET) +# define STM32F0_CAN1_TSR (STM32F0_CAN1_BASE+STM32F0_CAN_TSR_OFFSET) +# define STM32F0_CAN1_RF0R (STM32F0_CAN1_BASE+STM32F0_CAN_RF0R_OFFSET) +# define STM32F0_CAN1_RF1R (STM32F0_CAN1_BASE+STM32F0_CAN_RF1R_OFFSET) +# define STM32F0_CAN1_IER (STM32F0_CAN1_BASE+STM32F0_CAN_IER_OFFSET) +# define STM32F0_CAN1_ESR (STM32F0_CAN1_BASE+STM32F0_CAN_ESR_OFFSET) +# define STM32F0_CAN1_BTR (STM32F0_CAN1_BASE+STM32F0_CAN_BTR_OFFSET) + +# define STM32F0_CAN1_TIR(m) (STM32F0_CAN1_BASE+STM32F0_CAN_TIR_OFFSET(m)) +# define STM32F0_CAN1_TI0R (STM32F0_CAN1_BASE+STM32F0_CAN_TI0R_OFFSET) +# define STM32F0_CAN1_TI1R (STM32F0_CAN1_BASE+STM32F0_CAN_TI1R_OFFSET) +# define STM32F0_CAN1_TI2R (STM32F0_CAN1_BASE+STM32F0_CAN_TI2R_OFFSET) + +# define STM32F0_CAN1_TDTR(m) (STM32F0_CAN1_BASE+STM32F0_CAN_TDTR_OFFSET(m)) +# define STM32F0_CAN1_TDT0R (STM32F0_CAN1_BASE+STM32F0_CAN_TDT0R_OFFSET) +# define STM32F0_CAN1_TDT1R (STM32F0_CAN1_BASE+STM32F0_CAN_TDT1R_OFFSET) +# define STM32F0_CAN1_TDT2R (STM32F0_CAN1_BASE+STM32F0_CAN_TDT2R_OFFSET) + +# define STM32F0_CAN1_TDLR(m) (STM32F0_CAN1_BASE+STM32F0_CAN_TDLR_OFFSET(m)) +# define STM32F0_CAN1_TDL0R (STM32F0_CAN1_BASE+STM32F0_CAN_TDL0R_OFFSET) +# define STM32F0_CAN1_TDL1R (STM32F0_CAN1_BASE+STM32F0_CAN_TDL1R_OFFSET) +# define STM32F0_CAN1_TDL2R (STM32F0_CAN1_BASE+STM32F0_CAN_TDL2R_OFFSET) + +# define STM32F0_CAN1_TDHR(m) (STM32F0_CAN1_BASE+STM32F0_CAN_TDHR_OFFSET(m)) +# define STM32F0_CAN1_TDH0R (STM32F0_CAN1_BASE+STM32F0_CAN_TDH0R_OFFSET) +# define STM32F0_CAN1_TDH1R (STM32F0_CAN1_BASE+STM32F0_CAN_TDH1R_OFFSET) +# define STM32F0_CAN1_TDH2R (STM32F0_CAN1_BASE+STM32F0_CAN_TDH2R_OFFSET) + +# define STM32F0_CAN1_RIR(m) (STM32F0_CAN1_BASE+STM32F0_CAN_RIR_OFFSET(m)) +# define STM32F0_CAN1_RI0R (STM32F0_CAN1_BASE+STM32F0_CAN_RI0R_OFFSET) +# define STM32F0_CAN1_RI1R (STM32F0_CAN1_BASE+STM32F0_CAN_RI1R_OFFSET) + +# define STM32F0_CAN1_RDTR(m) (STM32F0_CAN1_BASE+STM32F0_CAN_RDTR_OFFSET(m)) +# define STM32F0_CAN1_RDT0R (STM32F0_CAN1_BASE+STM32F0_CAN_RDT0R_OFFSET) +# define STM32F0_CAN1_RDT1R (STM32F0_CAN1_BASE+STM32F0_CAN_RDT1R_OFFSET) + +# define STM32F0_CAN1_RDLR(m) (STM32F0_CAN1_BASE+STM32F0_CAN_RDLR_OFFSET(m)) +# define STM32F0_CAN1_RDL0R (STM32F0_CAN1_BASE+STM32F0_CAN_RDL0R_OFFSET) +# define STM32F0_CAN1_RDL1R (STM32F0_CAN1_BASE+STM32F0_CAN_RDL1R_OFFSET) + +# define STM32F0_CAN1_RDHR(m) (STM32F0_CAN1_BASE+STM32F0_CAN_RDHR_OFFSET(m)) +# define STM32F0_CAN1_RDH0R (STM32F0_CAN1_BASE+STM32F0_CAN_RDH0R_OFFSET) +# define STM32F0_CAN1_RDH1R (STM32F0_CAN1_BASE+STM32F0_CAN_RDH1R_OFFSET) + +# define STM32F0_CAN1_FMR (STM32F0_CAN1_BASE+STM32F0_CAN_FMR_OFFSET) +# define STM32F0_CAN1_FM1R (STM32F0_CAN1_BASE+STM32F0_CAN_FM1R_OFFSET) +# define STM32F0_CAN1_FS1R (STM32F0_CAN1_BASE+STM32F0_CAN_FS1R_OFFSET) +# define STM32F0_CAN1_FFA1R (STM32F0_CAN1_BASE+STM32F0_CAN_FFA1R_OFFSET) +# define STM32F0_CAN1_FA1R (STM32F0_CAN1_BASE+STM32F0_CAN_FA1R_OFFSET) +# define STM32F0_CAN1_FIR(b,i) (STM32F0_CAN1_BASE+STM32F0_CAN_FIR_OFFSET(b,i)) +#endif + +#if STM32F0_NCAN > 1 +# define STM32F0_CAN2_MCR (STM32F0_CAN2_BASE+STM32F0_CAN_MCR_OFFSET) +# define STM32F0_CAN2_MSR (STM32F0_CAN2_BASE+STM32F0_CAN_MSR_OFFSET) +# define STM32F0_CAN2_TSR (STM32F0_CAN2_BASE+STM32F0_CAN_TSR_OFFSET) +# define STM32F0_CAN2_RF0R (STM32F0_CAN2_BASE+STM32F0_CAN_RF0R_OFFSET) +# define STM32F0_CAN2_RF1R (STM32F0_CAN2_BASE+STM32F0_CAN_RF1R_OFFSET) +# define STM32F0_CAN2_IER (STM32F0_CAN2_BASE+STM32F0_CAN_IER_OFFSET) +# define STM32F0_CAN2_ESR (STM32F0_CAN2_BASE+STM32F0_CAN_ESR_OFFSET) +# define STM32F0_CAN2_BTR (STM32F0_CAN2_BASE+STM32F0_CAN_BTR_OFFSET) + +# define STM32F0_CAN2_TIR(m) (STM32F0_CAN2_BASE+STM32F0_CAN_TIR_OFFSET(m)) +# define STM32F0_CAN2_TI0R (STM32F0_CAN2_BASE+STM32F0_CAN_TI0R_OFFSET) +# define STM32F0_CAN2_TI1R (STM32F0_CAN2_BASE+STM32F0_CAN_TI1R_OFFSET) +# define STM32F0_CAN2_TI2R (STM32F0_CAN2_BASE+STM32F0_CAN_TI2R_OFFSET) + +# define STM32F0_CAN2_TDTR(m) (STM32F0_CAN2_BASE+STM32F0_CAN_TDTR_OFFSET(m)) +# define STM32F0_CAN2_TDT0R (STM32F0_CAN2_BASE+STM32F0_CAN_TDT0R_OFFSET) +# define STM32F0_CAN2_TDT1R (STM32F0_CAN2_BASE+STM32F0_CAN_TDT1R_OFFSET) +# define STM32F0_CAN2_TDT2R (STM32F0_CAN2_BASE+STM32F0_CAN_TDT2R_OFFSET) + +# define STM32F0_CAN2_TDLR(m) (STM32F0_CAN2_BASE+STM32F0_CAN_TDLR_OFFSET(m)) +# define STM32F0_CAN2_TDL0R (STM32F0_CAN2_BASE+STM32F0_CAN_TDL0R_OFFSET) +# define STM32F0_CAN2_TDL1R (STM32F0_CAN2_BASE+STM32F0_CAN_TDL1R_OFFSET) +# define STM32F0_CAN2_TDL2R (STM32F0_CAN2_BASE+STM32F0_CAN_TDL2R_OFFSET) + +# define STM32F0_CAN2_TDHR(m) (STM32F0_CAN2_BASE+STM32F0_CAN_TDHR_OFFSET(m)) +# define STM32F0_CAN2_TDH0R (STM32F0_CAN2_BASE+STM32F0_CAN_TDH0R_OFFSET) +# define STM32F0_CAN2_TDH1R (STM32F0_CAN2_BASE+STM32F0_CAN_TDH1R_OFFSET) +# define STM32F0_CAN2_TDH2R (STM32F0_CAN2_BASE+STM32F0_CAN_TDH2R_OFFSET) + +# define STM32F0_CAN2_RIR(m) (STM32F0_CAN2_BASE+STM32F0_CAN_RIR_OFFSET(m)) +# define STM32F0_CAN2_RI0R (STM32F0_CAN2_BASE+STM32F0_CAN_RI0R_OFFSET) +# define STM32F0_CAN2_RI1R (STM32F0_CAN2_BASE+STM32F0_CAN_RI1R_OFFSET) + +# define STM32F0_CAN2_RDTR(m) (STM32F0_CAN2_BASE+STM32F0_CAN_RDTR_OFFSET(m)) +# define STM32F0_CAN2_RDT0R (STM32F0_CAN2_BASE+STM32F0_CAN_RDT0R_OFFSET) +# define STM32F0_CAN2_RDT1R (STM32F0_CAN2_BASE+STM32F0_CAN_RDT1R_OFFSET) + +# define STM32F0_CAN2_RDLR(m) (STM32F0_CAN2_BASE+STM32F0_CAN_RDLR_OFFSET(m)) +# define STM32F0_CAN2_RDL0R (STM32F0_CAN2_BASE+STM32F0_CAN_RDL0R_OFFSET) +# define STM32F0_CAN2_RDL1R (STM32F0_CAN2_BASE+STM32F0_CAN_RDL1R_OFFSET) + +# define STM32F0_CAN2_RDHR(m) (STM32F0_CAN2_BASE+STM32F0_CAN_RDHR_OFFSET(m)) +# define STM32F0_CAN2_RDH0R (STM32F0_CAN2_BASE+STM32F0_CAN_RDH0R_OFFSET) +# define STM32F0_CAN2_RDH1R (STM32F0_CAN2_BASE+STM32F0_CAN_RDH1R_OFFSET) + +# define STM32F0_CAN2_FMR (STM32F0_CAN2_BASE+STM32F0_CAN_FMR_OFFSET) +# define STM32F0_CAN2_FM1R (STM32F0_CAN2_BASE+STM32F0_CAN_FM1R_OFFSET) +# define STM32F0_CAN2_FS1R (STM32F0_CAN2_BASE+STM32F0_CAN_FS1R_OFFSET) +# define STM32F0_CAN2_FFA1R (STM32F0_CAN2_BASE+STM32F0_CAN_FFA1R_OFFSET) +# define STM32F0_CAN2_FA1R (STM32F0_CAN2_BASE+STM32F0_CAN_FA1R_OFFSET) +# define STM32F0_CAN2_FIR(b,i) (STM32F0_CAN2_BASE+STM32F0_CAN_FIR_OFFSET(b,i)) +#endif + +/* Register Bitfield Definitions ****************************************************/ + +/* CAN master control register */ + +#define CAN_MCR_INRQ (1 << 0) /* Bit 0: Initialization Request */ +#define CAN_MCR_SLEEP (1 << 1) /* Bit 1: Sleep Mode Request */ +#define CAN_MCR_TXFP (1 << 2) /* Bit 2: Transmit FIFO Priority */ +#define CAN_MCR_RFLM (1 << 3) /* Bit 3: Receive FIFO Locked Mode */ +#define CAN_MCR_NART (1 << 4) /* Bit 4: No Automatic Retransmission */ +#define CAN_MCR_AWUM (1 << 5) /* Bit 5: Automatic Wakeup Mode */ +#define CAN_MCR_ABOM (1 << 6) /* Bit 6: Automatic Bus-Off Management */ +#define CAN_MCR_TTCM (1 << 7) /* Bit 7: Time Triggered Communication Mode Enable */ +#define CAN_MCR_RESET (1 << 15) /* Bit 15: bxCAN software master reset */ +#define CAN_MCR_DBF (1 << 16) /* Bit 16: Debug freeze */ + +/* CAN master status register */ + +#define CAN_MSR_INAK (1 << 0) /* Bit 0: Initialization Acknowledge */ +#define CAN_MSR_SLAK (1 << 1) /* Bit 1: Sleep Acknowledge */ +#define CAN_MSR_ERRI (1 << 2) /* Bit 2: Error Interrupt */ +#define CAN_MSR_WKUI (1 << 3) /* Bit 3: Wakeup Interrupt */ +#define CAN_MSR_SLAKI (1 << 4) /* Bit 4: Sleep acknowledge interrupt */ +#define CAN_MSR_TXM (1 << 8) /* Bit 8: Transmit Mode */ +#define CAN_MSR_RXM (1 << 9) /* Bit 9: Receive Mode */ +#define CAN_MSR_SAMP (1 << 10) /* Bit 10: Last Sample Point */ +#define CAN_MSR_RX (1 << 11) /* Bit 11: CAN Rx Signal */ + +/* CAN transmit status register */ + +#define CAN_TSR_RQCP0 (1 << 0) /* Bit 0: Request Completed Mailbox 0 */ +#define CAN_TSR_TXOK0 (1 << 1) /* Bit 1 : Transmission OK of Mailbox 0 */ +#define CAN_TSR_ALST0 (1 << 2) /* Bit 2 : Arbitration Lost for Mailbox 0 */ +#define CAN_TSR_TERR0 (1 << 3) /* Bit 3 : Transmission Error of Mailbox 0 */ +#define CAN_TSR_ABRQ0 (1 << 7) /* Bit 7 : Abort Request for Mailbox 0 */ +#define CAN_TSR_RQCP1 (1 << 8) /* Bit 8 : Request Completed Mailbox 1 */ +#define CAN_TSR_TXOK1 (1 << 9) /* Bit 9 : Transmission OK of Mailbox 1 */ +#define CAN_TSR_ALST1 (1 << 10) /* Bit 10 : Arbitration Lost for Mailbox 1 */ +#define CAN_TSR_TERR1 (1 << 11) /* Bit 11 : Transmission Error of Mailbox 1 */ +#define CAN_TSR_ABRQ1 (1 << 15) /* Bit 15 : Abort Request for Mailbox 1 */ +#define CAN_TSR_RQCP2 (1 << 16) /* Bit 16 : Request Completed Mailbox 2 */ +#define CAN_TSR_TXOK2 (1 << 17) /* Bit 17 : Transmission OK of Mailbox 2 */ +#define CAN_TSR_ALST2 (1 << 18) /* Bit 18: Arbitration Lost for Mailbox 2 */ +#define CAN_TSR_TERR2 (1 << 19) /* Bit 19: Transmission Error of Mailbox 2 */ +#define CAN_TSR_ABRQ2 (1 << 23) /* Bit 23: Abort Request for Mailbox 2 */ +#define CAN_TSR_CODE_SHIFT (24) /* Bits 25-24: Mailbox Code */ +#define CAN_TSR_CODE_MASK (3 << CAN_TSR_CODE_SHIFT) +#define CAN_TSR_TME0 (1 << 26) /* Bit 26: Transmit Mailbox 0 Empty */ +#define CAN_TSR_TME1 (1 << 27) /* Bit 27: Transmit Mailbox 1 Empty */ +#define CAN_TSR_TME2 (1 << 28) /* Bit 28: Transmit Mailbox 2 Empty */ +#define CAN_TSR_LOW0 (1 << 29) /* Bit 29: Lowest Priority Flag for Mailbox 0 */ +#define CAN_TSR_LOW1 (1 << 30) /* Bit 30: Lowest Priority Flag for Mailbox 1 */ +#define CAN_TSR_LOW2 (1 << 31) /* Bit 31: Lowest Priority Flag for Mailbox 2 */ + +/* CAN receive FIFO 0/1 registers */ + +#define CAN_RFR_FMP_SHIFT (0) /* Bits 1-0: FIFO Message Pending */ +#define CAN_RFR_FMP_MASK (3 << CAN_RFR_FMP_SHIFT) +#define CAN_RFR_FULL (1 << 3) /* Bit 3: FIFO 0 Full */ +#define CAN_RFR_FOVR (1 << 4) /* Bit 4: FIFO 0 Overrun */ +#define CAN_RFR_RFOM (1 << 5) /* Bit 5: Release FIFO 0 Output Mailbox */ + +/* CAN interrupt enable register */ + +#define CAN_IER_TMEIE (1 << 0) /* Bit 0: Transmit Mailbox Empty Interrupt Enable */ +#define CAN_IER_FMPIE0 (1 << 1) /* Bit 1: FIFO Message Pending Interrupt Enable */ +#define CAN_IER_FFIE0 (1 << 2) /* Bit 2: FIFO Full Interrupt Enable */ +#define CAN_IER_FOVIE0 (1 << 3) /* Bit 3: FIFO Overrun Interrupt Enable */ +#define CAN_IER_FMPIE1 (1 << 4) /* Bit 4: FIFO Message Pending Interrupt Enable */ +#define CAN_IER_FFIE1 (1 << 5) /* Bit 5: FIFO Full Interrupt Enable */ +#define CAN_IER_FOVIE1 (1 << 6) /* Bit 6: FIFO Overrun Interrupt Enable */ +#define CAN_IER_EWGIE (1 << 8) /* Bit 8: Error Warning Interrupt Enable */ +#define CAN_IER_EPVIE (1 << 9) /* Bit 9: Error Passive Interrupt Enable */ +#define CAN_IER_BOFIE (1 << 10) /* Bit 10: Bus-Off Interrupt Enable */ +#define CAN_IER_LECIE (1 << 11) /* Bit 11: Last Error Code Interrupt Enable */ +#define CAN_IER_ERRIE (1 << 15) /* Bit 15: Error Interrupt Enable */ +#define CAN_IER_WKUIE (1 << 16) /* Bit 16: Wakeup Interrupt Enable */ +#define CAN_IER_SLKIE (1 << 17) /* Bit 17: Sleep Interrupt Enable */ + +/* CAN error status register */ + +#define CAN_ESR_EWGF (1 << 0) /* Bit 0: Error Warning Flag */ +#define CAN_ESR_EPVF (1 << 1) /* Bit 1: Error Passive Flag */ +#define CAN_ESR_BOFF (1 << 2) /* Bit 2: Bus-Off Flag */ +#define CAN_ESR_LEC_SHIFT (4) /* Bits 6-4: Last Error Code */ +#define CAN_ESR_LEC_MASK (7 << CAN_ESR_LEC_SHIFT) +# define CAN_ESR_NOERROR (0 << CAN_ESR_LEC_SHIFT) /* 000: No Error */ +# define CAN_ESR_STUFFERROR (1 << CAN_ESR_LEC_SHIFT) /* 001: Stuff Error */ +# define CAN_ESR_FORMERROR (2 << CAN_ESR_LEC_SHIFT) /* 010: Form Error */ +# define CAN_ESR_ACKERROR (3 << CAN_ESR_LEC_SHIFT) /* 011: Acknowledgment Error */ +# define CAN_ESR_BRECERROR (4 << CAN_ESR_LEC_SHIFT) /* 100: Bit recessive Error */ +# define CAN_ESR_BDOMERROR (5 << CAN_ESR_LEC_SHIFT) /* 101: Bit dominant Error */ +# define CAN_ESR_CRCERRPR (6 << CAN_ESR_LEC_SHIFT) /* 110: CRC Error */ +# define CAN_ESR_SWERROR (7 << CAN_ESR_LEC_SHIFT) /* 111: Set by software */ +#define CAN_ESR_TEC_SHIFT (16) /* Bits 23-16: LS byte of the 9-bit Transmit Error Counter */ +#define CAN_ESR_TEC_MASK (0xff << CAN_ESR_TEC_SHIF) +#define CAN_ESR_REC_SHIFT (24) /* Bits 31-24: Receive Error Counter */ +#define CAN_ESR_REC_MASK (0xff << CAN_ESR_REC_SHIFT) + +/* CAN bit timing register */ + +#define CAN_BTR_BRP_SHIFT (0) /* Bits 9-0: Baud Rate Prescaler */ +#define CAN_BTR_BRP_MASK (0x03ff << CAN_BTR_BRP_SHIFT) +#define CAN_BTR_TS1_SHIFT (16) /* Bits 19-16: Time Segment 1 */ +#define CAN_BTR_TS1_MASK (0x0f << CAN_BTR_TS1_SHIFT) +#define CAN_BTR_TS2_SHIFT (20) /* Bits 22-20: Time Segment 2 */ +#define CAN_BTR_TS2_MASK (7 << CAN_BTR_TS2_SHIFT) +#define CAN_BTR_SJW_SHIFT (24) /* Bits 25-24: Resynchronization Jump Width */ +#define CAN_BTR_SJW_MASK (3 << CAN_BTR_SJW_SHIFT) +#define CAN_BTR_LBKM (1 << 30) /* Bit 30: Loop Back Mode (Debug) */ +#define CAN_BTR_SILM (1 << 31) /* Bit 31: Silent Mode (Debug) */ + +#define CAN_BTR_BRP_MAX (1024) /* Maximum BTR value (without decrement) */ +#define CAN_BTR_TSEG1_MAX (16) /* Maximum TSEG1 value (without decrement) */ +#define CAN_BTR_TSEG2_MAX (8) /* Maximum TSEG2 value (without decrement) */ + +/* TX mailbox identifier register */ + +#define CAN_TIR_TXRQ (1 << 0) /* Bit 0: Transmit Mailbox Request */ +#define CAN_TIR_RTR (1 << 1) /* Bit 1: Remote Transmission Request */ +#define CAN_TIR_IDE (1 << 2) /* Bit 2: Identifier Extension */ +#define CAN_TIR_EXID_SHIFT (3) /* Bit 3-31: Extended Identifier */ +#define CAN_TIR_EXID_MASK (0x1fffffff << CAN_TIR_EXID_SHIFT) +#define CAN_TIR_STID_SHIFT (21) /* Bits 21-31: Standard Identifier */ +#define CAN_TIR_STID_MASK (0x07ff << CAN_TIR_STID_SHIFT) + +/* Mailbox data length control and time stamp register */ + +#define CAN_TDTR_DLC_SHIFT (0) /* Bits 3:0: Data Length Code */ +#define CAN_TDTR_DLC_MASK (0x0f << CAN_TDTR_DLC_SHIFT) +#define CAN_TDTR_TGT (1 << 8) /* Bit 8: Transmit Global Time */ +#define CAN_TDTR_TIME_SHIFT (16) /* Bits 31:16: Message Time Stamp */ +#define CAN_TDTR_TIME_MASK (0xffff << CAN_TDTR_TIME_SHIFT) + +/* Mailbox data low register */ + +#define CAN_TDLR_DATA0_SHIFT (0) /* Bits 7-0: Data Byte 0 */ +#define CAN_TDLR_DATA0_MASK (0xff << CAN_TDLR_DATA0_SHIFT) +#define CAN_TDLR_DATA1_SHIFT (8) /* Bits 15-8: Data Byte 1 */ +#define CAN_TDLR_DATA1_MASK (0xff << CAN_TDLR_DATA1_SHIFT) +#define CAN_TDLR_DATA2_SHIFT (16) /* Bits 23-16: Data Byte 2 */ +#define CAN_TDLR_DATA2_MASK (0xff << CAN_TDLR_DATA2_SHIFT) +#define CAN_TDLR_DATA3_SHIFT (24) /* Bits 31-24: Data Byte 3 */ +#define CAN_TDLR_DATA3_MASK (0xff << CAN_TDLR_DATA3_SHIFT) + +/* Mailbox data high register */ + +#define CAN_TDHR_DATA4_SHIFT (0) /* Bits 7-0: Data Byte 4 */ +#define CAN_TDHR_DATA4_MASK (0xff << CAN_TDHR_DATA4_SHIFT) +#define CAN_TDHR_DATA5_SHIFT (8) /* Bits 15-8: Data Byte 5 */ +#define CAN_TDHR_DATA5_MASK (0xff << CAN_TDHR_DATA5_SHIFT) +#define CAN_TDHR_DATA6_SHIFT (16) /* Bits 23-16: Data Byte 6 */ +#define CAN_TDHR_DATA6_MASK (0xff << CAN_TDHR_DATA6_SHIFT) +#define CAN_TDHR_DATA7_SHIFT (24) /* Bits 31-24: Data Byte 7 */ +#define CAN_TDHR_DATA7_MASK (0xff << CAN_TDHR_DATA7_SHIFT) + +/* Rx FIFO mailbox identifier register */ + +#define CAN_RIR_RTR (1 << 1) /* Bit 1: Remote Transmission Request */ +#define CAN_RIR_IDE (1 << 2) /* Bit 2: Identifier Extension */ +#define CAN_RIR_EXID_SHIFT (3) /* Bit 3-31: Extended Identifier */ +#define CAN_RIR_EXID_MASK (0x1fffffff << CAN_RIR_EXID_SHIFT) +#define CAN_RIR_STID_SHIFT (21) /* Bits 21-31: Standard Identifier */ +#define CAN_RIR_STID_MASK (0x07ff << CAN_RIR_STID_SHIFT) + +/* Receive FIFO mailbox data length control and time stamp register */ + +#define CAN_RDTR_DLC_SHIFT (0) /* Bits 3:0: Data Length Code */ +#define CAN_RDTR_DLC_MASK (0x0f << CAN_RDTR_DLC_SHIFT) +#define CAN_RDTR_FMI_SHIFT (8) /* Bits 15-8: Filter Match Index */ +#define CAN_RDTR_FMI_MASK (0xff << CAN_RDTR_FM_SHIFT) +#define CAN_RDTR_TIME_SHIFT (16) /* Bits 31:16: Message Time Stamp */ +#define CAN_RDTR_TIME_MASK (0xffff << CAN_RDTR_TIME_SHIFT) + +/* Receive FIFO mailbox data low register */ + +#define CAN_RDLR_DATA0_SHIFT (0) /* Bits 7-0: Data Byte 0 */ +#define CAN_RDLR_DATA0_MASK (0xff << CAN_RDLR_DATA0_SHIFT) +#define CAN_RDLR_DATA1_SHIFT (8) /* Bits 15-8: Data Byte 1 */ +#define CAN_RDLR_DATA1_MASK (0xff << CAN_RDLR_DATA1_SHIFT) +#define CAN_RDLR_DATA2_SHIFT (16) /* Bits 23-16: Data Byte 2 */ +#define CAN_RDLR_DATA2_MASK (0xff << CAN_RDLR_DATA2_SHIFT) +#define CAN_RDLR_DATA3_SHIFT (24) /* Bits 31-24: Data Byte 3 */ +#define CAN_RDLR_DATA3_MASK (0xff << CAN_RDLR_DATA3_SHIFT) + +/* Receive FIFO mailbox data high register */ + +#define CAN_RDHR_DATA4_SHIFT (0) /* Bits 7-0: Data Byte 4 */ +#define CAN_RDHR_DATA4_MASK (0xff << CAN_RDHR_DATA4_SHIFT) +#define CAN_RDHR_DATA5_SHIFT (8) /* Bits 15-8: Data Byte 5 */ +#define CAN_RDHR_DATA5_MASK (0xff << CAN_RDHR_DATA5_SHIFT) +#define CAN_RDHR_DATA6_SHIFT (16) /* Bits 23-16: Data Byte 6 */ +#define CAN_RDHR_DATA6_MASK (0xff << CAN_RDHR_DATA6_SHIFT) +#define CAN_RDHR_DATA7_SHIFT (24) /* Bits 31-24: Data Byte 7 */ +#define CAN_RDHR_DATA7_MASK (0xff << CAN_RDHR_DATA7_SHIFT) + +/* CAN filter master register */ + +#define CAN_FMR_FINIT (1 << 0) /* Bit 0: Filter Init Mode */ + +/* CAN filter mode register */ + +#define CAN_FM1R_FBM_SHIFT (0) /* Bits 13:0: Filter Mode */ +#define CAN_FM1R_FBM_MASK (0x3fff << CAN_FM1R_FBM_SHIFT) + +/* CAN filter scale register */ + +#define CAN_FS1R_FSC_SHIFT (0) /* Bits 13:0: Filter Scale Configuration */ +#define CAN_FS1R_FSC_MASK (0x3fff << CAN_FS1R_FSC_SHIFT) + +/* CAN filter FIFO assignment register */ + +#define CAN_FFA1R_FFA_SHIFT (0) /* Bits 13:0: Filter FIFO Assignment */ +#define CAN_FFA1R_FFA_MASK (0x3fff << CAN_FFA1R_FFA_SHIFT) + +/* CAN filter activation register */ + +#define CAN_FA1R_FACT_SHIFT (0) /* Bits 13:0: Filter Active */ +#define CAN_FA1R_FACT_MASK (0x3fff << CAN_FA1R_FACT_SHIFT) + +#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_CAN_H */ diff --git a/arch/arm/src/stm32f0/chip/stm32f0_comp.h b/arch/arm/src/stm32f0/chip/stm32f0_comp.h new file mode 100644 index 0000000000..85284cd476 --- /dev/null +++ b/arch/arm/src/stm32f0/chip/stm32f0_comp.h @@ -0,0 +1,137 @@ +/************************************************************************************ + * arch/arm/src/stm32f0/chip/stm32f0_comp.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Mateusz Szafoni + * + * 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 __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_COMP_H +#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_COMP_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include "chip.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Register Offsets *****************************************************************/ + +#define STM32F0_COMP_CSR_OFFSET 0x001c /* COMP1/COMP2 Control register */ + +/* Register Addresses ***************************************************************/ + +#define STM32F0_COMP_CSR (STM32F0_COMP_BASE+STM32F0_COMP_CSR_OFFSET) + +/* Register Bitfield Definitions ****************************************************/ + +/* COMP control and status register */ + +#define COMP_CSR_COMP1EN (1 << 0) /* Bit 0: Comparator 1 enable */ +#define COMP_CSR_COMP1SW1 (1 << 1) /* Bit 1: Comparator 1 non inverting input DAC switch */ +#define COMP_CSR_COMP1MODE_SHIFT (2) /* Bits 2-3: Compator 1 mode */ +#define COMP_CSR_COMP1MODE_MASK (3 << COMP_CSR_COMP1MODE_SHIFT) +# define COMP_CSR_COMP1MODE_HIGH (0 << COMP_CSR_COMP1MODE_SHIFT) /* 00: High Speed / full power */ +# define COMP_CSR_COMP1MODE_MEDIUM (1 << COMP_CSR_COMP1MODE_SHIFT) /* 01: Medium Speed / medium power */ +# define COMP_CSR_COMP1MODE_LOW (2 << COMP_CSR_COMP1MODE_SHIFT) /* 10: Low Speed / low-power */ +# define COMP_CSR_COMP1MODE_VLOW (3 << COMP_CSR_COMP1MODE_SHIFT) /* 11: Very-low Speed / ultra-low power */ +#define COMP_CSR_COMP1INSEL_SHIFT (4) /* Bits 4-6: Comparator 1 inverting input selection */ +#define COMP_CSR_COMP1INSEL_MASK (7 << COMP_CSR_COMP1INSEL_SHIFT) +# define COMP_CSR_COMP1INSEL_1P4VREF (0 << COMP_CSR_COMP1INSEL_SHIFT) /* 000: 1/4 of Vrefint */ +# define COMP_CSR_COMP1INSEL_1P2VREF (1 << COMP_CSR_COMP1INSEL_SHIFT) /* 001: 1/2 of Vrefint */ +# define COMP_CSR_COMP1INSEL_3P4VREF (2 << COMP_CSR_COMP1INSEL_SHIFT) /* 010: 3/4 of Vrefint */ +# define COMP_CSR_COMP1INSEL_VREF (3 << COMP_CSR_COMP1INSEL_SHIFT) /* 011: Vrefint */ +# define COMP_CSR_COMP1INSEL_INM4 (4 << COMP_CSR_COMP1INSEL_SHIFT) /* 100: COMP1_INM4 (PA4 DAC_OUT1 if enabled) */ +# define COMP_CSR_COMP1INSEL_INM5 (5 << COMP_CSR_COMP1INSEL_SHIFT) /* 101: COMP1_INM5 (PA5 DAC_OUT2 if present and enabled) */ +# define COMP_CSR_COMP1INSEL_INM6 (6 << COMP_CSR_COMP1INSEL_SHIFT) /* 110: COMP1_INM6 (PA0) */ +#define COMP_CSR_COMP1OUTSEL_SHIFT (8) /* Bits 8-10: Comparator 1 output selection*/ +#define COMP_CSR_COMP1OUTSEL_MASK (7 << COMP_CSR_COMP1OUTSEL_MASK) +# define COMP_CSR_COMP1OUTSEL_NOSEL (0 << COMP_CSR_COMP1OUTSEL_MASK) /* 000: no selection */ +# define COMP_CSR_COMP1OUTSEL_T1BRK (1 << COMP_CSR_COMP1OUTSEL_MASK) /* 001: Timer 1 break input */ +# define COMP_CSR_COMP1OUTSEL_T1ICAP (2 << COMP_CSR_COMP1OUTSEL_MASK) /* 010: Timer 1 Input capture 1 */ +# define COMP_CSR_COMP1OUTSEL_T1OCRC (3 << COMP_CSR_COMP1OUTSEL_MASK) /* 011: Timer 1 OCrefclear input */ +# define COMP_CSR_COMP1OUTSEL_T2ICAP (4 << COMP_CSR_COMP1OUTSEL_MASK) /* 100: Timer 2 input capture 4 */ +# define COMP_CSR_COMP1OUTSEL_T2OCRC (5 << COMP_CSR_COMP1OUTSEL_MASK) /* 101: Timer 2 OCrefclear input */ +# define COMP_CSR_COMP1OUTSEL_T3ICAP (6 << COMP_CSR_COMP1OUTSEL_MASK) /* 110: Timer 3 input capture 1 */ +# define COMP_CSR_COMP1OUTSEL_T3OCRC (7 << COMP_CSR_COMP1OUTSEL_MASK) /* 111: Timer 3 OCrefclear input */ +#define COMP_CSR_COMP1POL (1 << 11) /* Bit 11: Comparator 1 output polarity */ +#define COMP_CSR_COMP1HYST_SHIFT (12) /* Bits 12-13: Comparator 1 hysteresis */ +#define COMP_CSR_COMP1HYST_MASK (3 << COMP_CSR_COMP1HYST_SHIFT) +# define COMP_CSR_COMP1HYST_NOHYST (0 << COMP_CSR_COMP1HYST_MASK) /* 00: No hysteresis */ +# define COMP_CSR_COMP1HYST_LOWHYST (1 << COMP_CSR_COMP1HYST_MASK) /* 01: Low hysteresis */ +# define COMP_CSR_COMP1HYST_MDHYST (2 << COMP_CSR_COMP1HYST_MASK) /* 10: Medium hysteresis */ +# define COMP_CSR_COMP1HYST_HIHYST (3 << COMP_CSR_COMP1HYST_MASK) /* 11: Low hysteresis */ +#define COMP_CSR_COMP1OUT (1 << 14) /* Bit 14: Comparator 1 output */ +#define COMP_CSR_COMP1LOCK (1 << 15) /* Bit 15: Comparator 1 lock */ + +#define COMP_CSR_COMP2EN (1 << 16) /* Bit 16: Comparator 2 enable */ +#define COMP_CSR_COMP2MODE_SHIFT (18) /* Bits 18-19: Compator 2 mode */ +#define COMP_CSR_COMP2MODE_MASK (3 << COMP_CSR_COMP2MODE_SHIFT) +# define COMP_CSR_COMP2MODE_HIGH (0 << COMP_CSR_COMP2MODE_SHIFT) /* 00: High Speed / full power */ +# define COMP_CSR_COMP2MODE_MEDIUM (1 << COMP_CSR_COMP2MODE_SHIFT) /* 01: Medium Speed / medium power */ +# define COMP_CSR_COMP2MODE_LOW (2 << COMP_CSR_COMP2MODE_SHIFT) /* 10: Low Speed / low-power */ +# define COMP_CSR_COMP2MODE_VLOW (3 << COMP_CSR_COMP2MODE_SHIFT) /* 11: Very-low Speed / ultra-low power */ +#define COMP_CSR_COMP2INSEL_SHIFT (20) /* Bits 20-22: Comparator 2 inverting input selection */ +#define COMP_CSR_COMP2INSEL_MASK (7 << COMP_CSR_COMP2INSEL_SHIFT) +# define COMP_CSR_COMP2INSEL_1P4VREF (0 << COMP_CSR_COMP2INSEL_SHIFT) /* 000: 1/4 of Vrefint */ +# define COMP_CSR_COMP2INSEL_1P2VREF (1 << COMP_CSR_COMP2INSEL_SHIFT) /* 001: 1/2 of Vrefint */ +# define COMP_CSR_COMP2INSEL_3P4VREF (2 << COMP_CSR_COMP2INSEL_SHIFT) /* 010: 3/4 of Vrefint */ +# define COMP_CSR_COMP2INSEL_VREF (3 << COMP_CSR_COMP2INSEL_SHIFT) /* 011: Vrefint */ +# define COMP_CSR_COMP2INSEL_INM4 (4 << COMP_CSR_COMP2INSEL_SHIFT) /* 100: COMP1_INM4 (PA4 DAC_OUT1 if enabled) */ +# define COMP_CSR_COMP2INSEL_INM5 (5 << COMP_CSR_COMP2INSEL_SHIFT) /* 101: COMP1_INM5 (PA5 DAC_OUT2 if present and enabled) */ +# define COMP_CSR_COMP2INSEL_INM6 (6 << COMP_CSR_COMP2INSEL_SHIFT) /* 110: COMP1_INM6 (PA2) */ +#define COMP_CSR_WNDWEN (1 << 23) /* Bit 23: Window mode enable */ +#define COMP_CSR_COMP2OUTSEL_SHIFT (24) /* Bits 24-26: Comparator 1 output selection*/ +#define COMP_CSR_COMP2OUTSEL_MASK (7 << COMP_CSR_COMP2OUTSEL_MASK) +# define COMP_CSR_COMP2OUTSEL_NOSEL (0 << COMP_CSR_COMP2OUTSEL_MASK) /* 000: no selection */ +# define COMP_CSR_COMP2OUTSEL_T1BRK (1 << COMP_CSR_COMP2OUTSEL_MASK) /* 001: Timer 1 break input */ +# define COMP_CSR_COMP2OUTSEL_T1ICAP (2 << COMP_CSR_COMP2OUTSEL_MASK) /* 010: Timer 1 Input capture 1 */ +# define COMP_CSR_COMP2OUTSEL_T1OCRC (3 << COMP_CSR_COMP2OUTSEL_MASK) /* 011: Timer 1 OCrefclear input */ +# define COMP_CSR_COMP2OUTSEL_T2ICAP (4 << COMP_CSR_COMP2OUTSEL_MASK) /* 100: Timer 2 input capture 4 */ +# define COMP_CSR_COMP2OUTSEL_T2OCRC (5 << COMP_CSR_COMP2OUTSEL_MASK) /* 101: Timer 2 OCrefclear input */ +# define COMP_CSR_COMP2OUTSEL_T3ICAP (6 << COMP_CSR_COMP2OUTSEL_MASK) /* 110: Timer 3 input capture 1 */ +# define COMP_CSR_COMP2OUTSEL_T3OCRC (7 << COMP_CSR_COMP2OUTSEL_MASK) /* 111: Timer 3 OCrefclear input */ +#define COMP_CSR_COMP2POL (1 << 27) /* Bit 27: Comparator 2 output polarity */ +#define COMP_CSR_COMP2HYST_SHIFT (12) /* Bits 12-13: Comparator 1 hysteresis */ +#define COMP_CSR_COMP2HYST_MASK (3 << COMP_CSR_COMP2HYST_SHIFT) +# define COMP_CSR_COMP2HYST_NOHYST (0 << COMP_CSR_COMP2HYST_MASK) /* 00: No hysteresis */ +# define COMP_CSR_COMP2HYST_LOWHYST (1 << COMP_CSR_COMP2HYST_MASK) /* 01: Low hysteresis */ +# define COMP_CSR_COMP2HYST_MDHYST (2 << COMP_CSR_COMP2HYST_MASK) /* 10: Medium hysteresis */ +# define COMP_CSR_COMP2HYST_HIHYST (3 << COMP_CSR_COMP2HYST_MASK) /* 11: Low hysteresis */ +#define COMP_CSR_COMP2OUT (1 << 14) /* Bit 14: Comparator 1 output */ +#define COMP_CSR_COMP2LOCK (1 << 15) /* Bit 15: Comparator 1 lock */ + +#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_COMP_H */ diff --git a/arch/arm/src/stm32f0/chip/stm32f0_crc.h b/arch/arm/src/stm32f0/chip/stm32f0_crc.h new file mode 100644 index 0000000000..beb4e625b1 --- /dev/null +++ b/arch/arm/src/stm32f0/chip/stm32f0_crc.h @@ -0,0 +1,89 @@ +/************************************************************************************ + * arch/arm/src/stm32f0/chip/stm32f0_crc.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_CRC_H +#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_CRC_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include "chip.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Register Offsets *****************************************************************/ + +#define STM32F0_CRC_DR_OFFSET 0x0000 /* Data register */ +#define STM32F0_CRC_IDR_OFFSET 0x0004 /* Independent Data register */ +#define STM32F0_CRC_CR_OFFSET 0x0008 /* Control register */ +#define STM32F0_CRC_INIT_OFFSET 0x0010 /* Initial CRC value register */ +#define STM32F0_CRC_POL_OFFSET 0x0014 /* CRC polynomial register */ + +/* Register Addresses ***************************************************************/ + +#define STM32F0_CRC_DR (STM32F0_CRC_BASE+STM32F0_CRC_DR_OFFSET) +#define STM32F0_CRC_IDR (STM32F0_CRC_BASE+STM32F0_CRC_IDR_OFFSET) +#define STM32F0_CRC_CR (STM32F0_CRC_BASE+STM32F0_CRC_CR_OFFSET) +#define STM32F0_CRC_INIT (STM32F0_CRC_BASE+STM32F0_CRC_INIT_OFFSET) +#define STM32F0_CRC_POL (STM32F0_CRC_BASE+STM32F0_CRC_POL_OFFSET) + +/* Register Bitfield Definitions ****************************************************/ + +/* CRC independent data register */ + +#define CRC_IDR_MASK 0xff /* These bits as a temporary location for one byte, not affected by RESET bit of CR */ + +/* CRC control register */ + +#define CRC_CR_RESET (1 << 0) /* This bit reset the CRC calculation unit and load CRC_DR with value of CRC_INIT */ +#define CRC_CR_POLYSIZE_SHIFT 3 /* Bits 3-4: Polynomial size (for STM32F07x and STM32F09x) */ +#define CRC_CR_POLYSIZE_MASK (3 << CRC_CR_POLYSIZE_SHIFT) +# define CRC_CR_POLYSIZE_32 (0 << CRC_CR_POLYSIZE_SHIFT) /* 00: 32 bit polynomial */ +# define CRC_CR_POLYSIZE_16 (1 << CRC_CR_POLYSIZE_SHIFT) /* 01: 16 bit polynomial */ +# define CRC_CR_POLYSIZE_8 (2 << CRC_CR_POLYSIZE_SHIFT) /* 10: 8 bit polynomial */ +# define CRC_CR_POLYSIZE_7 (3 << CRC_CR_POLYSIZE_SHIFT) /* 10: 8 bit polynomial */ +#define CRC_CR_REVIN_SHIFT 5 /* Bits 5-6: These bits ontrol the reversal of the bit order of the input data */ +#define CRC_CR_REVIN_MASK (3 << CRC_CR_REVIN_SHIFT) +# define CRC_CR_REVIN_NONE (0 << CRC_CR_REVIN_SHIFT) /* 00: bit order is not affected */ +# define CRC_CR_REVIN_BYTE (1 << CRC_CR_REVIN_SHIFT) /* 01: reversal done by byte */ +# define CRC_CR_REVIN_HWORD (2 << CRC_CR_REVIN_SHIFT) /* 10: reversal done by half-word */ +# define CRC_CR_REVIN_WORD (3 << CRC_CR_REVIN_SHIFT) /* 11: reversal done by word */ +#define CRC_CR_REVOUT (1 << 7) /* This bit controls the reversal of the bit order of the output data */ + +#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_CRC_H */ diff --git a/arch/arm/src/stm32f0/chip/stm32f0_crs.h b/arch/arm/src/stm32f0/chip/stm32f0_crs.h new file mode 100644 index 0000000000..61f26d10ae --- /dev/null +++ b/arch/arm/src/stm32f0/chip/stm32f0_crs.h @@ -0,0 +1,114 @@ +/************************************************************************************ + * arch/arm/src/stm32f0/chip/stm32f0_crs.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_CRS_H +#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_CRS_H + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Register Offsets *****************************************************************/ + +#define STM32F0_CRS_CR_OFFSET 0x0000 /* CRS control register */ +#define STM32F0_CRS_CFGR_OFFSET 0x0004 /* CRS configuration register */ +#define STM32F0_CRS_ISR_OFFSET 0x0008 /* CRS interrupt and status register */ +#define STM32F0_CRS_ICR_OFFSET 0x000c /* CRS interrupt flag clear register */ + +/* Register Addresses ***************************************************************/ + +#define STM32F0_CRS_CR (STM32F0_CRS_BASE+STM32F0_CRS_CR_OFFSET) +#define STM32F0_CRS_CFGR (STM32F0_CRS_BASE+STM32F0_CRS_CFGR_OFFSET) +#define STM32F0_CRS_ISR (STM32F0_CRS_BASE+STM32F0_CRS_ISR_OFFSET) +#define STM32F0_CRS_ICR (STM32F0_CRS_BASE+STM32F0_CRS_ICR_OFFSET) + +/* Register Bitfield Definitions ****************************************************/ + +/* CRS control register */ + +#define CRS_CR_SYNCOKIE (1 << 0) /* Bit 0: SYNC event OK interrupt enable */ +#define CRS_CR_SYNCWARNIE (1 << 1) /* Bit 1: SYNC warning interrupt enable */ +#define CRS_CR_ERRIE (1 << 2) /* Bit 2: Syncronization or Trimming error interrupt enabled */ +#define CRS_CR_ESYNCIE (1 << 3) /* Bit 3: Expected SYNC interrupt enable */ +#define CRS_CR_CEN (1 << 5) /* Bit 5: Frequency error counter enable */ +#define CRS_CR_AUTOTRIMEN (1 << 6) /* Bit 6: Automatic trimming enabled */ +#define CRS_CR_SWSYNC (1 << 7) /* Bit 7: Generate sofware SYNC event */ +#define CRS_CR_TRIM_SHIFT 8 /* Bits 8-13: HSI48 oscillator smooth trimming */ +#define CRS_CR_TRIM_MASK (0x3f << CRS_CR_TRIM_SHIFT) + +/* CRS configuration register */ + +#define CRS_CFGR_RELOAD_SHIFT 0 /* Bits 0-15: Counter reload value */ +#define CRS_CFGR_RELOAD_MASK (0xffff << CRS_CFGR_RELOAD_SHIFT) +#define CRS_CFGR_FELIM_SHIFT 16 /* Bits 16-23: Frequency error limit */ +#define CRS_CFGR_FELIM_MASK (0xff << CRS_CFGR_FELIM_SHIFT) +#define CRS_CFGR_SYNCDIV_SHIFT 24 /* Bits 24-26: SYNC divider */ +#define CRS_CFGR_SYNCDIV_MASK (7 << CRS_CFGR_SYNCDIV_SHIFT) +# define CRS_CFGR_SYNCDIV_d1 (0 << CRS_CFGR_SYNCDIV_SHIFT) /* Not divided */ +# define CRS_CFGR_SYNCDIV_d2 (1 << CRS_CFGR_SYNCDIV_SHIFT) /* divided by 2) */ +# define CRS_CFGR_SYNCDIV_d4 (2 << CRS_CFGR_SYNCDIV_SHIFT) /* divided by 4) */ +# define CRS_CFGR_SYNCDIV_d8 (3 << CRS_CFGR_SYNCDIV_SHIFT) /* divided by 8) */ +# define CRS_CFGR_SYNCDIV_d16 (4 << CRS_CFGR_SYNCDIV_SHIFT) /* divided by 16) */ +# define CRS_CFGR_SYNCDIV_d32 (5 << CRS_CFGR_SYNCDIV_SHIFT) /* divided by 32) */ +# define CRS_CFGR_SYNCDIV_d64 (6 << CRS_CFGR_SYNCDIV_SHIFT) /* divided by 64) */ +# define CRS_CFGR_SYNCDIV_d128 (6 << CRS_CFGR_SYNCDIV_SHIFT) /* divided by 128) */ +#define CRS_CFGR_SYNCSRC_SHIFT 28 /* Bits 28-29: SYNC signal source selection */ +#define CRS_CFGR_SYNCSRC_MASK (3 << CRS_CFGR_SYNCSRC_SHIFT) +# define CRS_CFGR_SYNCSRC_GPIO (0 << CRS_CFGR_SYNCSRC_SHIFT) /* GPIO as SYNC signal source */ +# define CRS_CFGR_SYNCSRC_LSE (1 << CRS_CFGR_SYNCSRC_SHIFT) /* LSE as SYNC signal source */ +# define CRS_CFGR_SYNCSRC_USBSOF (2 << CRS_CFGR_SYNCSRC_SHIFT) /* USB SOF as SYNC signal source */ +#define CRS_CFGR_SYNCPOL (1 << 30) /* SYNC polarity selection */ + +/* CRS interrupt and status register */ + +#define CRS_ISR_SYNCOKF (1 << 0) /* Bit 0: SYNC event OK flag */ +#define CRS_ISR_SYNCWARNF (1 << 1) /* Bit 1: SYNC warning flag */ +#define CRS_ISR_ERRF (1 << 2) /* Bit 2: Errot flag */ +#define CRS_ISR_ESYNCF (1 << 3) /* Bit 3: Expected SYNC flag */ +#define CRS_ISR_SYNCERR (1 << 8) /* Bit 8: SYNC error */ +#define CRS_ISR_SYNCMISS (1 << 9) /* Bit 9: SYNC missed */ +#define CRS_ISR_TRIMOVF (1 << 10) /* Bit 10: Trimming overflow or underflow */ +#define CRS_ISR_FEDIR (1 << 15) /* Bit 15: Frequency error direction */ +#define CRS_ISR_FECAP_SHIFT 16 /* Bits 16-31: Frequency error capture */ +#define CRS_ISR_FECAP_MASK (0xffff << CRS_ISR_FECAP_SHIFT) + +/* CRS interrupt flag clear register */ + +#define CRS_ICR_SYNCOKC (1 << 0) /* Bit 0: SYNC event OK clear flag */ +#define CRS_ICR_SYNCWARNC (1 << 1) /* Bit 1: SYNC waring clear flag */ +#define CRS_ICR_ERRC (1 << 2) /* Bit 2: Error clear flag */ +#define CRS_ICR_ESYNCC (1 << 3) /* Bit 3: Expected SYNC clear flag */ + +#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_CRS_H */ diff --git a/arch/arm/src/stm32f0/chip/stm32f0_dac.h b/arch/arm/src/stm32f0/chip/stm32f0_dac.h new file mode 100644 index 0000000000..ace8a9991a --- /dev/null +++ b/arch/arm/src/stm32f0/chip/stm32f0_dac.h @@ -0,0 +1,217 @@ +/************************************************************************************ + * arch/arm/src/stm32f0/chip/stm32f0_dac.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_DAC_H +#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_DAC_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include "chip.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Register Offsets *****************************************************************/ + +#define STM32F0_DAC_CR_OFFSET 0x0000 /* DAC control register */ +#define STM32F0_DAC_SWTRIGR_OFFSET 0x0004 /* DAC software trigger register */ +#define STM32F0_DAC_DHR12R1_OFFSET 0x0008 /* DAC channel 1 12-bit right-aligned data holding register */ +#define STM32F0_DAC_DHR12L1_OFFSET 0x000c /* DAC channel 1 12-bit left aligned data holding register */ +#define STM32F0_DAC_DHR8R1_OFFSET 0x0010 /* DAC channel 1 8-bit right aligned data holding register */ +#define STM32F0_DAC_DHR12R2_OFFSET 0x0014 /* DAC channel 2 12-bit right aligned data holding register */ +#define STM32F0_DAC_DHR12L2_OFFSET 0x0018 /* DAC channel 2 12-bit left aligned data holding register */ +#define STM32F0_DAC_DHR8R2_OFFSET 0x001c /* DAC channel 2 8-bit right-aligned data holding register */ +#define STM32F0_DAC_DHR12RD_OFFSET 0x0020 /* Dual DAC 12-bit right-aligned data holding register */ +#define STM32F0_DAC_DHR12LD_OFFSET 0x0024 /* DUAL DAC 12-bit left aligned data holding register */ +#define STM32F0_DAC_DHR8RD_OFFSET 0x0028 /* DUAL DAC 8-bit right aligned data holding register */ +#define STM32F0_DAC_DOR1_OFFSET 0x002c /* DAC channel 1 data output register */ +#define STM32F0_DAC_DOR2_OFFSET 0x0030 /* DAC channel 2 data output register */ +#define STM32F0_DAC_SR_OFFSET 0x0034 /* DAC status register */ + +/* Register Addresses ***************************************************************/ + +/* DAC */ + +# define STM32F0_DAC1_CR (STM32F0_DAC1_BASE+STM32F0_DAC_CR_OFFSET) +# define STM32F0_DAC1_SWTRIGR (STM32F0_DAC1_BASE+STM32F0_DAC_SWTRIGR_OFFSET) +# define STM32F0_DAC1_DHR12R1 (STM32F0_DAC1_BASE+STM32F0_DAC_DHR12R1_OFFSET) +# define STM32F0_DAC1_DHR12L1 (STM32F0_DAC1_BASE+STM32F0_DAC_DHR12L1_OFFSET) +# define STM32F0_DAC1_DHR8R1 (STM32F0_DAC1_BASE+STM32F0_DAC_DHR8R1_OFFSET) +# define STM32F0_DAC1_DHR12R2 (STM32F0_DAC1_BASE+STM32F0_DAC_DHR12R2_OFFSET) +# define STM32F0_DAC1_DHR12L2 (STM32F0_DAC1_BASE+STM32F0_DAC_DHR12L2_OFFSET) +# define STM32F0_DAC1_DHR8R2 (STM32F0_DAC1_BASE+STM32F0_DAC_DHR8R2_OFFSET) +# define STM32F0_DAC1_DHR12RD (STM32F0_DAC1_BASE+STM32F0_DAC_DHR12RD_OFFSET) +# define STM32F0_DAC1_DHR12LD (STM32F0_DAC1_BASE+STM32F0_DAC_DHR12LD_OFFSET) +# define STM32F0_DAC1_DHR8RD (STM32F0_DAC1_BASE+STM32F0_DAC_DHR8RD_OFFSET) +# define STM32F0_DAC1_DOR1 (STM32F0_DAC1_BASE+STM32F0_DAC_DOR1_OFFSET) +# define STM32F0_DAC1_DOR2 (STM32F0_DAC1_BASE+STM32F0_DAC_DOR2_OFFSET) +# define STM32F0_DAC1_SR (STM32F0_DAC1_BASE+STM32F0_DAC_SR_OFFSET) + +/* Register Bitfield Definitions ****************************************************/ + +/* DAC control register */ +/* These definitions may be used with the full, 32-bit register */ + +#define DAC_CR_EN1 (1 << 0) /* Bit 0: DAC channel 1 enable */ +#define DAC_CR_BOFF1 (1 << 1) /* Bit 1: DAC channel 1 output buffer disable */ +#define DAC_CR_TEN1 (1 << 2) /* Bit 2: DAC channel 1 trigger enable */ +#define DAC_CR_TSEL1_SHIFT (3) /* Bits 3-5: DAC channel 1 trigger selection */ +#define DAC_CR_TSEL1_MASK (7 << DAC_CR_TSEL1_SHIFT) +# define DAC_CR_TSEL1_TIM6 (0 << DAC_CR_TSEL1_SHIFT) /* Timer 6 TRGO event */ +# define DAC_CR_TSEL1_TIM3 (1 << DAC_CR_TSEL1_SHIFT) /* Timer 3 TRGO event */ +# define DAC_CR_TSEL1_TIM7 (2 << DAC_CR_TSEL1_SHIFT) /* Timer 7 TRGO event */ +# define DAC_CR_TSEL1_TIM15 (3 << DAC_CR_TSEL1_SHIFT) /* Timer 15 TRGO event, or */ +# define DAC_CR_TSEL1_TIM2 (4 << DAC_CR_TSEL1_SHIFT) /* Timer 2 TRGO event */ +# define DAC_CR_TSEL1_EXT9 (6 << DAC_CR_TSEL1_SHIFT) /* External line9 */ +# define DAC_CR_TSEL1_SW (7 << DAC_CR_TSEL1_SHIFT) /* Software trigger */ +#define DAC_CR_WAVE1_SHIFT (6) /* Bits 6-7: DAC channel 1 noise/triangle wave generation */ +#define DAC_CR_WAVE1_MASK (3 << DAC_CR_WAVE1_SHIFT) +# define DAC_CR_WAVE1_DISABLED (0 << DAC_CR_WAVE1_SHIFT) /* Wave generation disabled */ +# define DAC_CR_WAVE1_NOISE (1 << DAC_CR_WAVE1_SHIFT) /* Noise wave generation enabled */ +# define DAC_CR_WAVE1_TRIANGLE (2 << DAC_CR_WAVE1_SHIFT) /* Triangle wave generation enabled */ +#define DAC_CR_MAMP1_SHIFT (8) /* Bits 8-11: DAC channel 1 mask/amplitude selector */ +#define DAC_CR_MAMP1_MASK (15 << DAC_CR_MAMP1_SHIFT) +# define DAC_CR_MAMP1_AMP1 (0 << DAC_CR_MAMP1_SHIFT) /* Unmask bit0 of LFSR/triangle amplitude=1 */ +# define DAC_CR_MAMP1_AMP3 (1 << DAC_CR_MAMP1_SHIFT) /* Unmask bits[1:0] of LFSR/triangle amplitude=3 */ +# define DAC_CR_MAMP1_AMP7 (2 << DAC_CR_MAMP1_SHIFT) /* Unmask bits[2:0] of LFSR/triangle amplitude=7 */ +# define DAC_CR_MAMP1_AMP15 (3 << DAC_CR_MAMP1_SHIFT) /* Unmask bits[3:0] of LFSR/triangle amplitude=15 */ +# define DAC_CR_MAMP1_AMP31 (4 << DAC_CR_MAMP1_SHIFT) /* Unmask bits[4:0] of LFSR/triangle amplitude=31 */ +# define DAC_CR_MAMP1_AMP63 (5 << DAC_CR_MAMP1_SHIFT) /* Unmask bits[5:0] of LFSR/triangle amplitude=63 */ +# define DAC_CR_MAMP1_AMP127 (6 << DAC_CR_MAMP1_SHIFT) /* Unmask bits[6:0] of LFSR/triangle amplitude=127 */ +# define DAC_CR_MAMP1_AMP255 (7 << DAC_CR_MAMP1_SHIFT) /* Unmask bits[7:0] of LFSR/triangle amplitude=255 */ +# define DAC_CR_MAMP1_AMP511 (8 << DAC_CR_MAMP1_SHIFT) /* Unmask bits[8:0] of LFSR/triangle amplitude=511 */ +# define DAC_CR_MAMP1_AMP1023 (9 << DAC_CR_MAMP1_SHIFT) /* Unmask bits[9:0] of LFSR/triangle amplitude=1023 */ +# define DAC_CR_MAMP1_AMP2047 (10 << DAC_CR_MAMP1_SHIFT) /* Unmask bits[10:0] of LFSR/triangle amplitude=2047 */ +# define DAC_CR_MAMP1_AMP4095 (11 << DAC_CR_MAMP1_SHIFT) /* Unmask bits[11:0] of LFSR/triangle amplitude=4095 */ +#define DAC_CR_DMAEN1 (1 << 12) /* Bit 12: DAC channel 1 DMA enable */ +#define DAC_CR_DMAUDRIE1 (1 << 13) /* Bit 13: DAC channel 1 DMA Underrun Interrupt enable */ + +#define DAC_CR_EN2 (1 << 16) /* Bit 16: DAC channel 2 enable */ +#define DAC_CR_BOFF2 (1 << 17) /* Bit 17: DAC channel 2 output buffer disable */ +#define DAC_CR_TEN2 (1 << 18) /* Bit 18: DAC channel 2 trigger enable */ +#define DAC_CR_TSEL2_SHIFT (19) /* Bits 19-21: DAC channel 2 trigger selection */ +#define DAC_CR_TSEL2_MASK (7 << DAC_CR_TSEL2_SHIFT) +# define DAC_CR_TSEL2_TIM6 (0 << DAC_CR_TSEL2_SHIFT) /* Timer 6 TRGO event */ +# define DAC_CR_TSEL2_TIM3 (1 << DAC_CR_TSEL2_SHIFT) /* Timer 3 TRGO event */ +# define DAC_CR_TSEL2_TIM7 (2 << DAC_CR_TSEL2_SHIFT) /* Timer 7 TRGO event */ +# define DAC_CR_TSEL2_TIM15 (3 << DAC_CR_TSEL2_SHIFT) /* Timer 15 TRGO event */ +# define DAC_CR_TSEL2_TIM2 (4 << DAC_CR_TSEL2_SHIFT) /* Timer 2 TRGO event */ +# define DAC_CR_TSEL2_EXT9 (6 << DAC_CR_TSEL2_SHIFT) /* External line9 */ +# define DAC_CR_TSEL2_SW (7 << DAC_CR_TSEL2_SHIFT) /* Software trigger */ +#define DAC_CR_WAVE2_SHIFT (22) /* Bit 22-23: DAC channel 2 noise/triangle wave generation enable */ +#define DAC_CR_WAVE2_MASK (3 << DAC_CR_WAVE2_SHIFT) +# define DAC_CR_WAVE2_DISABLED (0 << DAC_CR_WAVE2_SHIFT) /* Wave generation disabled */ +# define DAC_CR_WAVE2_NOISE (1 << DAC_CR_WAVE2_SHIFT) /* Noise wave generation enabled */ +# define DAC_CR_WAVE2_TRIANGLE (2 << DAC_CR_WAVE2_SHIFT) /* Triangle wave generation enabled */ +#define DAC_CR_MAMP2_SHIFT (24) /* Bit 24-27: DAC channel 2 mask/amplitude selector */ +#define DAC_CR_MAMP2_MASK (15 << DAC_CR_MAMP2_SHIFT) +# define DAC_CR_MAMP2_AMP1 (0 << DAC_CR_MAMP2_SHIFT) /* Unmask bit0 of LFSR/triangle amplitude=1 */ +# define DAC_CR_MAMP2_AMP3 (1 << DAC_CR_MAMP2_SHIFT) /* Unmask bits[1:0] of LFSR/triangle amplitude=3 */ +# define DAC_CR_MAMP2_AMP7 (2 << DAC_CR_MAMP2_SHIFT) /* Unmask bits[2:0] of LFSR/triangle amplitude=7 */ +# define DAC_CR_MAMP2_AMP15 (3 << DAC_CR_MAMP2_SHIFT) /* Unmask bits[3:0] of LFSR/triangle amplitude=15 */ +# define DAC_CR_MAMP2_AMP31 (4 << DAC_CR_MAMP2_SHIFT) /* Unmask bits[4:0] of LFSR/triangle amplitude=31 */ +# define DAC_CR_MAMP2_AMP63 (5 << DAC_CR_MAMP2_SHIFT) /* Unmask bits[5:0] of LFSR/triangle amplitude=63 */ +# define DAC_CR_MAMP2_AMP127 (6 << DAC_CR_MAMP2_SHIFT) /* Unmask bits[6:0] of LFSR/triangle amplitude=127 */ +# define DAC_CR_MAMP2_AMP255 (7 << DAC_CR_MAMP2_SHIFT) /* Unmask bits[7:0] of LFSR/triangle amplitude=255 */ +# define DAC_CR_MAMP2_AMP511 (8 << DAC_CR_MAMP2_SHIFT) /* Unmask bits[8:0] of LFSR/triangle amplitude=511 */ +# define DAC_CR_MAMP2_AMP1023 (9 << DAC_CR_MAMP2_SHIFT) /* Unmask bits[9:0] of LFSR/triangle amplitude=1023 */ +# define DAC_CR_MAMP2_AMP2047 (10 << DAC_CR_MAMP2_SHIFT) /* Unmask bits[10:0] of LFSR/triangle amplitude=2047 */ +# define DAC_CR_MAMP2_AMP4095 (11 << DAC_CR_MAMP2_SHIFT) /* Unmask bits[11:0] of LFSR/triangle amplitude=4095 */ +#define DAC_CR_DMAEN2 (1 << 28) /* Bit 28: DAC channel 2 DMA enable */ +#define DAC_CR_DMAUDRIE2 (1 << 29) /* Bits 29: DAC channel 2 DMA underrun interrupt enable */ + +/* DAC software trigger register */ + +#define DAC_SWTRIGR_SWTRIG(n) (1 << ((n)-1)) +#define DAC_SWTRIGR_SWTRIG1 (1 << 0) /* Bit 0: DAC channel 1 software trigger */ +#define DAC_SWTRIGR_SWTRIG2 (1 << 1) /* Bit 1: DAC channel 2 software trigger */ + +/* DAC channel 1/2 12-bit right-aligned data holding register */ + +#define DAC_DHR12R_MASK (0x0fff) + +/* DAC channel 1/2 12-bit left aligned data holding register */ + +#define DAC_DHR12L_MASK (0xfff0) + +/* DAC channel 1/2 8-bit right aligned data holding register */ + +#define DAC_DHR8R_MASK (0x00ff) + +/* Dual DAC 12-bit right-aligned data holding register */ + +#define DAC_DHR12RD_DACC_SHIFT(n) (1 << (((n)-1) << 4)) +#define DAC_DHR12RD_DACC_MASK(n) (0xfff << DAC_DHR12RD_DACC_SHIFT(n)) + +#define DAC_DHR12RD_DACC1_SHIFT (0) /* Bits 0-11: DAC channel 1 12-bit right-aligned data */ +#define DAC_DHR12RD_DACC1_MASK (0xfff << DAC_DHR12RD_DACC2_SHIFT) +#define DAC_DHR12RD_DACC2_SHIFT (16) /* Bits 16-27: DAC channel 2 12-bit right-aligned data */ +#define DAC_DHR12RD_DACC2_MASK (0xfff << DAC_DHR12RD_DACC2_SHIFT) + +/* Dual DAC 12-bit left-aligned data holding register */ + +#define DAC_DHR12LD_DACC_SHIFT(n) ((1 << (((n)-1) << 4)) + 4) +#define DAC_DHR12LD_DACC_MASK(n) (0xfff << DAC_DHR12LD_DACC_SHIFT(n)) + +#define DAC_DHR12LD_DACC1_SHIFT (4) /* Bits 4-15: DAC channel 1 12-bit left-aligned data */ +#define DAC_DHR12LD_DACC1_MASK (0xfff << DAC_DHR12LD_DACC1_SHIFT) +#define DAC_DHR12LD_DACC2_SHIFT (20) /* Bits 20-31: DAC channel 2 12-bit left-aligned data */ +#define DAC_DHR12LD_DACC2_MASK (0xfff << DAC_DHR12LD_DACC2_SHIFT) + +/* DUAL DAC 8-bit right aligned data holding register */ + +#define DAC_DHR8RD_DACC_SHIFT(n) (1 << (((n)-1) << 3)) +#define DAC_DHR8RD_DACC_MASK(n) (0xff << DAC_DHR8RD_DACC_SHIFT(n)) + +#define DAC_DHR8RD_DACC1_SHIFT (0) /* Bits 0-7: DAC channel 1 8-bit right-aligned data */ +#define DAC_DHR8RD_DACC1_MASK (0xff << DAC_DHR8RD_DACC1_SHIFT) +#define DAC_DHR8RD_DACC2_SHIFT (8) /* Bits 8-15: DAC channel 2 8-bit right-aligned data */ +#define DAC_DHR8RD_DACC2_MASK (0xff << DAC_DHR8RD_DACC2_SHIFT) + +/* DAC channel 1/2 data output register */ + +#define DAC_DOR_MASK (0x0fff) + +/* DAC status register */ + +#define DAC_SR_DMAUDR(n) ((1 << (((n)-1) << 4)) + 13) +#define DAC_SR_DMAUDR1 (1 << 13) /* Bit 13: DAC channel 1 DMA underrun flag */ +#define DAC_SR_DMAUDR2 (1 << 29) /* Bit 29: DAC channel 2 DMA underrun flag */ + +#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_DAC_H */ diff --git a/arch/arm/src/stm32f0/chip/stm32f0_dma.h b/arch/arm/src/stm32f0/chip/stm32f0_dma.h new file mode 100644 index 0000000000..f14ddb1efe --- /dev/null +++ b/arch/arm/src/stm32f0/chip/stm32f0_dma.h @@ -0,0 +1,455 @@ +/************************************************************************************ + * arch/arm/src/stm32f0/chip/stm32f0_dma.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_DMA_H +#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_DMA_H + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* 12 Channels Total: 7 DMA1 Channels(1-7) (and 5 DMA2 channels (1-5) if STM32F09x) */ + +#define DMA1 0 +#define DMA2 1 +#define DMA3 2 +#define DMA4 3 +#define DMA5 4 +#define DMA6 5 +#define DMA7 6 + +/* Register Offsets *****************************************************************/ + +#define STM32F0_DMA_ISR_OFFSET 0x0000 /* DMA interrupt status register */ +#define STM32F0_DMA_IFCR_OFFSET 0x0004 /* DMA interrupt flag clear register */ + +#define STM32F0_DMACHAN_OFFSET(n) (0x0014*(n)) +#define STM32F0_DMACHAN1_OFFSET 0x0000 +#define STM32F0_DMACHAN2_OFFSET 0x0014 +#define STM32F0_DMACHAN3_OFFSET 0x0028 +#define STM32F0_DMACHAN4_OFFSET 0x003c +#define STM32F0_DMACHAN5_OFFSET 0x0050 +#define STM32F0_DMACHAN6_OFFSET 0x0064 +#define STM32F0_DMACHAN7_OFFSET 0x0078 + +#define STM32F0_DMACHAN_CCR_OFFSET 0x0008 /* DMA channel configuration register */ +#define STM32F0_DMACHAN_CNDTR_OFFSET 0x000c /* DMA channel number of data register */ +#define STM32F0_DMACHAN_CPAR_OFFSET 0x0010 /* DMA channel peripheral address register */ +#define STM32F0_DMACHAN_CMAR_OFFSET 0x0014 /* DMA channel memory address register */ + +#define STM32F0_DMA_CCR_OFFSET(n) (STM32F0_DMACHAN_CCR_OFFSET+STM32F0_DMACHAN_OFFSET(n)) +#define STM32F0_DMA_CNDTR_OFFSET(n) (STM32F0_DMACHAN_CNDTR_OFFSET+STM32F0_DMACHAN_OFFSET(n)) +#define STM32F0_DMA_CPAR_OFFSET(n) (STM32F0_DMACHAN_CPAR_OFFSET+STM32F0_DMACHAN_OFFSET(n)) +#define STM32F0_DMA_CMAR_OFFSET(n) (STM32F0_DMACHAN_CMAR_OFFSET+STM32F0_DMACHAN_OFFSET(n)) + +#define STM32F0_DMA_CCR1_OFFSET 0x0008 /* DMA channel 1 configuration register */ +#define STM32F0_DMA_CCR2_OFFSET 0x001c /* DMA channel 2 configuration register */ +#define STM32F0_DMA_CCR3_OFFSET 0x0030 /* DMA channel 3 configuration register */ +#define STM32F0_DMA_CCR4_OFFSET 0x0044 /* DMA channel 4 configuration register */ +#define STM32F0_DMA_CCR5_OFFSET 0x0058 /* DMA channel 5 configuration register */ +#define STM32F0_DMA_CCR6_OFFSET 0x006c /* DMA channel 6 configuration register */ +#define STM32F0_DMA_CCR7_OFFSET 0x0080 /* DMA channel 7 configuration register */ + +#define STM32F0_DMA_CNDTR1_OFFSET 0x000c /* DMA channel 1 number of data register */ +#define STM32F0_DMA_CNDTR2_OFFSET 0x0020 /* DMA channel 2 number of data register */ +#define STM32F0_DMA_CNDTR3_OFFSET 0x0034 /* DMA channel 3 number of data register */ +#define STM32F0_DMA_CNDTR4_OFFSET 0x0048 /* DMA channel 4 number of data register */ +#define STM32F0_DMA_CNDTR5_OFFSET 0x005c /* DMA channel 5 number of data register */ +#define STM32F0_DMA_CNDTR6_OFFSET 0x0070 /* DMA channel 6 number of data register */ +#define STM32F0_DMA_CNDTR7_OFFSET 0x0084 /* DMA channel 7 number of data register */ + +#define STM32F0_DMA_CPAR1_OFFSET 0x0010 /* DMA channel 1 peripheral address register */ +#define STM32F0_DMA_CPAR2_OFFSET 0x0024 /* DMA channel 2 peripheral address register */ +#define STM32F0_DMA_CPAR3_OFFSET 0x0038 /* DMA channel 3 peripheral address register */ +#define STM32F0_DMA_CPAR4_OFFSET 0x004c /* DMA channel 4 peripheral address register */ +#define STM32F0_DMA_CPAR5_OFFSET 0x0060 /* DMA channel 5 peripheral address register */ +#define STM32F0_DMA_CPAR6_OFFSET 0x0074 /* DMA channel 6 peripheral address register */ +#define STM32F0_DMA_CPAR7_OFFSET 0x0088 /* DMA channel 7 peripheral address register */ + +#define STM32F0_DMA_CMAR1_OFFSET 0x0014 /* DMA channel 1 memory address register */ +#define STM32F0_DMA_CMAR2_OFFSET 0x0028 /* DMA channel 2 memory address register */ +#define STM32F0_DMA_CMAR3_OFFSET 0x003c /* DMA channel 3 memory address register */ +#define STM32F0_DMA_CMAR4_OFFSET 0x0050 /* DMA channel 4 memory address register */ +#define STM32F0_DMA_CMAR5_OFFSET 0x0064 /* DMA channel 5 memory address register */ +#define STM32F0_DMA_CMAR6_OFFSET 0x0078 /* DMA channel 6 memory address register */ +#define STM32F0_DMA_CMAR7_OFFSET 0x008c /* DMA channel 7 memory address register */ + +#define STM32F0_DMA_CSELR_OFFSET 0x00a8 /* DMA channel selection register */ + +/* Register Addresses ***************************************************************/ + +#define STM32F0_DMA1_ISRC (STM32F0_DMA1_BASE+STM32F0_DMA_ISR_OFFSET) +#define STM32F0_DMA1_IFCR (STM32F0_DMA1_BASE+STM32F0_DMA_IFCR_OFFSET) + +#define STM32F0_DMA1_CCR(n) (STM32F0_DMA1_BASE+STM32F0_DMA_CCR_OFFSET(n)) +#define STM32F0_DMA1_CCR1 (STM32F0_DMA1_BASE+STM32F0_DMA_CCR1_OFFSET) +#define STM32F0_DMA1_CCR2 (STM32F0_DMA1_BASE+STM32F0_DMA_CCR2_OFFSET) +#define STM32F0_DMA1_CCR3 (STM32F0_DMA1_BASE+STM32F0_DMA_CCR3_OFFSET) +#define STM32F0_DMA1_CCR4 (STM32F0_DMA1_BASE+STM32F0_DMA_CCR4_OFFSET) +#define STM32F0_DMA1_CCR5 (STM32F0_DMA1_BASE+STM32F0_DMA_CCR5_OFFSET) +#define STM32F0_DMA1_CCR6 (STM32F0_DMA1_BASE+STM32F0_DMA_CCR6_OFFSET) +#define STM32F0_DMA1_CCR7 (STM32F0_DMA1_BASE+STM32F0_DMA_CCR7_OFFSET) + +#define STM32F0_DMA1_CNDTR(n) (STM32F0_DMA1_BASE+STM32F0_DMA_CNDTR_OFFSET(n)) +#define STM32F0_DMA1_CNDTR1 (STM32F0_DMA1_BASE+STM32F0_DMA_CNDTR1_OFFSET) +#define STM32F0_DMA1_CNDTR2 (STM32F0_DMA1_BASE+STM32F0_DMA_CNDTR2_OFFSET) +#define STM32F0_DMA1_CNDTR3 (STM32F0_DMA1_BASE+STM32F0_DMA_CNDTR3_OFFSET) +#define STM32F0_DMA1_CNDTR4 (STM32F0_DMA1_BASE+STM32F0_DMA_CNDTR4_OFFSET) +#define STM32F0_DMA1_CNDTR5 (STM32F0_DMA1_BASE+STM32F0_DMA_CNDTR5_OFFSET) +#define STM32F0_DMA1_CNDTR6 (STM32F0_DMA1_BASE+STM32F0_DMA_CNDTR6_OFFSET) +#define STM32F0_DMA1_CNDTR7 (STM32F0_DMA1_BASE+STM32F0_DMA_CNDTR7_OFFSET) + +#define STM32F0_DMA1_CPAR(n) (STM32F0_DMA1_BASE+STM32F0_DMA_CPAR_OFFSET(n)) +#define STM32F0_DMA1_CPAR1 (STM32F0_DMA1_BASE+STM32F0_DMA_CPAR1_OFFSET) +#define STM32F0_DMA1_CPAR2 (STM32F0_DMA1_BASE+STM32F0_DMA_CPAR2_OFFSET) +#define STM32F0_DMA1_CPAR3 (STM32F0_DMA1_BASE+STM32F0_DMA_CPAR3_OFFSET) +#define STM32F0_DMA1_CPAR4 (STM32F0_DMA1_BASE+STM32F0_DMA_CPAR4_OFFSET) +#define STM32F0_DMA1_CPAR5 (STM32F0_DMA1_BASE+STM32F0_DMA_CPAR5_OFFSET) +#define STM32F0_DMA1_CPAR6 (STM32F0_DMA1_BASE+STM32F0_DMA_CPAR6_OFFSET) +#define STM32F0_DMA1_CPAR7 (STM32F0_DMA1_BASE+STM32F0_DMA_CPAR7_OFFSET) + +#define STM32F0_DMA1_CMAR(n) (STM32F0_DMA1_BASE+STM32F0_DMA_CMAR_OFFSET(n)) +#define STM32F0_DMA1_CMAR1 (STM32F0_DMA1_BASE+STM32F0_DMA_CMAR1_OFFSET) +#define STM32F0_DMA1_CMAR2 (STM32F0_DMA1_BASE+STM32F0_DMA_CMAR2_OFFSET) +#define STM32F0_DMA1_CMAR3 (STM32F0_DMA1_BASE+STM32F0_DMA_CMAR3_OFFSET) +#define STM32F0_DMA1_CMAR4 (STM32F0_DMA1_BASE+STM32F0_DMA_CMAR4_OFFSET) +#define STM32F0_DMA1_CMAR5 (STM32F0_DMA1_BASE+STM32F0_DMA_CMAR5_OFFSET) +#define STM32F0_DMA1_CMAR6 (STM32F0_DMA1_BASE+STM32F0_DMA_CMAR6_OFFSET) +#define STM32F0_DMA1_CMAR7 (STM32F0_DMA1_BASE+STM32F0_DMA_CMAR7_OFFSET) + +#define STM32F0_DMA2_ISRC (STM32F0_DMA2_BASE+STM32F0_DMA_ISR_OFFSET) +#define STM32F0_DMA2_IFCR (STM32F0_DMA2_BASE+STM32F0_DMA_IFCR_OFFSET) + +#define STM32F0_DMA2_CCR(n) (STM32F0_DMA2_BASE+STM32F0_DMA_CCR_OFFSET(n)) +#define STM32F0_DMA2_CCR1 (STM32F0_DMA2_BASE+STM32F0_DMA_CCR1_OFFSET) +#define STM32F0_DMA2_CCR2 (STM32F0_DMA2_BASE+STM32F0_DMA_CCR2_OFFSET) +#define STM32F0_DMA2_CCR3 (STM32F0_DMA2_BASE+STM32F0_DMA_CCR3_OFFSET) +#define STM32F0_DMA2_CCR4 (STM32F0_DMA2_BASE+STM32F0_DMA_CCR4_OFFSET) +#define STM32F0_DMA2_CCR5 (STM32F0_DMA2_BASE+STM32F0_DMA_CCR5_OFFSET) +#define STM32F0_DMA2_CCR6 (STM32F0_DMA2_BASE+STM32F0_DMA_CCR6_OFFSET) +#define STM32F0_DMA2_CCR7 (STM32F0_DMA2_BASE+STM32F0_DMA_CCR7_OFFSET) + +#define STM32F0_DMA2_CNDTR(n) (STM32F0_DMA2_BASE+STM32F0_DMA_CNDTR_OFFSET(n)) +#define STM32F0_DMA2_CNDTR1 (STM32F0_DMA2_BASE+STM32F0_DMA_CNDTR1_OFFSET) +#define STM32F0_DMA2_CNDTR2 (STM32F0_DMA2_BASE+STM32F0_DMA_CNDTR2_OFFSET) +#define STM32F0_DMA2_CNDTR3 (STM32F0_DMA2_BASE+STM32F0_DMA_CNDTR3_OFFSET) +#define STM32F0_DMA2_CNDTR4 (STM32F0_DMA2_BASE+STM32F0_DMA_CNDTR4_OFFSET) +#define STM32F0_DMA2_CNDTR5 (STM32F0_DMA2_BASE+STM32F0_DMA_CNDTR5_OFFSET) +#define STM32F0_DMA2_CNDTR6 (STM32F0_DMA2_BASE+STM32F0_DMA_CNDTR6_OFFSET) +#define STM32F0_DMA2_CNDTR7 (STM32F0_DMA2_BASE+STM32F0_DMA_CNDTR7_OFFSET) + +#define STM32F0_DMA2_CPAR(n) (STM32F0_DMA2_BASE+STM32F0_DMA_CPAR_OFFSET(n)) +#define STM32F0_DMA2_CPAR1 (STM32F0_DMA2_BASE+STM32F0_DMA_CPAR1_OFFSET) +#define STM32F0_DMA2_CPAR2 (STM32F0_DMA2_BASE+STM32F0_DMA_CPAR2_OFFSET) +#define STM32F0_DMA2_CPAR3 (STM32F0_DMA2_BASE+STM32F0_DMA_CPAR3_OFFSET) +#define STM32F0_DMA2_CPAR4 (STM32F0_DMA2_BASE+STM32F0_DMA_CPAR4_OFFSET) +#define STM32F0_DMA2_CPAR5 (STM32F0_DMA2_BASE+STM32F0_DMA_CPAR5_OFFSET) +#define STM32F0_DMA2_CPAR6 (STM32F0_DMA2_BASE+STM32F0_DMA_CPAR6_OFFSET) +#define STM32F0_DMA2_CPAR7 (STM32F0_DMA2_BASE+STM32F0_DMA_CPAR7_OFFSET) + +#define STM32F0_DMA2_CMAR(n) (STM32F0_DMA2_BASE+STM32F0_DMA_CMAR_OFFSET(n)) +#define STM32F0_DMA2_CMAR1 (STM32F0_DMA2_BASE+STM32F0_DMA_CMAR1_OFFSET) +#define STM32F0_DMA2_CMAR2 (STM32F0_DMA2_BASE+STM32F0_DMA_CMAR2_OFFSET) +#define STM32F0_DMA2_CMAR3 (STM32F0_DMA2_BASE+STM32F0_DMA_CMAR3_OFFSET) +#define STM32F0_DMA2_CMAR4 (STM32F0_DMA2_BASE+STM32F0_DMA_CMAR4_OFFSET) +#define STM32F0_DMA2_CMAR5 (STM32F0_DMA2_BASE+STM32F0_DMA_CMAR5_OFFSET) +#define STM32F0_DMA2_CMAR6 (STM32F0_DMA2_BASE+STM32F0_DMA_CMAR6_OFFSET) +#define STM32F0_DMA2_CMAR7 (STM32F0_DMA2_BASE+STM32F0_DMA_CMAR7_OFFSET) + +/* Register Bitfield Definitions ****************************************************/ + +#define DMA_CHAN_SHIFT(n) ((n) << 2) +#define DMA_CHAN_MASK 0x0f +#define DMA_CHAN_GIF_BIT (1 << 0) /* Bit 0: Channel Global interrupt flag */ +#define DMA_CHAN_TCIF_BIT (1 << 1) /* Bit 1: Channel Transfer Complete flag */ +#define DMA_CHAN_HTIF_BIT (1 << 2) /* Bit 2: Channel Half Transfer flag */ +#define DMA_CHAN_TEIF_BIT (1 << 3) /* Bit 3: Channel Transfer Error flag */ + +/* DMA interrupt status register */ + +#define DMA_ISR_CHAN_SHIFT(n) DMA_CHAN_SHIFT(n) +#define DMA_ISR_CHAN_MASK(n) (DMA_CHAN_MASK << DMA_ISR_CHAN_SHIFT(n)) +#define DMA_ISR_CHAN1_SHIFT (0) /* Bits 3-0: DMA Channel 1 interrupt status */ +#define DMA_ISR_CHAN1_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN1_SHIFT) +#define DMA_ISR_CHAN2_SHIFT (4) /* Bits 7-4: DMA Channel 2 interrupt status */ +#define DMA_ISR_CHAN2_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN2_SHIFT) +#define DMA_ISR_CHAN3_SHIFT (8) /* Bits 11-8: DMA Channel 3 interrupt status */ +#define DMA_ISR_CHAN3_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN3_SHIFT) +#define DMA_ISR_CHAN4_SHIFT (12) /* Bits 15-12: DMA Channel 4 interrupt status */ +#define DMA_ISR_CHAN4_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN4_SHIFT) +#define DMA_ISR_CHAN5_SHIFT (16) /* Bits 19-16: DMA Channel 5 interrupt status */ +#define DMA_ISR_CHAN5_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN5_SHIFT) +#define DMA_ISR_CHAN6_SHIFT (20) /* Bits 23-20: DMA Channel 6 interrupt status */ +#define DMA_ISR_CHAN6_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN6_SHIFT) +#define DMA_ISR_CHAN7_SHIFT (24) /* Bits 27-24: DMA Channel 7 interrupt status */ +#define DMA_ISR_CHAN7_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN7_SHIFT) + +#define DMA_ISR_GIF(n) (DMA_CHAN_GIF_BIT << DMA_ISR_CHAN_SHIFT(n)) +#define DMA_ISR_TCIF(n) (DMA_CHAN_TCIF_BIT << DMA_ISR_CHAN_SHIFT(n)) +#define DMA_ISR_HTIF(n) (DMA_CHAN_HTIF_BIT << DMA_ISR_CHAN_SHIFT(n)) +#define DMA_ISR_TEIF(n) (DMA_CHAN_TEIF_BIT << DMA_ISR_CHAN_SHIFT(n)) + +/* DMA interrupt flag clear register */ + +#define DMA_IFCR_CHAN_SHIFT(n) DMA_CHAN_SHIFT(n) +#define DMA_IFCR_CHAN_MASK(n) (DMA_CHAN_MASK << DMA_IFCR_CHAN_SHIFT(n)) +#define DMA_IFCR_CHAN1_SHIFT (0) /* Bits 3-0: DMA Channel 1 interrupt flag clear */ +#define DMA_IFCR_CHAN1_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN1_SHIFT) +#define DMA_IFCR_CHAN2_SHIFT (4) /* Bits 7-4: DMA Channel 2 interrupt flag clear */ +#define DMA_IFCR_CHAN2_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN2_SHIFT) +#define DMA_IFCR_CHAN3_SHIFT (8) /* Bits 11-8: DMA Channel 3 interrupt flag clear */ +#define DMA_IFCR_CHAN3_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN3_SHIFT) +#define DMA_IFCR_CHAN4_SHIFT (12) /* Bits 15-12: DMA Channel 4 interrupt flag clear */ +#define DMA_IFCR_CHAN4_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN4_SHIFT) +#define DMA_IFCR_CHAN5_SHIFT (16) /* Bits 19-16: DMA Channel 5 interrupt flag clear */ +#define DMA_IFCR_CHAN5_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN5_SHIFT) +#define DMA_IFCR_CHAN6_SHIFT (20) /* Bits 23-20: DMA Channel 6 interrupt flag clear */ +#define DMA_IFCR_CHAN6_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN6_SHIFT) +#define DMA_IFCR_CHAN7_SHIFT (24) /* Bits 27-24: DMA Channel 7 interrupt flag clear */ +#define DMA_IFCR_CHAN7_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN7_SHIFT) +#define DMA_IFCR_ALLCHANNELS (0x0fffffff) + +#define DMA_IFCR_CGIF(n) (DMA_CHAN_GIF_BIT << DMA_IFCR_CHAN_SHIFT(n)) +#define DMA_IFCR_CTCIF(n) (DMA_CHAN_TCIF_BIT << DMA_IFCR_CHAN_SHIFT(n)) +#define DMA_IFCR_CHTIF(n) (DMA_CHAN_HTIF_BIT << DMA_IFCR_CHAN_SHIFT(n)) +#define DMA_IFCR_CTEIF(n) (DMA_CHAN_TEIF_BIT << DMA_IFCR_CHAN_SHIFT(n)) + +/* DMA channel configuration register */ + +#define DMA_CCR_EN (1 << 0) /* Bit 0: Channel enable */ +#define DMA_CCR_TCIE (1 << 1) /* Bit 1: Transfer complete interrupt enable */ +#define DMA_CCR_HTIE (1 << 2) /* Bit 2: Half Transfer interrupt enable */ +#define DMA_CCR_TEIE (1 << 3) /* Bit 3: Transfer error interrupt enable */ +#define DMA_CCR_DIR (1 << 4) /* Bit 4: Data transfer direction */ +#define DMA_CCR_CIRC (1 << 5) /* Bit 5: Circular mode */ +#define DMA_CCR_PINC (1 << 6) /* Bit 6: Peripheral increment mode */ +#define DMA_CCR_MINC (1 << 7) /* Bit 7: Memory increment mode */ +#define DMA_CCR_PSIZE_SHIFT (8) /* Bits 8-9: Peripheral size */ +#define DMA_CCR_PSIZE_MASK (3 << DMA_CCR_PSIZE_SHIFT) +# define DMA_CCR_PSIZE_8BITS (0 << DMA_CCR_PSIZE_SHIFT) /* 00: 8-bits */ +# define DMA_CCR_PSIZE_16BITS (1 << DMA_CCR_PSIZE_SHIFT) /* 01: 16-bits */ +# define DMA_CCR_PSIZE_32BITS (2 << DMA_CCR_PSIZE_SHIFT) /* 10: 32-bits */ +#define DMA_CCR_MSIZE_SHIFT (10) /* Bits 10-11: Memory size */ +#define DMA_CCR_MSIZE_MASK (3 << DMA_CCR_MSIZE_SHIFT) +# define DMA_CCR_MSIZE_8BITS (0 << DMA_CCR_MSIZE_SHIFT) /* 00: 8-bits */ +# define DMA_CCR_MSIZE_16BITS (1 << DMA_CCR_MSIZE_SHIFT) /* 01: 16-bits */ +# define DMA_CCR_MSIZE_32BITS (2 << DMA_CCR_MSIZE_SHIFT) /* 10: 32-bits */ +#define DMA_CCR_PL_SHIFT (12) /* Bits 12-13: Channel Priority level */ +#define DMA_CCR_PL_MASK (3 << DMA_CCR_PL_SHIFT) +# define DMA_CCR_PRILO (0 << DMA_CCR_PL_SHIFT) /* 00: Low */ +# define DMA_CCR_PRIMED (1 << DMA_CCR_PL_SHIFT) /* 01: Medium */ +# define DMA_CCR_PRIHI (2 << DMA_CCR_PL_SHIFT) /* 10: High */ +# define DMA_CCR_PRIVERYHI (3 << DMA_CCR_PL_SHIFT) /* 11: Very high */ +#define DMA_CCR_MEM2MEM (1 << 14) /* Bit 14: Memory to memory mode */ + +#define DMA_CCR_ALLINTS (DMA_CCR_TEIE|DMA_CCR_HTIE|DMA_CCR_TCIE) + +/* DMA channel number of data register */ + +#define DMA_CNDTR_NDT_SHIFT (0) /* Bits 15-0: Number of data to Transfer */ +#define DMA_CNDTR_NDT_MASK (0xffff << DMA_CNDTR_NDT_SHIFT) + +/* DMA Channel mapping. Each DMA channel has a mapping to one of several + * possible sources/sinks of data. The requests from peripherals assigned to a + * channel are multiplexed together before entering the DMA block. This means + * that only one request on a given channel can be enabled at once. + * + * Alternative DMA channel selections are provided with a numeric suffix like _1, + * _2, etc. Drivers, however, will use the pin selection without the numeric suffix. + * Additional definitions are required in the board.h file. + */ + +/* REVISE IT: based on STM32L4 DMA Header */ + +#define STM32F0_DMA1_CHAN1 (0) +#define STM32F0_DMA1_CHAN2 (1) +#define STM32F0_DMA1_CHAN3 (2) +#define STM32F0_DMA1_CHAN4 (3) +#define STM32F0_DMA1_CHAN5 (4) +#define STM32F0_DMA1_CHAN6 (5) +#define STM32F0_DMA1_CHAN7 (6) + +#define STM32F0_DMA2_CHAN1 (7) +#define STM32F0_DMA2_CHAN2 (8) +#define STM32F0_DMA2_CHAN3 (9) +#define STM32F0_DMA2_CHAN4 (10) +#define STM32F0_DMA2_CHAN5 (11) + +#define DMACHAN_SETTING(chan, sel) ( ( ( (sel) & 0xff) << 8) | ( (chan) & 0xff) ) +#define DMACHAN_SETTING_CHANNEL_MASK 0x00FF +#define DMACHAN_SETTING_CHANNEL_SHIFT (0) +#define DMACHAN_SETTING_FUNCTION_MASK 0xFF00 +#define DMACHAN_SETTING_FUNCTION_SHIFT (8) + +/* ADC */ + +#define DMACHAN_ADC1_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN1, 0) +#define DMACHAN_ADC1_2 DMACHAN_SETTING(STM32F0_DMA2_CHAN3, 0) + +#define DMACHAN_ADC2_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN1, 0) +#define DMACHAN_ADC2_2 DMACHAN_SETTING(STM32F0_DMA2_CHAN4, 0) + +#define DMACHAN_ADC3_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN1, 0) +#define DMACHAN_ADC3_2 DMACHAN_SETTING(STM32F0_DMA2_CHAN5, 0) + +/* AES */ + +#define DMACHAN_AES_IN_1 DMACHAN_SETTING(STM32F0_DMA2_CHAN1, 6) +#define DMACHAN_AES_IN_2 DMACHAN_SETTING(STM32F0_DMA2_CHAN5, 6) +#define DMACHAN_AES_OUT_1 DMACHAN_SETTING(STM32F0_DMA2_CHAN2, 6) +#define DMACHAN_AES_OUT_2 DMACHAN_SETTING(STM32F0_DMA2_CHAN3, 6) + +/* DAC */ + +#define DMACHAN_DAC1_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN3, 6) +#define DMACHAN_DAC1_2 DMACHAN_SETTING(STM32F0_DMA1_CHAN4, 5) +#define DMACHAN_DAC1_3 DMACHAN_SETTING(STM32F0_DMA2_CHAN4, 3) + +#define DMACHAN_DAC2 DMACHAN_SETTING(STM32F0_DMA2_CHAN5, 3) + +/* I2C */ + +#define DMACHAN_I2C1_RX_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN7, 3) +#define DMACHAN_I2C1_RX_2 DMACHAN_SETTING(STM32F0_DMA2_CHAN6, 5) +#define DMACHAN_I2C1_TX_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN6, 3) +#define DMACHAN_I2C1_TX_2 DMACHAN_SETTING(STM32F0_DMA2_CHAN7, 5) + +#define DMACHAN_I2C2_RX DMACHAN_SETTING(STM32F0_DMA1_CHAN5, 3) +#define DMACHAN_I2C2_TX DMACHAN_SETTING(STM32F0_DMA1_CHAN4, 3) + +#define DMACHAN_I2C3_RX DMACHAN_SETTING(STM32F0_DMA1_CHAN3, 2) +#define DMACHAN_I2C3_TX DMACHAN_SETTING(STM32F0_DMA1_CHAN2, 3) + +/* QUADSPI */ + +#define DMACHAN_QUADSPI_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN5, 5) +#define DMACHAN_QUADSPI_2 DMACHAN_SETTING(STM32F0_DMA2_CHAN7, 3) + +/* SPI */ + +#define DMACHAN_SPI1_RX_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN2, 1) +#define DMACHAN_SPI1_RX_2 DMACHAN_SETTING(STM32F0_DMA2_CHAN3, 4) +#define DMACHAN_SPI1_TX_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN3, 0) +#define DMACHAN_SPI1_TX_2 DMACHAN_SETTING(STM32F0_DMA2_CHAN4, 4) + +#define DMACHAN_SPI2_RX DMACHAN_SETTING(STM32F0_DMA1_CHAN4, 1) +#define DMACHAN_SPI2_TX DMACHAN_SETTING(STM32F0_DMA1_CHAN5, 1) + +#define DMACHAN_SPI3_RX DMACHAN_SETTING(STM32F0_DMA2_CHAN1, 3) +#define DMACHAN_SPI3_TX DMACHAN_SETTING(STM32F0_DMA2_CHAN2, 3) + +/* TIM */ + +#define DMACHAN_TIM1_CH1 DMACHAN_SETTING(STM32F0_DMA1_CHAN2, 7) +#define DMACHAN_TIM1_CH2 DMACHAN_SETTING(STM32F0_DMA1_CHAN3, 7) +#define DMACHAN_TIM1_CH3 DMACHAN_SETTING(STM32F0_DMA1_CHAN7, 7) +#define DMACHAN_TIM1_CH4 DMACHAN_SETTING(STM32F0_DMA1_CHAN4, 7) +#define DMACHAN_TIM1_COM DMACHAN_SETTING(STM32F0_DMA1_CHAN4, 7) +#define DMACHAN_TIM1_TRIG DMACHAN_SETTING(STM32F0_DMA1_CHAN4, 7) +#define DMACHAN_TIM1_UP DMACHAN_SETTING(STM32F0_DMA1_CHAN6, 7) + +#define DMACHAN_TIM2_CH1 DMACHAN_SETTING(STM32F0_DMA1_CHAN5, 4) +#define DMACHAN_TIM2_CH2 DMACHAN_SETTING(STM32F0_DMA1_CHAN7, 4) +#define DMACHAN_TIM2_CH3 DMACHAN_SETTING(STM32F0_DMA1_CHAN1, 4) +#define DMACHAN_TIM2_CH4 DMACHAN_SETTING(STM32F0_DMA1_CHAN7, 4) +#define DMACHAN_TIM2_UP DMACHAN_SETTING(STM32F0_DMA1_CHAN2, 4) + +#define DMACHAN_TIM3_CH1 DMACHAN_SETTING(STM32F0_DMA1_CHAN6, 5) +#define DMACHAN_TIM3_CH3 DMACHAN_SETTING(STM32F0_DMA1_CHAN2, 5) +#define DMACHAN_TIM3_CH4 DMACHAN_SETTING(STM32F0_DMA1_CHAN3, 5) +#define DMACHAN_TIM3_TRIG DMACHAN_SETTING(STM32F0_DMA1_CHAN6, 5) +#define DMACHAN_TIM3_UP DMACHAN_SETTING(STM32F0_DMA1_CHAN3, 5) + +#define DMACHAN_TIM4_CH1 DMACHAN_SETTING(STM32F0_DMA1_CHAN1, 6) +#define DMACHAN_TIM4_CH2 DMACHAN_SETTING(STM32F0_DMA1_CHAN4, 6) +#define DMACHAN_TIM4_CH3 DMACHAN_SETTING(STM32F0_DMA1_CHAN5, 6) +#define DMACHAN_TIM4_UP DMACHAN_SETTING(STM32F0_DMA1_CHAN7, 6) + +#define DMACHAN_TIM5_CH1 DMACHAN_SETTING(STM32F0_DMA2_CHAN5, 5) +#define DMACHAN_TIM5_CH2 DMACHAN_SETTING(STM32F0_DMA2_CHAN4, 5) +#define DMACHAN_TIM5_CH3 DMACHAN_SETTING(STM32F0_DMA2_CHAN2, 5) +#define DMACHAN_TIM5_CH4 DMACHAN_SETTING(STM32F0_DMA2_CHAN1, 5) +#define DMACHAN_TIM5_COM DMACHAN_SETTING(STM32F0_DMA2_CHAN1, 5) +#define DMACHAN_TIM5_TRIG DMACHAN_SETTING(STM32F0_DMA2_CHAN1, 5) +#define DMACHAN_TIM5_UP DMACHAN_SETTING(STM32F0_DMA2_CHAN2, 5) + +#define DMACHAN_TIM6_UP_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN3, 6) +#define DMACHAN_TIM6_UP_2 DMACHAN_SETTING(STM32F0_DMA2_CHAN4, 3) + +#define DMACHAN_TIM7_UP_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN4, 5) +#define DMACHAN_TIM7_UP_2 DMACHAN_SETTING(STM32F0_DMA2_CHAN5, 3) + +#define DMACHAN_TIM8_CH1 DMACHAN_SETTING(STM32F0_DMA2_CHAN6, 7) +#define DMACHAN_TIM8_CH2 DMACHAN_SETTING(STM32F0_DMA2_CHAN7, 7) +#define DMACHAN_TIM8_CH3 DMACHAN_SETTING(STM32F0_DMA2_CHAN1, 7) +#define DMACHAN_TIM8_CH4 DMACHAN_SETTING(STM32F0_DMA2_CHAN2, 7) +#define DMACHAN_TIM8_COM DMACHAN_SETTING(STM32F0_DMA2_CHAN2, 7) +#define DMACHAN_TIM8_TRIG DMACHAN_SETTING(STM32F0_DMA2_CHAN2, 7) +#define DMACHAN_TIM8_UP DMACHAN_SETTING(STM32F0_DMA2_CHAN1, 7) + +#define DMACHAN_TIM15_CH1 DMACHAN_SETTING(STM32F0_DMA1_CHAN5, 7) +#define DMACHAN_TIM15_COM DMACHAN_SETTING(STM32F0_DMA1_CHAN5, 7) +#define DMACHAN_TIM15_TRIG DMACHAN_SETTING(STM32F0_DMA1_CHAN5, 7) +#define DMACHAN_TIM15_UP DMACHAN_SETTING(STM32F0_DMA1_CHAN5, 7) + +#define DMACHAN_TIM16_CH1_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN3, 4) +#define DMACHAN_TIM16_CH1_2 DMACHAN_SETTING(STM32F0_DMA1_CHAN6, 4) +#define DMACHAN_TIM16_UP_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN3, 4) +#define DMACHAN_TIM16_UP_2 DMACHAN_SETTING(STM32F0_DMA1_CHAN6, 4) + +#define DMACHAN_TIM17_CH1_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN1, 5) +#define DMACHAN_TIM17_CH1_2 DMACHAN_SETTING(STM32F0_DMA1_CHAN7, 5) +#define DMACHAN_TIM17_UP_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN1, 5) +#define DMACHAN_TIM17_UP_2 DMACHAN_SETTING(STM32F0_DMA1_CHAN7, 5) + +/* UART */ + +#define DMACHAN_USART1_RX_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN5, 2) +#define DMACHAN_USART1_RX_2 DMACHAN_SETTING(STM32F0_DMA2_CHAN7, 2) +#define DMACHAN_USART1_TX_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN4, 2) +#define DMACHAN_USART1_TX_2 DMACHAN_SETTING(STM32F0_DMA2_CHAN6, 2) + +#define DMACHAN_USART2_RX DMACHAN_SETTING(STM32F0_DMA1_CHAN6, 2) +#define DMACHAN_USART2_TX DMACHAN_SETTING(STM32F0_DMA1_CHAN7, 2) + +#define DMACHAN_USART3_RX DMACHAN_SETTING(STM32F0_DMA1_CHAN3, 1) +#define DMACHAN_USART3_TX DMACHAN_SETTING(STM32F0_DMA1_CHAN2, 2) + +#define DMACHAN_UART5_RX DMACHAN_SETTING(STM32F0_DMA2_CHAN2, 2) +#define DMACHAN_UART5_TX DMACHAN_SETTING(STM32F0_DMA2_CHAN1, 2) + +#define DMACHAN_UART4_RX DMACHAN_SETTING(STM32F0_DMA2_CHAN5, 2) +#define DMACHAN_UART4_TX DMACHAN_SETTING(STM32F0_DMA2_CHAN3, 2) + +#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_DMA_H */ diff --git a/arch/arm/src/stm32f0/chip/stm32f0_exti.h b/arch/arm/src/stm32f0/chip/stm32f0_exti.h new file mode 100644 index 0000000000..2fae0979f2 --- /dev/null +++ b/arch/arm/src/stm32f0/chip/stm32f0_exti.h @@ -0,0 +1,130 @@ +/************************************************************************************ + * arch/arm/src/stm32f0/chip/stm32f0_exti.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_EXTI_H +#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_EXTI_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include "chip.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +#define STM32F0_NEXTI 31 +#define STM32F0_EXTI_MASK 0xffffffff + +#define STM32F0_EXTI_BIT(n) (1 << (n)) + +/* Register Offsets *****************************************************************/ + +#define STM32F0_EXTI_IMR_OFFSET 0x0000 /* Interrupt mask register */ +#define STM32F0_EXTI_EMR_OFFSET 0x0004 /* Event mask register */ +#define STM32F0_EXTI_RTSR_OFFSET 0x0008 /* Rising Trigger selection register */ +#define STM32F0_EXTI_FTSR_OFFSET 0x000c /* Falling Trigger selection register */ +#define STM32F0_EXTI_SWIER_OFFSET 0x0010 /* Software interrupt event register */ +#define STM32F0_EXTI_PR_OFFSET 0x0014 /* Pending register */ + +/* Register Addresses ***************************************************************/ + +#define STM32F0_EXTI_IMR (STM32F0_EXTI_BASE+STM32F0_EXTI_IMR_OFFSET) +#define STM32F0_EXTI_EMR (STM32F0_EXTI_BASE+STM32F0_EXTI_EMR_OFFSET) +#define STM32F0_EXTI_RTSR (STM32F0_EXTI_BASE+STM32F0_EXTI_RTSR_OFFSET) +#define STM32F0_EXTI_FTSR (STM32F0_EXTI_BASE+STM32F0_EXTI_FTSR_OFFSET) +#define STM32F0_EXTI_SWIER (STM32F0_EXTI_BASE+STM32F0_EXTI_SWIER_OFFSET) +#define STM32F0_EXTI_PR (STM32F0_EXTI_BASE+STM32F0_EXTI_PR_OFFSET) + +/* Register Bitfield Definitions ****************************************************/ + +/* EXTI lines > 15 are associated with internal devices: */ + +#define EXTI_PVD_LINE (1 << 16) /* EXTI line 16 is connected to the PVD output */ +#define EXTI_RTC_ALARM (1 << 17) /* EXTI line 17 is connected to the RTC Alarm event */ +#define EXTI_USB_WAKEUP (1 << 18) /* EXTI line 18 is connected to the USB wake up event */ +#define EXTI_RTC_TAMPER (1 << 19) /* EXTI line 19 is connected to the RTC Tamper and TimeStamp events */ +#define EXTI_RTC_WAKEUP (1 << 20) /* EXTI line 20 is connected to the RTC Wakeup event */ +#define EXTI_COMP1 (1 << 21) /* EXTI line 21 is connected to the COMP1 (comparator) output */ +#define EXTI_COMP2 (1 << 22) /* EXTI line 22 is connected to the COMP2 (comparator) output */ +#define EXTI_I2C1 (1 << 23) /* EXTI line 23 is connected to the I2C1 wakeup */ + /* EXTI line 24 is reserved (internally held low) */ +#define EXTI_USART1 (1 << 25) /* EXTI line 25 is connected to the USART1 wakeup */ +#define EXTI_USART2 (1 << 26) /* EXTI line 26 is connected to the USART2 wakeup */ +#define EXTI_CEC (1 << 27) /* EXTI line 27 is connected to the CEC wakeup */ +#define EXTI_USART3 (1 << 28) /* EXTI line 28 is connected to the USART3 wakeup */ + /* EXTI line 29 is reserved (internally held low) */ + /* EXTI line 30 is reserved (internally held low) */ +#define EXTI_VDDIO2 (1 << 31) /* EXTI line 31 is connected to the Vddio2 supply comparator */ + +/* Interrupt mask register */ + +#define EXTI_IMR_BIT(n) STM32F0_EXTI_BIT(n) /* 1=Interrupt request from line x is not masked */ +#define EXTI_IMR_SHIFT (0) /* Bits 0-X: Interrupt Mask for all lines */ +#define EXTI_IMR_MASK STM32F0_EXTI_MASK + +/* Event mask register */ + +#define EXTI_EMR_BIT(n) STM32F0_EXTI_BIT(n) /* 1=Event request from line x is not mask */ +#define EXTI_EMR_SHIFT (0) /* Bits Bits 0-X: Event Mask for all lines */ +#define EXTI_EMR_MASK STM32F0_EXTI_MASK + +/* Rising Trigger selection register */ + +#define EXTI_RTSR_BIT(n) STM32F0_EXTI_BIT(n) /* 1=Rising trigger enabled (for Event and Interrupt) for input line */ +#define EXTI_RTSR_SHIFT (0) /* Bits 0-X: Rising trigger event configuration bit for all lines */ +#define EXTI_RTSR_MASK STM32F0_EXTI_MASK + +/* Falling Trigger selection register */ + +#define EXTI_FTSR_BIT(n) STM32F0_EXTI_BIT(n) /* 1=Falling trigger enabled (for Event and Interrupt) for input line */ +#define EXTI_FTSR_SHIFT (0) /* Bits 0-X: Falling trigger event configuration bitfor all lines */ +#define EXTI_FTSR_MASK STM32F0_EXTI_MASK + +/* Software interrupt event register */ + +#define EXTI_SWIER_BIT(n) STM32F0_EXTI_BIT(n) /* 1=Sets the corresponding pending bit in EXTI_PR */ +#define EXTI_SWIER_SHIFT (0) /* Bits 0-X: Software Interrupt for all lines */ +#define EXTI_SWIER_MASK STM32F0_EXTI_MASK + +/* Pending register */ + +#define EXTI_PR_BIT(n) STM32F0_EXTI_BIT(n) /* 1=Selected trigger request occurred */ +#define EXTI_PR_SHIFT (0) /* Bits 0-X: Pending bit for all lines */ +#define EXTI_PR_MASK STM32F0_EXTI_MASK + +#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_EXTI_H */ diff --git a/arch/arm/src/stm32f0/chip/stm32f0_gpio.h b/arch/arm/src/stm32f0/chip/stm32f0_gpio.h new file mode 100644 index 0000000000..a371da57c9 --- /dev/null +++ b/arch/arm/src/stm32f0/chip/stm32f0_gpio.h @@ -0,0 +1,332 @@ +/************************************************************************************ + * arch/arm/src/stm32f0/chip/stm32f0_gpio.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_GPIO_H +#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_GPIO_H + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Register Offsets *****************************************************************/ + +#define STM32F0_GPIO_MODER_OFFSET 0x0000 /* GPIO port mode register */ +#define STM32F0_GPIO_OTYPER_OFFSET 0x0004 /* GPIO port output type register */ +#define STM32F0_GPIO_OSPEED_OFFSET 0x0008 /* GPIO port output speed register */ +#define STM32F0_GPIO_PUPDR_OFFSET 0x000c /* GPIO port pull-up/pull-down register */ +#define STM32F0_GPIO_IDR_OFFSET 0x0010 /* GPIO port input data register */ +#define STM32F0_GPIO_ODR_OFFSET 0x0014 /* GPIO port output data register */ +#define STM32F0_GPIO_BSRR_OFFSET 0x0018 /* GPIO port bit set/reset register */ +#define STM32F0_GPIO_LCKR_OFFSET 0x001c /* GPIO port configuration lock register */ +#define STM32F0_GPIO_AFRL_OFFSET 0x0020 /* GPIO alternate function low register */ +#define STM32F0_GPIO_AFRH_OFFSET 0x0024 /* GPIO alternate function high register */ +#define STM32F0_GPIO_BRR_OFFSET 0x0028 /* GPIO port bit reset register */ + +/* Register Addresses ***************************************************************/ + +#if STM32F0_NPORTS > 0 +# define STM32F0_GPIOA_MODER (STM32F0_GPIOA_BASE+STM32F0_GPIO_MODER_OFFSET) +# define STM32F0_GPIOA_OTYPER (STM32F0_GPIOA_BASE+STM32F0_GPIO_OTYPER_OFFSET) +# define STM32F0_GPIOA_OSPEED (STM32F0_GPIOA_BASE+STM32F0_GPIO_OSPEED_OFFSET) +# define STM32F0_GPIOA_PUPDR (STM32F0_GPIOA_BASE+STM32F0_GPIO_PUPDR_OFFSET) +# define STM32F0_GPIOA_IDR (STM32F0_GPIOA_BASE+STM32F0_GPIO_IDR_OFFSET) +# define STM32F0_GPIOA_ODR (STM32F0_GPIOA_BASE+STM32F0_GPIO_ODR_OFFSET) +# define STM32F0_GPIOA_BSRR (STM32F0_GPIOA_BASE+STM32F0_GPIO_BSRR_OFFSET) +# define STM32F0_GPIOA_LCKR (STM32F0_GPIOA_BASE+STM32F0_GPIO_LCKR_OFFSET) +# define STM32F0_GPIOA_AFRL (STM32F0_GPIOA_BASE+STM32F0_GPIO_AFRL_OFFSET) +# define STM32F0_GPIOA_AFRH (STM32F0_GPIOA_BASE+STM32F0_GPIO_AFRH_OFFSET) +#endif + +#if STM32F0_NPORTS > 1 +# define STM32F0_GPIOB_MODER (STM32F0_GPIOB_BASE+STM32F0_GPIO_MODER_OFFSET) +# define STM32F0_GPIOB_OTYPER (STM32F0_GPIOB_BASE+STM32F0_GPIO_OTYPER_OFFSET) +# define STM32F0_GPIOB_OSPEED (STM32F0_GPIOB_BASE+STM32F0_GPIO_OSPEED_OFFSET) +# define STM32F0_GPIOB_PUPDR (STM32F0_GPIOB_BASE+STM32F0_GPIO_PUPDR_OFFSET) +# define STM32F0_GPIOB_IDR (STM32F0_GPIOB_BASE+STM32F0_GPIO_IDR_OFFSET) +# define STM32F0_GPIOB_ODR (STM32F0_GPIOB_BASE+STM32F0_GPIO_ODR_OFFSET) +# define STM32F0_GPIOB_BSRR (STM32F0_GPIOB_BASE+STM32F0_GPIO_BSRR_OFFSET) +# define STM32F0_GPIOB_LCKR (STM32F0_GPIOB_BASE+STM32F0_GPIO_LCKR_OFFSET) +# define STM32F0_GPIOB_AFRL (STM32F0_GPIOB_BASE+STM32F0_GPIO_AFRL_OFFSET) +# define STM32F0_GPIOB_AFRH (STM32F0_GPIOB_BASE+STM32F0_GPIO_AFRH_OFFSET) +#endif + +#if STM32F0_NPORTS > 2 +# define STM32F0_GPIOC_MODER (STM32F0_GPIOC_BASE+STM32F0_GPIO_MODER_OFFSET) +# define STM32F0_GPIOC_OTYPER (STM32F0_GPIOC_BASE+STM32F0_GPIO_OTYPER_OFFSET) +# define STM32F0_GPIOC_OSPEED (STM32F0_GPIOC_BASE+STM32F0_GPIO_OSPEED_OFFSET) +# define STM32F0_GPIOC_PUPDR (STM32F0_GPIOC_BASE+STM32F0_GPIO_PUPDR_OFFSET) +# define STM32F0_GPIOC_IDR (STM32F0_GPIOC_BASE+STM32F0_GPIO_IDR_OFFSET) +# define STM32F0_GPIOC_ODR (STM32F0_GPIOC_BASE+STM32F0_GPIO_ODR_OFFSET) +# define STM32F0_GPIOC_BSRR (STM32F0_GPIOC_BASE+STM32F0_GPIO_BSRR_OFFSET) +# define STM32F0_GPIOC_LCKR (STM32F0_GPIOC_BASE+STM32F0_GPIO_LCKR_OFFSET) +# define STM32F0_GPIOC_AFRL (STM32F0_GPIOC_BASE+STM32F0_GPIO_AFRL_OFFSET) +# define STM32F0_GPIOC_AFRH (STM32F0_GPIOC_BASE+STM32F0_GPIO_AFRH_OFFSET) +#endif + +#if STM32F0_NPORTS > 3 +# define STM32F0_GPIOD_MODER (STM32F0_GPIOD_BASE+STM32F0_GPIO_MODER_OFFSET) +# define STM32F0_GPIOD_OTYPER (STM32F0_GPIOD_BASE+STM32F0_GPIO_OTYPER_OFFSET) +# define STM32F0_GPIOD_OSPEED (STM32F0_GPIOD_BASE+STM32F0_GPIO_OSPEED_OFFSET) +# define STM32F0_GPIOD_PUPDR (STM32F0_GPIOD_BASE+STM32F0_GPIO_PUPDR_OFFSET) +# define STM32F0_GPIOD_IDR (STM32F0_GPIOD_BASE+STM32F0_GPIO_IDR_OFFSET) +# define STM32F0_GPIOD_ODR (STM32F0_GPIOD_BASE+STM32F0_GPIO_ODR_OFFSET) +# define STM32F0_GPIOD_BSRR (STM32F0_GPIOD_BASE+STM32F0_GPIO_BSRR_OFFSET) +# define STM32F0_GPIOD_LCKR (STM32F0_GPIOD_BASE+STM32F0_GPIO_LCKR_OFFSET) +# define STM32F0_GPIOD_AFRL (STM32F0_GPIOD_BASE+STM32F0_GPIO_AFRL_OFFSET) +# define STM32F0_GPIOD_AFRH (STM32F0_GPIOD_BASE+STM32F0_GPIO_AFRH_OFFSET) +#endif + +#if STM32F0_NPORTS > 4 +# define STM32F0_GPIOE_MODER (STM32F0_GPIOE_BASE+STM32F0_GPIO_MODER_OFFSET) +# define STM32F0_GPIOE_OTYPER (STM32F0_GPIOE_BASE+STM32F0_GPIO_OTYPER_OFFSET) +# define STM32F0_GPIOE_OSPEED (STM32F0_GPIOE_BASE+STM32F0_GPIO_OSPEED_OFFSET) +# define STM32F0_GPIOE_PUPDR (STM32F0_GPIOE_BASE+STM32F0_GPIO_PUPDR_OFFSET) +# define STM32F0_GPIOE_IDR (STM32F0_GPIOE_BASE+STM32F0_GPIO_IDR_OFFSET) +# define STM32F0_GPIOE_ODR (STM32F0_GPIOE_BASE+STM32F0_GPIO_ODR_OFFSET) +# define STM32F0_GPIOE_BSRR (STM32F0_GPIOE_BASE+STM32F0_GPIO_BSRR_OFFSET) +# define STM32F0_GPIOE_LCKR (STM32F0_GPIOE_BASE+STM32F0_GPIO_LCKR_OFFSET) +# define STM32F0_GPIOE_AFRL (STM32F0_GPIOE_BASE+STM32F0_GPIO_AFRL_OFFSET) +# define STM32F0_GPIOE_AFRH (STM32F0_GPIOE_BASE+STM32F0_GPIO_AFRH_OFFSET) +#endif + +#if STM32F0_NPORTS > 5 +# define STM32F0_GPIOF_MODER (STM32F0_GPIOF_BASE+STM32F0_GPIO_MODER_OFFSET) +# define STM32F0_GPIOF_OTYPER (STM32F0_GPIOF_BASE+STM32F0_GPIO_OTYPER_OFFSET) +# define STM32F0_GPIOF_OSPEED (STM32F0_GPIOF_BASE+STM32F0_GPIO_OSPEED_OFFSET) +# define STM32F0_GPIOF_PUPDR (STM32F0_GPIOF_BASE+STM32F0_GPIO_PUPDR_OFFSET) +# define STM32F0_GPIOF_IDR (STM32F0_GPIOF_BASE+STM32F0_GPIO_IDR_OFFSET) +# define STM32F0_GPIOF_ODR (STM32F0_GPIOF_BASE+STM32F0_GPIO_ODR_OFFSET) +# define STM32F0_GPIOF_BSRR (STM32F0_GPIOF_BASE+STM32F0_GPIO_BSRR_OFFSET) +# define STM32F0_GPIOF_LCKR (STM32F0_GPIOF_BASE+STM32F0_GPIO_LCKR_OFFSET) +# define STM32F0_GPIOF_AFRL (STM32F0_GPIOF_BASE+STM32F0_GPIO_AFRL_OFFSET) +# define STM32F0_GPIOF_AFRH (STM32F0_GPIOF_BASE+STM32F0_GPIO_AFRH_OFFSET) +#endif + +/* Register Bitfield Definitions ****************************************************/ + +/* GPIO port mode register */ + +#define GPIO_MODER_INPUT (0) /* Input */ +#define GPIO_MODER_OUTPUT (1) /* General purpose output mode */ +#define GPIO_MODER_ALT (2) /* Alternate mode */ +#define GPIO_MODER_ANALOG (3) /* Analog mode */ + +#define GPIO_MODER_SHIFT(n) ((n) << 1) +#define GPIO_MODER_MASK(n) (3 << GPIO_MODER_SHIFT(n)) + +#define GPIO_MODER0_SHIFT (0) +#define GPIO_MODER0_MASK (3 << GPIO_MODER0_SHIFT) +#define GPIO_MODER1_SHIFT (2) +#define GPIO_MODER1_MASK (3 << GPIO_MODER1_SHIFT) +#define GPIO_MODER2_SHIFT (4) +#define GPIO_MODER2_MASK (3 << GPIO_MODER2_SHIFT) +#define GPIO_MODER3_SHIFT (6) +#define GPIO_MODER3_MASK (3 << GPIO_MODER3_SHIFT) +#define GPIO_MODER4_SHIFT (8) +#define GPIO_MODER4_MASK (3 << GPIO_MODER4_SHIFT) +#define GPIO_MODER5_SHIFT (10) +#define GPIO_MODER5_MASK (3 << GPIO_MODER5_SHIFT) +#define GPIO_MODER6_SHIFT (12) +#define GPIO_MODER6_MASK (3 << GPIO_MODER6_SHIFT) +#define GPIO_MODER7_SHIFT (14) +#define GPIO_MODER7_MASK (3 << GPIO_MODER7_SHIFT) +#define GPIO_MODER8_SHIFT (16) +#define GPIO_MODER8_MASK (3 << GPIO_MODER8_SHIFT) +#define GPIO_MODER9_SHIFT (18) +#define GPIO_MODER9_MASK (3 << GPIO_MODER9_SHIFT) +#define GPIO_MODER10_SHIFT (20) +#define GPIO_MODER10_MASK (3 << GPIO_MODER10_SHIFT) +#define GPIO_MODER11_SHIFT (22) +#define GPIO_MODER11_MASK (3 << GPIO_MODER11_SHIFT) +#define GPIO_MODER12_SHIFT (24) +#define GPIO_MODER12_MASK (3 << GPIO_MODER12_SHIFT) +#define GPIO_MODER13_SHIFT (26) +#define GPIO_MODER13_MASK (3 << GPIO_MODER13_SHIFT) +#define GPIO_MODER14_SHIFT (28) +#define GPIO_MODER14_MASK (3 << GPIO_MODER14_SHIFT) +#define GPIO_MODER15_SHIFT (30) +#define GPIO_MODER15_MASK (3 << GPIO_MODER15_SHIFT) + +/* GPIO port output type register */ + +#define GPIO_OTYPER_OD(n) (1 << (n)) /* 1=Output open-drain */ +#define GPIO_OTYPER_PP(n) (0) /* 0=Ouput push-pull */ + +/* GPIO port output speed register */ + +#define GPIO_OSPEED_2MHz (0) /* x0: 2 MHz Low speed */ +#define GPIO_OSPEED_10MHz (1) /* 01: 10 MHz Medium speed */ +#define GPIO_OSPEED_50MHz (3) /* 11: 50 MHz High speed */ + +#define GPIO_OSPEED_SHIFT(n) ((n) << 1) +#define GPIO_OSPEED_MASK(n) (3 << GPIO_OSPEED_SHIFT(n)) + +#define GPIO_OSPEED0_SHIFT (0) +#define GPIO_OSPEED0_MASK (3 << GPIO_OSPEED0_SHIFT) +#define GPIO_OSPEED1_SHIFT (2) +#define GPIO_OSPEED1_MASK (3 << GPIO_OSPEED1_SHIFT) +#define GPIO_OSPEED2_SHIFT (4) +#define GPIO_OSPEED2_MASK (3 << GPIO_OSPEED2_SHIFT) +#define GPIO_OSPEED3_SHIFT (6) +#define GPIO_OSPEED3_MASK (3 << GPIO_OSPEED3_SHIFT) +#define GPIO_OSPEED4_SHIFT (8) +#define GPIO_OSPEED4_MASK (3 << GPIO_OSPEED4_SHIFT) +#define GPIO_OSPEED5_SHIFT (10) +#define GPIO_OSPEED5_MASK (3 << GPIO_OSPEED5_SHIFT) +#define GPIO_OSPEED6_SHIFT (12) +#define GPIO_OSPEED6_MASK (3 << GPIO_OSPEED6_SHIFT) +#define GPIO_OSPEED7_SHIFT (14) +#define GPIO_OSPEED7_MASK (3 << GPIO_OSPEED7_SHIFT) +#define GPIO_OSPEED8_SHIFT (16) +#define GPIO_OSPEED8_MASK (3 << GPIO_OSPEED8_SHIFT) +#define GPIO_OSPEED9_SHIFT (18) +#define GPIO_OSPEED9_MASK (3 << GPIO_OSPEED9_SHIFT) +#define GPIO_OSPEED10_SHIFT (20) +#define GPIO_OSPEED10_MASK (3 << GPIO_OSPEED10_SHIFT) +#define GPIO_OSPEED11_SHIFT (22) +#define GPIO_OSPEED11_MASK (3 << GPIO_OSPEED11_SHIFT) +#define GPIO_OSPEED12_SHIFT (24) +#define GPIO_OSPEED12_MASK (3 << GPIO_OSPEED12_SHIFT) +#define GPIO_OSPEED13_SHIFT (26) +#define GPIO_OSPEED13_MASK (3 << GPIO_OSPEED13_SHIFT) +#define GPIO_OSPEED14_SHIFT (28) +#define GPIO_OSPEED14_MASK (3 << GPIO_OSPEED14_SHIFT) +#define GPIO_OSPEED15_SHIFT (30) +#define GPIO_OSPEED15_MASK (3 << GPIO_OSPEED15_SHIFT) + +/* GPIO port pull-up/pull-down register */ + +#define GPIO_PUPDR_NONE (0) /* No pull-up, pull-down */ +#define GPIO_PUPDR_PULLUP (1) /* Pull-up */ +#define GPIO_PUPDR_PULLDOWN (2) /* Pull-down */ + +#define GPIO_PUPDR_SHIFT(n) ((n) << 1) +#define GPIO_PUPDR_MASK(n) (3 << GPIO_PUPDR_SHIFT(n)) + +#define GPIO_PUPDR0_SHIFT (0) +#define GPIO_PUPDR0_MASK (3 << GPIO_PUPDR0_SHIFT) +#define GPIO_PUPDR1_SHIFT (2) +#define GPIO_PUPDR1_MASK (3 << GPIO_PUPDR1_SHIFT) +#define GPIO_PUPDR2_SHIFT (4) +#define GPIO_PUPDR2_MASK (3 << GPIO_PUPDR2_SHIFT) +#define GPIO_PUPDR3_SHIFT (6) +#define GPIO_PUPDR3_MASK (3 << GPIO_PUPDR3_SHIFT) +#define GPIO_PUPDR4_SHIFT (8) +#define GPIO_PUPDR4_MASK (3 << GPIO_PUPDR4_SHIFT) +#define GPIO_PUPDR5_SHIFT (10) +#define GPIO_PUPDR5_MASK (3 << GPIO_PUPDR5_SHIFT) +#define GPIO_PUPDR6_SHIFT (12) +#define GPIO_PUPDR6_MASK (3 << GPIO_PUPDR6_SHIFT) +#define GPIO_PUPDR7_SHIFT (14) +#define GPIO_PUPDR7_MASK (3 << GPIO_PUPDR7_SHIFT) +#define GPIO_PUPDR8_SHIFT (16) +#define GPIO_PUPDR8_MASK (3 << GPIO_PUPDR8_SHIFT) +#define GPIO_PUPDR9_SHIFT (18) +#define GPIO_PUPDR9_MASK (3 << GPIO_PUPDR9_SHIFT) +#define GPIO_PUPDR10_SHIFT (20) +#define GPIO_PUPDR10_MASK (3 << GPIO_PUPDR10_SHIFT) +#define GPIO_PUPDR11_SHIFT (22) +#define GPIO_PUPDR11_MASK (3 << GPIO_PUPDR11_SHIFT) +#define GPIO_PUPDR12_SHIFT (24) +#define GPIO_PUPDR12_MASK (3 << GPIO_PUPDR12_SHIFT) +#define GPIO_PUPDR13_SHIFT (26) +#define GPIO_PUPDR13_MASK (3 << GPIO_PUPDR13_SHIFT) +#define GPIO_PUPDR14_SHIFT (28) +#define GPIO_PUPDR14_MASK (3 << GPIO_PUPDR14_SHIFT) +#define GPIO_PUPDR15_SHIFT (30) +#define GPIO_PUPDR15_MASK (3 << GPIO_PUPDR15_SHIFT) + +/* GPIO port input data register */ + +#define GPIO_IDR(n) (1 << (n)) + +/* GPIO port output data register */ + +#define GPIO_ODR(n) (1 << (n)) + +/* GPIO port bit set/reset register */ + +#define GPIO_BSRR_SET(n) (1 << (n)) +#define GPIO_BSRR_RESET(n) (1 << ((n)+16)) + +/* GPIO port configuration lock register */ + +#define GPIO_LCKR(n) (1 << (n)) +#define GPIO_LCKK (1 << 16) /* Lock key */ + +/* GPIO alternate function low/high register */ + +#define GPIO_AFR_SHIFT(n) ((n) << 2) +#define GPIO_AFR_MASK(n) (15 << GPIO_AFR_SHIFT(n)) + +#define GPIO_AFRL0_SHIFT (0) +#define GPIO_AFRL0_MASK (15 << GPIO_AFRL0_SHIFT) +#define GPIO_AFRL1_SHIFT (4) +#define GPIO_AFRL1_MASK (15 << GPIO_AFRL1_SHIFT) +#define GPIO_AFRL2_SHIFT (8) +#define GPIO_AFRL2_MASK (15 << GPIO_AFRL2_SHIFT) +#define GPIO_AFRL3_SHIFT (12) +#define GPIO_AFRL3_MASK (15 << GPIO_AFRL3_SHIFT) +#define GPIO_AFRL4_SHIFT (16) +#define GPIO_AFRL4_MASK (15 << GPIO_AFRL4_SHIFT) +#define GPIO_AFRL5_SHIFT (20) +#define GPIO_AFRL5_MASK (15 << GPIO_AFRL5_SHIFT) +#define GPIO_AFRL6_SHIFT (24) +#define GPIO_AFRL6_MASK (15 << GPIO_AFRL6_SHIFT) +#define GPIO_AFRL7_SHIFT (28) +#define GPIO_AFRL7_MASK (15 << GPIO_AFRL7_SHIFT) + +#define GPIO_AFRH8_SHIFT (0) +#define GPIO_AFRH8_MASK (15 << GPIO_AFRH8_SHIFT) +#define GPIO_AFRH9_SHIFT (4) +#define GPIO_AFRH9_MASK (15 << GPIO_AFRH9_SHIFT) +#define GPIO_AFRH10_SHIFT (8) +#define GPIO_AFRH10_MASK (15 << GPIO_AFRH10_SHIFT) +#define GPIO_AFRH11_SHIFT (12) +#define GPIO_AFRH11_MASK (15 << GPIO_AFRH11_SHIFT) +#define GPIO_AFRH12_SHIFT (16) +#define GPIO_AFRH12_MASK (15 << GPIO_AFRH12_SHIFT) +#define GPIO_AFRH13_SHIFT (20) +#define GPIO_AFRH13_MASK (15 << GPIO_AFRH13_SHIFT) +#define GPIO_AFRH14_SHIFT (24) +#define GPIO_AFRH14_MASK (15 << GPIO_AFRH14_SHIFT) +#define GPIO_AFRH15_SHIFT (28) +#define GPIO_AFRH15_MASK (15 << GPIO_AFRH15_SHIFT) + +/* GPIO port bit reset register */ + +#define GPIO_BRR(n) (1 << (n)) + +#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_GPIO_H */ diff --git a/arch/arm/src/stm32f0/chip/stm32f0_i2c.h b/arch/arm/src/stm32f0/chip/stm32f0_i2c.h new file mode 100644 index 0000000000..7eb7c124d2 --- /dev/null +++ b/arch/arm/src/stm32f0/chip/stm32f0_i2c.h @@ -0,0 +1,237 @@ +/************************************************************************************ + * arch/arm/src/stm32f0/chip/stm32f0_i2c.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_I2C_H +#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_I2C_H + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Register Offsets *****************************************************************/ + +#define STM32F0_I2C_CR1_OFFSET 0x0000 /* Control register 1 (32-bit) */ +#define STM32F0_I2C_CR2_OFFSET 0x0004 /* Control register 2 (32-bit) */ +#define STM32F0_I2C_OAR1_OFFSET 0x0008 /* Own address register 1 (16-bit) */ +#define STM32F0_I2C_OAR2_OFFSET 0x000c /* Own address register 2 (16-bit) */ +#define STM32F0_I2C_TIMINGR_OFFSET 0x0010 /* Timing register */ +#define STM32F0_I2C_TIMEOUTR_OFFSET 0x0014 /* Timeout register */ +#define STM32F0_I2C_ISR_OFFSET 0x0018 /* Interrupt and Status register */ +#define STM32F0_I2C_ICR_OFFSET 0x001c /* Interrupt clear register */ +#define STM32F0_I2C_PECR_OFFSET 0x0020 /* Packet error checking register */ +#define STM32F0_I2C_RXDR_OFFSET 0x0024 /* Receive data register */ +#define STM32F0_I2C_TXDR_OFFSET 0x0028 /* Transmit data register */ + +/* Register Addresses ***************************************************************/ + +#if STM32F0_NI2C > 0 +# define STM32F0_I2C1_CR1 (STM32F0_I2C1_BASE+STM32F0_I2C_CR1_OFFSET) +# define STM32F0_I2C1_CR2 (STM32F0_I2C1_BASE+STM32F0_I2C_CR2_OFFSET) +# define STM32F0_I2C1_OAR1 (STM32F0_I2C1_BASE+STM32F0_I2C_OAR1_OFFSET) +# define STM32F0_I2C1_OAR2 (STM32F0_I2C1_BASE+STM32F0_I2C_OAR2_OFFSET) +# define STM32F0_I2C1_TIMINGR (STM32F0_I2C1_BASE+STM32F0_I2C_TIMINGR_OFFSET) +# define STM32F0_I2C1_TIMEOUTR (STM32F0_I2C1_BASE+STM32F0_I2C_TIMEOUTR_OFFSET) +# define STM32F0_I2C1_ISR (STM32F0_I2C1_BASE+STM32F0_I2C_ISR_OFFSET) +# define STM32F0_I2C1_ICR (STM32F0_I2C1_BASE+STM32F0_I2C_ICR_OFFSET) +# define STM32F0_I2C1_PECR (STM32F0_I2C1_BASE+STM32F0_I2C_PECR_OFFSET) +# define STM32F0_I2C1_RXDR (STM32F0_I2C1_BASE+STM32F0_I2C_RXDR_OFFSET) +# define STM32F0_I2C1_TXDR (STM32F0_I2C1_BASE+STM32F0_I2C_TXDR_OFFSET) +#endif + +#if STM32F0_NI2C > 1 +# define STM32F0_I2C2_CR1 (STM32F0_I2C2_BASE+STM32F0_I2C_CR1_OFFSET) +# define STM32F0_I2C2_CR2 (STM32F0_I2C2_BASE+STM32F0_I2C_CR2_OFFSET) +# define STM32F0_I2C2_OAR1 (STM32F0_I2C2_BASE+STM32F0_I2C_OAR1_OFFSET) +# define STM32F0_I2C2_OAR2 (STM32F0_I2C2_BASE+STM32F0_I2C_OAR2_OFFSET) +# define STM32F0_I2C2_TIMINGR (STM32F0_I2C2_BASE+STM32F0_I2C_TIMINGR_OFFSET) +# define STM32F0_I2C2_TIMEOUTR (STM32F0_I2C2_BASE+STM32F0_I2C_TIMEOUTR_OFFSET) +# define STM32F0_I2C2_ISR (STM32F0_I2C2_BASE+STM32F0_I2C_ISR_OFFSET) +# define STM32F0_I2C2_ICR (STM32F0_I2C2_BASE+STM32F0_I2C_ICR_OFFSET) +# define STM32F0_I2C2_PECR (STM32F0_I2C2_BASE+STM32F0_I2C_PECR_OFFSET) +# define STM32F0_I2C2_RXDR (STM32F0_I2C2_BASE+STM32F0_I2C_RXDR_OFFSET) +# define STM32F0_I2C2_TXDR (STM32F0_I2C2_BASE+STM32F0_I2C_TXDR_OFFSET) +#endif + +/* Register Bitfield Definitions ****************************************************/ + +/* Control register 1 */ + +#define I2C_CR1_PE (1 << 0) /* Bit 0: Peripheral Enable */ +#define I2C_CR1_TXIE (1 << 1) /* Bit 1: TX Interrupt enable */ +#define I2C_CR1_RXIE (1 << 2) /* Bit 2: RX Interrupt enable */ +#define I2C_CR1_ADDRIE (1 << 3) /* Bit 3: Address match interrupt enable (slave) */ +#define I2C_CR1_NACKIE (1 << 4) /* Bit 4: Not acknowledge received interrupt enable */ +#define I2C_CR1_STOPIE (1 << 5) /* Bit 5: STOP detection interrupt enable */ +#define I2C_CR1_TCIE (1 << 6) /* Bit 6: Transfer Complete interrupt enable */ +#define I2C_CR1_ERRIE (1 << 7) /* Bit 7: Error interrupts enable */ +#define I2C_CR1_DNF_SHIFT (8) /* Bits 8-11: Digital noise filter */ +#define I2C_CR1_DNF_MASK (15 << I2C_CR1_DNF_SHIFT) +# define I2C_CR1_DNF_DISABLE (0 << I2C_CR1_DNF_SHIFT) +# define I2C_CR1_DNF(n) ((n) << I2C_CR1_DNF_SHIFT) /* Up to n * Ti2cclk, n=1..15 */ +#define I2C_CR1_ANFOFF (1 << 12) /* Bit 12: Analog noise filter OFF */ +#define I2C_CR1_TXDMAEN (1 << 14) /* Bit 14: DMA transmission requests enable */ +#define I2C_CR1_RXDMAEN (1 << 15) /* Bit 15: DMA reception requests enable */ +#define I2C_CR1_SBC (1 << 16) /* Bit 16: Slave byte control */ +#define I2C_CR1_NOSTRETCH (1 << 17) /* Bit 17: Clock stretching disable */ +#define I2C_CR1_WUPEN (1 << 18) /* Bit 18: Wakeup from STOP enable */ +#define I2C_CR1_GCEN (1 << 19) /* Bit 19: General call enable */ +#define I2C_CR1_SMBHEN (1 << 20) /* Bit 20: SMBus Host address enable */ +#define I2C_CR1_SMBDEN (1 << 21) /* Bit 21: SMBus Device Default address enable */ +#define I2C_CR1_ALERTEN (1 << 22) /* Bit 22: SMBus alert enable */ +#define I2C_CR1_PECEN (1 << 23) /* Bit 23: PEC enable */ + +/* Control register 2 */ + +#define I2C_CR2_SADD10_SHIFT (0) /* Bits 0-9: Slave 10-bit address (master) */ +#define I2C_CR2_SADD10_MASK (0x3ff << I2C_CR2_SADD10_SHIFT) +#define I2C_CR2_SADD7_SHIFT (1) /* Bits 1-7: Slave 7-bit address (master) */ +#define I2C_CR2_SADD7_MASK (0x7f << I2C_CR2_SADD7_SHIFT) +#define I2C_CR2_RD_WRN (1 << 10) /* Bit 10: Transfer direction (master) */ +#define I2C_CR2_ADD10 (1 << 11) /* Bit 11: 10-bit addressing mode (master) */ +#define I2C_CR2_HEAD10R (1 << 12) /* Bit 12: 10-bit address header only read direction (master) */ +#define I2C_CR2_START (1 << 13) /* Bit 13: Start generation */ +#define I2C_CR2_STOP (1 << 14) /* Bit 14: Stop generation (master) */ +#define I2C_CR2_NACK (1 << 15) /* Bit 15: NACK generation (slave) */ +#define I2C_CR2_NBYTES_SHIFT (16) /* Bits 16-23: Number of bytes */ +#define I2C_CR2_NBYTES_MASK (0xff << I2C_CR2_NBYTES_SHIFT) +#define I2C_CR2_RELOAD (1 << 24) /* Bit 24: NBYTES reload mode */ +#define I2C_CR2_AUTOEND (1 << 25) /* Bit 25: Automatic end mode (master) */ +#define I2C_CR2_PECBYTE (1 << 26) /* Bit 26: Packet error checking byte */ + +/* Own address register 1 */ + +#define I2C_OAR1_OA1_10_SHIFT (0) /* Bits 0-9: 10-bit interface address */ +#define I2C_OAR1_OA1_10_MASK (0x3ff << I2C_OAR1_OA1_10_SHIFT) +#define I2C_OAR1_OA1_7_SHIFT (1) /* Bits 1-7: 7-bit interface address */ +#define I2C_OAR1_OA1_7_MASK (0x7f << I2C_OAR1_OA1_7_SHIFT) +#define I2C_OAR1_OA1MODE (1 << 10) /* Bit 10: Own Address 1 10-bit mode */ +#define I2C_OAR1_OA1EN (1 << 15) /* Bit 15: Own Address 1 enable */ + +/* Own address register 2 */ + +#define I2C_OAR2_OA2_SHIFT (1) /* Bits 1-7: 7-bit interface address */ +#define I2C_OAR2_OA2_MASK (0x7f << I2C_OAR2_OA2_SHIFT) +#define I2C_OAR2_OA2MSK_SHIFT (8) /* Bits 8-10: Own Address 2 masks */ +#define I2C_OAR2_OA2MSK_MASK (7 << I2C_OAR2_OA2MSK_SHIFT) +# define I2C_OAR2_OA2MSK_NONE (0 << I2C_OAR2_OA2MSK_SHIFT) /* No mask */ +# define I2C_OAR2_OA2MSK_2_7 (1 << I2C_OAR2_OA2MSK_SHIFT) /* Only OA2[7:2] are compared */ +# define I2C_OAR2_OA2MSK_3_7 (2 << I2C_OAR2_OA2MSK_SHIFT) /* Only OA2[7:3] are compared */ +# define I2C_OAR2_OA2MSK_4_7 (3 << I2C_OAR2_OA2MSK_SHIFT) /* Only OA2[7:4] are compared */ +# define I2C_OAR2_OA2MSK_5_7 (4 << I2C_OAR2_OA2MSK_SHIFT) /* Only OA2[7:5] are compared */ +# define I2C_OAR2_OA2MSK_6_7 (5 << I2C_OAR2_OA2MSK_SHIFT) /* Only OA2[7:6] are compared */ +# define I2C_OAR2_OA2MSK_7 (6 << I2C_OAR2_OA2MSK_SHIFT) /* Only OA2[7] is compared */ +# define I2C_OAR2_OA2MSK_ALL (7 << I2C_OAR2_OA2MSK_SHIFT) /* All 7-bit addresses acknowledged */ +#define I2C_OAR2_OA2EN (1 << 15) /* Bit 15: Own Address 2 enable */ + +/* Timing register */ + +#define I2C_TIMINGR_SCLL_SHIFT (0) /* Bits 0-7: SCL low period (master) */ +#define I2C_TIMINGR_SCLL_MASK (0xff << I2C_TIMINGR_SCLL_SHIFT) +# define I2C_TIMINGR_SCLL(n) (((n)-1) << I2C_TIMINGR_SCLL_SHIFT) /* tSCLL = n x tPRESC */ + +#define I2C_TIMINGR_SCLH_SHIFT (8) /* Bits 8-15: SCL high period (master) */ +#define I2C_TIMINGR_SCLH_MASK (0xff << I2C_TIMINGR_SCLH_SHIFT) +# define I2C_TIMINGR_SCLH(n) (((n)-1) << I2C_TIMINGR_SCLH_SHIFT) /* tSCLH = n x tPRESC */ + +#define I2C_TIMINGR_SDADEL_SHIFT (16) /* Bits 16-19: Data hold time */ +#define I2C_TIMINGR_SDADEL_MASK (15 << I2C_TIMINGR_SDADEL_SHIFT) +# define I2C_TIMINGR_SDADEL(n) ((n) << I2C_TIMINGR_SDADEL_SHIFT) /* tSDADEL= n x tPRESC */ + +#define I2C_TIMINGR_SCLDEL_SHIFT (20) /* Bits 20-23: Data setup time */ +#define I2C_TIMINGR_SCLDEL_MASK (15 << I2C_TIMINGR_SCLDEL_SHIFT) +# define I2C_TIMINGR_SCLDEL(n) (((n)-1) << I2C_TIMINGR_SCLDEL_SHIFT) /* tSCLDEL = n x tPRESC */ + +#define I2C_TIMINGR_PRESC_SHIFT (28) /* Bits 28-31: Timing prescaler */ +#define I2C_TIMINGR_PRESC_MASK (15 << I2C_TIMINGR_PRESC_SHIFT) +# define I2C_TIMINGR_PRESC(n) (((n)-1) << I2C_TIMINGR_PRESC_SHIFT) /* tPRESC = n x tI2CCLK */ + +/* Timeout register */ + +#define I2C_TIMEOUTR_A_SHIFT (0) /* Bits 0-11: Bus Timeout A */ +#define I2C_TIMEOUTR_A_MASK (0x0fff << I2C_TIMEOUTR_A_SHIFT) +# define I2C_TIMEOUTR_A(n) ((n) << I2C_TIMEOUTR_A_SHIFT) +#define I2C_TIMEOUTR_TIDLE (1 << 12) /* Bit 12: Idle clock timeout detection */ +#define I2C_TIMEOUTR_TIMOUTEN (1 << 15) /* Bit 15: Clock timeout enable */ +#define I2C_TIMEOUTR_B_SHIFT (16) /* Bits 16-27: Bus Timeout B */ +#define I2C_TIMEOUTR_B_MASK (0x0fff << I2C_TIMEOUTR_B_SHIFT) +# define I2C_TIMEOUTR_B(n) ((n) << I2C_TIMEOUTR_B_SHIFT) +#define I2C_TIMEOUTR_TEXTEN (1 << 31) /* Bits 31: Extended clock timeout enable */ + +/* Interrupt and Status register and interrupt clear register */ +/* Common interrupt bits */ + +#define I2C_INT_ADDR (1 << 3) /* Bit 3: Address matched (slave) */ +#define I2C_INT_NACK (1 << 4) /* Bit 4: Not Acknowledge received flag */ +#define I2C_INT_STOP (1 << 5) /* Bit 5: Stop detection flag */ +#define I2C_INT_BERR (1 << 8) /* Bit 8: Bus error */ +#define I2C_INT_ARLO (1 << 9) /* Bit 9: Arbitration lost */ +#define I2C_INT_OVR (1 << 10) /* Bit 10: Overrun/Underrun (slave) */ +#define I2C_INT_PECERR (1 << 11) /* Bit 11: PEC Error in reception */ +#define I2C_INT_TIMEOUT (1 << 12) /* Bit 12: Timeout or tLOW detection flag */ +#define I2C_INT_ALERT (1 << 13) /* Bit 13: SMBus alert */ + +/* Fields unique to the Interrupt and Status register */ + +#define I2C_ISR_TXE (1 << 0) /* Bit 0: Transmit data register empty (transmitters) */ +#define I2C_ISR_TXIS (1 << 1) /* Bit 1: Transmit interrupt status (transmitters) */ +#define I2C_ISR_RXNE (1 << 2) /* Bit 2: Receive data register not empty (receivers) */ +#define I2C_ISR_ADDR (1 << 3) /* Bit 3: Address Match (slave mode) */ +#define I2C_ISR_NACKF (1 << 4) /* Bit 4: Not Acknowledge received flag */ +#define I2C_ISR_STOPF (1 << 5) /* Bit 5: Stop detection flag */ +#define I2C_ISR_TC (1 << 6) /* Bit 6: Transfer Complete (master) */ +#define I2C_ISR_TCR (1 << 7) /* Bit 7: Transfer Complete Reload */ +#define I2C_ISR_BUSY (1 << 15) /* Bit 15: Bus busy */ +#define I2C_ISR_DIR (1 << 16) /* Bit 16: Transfer direction (slave) */ +#define I2C_ISR_ADDCODE_SHIFT (17) /* Bits 17-23: Address match code (slave) */ +#define I2C_ISR_ADDCODE_MASK (0x7f << I2C_ISR_ADDCODE_SHIFT) + +#define I2C_ISR_ERRORMASK (I2C_INT_BERR | I2C_INT_ARLO | I2C_INT_OVR | I2C_INT_PECERR | I2C_INT_TIMEOUT) + +#define I2C_ICR_CLEARMASK (I2C_INT_ADDR | I2C_INT_NACK | I2C_INT_STOP | I2C_INT_BERR | I2C_INT_ARLO \ + | I2C_INT_OVR | I2C_INT_PECERR | I2C_INT_TIMEOUT | I2C_INT_ALERT) + +/* Packet error checking register */ + +#define I2C_PECR_MASK (0xff) + +/* Receive data register */ + +#define I2C_RXDR_MASK (0xff) + +/* Transmit data register */ + +#define I2C_TXDR_MASK (0xff) + +#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_I2C_H */ diff --git a/arch/arm/src/stm32f0/chip/stm32f0_memorymap.h b/arch/arm/src/stm32f0/chip/stm32f0_memorymap.h new file mode 100644 index 0000000000..f2dffd1d90 --- /dev/null +++ b/arch/arm/src/stm32f0/chip/stm32f0_memorymap.h @@ -0,0 +1,52 @@ +/************************************************************************************ + * arch/arm/src/stm32f0/chip/stm32f0_memorymap.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_MEMORYMAP_H +#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_MEMORYMAP_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include "chip.h" + +#if defined(CONFIG_STM32F0_STM32F05X) +# include "chip/stm32f05xxx_memorymap.h" +#else +# error "Unsupported STM32 memory map" +#endif + +#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_MEMORYMAP_H */ diff --git a/arch/arm/src/stm32f0/chip/stm32f0_pwr.h b/arch/arm/src/stm32f0/chip/stm32f0_pwr.h new file mode 100644 index 0000000000..7eed5837ed --- /dev/null +++ b/arch/arm/src/stm32f0/chip/stm32f0_pwr.h @@ -0,0 +1,97 @@ +/************************************************************************************ + * arch/arm/src/stm32f0/chip/stm32f0_pwr.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_PWR_H +#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_PWR_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include "chip.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Register Offsets *****************************************************************/ + +#define STM32F0_PWR_CR_OFFSET 0x0000 /* Power control register */ +#define STM32F0_PWR_CSR_OFFSET 0x0004 /* Power control/status register */ + +/* Register Addresses ***************************************************************/ + +#define STM32F0_PWR_CR (STM32F0_PWR_BASE+STM32F0_PWR_CR_OFFSET) +#define STM32F0_PWR_CSR (STM32F0_PWR_BASE+STM32F0_PWR_CSR_OFFSET) + +/* Register Bitfield Definitions ****************************************************/ + +/* Power control register */ + +#define PWR_CR_LPDS (1 << 0) /* Bit 0: Low-Power Deepsleep/sleep; low power run */ +#define PWR_CR_PDDS (1 << 1) /* Bit 1: Power Down Deepsleep */ +#define PWR_CR_CWUF (1 << 2) /* Bit 2: Clear Wakeup Flag */ +#define PWR_CR_CSBF (1 << 3) /* Bit 3: Clear Standby Flag */ +#define PWR_CR_PVDE (1 << 4) /* Bit 4: Power Voltage Detector Enable */ +#define PWR_CR_PLS_SHIFT (5) /* Bits 7-5: PVD Level Selection */ +#define PWR_CR_PLS_MASK (7 << PWR_CR_PLS_SHIFT) +# define PWR_CR_2p2V (0 << PWR_CR_PLS_SHIFT) /* 000: 2.2V */ +# define PWR_CR_2p3V (1 << PWR_CR_PLS_SHIFT) /* 001: 2.3V */ +# define PWR_CR_2p4V (2 << PWR_CR_PLS_SHIFT) /* 010: 2.4V */ +# define PWR_CR_2p5V (3 << PWR_CR_PLS_SHIFT) /* 011: 2.5V */ +# define PWR_CR_2p6V (4 << PWR_CR_PLS_SHIFT) /* 100: 2.6V */ +# define PWR_CR_2p7V (5 << PWR_CR_PLS_SHIFT) /* 101: 2.7V */ +# define PWR_CR_2p8V (6 << PWR_CR_PLS_SHIFT) /* 110: 2.8V */ +# define PWR_CR_2p9V (7 << PWR_CR_PLS_SHIFT) /* 111: 2.9V */ +#define PWR_CR_DBP (1 << 8) /* Bit 8: Disable Backup Domain write protection */ + + +/* Power control/status register */ + +#define PWR_CSR_WUF (1 << 0) /* Bit 0: Wakeup Flag */ +#define PWR_CSR_SBF (1 << 1) /* Bit 1: Standby Flag */ +#define PWR_CSR_PVDO (1 << 2) /* Bit 2: PVD Output */ +#define PWR_CSR_VREFINTRDY (1 << 3) /* Bit 3: Internal voltage reference (VREFINT) ready flag */ +#define PWR_CSR_EWUP1 (1 << 8) /* Bit 8: Enable WKUP1 pin */ +#define PWR_CSR_EWUP2 (1 << 9) /* Bit 9: Enable WKUP2 pin */ +#define PWR_CSR_EWUP3 (1 << 10) /* Bit 10: Enable WKUP3 pin */ +#define PWR_CSR_EWUP4 (1 << 11) /* Bit 11: Enable WKUP4 pin */ +#define PWR_CSR_EWUP5 (1 << 12) /* Bit 12: Enable WKUP5 pin */ +#define PWR_CSR_EWUP6 (1 << 13) /* Bit 13: Enable WKUP6 pin */ +#define PWR_CSR_EWUP7 (1 << 14) /* Bit 14: Enable WKUP7 pin */ +#define PWR_CSR_EWUP8 (1 << 15) /* Bit 15: Enable WKUP8 pin */ + +#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_PWR_H */ diff --git a/arch/arm/src/stm32f0/chip/stm32f0_rcc.h b/arch/arm/src/stm32f0/chip/stm32f0_rcc.h new file mode 100644 index 0000000000..caf1cec7e2 --- /dev/null +++ b/arch/arm/src/stm32f0/chip/stm32f0_rcc.h @@ -0,0 +1,347 @@ +/************************************************************************************ + * arch/arm/src/stm32f0/chip/stm32f0_rcc.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_RCC_H +#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_RCC_H + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Register Offsets *****************************************************************/ + +#define STM32F0_RCC_CR_OFFSET 0x0000 /* Clock control register */ +#define STM32F0_RCC_CFGR_OFFSET 0x0004 /* Clock configuration register */ +#define STM32F0_RCC_CIR_OFFSET 0x0008 /* Clock interrupt register */ +#define STM32F0_RCC_APB2RSTR_OFFSET 0x000c /* APB2 Peripheral reset register */ +#define STM32F0_RCC_APB1RSTR_OFFSET 0x0010 /* APB1 Peripheral reset register */ +#define STM32F0_RCC_AHBENR_OFFSET 0x0014 /* AHB Peripheral Clock enable register */ +#define STM32F0_RCC_APB2ENR_OFFSET 0x0018 /* APB2 Peripheral Clock enable register */ +#define STM32F0_RCC_APB1ENR_OFFSET 0x001c /* APB1 Peripheral Clock enable register */ +#define STM32F0_RCC_BDCR_OFFSET 0x0020 /* Backup domain control register */ +#define STM32F0_RCC_CSR_OFFSET 0x0024 /* Control/status register */ +#define STM32F0_RCC_AHBRSTR_OFFSET 0x0028 /* AHB Reset register */ +#define STM32F0_RCC_CFGR2_OFFSET 0x002c /* Clock configuration register 2 */ + +/* Register Addresses ***************************************************************/ + +#define STM32F0_RCC_CR (STM32F0_RCC_BASE+STM32F0_RCC_CR_OFFSET) +#define STM32F0_RCC_CFGR (STM32F0_RCC_BASE+STM32F0_RCC_CFGR_OFFSET) +#define STM32F0_RCC_CIR (STM32F0_RCC_BASE+STM32F0_RCC_CIR_OFFSET) +#define STM32F0_RCC_APB2RSTR (STM32F0_RCC_BASE+STM32F0_RCC_APB2RSTR_OFFSET) +#define STM32F0_RCC_APB1RSTR (STM32F0_RCC_BASE+STM32F0_RCC_APB1RSTR_OFFSET) +#define STM32F0_RCC_AHBENR (STM32F0_RCC_BASE+STM32F0_RCC_AHBENR_OFFSET) +#define STM32F0_RCC_APB2ENR (STM32F0_RCC_BASE+STM32F0_RCC_APB2ENR_OFFSET) +#define STM32F0_RCC_APB1ENR (STM32F0_RCC_BASE+STM32F0_RCC_APB1ENR_OFFSET) +#define STM32F0_RCC_BDCR (STM32F0_RCC_BASE+STM32F0_RCC_BDCR_OFFSET) +#define STM32F0_RCC_CSR (STM32F0_RCC_BASE+STM32F0_RCC_CSR_OFFSET) +#define STM32F0_RCC_AHBRSTR (STM32F0_RCC_BASE+STM32F0_RCC_AHBRSTR_OFFSET) +#define STM32F0_RCC_CFGR2 (STM32F0_RCC_BASE+STM32F0_RCC_CFGR2_OFFSET) + +/* Register Bitfield Definitions ****************************************************/ + +/* Clock control register */ + +#define RCC_CR_HSION (1 << 0) /* Bit 0: Internal High Speed clock enable */ +#define RCC_CR_HSIRDY (1 << 1) /* Bit 1: Internal High Speed clock ready flag */ +#define RCC_CR_HSITRIM_SHIFT (3) /* Bits 7-3: Internal High Speed clock trimming */ +#define RCC_CR_HSITRIM_MASK (0x1f << RCC_CR_HSITRIM_SHIFT) +#define RCC_CR_HSICAL_SHIFT (8) /* Bits 15-8: Internal High Speed clock Calibration */ +#define RCC_CR_HSICAL_MASK (0xff << RCC_CR_HSICAL_SHIFT) +#define RCC_CR_HSEON (1 << 16) /* Bit 16: External High Speed clock enable */ +#define RCC_CR_HSERDY (1 << 17) /* Bit 17: External High Speed clock ready flag */ +#define RCC_CR_HSEBYP (1 << 18) /* Bit 18: External High Speed clock Bypass */ +#define RCC_CR_CSSON (1 << 19) /* Bit 19: Clock Security System enable */ +#define RCC_CR_PLLON (1 << 24) /* Bit 24: PLL enable */ +#define RCC_CR_PLLRDY (1 << 25) /* Bit 25: PLL clock ready flag */ + +/* Clock configuration register */ + +#define RCC_CFGR_SW_SHIFT (0) /* Bits 1-0: System clock Switch */ +#define RCC_CFGR_SW_MASK (3 << RCC_CFGR_SW_SHIFT) +# define RCC_CFGR_SW_HSI (0 << RCC_CFGR_SW_SHIFT) /* 00: HSI selected as system clock */ +# define RCC_CFGR_SW_HSE (1 << RCC_CFGR_SW_SHIFT) /* 01: HSE selected as system clock */ +# define RCC_CFGR_SW_PLL (2 << RCC_CFGR_SW_SHIFT) /* 10: PLL selected as system clock */ +# define RCC_CFGR_SW_HSI48 (3 << RCC_CFGR_SW_SHIFT) /* 11: HSI48 selected as system clock */ +#define RCC_CFGR_SWS_SHIFT (2) /* Bits 3-2: System Clock Switch Status */ +#define RCC_CFGR_SWS_MASK (3 << RCC_CFGR_SWS_SHIFT) +# define RCC_CFGR_SWS_HSI (0 << RCC_CFGR_SWS_SHIFT) /* 00: HSI oscillator used as system clock */ +# define RCC_CFGR_SWS_HSE (1 << RCC_CFGR_SWS_SHIFT) /* 01: HSE oscillator used as system clock */ +# define RCC_CFGR_SWS_PLL (2 << RCC_CFGR_SWS_SHIFT) /* 10: PLL used as system clock */ +# define RCC_CFGR_SWS_HSI48 (3 << RCC_CFGR_SWS_SHIFT) /* 11: HSI48 used as system clock */ +#define RCC_CFGR_HPRE_SHIFT (4) /* Bits 7-4: AHB prescaler */ +#define RCC_CFGR_HPRE_MASK (0x0f << RCC_CFGR_HPRE_SHIFT) +# define RCC_CFGR_HPRE_SYSCLK (0 << RCC_CFGR_HPRE_SHIFT) /* 0xxx: SYSCLK not divided */ +# define RCC_CFGR_HPRE_SYSCLKd2 (8 << RCC_CFGR_HPRE_SHIFT) /* 1000: SYSCLK divided by 2 */ +# define RCC_CFGR_HPRE_SYSCLKd4 (9 << RCC_CFGR_HPRE_SHIFT) /* 1001: SYSCLK divided by 4 */ +# define RCC_CFGR_HPRE_SYSCLKd8 (10 << RCC_CFGR_HPRE_SHIFT) /* 1010: SYSCLK divided by 8 */ +# define RCC_CFGR_HPRE_SYSCLKd16 (11 << RCC_CFGR_HPRE_SHIFT) /* 1011: SYSCLK divided by 16 */ +# define RCC_CFGR_HPRE_SYSCLKd64 (12 << RCC_CFGR_HPRE_SHIFT) /* 1100: SYSCLK divided by 64 */ +# define RCC_CFGR_HPRE_SYSCLKd128 (13 << RCC_CFGR_HPRE_SHIFT) /* 1101: SYSCLK divided by 128 */ +# define RCC_CFGR_HPRE_SYSCLKd256 (14 << RCC_CFGR_HPRE_SHIFT) /* 1110: SYSCLK divided by 256 */ +# define RCC_CFGR_HPRE_SYSCLKd512 (15 << RCC_CFGR_HPRE_SHIFT) /* 1111: SYSCLK divided by 512 */ +#define RCC_CFGR_PPRE1_SHIFT (8) /* Bits 10-8: APB Low speed prescaler (APB1) */ +#define RCC_CFGR_PPRE1_MASK (7 << RCC_CFGR_PPRE1_SHIFT) +# define RCC_CFGR_PPRE1_HCLK (0 << RCC_CFGR_PPRE1_SHIFT) /* 0xx: HCLK not divided */ +# define RCC_CFGR_PPRE1_HCLKd2 (4 << RCC_CFGR_PPRE1_SHIFT) /* 100: HCLK divided by 2 */ +# define RCC_CFGR_PPRE1_HCLKd4 (5 << RCC_CFGR_PPRE1_SHIFT) /* 101: HCLK divided by 4 */ +# define RCC_CFGR_PPRE1_HCLKd8 (6 << RCC_CFGR_PPRE1_SHIFT) /* 110: HCLK divided by 8 */ +# define RCC_CFGR_PPRE1_HCLKd16 (7 << RCC_CFGR_PPRE1_SHIFT) /* 111: HCLK divided by 16 */ + /* Bits 13-11: Reserve. Keep the reset value */ +#define RCC_CFGR_ADCPRE (1 << 14) /* Bit 14: ADC prescaler, Obsolete use ADC_CFGR2 */ +#define RCC_CFGR_PLLSRC_SHIFT (15) /* Bit 15: PLL input clock source */ +#define RCC_CFGR_PLLSRC_MASK (3 << RCC_CFGR_PLLSRC_SHIFT) +# define RCC_CFGR_PLLSRC_HSId2 (0 << RCC_CFGR_PLLSRC_SHIFT) /* 00: HSI/2 as PLL input clock */ +# define RCC_CFGR_PLLSRC_HS1_PREDIV (1 << RCC_CFGR_PLLSRC_SHIFT) /* 01: HSE/PREDIV as PLL input clock */ +# define RCC_CFGR_PLLSRC_HSE_PREDIV (2 << RCC_CFGR_PLLSRC_SHIFT) /* 10: HSE/PREDIV as PLL input clock */ +# define RCC_CFGR_PLLSRC_HSI48_PREDIV (3 << RCC_CFGR_PLLSRC_SHIFT) /* 11: HSI48/PREDIV as PLL input clock */ +#define RCC_CFGR_PLLXTPRE (1 << 17) /* Bit 17: HSE divider for PLL entry */ +#define RCC_CFGR_PLLMUL_SHIFT (18) /* Bits 21-18: PLL Multiplication Factor */ +#define RCC_CFGR_PLLMUL_MASK (0x0f << RCC_CFGR_PLLMUL_SHIFT) +# define RCC_CFGR_PLLMUL_CLKx2 (0 << RCC_CFGR_PLLMUL_SHIFT) /* 0000: PLL input clock x 2 */ +# define RCC_CFGR_PLLMUL_CLKx3 (1 << RCC_CFGR_PLLMUL_SHIFT) /* 0001: PLL input clock x 3 */ +# define RCC_CFGR_PLLMUL_CLKx4 (2 << RCC_CFGR_PLLMUL_SHIFT) /* 0010: PLL input clock x 4 */ +# define RCC_CFGR_PLLMUL_CLKx5 (3 << RCC_CFGR_PLLMUL_SHIFT) /* 0011: PLL input clock x 5 */ +# define RCC_CFGR_PLLMUL_CLKx6 (4 << RCC_CFGR_PLLMUL_SHIFT) /* 0100: PLL input clock x 6 */ +# define RCC_CFGR_PLLMUL_CLKx7 (5 << RCC_CFGR_PLLMUL_SHIFT) /* 0101: PLL input clock x 7 */ +# define RCC_CFGR_PLLMUL_CLKx8 (6 << RCC_CFGR_PLLMUL_SHIFT) /* 0110: PLL input clock x 8 */ +# define RCC_CFGR_PLLMUL_CLKx9 (7 << RCC_CFGR_PLLMUL_SHIFT) /* 0111: PLL input clock x 9 */ +# define RCC_CFGR_PLLMUL_CLKx10 (8 << RCC_CFGR_PLLMUL_SHIFT) /* 1000: PLL input clock x 10 */ +# define RCC_CFGR_PLLMUL_CLKx11 (9 << RCC_CFGR_PLLMUL_SHIFT) /* 1001: PLL input clock x 11 */ +# define RCC_CFGR_PLLMUL_CLKx12 (10 << RCC_CFGR_PLLMUL_SHIFT) /* 1010: PLL input clock x 12 */ +# define RCC_CFGR_PLLMUL_CLKx13 (11 << RCC_CFGR_PLLMUL_SHIFT) /* 1011: PLL input clock x 13 */ +# define RCC_CFGR_PLLMUL_CLKx14 (12 << RCC_CFGR_PLLMUL_SHIFT) /* 1100: PLL input clock x 14 */ +# define RCC_CFGR_PLLMUL_CLKx15 (13 << RCC_CFGR_PLLMUL_SHIFT) /* 1101: PLL input clock x 15 */ +# define RCC_CFGR_PLLMUL_CLKx16 (14 << RCC_CFGR_PLLMUL_SHIFT) /* 111x: PLL input clock x 16 */ + /* Bit 22-23: Reserved */ +#define RCC_CFGR_MCO_SHIFT (24) /* Bits 27-24: Microcontroller Clock Output */ +#define RCC_CFGR_MCO_MASK (15 << RCC_CFGR_MCO_SHIFT) +# define RCC_CFGR_NOCLK (0 << RCC_CFGR_MCO_SHIFT) /* 0000: No clock */ +# define RCC_CFGR_HSI14 (1 << RCC_CFGR_MCO_SHIFT) /* 0001: Internal RC 14MHz oscillator */ +# define RCC_CFGR_LSI (2 << RCC_CFGR_MCO_SHIFT) /* 0010: Internal Low Speed (LSI) oscillator */ +# define RCC_CFGR_LSE (2 << RCC_CFGR_MCO_SHIFT) /* 0011: External Low Speed (LSE) oscillator */ +# define RCC_CFGR_SYSCLK (4 << RCC_CFGR_MCO_SHIFT) /* 0100: System clock selected */ +# define RCC_CFGR_INTCLK (5 << RCC_CFGR_MCO_SHIFT) /* 0101: Internal 8 MHz RC oscillator clock selected */ +# define RCC_CFGR_EXTCLK (6 << RCC_CFGR_MCO_SHIFT) /* 0110: External 4-32 MHz oscillator clock selected */ +# define RCC_CFGR_PLLCLKd2 (7 << RCC_CFGR_MCO_SHIFT) /* 0111: PLL clock selected (divided by 1 or 2 depending on PLLNODIV */ +# define RCC_CFGR_PLL2CLK (8 << RCC_CFGR_MCO_SHIFT) /* 1000: Internal RC 48MHz (HSI48) oscillator */ +#define RCC_CFGR_MCOPRE_SHIFT (28) /* Bits 28-30: Microcontroller Clock Output Prescaler, not available on STM32F05x */ +#define RCC_CFGR_MCOPRE_MASK (3 << RCC_CFGR_MCOPRE_SHIFT) +# define RCC_CFGR_MCOPRE_div1 (0 << RCC_CFGR_MCOPRE_SHIFT) /* 000: MCO is divided by 1 */ +# define RCC_CFGR_MCOPRE_div2 (1 << RCC_CFGR_MCOPRE_SHIFT) /* 001: MCO is divided by 2 */ +# define RCC_CFGR_MCOPRE_div4 (2 << RCC_CFGR_MCOPRE_SHIFT) /* 010: MCO is divided by 4 */ +# define RCC_CFGR_MCOPRE_div8 (3 << RCC_CFGR_MCOPRE_SHIFT) /* 011: MCO is divided by 8 */ +# define RCC_CFGR_MCOPRE_div16 (4 << RCC_CFGR_MCOPRE_SHIFT) /* 100: MCO is divided by 16 */ +# define RCC_CFGR_MCOPRE_div32 (5 << RCC_CFGR_MCOPRE_SHIFT) /* 101: MCO is divided by 32 */ +# define RCC_CFGR_MCOPRE_div64 (6 << RCC_CFGR_MCOPRE_SHIFT) /* 110: MCO is divided by 64 */ +# define RCC_CFGR_MCOPRE_div128 (7 << RCC_CFGR_MCOPRE_SHIFT) /* 111: MCO is divided by 128 */ + + +/* Clock interrupt register */ + +#define RCC_CIR_LSIRDYF (1 << 0) /* Bit 0: LSI Ready Interrupt flag */ +#define RCC_CIR_LSERDYF (1 << 1) /* Bit 1: LSE Ready Interrupt flag */ +#define RCC_CIR_HSIRDYF (1 << 2) /* Bit 2: HSI Ready Interrupt flag */ +#define RCC_CIR_HSERDYF (1 << 3) /* Bit 3: HSE Ready Interrupt flag */ +#define RCC_CIR_PLLRDYF (1 << 4) /* Bit 4: PLL Ready Interrupt flag */ +#define RCC_CIR_HSI14RDYF (1 << 5) /* Bit 5: HSI14 Ready Interrupt flag */ +#define RCC_CIR_HSI48RDYF (1 << 6) /* Bit 6: HSI48 Ready Interrupt flag */ +#define RCC_CIR_CSSF (1 << 7) /* Bit 7: Clock Security System Interrupt flag */ +#define RCC_CIR_LSIRDYIE (1 << 8) /* Bit 8: LSI Ready Interrupt Enable */ +#define RCC_CIR_LSERDYIE (1 << 9) /* Bit 9: LSE Ready Interrupt Enable */ +#define RCC_CIR_HSIRDYIE (1 << 10) /* Bit 10: HSI Ready Interrupt Enable */ +#define RCC_CIR_HSERDYIE (1 << 11) /* Bit 11: HSE Ready Interrupt Enable */ +#define RCC_CIR_PLLRDYIE (1 << 12) /* Bit 12: PLL Ready Interrupt Enable */ +#define RCC_CIR_HSI14RDYIE (1 << 13) /* Bit 13: HSI14 Ready Interrupt Enable */ +#define RCC_CIR_HSI48RDYIE (1 << 14) /* Bit 14: HSI48 Ready Interrupt Enable */ +#define RCC_CIR_LSIRDYC (1 << 16) /* Bit 16: LSI Ready Interrupt Clear */ +#define RCC_CIR_LSERDYC (1 << 17) /* Bit 17: LSE Ready Interrupt Clear */ +#define RCC_CIR_HSIRDYC (1 << 18) /* Bit 18: HSI Ready Interrupt Clear */ +#define RCC_CIR_HSERDYC (1 << 19) /* Bit 19: HSE Ready Interrupt Clear */ +#define RCC_CIR_PLLRDYC (1 << 20) /* Bit 20: PLL Ready Interrupt Clear */ +#define RCC_CIR_HSI14RDYC (1 << 21) /* Bit 21: HSI14 Ready Interrupt Clear */ +#define RCC_CIR_HSI48RDYC (1 << 22) /* Bit 22: HSI48 Ready Interrupt Clear */ +#define RCC_CIR_CSSC (1 << 23) /* Bit 23: Clock Security System Interrupt Clear */ + +/* APB2 Peripheral reset register */ + +#define RCC_APB2RSTR_SYSCFGRST (1 << 0) /* Bit 0: SYSCFG reset */ +#define RCC_APB2RSTR_USART6RST (1 << 5) /* Bit 5: USART6 reset */ +#define RCC_APB2RSTR_USART7RST (1 << 6) /* Bit 6: USART7 reset */ +#define RCC_APB2RSTR_USART8RST (1 << 7) /* Bit 7: USART8 reset */ +#define RCC_APB2RSTR_ADCRST (1 << 9) /* Bit 9: ADC interface reset */ +#define RCC_APB2RSTR_TIM1RST (1 << 11) /* Bit 11: TIM1 Timer reset */ +#define RCC_APB2RSTR_SPI1RST (1 << 12) /* Bit 12: SPI 1 reset */ +#define RCC_APB2RSTR_USART1RST (1 << 14) /* Bit 14: USART1 reset */ +#define RCC_APB2RSTR_TIM15RST (1 << 16) /* Bit 16: TIM15 reset */ +#define RCC_APB2RSTR_TIM16RST (1 << 17) /* Bit 17: TIM16 reset */ +#define RCC_APB2RSTR_TIM17RST (1 << 18) /* Bit 18: TIM17 reset */ +#define RCC_APB2RSTR_DBGMCURST (1 << 22) /* Bit 22: Debug MCU reset */ + +/* APB1 Peripheral reset register */ + +#define RCC_APB1RSTR_TIM2RST (1 << 0) /* Bit 0: Timer 2 reset */ +#define RCC_APB1RSTR_TIM3RST (1 << 1) /* Bit 1: Timer 3 reset */ +#define RCC_APB1RSTR_TIM6RST (1 << 4) /* Bit 4: Timer 6 reset */ +#define RCC_APB1RSTR_TIM7RST (1 << 5) /* Bit 5: Timer 7 reset */ +#define RCC_APB1RSTR_TIM14RST (1 << 8) /* Bit 8: TIM14 reset */ +#define RCC_APB1RSTR_WWDGRST (1 << 11) /* Bit 11: Window Watchdog reset */ +#define RCC_APB1RSTR_SPI2RST (1 << 14) /* Bit 14: SPI 2 reset */ +#define RCC_APB1RSTR_USART2RST (1 << 17) /* Bit 17: USART 2 reset */ +#define RCC_APB1RSTR_USART3RST (1 << 18) /* Bit 18: USART 3 reset */ +#define RCC_APB1RSTR_UART4RST (1 << 19) /* Bit 19: UART 4 reset */ +#define RCC_APB1RSTR_UART5RST (1 << 20) /* Bit 20: UART 5 reset */ +#define RCC_APB1RSTR_I2C1RST (1 << 21) /* Bit 21: I2C 1 reset */ +#define RCC_APB1RSTR_I2C2RST (1 << 22) /* Bit 22: I2C 2 reset */ +#define RCC_APB1RSTR_USBRST (1 << 23) /* Bit 23: USB reset */ +#define RCC_APB1RSTR_CAN1RST (1 << 25) /* Bit 25: CAN1 reset */ +#define RCC_APB1RSTR_CRSRST (1 << 27) /* Bit 27: CRS / Backup interface reset */ +#define RCC_APB1RSTR_PWRRST (1 << 28) /* Bit 28: Power interface reset */ +#define RCC_APB1RSTR_DACRST (1 << 29) /* Bit 29: DAC interface reset */ +#define RCC_APB1RSTR_CECRST (1 << 30) /* Bit 30: CEC reset */ + +/* AHB Peripheral Clock enable register */ + +#define RCC_AHBENR_DMA1EN (1 << 0) /* Bit 0: DMA1 clock enable */ +#define RCC_AHBENR_DMA2EN (1 << 1) /* Bit 1: DMA2 clock enable */ +#define RCC_AHBENR_SRAMEN (1 << 2) /* Bit 2: SRAM interface clock enable */ +#define RCC_AHBENR_FLITFEN (1 << 4) /* Bit 4: FLITF clock enable */ +#define RCC_AHBENR_CRCEN (1 << 6) /* Bit 6: CRC clock enable */ +#define RCC_AHBENR_IOPAEN (1 << 17) /* Bit 17: I/O port A clock enable */ +#define RCC_AHBENR_IOPBEN (1 << 18) /* Bit 18: I/O port B clock enable */ +#define RCC_AHBENR_IOPCEN (1 << 19) /* Bit 19: I/O port C clock enable */ +#define RCC_AHBENR_IOPDEN (1 << 20) /* Bit 20: I/O port D clock enable */ +#define RCC_AHBENR_IOPEEN (1 << 21) /* Bit 21: I/O port E clock enable */ +#define RCC_AHBENR_IOPFEN (1 << 22) /* Bit 22: I/O port F clock enable */ +#define RCC_AHBENR_TSCEN (1 << 24) /* Bit 24: Touch sensing controller clock enable */ + +/* APB2 Peripheral Clock enable register */ + +#define RCC_APB2ENR_SYSCFGCOMPEN (1 << 0) /* Bit 0: SYSCFG & COMP clock enable */ +#define RCC_APB2ENR_USART6EN (1 << 5) /* Bit 5: USART6 clock enable */ +#define RCC_APB2ENR_USART7EN (1 << 6) /* Bit 6: USART7 clock enable */ +#define RCC_APB2ENR_USART8EN (1 << 7) /* Bit 7: USART8 & COMP clock enable */ +#define RCC_APB2ENR_ADCEN (1 << 9) /* Bit 10: ADC interface clock enable */ +#define RCC_APB2ENR_TIM1EN (1 << 11) /* Bit 11: TIM1 Timer clock enable */ +#define RCC_APB2ENR_SPI1EN (1 << 12) /* Bit 12: SPI 1 clock enable */ +#define RCC_APB2ENR_USART1EN (1 << 14) /* Bit 14: USART1 clock enable */ +#define RCC_APB2ENR_TIM15EN (1 << 16) /* Bit 16: TIM15 clock enable */ +#define RCC_APB2ENR_TIM16EN (1 << 17) /* Bit 17: TIM16 clock enable */ +#define RCC_APB2ENR_TIM17EN (1 << 18) /* Bit 18: TIM17 clock enable */ +#define RCC_APB2ENR_DBGMCUEN (1 << 22) /* Bit 18: Debug MCU clock enable */ + +/* APB1 Peripheral Clock enable register */ + +#define RCC_APB1ENR_TIM2EN (1 << 0) /* Bit 0: Timer 2 clock enable */ +#define RCC_APB1ENR_TIM3EN (1 << 1) /* Bit 1: Timer 3 clock enable */ +#define RCC_APB1ENR_TIM4EN (1 << 2) /* Bit 2: Timer 4 clock enable */ +#define RCC_APB1ENR_TIM6EN (1 << 4) /* Bit 4: Timer 6 clock enable */ +#define RCC_APB1ENR_TIM7EN (1 << 5) /* Bit 5: Timer 7 clock enable */ +#define RCC_APB1ENR_TIM14EN (1 << 8) /* Bit 8: Timer 14 clock enable */ +#define RCC_APB1ENR_WWDGEN (1 << 11) /* Bit 11: Window Watchdog clock enable */ +#define RCC_APB1ENR_SPI2EN (1 << 14) /* Bit 14: SPI 2 clock enable */ +#define RCC_APB1ENR_USART2EN (1 << 17) /* Bit 17: USART 2 clock enable */ +#define RCC_APB1ENR_USART3EN (1 << 18) /* Bit 18: USART 3 clock enable */ +#define RCC_APB1ENR_UART4EN (1 << 19) /* Bit 19: UART 4 clock enable */ +#define RCC_APB1ENR_UART5EN (1 << 20) /* Bit 20: UART 5 clock enable */ +#define RCC_APB1ENR_I2C1EN (1 << 21) /* Bit 21: I2C 1 clock enable */ +#define RCC_APB1ENR_I2C2EN (1 << 22) /* Bit 22: I2C 2 clock enable */ +#define RCC_APB1ENR_USBEN (1 << 23) /* Bit 23: USB clock enable */ +#define RCC_APB1ENR_CANEN (1 << 25) /* Bit 25: CAN clock enable */ +#define RCC_APB1ENR_CRSEN (1 << 27) /* Bit 27: CRS / Backup interface clock enable */ +#define RCC_APB1ENR_PWREN (1 << 28) /* Bit 28: Power interface clock enable */ +#define RCC_APB1ENR_DACEN (1 << 29) /* Bit 29: DAC interface clock enable */ +#define RCC_APB1ENR_CECEN (1 << 30) /* Bit 30: CEC clock enable */ + +/* RTC domain control register */ + +#define RCC_BDCR_LSEON (1 << 0) /* Bit 0: External Low Speed oscillator enable */ +#define RCC_BDCR_LSERDY (1 << 1) /* Bit 1: External Low Speed oscillator Ready */ +#define RCC_BDCR_LSEBYP (1 << 2) /* Bit 2: External Low Speed oscillator Bypass */ +#define RCC_BDCR_RTCSEL_SHIFT (8) /* Bits 9:8: RTC clock source selection */ +#define RCC_BDCR_RTCSEL_MASK (3 << RCC_BDCR_RTCSEL_SHIFT) +# define RCC_BDCR_RTCSEL_NOCLK (0 << RCC_BDCR_RTCSEL_SHIFT) /* 00: No clock */ +# define RCC_BDCR_RTCSEL_LSE (1 << RCC_BDCR_RTCSEL_SHIFT) /* 01: LSE oscillator clock used as RTC clock */ +# define RCC_BDCR_RTCSEL_LSI (2 << RCC_BDCR_RTCSEL_SHIFT) /* 10: LSI oscillator clock used as RTC clock */ +# define RCC_BDCR_RTCSEL_HSE (3 << RCC_BDCR_RTCSEL_SHIFT) /* 11: HSE oscillator clock divided by 128 used as RTC clock */ +#define RCC_BDCR_RTCEN (1 << 15) /* Bit 15: RTC clock enable */ +#define RCC_BDCR_BDRST (1 << 16) /* Bit 16: Backup domain software reset */ + +/* Control/status register */ + +#define RCC_CSR_LSION (1 << 0) /* Bit 0: Internal Low Speed oscillator enable */ +#define RCC_CSR_LSIRDY (1 << 1) /* Bit 1: Internal Low Speed oscillator Ready */ +#define RCC_CSR_V18PWRRSTF (1 << 23) /* Bit 23: Reset flag of the 1.8V domain */ +#define RCC_CSR_RMVF (1 << 24) /* Bit 24: Remove reset flag */ +#define RCC_CSR_OBLRSTF (1 << 25) /* Bit 24: Option byte loader reset flag */ +#define RCC_CSR_PINRSTF (1 << 26) /* Bit 26: PIN reset flag */ +#define RCC_CSR_PORRSTF (1 << 27) /* Bit 27: POR/PDR reset flag */ +#define RCC_CSR_SFTRSTF (1 << 28) /* Bit 28: Software Reset flag */ +#define RCC_CSR_IWDGRSTF (1 << 29) /* Bit 29: Independent Watchdog reset flag */ +#define RCC_CSR_WWDGRSTF (1 << 30) /* Bit 30: Window watchdog reset flag */ +#define RCC_CSR_LPWRRSTF (1 << 31) /* Bit 31: Low-Power reset flag */ + +/* AHB peripheral reset register */ + +#define RCC_AHBRSTR_IOPARST (1 << 17) /* Bit 17: I/O port A reset */ +#define RCC_AHBRSTR_IOPBRST (1 << 18) /* Bit 18: I/O port B reset */ +#define RCC_AHBRSTR_IOPCRST (1 << 19) /* Bit 19: I/O port C reset */ +#define RCC_AHBRSTR_IOPDRST (1 << 20) /* Bit 20: I/O port D reset */ +#define RCC_AHBRSTR_IOPERST (1 << 21) /* Bit 21: I/O port E reset */ +#define RCC_AHBRSTR_IOPFRST (1 << 22) /* Bit 22: I/O port F reset */ +#define RCC_AHBRSTR_TSCRST (1 << 24) /* Bit 24: Touch sensing reset */ + +/* Clock configuration register 2 */ + +#define RCC_CFGR2_PREDIV1_SHIFT (0) +#define RCC_CFGR2_PREDIV1_MASK (0x0f << RCC_CFGR2_PREDIV1_SHIFT) +# define RCC_CFGR2_PREDIV1d1 (0 << RCC_CFGR2_PREDIV1_SHIFT) +# define RCC_CFGR2_PREDIV1d2 (1 << RCC_CFGR2_PREDIV1_SHIFT) +# define RCC_CFGR2_PREDIV1d3 (2 << RCC_CFGR2_PREDIV1_SHIFT) +# define RCC_CFGR2_PREDIV1d4 (3 << RCC_CFGR2_PREDIV1_SHIFT) +# define RCC_CFGR2_PREDIV1d5 (4 << RCC_CFGR2_PREDIV1_SHIFT) +# define RCC_CFGR2_PREDIV1d6 (5 << RCC_CFGR2_PREDIV1_SHIFT) +# define RCC_CFGR2_PREDIV1d7 (6 << RCC_CFGR2_PREDIV1_SHIFT) +# define RCC_CFGR2_PREDIV1d8 (7 << RCC_CFGR2_PREDIV1_SHIFT) +# define RCC_CFGR2_PREDIV1d9 (8 << RCC_CFGR2_PREDIV1_SHIFT) +# define RCC_CFGR2_PREDIV1d10 (9 << RCC_CFGR2_PREDIV1_SHIFT) +# define RCC_CFGR2_PREDIV1d11 (10 << RCC_CFGR2_PREDIV1_SHIFT) +# define RCC_CFGR2_PREDIV1d12 (11 << RCC_CFGR2_PREDIV1_SHIFT) +# define RCC_CFGR2_PREDIV1d13 (12 << RCC_CFGR2_PREDIV1_SHIFT) +# define RCC_CFGR2_PREDIV1d14 (13 << RCC_CFGR2_PREDIV1_SHIFT) +# define RCC_CFGR2_PREDIV1d15 (14 << RCC_CFGR2_PREDIV1_SHIFT) +# define RCC_CFGR2_PREDIV1d16 (15 << RCC_CFGR2_PREDIV1_SHIFT) + +#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_RCC_H */ diff --git a/arch/arm/src/stm32f0/chip/stm32f0_rtcc.h b/arch/arm/src/stm32f0/chip/stm32f0_rtcc.h new file mode 100644 index 0000000000..e887e88baf --- /dev/null +++ b/arch/arm/src/stm32f0/chip/stm32f0_rtcc.h @@ -0,0 +1,329 @@ +/************************************************************************************ + * arch/arm/src/stm32f0/chip/stm32f0_rtcc.h.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_RTCC_H +#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_RTCC_H + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Register Offsets *****************************************************************/ + +#define STM32F0_RTC_TR_OFFSET 0x0000 /* RTC time register */ +#define STM32F0_RTC_DR_OFFSET 0x0004 /* RTC date register */ +#define STM32F0_RTC_CR_OFFSET 0x0008 /* RTC control register */ +#define STM32F0_RTC_ISR_OFFSET 0x000c /* RTC initialization and status register */ +#define STM32F0_RTC_PRER_OFFSET 0x0010 /* RTC prescaler register */ +#define STM32F0_RTC_WUTR_OFFSET 0x0014 /* RTC wakeup timer register */ +#define STM32F0_RTC_ALRMAR_OFFSET 0x001c /* RTC alarm A register */ +#define STM32F0_RTC_WPR_OFFSET 0x0024 /* RTC write protection register */ +#define STM32F0_RTC_SSR_OFFSET 0x0028 /* RTC sub second register */ +#define STM32F0_RTC_SHIFTR_OFFSET 0x002c /* RTC shift control register */ +#define STM32F0_RTC_TSTR_OFFSET 0x0030 /* RTC time stamp time register */ +#define STM32F0_RTC_TSDR_OFFSET 0x0034 /* RTC time stamp date register */ +#define STM32F0_RTC_TSSSR_OFFSET 0x0038 /* RTC timestamp sub second register */ +#define STM32F0_RTC_CALR_OFFSET 0x003c /* RTC calibration register */ +#define STM32F0_RTC_TAFCR_OFFSET 0x0040 /* RTC tamper and alternate function configuration register */ +#define STM32F0_RTC_ALRMASSR_OFFSET 0x0044 /* RTC alarm A sub second register */ + +#define STM32F0_RTC_BKR_OFFSET(n) (0x0050+((n)<<2)) +#define STM32F0_RTC_BK0R_OFFSET 0x0050 /* RTC backup register 0 */ +#define STM32F0_RTC_BK1R_OFFSET 0x0054 /* RTC backup register 1 */ +#define STM32F0_RTC_BK2R_OFFSET 0x0058 /* RTC backup register 2 */ +#define STM32F0_RTC_BK3R_OFFSET 0x005c /* RTC backup register 3 */ +#define STM32F0_RTC_BK4R_OFFSET 0x0060 /* RTC backup register 4 */ + +/* Register Addresses ***************************************************************/ + +#define STM32F0_RTC_TR (STM32F0_RTC_BASE+STM32F0_RTC_TR_OFFSET) +#define STM32F0_RTC_DR (STM32F0_RTC_BASE+STM32F0_RTC_DR_OFFSET) +#define STM32F0_RTC_CR (STM32F0_RTC_BASE+STM32F0_RTC_CR_OFFSET) +#define STM32F0_RTC_ISR (STM32F0_RTC_BASE+STM32F0_RTC_ISR_OFFSET) +#define STM32F0_RTC_PRER (STM32F0_RTC_BASE+STM32F0_RTC_PRER_OFFSET) +#define STM32F0_RTC_WUTR (STM32F0_RTC_BASE+STM32F0_RTC_WUTR_OFFSET) +#define STM32F0_RTC_ALRMAR (STM32F0_RTC_BASE+STM32F0_RTC_ALRMAR_OFFSET) +#define STM32F0_RTC_WPR (STM32F0_RTC_BASE+STM32F0_RTC_WPR_OFFSET) +#define STM32F0_RTC_SSR (STM32F0_RTC_BASE+STM32F0_RTC_SSR_OFFSET) +#define STM32F0_RTC_SHIFTR (STM32F0_RTC_BASE+STM32F0_RTC_SHIFTR_OFFSET) +#define STM32F0_RTC_TSTR (STM32F0_RTC_BASE+STM32F0_RTC_TSTR_OFFSET) +#define STM32F0_RTC_TSDR (STM32F0_RTC_BASE+STM32F0_RTC_TSDR_OFFSET) +#define STM32F0_RTC_TSSSR (STM32F0_RTC_BASE+STM32F0_RTC_TSSSR_OFFSET) +#define STM32F0_RTC_CALR (STM32F0_RTC_BASE+STM32F0_RTC_CALR_OFFSET) +#define STM32F0_RTC_TAFCR (STM32F0_RTC_BASE+STM32F0_RTC_TAFCR_OFFSET) +#define STM32F0_RTC_ALRMASSR (STM32F0_RTC_BASE+STM32F0_RTC_ALRMASSR_OFFSET) + +#define STM32F0_RTC_BKR(n) (STM32F0_RTC_BASE+STM32F0_RTC_BKR_OFFSET(n)) +#define STM32F0_RTC_BK0R (STM32F0_RTC_BASE+STM32F0_RTC_BK0R_OFFSET) +#define STM32F0_RTC_BK1R (STM32F0_RTC_BASE+STM32F0_RTC_BK1R_OFFSET) +#define STM32F0_RTC_BK2R (STM32F0_RTC_BASE+STM32F0_RTC_BK2R_OFFSET) +#define STM32F0_RTC_BK3R (STM32F0_RTC_BASE+STM32F0_RTC_BK3R_OFFSET) +#define STM32F0_RTC_BK4R (STM32F0_RTC_BASE+STM32F0_RTC_BK4R_OFFSET) + +#ifdef CONFIG_STM32F0_STM32F30XX +# define STM32F0_RTC_BKCOUNT 16 +#elif defined(CONFIG_STM32F0_STM32L15XX) +# define STM32F0_RTC_BKCOUNT 32 +#else +# define STM32F0_RTC_BKCOUNT 20 +#endif + +/* Register Bitfield Definitions ****************************************************/ + +/* RTC time register */ + +#define RTC_TR_SU_SHIFT (0) /* Bits 0-3: Second units in BCD format */ +#define RTC_TR_SU_MASK (15 << RTC_TR_SU_SHIFT) +#define RTC_TR_ST_SHIFT (4) /* Bits 4-6: Second tens in BCD format */ +#define RTC_TR_ST_MASK (7 << RTC_TR_ST_SHIFT) +#define RTC_TR_MNU_SHIFT (8) /* Bit 8-11: Minute units in BCD format */ +#define RTC_TR_MNU_MASK (15 << RTC_TR_MNU_SHIFT) +#define RTC_TR_MNT_SHIFT (12) /* Bits 12-14: Minute tens in BCD format */ +#define RTC_TR_MNT_MASK (7 << RTC_TR_MNT_SHIFT) +#define RTC_TR_HU_SHIFT (16) /* Bit 16-19: Hour units in BCD format */ +#define RTC_TR_HU_MASK (15 << RTC_TR_HU_SHIFT) +#define RTC_TR_HT_SHIFT (20) /* Bits 20-21: Hour tens in BCD format */ +#define RTC_TR_HT_MASK (3 << RTC_TR_HT_SHIFT) +#define RTC_TR_PM (1 << 22) /* Bit 22: AM/PM notation */ +#define RTC_TR_RESERVED_BITS (0xff808080) + +/* RTC date register */ + +#define RTC_DR_DU_SHIFT (0) /* Bits 0-3: Date units in BCD format */ +#define RTC_DR_DU_MASK (15 << RTC_DR_DU_SHIFT) +#define RTC_DR_DT_SHIFT (4) /* Bits 4-5: Date tens in BCD format */ +#define RTC_DR_DT_MASK (3 << RTC_DR_DT_SHIFT) +#define RTC_DR_MU_SHIFT (8) /* Bits 8-11: Month units in BCD format */ +#define RTC_DR_MU_MASK (15 << RTC_DR_MU_SHIFT) +#define RTC_DR_MT (1 << 12) /* Bit 12: Month tens in BCD format */ +#define RTC_DR_WDU_SHIFT (13) /* Bits 13-15: Week day units */ +#define RTC_DR_WDU_MASK (7 << RTC_DR_WDU_SHIFT) +# define RTC_DR_WDU_MONDAY (1 << RTC_DR_WDU_SHIFT) +# define RTC_DR_WDU_TUESDAY (2 << RTC_DR_WDU_SHIFT) +# define RTC_DR_WDU_WEDNESDAY (3 << RTC_DR_WDU_SHIFT) +# define RTC_DR_WDU_THURSDAY (4 << RTC_DR_WDU_SHIFT) +# define RTC_DR_WDU_FRIDAY (5 << RTC_DR_WDU_SHIFT) +# define RTC_DR_WDU_SATURDAY (6 << RTC_DR_WDU_SHIFT) +# define RTC_DR_WDU_SUNDAY (7 << RTC_DR_WDU_SHIFT) +#define RTC_DR_YU_SHIFT (16) /* Bits 16-19: Year units in BCD format */ +#define RTC_DR_YU_MASK (15 << RTC_DR_YU_SHIFT) +#define RTC_DR_YT_SHIFT (20) /* Bits 20-23: Year tens in BCD format */ +#define RTC_DR_YT_MASK (15 << RTC_DR_YT_SHIFT) +#define RTC_DR_RESERVED_BITS (0xff0000c0) + +/* RTC control register */ + +#define RTC_CR_WUCKSEL_SHIFT (0) /* Bits 0-2: Wakeup clock selection */ +#define RTC_CR_WUCKSEL_MASK (7 << RTC_CR_WUCKSEL_SHIFT) +# define RTC_CR_WUCKSEL_RTCDIV16 (0 << RTC_CR_WUCKSEL_SHIFT) /* 000: RTC/16 clock is selected */ +# define RTC_CR_WUCKSEL_RTCDIV8 (1 << RTC_CR_WUCKSEL_SHIFT) /* 001: RTC/8 clock is selected */ +# define RTC_CR_WUCKSEL_RTCDIV4 (2 << RTC_CR_WUCKSEL_SHIFT) /* 010: RTC/4 clock is selected */ +# define RTC_CR_WUCKSEL_RTCDIV2 (3 << RTC_CR_WUCKSEL_SHIFT) /* 011: RTC/2 clock is selected */ +# define RTC_CR_WUCKSEL_CKSPRE (4 << RTC_CR_WUCKSEL_SHIFT) /* 10x: ck_spre clock is selected */ +# define RTC_CR_WUCKSEL_CKSPREADD (6 << RTC_CR_WUCKSEL_SHIFT) /* 11x: ck_spr clock and 216 added WUT counter */ +#define RTC_CR_TSEDGE (1 << 3) /* Bit 3: Timestamp event active edge */ +#define RTC_CR_REFCKON (1 << 4) /* Bit 4: Reference clock detection enable (50 or 60 Hz) */ +#define RTC_CR_BYPSHAD (1 << 5) /* Bit 5: Bypass the shadow registers */ +#define RTC_CR_FMT (1 << 6) /* Bit 6: Hour format */ +#define RTC_CR_ALRAE (1 << 8) /* Bit 8: Alarm A enable */ +#define RTC_CR_WUTE (1 << 10) /* Bit 10: Wakeup timer enable */ +#define RTC_CR_TSE (1 << 11) /* Bit 11: Time stamp enable */ +#define RTC_CR_ALRAIE (1 << 12) /* Bit 12: Alarm A interrupt enable */ +#define RTC_CR_WUTIE (1 << 14) /* Bit 14: Wakeup timer interrupt enable */ +#define RTC_CR_TSIE (1 << 15) /* Bit 15: Timestamp interrupt enable */ +#define RTC_CR_ADD1H (1 << 16) /* Bit 16: Add 1 hour (summer time change) */ +#define RTC_CR_SUB1H (1 << 17) /* Bit 17: Subtract 1 hour (winter time change) */ +#define RTC_CR_BKP (1 << 18) /* Bit 18: Backup */ +#define RTC_CR_COSEL (1 << 19) /* Bit 19 : Calibration output selection */ +#define RTC_CR_POL (1 << 20) /* Bit 20: Output polarity */ +#define RTC_CR_OSEL_SHIFT (21) /* Bits 21-22: Output selection */ +#define RTC_CR_OSEL_MASK (3 << RTC_CR_OSEL_SHIFT) +# define RTC_CR_OSEL_DISABLED (0 << RTC_CR_OSEL_SHIFT) /* 00: Output disabled */ +# define RTC_CR_OSEL_ALRMA (1 << RTC_CR_OSEL_SHIFT) /* 01: Alarm A output enabled */ +# define RTC_CR_OSEL_ALRMB (2 << RTC_CR_OSEL_SHIFT) /* 10: Alarm B output enabled */ +# define RTC_CR_OSEL_WUT (3 << RTC_CR_OSEL_SHIFT) /* 11: Wakeup output enabled */ +#define RTC_CR_COE (1 << 23) /* Bit 23: Calibration output enable */ + +/* RTC initialization and status register */ + +#define RTC_ISR_ALRAWF (1 << 0) /* Bit 0: Alarm A write flag */ +#define RTC_ISR_WUTWF (1 << 2) /* Bit 2: Wakeup timer write flag */ +#define RTC_ISR_SHPF (1 << 3) /* Bit 3: Shift operation pending */ +#define RTC_ISR_INITS (1 << 4) /* Bit 4: Initialization status flag */ +#define RTC_ISR_RSF (1 << 5) /* Bit 5: Registers synchronization flag */ +#define RTC_ISR_INITF (1 << 6) /* Bit 6: Initialization flag */ +#define RTC_ISR_INIT (1 << 7) /* Bit 7: Initialization mode */ +#define RTC_ISR_ALRAF (1 << 8) /* Bit 8: Alarm A flag */ +#define RTC_ISR_WUTF (1 << 10) /* Bit 10: Wakeup timer flag */ +#define RTC_ISR_TSF (1 << 11) /* Bit 11: Timestamp flag */ +#define RTC_ISR_TSOVF (1 << 12) /* Bit 12: Timestamp overflow flag */ +#define RTC_ISR_TAMP1F (1 << 13) /* Bit 13: Tamper detection flag */ +#define RTC_ISR_TAMP2F (1 << 14) /* Bit 14: TAMPER2 detection flag */ +#define RTC_ISR_TAMP3F (1 << 15) /* Bit 15: TAMPER3 detection flag */ +#define RTC_ISR_RECALPF (1 << 16) /* Bit 16: Recalibration pending Flag */ +#define RTC_ISR_ALLFLAGS (0x00017fff) + +/* RTC prescaler register */ + +#define RTC_PRER_PREDIV_S_SHIFT (0) /* Bits 0-14: Synchronous prescaler factor */ +#define RTC_PRER_PREDIV_S_MASK (0x7fff << RTC_PRER_PREDIV_S_SHIFT) +#define RTC_PRER_PREDIV_A_SHIFT (16) /* Bits 16-22: Asynchronous prescaler factor */ +#define RTC_PRER_PREDIV_A_MASK (0x7f << RTC_PRER_PREDIV_A_SHIFT) + +/* RTC wakeup timer register */ + +#define RTC_WUTR_MASK (0xffff) /* Bits 15:0 Wakeup auto-reload value bits */ + +/* RTC alarm A register */ + +#define RTC_ALRMR_SU_SHIFT (0) /* Bits 0-3: Second units in BCD format. */ +#define RTC_ALRMR_SU_MASK (15 << RTC_ALRMR_SU_SHIFT) +#define RTC_ALRMR_ST_SHIFT (4) /* Bits 4-6: Second tens in BCD format. */ +#define RTC_ALRMR_ST_MASK (7 << RTC_ALRMR_ST_SHIFT) +#define RTC_ALRMR_MSK1 (1 << 7) /* Bit 7 : Alarm A seconds mask */ +#define RTC_ALRMR_MNU_SHIFT (8) /* Bits 8-11: Minute units in BCD format. */ +#define RTC_ALRMR_MNU_MASK (15 << RTC_ALRMR_MNU_SHIFT) +#define RTC_ALRMR_MNT_SHIFT (12) /* Bits 12-14: Minute tens in BCD format. */ +#define RTC_ALRMR_MNT_MASK (7 << RTC_ALRMR_MNT_SHIFT) +#define RTC_ALRMR_MSK2 (1 << 15) /* Bit 15 : Alarm A minutes mask */ +#define RTC_ALRMR_HU_SHIFT (16) /* Bits 16-19: Hour units in BCD format. */ +#define RTC_ALRMR_HU_MASK (15 << RTC_ALRMR_HU_SHIFT) +#define RTC_ALRMR_HT_SHIFT (20) /* Bits 20-21: Hour tens in BCD format. */ +#define RTC_ALRMR_HT_MASK (3 << RTC_ALRMR_HT_SHIFT) +#define RTC_ALRMR_PM (1 << 22) /* Bit 22 : AM/PM notation */ +#define RTC_ALRMR_MSK3 (1 << 23) /* Bit 23 : Alarm A hours mask */ +#define RTC_ALRMR_DU_SHIFT (24) /* Bits 24-27: Date units or day in BCD format. */ +#define RTC_ALRMR_DU_MASK (15 << RTC_ALRMR_DU_SHIFT) +#define RTC_ALRMR_DT_SHIFT (28) /* Bits 28-29: Date tens in BCD format. */ +#define RTC_ALRMR_DT_MASK (3 << RTC_ALRMR_DT_SHIFT) +#define RTC_ALRMR_WDSEL (1 << 30) /* Bit 30: Week day selection */ +#define RTC_ALRMR_MSK4 (1 << 31) /* Bit 31: Alarm A date mask */ + +/* RTC write protection register */ + +#define RTC_WPR_MASK (0xff) /* Bits 0-7: Write protection key */ + +/* RTC sub second register */ + +#define RTC_SSR_MASK (0xffff) /* Bits 0-15: Sub second value */ + +/* RTC shift control register */ + +#define RTC_SHIFTR_SUBFS_SHIFT (0) /* Bits 0-14: Subtract a fraction of a second */ +#define RTC_SHIFTR_SUBFS_MASK (0x7fff << RTC_SHIFTR_SUBFS_SHIFT) +#define RTC_SHIFTR_ADD1S (1 << 31) /* Bit 31: Add one second */ + +/* RTC time stamp time register */ + +#define RTC_TSTR_SU_SHIFT (0) /* Bits 0-3: Second units in BCD format. */ +#define RTC_TSTR_SU_MASK (15 << RTC_TSTR_SU_SHIFT) +#define RTC_TSTR_ST_SHIFT (4) /* Bits 4-6: Second tens in BCD format. */ +#define RTC_TSTR_ST_MASK (7 << RTC_TSTR_ST_SHIFT) +#define RTC_TSTR_MNU_SHIFT (8) /* Bits 8-11: Minute units in BCD format. */ +#define RTC_TSTR_MNU_MASK (15 << RTC_TSTR_MNU_SHIFT) +#define RTC_TSTR_MNT_SHIFT (12) /* Bits 12-14: Minute tens in BCD format. */ +#define RTC_TSTR_MNT_MASK (7 << RTC_TSTR_MNT_SHIFT) +#define RTC_TSTR_HU_SHIFT (16) /* Bits 16-19: Hour units in BCD format. */ +#define RTC_TSTR_HU_MASK (15 << RTC_TSTR_HU_SHIFT) +#define RTC_TSTR_HT_SHIFT (20) /* Bits 20-21: Hour tens in BCD format. */ +#define RTC_TSTR_HT_MASK (3 << RTC_TSTR_HT_SHIFT) +#define RTC_TSTR_PM (1 << 22) /* Bit 22: AM/PM notation */ + +/* RTC time stamp date register */ + +#define RTC_TSDR_DU_SHIFT (0) /* Bit 0-3: Date units in BCD format */ +#define RTC_TSDR_DU_MASK (15 << RTC_TSDR_DU_SHIFT) /* */ +#define RTC_TSDR_DT_SHIFT (4) /* Bits 4-5: Date tens in BCD format */ +#define RTC_TSDR_DT_MASK (3 << RTC_TSDR_DT_SHIFT) +#define RTC_TSDR_MU_SHIFT (8) /* Bits 8-11: Month units in BCD format */ +#define RTC_TSDR_MU_MASK (xx << RTC_TSDR_MU_SHIFT) +#define RTC_TSDR_MT (1 << 12) /* Bit 12: Month tens in BCD format */ +#define RTC_TSDR_WDU_SHIFT (13) /* Bits 13-15: Week day units */ +#define RTC_TSDR_WDU_MASK (7 << RTC_TSDR_WDU_SHIFT) + +/* RTC timestamp sub second register */ + +#define RTC_TSSSR_MASK (0xffff) /* Bits 0-15: Sub second value */ + +/* RTC calibration register */ + +#define RTC_CALR_CALM_SHIFT (0) /* Bits 0-8: Calibration minus */ +#define RTC_CALR_CALM_MASK (0x1ff << RTC_CALR_CALM_SHIFT) +#define RTC_CALR_CALW16 (1 << 13) /* Bit 13: Use a 16-second calibration cycle period */ +#define RTC_CALR_CALW8 (1 << 14) /* Bit 14: Use an 8-second calibration cycle period */ +#define RTC_CALR_CALP (1 << 15) /* Bit 15: Increase frequency of RTC by 488.5 ppm */ + +/* RTC tamper and alternate function configuration register */ + +#define RTC_TAFCR_TAMP1E (1 << 0) /* Bit 0: RTC_TAMP1 input detection enable */ +#define RTC_TAFCR_TAMP1TRG (1 << 1) /* Bit 1: Active level for RTC_TAMP1 input */ +#define RTC_TAFCR_TAMPIE (1 << 2) /* Bit 2: Tamper interrupt enable */ +#define RTC_TAFCR_TAMP3E (1 << 5) /* Bit 5: RTC_TAMP3 detection enable */ +#define RTC_TAFCR_TAMP3TRG (1 << 6) /* Bit 6: Active level for RTC_TAMP3 input */ +#define RTC_TAFCR_TAMPTS (1 << 7) /* Bit 7: Activate timestamp on tamper detection event */ +#define RTC_TAFCR_TAMPFREQ_SHIFT (8) /* Bits 8-10: Tamper sampling frequency */ +#define RTC_TAFCR_TAMPFREQ_MASK (7 << RTC_TAFCR_TAMPFREQ_SHIFT) +# define RTC_TAFCR_TAMPFREQ_DIV32768 (0 << RTC_TAFCR_TAMPFREQ_SHIFT) /* RTCCLK / 32768 (1 Hz) */ +# define RTC_TAFCR_TAMPFREQ_DIV16384 (1 << RTC_TAFCR_TAMPFREQ_SHIFT) /* RTCCLK / 16384 (2 Hz) */ +# define RTC_TAFCR_TAMPFREQ_DIV8192 (2 << RTC_TAFCR_TAMPFREQ_SHIFT) /* RTCCLK / 8192 (4 Hz) */ +# define RTC_TAFCR_TAMPFREQ_DIV4096 (3 << RTC_TAFCR_TAMPFREQ_SHIFT) /* RTCCLK / 4096 (8 Hz) */ +# define RTC_TAFCR_TAMPFREQ_DIV2048 (4 << RTC_TAFCR_TAMPFREQ_SHIFT) /* RTCCLK / 2048 (16 Hz) */ +# define RTC_TAFCR_TAMPFREQ_DIV1024 (5 << RTC_TAFCR_TAMPFREQ_SHIFT) /* RTCCLK / 1024 (32 Hz) */ +# define RTC_TAFCR_TAMPFREQ_DIV512 (6 << RTC_TAFCR_TAMPFREQ_SHIFT) /* RTCCLK / 512 (64 Hz) */ +# define RTC_TAFCR_TAMPFREQ_DIV256 (7 << RTC_TAFCR_TAMPFREQ_SHIFT) /* RTCCLK / 256 (128 Hz) */ +#define RTC_TAFCR_TAMPFLT_SHIFT (11) /* Bits 11-12: RTC_TAMPx filter count */ +#define RTC_TAFCR_TAMPFLT_MASK (3 << RTC_TAFCR_TAMPFLT_SHIFT) +#define RTC_TAFCR_TAMPPRCH_SHIFT (13) /* Bits 13-14: RTC_TAMPx precharge duration */ +#define RTC_TAFCR_TAMPPRCH_MASK (3 << RTC_TAFCR_TAMPPRCH_SHIFT) +# define RTC_TAFCR_TAMPPRCH_1CYCLE (0 << RTC_TAFCR_TAMPPRCH_SHIFT) /* 1 RTCCLK cycle */ +# define RTC_TAFCR_TAMPPRCH_2CYCLES (1 << RTC_TAFCR_TAMPPRCH_SHIFT) /* 2 RTCCLK cycles */ +# define RTC_TAFCR_TAMPPRCH_4CYCLES (2 << RTC_TAFCR_TAMPPRCH_SHIFT) /* 4 RTCCLK cycles */ +# define RTC_TAFCR_TAMPPRCH_5CYCLES (3 << RTC_TAFCR_TAMPPRCH_SHIFT) /* 8 RTCCLK cycles */ +#define RTC_TAFCR_TAMPPUDIS (1 << 15) /* Bit 15: RTC_TAMPx pull-up disable */ +#define RTC_TAFCR_PC13VALUE (1 << 18) /* Bit 18: RTC_ALARM output type/PC13 value */ +#define RTC_TAFCR_PC13MODE (1 << 19) /* Bit 19: PC13 mode */ +#define RTC_TAFCR_PC14VALUE (1 << 20) /* Bit 20: PC14 value */ +#define RTC_TAFCR_PC14MODE (1 << 21) /* Bit 21: PC14 mode */ +#define RTC_TAFCR_PC15VALUE (1 << 22) /* Bit 22: PC15 value */ +#define RTC_TAFCR_PC15MODE (1 << 23) /* Bit 23: PC15 mode */ + +/* RTC alarm A sub second register */ + +#define RTC_ALRMSSR_SS_SHIFT (0) /* Bits 0-14: Sub second value */ +#define RTC_ALRMSSR_SS_MASK (0x7fff << RTC_ALRMSSR_SS_SHIFT) +#define RTC_ALRMSSR_MASKSS_SHIFT (24) /* Bits 24-27: Mask the most-significant bits starting at this bit */ +#define RTC_ALRMSSR_MASKSS_MASK (0xf << RTC_ALRMSSR_MASKSS_SHIFT) + +#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_RTCC_H */ diff --git a/arch/arm/src/stm32f0/chip/stm32f0_spi.h b/arch/arm/src/stm32f0/chip/stm32f0_spi.h new file mode 100644 index 0000000000..87ab0ed258 --- /dev/null +++ b/arch/arm/src/stm32f0/chip/stm32f0_spi.h @@ -0,0 +1,252 @@ +/************************************************************************************ + * arch/arm/src/stm32f0/chip/stm32f0_spi.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Authors: 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_SPI_H +#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_SPI_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include "chip.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Maximum allowed speed as per data sheet for all SPIs (both pclk1 and pclk2)*/ + +#define STM32F0_SPI_CLK_MAX 50000000UL + +/* Register Offsets *****************************************************************/ + +#define STM32F0_SPI_CR1_OFFSET 0x0000 /* SPI Control Register 1 (16-bit) */ +#define STM32F0_SPI_CR2_OFFSET 0x0004 /* SPI control register 2 (16-bit) */ +#define STM32F0_SPI_SR_OFFSET 0x0008 /* SPI status register (16-bit) */ +#define STM32F0_SPI_DR_OFFSET 0x000c /* SPI data register (16-bit) */ +#define STM32F0_SPI_CRCPR_OFFSET 0x0010 /* SPI CRC polynomial register (16-bit) */ +#define STM32F0_SPI_RXCRCR_OFFSET 0x0014 /* SPI Rx CRC register (16-bit) */ +#define STM32F0_SPI_TXCRCR_OFFSET 0x0018 /* SPI Tx CRC register (16-bit) */ +#define STM32F0_SPI_I2SCFGR_OFFSET 0x001c /* I2S configuration register */ +#define STM32F0_SPI_I2SPR_OFFSET 0x0020 /* I2S prescaler register */ + +/* Register Addresses ***************************************************************/ + +#if STM32F0_NSPI > 0 +# define STM32F0_SPI1_CR1 (STM32F0_SPI1_BASE+STM32F0_SPI_CR1_OFFSET) +# define STM32F0_SPI1_CR2 (STM32F0_SPI1_BASE+STM32F0_SPI_CR2_OFFSET) +# define STM32F0_SPI1_SR (STM32F0_SPI1_BASE+STM32F0_SPI_SR_OFFSET) +# define STM32F0_SPI1_DR (STM32F0_SPI1_BASE+STM32F0_SPI_DR_OFFSET) +# define STM32F0_SPI1_CRCPR (STM32F0_SPI1_BASE+STM32F0_SPI_CRCPR_OFFSET) +# define STM32F0_SPI1_RXCRCR (STM32F0_SPI1_BASE+STM32F0_SPI_RXCRCR_OFFSET) +# define STM32F0_SPI1_TXCRCR (STM32F0_SPI1_BASE+STM32F0_SPI_TXCRCR_OFFSET) +#endif + +#if STM32F0_NSPI > 1 +# define STM32F0_SPI2_CR1 (STM32F0_SPI2_BASE+STM32F0_SPI_CR1_OFFSET) +# define STM32F0_SPI2_CR2 (STM32F0_SPI2_BASE+STM32F0_SPI_CR2_OFFSET) +# define STM32F0_SPI2_SR (STM32F0_SPI2_BASE+STM32F0_SPI_SR_OFFSET) +# define STM32F0_SPI2_DR (STM32F0_SPI2_BASE+STM32F0_SPI_DR_OFFSET) +# define STM32F0_SPI2_CRCPR (STM32F0_SPI2_BASE+STM32F0_SPI_CRCPR_OFFSET) +# define STM32F0_SPI2_RXCRCR (STM32F0_SPI2_BASE+STM32F0_SPI_RXCRCR_OFFSET) +# define STM32F0_SPI2_TXCRCR (STM32F0_SPI2_BASE+STM32F0_SPI_TXCRCR_OFFSET) +# define STM32F0_SPI2_I2SCFGR (STM32F0_SPI2_BASE+STM32F0_SPI_I2SCFGR_OFFSET) +# define STM32F0_SPI2_I2SPR (STM32F0_SPI2_BASE+STM32F0_SPI_I2SPR_OFFSET) +#endif + +#if STM32F0_NSPI > 2 +# define STM32F0_SPI3_CR1 (STM32F0_SPI3_BASE+STM32F0_SPI_CR1_OFFSET) +# define STM32F0_SPI3_CR2 (STM32F0_SPI3_BASE+STM32F0_SPI_CR2_OFFSET) +# define STM32F0_SPI3_SR (STM32F0_SPI3_BASE+STM32F0_SPI_SR_OFFSET) +# define STM32F0_SPI3_DR (STM32F0_SPI3_BASE+STM32F0_SPI_DR_OFFSET) +# define STM32F0_SPI3_CRCPR (STM32F0_SPI3_BASE+STM32F0_SPI_CRCPR_OFFSET) +# define STM32F0_SPI3_RXCRCR (STM32F0_SPI3_BASE+STM32F0_SPI_RXCRCR_OFFSET) +# define STM32F0_SPI3_TXCRCR (STM32F0_SPI3_BASE+STM32F0_SPI_TXCRCR_OFFSET) +# define STM32F0_SPI3_I2SCFGR (STM32F0_SPI3_BASE+STM32F0_SPI_I2SCFGR_OFFSET) +# define STM32F0_SPI3_I2SPR (STM32F0_SPI3_BASE+STM32F0_SPI_I2SPR_OFFSET) +#endif + +#if STM32F0_NSPI > 3 +# define STM32F0_SPI4_CR1 (STM32F0_SPI4_BASE+STM32F0_SPI_CR1_OFFSET) +# define STM32F0_SPI4_CR2 (STM32F0_SPI4_BASE+STM32F0_SPI_CR2_OFFSET) +# define STM32F0_SPI4_SR (STM32F0_SPI4_BASE+STM32F0_SPI_SR_OFFSET) +# define STM32F0_SPI4_DR (STM32F0_SPI4_BASE+STM32F0_SPI_DR_OFFSET) +# define STM32F0_SPI4_CRCPR (STM32F0_SPI4_BASE+STM32F0_SPI_CRCPR_OFFSET) +# define STM32F0_SPI4_RXCRCR (STM32F0_SPI4_BASE+STM32F0_SPI_RXCRCR_OFFSET) +# define STM32F0_SPI4_TXCRCR (STM32F0_SPI4_BASE+STM32F0_SPI_TXCRCR_OFFSET) +# define STM32F0_SPI4_I2SCFGR (STM32F0_SPI4_BASE+STM32F0_SPI_I2SCFGR_OFFSET) +# define STM32F0_SPI4_I2SPR (STM32F0_SPI4_BASE+STM32F0_SPI_I2SPR_OFFSET) +#endif + +#if STM32F0_NSPI > 4 +# define STM32F0_SPI5_CR1 (STM32F0_SPI5_BASE+STM32F0_SPI_CR1_OFFSET) +# define STM32F0_SPI5_CR2 (STM32F0_SPI5_BASE+STM32F0_SPI_CR2_OFFSET) +# define STM32F0_SPI5_SR (STM32F0_SPI5_BASE+STM32F0_SPI_SR_OFFSET) +# define STM32F0_SPI5_DR (STM32F0_SPI5_BASE+STM32F0_SPI_DR_OFFSET) +# define STM32F0_SPI5_CRCPR (STM32F0_SPI5_BASE+STM32F0_SPI_CRCPR_OFFSET) +# define STM32F0_SPI5_RXCRCR (STM32F0_SPI5_BASE+STM32F0_SPI_RXCRCR_OFFSET) +# define STM32F0_SPI5_TXCRCR (STM32F0_SPI5_BASE+STM32F0_SPI_TXCRCR_OFFSET) +# define STM32F0_SPI5_I2SCFGR (STM32F0_SPI5_BASE+STM32F0_SPI_I2SCFGR_OFFSET) +# define STM32F0_SPI5_I2SPR (STM32F0_SPI5_BASE+STM32F0_SPI_I2SPR_OFFSET) +#endif + +#if STM32F0_NSPI > 5 +# define STM32F0_SPI6_CR1 (STM32F0_SPI6_BASE+STM32F0_SPI_CR1_OFFSET) +# define STM32F0_SPI6_CR2 (STM32F0_SPI6_BASE+STM32F0_SPI_CR2_OFFSET) +# define STM32F0_SPI6_SR (STM32F0_SPI6_BASE+STM32F0_SPI_SR_OFFSET) +# define STM32F0_SPI6_DR (STM32F0_SPI6_BASE+STM32F0_SPI_DR_OFFSET) +# define STM32F0_SPI6_CRCPR (STM32F0_SPI6_BASE+STM32F0_SPI_CRCPR_OFFSET) +# define STM32F0_SPI6_RXCRCR (STM32F0_SPI6_BASE+STM32F0_SPI_RXCRCR_OFFSET) +# define STM32F0_SPI6_TXCRCR (STM32F0_SPI6_BASE+STM32F0_SPI_TXCRCR_OFFSET) +# define STM32F0_SPI6_I2SCFGR (STM32F0_SPI6_BASE+STM32F0_SPI_I2SCFGR_OFFSET) +# define STM32F0_SPI6_I2SPR (STM32F0_SPI6_BASE+STM32F0_SPI_I2SPR_OFFSET) +#endif + +/* Register Bitfield Definitions ****************************************************/ + +/* SPI Control Register 1 */ + +#define SPI_CR1_CPHA (1 << 0) /* Bit 0: Clock Phase */ +#define SPI_CR1_CPOL (1 << 1) /* Bit 1: Clock Polarity */ +#define SPI_CR1_MSTR (1 << 2) /* Bit 2: Master Selection */ +#define SPI_CR1_BR_SHIFT (3) /* Bits 5:3 Baud Rate Control */ +#define SPI_CR1_BR_MASK (7 << SPI_CR1_BR_SHIFT) +# define SPI_CR1_FPCLCKd2 (0 << SPI_CR1_BR_SHIFT) /* 000: fPCLK/2 */ +# define SPI_CR1_FPCLCKd4 (1 << SPI_CR1_BR_SHIFT) /* 001: fPCLK/4 */ +# define SPI_CR1_FPCLCKd8 (2 << SPI_CR1_BR_SHIFT) /* 010: fPCLK/8 */ +# define SPI_CR1_FPCLCKd16 (3 << SPI_CR1_BR_SHIFT) /* 011: fPCLK/16 */ +# define SPI_CR1_FPCLCKd32 (4 << SPI_CR1_BR_SHIFT) /* 100: fPCLK/32 */ +# define SPI_CR1_FPCLCKd64 (5 << SPI_CR1_BR_SHIFT) /* 101: fPCLK/64 */ +# define SPI_CR1_FPCLCKd128 (6 << SPI_CR1_BR_SHIFT) /* 110: fPCLK/128 */ +# define SPI_CR1_FPCLCKd256 (7 << SPI_CR1_BR_SHIFT) /* 111: fPCLK/256 */ +#define SPI_CR1_SPE (1 << 6) /* Bit 6: SPI Enable */ +#define SPI_CR1_LSBFIRST (1 << 7) /* Bit 7: Frame Format */ +#define SPI_CR1_SSI (1 << 8) /* Bit 8: Internal slave select */ +#define SPI_CR1_SSM (1 << 9) /* Bit 9: Software slave management */ +#define SPI_CR1_RXONLY (1 << 10) /* Bit 10: Receive only */ +#define SPI_CR1_CRCL (1 << 11) /* Bit 11: CRC length */ +#define SPI_CR1_CRCNEXT (1 << 12) /* Bit 12: Transmit CRC next */ +#define SPI_CR1_CRCEN (1 << 13) /* Bit 13: Hardware CRC calculation enable */ +#define SPI_CR1_BIDIOE (1 << 14) /* Bit 14: Output enable in bidirectional mode */ +#define SPI_CR1_BIDIMODE (1 << 15) /* Bit 15: Bidirectional data mode enable */ + +/* SPI Control Register 2 */ + +#define SPI_CR2_RXDMAEN (1 << 0) /* Bit 0: Rx Buffer DMA Enable */ +#define SPI_CR2_TXDMAEN (1 << 1) /* Bit 1: Tx Buffer DMA Enable */ +#define SPI_CR2_SSOE (1 << 2) /* Bit 2: SS Output Enable */ +#define SPI_CR2_NSSP (1 << 3) /* Bit 3 NSSP: NSS pulse management */ +#define SPI_CR2_FRF (1 << 4) /* Bit 4: Frame format */ +#define SPI_CR2_ERRIE (1 << 5) /* Bit 5: Error interrupt enable */ +#define SPI_CR2_RXNEIE (1 << 6) /* Bit 6: RX buffer not empty interrupt enable */ +#define SPI_CR2_TXEIE (1 << 7) /* Bit 7: Tx buffer empty interrupt enable */ +#define SPI_CR2_DS_SHIFT (8) /* Bits 8-11: Data size */ +#define SPI_CR2_DS_MASK (0xf << SPI_CR2_DS_SHIFT) +# define SPI_CR2_DS_VAL(bits) (((bits)-1) << SPI_CR2_DS_SHIFT) +# define SPI_CR2_DS_4BIT SPI_CR2_DS_VAL(4) +# define SPI_CR2_DS_5BIT SPI_CR2_DS_VAL(5) +# define SPI_CR2_DS_6BIT SPI_CR2_DS_VAL(6) +# define SPI_CR2_DS_7BIT SPI_CR2_DS_VAL(7) +# define SPI_CR2_DS_8BIT SPI_CR2_DS_VAL(8) +# define SPI_CR2_DS_9BIT SPI_CR2_DS_VAL(9) +# define SPI_CR2_DS_10BIT SPI_CR2_DS_VAL(10) +# define SPI_CR2_DS_11BIT SPI_CR2_DS_VAL(11) +# define SPI_CR2_DS_12BIT SPI_CR2_DS_VAL(12) +# define SPI_CR2_DS_13BIT SPI_CR2_DS_VAL(13) +# define SPI_CR2_DS_14BIT SPI_CR2_DS_VAL(14) +# define SPI_CR2_DS_15BIT SPI_CR2_DS_VAL(15) +# define SPI_CR2_DS_16BIT SPI_CR2_DS_VAL(16) +#define SPI_CR2_FRXTH (1 << 12) /* Bit 12: FIFO reception threshold */ +#define SPI_CR2_LDMARX (1 << 13) /* Bit 13: Last DMA transfer for receptione */ +#define SPI_CR2_LDMATX (1 << 14) /* Bit 14: Last DMA transfer for transmission */ + +/* SPI status register */ + +#define SPI_SR_RXNE (1 << 0) /* Bit 0: Receive buffer not empty */ +#define SPI_SR_TXE (1 << 1) /* Bit 1: Transmit buffer empty */ +#define SPI_SR_CHSIDE (1 << 2) /* Bit 2: Channel side (i2s) */ +#define SPI_SR_UDR (1 << 3) /* Bit 3: Underrun flag (i2s) */ +#define SPI_SR_CRCERR (1 << 4) /* Bit 4: CRC error flag */ +#define SPI_SR_MODF (1 << 5) /* Bit 5: Mode fault */ +#define SPI_SR_OVR (1 << 6) /* Bit 6: Overrun flag */ +#define SPI_SR_BSY (1 << 7) /* Bit 7: Busy flag */ +#define SPI_SR_FRE (1 << 8) /* Bit 8: Frame format error */ +#define SPI_SR_FRLVL_SHIFT (9) /* Bits 9-10: FIFO reception level */ +#define SPI_SR_FRLVL_MASK (3 << SPI_SR_FRLVL_SHIFT) +# define SPI_SR_FRLVL_EMPTY (0 << SPI_SR_FRLVL_SHIFT) /* FIFO empty */ +# define SPI_SR_FRLVL_QUARTER (1 << SPI_SR_FRLVL_SHIFT) /* 1/4 FIFO */ +# define SPI_SR_FRLVL_HALF (2 << SPI_SR_FRLVL_SHIFT) /* 1/2 FIFO */ +# define SPI_SR_FRLVL_FULL (3 << SPI_SR_FRLVL_SHIFT) /* FIFO full */ +#define SPI_SR_FTLVL_SHIFT (11) /* Bits 11-12: FIFO transmission level */ +#define SPI_SR_FTLVL_MASK (3 << SPI_SR_FTLVL_SHIFT) +# define SPI_SR_FTLVL_EMPTY (0 << SPI_SR_FTLVL_SHIFT) /* FIFO empty */ +# define SPI_SR_FTLVL_QUARTER (1 << SPI_SR_FTLVL_SHIFT) /* 1/4 FIFO */ +# define SPI_SR_FTLVL_HALF (2 << SPI_SR_FTLVL_SHIFT) /* 1/2 FIFO */ +# define SPI_SR_FTLVL_FULL (3 << SPI_SR_FTLVL_SHIFT) /* FIFO full */ + +/* I2S configuration register */ + +#define SPI_I2SCFGR_CHLEN (1 << 0) /* Bit 0: Channel length (number of bits per audio channel) */ +#define SPI_I2SCFGR_DATLEN_SHIFT (1) /* Bit 1-2: Data length to be transferred */ +#define SPI_I2SCFGR_DATLEN_MASK (3 << SPI_I2SCFGR_DATLEN_SHIFT) +# define SPI_I2SCFGR_DATLEN_16BIT (0 << SPI_I2SCFGR_DATLEN_SHIFT) /* 00: 16-bit data length */ +# define SPI_I2SCFGR_DATLEN_24BIT (1 << SPI_I2SCFGR_DATLEN_SHIFT) /* 01: 24-bit data length */ +# define SPI_I2SCFGR_DATLEN_32BIT (2 << SPI_I2SCFGR_DATLEN_SHIFT) /* 10: 32-bit data length */ +#define SPI_I2SCFGR_CKPOL (1 << 3) /* Bit 3: Steady state clock polarity */ +#define SPI_I2SCFGR_I2SSTD_SHIFT (4) /* Bit 4-5: I2S standard selection */ +#define SPI_I2SCFGR_I2SSTD_MASK (3 << SPI_I2SCFGR_I2SSTD_SHIFT) +# define SPI_I2SCFGR_I2SSTD_PHILLIPS (0 << SPI_I2SCFGR_I2SSTD_SHIFT) /* 00: I2S Phillips standard. */ +# define SPI_I2SCFGR_I2SSTD_MSB (1 << SPI_I2SCFGR_I2SSTD_SHIFT) /* 01: MSB justified standard (left justified) */ +# define SPI_I2SCFGR_I2SSTD_LSB (2 << SPI_I2SCFGR_I2SSTD_SHIFT) /* 10: LSB justified standard (right justified) */ +# define SPI_I2SCFGR_I2SSTD_PCM (3 << SPI_I2SCFGR_I2SSTD_SHIFT) /* 11: PCM standard */ +#define SPI_I2SCFGR_PCMSYNC (1 << 7) /* Bit 7: PCM frame synchronization */ +#define SPI_I2SCFGR_I2SCFG_SHIFT (8) /* Bit 8-9: I2S configuration mode */ +#define SPI_I2SCFGR_I2SCFG_MASK (3 << SPI_I2SCFGR_I2SCFG_SHIFT) +# define SPI_I2SCFGR_I2SCFG_STX (0 << SPI_I2SCFGR_I2SCFG_SHIFT) /* 00: Slave - transmit */ +# define SPI_I2SCFGR_I2SCFG_SRX (1 << SPI_I2SCFGR_I2SCFG_SHIFT) /* 01: Slave - receive */ +# define SPI_I2SCFGR_I2SCFG_MTX (2 << SPI_I2SCFGR_I2SCFG_SHIFT) /* 10: Master - transmit */ +# define SPI_I2SCFGR_I2SCFG_MRX (3 << SPI_I2SCFGR_I2SCFG_SHIFT) /* 11: Master - receive */ +#define SPI_I2SCFGR_I2SE (1 << 10) /* Bit 10: I2S Enable */ +#define SPI_I2SCFGR_I2SMOD (1 << 11) /* Bit 11: I2S mode selection */ + +/* I2S prescaler register */ + +#define SPI_I2SPR_I2SDIV_SHIFT (0) /* Bit 0-7: I2S Linear prescaler */ +#define SPI_I2SPR_I2SDIV_MASK (0xff << SPI_I2SPR_I2SDIV_SHIFT) +#define SPI_I2SPR_ODD (1 << 8) /* Bit 8: Odd factor for the prescaler */ +#define SPI_I2SPR_MCKOE (1 << 9) /* Bit 9: Master clock output enable */ + +#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_SPI_H */ diff --git a/arch/arm/src/stm32f0/chip/stm32f0_syscfg.h b/arch/arm/src/stm32f0/chip/stm32f0_syscfg.h new file mode 100644 index 0000000000..4715a43d2d --- /dev/null +++ b/arch/arm/src/stm32f0/chip/stm32f0_syscfg.h @@ -0,0 +1,390 @@ +/**************************************************************************************************** + * arch/arm/src/stm32f0/chip/stm32f0_syscfg.h + * + * 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. + * + ****************************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_SYSCFG_H +#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_SYSCFG_H + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include "chip.h" + +/**************************************************************************************************** + * Pre-processor Definitions + ****************************************************************************************************/ + +/* Register Offsets *********************************************************************************/ + +#define STM32F0_SYSCFG_CFGR1_OFFSET 0x0000 /* SYSCFG configuration register 1 */ +#define STM32F0_SYSCFG_EXTICR_OFFSET(p) (0x0008 + ((p) & 0x000c)) /* Registers are displaced by 4! */ +#define STM32F0_SYSCFG_EXTICR1_OFFSET 0x0008 /* SYSCFG external interrupt configuration register 1 */ +#define STM32F0_SYSCFG_EXTICR2_OFFSET 0x000c /* SYSCFG external interrupt configuration register 2 */ +#define STM32F0_SYSCFG_EXTICR3_OFFSET 0x0010 /* SYSCFG external interrupt configuration register 3 */ +#define STM32F0_SYSCFG_EXTICR4_OFFSET 0x0014 /* SYSCFG external interrupt configuration register 4 */ +#define STM32F0_SYSCFG_CFGR2_OFFSET 0x0018 /* SYSCFG configuration register 2 */ +#define STM32F0_SYSCFG_ITLINE0_OFFSET 0x0080 /* SYSCFG interrupt line 0 status register (STM32F09x) */ +#define STM32F0_SYSCFG_ITLINE1_OFFSET 0x0084 /* SYSCFG interrupt line 1 status register (STM32F09x) */ +#define STM32F0_SYSCFG_ITLINE2_OFFSET 0x0088 /* SYSCFG interrupt line 2 status register (STM32F09x) */ +#define STM32F0_SYSCFG_ITLINE3_OFFSET 0x008c /* SYSCFG interrupt line 3 status register (STM32F09x) */ +#define STM32F0_SYSCFG_ITLINE4_OFFSET 0x0090 /* SYSCFG interrupt line 4 status register (STM32F09x) */ +#define STM32F0_SYSCFG_ITLINE5_OFFSET 0x0094 /* SYSCFG interrupt line 5 status register (STM32F09x) */ +#define STM32F0_SYSCFG_ITLINE6_OFFSET 0x0098 /* SYSCFG interrupt line 6 status register (STM32F09x) */ +#define STM32F0_SYSCFG_ITLINE7_OFFSET 0x009c /* SYSCFG interrupt line 7 status register (STM32F09x) */ +#define STM32F0_SYSCFG_ITLINE8_OFFSET 0x00a0 /* SYSCFG interrupt line 8 status register (STM32F09x) */ +#define STM32F0_SYSCFG_ITLINE9_OFFSET 0x00a4 /* SYSCFG interrupt line 9 status register (STM32F09x) */ +#define STM32F0_SYSCFG_ITLINE10_OFFSET 0x00a8 /* SYSCFG interrupt line 10 status register (STM32F09x) */ +#define STM32F0_SYSCFG_ITLINE11_OFFSET 0x00ac /* SYSCFG interrupt line 11 status register (STM32F09x) */ +#define STM32F0_SYSCFG_ITLINE12_OFFSET 0x00b0 /* SYSCFG interrupt line 12 status register (STM32F09x) */ +#define STM32F0_SYSCFG_ITLINE13_OFFSET 0x00b4 /* SYSCFG interrupt line 13 status register (STM32F09x) */ +#define STM32F0_SYSCFG_ITLINE14_OFFSET 0x00b8 /* SYSCFG interrupt line 14 status register (STM32F09x) */ +#define STM32F0_SYSCFG_ITLINE15_OFFSET 0x00bc /* SYSCFG interrupt line 15 status register (STM32F09x) */ +#define STM32F0_SYSCFG_ITLINE16_OFFSET 0x00c0 /* SYSCFG interrupt line 16 status register (STM32F09x) */ +#define STM32F0_SYSCFG_ITLINE17_OFFSET 0x00c4 /* SYSCFG interrupt line 17 status register (STM32F09x) */ +#define STM32F0_SYSCFG_ITLINE18_OFFSET 0x00c8 /* SYSCFG interrupt line 18 status register (STM32F09x) */ +#define STM32F0_SYSCFG_ITLINE19_OFFSET 0x00cc /* SYSCFG interrupt line 19 status register (STM32F09x) */ +#define STM32F0_SYSCFG_ITLINE20_OFFSET 0x00d0 /* SYSCFG interrupt line 20 status register (STM32F09x) */ +#define STM32F0_SYSCFG_ITLINE21_OFFSET 0x00d4 /* SYSCFG interrupt line 21 status register (STM32F09x) */ +#define STM32F0_SYSCFG_ITLINE22_OFFSET 0x00d8 /* SYSCFG interrupt line 22 status register (STM32F09x) */ +#define STM32F0_SYSCFG_ITLINE23_OFFSET 0x00dc /* SYSCFG interrupt line 23 status register (STM32F09x) */ +#define STM32F0_SYSCFG_ITLINE24_OFFSET 0x00e0 /* SYSCFG interrupt line 24 status register (STM32F09x) */ +#define STM32F0_SYSCFG_ITLINE25_OFFSET 0x00e4 /* SYSCFG interrupt line 25 status register (STM32F09x) */ +#define STM32F0_SYSCFG_ITLINE26_OFFSET 0x00e8 /* SYSCFG interrupt line 26 status register (STM32F09x) */ +#define STM32F0_SYSCFG_ITLINE27_OFFSET 0x00ec /* SYSCFG interrupt line 27 status register (STM32F09x) */ +#define STM32F0_SYSCFG_ITLINE28_OFFSET 0x00f0 /* SYSCFG interrupt line 28 status register (STM32F09x) */ +#define STM32F0_SYSCFG_ITLINE29_OFFSET 0x00f4 /* SYSCFG interrupt line 29 status register (STM32F09x) */ +#define STM32F0_SYSCFG_ITLINE30_OFFSET 0x00f8 /* SYSCFG interrupt line 30 status register (STM32F09x) */ + +/* Register Addresses *******************************************************************************/ + +#define STM32F0_SYSCFG_CFGR1 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_CFGR1_OFFSET) + +#define STM32F0_SYSCFG_EXTICR(p) (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_EXTICR_OFFSET(p)) +#define STM32F0_SYSCFG_EXTICR1 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_EXTICR1_OFFSET) +#define STM32F0_SYSCFG_EXTICR2 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_EXTICR2_OFFSET) +#define STM32F0_SYSCFG_EXTICR3 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_EXTICR3_OFFSET) +#define STM32F0_SYSCFG_EXTICR4 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_EXTICR4_OFFSET) + +#define STM32F0_SYSCFG_CFGR2 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_CFGR2_OFFSET) + +#define STM32F0_SYSCFG_ITLINE0 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE0_OFFSET) +#define STM32F0_SYSCFG_ITLINE1 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE1_OFFSET) +#define STM32F0_SYSCFG_ITLINE2 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE2_OFFSET) +#define STM32F0_SYSCFG_ITLINE3 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE3_OFFSET) +#define STM32F0_SYSCFG_ITLINE4 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE4_OFFSET) +#define STM32F0_SYSCFG_ITLINE5 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE5_OFFSET) +#define STM32F0_SYSCFG_ITLINE6 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE6_OFFSET) +#define STM32F0_SYSCFG_ITLINE7 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE7_OFFSET) +#define STM32F0_SYSCFG_ITLINE8 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE8_OFFSET) +#define STM32F0_SYSCFG_ITLINE9 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE9_OFFSET) +#define STM32F0_SYSCFG_ITLINE10 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE10_OFFSET) +#define STM32F0_SYSCFG_ITLINE11 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE11_OFFSET) +#define STM32F0_SYSCFG_ITLINE12 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE12_OFFSET) +#define STM32F0_SYSCFG_ITLINE13 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE13_OFFSET) +#define STM32F0_SYSCFG_ITLINE14 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE14_OFFSET) +#define STM32F0_SYSCFG_ITLINE15 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE15_OFFSET) +#define STM32F0_SYSCFG_ITLINE16 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE16_OFFSET) +#define STM32F0_SYSCFG_ITLINE17 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE17_OFFSET) +#define STM32F0_SYSCFG_ITLINE18 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE18_OFFSET) +#define STM32F0_SYSCFG_ITLINE19 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE19_OFFSET) +#define STM32F0_SYSCFG_ITLINE20 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE20_OFFSET) +#define STM32F0_SYSCFG_ITLINE21 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE21_OFFSET) +#define STM32F0_SYSCFG_ITLINE22 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE22_OFFSET) +#define STM32F0_SYSCFG_ITLINE23 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE23_OFFSET) +#define STM32F0_SYSCFG_ITLINE24 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE24_OFFSET) +#define STM32F0_SYSCFG_ITLINE25 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE25_OFFSET) +#define STM32F0_SYSCFG_ITLINE26 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE26_OFFSET) +#define STM32F0_SYSCFG_ITLINE27 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE27_OFFSET) +#define STM32F0_SYSCFG_ITLINE28 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE28_OFFSET) +#define STM32F0_SYSCFG_ITLINE29 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE29_OFFSET) +#define STM32F0_SYSCFG_ITLINE30 (STM32F0_SYSCFG_BASE+STM32F0_SYSCFG_ITLINE30_OFFSET) + +/* Register Bitfield Definitions ********************************************************************/ + +/* SYSCFG memory remap register */ + +#define SYSCFG_CFGR1_MEMMODE_SHIFT (0) /* Bits 1:0 MEM_MODE: Memory mapping selection */ +#define SYSCFG_CFGR1_MEMMODE_MASK (3 << SYSCFG_CFGR1_MEMMODE_SHIFT) +# define SYSCFG_CFGR1_MEMMODE_FLASH (0 << SYSCFG_CFGR1_MEMMODE_SHIFT) /* 00: Main Flash at 0x00000000 */ +# define SYSCFG_CFGR1_MEMMODE_SYSTEM (1 << SYSCFG_CFGR1_MEMMODE_SHIFT) /* 01: System Flash at 0x00000000 */ +# define SYSCFG_CFGR1_MEMMODE_SRAM (3 << SYSCFG_CFGR1_MEMMODE_SHIFT) /* 11: Embedded SRAM at 0x00000000 */ +#define SYSCFG_CFGR1_PA11_PA12_RMP (1 << 4) /* Bit 4: PA11 and PA12 remapping bit for small packages */ +#define SYSCFG_CFGR1_IRMOD_SHIFT (6) /* Bits 6-7: IR Modulation Envelope signal selection */ +#define SYSCFG_CFGR1_IRMOD_MASK (3 << SYSCFG_CFGR1_IRMOD_SHIFT) +# define SYSCFG_CFGR1_IRMOD_TIM16 (0 << SYSCFG_CFGR1_IRMOD_SHIFT) /* 00: TIM16 selected */ +# define SYSCFG_CFGR1_IRMOD_USART1 (1 << SYSCFG_CFGR1_IRMOD_SHIFT) /* 01: USART1 selected */ +# define SYSCFG_CFGR1_IRMOD_USART4 (2 << SYSCFG_CFGR1_IRMOD_SHIFT) /* 10: USART1 selected */ +#define SYSCFG_CFGR1_ADC_DMARMP (1 << 8) /* Bit 8: ADC DMA remapping bit. Only STM32F03x/F04x/F05x/F07x */ +#define SYSCFG_CFGR1_USART1_TXDMARMP (1 << 9) /* Bit 9: USART1_TX_DMA request remapping bit. Only STM32F03x/F04x/F05x/F07x */ +#define SYSCFG_CFGR1_USART1_RXDMARMP (1 << 10) /* Bit 10: USART1_TX_DMA request remapping bit. Only STM32F03x/F04x/F05x/F07x */ +#define SYSCFG_CFGR1_TIM16_DMARMP (1 << 11) /* Bit 11: TIM16 DMA request remapping bit */ +#define SYSCFG_CFGR1_TIM17_DMARMP (1 << 12) /* Bit 12: TIM17 DMA request remapping bit */ +#define SYSCFG_CFGR1_TIM16_DMARMP2 (1 << 13) /* Bit 13: TIM16 alternate DMA request remapping bit */ +#define SYSCFG_CFGR1_TIM17_DMARMP2 (1 << 14) /* Bit 14: TIM17 alternate DMA request remapping bit */ +#define SYSCFG_CFGR1_I2C_PBXFMP_SHIFT (16) /* Bits 16-19: Fast Mode Plus (FM+) driving capability */ +#define SYSCFG_CFGR1_I2C_PBXFMP_MASK (15 << SYSCFG_CFGR1_I2C_PBXFMP_SHIFT) +#define SYSCFG_CFGR1_I2C1_FMP (1 << 20) /* Bit 20: I2C1 fast mode Plus driving capability */ +#define SYSCFG_CFGR1_I2C2_FMP (1 << 21) /* Bit 21: I2C2 fast mode Plus driving capability */ +#define SYSCFG_CFGR1_I2C_PAXFMP_SHIFT (22) /* Bits 22-23: Fast Mode Plus (FM+) driving capability */ +#define SYSCFG_CFGR1_I2C_PAXFMP_MASK (3 << SYSCFG_CFGR1_I2C_PAXFMP_SHIFT) +#define SYSCFG_CFGR1_SPI2_DMARMP (1 << 24) /* Bit 24: SPI2 DMA request remapping bit. */ +#define SYSCFG_CFGR1_USART2_DMARMP (1 << 25) /* Bit 25: USART2 DMA request remapping bit. */ +#define SYSCFG_CFGR1_USART3_DMARMP (1 << 26) /* Bit 26: USART3 DMA request remapping bit. */ +#define SYSCFG_CFGR1_I2C1_DMARMP (1 << 27) /* Bit 27: I2C1 DMA request remapping bit. */ +#define SYSCFG_CFGR1_TIM1_DMARMP (1 << 28) /* Bit 28: TIM1 DMA request remapping bit. */ +#define SYSCFG_CFGR1_TIM2_DMARMP (1 << 29) /* Bit 29: TIM2 DMA request remapping bit. */ +#define SYSCFG_CFGR1_TIM3_DMARMP (1 << 30) /* Bit 30: TIM3 DMA request remapping bit. */ + +/* SYSCFG external interrupt configuration register 1-4 */ + +#define SYSCFG_EXTICR_PORTA (0) /* 0000: PA[x] pin */ +#define SYSCFG_EXTICR_PORTB (1) /* 0001: PB[x] pin */ +#define SYSCFG_EXTICR_PORTC (2) /* 0010: PC[x] pin */ +#define SYSCFG_EXTICR_PORTD (3) /* 0011: PD[x] pin */ +#define SYSCFG_EXTICR_PORTE (4) /* 0100: PE[x] pin */ +#define SYSCFG_EXTICR_PORTF (5) /* 0101: PF[x] pin */ + +#define SYSCFG_EXTICR_PORT_MASK (15) +#define SYSCFG_EXTICR_EXTI_SHIFT(g) (((g) & 3) << 2) +#define SYSCFG_EXTICR_EXTI_MASK(g) (SYSCFG_EXTICR_PORT_MASK << (SYSCFG_EXTICR_EXTI_SHIFT(g))) + +#define SYSCFG_EXTICR1_EXTI0_SHIFT (0) /* Bits 0-3: EXTI 0 coinfiguration */ +#define SYSCFG_EXTICR1_EXTI0_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI0_SHIFT) +#define SYSCFG_EXTICR1_EXTI1_SHIFT (4) /* Bits 4-7: EXTI 1 coinfiguration */ +#define SYSCFG_EXTICR1_EXTI1_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI1_SHIFT) +#define SYSCFG_EXTICR1_EXTI2_SHIFT (8) /* Bits 8-11: EXTI 2 coinfiguration */ +#define SYSCFG_EXTICR1_EXTI2_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI2_SHIFT) +#define SYSCFG_EXTICR1_EXTI3_SHIFT (12) /* Bits 12-15: EXTI 3 coinfiguration */ +#define SYSCFG_EXTICR1_EXTI3_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI3_SHIFT) + +#define SYSCFG_EXTICR2_EXTI4_SHIFT (0) /* Bits 0-3: EXTI 4 coinfiguration */ +#define SYSCFG_EXTICR2_EXTI4_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI4_SHIFT) +#define SYSCFG_EXTICR2_EXTI5_SHIFT (4) /* Bits 4-7: EXTI 5 coinfiguration */ +#define SYSCFG_EXTICR2_EXTI5_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI5_SHIFT) +#define SYSCFG_EXTICR2_EXTI6_SHIFT (8) /* Bits 8-11: EXTI 6 coinfiguration */ +#define SYSCFG_EXTICR2_EXTI6_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI6_SHIFT) +#define SYSCFG_EXTICR2_EXTI7_SHIFT (12) /* Bits 12-15: EXTI 7 coinfiguration */ +#define SYSCFG_EXTICR2_EXTI7_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI7_SHIFT) + +#define SYSCFG_EXTICR3_EXTI8_SHIFT (0) /* Bits 0-3: EXTI 8 coinfiguration */ +#define SYSCFG_EXTICR3_EXTI8_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI8_SHIFT) +#define SYSCFG_EXTICR3_EXTI9_SHIFT (4) /* Bits 4-7: EXTI 9 coinfiguration */ +#define SYSCFG_EXTICR3_EXTI9_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI9_SHIFT) +#define SYSCFG_EXTICR3_EXTI10_SHIFT (8) /* Bits 8-11: EXTI 10 coinfiguration */ +#define SYSCFG_EXTICR3_EXTI10_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI10_SHIFT) +#define SYSCFG_EXTICR3_EXTI11_SHIFT (12) /* Bits 12-15: EXTI 11 coinfiguration */ +#define SYSCFG_EXTICR3_EXTI11_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI11_SHIFT) + +#define SYSCFG_EXTICR4_EXTI12_SHIFT (0) /* Bits 0-3: EXTI 12 coinfiguration */ +#define SYSCFG_EXTICR4_EXTI12_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI12_SHIFT) +#define SYSCFG_EXTICR4_EXTI13_SHIFT (4) /* Bits 4-7: EXTI 13 coinfiguration */ +#define SYSCFG_EXTICR4_EXTI13_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI13_SHIFT) +#define SYSCFG_EXTICR4_EXTI14_SHIFT (8) /* Bits 8-11: EXTI 14 coinfiguration */ +#define SYSCFG_EXTICR4_EXTI14_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI14_SHIFT) +#define SYSCFG_EXTICR4_EXTI15_SHIFT (12) /* Bits 12-15: EXTI 15 coinfiguration */ +#define SYSCFG_EXTICR4_EXTI15_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI15_SHIFT) + +/* SYSCFG configuration register 2 */ + +#define SYSCFG_CFGR2_LOCKUPLOCK (1 << 0) /* Bit 0: Cortex-M0 Hardfault output bit enable */ +#define SYSCFG_CFGR2_SRAM_PARITYLOCK (1 << 1) /* Bit 1: RAM parity lock */ +#define SYSCFG_CFGR2_PVDLOCK (1 << 2) /* Bit 2: PVD lock enable */ +#define SYSCFG_CFGR2_SRAM_PEF (1 << 8) /* Bit 8: SRAM parity error */ + +/* SYSCFG interrupt line 0 status register */ + +#define SYSCFG_ITLINE0_WWDG (1 << 0) /* Bit 0: Window Watchdog interrupt pending flag */ + +/* SYSCFG interrupt line 1 status register */ + +#define SYSCFG_ITLINE1_PVDOUT (1 << 0) /* Bit 0: PVD supply monitoring interrupt request pending (EXTI line 16) */ +#define SYSCFG_ITLINE1_VDDIO2 (1 << 0) /* Bit 1: VDDIO2 supply monitoring interrupt request pending (EXTI line 31) */ + +/* SYSCFG interrupt line 2 status register */ + +#define SYSCFG_ITLINE2_RTC_WAKEUP (1 << 0) /* Bit 0: RTC Wake Up interrupt request pending (EXTI line 20) */ +#define SYSCFG_ITLINE2_RTC_TSTAMP (1 << 1) /* Bit 1: RTC Tamper and TimeStamp interrupt request pending (EXTI line 19) */ +#define SYSCFG_ITLINE2_RTC_ALRA (1 << 2) /* Bit 2: RTC Alarm interrupt request pending (EXTI line 17) */ + +/* SYSCFG interrupt line 3 status register */ + +#define SYSCFG_ITLINE3_FLASH_ITF (1 << 0) /* Bit 0: Flash interface interrupt request pending */ + +/* SYSCFG interrupt line 4 status register */ + +#define SYSCFG_ITLINE4_RCC (1 << 0) /* Bit 0: Reset and clock control interrupt request pending */ +#define SYSCFG_ITLINE4_CRS (1 << 1) /* Bit 1: Clock recovery system interrupt request pending */ + +/* SYSCFG interrupt line 5 status register */ + +#define SYSCFG_ITLINE5_EXTI0 (1 << 0) /* Bit 0: EXTI line 0 interrupt request pending */ +#define SYSCFG_ITLINE5_EXTI1 (1 << 1) /* Bit 1: EXTI line 1 interrupt request pending */ + +/* SYSCFG interrupt line 6 status register */ + +#define SYSCFG_ITLINE6_EXTI2 (1 << 0) /* Bit 0: EXTI line 2 interrupt request pending */ +#define SYSCFG_ITLINE6_EXTI3 (1 << 1) /* Bit 1: EXTI line 3 interrupt request pending */ + +/* SYSCFG interrupt line 7 status register */ + +#define SYSCFG_ITLINE7_EXTI4 (1 << 0) /* Bit 0: EXTI line 4 interrupt request pending */ +#define SYSCFG_ITLINE7_EXTI5 (1 << 1) /* Bit 1: EXTI line 5 interrupt request pending */ +#define SYSCFG_ITLINE7_EXTI6 (1 << 2) /* Bit 2: EXTI line 6 interrupt request pending */ +#define SYSCFG_ITLINE7_EXTI7 (1 << 3) /* Bit 3: EXTI line 7 interrupt request pending */ +#define SYSCFG_ITLINE7_EXTI8 (1 << 4) /* Bit 4: EXTI line 8 interrupt request pending */ +#define SYSCFG_ITLINE7_EXTI9 (1 << 5) /* Bit 5: EXTI line 9 interrupt request pending */ +#define SYSCFG_ITLINE7_EXTI10 (1 << 6) /* Bit 6: EXTI line 10 interrupt request pending */ +#define SYSCFG_ITLINE7_EXTI11 (1 << 7) /* Bit 7: EXTI line 11 interrupt request pending */ +#define SYSCFG_ITLINE7_EXTI12 (1 << 8) /* Bit 8: EXTI line 12 interrupt request pending */ +#define SYSCFG_ITLINE7_EXTI13 (1 << 9) /* Bit 9: EXTI line 13 interrupt request pending */ +#define SYSCFG_ITLINE7_EXTI14 (1 << 10) /* Bit 10: EXTI line 14 interrupt request pending */ +#define SYSCFG_ITLINE7_EXTI15 (1 << 11) /* Bit 11: EXTI line 15 interrupt request pending */ + +/* SYSCFG interrupt line 8 status register */ + +#define SYSCFG_ITLINE8_TCS_MCE (1 << 0) /* Bit 0: Touch sensing controller max count error interrupt request pending */ +#define SYSCFG_ITLINE8_TCS_EOA (1 << 1) /* Bit 1: Touch sensing controller end of acquisition interrupt request pending */ + +/* SYSCFG interrupt line 9 status register */ + +#define SYSCFG_ITLINE9_DMA1_CH1 (1 << 0) /* Bit 0: DMA1 channel 1 interrupt request pending */ + +/* SYSCFG interrupt line 10 status register */ + +#define SYSCFG_ITLINE10_DMA1_CH2 (1 << 0) /* Bit 0: DMA1 channel 2 interrupt request pending */ +#define SYSCFG_ITLINE10_DMA1_CH3 (1 << 1) /* Bit 1: DMA1 channel 3 interrupt request pending */ +#define SYSCFG_ITLINE10_DMA2_CH1 (1 << 2) /* Bit 0: DMA2 channel 1 interrupt request pending */ +#define SYSCFG_ITLINE10_DMA2_CH2 (1 << 3) /* Bit 1: DMA2 channel 2 interrupt request pending */ + +/* SYSCFG interrupt line 11 status register */ + +#define SYSCFG_ITLINE11_DMA1_CH4 (1 << 0) /* Bit 0: DMA1 channel 4 interrupt request pending */ +#define SYSCFG_ITLINE11_DMA1_CH5 (1 << 1) /* Bit 1: DMA1 channel 5 interrupt request pending */ +#define SYSCFG_ITLINE11_DMA1_CH6 (1 << 2) /* Bit 2: DMA1 channel 6 interrupt request pending */ +#define SYSCFG_ITLINE11_DMA1_CH7 (1 << 3) /* Bit 3: DMA1 channel 7 interrupt request pending */ +#define SYSCFG_ITLINE11_DMA2_CH3 (1 << 4) /* Bit 4: DMA2 channel 3 interrupt request pending */ +#define SYSCFG_ITLINE11_DMA2_CH4 (1 << 5) /* Bit 5: DMA2 channel 4 interrupt request pending */ +#define SYSCFG_ITLINE11_DMA2_CH5 (1 << 6) /* Bit 6: DMA2 channel 5 interrupt request pending */ + +/* SYSCFG interrupt line 12 status register */ + +#define SYSCFG_ITLINE12_ADC (1 << 0) /* Bit 0: ADC interrupt request pending */ +#define SYSCFG_ITLINE12_COMP1 (1 << 1) /* Bit 1: Comparator 1 interrupt request pending */ +#define SYSCFG_ITLINE12_COMP2 (1 << 2) /* Bit 2: Comparator 2 interrupt request pending */ + +/* SYSCFG interrupt line 13 status register */ + +#define SYSCFG_ITLINE13_TIM1_CCU (1 << 0) /* Bit 0: TIM1 commutation interrupt request pending */ +#define SYSCFG_ITLINE13_TIM1_TRG (1 << 1) /* Bit 1: TIM1 triggerinterrupt request pending */ +#define SYSCFG_ITLINE13_TIM1_UPD (1 << 2) /* Bit 2: TIM1 update interrupt request pending */ +#define SYSCFG_ITLINE13_TIM1_BRK (1 << 3) /* Bit 3: TIM1 break interrupt request pending */ + +/* SYSCFG interrupt line 14 status register */ + +#define SYSCFG_ITLINE14_TIM1_CC (1 << 0) /* Bit 0: TIM1 capture compare interrupt request pending */ + +/* SYSCFG interrupt line 15 status register */ + +#define SYSCFG_ITLINE15_TIM2 (1 << 0) /* Bit 0: Timer 2 interrupt request pending */ + +/* SYSCFG interrupt line 16 status register */ + +#define SYSCFG_ITLINE16_TIM3 (1 << 0) /* Bit 0: Timer 3 interrupt request pending */ + +/* SYSCFG interrupt line 17 status register */ + +#define SYSCFG_ITLINE17_TIM6 (1 << 0) /* Bit 0: Timer 6 interrupt request pending */ +#define SYSCFG_ITLINE17_DAC (1 << 1) /* Bit 1: DAC underrun interrupt request pending */ + +/* SYSCFG interrupt line 18 status register */ + +#define SYSCFG_ITLINE18_TIM7 (1 << 0) /* Bit 0: Timer 7 interrupt request pending */ + +/* SYSCFG interrupt line 19 status register */ + +#define SYSCFG_ITLINE19_TIM14 (1 << 0) /* Bit 0: Timer 14 interrupt request pending */ + +/* SYSCFG interrupt line 20 status register */ + +#define SYSCFG_ITLINE20_TIM15 (1 << 0) /* Bit 0: Timer 15 interrupt request pending */ + +/* SYSCFG interrupt line 21 status register */ + +#define SYSCFG_ITLINE21_TIM16 (1 << 0) /* Bit 0: Timer 16 interrupt request pending */ + +/* SYSCFG interrupt line 22 status register */ + +#define SYSCFG_ITLINE22_TIM17 (1 << 0) /* Bit 0: Timer 17 interrupt request pending */ + +/* SYSCFG interrupt line 23 status register */ + +#define SYSCFG_ITLINE23_I2C1 (1 << 0) /* Bit 0: I2C1 interrupt request pending, combined with EXTI line 23 */ + +/* SYSCFG interrupt line 24 status register */ + +#define SYSCFG_ITLINE24_I2C2 (1 << 0) /* Bit 0: I2C2 interrupt request pending */ + +/* SYSCFG interrupt line 25 status register */ + +#define SYSCFG_ITLINE25_SPI1 (1 << 0) /* Bit 0: SPI1 interrupt request pending */ + +/* SYSCFG interrupt line 26 status register */ + +#define SYSCFG_ITLINE26_SPI2 (1 << 0) /* Bit 0: SPI2 interrupt request pending */ + +/* SYSCFG interrupt line 27 status register */ + +#define SYSCFG_ITLINE27_USART1 (1 << 0) /* Bit 0: USART1 interrupt request pending */ + +/* SYSCFG interrupt line 28 status register */ + +#define SYSCFG_ITLINE28_USART2 (1 << 0) /* Bit 0: USART2 interrupt request pending */ + +/* SYSCFG interrupt line 29 status register */ + +#define SYSCFG_ITLINE29_USART3 (1 << 0) /* Bit 0: USART3 interrupt request pending */ +#define SYSCFG_ITLINE29_USART4 (1 << 1) /* Bit 1: USART4 interrupt request pending */ +#define SYSCFG_ITLINE29_USART5 (1 << 2) /* Bit 2: USART5 interrupt request pending */ +#define SYSCFG_ITLINE29_USART6 (1 << 3) /* Bit 3: USART6 interrupt request pending */ +#define SYSCFG_ITLINE29_USART7 (1 << 4) /* Bit 4: USART7 interrupt request pending */ +#define SYSCFG_ITLINE29_USART8 (1 << 5) /* Bit 5: USART8 interrupt request pending */ + +/* SYSCFG interrupt line 30 status register */ + +#define SYSCFG_ITLINE30_CEC (1 << 0) /* Bit 0: CEC interrupt request pending, combined with EXTI line 27 */ +#define SYSCFG_ITLINE30_CAN (1 << 1) /* Bit 1: CAN interrupt request pending */ + +#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_SYSCFG_H */ diff --git a/arch/arm/src/stm32f0/chip/stm32f0_tim.h b/arch/arm/src/stm32f0/chip/stm32f0_tim.h new file mode 100644 index 0000000000..048da45690 --- /dev/null +++ b/arch/arm/src/stm32f0/chip/stm32f0_tim.h @@ -0,0 +1,51 @@ +/**************************************************************************************************** + * arch/arm/src/stm32f0/chip/stm32f0_tim.h + * + * 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. + * + ****************************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_TIM_H +#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_TIM_H + +/**************************************************************************************************** + * Pre-processor Definitions + ****************************************************************************************************/ + +/* TODO: Define the TIMx registers here */ + +/* Register Offsets *********************************************************************************/ + +/* Basic Timers - TIM6 and TIM7 */ + +/* Register Bitfield Definitions ********************************************************************/ + +#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_TIM_H */ diff --git a/arch/arm/src/stm32f0/chip/stm32f0_uart.h b/arch/arm/src/stm32f0/chip/stm32f0_uart.h new file mode 100644 index 0000000000..1a35d401b7 --- /dev/null +++ b/arch/arm/src/stm32f0/chip/stm32f0_uart.h @@ -0,0 +1,357 @@ +/************************************************************************************ + * arch/arm/src/stm32f0/chip/stm32f0_uart.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_UART_H +#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_UART_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include "chip.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Register Offsets *****************************************************************/ + +#define STM32F0_USART_CR1_OFFSET 0x0000 /* Control register 1 */ +#define STM32F0_USART_CR2_OFFSET 0x0004 /* Control register 2 */ +#define STM32F0_USART_CR3_OFFSET 0x0008 /* Control register 3 */ +#define STM32F0_USART_BRR_OFFSET 0x000c /* Baud Rate register */ +#define STM32F0_USART_GTPR_OFFSET 0x0010 /* Guard time and prescaler register */ +#define STM32F0_USART_RTOR_OFFSET 0x0014 /* Receiver timeout register */ +#define STM32F0_USART_RQR_OFFSET 0x0018 /* Request register */ +#define STM32F0_USART_ISR_OFFSET 0x001c /* Interrupot and status register */ +#define STM32F0_USART_ICR_OFFSET 0x0020 /* Interrupt flag clear register */ +#define STM32F0_USART_RDR_OFFSET 0x0024 /* Receive Data register */ +#define STM32F0_USART_TDR_OFFSET 0x0028 /* Transmit Data register */ + +/* Register Addresses ***************************************************************/ + +#if STM32F0_NUSART > 0 +# define STM32F0_USART1_CR1 (STM32F0_USART1_BASE+STM32F0_USART_CR1_OFFSET) +# define STM32F0_USART1_CR2 (STM32F0_USART1_BASE+STM32F0_USART_CR2_OFFSET) +# define STM32F0_USART1_CR3 (STM32F0_USART1_BASE+STM32F0_USART_CR3_OFFSET) +# define STM32F0_USART1_BRR (STM32F0_USART1_BASE+STM32F0_USART_BRR_OFFSET) +# define STM32F0_USART1_GTPR (STM32F0_USART1_BASE+STM32F0_USART_GTPR_OFFSET) +# define STM32F0_USART1_RTOR (STM32F0_USART1_BASE+STM32F0_USART_RTOR_OFFSET) +# define STM32F0_USART1_RQR (STM32F0_USART1_BASE+STM32F0_USART_RQR_OFFSET) +# define STM32F0_USART1_ISR (STM32F0_USART1_BASE+STM32F0_USART_ISR_OFFSET) +# define STM32F0_USART1_ICR (STM32F0_USART1_BASE+STM32F0_USART_ICR_OFFSET) +# define STM32F0_USART1_RDR (STM32F0_USART1_BASE+STM32F0_USART_RDR_OFFSET) +# define STM32F0_USART1_TDR (STM32F0_USART1_BASE+STM32F0_USART_TDR_OFFSET) +#endif + +#if STM32F0_NUSART > 1 +# define STM32F0_USART2_CR1 (STM32F0_USART2_BASE+STM32F0_USART_CR1_OFFSET) +# define STM32F0_USART2_CR2 (STM32F0_USART2_BASE+STM32F0_USART_CR2_OFFSET) +# define STM32F0_USART2_CR3 (STM32F0_USART2_BASE+STM32F0_USART_CR3_OFFSET) +# define STM32F0_USART2_BRR (STM32F0_USART2_BASE+STM32F0_USART_BRR_OFFSET) +# define STM32F0_USART2_GTPR (STM32F0_USART2_BASE+STM32F0_USART_GTPR_OFFSET) +# define STM32F0_USART2_RTOR (STM32F0_USART2_BASE+STM32F0_USART_RTOR_OFFSET) +# define STM32F0_USART2_RQR (STM32F0_USART2_BASE+STM32F0_USART_RQR_OFFSET) +# define STM32F0_USART2_ISR (STM32F0_USART2_BASE+STM32F0_USART_ISR_OFFSET) +# define STM32F0_USART2_ICR (STM32F0_USART2_BASE+STM32F0_USART_ICR_OFFSET) +# define STM32F0_USART2_RDR (STM32F0_USART2_BASE+STM32F0_USART_RDR_OFFSET) +# define STM32F0_USART2_TDR (STM32F0_USART2_BASE+STM32F0_USART_TDR_OFFSET) +#endif + +#if STM32F0_NUSART > 2 +# define STM32F0_USART3_CR1 (STM32F0_USART3_BASE+STM32F0_USART_CR1_OFFSET) +# define STM32F0_USART3_CR2 (STM32F0_USART3_BASE+STM32F0_USART_CR2_OFFSET) +# define STM32F0_USART3_CR3 (STM32F0_USART3_BASE+STM32F0_USART_CR3_OFFSET) +# define STM32F0_USART3_BRR (STM32F0_USART3_BASE+STM32F0_USART_BRR_OFFSET) +# define STM32F0_USART3_GTPR (STM32F0_USART3_BASE+STM32F0_USART_GTPR_OFFSET) +# define STM32F0_USART3_RTOR (STM32F0_USART3_BASE+STM32F0_USART_RTOR_OFFSET) +# define STM32F0_USART3_RQR (STM32F0_USART3_BASE+STM32F0_USART_RQR_OFFSET) +# define STM32F0_USART3_ISR (STM32F0_USART3_BASE+STM32F0_USART_ISR_OFFSET) +# define STM32F0_USART3_ICR (STM32F0_USART3_BASE+STM32F0_USART_ICR_OFFSET) +# define STM32F0_USART3_RDR (STM32F0_USART3_BASE+STM32F0_USART_RDR_OFFSET) +# define STM32F0_USART3_TDR (STM32F0_USART3_BASE+STM32F0_USART_TDR_OFFSET) +#endif + +#if STM32F0_NUSART > 3 +# define STM32F0_UART4_CR1 (STM32F0_UART4_BASE+STM32F0_USART_CR1_OFFSET) +# define STM32F0_UART4_CR2 (STM32F0_UART4_BASE+STM32F0_USART_CR2_OFFSET) +# define STM32F0_UART4_CR3 (STM32F0_UART4_BASE+STM32F0_USART_CR3_OFFSET) +# define STM32F0_UART4_BRR (STM32F0_UART4_BASE+STM32F0_USART_BRR_OFFSET) +# define STM32F0_UART4_GTPR (STM32F0_UART4_BASE+STM32F0_USART_GTPR_OFFSET) +# define STM32F0_UART4_RTOR (STM32F0_UART4_BASE+STM32F0_USART_RTOR_OFFSET) +# define STM32F0_UART4_RQR (STM32F0_UART4_BASE+STM32F0_USART_RQR_OFFSET) +# define STM32F0_UART4_ISR (STM32F0_UART4_BASE+STM32F0_USART_ISR_OFFSET) +# define STM32F0_UART4_ICR (STM32F0_UART4_BASE+STM32F0_USART_ICR_OFFSET) +# define STM32F0_UART4_RDR (STM32F0_UART4_BASE+STM32F0_USART_RDR_OFFSET) +# define STM32F0_UART4_TDR (STM32F0_UART4_BASE+STM32F0_USART_TDR_OFFSET) +#endif + +#if STM32F0_NUSART > 4 +# define STM32F0_UART5_CR1 (STM32F0_UART5_BASE+STM32F0_USART_CR1_OFFSET) +# define STM32F0_UART5_CR2 (STM32F0_UART5_BASE+STM32F0_USART_CR2_OFFSET) +# define STM32F0_UART5_CR3 (STM32F0_UART5_BASE+STM32F0_USART_CR3_OFFSET) +# define STM32F0_UART5_BRR (STM32F0_UART5_BASE+STM32F0_USART_BRR_OFFSET) +# define STM32F0_UART5_GTPR (STM32F0_UART5_BASE+STM32F0_USART_GTPR_OFFSET) +# define STM32F0_UART5_RTOR (STM32F0_UART5_BASE+STM32F0_USART_RTOR_OFFSET) +# define STM32F0_UART5_RQR (STM32F0_UART5_BASE+STM32F0_USART_RQR_OFFSET) +# define STM32F0_UART5_ISR (STM32F0_UART5_BASE+STM32F0_USART_ISR_OFFSET) +# define STM32F0_UART5_ICR (STM32F0_UART5_BASE+STM32F0_USART_ICR_OFFSET) +# define STM32F0_UART5_RDR (STM32F0_UART5_BASE+STM32F0_USART_RDR_OFFSET) +# define STM32F0_UART5_TDR (STM32F0_UART5_BASE+STM32F0_USART_TDR_OFFSET) +#endif + +#if STM32F0_NUSART > 5 +# define STM32F0_UART6_CR1 (STM32F0_UART6_BASE+STM32F0_USART_CR1_OFFSET) +# define STM32F0_UART6_CR2 (STM32F0_UART6_BASE+STM32F0_USART_CR2_OFFSET) +# define STM32F0_UART6_CR3 (STM32F0_UART6_BASE+STM32F0_USART_CR3_OFFSET) +# define STM32F0_UART6_BRR (STM32F0_UART6_BASE+STM32F0_USART_BRR_OFFSET) +# define STM32F0_UART6_GTPR (STM32F0_UART6_BASE+STM32F0_USART_GTPR_OFFSET) +# define STM32F0_UART6_RTOR (STM32F0_UART6_BASE+STM32F0_USART_RTOR_OFFSET) +# define STM32F0_UART6_RQR (STM32F0_UART6_BASE+STM32F0_USART_RQR_OFFSET) +# define STM32F0_UART6_ISR (STM32F0_UART6_BASE+STM32F0_USART_ISR_OFFSET) +# define STM32F0_UART6_ICR (STM32F0_UART6_BASE+STM32F0_USART_ICR_OFFSET) +# define STM32F0_UART6_RDR (STM32F0_UART6_BASE+STM32F0_USART_RDR_OFFSET) +# define STM32F0_UART6_TDR (STM32F0_UART6_BASE+STM32F0_USART_TDR_OFFSET) +#endif + +#if STM32F0_NUSART > 6 +# define STM32F0_UART7_CR1 (STM32F0_UART7_BASE+STM32F0_USART_CR1_OFFSET) +# define STM32F0_UART7_CR2 (STM32F0_UART7_BASE+STM32F0_USART_CR2_OFFSET) +# define STM32F0_UART7_CR3 (STM32F0_UART7_BASE+STM32F0_USART_CR3_OFFSET) +# define STM32F0_UART7_BRR (STM32F0_UART7_BASE+STM32F0_USART_BRR_OFFSET) +# define STM32F0_UART7_GTPR (STM32F0_UART7_BASE+STM32F0_USART_GTPR_OFFSET) +# define STM32F0_UART7_RTOR (STM32F0_UART7_BASE+STM32F0_USART_RTOR_OFFSET) +# define STM32F0_UART7_RQR (STM32F0_UART7_BASE+STM32F0_USART_RQR_OFFSET) +# define STM32F0_UART7_ISR (STM32F0_UART7_BASE+STM32F0_USART_ISR_OFFSET) +# define STM32F0_UART7_ICR (STM32F0_UART7_BASE+STM32F0_USART_ICR_OFFSET) +# define STM32F0_UART7_RDR (STM32F0_UART7_BASE+STM32F0_USART_RDR_OFFSET) +# define STM32F0_UART7_TDR (STM32F0_UART7_BASE+STM32F0_USART_TDR_OFFSET) +#endif + +#if STM32F0_NUSART > 7 +# define STM32F0_UART8_CR1 (STM32F0_UART8_BASE+STM32F0_USART_CR1_OFFSET) +# define STM32F0_UART8_CR2 (STM32F0_UART8_BASE+STM32F0_USART_CR2_OFFSET) +# define STM32F0_UART8_CR3 (STM32F0_UART8_BASE+STM32F0_USART_CR3_OFFSET) +# define STM32F0_UART8_BRR (STM32F0_UART8_BASE+STM32F0_USART_BRR_OFFSET) +# define STM32F0_UART8_GTPR (STM32F0_UART8_BASE+STM32F0_USART_GTPR_OFFSET) +# define STM32F0_UART8_RTOR (STM32F0_UART8_BASE+STM32F0_USART_RTOR_OFFSET) +# define STM32F0_UART8_RQR (STM32F0_UART8_BASE+STM32F0_USART_RQR_OFFSET) +# define STM32F0_UART8_ISR (STM32F0_UART8_BASE+STM32F0_USART_ISR_OFFSET) +# define STM32F0_UART8_ICR (STM32F0_UART8_BASE+STM32F0_USART_ICR_OFFSET) +# define STM32F0_UART8_RDR (STM32F0_UART8_BASE+STM32F0_USART_RDR_OFFSET) +# define STM32F0_UART8_TDR (STM32F0_UART8_BASE+STM32F0_USART_TDR_OFFSET) +#endif + +/* Register Bitfield Definitions ****************************************************/ + +/* Control register 1 */ + +#define USART_CR1_UE (1 << 0) /* Bit 0: USART Enable */ +#define USART_CR1_UESM (1 << 1) /* Bit 1: USART Enable in Stop mode*/ +#define USART_CR1_RE (1 << 2) /* Bit 2: Receiver Enable */ +#define USART_CR1_TE (1 << 3) /* Bit 3: Transmitter Enable */ +#define USART_CR1_IDLEIE (1 << 4) /* Bit 4: IDLE Interrupt Enable */ +#define USART_CR1_RXNEIE (1 << 5) /* Bit 5: RXNE Interrupt Enable */ +#define USART_CR1_TCIE (1 << 6) /* Bit 6: Transmission Complete Interrupt Enable */ +#define USART_CR1_TXEIE (1 << 7) /* Bit 7: TXE Interrupt Enable */ +#define USART_CR1_PEIE (1 << 8) /* Bit 8: PE Interrupt Enable */ +#define USART_CR1_PS (1 << 9) /* Bit 9: Parity Selection */ +#define USART_CR1_PCE (1 << 10) /* Bit 10: Parity Control Enable */ +#define USART_CR1_WAKE (1 << 11) /* Bit 11: Wakeup method */ +#define USART_CR1_M0 (1 << 12) /* Bit 12: word length */ +#define USART_CR1_MME (1 << 13) /* Bit 13: Mute mode enable */ +#define USART_CR1_CMIE (1 << 14) /* Bit 14: Character match interrupt enable */ +#define USART_CR1_OVER8 (1 << 15) /* Bit 15: Oversampling mode */ + +#define USART_CR1_DEDT_SHIFT (16) /* Bits 16..20 DE deactivation delay */ +#define USART_CR1_DEDT_MASK (0x1f << USART_CR1_DEDT_SHIFT) + +#define USART_CR1_DEAT_SHIFT (21) /* Bits 21..25 DE activation delay */ +#define USART_CR1_DEAT_MASK (0x1f << USART_CR1_DEAT_SHIFT) + +#define USART_CR1_RTOIE (1 << 26) /* Bit 26: Receiver timeout interrupt enable */ +#define USART_CR1_EOBIE (1 << 27) /* Bit 27: End of block interrupt enable */ +#define USART_CR1_M1 (1 << 28) /* Bit 12: word length */ + +#define USART_CR1_ALLINTS (USART_CR1_IDLEIE|USART_CR1_RXNEIE| \ + USART_CR1_TCIE|USART_CR1_TXEIE|USART_CR1_PEIE|USART_CR1_CMIE| \ + USART_CR1_RTOIE|USART_CR1_EOBIE) + +/* Control register 2 */ + +#define USART_CR2_ADDM7 (1 << 4) /* Bit 4: */ +#define USART_CR2_LBDL (1 << 5) /* Bit 5: LIN Break Detection Length */ +#define USART_CR2_LBDIE (1 << 6) /* Bit 6: LIN Break Detection Interrupt Enable */ +#define USART_CR2_LBCL (1 << 8) /* Bit 8: Last Bit Clock pulse */ +#define USART_CR2_CPHA (1 << 9) /* Bit 9: Clock Phase */ +#define USART_CR2_CPOL (1 << 10) /* Bit 10: Clock Polarity */ +#define USART_CR2_CLKEN (1 << 11) /* Bit 11: Clock Enable */ + +#define USART_CR2_STOP_SHIFT (12) /* Bits 13-12: STOP bits */ +#define USART_CR2_STOP_MASK (3 << USART_CR2_STOP_SHIFT) +# define USART_CR2_STOP1 (0 << USART_CR2_STOP_SHIFT) /* 00: 1 Stop bit */ +# define USART_CR2_STOP0p5 (1 << USART_CR2_STOP_SHIFT) /* 01: 0.5 Stop bit */ +# define USART_CR2_STOP2 (2 << USART_CR2_STOP_SHIFT) /* 10: 2 Stop bits */ +# define USART_CR2_STOP1p5 (3 << USART_CR2_STOP_SHIFT) /* 11: 1.5 Stop bit */ + +#define USART_CR2_LINEN (1 << 14) /* Bit 14: LIN mode enable */ +#define USART_CR2_SWAP (1 << 15) /* Bit 15: Swap TX/RX pins */ +#define USART_CR2_RXINV (1 << 16) /* Bit 16: RX pin active level inversion */ +#define USART_CR2_TXINV (1 << 17) /* Bit 17: TX pin active level inversion */ +#define USART_CR2_DATAINV (1 << 18) /* Bit 18: Binary data inversion */ +#define USART_CR2_MSBFIRST (1 << 19) /* Bit 19: Most significant bit first */ +#define USART_CR2_ABREN (1 << 20) /* Bit 20: Auto Baud rate enable */ + +#define USART_CR2_ABRMOD_SHIFT (21) /* Bits 21-22: Autobaud rate mode*/ +#define USART_CR2_ABRMOD_MASK (3 << USART_CR2_ABRMOD_SHIFT) +#define USART_CR2_ABRMOD_START (0 << USART_CR2_ABRMOD_SHIFT) /* 00: Start bit */ +#define USART_CR2_ABRMOD_EDGES (1 << USART_CR2_ABRMOD_SHIFT) /* 01: Falling-to-falling edge -> frame must start with 10xxxxxx */ +#define USART_CR2_ABRMOD_7F (2 << USART_CR2_ABRMOD_SHIFT) /* 10: 0x7F */ +#define USART_CR2_ABRMOD_55 (3 << USART_CR2_ABRMOD_SHIFT) /* 11: 0x55 */ + +#define USART_CR2_RTOEN (1 << 23) /* Bit 23: Receiver timeout enable */ + +#define USART_CR2_ADD_SHIFT (24) /* Bits 24-31: Address of the USART node */ +#define USART_CR2_ADD_MASK (0xff << USART_CR2_ADD_SHIFT) + +/* Control register 3 */ + +#define USART_CR3_EIE (1 << 0) /* Bit 0: Error Interrupt Enable */ +#define USART_CR3_IREN (1 << 1) /* Bit 1: IrDA mode Enable */ +#define USART_CR3_IRLP (1 << 2) /* Bit 2: IrDA Low-Power */ +#define USART_CR3_HDSEL (1 << 3) /* Bit 3: Half-Duplex Selection */ +#define USART_CR3_NACK (1 << 4) /* Bit 4: Smartcard NACK enable */ +#define USART_CR3_SCEN (1 << 5) /* Bit 5: Smartcard mode enable */ +#define USART_CR3_DMAR (1 << 6) /* Bit 6: DMA Enable Receiver */ +#define USART_CR3_DMAT (1 << 7) /* Bit 7: DMA Enable Transmitter */ +#define USART_CR3_RTSE (1 << 8) /* Bit 8: RTS Enable */ +#define USART_CR3_CTSE (1 << 9) /* Bit 9: CTS Enable */ +#define USART_CR3_CTSIE (1 << 10) /* Bit 10: CTS Interrupt Enable */ +#define USART_CR3_ONEBIT (1 << 11) /* Bit 11: One sample bit method Enable */ +#define USART_CR3_OVRDIS (1 << 12) /* Bit 12: Overrun Disable */ +#define USART_CR3_DDRE (1 << 13) /* Bit 13: DMA disable on Reception error */ +#define USART_CR3_DEM (1 << 14) /* Bit 14: Driver Enable mode */ +#define USART_CR3_DEP (1 << 15) /* Bit 15: Driver Enable polarity selection */ +#define USART_CR3_SCARCNT2_SHIFT (17) /* Bits 17-19: Smart card auto retry count */ +#define USART_CR3_SCARCNT2_MASK (7 << USART_CR3_SCARCNT2_SHIFT) +#define USART_CR3_WUS_SHIFT (20) /* Bits 20-21: Wakeup from Stop mode interrupt flag selection */ +#define USART_CR3_WUS_MASK (3 << USART_CR3_WUS_SHIFT) +#define USART_CR3_WUS_ADDRESS (0 << USART_CR3_WUS_SHIFT) /* 00: WUF active on address match */ +#define USART_CR3_WUS_START (2 << USART_CR3_WUS_SHIFT) /* 10: WUF active on Start bit detection */ +#define USART_CR3_WUS_RXNE (3 << USART_CR3_WUS_SHIFT) /* 11: WUF active on RXNE */ +#define USART_CR3_WUFIE (1 << 22) /* Bit 22: Wakeup from Stop mode interrupt enable */ + +/* Baud Rate Register */ + +#define USART_BRR_FRAC_SHIFT (0) /* Bits 3-0: fraction of USARTDIV */ +#define USART_BRR_FRAC_MASK (0x0f << USART_BRR_FRAC_SHIFT) +#define USART_BRR_MANT_SHIFT (4) /* Bits 15-4: mantissa of USARTDIV */ +#define USART_BRR_MANT_MASK (0x0fff << USART_BRR_MANT_SHIFT) + +/* Guard time and prescaler register */ + +#define USART_GTPR_PSC_SHIFT (0) /* Bits 0-7: Prescaler value */ +#define USART_GTPR_PSC_MASK (0xff << USART_GTPR_PSC_SHIFT) +#define USART_GTPR_GT_SHIFT (8) /* Bits 8-15: Guard time value */ +#define USART_GTPR_GT_MASK (0xff << USART_GTPR_GT_SHIFT) + +/* Receiver timeout register */ + +#define USART_RTOR_RTO_SHIFT (0) /* Bits 0-23: Receiver timeout value */ +#define USART_RTOR_RTO_MASK (0xffffff << USART_RTOR_RTO_SHIFT) +#define USART_RTOR_BLEN_SHIFT (24) /* Bits 24-31: Block length */ +#define USART_RTOR_BLEN_MASK (0xff << USART_RTOR_BLEN_SHIFT) + +/* Request Register */ + +#define USART_RQR_ABRRQ (1 << 0) /* Bit 0: Auto baud rate request */ +#define USART_RQR_SBKRQ (1 << 1) /* Bit 1: Send Break */ +#define USART_RQR_MMRQ (1 << 2) /* Bit 2: Mute mode request */ +#define USART_RQR_RXFRQ (1 << 3) /* Bit 3: Receive data flush request */ +#define USART_RQR_TXFRQ (1 << 4) /* Bit 4: Transmit data flush request */ + +/* Interrupt and Status register */ + +#define USART_ISR_PE (1 << 0) /* Bit 0: Parity Error */ +#define USART_ISR_FE (1 << 1) /* Bit 1: Framing Error */ +#define USART_ISR_NF (1 << 2) /* Bit 2: Noise Error Flag */ +#define USART_ISR_ORE (1 << 3) /* Bit 3: OverRun Error */ +#define USART_ISR_IDLE (1 << 4) /* Bit 4: IDLE line detected */ +#define USART_ISR_RXNE (1 << 5) /* Bit 5: Read Data Register Not Empty */ +#define USART_ISR_TC (1 << 6) /* Bit 6: Transmission Complete */ +#define USART_ISR_TXE (1 << 7) /* Bit 7: Transmit Data Register Empty */ +#define USART_ISR_LBDF (1 << 8) /* Bit 8: LIN Break Detection Flag */ +#define USART_ISR_CTSIF (1 << 9) /* Bit 9: CTS Interrupt flag */ +#define USART_ISR_CTS (1 << 10) /* Bit 9: CTS Flag */ +#define USART_ISR_RTOF (1 << 11) /* Bit 10: Receiver timeout Flag */ +#define USART_ISR_EOBF (1 << 12) /* Bit 11: End of block Flag */ +#define USART_ISR_ABRE (1 << 13) /* Bit 12: Auto baud rate Error */ +#define USART_ISR_ABRF (1 << 15) /* Bit 14: Auto baud rate Flag */ +#define USART_ISR_BUSY (1 << 16) /* Bit 15: Busy Flag */ +#define USART_ISR_CMF (1 << 17) /* Bit 16: Character match Flag */ +#define USART_ISR_SBKF (1 << 18) /* Bit 17: Send break Flag */ +#define USART_ISR_RWU (1 << 19) /* Bit 18: Receiver wakeup from Mute mode */ +#define USART_ISR_WUF (1 << 20) /* Bit 19: Wakeup from Stop mode Flag */ +#define USART_ISR_TEACK (1 << 21) /* Bit 20: Transmit enable acknowledge Flag */ +#define USART_ISR_REACK (1 << 22) /* Bit 21: Receive enable acknowledge Flag */ + +/* ICR */ + +#define USART_ICR_PECF (1 << 0) /* Bit 0: Parity error clear flag */ +#define USART_ICR_FECF (1 << 1) /* Bit 1: Framing error clear flag */ +#define USART_ICR_NCF (1 << 2) /* Bit 2: Noise detected clear flag */ +#define USART_ICR_ORECF (1 << 3) /* Bit 3: Overrun error clear flag */ +#define USART_ICR_IDLECF (1 << 4) /* Bit 4: Idle line detected clear flag */ +#define USART_ICR_TCCF (1 << 6) /* Bit 6: Transmission complete clear flag */ +#define USART_ICR_LBDCF (1 << 8) /* Bit 8: LIN break detection clear flag */ +#define USART_ICR_CTSCF (1 << 9) /* Bit 9: CTS clear flag */ +#define USART_ICR_RTOCF (1 << 11) /* Bit 11: Receiver timeout clear flag */ +#define USART_ICR_EOBCF (1 << 12) /* Bit 12: End of block clear flag */ +#define USART_ICR_CMCF (1 << 17) /* Bit 17: Character match clear flag */ +#define USART_ICR_WUCF (1 << 20) /* Bit 20: Wakeup from Stop mode clear flag */ + +/* Receive Data register */ + +#define USART_RDR_SHIFT (0) /* Bits 8:0: Data value */ +#define USART_RDR_MASK (0xff << USART_RDR_SHIFT) + +/* Transmit Data register */ + +#define USART_TDR_SHIFT (0) /* Bits 8:0: Data value */ +#define USART_TDR_MASK (0xff << USART_TDR_SHIFT) + +#endif /* __ARCH_ARM_STC_STM32F0_CHIP_STM32F0_UART_H */ diff --git a/arch/arm/src/stm32f0/chip/stm32f0_usbdev.h b/arch/arm/src/stm32f0/chip/stm32f0_usbdev.h new file mode 100644 index 0000000000..c4eeb6ca53 --- /dev/null +++ b/arch/arm/src/stm32f0/chip/stm32f0_usbdev.h @@ -0,0 +1,262 @@ +/************************************************************************************ + * arch/arm/src/stm32f0/chip/stm32f0_usbdev.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_USBDEV_H +#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_USBDEV_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Register Offsets *****************************************************************/ + +/* Endpoint Registers */ + +#define STM32F0_USB_EPR_OFFSET(n) ((n) << 2) /* USB endpoint n register (16-bits) */ +#define STM32F0_USB_EP0R_OFFSET 0x0000 /* USB endpoint 0 register (16-bits) */ +#define STM32F0_USB_EP1R_OFFSET 0x0004 /* USB endpoint 1 register (16-bits) */ +#define STM32F0_USB_EP2R_OFFSET 0x0008 /* USB endpoint 2 register (16-bits) */ +#define STM32F0_USB_EP3R_OFFSET 0x000c /* USB endpoint 3 register (16-bits) */ +#define STM32F0_USB_EP4R_OFFSET 0x0010 /* USB endpoint 4 register (16-bits) */ +#define STM32F0_USB_EP5R_OFFSET 0x0014 /* USB endpoint 5 register (16-bits) */ +#define STM32F0_USB_EP6R_OFFSET 0x0018 /* USB endpoint 6 register (16-bits) */ +#define STM32F0_USB_EP7R_OFFSET 0x001c /* USB endpoint 7 register (16-bits) */ + +/* Common Registers */ + +#define STM32F0_USB_CNTR_OFFSET 0x0040 /* USB control register (16-bits) */ +#define STM32F0_USB_ISTR_OFFSET 0x0044 /* USB interrupt status register (16-bits) */ +#define STM32F0_USB_FNR_OFFSET 0x0048 /* USB frame number register (16-bits) */ +#define STM32F0_USB_DADDR_OFFSET 0x004c /* USB device address (16-bits) */ +#define STM32F0_USB_BTABLE_OFFSET 0x0050 /* Buffer table address (16-bits) */ +#define STM32F0_USB_LPMCSR_OFFSET 0x0054 /* LPM control and status register */ +#define STM32F0_USB_BCDR_OFFSET 0x0058 /* Battery charging detector */ + +/* Buffer Descriptor Table (Relatative to BTABLE address) */ + +#define STM32F0_USB_ADDR_TX_WOFFSET (0) /* Transmission buffer address n (16-bits) */ +#define STM32F0_USB_COUNT_TX_WOFFSET (2) /* Transmission byte count n (16-bits) */ +#define STM32F0_USB_ADDR_RX_WOFFSET (4) /* Reception buffer address n (16-bits) */ +#define STM32F0_USB_COUNT_RX_WOFFSET (6) /* Reception byte count n (16-bits) */ + +#define STM32F0_USB_BTABLE_RADDR(ep,o) ((((uint32_t)getreg16(STM32F0_USB_BTABLE) + ((ep) << 3)) + (o)) << 1) +#define STM32F0_USB_ADDR_TX_OFFSET(ep) STM32F0_USB_BTABLE_RADDR(ep,STM32F0_USB_ADDR_TX_WOFFSET) +#define STM32F0_USB_COUNT_TX_OFFSET(ep) STM32F0_USB_BTABLE_RADDR(ep,STM32F0_USB_COUNT_TX_WOFFSET) +#define STM32F0_USB_ADDR_RX_OFFSET(ep) STM32F0_USB_BTABLE_RADDR(ep,STM32F0_USB_ADDR_RX_WOFFSET) +#define STM32F0_USB_COUNT_RX_OFFSET(ep) STM32F0_USB_BTABLE_RADDR(ep,STM32F0_USB_COUNT_RX_WOFFSET) + +/* Register Addresses ***************************************************************/ + +/* Endpoint Registers */ + +#define STM32F0_USB_EPR(n) (STM32F0_USB_BASE+STM32F0_USB_EPR_OFFSET(n)) +#define STM32F0_USB_EP0R (STM32F0_USB_BASE+STM32F0_USB_EP0R_OFFSET) +#define STM32F0_USB_EP1R (STM32F0_USB_BASE+STM32F0_USB_EP1R_OFFSET) +#define STM32F0_USB_EP2R (STM32F0_USB_BASE+STM32F0_USB_EP2R_OFFSET) +#define STM32F0_USB_EP3R (STM32F0_USB_BASE+STM32F0_USB_EP3R_OFFSET) +#define STM32F0_USB_EP4R (STM32F0_USB_BASE+STM32F0_USB_EP4R_OFFSET) +#define STM32F0_USB_EP5R (STM32F0_USB_BASE+STM32F0_USB_EP5R_OFFSET) +#define STM32F0_USB_EP6R (STM32F0_USB_BASE+STM32F0_USB_EP6R_OFFSET) +#define STM32F0_USB_EP7R (STM32F0_USB_BASE+STM32F0_USB_EP7R_OFFSET) + +/* Common Registers */ + +#define STM32F0_USB_CNTR (STM32F0_USB_BASE+STM32F0_USB_CNTR_OFFSET) +#define STM32F0_USB_ISTR (STM32F0_USB_BASE+STM32F0_USB_ISTR_OFFSET) +#define STM32F0_USB_FNR (STM32F0_USB_BASE+STM32F0_USB_FNR_OFFSET) +#define STM32F0_USB_DADDR (STM32F0_USB_BASE+STM32F0_USB_DADDR_OFFSET) +#define STM32F0_USB_BTABLE (STM32F0_USB_BASE+STM32F0_USB_BTABLE_OFFSET) +#define STM32F0_USB_LPMCSR_OFFSET (STM32F0_USB_BASE+STM32F0_USB_LPMCSR_OFFSET) +#define STM32F0_USB_BCDR_OFFSET (STM32F0_USB_BASE+STM32F0_USB_BCDR_OFFSET) + +/* Buffer Descriptor Table (Relatative to BTABLE address) */ + +#define STM32F0_USB_BTABLE_ADDR(ep,o) (STM32F0_USBRAM_BASE+STM32F0_USB_BTABLE_RADDR(ep,o)) +#define STM32F0_USB_ADDR_TX(ep) STM32F0_USB_BTABLE_ADDR(ep,STM32F0_USB_ADDR_TX_WOFFSET) +#define STM32F0_USB_COUNT_TX(ep) STM32F0_USB_BTABLE_ADDR(ep,STM32F0_USB_COUNT_TX_WOFFSET) +#define STM32F0_USB_ADDR_RX(ep) STM32F0_USB_BTABLE_ADDR(ep,STM32F0_USB_ADDR_RX_WOFFSET) +#define STM32F0_USB_COUNT_RX(ep) STM32F0_USB_BTABLE_ADDR(ep,STM32F0_USB_COUNT_RX_WOFFSET) + +/* Register Bitfield Definitions ****************************************************/ + +/* USB endpoint register */ + +#define USB_EPR_EA_SHIFT (0) /* Bits 3:0 [3:0]: Endpoint Address */ +#define USB_EPR_EA_MASK (0X0f << USB_EPR_EA_SHIFT) +#define USB_EPR_STATTX_SHIFT (4) /* Bits 5-4: Status bits, for transmission transfers */ +#define USB_EPR_STATTX_MASK (3 << USB_EPR_STATTX_SHIFT) +# define USB_EPR_STATTX_DIS (0 << USB_EPR_STATTX_SHIFT) /* EndPoint TX DISabled */ +# define USB_EPR_STATTX_STALL (1 << USB_EPR_STATTX_SHIFT) /* EndPoint TX STALLed */ +# define USB_EPR_STATTX_NAK (2 << USB_EPR_STATTX_SHIFT) /* EndPoint TX NAKed */ +# define USB_EPR_STATTX_VALID (3 << USB_EPR_STATTX_SHIFT) /* EndPoint TX VALID */ +# define USB_EPR_STATTX_DTOG1 (1 << USB_EPR_STATTX_SHIFT) /* EndPoint TX Data Toggle bit1 */ +# define USB_EPR_STATTX_DTOG2 (2 << USB_EPR_STATTX_SHIFT) /* EndPoint TX Data Toggle bit2 */ +#define USB_EPR_DTOG_TX (1 << 6) /* Bit 6: Data Toggle, for transmission transfers */ +#define USB_EPR_CTR_TX (1 << 7) /* Bit 7: Correct Transfer for transmission */ +#define USB_EPR_EP_KIND (1 << 8) /* Bit 8: Endpoint Kind */ +#define USB_EPR_EPTYPE_SHIFT (9) /* Bits 10-9: Endpoint type */ +#define USB_EPR_EPTYPE_MASK (3 << USB_EPR_EPTYPE_SHIFT) +# define USB_EPR_EPTYPE_BULK (0 << USB_EPR_EPTYPE_SHIFT) /* EndPoint BULK */ +# define USB_EPR_EPTYPE_CONTROL (1 << USB_EPR_EPTYPE_SHIFT) /* EndPoint CONTROL */ +# define USB_EPR_EPTYPE_ISOC (2 << USB_EPR_EPTYPE_SHIFT) /* EndPoint ISOCHRONOUS */ +# define USB_EPR_EPTYPE_INTERRUPT (3 << USB_EPR_EPTYPE_SHIFT) /* EndPoint INTERRUPT */ +#define USB_EPR_SETUP (1 << 11) /* Bit 11: Setup transaction completed */ +#define USB_EPR_STATRX_SHIFT (12) /* Bits 13-12: Status bits, for reception transfers */ +#define USB_EPR_STATRX_MASK (3 << USB_EPR_STATRX_SHIFT) +# define USB_EPR_STATRX_DIS (0 << USB_EPR_STATRX_SHIFT) /* EndPoint RX DISabled */ +# define USB_EPR_STATRX_STALL (1 << USB_EPR_STATRX_SHIFT) /* EndPoint RX STALLed */ +# define USB_EPR_STATRX_NAK (2 << USB_EPR_STATRX_SHIFT) /* EndPoint RX NAKed */ +# define USB_EPR_STATRX_VALID (3 << USB_EPR_STATRX_SHIFT) /* EndPoint RX VALID */ +# define USB_EPR_STATRX_DTOG1 (1 << USB_EPR_STATRX_SHIFT) /* EndPoint RX Data TOGgle bit1 */ +# define USB_EPR_STATRX_DTOG2 (2 << USB_EPR_STATRX_SHIFT) /* EndPoint RX Data TOGgle bit1 */ +#define USB_EPR_DTOG_RX (1 << 14) /* Bit 14: Data Toggle, for reception transfers */ +#define USB_EPR_CTR_RX (1 << 15) /* Bit 15: Correct Transfer for reception */ + +/* USB control register */ + +#define USB_CNTR_FRES (1 << 0) /* Bit 0: Force USB Reset */ +#define USB_CNTR_PDWN (1 << 1) /* Bit 1: Power down */ +#define USB_CNTR_LPMODE (1 << 2) /* Bit 2: Low-power mode */ +#define USB_CNTR_FSUSP (1 << 3) /* Bit 3: Force suspend */ +#define USB_CNTR_RESUME (1 << 4) /* Bit 4: Resume request */ +#define USB_CNTR_L1RESUME (1 << 5) /* Bit 5: LPM L1 Resume request */ +#define USB_CNTR_L1REQM (1 << 7) /* Bit 6: LPM L1 state request interrupt mask */ +#define USB_CNTR_ESOFM (1 << 8) /* Bit 8: Expected Start Of Frame Interrupt Mask */ +#define USB_CNTR_SOFM (1 << 9) /* Bit 9: Start Of Frame Interrupt Mask */ +#define USB_CNTR_RESETM (1 << 10) /* Bit 10: USB Reset Interrupt Mask */ +#define USB_CNTR_SUSPM (1 << 11) /* Bit 11: Suspend mode Interrupt Mask */ +#define USB_CNTR_WKUPM (1 << 12) /* Bit 12: Wakeup Interrupt Mask */ +#define USB_CNTR_ERRM (1 << 13) /* Bit 13: Error Interrupt Mask */ +#define USB_CNTR_PMAOVRNM (1 << 14) /* Bit 14: Packet Memory Area Over / Underrun Interrupt Mask */ +#define USB_CNTR_CTRM (1 << 15) /* Bit 15: Correct Transfer Interrupt Mask */ + +#define USB_CNTR_ALLINTS (USB_CNTR_ESOFM|USB_CNTR_SOFM|USB_CNTR_RESETM|USB_CNTR_SUSPM|\ + USB_CNTR_WKUPM|USB_CNTR_ERRM|USB_CNTR_DMAOVRNM|USB_CNTR_CTRM) + +/* USB interrupt status register */ + +#define USB_ISTR_EPID_SHIFT (0) /* Bits 3-0: Endpoint Identifier */ +#define USB_ISTR_EPID_MASK (0x0f << USB_ISTR_EPID_SHIFT) +#define USB_ISTR_DIR (1 << 4) /* Bit 4: Direction of transaction */ +#define USB_ISTR_L1REQ (1 << 7) /* Bit 7: LPM L1 state request */ +#define USB_ISTR_ESOF (1 << 8) /* Bit 8: Expected Start Of Frame */ +#define USB_ISTR_SOF (1 << 9) /* Bit 9: Start Of Frame */ +#define USB_ISTR_RESET (1 << 10) /* Bit 10: USB RESET request */ +#define USB_ISTR_SUSP (1 << 11) /* Bit 11: Suspend mode request */ +#define USB_ISTR_WKUP (1 << 12) /* Bit 12: Wake up */ +#define USB_ISTR_ERR (1 << 13) /* Bit 13: Error */ +#define USB_ISTR_PMAOVRN (1 << 14) /* Bit 14: Packet Memory Area Over / Underrun */ +#define USB_ISTR_CTR (1 << 15) /* Bit 15: Correct Transfer */ + +#define USB_ISTR_ALLINTS (USB_ISTR_ESOF|USB_ISTR_SOF|USB_ISTR_RESET|USB_ISTR_SUSP|\ + USB_ISTR_WKUP|USB_ISTR_ERR|USB_ISTR_DMAOVRN|USB_ISTR_CTR) + +/* USB frame number register */ + +#define USB_FNR_FN_SHIFT (0) /* Bits 10-0: Frame Number */ +#define USB_FNR_FN_MASK (0x07ff << USB_FNR_FN_SHIFT) +#define USB_FNR_LSOF_SHIFT (11) /* Bits 12-11: Lost SOF */ +#define USB_FNR_LSOF_MASK (3 << USB_FNR_LSOF_SHIFT) +#define USB_FNR_LCK (1 << 13) /* Bit 13: Locked */ +#define USB_FNR_RXDM (1 << 14) /* Bit 14: Receive Data - Line Status */ +#define USB_FNR_RXDP (1 << 15) /* Bit 15: Receive Data + Line Status */ + +/* USB device address */ + +#define USB_DADDR_ADD_SHIFT (0) /* Bits 6-0: Device Address */ +#define USB_DADDR_ADD_MASK (0x7f << USB_DADDR_ADD_SHIFT) +#define USB_DADDR_EF (1 << 7) /* Bit 7: Enable Function */ + +/* Buffer table address */ + +#define USB_BTABLE_SHIFT (3) /* Bits 15:3: Buffer Table */ +#define USB_BTABLE_MASK (0x1fff << USB_BTABLE_SHIFT) + +/* LPM control and status register */ + +#define USB_LPMCSR_LPMEN (1 << 0) /* Bit 0: LPM support enable */ +#define USB_LPMCSR_LPMACK (1 << 1) /* Bit 1: LPM Token acknowledge enable */ +#define USB_LPMCSR_REMWAKE (1 << 3) /* Bit 3: bRemoteWake value */ +#define USB_LPMCSR_BESL_OFFSET (4) /* Bits 4-7: BESL value */ +#define USB_LPMCSR_BESL_MASK (0xf << USB_LPMCSR_BESL_OFFSET) + +/* Battery charging detector */ + +#define USB_BCDR_BCDEN (1 << 0) /* Bit 0: Battery charging detector (BCD) enable */ +#define USB_BCDR_DCDEN (1 << 1) /* Bit 1: Data contact detection (DCD) mode enable */ +#define USB_BCDR_PDEN (1 << 2) /* Bit 2: Primary detection (PD) mode enable */ +#define USB_BCDR_SDEN (1 << 3) /* Bit 3: Secondary detection (SD) mode enable */ +#define USB_BCDR_DCDET (1 << 4) /* Bit 4: Data contact detection (DCD) status */ +#define USB_BCDR_PDET (1 << 5) /* Bit 5: Primary detection (PD) status */ +#define USB_BCDR_SDET (1 << 6) /* Bit 6: Secondary detection (SD) status */ +#define USB_BCDR_PS2DET (1 << 7) /* Bit 7: DM pull-up detection status */ +#define USB_BCDR_DPPU (1 << 15) /* Bit 15: DP pull-up control */ + +/* Transmission buffer address */ + +#define USB_ADDR_TX_ZERO (1 << 0) /* Bit 0 Must always be written as ‘0’ */ +#define USB_ADDR_TX_SHIFT (1) /* Bits 15-1: Transmission Buffer Address */ +#define USB_ADDR_TX_MASK (0x7fff << USB_ADDR_ADDR_TX_SHIFT) + +/* Transmission byte count */ + +#define USB_COUNT_TX_SHIFT (0) /* Bits 0-9: Transmission Byte Count */ +#define USB_COUNT_TX_MASK (0x03ff << USB_COUNT_COUNT_TX_SHIFT) +#define USB_COUNT_NUMBLOCK_OFFSET (10) /* Bits 10-14: Number of blocks */ +#define USB_COUNT_NUMBLOCK_MASK (1 << USB_COUNT_NUMBLOCK_OFFSET) +#define USB_COUNT_BLSIZE (1 << 15) /* Bit 15: Block size */ + +/* Reception buffer address */ + +#define USB_ADDR_RX_ZERO (1 << 0) /* Bit 0 This bit must always be written as ‘0’ */ +#define USB_ADDR_RX_SHIFT (1) /* Bits 15:1 ADDRn_RX[15:1]: Reception Buffer Address */ +#define USB_ADDR_RX_MASK (0x7fff << USB_ADDR_RX_SHIFT) + +/* Reception byte count */ + +#define USB_COUNT_RX_BL_SIZE (1 << 15) /* Bit 15: BLock SIZE. */ +#define USB_COUNT_RX_NUM_BLOCK_SHIFT (10) /* Bits 14-10: Number of blocks */ +#define USB_COUNT_RX_NUM_BLOCK_MASK (0x1f << USB_COUNT_RX_NUM_BLOCK_SHIFT) +#define USB_COUNT_RX_SHIFT (0) /* Bits 9-0: Reception Byte Count */ +#define USB_COUNT_RX_MASK (0x03ff << USB_COUNT_RX_SHIFT) + +#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_USBDEV_H */ diff --git a/arch/arm/src/stm32f0/chip/stm32f0_wdt.h b/arch/arm/src/stm32f0/chip/stm32f0_wdt.h new file mode 100644 index 0000000000..7f731f6b48 --- /dev/null +++ b/arch/arm/src/stm32f0/chip/stm32f0_wdt.h @@ -0,0 +1,141 @@ +/************************************************************************************ + * arch/arm/src/stm32f0/chip/stm32f0_wdg.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_WDG_H +#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_WDG_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include "chip.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Register Offsets *****************************************************************/ + +#define STM32F0_IWDG_KR_OFFSET 0x0000 /* Key register (32-bit) */ +#define STM32F0_IWDG_PR_OFFSET 0x0004 /* Prescaler register (32-bit) */ +#define STM32F0_IWDG_RLR_OFFSET 0x0008 /* Reload register (32-bit) */ +#define STM32F0_IWDG_SR_OFFSET 0x000c /* Status register (32-bit) */ +#define STM32F0_IWDG_WINR_OFFSET 0x0010 /* Window register (32-bit) */ + +#define STM32F0_WWDG_CR_OFFSET 0x0000 /* Control Register (32-bit) */ +#define STM32F0_WWDG_CFR_OFFSET 0x0004 /* Configuration register (32-bit) */ +#define STM32F0_WWDG_SR_OFFSET 0x0008 /* Status register (32-bit) */ + +/* Register Addresses ***************************************************************/ + +#define STM32F0_IWDG_KR (STM32F0_IWDG_BASE+STM32F0_IWDG_KR_OFFSET) +#define STM32F0_IWDG_PR (STM32F0_IWDG_BASE+STM32F0_IWDG_PR_OFFSET) +#define STM32F0_IWDG_RLR (STM32F0_IWDG_BASE+STM32F0_IWDG_RLR_OFFSET) +#define STM32F0_IWDG_SR (STM32F0_IWDG_BASE+STM32F0_IWDG_SR_OFFSET) +#define STM32F0_IWDG_WINR (STM32F0_IWDG_BASE+STM32F0_IWDG_WINR_OFFSET) + +#define STM32F0_WWDG_CR (STM32F0_WWDG_BASE+STM32F0_WWDG_CR_OFFSET) +#define STM32F0_WWDG_CFR (STM32F0_WWDG_BASE+STM32F0_WWDG_CFR_OFFSET) +#define STM32F0_WWDG_SR (STM32F0_WWDG_BASE+STM32F0_WWDG_SR_OFFSET) + +/* Register Bitfield Definitions ****************************************************/ + +/* Key register (32-bit) */ + +#define IWDG_KR_KEY_SHIFT (0) /* Bits 15-0: Key value (write only, read 0000h) */ +#define IWDG_KR_KEY_MASK (0xffff << IWDG_KR_KEY_SHIFT) + +#define IWDG_KR_KEY_ENABLE (0x5555) /* Enable register access */ +#define IWDG_KR_KEY_DISABLE (0x0000) /* Disable register access */ +#define IWDG_KR_KEY_RELOAD (0xaaaa) /* Reload the counter */ +#define IWDG_KR_KEY_START (0xcccc) /* Start the watchdog */ + +/* Prescaler register (32-bit) */ + +#define IWDG_PR_SHIFT (0) /* Bits 2-0: Prescaler divider */ +#define IWDG_PR_MASK (7 << IWDG_PR_SHIFT) +# define IWDG_PR_DIV4 (0 << IWDG_PR_SHIFT) /* 000: divider /4 */ +# define IWDG_PR_DIV8 (1 << IWDG_PR_SHIFT) /* 001: divider /8 */ +# define IWDG_PR_DIV16 (2 << IWDG_PR_SHIFT) /* 010: divider /16 */ +# define IWDG_PR_DIV32 (3 << IWDG_PR_SHIFT) /* 011: divider /32 */ +# define IWDG_PR_DIV64 (4 << IWDG_PR_SHIFT) /* 100: divider /64 */ +# define IWDG_PR_DIV128 (5 << IWDG_PR_SHIFT) /* 101: divider /128 */ +# define IWDG_PR_DIV256 (6 << IWDG_PR_SHIFT) /* 11x: divider /256 */ + +/* Reload register (32-bit) */ + +#define IWDG_RLR_RL_SHIFT (0) /* Bits11:0 RL[11:0]: Watchdog counter reload value */ +#define IWDG_RLR_RL_MASK (0x0fff << IWDG_RLR_RL_SHIFT) + +#define IWDG_RLR_MAX (0xfff) + +/* Status register (32-bit) */ + +#define IWDG_SR_PVU (1 << 0) /* Bit 0: Watchdog prescaler value update */ +#define IWDG_SR_RVU (1 << 1) /* Bit 1: Watchdog counter reload value update */ +#define IWDG_SR_WVU (1 << 2) /* Bit 2: Watchdog counter window value update */ + +/* Window register (32-bit) */ + +#define IWDG_WINR_SHIFT (0) +#define IWDG_WINR_MASK (0x0fff << IWDG_WINR_SHIFT) + +/* Control Register (32-bit) */ + +#define WWDG_CR_T_SHIFT (0) /* Bits 6:0 T[6:0]: 7-bit counter (MSB to LSB) */ +#define WWDG_CR_T_MASK (0x7f << WWDG_CR_T_SHIFT) +# define WWDG_CR_T_MAX (0x3f << WWDG_CR_T_SHIFT) +# define WWDG_CR_T_RESET (0x40 << WWDG_CR_T_SHIFT) +#define WWDG_CR_WDGA (1 << 7) /* Bit 7: Activation bit */ + +/* Configuration register (32-bit) */ + +#define WWDG_CFR_W_SHIFT (0) /* Bits 6:0 W[6:0] 7-bit window value */ +#define WWDG_CFR_W_MASK (0x7f << WWDG_CFR_W_SHIFT) +#define WWDG_CFR_WDGTB_SHIFT (7) /* Bits 8:7 [1:0]: Timer Base */ +#define WWDG_CFR_WDGTB_MASK (3 << WWDG_CFR_WDGTB_SHIFT) +# define WWDG_CFR_PCLK1 (0 << WWDG_CFR_WDGTB_SHIFT) /* 00: CK Counter Clock (PCLK1 div 4096) div 1 */ +# define WWDG_CFR_PCLK1d2 (1 << WWDG_CFR_WDGTB_SHIFT) /* 01: CK Counter Clock (PCLK1 div 4096) div 2 */ +# define WWDG_CFR_PCLK1d4 (2 << WWDG_CFR_WDGTB_SHIFT) /* 10: CK Counter Clock (PCLK1 div 4096) div 4 */ +# define WWDG_CFR_PCLK1d8 (3 << WWDG_CFR_WDGTB_SHIFT) /* 11: CK Counter Clock (PCLK1 div 4096) div 8 */ +#define WWDG_CFR_EWI (1 << 9) /* Bit 9: Early Wakeup Interrupt */ + +/* Status register (32-bit) */ + +#define WWDG_SR_EWIF (1 << 0) /* Bit 0: Early Wakeup Interrupt Flag */ + +#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_WDG_H */ diff --git a/arch/arm/src/stm32f0/stm32f0_clockconfig.c b/arch/arm/src/stm32f0/stm32f0_clockconfig.c new file mode 100644 index 0000000000..56a26b30e3 --- /dev/null +++ b/arch/arm/src/stm32f0/stm32f0_clockconfig.c @@ -0,0 +1,112 @@ +/**************************************************************************** + * arch/arm/src/stm32f0/stm32f0_clockconfig.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include +#include + +#include "up_arch.h" +#include "up_internal.h" +#include "stm32f0_rcc.h" +#include "stm32f0_clockconfig.h" +#include "chip/stm32f0_syscfg.h" +#include "chip/stm32f0_gpio.h" + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32f0_clockconfig + * + * Description: + * Called to initialize the STM32F0xx. This does whatever setup is needed + * to put the SoC in a usable state. This includes the initialization of + * clocking using the settings in board.h. + * + ****************************************************************************/ + +void stm32f0_clockconfig(void) +{ + int regval; + + /* Verify if PLL is already setup, if so define to use HSI mode */ + + if ((getreg32(STM32F0_RCC_CFGR) & RCC_CFGR_SWS_MASK) == RCC_CFGR_SWS_PLL) + { + /* Select HSI mode */ + + regval = getreg32(STM32F0_RCC_CFGR); + regval &= (uint32_t) (~RCC_CFGR_SW_MASK); + putreg32(regval, STM32F0_RCC_CFGR); + + while ((getreg32(STM32F0_RCC_CFGR) & RCC_CFGR_SWS_MASK) != RCC_CFGR_SWS_HSI) ; + } + + /* Disable the PLL */ + + regval = getreg32(STM32F0_RCC_CR); + regval &= (uint32_t)(~RCC_CR_PLLON); + putreg32(regval, STM32F0_RCC_CR); + while ((getreg32(STM32F0_RCC_CR) & RCC_CR_PLLRDY) != 0) ; + + /* Configure the PLL. Multiple x6 to get 48MHz */ + + regval = getreg32(STM32F0_RCC_CFGR); + regval &= (RCC_CFGR_PLLMUL_CLKx6 | ~RCC_CFGR_PLLMUL_MASK); + putreg32(regval, STM32F0_RCC_CFGR); + + /* Enable the PLL */ + + regval = getreg32(STM32F0_RCC_CR); + regval |= RCC_CR_PLLON; + putreg32(regval, STM32F0_RCC_CR); + while ((getreg32(STM32F0_RCC_CR) & RCC_CR_PLLRDY) == 0) ; + + /* Configure to use the PLL */ + + regval = getreg32(STM32F0_RCC_CFGR); + regval |= (uint32_t) (RCC_CFGR_SW_PLL); + putreg32(regval, STM32F0_RCC_CFGR); + while ((getreg32(STM32F0_RCC_CFGR) & RCC_CFGR_SW_MASK) != RCC_CFGR_SW_PLL) ; +} diff --git a/arch/arm/src/stm32f0/stm32f0_clockconfig.h b/arch/arm/src/stm32f0/stm32f0_clockconfig.h new file mode 100644 index 0000000000..7d264faf3d --- /dev/null +++ b/arch/arm/src/stm32f0/stm32f0_clockconfig.h @@ -0,0 +1,76 @@ +/************************************************************************************ + * arch/arm/src/stm32f0/stm32f0_clockconfig.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32F0_STM32F0_CLOCKCONFIG_H +#define __ARCH_ARM_SRC_STM32F0_STM32F0_CLOCKCONFIG_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +#ifndef __ASSEMBLY__ +#ifdef __cplusplus +extern "C" +{ +#endif + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32f0_clockconfig + * + * Description: + * Called to initialize the STM32F0XX. This does whatever setup is needed to put + * the MCU in a usable state. This includes the initialization of clocking using + * the settings in board.h. + * + ************************************************************************************/ + +void stm32f0_clockconfig(void); + +#ifdef __cplusplus +} +#endif +#endif /* __ASSEMBLY__ */ + +#endif /* __ARCH_ARM_SRC_STM32F0_STM32F0_CLOCKCONFIG_H */ diff --git a/arch/arm/src/stm32f0/stm32f0_gpio.c b/arch/arm/src/stm32f0/stm32f0_gpio.c new file mode 100644 index 0000000000..3c4aa57b22 --- /dev/null +++ b/arch/arm/src/stm32f0/stm32f0_gpio.c @@ -0,0 +1,427 @@ +/**************************************************************************** + * arch/arm/src/stm32f0/stm32f0_gpio.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#include +#include + +#include "up_arch.h" + +#include "chip.h" +#include "stm32f0_gpio.h" + +#include "chip/stm32f0_syscfg.h" + +/**************************************************************************** + * Public Data + ****************************************************************************/ +/* Base addresses for each GPIO block */ + +const uint32_t g_gpiobase[STM32F0_NPORTS] = +{ +#if STM32F0_NPORTS > 0 + STM32F0_GPIOA_BASE, +#endif +#if STM32F0_NPORTS > 1 + STM32F0_GPIOB_BASE, +#endif +#if STM32F0_NPORTS > 2 + STM32F0_GPIOC_BASE, +#endif +#if STM32F0_NPORTS > 3 + STM32F0_GPIOD_BASE, +#endif +#if STM32F0_NPORTS > 4 + STM32F0_GPIOE_BASE, +#endif +#if STM32F0_NPORTS > 5 + STM32F0_GPIOF_BASE, +#endif +}; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: stm32f0_gpioinit + * + * Description: + * Based on configuration within the .config file, it does: + * - Remaps positions of alternative functions. + * + * Typically called from stm32f0_start(). + * + * Assumptions: + * This function is called early in the initialization sequence so that + * no mutual exlusion is necessary. + * + ****************************************************************************/ + +void stm32f0_gpioinit(void) +{ +} + +/**************************************************************************** + * Name: stm32f0_configgpio + * + * Description: + * Configure a GPIO pin based on bit-encoded description of the pin. + * Once it is configured as Alternative (GPIO_ALT|GPIO_CNF_AFPP|...) + * function, it must be unconfigured with stm32f0_unconfiggpio() with + * the same cfgset first before it can be set to non-alternative function. + * + * Returns: + * OK on success + * A negated errono valu on invalid port, or when pin is locked as ALT + * function. + * + * To-Do: Auto Power Enable + ****************************************************************************/ + +int stm32f0_configgpio(uint32_t cfgset) +{ + uintptr_t base; + uint32_t regval; + uint32_t setting; + unsigned int regoffset; + unsigned int port; + unsigned int pin; + unsigned int pos; + unsigned int pinmode; + irqstate_t flags; + + /* Verify that this hardware supports the select GPIO port */ + + port = (cfgset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT; + if (port >= STM32F0_NPORTS) + { + return -EINVAL; + } + + /* Get the port base address */ + + base = g_gpiobase[port]; + + /* Get the pin number and select the port configuration register for that + * pin + */ + + pin = (cfgset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT; + + /* Set up the mode register (and remember whether the pin mode) */ + + switch (cfgset & GPIO_MODE_MASK) + { + default: + case GPIO_INPUT: /* Input mode */ + pinmode = GPIO_MODER_INPUT; + break; + + case GPIO_OUTPUT: /* General purpose output mode */ + stm32f0_gpiowrite(cfgset, (cfgset & GPIO_OUTPUT_SET) != 0); /* Set the initial output value */ + pinmode = GPIO_MODER_OUTPUT; + break; + + case GPIO_ALT: /* Alternate function mode */ + pinmode = GPIO_MODER_ALT; + break; + + case GPIO_ANALOG: /* Analog mode */ + pinmode = GPIO_MODER_ANALOG; + break; + } + + /* Interrupts must be disabled from here on out so that we have mutually + * exclusive access to all of the GPIO configuration registers. + */ + + flags = enter_critical_section(); + + /* Now apply the configuration to the mode register */ + + regval = getreg32(base + STM32F0_GPIO_MODER_OFFSET); + regval &= ~GPIO_MODER_MASK(pin); + regval |= ((uint32_t)pinmode << GPIO_MODER_SHIFT(pin)); + putreg32(regval, base + STM32F0_GPIO_MODER_OFFSET); + + /* Set up the pull-up/pull-down configuration (all but analog pins) */ + + setting = GPIO_PUPDR_NONE; + if (pinmode != GPIO_MODER_ANALOG) + { + switch (cfgset & GPIO_PUPD_MASK) + { + default: + case GPIO_FLOAT: /* No pull-up, pull-down */ + break; + + case GPIO_PULLUP: /* Pull-up */ + setting = GPIO_PUPDR_PULLUP; + break; + + case GPIO_PULLDOWN: /* Pull-down */ + setting = GPIO_PUPDR_PULLDOWN; + break; + } + } + + regval = getreg32(base + STM32F0_GPIO_PUPDR_OFFSET); + regval &= ~GPIO_PUPDR_MASK(pin); + regval |= (setting << GPIO_PUPDR_SHIFT(pin)); + putreg32(regval, base + STM32F0_GPIO_PUPDR_OFFSET); + + /* Set the alternate function (Only alternate function pins) */ + + if (pinmode == GPIO_MODER_ALT) + { + setting = (cfgset & GPIO_AF_MASK) >> GPIO_AF_SHIFT; + } + else + { + setting = 0; + } + + if (pin < 8) + { + regoffset = STM32F0_GPIO_AFRL_OFFSET; + pos = pin; + } + else + { + regoffset = STM32F0_GPIO_AFRH_OFFSET; + pos = pin - 8; + } + + regval = getreg32(base + regoffset); + regval &= ~GPIO_AFR_MASK(pos); + regval |= (setting << GPIO_AFR_SHIFT(pos)); + putreg32(regval, base + regoffset); + + /* Set speed (Only outputs and alternate function pins) */ + + if (pinmode == GPIO_MODER_OUTPUT || pinmode == GPIO_MODER_ALT) + { + switch (cfgset & GPIO_SPEED_MASK) + { + default: + case GPIO_SPEED_2MHz: /* 2 MHz Low speed output */ + setting = GPIO_OSPEED_2MHz; + break; + + case GPIO_SPEED_10MHz: /* 10 MHz Medium speed output */ + setting = GPIO_OSPEED_10MHz; + break; + + case GPIO_SPEED_50MHz: /* 50 MHz High speed output */ + setting = GPIO_OSPEED_50MHz; + break; + } + } + else + { + setting = 0; + } + + regval = getreg32(base + STM32F0_GPIO_OSPEED_OFFSET); + regval &= ~GPIO_OSPEED_MASK(pin); + regval |= (setting << GPIO_OSPEED_SHIFT(pin)); + putreg32(regval, base + STM32F0_GPIO_OSPEED_OFFSET); + + /* Set push-pull/open-drain (Only outputs and alternate function pins) */ + + regval = getreg32(base + STM32F0_GPIO_OTYPER_OFFSET); + setting = GPIO_OTYPER_OD(pin); + + if ((pinmode == GPIO_MODER_OUTPUT || pinmode == GPIO_MODER_ALT) && + (cfgset & GPIO_OPENDRAIN) != 0) + { + regval |= setting; + } + else + { + regval &= ~setting; + } + + putreg32(regval, base + STM32F0_GPIO_OTYPER_OFFSET); + + /* Otherwise, it is an input pin. Should it configured as an EXTI interrupt? */ + + if ((cfgset & GPIO_EXTI) != 0) + { +#if 0 + /* "In STM32 F1 the selection of the EXTI line source is performed through + * the EXTIx bits in the AFIO_EXTICRx registers, while in F2 series this + * selection is done through the EXTIx bits in the SYSCFG_EXTICRx registers. + * + * "Only the mapping of the EXTICRx registers has been changed, without any + * changes to the meaning of the EXTIx bits. However, the range of EXTI + * bits values has been extended to 0b1000 to support the two ports added + * in F2, port H and I (in F1 series the maximum value is 0b0110)." + */ + + uint32_t regaddr; + int shift; + + /* Set the bits in the SYSCFG EXTICR register */ + + regaddr = STM32F0_SYSCFG_EXTICR(pin); + regval = getreg32(regaddr); + shift = SYSCFG_EXTICR_EXTI_SHIFT(pin); + regval &= ~(SYSCFG_EXTICR_PORT_MASK << shift); + regval |= (((uint32_t)port) << shift); + + putreg32(regval, regaddr); +#endif + } + + leave_critical_section(flags); + return OK; +} + +/**************************************************************************** + * Name: stm32f0_unconfiggpio + * + * Description: + * Unconfigure a GPIO pin based on bit-encoded description of the pin, set it + * into default HiZ state (and possibly mark it's unused) and unlock it whether + * it was previsouly selected as alternative function (GPIO_ALT|GPIO_CNF_AFPP|...). + * + * This is a safety function and prevents hardware from schocks, as unexpected + * write to the Timer Channel Output GPIO to fixed '1' or '0' while it should + * operate in PWM mode could produce excessive on-board currents and trigger + * over-current/alarm function. + * + * Returns: + * OK on success + * A negated errno value on invalid port + * + * To-Do: Auto Power Disable + ****************************************************************************/ + +int stm32f0_unconfiggpio(uint32_t cfgset) +{ + /* Reuse port and pin number and set it to default HiZ INPUT */ + + cfgset &= GPIO_PORT_MASK | GPIO_PIN_MASK; + cfgset |= GPIO_INPUT | GPIO_FLOAT; + + /* To-Do: Mark its unuse for automatic power saving options */ + + return stm32f0_configgpio(cfgset); +} + +/**************************************************************************** + * Name: stm32f0_gpiowrite + * + * Description: + * Write one or zero to the selected GPIO pin + * + ****************************************************************************/ + +void stm32f0_gpiowrite(uint32_t pinset, bool value) +{ + uint32_t base; + uint32_t bit; + unsigned int port; + unsigned int pin; + + port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT; + if (port < STM32F0_NPORTS) + { + /* Get the port base address */ + + base = g_gpiobase[port]; + + /* Get the pin number */ + + pin = (pinset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT; + + /* Set or clear the output on the pin */ + + if (value) + { + bit = GPIO_BSRR_SET(pin); + } + else + { + bit = GPIO_BSRR_RESET(pin); + } + + putreg32(bit, base + STM32F0_GPIO_BSRR_OFFSET); + + } +} + +/**************************************************************************** + * Name: stm32f0_gpioread + * + * Description: + * Read one or zero from the selected GPIO pin + * + ****************************************************************************/ + +bool stm32f0_gpioread(uint32_t pinset) +{ + uint32_t base; + unsigned int port; + unsigned int pin; + + port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT; + if (port < STM32F0_NPORTS) + { + /* Get the port base address */ + + base = g_gpiobase[port]; + + /* Get the pin number and return the input state of that pin */ + + pin = (pinset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT; + return ((getreg32(base + STM32F0_GPIO_IDR_OFFSET) & (1 << pin)) != 0); + } + + return 0; +} diff --git a/arch/arm/src/stm32f0/stm32f0_gpio.h b/arch/arm/src/stm32f0/stm32f0_gpio.h new file mode 100644 index 0000000000..2aeb05da6e --- /dev/null +++ b/arch/arm/src/stm32f0/stm32f0_gpio.h @@ -0,0 +1,378 @@ +/************************************************************************************ + * arch/arm/src/stm32f0/stm32f0_gpio.h + * + * Copyright (C) 2009, 2011-2012, 2015 Gregory Nutt. All rights reserved. + * Copyright (C) 2015-2016 Sebastien Lorquet. All rights reserved. + * Author: Gregory Nutt + * Sebastien Lorquet + * + * 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 __ARCH_ARM_SRC_STM32F0_STM32F0_GPIO_H +#define __ARCH_ARM_SRC_STM32F0_STM32F0_GPIO_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#ifndef __ASSEMBLY__ +# include +# include +#endif + +#include +#include + +#include "chip.h" + +#if defined(CONFIG_STM32F0_STM32F05X) +# include "chip/stm32f05xr_pinmap.h" +#else +# error "Unsupported STM32F0 chip" +#endif + +/************************************************************************************ + * Pre-Processor Declarations + ************************************************************************************/ + +/* Bit-encoded input to stm32f0_configgpio() */ + +/* Each port bit of the general-purpose I/O (GPIO) ports can be individually configured + * by software in several modes: + * + * - Input floating + * - Input pull-up + * - Input-pull-down + * - Output open-drain with pull-up or pull-down capability + * - Output push-pull with pull-up or pull-down capability + * - Alternate function push-pull with pull-up or pull-down capability + * - Alternate function open-drain with pull-up or pull-down capability + * - Analog + * + * 20-bit Encoding: 1111 1111 1100 0000 0000 + * 9876 5432 1098 7654 3210 + * ---- ---- ---- ---- ---- + * Inputs: MMUU .... ...X PPPP BBBB + * Outputs: MMUU .... FFOV PPPP BBBB + * Alternate Functions: MMUU AAAA FFO. PPPP BBBB + * Analog: MM.. .... .... PPPP BBBB + */ + +/* Mode: + * + * 1111 1111 1100 0000 0000 + * 9876 5432 1098 7654 3210 + * ---- ---- ---- ---- ---- + * MM.. .... .... .... .... + */ + +#define GPIO_MODE_SHIFT (18) /* Bits 18-19: GPIO port mode */ +#define GPIO_MODE_MASK (3 << GPIO_MODE_SHIFT) +# define GPIO_INPUT (0 << GPIO_MODE_SHIFT) /* Input mode */ +# define GPIO_OUTPUT (1 << GPIO_MODE_SHIFT) /* General purpose output mode */ +# define GPIO_ALT (2 << GPIO_MODE_SHIFT) /* Alternate function mode */ +# define GPIO_ANALOG (3 << GPIO_MODE_SHIFT) /* Analog mode */ + +/* Input/output pull-ups/downs (not used with analog): + * + * 1111 1111 1100 0000 0000 + * 9876 5432 1098 7654 3210 + * ---- ---- ---- ---- ---- + * ..UU .... .... .... .... + */ + +#define GPIO_PUPD_SHIFT (16) /* Bits 16-17: Pull-up/pull down */ +#define GPIO_PUPD_MASK (3 << GPIO_PUPD_SHIFT) +# define GPIO_FLOAT (0 << GPIO_PUPD_SHIFT) /* No pull-up, pull-down */ +# define GPIO_PULLUP (1 << GPIO_PUPD_SHIFT) /* Pull-up */ +# define GPIO_PULLDOWN (2 << GPIO_PUPD_SHIFT) /* Pull-down */ + +/* Alternate Functions: + * + * 1111 1111 1100 0000 0000 + * 9876 5432 1098 7654 3210 + * ---- ---- ---- ---- ---- + * .... AAAA .... .... .... + */ + +#define GPIO_AF_SHIFT (12) /* Bits 12-15: Alternate function */ +#define GPIO_AF_MASK (15 << GPIO_AF_SHIFT) +# define GPIO_AF(n) ((n) << GPIO_AF_SHIFT) +# define GPIO_AF0 (0 << GPIO_AF_SHIFT) +# define GPIO_AF1 (1 << GPIO_AF_SHIFT) +# define GPIO_AF2 (2 << GPIO_AF_SHIFT) +# define GPIO_AF3 (3 << GPIO_AF_SHIFT) +# define GPIO_AF4 (4 << GPIO_AF_SHIFT) +# define GPIO_AF5 (5 << GPIO_AF_SHIFT) +# define GPIO_AF6 (6 << GPIO_AF_SHIFT) +# define GPIO_AF7 (7 << GPIO_AF_SHIFT) +# define GPIO_AF8 (8 << GPIO_AF_SHIFT) +# define GPIO_AF9 (9 << GPIO_AF_SHIFT) +# define GPIO_AF10 (10 << GPIO_AF_SHIFT) +# define GPIO_AF11 (11 << GPIO_AF_SHIFT) +# define GPIO_AF12 (12 << GPIO_AF_SHIFT) +# define GPIO_AF13 (13 << GPIO_AF_SHIFT) +# define GPIO_AF14 (14 << GPIO_AF_SHIFT) +# define GPIO_AF15 (15 << GPIO_AF_SHIFT) + +/* Output/Alt function frequency selection: + * + * 1111 1111 1100 0000 0000 + * 9876 5432 1098 7654 3210 + * ---- ---- ---- ---- ---- + * .... .... FF.. .... .... + */ + +#define GPIO_SPEED_SHIFT (10) /* Bits 10-11: GPIO frequency selection */ +#define GPIO_SPEED_MASK (3 << GPIO_SPEED_SHIFT) +# define GPIO_SPEED_2MHz (0 << GPIO_SPEED_SHIFT) /* 2 MHz Low speed output */ +# define GPIO_SPEED_10MHz (1 << GPIO_SPEED_SHIFT) /* 10 MHz Medium speed output */ +# define GPIO_SPEED_50MHz (2 << GPIO_SPEED_SHIFT) /* 50 MHz High speed output */ + +/* Output/Alt function type selection: + * + * 1111 1111 1100 0000 0000 + * 9876 5432 1098 7654 3210 + * ---- ---- ---- ---- ---- + * .... .... ..O. .... .... + */ + +#define GPIO_OPENDRAIN (1 << 9) /* Bit9: 1=Open-drain output */ +#define GPIO_PUSHPULL (0) /* Bit9: 0=Push-pull output */ + +/* If the pin is a GPIO digital output, then this identifies the initial output value. + * If the pin is an input, this bit is overloaded to provide the qualifier to + * distinquish input pull-up and -down: + * + * 1111 1111 1100 0000 0000 + * 9876 5432 1098 7654 3210 + * ---- ---- ---- ---- ---- + * .... .... ...V .... .... + */ + +#define GPIO_OUTPUT_SET (1 << 8) /* Bit 8: If output, inital value of output */ +#define GPIO_OUTPUT_CLEAR (0) + +/* External interrupt selection (GPIO inputs only): + * + * 1111 1111 1100 0000 0000 + * 9876 5432 1098 7654 3210 + * ---- ---- ---- ---- ---- + * .... .... ...X .... .... + */ + +#define GPIO_EXTI (1 << 8) /* Bit 8: Configure as EXTI interrupt */ + +/* This identifies the GPIO port: + * + * 1111 1111 1100 0000 0000 + * 9876 5432 1098 7654 3210 + * ---- ---- ---- ---- ---- + * .... .... .... PPPP .... + */ + +#define GPIO_PORT_SHIFT (4) /* Bit 4-7: Port number */ +#define GPIO_PORT_MASK (15 << GPIO_PORT_SHIFT) +# define GPIO_PORTA (0 << GPIO_PORT_SHIFT) /* GPIOA */ +# define GPIO_PORTB (1 << GPIO_PORT_SHIFT) /* GPIOB */ +# define GPIO_PORTC (2 << GPIO_PORT_SHIFT) /* GPIOC */ +# define GPIO_PORTD (3 << GPIO_PORT_SHIFT) /* GPIOD */ +# define GPIO_PORTE (4 << GPIO_PORT_SHIFT) /* GPIOE */ +# define GPIO_PORTF (5 << GPIO_PORT_SHIFT) /* GPIOF */ +# define GPIO_PORTG (6 << GPIO_PORT_SHIFT) /* GPIOG */ +# define GPIO_PORTH (7 << GPIO_PORT_SHIFT) /* GPIOH */ + +/* This identifies the bit in the port: + * + * 1111 1111 1100 0000 0000 + * 9876 5432 1098 7654 3210 + * ---- ---- ---- ---- ---- + * .... .... .... .... BBBB + */ + +#define GPIO_PIN_SHIFT (0) /* Bits 0-3: GPIO number: 0-15 */ +#define GPIO_PIN_MASK (15 << GPIO_PIN_SHIFT) +# define GPIO_PIN0 (0 << GPIO_PIN_SHIFT) +# define GPIO_PIN1 (1 << GPIO_PIN_SHIFT) +# define GPIO_PIN2 (2 << GPIO_PIN_SHIFT) +# define GPIO_PIN3 (3 << GPIO_PIN_SHIFT) +# define GPIO_PIN4 (4 << GPIO_PIN_SHIFT) +# define GPIO_PIN5 (5 << GPIO_PIN_SHIFT) +# define GPIO_PIN6 (6 << GPIO_PIN_SHIFT) +# define GPIO_PIN7 (7 << GPIO_PIN_SHIFT) +# define GPIO_PIN8 (8 << GPIO_PIN_SHIFT) +# define GPIO_PIN9 (9 << GPIO_PIN_SHIFT) +# define GPIO_PIN10 (10 << GPIO_PIN_SHIFT) +# define GPIO_PIN11 (11 << GPIO_PIN_SHIFT) +# define GPIO_PIN12 (12 << GPIO_PIN_SHIFT) +# define GPIO_PIN13 (13 << GPIO_PIN_SHIFT) +# define GPIO_PIN14 (14 << GPIO_PIN_SHIFT) +# define GPIO_PIN15 (15 << GPIO_PIN_SHIFT) + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/* Base addresses for each GPIO block */ + +EXTERN const uint32_t g_gpiobase[STM32F0_NPORTS]; + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32f0_configgpio + * + * Description: + * Configure a GPIO pin based on bit-encoded description of the pin. + * Once it is configured as Alternative (GPIO_ALT|GPIO_CNF_AFPP|...) + * function, it must be unconfigured with stm32f0_unconfiggpio() with + * the same cfgset first before it can be set to non-alternative function. + * + * Returns: + * OK on success + * ERROR on invalid port, or when pin is locked as ALT function. + * + ************************************************************************************/ + +int stm32f0_configgpio(uint32_t cfgset); + +/************************************************************************************ + * Name: stm32f0_unconfiggpio + * + * Description: + * Unconfigure a GPIO pin based on bit-encoded description of the pin, set it + * into default HiZ state (and possibly mark it's unused) and unlock it whether + * it was previsouly selected as alternative function (GPIO_ALT|GPIO_CNF_AFPP|...). + * + * This is a safety function and prevents hardware from schocks, as unexpected + * write to the Timer Channel Output GPIO to fixed '1' or '0' while it should + * operate in PWM mode could produce excessive on-board currents and trigger + * over-current/alarm function. + * + * Returns: + * OK on success + * ERROR on invalid port + * + ************************************************************************************/ + +int stm32f0_unconfiggpio(uint32_t cfgset); + +/************************************************************************************ + * Name: stm32f0_gpiowrite + * + * Description: + * Write one or zero to the selected GPIO pin + * + ************************************************************************************/ + +void stm32f0_gpiowrite(uint32_t pinset, bool value); + +/************************************************************************************ + * Name: stm32f0_gpioread + * + * Description: + * Read one or zero from the selected GPIO pin + * + ************************************************************************************/ + +bool stm32f0_gpioread(uint32_t pinset); + +/************************************************************************************ + * Name: stm32f0_gpiosetevent + * + * Description: + * Sets/clears GPIO based event and interrupt triggers. + * + * Input Parameters: + * pinset - GPIO pin configuration + * risingedge - Enables interrupt on rising edges + * fallingedge - Enables interrupt on falling edges + * event - Generate event when set + * func - When non-NULL, generate interrupt + * arg - Argument passed to the interrupt callback + * + * Returned Value: + * Zero (OK) is returned on success, otherwise a negated errno value is returned + * to indicate the nature of the failure. + * + ************************************************************************************/ + +int stm32f0_gpiosetevent(uint32_t pinset, bool risingedge, bool fallingedge, + bool event, xcpt_t func, void *arg); + +/************************************************************************************ + * Function: stm32f0_dumpgpio + * + * Description: + * Dump all GPIO registers associated with the provided base address + * + ************************************************************************************/ + +#ifdef CONFIG_DEBUG_FEATURES +int stm32f0_dumpgpio(uint32_t pinset, const char *msg); +#else +# define stm32f0_dumpgpio(p,m) +#endif + +/************************************************************************************ + * Function: stm32f0_gpioinit + * + * Description: + * Based on configuration within the .config file, it does: + * - Remaps positions of alternative functions. + * + * Typically called from stm32f0_start(). + * + ************************************************************************************/ + +void stm32f0_gpioinit(void); + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __ARCH_ARM_SRC_STM32F0_STM32F0_GPIO_H */ diff --git a/arch/arm/src/stm32f0/stm32f0_idle.c b/arch/arm/src/stm32f0/stm32f0_idle.c new file mode 100644 index 0000000000..10293fe308 --- /dev/null +++ b/arch/arm/src/stm32f0/stm32f0_idle.c @@ -0,0 +1,110 @@ +/**************************************************************************** + * arch/arm/src/stm32f0/stm32f0_idle.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include + +#include "up_internal.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Does the board support an IDLE LED to indicate that the board is in the + * IDLE state? + */ + +#if defined(CONFIG_ARCH_LEDS) && defined(LED_IDLE) +# define BEGIN_IDLE() board_autoled_on(LED_IDLE) +# define END_IDLE() board_autoled_off(LED_IDLE) +#else +# define BEGIN_IDLE() +# define END_IDLE() +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_idle + * + * Description: + * up_idle() is the logic that will be executed when their is no other + * ready-to-run task. This is processor idle time and will continue until + * some interrupt occurs to cause a context switch from the idle task. + * + * Processing in this state may be processor-specific. e.g., this is where + * power management operations might be performed. + * + ****************************************************************************/ + +void up_idle(void) +{ +#if defined(CONFIG_SUPPRESS_INTERRUPTS) || defined(CONFIG_SUPPRESS_TIMER_INTS) + /* If the system is idle and there are no timer interrupts, then process + * "fake" timer interrupts. Hopefully, something will wake up. + */ + + sched_process_timer(); +#else + +/* If the g_dma_inprogress is zero, then there is no DMA in progress. This + * value is needed in the IDLE loop to determine if the IDLE loop should + * go into lower power power consumption modes. According to the LPC17xx + * User Manual: "The DMA controller can continue to work in Sleep mode, and + * has access to the peripheral SRAMs and all peripheral registers. The + * flash memory and the Main SRAM are not available in Sleep mode, they are + * disabled in order to save power." + */ + +#ifdef CONFIG_STM32F0_GPDMA + if (g_dma_inprogress == 0) +#endif + { + /* Sleep until an interrupt occurs in order to save power */ + + BEGIN_IDLE(); + asm("WFI"); + END_IDLE(); + } +#endif +} diff --git a/arch/arm/src/stm32f0/stm32f0_irq.c b/arch/arm/src/stm32f0/stm32f0_irq.c new file mode 100644 index 0000000000..c3f5607370 --- /dev/null +++ b/arch/arm/src/stm32f0/stm32f0_irq.c @@ -0,0 +1,340 @@ +/**************************************************************************** + * arch/arm/src/stm32f0/stm32f0_irq.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include +#include +#include + +#include "nvic.h" +#include "up_arch.h" +#include "up_internal.h" + +//#include "stm32f0_irq.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Get a 32-bit version of the default priority */ + +#define DEFPRIORITY32 \ + (NVIC_SYSH_PRIORITY_DEFAULT << 24 | NVIC_SYSH_PRIORITY_DEFAULT << 16 | \ + NVIC_SYSH_PRIORITY_DEFAULT << 8 | NVIC_SYSH_PRIORITY_DEFAULT) + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/* g_current_regs[] holds a references to the current interrupt level + * register storage structure. If is non-NULL only during interrupt + * processing. Access to g_current_regs[] must be through the macro + * CURRENT_REGS for portability. + */ + +volatile uint32_t *g_current_regs[1]; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32f0_dumpnvic + * + * Description: + * Dump some interesting NVIC registers + * + ****************************************************************************/ + +#if defined(CONFIG_DEBUG_IRQ_INFO) +static void stm32f0_dumpnvic(const char *msg, int irq) +{ + irqstate_t flags; + + flags = enter_critical_section(); + + irqinfo("NVIC (%s, irq=%d):\n", msg, irq); + irqinfo(" ISER: %08x ICER: %08x\n", + getreg32(ARMV6M_NVIC_ISER), getreg32(ARMV6M_NVIC_ICER)); + irqinfo(" ISPR: %08x ICPR: %08x\n", + getreg32(ARMV6M_NVIC_ISPR), getreg32(ARMV6M_NVIC_ICPR)); + irqinfo(" IRQ PRIO: %08x %08x %08x %08x\n", + getreg32(ARMV6M_NVIC_IPR0), getreg32(ARMV6M_NVIC_IPR1), + getreg32(ARMV6M_NVIC_IPR2), getreg32(ARMV6M_NVIC_IPR3)); + irqinfo(" %08x %08x %08x %08x\n", + getreg32(ARMV6M_NVIC_IPR4), getreg32(ARMV6M_NVIC_IPR5), + getreg32(ARMV6M_NVIC_IPR6), getreg32(ARMV6M_NVIC_IPR7)); + + irqinfo("SYSCON:\n"); + irqinfo(" CPUID: %08x\n", + getreg32(ARMV6M_SYSCON_CPUID)); + irqinfo(" ICSR: %08x AIRCR: %08x\n", + getreg32(ARMV6M_SYSCON_ICSR), getreg32(ARMV6M_SYSCON_AIRCR)); + irqinfo(" SCR: %08x CCR: %08x\n", + getreg32(ARMV6M_SYSCON_SCR), getreg32(ARMV6M_SYSCON_CCR)); + irqinfo(" SHPR2: %08x SHPR3: %08x\n", + getreg32(ARMV6M_SYSCON_SHPR2), getreg32(ARMV6M_SYSCON_SHPR3)); + + leave_critical_section(flags); +} + +#else +# define stm32f0_dumpnvic(msg, irq) +#endif + +/**************************************************************************** + * Name: stm32f0_nmi, stm32f0_busfault, stm32f0_usagefault, stm32f0_pendsv, + * stm32f0_dbgmonitor, stm32f0_pendsv, stm32f0_reserved + * + * Description: + * Handlers for various execptions. None are handled and all are fatal + * error conditions. The only advantage these provided over the default + * unexpected interrupt handler is that they provide a diagnostic output. + * + ****************************************************************************/ + +#ifdef CONFIG_DEBUG_FEATURES +static int stm32f0_nmi(int irq, FAR void *context, FAR void *arg) +{ + (void)up_irq_save(); + _err("PANIC!!! NMI received\n"); + PANIC(); + return 0; +} + +static int stm32f0_pendsv(int irq, FAR void *context, FAR void *arg) +{ + (void)up_irq_save(); + _err("PANIC!!! PendSV received\n"); + PANIC(); + return 0; +} + +static int stm32f0_reserved(int irq, FAR void *context, FAR void *arg) +{ + (void)up_irq_save(); + _err("PANIC!!! Reserved interrupt\n"); + PANIC(); + return 0; +} +#endif + +/**************************************************************************** + * Name: stm32f0_clrpend + * + * Description: + * Clear a pending interrupt at the NVIC. + * + ****************************************************************************/ + +static inline void stm32f0_clrpend(int irq) +{ + /* This will be called on each interrupt exit whether the interrupt can be + * enambled or not. So this assertion is necessarily lame. + */ + + DEBUGASSERT((unsigned)irq < NR_IRQS); + + /* Check for an external interrupt */ + + if (irq >= STM32F0_IRQ_EXTINT && irq < (STM32F0_IRQ_EXTINT + 32)) + { + /* Set the appropriate bit in the ISER register to enable the + * interrupt + */ + + putreg32((1 << (irq - STM32F0_IRQ_EXTINT)), ARMV6M_NVIC_ICPR); + } +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_irqinitialize + ****************************************************************************/ + +void up_irqinitialize(void) +{ + uint32_t regaddr; + int i; + + /* Disable all interrupts */ + + putreg32(0xffffffff, ARMV6M_NVIC_ICER); + + /* Set all interrupts (and exceptions) to the default priority */ + + putreg32(DEFPRIORITY32, ARMV6M_SYSCON_SHPR2); + putreg32(DEFPRIORITY32, ARMV6M_SYSCON_SHPR3); + + /* Now set all of the interrupt lines to the default priority */ + + for (i = 0; i < 8; i++) + { + regaddr = ARMV6M_NVIC_IPR(i); + putreg32(DEFPRIORITY32, regaddr); + } + + /* currents_regs is non-NULL only while processing an interrupt */ + + CURRENT_REGS = NULL; + + /* Attach the SVCall and Hard Fault exception handlers. The SVCall + * exception is used for performing context switches; The Hard Fault + * must also be caught because a SVCall may show up as a Hard Fault + * under certain conditions. + */ + + irq_attach(STM32F0_IRQ_SVCALL, up_svcall, NULL); + irq_attach(STM32F0_IRQ_HARDFAULT, up_hardfault, NULL); + + /* Attach all other processor exceptions (except reset and sys tick) */ + +#ifdef CONFIG_DEBUG_FEATURES + irq_attach(STM32F0_IRQ_NMI, stm32f0_nmi, NULL); + irq_attach(STM32F0_IRQ_PENDSV, stm32f0_pendsv, NULL); + irq_attach(STM32F0_IRQ_RESERVED, stm32f0_reserved, NULL); +#endif + + stm32f0_dumpnvic("initial", NR_IRQS); + + /* Initialize logic to support a second level of interrupt decoding for + * configured pin interrupts. + */ + +#ifdef CONFIG_STM32F0_GPIOIRQ + stm32f0_gpioirqinitialize(); +#endif + +#ifndef CONFIG_SUPPRESS_INTERRUPTS + + /* And finally, enable interrupts */ + + up_irq_enable(); +#endif +} + +/**************************************************************************** + * Name: up_disable_irq + * + * Description: + * Disable the IRQ specified by 'irq' + * + ****************************************************************************/ + +void up_disable_irq(int irq) +{ + DEBUGASSERT((unsigned)irq < NR_IRQS); + + /* Check for an external interrupt */ + + if (irq >= STM32F0_IRQ_EXTINT && irq < (STM32F0_IRQ_EXTINT + 32)) + { + /* Set the appropriate bit in the ICER register to disable the + * interrupt + */ + + putreg32((1 << (irq - STM32F0_IRQ_EXTINT)), ARMV6M_NVIC_ICER); + } + + /* Handle processor exceptions. Only SysTick can be disabled */ + + else if (irq == STM32F0_IRQ_SYSTICK) + { + modifyreg32(ARMV6M_SYSTICK_CSR, SYSTICK_CSR_ENABLE, 0); + } + + stm32f0_dumpnvic("disable", irq); +} + +/**************************************************************************** + * Name: up_enable_irq + * + * Description: + * Enable the IRQ specified by 'irq' + * + ****************************************************************************/ + +void up_enable_irq(int irq) +{ + /* This will be called on each interrupt exit whether the interrupt can be + * enabled or not. So this assertion is necessarily lame. + */ + + DEBUGASSERT((unsigned)irq < NR_IRQS); + + /* Check for external interrupt */ + + if (irq >= STM32F0_IRQ_EXTINT && irq < (STM32F0_IRQ_EXTINT + 32)) + { + /* Set the appropriate bit in the ISER register to enable the + * interrupt + */ + + putreg32((1 << (irq - STM32F0_IRQ_EXTINT)), ARMV6M_NVIC_ISER); + } + + /* Handle processor exceptions. Only SysTick can be disabled */ + + else if (irq == STM32F0_IRQ_SYSTICK) + { + modifyreg32(ARMV6M_SYSTICK_CSR, 0, SYSTICK_CSR_ENABLE); + } + + stm32f0_dumpnvic("enable", irq); +} + +/**************************************************************************** + * Name: up_ack_irq + * + * Description: + * Acknowledge the IRQ + * + ****************************************************************************/ + +void up_ack_irq(int irq) +{ + stm32f0_clrpend(irq); +} diff --git a/arch/arm/src/stm32f0/stm32f0_lowputc.c b/arch/arm/src/stm32f0/stm32f0_lowputc.c new file mode 100644 index 0000000000..b4a276ba89 --- /dev/null +++ b/arch/arm/src/stm32f0/stm32f0_lowputc.c @@ -0,0 +1,366 @@ +/**************************************************************************** + * arch/arm/src/stm32f0/stm32f0_lowputc.c + * + * Copyright (C) 2009, 2012 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include + +#include "up_internal.h" +#include "up_arch.h" + +#include "chip.h" + +#include "stm32f0_rcc.h" +#include "stm32f0_gpio.h" +#include "stm32f0_uart.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Select USART parameters for the selected console */ + +#ifdef HAVE_CONSOLE +# if defined(CONFIG_USART1_SERIAL_CONSOLE) +# define STM32F0_CONSOLE_BASE STM32F0_USART1_BASE +# define STM32F0_APBCLOCK STM32F0_PCLK2_FREQUENCY +# define STM32F0_CONSOLE_APBREG STM32F0_RCC_APB2ENR +# define STM32F0_CONSOLE_APBEN RCC_APB2ENR_USART1EN +# define STM32F0_CONSOLE_BAUD CONFIG_USART1_BAUD +# define STM32F0_CONSOLE_BITS CONFIG_USART1_BITS +# define STM32F0_CONSOLE_PARITY CONFIG_USART1_PARITY +# define STM32F0_CONSOLE_2STOP CONFIG_USART1_2STOP +# define STM32F0_CONSOLE_TX GPIO_USART1_TX +# define STM32F0_CONSOLE_RX GPIO_USART1_RX +# ifdef CONFIG_USART1_RS485 +# define STM32F0_CONSOLE_RS485_DIR GPIO_USART1_RS485_DIR +# if (CONFIG_USART1_RS485_DIR_POLARITY == 0) +# define STM32F0_CONSOLE_RS485_DIR_POLARITY false +# else +# define STM32F0_CONSOLE_RS485_DIR_POLARITY true +# endif +# endif +# elif defined(CONFIG_USART2_SERIAL_CONSOLE) +# define STM32F0_CONSOLE_BASE STM32F0_USART2_BASE +# define STM32F0_APBCLOCK STM32F0_PCLK1_FREQUENCY +# define STM32F0_CONSOLE_APBREG STM32F0_RCC_APB1ENR1 +# define STM32F0_CONSOLE_APBEN RCC_APB1ENR1_USART2EN +# define STM32F0_CONSOLE_BAUD CONFIG_USART2_BAUD +# define STM32F0_CONSOLE_BITS CONFIG_USART2_BITS +# define STM32F0_CONSOLE_PARITY CONFIG_USART2_PARITY +# define STM32F0_CONSOLE_2STOP CONFIG_USART2_2STOP +# define STM32F0_CONSOLE_TX GPIO_USART2_TX +# define STM32F0_CONSOLE_RX GPIO_USART2_RX +# ifdef CONFIG_USART2_RS485 +# define STM32F0_CONSOLE_RS485_DIR GPIO_USART2_RS485_DIR +# if (CONFIG_USART2_RS485_DIR_POLARITY == 0) +# define STM32F0_CONSOLE_RS485_DIR_POLARITY false +# else +# define STM32F0_CONSOLE_RS485_DIR_POLARITY true +# endif +# endif +# elif defined(CONFIG_USART3_SERIAL_CONSOLE) +# define STM32F0_CONSOLE_BASE STM32F0_USART3_BASE +# define STM32F0_APBCLOCK STM32F0_PCLK1_FREQUENCY +# define STM32F0_CONSOLE_APBREG STM32F0_RCC_APB1ENR1 +# define STM32F0_CONSOLE_APBEN RCC_APB1ENR1_USART3EN +# define STM32F0_CONSOLE_BAUD CONFIG_USART3_BAUD +# define STM32F0_CONSOLE_BITS CONFIG_USART3_BITS +# define STM32F0_CONSOLE_PARITY CONFIG_USART3_PARITY +# define STM32F0_CONSOLE_2STOP CONFIG_USART3_2STOP +# define STM32F0_CONSOLE_TX GPIO_USART3_TX +# define STM32F0_CONSOLE_RX GPIO_USART3_RX +# ifdef CONFIG_USART3_RS485 +# define STM32F0_CONSOLE_RS485_DIR GPIO_USART3_RS485_DIR +# if (CONFIG_USART3_RS485_DIR_POLARITY == 0) +# define STM32F0_CONSOLE_RS485_DIR_POLARITY false +# else +# define STM32F0_CONSOLE_RS485_DIR_POLARITY true +# endif +# endif +# elif defined(CONFIG_UART4_SERIAL_CONSOLE) +# define STM32F0_CONSOLE_BASE STM32F0_UART4_BASE +# define STM32F0_APBCLOCK STM32F0_PCLK1_FREQUENCY +# define STM32F0_CONSOLE_APBREG STM32F0_RCC_APB1ENR1 +# define STM32F0_CONSOLE_APBEN RCC_APB1ENR1_UART4EN +# define STM32F0_CONSOLE_BAUD CONFIG_UART4_BAUD +# define STM32F0_CONSOLE_BITS CONFIG_UART4_BITS +# define STM32F0_CONSOLE_PARITY CONFIG_UART4_PARITY +# define STM32F0_CONSOLE_2STOP CONFIG_UART4_2STOP +# define STM32F0_CONSOLE_TX GPIO_UART4_TX +# define STM32F0_CONSOLE_RX GPIO_UART4_RX +# ifdef CONFIG_UART4_RS485 +# define STM32F0_CONSOLE_RS485_DIR GPIO_UART4_RS485_DIR +# if (CONFIG_UART4_RS485_DIR_POLARITY == 0) +# define STM32F0_CONSOLE_RS485_DIR_POLARITY false +# else +# define STM32F0_CONSOLE_RS485_DIR_POLARITY true +# endif +# endif +# elif defined(CONFIG_UART5_SERIAL_CONSOLE) +# define STM32F0_CONSOLE_BASE STM32F0_UART5_BASE +# define STM32F0_APBCLOCK STM32F0_PCLK1_FREQUENCY +# define STM32F0_CONSOLE_APBREG STM32F0_RCC_APB1ENR1 +# define STM32F0_CONSOLE_APBEN RCC_APB1ENR1_UART5EN +# define STM32F0_CONSOLE_BAUD CONFIG_UART5_BAUD +# define STM32F0_CONSOLE_BITS CONFIG_UART5_BITS +# define STM32F0_CONSOLE_PARITY CONFIG_UART5_PARITY +# define STM32F0_CONSOLE_2STOP CONFIG_UART5_2STOP +# define STM32F0_CONSOLE_TX GPIO_UART5_TX +# define STM32F0_CONSOLE_RX GPIO_UART5_RX +# ifdef CONFIG_UART5_RS485 +# define STM32F0_CONSOLE_RS485_DIR GPIO_UART5_RS485_DIR +# if (CONFIG_UART5_RS485_DIR_POLARITY == 0) +# define STM32F0_CONSOLE_RS485_DIR_POLARITY false +# else +# define STM32F0_CONSOLE_RS485_DIR_POLARITY true +# endif +# endif +# endif + + /* CR1 settings */ + +# if STM32F0_CONSOLE_BITS == 9 +# define USART_CR1_M0_VALUE USART_CR1_M0 +# define USART_CR1_M1_VALUE 0 +# elif STM32F0_CONSOLE_BITS == 7 +# define USART_CR1_M0_VALUE 0 +# define USART_CR1_M1_VALUE USART_CR1_M1 +# else /* 8 bits */ +# define USART_CR1_M0_VALUE 0 +# define USART_CR1_M1_VALUE 0 +# endif + +# if STM32F0_CONSOLE_PARITY == 1 /* odd parity */ +# define USART_CR1_PARITY_VALUE (USART_CR1_PCE|USART_CR1_PS) +# elif STM32F0_CONSOLE_PARITY == 2 /* even parity */ +# define USART_CR1_PARITY_VALUE USART_CR1_PCE +# else /* no parity */ +# define USART_CR1_PARITY_VALUE 0 +# endif + +# define USART_CR1_CLRBITS \ + (USART_CR1_UESM | USART_CR1_RE | USART_CR1_TE | USART_CR1_PS | \ + USART_CR1_PCE | USART_CR1_WAKE | USART_CR1_M0 | USART_CR1_M1 | \ + USART_CR1_MME | USART_CR1_OVER8 | USART_CR1_DEDT_MASK | \ + USART_CR1_DEAT_MASK | USART_CR1_ALLINTS) + +# define USART_CR1_SETBITS (USART_CR1_M0_VALUE|USART_CR1_M1_VALUE|USART_CR1_PARITY_VALUE) + + /* CR2 settings */ + +# if STM32F0_CONSOLE_2STOP != 0 +# define USART_CR2_STOP2_VALUE USART_CR2_STOP2 +# else +# define USART_CR2_STOP2_VALUE 0 +# endif + +# define USART_CR2_CLRBITS \ + (USART_CR2_ADDM7 | USART_CR2_LBDL | USART_CR2_LBDIE | USART_CR2_LBCL | \ + USART_CR2_CPHA | USART_CR2_CPOL | USART_CR2_CLKEN | USART_CR2_STOP_MASK | \ + USART_CR2_LINEN | USART_CR2_SWAP | USART_CR2_RXINV | USART_CR2_TXINV | \ + USART_CR2_DATAINV | USART_CR2_MSBFIRST | USART_CR2_ABREN | \ + USART_CR2_ABRMOD_MASK | USART_CR2_RTOEN | USART_CR2_ADD_MASK) + +# define USART_CR2_SETBITS USART_CR2_STOP2_VALUE + + /* CR3 settings */ + +# define USART_CR3_CLRBITS \ + (USART_CR3_EIE | USART_CR3_IREN | USART_CR3_IRLP | USART_CR3_HDSEL | \ + USART_CR3_NACK | USART_CR3_SCEN | USART_CR3_DMAR | USART_CR3_DMAT | \ + USART_CR3_RTSE | USART_CR3_CTSE | USART_CR3_CTSIE | USART_CR3_ONEBIT | \ + USART_CR3_OVRDIS | USART_CR3_DDRE | USART_CR3_DEM | USART_CR3_DEP | \ + USART_CR3_SCARCNT2_MASK | USART_CR3_WUS_MASK | USART_CR3_WUFIE) + +# define USART_CR3_SETBITS 0 + +# undef USE_OVER8 + + /* Calculate USART BAUD rate divider */ + + /* Baud rate for standard USART (SPI mode included): + * + * In case of oversampling by 16, the equation is: + * baud = fCK / UARTDIV + * UARTDIV = fCK / baud + * + * In case of oversampling by 8, the equation is: + * + * baud = 2 * fCK / UARTDIV + * UARTDIV = 2 * fCK / baud + */ + +# define STM32F0_USARTDIV8 \ + (((STM32F0_APBCLOCK << 1) + (STM32F0_CONSOLE_BAUD >> 1)) / STM32F0_CONSOLE_BAUD) +# define STM32F0_USARTDIV16 \ + ((STM32F0_APBCLOCK + (STM32F0_CONSOLE_BAUD >> 1)) / STM32F0_CONSOLE_BAUD) + + /* Use oversamply by 8 only if the divisor is small. But what is small? */ + +# if STM32F0_USARTDIV8 > 100 +# define STM32F0_BRR_VALUE STM32F0_USARTDIV16 +# else +# define USE_OVER8 1 +# define STM32F0_BRR_VALUE \ + ((STM32F0_USARTDIV8 & 0xfff0) | ((STM32F0_USARTDIV8 & 0x000f) >> 1)) +# endif + +#endif /* HAVE_CONSOLE */ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_lowputc + * + * Description: + * Output one byte on the serial console + * + ****************************************************************************/ + +void up_lowputc(char ch) +{ +#ifdef HAVE_CONSOLE + /* Wait until the TX data register is empty */ + + while ((getreg32(STM32F0_CONSOLE_BASE + STM32F0_USART_ISR_OFFSET) & USART_ISR_TXE) == 0); +#ifdef STM32F0_CONSOLE_RS485_DIR + stm32f0_gpiowrite(STM32F0_CONSOLE_RS485_DIR, STM32F0_CONSOLE_RS485_DIR_POLARITY); +#endif + + /* Then send the character */ + + putreg32((uint32_t)ch, STM32F0_CONSOLE_BASE + STM32F0_USART_TDR_OFFSET); + +#ifdef STM32F0_CONSOLE_RS485_DIR + while ((getreg32(STM32F0_CONSOLE_BASE + STM32F0_USART_ISR_OFFSET) & USART_ISR_TC) == 0); + stm32f0_gpiowrite(STM32F0_CONSOLE_RS485_DIR, !STM32F0_CONSOLE_RS485_DIR_POLARITY); +#endif + +#endif /* HAVE_CONSOLE */ +} + +/**************************************************************************** + * Name: stm32f0_lowsetup + * + * Description: + * This performs basic initialization of the USART used for the serial + * console. Its purpose is to get the console output availabe as soon + * as possible. + * + ****************************************************************************/ + +void stm32f0_lowsetup(void) +{ +#if defined(HAVE_UART) +#if defined(HAVE_CONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG) + uint32_t cr; +#endif + +#if defined(HAVE_CONSOLE) + /* Enable USART APB1/2 clock */ + + modifyreg32(STM32F0_CONSOLE_APBREG, 0, STM32F0_CONSOLE_APBEN); +#endif + + /* Enable the console USART and configure GPIO pins needed for rx/tx. + * + * NOTE: Clocking for selected U[S]ARTs was already provided in stm32f0_rcc.c + */ + +#ifdef STM32F0_CONSOLE_TX + stm32f0_configgpio(STM32F0_CONSOLE_TX); +#endif +#ifdef STM32F0_CONSOLE_RX + stm32f0_configgpio(STM32F0_CONSOLE_RX); +#endif + +#ifdef STM32F0_CONSOLE_RS485_DIR + stm32f0_configgpio(STM32F0_CONSOLE_RS485_DIR); + stm32f0_gpiowrite(STM32F0_CONSOLE_RS485_DIR, !STM32F0_CONSOLE_RS485_DIR_POLARITY); +#endif + + /* Enable and configure the selected console device */ + +#if defined(HAVE_CONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG) + /* Configure CR2 */ + + cr = getreg32(STM32F0_CONSOLE_BASE + STM32F0_USART_CR2_OFFSET); + cr &= ~USART_CR2_CLRBITS; + cr |= USART_CR2_SETBITS; + putreg32(cr, STM32F0_CONSOLE_BASE + STM32F0_USART_CR2_OFFSET); + + /* Configure CR1 */ + + cr = getreg32(STM32F0_CONSOLE_BASE + STM32F0_USART_CR1_OFFSET); + cr &= ~USART_CR1_CLRBITS; + cr |= USART_CR1_SETBITS; + putreg32(cr, STM32F0_CONSOLE_BASE + STM32F0_USART_CR1_OFFSET); + + /* Configure CR3 */ + + cr = getreg32(STM32F0_CONSOLE_BASE + STM32F0_USART_CR3_OFFSET); + cr &= ~USART_CR3_CLRBITS; + cr |= USART_CR3_SETBITS; + putreg32(cr, STM32F0_CONSOLE_BASE + STM32F0_USART_CR3_OFFSET); + + /* Configure the USART Baud Rate */ + + putreg32(STM32F0_BRR_VALUE, STM32F0_CONSOLE_BASE + STM32F0_USART_BRR_OFFSET); + + /* Select oversampling by 8 */ + + cr = getreg32(STM32F0_CONSOLE_BASE + STM32F0_USART_CR1_OFFSET); +#ifdef USE_OVER8 + cr |= USART_CR1_OVER8; + putreg32(cr, STM32F0_CONSOLE_BASE + STM32F0_USART_CR1_OFFSET); +#endif + + /* Enable Rx, Tx, and the USART */ + + cr |= (USART_CR1_UE | USART_CR1_TE | USART_CR1_RE); + putreg32(cr, STM32F0_CONSOLE_BASE + STM32F0_USART_CR1_OFFSET); + +#endif /* HAVE_CONSOLE && !CONFIG_SUPPRESS_UART_CONFIG */ +#endif /* HAVE_UART */ +} diff --git a/arch/arm/src/stm32f0/stm32f0_lowputc.h b/arch/arm/src/stm32f0/stm32f0_lowputc.h new file mode 100644 index 0000000000..a24b801e58 --- /dev/null +++ b/arch/arm/src/stm32f0/stm32f0_lowputc.h @@ -0,0 +1,79 @@ +/************************************************************************************ + * arch/arm/src/stm32f0/stm32f0_lowputc.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32F0_STM32F0_LOWPUTC_H +#define __ARCH_ARM_SRC_STM32F0_STM32F0_LOWPUTC_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include "chip.h" + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/************************************************************************************ + * Name: stm32f0_lowsetup + * + * Description: + * Called at the very beginning of _start. Performs low level initialization + * of serial console. + * + ************************************************************************************/ + +void stm32f0_lowsetup(void); + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __ARCH_ARM_SRC_STM32F0_STM32F0_LOWPUTC_H */ diff --git a/arch/arm/src/stm32f0/stm32f0_rcc.h b/arch/arm/src/stm32f0/stm32f0_rcc.h new file mode 100644 index 0000000000..a6894553cb --- /dev/null +++ b/arch/arm/src/stm32f0/stm32f0_rcc.h @@ -0,0 +1,50 @@ +/************************************************************************************ + * arch/arm/src/stm32f0/stm32f0_rcc.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32F0_STM32F0_RRC_H +#define __ARCH_ARM_SRC_STM32F0_STM32F0_RRC_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include "up_arch.h" +#include "chip.h" + +#include "chip/stm32f0_rcc.h" + +#endif /* __ARCH_ARM_SRC_STM32F0_STM32F0_RCC_H */ diff --git a/arch/arm/src/stm32f0/stm32f0_serial.c b/arch/arm/src/stm32f0/stm32f0_serial.c new file mode 100644 index 0000000000..579132389c --- /dev/null +++ b/arch/arm/src/stm32f0/stm32f0_serial.c @@ -0,0 +1,2560 @@ +/**************************************************************************** + * arch/arm/src/stm32f0/stm32f0_serial.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#ifdef CONFIG_SERIAL_TERMIOS +# include +#endif + +#include +#include + +#include "chip.h" +#include "stm32f0_uart.h" +//#include "stm32f0_dma.h" +#include "stm32f0_rcc.h" +#include "up_arch.h" +#include "up_internal.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Some sanity checks *******************************************************/ +/* DMA configuration */ + +/* If DMA is enabled on any USART, then very that other pre-requisites + * have also been selected. + * UART DMA1 DMA2 + * 1 X X + * 2 X + * 3 X + * 4 X + * 5 X + */ + +#ifdef SERIAL_HAVE_DMA + +/* Verify that DMA has been enabled and the DMA channel has been defined. + */ + +# if defined(CONFIG_USART2_RXDMA) || defined(CONFIG_USART3_RXDMA) +# ifndef CONFIG_STM32F0_DMA1 +# error STM32F0 USART2/3 receive DMA requires CONFIG_STM32F0_DMA1 +# endif +# endif + +# if defined(CONFIG_USART4_RXDMA) || defined(CONFIG_USART5_RXDMA) +# ifndef CONFIG_STM32F0_DMA2 +# error STM32F0 UART4/5 receive DMA requires CONFIG_STM32F0_DMA2 +# endif +# endif + +/* Currently RS-485 support cannot be enabled when RXDMA is in use due to lack + * of testing - RS-485 support was developed on STM32F1x + */ + +# if (defined(CONFIG_USART1_RXDMA) && defined(CONFIG_USART1_RS485)) || \ + (defined(CONFIG_USART2_RXDMA) && defined(CONFIG_USART2_RS485)) || \ + (defined(CONFIG_USART3_RXDMA) && defined(CONFIG_USART3_RS485)) || \ + (defined(CONFIG_USART4_RXDMA) && defined(CONFIG_USART4_RS485)) || \ + (defined(CONFIG_USART5_RXDMA) && defined(CONFIG_USART5_RS485)) +# error "RXDMA and RS-485 cannot be enabled at the same time for the same U[S]ART" +# endif + +/* For the L4, there are alternate DMA channels for USART1. + * Logic in the board.h file make the DMA channel selection by defining + * the following in the board.h file. + */ + +# if defined(CONFIG_USART1_RXDMA) && !defined(DMAMAP_USART1_RX) +# error "USART1 DMA channel not defined (DMAMAP_USART1_RX)" +# endif + +/* UART2-5 have no alternate channels */ + +# define DMAMAP_USART2_RX DMACHAN_USART2_RX +# define DMAMAP_USART3_RX DMACHAN_USART3_RX +# define DMAMAP_USART4_RX DMACHAN_USART4_RX +# define DMAMAP_USART5_RX DMACHAN_USART5_RX + +/* The DMA buffer size when using RX DMA to emulate a FIFO. + * + * When streaming data, the generic serial layer will be called + * every time the FIFO receives half this number of bytes. + */ + +# define RXDMA_BUFFER_SIZE 32 + +/* DMA priority */ + +# ifndef CONFIG_USART_DMAPRIO +# define CONFIG_USART_DMAPRIO DMA_CCR_PRIMED +# endif +# if (CONFIG_USART_DMAPRIO & ~DMA_CCR_PL_MASK) != 0 +# error "Illegal value for CONFIG_USART_DMAPRIO" +# endif + +/* DMA control words */ + +# define SERIAL_DMA_CONTROL_WORD \ + (DMA_CCR_CIRC | \ + DMA_CCR_MINC | \ + DMA_CCR_PSIZE_8BITS | \ + DMA_CCR_MSIZE_8BITS | \ + CONFIG_USART_DMAPRIO) +# ifdef CONFIG_SERIAL_IFLOWCONTROL +# define SERIAL_DMA_IFLOW_CONTROL_WORD \ + (DMA_CCR_MINC | \ + DMA_CCR_PSIZE_8BITS | \ + DMA_CCR_MSIZE_8BITS | \ + CONFIG_USART_DMAPRIO) +# endif + +#endif + +/* Power management definitions */ + +#if defined(CONFIG_PM) && !defined(CONFIG_PM_SERIAL_ACTIVITY) +# define CONFIG_PM_SERIAL_ACTIVITY 10 +# define PM_IDLE_DOMAIN 0 /* Revisit */ +#endif + +/* Keep track if a Break was set + * + * Note: + * + * 1) This value is set in the priv->ie but never written to the control + * register. It must not collide with USART_CR1_USED_INTS or USART_CR3_EIE + * 2) USART_CR3_EIE is also carried in the up_dev_s ie member. + * + * See stm32f0serial_restoreusartint where the masking is done. + */ + +#ifdef CONFIG_STM32F0_SERIALBRK_BSDCOMPAT +# define USART_CR1_IE_BREAK_INPROGRESS_SHFTS 15 +# define USART_CR1_IE_BREAK_INPROGRESS (1 << USART_CR1_IE_BREAK_INPROGRESS_SHFTS) +#endif + +#ifdef USE_SERIALDRIVER +#ifdef HAVE_USART + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct stm32f0_serial_s +{ + struct uart_dev_s dev; /* Generic UART device */ + uint16_t ie; /* Saved interrupt mask bits value */ + uint16_t sr; /* Saved status bits */ + + /* If termios are supported, then the following fields may vary at + * runtime. + */ + +#ifdef CONFIG_SERIAL_TERMIOS + uint8_t parity; /* 0=none, 1=odd, 2=even */ + uint8_t bits; /* Number of bits (7 or 8) */ + bool stopbits2; /* True: Configure with 2 stop bits instead of 1 */ +#ifdef CONFIG_SERIAL_IFLOWCONTROL + bool iflow; /* input flow control (RTS) enabled */ +#endif +#ifdef CONFIG_SERIAL_OFLOWCONTROL + bool oflow; /* output flow control (CTS) enabled */ +#endif + uint32_t baud; /* Configured baud */ +#else + const uint8_t parity; /* 0=none, 1=odd, 2=even */ + const uint8_t bits; /* Number of bits (7 or 8) */ + const bool stopbits2; /* True: Configure with 2 stop bits instead of 1 */ +#ifdef CONFIG_SERIAL_IFLOWCONTROL + const bool iflow; /* input flow control (RTS) enabled */ +#endif +#ifdef CONFIG_SERIAL_OFLOWCONTROL + const bool oflow; /* output flow control (CTS) enabled */ +#endif + const uint32_t baud; /* Configured baud */ +#endif + + const uint8_t irq; /* IRQ associated with this USART */ + const uint32_t apbclock; /* PCLK 1 or 2 frequency */ + const uint32_t usartbase; /* Base address of USART registers */ + const uint32_t tx_gpio; /* U[S]ART TX GPIO pin configuration */ + const uint32_t rx_gpio; /* U[S]ART RX GPIO pin configuration */ +#ifdef CONFIG_SERIAL_IFLOWCONTROL + const uint32_t rts_gpio; /* U[S]ART RTS GPIO pin configuration */ +#endif +#ifdef CONFIG_SERIAL_OFLOWCONTROL + const uint32_t cts_gpio; /* U[S]ART CTS GPIO pin configuration */ +#endif + +#ifdef SERIAL_HAVE_DMA + const unsigned int rxdma_channel; /* DMA channel assigned */ +#endif + + /* RX DMA state */ + +#ifdef SERIAL_HAVE_DMA + DMA_HANDLE rxdma; /* currently-open receive DMA stream */ + bool rxenable; /* DMA-based reception en/disable */ + uint32_t rxdmanext; /* Next byte in the DMA buffer to be read */ + char *const rxfifo; /* Receive DMA buffer */ +#endif + +#ifdef HAVE_RS485 + const uint32_t rs485_dir_gpio; /* U[S]ART RS-485 DIR GPIO pin configuration */ + const bool rs485_dir_polarity; /* U[S]ART RS-485 DIR pin state for TX enabled */ +#endif +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +#ifndef CONFIG_SUPPRESS_UART_CONFIG +static void stm32f0serial_setformat(FAR struct uart_dev_s *dev); +#endif +static int stm32f0serial_setup(FAR struct uart_dev_s *dev); +static void stm32f0serial_shutdown(FAR struct uart_dev_s *dev); +static int stm32f0serial_attach(FAR struct uart_dev_s *dev); +static void stm32f0serial_detach(FAR struct uart_dev_s *dev); +static int up_interrupt(int irq, FAR void *context, FAR void *arg); +static int stm32f0serial_ioctl(FAR struct file *filep, int cmd, + unsigned long arg); +#ifndef SERIAL_HAVE_ONLY_DMA +static int stm32f0serial_receive(FAR struct uart_dev_s *dev, + FAR unsigned int *status); +static void stm32f0serial_rxint(FAR struct uart_dev_s *dev, bool enable); +static bool stm32f0serial_rxavailable(FAR struct uart_dev_s *dev); +#endif +#ifdef CONFIG_SERIAL_IFLOWCONTROL +static bool stm32f0serial_rxflowcontrol(FAR struct uart_dev_s *dev, + unsigned int nbuffered, bool upper); +#endif +static void stm32f0serial_send(FAR struct uart_dev_s *dev, int ch); +static void stm32f0serial_txint(FAR struct uart_dev_s *dev, bool enable); +static bool stm32f0serial_txready(FAR struct uart_dev_s *dev); + +#ifdef SERIAL_HAVE_DMA +static int stm32f0serial_dmasetup(FAR struct uart_dev_s *dev); +static void stm32f0serial_dmashutdown(FAR struct uart_dev_s *dev); +static int stm32f0serial_dmareceive(FAR struct uart_dev_s *dev, + FAR unsigned int *status); +static void stm32f0serial_dmarxint(FAR struct uart_dev_s *dev, bool enable); +static bool stm32f0serial_dmarxavailable(struct uart_dev_s *dev); + +static void stm32f0serial_dmarxcallback(DMA_HANDLE handle, uint8_t status, + FAR void *arg); +#endif + +#ifdef CONFIG_PM +static void stm32f0serial_pmnotify(FAR struct pm_callback_s *cb, int domain, + enum pm_state_e pmstate); +static int stm32f0serial_pmprepare(FAR struct pm_callback_s *cb, int domain, + enum pm_state_e pmstate); +#endif + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +#ifndef SERIAL_HAVE_ONLY_DMA +static const struct uart_ops_s g_uart_ops = +{ + .setup = stm32f0serial_setup, + .shutdown = stm32f0serial_shutdown, + .attach = stm32f0serial_attach, + .detach = stm32f0serial_detach, + .ioctl = stm32f0serial_ioctl, + .receive = stm32f0serial_receive, + .rxint = stm32f0serial_rxint, + .rxavailable = stm32f0serial_rxavailable, +#ifdef CONFIG_SERIAL_IFLOWCONTROL + .rxflowcontrol = stm32f0serial_rxflowcontrol, +#endif + .send = stm32f0serial_send, + .txint = stm32f0serial_txint, + .txready = stm32f0serial_txready, + .txempty = stm32f0serial_txready, +}; +#endif + +#ifdef SERIAL_HAVE_DMA +static const struct uart_ops_s g_uart_dma_ops = +{ + .setup = stm32f0serial_dmasetup, + .shutdown = stm32f0serial_dmashutdown, + .attach = stm32f0serial_attach, + .detach = stm32f0serial_detach, + .ioctl = stm32f0serial_ioctl, + .receive = stm32f0serial_dmareceive, + .rxint = stm32f0serial_dmarxint, + .rxavailable = stm32f0serial_dmarxavailable, +#ifdef CONFIG_SERIAL_IFLOWCONTROL + .rxflowcontrol = stm32f0serial_rxflowcontrol, +#endif + .send = stm32f0serial_send, + .txint = stm32f0serial_txint, + .txready = stm32f0serial_txready, + .txempty = stm32f0serial_txready, +}; +#endif + +/* I/O buffers */ + +#ifdef CONFIG_STM32F0_USART1 +static char g_usart1rxbuffer[CONFIG_USART1_RXBUFSIZE]; +static char g_usart1txbuffer[CONFIG_USART1_TXBUFSIZE]; +# ifdef CONFIG_USART1_RXDMA +static char g_usart1rxfifo[RXDMA_BUFFER_SIZE]; +# endif +#endif + +#ifdef CONFIG_STM32F0_USART2 +static char g_usart2rxbuffer[CONFIG_USART2_RXBUFSIZE]; +static char g_usart2txbuffer[CONFIG_USART2_TXBUFSIZE]; +# ifdef CONFIG_USART2_RXDMA +static char g_usart2rxfifo[RXDMA_BUFFER_SIZE]; +# endif +#endif + +#ifdef CONFIG_STM32F0_USART3 +static char g_usart3rxbuffer[CONFIG_USART3_RXBUFSIZE]; +static char g_usart3txbuffer[CONFIG_USART3_TXBUFSIZE]; +# ifdef CONFIG_USART3_RXDMA +static char g_usart3rxfifo[RXDMA_BUFFER_SIZE]; +# endif +#endif + +#ifdef CONFIG_STM32F0_USART4 +static char g_uart4rxbuffer[CONFIG_USART4_RXBUFSIZE]; +static char g_uart4txbuffer[CONFIG_USART4_TXBUFSIZE]; +# ifdef CONFIG_USART4_RXDMA +static char g_uart4rxfifo[RXDMA_BUFFER_SIZE]; +# endif +#endif + +#ifdef CONFIG_STM32F0_USART5 +static char g_uart5rxbuffer[CONFIG_USART5_RXBUFSIZE]; +static char g_uart5txbuffer[CONFIG_USART5_TXBUFSIZE]; +# ifdef CONFIG_USART5_RXDMA +static char g_uart5rxfifo[RXDMA_BUFFER_SIZE]; +# endif +#endif + +/* This describes the state of the STM32 USART1 ports. */ + +#ifdef CONFIG_STM32F0_USART1 +static struct stm32f0_serial_s g_usart1priv = +{ + .dev = + { +#if CONSOLE_USART == 1 + .isconsole = true, +#endif + .recv = + { + .size = CONFIG_USART1_RXBUFSIZE, + .buffer = g_usart1rxbuffer, + }, + .xmit = + { + .size = CONFIG_USART1_TXBUFSIZE, + .buffer = g_usart1txbuffer, + }, +#ifdef CONFIG_USART1_RXDMA + .ops = &g_uart_dma_ops, +#else + .ops = &g_uart_ops, +#endif + .priv = &g_usart1priv, + }, + + .irq = STM32F0_IRQ_USART1, + .parity = CONFIG_USART1_PARITY, + .bits = CONFIG_USART1_BITS, + .stopbits2 = CONFIG_USART1_2STOP, + .baud = CONFIG_USART1_BAUD, + .apbclock = STM32F0_PCLK2_FREQUENCY, + .usartbase = STM32F0_USART1_BASE, + .tx_gpio = GPIO_USART1_TX, + .rx_gpio = GPIO_USART1_RX, +#if defined(CONFIG_SERIAL_OFLOWCONTROL) && defined(CONFIG_USART1_OFLOWCONTROL) + .oflow = true, + .cts_gpio = GPIO_USART1_CTS, +#endif +#if defined(CONFIG_SERIAL_IFLOWCONTROL) && defined(CONFIG_USART1_IFLOWCONTROL) + .iflow = true, + .rts_gpio = GPIO_USART1_RTS, +#endif +#ifdef CONFIG_USART1_RXDMA + .rxdma_channel = DMAMAP_USART1_RX, + .rxfifo = g_usart1rxfifo, +#endif + +#ifdef CONFIG_USART1_RS485 + .rs485_dir_gpio = GPIO_USART1_RS485_DIR, +# if (CONFIG_USART1_RS485_DIR_POLARITY == 0) + .rs485_dir_polarity = false, +# else + .rs485_dir_polarity = true, +# endif +#endif +}; +#endif + +/* This describes the state of the STM32 USART2 port. */ + +#ifdef CONFIG_STM32F0_USART2 +static struct stm32f0_serial_s g_usart2priv = +{ + .dev = + { +#if CONSOLE_USART == 2 + .isconsole = true, +#endif + .recv = + { + .size = CONFIG_USART2_RXBUFSIZE, + .buffer = g_usart2rxbuffer, + }, + .xmit = + { + .size = CONFIG_USART2_TXBUFSIZE, + .buffer = g_usart2txbuffer, + }, +#ifdef CONFIG_USART2_RXDMA + .ops = &g_uart_dma_ops, +#else + .ops = &g_uart_ops, +#endif + .priv = &g_usart2priv, + }, + + .irq = STM32F0_IRQ_USART2, + .parity = CONFIG_USART2_PARITY, + .bits = CONFIG_USART2_BITS, + .stopbits2 = CONFIG_USART2_2STOP, + .baud = CONFIG_USART2_BAUD, + .apbclock = STM32F0_PCLK1_FREQUENCY, + .usartbase = STM32F0_USART2_BASE, + .tx_gpio = GPIO_USART2_TX, + .rx_gpio = GPIO_USART2_RX, +#if defined(CONFIG_SERIAL_OFLOWCONTROL) && defined(CONFIG_USART2_OFLOWCONTROL) + .oflow = true, + .cts_gpio = GPIO_USART2_CTS, +#endif +#if defined(CONFIG_SERIAL_IFLOWCONTROL) && defined(CONFIG_USART2_IFLOWCONTROL) + .iflow = true, + .rts_gpio = GPIO_USART2_RTS, +#endif +#ifdef CONFIG_USART2_RXDMA + .rxdma_channel = DMAMAP_USART2_RX, + .rxfifo = g_usart2rxfifo, +#endif + +#ifdef CONFIG_USART2_RS485 + .rs485_dir_gpio = GPIO_USART2_RS485_DIR, +# if (CONFIG_USART2_RS485_DIR_POLARITY == 0) + .rs485_dir_polarity = false, +# else + .rs485_dir_polarity = true, +# endif +#endif +}; +#endif + +/* This describes the state of the STM32 USART3 port. */ + +#ifdef CONFIG_STM32F0_USART3 +static struct stm32f0_serial_s g_usart3priv = +{ + .dev = + { +#if CONSOLE_USART == 3 + .isconsole = true, +#endif + .recv = + { + .size = CONFIG_USART3_RXBUFSIZE, + .buffer = g_usart3rxbuffer, + }, + .xmit = + { + .size = CONFIG_USART3_TXBUFSIZE, + .buffer = g_usart3txbuffer, + }, +#ifdef CONFIG_USART3_RXDMA + .ops = &g_uart_dma_ops, +#else + .ops = &g_uart_ops, +#endif + .priv = &g_usart3priv, + }, + + .irq = STM32F0_IRQ_USART3, + .parity = CONFIG_USART3_PARITY, + .bits = CONFIG_USART3_BITS, + .stopbits2 = CONFIG_USART3_2STOP, + .baud = CONFIG_USART3_BAUD, + .apbclock = STM32F0_PCLK1_FREQUENCY, + .usartbase = STM32F0_USART3_BASE, + .tx_gpio = GPIO_USART3_TX, + .rx_gpio = GPIO_USART3_RX, +#if defined(CONFIG_SERIAL_OFLOWCONTROL) && defined(CONFIG_USART3_OFLOWCONTROL) + .oflow = true, + .cts_gpio = GPIO_USART3_CTS, +#endif +#if defined(CONFIG_SERIAL_IFLOWCONTROL) && defined(CONFIG_USART3_IFLOWCONTROL) + .iflow = true, + .rts_gpio = GPIO_USART3_RTS, +#endif +#ifdef CONFIG_USART3_RXDMA + .rxdma_channel = DMAMAP_USART3_RX, + .rxfifo = g_usart3rxfifo, +#endif + +#ifdef CONFIG_USART3_RS485 + .rs485_dir_gpio = GPIO_USART3_RS485_DIR, +# if (CONFIG_USART3_RS485_DIR_POLARITY == 0) + .rs485_dir_polarity = false, +# else + .rs485_dir_polarity = true, +# endif +#endif +}; +#endif + +/* This describes the state of the STM32 UART4 port. */ + +#ifdef CONFIG_STM32F0_USART4 +static struct stm32f0_serial_s g_uart4priv = +{ + .dev = + { +#if CONSOLE_USART == 4 + .isconsole = true, +#endif + .recv = + { + .size = CONFIG_USART4_RXBUFSIZE, + .buffer = g_uart4rxbuffer, + }, + .xmit = + { + .size = CONFIG_USART4_TXBUFSIZE, + .buffer = g_uart4txbuffer, + }, +#ifdef CONFIG_USART4_RXDMA + .ops = &g_uart_dma_ops, +#else + .ops = &g_uart_ops, +#endif + .priv = &g_uart4priv, + }, + + .irq = STM32F0_IRQ_USART4, + .parity = CONFIG_USART4_PARITY, + .bits = CONFIG_USART4_BITS, + .stopbits2 = CONFIG_USART4_2STOP, +#ifdef CONFIG_SERIAL_IFLOWCONTROL + .iflow = false, +#endif +#ifdef CONFIG_SERIAL_OFLOWCONTROL + .oflow = false, +#endif + .baud = CONFIG_USART4_BAUD, + .apbclock = STM32F0_PCLK1_FREQUENCY, + .usartbase = STM32F0_USART4_BASE, + .tx_gpio = GPIO_USART4_TX, + .rx_gpio = GPIO_USART4_RX, +#ifdef CONFIG_SERIAL_OFLOWCONTROL + .cts_gpio = 0, +#endif +#ifdef CONFIG_SERIAL_IFLOWCONTROL + .rts_gpio = 0, +#endif +#ifdef CONFIG_USART4_RXDMA + .rxdma_channel = DMAMAP_USART4_RX, + .rxfifo = g_uart4rxfifo, +#endif + +#ifdef CONFIG_USART4_RS485 + .rs485_dir_gpio = GPIO_USART4_RS485_DIR, +# if (CONFIG_USART4_RS485_DIR_POLARITY == 0) + .rs485_dir_polarity = false, +# else + .rs485_dir_polarity = true, +# endif +#endif +}; +#endif + +/* This describes the state of the STM32 UART5 port. */ + +#ifdef CONFIG_STM32F0_USART5 +static struct stm32f0_serial_s g_uart5priv = +{ + .dev = + { +#if CONSOLE_USART == 5 + .isconsole = true, +#endif + .recv = + { + .size = CONFIG_USART5_RXBUFSIZE, + .buffer = g_uart5rxbuffer, + }, + .xmit = + { + .size = CONFIG_USART5_TXBUFSIZE, + .buffer = g_uart5txbuffer, + }, +#ifdef CONFIG_USART5_RXDMA + .ops = &g_uart_dma_ops, +#else + .ops = &g_uart_ops, +#endif + .priv = &g_uart5priv, + }, + + .irq = STM32F0_IRQ_USART5, + .parity = CONFIG_USART5_PARITY, + .bits = CONFIG_USART5_BITS, + .stopbits2 = CONFIG_USART5_2STOP, +#ifdef CONFIG_SERIAL_IFLOWCONTROL + .iflow = false, +#endif +#ifdef CONFIG_SERIAL_OFLOWCONTROL + .oflow = false, +#endif + .baud = CONFIG_USART5_BAUD, + .apbclock = STM32F0_PCLK1_FREQUENCY, + .usartbase = STM32F0_USART5_BASE, + .tx_gpio = GPIO_USART5_TX, + .rx_gpio = GPIO_USART5_RX, +#ifdef CONFIG_SERIAL_OFLOWCONTROL + .cts_gpio = 0, +#endif +#ifdef CONFIG_SERIAL_IFLOWCONTROL + .rts_gpio = 0, +#endif +#ifdef CONFIG_USART5_RXDMA + .rxdma_channel = DMAMAP_USART5_RX, + .rxfifo = g_uart5rxfifo, +#endif + +#ifdef CONFIG_USART5_RS485 + .rs485_dir_gpio = GPIO_USART5_RS485_DIR, +# if (CONFIG_USART5_RS485_DIR_POLARITY == 0) + .rs485_dir_polarity = false, +# else + .rs485_dir_polarity = true, +# endif +#endif +}; +#endif + +/* This table lets us iterate over the configured USARTs */ + +FAR static struct stm32f0_serial_s * const uart_devs[STM32F0_NUSART] = +{ +#ifdef CONFIG_STM32F0_USART1 + [0] = &g_usart1priv, +#endif +#ifdef CONFIG_STM32F0_USART2 + [1] = &g_usart2priv, +#endif +#ifdef CONFIG_STM32F0_USART3 + [2] = &g_usart3priv, +#endif +#ifdef CONFIG_STM32F0_USART4 + [3] = &g_uart4priv, +#endif +#ifdef CONFIG_STM32F0_USART5 + [4] = &g_uart5priv, +#endif +}; + +#ifdef CONFIG_PM +static struct pm_callback_s g_serialcb = +{ + .notify = stm32f0serial_pmnotify, + .prepare = stm32f0serial_pmprepare, +}; +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32f0serial_getreg + ****************************************************************************/ + +static inline uint32_t stm32f0serial_getreg(FAR struct stm32f0_serial_s *priv, + int offset) +{ + return getreg32(priv->usartbase + offset); +} + +/**************************************************************************** + * Name: stm32f0serial_putreg + ****************************************************************************/ + +static inline void stm32f0serial_putreg(FAR struct stm32f0_serial_s *priv, + int offset, uint32_t value) +{ + putreg32(value, priv->usartbase + offset); +} + +/**************************************************************************** + * Name: stm32f0serial_restoreusartint + ****************************************************************************/ + +static void stm32f0serial_restoreusartint(FAR struct stm32f0_serial_s *priv, + uint16_t ie) +{ + uint32_t cr; + + /* Save the interrupt mask */ + + priv->ie = ie; + + /* And restore the interrupt state (see the interrupt enable/usage table above) */ + + cr = stm32f0serial_getreg(priv, STM32F0_USART_CR1_OFFSET); + cr &= ~(USART_CR1_USED_INTS); + cr |= (ie & (USART_CR1_USED_INTS)); + stm32f0serial_putreg(priv, STM32F0_USART_CR1_OFFSET, cr); + + cr = stm32f0serial_getreg(priv, STM32F0_USART_CR3_OFFSET); + cr &= ~USART_CR3_EIE; + cr |= (ie & USART_CR3_EIE); + stm32f0serial_putreg(priv, STM32F0_USART_CR3_OFFSET, cr); +} + +/**************************************************************************** + * Name: stm32f0serial_disableusartint + ****************************************************************************/ + +static inline void stm32f0serial_disableusartint(FAR struct stm32f0_serial_s *priv, + FAR uint16_t *ie) +{ + if (ie) + { + uint32_t cr1; + uint32_t cr3; + + /* USART interrupts: + * + * Enable Status Meaning Usage + * ------------------ --------------- ------------------------------ ---------- + * USART_CR1_IDLEIE USART_ISR_IDLE Idle Line Detected (not used) + * USART_CR1_RXNEIE USART_ISR_RXNE Received Data Ready to be Read + * " " USART_ISR_ORE Overrun Error Detected + * USART_CR1_TCIE USART_ISR_TC Transmission Complete (used only for RS-485) + * USART_CR1_TXEIE USART_ISR_TXE Transmit Data Register Empty + * USART_CR1_PEIE USART_ISR_PE Parity Error + * + * USART_CR2_LBDIE USART_ISR_LBD Break Flag (not used) + * USART_CR3_EIE USART_ISR_FE Framing Error + * " " USART_ISR_NF Noise Flag + * " " USART_ISR_ORE Overrun Error Detected + * USART_CR3_CTSIE USART_ISR_CTS CTS flag (not used) + */ + + cr1 = stm32f0serial_getreg(priv, STM32F0_USART_CR1_OFFSET); + cr3 = stm32f0serial_getreg(priv, STM32F0_USART_CR3_OFFSET); + + /* Return the current interrupt mask value for the used interrupts. Notice + * that this depends on the fact that none of the used interrupt enable bits + * overlap. This logic would fail if we needed the break interrupt! + */ + + *ie = (cr1 & (USART_CR1_USED_INTS)) | (cr3 & USART_CR3_EIE); + } + + /* Disable all interrupts */ + + stm32f0serial_restoreusartint(priv, 0); +} + +/**************************************************************************** + * Name: stm32f0serial_dmanextrx + * + * Description: + * Returns the index into the RX FIFO where the DMA will place the next + * byte that it receives. + * + ****************************************************************************/ + +#ifdef SERIAL_HAVE_DMA +static int stm32f0serial_dmanextrx(FAR struct stm32f0_serial_s *priv) +{ + size_t dmaresidual; + + dmaresidual = stm32f0_dmaresidual(priv->rxdma); + + return (RXDMA_BUFFER_SIZE - (int)dmaresidual); +} +#endif + +/**************************************************************************** + * Name: stm32f0serial_setformat + * + * Description: + * Set the serial line format and speed. + * + ****************************************************************************/ + +#ifndef CONFIG_SUPPRESS_UART_CONFIG +static void stm32f0serial_setformat(FAR struct uart_dev_s *dev) +{ + FAR struct stm32f0_serial_s *priv = (FAR struct stm32f0_serial_s *)dev->priv; + uint32_t regval; + + /* This first implementation is for U[S]ARTs that support oversampling + * by 8 in additional to the standard oversampling by 16. + */ + + uint32_t usartdiv8; + uint32_t cr1; + uint32_t brr; + + /* In case of oversampling by 8, the equation is: + * + * baud = 2 * fCK / usartdiv8 + * usartdiv8 = 2 * fCK / baud + */ + + usartdiv8 = ((priv->apbclock << 1) + (priv->baud >> 1)) / priv->baud; + + /* Baud rate for standard USART (SPI mode included): + * + * In case of oversampling by 16, the equation is: + * baud = fCK / usartdiv16 + * usartdiv16 = fCK / baud + * = 2 * usartdiv8 + */ + + /* Use oversamply by 8 only if the divisor is small. But what is small? */ + + cr1 = stm32f0serial_getreg(priv, STM32F0_USART_CR1_OFFSET); + if (usartdiv8 > 100) + { + /* Use usartdiv16 */ + + brr = (usartdiv8 + 1) >> 1; + + /* Clear oversampling by 8 to enable oversampling by 16 */ + + cr1 &= ~USART_CR1_OVER8; + } + else + { + DEBUGASSERT(usartdiv8 >= 8); + + /* Perform mysterious operations on bits 0-3 */ + + brr = ((usartdiv8 & 0xfff0) | ((usartdiv8 & 0x000f) >> 1)); + + /* Set oversampling by 8 */ + + cr1 |= USART_CR1_OVER8; + } + + stm32f0serial_putreg(priv, STM32F0_USART_CR1_OFFSET, cr1); + stm32f0serial_putreg(priv, STM32F0_USART_BRR_OFFSET, brr); + + /* Configure parity mode */ + + regval = stm32f0serial_getreg(priv, STM32F0_USART_CR1_OFFSET); + regval &= ~(USART_CR1_PCE | USART_CR1_PS | USART_CR1_M0 | USART_CR1_M1); + + if (priv->parity == 1) /* Odd parity */ + { + regval |= (USART_CR1_PCE | USART_CR1_PS); + } + else if (priv->parity == 2) /* Even parity */ + { + regval |= USART_CR1_PCE; + } + + /* Configure word length (parity uses one of configured bits) + * + * Default: 1 start, 8 data (no parity), n stop, OR + * 1 start, 7 data + parity, n stop + */ + + if (priv->bits == 9 || (priv->bits == 8 && priv->parity != 0)) + { + /* Select: 1 start, 8 data + parity, n stop, OR + * 1 start, 9 data (no parity), n stop. + */ + + regval |= USART_CR1_M0; + } + else if (priv->bits == 7 && priv->parity == 0) + { + /* Select: 1 start, 7 data (no parity), n stop, OR + */ + + regval |= USART_CR1_M1; + } + /* Else Select: 1 start, 7 data + parity, n stop, OR + * 1 start, 8 data (no parity), n stop. + */ + + stm32f0serial_putreg(priv, STM32F0_USART_CR1_OFFSET, regval); + + /* Configure STOP bits */ + + regval = stm32f0serial_getreg(priv, STM32F0_USART_CR2_OFFSET); + regval &= ~(USART_CR2_STOP_MASK); + + if (priv->stopbits2) + { + regval |= USART_CR2_STOP2; + } + + stm32f0serial_putreg(priv, STM32F0_USART_CR2_OFFSET, regval); + + /* Configure hardware flow control */ + + regval = stm32f0serial_getreg(priv, STM32F0_USART_CR3_OFFSET); + regval &= ~(USART_CR3_CTSE | USART_CR3_RTSE); + +#if defined(CONFIG_SERIAL_IFLOWCONTROL) && !defined(CONFIG_STM32F0_FLOWCONTROL_BROKEN) + if (priv->iflow && (priv->rts_gpio != 0)) + { + regval |= USART_CR3_RTSE; + } +#endif + +#ifdef CONFIG_SERIAL_OFLOWCONTROL + if (priv->oflow && (priv->cts_gpio != 0)) + { + regval |= USART_CR3_CTSE; + } +#endif + + stm32f0serial_putreg(priv, STM32F0_USART_CR3_OFFSET, regval); +} +#endif /* CONFIG_SUPPRESS_UART_CONFIG */ + +/**************************************************************************** + * Name: stm32f0serial_setapbclock + * + * Description: + * Enable or disable APB clock for the USART peripheral + * + * Input parameters: + * dev - A reference to the UART driver state structure + * on - Enable clock if 'on' is 'true' and disable if 'false' + * + ****************************************************************************/ + +static void stm32f0serial_setapbclock(FAR struct uart_dev_s *dev, bool on) +{ + FAR struct stm32f0_serial_s *priv = (FAR struct stm32f0_serial_s *)dev->priv; + uint32_t rcc_en; + uint32_t regaddr; + + /* Determine which USART to configure */ + + switch (priv->usartbase) + { + default: + return; +#ifdef CONFIG_STM32F0_USART1 + case STM32F0_USART1_BASE: + rcc_en = RCC_APB2ENR_USART1EN; + regaddr = STM32F0_RCC_APB2ENR; + break; +#endif +#ifdef CONFIG_STM32F0_USART2 + case STM32F0_USART2_BASE: + rcc_en = RCC_APB1ENR1_USART2EN; + regaddr = STM32F0_RCC_APB1ENR1; + break; +#endif +#ifdef CONFIG_STM32F0_USART3 + case STM32F0_USART3_BASE: + rcc_en = RCC_APB1ENR1_USART3EN; + regaddr = STM32F0_RCC_APB1ENR1; + break; +#endif +#ifdef CONFIG_STM32F0_USART4 + case STM32F0_USART4_BASE: + rcc_en = RCC_APB1ENR1_USART4EN; + regaddr = STM32F0_RCC_APB1ENR1; + break; +#endif +#ifdef CONFIG_STM32F0_USART5 + case STM32F0_USART5_BASE: + rcc_en = RCC_APB1ENR1_USART5EN; + regaddr = STM32F0_RCC_APB1ENR1; + break; +#endif + } + + /* Enable/disable APB 1/2 clock for USART */ + + if (on) + { + modifyreg32(regaddr, 0, rcc_en); + } + else + { + modifyreg32(regaddr, rcc_en, 0); + } +} + +/**************************************************************************** + * Name: stm32f0serial_setup + * + * Description: + * Configure the USART baud, bits, parity, etc. This method is called the + * first time that the serial port is opened. + * + ****************************************************************************/ + +static int stm32f0serial_setup(FAR struct uart_dev_s *dev) +{ + FAR struct stm32f0_serial_s *priv = (FAR struct stm32f0_serial_s *)dev->priv; + +#ifndef CONFIG_SUPPRESS_UART_CONFIG + uint32_t regval; + + /* Note: The logic here depends on the fact that that the USART module + * was enabled in stm32f0_lowsetup(). + */ + + /* Enable USART APB1/2 clock */ + + stm32f0serial_setapbclock(dev, true); + + /* Configure pins for USART use */ + + stm32f0_configgpio(priv->tx_gpio); + stm32f0_configgpio(priv->rx_gpio); + +#ifdef CONFIG_SERIAL_OFLOWCONTROL + if (priv->cts_gpio != 0) + { + stm32f0_configgpio(priv->cts_gpio); + } +#endif + +#ifdef CONFIG_SERIAL_IFLOWCONTROL + if (priv->rts_gpio != 0) + { + uint32_t config = priv->rts_gpio; + +#ifdef CONFIG_STM32F0_FLOWCONTROL_BROKEN + /* Instead of letting hw manage this pin, we will bitbang */ + + config = (config & ~GPIO_MODE_MASK) | GPIO_OUTPUT; +#endif + stm32f0_configgpio(config); + } +#endif + +#ifdef HAVE_RS485 + if (priv->rs485_dir_gpio != 0) + { + stm32f0_configgpio(priv->rs485_dir_gpio); + stm32f0_gpiowrite(priv->rs485_dir_gpio, !priv->rs485_dir_polarity); + } +#endif + + /* Configure CR2 */ + /* Clear STOP, CLKEN, CPOL, CPHA, LBCL, and interrupt enable bits */ + + regval = stm32f0serial_getreg(priv, STM32F0_USART_CR2_OFFSET); + regval &= ~(USART_CR2_STOP_MASK | USART_CR2_CLKEN | USART_CR2_CPOL | + USART_CR2_CPHA | USART_CR2_LBCL | USART_CR2_LBDIE); + + /* Configure STOP bits */ + + if (priv->stopbits2) + { + regval |= USART_CR2_STOP2; + } + + stm32f0serial_putreg(priv, STM32F0_USART_CR2_OFFSET, regval); + + /* Configure CR1 */ + /* Clear TE, REm and all interrupt enable bits */ + + regval = stm32f0serial_getreg(priv, STM32F0_USART_CR1_OFFSET); + regval &= ~(USART_CR1_TE | USART_CR1_RE | USART_CR1_ALLINTS); + + stm32f0serial_putreg(priv, STM32F0_USART_CR1_OFFSET, regval); + + /* Configure CR3 */ + /* Clear CTSE, RTSE, and all interrupt enable bits */ + + regval = stm32f0serial_getreg(priv, STM32F0_USART_CR3_OFFSET); + regval &= ~(USART_CR3_CTSIE | USART_CR3_CTSE | USART_CR3_RTSE | + USART_CR3_EIE); + + stm32f0serial_putreg(priv, STM32F0_USART_CR3_OFFSET, regval); + + /* Configure the USART line format and speed. */ + + stm32f0serial_setformat(dev); + + /* Enable Rx, Tx, and the USART */ + + regval = stm32f0serial_getreg(priv, STM32F0_USART_CR1_OFFSET); + regval |= (USART_CR1_UE | USART_CR1_TE | USART_CR1_RE); + stm32f0serial_putreg(priv, STM32F0_USART_CR1_OFFSET, regval); + +#endif /* CONFIG_SUPPRESS_UART_CONFIG */ + + /* Set up the cached interrupt enables value */ + + priv->ie = 0; + return OK; +} + +/**************************************************************************** + * Name: stm32f0serial_dmasetup + * + * Description: + * Configure the USART baud, bits, parity, etc. This method is called the + * first time that the serial port is opened. + * + ****************************************************************************/ + +#ifdef SERIAL_HAVE_DMA +static int stm32f0serial_dmasetup(FAR struct uart_dev_s *dev) +{ + FAR struct stm32f0_serial_s *priv = (FAR struct stm32f0_serial_s *)dev->priv; + int result; + uint32_t regval; + + /* Do the basic UART setup first, unless we are the console */ + + if (!dev->isconsole) + { + result = stm32f0serial_setup(dev); + if (result != OK) + { + return result; + } + } + + /* Acquire the DMA channel. This should always succeed. */ + + priv->rxdma = stm32f0_dmachannel(priv->rxdma_channel); + +#ifdef CONFIG_SERIAL_IFLOWCONTROL + if (priv->iflow) + { + /* Configure for non-circular DMA reception into the RX FIFO */ + + stm32f0_dmasetup(priv->rxdma, + priv->usartbase + STM32F0_USART_RDR_OFFSET, + (uint32_t)priv->rxfifo, + RXDMA_BUFFER_SIZE, + SERIAL_DMA_IFLOW_CONTROL_WORD); + } + else +#endif + { + /* Configure for circular DMA reception into the RX FIFO */ + + stm32f0_dmasetup(priv->rxdma, + priv->usartbase + STM32F0_USART_RDR_OFFSET, + (uint32_t)priv->rxfifo, + RXDMA_BUFFER_SIZE, + SERIAL_DMA_CONTROL_WORD); + } + + /* Reset our DMA shadow pointer to match the address just + * programmed above. + */ + + priv->rxdmanext = 0; + + /* Enable receive DMA for the UART */ + + regval = stm32f0serial_getreg(priv, STM32F0_USART_CR3_OFFSET); + regval |= USART_CR3_DMAR; + stm32f0serial_putreg(priv, STM32F0_USART_CR3_OFFSET, regval); + +#ifdef CONFIG_SERIAL_IFLOWCONTROL + if (priv->iflow) + { + /* Start the DMA channel, and arrange for callbacks at the full point + * in the FIFO. After buffer gets full, hardware flow-control kicks + * in and DMA transfer is stopped. + */ + + stm32f0_dmastart(priv->rxdma, stm32f0serial_dmarxcallback, + (void *)priv, false); + } + else +#endif + { + /* Start the DMA channel, and arrange for callbacks at the half and + * full points in the FIFO. This ensures that we have half a FIFO + * worth of time to claim bytes before they are overwritten. + */ + + stm32f0_dmastart(priv->rxdma, stm32f0serial_dmarxcallback, + (void *)priv, true); + } + + return OK; +} +#endif + +/**************************************************************************** + * Name: stm32f0serial_shutdown + * + * Description: + * Disable the USART. This method is called when the serial + * port is closed + * + ****************************************************************************/ + +static void stm32f0serial_shutdown(FAR struct uart_dev_s *dev) +{ + FAR struct stm32f0_serial_s *priv = (FAR struct stm32f0_serial_s *)dev->priv; + uint32_t regval; + + /* Disable all interrupts */ + + stm32f0serial_disableusartint(priv, NULL); + + /* Disable USART APB1/2 clock */ + + stm32f0serial_setapbclock(dev, false); + + /* Disable Rx, Tx, and the UART */ + + regval = stm32f0serial_getreg(priv, STM32F0_USART_CR1_OFFSET); + regval &= ~(USART_CR1_UE | USART_CR1_TE | USART_CR1_RE); + stm32f0serial_putreg(priv, STM32F0_USART_CR1_OFFSET, regval); + + /* Release pins. "If the serial-attached device is powered down, the TX + * pin causes back-powering, potentially confusing the device to the point + * of complete lock-up." + * + * REVISIT: Is unconfiguring the pins appropriate for all device? If not, + * then this may need to be a configuration option. + */ + + stm32f0_unconfiggpio(priv->tx_gpio); + stm32f0_unconfiggpio(priv->rx_gpio); + +#ifdef CONFIG_SERIAL_OFLOWCONTROL + if (priv->cts_gpio != 0) + { + stm32f0_unconfiggpio(priv->cts_gpio); + } +#endif + +#ifdef CONFIG_SERIAL_IFLOWCONTROL + if (priv->rts_gpio != 0) + { + stm32f0_unconfiggpio(priv->rts_gpio); + } +#endif + +#ifdef HAVE_RS485 + if (priv->rs485_dir_gpio != 0) + { + stm32f0_unconfiggpio(priv->rs485_dir_gpio); + } +#endif +} + +/**************************************************************************** + * Name: stm32f0serial_dmashutdown + * + * Description: + * Disable the USART. This method is called when the serial + * port is closed + * + ****************************************************************************/ + +#ifdef SERIAL_HAVE_DMA +static void stm32f0serial_dmashutdown(FAR struct uart_dev_s *dev) +{ + FAR struct stm32f0_serial_s *priv = (FAR struct stm32f0_serial_s *)dev->priv; + + /* Perform the normal UART shutdown */ + + stm32f0serial_shutdown(dev); + + /* Stop the DMA channel */ + + stm32f0_dmastop(priv->rxdma); + + /* Release the DMA channel */ + + stm32f0_dmafree(priv->rxdma); + priv->rxdma = NULL; +} +#endif + +/**************************************************************************** + * Name: stm32f0serial_attach + * + * Description: + * Configure the USART to operation in interrupt driven mode. This method is + * called when the serial port is opened. Normally, this is just after the + * the setup() method is called, however, the serial console may operate in + * a non-interrupt driven mode during the boot phase. + * + * RX and TX interrupts are not enabled when by the attach method (unless the + * hardware supports multiple levels of interrupt enabling). The RX and TX + * interrupts are not enabled until the txint() and rxint() methods are called. + * + ****************************************************************************/ + +static int stm32f0serial_attach(FAR struct uart_dev_s *dev) +{ + FAR struct stm32f0_serial_s *priv = (FAR struct stm32f0_serial_s *)dev->priv; + int ret; + + /* Attach and enable the IRQ */ + + ret = irq_attach(priv->irq, up_interrupt, priv); + if (ret == OK) + { + /* Enable the interrupt (RX and TX interrupts are still disabled + * in the USART + */ + + up_enable_irq(priv->irq); + } + + return ret; +} + +/**************************************************************************** + * Name: stm32f0serial_detach + * + * Description: + * Detach USART interrupts. This method is called when the serial port is + * closed normally just before the shutdown method is called. The exception + * is the serial console which is never shutdown. + * + ****************************************************************************/ + +static void stm32f0serial_detach(FAR struct uart_dev_s *dev) +{ + FAR struct stm32f0_serial_s *priv = (FAR struct stm32f0_serial_s *)dev->priv; + up_disable_irq(priv->irq); + irq_detach(priv->irq); +} + +/**************************************************************************** + * Name: up_interrupt + * + * Description: + * This is the USART interrupt handler. It will be invoked when an + * interrupt received on the 'irq' It should call uart_transmitchars or + * uart_receivechar to perform the appropriate data transfers. The + * interrupt handling logic must be able to map the 'irq' number into the + * appropriate uart_dev_s structure in order to call these functions. + * + ****************************************************************************/ + +static int up_interrupt(int irq, FAR void *context, FAR void *arg) +{ + FAR struct stm32f0_serial_s *priv = (FAR struct stm32f0_serial_s *)arg; + int passes; + bool handled; + + DEBUGASSERT(priv != NULL); + + /* Report serial activity to the power management logic */ + +#if defined(CONFIG_PM) && CONFIG_PM_SERIAL_ACTIVITY > 0 + pm_activity(PM_IDLE_DOMAIN, CONFIG_PM_SERIAL_ACTIVITY); +#endif + + /* Loop until there are no characters to be transferred or, + * until we have been looping for a long time. + */ + + handled = true; + for (passes = 0; passes < 256 && handled; passes++) + { + handled = false; + + /* Get the masked USART status word. */ + + priv->sr = stm32f0serial_getreg(priv, STM32F0_USART_ISR_OFFSET); + + /* USART interrupts: + * + * Enable Status Meaning Usage + * ------------------ --------------- ------------------------------- ---------- + * USART_CR1_IDLEIE USART_ISR_IDLE Idle Line Detected (not used) + * USART_CR1_RXNEIE USART_ISR_RXNE Received Data Ready to be Read + * " " USART_ISR_ORE Overrun Error Detected + * USART_CR1_TCIE USART_ISR_TC Transmission Complete (used only for RS-485) + * USART_CR1_TXEIE USART_ISR_TXE Transmit Data Register Empty + * USART_CR1_PEIE USART_ISR_PE Parity Error + * + * USART_CR2_LBDIE USART_ISR_LBD Break Flag (not used) + * USART_CR3_EIE USART_ISR_FE Framing Error + * " " USART_ISR_NE Noise Error + * " " USART_ISR_ORE Overrun Error Detected + * USART_CR3_CTSIE USART_ISR_CTS CTS flag (not used) + * + * NOTE: Some of these status bits must be cleared by explicity writing zero + * to the SR register: USART_ISR_CTS, USART_ISR_LBD. Note of those are currently + * being used. + */ + +#ifdef HAVE_RS485 + /* Transmission of whole buffer is over - TC is set, TXEIE is cleared. + * Note - this should be first, to have the most recent TC bit value from + * SR register - sending data affects TC, but without refresh we will not + * know that... + */ + + if ((priv->sr & USART_ISR_TC) != 0 && (priv->ie & USART_CR1_TCIE) != 0 && + (priv->ie & USART_CR1_TXEIE) == 0) + { + stm32f0_gpiowrite(priv->rs485_dir_gpio, !priv->rs485_dir_polarity); + stm32f0serial_restoreusartint(priv, priv->ie & ~USART_CR1_TCIE); + } +#endif + + /* Handle incoming, receive bytes. */ + + if ((priv->sr & USART_ISR_RXNE) != 0 && (priv->ie & USART_CR1_RXNEIE) != 0) + { + /* Received data ready... process incoming bytes. NOTE the check for + * RXNEIE: We cannot call uart_recvchards of RX interrupts are disabled. + */ + + uart_recvchars(&priv->dev); + handled = true; + } + + /* We may still have to read from the DR register to clear any pending + * error conditions. + */ + + else if ((priv->sr & (USART_ISR_ORE | USART_ISR_NF | USART_ISR_FE)) != 0) + { + /* These errors are cleared by writing the corresponding bit to the + * interrupt clear register (ICR). + */ + + stm32f0serial_putreg(priv, STM32F0_USART_ICR_OFFSET, + (USART_ICR_NCF | USART_ICR_ORECF | USART_ICR_FECF)); + } + + /* Handle outgoing, transmit bytes */ + + if ((priv->sr & USART_ISR_TXE) != 0 && (priv->ie & USART_CR1_TXEIE) != 0) + { + /* Transmit data register empty ... process outgoing bytes */ + + uart_xmitchars(&priv->dev); + handled = true; + } + } + + return OK; +} + +/**************************************************************************** + * Name: stm32f0serial_ioctl + * + * Description: + * All ioctl calls will be routed through this method + * + ****************************************************************************/ + +static int stm32f0serial_ioctl(FAR struct file *filep, int cmd, + unsigned long arg) +{ +#if defined(CONFIG_SERIAL_TERMIOS) || defined(CONFIG_SERIAL_TIOCSERGSTRUCT) + FAR struct inode *inode = filep->f_inode; + FAR struct uart_dev_s *dev = inode->i_private; +#endif +#if defined(CONFIG_SERIAL_TERMIOS) + FAR struct stm32f0_serial_s *priv = (FAR struct stm32f0_serial_s *)dev->priv; +#endif + int ret = OK; + + switch (cmd) + { +#ifdef CONFIG_SERIAL_TIOCSERGSTRUCT + case TIOCSERGSTRUCT: + { + FAR struct stm32f0_serial_s *user = (FAR struct stm32f0_serial_s *)arg; + if (!user) + { + ret = -EINVAL; + } + else + { + memcpy(user, dev, sizeof(struct stm32f0_serial_s)); + } + } + break; +#endif + +#ifdef CONFIG_STM32F0_USART_SINGLEWIRE +#warning please review the potential use of ALTERNATE_FUNCTION_OPENDRAIN + case TIOCSSINGLEWIRE: + { + /* Change the TX port to be open-drain/push-pull and enable/disable + * half-duplex mode. + */ + + uint32_t cr = stm32f0serial_getreg(priv, STM32F0_USART_CR3_OFFSET); + + if (arg == SER_SINGLEWIRE_ENABLED) + { + stm32f0_configgpio(priv->tx_gpio | GPIO_OPENDRAIN); + cr |= USART_CR3_HDSEL; + } + else + { + stm32f0_configgpio(priv->tx_gpio | GPIO_PUSHPULL); + cr &= ~USART_CR3_HDSEL; + } + + stm32f0serial_putreg(priv, STM32F0_USART_CR3_OFFSET, cr); + } + break; +#endif + +#ifdef CONFIG_SERIAL_TERMIOS + case TCGETS: + { + FAR struct termios *termiosp = (FAR struct termios *)arg; + + if (!termiosp) + { + ret = -EINVAL; + break; + } + + cfsetispeed(termiosp, priv->baud); + + /* Note that since we only support 8/9 bit modes and + * there is no way to report 9-bit mode, we always claim 8. + */ + + termiosp->c_cflag = + ((priv->parity != 0) ? PARENB : 0) | + ((priv->parity == 1) ? PARODD : 0) | + ((priv->stopbits2) ? CSTOPB : 0) | +#ifdef CONFIG_SERIAL_OFLOWCONTROL + ((priv->oflow) ? CCTS_OFLOW : 0) | +#endif +#ifdef CONFIG_SERIAL_IFLOWCONTROL + ((priv->iflow) ? CRTS_IFLOW : 0) | +#endif + CS8; + + /* TODO: CCTS_IFLOW, CCTS_OFLOW */ + } + break; + + case TCSETS: + { + FAR struct termios *termiosp = (FAR struct termios *)arg; + + if (!termiosp) + { + ret = -EINVAL; + break; + } + + /* Perform some sanity checks before accepting any changes */ + + if (((termiosp->c_cflag & CSIZE) != CS8) +#ifdef CONFIG_SERIAL_IFLOWCONTROL + || ((termiosp->c_cflag & CCTS_OFLOW) && (priv->cts_gpio == 0)) +#endif +#ifdef CONFIG_SERIAL_IFLOWCONTROL + || ((termiosp->c_cflag & CRTS_IFLOW) && (priv->rts_gpio == 0)) +#endif + ) + { + ret = -EINVAL; + break; + } + + if (termiosp->c_cflag & PARENB) + { + priv->parity = (termiosp->c_cflag & PARODD) ? 1 : 2; + } + else + { + priv->parity = 0; + } + + priv->stopbits2 = (termiosp->c_cflag & CSTOPB) != 0; +#ifdef CONFIG_SERIAL_OFLOWCONTROL + priv->oflow = (termiosp->c_cflag & CCTS_OFLOW) != 0; +#endif +#ifdef CONFIG_SERIAL_IFLOWCONTROL + priv->iflow = (termiosp->c_cflag & CRTS_IFLOW) != 0; +#endif + + /* Note that since there is no way to request 9-bit mode + * and no way to support 5/6/7-bit modes, we ignore them + * all here. + */ + + /* Note that only cfgetispeed is used because we have knowledge + * that only one speed is supported. + */ + + priv->baud = cfgetispeed(termiosp); + + /* Effect the changes immediately - note that we do not implement + * TCSADRAIN / TCSAFLUSH + */ + + stm32f0serial_setformat(dev); + } + break; +#endif /* CONFIG_SERIAL_TERMIOS */ + +#ifdef CONFIG_STM32F0_USART_BREAKS +# ifdef CONFIG_STM32F0_SERIALBRK_BSDCOMPAT + case TIOCSBRK: /* BSD compatibility: Turn break on, unconditionally */ + { + irqstate_t flags; + uint32_t tx_break; + + flags = enter_critical_section(); + + /* Disable any further tx activity */ + + priv->ie |= USART_CR1_IE_BREAK_INPROGRESS; + + stm32f0serial_txint(dev, false); + + /* Configure TX as a GPIO output pin and Send a break signal*/ + + tx_break = GPIO_OUTPUT | (~(GPIO_MODE_MASK|GPIO_OUTPUT_SET) & priv->tx_gpio); + stm32f0_configgpio(tx_break); + + leave_critical_section(flags); + } + break; + + case TIOCCBRK: /* BSD compatibility: Turn break off, unconditionally */ + { + irqstate_t flags; + + flags = enter_critical_section(); + + /* Configure TX back to U(S)ART */ + + stm32f0_configgpio(priv->tx_gpio); + + priv->ie &= ~USART_CR1_IE_BREAK_INPROGRESS; + + /* Enable further tx activity */ + + stm32f0serial_txint(dev, true); + + leave_critical_section(flags); + } + break; +# else + case TIOCSBRK: /* No BSD compatibility: Turn break on for M bit times */ + { + uint32_t cr1; + irqstate_t flags; + + flags = enter_critical_section(); + cr1 = stm32f0serial_getreg(priv, STM32F0_USART_CR1_OFFSET); + stm32f0serial_putreg(priv, STM32F0_USART_CR1_OFFSET, cr1 | USART_CR1_SBK); + leave_critical_section(flags); + } + break; + + case TIOCCBRK: /* No BSD compatibility: May turn off break too soon */ + { + uint32_t cr1; + irqstate_t flags; + + flags = enter_critical_section(); + cr1 = stm32f0serial_getreg(priv, STM32F0_USART_CR1_OFFSET); + stm32f0serial_putreg(priv, STM32F0_USART_CR1_OFFSET, cr1 & ~USART_CR1_SBK); + leave_critical_section(flags); + } + break; +# endif +#endif + + default: + ret = -ENOTTY; + break; + } + + return ret; +} + +/**************************************************************************** + * Name: stm32f0serial_receive + * + * Description: + * Called (usually) from the interrupt level to receive one + * character from the USART. Error bits associated with the + * receipt are provided in the return 'status'. + * + ****************************************************************************/ + +#ifndef SERIAL_HAVE_ONLY_DMA +static int stm32f0serial_receive(FAR struct uart_dev_s *dev, + FAR unsigned int *status) +{ + FAR struct stm32f0_serial_s *priv = (FAR struct stm32f0_serial_s *)dev->priv; + uint32_t rdr; + + /* Get the Rx byte */ + + rdr = stm32f0serial_getreg(priv, STM32F0_USART_RDR_OFFSET); + + /* Get the Rx byte plux error information. Return those in status */ + + *status = priv->sr << 16 | rdr; + priv->sr = 0; + + /* Then return the actual received byte */ + + return rdr & 0xff; +} +#endif + +/**************************************************************************** + * Name: stm32f0serial_rxint + * + * Description: + * Call to enable or disable RX interrupts + * + ****************************************************************************/ + +#ifndef SERIAL_HAVE_ONLY_DMA +static void stm32f0serial_rxint(FAR struct uart_dev_s *dev, bool enable) +{ + FAR struct stm32f0_serial_s *priv = (FAR struct stm32f0_serial_s *)dev->priv; + irqstate_t flags; + uint16_t ie; + + /* USART receive interrupts: + * + * Enable Status Meaning Usage + * ------------------ --------------- ------------------------------- ---------- + * USART_CR1_IDLEIE USART_ISR_IDLE Idle Line Detected (not used) + * USART_CR1_RXNEIE USART_ISR_RXNE Received Data Ready to be Read + * " " USART_ISR_ORE Overrun Error Detected + * USART_CR1_PEIE USART_ISR_PE Parity Error + * + * USART_CR2_LBDIE USART_ISR_LBD Break Flag (not used) + * USART_CR3_EIE USART_ISR_FE Framing Error + * " " USART_ISR_NF Noise Flag + * " " USART_ISR_ORE Overrun Error Detected + */ + + flags = enter_critical_section(); + ie = priv->ie; + if (enable) + { + /* Receive an interrupt when their is anything in the Rx data register (or an Rx + * timeout occurs). + */ + +#ifndef CONFIG_SUPPRESS_SERIAL_INTS +#ifdef CONFIG_USART_ERRINTS + ie |= (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR3_EIE); +#else + ie |= USART_CR1_RXNEIE; +#endif +#endif + } + else + { + ie &= ~(USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR3_EIE); + } + + /* Then set the new interrupt state */ + + stm32f0serial_restoreusartint(priv, ie); + leave_critical_section(flags); +} +#endif + +/**************************************************************************** + * Name: stm32f0serial_rxavailable + * + * Description: + * Return true if the receive register is not empty + * + ****************************************************************************/ + +#ifndef SERIAL_HAVE_ONLY_DMA +static bool stm32f0serial_rxavailable(FAR struct uart_dev_s *dev) +{ + FAR struct stm32f0_serial_s *priv = (FAR struct stm32f0_serial_s *)dev->priv; + return ((stm32f0serial_getreg(priv, STM32F0_USART_ISR_OFFSET) & USART_ISR_RXNE) != 0); +} +#endif + +/**************************************************************************** + * Name: stm32f0serial_rxflowcontrol + * + * Description: + * Called when Rx buffer is full (or exceeds configured watermark levels + * if CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS is defined). + * Return true if UART activated RX flow control to block more incoming + * data + * + * Input parameters: + * dev - UART device instance + * nbuffered - the number of characters currently buffered + * (if CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS is + * not defined the value will be 0 for an empty buffer or the + * defined buffer size for a full buffer) + * upper - true indicates the upper watermark was crossed where + * false indicates the lower watermark has been crossed + * + * Returned Value: + * true if RX flow control activated. + * + ****************************************************************************/ + +#ifdef CONFIG_SERIAL_IFLOWCONTROL +static bool stm32f0serial_rxflowcontrol(FAR struct uart_dev_s *dev, + unsigned int nbuffered, bool upper) +{ + FAR struct stm32f0_serial_s *priv = (FAR struct stm32f0_serial_s *)dev->priv; + +#if defined(CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS) && \ + defined(CONFIG_STM32F0_FLOWCONTROL_BROKEN) + if (priv->iflow && (priv->rts_gpio != 0)) + { + /* Assert/de-assert nRTS set it high resume/stop sending */ + + stm32f0_gpiowrite(priv->rts_gpio, upper); + return upper; + } + +#else + if (priv->iflow) + { + /* Is the RX buffer full? */ + + if (upper) + { + /* Disable Rx interrupt to prevent more data being from + * peripheral. When hardware RTS is enabled, this will + * prevent more data from coming in. + * + * This function is only called when UART recv buffer is full, + * that is: "dev->recv.head + 1 == dev->recv.tail". + * + * Logic in "uart_read" will automatically toggle Rx interrupts + * when buffer is read empty and thus we do not have to re- + * enable Rx interrupts. + */ + + uart_disablerxint(dev); + return true; + } + + /* No.. The RX buffer is empty */ + + else + { + /* We might leave Rx interrupt disabled if full recv buffer was + * read empty. Enable Rx interrupt to make sure that more input is + * received. + */ + + uart_enablerxint(dev); + } + } +#endif + + return false; +} +#endif + +/**************************************************************************** + * Name: stm32f0serial_dmareceive + * + * Description: + * Called (usually) from the interrupt level to receive one + * character from the USART. Error bits associated with the + * receipt are provided in the return 'status'. + * + ****************************************************************************/ + +#ifdef SERIAL_HAVE_DMA +static int stm32f0serial_dmareceive(FAR struct uart_dev_s *dev, + FAR unsigned int *status) +{ + FAR struct stm32f0_serial_s *priv = (FAR struct stm32f0_serial_s *)dev->priv; + int c = 0; + + if (stm32f0serial_dmanextrx(priv) != priv->rxdmanext) + { + c = priv->rxfifo[priv->rxdmanext]; + + priv->rxdmanext++; + if (priv->rxdmanext == RXDMA_BUFFER_SIZE) + { +#ifdef CONFIG_SERIAL_IFLOWCONTROL + if (priv->iflow) + { + /* RX DMA buffer full. RX paused, RTS line pulled up to prevent + * more input data from other end. + */ + } + else +#endif + { + priv->rxdmanext = 0; + } + } + } + + return c; +} +#endif + +/**************************************************************************** + * Name: stm32f0serial_dmareenable + * + * Description: + * Call to re-enable RX DMA. + * + ****************************************************************************/ + +#if defined(SERIAL_HAVE_DMA) && defined(CONFIG_SERIAL_IFLOWCONTROL) +static void stm32f0serial_dmareenable(FAR struct stm32f0_serial_s *priv) +{ + /* Configure for non-circular DMA reception into the RX fifo */ + + stm32f0_dmasetup(priv->rxdma, + priv->usartbase + STM32F0_USART_RDR_OFFSET, + (uint32_t)priv->rxfifo, + RXDMA_BUFFER_SIZE, + SERIAL_DMA_IFLOW_CONTROL_WORD); + + /* Reset our DMA shadow pointer to match the address just + * programmed above. + */ + + priv->rxdmanext = 0; + + /* Start the DMA channel, and arrange for callbacks at the full point in + * the FIFO. After buffer gets full, hardware flow-control kicks in and + * DMA transfer is stopped. + */ + + stm32f0_dmastart(priv->rxdma, stm32f0serial_dmarxcallback, (FAR void *)priv, + false); +} +#endif + +/**************************************************************************** + * Name: stm32f0serial_dmarxint + * + * Description: + * Call to enable or disable RX interrupts + * + ****************************************************************************/ + +#ifdef SERIAL_HAVE_DMA +static void stm32f0serial_dmarxint(FAR struct uart_dev_s *dev, bool enable) +{ + FAR struct stm32f0_serial_s *priv = (FAR struct stm32f0_serial_s *)dev->priv; + + /* En/disable DMA reception. + * + * Note that it is not safe to check for available bytes and immediately + * pass them to uart_recvchars as that could potentially recurse back + * to us again. Instead, bytes must wait until the next up_dma_poll or + * DMA event. + */ + + priv->rxenable = enable; + +#ifdef CONFIG_SERIAL_IFLOWCONTROL + if (priv->iflow && priv->rxenable && (priv->rxdmanext == RXDMA_BUFFER_SIZE)) + { + /* Re-enable RX DMA. */ + + stm32f0serial_dmareenable(priv); + } +#endif +} +#endif + +/**************************************************************************** + * Name: stm32f0serial_dmarxavailable + * + * Description: + * Return true if the receive register is not empty + * + ****************************************************************************/ + +#ifdef SERIAL_HAVE_DMA +static bool stm32f0serial_dmarxavailable(FAR struct uart_dev_s *dev) +{ + FAR struct stm32f0_serial_s *priv = (FAR struct stm32f0_serial_s *)dev->priv; + + /* Compare our receive pointer to the current DMA pointer, if they + * do not match, then there are bytes to be received. + */ + + return (stm32f0serial_dmanextrx(priv) != priv->rxdmanext); +} +#endif + +/**************************************************************************** + * Name: stm32f0serial_send + * + * Description: + * This method will send one byte on the USART + * + ****************************************************************************/ + +static void stm32f0serial_send(FAR struct uart_dev_s *dev, int ch) +{ + FAR struct stm32f0_serial_s *priv = (FAR struct stm32f0_serial_s *)dev->priv; + +#ifdef HAVE_RS485 + if (priv->rs485_dir_gpio != 0) + { + stm32f0_gpiowrite(priv->rs485_dir_gpio, priv->rs485_dir_polarity); + } +#endif + + stm32f0serial_putreg(priv, STM32F0_USART_TDR_OFFSET, (uint32_t)ch); +} + +/**************************************************************************** + * Name: stm32f0serial_txint + * + * Description: + * Call to enable or disable TX interrupts + * + ****************************************************************************/ + +static void stm32f0serial_txint(FAR struct uart_dev_s *dev, bool enable) +{ + FAR struct stm32f0_serial_s *priv = (FAR struct stm32f0_serial_s *)dev->priv; + irqstate_t flags; + + /* USART transmit interrupts: + * + * Enable Status Meaning Usage + * ------------------ --------------- ---------------------------- ---------- + * USART_CR1_TCIE USART_ISR_TC Transmission Complete (used only for RS-485) + * USART_CR1_TXEIE USART_ISR_TXE Transmit Data Register Empty + * USART_CR3_CTSIE USART_ISR_CTS CTS flag (not used) + */ + + flags = enter_critical_section(); + if (enable) + { + /* Set to receive an interrupt when the TX data register is empty */ + +#ifndef CONFIG_SUPPRESS_SERIAL_INTS + uint16_t ie = priv->ie | USART_CR1_TXEIE; + + /* If RS-485 is supported on this U[S]ART, then also enable the + * transmission complete interrupt. + */ + +# ifdef HAVE_RS485 + if (priv->rs485_dir_gpio != 0) + { + ie |= USART_CR1_TCIE; + } +# endif + +# ifdef CONFIG_STM32F0_SERIALBRK_BSDCOMPAT + if (priv->ie & USART_CR1_IE_BREAK_INPROGRESS) + { + return; + } +# endif + + stm32f0serial_restoreusartint(priv, ie); + + /* Fake a TX interrupt here by just calling uart_xmitchars() with + * interrupts disabled (note this may recurse). + */ + + uart_xmitchars(dev); +#endif + } + else + { + /* Disable the TX interrupt */ + + stm32f0serial_restoreusartint(priv, priv->ie & ~USART_CR1_TXEIE); + } + + leave_critical_section(flags); +} + +/**************************************************************************** + * Name: stm32f0serial_txready + * + * Description: + * Return true if the transmit data register is empty + * + ****************************************************************************/ + +static bool stm32f0serial_txready(FAR struct uart_dev_s *dev) +{ + FAR struct stm32f0_serial_s *priv = (FAR struct stm32f0_serial_s *)dev->priv; + return ((stm32f0serial_getreg(priv, STM32F0_USART_ISR_OFFSET) & USART_ISR_TXE) != 0); +} + +/**************************************************************************** + * Name: stm32f0serial_dmarxcallback + * + * Description: + * This function checks the current DMA state and calls the generic + * serial stack when bytes appear to be available. + * + ****************************************************************************/ + +#ifdef SERIAL_HAVE_DMA +static void stm32f0serial_dmarxcallback(DMA_HANDLE handle, uint8_t status, + FAR void *arg) +{ + FAR struct stm32f0_serial_s *priv = (FAR struct stm32f0_serial_s *)arg; + + if (priv->rxenable && stm32f0serial_dmarxavailable(&priv->dev)) + { + uart_recvchars(&priv->dev); + +#ifdef CONFIG_SERIAL_IFLOWCONTROL + if (priv->iflow && priv->rxenable && + (priv->rxdmanext == RXDMA_BUFFER_SIZE)) + { + /* Re-enable RX DMA. */ + + stm32f0serial_dmareenable(priv); + } +#endif + } +} +#endif + +/**************************************************************************** + * Name: stm32f0serial_pmnotify + * + * Description: + * Notify the driver of new power state. This callback is called after + * all drivers have had the opportunity to prepare for the new power state. + * + * Input Parameters: + * + * cb - Returned to the driver. The driver version of the callback + * structure may include additional, driver-specific state data at + * the end of the structure. + * + * pmstate - Identifies the new PM state + * + * Returned Value: + * None - The driver already agreed to transition to the low power + * consumption state when when it returned OK to the prepare() call. + * + * + ****************************************************************************/ + +#ifdef CONFIG_PM +static void stm32f0serial_pmnotify(FAR struct pm_callback_s *cb, int domain, + enum pm_state_e pmstate) +{ + switch (pmstate) + { + case(PM_NORMAL): + { + /* Logic for PM_NORMAL goes here */ + + } + break; + + case(PM_IDLE): + { + /* Logic for PM_IDLE goes here */ + + } + break; + + case(PM_STANDBY): + { + /* Logic for PM_STANDBY goes here */ + + } + break; + + case(PM_SLEEP): + { + /* Logic for PM_SLEEP goes here */ + + } + break; + + default: + /* Should not get here */ + break; + } +} +#endif + +/**************************************************************************** + * Name: stm32f0serial_pmprepare + * + * Description: + * Request the driver to prepare for a new power state. This is a warning + * that the system is about to enter into a new power state. The driver + * should begin whatever operations that may be required to enter power + * state. The driver may abort the state change mode by returning a + * non-zero value from the callback function. + * + * Input Parameters: + * + * cb - Returned to the driver. The driver version of the callback + * structure may include additional, driver-specific state data at + * the end of the structure. + * + * pmstate - Identifies the new PM state + * + * Returned Value: + * Zero - (OK) means the event was successfully processed and that the + * driver is prepared for the PM state change. + * + * Non-zero - means that the driver is not prepared to perform the tasks + * needed achieve this power setting and will cause the state + * change to be aborted. NOTE: The prepare() method will also + * be called when reverting from lower back to higher power + * consumption modes (say because another driver refused a + * lower power state change). Drivers are not permitted to + * return non-zero values when reverting back to higher power + * consumption modes! + * + ****************************************************************************/ + +#ifdef CONFIG_PM +static int stm32f0serial_pmprepare(FAR struct pm_callback_s *cb, int domain, + enum pm_state_e pmstate) +{ + /* Logic to prepare for a reduced power state goes here. */ + + return OK; +} +#endif +#endif /* HAVE_USART */ +#endif /* USE_SERIALDRIVER */ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +#ifdef USE_SERIALDRIVER + +/**************************************************************************** + * Name: up_earlyserialinit + * + * Description: + * Performs the low level USART initialization early in debug so that the + * serial console will be available during bootup. This must be called + * before stm32f0serial_getregit. + * + ****************************************************************************/ + +#ifdef USE_EARLYSERIALINIT +void up_earlyserialinit(void) +{ +#ifdef HAVE_USART + unsigned i; + + /* Disable all USART interrupts */ + + for (i = 0; i < STM32F0_NUSART; i++) + { + if (uart_devs[i]) + { + stm32f0serial_disableusartint(uart_devs[i], NULL); + } + } + + /* Configure whichever one is the console */ + +#if CONSOLE_USART > 0 + stm32f0serial_setup(&uart_devs[CONSOLE_USART - 1]->dev); +#endif +#endif /* HAVE UART */ +} +#endif + +/**************************************************************************** + * Name: stm32f0serial_getregit + * + * Description: + * Register serial console and serial ports. This assumes + * that up_earlyserialinit was called previously. + * + ****************************************************************************/ + +void up_serialinit(void) +{ +#ifdef HAVE_USART + char devname[16]; + unsigned i; + unsigned minor = 0; +#ifdef CONFIG_PM + int ret; +#endif + + /* Register to receive power management callbacks */ + +#ifdef CONFIG_PM + ret = pm_register(&g_serialcb); + DEBUGASSERT(ret == OK); + UNUSED(ret); +#endif + + /* Register the console */ + +#if CONSOLE_USART > 0 + (void)uart_register("/dev/console", &uart_devs[CONSOLE_USART - 1]->dev); + +#ifndef CONFIG_SERIAL_DISABLE_REORDERING + /* If not disabled, register the console UART to ttyS0 and exclude + * it from initializing it further down + */ + + (void)uart_register("/dev/ttyS0", &uart_devs[CONSOLE_USART - 1]->dev); + minor = 1; +#endif + +#ifdef SERIAL_HAVE_CONSOLE_DMA + /* If we need to re-initialise the console to enable DMA do that here. */ + + stm32f0serial_dmasetup(&uart_devs[CONSOLE_USART - 1]->dev); +#endif +#endif /* CONSOLE_USART > 0 */ + + /* Register all remaining USARTs */ + + strcpy(devname, "/dev/ttySx"); + + for (i = 0; i < STM32F0_NUSART; i++) + { + /* Don't create a device for non-configured ports. */ + + if (uart_devs[i] == 0) + { + continue; + } + +#ifndef CONFIG_SERIAL_DISABLE_REORDERING + /* Don't create a device for the console - we did that above */ + + if (uart_devs[i]->dev.isconsole) + { + continue; + } +#endif + + /* Register USARTs as devices in increasing order */ + + devname[9] = '0' + minor++; + (void)uart_register(devname, &uart_devs[i]->dev); + } +#endif /* HAVE UART */ +} + +/**************************************************************************** + * Name: stm32f0serial_dmapoll + * + * Description: + * Checks receive DMA buffers for received bytes that have not accumulated + * to the point where the DMA half/full interrupt has triggered. + * + * This function should be called from a timer or other periodic context. + * + ****************************************************************************/ + +#ifdef SERIAL_HAVE_DMA +void stm32f0serial_dmapoll(void) +{ + irqstate_t flags; + + flags = enter_critical_section(); + +#ifdef CONFIG_USART1_RXDMA + if (g_usart1priv.rxdma != NULL) + { + stm32f0serial_dmarxcallback(g_usart1priv.rxdma, 0, &g_usart1priv); + } +#endif + +#ifdef CONFIG_USART2_RXDMA + if (g_usart2priv.rxdma != NULL) + { + stm32f0serial_dmarxcallback(g_usart2priv.rxdma, 0, &g_usart2priv); + } +#endif + +#ifdef CONFIG_USART3_RXDMA + if (g_usart3priv.rxdma != NULL) + { + stm32f0serial_dmarxcallback(g_usart3priv.rxdma, 0, &g_usart3priv); + } +#endif + +#ifdef CONFIG_USART4_RXDMA + if (g_uart4priv.rxdma != NULL) + { + stm32f0serial_dmarxcallback(g_uart4priv.rxdma, 0, &g_uart4priv); + } +#endif + +#ifdef CONFIG_USART5_RXDMA + if (g_uart5priv.rxdma != NULL) + { + stm32f0serial_dmarxcallback(g_uart5priv.rxdma, 0, &g_uart5priv); + } +#endif + + leave_critical_section(flags); +} +#endif + +/**************************************************************************** + * Name: up_putc + * + * Description: + * Provide priority, low-level access to support OS debug writes + * + ****************************************************************************/ + +int up_putc(int ch) +{ +#if CONSOLE_USART > 0 + struct stm32f0_serial_s *priv = uart_devs[CONSOLE_USART - 1]; + uint16_t ie; + + stm32f0serial_disableusartint(priv, &ie); + + /* Check for LF */ + + if (ch == '\n') + { + /* Add CR */ + + up_lowputc('\r'); + } + + up_lowputc(ch); + stm32f0serial_restoreusartint(priv, ie); +#endif + return ch; +} + +#else /* USE_SERIALDRIVER */ + +/**************************************************************************** + * Name: up_putc + * + * Description: + * Provide priority, low-level access to support OS debug writes + * + ****************************************************************************/ + +int up_putc(int ch) +{ +#if CONSOLE_USART > 0 + /* Check for LF */ + + if (ch == '\n') + { + /* Add CR */ + + up_lowputc('\r'); + } + + up_lowputc(ch); +#endif + + return ch; +} + +#endif /* USE_SERIALDRIVER */ diff --git a/arch/arm/src/stm32f0/stm32f0_serial.h b/arch/arm/src/stm32f0/stm32f0_serial.h new file mode 100644 index 0000000000..4539b0cdb8 --- /dev/null +++ b/arch/arm/src/stm32f0/stm32f0_serial.h @@ -0,0 +1,82 @@ +/************************************************************************************ + * arch/arm/src/stm32f0/stm32f0_serial.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32F0_STM32F0_SERIAL_H +#define __ARCH_ARM_SRC_STM32F0_STM32F0_SERIAL_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include + +#include "chip/stm32f0_uart.h" +#include "chip/stm32f0_syscfg.h" + +#include "stm32f0_gpio.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Configuration *********************************************************************/ + +/* Are any UARTs enabled? */ + +#undef HAVE_UART +#if defined(CONFIG_STM32F0_UART0) +# define HAVE_UART 1 +#endif + +/* Is there a serial console? There should be at most one defined. It could be on + * any UARTn, n=0,1,2,3 + */ + +#if defined(CONFIG_UART0_SERIAL_CONSOLE) && defined(CONFIG_STM32F0_UART0) +# define HAVE_SERIAL_CONSOLE 1 +#else +# undef CONFIG_UART0_SERIAL_CONSOLE +# undef HAVE_SERIAL_CONSOLE +#endif + +/* We cannot allow the DLM/DLL divisor to become to small or will will lose too + * much accuracy. This following is a "fudge factor" that represents the minimum + * value of the divisor that we will permit. + */ + +#define UART_MINDL 32 + +#endif /* __ARCH_ARM_SRC_STM32F0_STM32F0_SERIAL_H */ diff --git a/arch/arm/src/stm32f0/stm32f0_start.c b/arch/arm/src/stm32f0/stm32f0_start.c new file mode 100644 index 0000000000..0c837698bb --- /dev/null +++ b/arch/arm/src/stm32f0/stm32f0_start.c @@ -0,0 +1,170 @@ +/**************************************************************************** + * arch/arm/src/stm32f0/stm32f0_start.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include +#include + +#include "up_arch.h" +#include "up_internal.h" + +#include "stm32f0_clockconfig.h" +#include "stm32f0_lowputc.h" + +#ifdef CONFIG_ARCH_FPU +# include "nvic.h" +#endif + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define IDLE_STACK ((uint32_t)&_ebss+CONFIG_IDLETHREAD_STACKSIZE-4) +#define HEAP_BASE ((uint32_t)&_ebss+CONFIG_IDLETHREAD_STACKSIZE) + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +const uint32_t g_idle_topstack = IDLE_STACK; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: showprogress + * + * Description: + * Print a character on the UART to show boot status. + * + ****************************************************************************/ + +#ifdef CONFIG_DEBUG_FEATURES +# define showprogress(c) up_lowputc(c) +#else +# define showprogress(c) +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: _start + * + * Description: + * This is the reset entry point. + * + ****************************************************************************/ + +void __start(void) +{ + const uint32_t *src; + uint32_t *dest; + + /* Configure the uart so that we can get debug output as soon as possible */ + + stm32f0_clockconfig(); + stm32f0_lowsetup(); + showprogress('A'); + + /* Clear .bss. We'll do this inline (vs. calling memset) just to be + * certain that there are no issues with the state of global variables. + */ + + for (dest = &_sbss; dest < &_ebss; ) + { + *dest++ = 0; + } + + showprogress('B'); + + /* Move the initialized data section from his temporary holding spot in + * FLASH into the correct place in SRAM. The correct place in SRAM is + * give by _sdata and _edata. The temporary location is in FLASH at the + * end of all of the other read-only data (.text, .rodata) at _eronly. + */ + + for (src = &_eronly, dest = &_sdata; dest < &_edata; ) + { + *dest++ = *src++; + } + + showprogress('C'); + + /* Perform early serial initialization */ + +#ifdef USE_EARLYSERIALINIT + up_earlyserialinit(); +#endif + showprogress('D'); + + /* For the case of the separate user-/kernel-space build, perform whatever + * platform specific initialization of the user memory is required. + * Normally this just means initializing the user space .data and .bss + * segments. + */ + +#ifdef CONFIG_BUILD_PROTECTED + stm32f0_userspace(); + showprogress('E'); +#endif + + /* Initialize onboard resources */ + + stm32f0_boardinitialize(); + showprogress('F'); + + /* Then start NuttX */ + + showprogress('\r'); + showprogress('\n'); + + os_start(); + + /* Shouldn't get here */ + + for (; ; ); +} diff --git a/arch/arm/src/stm32f0/stm32f0_timerisr.c b/arch/arm/src/stm32f0/stm32f0_timerisr.c new file mode 100644 index 0000000000..07c7a1c57d --- /dev/null +++ b/arch/arm/src/stm32f0/stm32f0_timerisr.c @@ -0,0 +1,164 @@ +/**************************************************************************** + * arch/arm/src/stm32f0/stm32f0_timerisr.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#include "nvic.h" +#include "clock/clock.h" +#include "up_internal.h" +#include "up_arch.h" + +#include "chip.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* "The CLKSOURCE bit in SysTick Control and Status register selects either + * the core clock (when CLKSOURCE = 1) or a divide-by-16 of the core clock + * (when CLKSOURCE = 0). ..." + */ + +#if defined(CONFIG_STM32F0_SYSTICK_CORECLK) +# define SYSTICK_CLOCK STM32F0_MCLK /* Core clock */ +#elif defined(CONFIG_STM32F0_SYSTICK_CORECLK_DIV16) +# define SYSTICK_CLOCK (STM32F0_MCLK / 16) /* Core clock divided by 16 */ +#endif + +/* The desired timer interrupt frequency is provided by the definition + * CLK_TCK (see include/time.h). CLK_TCK defines the desired number of + * system clock ticks per second. That value is a user configurable setting + * that defaults to 100 (100 ticks per second = 10 MS interval). + * + * Then, for example, if the external high speed crystal is the SysTick + * clock source and BOARD_XTALHI_FREQUENCY is 12MHz and CLK_TCK is 100, then + * the reload value would be: + * + * SYSTICK_RELOAD = (12,000,000 / 100) - 1 + * = 119,999 + * = 0x1d4bf + * + * Which fits within the maximum 24-bit reload value. + */ + +#define SYSTICK_RELOAD ((SYSTICK_CLOCK / CLK_TCK) - 1) + +/* The size of the reload field is 24 bits. Verify that the reload value + * will fit in the reload register. + */ + +#if SYSTICK_RELOAD > 0x00ffffff +# error SYSTICK_RELOAD exceeds the range of the RELOAD register +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: stm32f0_timerisr + * + * Description: + * The timer ISR will perform a variety of services for various portions + * of the systems. + * + ****************************************************************************/ + +static int stm32f0_timerisr(int irq, uint32_t *regs, FAR void *arg) +{ + /* Process timer interrupt */ + + sched_process_timer(); + return 0; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: arm_timer_initialize + * + * Description: + * This function is called during start-up to initialize + * the timer interrupt. + * + ****************************************************************************/ + +void arm_timer_initialize(void) +{ + uint32_t regval; + + /* Set the SysTick interrupt to the default priority */ + + regval = getreg32(ARMV6M_SYSCON_SHPR3); + regval &= ~SYSCON_SHPR3_PRI_15_MASK; + regval |= (NVIC_SYSH_PRIORITY_DEFAULT << SYSCON_SHPR3_PRI_15_SHIFT); + putreg32(regval, ARMV6M_SYSCON_SHPR3); + + /* Configure SysTick to interrupt at the requested rate */ + + putreg32(SYSTICK_RELOAD, ARMV6M_SYSTICK_RVR); + + /* Attach the timer interrupt vector */ + + (void)irq_attach(STM32F0_IRQ_SYSTICK, (xcpt_t)stm32f0_timerisr, NULL); + + /* Enable SysTick interrupts. "The CLKSOURCE bit in SysTick Control and + * Status register selects either the core clock (when CLKSOURCE = 1) or + * a divide-by-16 of the core clock (when CLKSOURCE = 0). ..." + */ + +#ifdef CONFIG_STM32F0_SYSTICK_CORECLK + putreg32((SYSTICK_CSR_CLKSOURCE | SYSTICK_CSR_TICKINT | SYSTICK_CSR_ENABLE), + ARMV6M_SYSTICK_CSR); +#else + putreg32((SYSTICK_CSR_TICKINT | SYSTICK_CSR_ENABLE), ARMV6M_SYSTICK_CSR); +#endif + + /* And enable the timer interrupt */ + + up_enable_irq(STM32F0_IRQ_SYSTICK); +} diff --git a/arch/arm/src/stm32f0/stm32f0_uart.h b/arch/arm/src/stm32f0/stm32f0_uart.h new file mode 100644 index 0000000000..d3ee1d7d45 --- /dev/null +++ b/arch/arm/src/stm32f0/stm32f0_uart.h @@ -0,0 +1,433 @@ +/************************************************************************************ + * arch/arm/src/stm32/stm32f0_uart.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_STC_STM32F0_STM32F0_UART_H +#define __ARCH_ARM_STC_STM32F0_STM32F0_UART_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include "chip.h" + +#include "chip/stm32f0_uart.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* Make sure that we have not enabled more U[S]ARTs than are supported by the + * device. + */ + +#if STM32F0_NUSART < 8 || !defined(CONFIG_STM32F0_HAVE_USART8) +# undef CONFIG_STM32F0_USART8 +#endif +#if STM32F0_NUSART < 7 || !defined(CONFIG_STM32F0_HAVE_USART7) +# undef CONFIG_STM32F0_USART7 +#endif +#if STM32F0_NUSART < 6 || !defined(CONFIG_STM32F0_HAVE_USART6) +# undef CONFIG_STM32F0_USART6 +#endif +#if STM32F0_NUSART < 5 || !defined(CONFIG_STM32F0_HAVE_USART5) +# undef CONFIG_STM32F0_USART5 +#endif +#if STM32F0_NUSART < 4 || !defined(CONFIG_STM32F0_HAVE_USART4) +# undef CONFIG_STM32F0_USART4 +#endif +#if STM32F0_NUSART < 3 || !defined(CONFIG_STM32F0_HAVE_USART3) +# undef CONFIG_STM32F0_USART3 +#endif +#if STM32F0_NUSART < 2 +# undef CONFIG_STM32F0_USART2 +#endif +#if STM32F0_NUSART < 1 +# undef CONFIG_STM32F0_USART1 +#endif + +/* Is there a USART enabled? */ + +#if defined(CONFIG_STM32F0_USART1) || defined(CONFIG_STM32F0_USART2) || \ + defined(CONFIG_STM32F0_USART3) || defined(CONFIG_STM32F0_USART4) || \ + defined(CONFIG_STM32F0_USART5) +# define HAVE_USART 1 +#endif + +/* Sanity checks */ + +#if !defined(CONFIG_STM32F0_USART1) +# undef CONFIG_STM32F0_USART1_SERIALDRIVER +# undef CONFIG_STM32F0_USART1_1WIREDRIVER +#endif +#if !defined(CONFIG_STM32F0_USART2) +# undef CONFIG_STM32F0_USART2_SERIALDRIVER +# undef CONFIG_STM32F0_USART2_1WIREDRIVER +#endif +#if !defined(CONFIG_STM32F0_USART3) +# undef CONFIG_STM32F0_USART3_SERIALDRIVER +# undef CONFIG_STM32F0_USART3_1WIREDRIVER +#endif +#if !defined(CONFIG_STM32F0_USART4) +# undef CONFIG_STM32F0_USART4_SERIALDRIVER +# undef CONFIG_STM32F0_USART4_1WIREDRIVER +#endif +#if !defined(CONFIG_STM32F0_USART5) +# undef CONFIG_STM32F0_USART5_SERIALDRIVER +# undef CONFIG_STM32F0_USART5_1WIREDRIVER +#endif +#if !defined(CONFIG_STM32F0_USART6) +# undef CONFIG_STM32F0_USART6_SERIALDRIVER +# undef CONFIG_STM32F0_USART6_1WIREDRIVER +#endif +#if !defined(CONFIG_STM32F0_USART7) +# undef CONFIG_STM32F0_USART7_SERIALDRIVER +# undef CONFIG_STM32F0_USART7_1WIREDRIVER +#endif +#if !defined(CONFIG_STM32F0_USART8) +# undef CONFIG_STM32F0_USART8_SERIALDRIVER +# undef CONFIG_STM32F0_USART8_1WIREDRIVER +#endif + +/* Check 1-Wire and U(S)ART conflicts */ + +#if defined(CONFIG_STM32F0_USART1_1WIREDRIVER) && defined(CONFIG_STM32F0_USART1_SERIALDRIVER) +# error Both CONFIG_STM32F0_USART1_1WIREDRIVER and CONFIG_STM32F0_USART1_SERIALDRIVER defined +# undef CONFIG_STM32F0_USART1_1WIREDRIVER +#endif +#if defined(CONFIG_STM32F0_USART2_1WIREDRIVER) && defined(CONFIG_STM32F0_USART2_SERIALDRIVER) +# error Both CONFIG_STM32F0_USART2_1WIREDRIVER and CONFIG_STM32F0_USART2_SERIALDRIVER defined +# undef CONFIG_STM32F0_USART2_1WIREDRIVER +#endif +#if defined(CONFIG_STM32F0_USART3_1WIREDRIVER) && defined(CONFIG_STM32F0_USART3_SERIALDRIVER) +# error Both CONFIG_STM32F0_USART3_1WIREDRIVER and CONFIG_STM32F0_USART3_SERIALDRIVER defined +# undef CONFIG_STM32F0_USART3_1WIREDRIVER +#endif +#if defined(CONFIG_STM32F0_USART4_1WIREDRIVER) && defined(CONFIG_STM32F0_USART4_SERIALDRIVER) +# error Both CONFIG_STM32F0_USART4_1WIREDRIVER and CONFIG_STM32F0_USART4_SERIALDRIVER defined +# undef CONFIG_STM32F0_USART4_1WIREDRIVER +#endif +#if defined(CONFIG_STM32F0_USART5_1WIREDRIVER) && defined(CONFIG_STM32F0_USART5_SERIALDRIVER) +# error Both CONFIG_STM32F0_USART5_1WIREDRIVER and CONFIG_STM32F0_USART5_SERIALDRIVER defined +# undef CONFIG_STM32F0_USART5_1WIREDRIVER +#endif +#if defined(CONFIG_STM32F0_USART6_1WIREDRIVER) && defined(CONFIG_STM32F0_USART6_SERIALDRIVER) +# error Both CONFIG_STM32F0_USART6_1WIREDRIVER and CONFIG_STM32F0_USART6_SERIALDRIVER defined +# undef CONFIG_STM32F0_USART6_1WIREDRIVER +#endif +#if defined(CONFIG_STM32F0_USART7_1WIREDRIVER) && defined(CONFIG_STM32F0_USART7_SERIALDRIVER) +# error Both CONFIG_STM32F0_USART7_1WIREDRIVER and CONFIG_STM32F0_USART7_SERIALDRIVER defined +# undef CONFIG_STM32F0_USART7_1WIREDRIVER +#endif +#if defined(CONFIG_STM32F0_USART8_1WIREDRIVER) && defined(CONFIG_STM32F0_USART8_SERIALDRIVER) +# error Both CONFIG_STM32F0_USART8_1WIREDRIVER and CONFIG_STM32F0_USART8_SERIALDRIVER defined +# undef CONFIG_STM32F0_USART8_1WIREDRIVER +#endif + +/* Is the serial driver enabled? */ + +#if defined(CONFIG_STM32F0_USART1_SERIALDRIVER) || defined(CONFIG_STM32F0_USART2_SERIALDRIVER) || \ + defined(CONFIG_STM32F0_USART3_SERIALDRIVER) || defined(CONFIG_STM32F0_USART4_SERIALDRIVER) || \ + defined(CONFIG_STM32F0_USART5_SERIALDRIVER) || defined(CONFIG_STM32F0_USART6_SERIALDRIVER) || \ + defined(CONFIG_STM32F0_USART7_SERIALDRIVER) || defined(CONFIG_STM32F0_USART8_SERIALDRIVER) +# define HAVE_SERIALDRIVER 1 +#endif + +/* Is the 1-Wire driver? */ + +#if defined(CONFIG_STM32F0_USART1_1WIREDRIVER) || defined(CONFIG_STM32F0_USART2_1WIREDRIVER) || \ + defined(CONFIG_STM32F0_USART3_1WIREDRIVER) || defined(CONFIG_STM32F0_USART4_1WIREDRIVER) || \ + defined(CONFIG_STM32F0_USART5_1WIREDRIVER) || defined(CONFIG_STM32F0_USART6_1WIREDRIVER) || \ + defined(CONFIG_STM32F0_USART7_1WIREDRIVER) || defined(CONFIG_STM32F0_USART8_1WIREDRIVER) +# define HAVE_1WIREDRIVER 1 +#endif + +/* Is there a serial console? */ + +#if defined(CONFIG_USART1_SERIAL_CONSOLE) && defined(CONFIG_STM32F0_USART1_SERIALDRIVER) +# undef CONFIG_USART2_SERIAL_CONSOLE +# undef CONFIG_USART3_SERIAL_CONSOLE +# undef CONFIG_USART4_SERIAL_CONSOLE +# undef CONFIG_USART5_SERIAL_CONSOLE +# undef CONFIG_USART6_SERIAL_CONSOLE +# undef CONFIG_USART7_SERIAL_CONSOLE +# undef CONFIG_USART8_SERIAL_CONSOLE +# define CONSOLE_USART 1 +# define HAVE_CONSOLE 1 +#elif defined(CONFIG_USART2_SERIAL_CONSOLE) && defined(CONFIG_STM32F0_USART2_SERIALDRIVER) +# undef CONFIG_USART1_SERIAL_CONSOLE +# undef CONFIG_USART3_SERIAL_CONSOLE +# undef CONFIG_USART4_SERIAL_CONSOLE +# undef CONFIG_USART5_SERIAL_CONSOLE +# undef CONFIG_USART6_SERIAL_CONSOLE +# undef CONFIG_USART7_SERIAL_CONSOLE +# undef CONFIG_USART8_SERIAL_CONSOLE +# define CONSOLE_USART 2 +# define HAVE_CONSOLE 1 +#elif defined(CONFIG_USART3_SERIAL_CONSOLE) && defined(CONFIG_STM32F0_USART3_SERIALDRIVER) +# undef CONFIG_USART1_SERIAL_CONSOLE +# undef CONFIG_USART2_SERIAL_CONSOLE +# undef CONFIG_USART4_SERIAL_CONSOLE +# undef CONFIG_USART5_SERIAL_CONSOLE +# undef CONFIG_USART6_SERIAL_CONSOLE +# undef CONFIG_USART7_SERIAL_CONSOLE +# undef CONFIG_USART8_SERIAL_CONSOLE +# define CONSOLE_USART 3 +# define HAVE_CONSOLE 1 +#elif defined(CONFIG_USART4_SERIAL_CONSOLE) && defined(CONFIG_STM32F0_USART4_SERIALDRIVER) +# undef CONFIG_USART1_SERIAL_CONSOLE +# undef CONFIG_USART2_SERIAL_CONSOLE +# undef CONFIG_USART3_SERIAL_CONSOLE +# undef CONFIG_USART5_SERIAL_CONSOLE +# undef CONFIG_USART6_SERIAL_CONSOLE +# undef CONFIG_USART7_SERIAL_CONSOLE +# undef CONFIG_USART8_SERIAL_CONSOLE +# define CONSOLE_USART 4 +# define HAVE_CONSOLE 1 +#elif defined(CONFIG_USART5_SERIAL_CONSOLE) && defined(CONFIG_STM32F0_USART5_SERIALDRIVER) +# undef CONFIG_USART1_SERIAL_CONSOLE +# undef CONFIG_USART2_SERIAL_CONSOLE +# undef CONFIG_USART3_SERIAL_CONSOLE +# undef CONFIG_USART4_SERIAL_CONSOLE +# undef CONFIG_USART6_SERIAL_CONSOLE +# undef CONFIG_USART7_SERIAL_CONSOLE +# undef CONFIG_USART8_SERIAL_CONSOLE +# define CONSOLE_USART 5 +# define HAVE_CONSOLE 1 +#elif defined(CONFIG_USART6_SERIAL_CONSOLE) && defined(CONFIG_STM32F0_USART6_SERIALDRIVER) +# undef CONFIG_USART1_SERIAL_CONSOLE +# undef CONFIG_USART2_SERIAL_CONSOLE +# undef CONFIG_USART3_SERIAL_CONSOLE +# undef CONFIG_USART4_SERIAL_CONSOLE +# undef CONFIG_USART5_SERIAL_CONSOLE +# undef CONFIG_USART7_SERIAL_CONSOLE +# undef CONFIG_USART8_SERIAL_CONSOLE +# define CONSOLE_USART 6 +# define HAVE_CONSOLE 1 +#elif defined(CONFIG_USART7_SERIAL_CONSOLE) && defined(CONFIG_STM32F0_USART7_SERIALDRIVER) +# undef CONFIG_USART1_SERIAL_CONSOLE +# undef CONFIG_USART2_SERIAL_CONSOLE +# undef CONFIG_USART3_SERIAL_CONSOLE +# undef CONFIG_USART4_SERIAL_CONSOLE +# undef CONFIG_USART5_SERIAL_CONSOLE +# undef CONFIG_USART6_SERIAL_CONSOLE +# undef CONFIG_USART5_SERIAL_CONSOLE +# undef CONFIG_USART8_SERIAL_CONSOLE +# define CONSOLE_USART 7 +# define HAVE_CONSOLE 1 +#elif defined(CONFIG_USART8_SERIAL_CONSOLE) && defined(CONFIG_STM32F0_USART8_SERIALDRIVER) +# undef CONFIG_USART1_SERIAL_CONSOLE +# undef CONFIG_USART2_SERIAL_CONSOLE +# undef CONFIG_USART3_SERIAL_CONSOLE +# undef CONFIG_USART4_SERIAL_CONSOLE +# undef CONFIG_USART6_SERIAL_CONSOLE +# undef CONFIG_USART6_SERIAL_CONSOLE +# undef CONFIG_USART7_SERIAL_CONSOLE +# define CONSOLE_USART 8 +# define HAVE_CONSOLE 1 +#else +# undef CONFIG_USART1_SERIAL_CONSOLE +# undef CONFIG_USART2_SERIAL_CONSOLE +# undef CONFIG_USART3_SERIAL_CONSOLE +# undef CONFIG_USART4_SERIAL_CONSOLE +# undef CONFIG_USART5_SERIAL_CONSOLE +# undef CONFIG_USART6_SERIAL_CONSOLE +# undef CONFIG_USART7_SERIAL_CONSOLE +# undef CONFIG_USART8_SERIAL_CONSOLE +# define CONSOLE_USART 0 +# undef HAVE_CONSOLE +#endif + +/* DMA support is only provided if CONFIG_ARCH_DMA is in the NuttX configuration */ + +#if !defined(HAVE_SERIALDRIVER) || !defined(CONFIG_ARCH_DMA) +# undef CONFIG_USART1_RXDMA +# undef CONFIG_USART2_RXDMA +# undef CONFIG_USART3_RXDMA +# undef CONFIG_USART4_RXDMA +# undef CONFIG_USART5_RXDMA +# undef CONFIG_USART6_RXDMA +# undef CONFIG_USART7_RXDMA +# undef CONFIG_USART8_RXDMA +#endif + +/* Disable the DMA configuration on all unused USARTs */ + +#ifndef CONFIG_STM32F0_USART1_SERIALDRIVER +# undef CONFIG_USART1_RXDMA +#endif + +#ifndef CONFIG_STM32F0_USART2_SERIALDRIVER +# undef CONFIG_USART2_RXDMA +#endif + +#ifndef CONFIG_STM32F0_USART3_SERIALDRIVER +# undef CONFIG_USART3_RXDMA +#endif + +#ifndef CONFIG_STM32F0_USART4_SERIALDRIVER +# undef CONFIG_USART4_RXDMA +#endif + +#ifndef CONFIG_STM32F0_USART5_SERIALDRIVER +# undef CONFIG_USART5_RXDMA +#endif + +#ifndef CONFIG_STM32F0_USART6_SERIALDRIVER +# undef CONFIG_USART6_RXDMA +#endif + +#ifndef CONFIG_STM32F0_USART7_SERIALDRIVER +# undef CONFIG_USART7_RXDMA +#endif + +#ifndef CONFIG_STM32F0_USART8_SERIALDRIVER +# undef CONFIG_USART8_RXDMA +#endif + +/* Is DMA available on any (enabled) USART? */ + +#undef SERIAL_HAVE_DMA +#if defined(CONFIG_USART1_RXDMA) || defined(CONFIG_USART2_RXDMA) || \ + defined(CONFIG_USART3_RXDMA) || defined(CONFIG_USART4_RXDMA) || \ + defined(CONFIG_USART5_RXDMA) || defined(CONFIG_USART6_RXDMA) || \ + defined(CONFIG_USART7_RXDMA) || defined(CONFIG_USART8_RXDMA) +# define SERIAL_HAVE_DMA 1 +#endif + +/* Is DMA used on the console USART? */ + +#undef SERIAL_HAVE_CONSOLE_DMA +#if defined(CONFIG_USART1_SERIAL_CONSOLE) && defined(CONFIG_USART1_RXDMA) +# define SERIAL_HAVE_CONSOLE_DMA 1 +#elif defined(CONFIG_USART2_SERIAL_CONSOLE) && defined(CONFIG_USART2_RXDMA) +# define SERIAL_HAVE_CONSOLE_DMA 1 +#elif defined(CONFIG_USART3_SERIAL_CONSOLE) && defined(CONFIG_USART3_RXDMA) +# define SERIAL_HAVE_CONSOLE_DMA 1 +#elif defined(CONFIG_USART4_SERIAL_CONSOLE) && defined(CONFIG_USART4_RXDMA) +# define SERIAL_HAVE_CONSOLE_DMA 1 +#elif defined(CONFIG_USART5_SERIAL_CONSOLE) && defined(CONFIG_USART5_RXDMA) +# define SERIAL_HAVE_CONSOLE_DMA 1 +#elif defined(CONFIG_USART6_SERIAL_CONSOLE) && defined(CONFIG_USART6_RXDMA) +# define SERIAL_HAVE_CONSOLE_DMA 1 +#elif defined(CONFIG_USART7_SERIAL_CONSOLE) && defined(CONFIG_USART7_RXDMA) +# define SERIAL_HAVE_CONSOLE_DMA 1 +#elif defined(CONFIG_USART8_SERIAL_CONSOLE) && defined(CONFIG_USART8_RXDMA) +# define SERIAL_HAVE_CONSOLE_DMA 1 +#endif + +/* Is DMA used on all (enabled) USARTs */ + +#define SERIAL_HAVE_ONLY_DMA 1 +#if defined(CONFIG_STM32F0_USART1_SERIALDRIVER) && !defined(CONFIG_USART1_RXDMA) +# undef SERIAL_HAVE_ONLY_DMA +#elif defined(CONFIG_STM32F0_USART2_SERIALDRIVER) && !defined(CONFIG_USART2_RXDMA) +# undef SERIAL_HAVE_ONLY_DMA +#elif defined(CONFIG_STM32F0_USART3_SERIALDRIVER) && !defined(CONFIG_USART3_RXDMA) +# undef SERIAL_HAVE_ONLY_DMA +#elif defined(CONFIG_STM32F0_USART4_SERIALDRIVER) && !defined(CONFIG_USART4_RXDMA) +# undef SERIAL_HAVE_ONLY_DMA +#elif defined(CONFIG_STM32F0_USART5_SERIALDRIVER) && !defined(CONFIG_USART5_RXDMA) +# undef SERIAL_HAVE_ONLY_DMA +#elif defined(CONFIG_STM32F0_USART6_SERIALDRIVER) && !defined(CONFIG_USART6_RXDMA) +# undef SERIAL_HAVE_ONLY_DMA +#elif defined(CONFIG_STM32F0_USART7_SERIALDRIVER) && !defined(CONFIG_USART7_RXDMA) +# undef SERIAL_HAVE_ONLY_DMA +#elif defined(CONFIG_STM32F0_USART8_SERIALDRIVER) && !defined(CONFIG_USART8_RXDMA) +# undef SERIAL_HAVE_ONLY_DMA +#endif + +/* Is RS-485 used? */ + +#if defined(CONFIG_USART1_RS485) || defined(CONFIG_USART2_RS485) || \ + defined(CONFIG_USART3_RS485) || defined(CONFIG_USART4_RS485) || \ + defined(CONFIG_USART5_RS485) || defined(CONFIG_USART6_RS485) || \ + defined(CONFIG_USART7_RS485) || defined(CONFIG_USART8_RS485) +# define HAVE_RS485 1 +#endif + +#ifdef HAVE_RS485 +# define USART_CR1_USED_INTS (USART_CR1_RXNEIE | USART_CR1_TXEIE | USART_CR1_PEIE | USART_CR1_TCIE) +#else +# define USART_CR1_USED_INTS (USART_CR1_RXNEIE | USART_CR1_TXEIE | USART_CR1_PEIE) +#endif + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32f0_serial_dma_poll + * + * Description: + * Must be called periodically if any STM32 USART is configured for DMA. The DMA + * callback is triggered for each fifo size/2 bytes, but this can result in some + * bytes being transferred but not collected if the incoming data is not a whole + * multiple of half the FIFO size. + * + * May be safely called from either interrupt or thread context. + * + ************************************************************************************/ + +#ifdef SERIAL_HAVE_DMA +void stm32f0_serial_dma_poll(void); +#endif + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __ARCH_ARM_STC_STM32F0_STM32F0_UART_H */ -- GitLab From c910334ced35d79d9e9caf68e788f4adabc4463d Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 14 Apr 2017 08:13:18 -0600 Subject: [PATCH 434/990] Make sure that Alan is listed as author in new files. --- arch/arm/include/stm32f0/chip.h | 1 + arch/arm/include/stm32f0/irq.h | 1 + arch/arm/src/stm32f0/Make.defs | 1 + arch/arm/src/stm32f0/chip.h | 1 + arch/arm/src/stm32f0/chip/stm32f05xr_pinmap.h | 1 + arch/arm/src/stm32f0/chip/stm32f05xxx_memorymap.h | 1 + arch/arm/src/stm32f0/chip/stm32f0_adc.h | 1 + arch/arm/src/stm32f0/chip/stm32f0_can.h | 1 + arch/arm/src/stm32f0/chip/stm32f0_comp.h | 1 + arch/arm/src/stm32f0/chip/stm32f0_crc.h | 1 + arch/arm/src/stm32f0/chip/stm32f0_crs.h | 1 + arch/arm/src/stm32f0/chip/stm32f0_dac.h | 1 + arch/arm/src/stm32f0/chip/stm32f0_dma.h | 1 + arch/arm/src/stm32f0/chip/stm32f0_exti.h | 1 + arch/arm/src/stm32f0/chip/stm32f0_gpio.h | 1 + arch/arm/src/stm32f0/chip/stm32f0_i2c.h | 1 + arch/arm/src/stm32f0/chip/stm32f0_memorymap.h | 1 + arch/arm/src/stm32f0/chip/stm32f0_pwr.h | 1 + arch/arm/src/stm32f0/chip/stm32f0_rcc.h | 1 + arch/arm/src/stm32f0/chip/stm32f0_rtcc.h | 1 + arch/arm/src/stm32f0/chip/stm32f0_syscfg.h | 1 + arch/arm/src/stm32f0/chip/stm32f0_tim.h | 1 + arch/arm/src/stm32f0/chip/stm32f0_uart.h | 1 + arch/arm/src/stm32f0/chip/stm32f0_usbdev.h | 1 + arch/arm/src/stm32f0/chip/stm32f0_wdt.h | 1 + arch/arm/src/stm32f0/stm32f0_clockconfig.c | 1 + arch/arm/src/stm32f0/stm32f0_clockconfig.h | 1 + arch/arm/src/stm32f0/stm32f0_gpio.c | 1 + arch/arm/src/stm32f0/stm32f0_gpio.h | 1 + arch/arm/src/stm32f0/stm32f0_idle.c | 1 + arch/arm/src/stm32f0/stm32f0_irq.c | 1 + arch/arm/src/stm32f0/stm32f0_lowputc.c | 1 + arch/arm/src/stm32f0/stm32f0_lowputc.h | 1 + arch/arm/src/stm32f0/stm32f0_rcc.h | 1 + arch/arm/src/stm32f0/stm32f0_serial.c | 1 + arch/arm/src/stm32f0/stm32f0_serial.h | 1 + arch/arm/src/stm32f0/stm32f0_start.c | 1 + arch/arm/src/stm32f0/stm32f0_timerisr.c | 1 + arch/arm/src/stm32f0/stm32f0_uart.h | 1 + 39 files changed, 39 insertions(+) diff --git a/arch/arm/include/stm32f0/chip.h b/arch/arm/include/stm32f0/chip.h index e8c2363680..754cfce616 100644 --- a/arch/arm/include/stm32f0/chip.h +++ b/arch/arm/include/stm32f0/chip.h @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/include/stm32f0/irq.h b/arch/arm/include/stm32f0/irq.h index 4d3fd84d8d..298def1fa0 100644 --- a/arch/arm/include/stm32f0/irq.h +++ b/arch/arm/include/stm32f0/irq.h @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/Make.defs b/arch/arm/src/stm32f0/Make.defs index 6a42cddc97..b54aa7c348 100644 --- a/arch/arm/src/stm32f0/Make.defs +++ b/arch/arm/src/stm32f0/Make.defs @@ -3,6 +3,7 @@ # # Copyright (C) 2017 Gregory Nutt. All rights reserved. # Author: Gregory Nutt + * Alan Carvalho de Assis # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/chip.h b/arch/arm/src/stm32f0/chip.h index 5bf33a0e23..0300f9f7da 100644 --- a/arch/arm/src/stm32f0/chip.h +++ b/arch/arm/src/stm32f0/chip.h @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/chip/stm32f05xr_pinmap.h b/arch/arm/src/stm32f0/chip/stm32f05xr_pinmap.h index 29ee3e5f01..63b2c51f0b 100644 --- a/arch/arm/src/stm32f0/chip/stm32f05xr_pinmap.h +++ b/arch/arm/src/stm32f0/chip/stm32f05xr_pinmap.h @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/chip/stm32f05xxx_memorymap.h b/arch/arm/src/stm32f0/chip/stm32f05xxx_memorymap.h index 0c0ad1a40d..fc85a81fd7 100644 --- a/arch/arm/src/stm32f0/chip/stm32f05xxx_memorymap.h +++ b/arch/arm/src/stm32f0/chip/stm32f05xxx_memorymap.h @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/chip/stm32f0_adc.h b/arch/arm/src/stm32f0/chip/stm32f0_adc.h index a516e99b20..00ecab0d64 100644 --- a/arch/arm/src/stm32f0/chip/stm32f0_adc.h +++ b/arch/arm/src/stm32f0/chip/stm32f0_adc.h @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/chip/stm32f0_can.h b/arch/arm/src/stm32f0/chip/stm32f0_can.h index 97fb9e7ad0..05174ef1de 100644 --- a/arch/arm/src/stm32f0/chip/stm32f0_can.h +++ b/arch/arm/src/stm32f0/chip/stm32f0_can.h @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/chip/stm32f0_comp.h b/arch/arm/src/stm32f0/chip/stm32f0_comp.h index 85284cd476..f611f98ac3 100644 --- a/arch/arm/src/stm32f0/chip/stm32f0_comp.h +++ b/arch/arm/src/stm32f0/chip/stm32f0_comp.h @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Mateusz Szafoni + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/chip/stm32f0_crc.h b/arch/arm/src/stm32f0/chip/stm32f0_crc.h index beb4e625b1..ca21026674 100644 --- a/arch/arm/src/stm32f0/chip/stm32f0_crc.h +++ b/arch/arm/src/stm32f0/chip/stm32f0_crc.h @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/chip/stm32f0_crs.h b/arch/arm/src/stm32f0/chip/stm32f0_crs.h index 61f26d10ae..ae2f3cd5cd 100644 --- a/arch/arm/src/stm32f0/chip/stm32f0_crs.h +++ b/arch/arm/src/stm32f0/chip/stm32f0_crs.h @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/chip/stm32f0_dac.h b/arch/arm/src/stm32f0/chip/stm32f0_dac.h index ace8a9991a..d4d1900999 100644 --- a/arch/arm/src/stm32f0/chip/stm32f0_dac.h +++ b/arch/arm/src/stm32f0/chip/stm32f0_dac.h @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/chip/stm32f0_dma.h b/arch/arm/src/stm32f0/chip/stm32f0_dma.h index f14ddb1efe..b362d24d59 100644 --- a/arch/arm/src/stm32f0/chip/stm32f0_dma.h +++ b/arch/arm/src/stm32f0/chip/stm32f0_dma.h @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/chip/stm32f0_exti.h b/arch/arm/src/stm32f0/chip/stm32f0_exti.h index 2fae0979f2..a181473668 100644 --- a/arch/arm/src/stm32f0/chip/stm32f0_exti.h +++ b/arch/arm/src/stm32f0/chip/stm32f0_exti.h @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/chip/stm32f0_gpio.h b/arch/arm/src/stm32f0/chip/stm32f0_gpio.h index a371da57c9..7f7cd39516 100644 --- a/arch/arm/src/stm32f0/chip/stm32f0_gpio.h +++ b/arch/arm/src/stm32f0/chip/stm32f0_gpio.h @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/chip/stm32f0_i2c.h b/arch/arm/src/stm32f0/chip/stm32f0_i2c.h index 7eb7c124d2..dc67742478 100644 --- a/arch/arm/src/stm32f0/chip/stm32f0_i2c.h +++ b/arch/arm/src/stm32f0/chip/stm32f0_i2c.h @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/chip/stm32f0_memorymap.h b/arch/arm/src/stm32f0/chip/stm32f0_memorymap.h index f2dffd1d90..704b3466aa 100644 --- a/arch/arm/src/stm32f0/chip/stm32f0_memorymap.h +++ b/arch/arm/src/stm32f0/chip/stm32f0_memorymap.h @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/chip/stm32f0_pwr.h b/arch/arm/src/stm32f0/chip/stm32f0_pwr.h index 7eed5837ed..609d6712a0 100644 --- a/arch/arm/src/stm32f0/chip/stm32f0_pwr.h +++ b/arch/arm/src/stm32f0/chip/stm32f0_pwr.h @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/chip/stm32f0_rcc.h b/arch/arm/src/stm32f0/chip/stm32f0_rcc.h index caf1cec7e2..aed20d1608 100644 --- a/arch/arm/src/stm32f0/chip/stm32f0_rcc.h +++ b/arch/arm/src/stm32f0/chip/stm32f0_rcc.h @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/chip/stm32f0_rtcc.h b/arch/arm/src/stm32f0/chip/stm32f0_rtcc.h index e887e88baf..dbb11322fb 100644 --- a/arch/arm/src/stm32f0/chip/stm32f0_rtcc.h +++ b/arch/arm/src/stm32f0/chip/stm32f0_rtcc.h @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/chip/stm32f0_syscfg.h b/arch/arm/src/stm32f0/chip/stm32f0_syscfg.h index 4715a43d2d..9d53a3d893 100644 --- a/arch/arm/src/stm32f0/chip/stm32f0_syscfg.h +++ b/arch/arm/src/stm32f0/chip/stm32f0_syscfg.h @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/chip/stm32f0_tim.h b/arch/arm/src/stm32f0/chip/stm32f0_tim.h index 048da45690..12add9370f 100644 --- a/arch/arm/src/stm32f0/chip/stm32f0_tim.h +++ b/arch/arm/src/stm32f0/chip/stm32f0_tim.h @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/chip/stm32f0_uart.h b/arch/arm/src/stm32f0/chip/stm32f0_uart.h index 1a35d401b7..3b7ff61da9 100644 --- a/arch/arm/src/stm32f0/chip/stm32f0_uart.h +++ b/arch/arm/src/stm32f0/chip/stm32f0_uart.h @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/chip/stm32f0_usbdev.h b/arch/arm/src/stm32f0/chip/stm32f0_usbdev.h index c4eeb6ca53..a809c45172 100644 --- a/arch/arm/src/stm32f0/chip/stm32f0_usbdev.h +++ b/arch/arm/src/stm32f0/chip/stm32f0_usbdev.h @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/chip/stm32f0_wdt.h b/arch/arm/src/stm32f0/chip/stm32f0_wdt.h index 7f731f6b48..8c26ae717c 100644 --- a/arch/arm/src/stm32f0/chip/stm32f0_wdt.h +++ b/arch/arm/src/stm32f0/chip/stm32f0_wdt.h @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/stm32f0_clockconfig.c b/arch/arm/src/stm32f0/stm32f0_clockconfig.c index 56a26b30e3..4fa56e37d4 100644 --- a/arch/arm/src/stm32f0/stm32f0_clockconfig.c +++ b/arch/arm/src/stm32f0/stm32f0_clockconfig.c @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/stm32f0_clockconfig.h b/arch/arm/src/stm32f0/stm32f0_clockconfig.h index 7d264faf3d..06f104b524 100644 --- a/arch/arm/src/stm32f0/stm32f0_clockconfig.h +++ b/arch/arm/src/stm32f0/stm32f0_clockconfig.h @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/stm32f0_gpio.c b/arch/arm/src/stm32f0/stm32f0_gpio.c index 3c4aa57b22..ffa77a43ec 100644 --- a/arch/arm/src/stm32f0/stm32f0_gpio.c +++ b/arch/arm/src/stm32f0/stm32f0_gpio.c @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/stm32f0_gpio.h b/arch/arm/src/stm32f0/stm32f0_gpio.h index 2aeb05da6e..6f3220a69e 100644 --- a/arch/arm/src/stm32f0/stm32f0_gpio.h +++ b/arch/arm/src/stm32f0/stm32f0_gpio.h @@ -4,6 +4,7 @@ * Copyright (C) 2009, 2011-2012, 2015 Gregory Nutt. All rights reserved. * Copyright (C) 2015-2016 Sebastien Lorquet. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * Sebastien Lorquet * * Redistribution and use in source and binary forms, with or without diff --git a/arch/arm/src/stm32f0/stm32f0_idle.c b/arch/arm/src/stm32f0/stm32f0_idle.c index 10293fe308..b785c07a46 100644 --- a/arch/arm/src/stm32f0/stm32f0_idle.c +++ b/arch/arm/src/stm32f0/stm32f0_idle.c @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/stm32f0_irq.c b/arch/arm/src/stm32f0/stm32f0_irq.c index c3f5607370..96462f3b03 100644 --- a/arch/arm/src/stm32f0/stm32f0_irq.c +++ b/arch/arm/src/stm32f0/stm32f0_irq.c @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/stm32f0_lowputc.c b/arch/arm/src/stm32f0/stm32f0_lowputc.c index b4a276ba89..566dc14bf9 100644 --- a/arch/arm/src/stm32f0/stm32f0_lowputc.c +++ b/arch/arm/src/stm32f0/stm32f0_lowputc.c @@ -3,6 +3,7 @@ * * Copyright (C) 2009, 2012 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/stm32f0_lowputc.h b/arch/arm/src/stm32f0/stm32f0_lowputc.h index a24b801e58..9584d9faa5 100644 --- a/arch/arm/src/stm32f0/stm32f0_lowputc.h +++ b/arch/arm/src/stm32f0/stm32f0_lowputc.h @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/stm32f0_rcc.h b/arch/arm/src/stm32f0/stm32f0_rcc.h index a6894553cb..ca8f537059 100644 --- a/arch/arm/src/stm32f0/stm32f0_rcc.h +++ b/arch/arm/src/stm32f0/stm32f0_rcc.h @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/stm32f0_serial.c b/arch/arm/src/stm32f0/stm32f0_serial.c index 579132389c..66f88e38eb 100644 --- a/arch/arm/src/stm32f0/stm32f0_serial.c +++ b/arch/arm/src/stm32f0/stm32f0_serial.c @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/stm32f0_serial.h b/arch/arm/src/stm32f0/stm32f0_serial.h index 4539b0cdb8..d3f032953b 100644 --- a/arch/arm/src/stm32f0/stm32f0_serial.h +++ b/arch/arm/src/stm32f0/stm32f0_serial.h @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/stm32f0_start.c b/arch/arm/src/stm32f0/stm32f0_start.c index 0c837698bb..a02fb464c7 100644 --- a/arch/arm/src/stm32f0/stm32f0_start.c +++ b/arch/arm/src/stm32f0/stm32f0_start.c @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/stm32f0_timerisr.c b/arch/arm/src/stm32f0/stm32f0_timerisr.c index 07c7a1c57d..3887b24a71 100644 --- a/arch/arm/src/stm32f0/stm32f0_timerisr.c +++ b/arch/arm/src/stm32f0/stm32f0_timerisr.c @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/arch/arm/src/stm32f0/stm32f0_uart.h b/arch/arm/src/stm32f0/stm32f0_uart.h index d3ee1d7d45..4fb7b1c05f 100644 --- a/arch/arm/src/stm32f0/stm32f0_uart.h +++ b/arch/arm/src/stm32f0/stm32f0_uart.h @@ -3,6 +3,7 @@ * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions -- GitLab From 2cc7744b0cbf3b6d906d30dbdf237c5c7e866472 Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Fri, 14 Apr 2017 08:33:52 -0600 Subject: [PATCH 435/990] Add stm32f0discovery board support --- arch/arm/src/stm32f0/Make.defs | 2 +- configs/Kconfig | 13 + configs/README.txt | 4 + configs/stm32f0discovery/Kconfig | 8 + configs/stm32f0discovery/README.txt | 0 configs/stm32f0discovery/include/board.h | 277 +++++ configs/stm32f0discovery/nsh/Make.defs | 113 ++ configs/stm32f0discovery/nsh/defconfig | 1048 +++++++++++++++++ configs/stm32f0discovery/nsh/setenv.sh | 76 ++ configs/stm32f0discovery/scripts/flash.ld | 120 ++ configs/stm32f0discovery/scripts/gnu-elf.ld | 130 ++ configs/stm32f0discovery/src/.gitignore | 2 + configs/stm32f0discovery/src/Makefile | 68 ++ configs/stm32f0discovery/src/stm32_appinit.c | 87 ++ configs/stm32f0discovery/src/stm32_autoleds.c | 138 +++ configs/stm32f0discovery/src/stm32_boot.c | 95 ++ configs/stm32f0discovery/src/stm32_bringup.c | 80 ++ configs/stm32f0discovery/src/stm32_buttons.c | 162 +++ configs/stm32f0discovery/src/stm32_userleds.c | 110 ++ .../stm32f0discovery/src/stm32f0discovery.h | 133 +++ 20 files changed, 2665 insertions(+), 1 deletion(-) create mode 100644 configs/stm32f0discovery/Kconfig create mode 100644 configs/stm32f0discovery/README.txt create mode 100644 configs/stm32f0discovery/include/board.h create mode 100644 configs/stm32f0discovery/nsh/Make.defs create mode 100644 configs/stm32f0discovery/nsh/defconfig create mode 100644 configs/stm32f0discovery/nsh/setenv.sh create mode 100644 configs/stm32f0discovery/scripts/flash.ld create mode 100644 configs/stm32f0discovery/scripts/gnu-elf.ld create mode 100644 configs/stm32f0discovery/src/.gitignore create mode 100644 configs/stm32f0discovery/src/Makefile create mode 100644 configs/stm32f0discovery/src/stm32_appinit.c create mode 100644 configs/stm32f0discovery/src/stm32_autoleds.c create mode 100644 configs/stm32f0discovery/src/stm32_boot.c create mode 100644 configs/stm32f0discovery/src/stm32_bringup.c create mode 100644 configs/stm32f0discovery/src/stm32_buttons.c create mode 100644 configs/stm32f0discovery/src/stm32_userleds.c create mode 100644 configs/stm32f0discovery/src/stm32f0discovery.h diff --git a/arch/arm/src/stm32f0/Make.defs b/arch/arm/src/stm32f0/Make.defs index b54aa7c348..ada01348f7 100644 --- a/arch/arm/src/stm32f0/Make.defs +++ b/arch/arm/src/stm32f0/Make.defs @@ -3,7 +3,7 @@ # # Copyright (C) 2017 Gregory Nutt. All rights reserved. # Author: Gregory Nutt - * Alan Carvalho de Assis +# Alan Carvalho de Assis # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions diff --git a/configs/Kconfig b/configs/Kconfig index 27d98e0821..6467bafe1e 100644 --- a/configs/Kconfig +++ b/configs/Kconfig @@ -1037,6 +1037,15 @@ config ARCH_BOARD_STM3240G_EVAL microcontroller (ARM Cortex-M4 with FPU). This port uses a GNU Cortex-M4 toolchain (such as CodeSourcery). +config ARCH_BOARD_STM32F0_DISCOVERY + bool "STMicro STM32F0-Discovery board" + depends on ARCH_CHIP_STM32F051R8 + select ARCH_HAVE_LEDS + select ARCH_HAVE_BUTTONS + select ARCH_HAVE_IRQBUTTONS + ---help--- + STMicro STM32F-Discovery board based on the STMicro ARCH_CHIP_STM32F051R8 MCU. + config ARCH_BOARD_STM32F3_DISCOVERY bool "STMicro STM32F3-Discovery board" depends on ARCH_CHIP_STM32F303VC @@ -1522,6 +1531,7 @@ config ARCH_BOARD default "photon" if ARCH_BOARD_PHOTON default "stm32butterfly2" if ARCH_BOARD_STM32_BUTTERFLY2 default "stm32_tiny" if ARCH_BOARD_STM32_TINY + default "stm32f0discovery" if ARCH_BOARD_STM32F0_DISCOVERY default "stm32f103-minimum" if ARCH_BOARD_STM32F103_MINIMUM default "stm3210e-eval" if ARCH_BOARD_STM3210E_EVAL default "stm3220g-eval" if ARCH_BOARD_STM3220G_EVAL @@ -1881,6 +1891,9 @@ endif if ARCH_BOARD_STM32_TINY source "configs/stm32_tiny/Kconfig" endif +if ARCH_BOARD_STM32F0_DISCOVERY +source "configs/stm32f0discovery/Kconfig" +endif if ARCH_BOARD_STM32F103_MINIMUM source "configs/stm32f103-minimum/Kconfig" endif diff --git a/configs/README.txt b/configs/README.txt index f33e3a0692..dea227d8a7 100644 --- a/configs/README.txt +++ b/configs/README.txt @@ -660,6 +660,10 @@ configs/stm32butterfly2 Kamami stm32butterfly2 development board with optional ETH phy. See https://kamami.pl/zestawy-uruchomieniowe-stm32/178507-stm32butterfly2.html +configs/stm32f0discovery + STMicro STM32F-Discovery board based on the STMicro ARCH_CHIP_STM32F051R8 + MCU. + configs/stm32f103-minimum Generic STM32F103C8T6 Minimum ARM Development Board. diff --git a/configs/stm32f0discovery/Kconfig b/configs/stm32f0discovery/Kconfig new file mode 100644 index 0000000000..f1776ced8b --- /dev/null +++ b/configs/stm32f0discovery/Kconfig @@ -0,0 +1,8 @@ +# +# For a description of the syntax of this configuration file, +# see the file kconfig-language.txt in the NuttX tools repository. +# + +if ARCH_BOARD_STM32F0_DISCOVERY + +endif diff --git a/configs/stm32f0discovery/README.txt b/configs/stm32f0discovery/README.txt new file mode 100644 index 0000000000..e69de29bb2 diff --git a/configs/stm32f0discovery/include/board.h b/configs/stm32f0discovery/include/board.h new file mode 100644 index 0000000000..c6f7f32733 --- /dev/null +++ b/configs/stm32f0discovery/include/board.h @@ -0,0 +1,277 @@ +/************************************************************************************ + * configs/stm32f0discovery/include/board.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Alan Carvalho de Assis + * + * 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 __CONFIG_STM32F0DISCOVERY_INCLUDE_BOARD_H +#define __CONFIG_STM32F0DISCOVERY_INCLUDE_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#ifndef __ASSEMBLY__ +# include +#endif + +#include "stm32f0_rcc.h" +#include "stm32f0.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ +/* Four different clock sources can be used to drive the system clock (SYSCLK): + * + * - HSI high-speed internal oscillator clock + * Generated from an internal 16 MHz RC oscillator + * - HSE high-speed external oscillator clock + * Normally driven by an external crystal (X3). However, this crystal is not fitted + * on the STM32L-Discovery board. + * - PLL clock + * - MSI multispeed internal oscillator clock + * The MSI clock signal is generated from an internal RC oscillator. Seven frequency + * ranges are available: 65.536 kHz, 131.072 kHz, 262.144 kHz, 524.288 kHz, 1.048 MHz, + * 2.097 MHz (default value) and 4.194 MHz. + * + * The devices have the following two secondary clock sources + * - LSI low-speed internal RC clock + * Drives the watchdog and RTC. Approximately 37KHz + * - LSE low-speed external oscillator clock + * Driven by 32.768KHz crystal (X2) on the OSC32_IN and OSC32_OUT pins. + */ + +#define STM32F0_BOARD_XTAL 8000000ul /* X3 on board (not fitted)*/ + +#define STM32F0_HSI_FREQUENCY 16000000ul /* Approximately 16MHz */ +#define STM32F0_HSE_FREQUENCY STM32F0_BOARD_XTAL +#define STM32F0_MSI_FREQUENCY 2097000 /* Default is approximately 2.097Mhz */ +#define STM32F0_LSI_FREQUENCY 37000 /* Approximately 37KHz */ +#define STM32F0_LSE_FREQUENCY 32768 /* X2 on board */ + +/* This is the clock setup we configure for: + * + * SYSCLK = BOARD_OSCCLK_FREQUENCY = 12MHz -> Select Main oscillator for source + * PLL0CLK = (2 * 20 * SYSCLK) / 1 = 480MHz -> PLL0 multipler=20, pre-divider=1 + * MCLK = 480MHz / 6 = 80MHz -> MCLK divider = 6 + */ + +#define STM32F0_MCLK 48000000 /* 48Mhz */ + +/* PLL Configuration + * + * - PLL source is HSI -> 16MHz input (nominal) + * - PLL multipler is 6 -> 96MHz PLL VCO clock output (for USB) + * - PLL output divider 3 -> 32MHz divided down PLL VCO clock output + * + * Resulting SYSCLK frequency is 16MHz x 6 / 3 = 32MHz + * + * USB/SDIO: + * If the USB or SDIO interface is used in the application, the PLL VCO + * clock (defined by STM32F0_CFGR_PLLMUL) must be programmed to output a 96 + * MHz frequency. This is required to provide a 48 MHz clock to the USB or + * SDIO (SDIOCLK or USBCLK = PLLVCO/2). + * SYSCLK + * The system clock is derived from the PLL VCO divided by the output division factor. + * Limitations: + * 96 MHz as PLLVCO when the product is in range 1 (1.8V), + * 48 MHz as PLLVCO when the product is in range 2 (1.5V), + * 24 MHz when the product is in range 3 (1.2V). + * Output division to avoid exceeding 32 MHz as SYSCLK. + * The minimum input clock frequency for PLL is 2 MHz (when using HSE as PLL source). + */ + +#define STM32F0_CFGR_PLLSRC 0 /* Source is 16MHz HSI */ +#ifdef CONFIG_STM32F0_USB +# define STM32F0_CFGR_PLLMUL RCC_CFGR_PLLMUL_CLKx6 /* PLLMUL = 6 */ +# define STM32F0_CFGR_PLLDIV RCC_CFGR_PLLDIV_3 /* PLLDIV = 3 */ +# define STM32F0_PLL_FREQUENCY (6*STM32F0_HSI_FREQUENCY) /* PLL VCO Frequency is 96MHz */ +#else +# define STM32F0_CFGR_PLLMUL RCC_CFGR_PLLMUL_CLKx4 /* PLLMUL = 4 */ +# define STM32F0_CFGR_PLLDIV RCC_CFGR_PLLDIV_2 /* PLLDIV = 2 */ +# define STM32F0_PLL_FREQUENCY (4*STM32F0_HSI_FREQUENCY) /* PLL VCO Frequency is 64MHz */ +#endif + +/* Use the PLL and set the SYSCLK source to be the divided down PLL VCO output + * frequency (STM32F0_PLL_FREQUENCY divided by the PLLDIV value). + */ + +#define STM32F0_SYSCLK_SW RCC_CFGR_SW_PLL /* Use the PLL as the SYSCLK */ +#define STM32F0_SYSCLK_SWS RCC_CFGR_SWS_PLL +#ifdef CONFIG_STM32F0_USB +# define STM32F0_SYSCLK_FREQUENCY (STM32F0_PLL_FREQUENCY/3) /* SYSCLK frequence is 96MHz/PLLDIV = 32MHz */ +#else +# define STM32F0_SYSCLK_FREQUENCY (STM32F0_PLL_FREQUENCY/2) /* SYSCLK frequence is 64MHz/PLLDIV = 32MHz */ +#endif + +/* AHB clock (HCLK) is SYSCLK (32MHz) */ + +#define STM32F0_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK +#define STM32F0_HCLK_FREQUENCY STM32F0_SYSCLK_FREQUENCY +#define STM32F0_BOARD_HCLK STM32F0_HCLK_FREQUENCY /* Same as above, to satisfy compiler */ + +/* APB2 clock (PCLK2) is HCLK (32MHz) */ + +#define STM32F0_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK +#define STM32F0_PCLK2_FREQUENCY STM32F0_HCLK_FREQUENCY +#define STM32F0_APB2_CLKIN (STM32F0_PCLK2_FREQUENCY) + +/* APB2 timers 9, 10, and 11 will receive PCLK2. */ + +#define STM32F0_APB2_TIM9_CLKIN (STM32F0_PCLK2_FREQUENCY) +#define STM32F0_APB2_TIM10_CLKIN (STM32F0_PCLK2_FREQUENCY) +#define STM32F0_APB2_TIM11_CLKIN (STM32F0_PCLK2_FREQUENCY) + +/* APB1 clock (PCLK1) is HCLK (32MHz) */ + +#define STM32F0_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLK +#define STM32F0_PCLK1_FREQUENCY (STM32F0_HCLK_FREQUENCY) + +/* APB1 timers 2-7 will receive PCLK1 */ + +#define STM32F0_APB1_TIM2_CLKIN (STM32F0_PCLK1_FREQUENCY) +#define STM32F0_APB1_TIM3_CLKIN (STM32F0_PCLK1_FREQUENCY) +#define STM32F0_APB1_TIM4_CLKIN (STM32F0_PCLK1_FREQUENCY) +#define STM32F0_APB1_TIM5_CLKIN (STM32F0_PCLK1_FREQUENCY) +#define STM32F0_APB1_TIM6_CLKIN (STM32F0_PCLK1_FREQUENCY) +#define STM32F0_APB1_TIM7_CLKIN (STM32F0_PCLK1_FREQUENCY) + +/* LED definitions ******************************************************************/ +/* The STM32L-Discovery board has four LEDs. Two of these are controlled by + * logic on the board and are not available for software control: + * + * LD1 COM: LD2 default status is red. LD2 turns to green to indicate that + * communications are in progress between the PC and the ST-LINK/V2. + * LD2 PWR: Red LED indicates that the board is powered. + * + * And two LEDs can be controlled by software: + * + * User LD3: Green LED is a user LED connected to the I/O PB7 of the STM32L152 + * MCU. + * User LD4: Blue LED is a user LED connected to the I/O PB6 of the STM32L152 + * MCU. + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any + * way. The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +#define BOARD_LED1 0 /* User LD3 */ +#define BOARD_LED2 1 /* User LD4 */ +#define BOARD_NLEDS 2 + +/* LED bits for use with board_userled_all() */ + +#define BOARD_LED1_BIT (1 << BOARD_LED1) +#define BOARD_LED2_BIT (1 << BOARD_LED2) + +/* If CONFIG_ARCH_LEDs is defined, then NuttX will control the 8 LEDs on board the + * STM32L-Discovery. The following definitions describe how NuttX controls the LEDs: + * + * SYMBOL Meaning LED state + * LED1 LED2 + * ------------------- ----------------------- -------- -------- + * LED_STARTED NuttX has been started OFF OFF + * LED_HEAPALLOCATE Heap has been allocated OFF OFF + * LED_IRQSENABLED Interrupts enabled OFF OFF + * LED_STACKCREATED Idle stack created ON OFF + * LED_INIRQ In an interrupt No change + * LED_SIGNAL In a signal handler No change + * LED_ASSERTION An assertion failed No change + * LED_PANIC The system has crashed OFF Blinking + * LED_IDLE STM32 is is sleep mode Not used + */ + +#define LED_STARTED 0 +#define LED_HEAPALLOCATE 0 +#define LED_IRQSENABLED 0 +#define LED_STACKCREATED 1 +#define LED_INIRQ 2 +#define LED_SIGNAL 2 +#define LED_ASSERTION 2 +#define LED_PANIC 3 + +/* Button definitions ***************************************************************/ +/* The STM32L-Discovery supports two buttons; only one button is controllable by + * software: + * + * B1 USER: user and wake-up button connected to the I/O PA0 of the STM32L152RBT6. + * B2 RESET: pushbutton connected to NRST is used to RESET the STM32L152RBT6. + */ + +#define BUTTON_USER 0 +#define NUM_BUTTONS 1 + +#define BUTTON_USER_BIT (1 << BUTTON_USER) + +/* Alternate Pin Functions **********************************************************/ +/* The STM32L-Discovery has no on-board RS-232 driver. Further, there are no USART + * pins that do not conflict with the on board resources, in particular, the LCD: + * Most USART pins are available if the LCD is enabled; USART2 may be used if either + * the LCD or the on-board LEDs are disabled. + * + * PA9 USART1_TX LCD glass COM1 P2, pin 22 + * PA10 USART1_RX LCD glass COM2 P2, pin 21 + * PB6 USART1_TX LED Blue P2, pin 8 + * PB7 USART1_RX LED Green P2, pin 7 + * + * PA2 USART2_TX LCD SEG1 P1, pin 17 + * PA3 USART2_RX LCD SEG2 P1, pin 18 + * + * PB10 USART3_TX LCD SEG6 P1, pin 22 + * PB11 USART3_RX LCD SEG7 P1, pin 23 + * PC10 USART3_TX LCD SEG22 P2, pin 15 + * PC11 USART3_RX LCD SEG23 P2, pin 14 + */ + +/* Select PA9 and PA10 if the LCD is not enabled */ + +//#define GPIO_USART1_RX GPIO_USART1_RX_1 /* PA10 */ +//#define GPIO_USART1_TX GPIO_USART1_TX_1 /* PA9 */ + +/* This there are no other options for USART1 on this part */ + +#define GPIO_USART2_RX GPIO_USART2_RX_1 /* PA3 */ +#define GPIO_USART2_TX GPIO_USART2_TX_1 /* PA2 */ + +/* Arbirtrarily select PB10 and PB11 */ + +#define GPIO_USART3_RX GPIO_USART3_RX_1 /* PB11 */ +#define GPIO_USART3_TX GPIO_USART3_TX_1 /* PB10 */ + +#endif /* __CONFIG_STM32F0DISCOVERY_INCLUDE_BOARD_H */ diff --git a/configs/stm32f0discovery/nsh/Make.defs b/configs/stm32f0discovery/nsh/Make.defs new file mode 100644 index 0000000000..1ff7482b1a --- /dev/null +++ b/configs/stm32f0discovery/nsh/Make.defs @@ -0,0 +1,113 @@ +############################################################################ +# configs/stm32f0discovery/nsh/Make.defs +# +# Copyright (C) 2017 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# Alan Carvalho de Assis +# +# 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. +# +############################################################################ + +include ${TOPDIR}/.config +include ${TOPDIR}/tools/Config.mk +include ${TOPDIR}/arch/arm/src/armv6-m/Toolchain.defs + +LDSCRIPT = flash.ld + +ifeq ($(WINTOOL),y) + # Windows-native toolchains + DIRLINK = $(TOPDIR)/tools/copydir.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mkwindeps.sh + ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" + ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" +else + # Linux/Cygwin-native toolchain + MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT) + ARCHINCLUDES = -I. -isystem $(TOPDIR)/include + ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) +endif + +CC = $(CROSSDEV)gcc +CXX = $(CROSSDEV)g++ +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(ARCROSSDEV)ar rcs +NM = $(ARCROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump + +ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} +ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} + +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + ARCHOPTIMIZATION = -g +endif + +ifneq ($(CONFIG_DEBUG_NOOPT),y) + ARCHOPTIMIZATION += $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer +endif + +ARCHCFLAGS = -fno-builtin +ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fcheck-new -fno-rtti +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow -Wundef +ARCHWARNINGSXX = -Wall -Wshadow -Wundef +ARCHDEFINES = +ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 + +CFLAGS = $(ARCHCFLAGS) $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) +CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +NXFLATLDFLAGS1 = -r -d -warn-common +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections +LDNXFLATFLAGS = -e main -s 2048 + +ASMEXT = .S +OBJEXT = .o +LIBEXT = .a +EXEEXT = + +ifneq ($(CROSSDEV),arm-nuttx-elf-) + LDFLAGS += -nostartfiles -nodefaultlibs +endif +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + LDFLAGS += -g +endif + + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -Wundef -g -pipe +HOSTLDFLAGS = diff --git a/configs/stm32f0discovery/nsh/defconfig b/configs/stm32f0discovery/nsh/defconfig new file mode 100644 index 0000000000..da5233fe02 --- /dev/null +++ b/configs/stm32f0discovery/nsh/defconfig @@ -0,0 +1,1048 @@ +# +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# + +# +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set +CONFIG_DEFAULT_SMALL=y +CONFIG_HOST_LINUX=y +# CONFIG_HOST_OSX is not set +# CONFIG_HOST_WINDOWS is not set +# CONFIG_HOST_OTHER is not set + +# +# Build Configuration +# +# CONFIG_APPS_DIR="../apps" +CONFIG_BUILD_FLAT=y +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +# CONFIG_INTELHEX_BINARY is not set +# CONFIG_MOTOROLA_SREC is not set +CONFIG_RAW_BINARY=y +# CONFIG_UBOOT_UIMAGE is not set + +# +# Customize Header Files +# +# CONFIG_ARCH_STDINT_H is not set +# CONFIG_ARCH_STDBOOL_H is not set +# CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_FLOAT_H is not set +# CONFIG_ARCH_STDARG_H is not set +# CONFIG_ARCH_DEBUG_H is not set + +# +# Debug Options +# +CONFIG_DEBUG_ALERT=y +# CONFIG_DEBUG_FEATURES is not set +CONFIG_ARCH_HAVE_STACKCHECK=y +# CONFIG_STACK_COLORATION is not set +# CONFIG_ARCH_HAVE_HEAPCHECK is not set +# CONFIG_DEBUG_SYMBOLS is not set +CONFIG_ARCH_HAVE_CUSTOMOPT=y +# CONFIG_DEBUG_NOOPT is not set +# CONFIG_DEBUG_CUSTOMOPT is not set +CONFIG_DEBUG_FULLOPT=y + +# +# System Type +# +CONFIG_ARCH_ARM=y +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_MISOC is not set +# CONFIG_ARCH_RENESAS is not set +# CONFIG_ARCH_RISCV is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_XTENSA is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="arm" + +# +# ARM Options +# +# CONFIG_ARCH_CHIP_A1X is not set +# CONFIG_ARCH_CHIP_C5471 is not set +# CONFIG_ARCH_CHIP_DM320 is not set +# CONFIG_ARCH_CHIP_EFM32 is not set +# CONFIG_ARCH_CHIP_IMX1 is not set +# CONFIG_ARCH_CHIP_IMX6 is not set +# CONFIG_ARCH_CHIP_KINETIS is not set +# CONFIG_ARCH_CHIP_KL is not set +# CONFIG_ARCH_CHIP_LM is not set +# CONFIG_ARCH_CHIP_TIVA is not set +# CONFIG_ARCH_CHIP_LPC11XX is not set +# CONFIG_ARCH_CHIP_LPC17XX is not set +# CONFIG_ARCH_CHIP_LPC214X is not set +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_NUC1XX is not set +# CONFIG_ARCH_CHIP_SAMA5 is not set +# CONFIG_ARCH_CHIP_SAMD is not set +# CONFIG_ARCH_CHIP_SAML is not set +# CONFIG_ARCH_CHIP_SAM34 is not set +# CONFIG_ARCH_CHIP_SAMV7 is not set +# CONFIG_ARCH_CHIP_STM32 is not set +CONFIG_ARCH_CHIP_STM32F0=y +# CONFIG_ARCH_CHIP_STM32F7 is not set +# CONFIG_ARCH_CHIP_STM32L4 is not set +# CONFIG_ARCH_CHIP_STR71X is not set +# CONFIG_ARCH_CHIP_TMS570 is not set +# CONFIG_ARCH_CHIP_XMC4 is not set +# CONFIG_ARCH_ARM7TDMI is not set +# CONFIG_ARCH_ARM926EJS is not set +# CONFIG_ARCH_ARM920T is not set +CONFIG_ARCH_CORTEXM0=y +# CONFIG_ARCH_CORTEXM23 is not set +# CONFIG_ARCH_CORTEXM3 is not set +# CONFIG_ARCH_CORTEXM33 is not set +# CONFIG_ARCH_CORTEXM4 is not set +# CONFIG_ARCH_CORTEXM7 is not set +# CONFIG_ARCH_CORTEXA5 is not set +# CONFIG_ARCH_CORTEXA8 is not set +# CONFIG_ARCH_CORTEXA9 is not set +# CONFIG_ARCH_CORTEXR4 is not set +# CONFIG_ARCH_CORTEXR4F is not set +# CONFIG_ARCH_CORTEXR5 is not set +# CONFIG_ARCH_CORTEX5F is not set +# CONFIG_ARCH_CORTEXR7 is not set +# CONFIG_ARCH_CORTEXR7F is not set +CONFIG_ARCH_FAMILY="armv6-m" +CONFIG_ARCH_CHIP="stm32f0" +# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARM_TOOLCHAIN_GNU is not set +CONFIG_ARCH_HAVE_CMNVECTOR=y +# CONFIG_ARMV7M_CMNVECTOR is not set +# CONFIG_ARMV7M_LAZYFPU is not set +# CONFIG_ARCH_HAVE_FPU is not set +# CONFIG_ARCH_HAVE_DPFPU is not set +# CONFIG_ARCH_HAVE_TRUSTZONE is not set +# CONFIG_ARM_HAVE_MPU_UNIFIED is not set + +# +# ARMV6M Configuration Options +# +# CONFIG_ARMV6M_TOOLCHAIN_BUILDROOT is not set +# CONFIG_ARMV6M_TOOLCHAIN_CODEREDL is not set +# CONFIG_ARMV6M_TOOLCHAIN_CODESOURCERYL is not set +CONFIG_ARMV6M_TOOLCHAIN_GNU_EABIL=y + +# +# STM32F0xx Configuration Options +# +# CONFIG_ARCH_CHIP_STM32F030C6 is not set +# CONFIG_ARCH_CHIP_STM32F030C8 is not set +# CONFIG_ARCH_CHIP_STM32F030CC is not set +# CONFIG_ARCH_CHIP_STM32F030F4 is not set +# CONFIG_ARCH_CHIP_STM32F030K6 is not set +# CONFIG_ARCH_CHIP_STM32F030R8 is not set +# CONFIG_ARCH_CHIP_STM32F030RC is not set +# CONFIG_ARCH_CHIP_STM32F031C4 is not set +# CONFIG_ARCH_CHIP_STM32F031C6 is not set +# CONFIG_ARCH_CHIP_STM32F031E6 is not set +# CONFIG_ARCH_CHIP_STM32F031F4 is not set +# CONFIG_ARCH_CHIP_STM32F031F6 is not set +# CONFIG_ARCH_CHIP_STM32F031G4 is not set +# CONFIG_ARCH_CHIP_STM32F031G6 is not set +# CONFIG_ARCH_CHIP_STM32F031K4 is not set +# CONFIG_ARCH_CHIP_STM32F031K6 is not set +# CONFIG_ARCH_CHIP_STM32F038C6 is not set +# CONFIG_ARCH_CHIP_STM32F038E6 is not set +# CONFIG_ARCH_CHIP_STM32F038F6 is not set +# CONFIG_ARCH_CHIP_STM32F038G6 is not set +# CONFIG_ARCH_CHIP_STM32F038K6 is not set +# CONFIG_ARCH_CHIP_STM32F042C4 is not set +# CONFIG_ARCH_CHIP_STM32F042C6 is not set +# CONFIG_ARCH_CHIP_STM32F042F4 is not set +# CONFIG_ARCH_CHIP_STM32F042F6 is not set +# CONFIG_ARCH_CHIP_STM32F042G4 is not set +# CONFIG_ARCH_CHIP_STM32F042G6 is not set +# CONFIG_ARCH_CHIP_STM32F042K4 is not set +# CONFIG_ARCH_CHIP_STM32F042K6 is not set +# CONFIG_ARCH_CHIP_STM32F042T6 is not set +# CONFIG_ARCH_CHIP_STM32F048C6 is not set +# CONFIG_ARCH_CHIP_STM32F048G6 is not set +# CONFIG_ARCH_CHIP_STM32F048T6 is not set +# CONFIG_ARCH_CHIP_STM32F051C4 is not set +# CONFIG_ARCH_CHIP_STM32F051C6 is not set +# CONFIG_ARCH_CHIP_STM32F051C8 is not set +# CONFIG_ARCH_CHIP_STM32F051K4 is not set +# CONFIG_ARCH_CHIP_STM32F051K6 is not set +# CONFIG_ARCH_CHIP_STM32F051K8 is not set +# CONFIG_ARCH_CHIP_STM32F051R4 is not set +# CONFIG_ARCH_CHIP_STM32F051R6 is not set +CONFIG_ARCH_CHIP_STM32F051R8=y +# CONFIG_ARCH_CHIP_STM32F051T8 is not set +# CONFIG_ARCH_CHIP_STM32F058C8 is not set +# CONFIG_ARCH_CHIP_STM32F058R8 is not set +# CONFIG_ARCH_CHIP_STM32F058T8 is not set +# CONFIG_ARCH_CHIP_STM32F070C6 is not set +# CONFIG_ARCH_CHIP_STM32F070CB is not set +# CONFIG_ARCH_CHIP_STM32F070F6 is not set +# CONFIG_ARCH_CHIP_STM32F070RB is not set +# CONFIG_ARCH_CHIP_STM32F071C8 is not set +# CONFIG_ARCH_CHIP_STM32F071CB is not set +# CONFIG_ARCH_CHIP_STM32F071RB is not set +# CONFIG_ARCH_CHIP_STM32F071V8 is not set +# CONFIG_ARCH_CHIP_STM32F071VB is not set +# CONFIG_ARCH_CHIP_STM32F072C8 is not set +# CONFIG_ARCH_CHIP_STM32F072CB is not set +# CONFIG_ARCH_CHIP_STM32F072R8 is not set +# CONFIG_ARCH_CHIP_STM32F072RB is not set +# CONFIG_ARCH_CHIP_STM32F072V8 is not set +# CONFIG_ARCH_CHIP_STM32F072VB is not set +# CONFIG_ARCH_CHIP_STM32F078CB is not set +# CONFIG_ARCH_CHIP_STM32F078RB is not set +# CONFIG_ARCH_CHIP_STM32F078VB is not set +# CONFIG_ARCH_CHIP_STM32F091CB is not set +# CONFIG_ARCH_CHIP_STM32F091CC is not set +# CONFIG_ARCH_CHIP_STM32F091RB is not set +# CONFIG_ARCH_CHIP_STM32F091RC is not set +# CONFIG_ARCH_CHIP_STM32F091VB is not set +# CONFIG_ARCH_CHIP_STM32F091VC is not set +# CONFIG_ARCH_CHIP_STM32F098CC is not set +# CONFIG_ARCH_CHIP_STM32F098RC is not set +# CONFIG_ARCH_CHIP_STM32F098VC is not set +# CONFIG_STM32F0_STM32F03X is not set +# CONFIG_STM32F0_STM32F04X is not set +CONFIG_STM32F0_STM32F05X=y +# CONFIG_STM32F0_STM32F07X is not set +# CONFIG_STM32F0_STM32F09X is not set +# CONFIG_STM32F0_VALUELINE is not set +CONFIG_STM32F0_ACCESSLINE=y +# CONFIG_STM32F0_LOWVOLTLINE is not set +# CONFIG_STM32F0_USBLINE is not set +# CONFIG_STM32F0_DFU is not set +CONFIG_STM32F0_SYSTICK_CORECLK=y +# CONFIG_STM32F0_SYSTICK_CORECLK_DIV16 is not set + +# +# STM32 Peripheral Support +# +# CONFIG_STM32F0_HAVE_CCM is not set +# CONFIG_STM32F0_HAVE_USBDEV is not set +CONFIG_STM32F0_HAVE_OTGFS=y +# CONFIG_STM32F0_HAVE_FSMC is not set +# CONFIG_STM32F0_HAVE_HRTIM1 is not set +# CONFIG_STM32F0_HAVE_LTDC is not set +CONFIG_STM32F0_HAVE_USART3=y +CONFIG_STM32F0_HAVE_USART4=y +CONFIG_STM32F0_HAVE_USART5=y +# CONFIG_STM32F0_HAVE_USART6 is not set +# CONFIG_STM32F0_HAVE_USART7 is not set +# CONFIG_STM32F0_HAVE_USART8 is not set +CONFIG_STM32F0_HAVE_TIM1=y +# CONFIG_STM32F0_HAVE_TIM2 is not set +# CONFIG_STM32F0_HAVE_TIM3 is not set +# CONFIG_STM32F0_HAVE_TIM4 is not set +CONFIG_STM32F0_HAVE_TIM5=y +CONFIG_STM32F0_HAVE_TIM6=y +CONFIG_STM32F0_HAVE_TIM7=y +# CONFIG_STM32F0_HAVE_TIM8 is not set +# CONFIG_STM32F0_HAVE_TIM9 is not set +# CONFIG_STM32F0_HAVE_TIM10 is not set +# CONFIG_STM32F0_HAVE_TIM11 is not set +# CONFIG_STM32F0_HAVE_TIM12 is not set +# CONFIG_STM32F0_HAVE_TIM13 is not set +# CONFIG_STM32F0_HAVE_TIM14 is not set +# CONFIG_STM32F0_HAVE_TIM15 is not set +# CONFIG_STM32F0_HAVE_TIM16 is not set +# CONFIG_STM32F0_HAVE_TIM17 is not set +# CONFIG_STM32F0_HAVE_TSC is not set +CONFIG_STM32F0_HAVE_ADC2=y +# CONFIG_STM32F0_HAVE_ADC3 is not set +# CONFIG_STM32F0_HAVE_ADC4 is not set +# CONFIG_STM32F0_HAVE_ADC1_DMA is not set +# CONFIG_STM32F0_HAVE_ADC2_DMA is not set +# CONFIG_STM32F0_HAVE_ADC3_DMA is not set +# CONFIG_STM32F0_HAVE_ADC4_DMA is not set +# CONFIG_STM32F0_HAVE_SDADC1 is not set +# CONFIG_STM32F0_HAVE_SDADC2 is not set +# CONFIG_STM32F0_HAVE_SDADC3 is not set +# CONFIG_STM32F0_HAVE_SDADC1_DMA is not set +# CONFIG_STM32F0_HAVE_SDADC2_DMA is not set +# CONFIG_STM32F0_HAVE_SDADC3_DMA is not set +CONFIG_STM32F0_HAVE_CAN1=y +CONFIG_STM32F0_HAVE_CAN2=y +# CONFIG_STM32F0_HAVE_COMP1 is not set +# CONFIG_STM32F0_HAVE_COMP2 is not set +# CONFIG_STM32F0_HAVE_COMP3 is not set +# CONFIG_STM32F0_HAVE_COMP4 is not set +# CONFIG_STM32F0_HAVE_COMP5 is not set +# CONFIG_STM32F0_HAVE_COMP6 is not set +# CONFIG_STM32F0_HAVE_COMP7 is not set +# CONFIG_STM32F0_HAVE_DAC1 is not set +# CONFIG_STM32F0_HAVE_DAC2 is not set +# CONFIG_STM32F0_HAVE_RNG is not set +CONFIG_STM32F0_HAVE_ETHMAC=y +# CONFIG_STM32F0_HAVE_I2C2 is not set +# CONFIG_STM32F0_HAVE_I2C3 is not set +CONFIG_STM32F0_HAVE_SPI2=y +CONFIG_STM32F0_HAVE_SPI3=y +# CONFIG_STM32F0_HAVE_SPI4 is not set +# CONFIG_STM32F0_HAVE_SPI5 is not set +# CONFIG_STM32F0_HAVE_SPI6 is not set +# CONFIG_STM32F0_HAVE_SAIPLL is not set +# CONFIG_STM32F0_HAVE_I2SPLL is not set +# CONFIG_STM32F0_HAVE_OPAMP1 is not set +# CONFIG_STM32F0_HAVE_OPAMP2 is not set +# CONFIG_STM32F0_HAVE_OPAMP3 is not set +# CONFIG_STM32F0_HAVE_OPAMP4 is not set +# CONFIG_STM32F0_ADC1 is not set +# CONFIG_STM32F0_ADC2 is not set +# CONFIG_STM32F0_COMP is not set +# CONFIG_STM32F0_BKP is not set +# CONFIG_STM32F0_BKPSRAM is not set +# CONFIG_STM32F0_CAN1 is not set +# CONFIG_STM32F0_CAN2 is not set +# CONFIG_STM32F0_CRC is not set +# CONFIG_STM32F0_DMA1 is not set +# CONFIG_STM32F0_DMA2 is not set +# CONFIG_STM32F0_I2C1 is not set +CONFIG_STM32F0_PWR=y +# CONFIG_STM32F0_SDIO is not set +# CONFIG_STM32F0_SPI1 is not set +# CONFIG_STM32F0_SPI2 is not set +# CONFIG_STM32F0_SPI3 is not set +CONFIG_STM32F0_SYSCFG=y +# CONFIG_STM32F0_TIM1 is not set +# CONFIG_STM32F0_TIM2 is not set +# CONFIG_STM32F0_TIM5 is not set +# CONFIG_STM32F0_TIM6 is not set +# CONFIG_STM32F0_TIM7 is not set +CONFIG_STM32F0_USART1=y +# CONFIG_STM32F0_USART2 is not set +# CONFIG_STM32F0_USART3 is not set +# CONFIG_STM32F0_USART4 is not set +# CONFIG_STM32F0_USART5 is not set +# CONFIG_STM32F0_IWDG is not set +# CONFIG_STM32F0_WWDG is not set +CONFIG_STM32F0_USART=y +CONFIG_STM32F0_SERIALDRIVER=y + +# +# U[S]ART Configuration +# + +# +# U[S]ART Device Configuration +# +CONFIG_STM32F0_USART1F0_SERIALDRIVER=y +# CONFIG_STM32F0_USART1_1WIREDRIVER is not set + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_VECNOTIRQ is not set +# CONFIG_ARCH_DMA is not set +CONFIG_ARCH_HAVE_IRQPRIO=y +# CONFIG_ARCH_L2CACHE is not set +# CONFIG_ARCH_HAVE_COHERENT_DCACHE is not set +# CONFIG_ARCH_HAVE_ADDRENV is not set +# CONFIG_ARCH_NEED_ADDRENV_MAPPING is not set +# CONFIG_ARCH_HAVE_MULTICPU is not set +CONFIG_ARCH_HAVE_VFORK=y +# CONFIG_ARCH_HAVE_MMU is not set +# CONFIG_ARCH_HAVE_MPU is not set +# CONFIG_ARCH_NAND_HWECC is not set +# CONFIG_ARCH_HAVE_EXTCLK is not set +# CONFIG_ARCH_HAVE_POWEROFF is not set +CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_IRQPRIO is not set +CONFIG_ARCH_STACKDUMP=y +# CONFIG_ENDIAN_BIG is not set +# CONFIG_ARCH_IDLE_CUSTOM is not set +# CONFIG_ARCH_HAVE_RAMFUNCS is not set +# CONFIG_ARCH_HAVE_RAMVECTORS is not set +# CONFIG_ARCH_MINIMAL_VECTORTABLE is not set + +# +# Board Settings +# +CONFIG_BOARD_LOOPSPERMSEC=2796 +# CONFIG_ARCH_CALIBRATION is not set + +# +# Interrupt options +# +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y +CONFIG_ARCH_INTERRUPTSTACK=0 +# CONFIG_ARCH_HAVE_HIPRI_INTERRUPT is not set + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Boot Memory Configuration +# +CONFIG_RAM_START=0x20000000 +CONFIG_RAM_SIZE=8192 +# CONFIG_ARCH_HAVE_SDRAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_STM32F0_DISCOVERY=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="stm32f0discovery" + +# +# Common Board Options +# +CONFIG_ARCH_HAVE_LEDS=y +CONFIG_ARCH_LEDS=y +CONFIG_ARCH_HAVE_BUTTONS=y +# CONFIG_ARCH_BUTTONS is not set +CONFIG_ARCH_HAVE_IRQBUTTONS=y + +# +# Board-Specific Options +# +# CONFIG_BOARD_CRASHDUMP is not set +# CONFIG_LIB_BOARDCTL is not set + +# +# RTOS Features +# +CONFIG_DISABLE_OS_API=y +CONFIG_DISABLE_POSIX_TIMERS=y +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_DISABLE_SIGNALS is not set +CONFIG_DISABLE_MQUEUE=y +CONFIG_DISABLE_ENVIRON=y + +# +# Clocks and Timers +# +CONFIG_USEC_PER_TICK=10000 +# CONFIG_SYSTEM_TIME64 is not set +# CONFIG_CLOCK_MONOTONIC is not set +# CONFIG_ARCH_HAVE_TIMEKEEPING is not set +# CONFIG_JULIAN_TIME is not set +CONFIG_START_YEAR=2013 +CONFIG_START_MONTH=5 +CONFIG_START_DAY=19 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=4 +CONFIG_WDOG_INTRESERVE=0 +CONFIG_PREALLOC_TIMERS=0 + +# +# Tasks and Scheduling +# +# CONFIG_SPINLOCK is not set +# CONFIG_INIT_NONE is not set +CONFIG_INIT_ENTRYPOINT=y +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_RR_INTERVAL=200 +# CONFIG_SCHED_SPORADIC is not set +CONFIG_TASK_NAME_SIZE=0 +CONFIG_MAX_TASKS=8 +# CONFIG_SCHED_HAVE_PARENT is not set +CONFIG_SCHED_WAITPID=y + +# +# Pthread Options +# +# CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set +CONFIG_NPTHREAD_KEYS=0 +# CONFIG_PTHREAD_CLEANUP is not set +# CONFIG_CANCELLATION_POINTS is not set + +# +# Performance Monitoring +# +# CONFIG_SCHED_CPULOAD is not set +# CONFIG_SCHED_INSTRUMENTATION is not set + +# +# Files and I/O +# +CONFIG_DEV_CONSOLE=y +# CONFIG_FDCLONE_DISABLE is not set +# CONFIG_FDCLONE_STDIO is not set +CONFIG_SDCLONE_DISABLE=y +CONFIG_NFILE_DESCRIPTORS=6 +CONFIG_NFILE_STREAMS=6 +CONFIG_NAME_MAX=32 +# CONFIG_PRIORITY_INHERITANCE is not set + +# +# RTOS hooks +# +# CONFIG_BOARD_INITIALIZE is not set +# CONFIG_SCHED_STARTHOOK is not set +# CONFIG_SCHED_ATEXIT is not set +# CONFIG_SCHED_ONEXIT is not set + +# +# Signal Numbers +# +CONFIG_SIG_SIGUSR1=1 +CONFIG_SIG_SIGUSR2=2 +CONFIG_SIG_SIGALARM=3 +CONFIG_SIG_SIGCONDTIMEDOUT=16 +# CONFIG_MODULE is not set + +# +# Work queue support +# +# CONFIG_SCHED_WORKQUEUE is not set +# CONFIG_SCHED_HPWORK is not set +# CONFIG_SCHED_LPWORK is not set + +# +# Stack and heap information +# +CONFIG_IDLETHREAD_STACKSIZE=1024 +CONFIG_USERMAIN_STACKSIZE=1536 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=1536 +# CONFIG_LIB_SYSCALL is not set + +# +# Device Drivers +# +CONFIG_DISABLE_POLL=y +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_DEV_URANDOM is not set +# CONFIG_DEV_LOOP is not set + +# +# Buffering +# +# CONFIG_DRVR_WRITEBUFFER is not set +# CONFIG_DRVR_READAHEAD is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_ARCH_HAVE_PWM_PULSECOUNT is not set +# CONFIG_ARCH_HAVE_PWM_MULTICHAN is not set +# CONFIG_PWM is not set +# CONFIG_ARCH_HAVE_I2CRESET is not set +# CONFIG_I2C is not set +# CONFIG_ARCH_HAVE_SPI_CRCGENERATION is not set +# CONFIG_ARCH_HAVE_SPI_CS_CONTROL is not set +# CONFIG_ARCH_HAVE_SPI_BITORDER is not set +# CONFIG_SPI is not set +# CONFIG_I2S is not set + +# +# Timer Driver Support +# +# CONFIG_TIMER is not set +# CONFIG_ONESHOT is not set +# CONFIG_RTC is not set +# CONFIG_WATCHDOG is not set +# CONFIG_ANALOG is not set +# CONFIG_AUDIO_DEVICES is not set +# CONFIG_VIDEO_DEVICES is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set + +# +# IO Expander/GPIO Support +# +# CONFIG_IOEXPANDER is not set +# CONFIG_DEV_GPIO is not set + +# +# LCD Driver Support +# +# CONFIG_LCD is not set +# CONFIG_SLCD is not set + +# +# LED Support +# +# CONFIG_USERLED is not set +# CONFIG_RGBLED is not set +# CONFIG_PCA9635PW is not set +# CONFIG_NCP5623C is not set +# CONFIG_MMCSD is not set +# CONFIG_MODEM is not set +# CONFIG_MTD is not set +# CONFIG_EEPROM is not set +# CONFIG_PIPES is not set +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +CONFIG_SERIAL=y +CONFIG_DEV_LOWCONSOLE=y +# CONFIG_SERIAL_REMOVABLE is not set +# CONFIG_SERIAL_CONSOLE is not set +# CONFIG_16550_UART is not set +# CONFIG_UART_SERIALDRIVER is not set +# CONFIG_UART0_SERIALDRIVER is not set +# CONFIG_UART1_SERIALDRIVER is not set +# CONFIG_UART2_SERIALDRIVER is not set +# CONFIG_UART3_SERIALDRIVER is not set +# CONFIG_UART4_SERIALDRIVER is not set +# CONFIG_UART5_SERIALDRIVER is not set +# CONFIG_UART6_SERIALDRIVER is not set +# CONFIG_UART7_SERIALDRIVER is not set +# CONFIG_UART8_SERIALDRIVER is not set +# CONFIG_SCI0_SERIALDRIVER is not set +# CONFIG_SCI1_SERIALDRIVER is not set +# CONFIG_USART0_SERIALDRIVER is not set +CONFIG_USART1_SERIALDRIVER=y +# CONFIG_USART2_SERIALDRIVER is not set +# CONFIG_USART3_SERIALDRIVER is not set +# CONFIG_USART4_SERIALDRIVER is not set +# CONFIG_USART5_SERIALDRIVER is not set +# CONFIG_USART6_SERIALDRIVER is not set +# CONFIG_USART7_SERIALDRIVER is not set +# CONFIG_USART8_SERIALDRIVER is not set +# CONFIG_OTHER_UART_SERIALDRIVER is not set +CONFIG_MCU_SERIAL=y +# CONFIG_SERIAL_IFLOWCONTROL is not set +# CONFIG_SERIAL_OFLOWCONTROL is not set +# CONFIG_SERIAL_DMA is not set +CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y +# CONFIG_USART1_SERIAL_CONSOLE is not set +# CONFIG_OTHER_SERIAL_CONSOLE is not set +CONFIG_NO_SERIAL_CONSOLE=y + +# +# USART1 Configuration +# +CONFIG_USART1_RXBUFSIZE=32 +CONFIG_USART1_TXBUFSIZE=32 +CONFIG_USART1_BAUD=115200 +CONFIG_USART1_BITS=8 +CONFIG_USART1_PARITY=0 +CONFIG_USART1_2STOP=0 +# CONFIG_USART1_IFLOWCONTROL is not set +# CONFIG_USART1_OFLOWCONTROL is not set +# CONFIG_USART1_DMA is not set +# CONFIG_PSEUDOTERM is not set +# CONFIG_USBDEV is not set +# CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set +# CONFIG_HAVE_USBTRACE is not set +# CONFIG_DRIVERS_WIRELESS is not set +# CONFIG_DRIVERS_CONTACTLESS is not set + +# +# System Logging +# +# CONFIG_ARCH_SYSLOG is not set +# CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_INTBUFFER is not set +# CONFIG_SYSLOG_TIMESTAMP is not set +# CONFIG_SYSLOG_SERIAL_CONSOLE is not set +# CONFIG_SYSLOG_CHAR is not set +CONFIG_SYSLOG_CONSOLE=y +# CONFIG_SYSLOG_NONE is not set +# CONFIG_SYSLOG_FILE is not set +# CONFIG_SYSLOG_CHARDEV is not set + +# +# Networking Support +# +# CONFIG_ARCH_HAVE_NET is not set +# CONFIG_ARCH_HAVE_PHY is not set +# CONFIG_NET is not set + +# +# Crypto API +# +# CONFIG_CRYPTO is not set + +# +# File Systems +# + +# +# File system configuration +# +CONFIG_DISABLE_MOUNTPOINT=y +CONFIG_DISABLE_PSEUDOFS_OPERATIONS=y +# CONFIG_FS_READABLE is not set +# CONFIG_FS_WRITABLE is not set +# CONFIG_FS_NAMED_SEMAPHORES is not set +# CONFIG_FS_RAMMAP is not set +# CONFIG_FS_PROCFS is not set +# CONFIG_FS_UNIONFS is not set + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +CONFIG_MM_SMALL=y +CONFIG_MM_REGIONS=1 +# CONFIG_ARCH_HAVE_HEAP2 is not set +# CONFIG_GRAN is not set + +# +# Audio Support +# +# CONFIG_AUDIO is not set + +# +# Wireless Support +# + +# +# Binary Loader +# +CONFIG_BINFMT_DISABLE=y +# CONFIG_PIC is not set +# CONFIG_SYMTAB_ORDEREDBYNAME is not set + +# +# Library Routines +# + +# +# Standard C Library Options +# + +# +# Standard C I/O +# +CONFIG_STDIO_DISABLE_BUFFERING=y +CONFIG_NUNGET_CHARS=0 +# CONFIG_NOPRINTF_FIELDWIDTH is not set +# CONFIG_LIBC_FLOATINGPOINT is not set +# CONFIG_LIBC_LONG_LONG is not set +# CONFIG_LIBC_SCANSET is not set +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_MEMCPY_VIK is not set +# CONFIG_LIBM is not set + +# +# Architecture-Specific Support +# +CONFIG_ARCH_LOWPUTC=y +# CONFIG_ARCH_ROMGETC is not set +# CONFIG_LIBC_ARCH_MEMCPY is not set +# CONFIG_LIBC_ARCH_MEMCMP is not set +# CONFIG_LIBC_ARCH_MEMMOVE is not set +# CONFIG_LIBC_ARCH_MEMSET is not set +# CONFIG_LIBC_ARCH_STRCHR is not set +# CONFIG_LIBC_ARCH_STRCMP is not set +# CONFIG_LIBC_ARCH_STRCPY is not set +# CONFIG_LIBC_ARCH_STRNCPY is not set +# CONFIG_LIBC_ARCH_STRLEN is not set +# CONFIG_LIBC_ARCH_STRNLEN is not set +# CONFIG_LIBC_ARCH_ELF is not set + +# +# stdlib Options +# +CONFIG_LIB_RAND_ORDER=1 + +# +# Program Execution Options +# +CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024 +CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=1536 + +# +# errno Decode Support +# +# CONFIG_LIBC_STRERROR is not set +# CONFIG_LIBC_PERROR_STDOUT is not set + +# +# memcpy/memset Options +# +# CONFIG_MEMSET_OPTSPEED is not set +# CONFIG_LIBC_DLLFCN is not set +# CONFIG_LIBC_MODLIB is not set +# CONFIG_LIBC_WCHAR is not set +# CONFIG_LIBC_LOCALE is not set + +# +# Time/Time Zone Support +# +# CONFIG_TIME_EXTENDED is not set +CONFIG_ARCH_HAVE_TLS=y + +# +# Thread Local Storage (TLS) +# +# CONFIG_TLS is not set + +# +# Network-Related Options +# +# CONFIG_LIBC_IPv4_ADDRCONV is not set +# CONFIG_LIBC_IPv6_ADDRCONV is not set +# CONFIG_LIBC_NETDB is not set + +# +# NETDB Support +# +# CONFIG_LIBC_IOCTL_VARIADIC is not set +CONFIG_LIB_SENDFILE_BUFSIZE=512 + +# +# Non-standard Library Support +# +# CONFIG_LIB_CRC64_FAST is not set +# CONFIG_LIB_KBDCODEC is not set +# CONFIG_LIB_SLCDCODEC is not set +# CONFIG_LIB_HEX2BIN is not set + +# +# Basic CXX Support +# +# CONFIG_C99_BOOL8 is not set +# CONFIG_HAVE_CXX is not set + +# +# Application Configuration +# + +# +# CAN Utilities +# + +# +# Examples +# +# CONFIG_EXAMPLES_BUTTONS is not set +# CONFIG_EXAMPLES_CCTYPE is not set +# CONFIG_EXAMPLES_CHAT is not set +# CONFIG_EXAMPLES_CONFIGDATA is not set +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HIDKBD is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_JSON is not set +# CONFIG_EXAMPLES_KEYPADTEST is not set +# CONFIG_EXAMPLES_MEDIA is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MODBUS is not set +# CONFIG_EXAMPLES_MOUNT is not set +CONFIG_EXAMPLES_NSH=y +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXLINES is not set +# CONFIG_EXAMPLES_NXTERM is not set +# CONFIG_EXAMPLES_NXTEXT is not set +# CONFIG_EXAMPLES_OSTEST is not set +# CONFIG_EXAMPLES_PCA9635 is not set +# CONFIG_EXAMPLES_POSIXSPAWN is not set +# CONFIG_EXAMPLES_PPPD is not set +# CONFIG_EXAMPLES_RFID_READUID is not set +# CONFIG_EXAMPLES_RGBLED is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERIALBLASTER is not set +# CONFIG_EXAMPLES_SERIALRX is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_SLCD is not set +# CONFIG_EXAMPLES_SMART is not set +# CONFIG_EXAMPLES_SMP is not set +# CONFIG_EXAMPLES_STAT is not set +# CONFIG_EXAMPLES_TCPECHO is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_WATCHDOG is not set +# CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set + +# +# File System Utilities +# +# CONFIG_FSUTILS_INIFILE is not set + +# +# GPS Utilities +# +# CONFIG_GPSUTILS_MINMEA_LIB is not set + +# +# Graphics Support +# +# CONFIG_TIFF is not set +# CONFIG_GRAPHICS_TRAVELER is not set + +# +# Interpreters +# +# CONFIG_INTERPRETERS_FICL is not set +# CONFIG_INTERPRETERS_MICROPYTHON is not set +# CONFIG_INTERPRETERS_MINIBASIC is not set +# CONFIG_INTERPRETERS_PCODE is not set + +# +# FreeModBus +# +# CONFIG_MODBUS is not set + +# +# Network Utilities +# +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_ESP8266 is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_JSON is not set +# CONFIG_NETUTILS_SMTP is not set + +# +# NSH Library +# +CONFIG_NSH_LIBRARY=y +# CONFIG_NSH_MOTD is not set + +# +# Command Line Configuration +# +CONFIG_NSH_READLINE=y +# CONFIG_NSH_CLE is not set +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_DISABLE_SEMICOLON=y +CONFIG_NSH_MAXARGUMENTS=6 +# CONFIG_NSH_ARGCAT is not set +CONFIG_NSH_NESTDEPTH=3 +# CONFIG_NSH_DISABLEBG is not set + +# +# Disable Individual commands +# +CONFIG_NSH_DISABLE_ADDROUTE=y +CONFIG_NSH_DISABLE_BASENAME=y +# CONFIG_NSH_DISABLE_CAT is not set +CONFIG_NSH_DISABLE_CD=y +CONFIG_NSH_DISABLE_CP=y +CONFIG_NSH_DISABLE_CMP=y +CONFIG_NSH_DISABLE_DATE=y +CONFIG_NSH_DISABLE_DD=y +CONFIG_NSH_DISABLE_DF=y +CONFIG_NSH_DISABLE_DELROUTE=y +CONFIG_NSH_DISABLE_DIRNAME=y +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_FREE is not set +CONFIG_NSH_DISABLE_GET=y +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_HEXDUMP is not set +CONFIG_NSH_DISABLE_IFCONFIG=y +CONFIG_NSH_DISABLE_IFUPDOWN=y +# CONFIG_NSH_DISABLE_KILL is not set +CONFIG_NSH_DISABLE_LOSETUP=y +CONFIG_NSH_DISABLE_LOSMART=y +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MB is not set +CONFIG_NSH_DISABLE_MKDIR=y +CONFIG_NSH_DISABLE_MKRD=y +# CONFIG_NSH_DISABLE_MH is not set +CONFIG_NSH_DISABLE_MOUNT=y +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_MW is not set +CONFIG_NSH_DISABLE_PRINTF=y +# CONFIG_NSH_DISABLE_PS is not set +CONFIG_NSH_DISABLE_PUT=y +# CONFIG_NSH_DISABLE_PWD is not set +CONFIG_NSH_DISABLE_RM=y +CONFIG_NSH_DISABLE_RMDIR=y +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SH is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +CONFIG_NSH_DISABLE_TIME=y +# CONFIG_NSH_DISABLE_TEST is not set +CONFIG_NSH_DISABLE_UMOUNT=y +CONFIG_NSH_DISABLE_UNAME=y +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_NSH_DISABLE_WGET=y +# CONFIG_NSH_DISABLE_XD is not set +CONFIG_NSH_MMCSDMINOR=0 + +# +# Configure Command Options +# +CONFIG_NSH_CODECS_BUFSIZE=128 +# CONFIG_NSH_CMDOPT_HEXDUMP is not set +CONFIG_NSH_FILEIOSIZE=64 + +# +# Scripting Support +# +CONFIG_NSH_DISABLESCRIPT=y + +# +# Console Configuration +# +CONFIG_NSH_CONSOLE=y +# CONFIG_NSH_ALTCONDEV is not set +# CONFIG_NSH_ARCHINIT is not set +# CONFIG_NSH_LOGIN is not set +# CONFIG_NSH_CONSOLE_LOGIN is not set + +# +# NxWidgets/NxWM +# + +# +# Platform-specific Support +# +# CONFIG_PLATFORM_CONFIGDATA is not set + +# +# System Libraries and NSH Add-Ons +# +# CONFIG_SYSTEM_CLE is not set +# CONFIG_SYSTEM_CUTERM is not set +# CONFIG_SYSTEM_FREE is not set +# CONFIG_SYSTEM_HEX2BIN is not set +# CONFIG_SYSTEM_HEXED is not set +# CONFIG_SYSTEM_INSTALL is not set +# CONFIG_SYSTEM_RAMTEST is not set +CONFIG_READLINE_HAVE_EXTMATCH=y +CONFIG_SYSTEM_READLINE=y +CONFIG_READLINE_ECHO=y +# CONFIG_READLINE_TABCOMPLETION is not set +# CONFIG_READLINE_CMD_HISTORY is not set +# CONFIG_SYSTEM_SUDOKU is not set +# CONFIG_SYSTEM_SYSTEM is not set +# CONFIG_SYSTEM_TEE is not set +# CONFIG_SYSTEM_UBLOXMODEM is not set +# CONFIG_SYSTEM_VI is not set +# CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# diff --git a/configs/stm32f0discovery/nsh/setenv.sh b/configs/stm32f0discovery/nsh/setenv.sh new file mode 100644 index 0000000000..f131c7cefb --- /dev/null +++ b/configs/stm32f0discovery/nsh/setenv.sh @@ -0,0 +1,76 @@ +#!/bin/bash +# configs/stm32f0discovery/nsh/setenv.sh +# +# Copyright (C) 2017 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# Alan Carvalho de Assis +# +# 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. +# + +if [ "$_" = "$0" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +fi + +WD=`pwd` +if [ ! -x "setenv.sh" ]; then + echo "This script must be executed from the top-level NuttX build directory" + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then + export PATH_ORIG="${PATH}" +fi + +# This is the Cygwin path to the location where I installed the RIDE +# toolchain under windows. You will also have to edit this if you install +# the RIDE toolchain in any other location +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" + +# This is the Cygwin path to the location where I installed the CodeSourcery +# toolchain under windows. You will also have to edit this if you install +# the CodeSourcery toolchain in any other location +export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" + +# These are the Cygwin paths to the locations where I installed the Atollic +# toolchain under windows. You will also have to edit this if you install +# the Atollic toolchain in any other location. /usr/bin is added before +# the Atollic bin path because there is are binaries named gcc.exe and g++.exe +# at those locations as well. +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" + +# This is the Cygwin path to the location where I build the buildroot +# toolchain. +#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" + +# Add the path to the toolchain to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" + +echo "PATH : ${PATH}" diff --git a/configs/stm32f0discovery/scripts/flash.ld b/configs/stm32f0discovery/scripts/flash.ld new file mode 100644 index 0000000000..2996e3017a --- /dev/null +++ b/configs/stm32f0discovery/scripts/flash.ld @@ -0,0 +1,120 @@ +/**************************************************************************** + * configs/stm32f0discovery/scripts/flash.ld + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Alan Carvalho de Assis + * + * 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. + * + ****************************************************************************/ + +/* The STM32F051R8T6 has 64KB of FLASH beginning at address 0x0800:0000 and + * 8Kb of SRAM at address 0x20000000. + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x08000000, LENGTH = 64K + sram (rwx) : ORIGIN = 0x20000000, LENGTH = 8K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + } > flash + + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/configs/stm32f0discovery/scripts/gnu-elf.ld b/configs/stm32f0discovery/scripts/gnu-elf.ld new file mode 100644 index 0000000000..7361e546da --- /dev/null +++ b/configs/stm32f0discovery/scripts/gnu-elf.ld @@ -0,0 +1,130 @@ +/**************************************************************************** + * configs/stm32f0discovery/scripts/gnu-elf.ld + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Alan Carvalho de Assis + * + * 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. + * + ****************************************************************************/ + +SECTIONS +{ + .text 0x00000000 : + { + _stext = . ; + *(.text) + *(.text.*) + *(.gnu.warning) + *(.stub) + *(.glue_7) + *(.glue_7t) + *(.jcr) + + /* C++ support: The .init and .fini sections contain specific logic + * to manage static constructors and destructors. + */ + + *(.gnu.linkonce.t.*) + *(.init) /* Old ABI */ + *(.fini) /* Old ABI */ + _etext = . ; + } + + .rodata : + { + _srodata = . ; + *(.rodata) + *(.rodata1) + *(.rodata.*) + *(.gnu.linkonce.r*) + _erodata = . ; + } + + .data : + { + _sdata = . ; + *(.data) + *(.data1) + *(.data.*) + *(.gnu.linkonce.d*) + _edata = . ; + } + + /* C++ support. For each global and static local C++ object, + * GCC creates a small subroutine to construct the object. Pointers + * to these routines (not the routines themselves) are stored as + * simple, linear arrays in the .ctors section of the object file. + * Similarly, pointers to global/static destructor routines are + * stored in .dtors. + */ + + .ctors : + { + _sctors = . ; + *(.ctors) /* Old ABI: Unallocated */ + *(.init_array) /* New ABI: Allocated */ + _edtors = . ; + } + + .dtors : + { + _sdtors = . ; + *(.dtors) /* Old ABI: Unallocated */ + *(.fini_array) /* New ABI: Allocated */ + _edtors = . ; + } + + .bss : + { + _sbss = . ; + *(.bss) + *(.bss.*) + *(.sbss) + *(.sbss.*) + *(.gnu.linkonce.b*) + *(COMMON) + _ebss = . ; + } + + /* Stabs debugging sections. */ + + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/configs/stm32f0discovery/src/.gitignore b/configs/stm32f0discovery/src/.gitignore new file mode 100644 index 0000000000..726d936e1e --- /dev/null +++ b/configs/stm32f0discovery/src/.gitignore @@ -0,0 +1,2 @@ +/.depend +/Make.dep diff --git a/configs/stm32f0discovery/src/Makefile b/configs/stm32f0discovery/src/Makefile new file mode 100644 index 0000000000..f1458e3cfb --- /dev/null +++ b/configs/stm32f0discovery/src/Makefile @@ -0,0 +1,68 @@ +############################################################################ +# configs/stm32f0discovery/src/Makefile +# +# Copyright (C) 2017 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# Alan Carvalho de Assis +# +# 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. +# +############################################################################ + +-include $(TOPDIR)/Make.defs + +ASRCS = +CSRCS = stm32_boot.c stm32_bringup.c + +ifeq ($(CONFIG_ARCH_LEDS),y) +CSRCS += stm32_autoleds.c +else +CSRCS += stm32_userleds.c +endif + +ifeq ($(CONFIG_ARCH_BUTTONS),y) +CSRCS += stm32_buttons.c +endif + +ifeq ($(CONFIG_STM32F0_SPI),y) +CSRCS += stm32_spi.c +endif + +ifeq ($(CONFIG_PWM),y) +CSRCS += stm32_pwm.c +endif + +ifeq ($(CONFIG_QENCODER),y) +CSRCS += stm32_qencoder.c +endif + +ifeq ($(CONFIG_LIB_BOARDCTL),y) +CSRCS += stm32_appinit.c +endif + +include $(TOPDIR)/configs/Board.mk diff --git a/configs/stm32f0discovery/src/stm32_appinit.c b/configs/stm32f0discovery/src/stm32_appinit.c new file mode 100644 index 0000000000..a69c731e1e --- /dev/null +++ b/configs/stm32f0discovery/src/stm32_appinit.c @@ -0,0 +1,87 @@ +/**************************************************************************** + * config/stm32f0discovery/src/stm32_appinit.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Alan Carvalho de Assis + * + * 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 "stm32f0discovery.h" + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; the meaning of the argument is a contract + * between the board-specific initalization logic and the the + * matching application logic. The value cold be such things as a + * mode enumeration value, a set of DIP switch switch settings, a + * pointer to configuration data read from a file or serial FLASH, + * or whatever you would like to do with it. Every implementation + * should accept zero/NULL as a default configuration. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ + +int board_app_initialize(uintptr_t arg) +{ + /* Did we already initialize via board_initialize()? */ + +#ifndef CONFIG_BOARD_INITIALIZE + return stm32_bringup(); +#else + return OK; +#endif +} diff --git a/configs/stm32f0discovery/src/stm32_autoleds.c b/configs/stm32f0discovery/src/stm32_autoleds.c new file mode 100644 index 0000000000..6423d1818c --- /dev/null +++ b/configs/stm32f0discovery/src/stm32_autoleds.c @@ -0,0 +1,138 @@ +/**************************************************************************** + * configs/stm32f0discovery/src/stm32_autoleds.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Alan Carvalho de Assis + * + * 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 "chip.h" +#include "stm32f0.h" +#include "stm32f0discovery.h" + +#ifdef CONFIG_ARCH_LEDS + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* If CONFIG_ARCH_LEDs is defined, then NuttX will control the 2 LEDs on + * board the STM32L-Discovery. The following definitions describe how NuttX + * controls the LEDs: + * + * SYMBOL Meaning LED state + * LED1 LED2 + * ------------------- ----------------------- -------- -------- + * LED_STARTED NuttX has been started OFF OFF + * LED_HEAPALLOCATE Heap has been allocated OFF OFF + * LED_IRQSENABLED Interrupts enabled OFF OFF + * LED_STACKCREATED Idle stack created ON OFF + * LED_INIRQ In an interrupt No change + * LED_SIGNAL In a signal handler No change + * LED_ASSERTION An assertion failed No change + * LED_PANIC The system has crashed OFF Blinking + * LED_IDLE STM32 is is sleep mode Not used + */ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_autoled_initialize + ****************************************************************************/ + +void board_autoled_initialize(void) +{ + /* Configure LED1-2 GPIOs for output */ + + stm32f0_configgpio(GPIO_LED1); + stm32f0_configgpio(GPIO_LED2); +} + +/**************************************************************************** + * Name: board_autoled_on + ****************************************************************************/ + +void board_autoled_on(int led) +{ + bool led1on = false; + bool led2on = false; + + switch (led) + { + case 0: /* LED_STARTED, LED_HEAPALLOCATE, LED_IRQSENABLED */ + break; + + case 1: /* LED_STACKCREATED */ + led1on = true; + break; + + default: + case 2: /* LED_INIRQ, LED_SIGNAL, LED_ASSERTION */ + return; + + case 3: /* LED_PANIC */ + led2on = true; + break; + } + + stm32f0_gpiowrite(GPIO_LED1, led1on); + stm32f0_gpiowrite(GPIO_LED2, led2on); +} + +/**************************************************************************** + * Name: board_autoled_off + ****************************************************************************/ + +void board_autoled_off(int led) +{ + if (led != 2) + { + stm32f0_gpiowrite(GPIO_LED1, false); + stm32f0_gpiowrite(GPIO_LED2, false); + } +} + +#endif /* CONFIG_ARCH_LEDS */ diff --git a/configs/stm32f0discovery/src/stm32_boot.c b/configs/stm32f0discovery/src/stm32_boot.c new file mode 100644 index 0000000000..5c04acd03f --- /dev/null +++ b/configs/stm32f0discovery/src/stm32_boot.c @@ -0,0 +1,95 @@ +/************************************************************************************ + * configs/stm32f0discovery/src/stm32f0_boot.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Alan Carvalho de Assis + * + * 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 "up_arch.h" +#include "stm32f0discovery.h" + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32f0_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the intitialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +void stm32f0_boardinitialize(void) +{ +#ifdef CONFIG_ARCH_LEDS + /* Configure on-board LEDs if LED support has been selected. */ + + board_autoled_initialize(); +#endif +} + +/**************************************************************************** + * Name: board_initialize + * + * Description: + * If CONFIG_BOARD_INITIALIZE is selected, then an additional + * initialization call will be performed in the boot-up sequence to a + * function called board_initialize(). board_initialize() will be + * called immediately after up_initialize() is called and just before the + * initial application is started. This additional initialization phase + * may be used, for example, to initialize board-specific device drivers. + * + ****************************************************************************/ + +#ifdef CONFIG_BOARD_INITIALIZE +void board_initialize(void) +{ + /* Perform board-specific initialization here if so configured */ + + (void)stm32_bringup(); +} +#endif + diff --git a/configs/stm32f0discovery/src/stm32_bringup.c b/configs/stm32f0discovery/src/stm32_bringup.c new file mode 100644 index 0000000000..317329b07c --- /dev/null +++ b/configs/stm32f0discovery/src/stm32_bringup.c @@ -0,0 +1,80 @@ +/**************************************************************************** + * config/stm32f0discovery/src/stm32_bringup.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include "stm32f0discovery.h" + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_bringup + * + * Description: + * Perform architecture-specific initialization + * + * CONFIG_BOARD_INITIALIZE=y : + * Called from board_initialize(). + * + * CONFIG_BOARD_INITIALIZE=n && CONFIG_LIB_BOARDCTL=y : + * Called from the NSH library + * + ****************************************************************************/ + +int stm32_bringup(void) +{ + int ret; + +#ifdef CONFIG_FS_PROCFS + /* Mount the procfs file system */ + + ret = mount(NULL, "/proc", "procfs", 0, NULL); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: Failed to mount procfs at /proc: %d\n", ret); + } +#endif + + UNUSED(ret); + return OK; +} diff --git a/configs/stm32f0discovery/src/stm32_buttons.c b/configs/stm32f0discovery/src/stm32_buttons.c new file mode 100644 index 0000000000..1bcc3b5e54 --- /dev/null +++ b/configs/stm32f0discovery/src/stm32_buttons.c @@ -0,0 +1,162 @@ +/**************************************************************************** + * configs/stm32f0discovery/src/board_buttons.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Alan Carvalho de Assis + * + * 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 "stm32f0discovery.h" + +#ifdef CONFIG_ARCH_BUTTONS + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* Pin configuration for each STM32F3Discovery button. This array is indexed by + * the BUTTON_* definitions in board.h + */ + +static const uint32_t g_buttons[NUM_BUTTONS] = +{ + GPIO_BTN_USER +}; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_button_initialize + * + * Description: + * board_button_initialize() must be called to initialize button resources. After + * that, board_buttons() may be called to collect the current state of all + * buttons or board_button_irq() may be called to register button interrupt + * handlers. + * + ****************************************************************************/ + +void board_button_initialize(void) +{ + int i; + + /* Configure the GPIO pins as inputs. NOTE that EXTI interrupts are + * configured for all pins. + */ + + for (i = 0; i < NUM_BUTTONS; i++) + { + stm32_configgpio(g_buttons[i]); + } +} + +/**************************************************************************** + * Name: board_buttons + ****************************************************************************/ + +uint8_t board_buttons(void) +{ + uint8_t ret = 0; + int i; + + /* Check that state of each key */ + + for (i = 0; i < NUM_BUTTONS; i++) + { + /* A LOW value means that the key is pressed. + */ + + bool released = stm32_gpioread(g_buttons[i]); + + /* Accumulate the set of depressed (not released) keys */ + + if (!released) + { + ret |= (1 << i); + } + } + + return ret; +} + +/************************************************************************************ + * Button support. + * + * Description: + * board_button_initialize() must be called to initialize button resources. After + * that, board_buttons() may be called to collect the current state of all + * buttons or board_button_irq() may be called to register button interrupt + * handlers. + * + * After board_button_initialize() has been called, board_buttons() may be called to + * collect the state of all buttons. board_buttons() returns an 8-bit bit set + * with each bit associated with a button. See the BUTTON_*_BIT + * definitions in board.h for the meaning of each bit. + * + * board_button_irq() may be called to register an interrupt handler that will + * be called when a button is depressed or released. The ID value is a + * button enumeration value that uniquely identifies a button resource. See the + * BUTTON_* definitions in board.h for the meaning of enumeration + * value. + * + ************************************************************************************/ + +#ifdef CONFIG_ARCH_IRQBUTTONS +int board_button_irq(int id, xcpt_t irqhandler, FAR void *arg) +{ + int ret = -EINVAL; + + /* The following should be atomic */ + + if (id >= MIN_IRQBUTTON && id <= MAX_IRQBUTTON) + { + ret = stm32_gpiosetevent(g_buttons[id], true, true, true, irqhandler, arg); + } + + return ret; +} +#endif +#endif /* CONFIG_ARCH_BUTTONS */ diff --git a/configs/stm32f0discovery/src/stm32_userleds.c b/configs/stm32f0discovery/src/stm32_userleds.c new file mode 100644 index 0000000000..1478c7375c --- /dev/null +++ b/configs/stm32f0discovery/src/stm32_userleds.c @@ -0,0 +1,110 @@ +/**************************************************************************** + * configs/stm32f0discovery/src/stm32_userleds.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Alan Carvalho de Assis + * + * 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 "chip.h" +#include "stm32.h" +#include "stm32f0discovery.h" + +#ifndef CONFIG_ARCH_LEDS + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_userled_initialize + ****************************************************************************/ + +void board_userled_initialize(void) +{ + /* Configure LED1-2 GPIOs for output */ + + stm32_configgpio(GPIO_LED1); + stm32_configgpio(GPIO_LED2); +} + +/**************************************************************************** + * Name: board_userled + ****************************************************************************/ + +void board_userled(int led, bool ledon) +{ + uint32_t ledcfg; + + if (led == BOARD_LED1) + { + ledcfg = GPIO_LED1; + } + else if (led == BOARD_LED2) + { + ledcfg = GPIO_LED2; + } + else + { + return; + } + + stm32_gpiowrite(ledcfg, ledon); +} + +/**************************************************************************** + * Name: board_userled_all + ****************************************************************************/ + +void board_userled_all(uint8_t ledset) +{ + bool ledon; + + ledon = ((ledset & BOARD_LED1_BIT) != 0); + stm32_gpiowrite(GPIO_LED1, ledon); + + ledon = ((ledset & BOARD_LED2_BIT) != 0); + stm32_gpiowrite(GPIO_LED2, ledon); +} + +#endif /* !CONFIG_ARCH_LEDS */ diff --git a/configs/stm32f0discovery/src/stm32f0discovery.h b/configs/stm32f0discovery/src/stm32f0discovery.h new file mode 100644 index 0000000000..29da8bd017 --- /dev/null +++ b/configs/stm32f0discovery/src/stm32f0discovery.h @@ -0,0 +1,133 @@ +/**************************************************************************************************** + * configs/stm32f0discovery/src/stm32f0discovery.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Alan Carvalho de Assis + * + * 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 __CONFIGS_STM32F0DISCOVERY_SRC_STM32F0DISCOVERY_H +#define __CONFIGS_STM32F0DISCOVERY_SRC_STM32F0DISCOVERY_H + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include + +/**************************************************************************************************** + * Pre-processor Definitions + ****************************************************************************************************/ + +/* Configuration ************************************************************************************/ +/* How many SPI modules does this chip support? */ + +#if STM32F0_NSPI < 1 +# undef CONFIG_STM32F0_SPI1 +# undef CONFIG_STM32F0_SPI2 +# undef CONFIG_STM32F0_SPI3 +#elif STM32F0_NSPI < 2 +# undef CONFIG_STM32F0_SPI2 +# undef CONFIG_STM32F0_SPI3 +#elif STM32F0_NSPI < 3 +# undef CONFIG_STM32F0_SPI3 +#endif + +/* STM32F0Discovery GPIOs ***************************************************************************/ +/* The STM32F0Discovery board has four LEDs. Two of these are controlled by logic on the board and + * are not available for software control: + * + * LD1 COM: LD2 default status is red. LD2 turns to green to indicate that communications are in + * progress between the PC and the ST-LINK/V2. + * LD2 PWR: Red LED indicates that the board is powered. + * + * And two LEDs can be controlled by software: + * + * User LD3: Green LED is a user LED connected to the I/O PB7 of the STM32L152 MCU. + * User LD4: Blue LED is a user LED connected to the I/O PB6 of the STM32L152 MCU. + * + * The other side of the LED connects to ground so high value will illuminate the LED. + */ + +#define GPIO_LED1 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_10MHz | \ + GPIO_OUTPUT_CLEAR | GPIO_PORTC | GPIO_PIN9) +#define GPIO_LED2 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_10MHz | \ + GPIO_OUTPUT_CLEAR | GPIO_PORTC | GPIO_PIN8) + +/* Button definitions *******************************************************************************/ +/* The STM32F0Discovery supports two buttons; only one button is controllable by software: + * + * B1 USER: user and wake-up button connected to the I/O PA0 of the STM32F303VCT6. + * B2 RESET: pushbutton connected to NRST is used to RESET the STM32F303VCT6. + * + * NOTE that EXTI interrupts are configured + */ + +#define MIN_IRQBUTTON BUTTON_USER +#define MAX_IRQBUTTON BUTTON_USER +#define NUM_IRQBUTTONS 1 + +#define GPIO_BTN_USER (GPIO_INPUT | GPIO_FLOAT | GPIO_EXTI | GPIO_PORTA | GPIO_PIN0) + +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + +/**************************************************************************************************** + * Public data + ****************************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************************************** + * Public Functions + ****************************************************************************************************/ + +/**************************************************************************** + * Name: stm32_bringup + * + * Description: + * Perform architecture-specific initialization + * + * CONFIG_BOARD_INITIALIZE=y : + * Called from board_initialize(). + * + * CONFIG_BOARD_INITIALIZE=n && CONFIG_LIB_BOARDCTL=y : + * Called from the NSH library + * + ****************************************************************************/ + +int stm32_bringup(void); + +#endif /* __ASSEMBLY__ */ +#endif /* __CONFIGS_STM32F0DISCOVERY_SRC_STM32F0DISCOVERY_H */ -- GitLab From 2a7909aade50776048ca2584de2c54d861c40c2e Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Fri, 14 Apr 2017 08:50:47 -0600 Subject: [PATCH 436/990] Small fixes to get stm32f0discovery compiled correctly --- configs/stm32f0discovery/include/board.h | 1 - configs/stm32f0discovery/src/stm32_autoleds.c | 1 - configs/stm32f0discovery/src/stm32_bringup.c | 1 + configs/stm32f0discovery/src/stm32f0discovery.h | 2 ++ 4 files changed, 3 insertions(+), 2 deletions(-) diff --git a/configs/stm32f0discovery/include/board.h b/configs/stm32f0discovery/include/board.h index c6f7f32733..184c374276 100644 --- a/configs/stm32f0discovery/include/board.h +++ b/configs/stm32f0discovery/include/board.h @@ -48,7 +48,6 @@ #endif #include "stm32f0_rcc.h" -#include "stm32f0.h" /************************************************************************************ * Pre-processor Definitions diff --git a/configs/stm32f0discovery/src/stm32_autoleds.c b/configs/stm32f0discovery/src/stm32_autoleds.c index 6423d1818c..1627bf2e25 100644 --- a/configs/stm32f0discovery/src/stm32_autoleds.c +++ b/configs/stm32f0discovery/src/stm32_autoleds.c @@ -48,7 +48,6 @@ #include #include "chip.h" -#include "stm32f0.h" #include "stm32f0discovery.h" #ifdef CONFIG_ARCH_LEDS diff --git a/configs/stm32f0discovery/src/stm32_bringup.c b/configs/stm32f0discovery/src/stm32_bringup.c index 317329b07c..61003b54f8 100644 --- a/configs/stm32f0discovery/src/stm32_bringup.c +++ b/configs/stm32f0discovery/src/stm32_bringup.c @@ -40,6 +40,7 @@ #include #include +#include #include "stm32f0discovery.h" diff --git a/configs/stm32f0discovery/src/stm32f0discovery.h b/configs/stm32f0discovery/src/stm32f0discovery.h index 29da8bd017..fca605e006 100644 --- a/configs/stm32f0discovery/src/stm32f0discovery.h +++ b/configs/stm32f0discovery/src/stm32f0discovery.h @@ -45,6 +45,8 @@ #include #include +#include "stm32f0_gpio.h" + /**************************************************************************************************** * Pre-processor Definitions ****************************************************************************************************/ -- GitLab From 2158c2d582ea9092ed49863953ad422114c135fc Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 14 Apr 2017 08:53:24 -0600 Subject: [PATCH 437/990] STM32F0 Discovery: Remove inclusion of stm32_rcc.h in board.h --- configs/stm32f0discovery/include/board.h | 2 -- 1 file changed, 2 deletions(-) diff --git a/configs/stm32f0discovery/include/board.h b/configs/stm32f0discovery/include/board.h index 184c374276..4123b11f56 100644 --- a/configs/stm32f0discovery/include/board.h +++ b/configs/stm32f0discovery/include/board.h @@ -47,8 +47,6 @@ # include #endif -#include "stm32f0_rcc.h" - /************************************************************************************ * Pre-processor Definitions ************************************************************************************/ -- GitLab From 879273f63e5d68b065eeda960b2ffac3927a7472 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 14 Apr 2017 09:32:15 -0600 Subject: [PATCH 438/990] arch/arm/Kconfig: Add option for STM32F0 --- arch/arm/Kconfig | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/arch/arm/Kconfig b/arch/arm/Kconfig index 228472890e..b7ccb129b3 100644 --- a/arch/arm/Kconfig +++ b/arch/arm/Kconfig @@ -232,6 +232,13 @@ config ARCH_CHIP_STM32 ---help--- STMicro STM32 architectures (ARM Cortex-M3/4). +config ARCH_CHIP_STM32F0 + bool "STMicro STM32 F0" + select ARCH_CORTEXM0 + select ARCH_HAVE_CMNVECTOR + ---help--- + STMicro STM32 architectures (ARM Cortex-M0). + config ARCH_CHIP_STM32F7 bool "STMicro STM32 F7" select ARCH_HAVE_CMNVECTOR @@ -441,6 +448,7 @@ config ARCH_CHIP default "sam34" if ARCH_CHIP_SAM34 default "samv7" if ARCH_CHIP_SAMV7 default "stm32" if ARCH_CHIP_STM32 + default "stm32f0" if ARCH_CHIP_STM32F0 default "stm32f7" if ARCH_CHIP_STM32F7 default "stm32l4" if ARCH_CHIP_STM32L4 default "str71x" if ARCH_CHIP_STR71X @@ -697,6 +705,9 @@ endif if ARCH_CHIP_STM32 source arch/arm/src/stm32/Kconfig endif +if ARCH_CHIP_STM32F0 +source arch/arm/src/stm32f0/Kconfig +endif if ARCH_CHIP_STM32F7 source arch/arm/src/stm32f7/Kconfig endif -- GitLab From badd36170d97d617ba4580386b4e19e683ed7ab9 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 14 Apr 2017 10:38:46 -0600 Subject: [PATCH 439/990] IEEE802.15.4: There is only one instance of the IEEE802.15.4 MAC lower level. There is no need for the interface to be indirect via a vtable. In this case, standard global functions should be used. --- configs/clicker2-stm32/src/stm32_mrf24j40.c | 2 +- .../wireless/ieee802154/ieee802154_mac.h | 416 +++++++++----- wireless/ieee802154/mac802154.c | 374 +++++------- wireless/ieee802154/mac802154_device.c | 13 +- wireless/ieee802154/mac802154_netdev.c | 544 ++++++++---------- 5 files changed, 681 insertions(+), 668 deletions(-) diff --git a/configs/clicker2-stm32/src/stm32_mrf24j40.c b/configs/clicker2-stm32/src/stm32_mrf24j40.c index 8f6868f59e..e1b664f28b 100644 --- a/configs/clicker2-stm32/src/stm32_mrf24j40.c +++ b/configs/clicker2-stm32/src/stm32_mrf24j40.c @@ -228,7 +228,7 @@ static int stm32_mrf24j40_devsetup(FAR struct stm32_priv_s *priv) { FAR struct ieee802154_radio_s *radio; #ifdef CONFIG_IEEE802154_MAC - FAR struct ieee802154_mac_s *mac; + MACHANDLE mac; #endif FAR struct spi_dev_s *spi; int ret; diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index 5dbed05ea7..acfc541c58 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -881,96 +881,12 @@ struct ieee802154_netmac_s }; #endif -/* MAC Interface Operations *************************************************/ - -struct ieee802154_mac_s; /* Forward reference */ -struct ieee802154_maccb_s; /* Forward reference */ - -struct ieee802154_macops_s -{ - /* Requests, confirmed asynchronously via callbacks */ - - /* Transmit a data frame */ - - CODE int (*req_data)(FAR struct ieee802154_mac_s *mac, - FAR struct ieee802154_data_req_s *req); - - /* Cancel transmission of a data frame */ - - CODE int (*req_purge)(FAR struct ieee802154_mac_s *mac, uint8_t handle); - - /* Start association with coordinator */ - - CODE int (*req_associate)(FAR struct ieee802154_mac_s *mac, - FAR struct ieee802154_assoc_req_s *req); - - /* Start disassociation with coordinator */ - - CODE int (*req_disassociate)(FAR struct ieee802154_mac_s *mac, - FAR struct ieee802154_disassoc_req_s *req); - - /* Read the PIB */ - - CODE int (*req_get)(FAR struct ieee802154_mac_s *mac, - enum ieee802154_pib_attr_e attr); - - /* Allocate or deallocate a GTS */ - - CODE int (*req_gts)(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *characteristics); - - /* MAC layer reset */ - - CODE int (*req_reset)(FAR struct ieee802154_mac_s *mac, bool setdefaults); - - /* PHY receiver control */ - - CODE int (*req_rxenable)(FAR struct ieee802154_mac_s *mac, bool deferrable, - int ontime, int duration); - - /* Start a network scan */ - - CODE int (*req_scan)(FAR struct ieee802154_mac_s *mac, uint8_t type, - uint32_t channels, int duration); - - /* Change the PIB */ - - CODE int (*req_set)(FAR struct ieee802154_mac_s *mac, int attribute, - FAR uint8_t *value, int valuelen); - - CODE int (*req_start)(FAR struct ieee802154_mac_s *mac, uint16_t panid, - int channel, uint8_t bo, uint8_t fo, bool coord, - bool batext, bool realign); - - CODE int (*req_sync)(FAR struct ieee802154_mac_s *mac, int channel, - bool track); - - CODE int (*req_poll)(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *coordaddr); - - /* Synchronous Responses to Indications received via callbacks */ - - /* Reply to an association request */ - - CODE int (*rsp_associate)(FAR struct ieee802154_mac_s *mac, uint8_t eadr, - uint16_t saddr, int status); - - /* Orphan device management */ - - CODE int (*rsp_orphan)(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *orphanaddr, uint16_t saddr, - bool associated); - - /* Bind callbacks to the IEEE802.15.4 MAC */ - - CODE int (*bind)(FAR struct ieee802154_mac_s *mac, - FAR const struct ieee802154_maccb_s *cb); - - /* IOCTL support */ +/* This is an opaque reference to the MAC's internal private state. It is + * returned by mac802154_create() when it is created. It may then be used + * at other interfaces in order to interact with the MAC. + */ - CODE int (*ioctl)(FAR struct ieee802154_mac_s *mac, int cmd, - unsigned long arg); -}; +typedef FAR void *MACHANDLE; /* Notifications */ @@ -980,99 +896,83 @@ struct ieee802154_maccb_s /* Data frame was received by remote device */ - CODE void (*conf_data)(FAR struct ieee802154_mac_s *mac, + CODE void (*conf_data)(MACHANDLE mac, FAR struct ieee802154_data_conf_s *conf); /* Data frame was purged */ - CODE void (*conf_purge)(FAR struct ieee802154_mac_s *mac, uint8_t handle, - int status); + CODE void (*conf_purge)(MACHANDLE mac, uint8_t handle, int status); /* Association request completed */ - CODE void (*conf_associate)(FAR struct ieee802154_mac_s *mac, - uint16_t saddr, int status); + CODE void (*conf_associate)(MACHANDLE mac, uint16_t saddr, int status); /* Disassociation request completed */ - CODE void (*conf_disassociate)(FAR struct ieee802154_mac_s *mac, - int status); + CODE void (*conf_disassociate)(MACHANDLE mac, int status); /* PIvoata returned */ - CODE void (*conf_get)(FAR struct ieee802154_mac_s *mac, int status, - int attribute, FAR uint8_t *value, - int valuelen); + CODE void (*conf_get)(MACHANDLE mac, int status, int attribute, + FAR uint8_t *value, int valuelen); /* GTvoanagement completed */ - CODE void (*conf_gts)(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *characteristics, int status); + CODE void (*conf_gts)(MACHANDLE mac, FAR uint8_t *characteristics, + int status); /* MAveset completed */ - CODE void (*conf_reset)(FAR struct ieee802154_mac_s *mac, int status); + CODE void (*conf_reset)(MACHANDLE mac, int status); - CODE void (*conf_rxenable)(FAR struct ieee802154_mac_s *mac, int status); + CODE void (*conf_rxenable)(MACHANDLE mac, int status); - CODE void (*conf_scan)(FAR struct ieee802154_mac_s *mac, int status, - uint8_t type, uint32_t unscanned, int rsltsize, + CODE void (*conf_scan)(MACHANDLE mac, int status, uint8_t type, + uint32_t unscanned, int rsltsize, FAR uint8_t *edlist, FAR uint8_t *pandescs); - CODE void (*conf_set)(FAR struct ieee802154_mac_s *mac, int status, - int attribute); + CODE void (*conf_set)(MACHANDLE mac, int status, int attribute); - CODE void (*conf_start)(FAR struct ieee802154_mac_s *mac, int status); + CODE void (*conf_start)(MACHANDLE mac, int status); - CODE void (*conf_poll)(FAR struct ieee802154_mac_s *mac, int status); + CODE void (*conf_poll)(MACHANDLE mac, int status); /* Asynchronous event indications, replied to synchronously with responses */ /* Data frame received */ - CODE void (*ind_data)(FAR struct ieee802154_mac_s *mac, FAR uint8_t *buf, - int len); + CODE void (*ind_data)(MACHANDLE mac, FAR uint8_t *buf, int len); /* Association request received */ - CODE void (*ind_associate)(FAR struct ieee802154_mac_s *mac, - uint16_t clipanid, FAR uint8_t *clieaddr); + CODE void (*ind_associate)(MACHANDLE mac, uint16_t clipanid, + FAR uint8_t *clieaddr); /* Disassociation request received */ - CODE void (*ind_disassociate)(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *eadr, uint8_t reason); + CODE void (*ind_disassociate)(MACHANDLE mac, FAR uint8_t *eadr, + uint8_t reason); /* Beacon notification */ - CODE void (*ind_beaconnotify)(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *bsn, FAR struct ieee802154_pan_desc_s *pandesc, + CODE void (*ind_beaconnotify)(MACHANDLE mac, FAR uint8_t *bsn, + FAR struct ieee802154_pan_desc_s *pandesc, FAR uint8_t *sdu, int sdulen); /* GTS management request received */ - CODE void (*ind_gts)(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *devaddr, FAR uint8_t *characteristics); + CODE void (*ind_gts)(MACHANDLE mac, FAR uint8_t *devaddr, + FAR uint8_t *characteristics); /* Orphan device detected */ - CODE void (*ind_orphan)(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *orphanaddr); + CODE void (*ind_orphan)(MACHANDLE mac, FAR uint8_t *orphanaddr); - CODE void (*ind_commstatus)(FAR struct ieee802154_mac_s *mac, - uint16_t panid, FAR uint8_t *src, - FAR uint8_t *dst, int status); + CODE void (*ind_commstatus)(MACHANDLE mac, uint16_t panid, + FAR uint8_t *src, FAR uint8_t *dst, + int status); - CODE void (*ind_syncloss)(FAR struct ieee802154_mac_s *mac, int reason); -}; - -struct ieee802154_mac_s -{ - /* Publicly visiable part of the MAC interface */ - - struct ieee802154_macops_s ops; - - /* MAC private data may follow */ + CODE void (*ind_syncloss)(MACHANDLE mac, int reason); }; #ifdef __cplusplus @@ -1109,13 +1009,11 @@ struct ieee802154_radio_s; /* Forward reference */ * radiodev - an instance of an IEEE 802.15.4 radio * * Returned Value: - * A MAC structure that has pointers to MAC operations - * and responses. + * An opaque reference to the MAC state data. * ****************************************************************************/ -FAR struct ieee802154_mac_s * - mac802154_create(FAR struct ieee802154_radio_s *radiodev); +MACHANDLE mac802154_create(FAR struct ieee802154_radio_s *radiodev); /**************************************************************************** * Name: mac802154dev_register @@ -1135,7 +1033,7 @@ FAR struct ieee802154_mac_s * * ****************************************************************************/ -int mac802154dev_register(FAR struct ieee802154_mac_s *mac, int minor); +int mac802154dev_register(MACHANDLE mac, int minor); /**************************************************************************** * Name: mac802154netdev_register @@ -1153,7 +1051,245 @@ int mac802154dev_register(FAR struct ieee802154_mac_s *mac, int minor); * ****************************************************************************/ -int mac802154netdev_register(FAR struct ieee802154_mac_s *mac); +int mac802154netdev_register(MACHANDLE mac); + +/**************************************************************************** + * Name: mac802154_bind + * + * Description: + * Bind the MAC callback table to the MAC state. + * + * Parameters: + * mac - Reference to the MAC driver state structure + * cb - MAC callback operations + * + * Returned Value: + * OK on success; Negated errno on failure. + * + ****************************************************************************/ + +int mac802154_bind(MACHANDLE mac, FAR const struct ieee802154_maccb_s *cb); + +/**************************************************************************** + * Name: mac802154_ioctl + * + * Description: + * Handle MAC and radio IOCTL commands directed to the MAC. + * + * Parameters: + * mac - Reference to the MAC driver state structure + * cmd - The IOCTL command + * arg - The argument for the IOCTL command + * + * Returned Value: + * OK on success; Negated errno on failure. + * + ****************************************************************************/ + +int mac802154_ioctl(MACHANDLE mac, int cmd, unsigned long arg); + +/**************************************************************************** + * MAC Interface Operations + ****************************************************************************/ + +/**************************************************************************** + * Name: mac802154_req_data + * + * Description: + * The MCPS-DATA.request primitive requests the transfer of a data SPDU + * (i.e., MSDU) from a local SSCS entity to a single peer SSCS entity. + * Confirmation is returned via the + * struct ieee802154_maccb_s->conf_data callback. + * + ****************************************************************************/ + +int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req); + +/**************************************************************************** + * Name: mac802154_req_purge + * + * Description: + * The MCPS-PURGE.request primitive allows the next higher layer to purge an + * MSDU from the transaction queue. Confirmation is returned via + * the struct ieee802154_maccb_s->conf_purge callback. + * + ****************************************************************************/ + +int mac802154_req_purge(MACHANDLE mac, uint8_t handle); + +/**************************************************************************** + * Name: mac802154_req_associate + * + * Description: + * The MLME-ASSOCIATE.request primitive allows a device to request an + * association with a coordinator. Confirmation is returned via the + * struct ieee802154_maccb_s->conf_associate callback. + * + ****************************************************************************/ + +int mac802154_req_associate(MACHANDLE mac + FAR struct ieee802154_assoc_req_s *req); + +/**************************************************************************** + * Name: mac802154_req_disassociate + * + * Description: + * The MLME-DISASSOCIATE.request primitive is used by an associated device to + * notify the coordinator of its intent to leave the PAN. It is also used by + * the coordinator to instruct an associated device to leave the PAN. + * Confirmation is returned via the + * struct ieee802154_maccb_s->conf_disassociate callback. + * + ****************************************************************************/ + +int mac802154_req_disassociate(MACHANDLE mac, + FAR struct ieee802154_disassoc_req_s *req); + +/**************************************************************************** + * Name: mac802154_req_get + * + * Description: + * The MLME-GET.request primitive requests information about a given PIB + * attribute. Actual data is returned via the + * struct ieee802154_maccb_s->conf_get callback. + * + ****************************************************************************/ + +int mac802154_req_get(MACHANDLE mac, enum ieee802154_pib_attr_e attr); + +/**************************************************************************** + * Name: mac802154_req_gts + * + * Description: + * The MLME-GTS.request primitive allows a device to send a request to the PAN + * coordinator to allocate a new GTS or to deallocate an existing GTS. + * Confirmation is returned via the + * struct ieee802154_maccb_s->conf_gts callback. + * + ****************************************************************************/ + +int mac802154_req_gts(MACHANDLE mac, FAR uint8_t *characteristics); + +/**************************************************************************** + * Name: mac802154_req_reset + * + * Description: + * The MLME-RESET.request primitive allows the next higher layer to request + * that the MLME performs a reset operation. Confirmation is returned via + * the struct ieee802154_maccb_s->conf_reset callback. + * + ****************************************************************************/ + +int mac802154_req_reset(MACHANDLE mac, bool setdefaults); + +/**************************************************************************** + * Name: mac802154_req_rxenable + * + * Description: + * The MLME-RX-ENABLE.request primitive allows the next higher layer to + * request that the receiver is enable for a finite period of time. + * Confirmation is returned via the + * struct ieee802154_maccb_s->conf_rxenable callback. + * + ****************************************************************************/ + +int mac802154_req_rxenable(MACHANDLE mac, bool deferrable, int ontime, + int duration); + +/**************************************************************************** + * Name: mac802154_req_scan + * + * Description: + * The MLME-SCAN.request primitive is used to initiate a channel scan over a + * given list of channels. A device can use a channel scan to measure the + * energy on the channel, search for the coordinator with which it associated, + * or search for all coordinators transmitting beacon frames within the POS of + * the scanning device. Scan results are returned + * via MULTIPLE calls to the struct ieee802154_maccb_s->conf_scan callback. + * This is a difference with the official 802.15.4 specification, implemented + * here to save memory. + * + ****************************************************************************/ + +int mac802154_req_scan(MACHANDLE mac, uint8_t type, uint32_t channels, + int duration); + +/**************************************************************************** + * Name: mac802154_req_set + * + * Description: + * The MLME-SET.request primitive attempts to write the given value to the + * indicated MAC PIB attribute. Confirmation is returned via the + * struct ieee802154_maccb_s->conf_set callback. + * + ****************************************************************************/ + +int mac802154_req_set(MACHANDLE mac, int attribute, FAR uint8_t *value, + int valuelen); + +/**************************************************************************** + * Name: mac802154_req_start + * + * Description: + * The MLME-START.request primitive makes a request for the device to start + * using a new superframe configuration. Confirmation is returned + * via the struct ieee802154_maccb_s->conf_start callback. + * + ****************************************************************************/ + +int mac802154_req_start(MACHANDLE mac, uint16_t panid, int channel, + uint8_t bo, uint8_t fo, bool coord, bool batext, + bool realign); + +/**************************************************************************** + * Name: mac802154_req_sync + * + * Description: + * The MLME-SYNC.request primitive requests to synchronize with the + * coordinator by acquiring and, if specified, tracking its beacons. + * Confirmation is returned via the + * struct ieee802154_maccb_s->int_commstatus callback. TOCHECK. + * + ****************************************************************************/ + +int mac802154_req_sync(MACHANDLE mac, int channel, bool track); + +/**************************************************************************** + * Name: mac802154_req_poll + * + * Description: + * The MLME-POLL.request primitive prompts the device to request data from the + * coordinator. Confirmation is returned via the + * struct ieee802154_maccb_s->conf_poll callback, followed by a + * struct ieee802154_maccb_s->ind_data callback. + * + ****************************************************************************/ + +int mac802154_req_poll(MACHANDLE mac, FAR uint8_t *coordaddr); + +/**************************************************************************** + * Name: mac802154_rsp_associate + * + * Description: + * The MLME-ASSOCIATE.response primitive is used to initiate a response to an + * MLME-ASSOCIATE.indication primitive. + * + ****************************************************************************/ + +int mac802154_rsp_associate(MACHANDLE mac, uint8_t eadr, uint16_t saddr, + int status); + +/**************************************************************************** + * Name: mac802154_rsp_orphan + * + * Description: + * The MLME-ORPHAN.response primitive allows the next higher layer of a + * coordinator to respond to the MLME-ORPHAN.indication primitive. + * + ****************************************************************************/ + +int mac802154_rsp_orphan(MACHANDLE mac, FAR uint8_t *orphanaddr, + uint16_t saddr, bool associated); #undef EXTERN #ifdef __cplusplus diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index a1bf265534..693e2db771 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -55,13 +55,13 @@ * Private Types ****************************************************************************/ -/* The privmac structure is an extension of the public ieee802154_mac_s type. - * It contains storage for the IEEE802.15.4 MIB attributes. +/* The privmac structure holds the internal state of the MAC and is the + * underlying represention of the opaque MACHANDLE. It contains storage for + * the IEEE802.15.4 MIB attributes. */ struct ieee802154_privmac_s { - struct ieee802154_mac_s pubmac; /* This MUST be the first member */ FAR struct ieee802154_radio_s *radio; /* Contained IEEE802.15.4 radio dev */ FAR const struct ieee802154_maccb_s *cb; /* Contained MAC callbacks */ @@ -104,75 +104,6 @@ struct ieee802154_privmac_s #endif }; -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/* MAC Data Service (MCPS) functions */ - -static int mac802154_req_data(FAR struct ieee802154_mac_s *mac, - FAR struct ieee802154_data_req_s *req); -static int mac802154_req_purge(FAR struct ieee802154_mac_s *mac, - uint8_t handle); - -/* MAC Sublayer Management Entity (MLME) functions */ - -static int mac802154_req_associate(FAR struct ieee802154_mac_s *mac, - FAR struct ieee802154_assoc_req_s *req); -static int mac802154_req_disassociate(FAR struct ieee802154_mac_s *mac, - FAR struct ieee802154_disassoc_req_s *req); -static int mac802154_req_get(FAR struct ieee802154_mac_s *mac, - enum ieee802154_pib_attr_e attr); -static int mac802154_req_gts(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *characteristics); -static int mac802154_req_reset(FAR struct ieee802154_mac_s *mac, - bool setdefaults); -static int mac802154_req_rxenable(FAR struct ieee802154_mac_s *mac, - bool deferrable, int ontime, int duration); -static int mac802154_req_scan(FAR struct ieee802154_mac_s *mac, - uint8_t type, uint32_t channels, int duration); -static int mac802154_req_set(FAR struct ieee802154_mac_s *mac, - int attribute, FAR uint8_t *value, int valuelen); -static int mac802154_req_start(FAR struct ieee802154_mac_s *mac, - uint16_t panid, int channel, uint8_t bo, uint8_t fo, - bool coord, bool batext, bool realign); -static int mac802154_req_sync(FAR struct ieee802154_mac_s *mac, - int channel, bool track); -static int mac802154_req_poll(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *coordaddr); -static int mac802154_rsp_associate(FAR struct ieee802154_mac_s *mac, - uint8_t eadr, uint16_t saddr, int status); -static int mac802154_rsp_orphan(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *orphanaddr, uint16_t saddr, bool associated); - -static int mac802154_bind(FAR struct ieee802154_mac_s *mac, - FAR struct ieee802154_maccb_s *cb); -static int mac802154_ioctl(FAR struct ieee802154_mac_s *mac, int cmd, - unsigned long arg); - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -static const struct ieee802154_macops_s mac802154ops = -{ - .req_data = mac802154_req_data, - .req_purge = mac802154_req_purge, - .req_associate = mac802154_req_associate, - .req_disassociate = mac802154_req_disassociate, - .req_get = mac802154_req_get, - .req_gts = mac802154_req_gts, - .req_reset = mac802154_req_reset, - .req_rxenable = mac802154_req_rxenable, - .req_scan = mac802154_req_scan, - .req_set = mac802154_req_set, - .req_start = mac802154_req_start, - .req_sync = mac802154_req_sync, - .req_poll = mac802154_req_poll, - .rsp_associate = mac802154_rsp_associate, - .rsp_orphan = mac802154_rsp_orphan, -}; - /**************************************************************************** * Private Functions ****************************************************************************/ @@ -241,11 +172,125 @@ static int mac802154_applymib(FAR struct ieee802154_privmac_s *priv) } /**************************************************************************** - * API Functions + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: mac802154_create + * + * Description: + * Create a 802.15.4 MAC device from a 802.15.4 compatible radio device. + * + * The returned MAC structure should be passed to either the next highest + * layer in the network stack, or registered with a mac802154dev character + * or network drivers. In any of these scenarios, the next highest layer + * should register a set of callbacks with the MAC layer by setting the + * mac->cbs member. + * + * NOTE: This API does not create any device accessible to userspace. If you + * want to call these APIs from userspace, you have to wrap your mac in a + * character device via mac802154_device.c. + * + * Input Parameters: + * radiodev - an instance of an IEEE 802.15.4 radio + * + * Returned Value: + * An opaque reference to the MAC state data. + * + ****************************************************************************/ + +MACHANDLE mac802154_create(FAR struct ieee802154_radio_s *radiodev) +{ + FAR struct ieee802154_privmac_s *mac; + + /* Allocate object */ + + mac = (FAR struct ieee802154_privmac_s *) + kmm_zalloc(sizeof(struct ieee802154_privmac_s)); + + if (mac == NULL) + { + return NULL; + } + + /* Initialize fields */ + + mac->radio = radiodev; + + mac802154_defaultmib(mac); + mac802154_applymib(mac); + + return (MACHANDLE)mac; +} + +/**************************************************************************** + * Name: mac802154_bind + * + * Description: + * Bind the MAC callback table to the MAC state. + * + * Parameters: + * mac - Reference to the MAC driver state structure + * cb - MAC callback operations + * + * Returned Value: + * OK on success; Negated errno on failure. + * ****************************************************************************/ +int mac802154_bind(MACHANDLE mac, FAR const struct ieee802154_maccb_s *cb) +{ + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; + + priv->cb = cb; + return OK; +} + /**************************************************************************** - * Name: mac802154_reqdata + * Name: mac802154_ioctl + * + * Description: + * Handle MAC and radio IOCTL commands directed to the MAC. + * + * Parameters: + * mac - Reference to the MAC driver state structure + * cmd - The IOCTL command + * arg - The argument for the IOCTL command + * + * Returned Value: + * OK on success; Negated errno on failure. + * + ****************************************************************************/ + +int mac802154_ioctl(MACHANDLE mac, int cmd, unsigned long arg) +{ + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; + int ret = -EINVAL; + + /* Check for IOCTLs aimed at the IEEE802.15.4 MAC layer */ + + if (_MAC802154IOCVALID(cmd)) + { + /* Handle the MAC IOCTL command */ +#warning Missing logic + } + + /* No, other IOCTLs must be aimed at the IEEE802.15.4 radio layer */ + + else + { + ret = priv->radio->ioctl(priv->radio, cmd, arg); + } +} + +/**************************************************************************** + * MAC Interface Operations + ****************************************************************************/ + +/**************************************************************************** + * Name: mac802154_req_data * * Description: * The MCPS-DATA.request primitive requests the transfer of a data SPDU @@ -255,15 +300,14 @@ static int mac802154_applymib(FAR struct ieee802154_privmac_s *priv) * ****************************************************************************/ -static int mac802154_req_data(FAR struct ieee802154_mac_s *mac, - FAR struct ieee802154_data_req_s *req) +int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } /**************************************************************************** - * Name: mac802154_reqpurge + * Name: mac802154_req_purge * * Description: * The MCPS-PURGE.request primitive allows the next higher layer to purge an @@ -272,8 +316,7 @@ static int mac802154_req_data(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -static int mac802154_req_purge(FAR struct ieee802154_mac_s *mac, - uint8_t handle) +int mac802154_req_purge(MACHANDLE mac, uint8_t handle) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; @@ -289,10 +332,10 @@ static int mac802154_req_purge(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -static int mac802154_req_associate(FAR struct ieee802154_mac_s *mac, - FAR struct ieee802154_assoc_req_s *req) +int mac802154_req_associate(MACHANDLE mac + FAR struct ieee802154_assoc_req_s *req) { - FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *)mac; + FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } @@ -308,8 +351,8 @@ static int mac802154_req_associate(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -static int mac802154_req_disassociate(FAR struct ieee802154_mac_s *mac, - FAR struct ieee802154_disassoc_req_s *req) +int mac802154_req_disassociate(MACHANDLE mac, + FAR struct ieee802154_disassoc_req_s *req) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; @@ -325,8 +368,7 @@ static int mac802154_req_disassociate(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -static int mac802154_req_get(FAR struct ieee802154_mac_s *mac, - enum ieee802154_pib_attr_e attr) +int mac802154_req_get(MACHANDLE mac, enum ieee802154_pib_attr_e attr) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; @@ -343,8 +385,7 @@ static int mac802154_req_get(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -static int mac802154_req_gts(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *characteristics) +int mac802154_req_gts(MACHANDLE mac, FAR uint8_t *characteristics) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; @@ -360,8 +401,7 @@ static int mac802154_req_gts(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -static int mac802154_req_reset(FAR struct ieee802154_mac_s *mac, - bool setdefaults) +int mac802154_req_reset(MACHANDLE mac, bool setdefaults) { FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; return -ENOTTY; @@ -378,8 +418,8 @@ static int mac802154_req_reset(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -static int mac802154_req_rxenable(FAR struct ieee802154_mac_s *mac, - bool deferrable, int ontime, int duration) +int mac802154_req_rxenable(MACHANDLE mac, bool deferrable, int ontime, + int duration) { FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; @@ -400,8 +440,8 @@ static int mac802154_req_rxenable(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -static int mac802154_req_scan(FAR struct ieee802154_mac_s *mac, - uint8_t type, uint32_t channels, int duration) +int mac802154_req_scan(MACHANDLE mac, uint8_t type, uint32_t channels, + int duration) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; @@ -417,8 +457,8 @@ static int mac802154_req_scan(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -static int mac802154_req_set(FAR struct ieee802154_mac_s *mac, - int attribute, FAR uint8_t *value, int valuelen) +int mac802154_req_set(MACHANDLE mac, int attribute, FAR uint8_t *value, + int valuelen) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; @@ -434,10 +474,9 @@ static int mac802154_req_set(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -static int mac802154_req_start(FAR struct ieee802154_mac_s *mac, - uint16_t panid, int channel, uint8_t bo, - uint8_t fo, bool coord, bool batext, - bool realign) +int mac802154_req_start(MACHANDLE mac, uint16_t panid, int channel, + uint8_t bo, uint8_t fo, bool coord, bool batext, + bool realign) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; @@ -454,8 +493,7 @@ static int mac802154_req_start(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -static int mac802154_req_sync(FAR struct ieee802154_mac_s *mac, - int channel, bool track) +int mac802154_req_sync(MACHANDLE mac, int channel, bool track) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; @@ -472,8 +510,7 @@ static int mac802154_req_sync(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -static int mac802154_req_poll(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *coordaddr) +int mac802154_req_poll(MACHANDLE mac, FAR uint8_t *coordaddr) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; @@ -488,8 +525,8 @@ static int mac802154_req_poll(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -static int mac802154_rsp_associate(FAR struct ieee802154_mac_s *mac, - uint8_t eadr, uint16_t saddr, int status) +int mac802154_rsp_associate(MACHANDLE mac, uint8_t eadr, uint16_t saddr, + int status) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; @@ -504,131 +541,10 @@ static int mac802154_rsp_associate(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -static int mac802154_rsp_orphan(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *orphanaddr, uint16_t saddr, - bool associated) +int mac802154_rsp_orphan(MACHANDLE mac, FAR uint8_t *orphanaddr, + uint16_t saddr, bool associated) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } - -/**************************************************************************** - * Name: mac802154_bind - * - * Description: - * Bind the MAC callback table to the MAC state. - * - * Parameters: - * mac - Reference to the MAC driver state structure - * cb - MAC callback operations - * - * Returned Value: - * OK on success; Negated errno on failure. - * - ****************************************************************************/ - -static int mac802154_bind(FAR struct ieee802154_mac_s *mac, - FAR const struct ieee802154_maccb_s *cb) -{ - FAR struct ieee802154_privmac_s *priv = - (FAR struct ieee802154_privmac_s *)mac; - - priv->cb = cb; - return OK; -} - -/**************************************************************************** - * Name: mac802154_ioctl - * - * Description: - * Handle MAC and radio IOCTL commands directed to the MAC. - * - * Parameters: - * mac - Reference to the MAC driver state structure - * cmd - The IOCTL command - * arg - The argument for the IOCTL command - * - * Returned Value: - * OK on success; Negated errno on failure. - * - ****************************************************************************/ - -static int mac802154_ioctl(FAR struct ieee802154_mac_s *mac, int cmd, - unsigned long arg) -{ - FAR struct ieee802154_privmac_s *priv = - (FAR struct ieee802154_privmac_s *)mac; - int ret = -EINVAL; - - /* Check for IOCTLs aimed at the IEEE802.15.4 MAC layer */ - - if (_MAC802154IOCVALID(cmd)) - { - /* Handle the MAC IOCTL command */ -#warning Missing logic - } - - /* No, other IOCTLs must be aimed at the IEEE802.15.4 radio layer */ - - else - { - ret = priv->radio->ioctl(priv->radio, cmd, arg); - } -} -#endif - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: mac802154_create - * - * Description: - * Create a 802.15.4 MAC device from a 802.15.4 compatible radio device. - * - * The returned MAC structure should be passed to either the next highest - * layer in the network stack, or registered with a mac802154dev character - * or network drivers. In any of these scenarios, the next highest layer - * should register a set of callbacks with the MAC layer by setting the - * mac->cbs member. - * - * NOTE: This API does not create any device accessible to userspace. If you - * want to call these APIs from userspace, you have to wrap your mac in a - * character device via mac802154_device.c. - * - * Input Parameters: - * radiodev - an instance of an IEEE 802.15.4 radio - * - * Returned Value: - * A MAC structure that has pointers to MAC operations - * and responses. - * - ****************************************************************************/ - -FAR struct ieee802154_mac_s * - mac802154_create(FAR struct ieee802154_radio_s *radiodev) -{ - FAR struct ieee802154_privmac_s *mac; - - /* Allocate object */ - - mac = (FAR struct ieee802154_privmac_s *) - kmm_zalloc(sizeof(struct ieee802154_privmac_s)); - - if (mac == NULL) - { - return NULL; - } - - /* Initialize fields */ - - mac->radio = radiodev; - mac->pubmac.ops = mac802154ops; - - mac802154_defaultmib(mac); - mac802154_applymib(mac); - - return &mac->pubmac; -} diff --git a/wireless/ieee802154/mac802154_device.c b/wireless/ieee802154/mac802154_device.c index 83e33f8cf3..fde4cab707 100644 --- a/wireless/ieee802154/mac802154_device.c +++ b/wireless/ieee802154/mac802154_device.c @@ -66,15 +66,14 @@ struct mac802154_devwrapper_s { - FAR struct ieee802154_mac_s *md_mac; /* Saved binding to the mac layer */ - sem_t md_exclsem; /* Exclusive device access */ + MACHANDLE md_mac; /* Saved binding to the mac layer */ + sem_t md_exclsem; /* Exclusive device access */ /* The following is a singly linked list of open references to the * MAC device. */ FAR struct mac802154_open_s *md_open; - FAR struct mac802154dev_dwait_s *md_dwait; }; @@ -452,7 +451,7 @@ static int mac802154dev_ioctl(FAR struct file *filep, int cmd, { FAR struct inode *inode; FAR struct mac802154_devwrapper_s *dev; - FAR struct ieee802154_mac_s *mac; + MACHANDLE mac; int ret; DEBUGASSERT(filep != NULL && filep->f_priv != NULL && @@ -484,8 +483,8 @@ static int mac802154dev_ioctl(FAR struct file *filep, int cmd, return ret; } -void mac802154dev_conf_data(FAR struct ieee802154_mac_s *mac, - FAR struct ieee802154_data_conf_s *conf) +void mac802154dev_conf_data(MACHANDLE mac, + FAR struct ieee802154_data_conf_s *conf) { FAR struct mac802154_devwrapper_s *dev; FAR struct mac802154dev_dwait_s *curr; @@ -537,7 +536,7 @@ void mac802154dev_conf_data(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -int mac802154dev_register(FAR struct ieee802154_mac_s *mac, int minor) +int mac802154dev_register(MACHANDLE mac, int minor) { FAR struct mac802154_devwrapper_s *dev; char devname[DEVNAME_FMTLEN]; diff --git a/wireless/ieee802154/mac802154_netdev.c b/wireless/ieee802154/mac802154_netdev.c index 6dd798f24b..616d57adfd 100644 --- a/wireless/ieee802154/mac802154_netdev.c +++ b/wireless/ieee802154/mac802154_netdev.c @@ -111,25 +111,25 @@ /* This is our private version of the MAC callback stucture */ -struct mac802154_callback_s +struct macnet_callback_s { /* This holds the information visible to the MAC layer */ struct ieee802154_maccb_s mc_cb; /* Interface understood by the MAC layer */ - FAR struct mac802154_driver_s *mc_priv; /* Our priv data */ + FAR struct macnet_driver_s *mc_priv; /* Our priv data */ }; -/* The mac802154_driver_s encapsulates all state information for a single +/* The macnet_driver_s encapsulates all state information for a single * IEEE802.15.4 MAC interface. */ -struct mac802154_driver_s +struct macnet_driver_s { /* This holds the information visible to the NuttX network */ - struct ieee802154_driver_s md_dev; /* Interface understood by the network */ - FAR struct ieee802154_mac_s *md_mac; /* Contained MAC interface */ - struct mac802154_callback_s md_cb; /* Callback information */ + struct ieee802154_driver_s md_dev; /* Interface understood by the network */ + struct macnet_callback_s md_cb; /* Callback information */ + MACHANDLE md_mac; /* Contained MAC interface */ /* For internal use by this driver */ @@ -140,20 +140,6 @@ struct mac802154_driver_s struct work_s md_pollwork; /* For deferring poll work to the work queue */ }; -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/* A single packet buffer per device is used here. There might be multiple - * packet buffers in a more complex, pipelined design. - */ - -static uint8_t g_pktbuf[MAX_NET_DEV_MTU + CONFIG_NET_GUARDSIZE]; - -/* Driver state structure */ - -static struct mac802154_driver_s g_skel[CONFIG_IEEE802154_NETDEV_NINTERFACES]; - /**************************************************************************** * Private Function Prototypes ****************************************************************************/ @@ -161,93 +147,84 @@ static struct mac802154_driver_s g_skel[CONFIG_IEEE802154_NETDEV_NINTERFACES]; /* IEE802.15.4 MAC callback functions ***************************************/ /* Asynchronous confirmations to requests */ -static void mac802154_conf_data(FAR struct ieee802154_mac_s *mac, +static void macnet_conf_data(MACHANDLE mac, FAR struct ieee802154_data_conf_s *conf); -static void mac802154_conf_purge(FAR struct ieee802154_mac_s *mac, - uint8_t handle, int status); -static void mac802154_conf_associate(FAR struct ieee802154_mac_s *mac, - uint16_t saddr, int status); -static void mac802154_conf_disassociate(FAR struct ieee802154_mac_s *mac, -static void mac802154_conf_get(FAR struct ieee802154_mac_s *mac, int status, - int attribute, FAR uint8_t *value, int valuelen); -static void mac802154_conf_gts(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *characteristics, int status); -static void mac802154_conf_reset(FAR struct ieee802154_mac_s *mac, - int status); -static void mac802154_conf_rxenable(FAR struct ieee802154_mac_s *mac, - int status); -static void mac802154_conf_scan(FAR struct ieee802154_mac_s *mac, - int status, uint8_t type, uint32_t unscanned, int rsltsize, - FAR uint8_t *edlist, FAR uint8_t *pandescs); -static void mac802154_conf_set(FAR struct ieee802154_mac_s *mac, int status, - int attribute); -static void mac802154_conf_start(FAR struct ieee802154_mac_s *mac, - int status); -static void mac802154_conf_poll(FAR struct ieee802154_mac_s *mac, +static void macnet_conf_purge(MACHANDLE mac, uint8_t handle, int status); +static void macnet_conf_associate(MACHANDLE mac, uint16_t saddr, int status); +static void macnet_conf_disassociate(MACHANDLE mac, int status); +static void macnet_conf_get(MACHANDLE mac, int status, int attribute, + FAR uint8_t *value, int valuelen); +static void macnet_conf_gts(MACHANDLE mac, FAR uint8_t *characteristics, int status); +static void macnet_conf_reset(MACHANDLE mac, int status); +static void macnet_conf_rxenable(MACHANDLE mac, int status); +static void macnet_conf_scan(MACHANDLE mac, int status, uint8_t type, + uint32_t unscanned, int rsltsize, FAR uint8_t *edlist, + FAR uint8_t *pandescs); +static void macnet_conf_set(MACHANDLE mac, int status, int attribute); +static void macnet_conf_start(MACHANDLE mac, int status); +static void macnet_conf_poll(MACHANDLE mac, int status); /* Asynchronous event indications, replied to synchronously with responses */ -static void mac802154_ind_data(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *buf, int len); -static void mac802154_ind_associate(FAR struct ieee802154_mac_s *mac, - uint16_t clipanid, FAR uint8_t *clieaddr); -static void mac802154_ind_disassociate(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *eadr, uint8_t reason); -static void mac802154_ind_beaconnotify(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *bsn, FAR struct ieee802154_pan_desc_s *pandesc, - FAR uint8_t *sdu, int sdulen); -static void mac802154_ind_gts(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *devaddr, FAR uint8_t *characteristics); -static void mac802154_ind_orphan(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *orphanaddr); -static void mac802154_ind_commstatus(FAR struct ieee802154_mac_s *mac, - uint16_t panid, FAR uint8_t *src, FAR uint8_t *dst, - int status); -static void mac802154_ind_syncloss(FAR struct ieee802154_mac_s *mac, - int reason); +static void macnet_ind_data(MACHANDLE mac, FAR uint8_t *buf, int len); +static void macnet_ind_associate(MACHANDLE mac, uint16_t clipanid, + FAR uint8_t *clieaddr); +static void macnet_ind_disassociate(MACHANDLE mac, FAR uint8_t *eadr, + uint8_t reason); +static void macnet_ind_beaconnotify(MACHANDLE mac, FAR uint8_t *bsn, + FAR struct ieee802154_pan_desc_s *pandesc, FAR uint8_t *sdu, + int sdulen); +static void macnet_ind_gts(MACHANDLE mac, FAR uint8_t *devaddr, + FAR uint8_t *characteristics); +static void macnet_ind_orphan(MACHANDLE mac, FAR uint8_t *orphanaddr); +static void macnet_ind_commstatus(MACHANDLE mac, uint16_t panid, + FAR uint8_t *src, FAR uint8_t *dst, int status); +static void macnet_ind_syncloss(MACHANDLE mac, int reason); /* Network interface support ************************************************/ /* Common TX logic */ -static int mac802154_transmit(FAR struct mac802154_driver_s *priv); -static int mac802154_txpoll(FAR struct net_driver_s *dev); +static int macnet_transmit(FAR struct macnet_driver_s *priv); +static int macnet_txpoll(FAR struct net_driver_s *dev); /* Frame transfer */ -static void mac802154_receive(FAR struct mac802154_driver_s *priv); -static void mac802154_txdone(FAR struct mac802154_driver_s *priv); +static void macnet_receive(FAR struct macnet_driver_s *priv); +static void macnet_txdone(FAR struct macnet_driver_s *priv); -static void mac802154_transfer_work(FAR void *arg); -static int mac802154_transfer(int irq, FAR void *context, FAR void *arg); +static void macnet_transfer_work(FAR void *arg); +static int macnet_transfer(int irq, FAR void *context, FAR void *arg); /* Watchdog timer expirations */ -static void mac802154_txtimeout_work(FAR void *arg); -static void mac802154_txtimeout_expiry(int argc, wdparm_t arg, ...); +static void macnet_txtimeout_work(FAR void *arg); +static void macnet_txtimeout_expiry(int argc, wdparm_t arg, ...); -static void mac802154_poll_work(FAR void *arg); -static void mac802154_poll_expiry(int argc, wdparm_t arg, ...); +static void macnet_poll_work(FAR void *arg); +static void macnet_poll_expiry(int argc, wdparm_t arg, ...); /* NuttX callback functions */ -static int mac802154_ifup(FAR struct net_driver_s *dev); -static int mac802154_ifdown(FAR struct net_driver_s *dev); +static int macnet_ifup(FAR struct net_driver_s *dev); +static int macnet_ifdown(FAR struct net_driver_s *dev); -static void mac802154_txavail_work(FAR void *arg); -static int mac802154_txavail(FAR struct net_driver_s *dev); +static void macnet_txavail_work(FAR void *arg); +static int macnet_txavail(FAR struct net_driver_s *dev); #if defined(CONFIG_NET_IGMP) || defined(CONFIG_NET_ICMPv6) -static int mac802154_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac); +static int macnet_addmac(FAR struct net_driver_s *dev, + FAR const uint8_t *mac); #ifdef CONFIG_NET_IGMP -static int mac802154_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac); +static int macnet_rmmac(FAR struct net_driver_s *dev, + FAR const uint8_t *mac); #endif #ifdef CONFIG_NET_ICMPv6 -static void mac802154_ipv6multicast(FAR struct mac802154_driver_s *priv); +static void macnet_ipv6multicast(FAR struct macnet_driver_s *priv); #endif #endif #ifdef CONFIG_NETDEV_IOCTL -static int mac802154_ioctl(FAR struct net_driver_s *dev, int cmd, long arg); +static int macnet_ioctl(FAR struct net_driver_s *dev, int cmd, long arg); #endif /**************************************************************************** @@ -255,367 +232,352 @@ static int mac802154_ioctl(FAR struct net_driver_s *dev, int cmd, long arg); ****************************************************************************/ /**************************************************************************** - * Name: mac802154_conf_data + * Name: macnet_conf_data * * Description: * Data frame was received by remote device * ****************************************************************************/ -static void mac802154_conf_data(FAR struct ieee802154_mac_s *mac, - FAR struct ieee802154_data_conf_s *conf) +static void macnet_conf_data(MACHANDLE mac, + FAR struct ieee802154_data_conf_s *conf) { - FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; - FAR struct mac802154_driver_s *priv; + FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac; + FAR struct macnet_driver_s *priv; DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); priv = cb->mc_priv; } /**************************************************************************** - * Name: mac802154_conf_purge + * Name: macnet_conf_purge * * Description: * Data frame was purged * ****************************************************************************/ -static void mac802154_conf_purge(FAR struct ieee802154_mac_s *mac, - uint8_t handle, int status) +static void macnet_conf_purge(MACHANDLE mac, uint8_t handle, int status) { - FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; - FAR struct mac802154_driver_s *priv; + FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac; + FAR struct macnet_driver_s *priv; DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); priv = cb->mc_priv; } /**************************************************************************** - * Name: mac802154_conf_associate + * Name: macnet_conf_associate * * Description: * Association request completed * ****************************************************************************/ -static void mac802154_conf_associate(FAR struct ieee802154_mac_s *mac, - uint16_t saddr, int status) +static void macnet_conf_associate(MACHANDLE mac, uint16_t saddr, int status) { - FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; - FAR struct mac802154_driver_s *priv; + FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac; + FAR struct macnet_driver_s *priv; DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); priv = cb->mc_priv; } /**************************************************************************** - * Name: mac802154_conf_disassociate + * Name: macnet_conf_disassociate * * Description: * Disassociation request completed * ****************************************************************************/ -static void mac802154_conf_disassociate(FAR struct ieee802154_mac_s *mac, +static void macnet_conf_disassociate(MACHANDLE mac, int status) { - FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; - FAR struct mac802154_driver_s *priv; + FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac; + FAR struct macnet_driver_s *priv; DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); priv = cb->mc_priv; } /**************************************************************************** - * Name: mac802154_conf_get + * Name: macnet_conf_get * * Description: * PIvoata returned * ****************************************************************************/ -static void mac802154_conf_get(FAR struct ieee802154_mac_s *mac, int status, - int attribute, FAR uint8_t *value, - int valuelen) +static void macnet_conf_get(MACHANDLE mac, int status, int attribute, + FAR uint8_t *value, int valuelen) { - FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; - FAR struct mac802154_driver_s *priv; + FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac; + FAR struct macnet_driver_s *priv; DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); priv = cb->mc_priv; } /**************************************************************************** - * Name: mac802154_conf_gts + * Name: macnet_conf_gts * * Description: * GTvoanagement completed * ****************************************************************************/ -static void mac802154_conf_gts(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *characteristics, int status) +static void macnet_conf_gts(MACHANDLE mac, FAR uint8_t *characteristics, + int status) { - FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; - FAR struct mac802154_driver_s *priv; + FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac; + FAR struct macnet_driver_s *priv; DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); priv = cb->mc_priv; } /**************************************************************************** - * Name: mac802154_conf_reset + * Name: macnet_conf_reset * * Description: * MAveset completed * ****************************************************************************/ -static void mac802154_conf_reset(FAR struct ieee802154_mac_s *mac, - int status) +static void macnet_conf_reset(MACHANDLE mac, int status) { - FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; - FAR struct mac802154_driver_s *priv; + FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac; + FAR struct macnet_driver_s *priv; DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); priv = cb->mc_priv; } /**************************************************************************** - * Name: mac802154_conf_rxenable + * Name: macnet_conf_rxenable * * Description: * ****************************************************************************/ -static void mac802154_conf_rxenable(FAR struct ieee802154_mac_s *mac, - int status) +static void macnet_conf_rxenable(MACHANDLE mac, int status) { - FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; - FAR struct mac802154_driver_s *priv; + FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac; + FAR struct macnet_driver_s *priv; DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); priv = cb->mc_priv; } /**************************************************************************** - * Name: mac802154_conf_scan + * Name: macnet_conf_scan * * Description: * ****************************************************************************/ -static void mac802154_conf_scan(FAR struct ieee802154_mac_s *mac, - int status, uint8_t type, - uint32_t unscanned, int rsltsize, - FAR uint8_t *edlist, FAR uint8_t *pandescs) +static void macnet_conf_scan(MACHANDLE mac, int status, uint8_t type, + uint32_t unscanned, int rsltsize, + FAR uint8_t *edlist, FAR uint8_t *pandescs) { - FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; - FAR struct mac802154_driver_s *priv; + FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac; + FAR struct macnet_driver_s *priv; DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); priv = cb->mc_priv; } /**************************************************************************** - * Name: mac802154_conf_set + * Name: macnet_conf_set * * Description: * ****************************************************************************/ -static void mac802154_conf_set(FAR struct ieee802154_mac_s *mac, int status, - int attribute) +static void macnet_conf_set(MACHANDLE mac, int status, int attribute) { - FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; - FAR struct mac802154_driver_s *priv; + FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac; + FAR struct macnet_driver_s *priv; DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); priv = cb->mc_priv; } /**************************************************************************** - * Name: mac802154_conf_start + * Name: macnet_conf_start * * Description: * ****************************************************************************/ -static void mac802154_conf_start(FAR struct ieee802154_mac_s *mac, - int status) +static void macnet_conf_start(MACHANDLE mac, int status) { - FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; - FAR struct mac802154_driver_s *priv; + FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac; + FAR struct macnet_driver_s *priv; DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); priv = cb->mc_priv; } /**************************************************************************** - * Name: mac802154_conf_poll + * Name: macnet_conf_poll * * Description: * ****************************************************************************/ -static void mac802154_conf_poll(FAR struct ieee802154_mac_s *mac, - int status) +static void macnet_conf_poll(MACHANDLE mac, int status) { - FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; - FAR struct mac802154_driver_s *priv; + FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac; + FAR struct macnet_driver_s *priv; DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); priv = cb->mc_priv; } /**************************************************************************** - * Name: mac802154_ind_data + * Name: macnet_ind_data * * Description: * Data frame received * ****************************************************************************/ -static void mac802154_ind_data(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *buf, int len) +static void macnet_ind_data(MACHANDLE mac, FAR uint8_t *buf, int len) { - FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; - FAR struct mac802154_driver_s *priv; + FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac; + FAR struct macnet_driver_s *priv; DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); priv = cb->mc_priv; } /**************************************************************************** - * Name: mac802154_ind_associate + * Name: macnet_ind_associate * * Description: * Association request received * ****************************************************************************/ -static void mac802154_ind_associate(FAR struct ieee802154_mac_s *mac, - uint16_t clipanid, - FAR uint8_t *clieaddr) +static void macnet_ind_associate(MACHANDLE mac, uint16_t clipanid, + FAR uint8_t *clieaddr) { - FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; - FAR struct mac802154_driver_s *priv; + FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac; + FAR struct macnet_driver_s *priv; DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); priv = cb->mc_priv; } /**************************************************************************** - * Name: mac802154_ind_disassociate + * Name: macnet_ind_disassociate * * Description: * Disassociation request received * ****************************************************************************/ -static void mac802154_ind_disassociate(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *eadr, uint8_t reason) +static void macnet_ind_disassociate(MACHANDLE mac, FAR uint8_t *eadr, + uint8_t reason) { - FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; - FAR struct mac802154_driver_s *priv; + FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac; + FAR struct macnet_driver_s *priv; DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); priv = cb->mc_priv; } /**************************************************************************** - * Name: mac802154_ind_beaconnotify + * Name: macnet_ind_beaconnotify * * Description: * Beacon notification * ****************************************************************************/ -static void mac802154_ind_beaconnotify(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *bsn, - FAR struct ieee802154_pan_desc_s *pandesc, - FAR uint8_t *sdu, int sdulen) +static void macnet_ind_beaconnotify(MACHANDLE mac, FAR uint8_t *bsn, + FAR struct ieee802154_pan_desc_s *pandesc, + FAR uint8_t *sdu, int sdulen) { - FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; - FAR struct mac802154_driver_s *priv; + FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac; + FAR struct macnet_driver_s *priv; DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); priv = cb->mc_priv; } /**************************************************************************** - * Name: mac802154_ind_gts + * Name: macnet_ind_gts * * Description: * GTS management request received * ****************************************************************************/ -static void mac802154_ind_gts(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *devaddr, - FAR uint8_t *characteristics) +static void macnet_ind_gts(MACHANDLE mac, FAR uint8_t *devaddr, + FAR uint8_t *characteristics) { - FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; - FAR struct mac802154_driver_s *priv; + FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac; + FAR struct macnet_driver_s *priv; DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); priv = cb->mc_priv; } /**************************************************************************** - * Name: mac802154_ind_orphan + * Name: macnet_ind_orphan * * Description: * Orphan device detected * ****************************************************************************/ -static void mac802154_ind_orphan(FAR struct ieee802154_mac_s *mac, - FAR uint8_t *orphanaddr) +static void macnet_ind_orphan(MACHANDLE mac, FAR uint8_t *orphanaddr) { - FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; - FAR struct mac802154_driver_s *priv; + FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac; + FAR struct macnet_driver_s *priv; DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); priv = cb->mc_priv; } /**************************************************************************** - * Name: mac802154_ind_commstatus + * Name: macnet_ind_commstatus * * Description: * ****************************************************************************/ -static void mac802154_ind_commstatus(FAR struct ieee802154_mac_s *mac, - uint16_t panid, FAR uint8_t *src, - FAR uint8_t *dst, int status) +static void macnet_ind_commstatus(MACHANDLE mac, uint16_t panid, + FAR uint8_t *src, FAR uint8_t *dst, + int status) { - FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; - FAR struct mac802154_driver_s *priv; + FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac; + FAR struct macnet_driver_s *priv; DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); priv = cb->mc_priv; } /**************************************************************************** - * Name: mac802154_ind_syncloss + * Name: macnet_ind_syncloss * * Description: * ****************************************************************************/ -static void mac802154_ind_syncloss(FAR struct ieee802154_mac_s *mac, - int reason) +static void macnet_ind_syncloss(MACHANDLE mac, int reason) { - FAR struct mac802154_callback_s *cb = (FAR struct mac802154_callback_s *)mac; - FAR struct mac802154_driver_s *priv; + FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac; + FAR struct macnet_driver_s *priv; DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); priv = cb->mc_priv; } /**************************************************************************** - * Name: mac802154_transmit + * Name: macnet_transmit * * Description: * Start hardware transmission. Called either from the txdone interrupt @@ -633,7 +595,7 @@ static void mac802154_ind_syncloss(FAR struct ieee802154_mac_s *mac, * ****************************************************************************/ -static int mac802154_transmit(FAR struct mac802154_driver_s *priv) +static int macnet_transmit(FAR struct macnet_driver_s *priv) { /* Verify that the hardware is ready to send another packet. If we get * here, then we are committed to sending a packet; Higher level logic @@ -651,12 +613,12 @@ static int mac802154_transmit(FAR struct mac802154_driver_s *priv) /* Setup the TX timeout watchdog (perhaps restarting the timer) */ (void)wd_start(priv->md_txtimeout, skeleton_TXTIMEOUT, - mac802154_txtimeout_expiry, 1, (wdparm_t)priv); + macnet_txtimeout_expiry, 1, (wdparm_t)priv); return OK; } /**************************************************************************** - * Name: mac802154_txpoll + * Name: macnet_txpoll * * Description: * The transmitter is available, check if the network has any outgoing @@ -679,9 +641,9 @@ static int mac802154_transmit(FAR struct mac802154_driver_s *priv) * ****************************************************************************/ -static int mac802154_txpoll(FAR struct net_driver_s *dev) +static int macnet_txpoll(FAR struct net_driver_s *dev) { - FAR struct mac802154_driver_s *priv = (FAR struct mac802154_driver_s *)dev->d_private; + FAR struct macnet_driver_s *priv = (FAR struct macnet_driver_s *)dev->d_private; /* If the polling resulted in data that should be sent out, the field * i_framelist will set to a new, outgoing list of frames. @@ -691,7 +653,7 @@ static int mac802154_txpoll(FAR struct net_driver_s *dev) { /* And send the packet */ - mac802154_transmit(priv); + macnet_transmit(priv); } /* If zero is returned, the polling will continue until all connections have @@ -702,7 +664,7 @@ static int mac802154_txpoll(FAR struct net_driver_s *dev) } /**************************************************************************** - * Name: mac802154_receive + * Name: macnet_receive * * Description: * An interrupt was received indicating the availability of a new RX packet @@ -718,7 +680,7 @@ static int mac802154_txpoll(FAR struct net_driver_s *dev) * ****************************************************************************/ -static void mac802154_receive(FAR struct mac802154_driver_s *priv) +static void macnet_receive(FAR struct macnet_driver_s *priv) { FAR struct iob_s *iob; FAR struct iob_s *fptr; @@ -753,12 +715,12 @@ static void mac802154_receive(FAR struct mac802154_driver_s *priv) { /* And send the packet */ - mac802154_transmit(priv); + macnet_transmit(priv); } } /**************************************************************************** - * Name: mac802154_txdone + * Name: macnet_txdone * * Description: * An interrupt was received indicating that the last TX packet(s) is done @@ -774,7 +736,7 @@ static void mac802154_receive(FAR struct mac802154_driver_s *priv) * ****************************************************************************/ -static void mac802154_txdone(FAR struct mac802154_driver_s *priv) +static void macnet_txdone(FAR struct macnet_driver_s *priv) { int delay; @@ -794,11 +756,11 @@ static void mac802154_txdone(FAR struct mac802154_driver_s *priv) /* In any event, poll the network for new TX data */ - (void)devif_poll(&priv->md_dev, mac802154_txpoll); + (void)devif_poll(&priv->md_dev, macnet_txpoll); } /**************************************************************************** - * Name: mac802154_transfer_work + * Name: macnet_transfer_work * * Description: * Perform interrupt related work from the worker thread @@ -814,9 +776,9 @@ static void mac802154_txdone(FAR struct mac802154_driver_s *priv) * ****************************************************************************/ -static void mac802154_transfer_work(FAR void *arg) +static void macnet_transfer_work(FAR void *arg) { - FAR struct mac802154_driver_s *priv = (FAR struct mac802154_driver_s *)arg; + FAR struct macnet_driver_s *priv = (FAR struct macnet_driver_s *)arg; /* Lock the network and serialize driver operations if necessary. * NOTE: Serialization is only required in the case where the driver work @@ -832,16 +794,16 @@ static void mac802154_transfer_work(FAR void *arg) /* Handle interrupts according to status bit settings */ - /* Check if we received an incoming packet, if so, call mac802154_receive() */ + /* Check if we received an incoming packet, if so, call macnet_receive() */ - mac802154_receive(priv); + macnet_receive(priv); - /* Check if a packet transmission just completed. If so, call mac802154_txdone. + /* Check if a packet transmission just completed. If so, call macnet_txdone. * This may disable further Tx interrupts if there are no pending * transmissions. */ - mac802154_txdone(priv); + macnet_txdone(priv); net_unlock(); /* Re-enable Ethernet interrupts */ @@ -850,7 +812,7 @@ static void mac802154_transfer_work(FAR void *arg) } /**************************************************************************** - * Name: mac802154_transfer + * Name: macnet_transfer * * Description: * Hardware interrupt handler @@ -866,9 +828,9 @@ static void mac802154_transfer_work(FAR void *arg) * ****************************************************************************/ -static int mac802154_transfer(int irq, FAR void *context, FAR void *arg) +static int macnet_transfer(int irq, FAR void *context, FAR void *arg) { - FAR struct mac802154_driver_s *priv = &g_skel[0]; + FAR struct macnet_driver_s *priv = (FAR struct macnet_driver_s *)arg; /* Disable further Ethernet interrupts. Because Ethernet interrupts are * also disabled if the TX timeout event occurs, there can be no race @@ -890,12 +852,12 @@ static int mac802154_transfer(int irq, FAR void *context, FAR void *arg) /* Schedule to perform the interrupt processing on the worker thread. */ - work_queue(ETHWORK, &priv->md_irqwork, mac802154_transfer_work, priv, 0); + work_queue(ETHWORK, &priv->md_irqwork, macnet_transfer_work, priv, 0); return OK; } /**************************************************************************** - * Name: mac802154_txtimeout_work + * Name: macnet_txtimeout_work * * Description: * Perform TX timeout related work from the worker thread @@ -911,9 +873,9 @@ static int mac802154_transfer(int irq, FAR void *context, FAR void *arg) * ****************************************************************************/ -static void mac802154_txtimeout_work(FAR void *arg) +static void macnet_txtimeout_work(FAR void *arg) { - FAR struct mac802154_driver_s *priv = (FAR struct mac802154_driver_s *)arg; + FAR struct macnet_driver_s *priv = (FAR struct macnet_driver_s *)arg; /* Lock the network and serialize driver operations if necessary. * NOTE: Serialization is only required in the case where the driver work @@ -931,12 +893,12 @@ static void mac802154_txtimeout_work(FAR void *arg) /* Then poll the network for new XMIT data */ - (void)devif_poll(&priv->md_dev, mac802154_txpoll); + (void)devif_poll(&priv->md_dev, macnet_txpoll); net_unlock(); } /**************************************************************************** - * Name: mac802154_txtimeout_expiry + * Name: macnet_txtimeout_expiry * * Description: * Our TX watchdog timed out. Called from the timer interrupt handler. @@ -954,9 +916,9 @@ static void mac802154_txtimeout_work(FAR void *arg) * ****************************************************************************/ -static void mac802154_txtimeout_expiry(int argc, wdparm_t arg, ...) +static void macnet_txtimeout_expiry(int argc, wdparm_t arg, ...) { - FAR struct mac802154_driver_s *priv = (FAR struct mac802154_driver_s *)arg; + FAR struct macnet_driver_s *priv = (FAR struct macnet_driver_s *)arg; /* Disable further Ethernet interrupts. This will prevent some race * conditions with interrupt work. There is still a potential race @@ -967,11 +929,11 @@ static void mac802154_txtimeout_expiry(int argc, wdparm_t arg, ...) /* Schedule to perform the TX timeout processing on the worker thread. */ - work_queue(ETHWORK, &priv->md_irqwork, mac802154_txtimeout_work, priv, 0); + work_queue(ETHWORK, &priv->md_irqwork, macnet_txtimeout_work, priv, 0); } /**************************************************************************** - * Name: mac802154_poll_process + * Name: macnet_poll_process * * Description: * Perform the periodic poll. This may be called either from watchdog @@ -987,12 +949,12 @@ static void mac802154_txtimeout_expiry(int argc, wdparm_t arg, ...) * ****************************************************************************/ -static inline void mac802154_poll_process(FAR struct mac802154_driver_s *priv) +static inline void macnet_poll_process(FAR struct macnet_driver_s *priv) { } /**************************************************************************** - * Name: mac802154_poll_work + * Name: macnet_poll_work * * Description: * Perform periodic polling from the worker thread @@ -1008,9 +970,9 @@ static inline void mac802154_poll_process(FAR struct mac802154_driver_s *priv) * ****************************************************************************/ -static void mac802154_poll_work(FAR void *arg) +static void macnet_poll_work(FAR void *arg) { - FAR struct mac802154_driver_s *priv = (FAR struct mac802154_driver_s *)arg; + FAR struct macnet_driver_s *priv = (FAR struct macnet_driver_s *)arg; /* Lock the network and serialize driver operations if necessary. * NOTE: Serialization is only required in the case where the driver work @@ -1031,17 +993,17 @@ static void mac802154_poll_work(FAR void *arg) * progress, we will missing TCP time state updates? */ - (void)devif_timer(&priv->md_dev, mac802154_txpoll); + (void)devif_timer(&priv->md_dev, macnet_txpoll); /* Setup the watchdog poll timer again */ - (void)wd_start(priv->md_txpoll, skeleton_WDDELAY, mac802154_poll_expiry, 1, + (void)wd_start(priv->md_txpoll, skeleton_WDDELAY, macnet_poll_expiry, 1, (wdparm_t)priv); net_unlock(); } /**************************************************************************** - * Name: mac802154_poll_expiry + * Name: macnet_poll_expiry * * Description: * Periodic timer handler. Called from the timer interrupt handler. @@ -1058,17 +1020,17 @@ static void mac802154_poll_work(FAR void *arg) * ****************************************************************************/ -static void mac802154_poll_expiry(int argc, wdparm_t arg, ...) +static void macnet_poll_expiry(int argc, wdparm_t arg, ...) { - FAR struct mac802154_driver_s *priv = (FAR struct mac802154_driver_s *)arg; + FAR struct macnet_driver_s *priv = (FAR struct macnet_driver_s *)arg; /* Schedule to perform the interrupt processing on the worker thread. */ - work_queue(ETHWORK, &priv->md_pollwork, mac802154_poll_work, priv, 0); + work_queue(ETHWORK, &priv->md_pollwork, macnet_poll_work, priv, 0); } /**************************************************************************** - * Name: mac802154_ifup + * Name: macnet_ifup * * Description: * NuttX Callback: Bring up the Ethernet interface when an IP address is @@ -1084,9 +1046,9 @@ static void mac802154_poll_expiry(int argc, wdparm_t arg, ...) * ****************************************************************************/ -static int mac802154_ifup(FAR struct net_driver_s *dev) +static int macnet_ifup(FAR struct net_driver_s *dev) { - FAR struct mac802154_driver_s *priv = (FAR struct mac802154_driver_s *)dev->d_private; + FAR struct macnet_driver_s *priv = (FAR struct macnet_driver_s *)dev->d_private; #ifdef CONFIG_NET_IPv4 ninfo("Bringing up: %d.%d.%d.%d\n", @@ -1107,12 +1069,12 @@ static int mac802154_ifup(FAR struct net_driver_s *dev) #ifdef CONFIG_NET_ICMPv6 /* Set up IPv6 multicast address filtering */ - mac802154_ipv6multicast(priv); + macnet_ipv6multicast(priv); #endif /* Set and activate a timer process */ - (void)wd_start(priv->md_txpoll, skeleton_WDDELAY, mac802154_poll_expiry, 1, + (void)wd_start(priv->md_txpoll, skeleton_WDDELAY, macnet_poll_expiry, 1, (wdparm_t)priv); /* Enable the Ethernet interrupt */ @@ -1123,7 +1085,7 @@ static int mac802154_ifup(FAR struct net_driver_s *dev) } /**************************************************************************** - * Name: mac802154_ifdown + * Name: macnet_ifdown * * Description: * NuttX Callback: Stop the interface. @@ -1138,9 +1100,9 @@ static int mac802154_ifup(FAR struct net_driver_s *dev) * ****************************************************************************/ -static int mac802154_ifdown(FAR struct net_driver_s *dev) +static int macnet_ifdown(FAR struct net_driver_s *dev) { - FAR struct mac802154_driver_s *priv = (FAR struct mac802154_driver_s *)dev->d_private; + FAR struct macnet_driver_s *priv = (FAR struct macnet_driver_s *)dev->d_private; irqstate_t flags; /* Disable the Ethernet interrupt */ @@ -1154,7 +1116,7 @@ static int mac802154_ifdown(FAR struct net_driver_s *dev) wd_cancel(priv->md_txtimeout); /* Put the EMAC in its reset, non-operational state. This should be - * a known configuration that will guarantee the mac802154_ifup() always + * a known configuration that will guarantee the macnet_ifup() always * successfully brings the interface back up. */ @@ -1166,7 +1128,7 @@ static int mac802154_ifdown(FAR struct net_driver_s *dev) } /**************************************************************************** - * Name: mac802154_txavail_work + * Name: macnet_txavail_work * * Description: * Perform an out-of-cycle poll on the worker thread. @@ -1182,9 +1144,9 @@ static int mac802154_ifdown(FAR struct net_driver_s *dev) * ****************************************************************************/ -static void mac802154_txavail_work(FAR void *arg) +static void macnet_txavail_work(FAR void *arg) { - FAR struct mac802154_driver_s *priv = (FAR struct mac802154_driver_s *)arg; + FAR struct macnet_driver_s *priv = (FAR struct macnet_driver_s *)arg; /* Lock the network and serialize driver operations if necessary. * NOTE: Serialization is only required in the case where the driver work @@ -1202,14 +1164,14 @@ static void mac802154_txavail_work(FAR void *arg) /* If so, then poll the network for new XMIT data */ - (void)devif_poll(&priv->md_dev, mac802154_txpoll); + (void)devif_poll(&priv->md_dev, macnet_txpoll); } net_unlock(); } /**************************************************************************** - * Name: mac802154_txavail + * Name: macnet_txavail * * Description: * Driver callback invoked when new TX data is available. This is a @@ -1227,9 +1189,9 @@ static void mac802154_txavail_work(FAR void *arg) * ****************************************************************************/ -static int mac802154_txavail(FAR struct net_driver_s *dev) +static int macnet_txavail(FAR struct net_driver_s *dev) { - FAR struct mac802154_driver_s *priv = (FAR struct mac802154_driver_s *)dev->d_private; + FAR struct macnet_driver_s *priv = (FAR struct macnet_driver_s *)dev->d_private; /* Is our single work structure available? It may not be if there are * pending interrupt actions and we will have to ignore the Tx @@ -1240,14 +1202,14 @@ static int mac802154_txavail(FAR struct net_driver_s *dev) { /* Schedule to serialize the poll on the worker thread. */ - work_queue(ETHWORK, &priv->md_pollwork, mac802154_txavail_work, priv, 0); + work_queue(ETHWORK, &priv->md_pollwork, macnet_txavail_work, priv, 0); } return OK; } /**************************************************************************** - * Name: mac802154_addmac + * Name: macnet_addmac * * Description: * NuttX Callback: Add the specified MAC address to the hardware multicast @@ -1265,9 +1227,9 @@ static int mac802154_txavail(FAR struct net_driver_s *dev) ****************************************************************************/ #if defined(CONFIG_NET_IGMP) || defined(CONFIG_NET_ICMPv6) -static int mac802154_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) +static int macnet_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) { - FAR struct mac802154_driver_s *priv = (FAR struct mac802154_driver_s *)dev->d_private; + FAR struct macnet_driver_s *priv = (FAR struct macnet_driver_s *)dev->d_private; /* Add the MAC address to the hardware multicast routing table */ @@ -1276,7 +1238,7 @@ static int mac802154_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac #endif /**************************************************************************** - * Name: mac802154_rmmac + * Name: macnet_rmmac * * Description: * NuttX Callback: Remove the specified MAC address from the hardware multicast @@ -1294,9 +1256,9 @@ static int mac802154_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac ****************************************************************************/ #ifdef CONFIG_NET_IGMP -static int mac802154_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) +static int macnet_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) { - FAR struct mac802154_driver_s *priv = (FAR struct mac802154_driver_s *)dev->d_private; + FAR struct macnet_driver_s *priv = (FAR struct macnet_driver_s *)dev->d_private; /* Add the MAC address to the hardware multicast routing table */ @@ -1305,7 +1267,7 @@ static int mac802154_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) #endif /**************************************************************************** - * Name: mac802154_ipv6multicast + * Name: macnet_ipv6multicast * * Description: * Configure the IPv6 multicast MAC address. @@ -1321,7 +1283,7 @@ static int mac802154_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) ****************************************************************************/ #ifdef CONFIG_NET_ICMPv6 -static void mac802154_ipv6multicast(FAR struct mac802154_driver_s *priv) +static void macnet_ipv6multicast(FAR struct macnet_driver_s *priv) { FAR struct net_driver_s *dev; uint16_t tmp16; @@ -1354,7 +1316,7 @@ static void mac802154_ipv6multicast(FAR struct mac802154_driver_s *priv) ninfo("IPv6 Multicast: %02x:%02x:%02x:%02x:%02x:%02x\n", mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]); - (void)mac802154_addmac(dev, mac); + (void)macnet_addmac(dev, mac); #ifdef CONFIG_NET_ICMPv6_AUTOCONF /* Add the IPv6 all link-local nodes Ethernet address. This is the @@ -1362,7 +1324,7 @@ static void mac802154_ipv6multicast(FAR struct mac802154_driver_s *priv) * packets. */ - (void)mac802154_addmac(dev, g_ipv6_ethallnodes.ether_addr_octet); + (void)macnet_addmac(dev, g_ipv6_ethallnodes.ether_addr_octet); #endif /* CONFIG_NET_ICMPv6_AUTOCONF */ @@ -1372,14 +1334,14 @@ static void mac802154_ipv6multicast(FAR struct mac802154_driver_s *priv) * packets. */ - (void)mac802154_addmac(dev, g_ipv6_ethallrouters.ether_addr_octet); + (void)macnet_addmac(dev, g_ipv6_ethallrouters.ether_addr_octet); #endif /* CONFIG_NET_ICMPv6_ROUTER */ } #endif /* CONFIG_NET_ICMPv6 */ /**************************************************************************** - * Name: mac802154_ioctl + * Name: macnet_ioctl * * Description: * Handle network IOCTL commands directed to this device. @@ -1397,9 +1359,9 @@ static void mac802154_ipv6multicast(FAR struct mac802154_driver_s *priv) ****************************************************************************/ #ifdef CONFIG_NETDEV_IOCTL -static int mac802154_ioctl(FAR struct net_driver_s *dev, int cmd, long arg) +static int macnet_ioctl(FAR struct net_driver_s *dev, int cmd, long arg) { - FAR struct mac802154_driver_s *priv = (FAR struct mac802154_driver_s *)dev->d_private; + FAR struct macnet_driver_s *priv = (FAR struct macnet_driver_s *)dev->d_private; int ret = -EINVAL; /* Check for IOCTLs aimed at the IEEE802.15.4 MAC layer */ @@ -1461,9 +1423,9 @@ static int mac802154_ioctl(FAR struct net_driver_s *dev, int cmd, long arg) * ****************************************************************************/ -int mac802154netdev_register(FAR struct ieee802154_mac_s *mac); +int mac802154netdev_register(MACHANDLE mac) { - FAR struct mac802154_driver_s *priv; + FAR struct macnet_driver_s *priv; FAR struct net_driver_s *dev; FAR uint8_t *pktbuf; int ret; @@ -1472,8 +1434,8 @@ int mac802154netdev_register(FAR struct ieee802154_mac_s *mac); /* Get the interface structure associated with this interface number. */ - priv = (FAR struct mac802154_driver_s *) - kmm_zalloc(sizeof(struct mac802154_driver_s)); + priv = (FAR struct macnet_driver_s *) + kmm_zalloc(sizeof(struct macnet_driver_s)); if (priv == NULL) { @@ -1497,15 +1459,15 @@ int mac802154netdev_register(FAR struct ieee802154_mac_s *mac); dev = &ieee->md_dev.i_dev; dev->d_buf = pktbuf; /* Single packet buffer */ - dev->d_ifup = mac802154_ifup; /* I/F up (new IP address) callback */ - dev->d_ifdown = mac802154_ifdown; /* I/F down callback */ - dev->d_txavail = mac802154_txavail; /* New TX data callback */ + dev->d_ifup = macnet_ifup; /* I/F up (new IP address) callback */ + dev->d_ifdown = macnet_ifdown; /* I/F down callback */ + dev->d_txavail = macnet_txavail; /* New TX data callback */ #ifdef CONFIG_NET_IGMP - dev->d_addmac = mac802154_addmac; /* Add multicast MAC address */ - dev->d_rmmac = mac802154_rmmac; /* Remove multicast MAC address */ + dev->d_addmac = macnet_addmac; /* Add multicast MAC address */ + dev->d_rmmac = macnet_rmmac; /* Remove multicast MAC address */ #endif #ifdef CONFIG_NETDEV_IOCTL - dev->d_ioctl = mac802154_ioctl; /* Handle network IOCTL commands */ + dev->d_ioctl = macnet_ioctl; /* Handle network IOCTL commands */ #endif dev->d_private = (FAR void *)priv; /* Used to recover private state from dev */ @@ -1522,26 +1484,26 @@ int mac802154netdev_register(FAR struct ieee802154_mac_s *mac); priv->md_cb.mc_priv = priv; maccb = &priv->md_cb.mc_cb; - maccb->conf_data = mac802154_conf_data; - maccb->conf_purge = mac802154_conf_purge; - maccb->conf_associate = mac802154_conf_associate; - maccb->conf_disassociate = mac802154_conf_disassociate; - maccb->conf_get = mac802154_conf_get; - maccb->conf_gts = mac802154_conf_gts; - maccb->conf_reset = mac802154_conf_reset; - maccb->conf_rxenable = mac802154_conf_rxenable; - maccb->conf_scan = mac802154_conf_scan; - maccb->conf_set = mac802154_conf_set; - maccb->conf_start = mac802154_conf_start; - maccb->conf_poll = mac802154_conf_poll; - maccb->ind_data = mac802154_ind_data; - maccb->ind_associate = mac802154_ind_associate; - maccb->ind_disassociate = mac802154_ind_disassociate; - maccb->ind_beaconnotify = mac802154_ind_beaconnotify; - maccb->ind_gts = mac802154_ind_gts; - maccb->ind_orphan = mac802154_ind_orphan; - maccb->ind_commstatus = mac802154_ind_commstatus; - maccb->ind_syncloss = mac802154_ind_syncloss; + maccb->conf_data = macnet_conf_data; + maccb->conf_purge = macnet_conf_purge; + maccb->conf_associate = macnet_conf_associate; + maccb->conf_disassociate = macnet_conf_disassociate; + maccb->conf_get = macnet_conf_get; + maccb->conf_gts = macnet_conf_gts; + maccb->conf_reset = macnet_conf_reset; + maccb->conf_rxenable = macnet_conf_rxenable; + maccb->conf_scan = macnet_conf_scan; + maccb->conf_set = macnet_conf_set; + maccb->conf_start = macnet_conf_start; + maccb->conf_poll = macnet_conf_poll; + maccb->ind_data = macnet_ind_data; + maccb->ind_associate = macnet_ind_associate; + maccb->ind_disassociate = macnet_ind_disassociate; + maccb->ind_beaconnotify = macnet_ind_beaconnotify; + maccb->ind_gts = macnet_ind_gts; + maccb->ind_orphan = macnet_ind_orphan; + maccb->ind_commstatus = macnet_ind_commstatus; + maccb->ind_syncloss = macnet_ind_syncloss; /* Bind the callback structure */ @@ -1563,7 +1525,7 @@ int mac802154netdev_register(FAR struct ieee802154_mac_s *mac); /* Put the interface in the down state. */ - mac802154_ifdown(dev); + macnet_ifdown(dev); /* Register the device with the OS so that socket IOCTLs can be performed */ -- GitLab From 6004f33f617bf4ae56522227d0a391754e399ccd Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 14 Apr 2017 10:47:46 -0600 Subject: [PATCH 440/990] Trivial cleanup --- wireless/ieee802154/mac802154_netdev.c | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/wireless/ieee802154/mac802154_netdev.c b/wireless/ieee802154/mac802154_netdev.c index 616d57adfd..1f5e68729f 100644 --- a/wireless/ieee802154/mac802154_netdev.c +++ b/wireless/ieee802154/mac802154_netdev.c @@ -214,17 +214,18 @@ static int macnet_txavail(FAR struct net_driver_s *dev); #if defined(CONFIG_NET_IGMP) || defined(CONFIG_NET_ICMPv6) static int macnet_addmac(FAR struct net_driver_s *dev, - FAR const uint8_t *mac); + FAR const uint8_t *mac); #ifdef CONFIG_NET_IGMP static int macnet_rmmac(FAR struct net_driver_s *dev, - FAR const uint8_t *mac); + FAR const uint8_t *mac); #endif #ifdef CONFIG_NET_ICMPv6 static void macnet_ipv6multicast(FAR struct macnet_driver_s *priv); #endif #endif #ifdef CONFIG_NETDEV_IOCTL -static int macnet_ioctl(FAR struct net_driver_s *dev, int cmd, long arg); +static int macnet_ioctl(FAR struct net_driver_s *dev, int cmd, + unsigned long arg); #endif /**************************************************************************** @@ -1359,7 +1360,8 @@ static void macnet_ipv6multicast(FAR struct macnet_driver_s *priv) ****************************************************************************/ #ifdef CONFIG_NETDEV_IOCTL -static int macnet_ioctl(FAR struct net_driver_s *dev, int cmd, long arg) +static int macnet_ioctl(FAR struct net_driver_s *dev, int cmd, + unsigned long arg) { FAR struct macnet_driver_s *priv = (FAR struct macnet_driver_s *)dev->d_private; int ret = -EINVAL; -- GitLab From fba8c96540c0af29fd108d885dfc8294905e9fd1 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 14 Apr 2017 11:24:40 -0600 Subject: [PATCH 441/990] ieee802.15.4: New global functions exported by the lower MAC layer should be private to the MAC module. Function prototypes moved from include/nuttx/wireless/ieee802154/ieee802154_mac.h to wireless/ieee802154/mac802154.h --- .../wireless/ieee802154/ieee802154_mac.h | 238 -------------- wireless/ieee802154/Make.defs | 2 +- wireless/ieee802154/mac802154.c | 2 + wireless/ieee802154/mac802154.h | 304 ++++++++++++++++++ wireless/ieee802154/mac802154_device.c | 2 + wireless/ieee802154/mac802154_loopback.c | 2 + wireless/ieee802154/mac802154_netdev.c | 2 + 7 files changed, 313 insertions(+), 239 deletions(-) create mode 100644 wireless/ieee802154/mac802154.h diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index acfc541c58..8bef67a14d 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -1053,244 +1053,6 @@ int mac802154dev_register(MACHANDLE mac, int minor); int mac802154netdev_register(MACHANDLE mac); -/**************************************************************************** - * Name: mac802154_bind - * - * Description: - * Bind the MAC callback table to the MAC state. - * - * Parameters: - * mac - Reference to the MAC driver state structure - * cb - MAC callback operations - * - * Returned Value: - * OK on success; Negated errno on failure. - * - ****************************************************************************/ - -int mac802154_bind(MACHANDLE mac, FAR const struct ieee802154_maccb_s *cb); - -/**************************************************************************** - * Name: mac802154_ioctl - * - * Description: - * Handle MAC and radio IOCTL commands directed to the MAC. - * - * Parameters: - * mac - Reference to the MAC driver state structure - * cmd - The IOCTL command - * arg - The argument for the IOCTL command - * - * Returned Value: - * OK on success; Negated errno on failure. - * - ****************************************************************************/ - -int mac802154_ioctl(MACHANDLE mac, int cmd, unsigned long arg); - -/**************************************************************************** - * MAC Interface Operations - ****************************************************************************/ - -/**************************************************************************** - * Name: mac802154_req_data - * - * Description: - * The MCPS-DATA.request primitive requests the transfer of a data SPDU - * (i.e., MSDU) from a local SSCS entity to a single peer SSCS entity. - * Confirmation is returned via the - * struct ieee802154_maccb_s->conf_data callback. - * - ****************************************************************************/ - -int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req); - -/**************************************************************************** - * Name: mac802154_req_purge - * - * Description: - * The MCPS-PURGE.request primitive allows the next higher layer to purge an - * MSDU from the transaction queue. Confirmation is returned via - * the struct ieee802154_maccb_s->conf_purge callback. - * - ****************************************************************************/ - -int mac802154_req_purge(MACHANDLE mac, uint8_t handle); - -/**************************************************************************** - * Name: mac802154_req_associate - * - * Description: - * The MLME-ASSOCIATE.request primitive allows a device to request an - * association with a coordinator. Confirmation is returned via the - * struct ieee802154_maccb_s->conf_associate callback. - * - ****************************************************************************/ - -int mac802154_req_associate(MACHANDLE mac - FAR struct ieee802154_assoc_req_s *req); - -/**************************************************************************** - * Name: mac802154_req_disassociate - * - * Description: - * The MLME-DISASSOCIATE.request primitive is used by an associated device to - * notify the coordinator of its intent to leave the PAN. It is also used by - * the coordinator to instruct an associated device to leave the PAN. - * Confirmation is returned via the - * struct ieee802154_maccb_s->conf_disassociate callback. - * - ****************************************************************************/ - -int mac802154_req_disassociate(MACHANDLE mac, - FAR struct ieee802154_disassoc_req_s *req); - -/**************************************************************************** - * Name: mac802154_req_get - * - * Description: - * The MLME-GET.request primitive requests information about a given PIB - * attribute. Actual data is returned via the - * struct ieee802154_maccb_s->conf_get callback. - * - ****************************************************************************/ - -int mac802154_req_get(MACHANDLE mac, enum ieee802154_pib_attr_e attr); - -/**************************************************************************** - * Name: mac802154_req_gts - * - * Description: - * The MLME-GTS.request primitive allows a device to send a request to the PAN - * coordinator to allocate a new GTS or to deallocate an existing GTS. - * Confirmation is returned via the - * struct ieee802154_maccb_s->conf_gts callback. - * - ****************************************************************************/ - -int mac802154_req_gts(MACHANDLE mac, FAR uint8_t *characteristics); - -/**************************************************************************** - * Name: mac802154_req_reset - * - * Description: - * The MLME-RESET.request primitive allows the next higher layer to request - * that the MLME performs a reset operation. Confirmation is returned via - * the struct ieee802154_maccb_s->conf_reset callback. - * - ****************************************************************************/ - -int mac802154_req_reset(MACHANDLE mac, bool setdefaults); - -/**************************************************************************** - * Name: mac802154_req_rxenable - * - * Description: - * The MLME-RX-ENABLE.request primitive allows the next higher layer to - * request that the receiver is enable for a finite period of time. - * Confirmation is returned via the - * struct ieee802154_maccb_s->conf_rxenable callback. - * - ****************************************************************************/ - -int mac802154_req_rxenable(MACHANDLE mac, bool deferrable, int ontime, - int duration); - -/**************************************************************************** - * Name: mac802154_req_scan - * - * Description: - * The MLME-SCAN.request primitive is used to initiate a channel scan over a - * given list of channels. A device can use a channel scan to measure the - * energy on the channel, search for the coordinator with which it associated, - * or search for all coordinators transmitting beacon frames within the POS of - * the scanning device. Scan results are returned - * via MULTIPLE calls to the struct ieee802154_maccb_s->conf_scan callback. - * This is a difference with the official 802.15.4 specification, implemented - * here to save memory. - * - ****************************************************************************/ - -int mac802154_req_scan(MACHANDLE mac, uint8_t type, uint32_t channels, - int duration); - -/**************************************************************************** - * Name: mac802154_req_set - * - * Description: - * The MLME-SET.request primitive attempts to write the given value to the - * indicated MAC PIB attribute. Confirmation is returned via the - * struct ieee802154_maccb_s->conf_set callback. - * - ****************************************************************************/ - -int mac802154_req_set(MACHANDLE mac, int attribute, FAR uint8_t *value, - int valuelen); - -/**************************************************************************** - * Name: mac802154_req_start - * - * Description: - * The MLME-START.request primitive makes a request for the device to start - * using a new superframe configuration. Confirmation is returned - * via the struct ieee802154_maccb_s->conf_start callback. - * - ****************************************************************************/ - -int mac802154_req_start(MACHANDLE mac, uint16_t panid, int channel, - uint8_t bo, uint8_t fo, bool coord, bool batext, - bool realign); - -/**************************************************************************** - * Name: mac802154_req_sync - * - * Description: - * The MLME-SYNC.request primitive requests to synchronize with the - * coordinator by acquiring and, if specified, tracking its beacons. - * Confirmation is returned via the - * struct ieee802154_maccb_s->int_commstatus callback. TOCHECK. - * - ****************************************************************************/ - -int mac802154_req_sync(MACHANDLE mac, int channel, bool track); - -/**************************************************************************** - * Name: mac802154_req_poll - * - * Description: - * The MLME-POLL.request primitive prompts the device to request data from the - * coordinator. Confirmation is returned via the - * struct ieee802154_maccb_s->conf_poll callback, followed by a - * struct ieee802154_maccb_s->ind_data callback. - * - ****************************************************************************/ - -int mac802154_req_poll(MACHANDLE mac, FAR uint8_t *coordaddr); - -/**************************************************************************** - * Name: mac802154_rsp_associate - * - * Description: - * The MLME-ASSOCIATE.response primitive is used to initiate a response to an - * MLME-ASSOCIATE.indication primitive. - * - ****************************************************************************/ - -int mac802154_rsp_associate(MACHANDLE mac, uint8_t eadr, uint16_t saddr, - int status); - -/**************************************************************************** - * Name: mac802154_rsp_orphan - * - * Description: - * The MLME-ORPHAN.response primitive allows the next higher layer of a - * coordinator to respond to the MLME-ORPHAN.indication primitive. - * - ****************************************************************************/ - -int mac802154_rsp_orphan(MACHANDLE mac, FAR uint8_t *orphanaddr, - uint16_t saddr, bool associated); - #undef EXTERN #ifdef __cplusplus } diff --git a/wireless/ieee802154/Make.defs b/wireless/ieee802154/Make.defs index fc4db543bf..8a0466eb82 100644 --- a/wireless/ieee802154/Make.defs +++ b/wireless/ieee802154/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # wireless/ieee802145/Make.defs # -# Copyright (C) 2016 Gregory Nutt. All rights reserved. +# Copyright (C) 2016-2017 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index 693e2db771..5dcb8b7fee 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -47,6 +47,8 @@ #include #include +#include "mac802154.h" + /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ diff --git a/wireless/ieee802154/mac802154.h b/wireless/ieee802154/mac802154.h new file mode 100644 index 0000000000..696977259f --- /dev/null +++ b/wireless/ieee802154/mac802154.h @@ -0,0 +1,304 @@ +/**************************************************************************** + * wireless/ieee802154/mac802154.h + * + * Copyright (C) 2016 Sebastien Lorquet. All rights reserved. + * Copyright (C) 2017 Verge Inc. All rights reserved. + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * + * Author: Sebastien Lorquet + * Author: Anthony Merlino + * + * The naming and comments for various fields are taken directly + * from the IEEE 802.15.4 2011 standard. + * + * 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 __WIRELESS_IEEE802154__MAC802154_H +#define __WIRELESS_IEEE802154__MAC802154_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + + /**************************************************************************** + * Name: mac802154_bind + * + * Description: + * Bind the MAC callback table to the MAC state. + * + * Parameters: + * mac - Reference to the MAC driver state structure + * cb - MAC callback operations + * + * Returned Value: + * OK on success; Negated errno on failure. + * + ****************************************************************************/ + +int mac802154_bind(MACHANDLE mac, FAR const struct ieee802154_maccb_s *cb); + +/**************************************************************************** + * Name: mac802154_ioctl + * + * Description: + * Handle MAC and radio IOCTL commands directed to the MAC. + * + * Parameters: + * mac - Reference to the MAC driver state structure + * cmd - The IOCTL command + * arg - The argument for the IOCTL command + * + * Returned Value: + * OK on success; Negated errno on failure. + * + ****************************************************************************/ + +int mac802154_ioctl(MACHANDLE mac, int cmd, unsigned long arg); + +/**************************************************************************** + * MAC Interface Operations + ****************************************************************************/ + +/**************************************************************************** + * Name: mac802154_req_data + * + * Description: + * The MCPS-DATA.request primitive requests the transfer of a data SPDU + * (i.e., MSDU) from a local SSCS entity to a single peer SSCS entity. + * Confirmation is returned via the + * struct ieee802154_maccb_s->conf_data callback. + * + ****************************************************************************/ + +int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req); + +/**************************************************************************** + * Name: mac802154_req_purge + * + * Description: + * The MCPS-PURGE.request primitive allows the next higher layer to purge an + * MSDU from the transaction queue. Confirmation is returned via + * the struct ieee802154_maccb_s->conf_purge callback. + * + ****************************************************************************/ + +int mac802154_req_purge(MACHANDLE mac, uint8_t handle); + +/**************************************************************************** + * Name: mac802154_req_associate + * + * Description: + * The MLME-ASSOCIATE.request primitive allows a device to request an + * association with a coordinator. Confirmation is returned via the + * struct ieee802154_maccb_s->conf_associate callback. + * + ****************************************************************************/ + +int mac802154_req_associate(MACHANDLE mac + FAR struct ieee802154_assoc_req_s *req); + +/**************************************************************************** + * Name: mac802154_req_disassociate + * + * Description: + * The MLME-DISASSOCIATE.request primitive is used by an associated device to + * notify the coordinator of its intent to leave the PAN. It is also used by + * the coordinator to instruct an associated device to leave the PAN. + * Confirmation is returned via the + * struct ieee802154_maccb_s->conf_disassociate callback. + * + ****************************************************************************/ + +int mac802154_req_disassociate(MACHANDLE mac, + FAR struct ieee802154_disassoc_req_s *req); + +/**************************************************************************** + * Name: mac802154_req_get + * + * Description: + * The MLME-GET.request primitive requests information about a given PIB + * attribute. Actual data is returned via the + * struct ieee802154_maccb_s->conf_get callback. + * + ****************************************************************************/ + +int mac802154_req_get(MACHANDLE mac, enum ieee802154_pib_attr_e attr); + +/**************************************************************************** + * Name: mac802154_req_gts + * + * Description: + * The MLME-GTS.request primitive allows a device to send a request to the PAN + * coordinator to allocate a new GTS or to deallocate an existing GTS. + * Confirmation is returned via the + * struct ieee802154_maccb_s->conf_gts callback. + * + ****************************************************************************/ + +int mac802154_req_gts(MACHANDLE mac, FAR uint8_t *characteristics); + +/**************************************************************************** + * Name: mac802154_req_reset + * + * Description: + * The MLME-RESET.request primitive allows the next higher layer to request + * that the MLME performs a reset operation. Confirmation is returned via + * the struct ieee802154_maccb_s->conf_reset callback. + * + ****************************************************************************/ + +int mac802154_req_reset(MACHANDLE mac, bool setdefaults); + +/**************************************************************************** + * Name: mac802154_req_rxenable + * + * Description: + * The MLME-RX-ENABLE.request primitive allows the next higher layer to + * request that the receiver is enable for a finite period of time. + * Confirmation is returned via the + * struct ieee802154_maccb_s->conf_rxenable callback. + * + ****************************************************************************/ + +int mac802154_req_rxenable(MACHANDLE mac, bool deferrable, int ontime, + int duration); + +/**************************************************************************** + * Name: mac802154_req_scan + * + * Description: + * The MLME-SCAN.request primitive is used to initiate a channel scan over a + * given list of channels. A device can use a channel scan to measure the + * energy on the channel, search for the coordinator with which it associated, + * or search for all coordinators transmitting beacon frames within the POS of + * the scanning device. Scan results are returned + * via MULTIPLE calls to the struct ieee802154_maccb_s->conf_scan callback. + * This is a difference with the official 802.15.4 specification, implemented + * here to save memory. + * + ****************************************************************************/ + +int mac802154_req_scan(MACHANDLE mac, uint8_t type, uint32_t channels, + int duration); + +/**************************************************************************** + * Name: mac802154_req_set + * + * Description: + * The MLME-SET.request primitive attempts to write the given value to the + * indicated MAC PIB attribute. Confirmation is returned via the + * struct ieee802154_maccb_s->conf_set callback. + * + ****************************************************************************/ + +int mac802154_req_set(MACHANDLE mac, int attribute, FAR uint8_t *value, + int valuelen); + +/**************************************************************************** + * Name: mac802154_req_start + * + * Description: + * The MLME-START.request primitive makes a request for the device to start + * using a new superframe configuration. Confirmation is returned + * via the struct ieee802154_maccb_s->conf_start callback. + * + ****************************************************************************/ + +int mac802154_req_start(MACHANDLE mac, uint16_t panid, int channel, + uint8_t bo, uint8_t fo, bool coord, bool batext, + bool realign); + +/**************************************************************************** + * Name: mac802154_req_sync + * + * Description: + * The MLME-SYNC.request primitive requests to synchronize with the + * coordinator by acquiring and, if specified, tracking its beacons. + * Confirmation is returned via the + * struct ieee802154_maccb_s->int_commstatus callback. TOCHECK. + * + ****************************************************************************/ + +int mac802154_req_sync(MACHANDLE mac, int channel, bool track); + +/**************************************************************************** + * Name: mac802154_req_poll + * + * Description: + * The MLME-POLL.request primitive prompts the device to request data from the + * coordinator. Confirmation is returned via the + * struct ieee802154_maccb_s->conf_poll callback, followed by a + * struct ieee802154_maccb_s->ind_data callback. + * + ****************************************************************************/ + +int mac802154_req_poll(MACHANDLE mac, FAR uint8_t *coordaddr); + +/**************************************************************************** + * Name: mac802154_rsp_associate + * + * Description: + * The MLME-ASSOCIATE.response primitive is used to initiate a response to an + * MLME-ASSOCIATE.indication primitive. + * + ****************************************************************************/ + +int mac802154_rsp_associate(MACHANDLE mac, uint8_t eadr, uint16_t saddr, + int status); + +/**************************************************************************** + * Name: mac802154_rsp_orphan + * + * Description: + * The MLME-ORPHAN.response primitive allows the next higher layer of a + * coordinator to respond to the MLME-ORPHAN.indication primitive. + * + ****************************************************************************/ + +int mac802154_rsp_orphan(MACHANDLE mac, FAR uint8_t *orphanaddr, + uint16_t saddr, bool associated); + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* __WIRELESS_IEEE802154__MAC802154_H */ diff --git a/wireless/ieee802154/mac802154_device.c b/wireless/ieee802154/mac802154_device.c index fde4cab707..059514c5d8 100644 --- a/wireless/ieee802154/mac802154_device.c +++ b/wireless/ieee802154/mac802154_device.c @@ -51,6 +51,8 @@ #include +#include "mac802154.h" + /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ diff --git a/wireless/ieee802154/mac802154_loopback.c b/wireless/ieee802154/mac802154_loopback.c index 71255f0d60..b3c0c4cdf5 100644 --- a/wireless/ieee802154/mac802154_loopback.c +++ b/wireless/ieee802154/mac802154_loopback.c @@ -56,6 +56,8 @@ #include #include +#include "mac802154.h" + #ifdef CONFIG_IEEE802154_LOOPBACK /**************************************************************************** diff --git a/wireless/ieee802154/mac802154_netdev.c b/wireless/ieee802154/mac802154_netdev.c index 1f5e68729f..6cbb6d5840 100644 --- a/wireless/ieee802154/mac802154_netdev.c +++ b/wireless/ieee802154/mac802154_netdev.c @@ -60,6 +60,8 @@ #include #include +#include "mac802154.h" + #ifdef CONFIG_NET_6LOWPAN /**************************************************************************** -- GitLab From 4602212612d618a7adce2038b653ec6b4333ce38 Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Fri, 14 Apr 2017 11:42:20 -0600 Subject: [PATCH 442/990] Fix serial compilation issues --- arch/arm/src/stm32f0/chip/stm32f0_pinmap.h | 53 ++++++++++++++++++++++ arch/arm/src/stm32f0/stm32f0_serial.c | 15 ++++-- configs/stm32f0discovery/include/board.h | 33 -------------- 3 files changed, 64 insertions(+), 37 deletions(-) create mode 100644 arch/arm/src/stm32f0/chip/stm32f0_pinmap.h diff --git a/arch/arm/src/stm32f0/chip/stm32f0_pinmap.h b/arch/arm/src/stm32f0/chip/stm32f0_pinmap.h new file mode 100644 index 0000000000..a586cbdbc7 --- /dev/null +++ b/arch/arm/src/stm32f0/chip/stm32f0_pinmap.h @@ -0,0 +1,53 @@ +/************************************************************************************ + * arch/arm/src/stm32f0/chip/stm32f0_pinmap.h + * + * Copyright (C) 2015 Sebastien Lorquet. All rights reserved. + * Author: Sebastien Lorquet + * + * 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 __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_PINMAP_H +#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_PINMAP_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include "chip.h" + +#if defined(CONFIG_STM32F0_STM32F05X) +# include "chip/stm32f05xr_pinmap.h" +#else +# error "Unsupported STM32F0 pin map" +#endif + +#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_PINMAP_H */ + diff --git a/arch/arm/src/stm32f0/stm32f0_serial.c b/arch/arm/src/stm32f0/stm32f0_serial.c index 66f88e38eb..6c122328af 100644 --- a/arch/arm/src/stm32f0/stm32f0_serial.c +++ b/arch/arm/src/stm32f0/stm32f0_serial.c @@ -59,14 +59,21 @@ #endif #include -#include +#include "up_arch.h" +#include "up_internal.h" #include "chip.h" +#include "stm32f0_gpio.h" #include "stm32f0_uart.h" -//#include "stm32f0_dma.h" #include "stm32f0_rcc.h" -#include "up_arch.h" -#include "up_internal.h" +#include "chip/stm32f0_pinmap.h" + +/* board.h should be included last. It may depend on defintions from + * previous header files and it may, in certain cases, override definitions + * provided in previous header files. + */ + +#include /**************************************************************************** * Pre-processor Definitions diff --git a/configs/stm32f0discovery/include/board.h b/configs/stm32f0discovery/include/board.h index 4123b11f56..4840067e96 100644 --- a/configs/stm32f0discovery/include/board.h +++ b/configs/stm32f0discovery/include/board.h @@ -237,38 +237,5 @@ #define BUTTON_USER_BIT (1 << BUTTON_USER) /* Alternate Pin Functions **********************************************************/ -/* The STM32L-Discovery has no on-board RS-232 driver. Further, there are no USART - * pins that do not conflict with the on board resources, in particular, the LCD: - * Most USART pins are available if the LCD is enabled; USART2 may be used if either - * the LCD or the on-board LEDs are disabled. - * - * PA9 USART1_TX LCD glass COM1 P2, pin 22 - * PA10 USART1_RX LCD glass COM2 P2, pin 21 - * PB6 USART1_TX LED Blue P2, pin 8 - * PB7 USART1_RX LED Green P2, pin 7 - * - * PA2 USART2_TX LCD SEG1 P1, pin 17 - * PA3 USART2_RX LCD SEG2 P1, pin 18 - * - * PB10 USART3_TX LCD SEG6 P1, pin 22 - * PB11 USART3_RX LCD SEG7 P1, pin 23 - * PC10 USART3_TX LCD SEG22 P2, pin 15 - * PC11 USART3_RX LCD SEG23 P2, pin 14 - */ - -/* Select PA9 and PA10 if the LCD is not enabled */ - -//#define GPIO_USART1_RX GPIO_USART1_RX_1 /* PA10 */ -//#define GPIO_USART1_TX GPIO_USART1_TX_1 /* PA9 */ - -/* This there are no other options for USART1 on this part */ - -#define GPIO_USART2_RX GPIO_USART2_RX_1 /* PA3 */ -#define GPIO_USART2_TX GPIO_USART2_TX_1 /* PA2 */ - -/* Arbirtrarily select PB10 and PB11 */ - -#define GPIO_USART3_RX GPIO_USART3_RX_1 /* PB11 */ -#define GPIO_USART3_TX GPIO_USART3_TX_1 /* PB10 */ #endif /* __CONFIG_STM32F0DISCOVERY_INCLUDE_BOARD_H */ -- GitLab From 03cbf21cd8810d10a5ca1bfc2866b66315a6c2f8 Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Fri, 14 Apr 2017 11:44:51 -0600 Subject: [PATCH 443/990] Replace HAVE_USART with HAVE_UART --- arch/arm/src/stm32f0/stm32f0_serial.c | 8 ++++---- arch/arm/src/stm32f0/stm32f0_uart.h | 14 +++++++------- 2 files changed, 11 insertions(+), 11 deletions(-) diff --git a/arch/arm/src/stm32f0/stm32f0_serial.c b/arch/arm/src/stm32f0/stm32f0_serial.c index 6c122328af..0423b9ff94 100644 --- a/arch/arm/src/stm32f0/stm32f0_serial.c +++ b/arch/arm/src/stm32f0/stm32f0_serial.c @@ -196,7 +196,7 @@ #endif #ifdef USE_SERIALDRIVER -#ifdef HAVE_USART +#ifdef HAVE_UART /**************************************************************************** * Private Types @@ -2327,7 +2327,7 @@ static int stm32f0serial_pmprepare(FAR struct pm_callback_s *cb, int domain, return OK; } #endif -#endif /* HAVE_USART */ +#endif /* HAVE_UART */ #endif /* USE_SERIALDRIVER */ /**************************************************************************** @@ -2349,7 +2349,7 @@ static int stm32f0serial_pmprepare(FAR struct pm_callback_s *cb, int domain, #ifdef USE_EARLYSERIALINIT void up_earlyserialinit(void) { -#ifdef HAVE_USART +#ifdef HAVE_UART unsigned i; /* Disable all USART interrupts */ @@ -2382,7 +2382,7 @@ void up_earlyserialinit(void) void up_serialinit(void) { -#ifdef HAVE_USART +#ifdef HAVE_UART char devname[16]; unsigned i; unsigned minor = 0; diff --git a/arch/arm/src/stm32f0/stm32f0_uart.h b/arch/arm/src/stm32f0/stm32f0_uart.h index 4fb7b1c05f..80229a2831 100644 --- a/arch/arm/src/stm32f0/stm32f0_uart.h +++ b/arch/arm/src/stm32f0/stm32f0_uart.h @@ -54,22 +54,22 @@ * device. */ -#if STM32F0_NUSART < 8 || !defined(CONFIG_STM32F0_HAVE_USART8) +#if STM32F0_NUSART < 8 || !defined(CONFIG_STM32F0_HAVE_UART8) # undef CONFIG_STM32F0_USART8 #endif -#if STM32F0_NUSART < 7 || !defined(CONFIG_STM32F0_HAVE_USART7) +#if STM32F0_NUSART < 7 || !defined(CONFIG_STM32F0_HAVE_UART7) # undef CONFIG_STM32F0_USART7 #endif -#if STM32F0_NUSART < 6 || !defined(CONFIG_STM32F0_HAVE_USART6) +#if STM32F0_NUSART < 6 || !defined(CONFIG_STM32F0_HAVE_UART6) # undef CONFIG_STM32F0_USART6 #endif -#if STM32F0_NUSART < 5 || !defined(CONFIG_STM32F0_HAVE_USART5) +#if STM32F0_NUSART < 5 || !defined(CONFIG_STM32F0_HAVE_UART5) # undef CONFIG_STM32F0_USART5 #endif -#if STM32F0_NUSART < 4 || !defined(CONFIG_STM32F0_HAVE_USART4) +#if STM32F0_NUSART < 4 || !defined(CONFIG_STM32F0_HAVE_UART4) # undef CONFIG_STM32F0_USART4 #endif -#if STM32F0_NUSART < 3 || !defined(CONFIG_STM32F0_HAVE_USART3) +#if STM32F0_NUSART < 3 || !defined(CONFIG_STM32F0_HAVE_UART3) # undef CONFIG_STM32F0_USART3 #endif #if STM32F0_NUSART < 2 @@ -84,7 +84,7 @@ #if defined(CONFIG_STM32F0_USART1) || defined(CONFIG_STM32F0_USART2) || \ defined(CONFIG_STM32F0_USART3) || defined(CONFIG_STM32F0_USART4) || \ defined(CONFIG_STM32F0_USART5) -# define HAVE_USART 1 +# define HAVE_UART 1 #endif /* Sanity checks */ -- GitLab From beee02843ae8f98a68059d623f41160d2e877963 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 14 Apr 2017 12:05:28 -0600 Subject: [PATCH 444/990] wireless/ieee802154: Fix some easy compilation problems introduced with header file changes. --- .../clicker2-stm32/mrf24j40-radio/defconfig | 35 ++++++++++++++----- .../wireless/ieee802154/ieee802154_mac.h | 4 +-- .../wireless/ieee802154/ieee802154_radio.h | 20 ++--------- wireless/ieee802154/mac802154.c | 13 +++++-- wireless/ieee802154/mac802154.h | 4 +-- 5 files changed, 43 insertions(+), 33 deletions(-) diff --git a/configs/clicker2-stm32/mrf24j40-radio/defconfig b/configs/clicker2-stm32/mrf24j40-radio/defconfig index db009c3ed3..33284b022c 100644 --- a/configs/clicker2-stm32/mrf24j40-radio/defconfig +++ b/configs/clicker2-stm32/mrf24j40-radio/defconfig @@ -373,9 +373,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -389,7 +393,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -410,6 +417,7 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set # CONFIG_STM32_OTGFS is not set # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -660,7 +668,10 @@ CONFIG_SCHED_WAITPID=y # # Pthread Options # -# CONFIG_MUTEX_TYPES is not set +# CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -856,6 +867,7 @@ CONFIG_USART3_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set CONFIG_DRIVERS_WIRELESS=y # CONFIG_WL_CC1101 is not set @@ -950,6 +962,7 @@ CONFIG_MM_REGIONS=1 CONFIG_WIRELESS=y CONFIG_WIRELESS_IEEE802154=y CONFIG_IEEE802154_MAC=y +# CONFIG_IEEE802154_MAC_DEV is not set CONFIG_IEEE802154_DEV=y # @@ -1177,13 +1190,6 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_TIFF is not set # CONFIG_GRAPHICS_TRAVELER is not set -# -# IEEE 802.15.4 applications -# -CONFIG_IEEE802154_COMMON=y -CONFIG_IEEE802154_COORD=y -CONFIG_IEEE802154_I8SAK=y - # # Interpreters # @@ -1336,3 +1342,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +CONFIG_IEEE802154_COMMON=y +CONFIG_IEEE802154_COORD=y +CONFIG_IEEE802154_I8SAK=y diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index 8bef67a14d..6ad8158c80 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -851,9 +851,9 @@ struct ieee802154_pollreq_s union ieee802154_macarg_u { struct ieee802154_assoc_req_s assocreq; /* MAC802154IOC_MLME_ASSOC_REQUEST */ - struct ieee802154_assocresp_s assocresp: /* MAC802154IOC_MLME_ASSOC_RESPONSE */ + struct ieee802154_assocresp_s assocresp; /* MAC802154IOC_MLME_ASSOC_RESPONSE */ struct ieee802154_disassoc_req_s disassocreq; /* MAC802154IOC_MLME_DISASSOC_REQUEST */ - struct ieee802154_mlmereq_s getreq; /* MAC802154IOC_MLME_GET_REQUEST */ + struct ieee802154_getreq_s getreq; /* MAC802154IOC_MLME_GET_REQUEST */ struct ieee802154_gtsreq_s gtsreq; /* MAC802154IOC_MLME_GTS_REQUEST */ struct ieee802154_orphanresp_s orphanresp; /* MAC802154IOC_MLME_ORPHAN_RESPONSE */ struct ieee802154_resetreq_s resetreq; /* MAC802154IOC_MLME_RESET_REQUEST */ diff --git a/include/nuttx/wireless/ieee802154/ieee802154_radio.h b/include/nuttx/wireless/ieee802154/ieee802154_radio.h index 5bee1e3d52..eef94e328f 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_radio.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_radio.h @@ -138,7 +138,7 @@ union ieee802154_radioarg_u bool promisc; /* PHY802154IOC_GET/SET_EADDR */ uint8_t devmode; /* PHY802154IOC_GET/SET_DEVMODE */ int32_t txpwr; /* PHY802154IOC_GET/SET_TXPWR */ - bool energy /* PHY802154IOC_ENERGYDETECT */ + bool energy; /* PHY802154IOC_ENERGYDETECT */ struct ieee802154_cca_s cca; /* PHY802154IOC_GET/SET_CCA */ }; @@ -158,23 +158,7 @@ struct ieee802154_netradio_s /* IEEE802.15.4 Radio Interface Operations **********************************/ -struct ieee802154_cca_s -{ - uint8_t use_ed : 1; /* CCA using ED */ - uint8_t use_cs : 1; /* CCA using carrier sense */ - uint8_t edth; /* Energy detection threshold for CCA */ - uint8_t csth; /* Carrier sense threshold for CCA */ -}; - -struct ieee802154_packet_s -{ - uint8_t len; - uint8_t data[127]; - uint8_t lqi; - uint8_t rssi; -}; - -struct ieee802154_radio_s; +struct ieee802154_radio_s; /* Forward reference */ struct ieee802154_radioops_s { diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index 5dcb8b7fee..e8f046f284 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -45,6 +45,7 @@ #include #include +#include #include #include "mac802154.h" @@ -271,6 +272,8 @@ int mac802154_ioctl(MACHANDLE mac, int cmd, unsigned long arg) (FAR struct ieee802154_privmac_s *)mac; int ret = -EINVAL; + DEBUGASSERT(priv != NULL); + /* Check for IOCTLs aimed at the IEEE802.15.4 MAC layer */ if (_MAC802154IOCVALID(cmd)) @@ -283,8 +286,14 @@ int mac802154_ioctl(MACHANDLE mac, int cmd, unsigned long arg) else { - ret = priv->radio->ioctl(priv->radio, cmd, arg); + DEBUGASSERT(priv->radio != NULL && + priv->radio->ops != NULL && + priv->radio->ops->ioctl != NULL); + + ret = priv->radio->ops->ioctl(priv->radio, cmd, arg); } + + return ret; } /**************************************************************************** @@ -334,7 +343,7 @@ int mac802154_req_purge(MACHANDLE mac, uint8_t handle) * ****************************************************************************/ -int mac802154_req_associate(MACHANDLE mac +int mac802154_req_associate(MACHANDLE mac, FAR struct ieee802154_assoc_req_s *req) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; diff --git a/wireless/ieee802154/mac802154.h b/wireless/ieee802154/mac802154.h index 696977259f..8321e905ea 100644 --- a/wireless/ieee802154/mac802154.h +++ b/wireless/ieee802154/mac802154.h @@ -52,7 +52,7 @@ #include #include -#include +#include /**************************************************************************** * Public Function Prototypes @@ -132,7 +132,7 @@ int mac802154_req_purge(MACHANDLE mac, uint8_t handle); * ****************************************************************************/ -int mac802154_req_associate(MACHANDLE mac +int mac802154_req_associate(MACHANDLE mac, FAR struct ieee802154_assoc_req_s *req); /**************************************************************************** -- GitLab From 0c4ff5e60b110925754e58b9f4938df84b6490bb Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 14 Apr 2017 12:59:49 -0600 Subject: [PATCH 445/990] wireless/ieee802154: Add radio IOCTL helpers --- wireless/ieee802154/Make.defs | 2 +- wireless/ieee802154/mac802154_device.c | 2 +- wireless/ieee802154/radio802154_device.c | 2 +- wireless/ieee802154/radio802154_ioctl.c | 487 +++++++++++++++++++++++ wireless/ieee802154/radio802154_ioctl.h | 255 ++++++++++++ 5 files changed, 745 insertions(+), 3 deletions(-) create mode 100644 wireless/ieee802154/radio802154_ioctl.c create mode 100644 wireless/ieee802154/radio802154_ioctl.h diff --git a/wireless/ieee802154/Make.defs b/wireless/ieee802154/Make.defs index 8a0466eb82..a2ec823d3b 100644 --- a/wireless/ieee802154/Make.defs +++ b/wireless/ieee802154/Make.defs @@ -37,7 +37,7 @@ ifeq ($(CONFIG_WIRELESS_IEEE802154),y) # Include IEEE 802.15.4 support -CSRCS = +CSRCS = radio802154_ioctl.c # Include wireless devices build support diff --git a/wireless/ieee802154/mac802154_device.c b/wireless/ieee802154/mac802154_device.c index 059514c5d8..f4973d0a47 100644 --- a/wireless/ieee802154/mac802154_device.c +++ b/wireless/ieee802154/mac802154_device.c @@ -1,5 +1,5 @@ /**************************************************************************** - * drivers/ieee802154/mac802154_device.c + * wireless/ieee802154/mac802154_device.c * * Copyright (C) 2017 Verge Inc. All rights reserved. * Author: Anthony Merlino diff --git a/wireless/ieee802154/radio802154_device.c b/wireless/ieee802154/radio802154_device.c index a3a4161ffc..b58c0a6f97 100644 --- a/wireless/ieee802154/radio802154_device.c +++ b/wireless/ieee802154/radio802154_device.c @@ -1,5 +1,5 @@ /**************************************************************************** - * drivers/ieee802154/radio802154_device.c + * wireless/ieee802154/radio802154_device.c * * Copyright (C) 2014-2015 Gregory Nutt. All rights reserved. * Copyright (C) 2014-2015 Sebastien Lorquet. All rights reserved. diff --git a/wireless/ieee802154/radio802154_ioctl.c b/wireless/ieee802154/radio802154_ioctl.c new file mode 100644 index 0000000000..d86366c987 --- /dev/null +++ b/wireless/ieee802154/radio802154_ioctl.c @@ -0,0 +1,487 @@ +/**************************************************************************** + * wireless/ieee802154/radio802154_ioctl.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define RADIO_IOCTL(r,c,a) \ + (r)->ops->ioctl((r),(c),(unsigned long)((uintptr_t)(a))) + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: radio802154_setchannel + * + * Description: + * Define the current radio channel the device is operating on. + * In the 2.4 GHz, there are 16 channels, each 2 MHz wide, 5 MHz spacing: + * Chan MHz Chan MHz Chan MHz Chan MHz + * 11 2405 15 2425 19 2445 23 2465 + * 12 2410 16 2430 20 2450 24 2470 + * 13 2415 17 2435 21 2455 25 2475 + * 14 2420 18 2440 22 2460 26 2480 + * + ****************************************************************************/ + +int radio802154_setchannel(FAR struct ieee802154_radio_s *radio, + uint8_t chan) +{ + union ieee802154_radioarg_u arg; + int ret; + + arg.channel = chan; + + ret = RADIO_IOCTL(radio, PHY802154IOC_SET_CHAN, &arg); + if (ret < 0) + { + wlerr("ERROR: PHY802154IOC_SET_CHAN failed: %d\n", ret); + } + + return ret; +} + +/**************************************************************************** + * Name: radio802154_getchannel + * + * Description: + * Define the current radio channel the device is operating on. + * + ****************************************************************************/ + +int radio802154_getchannel(FAR struct ieee802154_radio_s *radio, + FAR uint8_t *chan) +{ + union ieee802154_radioarg_u arg; + int ret; + + ret = RADIO_IOCTL(radio, PHY802154IOC_GET_CHAN, &arg); + if (ret < 0) + { + wlerr("ERROR: PHY802154IOC_GET_CHAN failed: %d\n", ret); + } + + *chan = arg.channel; + return ret; +} + +/**************************************************************************** + * Name: radio802154_setpanid + * + * Description: + * Define the PAN ID the device is operating on. + * + ****************************************************************************/ + +int radio802154_setpanid(FAR struct ieee802154_radio_s *radio, + uint16_t panid) +{ + union ieee802154_radioarg_u arg; + int ret; + + arg.panid = panid; + + ret = RADIO_IOCTL(radio, PHY802154IOC_SET_PANID, &arg); + if (ret < 0) + { + wlerr("ERROR: PHY802154IOC_SET_PANID failed: %d\n", ret); + } + + return ret; +} + +/**************************************************************************** + * Name: radio802154_getpanid + * + * Description: + * Define the current PAN ID the device is operating on. + * + ****************************************************************************/ + +int radio802154_getpanid(FAR struct ieee802154_radio_s *radio, + FAR uint16_t *panid) +{ + union ieee802154_radioarg_u arg; + int ret; + + ret = RADIO_IOCTL(radio, PHY802154IOC_GET_PANID, &arg); + if (ret < 0) + { + wlerr("ERROR: PHY802154IOC_GET_PANID failed: %d\n", ret); + } + + *panid = arg.panid; + return ret; +} + +/**************************************************************************** + * Name: radio802154_setsaddr + * + * Description: + * Define the device short address. The following addresses are special: + * FFFEh : Broadcast + * FFFFh : Unspecified + * + ****************************************************************************/ + +int radio802154_setsaddr(FAR struct ieee802154_radio_s *radio, + uint16_t saddr) +{ + union ieee802154_radioarg_u arg; + int ret; + + arg.saddr = saddr; + + ret = RADIO_IOCTL(radio, PHY802154IOC_SET_SADDR, &arg); + if (ret < 0) + { + wlerr("ERROR: PHY802154IOC_SET_SADDR failed: %d\n", ret); + } + + return ret; +} + +/**************************************************************************** + * Name: radio802154_getsaddr + * + * Description: + * Define the current short address the device is using. + * + ****************************************************************************/ + +int radio802154_getsaddr(FAR struct ieee802154_radio_s *radio, + FAR uint16_t *saddr) +{ + union ieee802154_radioarg_u arg; + int ret; + + ret = RADIO_IOCTL(radio, PHY802154IOC_GET_SADDR, &arg); + if (ret < 0) + { + wlerr("ERROR: PHY802154IOC_GET_SADDR failed: %d\n", ret); + } + + *saddr = arg.saddr; + return ret; +} + +/**************************************************************************** + * Name: radio802154_seteaddr + * + * Description: + * Define the device extended address. The following addresses are special: + * FFFFFFFFFFFFFFFFh : Unspecified + * + ****************************************************************************/ + +int radio802154_seteaddr(FAR struct ieee802154_radio_s *radio, + FAR uint8_t *eaddr) +{ + union ieee802154_radioarg_u arg; + int ret; + + memcpy(arg.eaddr, eaddr, EADDR_SIZE); /* REVISIT */ + + ret = RADIO_IOCTL(radio, PHY802154IOC_SET_EADDR, &arg); + if (ret < 0) + { + wlerr("ERROR: PHY802154IOC_SET_EADDR failed: %d\n", ret); + } + + return ret; +} + +/**************************************************************************** + * Name: radio802154_geteaddr + * + * Description: + * Define the current extended address the device is using. + * + ****************************************************************************/ + +int radio802154_geteaddr(FAR struct ieee802154_radio_s *radio, + FAR uint8_t *eaddr) +{ + union ieee802154_radioarg_u arg; + int ret; + + ret = RADIO_IOCTL(radio, PHY802154IOC_GET_EADDR, &arg); + if (ret < 0) + { + wlerr("ERROR: PHY802154IOC_GET_EADDR failed: %d\n", ret); + } + + memcpy(eaddr, arg.eaddr, EADDR_SIZE); /* REVISIT */ + return ret; +} + +/**************************************************************************** + * Name: radio802154_setpromisc + * + * Description: + * Set the device into promiscuous mode, e.g do not filter any incoming + * frame. + * + ****************************************************************************/ + +int radio802154_setpromisc(FAR struct ieee802154_radio_s *radio, + bool promisc) +{ + union ieee802154_radioarg_u arg; + int ret; + + arg.promisc = promisc; + + ret = RADIO_IOCTL(radio, PHY802154IOC_SET_PROMISC, &arg); + if (ret < 0) + { + wlerr("ERROR: PHY802154IOC_SET_PROMISC failed: %d\n", ret); + } + + return ret; +} + +/**************************************************************************** + * Name: radio802154_getpromisc + * + * Description: + * Get the device receive mode. + * + ****************************************************************************/ + +int radio802154_getpromisc(FAR struct ieee802154_radio_s *radio, + FAR bool *promisc) +{ + union ieee802154_radioarg_u arg; + int ret; + + ret = RADIO_IOCTL(radio, PHY802154IOC_GET_PROMISC, &arg); + if (ret < 0) + { + wlerr("ERROR: PHY802154IOC_GET_PROMISC failed: %d\n", ret); + } + + *promisc = arg.promisc; + return ret; +} + +/**************************************************************************** + * Name: radio802154_setdevmode + * + * Description: + * Define the device behaviour: normal end device or coordinator + * + ****************************************************************************/ + +int radio802154_setdevmode(FAR struct ieee802154_radio_s *radio, + uint8_t mode) +{ + union ieee802154_radioarg_u arg; + int ret; + + arg.devmode = mode; + + ret = RADIO_IOCTL(radio, PHY802154IOC_SET_DEVMODE, &arg); + if (ret < 0) + { + wlerr("ERROR: PHY802154IOC_SET_DEVMODE failed: %d\n", ret); + } + + return ret; +} + +/**************************************************************************** + * Name: radio802154_setdevmode + * + * Description: + * Return the current device mode + * + ****************************************************************************/ + +int radio802154_getdevmode(FAR struct ieee802154_radio_s *radio, + FAR uint8_t *mode) +{ + union ieee802154_radioarg_u arg; + int ret; + + ret = RADIO_IOCTL(radio, PHY802154IOC_GET_DEVMODE, &arg); + if (ret < 0) + { + wlerr("ERROR: PHY802154IOC_GET_DEVMODE failed: %d\n", ret); + } + + *mode = arg.devmode; + return ret; +} + +/**************************************************************************** + * Name: radio802154_settxpower + * + * Description: + * Define the transmit power. Value is passed in mBm, it is rounded to + * the nearest value. Some MRF modules have a power amplifier, this routine + * does not care about this. We only change the CHIP output power. + * + ****************************************************************************/ + +int radio802154_settxpower(FAR struct ieee802154_radio_s *radio, + int32_t txpwr) +{ + union ieee802154_radioarg_u arg; + int ret; + + arg.txpwr = txpwr; + + ret = RADIO_IOCTL(radio, PHY802154IOC_SET_TXPWR, &arg); + if (ret < 0) + { + wlerr("ERROR: PHY802154IOC_SET_TXPWR failed: %d\n", ret); + } + + return ret; +} + +/**************************************************************************** + * Name: radio802154_gettxpower + * + * Description: + * Return the actual transmit power, in mBm. + * + ****************************************************************************/ + +int radio802154_gettxpower(FAR struct ieee802154_radio_s *radio, + FAR int32_t *txpwr) +{ + union ieee802154_radioarg_u arg; + int ret; + + ret = RADIO_IOCTL(radio, PHY802154IOC_GET_TXPWR, &arg); + if (ret < 0) + { + wlerr("ERROR: PHY802154IOC_GET_TXPWR failed: %d\n", ret); + } + + *txpwr = arg.txpwr; + return ret; +} + +/**************************************************************************** + * Name: radio802154_setcca + * + * Description: + * Define the Clear Channel Assessement method. + * + ****************************************************************************/ + +int radio802154_setcca(FAR struct ieee802154_radio_s *radio, + FAR struct ieee802154_cca_s *cca) +{ + union ieee802154_radioarg_u arg; + int ret; + + memcpy(&arg.cca, cca, sizeof(struct ieee802154_cca_s)); + + ret = RADIO_IOCTL(radio, PHY802154IOC_SET_CCA, &arg); + if (ret < 0) + { + wlerr("ERROR: PHY802154IOC_SET_CCA failed: %d\n", ret); + } + + return ret; +} + +/**************************************************************************** + * Name: radio802154_getcca + * + * Description: + * Return the Clear Channel Assessement method. + * + ****************************************************************************/ + +int radio802154_getcca(FAR struct ieee802154_radio_s *radio, + FAR struct ieee802154_cca_s *cca) +{ + union ieee802154_radioarg_u arg; + int ret; + + ret = RADIO_IOCTL(radio, PHY802154IOC_GET_CCA, &arg); + if (ret < 0) + { + wlerr("ERROR: PHY802154IOC_GET_CCA failed: %d\n", ret); + } + + memcpy(cca, &arg.cca, sizeof(struct ieee802154_cca_s)); + return ret; +} + +/**************************************************************************** + * Name: radio802154_energydetect + * + * Description: + * Measure the RSSI level for the current channel. + * + ****************************************************************************/ + +int radio802154_energydetect(FAR struct ieee802154_radio_s *radio, + FAR uint8_t *energy) + +{ + union ieee802154_radioarg_u arg; + int ret; + + ret = RADIO_IOCTL(radio, PHY802154IOC_ENERGYDETECT, &arg); + if (ret < 0) + { + wlerr("ERROR: PHY802154IOC_ENERGYDETECT failed: %d\n", ret); + } + + *energy = arg.energy; + return ret; +} diff --git a/wireless/ieee802154/radio802154_ioctl.h b/wireless/ieee802154/radio802154_ioctl.h new file mode 100644 index 0000000000..d09ad57103 --- /dev/null +++ b/wireless/ieee802154/radio802154_ioctl.h @@ -0,0 +1,255 @@ +/**************************************************************************** + * wireless/ieee802154/radio802154_ioctl.h + * + * 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. + * + ****************************************************************************/ + +#ifndef __WIRELESS_IEEE802154_RADIO802154_IOCTL_H +#define __WIRELESS_IEEE802154_RADIO802154_IOCTL_H 1 + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include + +#include "radio802154_ioctl.h" + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: radio802154_setchannel + * + * Description: + * Define the current radio channel the device is operating on. + * In the 2.4 GHz, there are 16 channels, each 2 MHz wide, 5 MHz spacing: + * Chan MHz Chan MHz Chan MHz Chan MHz + * 11 2405 15 2425 19 2445 23 2465 + * 12 2410 16 2430 20 2450 24 2470 + * 13 2415 17 2435 21 2455 25 2475 + * 14 2420 18 2440 22 2460 26 2480 + * + ****************************************************************************/ + +int radio802154_setchannel(FAR struct ieee802154_radio_s *radio, + uint8_t chan); + +/**************************************************************************** + * Name: radio802154_getchannel + * + * Description: + * Define the current radio channel the device is operating on. + * + ****************************************************************************/ + +int radio802154_getchannel(FAR struct ieee802154_radio_s *radio, + FAR uint8_t *chan); + +/**************************************************************************** + * Name: radio802154_setpanid + * + * Description: + * Define the PAN ID the device is operating on. + * + ****************************************************************************/ + +int radio802154_setpanid(FAR struct ieee802154_radio_s *radio, + uint16_t panid); + +/**************************************************************************** + * Name: radio802154_getpanid + * + * Description: + * Define the current PAN ID the device is operating on. + * + ****************************************************************************/ + +int radio802154_getpanid(FAR struct ieee802154_radio_s *radio, + FAR uint16_t *panid); + +/**************************************************************************** + * Name: radio802154_setsaddr + * + * Description: + * Define the device short address. The following addresses are special: + * FFFEh : Broadcast + * FFFFh : Unspecified + * + ****************************************************************************/ + +int radio802154_setsaddr(FAR struct ieee802154_radio_s *radio, + uint16_t saddr); + +/**************************************************************************** + * Name: radio802154_getsaddr + * + * Description: + * Define the current short address the device is using. + * + ****************************************************************************/ + +int radio802154_getsaddr(FAR struct ieee802154_radio_s *radio, + FAR uint16_t *saddr); + +/**************************************************************************** + * Name: radio802154_seteaddr + * + * Description: + * Define the device extended address. The following addresses are special: + * FFFFFFFFFFFFFFFFh : Unspecified + * + ****************************************************************************/ + +int radio802154_seteaddr(FAR struct ieee802154_radio_s *radio, + FAR uint8_t *eaddr); + +/**************************************************************************** + * Name: radio802154_geteaddr + * + * Description: + * Define the current extended address the device is using. + * + ****************************************************************************/ + +int radio802154_geteaddr(FAR struct ieee802154_radio_s *radio, + FAR uint8_t *eaddr); + +/**************************************************************************** + * Name: radio802154_setpromisc + * + * Description: + * Set the device into promiscuous mode, e.g do not filter any incoming + * frame. + * + ****************************************************************************/ + +int radio802154_setpromisc(FAR struct ieee802154_radio_s *radio, + bool promisc); + +/**************************************************************************** + * Name: radio802154_getpromisc + * + * Description: + * Get the device receive mode. + * + ****************************************************************************/ + +int radio802154_getpromisc(FAR struct ieee802154_radio_s *radio, + FAR bool *promisc); + +/**************************************************************************** + * Name: radio802154_setdevmode + * + * Description: + * Define the device behaviour: normal end device or coordinator + * + ****************************************************************************/ + +int radio802154_setdevmode(FAR struct ieee802154_radio_s *radio, + uint8_t mode); + +/**************************************************************************** + * Name: radio802154_setdevmode + * + * Description: + * Return the current device mode + * + ****************************************************************************/ + +int radio802154_getdevmode(FAR struct ieee802154_radio_s *radio, + FAR uint8_t *mode); + +/**************************************************************************** + * Name: radio802154_settxpower + * + * Description: + * Define the transmit power. Value is passed in mBm, it is rounded to + * the nearest value. Some MRF modules have a power amplifier, this routine + * does not care about this. We only change the CHIP output power. + * + ****************************************************************************/ + +int radio802154_settxpower(FAR struct ieee802154_radio_s *radio, + int32_t txpwr); + +/**************************************************************************** + * Name: radio802154_gettxpower + * + * Description: + * Return the actual transmit power, in mBm. + * + ****************************************************************************/ + +int radio802154_gettxpower(FAR struct ieee802154_radio_s *radio, + FAR int32_t *txpwr); + +/**************************************************************************** + * Name: radio802154_setcca + * + * Description: + * Define the Clear Channel Assessement method. + * + ****************************************************************************/ + +int radio802154_setcca(FAR struct ieee802154_radio_s *radio, + FAR struct ieee802154_cca_s *cca); + +/**************************************************************************** + * Name: radio802154_getcca + * + * Description: + * Return the Clear Channel Assessement method. + * + ****************************************************************************/ + +int radio802154_getcca(FAR struct ieee802154_radio_s *radio, + FAR struct ieee802154_cca_s *cca); + +/**************************************************************************** + * Name: radio802154_energydetect + * + * Description: + * Measure the RSSI level for the current channel. + * + ****************************************************************************/ + +int radio802154_energydetect(FAR struct ieee802154_radio_s *radio, + FAR uint8_t *energy); + +#endif /* __WIRELESS_IEEE802154_RADIO802154_IOCTL_H */ -- GitLab From 92c83489ba1142129c910a5987afece88e79d56e Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 14 Apr 2017 13:04:24 -0600 Subject: [PATCH 446/990] radio802154_device.c now accesses the PHY layer via the IOCTL helper functions. --- wireless/ieee802154/radio802154_device.c | 36 +++++++++++++----------- 1 file changed, 19 insertions(+), 17 deletions(-) diff --git a/wireless/ieee802154/radio802154_device.c b/wireless/ieee802154/radio802154_device.c index b58c0a6f97..ac76283c7d 100644 --- a/wireless/ieee802154/radio802154_device.c +++ b/wireless/ieee802154/radio802154_device.c @@ -52,6 +52,8 @@ #include #include +#include "radio802154_ioctl.h" + /**************************************************************************** * Private Types ****************************************************************************/ @@ -390,71 +392,71 @@ static int radio802154dev_ioctl(FAR struct file *filep, int cmd, switch (cmd) { case PHY802154IOC_SET_CHAN: - ret = child->ops->setchannel(child, (uint8_t)arg); + ret = radio802154_setchannel(child, (uint8_t)arg); break; case PHY802154IOC_GET_CHAN: - ret = child->ops->getchannel(child, (FAR uint8_t*)arg); + ret = radio802154_getchannel(child, (FAR uint8_t*)arg); break; case PHY802154IOC_SET_PANID: - ret = child->ops->setpanid(child, (uint16_t)arg); + ret = radio802154_setpanid(child, (uint16_t)arg); break; case PHY802154IOC_GET_PANID: - ret = child->ops->getpanid(child, (FAR uint16_t*)arg); + ret = radio802154_getpanid(child, (FAR uint16_t*)arg); break; case PHY802154IOC_SET_SADDR: - ret = child->ops->setsaddr(child, (uint16_t)arg); + ret = radio802154_setsaddr(child, (uint16_t)arg); break; case PHY802154IOC_GET_SADDR: - ret = child->ops->getsaddr(child, (FAR uint16_t*)arg); + ret = radio802154_getsaddr(child, (FAR uint16_t*)arg); break; case PHY802154IOC_SET_EADDR: - ret = child->ops->seteaddr(child, (FAR uint8_t*)arg); + ret = radio802154_seteaddr(child, (FAR uint8_t*)arg); break; case PHY802154IOC_GET_EADDR: - ret = child->ops->geteaddr(child, (FAR uint8_t*)arg); + ret = radio802154_geteaddr(child, (FAR uint8_t*)arg); break; case PHY802154IOC_SET_PROMISC: - ret = child->ops->setpromisc(child, (bool)arg); + ret = radio802154_setpromisc(child, (bool)arg); break; case PHY802154IOC_GET_PROMISC: - ret = child->ops->getpromisc(child, (FAR bool*)arg); + ret = radio802154_getpromisc(child, (FAR bool*)arg); break; case PHY802154IOC_SET_DEVMODE: - ret = child->ops->setdevmode(child, (uint8_t)arg); + ret = radio802154_setdevmode(child, (uint8_t)arg); break; case PHY802154IOC_GET_DEVMODE: - ret = child->ops->getdevmode(child, (FAR uint8_t*)arg); + ret = radio802154_getdevmode(child, (FAR uint8_t*)arg); break; case PHY802154IOC_SET_TXPWR: - ret = child->ops->settxpower(child, (int32_t)arg); + ret = radio802154_settxpower(child, (int32_t)arg); break; case PHY802154IOC_GET_TXPWR: - ret = child->ops->gettxpower(child, (FAR int32_t*)arg); + ret = radio802154_gettxpower(child, (FAR int32_t*)arg); break; case PHY802154IOC_SET_CCA: - ret = child->ops->setcca(child, (FAR struct ieee802154_cca_s*)arg); + ret = radio802154_setcca(child, (FAR struct ieee802154_cca_s*)arg); break; case PHY802154IOC_GET_CCA: - ret = child->ops->getcca(child, (FAR struct ieee802154_cca_s*)arg); + ret = radio802154_getcca(child, (FAR struct ieee802154_cca_s*)arg); break; case PHY802154IOC_ENERGYDETECT: - ret = child->ops->energydetect(child, (FAR uint8_t*)arg); + ret = radio802154_energydetect(child, (FAR uint8_t*)arg); break; default: -- GitLab From 935cc4e3de2f06e64572d132e8851a00a3d43bb9 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 14 Apr 2017 13:30:36 -0600 Subject: [PATCH 447/990] Add a placeholder for nucleo-64 boards. Currently these are in various directories nucleo-f303re, nucleo-f334r8, and nucleo-l476rg but need to be consolidated here because these are all the same boards. --- Documentation/README.html | 2 + README.txt | 2 + configs/nucleo-64/README.txt | 141 +++++++++++++++++++++++++++++++++++ 3 files changed, 145 insertions(+) create mode 100644 configs/nucleo-64/README.txt diff --git a/Documentation/README.html b/Documentation/README.html index 8cc093715d..e360426ef5 100644 --- a/Documentation/README.html +++ b/Documentation/README.html @@ -161,6 +161,8 @@ nuttx/ | | `- README.txt | |- nucleo-144/ | | `- README.txt + | |- nucleo-64/ + | | `- README.txt | |- nucleo-f4x1re/ | | `- README.txt | |- nutiny-nuc120/ diff --git a/README.txt b/README.txt index af17a2334d..51306cfbb8 100644 --- a/README.txt +++ b/README.txt @@ -1548,6 +1548,8 @@ nuttx/ | | `- README.txt | |- nucleo-144/ | | `- README.txt + | |- nucleo-64/ + | | `- README.txt | |- nucleo-f4x1re/ | | `- README.txt | |- nutiny-nuc120/ diff --git a/configs/nucleo-64/README.txt b/configs/nucleo-64/README.txt new file mode 100644 index 0000000000..a33b49185d --- /dev/null +++ b/configs/nucleo-64/README.txt @@ -0,0 +1,141 @@ +README +====== + +This README discusses issues unique to NuttX configurations for the STMicro +Nucleo-64 board family + +Contents +======== + + - Nucleo-64 Boards + - Nucleo-F303RE + - Nucleo-F334R8 + - Nucleo-L476RG + - Development Environment + - Basic configuaration & build steps + - Hardware + - Button + - LED + - U[S]ARTs and Serial Consoles + - SPI + - SDIO - MMC + - Configurations + +Nucleo-64 Boards: +================= + +The Nucleo-64 is a standard board for use with several STM32 parts in the +LQFP64 package. Variants include + + Order code Targeted STM32 + ------------- -------------- + NUCLEO-F030R8 STM32F030R8T6 + NUCLEO-F070RB STM32F070RBT6 + NUCLEO-F072RB STM32F072RBT6 + NUCLEO-F091RC STM32F091RCT6 + NUCLEO-F103RB STM32F103RBT6 + NUCLEO-F302R8 STM32F302R8T6 + NUCLEO-F303RE STM32F303RET6 + NUCLEO-F334R8 STM32F334R8T6 + NUCLEO-F401RE STM32F401RET6 + NUCLEO-F410RB STM32F410RBT6 + NUCLEO-F411RE STM32F411RET6 + NUCLEO-F446RE STM32F446RET6 + NUCLEO-L053R8 STM32L053R8T6 + NUCLEO-L073RZ STM32L073RZT6 + NUCLEO-L152RE STM32L152RET6 + NUCLEO-L452RE STM32L452RET6 + NUCLEO-L476RG STM32L476RGT6 + +This directory is intended to support all Nucleo-64 variants since the +boards are identical, differing only in the installed part. This common +board design provides uniformity in the documentation from ST and should +allow us to quickly change configurations by just cloning a configuration +and changing the CPU choice and board initialization. Unfortunately for +the developer, the CPU specific information must be extracted from the +common information in the documentation. + +Please read the User Manaul UM1727: Getting started with STM32 Nucleo board +software development tools and take note of the Powering options for the +board (6.3 Power supply and power selection) and the Solder bridges based +hardware configuration changes that are configurable (6.11 Solder bridges). + +Common Board Features: +--------------------- + +The STM32 Nucleo board offers the following features: + + - STM32 microcontroller in LQFP64 package + - Two types of extension resources + Arduino™ Uno V3 connectivity + ST morpho extension pin headers for full access to all STM32 I/Os + - ARM® mbed™ (see http://mbed.org) + - On-board ST-LINK/V2-1 debugger and programmer with SWD connector + Selection-mode switch to use the kit as a standalone ST-LINK/V2-1 + - Flexible board power supply: + USB VBUS or external source (3.3V, 5V, 7 - 12V) + Power management access point + - Three LEDs: + USB communication (LD1), user LED (LD2), power LED (LD3) + - Two push-buttons: USER and RESET + - USB re-enumeration capability. Three different interfaces supported on USB: + Virtual COM port + Mass storage + Debug port + - Comprehensive free software HAL library including a variety of software examples + + Peripherals: 8 leds, 2 push button (3 LEDs, 1 button) under software + control + Debug: STLINK/V2-1 debugger/programmer Uses a STM32F103CB to + provide a ST-Link for programming, debug similar to the + OpenOcd FTDI function - USB to JTAG front-end. + + Expansion I/F: ST Zio and Extended Ardino and Morpho Headers + +Nucleo-F303RE +============= + +Nucleo-F334R8 +============= + +Nucleo-L476RG +============= + +Development Environment +======================= + + Either Linux or Cygwin on Windows can be used for the development environment. + The source has been built only using the GNU toolchain (see below). Other + toolchains will likely cause problems. + + All testing has been conducted using the GNU toolchain from ARM for Linux. + found here https://launchpad.net/gcc-arm-embedded/4.9/4.9-2015-q3-update/+download/gcc-arm-none-eabi-4_9-2015q3-20150921-linux.tar.bz2 + + If you change the default toolchain, then you may also have to modify the PATH in + the setenv.h file if your make cannot find the tools. + +Basic configuration & build steps +================================== + + A GNU GCC-based toolchain is assumed. The files */setenv.sh should + be modified to point to the correct path to the Cortex-M4 GCC toolchain (if + different from the default in your PATH variable). + + - Configures nuttx creating .config file in the nuttx directory. + cd tools && ./configure.sh nucleo-f746zg/nsh && cd .. + - Refreshes the .config file with the latest available configurations. + make oldconfig + - Select the features you want in the build. + make menuconfig + - Builds Nuttx with the features you selected. + make + +Hardware +======== + +Serial Console +============== + +Configurations +============== + -- GitLab From a8706d8afaa01b9eb723662f9db6c7acea72dbca Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 14 Apr 2017 13:58:25 -0600 Subject: [PATCH 448/990] wireless/ieee802154: Correct a few more compile issues. --- wireless/ieee802154/mac802154_device.c | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/wireless/ieee802154/mac802154_device.c b/wireless/ieee802154/mac802154_device.c index f4973d0a47..18d88cf9b3 100644 --- a/wireless/ieee802154/mac802154_device.c +++ b/wireless/ieee802154/mac802154_device.c @@ -377,6 +377,7 @@ static ssize_t mac802154dev_write(FAR struct file *filep, FAR struct inode *inode; FAR struct mac802154_devwrapper_s *dev; FAR struct ieee802154_data_req_s *req; + FAR struct ieee802154_frame_s *frame; struct mac802154dev_dwait_s dwait; int ret; @@ -396,7 +397,7 @@ static ssize_t mac802154dev_write(FAR struct file *filep, } DEBUGASSERT(buffer != NULL); - frame = *(FAR struct ieee802154_frame_s *)buffer; + frame = (FAR struct ieee802154_frame_s *)buffer; /* Get exclusive access to the driver structure */ @@ -414,11 +415,11 @@ static ssize_t mac802154dev_write(FAR struct file *filep, /* Link the wait struct */ dwait.mw_flink = dev->md_dwait; - dev->md_wait = &dwait; + dev->md_dwait = &dwait; /* Pass the request to the MAC layer */ - ret = dev->md_mac->ops.req_data(dev->md_mac, req); + ret = mac802154_req_data(dev->md_mac, req); mac802154dev_givesem(&dev->md_exclsem); @@ -430,7 +431,7 @@ static ssize_t mac802154dev_write(FAR struct file *filep, /* Wait for the DATA.confirm callback to be called for our handle */ - sem_wait(dwait.mw_sem); + sem_wait(&dwait.mw_sem); /* The unlinking of the wait struct happens inside the callback. This * is more efficient since it will already have to find the struct in @@ -506,7 +507,7 @@ void mac802154dev_conf_data(MACHANDLE mac, if (ret < 0) { wlerr("ERROR: mac802154dev_takesem failed: %d\n", ret); - return ret; + return; } /* Search to see if there is a dwait pending for this transaction */ -- GitLab From fffdba08356e087eca860b40523d257a9c701255 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 14 Apr 2017 17:15:58 -0600 Subject: [PATCH 449/990] Revert "Add a placeholder for nucleo-64 boards. Currently these are in various directories nucleo-f303re, nucleo-f334r8, and nucleo-l476rg but need to be consolidated here because these are all the same boards." This reverts commit 935cc4e3de2f06e64572d132e8851a00a3d43bb9. --- Documentation/README.html | 2 - README.txt | 2 - configs/nucleo-64/README.txt | 141 ----------------------------------- 3 files changed, 145 deletions(-) delete mode 100644 configs/nucleo-64/README.txt diff --git a/Documentation/README.html b/Documentation/README.html index e360426ef5..8cc093715d 100644 --- a/Documentation/README.html +++ b/Documentation/README.html @@ -161,8 +161,6 @@ nuttx/ | | `- README.txt | |- nucleo-144/ | | `- README.txt - | |- nucleo-64/ - | | `- README.txt | |- nucleo-f4x1re/ | | `- README.txt | |- nutiny-nuc120/ diff --git a/README.txt b/README.txt index 51306cfbb8..af17a2334d 100644 --- a/README.txt +++ b/README.txt @@ -1548,8 +1548,6 @@ nuttx/ | | `- README.txt | |- nucleo-144/ | | `- README.txt - | |- nucleo-64/ - | | `- README.txt | |- nucleo-f4x1re/ | | `- README.txt | |- nutiny-nuc120/ diff --git a/configs/nucleo-64/README.txt b/configs/nucleo-64/README.txt deleted file mode 100644 index a33b49185d..0000000000 --- a/configs/nucleo-64/README.txt +++ /dev/null @@ -1,141 +0,0 @@ -README -====== - -This README discusses issues unique to NuttX configurations for the STMicro -Nucleo-64 board family - -Contents -======== - - - Nucleo-64 Boards - - Nucleo-F303RE - - Nucleo-F334R8 - - Nucleo-L476RG - - Development Environment - - Basic configuaration & build steps - - Hardware - - Button - - LED - - U[S]ARTs and Serial Consoles - - SPI - - SDIO - MMC - - Configurations - -Nucleo-64 Boards: -================= - -The Nucleo-64 is a standard board for use with several STM32 parts in the -LQFP64 package. Variants include - - Order code Targeted STM32 - ------------- -------------- - NUCLEO-F030R8 STM32F030R8T6 - NUCLEO-F070RB STM32F070RBT6 - NUCLEO-F072RB STM32F072RBT6 - NUCLEO-F091RC STM32F091RCT6 - NUCLEO-F103RB STM32F103RBT6 - NUCLEO-F302R8 STM32F302R8T6 - NUCLEO-F303RE STM32F303RET6 - NUCLEO-F334R8 STM32F334R8T6 - NUCLEO-F401RE STM32F401RET6 - NUCLEO-F410RB STM32F410RBT6 - NUCLEO-F411RE STM32F411RET6 - NUCLEO-F446RE STM32F446RET6 - NUCLEO-L053R8 STM32L053R8T6 - NUCLEO-L073RZ STM32L073RZT6 - NUCLEO-L152RE STM32L152RET6 - NUCLEO-L452RE STM32L452RET6 - NUCLEO-L476RG STM32L476RGT6 - -This directory is intended to support all Nucleo-64 variants since the -boards are identical, differing only in the installed part. This common -board design provides uniformity in the documentation from ST and should -allow us to quickly change configurations by just cloning a configuration -and changing the CPU choice and board initialization. Unfortunately for -the developer, the CPU specific information must be extracted from the -common information in the documentation. - -Please read the User Manaul UM1727: Getting started with STM32 Nucleo board -software development tools and take note of the Powering options for the -board (6.3 Power supply and power selection) and the Solder bridges based -hardware configuration changes that are configurable (6.11 Solder bridges). - -Common Board Features: ---------------------- - -The STM32 Nucleo board offers the following features: - - - STM32 microcontroller in LQFP64 package - - Two types of extension resources - Arduino™ Uno V3 connectivity - ST morpho extension pin headers for full access to all STM32 I/Os - - ARM® mbed™ (see http://mbed.org) - - On-board ST-LINK/V2-1 debugger and programmer with SWD connector - Selection-mode switch to use the kit as a standalone ST-LINK/V2-1 - - Flexible board power supply: - USB VBUS or external source (3.3V, 5V, 7 - 12V) - Power management access point - - Three LEDs: - USB communication (LD1), user LED (LD2), power LED (LD3) - - Two push-buttons: USER and RESET - - USB re-enumeration capability. Three different interfaces supported on USB: - Virtual COM port - Mass storage - Debug port - - Comprehensive free software HAL library including a variety of software examples - - Peripherals: 8 leds, 2 push button (3 LEDs, 1 button) under software - control - Debug: STLINK/V2-1 debugger/programmer Uses a STM32F103CB to - provide a ST-Link for programming, debug similar to the - OpenOcd FTDI function - USB to JTAG front-end. - - Expansion I/F: ST Zio and Extended Ardino and Morpho Headers - -Nucleo-F303RE -============= - -Nucleo-F334R8 -============= - -Nucleo-L476RG -============= - -Development Environment -======================= - - Either Linux or Cygwin on Windows can be used for the development environment. - The source has been built only using the GNU toolchain (see below). Other - toolchains will likely cause problems. - - All testing has been conducted using the GNU toolchain from ARM for Linux. - found here https://launchpad.net/gcc-arm-embedded/4.9/4.9-2015-q3-update/+download/gcc-arm-none-eabi-4_9-2015q3-20150921-linux.tar.bz2 - - If you change the default toolchain, then you may also have to modify the PATH in - the setenv.h file if your make cannot find the tools. - -Basic configuration & build steps -================================== - - A GNU GCC-based toolchain is assumed. The files */setenv.sh should - be modified to point to the correct path to the Cortex-M4 GCC toolchain (if - different from the default in your PATH variable). - - - Configures nuttx creating .config file in the nuttx directory. - cd tools && ./configure.sh nucleo-f746zg/nsh && cd .. - - Refreshes the .config file with the latest available configurations. - make oldconfig - - Select the features you want in the build. - make menuconfig - - Builds Nuttx with the features you selected. - make - -Hardware -======== - -Serial Console -============== - -Configurations -============== - -- GitLab From 6d18300f981f34de6417d5cc596cc8d4f2409ab6 Mon Sep 17 00:00:00 2001 From: ahb Date: Sat, 15 Apr 2017 11:13:24 +0200 Subject: [PATCH 450/990] not a clean fix, but at least makes DHCP working with CONFIG_NETDEV_MULTINIC --- net/netdev/netdev_findbyaddr.c | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/net/netdev/netdev_findbyaddr.c b/net/netdev/netdev_findbyaddr.c index 25fbc02b8d..67ee9b558b 100644 --- a/net/netdev/netdev_findbyaddr.c +++ b/net/netdev/netdev_findbyaddr.c @@ -217,9 +217,11 @@ FAR struct net_driver_s *netdev_findby_ipv4addr(in_addr_t ripaddr) * broadcast packet out ALL local networks. I am not sure * of that and, in any event, there is nothing we can do * about that here. + * For now, simply return the first network interface in order + * to have working DHCP with CONFIG_NETDEV_MULTINIC. */ - return NULL; + return g_netdevices; } else { -- GitLab From 11d3db5c35d4cb0c0dde579cbe86e7a4ce062c54 Mon Sep 17 00:00:00 2001 From: Simon Piriou Date: Thu, 13 Apr 2017 20:31:39 +0200 Subject: [PATCH 451/990] photon: add sdpcm + thread support for wlan --- arch/arm/src/stm32/stm32_sdio.c | 3 +- drivers/wireless/ieee80211/Make.defs | 1 + .../wireless/ieee80211/bcm43362_constants.h | 84 ----- drivers/wireless/ieee80211/bcmf_driver.h | 12 + drivers/wireless/ieee80211/bcmf_sdio.c | 314 +++++++++++++++--- drivers/wireless/ieee80211/bcmf_sdio.h | 6 + drivers/wireless/ieee80211/bcmf_sdio_core.h | 1 + drivers/wireless/ieee80211/bcmf_sdpcm.c | 217 ++++++++++++ drivers/wireless/ieee80211/bcmf_sdpcm.h | 35 ++ 9 files changed, 543 insertions(+), 130 deletions(-) create mode 100644 drivers/wireless/ieee80211/bcmf_sdpcm.c create mode 100644 drivers/wireless/ieee80211/bcmf_sdpcm.h diff --git a/arch/arm/src/stm32/stm32_sdio.c b/arch/arm/src/stm32/stm32_sdio.c index d3a8884447..3f67c8b900 100644 --- a/arch/arm/src/stm32/stm32_sdio.c +++ b/arch/arm/src/stm32/stm32_sdio.c @@ -186,8 +186,7 @@ /* Big DTIMER setting */ -// #define SDIO_DTIMER_DATATIMEOUT (0x000fffff) -#define SDIO_DTIMER_DATATIMEOUT (0xffffffff) +#define SDIO_DTIMER_DATATIMEOUT (0x000fffff) /* DMA channel/stream configuration register settings. The following * must be selected. The DMA driver will select the remaining fields. diff --git a/drivers/wireless/ieee80211/Make.defs b/drivers/wireless/ieee80211/Make.defs index b18d123546..440e5a9f23 100644 --- a/drivers/wireless/ieee80211/Make.defs +++ b/drivers/wireless/ieee80211/Make.defs @@ -43,6 +43,7 @@ ifeq ($(CONFIG_DRIVERS_IEEE80211),y) ifeq ($(CONFIG_IEEE80211_BROADCOM_FULLMAC_SDIO),y) CSRCS += bcmf_sdio.c CSRCS += bcmf_core.c + CSRCS += bcmf_sdpcm.c CSRCS += mmc_sdio.c endif diff --git a/drivers/wireless/ieee80211/bcm43362_constants.h b/drivers/wireless/ieee80211/bcm43362_constants.h index 929bdf4042..0911bdfbe8 100644 --- a/drivers/wireless/ieee80211/bcm43362_constants.h +++ b/drivers/wireless/ieee80211/bcm43362_constants.h @@ -61,94 +61,10 @@ /* Chipcommon registers */ #define CHIPCOMMON_GPIO_CONTROL ((uint32_t) (CHIPCOMMON_BASE_ADDRESS + 0x6C) ) -/****************************************************** - * SDIO Constants - ******************************************************/ -/* CurrentSdiodProgGuide r23 */ - -/* Base registers */ -#define SDIO_CORE ((uint32_t) (SDIO_BASE_ADDRESS + 0x00) ) -#define SDIO_INT_STATUS ((uint32_t) (SDIO_BASE_ADDRESS + 0x20) ) -#define SDIO_TO_SB_MAILBOX ((uint32_t) (SDIO_BASE_ADDRESS + 0x40) ) -#define SDIO_TO_SB_MAILBOX_DATA ((uint32_t) (SDIO_BASE_ADDRESS + 0x48) ) -#define SDIO_TO_HOST_MAILBOX_DATA ((uint32_t) (SDIO_BASE_ADDRESS + 0x4C) ) -#define SDIO_TO_SB_MAIL_BOX ((uint32_t) (SDIO_BASE_ADDRESS + 0x40) ) -#define SDIO_INT_HOST_MASK ((uint32_t) (SDIO_BASE_ADDRESS + 0x24) ) -#define SDIO_FUNCTION_INT_MASK ((uint32_t) (SDIO_BASE_ADDRESS + 0x34) ) - -/* SDIO Function 0 (SDIO Bus) register addresses */ - -/* SDIO Device CCCR offsets */ -/* TODO: What does CIS/CCCR stand for? */ -/* CCCR accesses do not require backpane clock */ -#define SDIOD_CCCR_UHS_I ( (uint32_t) 0x14 ) /* UHS-I Support */ -#define SDIOD_CCCR_DRIVE ( (uint32_t) 0x15 ) /* Drive Strength */ -#define SDIOD_CCCR_INTEXT ( (uint32_t) 0x16 ) /* Interrupt Extension */ -#define SDIOD_SEP_INT_CTL ( (uint32_t) 0xF2 ) /* Separate Interrupt Control*/ -#define SDIOD_CCCR_F1INFO ( (uint32_t) 0x100 ) /* Function 1 (Backplane) Info */ -#define SDIOD_CCCR_F1HP ( (uint32_t) 0x102 ) /* Function 1 (Backplane) High Power */ -#define SDIOD_CCCR_F1CISPTR_0 ( (uint32_t) 0x109 ) /* Function 1 (Backplane) CIS Base Address Pointer Register 0 (LSB) */ -#define SDIOD_CCCR_F1CISPTR_1 ( (uint32_t) 0x10A ) /* Function 1 (Backplane) CIS Base Address Pointer Register 1 */ -#define SDIOD_CCCR_F1CISPTR_2 ( (uint32_t) 0x10B ) /* Function 1 (Backplane) CIS Base Address Pointer Register 2 (MSB - only bit 1 valid) */ -#define SDIOD_CCCR_F1BLKSIZE_0 ( (uint32_t) 0x110 ) /* Function 1 (Backplane) SDIO Block Size Register 0 (LSB) */ -#define SDIOD_CCCR_F1BLKSIZE_1 ( (uint32_t) 0x111 ) /* Function 1 (Backplane) SDIO Block Size Register 1 (MSB) */ -#define SDIOD_CCCR_F2INFO ( (uint32_t) 0x200 ) /* Function 2 (WLAN Data FIFO) Info */ -#define SDIOD_CCCR_F2HP ( (uint32_t) 0x202 ) /* Function 2 (WLAN Data FIFO) High Power */ -#define SDIOD_CCCR_F2CISPTR_0 ( (uint32_t) 0x209 ) /* Function 2 (WLAN Data FIFO) CIS Base Address Pointer Register 0 (LSB) */ -#define SDIOD_CCCR_F2CISPTR_1 ( (uint32_t) 0x20A ) /* Function 2 (WLAN Data FIFO) CIS Base Address Pointer Register 1 */ -#define SDIOD_CCCR_F2CISPTR_2 ( (uint32_t) 0x20B ) /* Function 2 (WLAN Data FIFO) CIS Base Address Pointer Register 2 (MSB - only bit 1 valid) */ -#define SDIOD_CCCR_F2BLKSIZE_0 ( (uint32_t) 0x210 ) /* Function 2 (WLAN Data FIFO) SDIO Block Size Register 0 (LSB) */ -#define SDIOD_CCCR_F2BLKSIZE_1 ( (uint32_t) 0x211 ) /* Function 2 (WLAN Data FIFO) SDIO Block Size Register 1 (MSB) */ -#define SDIOD_CCCR_F3INFO ( (uint32_t) 0x300 ) /* Function 3 (Bluetooth Data FIFO) Info */ -#define SDIOD_CCCR_F3HP ( (uint32_t) 0x302 ) /* Function 3 (Bluetooth Data FIFO) High Power */ -#define SDIOD_CCCR_F3CISPTR_0 ( (uint32_t) 0x309 ) /* Function 3 (Bluetooth Data FIFO) CIS Base Address Pointer Register 0 (LSB) */ -#define SDIOD_CCCR_F3CISPTR_1 ( (uint32_t) 0x30A ) /* Function 3 (Bluetooth Data FIFO) CIS Base Address Pointer Register 1 */ -#define SDIOD_CCCR_F3CISPTR_2 ( (uint32_t) 0x30B ) /* Function 3 (Bluetooth Data FIFO) CIS Base Address Pointer Register 2 (MSB - only bit 1 valid) */ -#define SDIOD_CCCR_F3BLKSIZE_0 ( (uint32_t) 0x310 ) /* Function 3 (Bluetooth Data FIFO) SDIO Block Size Register 0 (LSB) */ -#define SDIOD_CCCR_F3BLKSIZE_1 ( (uint32_t) 0x311 ) /* Function 3 (Bluetooth Data FIFO) SDIO Block Size Register 1 (MSB) */ - - -/* SDIO Function 1 (Backplane) register addresses */ -/* Addresses 0x00000000 - 0x0000FFFF are directly access the backplane - * throught the backplane window. Addresses above 0x0000FFFF are - * registers relating to backplane access, and do not require a backpane - * clock to access them - */ -#define SDIO_GPIO_SELECT ( (uint32_t) 0x10005 ) -#define SDIO_GPIO_OUTPUT ( (uint32_t) 0x10006 ) -#define SDIO_GPIO_ENABLE ( (uint32_t) 0x10007 ) -#define SDIO_FUNCTION2_WATERMARK ( (uint32_t) 0x10008 ) -#define SDIO_DEVICE_CONTROL ( (uint32_t) 0x10009 ) -#define SDIO_BACKPLANE_ADDRESS_LOW ( (uint32_t) 0x1000A ) -#define SDIO_BACKPLANE_ADDRESS_MID ( (uint32_t) 0x1000B ) -#define SDIO_BACKPLANE_ADDRESS_HIGH ( (uint32_t) 0x1000C ) -#define SDIO_FRAME_CONTROL ( (uint32_t) 0x1000D ) -#define SDIO_CHIP_CLOCK_CSR ( (uint32_t) 0x1000E ) -#define SDIO_PULL_UP ( (uint32_t) 0x1000F ) -#define SDIO_READ_FRAME_BC_LOW ( (uint32_t) 0x1001B ) -#define SDIO_READ_FRAME_BC_HIGH ( (uint32_t) 0x1001C ) - -#define I_HMB_SW_MASK ( (uint32_t) 0x000000F0 ) -#define I_HMB_FRAME_IND ( 1<<6 ) -#define FRAME_AVAILABLE_MASK I_HMB_SW_MASK - /****************************************************** * Bit Masks ******************************************************/ -/* SDIO_FRAME_CONTROL Bits */ -#define SFC_RF_TERM ( (uint32_t) (1 << 0) ) /* Read Frame Terminate */ -#define SFC_WF_TERM ( (uint32_t) (1 << 1) ) /* Write Frame Terminate */ -#define SFC_CRC4WOOS ( (uint32_t) (1 << 2) ) /* HW reports CRC error for write out of sync */ -#define SFC_ABORTALL ( (uint32_t) (1 << 3) ) /* Abort cancels all in-progress frames */ - -/* SDIO_TO_SB_MAIL_BOX bits corresponding to intstatus bits */ -#define SMB_NAK ( (uint32_t) (1 << 0) ) /* To SB Mailbox Frame NAK */ -#define SMB_INT_ACK ( (uint32_t) (1 << 1) ) /* To SB Mailbox Host Interrupt ACK */ -#define SMB_USE_OOB ( (uint32_t) (1 << 2) ) /* To SB Mailbox Use OOB Wakeup */ -#define SMB_DEV_INT ( (uint32_t) (1 << 3) ) /* To SB Mailbox Miscellaneous Interrupt */ - - #define WL_CHANSPEC_BAND_MASK (0xf000) #define WL_CHANSPEC_BAND_5G (0x1000) #define WL_CHANSPEC_BAND_2G (0x2000) diff --git a/drivers/wireless/ieee80211/bcmf_driver.h b/drivers/wireless/ieee80211/bcmf_driver.h index 0156e9021d..6225f7396e 100644 --- a/drivers/wireless/ieee80211/bcmf_driver.h +++ b/drivers/wireless/ieee80211/bcmf_driver.h @@ -36,6 +36,7 @@ #ifndef __DRIVERS_WIRELESS_IEEE80211_BCMF_DRIVER_H #define __DRIVERS_WIRELESS_IEEE80211_BCMF_DRIVER_H +#include #include /* This structure contains the unique state of the Broadcom FullMAC driver */ @@ -49,6 +50,17 @@ struct bcmf_dev_s uint32_t (*get_core_base_address)(unsigned int core); /* Get chip specific base address for evey cores */ + + sem_t sem; /* Semaphore for processing thread event */ + struct wdog_s *waitdog; /* Processing thread waitdog */ + bool ready; /* Current device status */ + bool sleeping; /* Current sleep status */ + volatile bool irq_pending; /* True if interrupt is pending */ + uint32_t intstatus; /* Copy of device current interrupt status */ + + uint8_t max_seq; /* Maximum transmit sequence allowed */ + uint8_t tx_seq; /* Transmit sequence number (next) */ + uint8_t rx_seq; /* Receive sequence number (expected) */ }; #endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_DRIVER_H */ diff --git a/drivers/wireless/ieee80211/bcmf_sdio.c b/drivers/wireless/ieee80211/bcmf_sdio.c index 5fecd45cb4..9d5a26377c 100644 --- a/drivers/wireless/ieee80211/bcmf_sdio.c +++ b/drivers/wireless/ieee80211/bcmf_sdio.c @@ -49,6 +49,7 @@ #include #include #include +#include #include #include @@ -56,6 +57,7 @@ #include "bcmf_sdio.h" #include "bcmf_core.h" +#include "bcmf_sdpcm.h" /**************************************************************************** * Pre-processor Definitions @@ -65,6 +67,11 @@ #define BCMF_DEVICE_START_DELAY_MS 10 #define BCMF_CLOCK_SETUP_DELAY_MS 500 +#define BCMF_THREAD_NAME "bcmf" +#define BCMF_THREAD_STACK_SIZE 2048 + +#define BCMF_WAITDOG_TIMEOUT_TICK (5*CLOCKS_PER_SEC) + /**************************************************************************** * Private Types ****************************************************************************/ @@ -80,6 +87,16 @@ static int bcmf_chipinitialize(FAR struct bcmf_dev_s *priv); static int bcmf_oob_irq(int irq, FAR void *context, FAR void *arg); +static int bcmf_sdio_bus_sleep(FAR struct bcmf_dev_s *priv, bool sleep); + +static void bcmf_sdio_waitdog_timeout(int argc, wdparm_t arg1, ...); +static int bcmf_sdio_thread(int argc, char **argv); + +static int bcmf_sdio_find_block_size(unsigned int size); + +/* FIXME remove */ +FAR struct bcmf_dev_s *g_sdio_priv; + /**************************************************************************** * Private Data ****************************************************************************/ @@ -90,7 +107,79 @@ static int bcmf_oob_irq(int irq, FAR void *context, FAR void *arg); int bcmf_oob_irq(int irq, FAR void *context, FAR void *arg) { - /* TODO */ + FAR struct bcmf_dev_s *priv = (struct bcmf_dev_s*)arg; + + if (priv->ready) + { + /* Signal bmcf thread */ + priv->irq_pending = true; + + sem_post(&priv->sem); + } + return OK; +} + +int bcmf_sdio_bus_sleep(FAR struct bcmf_dev_s *priv, bool sleep) +{ + int ret; + int loops; + uint8_t value; + + _info("request %s currently %s\n", + (sleep ? "SLEEP" : "WAKE"), + (priv->sleeping ? "SLEEP" : "WAKE")); + + if (priv->sleeping == sleep) + { + return OK; + } + + if (sleep) + { + priv->sleeping = true; + return bcmf_write_reg(priv, 1, SBSDIO_FUNC1_CHIPCLKCSR, 0); + } + else + { + /* Request HT Avail */ + + ret = bcmf_write_reg(priv, 1, SBSDIO_FUNC1_CHIPCLKCSR, + SBSDIO_HT_AVAIL_REQ | SBSDIO_FORCE_HT); + if (ret != OK) + { + _err("HT Avail request failed %d\n", ret); + return ret; + } + + /* Wait for High Troughput clock */ + + loops = 20; + while (--loops > 0) + { + up_mdelay(1); + ret = bcmf_read_reg(priv, 1, SBSDIO_FUNC1_CHIPCLKCSR, &value); + + if (ret != OK) + { + return ret; + } + + if (value & SBSDIO_HT_AVAIL) + { + /* High Throughput clock is ready */ + break; + } + } + + if (loops <= 0) + { + _err("HT clock not ready\n"); + return -ETIMEDOUT; + } + + priv->sleeping = false; + } + return OK; } @@ -101,7 +190,6 @@ int bcmf_oob_irq(int irq, FAR void *context, FAR void *arg) int bcmf_probe(FAR struct bcmf_dev_s *priv) { int ret; - uint8_t value; /* Probe sdio card compatible device */ @@ -248,6 +336,13 @@ int bcmf_businitialize(FAR struct bcmf_dev_s *priv) return ret; } + return OK; +} + +int bcmf_bus_setup_interrupts(FAR struct bcmf_dev_s *priv) +{ + int ret; + /* Configure gpio interrupt pin */ bcmf_board_setup_oob_irq(priv->minor, bcmf_oob_irq, (void*)priv); @@ -274,32 +369,12 @@ int bcmf_businitialize(FAR struct bcmf_dev_s *priv) return ret; } - _info("wait high throughput clock\n"); - - /* Wait for High Troughput clock to be sure function 2 is running */ - - loops = 10; - while (--loops > 0) - { - up_mdelay(10); - ret = bcmf_read_reg(priv, 1, SBSDIO_FUNC1_CHIPCLKCSR, &value); - - if (ret != OK) - { - return ret; - } - - if (value & SBSDIO_HT_AVAIL) - { - /* High Throughput clock is ready */ - break; - } - } + /* Wake up chip to be sure function 2 is running */ - if (loops <= 0) + ret = bcmf_sdio_bus_sleep(priv, false); + if (ret != OK) { - _err("HT clock not ready\n"); - return -ETIMEDOUT; + return ret; } /* FN2 successfully enabled, set core and enable interrupts */ @@ -361,6 +436,22 @@ void bcmf_hwuninitialize(FAR struct bcmf_dev_s *priv) bcmf_board_reset(priv->minor, true); } +int bcmf_sdio_find_block_size(unsigned int size) +{ + int ret = 0; + int size_copy = size; + while (size_copy) { + size_copy >>= 1; + ret++; + } + + if (size & (size-1)) + { + return 1< 0 && len % 64 == 0) + if (len >= 64) { - blocklen = 64; - nblocks = len / 64; - } - else if (len > 20) - { - // FIXME + /* Use block mode */ + blocklen = 64; nblocks = (len+63) / 64; } else { - blocklen = len; + /* Use byte mode */ + + blocklen = bcmf_sdio_find_block_size(len); nblocks = 0; } - // _info("try extended %d %d %d\n", len, blocklen, nblocks); + return sdio_io_rw_extended(priv->sdio_dev, write, function, address, true, buf, blocklen, nblocks); - - // return -EINVAL; } /**************************************************************************** @@ -460,6 +552,24 @@ int bcmf_sdio_initialize(int minor, FAR struct sdio_dev_s *dev) memset(priv, 0, sizeof(*priv)); priv->sdio_dev = dev; priv->minor = minor; + priv->ready = false; + priv->sleeping = true; + + if ((ret = sem_init(&priv->sem, 0, 0)) != OK) + { + goto exit_free_priv; + } + if ((ret = sem_setprotocol(&priv->sem, SEM_PRIO_NONE)) != OK) + { + goto exit_free_priv; + } + + priv->waitdog = wd_create(); + if (!priv->waitdog) + { + ret = -ENOMEM; + goto exit_free_priv; + } /* Initialize device hardware */ @@ -467,7 +577,7 @@ int bcmf_sdio_initialize(int minor, FAR struct sdio_dev_s *dev) if (ret != OK) { - goto exit_free_priv; + goto exit_free_waitdog; } /* Probe device */ @@ -488,10 +598,37 @@ int bcmf_sdio_initialize(int minor, FAR struct sdio_dev_s *dev) goto exit_uninit_hw; } - /* FIXME wait for the chip to be ready to receive commands */ up_mdelay(100); + priv->ready = true; + + ret = bcmf_bus_setup_interrupts(priv); + if (ret != OK) + { + goto exit_uninit_hw; + } + + /* FIXME global variable for now */ + g_sdio_priv = priv; + + /* Start the waitdog timer */ + + wd_start(priv->waitdog, BCMF_WAITDOG_TIMEOUT_TICK, bcmf_sdio_waitdog_timeout, 0); + + /* Spawn bcmf daemon thread */ + + ret = kernel_thread(BCMF_THREAD_NAME, SCHED_PRIORITY_MAX, + BCMF_THREAD_STACK_SIZE, bcmf_sdio_thread, + (FAR char * const *)NULL); + + if (ret <= 0) + { + _err("Cannot spawn bcmf thread\n"); + ret = -EBADE; + goto exit_uninit_hw; + } + /* Device is up and running TODO Create a wlan device name and register network driver here */ @@ -499,9 +636,11 @@ int bcmf_sdio_initialize(int minor, FAR struct sdio_dev_s *dev) exit_uninit_hw: bcmf_hwuninitialize(priv); - +exit_free_waitdog: + // TODO exit_free_priv: kmm_free(priv); + priv->ready = false; return ret; } @@ -530,3 +669,90 @@ int bcmf_chipinitialize(FAR struct bcmf_dev_s *priv) } return OK; } + +void bcmf_sdio_waitdog_timeout(int argc, wdparm_t arg1, ...) +{ + FAR struct bcmf_dev_s *priv = g_sdio_priv; + + /* Notify bcmf thread */ + sem_post(&priv->sem); +} + +int bcmf_sdio_thread(int argc, char **argv) +{ + int ret; + FAR struct bcmf_dev_s *priv = g_sdio_priv; + + _info("Enter\n"); + + /* FIXME wait for the chip to be ready to receive commands */ + + up_mdelay(50); + + while (1) + { + /* Wait for event (device interrupt, user request or waitdog timer) */ + + ret = sem_wait(&priv->sem); + if (ret != OK) + { + _err("Error while waiting for semaphore\n"); + break; + } + + /* Restart the waitdog timer */ + + wd_start(priv->waitdog, BCMF_WAITDOG_TIMEOUT_TICK, + bcmf_sdio_waitdog_timeout, 0); + + /* Wake up device */ + + bcmf_sdio_bus_sleep(priv, false); + + if (priv->irq_pending) + { + /* Woken up by interrupt, read device status */ + + priv->irq_pending = false; + + _info("process irq\n"); + + bcmf_read_sbregw(priv, + CORE_BUS_REG(priv->get_core_base_address(SDIOD_CORE_ID), + intstatus), &priv->intstatus); + + /* Clear interrupts */ + + bcmf_write_sbregw(priv, + CORE_BUS_REG(priv->get_core_base_address(SDIOD_CORE_ID), + intstatus), priv->intstatus); + _info("intstatus %x\n", priv->intstatus); + } + + /* On frame indication, read available frames */ + + if (priv->intstatus & I_HMB_FRAME_IND) + { + _info("Frames available\n"); + + do + { + ret = bcmf_sdpcm_readframe(priv); + } while (ret == OK); + + if (ret == -ENODATA) + { + /* All frames processed */ + _info("All frames processed\n"); + priv->intstatus &= ~I_HMB_FRAME_IND; + } + } + + // TODO send all queued frames + + /* If we're done for now, turn off clock request. */ + + bcmf_sdio_bus_sleep(priv, true); + } + return 0; +} \ No newline at end of file diff --git a/drivers/wireless/ieee80211/bcmf_sdio.h b/drivers/wireless/ieee80211/bcmf_sdio.h index 614f62ab21..bb66daca25 100644 --- a/drivers/wireless/ieee80211/bcmf_sdio.h +++ b/drivers/wireless/ieee80211/bcmf_sdio.h @@ -8,6 +8,12 @@ #include #include +/* FIXME: Low level bus data transfer function + * To avoid bus error, len will be aligned to: + * - upper power of 2 iflen is lesser than 64 + * - upper 64 bytes block if len is greater than 64 + */ + int bcmf_transfer_bytes(FAR struct bcmf_dev_s *priv, bool write, uint8_t function, uint32_t address, uint8_t *buf, unsigned int len); diff --git a/drivers/wireless/ieee80211/bcmf_sdio_core.h b/drivers/wireless/ieee80211/bcmf_sdio_core.h index a3aca72108..c6ad612c11 100644 --- a/drivers/wireless/ieee80211/bcmf_sdio_core.h +++ b/drivers/wireless/ieee80211/bcmf_sdio_core.h @@ -59,6 +59,7 @@ #define SSB_TMSLOW_BE 0x80000000 /* BIST Enable */ #define I_HMB_SW_MASK ( (uint32_t) 0x000000F0 ) +#define I_HMB_FRAME_IND ( 1<<6 ) enum { CHIPCOMMON_CORE_ID, diff --git a/drivers/wireless/ieee80211/bcmf_sdpcm.c b/drivers/wireless/ieee80211/bcmf_sdpcm.c new file mode 100644 index 0000000000..c7c3facc57 --- /dev/null +++ b/drivers/wireless/ieee80211/bcmf_sdpcm.c @@ -0,0 +1,217 @@ +/**************************************************************************** + * drivers/wireless/ieee80211/bcmf_sdpcm.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Simon Piriou + * + * 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 "bcmf_sdio.h" +#include "bcmf_core.h" +#include "bcmf_sdpcm.h" + +/* SDA_FRAMECTRL */ +#define SFC_RF_TERM (1 << 0) /* Read Frame Terminate */ +#define SFC_WF_TERM (1 << 1) /* Write Frame Terminate */ +#define SFC_CRC4WOOS (1 << 2) /* CRC error for write out of sync */ +#define SFC_ABORTALL (1 << 3) /* Abort all in-progress frames */ + +/* tosbmailbox bits corresponding to intstatus bits */ +#define SMB_NAK (1 << 0) /* Frame NAK */ +#define SMB_INT_ACK (1 << 1) /* Host Interrupt ACK */ +#define SMB_USE_OOB (1 << 2) /* Use OOB Wakeup */ +#define SMB_DEV_INT (1 << 3) /* Miscellaneous Interrupt */ + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static int bcmf_sdpcm_rxfail(FAR struct bcmf_dev_s *priv, bool retry); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +int bcmf_sdpcm_rxfail(FAR struct bcmf_dev_s *priv, bool retry) +{ + /* issue abort command for F2 through F0 */ + + bcmf_write_reg(priv, 0, SDIO_CCCR_IOABORT, 2); + + bcmf_write_reg(priv, 1, SBSDIO_FUNC1_FRAMECTRL, SFC_RF_TERM); + + /* TODO Wait until the packet has been flushed (device/FIFO stable) */ + + /* Send NAK to retry to read frame */ + if (retry) + { + bcmf_write_sbregb(priv, + CORE_BUS_REG(priv->get_core_base_address(SDIOD_CORE_ID), + tosbmailbox), SMB_NAK); + } + + return 0; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +int bcmf_sdpcm_process_header(FAR struct bcmf_dev_s *priv, + struct bcmf_sdpcm_header *header) +{ + uint16_t len; + + len = header->frametag[0]; + + if (header->data_offset < sizeof(struct bcmf_sdpcm_header) || + header->data_offset > len) + { + _err("Invalid data offset\n"); + bcmf_sdpcm_rxfail(priv, false); + return -ENXIO; + } + + /* Update tx credits */ + + _info("update credit %x %x %x\n", header->credit, + priv->tx_seq, priv->max_seq); + + if (header->credit - priv->tx_seq > 0x40) + { + _err("seq %d: max tx seq number error\n", priv->tx_seq); + priv->max_seq = priv->tx_seq + 2; + } + else + { + priv->max_seq = header->credit; + } + + return OK; +} + +// FIXME remove +uint8_t tmp_buffer[512]; +int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv) +{ + int ret; + uint16_t len, checksum; + struct bcmf_sdpcm_header *header = (struct bcmf_sdpcm_header*)tmp_buffer; + + /* Read header */ + + ret = bcmf_transfer_bytes(priv, false, 2, 0, (uint8_t*)header, 4); + if (ret != OK) + { + _info("failread size\n"); + ret = -EIO; + goto exit_abort; + } + + len = header->frametag[0]; + checksum = header->frametag[1]; + + /* All zero means no more to read */ + + if (!(len | checksum)) + { + return -ENODATA; + } + + if (((~len & 0xffff) ^ checksum) || len < sizeof(struct bcmf_sdpcm_header)) + { + _err("Invalid header checksum or len %x %x\n", len, checksum); + ret = -EIO; + goto exit_abort; + } + + // FIXME define for size + if (len > 512) + { + _err("Frame is too large, cancel %d\n", len); + ret = -ENOMEM; + goto exit_abort; + } + + /* Read remaining frame data */ + + ret = bcmf_transfer_bytes(priv, false, 2, 0, (uint8_t*)header+4, len - 4); + if (ret != OK) + { + ret = -EIO; + goto exit_abort; + } + + /* Process and validate header */ + + ret = bcmf_sdpcm_process_header(priv, header); + if (ret != OK) + { + _err("Error while processing header %d\n", ret); + } + + return ret; + +exit_abort: + bcmf_sdpcm_rxfail(priv, false); + return ret; +} + +int bcmf_sdpcm_iovar_data_get(FAR struct bcmf_dev_s *priv, char *name, + void *data, unsigned int len) +{ + // TODO implement + return -EINVAL; +} diff --git a/drivers/wireless/ieee80211/bcmf_sdpcm.h b/drivers/wireless/ieee80211/bcmf_sdpcm.h new file mode 100644 index 0000000000..2f2844e651 --- /dev/null +++ b/drivers/wireless/ieee80211/bcmf_sdpcm.h @@ -0,0 +1,35 @@ +#ifndef __DRIVERS_WIRELESS_IEEE80211_BCMF_SDPCM_H +#define __DRIVERS_WIRELESS_IEEE80211_BCMF_SDPCM_H + +#include "bcmf_driver.h" +#include + +struct bcmf_sdpcm_header { + uint16_t frametag[2]; + uint8_t sequence; + uint8_t channel_flags; + uint8_t next_length; + uint8_t data_offset; + uint8_t flow_control; + uint8_t credit; + uint16_t padding; +}; + +struct bcmf_sdpcm_cdc_dcmd { + struct bcmf_sdpcm_header header; + uint32_t cmd; /* dongle command value */ + uint32_t len; /* lower 16: output buflen; + * upper 16: input buflen (excludes header) */ + uint32_t flags; /* flag defns given below */ + uint32_t status; /* status code returned from the device */ +}; + +int bcmf_sdpcm_process_header(FAR struct bcmf_dev_s *priv, + struct bcmf_sdpcm_header *header); + +int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv); + +int bcmf_sdpcm_iovar_data_get(FAR struct bcmf_dev_s *priv, char *name, + void *data, unsigned int len); + +#endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_SDPCM_H */ \ No newline at end of file -- GitLab From eee89102d8a8f07738895690e1d974b55beba411 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 15 Apr 2017 06:00:42 -0600 Subject: [PATCH 452/990] networking: IPv4 change of last PR should also be applied to corresponding IPv6 logic. --- net/netdev/netdev_findbyaddr.c | 14 ++++++++++---- 1 file changed, 10 insertions(+), 4 deletions(-) diff --git a/net/netdev/netdev_findbyaddr.c b/net/netdev/netdev_findbyaddr.c index 67ee9b558b..6aea450393 100644 --- a/net/netdev/netdev_findbyaddr.c +++ b/net/netdev/netdev_findbyaddr.c @@ -1,7 +1,7 @@ /**************************************************************************** * net/netdev/netdev_findbyaddr.c * - * Copyright (C) 2007-2009, 2014-2015 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009, 2014-2015, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -217,8 +217,10 @@ FAR struct net_driver_s *netdev_findby_ipv4addr(in_addr_t ripaddr) * broadcast packet out ALL local networks. I am not sure * of that and, in any event, there is nothing we can do * about that here. - * For now, simply return the first network interface in order - * to have working DHCP with CONFIG_NETDEV_MULTINIC. + * + * REVISIT: For now, arbitrarily return the first network + * interface in the list of network devices. The broadcast + * will be sent on that device only. */ return g_netdevices; @@ -337,9 +339,13 @@ FAR struct net_driver_s *netdev_findby_ipv6addr(const net_ipv6addr_t ripaddr) * broadcast packet out ALL local networks. I am not sure * of that and, in any event, there is nothing we can do * about that here. + * + * REVISIT: For now, arbitrarily return the first network + * interface in the list of network devices. The broadcast + * will be sent on that device only. */ - return NULL; + return g_netdevices; } else { -- GitLab From 0652cbfd12ac20915bce9ba13b9a9ff1632430e3 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 15 Apr 2017 07:40:14 -0600 Subject: [PATCH 453/990] Update TODO list and README files. --- Documentation/README.html | 8 +++++++- README.txt | 6 ++++++ TODO | 18 ++++++++++++++++-- configs/nucleo-f303re/README.txt | 26 ++++++++++++++++++++++++++ configs/nucleo-f334r8/README.txt | 26 ++++++++++++++++++++++++++ configs/nucleo-f4x1re/README.txt | 28 ++++++++++++++++++++++++++++ configs/nucleo-l476rg/README.txt | 28 ++++++++++++++++++++++++++++ 7 files changed, 137 insertions(+), 3 deletions(-) create mode 100644 configs/nucleo-f303re/README.txt create mode 100644 configs/nucleo-f334r8/README.txt diff --git a/Documentation/README.html b/Documentation/README.html index 8cc093715d..2fb8e115e1 100644 --- a/Documentation/README.html +++ b/Documentation/README.html @@ -8,7 +8,7 @@

NuttX README Files

-

Last Updated: April 8, 2017

+

Last Updated: April 15, 2017

@@ -161,8 +161,14 @@ nuttx/ | | `- README.txt | |- nucleo-144/ | | `- README.txt + | |- nucleo-f303re/ + | | `- README.txt + | |- nucleo-f334r8/ + | | `- README.txt | |- nucleo-f4x1re/ | | `- README.txt + | |- nucleo-l476rg/ + | | `- README.txt | |- nutiny-nuc120/ | | `- README.txt | |- olimex-efm32g880f129-stk/ diff --git a/README.txt b/README.txt index af17a2334d..fc318715b3 100644 --- a/README.txt +++ b/README.txt @@ -1548,8 +1548,14 @@ nuttx/ | | `- README.txt | |- nucleo-144/ | | `- README.txt + | |- nucleo-f303re/ + | | `- README.txt + | |- nucleo-f334r8/ + | | `- README.txt | |- nucleo-f4x1re/ | | `- README.txt + | |- nucleo-l476rg/ + | | `- README.txt | |- nutiny-nuc120/ | | `- README.txt | |- olimex-efm32g880f129-stk/ diff --git a/TODO b/TODO index 93db26ced4..b85d480335 100644 --- a/TODO +++ b/TODO @@ -1,4 +1,4 @@ -NuttX TODO List (Last updated April 12, 2017) +NuttX TODO List (Last updated April 15, 2017) ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ This file summarizes known NuttX bugs, limitations, inconsistencies with @@ -19,7 +19,7 @@ nuttx/: (8) Kernel/Protected Build (3) C++ Support (6) Binary loaders (binfmt/) - (14) Network (net/, drivers/net) + (15) Network (net/, drivers/net) (4) USB (drivers/usbdev, drivers/usbhost) (0) Other drivers (drivers/) (12) Libraries (libc/, libm/) @@ -1145,6 +1145,20 @@ o Network (net/, drivers/net) Status: Open Priority: Low. Really just as aesthetic maintainability issue. + Title: BROADCAST WITH MULTIPLE NETWORK INTERFACES + Description: There is currently no mechanism to send a broadcast packet + out through several network interfaces. Currently packets + can be sent to only one device. Logic in netdev_findby_ipvXaddr() + currently just selects the first device in the list of + devices; only that device will receive broadcast packets. + Status: Open + Priority: High if you require broadcast on multiple networks. There is + no simple solution known at this time, however. Perhaps + netdev_findby_ipvXaddr() should return a list of devices rather + than a single device? All upstream logic would then have to + deal with a list of devices. That would be a huge effect and + certainly doesn't dount as a "simple solution". + o USB (drivers/usbdev, drivers/usbhost) ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/configs/nucleo-f303re/README.txt b/configs/nucleo-f303re/README.txt new file mode 100644 index 0000000000..b8f1c239d7 --- /dev/null +++ b/configs/nucleo-f303re/README.txt @@ -0,0 +1,26 @@ +Nucleo-64 Boards +================ + +The Nucleo-F303RE is a member of the Nucleo-64 board family. The Nucleo-64 +is a standard board for use with several STM32 parts in the LQFP64 package. +Variants include + + Order code Targeted STM32 + ------------- -------------- + NUCLEO-F030R8 STM32F030R8T6 + NUCLEO-F070RB STM32F070RBT6 + NUCLEO-F072RB STM32F072RBT6 + NUCLEO-F091RC STM32F091RCT6 + NUCLEO-F103RB STM32F103RBT6 + NUCLEO-F302R8 STM32F302R8T6 + NUCLEO-F303RE STM32F303RET6 + NUCLEO-F334R8 STM32F334R8T6 + NUCLEO-F401RE STM32F401RET6 + NUCLEO-F410RB STM32F410RBT6 + NUCLEO-F411RE STM32F411RET6 + NUCLEO-F446RE STM32F446RET6 + NUCLEO-L053R8 STM32L053R8T6 + NUCLEO-L073RZ STM32L073RZT6 + NUCLEO-L152RE STM32L152RET6 + NUCLEO-L452RE STM32L452RET6 + NUCLEO-L476RG STM32L476RGT6 diff --git a/configs/nucleo-f334r8/README.txt b/configs/nucleo-f334r8/README.txt new file mode 100644 index 0000000000..b8f1c239d7 --- /dev/null +++ b/configs/nucleo-f334r8/README.txt @@ -0,0 +1,26 @@ +Nucleo-64 Boards +================ + +The Nucleo-F303RE is a member of the Nucleo-64 board family. The Nucleo-64 +is a standard board for use with several STM32 parts in the LQFP64 package. +Variants include + + Order code Targeted STM32 + ------------- -------------- + NUCLEO-F030R8 STM32F030R8T6 + NUCLEO-F070RB STM32F070RBT6 + NUCLEO-F072RB STM32F072RBT6 + NUCLEO-F091RC STM32F091RCT6 + NUCLEO-F103RB STM32F103RBT6 + NUCLEO-F302R8 STM32F302R8T6 + NUCLEO-F303RE STM32F303RET6 + NUCLEO-F334R8 STM32F334R8T6 + NUCLEO-F401RE STM32F401RET6 + NUCLEO-F410RB STM32F410RBT6 + NUCLEO-F411RE STM32F411RET6 + NUCLEO-F446RE STM32F446RET6 + NUCLEO-L053R8 STM32L053R8T6 + NUCLEO-L073RZ STM32L073RZT6 + NUCLEO-L152RE STM32L152RET6 + NUCLEO-L452RE STM32L452RET6 + NUCLEO-L476RG STM32L476RGT6 diff --git a/configs/nucleo-f4x1re/README.txt b/configs/nucleo-f4x1re/README.txt index 4a84121a40..9ea6be28ab 100644 --- a/configs/nucleo-f4x1re/README.txt +++ b/configs/nucleo-f4x1re/README.txt @@ -65,6 +65,7 @@ Board features, however, are identical: Contents ======== + - Nucleo-64 Boards - Development Environment - GNU Toolchain Options - IDEs @@ -79,6 +80,33 @@ Contents - Shields - Configurations +Nucleo-64 Boards +================ + +The Nucleo-F4x1RE boards are members of the Nucleo-64 board family. The +Nucleo-64 is a standard board for use with several STM32 parts in the +LQFP64 package. Variants include + + Order code Targeted STM32 + ------------- -------------- + NUCLEO-F030R8 STM32F030R8T6 + NUCLEO-F070RB STM32F070RBT6 + NUCLEO-F072RB STM32F072RBT6 + NUCLEO-F091RC STM32F091RCT6 + NUCLEO-F103RB STM32F103RBT6 + NUCLEO-F302R8 STM32F302R8T6 + NUCLEO-F303RE STM32F303RET6 + NUCLEO-F334R8 STM32F334R8T6 + NUCLEO-F401RE STM32F401RET6 + NUCLEO-F410RB STM32F410RBT6 + NUCLEO-F411RE STM32F411RET6 + NUCLEO-F446RE STM32F446RET6 + NUCLEO-L053R8 STM32L053R8T6 + NUCLEO-L073RZ STM32L073RZT6 + NUCLEO-L152RE STM32L152RET6 + NUCLEO-L452RE STM32L452RET6 + NUCLEO-L476RG STM32L476RGT6 + Development Environment ======================= diff --git a/configs/nucleo-l476rg/README.txt b/configs/nucleo-l476rg/README.txt index d576d83d88..72ab182d87 100644 --- a/configs/nucleo-l476rg/README.txt +++ b/configs/nucleo-l476rg/README.txt @@ -41,6 +41,7 @@ Board features: Contents ======== + - Nucleo-64 Boards - Development Environment - GNU Toolchain Options - IDEs @@ -55,6 +56,33 @@ Contents - Shields - Configurations +Nucleo-64 Boards +================ + +The Nucleo-L476RG is a member of the Nucleo-64 board family. The Nucleo-64 +is a standard board for use with several STM32 parts in the LQFP64 package. +Variants include + + Order code Targeted STM32 + ------------- -------------- + NUCLEO-F030R8 STM32F030R8T6 + NUCLEO-F070RB STM32F070RBT6 + NUCLEO-F072RB STM32F072RBT6 + NUCLEO-F091RC STM32F091RCT6 + NUCLEO-F103RB STM32F103RBT6 + NUCLEO-F302R8 STM32F302R8T6 + NUCLEO-F303RE STM32F303RET6 + NUCLEO-F334R8 STM32F334R8T6 + NUCLEO-F401RE STM32F401RET6 + NUCLEO-F410RB STM32F410RBT6 + NUCLEO-F411RE STM32F411RET6 + NUCLEO-F446RE STM32F446RET6 + NUCLEO-L053R8 STM32L053R8T6 + NUCLEO-L073RZ STM32L073RZT6 + NUCLEO-L152RE STM32L152RET6 + NUCLEO-L452RE STM32L452RET6 + NUCLEO-L476RG STM32L476RGT6 + Development Environment ======================= -- GitLab From bdd66ea6c70f684b851c4596a21fe661c11c0211 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 15 Apr 2017 08:53:42 -0600 Subject: [PATCH 454/990] 6loWPAN: Add some checks for the case where there are multiple network devices and multiple link layer protocols. --- net/sixlowpan/sixlowpan_send.c | 19 ++++++++++++++++++- 1 file changed, 18 insertions(+), 1 deletion(-) diff --git a/net/sixlowpan/sixlowpan_send.c b/net/sixlowpan/sixlowpan_send.c index 8338a41347..1dd8f86c66 100644 --- a/net/sixlowpan/sixlowpan_send.c +++ b/net/sixlowpan/sixlowpan_send.c @@ -161,7 +161,24 @@ static uint16_t send_interrupt(FAR struct net_driver_s *dev, ninfo("flags: %04x: %d\n", flags); - /* Check if the IEEE802.15.4 went down */ +#ifdef CONFIG_NET_MULTILINK + /* Verify that this is an IEEE802.15.4 network driver. */ + + if (dev->d_lltype != NET_LL_IEEE802154) + { + return flags; + } +#endif + +#ifdef CONFIG_NET_MULTINIC + /* REVISIT: Verify that this is the correct IEEE802.15.4 network driver to + * route the outgoing frame(s). Chances are that there is only one + * IEEE802.15.4 network driver + */ + +#endif + + /* Check if the IEEE802.15.4 network driver went down */ if ((flags & NETDEV_DOWN) != 0) { -- GitLab From 2576f2b2b1eea5600bbe3c2a5684b6f7c66b1dfd Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 15 Apr 2017 09:11:52 -0600 Subject: [PATCH 455/990] net/: Add IOCTL support for forwarding IEEE802.15.4 MAC and PHY IOCTLs. --- net/netdev/netdev_ioctl.c | 74 +++++++++++++++++++++++++++++++++++++++ 1 file changed, 74 insertions(+) diff --git a/net/netdev/netdev_ioctl.c b/net/netdev/netdev_ioctl.c index 1a845774fc..5dc882fbc3 100644 --- a/net/netdev/netdev_ioctl.c +++ b/net/netdev/netdev_ioctl.c @@ -70,6 +70,10 @@ #ifdef CONFIG_NETDEV_WIRELESS_IOCTL # include +#ifdef CONFIG_NET_6LOWPAN +# include +# include +#endif #endif #include "arp/arp.h" @@ -349,6 +353,76 @@ static FAR struct net_driver_s *netdev_wifrdev(FAR struct iwreq *req) } #endif +/**************************************************************************** + * Name: netdev_iee802154_ioctl + * + * Description: + * Perform IEEE802.15.4 network device specific operations. + * + * Parameters: + * psock Socket structure + * dev Ethernet driver device structure + * cmd The ioctl command + * req The argument of the ioctl cmd + * + * Return: + * >=0 on success (positive non-zero values are cmd-specific) + * Negated errno returned on failure. + * + ****************************************************************************/ + +#if defined(CONFIG_NETDEV_IOCTL) && defined(CONFIG_NET_6LOWPAN) +static int netdev_iee802154_ioctl(FAR struct socket *psock, int cmd, + unsigned long arg) +{ + FAR struct net_driver_s *dev; + FAR char *ifname; + int ret = -ENOTTY; + + if (req != NULL) + { + /* Verify that this is either a valid IEEE802.15.4 radio IOCTL command + * or a valid IEEE802.15.4 MAC IOCTL command. + */ + + if (_PHY802154IOCVALID(cmd)) + { + /* Get the IEEE802.15.4 network device to receive the radio IOCTL + * commdand + */ + + FAR struct ieee802154_netradio_s *radio = + (FAR struct ieee802154_netradio_s *)((uintptr_t)arg); + + ifname = radio->ifr_name; + } + else if (_MAC802154IOCVALID(cmd)) + { + /* Get the IEEE802.15.4 MAC device to receive the radio IOCTL + * commdand + */ + + FAR struct ieee802154_netmac_s *netmac = + (FAR struct ieee802154_netmac_s *)((uintptr_t)arg); + + ifname = netmac->ifr_name; + } + else + { + /* The IOCTL command is neither */ + + return -ENOTTY; + } + + /* Perform the device IOCTL */ + + ret = dev->d_ioctl(dev, cmd, arg); + } + + return ret; +} +#endif + /**************************************************************************** * Name: netdev_wifrioctl * -- GitLab From 78bc1aa6bc5a1f916f7773896b8c968146f8f0b2 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 15 Apr 2017 09:33:27 -0600 Subject: [PATCH 456/990] Argument of network device IOCTL should be unsigned long, just as will all other IOCTL methods. --- arch/arm/src/kinetis/kinetis_enet.c | 20 +++++++++++--------- arch/arm/src/lpc43xx/lpc43_ethernet.c | 22 ++++++++++++++-------- arch/arm/src/sam34/sam_emac.c | 4 ++-- arch/arm/src/sama5/sam_emaca.c | 4 ++-- arch/arm/src/sama5/sam_emacb.c | 4 ++-- arch/arm/src/sama5/sam_gmac.c | 4 ++-- arch/arm/src/samv7/sam_emac.c | 4 ++-- arch/arm/src/stm32/stm32_eth.c | 22 ++++++++++++++-------- arch/arm/src/stm32f7/stm32_ethernet.c | 23 +++++++++++++---------- arch/arm/src/tiva/tm4c_ethernet.c | 20 +++++++++++++------- drivers/net/skeleton.c | 18 +++++++++++------- include/nuttx/net/netdev.h | 3 ++- net/netdev/netdev_ioctl.c | 6 +++--- 13 files changed, 91 insertions(+), 63 deletions(-) diff --git a/arch/arm/src/kinetis/kinetis_enet.c b/arch/arm/src/kinetis/kinetis_enet.c index 694b155734..37910fc9b9 100644 --- a/arch/arm/src/kinetis/kinetis_enet.c +++ b/arch/arm/src/kinetis/kinetis_enet.c @@ -297,28 +297,30 @@ static void kinetis_polltimer_expiry(int argc, uint32_t arg, ...); /* NuttX callback functions */ -static int kinetis_ifup(struct net_driver_s *dev); -static int kinetis_ifdown(struct net_driver_s *dev); +static int kinetis_ifup(struct net_driver_s *dev); +static int kinetis_ifdown(struct net_driver_s *dev); static void kinetis_txavail_work(FAR void *arg); -static int kinetis_txavail(struct net_driver_s *dev); +static int kinetis_txavail(struct net_driver_s *dev); #ifdef CONFIG_NET_IGMP -static int kinetis_addmac(struct net_driver_s *dev, FAR const uint8_t *mac); -static int kinetis_rmmac(struct net_driver_s *dev, FAR const uint8_t *mac); +static int kinetis_addmac(struct net_driver_s *dev, + FAR const uint8_t *mac); +static int kinetis_rmmac(struct net_driver_s *dev, FAR const uint8_t *mac); #endif #ifdef CONFIG_NETDEV_PHY_IOCTL -static int kinetis_ioctl(struct net_driver_s *dev, int cmd, long arg); +static int kinetis_ioctl(struct net_driver_s *dev, int cmd, + unsigned long arg); #endif /* PHY/MII support */ static inline void kinetis_initmii(struct kinetis_driver_s *priv); static int kinetis_writemii(struct kinetis_driver_s *priv, uint8_t phyaddr, - uint8_t regaddr, uint16_t data); + uint8_t regaddr, uint16_t data); static int kinetis_readmii(struct kinetis_driver_s *priv, uint8_t phyaddr, - uint8_t regaddr, uint16_t *data); + uint8_t regaddr, uint16_t *data); static inline int kinetis_initphy(struct kinetis_driver_s *priv); /* Initialization */ @@ -1447,7 +1449,7 @@ static int kinetis_rmmac(struct net_driver_s *dev, FAR const uint8_t *mac) ****************************************************************************/ #ifdef CONFIG_NETDEV_PHY_IOCTL -static int kinetis_ioctl(struct net_driver_s *dev, int cmd, long arg) +static int kinetis_ioctl(struct net_driver_s *dev, int cmd, unsigned long arg) { int ret; FAR struct kinetis_driver_s *priv = diff --git a/arch/arm/src/lpc43xx/lpc43_ethernet.c b/arch/arm/src/lpc43xx/lpc43_ethernet.c index 1aeca91d89..171f20ee74 100644 --- a/arch/arm/src/lpc43xx/lpc43_ethernet.c +++ b/arch/arm/src/lpc43xx/lpc43_ethernet.c @@ -572,7 +572,8 @@ static void lpc43_checksetup(void); static void lpc43_initbuffer(FAR struct lpc43_ethmac_s *priv); static inline uint8_t *lpc43_allocbuffer(FAR struct lpc43_ethmac_s *priv); -static inline void lpc43_freebuffer(FAR struct lpc43_ethmac_s *priv, uint8_t *buffer); +static inline void lpc43_freebuffer(FAR struct lpc43_ethmac_s *priv, + uint8_t *buffer); static inline bool lpc43_isfreebuffer(FAR struct lpc43_ethmac_s *priv); /* Common TX logic */ @@ -583,11 +584,13 @@ static void lpc43_dopoll(FAR struct lpc43_ethmac_s *priv); /* Interrupt handling */ -static void lpc43_enableint(FAR struct lpc43_ethmac_s *priv, uint32_t ierbit); -static void lpc43_disableint(FAR struct lpc43_ethmac_s *priv, uint32_t ierbit); +static void lpc43_enableint(FAR struct lpc43_ethmac_s *priv, + uint32_t ierbit); +static void lpc43_disableint(FAR struct lpc43_ethmac_s *priv, + uint32_t ierbit); static void lpc43_freesegment(FAR struct lpc43_ethmac_s *priv, - FAR struct eth_rxdesc_s *rxfirst, int segments); + FAR struct eth_rxdesc_s *rxfirst, int segments); static int lpc43_recvframe(FAR struct lpc43_ethmac_s *priv); static void lpc43_receive(FAR struct lpc43_ethmac_s *priv); static void lpc43_freeframe(FAR struct lpc43_ethmac_s *priv); @@ -619,7 +622,8 @@ static int lpc43_addmac(struct net_driver_s *dev, FAR const uint8_t *mac); static int lpc43_rmmac(struct net_driver_s *dev, FAR const uint8_t *mac); #endif #ifdef CONFIG_NETDEV_PHY_IOCTL -static int lpc43_ioctl(struct net_driver_s *dev, int cmd, long arg); +static int lpc43_ioctl(struct net_driver_s *dev, int cmd, + unsigned long arg); #endif /* Descriptor Initialization */ @@ -630,8 +634,10 @@ static void lpc43_rxdescinit(FAR struct lpc43_ethmac_s *priv); #if defined(CONFIG_NETDEV_PHY_IOCTL) && defined(CONFIG_ARCH_PHY_INTERRUPT) static int lpc43_phyintenable(FAR struct lpc43_ethmac_s *priv); #endif -static int lpc43_phyread(uint16_t phydevaddr, uint16_t phyregaddr, uint16_t *value); -static int lpc43_phywrite(uint16_t phydevaddr, uint16_t phyregaddr, uint16_t value); +static int lpc43_phyread(uint16_t phydevaddr, uint16_t phyregaddr, + uint16_t *value); +static int lpc43_phywrite(uint16_t phydevaddr, uint16_t phyregaddr, + uint16_t value); #ifdef CONFIG_ETH0_PHY_DM9161 static inline int lpc43_dm9161(FAR struct lpc43_ethmac_s *priv); #endif @@ -2739,7 +2745,7 @@ static void lpc43_rxdescinit(FAR struct lpc43_ethmac_s *priv) ****************************************************************************/ #ifdef CONFIG_NETDEV_PHY_IOCTL -static int lpc43_ioctl(struct net_driver_s *dev, int cmd, long arg) +static int lpc43_ioctl(struct net_driver_s *dev, int cmd, unsigned long arg) { #ifdef CONFIG_ARCH_PHY_INTERRUPT FAR struct lpc43_ethmac_s *priv = (FAR struct lpc43_ethmac_s *)dev->d_private; diff --git a/arch/arm/src/sam34/sam_emac.c b/arch/arm/src/sam34/sam_emac.c index c5db8c01a4..f1db43f0ca 100644 --- a/arch/arm/src/sam34/sam_emac.c +++ b/arch/arm/src/sam34/sam_emac.c @@ -409,7 +409,7 @@ static int sam_rmmac(struct net_driver_s *dev, const uint8_t *mac); #endif #ifdef CONFIG_NETDEV_PHY_IOCTL -static int sam_ioctl(struct net_driver_s *dev, int cmd, long arg); +static int sam_ioctl(struct net_driver_s *dev, int cmd, unsigned long arg); #endif /* PHY Initialization */ @@ -2310,7 +2310,7 @@ static int sam_rmmac(struct net_driver_s *dev, const uint8_t *mac) ****************************************************************************/ #ifdef CONFIG_NETDEV_PHY_IOCTL -static int sam_ioctl(struct net_driver_s *dev, int cmd, long arg) +static int sam_ioctl(struct net_driver_s *dev, int cmd, unsigned long arg) { struct sam_emac_s *priv = (struct sam_emac_s *)dev->d_private; int ret; diff --git a/arch/arm/src/sama5/sam_emaca.c b/arch/arm/src/sama5/sam_emaca.c index 92e18b160a..09cba2280f 100644 --- a/arch/arm/src/sama5/sam_emaca.c +++ b/arch/arm/src/sama5/sam_emaca.c @@ -414,7 +414,7 @@ static int sam_rmmac(struct net_driver_s *dev, const uint8_t *mac); #endif #ifdef CONFIG_NETDEV_PHY_IOCTL -static int sam_ioctl(struct net_driver_s *dev, int cmd, long arg); +static int sam_ioctl(struct net_driver_s *dev, int cmd, unsigned long arg); #endif /* PHY Initialization */ @@ -2346,7 +2346,7 @@ static int sam_rmmac(struct net_driver_s *dev, const uint8_t *mac) ****************************************************************************/ #ifdef CONFIG_NETDEV_PHY_IOCTL -static int sam_ioctl(struct net_driver_s *dev, int cmd, long arg) +static int sam_ioctl(struct net_driver_s *dev, int cmd, unsigned long arg) { struct sam_emac_s *priv = (struct sam_emac_s *)dev->d_private; int ret; diff --git a/arch/arm/src/sama5/sam_emacb.c b/arch/arm/src/sama5/sam_emacb.c index 3fd2f903fb..10c120cc47 100644 --- a/arch/arm/src/sama5/sam_emacb.c +++ b/arch/arm/src/sama5/sam_emacb.c @@ -508,7 +508,7 @@ static int sam_rmmac(struct net_driver_s *dev, const uint8_t *mac); #endif #ifdef CONFIG_NETDEV_PHY_IOCTL -static int sam_ioctl(struct net_driver_s *dev, int cmd, long arg); +static int sam_ioctl(struct net_driver_s *dev, int cmd, unsigned long arg); #endif /* PHY Initialization */ @@ -2713,7 +2713,7 @@ static int sam_rmmac(struct net_driver_s *dev, const uint8_t *mac) ****************************************************************************/ #ifdef CONFIG_NETDEV_PHY_IOCTL -static int sam_ioctl(struct net_driver_s *dev, int cmd, long arg) +static int sam_ioctl(struct net_driver_s *dev, int cmd, unsigned long arg) { struct sam_emac_s *priv = (struct sam_emac_s *)dev->d_private; int ret; diff --git a/arch/arm/src/sama5/sam_gmac.c b/arch/arm/src/sama5/sam_gmac.c index a3d296b349..0988f8aedb 100644 --- a/arch/arm/src/sama5/sam_gmac.c +++ b/arch/arm/src/sama5/sam_gmac.c @@ -339,7 +339,7 @@ static int sam_rmmac(struct net_driver_s *dev, const uint8_t *mac); #endif #ifdef CONFIG_NETDEV_PHY_IOCTL -static int sam_ioctl(struct net_driver_s *dev, int cmd, long arg); +static int sam_ioctl(struct net_driver_s *dev, int cmd, unsigned long arg); #endif /* PHY Initialization */ @@ -2301,7 +2301,7 @@ static int sam_rmmac(struct net_driver_s *dev, const uint8_t *mac) ****************************************************************************/ #ifdef CONFIG_NETDEV_PHY_IOCTL -static int sam_ioctl(struct net_driver_s *dev, int cmd, long arg) +static int sam_ioctl(struct net_driver_s *dev, int cmd, unsigned long arg) { struct sam_gmac_s *priv = (struct sam_gmac_s *)dev->d_private; int ret; diff --git a/arch/arm/src/samv7/sam_emac.c b/arch/arm/src/samv7/sam_emac.c index 8905ee5554..4432570c78 100644 --- a/arch/arm/src/samv7/sam_emac.c +++ b/arch/arm/src/samv7/sam_emac.c @@ -610,7 +610,7 @@ static int sam_rmmac(struct net_driver_s *dev, const uint8_t *mac); #endif #ifdef CONFIG_NETDEV_PHY_IOCTL -static int sam_ioctl(struct net_driver_s *dev, int cmd, long arg); +static int sam_ioctl(struct net_driver_s *dev, int cmd, unsigned long arg); #endif /* PHY Initialization */ @@ -3164,7 +3164,7 @@ static int sam_rmmac(struct net_driver_s *dev, const uint8_t *mac) ****************************************************************************/ #ifdef CONFIG_NETDEV_PHY_IOCTL -static int sam_ioctl(struct net_driver_s *dev, int cmd, long arg) +static int sam_ioctl(struct net_driver_s *dev, int cmd, unsigned long arg) { struct sam_emac_s *priv = (struct sam_emac_s *)dev->d_private; int ret; diff --git a/arch/arm/src/stm32/stm32_eth.c b/arch/arm/src/stm32/stm32_eth.c index b17077fd54..0b1bbd247c 100644 --- a/arch/arm/src/stm32/stm32_eth.c +++ b/arch/arm/src/stm32/stm32_eth.c @@ -635,7 +635,8 @@ static void stm32_checksetup(void); static void stm32_initbuffer(FAR struct stm32_ethmac_s *priv); static inline uint8_t *stm32_allocbuffer(FAR struct stm32_ethmac_s *priv); -static inline void stm32_freebuffer(FAR struct stm32_ethmac_s *priv, uint8_t *buffer); +static inline void stm32_freebuffer(FAR struct stm32_ethmac_s *priv, + uint8_t *buffer); static inline bool stm32_isfreebuffer(FAR struct stm32_ethmac_s *priv); /* Common TX logic */ @@ -646,11 +647,13 @@ static void stm32_dopoll(FAR struct stm32_ethmac_s *priv); /* Interrupt handling */ -static void stm32_enableint(FAR struct stm32_ethmac_s *priv, uint32_t ierbit); -static void stm32_disableint(FAR struct stm32_ethmac_s *priv, uint32_t ierbit); +static void stm32_enableint(FAR struct stm32_ethmac_s *priv, + uint32_t ierbit); +static void stm32_disableint(FAR struct stm32_ethmac_s *priv, + uint32_t ierbit); static void stm32_freesegment(FAR struct stm32_ethmac_s *priv, - FAR struct eth_rxdesc_s *rxfirst, int segments); + FAR struct eth_rxdesc_s *rxfirst, int segments); static int stm32_recvframe(FAR struct stm32_ethmac_s *priv); static void stm32_receive(FAR struct stm32_ethmac_s *priv); static void stm32_freeframe(FAR struct stm32_ethmac_s *priv); @@ -682,7 +685,8 @@ static int stm32_addmac(struct net_driver_s *dev, FAR const uint8_t *mac); static int stm32_rmmac(struct net_driver_s *dev, FAR const uint8_t *mac); #endif #ifdef CONFIG_NETDEV_PHY_IOCTL -static int stm32_ioctl(struct net_driver_s *dev, int cmd, long arg); +static int stm32_ioctl(struct net_driver_s *dev, int cmd, + unsigned long arg); #endif /* Descriptor Initialization */ @@ -697,9 +701,11 @@ static int stm32_phyintenable(FAR struct stm32_ethmac_s *priv); #endif #if defined(CONFIG_STM32_AUTONEG) || defined(CONFIG_NETDEV_PHY_IOCTL) || \ defined(CONFIG_ETH0_PHY_DM9161) -static int stm32_phyread(uint16_t phydevaddr, uint16_t phyregaddr, uint16_t *value); +static int stm32_phyread(uint16_t phydevaddr, uint16_t phyregaddr, + uint16_t *value); #endif -static int stm32_phywrite(uint16_t phydevaddr, uint16_t phyregaddr, uint16_t value); +static int stm32_phywrite(uint16_t phydevaddr, uint16_t phyregaddr, + uint16_t value); #ifdef CONFIG_ETH0_PHY_DM9161 static inline int stm32_dm9161(FAR struct stm32_ethmac_s *priv); #endif @@ -2805,7 +2811,7 @@ static void stm32_rxdescinit(FAR struct stm32_ethmac_s *priv) ****************************************************************************/ #ifdef CONFIG_NETDEV_PHY_IOCTL -static int stm32_ioctl(struct net_driver_s *dev, int cmd, long arg) +static int stm32_ioctl(struct net_driver_s *dev, int cmd, unsigned long arg) { #ifdef CONFIG_ARCH_PHY_INTERRUPT FAR struct stm32_ethmac_s *priv = (FAR struct stm32_ethmac_s *)dev->d_private; diff --git a/arch/arm/src/stm32f7/stm32_ethernet.c b/arch/arm/src/stm32f7/stm32_ethernet.c index 961b21bf26..0885c086cd 100644 --- a/arch/arm/src/stm32f7/stm32_ethernet.c +++ b/arch/arm/src/stm32f7/stm32_ethernet.c @@ -678,9 +678,10 @@ static void stm32_checksetup(void); /* Free buffer management */ static void stm32_initbuffer(struct stm32_ethmac_s *priv, - uint8_t *txbuffer); + uint8_t *txbuffer); static inline uint8_t *stm32_allocbuffer(struct stm32_ethmac_s *priv); -static inline void stm32_freebuffer(struct stm32_ethmac_s *priv, uint8_t *buffer); +static inline void stm32_freebuffer(struct stm32_ethmac_s *priv, + uint8_t *buffer); static inline bool stm32_isfreebuffer(struct stm32_ethmac_s *priv); /* Common TX logic */ @@ -695,7 +696,7 @@ static void stm32_enableint(struct stm32_ethmac_s *priv, uint32_t ierbit); static void stm32_disableint(struct stm32_ethmac_s *priv, uint32_t ierbit); static void stm32_freesegment(struct stm32_ethmac_s *priv, - struct eth_rxdesc_s *rxfirst, int segments); + struct eth_rxdesc_s *rxfirst, int segments); static int stm32_recvframe(struct stm32_ethmac_s *priv); static void stm32_receive(struct stm32_ethmac_s *priv); static void stm32_freeframe(struct stm32_ethmac_s *priv); @@ -727,24 +728,26 @@ static int stm32_addmac(struct net_driver_s *dev, const uint8_t *mac); static int stm32_rmmac(struct net_driver_s *dev, const uint8_t *mac); #endif #ifdef CONFIG_NETDEV_PHY_IOCTL -static int stm32_ioctl(struct net_driver_s *dev, int cmd, long arg); +static int stm32_ioctl(struct net_driver_s *dev, int cmd, + unsigned long arg); #endif /* Descriptor Initialization */ static void stm32_txdescinit(struct stm32_ethmac_s *priv, - union stm32_txdesc_u *txtable); + union stm32_txdesc_u *txtable); static void stm32_rxdescinit(struct stm32_ethmac_s *priv, - union stm32_rxdesc_u *rxtable, - uint8_t *rxbuffer); + union stm32_rxdesc_u *rxtable, uint8_t *rxbuffer); /* PHY Initialization */ #if defined(CONFIG_NETDEV_PHY_IOCTL) && defined(CONFIG_ARCH_PHY_INTERRUPT) static int stm32_phyintenable(struct stm32_ethmac_s *priv); #endif -static int stm32_phyread(uint16_t phydevaddr, uint16_t phyregaddr, uint16_t *value); -static int stm32_phywrite(uint16_t phydevaddr, uint16_t phyregaddr, uint16_t value); +static int stm32_phyread(uint16_t phydevaddr, uint16_t phyregaddr, + uint16_t *value); +static int stm32_phywrite(uint16_t phydevaddr, uint16_t phyregaddr, + uint16_t value); #ifdef CONFIG_ETH0_PHY_DM9161 static inline int stm32_dm9161(struct stm32_ethmac_s *priv); #endif @@ -2938,7 +2941,7 @@ static void stm32_rxdescinit(struct stm32_ethmac_s *priv, ****************************************************************************/ #ifdef CONFIG_NETDEV_PHY_IOCTL -static int stm32_ioctl(struct net_driver_s *dev, int cmd, long arg) +static int stm32_ioctl(struct net_driver_s *dev, int cmd, unsigned long arg) { #ifdef CONFIG_ARCH_PHY_INTERRUPT struct stm32_ethmac_s *priv = (struct stm32_ethmac_s *)dev->d_private; diff --git a/arch/arm/src/tiva/tm4c_ethernet.c b/arch/arm/src/tiva/tm4c_ethernet.c index f6c6870f4c..cf0661d36e 100644 --- a/arch/arm/src/tiva/tm4c_ethernet.c +++ b/arch/arm/src/tiva/tm4c_ethernet.c @@ -685,7 +685,8 @@ static void tiva_checksetup(void); static void tiva_initbuffer(FAR struct tiva_ethmac_s *priv); static inline uint8_t *tiva_allocbuffer(FAR struct tiva_ethmac_s *priv); -static inline void tiva_freebuffer(FAR struct tiva_ethmac_s *priv, uint8_t *buffer); +static inline void tiva_freebuffer(FAR struct tiva_ethmac_s *priv, + uint8_t *buffer); static inline bool tiva_isfreebuffer(FAR struct tiva_ethmac_s *priv); /* Common TX logic */ @@ -697,10 +698,11 @@ static void tiva_dopoll(FAR struct tiva_ethmac_s *priv); /* Interrupt handling */ static void tiva_enableint(FAR struct tiva_ethmac_s *priv, uint32_t ierbit); -static void tiva_disableint(FAR struct tiva_ethmac_s *priv, uint32_t ierbit); +static void tiva_disableint(FAR struct tiva_ethmac_s *priv, + uint32_t ierbit); static void tiva_freesegment(FAR struct tiva_ethmac_s *priv, - FAR struct emac_rxdesc_s *rxfirst, int segments); + FAR struct emac_rxdesc_s *rxfirst, int segments); static int tiva_recvframe(FAR struct tiva_ethmac_s *priv); static void tiva_receive(FAR struct tiva_ethmac_s *priv); static void tiva_freeframe(FAR struct tiva_ethmac_s *priv); @@ -732,7 +734,8 @@ static int tiva_addmac(struct net_driver_s *dev, FAR const uint8_t *mac); static int tiva_rmmac(struct net_driver_s *dev, FAR const uint8_t *mac); #endif #ifdef CONFIG_NETDEV_PHY_IOCTL -static int tiva_ioctl(struct net_driver_s *dev, int cmd, long arg); +static int tiva_ioctl(struct net_driver_s *dev, int cmd, + unsigned long arg); #endif /* Descriptor Initialization */ @@ -745,8 +748,10 @@ static void tiva_rxdescinit(FAR struct tiva_ethmac_s *priv); #ifdef CONFIG_TIVA_PHY_INTERRUPTS static void tiva_phy_intenable(bool enable); #endif -static int tiva_phyread(uint16_t phydevaddr, uint16_t phyregaddr, uint16_t *value); -static int tiva_phywrite(uint16_t phydevaddr, uint16_t phyregaddr, uint16_t value); +static int tiva_phyread(uint16_t phydevaddr, uint16_t phyregaddr, + uint16_t *value); +static int tiva_phywrite(uint16_t phydevaddr, uint16_t phyregaddr, + uint16_t value); static int tiva_phyinit(FAR struct tiva_ethmac_s *priv); /* MAC/DMA Initialization */ @@ -766,6 +771,7 @@ static int tive_emac_configure(FAR struct tiva_ethmac_s *priv); /**************************************************************************** * Private Functions ****************************************************************************/ + /**************************************************************************** * Name: tiva_getreg * @@ -2855,7 +2861,7 @@ static void tiva_rxdescinit(FAR struct tiva_ethmac_s *priv) ****************************************************************************/ #ifdef CONFIG_NETDEV_PHY_IOCTL -static int tiva_ioctl(struct net_driver_s *dev, int cmd, long arg) +static int tiva_ioctl(struct net_driver_s *dev, int cmd, unsigned long arg) { int ret; diff --git a/drivers/net/skeleton.c b/drivers/net/skeleton.c index 94380212f6..77f1aea82d 100644 --- a/drivers/net/skeleton.c +++ b/drivers/net/skeleton.c @@ -175,23 +175,26 @@ static void skel_poll_expiry(int argc, wdparm_t arg, ...); /* NuttX callback functions */ -static int skel_ifup(FAR struct net_driver_s *dev); -static int skel_ifdown(FAR struct net_driver_s *dev); +static int skel_ifup(FAR struct net_driver_s *dev); +static int skel_ifdown(FAR struct net_driver_s *dev); static void skel_txavail_work(FAR void *arg); -static int skel_txavail(FAR struct net_driver_s *dev); +static int skel_txavail(FAR struct net_driver_s *dev); #if defined(CONFIG_NET_IGMP) || defined(CONFIG_NET_ICMPv6) -static int skel_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac); +static int skel_addmac(FAR struct net_driver_s *dev, + FAR const uint8_t *mac); #ifdef CONFIG_NET_IGMP -static int skel_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac); +static int skel_rmmac(FAR struct net_driver_s *dev, + FAR const uint8_t *mac); #endif #ifdef CONFIG_NET_ICMPv6 static void skel_ipv6multicast(FAR struct skel_driver_s *priv); #endif #endif #ifdef CONFIG_NETDEV_IOCTL -static int skel_ioctl(FAR struct net_driver_s *dev, int cmd, long arg); +static int skel_ioctl(FAR struct net_driver_s *dev, int cmd, + unsigned long arg); #endif /**************************************************************************** @@ -1095,7 +1098,8 @@ static void skel_ipv6multicast(FAR struct skel_driver_s *priv) ****************************************************************************/ #ifdef CONFIG_NETDEV_IOCTL -static int skel_ioctl(FAR struct net_driver_s *dev, int cmd, long arg) +static int skel_ioctl(FAR struct net_driver_s *dev, int cmd, + unsigned long arg) { FAR struct skel_driver_s *priv = (FAR struct skel_driver_s *)dev->d_private; int ret; diff --git a/include/nuttx/net/netdev.h b/include/nuttx/net/netdev.h index 12b71840d7..844117ee79 100644 --- a/include/nuttx/net/netdev.h +++ b/include/nuttx/net/netdev.h @@ -331,7 +331,8 @@ struct net_driver_s int (*d_rmmac)(FAR struct net_driver_s *dev, FAR const uint8_t *mac); #endif #ifdef CONFIG_NETDEV_IOCTL - int (*d_ioctl)(FAR struct net_driver_s *dev, int cmd, long arg); + int (*d_ioctl)(FAR struct net_driver_s *dev, int cmd, + unsigned long arg); #endif /* Drivers may attached device-specific, private information */ diff --git a/net/netdev/netdev_ioctl.c b/net/netdev/netdev_ioctl.c index 1a845774fc..8abe8aaf18 100644 --- a/net/netdev/netdev_ioctl.c +++ b/net/netdev/netdev_ioctl.c @@ -385,7 +385,7 @@ static int netdev_wifrioctl(FAR struct socket *psock, int cmd, { /* Just forward the IOCTL to the wireless driver */ - ret = dev->d_ioctl(dev, cmd, ((long)(uintptr_t)req)); + ret = dev->d_ioctl(dev, cmd, ((unsigned long)(uintptr_t)req)); } } @@ -827,7 +827,7 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, if (dev && dev->d_ioctl) { struct mii_iotcl_notify_s *notify = &req->ifr_ifru.ifru_mii_notify; - ret = dev->d_ioctl(dev, cmd, ((long)(uintptr_t)notify)); + ret = dev->d_ioctl(dev, cmd, ((unsigned long)(uintptr_t)notify)); } } break; @@ -841,7 +841,7 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, if (dev && dev->d_ioctl) { struct mii_ioctl_data_s *mii_data = &req->ifr_ifru.ifru_mii_data; - ret = dev->d_ioctl(dev, cmd, ((long)(uintptr_t)mii_data)); + ret = dev->d_ioctl(dev, cmd, ((unsigned long)(uintptr_t)mii_data)); } } break; -- GitLab From 30db2835a182c2e8c687b023b348c16ee675fc56 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 15 Apr 2017 09:36:11 -0600 Subject: [PATCH 457/990] Trivial fix to spacing --- wireless/ieee802154/mac802154_netdev.c | 22 +++++++++++----------- 1 file changed, 11 insertions(+), 11 deletions(-) diff --git a/wireless/ieee802154/mac802154_netdev.c b/wireless/ieee802154/mac802154_netdev.c index 6cbb6d5840..d27daf3ef3 100644 --- a/wireless/ieee802154/mac802154_netdev.c +++ b/wireless/ieee802154/mac802154_netdev.c @@ -1462,24 +1462,24 @@ int mac802154netdev_register(MACHANDLE mac) /* Initialize the driver structure */ dev = &ieee->md_dev.i_dev; - dev->d_buf = pktbuf; /* Single packet buffer */ - dev->d_ifup = macnet_ifup; /* I/F up (new IP address) callback */ - dev->d_ifdown = macnet_ifdown; /* I/F down callback */ - dev->d_txavail = macnet_txavail; /* New TX data callback */ + dev->d_buf = pktbuf; /* Single packet buffer */ + dev->d_ifup = macnet_ifup; /* I/F up (new IP address) callback */ + dev->d_ifdown = macnet_ifdown; /* I/F down callback */ + dev->d_txavail = macnet_txavail; /* New TX data callback */ #ifdef CONFIG_NET_IGMP - dev->d_addmac = macnet_addmac; /* Add multicast MAC address */ - dev->d_rmmac = macnet_rmmac; /* Remove multicast MAC address */ + dev->d_addmac = macnet_addmac; /* Add multicast MAC address */ + dev->d_rmmac = macnet_rmmac; /* Remove multicast MAC address */ #endif #ifdef CONFIG_NETDEV_IOCTL - dev->d_ioctl = macnet_ioctl; /* Handle network IOCTL commands */ + dev->d_ioctl = macnet_ioctl; /* Handle network IOCTL commands */ #endif - dev->d_private = (FAR void *)priv; /* Used to recover private state from dev */ + dev->d_private = (FAR void *)priv; /* Used to recover private state from dev */ /* Create a watchdog for timing polling for and timing of transmisstions */ - priv->md_mac = mac; /* Save the MAC interface instance */ - priv->md_txpoll = wd_create(); /* Create periodic poll timer */ - priv->md_txtimeout = wd_create(); /* Create TX timeout timer */ + priv->md_mac = mac; /* Save the MAC interface instance */ + priv->md_txpoll = wd_create(); /* Create periodic poll timer */ + priv->md_txtimeout = wd_create(); /* Create TX timeout timer */ DEBUGASSERT(priv->md_txpoll != NULL && priv->md_txtimeout != NULL); -- GitLab From 5c32abb4425556b8ba11f0edf49d53e1e9acb3ef Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Wed, 5 Apr 2017 21:07:52 -0400 Subject: [PATCH 458/990] wireless/ieee802154: Adds ability to receive notifications from MAC char driver --- .../wireless/ieee802154/ieee802154_mac.h | 37 +++-- wireless/ieee802154/mac802154_device.c | 154 ++++++++++++++++-- 2 files changed, 157 insertions(+), 34 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index 6ad8158c80..1a7929cb3e 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -83,22 +83,27 @@ * Request and Response primitives. */ -#define MAC802154IOC_MLME_ASSOC_REQUEST _MAC802154IOC(0x0001) -#define MAC802154IOC_MLME_ASSOC_RESPONSE _MAC802154IOC(0x0002) -#define MAC802154IOC_MLME_DISASSOC_REQUEST _MAC802154IOC(0x0003) -#define MAC802154IOC_MLME_GET_REQUEST _MAC802154IOC(0x0004) -#define MAC802154IOC_MLME_GTS_REQUEST _MAC802154IOC(0x0005) -#define MAC802154IOC_MLME_ORPHAN_RESPONSE _MAC802154IOC(0x0006) -#define MAC802154IOC_MLME_RESET_REQUEST _MAC802154IOC(0x0007) -#define MAC802154IOC_MLME_RXENABLE_REQUEST _MAC802154IOC(0x0008) -#define MAC802154IOC_MLME_SCAN_REQUEST _MAC802154IOC(0x0009) -#define MAC802154IOC_MLME_SET_REQUEST _MAC802154IOC(0x000A) -#define MAC802154IOC_MLME_START_REQUEST _MAC802154IOC(0x000B) -#define MAC802154IOC_MLME_SYNC_REQUEST _MAC802154IOC(0x000C) -#define MAC802154IOC_MLME_POLL_REQUEST _MAC802154IOC(0x000D) -#define MAC802154IOC_MLME_DPS_REQUEST _MAC802154IOC(0x000E) -#define MAC802154IOC_MLME_SOUNDING_REQUEST _MAC802154IOC(0x000F) -#define MAC802154IOC_MLME_CALIBRATE_REQUEST _MAC802154IOC(0x0010) +#define MAC802154IOC_MCPS_REGISTER _MAC802154IOC(0x0001) + +#define MAC802154IOC_MLME_REGISER _MAC802154IOC(0x0002); +#define MAC802154IOC_MLME_ASSOC_REQUEST _MAC802154IOC(0x0003) +#define MAC802154IOC_MLME_ASSOC_RESPONSE _MAC802154IOC(0x0004) +#define MAC802154IOC_MLME_DISASSOC_REQUEST _MAC802154IOC(0x0005) +#define MAC802154IOC_MLME_GET_REQUEST _MAC802154IOC(0x0006) +#define MAC802154IOC_MLME_GTS_REQUEST _MAC802154IOC(0x0007) +#define MAC802154IOC_MLME_ORPHAN_RESPONSE _MAC802154IOC(0x0008) +#define MAC802154IOC_MLME_RESET_REQUEST _MAC802154IOC(0x0009) +#define MAC802154IOC_MLME_RXENABLE_REQUEST _MAC802154IOC(0x000A) +#define MAC802154IOC_MLME_SCAN_REQUEST _MAC802154IOC(0x000B) +#define MAC802154IOC_MLME_SET_REQUEST _MAC802154IOC(0x000C) +#define MAC802154IOC_MLME_START_REQUEST _MAC802154IOC(0x000D) +#define MAC802154IOC_MLME_SYNC_REQUEST _MAC802154IOC(0x000E) +#define MAC802154IOC_MLME_POLL_REQUEST _MAC802154IOC(0x000F) +#define MAC802154IOC_MLME_DPS_REQUEST _MAC802154IOC(0x0010) +#define MAC802154IOC_MLME_SOUNDING_REQUEST _MAC802154IOC(0x0011) +#define MAC802154IOC_MLME_CALIBRATE_REQUEST _MAC802154IOC(0x0012) + + /* IEEE 802.15.4 MAC Interface **********************************************/ diff --git a/wireless/ieee802154/mac802154_device.c b/wireless/ieee802154/mac802154_device.c index 18d88cf9b3..67631e7c63 100644 --- a/wireless/ieee802154/mac802154_device.c +++ b/wireless/ieee802154/mac802154_device.c @@ -77,15 +77,33 @@ struct mac802154_devwrapper_s FAR struct mac802154_open_s *md_open; FAR struct mac802154dev_dwait_s *md_dwait; + +#ifndef CONFIG_DISABLE_SIGNALS + /* MCPS Service notification information */ + + struct mac802154dev_notify_s md_mcps_notify; + pid_t md_mcps_pid; + + /* MLME Service notification information */ + + struct mac802154dev_notify_s md_mlme_notify; + pid_t md_mlme_pid; + +#endif +}; + +struct mac802154dev_notify_s +{ + uint8_t mn_signo; /* Signal number to use in the notification */ }; /* This structure describes the state of one open mac driver instance */ -struct mac802154_open_s +struct mac802154dev_open_s { /* Supports a singly linked list */ - FAR struct mac802154_open_s *md_flink; + FAR struct mac802154dev_open_s *md_flink; /* The following will be true if we are closing */ @@ -96,7 +114,7 @@ struct mac802154dev_dwait_s { uint8_t mw_handle; /* The msdu handle identifying the frame */ sem_t mw_sem; /* The semaphore used to signal the completion */ - int status; /* The success/error of the transaction */ + int mw_status; /* The success/error of the transaction */ /* Supports a singly linked list */ @@ -181,7 +199,7 @@ static int mac802154dev_open(FAR struct file *filep) { FAR struct inode *inode; FAR struct mac802154_devwrapper_s *dev; - FAR struct mac802154_open_s *opriv; + FAR struct mac802154dev_open_s *opriv; int ret; DEBUGASSERT(filep != NULL && filep->f_inode != NULL); @@ -201,8 +219,8 @@ static int mac802154dev_open(FAR struct file *filep) /* Allocate a new open struct */ - opriv = (FAR struct mac802154_open_s *) - kmm_zalloc(sizeof(struct mac802154_open_s)); + opriv = (FAR struct mac802154dev_open_s *) + kmm_zalloc(sizeof(struct mac802154dev_open_s)); if (!opriv) { @@ -238,9 +256,9 @@ static int mac802154dev_close(FAR struct file *filep) { FAR struct inode *inode; FAR struct mac802154_devwrapper_s *dev; - FAR struct mac802154_open_s *opriv; - FAR struct mac802154_open_s *curr; - FAR struct mac802154_open_s *prev; + FAR struct mac802154dev_open_s *opriv; + FAR struct mac802154dev_open_s *curr; + FAR struct mac802154dev_open_s *prev; irqstate_t flags; bool closing; int ret; @@ -431,7 +449,13 @@ static ssize_t mac802154dev_write(FAR struct file *filep, /* Wait for the DATA.confirm callback to be called for our handle */ - sem_wait(&dwait.mw_sem); + if(sem_wait(dwait.mw_sem) < 0) + { + /* This should only happen if the wait was canceled by an signal */ + + DEBUGASSERT(errno == EINTR); + return -EINTR; + } /* The unlinking of the wait struct happens inside the callback. This * is more efficient since it will already have to find the struct in @@ -476,6 +500,57 @@ static int mac802154dev_ioctl(FAR struct file *filep, int cmd, switch (cmd) { +#ifndef CONFIG_DISABLE_SIGNALS + /* Command: MAC802154IOC_MLME_REGISTER, MAC802154IOC_MCPS_REGISTER + * Description: Register to receive a signal whenever there is a + * event primitive sent from the MAC layer. + * Argument: A read-only pointer to an instance of struct + * mac802154dev_notify_s + * Return: Zero (OK) on success. Minus one will be returned on + * failure with the errno value set appropriately. + */ + + case MAC802154IOC_MLME_REGISTER: + { + FAR struct mac802154dev_notify_s *notify = + (FAR struct mac802154dev_notify_s *)((uintptr_t)arg); + + if (notify) + { + /* Save the notification events */ + + dev->md_mlme_notify.mn_signo = notify->mn_signo; + dev->md_mlme_pid = getpid(); + + return OK; + } + } + break; + case MAC802154IOC_MCPS_REGISTER: + { + FAR struct mac802154dev_notify_s *notify = + (FAR struct mac802154dev_notify_s *)((uintptr_t)arg); + + if (notify) + { + /* Save the notification events */ + + dev->md_mcps_notify.mn_signo = notify->mn_signo; + dev->md_mcps_pid = getpid(); + + return OK; + } + } + break; +#endif + case MAC802154IOC_MLME_ASSOC_REQUEST: + { + FAR struct ieee802154_assoc_req_s *req = + (FAR struct ieee802154_assoc_req_s *)((uintptr_t)arg); + + + } + break; default: wlerr("ERROR: Unrecognized command %ld\n", cmd); ret = -EINVAL; @@ -501,20 +576,63 @@ void mac802154dev_conf_data(MACHANDLE mac, */ #warning Missing logic - /* Get exclusive access to the driver structure */ - - ret = mac802154dev_takesem(&dev->md_exclsem); - if (ret < 0) - { - wlerr("ERROR: mac802154dev_takesem failed: %d\n", ret); - return; - } + /* Get exclusive access to the driver structure. We don't care about any + * signals so if we see one, just go back to trying to get access again */ + + while(mac802154dev_takesem(&dev->md_exclsem) != OK); /* Search to see if there is a dwait pending for this transaction */ for (prev = NULL, curr = dev->md_dwait; curr && curr->mw_handle != conf->msdu_handle; prev = curr, curr = curr->mw_flink); + + /* If a dwait is found */ + + if (curr) + { + /* Unlink the structure from the list. The struct should be allocated on + * the calling write's stack, so we don't need to worry about deallocating + * here */ + + if (prev) + { + prev->mw_flink = curr->mw_flink; + } + else + { + dev->md_dwait = curr->mw_flink; + } + + /* Copy the transmission status into the dwait struct */ + + curr->mw_status = conf->msdu_handle; + + /* Wake the thread waiting for the data transmission */ + + sem_post(&curr->mw_sem); + + /* Release the driver */ + + mac802154dev_givesem(&dev->md_exclsem); + } + + +#ifndef CONFIG_DISABLE_SIGNALS + /* Send a signal to the registered application */ + +#ifdef CONFIG_CAN_PASS_STRUCTS + /* Copy the status as the signal data to be optionally used by app */ + + union sigval value; + value.sival_int = (int)conf->status; + (void)sigqueue(dev->md_mcps_pid, dev->md_mcps_notify.mn_signo, value); +#else + (void)sigqueue(dev->md_mcps_pid, dev->md_mcps_notify.mn_signo, + value.sival_ptr); +#endif + +#endif } /**************************************************************************** -- GitLab From dce2e774df9724f81dcd458f58a2cd14316da487 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Thu, 6 Apr 2017 09:38:09 -0400 Subject: [PATCH 459/990] wireless/ieee802154: Fixes comments from previous commit --- include/nuttx/wireless/ieee802154/ieee802154_mac.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index 1a7929cb3e..d26bda9529 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -916,17 +916,17 @@ struct ieee802154_maccb_s CODE void (*conf_disassociate)(MACHANDLE mac, int status); - /* PIvoata returned */ + /* PIB data returned */ CODE void (*conf_get)(MACHANDLE mac, int status, int attribute, FAR uint8_t *value, int valuelen); - /* GTvoanagement completed */ + /* GTS management completed */ CODE void (*conf_gts)(MACHANDLE mac, FAR uint8_t *characteristics, int status); - /* MAveset completed */ + /* MAC reset completed */ CODE void (*conf_reset)(MACHANDLE mac, int status); -- GitLab From 54939d46160172eddacf493a5ac89fb9002ee240 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 15 Apr 2017 10:23:29 -0600 Subject: [PATCH 460/990] network IOCTLs: Some corrections and updates to a previous commit --- net/Kconfig | 1 + net/netdev/netdev_ioctl.c | 28 ++++++++++++++++++++++------ 2 files changed, 23 insertions(+), 6 deletions(-) diff --git a/net/Kconfig b/net/Kconfig index da5eab15d2..49e927193d 100644 --- a/net/Kconfig +++ b/net/Kconfig @@ -136,6 +136,7 @@ config NET_6LOWPAN default n select NETDEV_MULTINIC if NET_ETHERNET || NET_LOOPBACK || NET_SLIP || NET_TUN select NET_MULTILINK if NET_ETHERNET || NET_LOOPBACK || NET_SLIP || NET_TUN + select NETDEV_IOCTL depends on EXPERIMENTAL && NET_IPv6 ---help--- Enable support for IEEE 802.15.4 Low power Wireless Personal Area diff --git a/net/netdev/netdev_ioctl.c b/net/netdev/netdev_ioctl.c index 3b5ca1f4e1..bc4d670379 100644 --- a/net/netdev/netdev_ioctl.c +++ b/net/netdev/netdev_ioctl.c @@ -70,11 +70,12 @@ #ifdef CONFIG_NETDEV_WIRELESS_IOCTL # include -#ifdef CONFIG_NET_6LOWPAN +#endif + +#if defined(CONFIG_NETDEV_IOCTL) && defined(CONFIG_NET_6LOWPAN) # include # include #endif -#endif #include "arp/arp.h" #include "socket/socket.h" @@ -379,7 +380,7 @@ static int netdev_iee802154_ioctl(FAR struct socket *psock, int cmd, FAR char *ifname; int ret = -ENOTTY; - if (req != NULL) + if (arg != 0ul) { /* Verify that this is either a valid IEEE802.15.4 radio IOCTL command * or a valid IEEE802.15.4 MAC IOCTL command. @@ -414,9 +415,15 @@ static int netdev_iee802154_ioctl(FAR struct socket *psock, int cmd, return -ENOTTY; } - /* Perform the device IOCTL */ + /* Find the device with this name */ + + dev = netdev_findbyname(ifname); + if (dev != NULL) + { + /* Perform the device IOCTL */ - ret = dev->d_ioctl(dev, cmd, arg); + ret = dev->d_ioctl(dev, cmd, arg); + } } return ret; @@ -1301,7 +1308,7 @@ int psock_ioctl(FAR struct socket *psock, int cmd, unsigned long arg) ret = netdev_ifrioctl(psock, cmd, (FAR struct ifreq *)((uintptr_t)arg)); #if defined(CONFIG_NETDEV_IOCTL) && defined(CONFIG_NETDEV_WIRELESS_IOCTL) - /* Check a wireless network command */ + /* Check for a wireless network command */ if (ret == -ENOTTY) { @@ -1309,6 +1316,15 @@ int psock_ioctl(FAR struct socket *psock, int cmd, unsigned long arg) } #endif +#if defined(CONFIG_NETDEV_IOCTL) && defined(CONFIG_NET_6LOWPAN) + /* Check for a IEEE802.15.4 network device command */ + + if (ret == -ENOTTY) + { + ret = netdev_iee802154_ioctl(psock, cmd, arg); + } +#endif + #ifdef CONFIG_NET_IGMP /* Check for address filtering commands */ -- GitLab From ebf05cb9f56278b03965f86ea8a1c33634cbfec5 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 15 Apr 2017 10:29:37 -0600 Subject: [PATCH 461/990] network IOCTL: Clean up some naming and spacing. --- net/netdev/netdev_ioctl.c | 163 ++++++++++++++++++++------------------ 1 file changed, 84 insertions(+), 79 deletions(-) diff --git a/net/netdev/netdev_ioctl.c b/net/netdev/netdev_ioctl.c index 8abe8aaf18..a0c58491df 100644 --- a/net/netdev/netdev_ioctl.c +++ b/net/netdev/netdev_ioctl.c @@ -100,7 +100,7 @@ ****************************************************************************/ /**************************************************************************** - * Name: ioctl_addipv4route + * Name: ioctl_add_ipv4route * * Description: * Add an IPv4 route to the routing table. @@ -111,7 +111,7 @@ ****************************************************************************/ #if defined(CONFIG_NET_ROUTE) && defined(CONFIG_NET_IPv4) -static int ioctl_addipv4route(FAR struct rtentry *rtentry) +static int ioctl_add_ipv4route(FAR struct rtentry *rtentry) { FAR struct sockaddr_in *addr; in_addr_t target; @@ -152,7 +152,7 @@ static int ioctl_addipv4route(FAR struct rtentry *rtentry) ****************************************************************************/ #if defined(CONFIG_NET_ROUTE) && defined(CONFIG_NET_IPv6) -static int ioctl_addipv6route(FAR struct rtentry *rtentry) +static int ioctl_add_ipv4route(FAR struct rtentry *rtentry) { FAR struct sockaddr_in6 *target; FAR struct sockaddr_in6 *netmask; @@ -179,7 +179,7 @@ static int ioctl_addipv6route(FAR struct rtentry *rtentry) #endif /* CONFIG_NET_ROUTE && CONFIG_NET_IPv6 */ /**************************************************************************** - * Name: ioctl_delipv4route + * Name: ioctl_del_ipv4route * * Description: * Delete an IPv4 route to the routing table. @@ -190,7 +190,7 @@ static int ioctl_addipv6route(FAR struct rtentry *rtentry) ****************************************************************************/ #if defined(CONFIG_NET_ROUTE) && defined(CONFIG_NET_IPv4) -static int ioctl_delipv4route(FAR struct rtentry *rtentry) +static int ioctl_del_ipv4route(FAR struct rtentry *rtentry) { FAR struct sockaddr_in *addr; in_addr_t target; @@ -207,7 +207,7 @@ static int ioctl_delipv4route(FAR struct rtentry *rtentry) #endif /* CONFIG_NET_ROUTE && CONFIG_NET_IPv4 */ /**************************************************************************** - * Name: ioctl_delipv6route + * Name: ioctl_del_ipv6route * * Description: * Delete an IPv6 route to the routing table. @@ -218,7 +218,7 @@ static int ioctl_delipv4route(FAR struct rtentry *rtentry) ****************************************************************************/ #if defined(CONFIG_NET_ROUTE) && defined(CONFIG_NET_IPv6) -static int ioctl_delipv6route(FAR struct rtentry *rtentry) +static int ioctl_del_ipv6route(FAR struct rtentry *rtentry) { FAR struct sockaddr_in6 *target; FAR struct sockaddr_in6 *netmask; @@ -231,7 +231,7 @@ static int ioctl_delipv6route(FAR struct rtentry *rtentry) #endif /* CONFIG_NET_ROUTE && CONFIG_NET_IPv6 */ /**************************************************************************** - * Name: ioctl_getipv4addr + * Name: ioctl_get_ipv4addr * * Description: * Copy IP addresses from device structure to user memory. @@ -243,7 +243,8 @@ static int ioctl_delipv6route(FAR struct rtentry *rtentry) ****************************************************************************/ #ifdef CONFIG_NET_IPv4 -static void ioctl_getipv4addr(FAR struct sockaddr *outaddr, in_addr_t inaddr) +static void ioctl_get_ipv4addr(FAR struct sockaddr *outaddr, + in_addr_t inaddr) { FAR struct sockaddr_in *dest = (FAR struct sockaddr_in *)outaddr; dest->sin_family = AF_INET; @@ -253,7 +254,7 @@ static void ioctl_getipv4addr(FAR struct sockaddr *outaddr, in_addr_t inaddr) #endif /**************************************************************************** - * Name: ioctl_getipv6addr + * Name: ioctl_get_ipv6addr * * Description: * Copy IP addresses from device structure to user memory. @@ -265,8 +266,8 @@ static void ioctl_getipv4addr(FAR struct sockaddr *outaddr, in_addr_t inaddr) ****************************************************************************/ #ifdef CONFIG_NET_IPv6 -static void ioctl_getipv6addr(FAR struct sockaddr_storage *outaddr, - FAR const net_ipv6addr_t inaddr) +static void ioctl_get_ipv6addr(FAR struct sockaddr_storage *outaddr, + FAR const net_ipv6addr_t inaddr) { FAR struct sockaddr_in6 *dest = (FAR struct sockaddr_in6 *)outaddr; dest->sin6_family = AF_INET6; @@ -276,7 +277,7 @@ static void ioctl_getipv6addr(FAR struct sockaddr_storage *outaddr, #endif /**************************************************************************** - * Name: ioctl_setipv4addr + * Name: ioctl_set_ipv4addr * * Description: * Copy IP addresses from user memory into the device structure @@ -289,8 +290,8 @@ static void ioctl_getipv6addr(FAR struct sockaddr_storage *outaddr, ****************************************************************************/ #ifdef CONFIG_NET_IPv4 -static void ioctl_setipv4addr(FAR in_addr_t *outaddr, - FAR const struct sockaddr *inaddr) +static void ioctl_set_ipv4addr(FAR in_addr_t *outaddr, + FAR const struct sockaddr *inaddr) { FAR const struct sockaddr_in *src = (FAR const struct sockaddr_in *)inaddr; *outaddr = src->sin_addr.s_addr; @@ -298,7 +299,7 @@ static void ioctl_setipv4addr(FAR in_addr_t *outaddr, #endif /**************************************************************************** - * Name: ioctl_setipv6addr + * Name: ioctl_set_ipv6addr * * Description: * Copy IP addresses from user memory into the device structure @@ -311,8 +312,8 @@ static void ioctl_setipv4addr(FAR in_addr_t *outaddr, ****************************************************************************/ #ifdef CONFIG_NET_IPv6 -static void ioctl_setipv6addr(FAR net_ipv6addr_t outaddr, - FAR const struct sockaddr_storage *inaddr) +static void ioctl_set_ipv6addr(FAR net_ipv6addr_t outaddr, + FAR const struct sockaddr_storage *inaddr) { FAR const struct sockaddr_in6 *src = (FAR const struct sockaddr_in6 *)inaddr; memcpy(outaddr, src->sin6_addr.in6_u.u6_addr8, 16); @@ -320,7 +321,7 @@ static void ioctl_setipv6addr(FAR net_ipv6addr_t outaddr, #endif /**************************************************************************** - * Name: netdev_wifrdev + * Name: netdev_wifr_dev * * Description: * Verify the struct iwreq and get the Wireless device. @@ -334,7 +335,7 @@ static void ioctl_setipv6addr(FAR net_ipv6addr_t outaddr, ****************************************************************************/ #if defined(CONFIG_NETDEV_IOCTL) && defined(CONFIG_NETDEV_WIRELESS_IOCTL) -static FAR struct net_driver_s *netdev_wifrdev(FAR struct iwreq *req) +static FAR struct net_driver_s *netdev_wifr_dev(FAR struct iwreq *req) { if (req != NULL) { @@ -350,7 +351,7 @@ static FAR struct net_driver_s *netdev_wifrdev(FAR struct iwreq *req) #endif /**************************************************************************** - * Name: netdev_wifrioctl + * Name: netdev_wifr_ioctl * * Description: * Perform wireless network device specific operations. @@ -368,8 +369,8 @@ static FAR struct net_driver_s *netdev_wifrdev(FAR struct iwreq *req) ****************************************************************************/ #if defined(CONFIG_NETDEV_IOCTL) && defined(CONFIG_NETDEV_WIRELESS_IOCTL) -static int netdev_wifrioctl(FAR struct socket *psock, int cmd, - FAR struct iwreq *req) +static int netdev_wifr_ioctl(FAR struct socket *psock, int cmd, + FAR struct iwreq *req) { FAR struct net_driver_s *dev; int ret = -ENOTTY; @@ -380,7 +381,7 @@ static int netdev_wifrioctl(FAR struct socket *psock, int cmd, { /* Get the wireless device associated with the IOCTL command */ - dev = netdev_wifrdev(req); + dev = netdev_wifr_dev(req); if (dev) { /* Just forward the IOCTL to the wireless driver */ @@ -394,7 +395,7 @@ static int netdev_wifrioctl(FAR struct socket *psock, int cmd, #endif /**************************************************************************** - * Name: netdev_ifrdev + * Name: netdev_ifr_dev * * Description: * Verify the struct ifreq and get the Ethernet device. @@ -407,7 +408,7 @@ static int netdev_wifrioctl(FAR struct socket *psock, int cmd, * ****************************************************************************/ -static FAR struct net_driver_s *netdev_ifrdev(FAR struct ifreq *req) +static FAR struct net_driver_s *netdev_ifr_dev(FAR struct ifreq *req) { if (req != NULL) { @@ -422,7 +423,7 @@ static FAR struct net_driver_s *netdev_ifrdev(FAR struct ifreq *req) } /**************************************************************************** - * Name: netdev_ifrioctl + * Name: netdev_ifr_ioctl * * Description: * Perform network device specific operations. @@ -438,8 +439,8 @@ static FAR struct net_driver_s *netdev_ifrdev(FAR struct ifreq *req) * ****************************************************************************/ -static int netdev_ifrioctl(FAR struct socket *psock, int cmd, - FAR struct ifreq *req) +static int netdev_ifr_ioctl(FAR struct socket *psock, int cmd, + FAR struct ifreq *req) { FAR struct net_driver_s *dev; int ret = -EINVAL; @@ -453,10 +454,10 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, #ifdef CONFIG_NET_IPv4 case SIOCGIFADDR: /* Get IP address */ { - dev = netdev_ifrdev(req); + dev = netdev_ifr_dev(req); if (dev) { - ioctl_getipv4addr(&req->ifr_addr, dev->d_ipaddr); + ioctl_get_ipv4addr(&req->ifr_addr, dev->d_ipaddr); ret = OK; } } @@ -467,11 +468,11 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, #ifdef CONFIG_NET_IPv4 case SIOCSIFADDR: /* Set IP address */ { - dev = netdev_ifrdev(req); + dev = netdev_ifr_dev(req); if (dev) { netdev_ifdown(dev); - ioctl_setipv4addr(&dev->d_ipaddr, &req->ifr_addr); + ioctl_set_ipv4addr(&dev->d_ipaddr, &req->ifr_addr); netdev_ifup(dev); ret = OK; } @@ -482,10 +483,10 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, #ifdef CONFIG_NET_IPv4 case SIOCGIFDSTADDR: /* Get P-to-P address */ { - dev = netdev_ifrdev(req); + dev = netdev_ifr_dev(req); if (dev) { - ioctl_getipv4addr(&req->ifr_dstaddr, dev->d_draddr); + ioctl_get_ipv4addr(&req->ifr_dstaddr, dev->d_draddr); ret = OK; } } @@ -495,10 +496,10 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, #ifdef CONFIG_NET_IPv4 case SIOCSIFDSTADDR: /* Set P-to-P address */ { - dev = netdev_ifrdev(req); + dev = netdev_ifr_dev(req); if (dev) { - ioctl_setipv4addr(&dev->d_draddr, &req->ifr_dstaddr); + ioctl_set_ipv4addr(&dev->d_draddr, &req->ifr_dstaddr); ret = OK; } } @@ -517,10 +518,10 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, #ifdef CONFIG_NET_IPv4 case SIOCGIFNETMASK: /* Get network mask */ { - dev = netdev_ifrdev(req); + dev = netdev_ifr_dev(req); if (dev) { - ioctl_getipv4addr(&req->ifr_addr, dev->d_netmask); + ioctl_get_ipv4addr(&req->ifr_addr, dev->d_netmask); ret = OK; } } @@ -530,10 +531,10 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, #ifdef CONFIG_NET_IPv4 case SIOCSIFNETMASK: /* Set network mask */ { - dev = netdev_ifrdev(req); + dev = netdev_ifr_dev(req); if (dev) { - ioctl_setipv4addr(&dev->d_netmask, &req->ifr_addr); + ioctl_set_ipv4addr(&dev->d_netmask, &req->ifr_addr); ret = OK; } } @@ -543,12 +544,12 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, #ifdef CONFIG_NET_IPv6 case SIOCGLIFADDR: /* Get IP address */ { - dev = netdev_ifrdev(req); + dev = netdev_ifr_dev(req); if (dev) { FAR struct lifreq *lreq = (FAR struct lifreq *)req; - ioctl_getipv6addr(&lreq->lifr_addr, dev->d_ipv6addr); + ioctl_get_ipv6addr(&lreq->lifr_addr, dev->d_ipv6addr); ret = OK; } } @@ -558,13 +559,13 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, #ifdef CONFIG_NET_IPv6 case SIOCSLIFADDR: /* Set IP address */ { - dev = netdev_ifrdev(req); + dev = netdev_ifr_dev(req); if (dev) { FAR struct lifreq *lreq = (FAR struct lifreq *)req; netdev_ifdown(dev); - ioctl_setipv6addr(dev->d_ipv6addr, &lreq->lifr_addr); + ioctl_set_ipv6addr(dev->d_ipv6addr, &lreq->lifr_addr); netdev_ifup(dev); ret = OK; } @@ -575,12 +576,12 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, #ifdef CONFIG_NET_IPv6 case SIOCGLIFDSTADDR: /* Get P-to-P address */ { - dev = netdev_ifrdev(req); + dev = netdev_ifr_dev(req); if (dev) { FAR struct lifreq *lreq = (FAR struct lifreq *)req; - ioctl_getipv6addr(&lreq->lifr_dstaddr, dev->d_ipv6draddr); + ioctl_get_ipv6addr(&lreq->lifr_dstaddr, dev->d_ipv6draddr); ret = OK; } } @@ -590,12 +591,12 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, #ifdef CONFIG_NET_IPv6 case SIOCSLIFDSTADDR: /* Set P-to-P address */ { - dev = netdev_ifrdev(req); + dev = netdev_ifr_dev(req); if (dev) { FAR struct lifreq *lreq = (FAR struct lifreq *)req; - ioctl_setipv6addr(dev->d_ipv6draddr, &lreq->lifr_dstaddr); + ioctl_set_ipv6addr(dev->d_ipv6draddr, &lreq->lifr_dstaddr); ret = OK; } } @@ -614,12 +615,12 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, #ifdef CONFIG_NET_IPv6 case SIOCGLIFNETMASK: /* Get network mask */ { - dev = netdev_ifrdev(req); + dev = netdev_ifr_dev(req); if (dev) { FAR struct lifreq *lreq = (FAR struct lifreq *)req; - ioctl_getipv6addr(&lreq->lifr_addr, dev->d_ipv6netmask); + ioctl_get_ipv6addr(&lreq->lifr_addr, dev->d_ipv6netmask); ret = OK; } } @@ -629,11 +630,11 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, #ifdef CONFIG_NET_IPv6 case SIOCSLIFNETMASK: /* Set network mask */ { - dev = netdev_ifrdev(req); + dev = netdev_ifr_dev(req); if (dev) { FAR struct lifreq *lreq = (FAR struct lifreq *)req; - ioctl_setipv6addr(dev->d_ipv6netmask, &lreq->lifr_addr); + ioctl_set_ipv6addr(dev->d_ipv6netmask, &lreq->lifr_addr); ret = OK; } } @@ -643,7 +644,7 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, case SIOCGLIFMTU: /* Get MTU size */ case SIOCGIFMTU: /* Get MTU size */ { - dev = netdev_ifrdev(req); + dev = netdev_ifr_dev(req); if (dev) { req->ifr_mtu = NET_DEV_MTU(dev); @@ -655,7 +656,7 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, #ifdef CONFIG_NET_ICMPv6_AUTOCONF case SIOCIFAUTOCONF: /* Perform ICMPv6 auto-configuration */ { - dev = netdev_ifrdev(req); + dev = netdev_ifr_dev(req); if (dev) { ret = icmpv6_autoconfig(dev); @@ -668,7 +669,7 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, { /* Is this a request to bring the interface up? */ - dev = netdev_ifrdev(req); + dev = netdev_ifr_dev(req); if (dev) { if ((req->ifr_flags & IFF_UP) != 0) @@ -694,7 +695,7 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, case SIOCGIFFLAGS: /* Gets the interface flags */ { - dev = netdev_ifrdev(req); + dev = netdev_ifr_dev(req); if (dev) { req->ifr_flags = dev->d_flags; @@ -709,7 +710,7 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, #if defined(CONFIG_NET_ETHERNET) || defined(CONFIG_NET_6LOWPAN) case SIOCGIFHWADDR: /* Get hardware address */ { - dev = netdev_ifrdev(req); + dev = netdev_ifr_dev(req); if (dev) { #ifdef CONFIG_NET_ETHERNET @@ -753,7 +754,7 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, case SIOCSIFHWADDR: /* Set hardware address -- will not take effect until ifup */ { - dev = netdev_ifrdev(req); + dev = netdev_ifr_dev(req); if (dev) { #ifdef CONFIG_NET_ETHERNET @@ -797,7 +798,7 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, case SIOCDIFADDR: /* Delete IP address */ { - dev = netdev_ifrdev(req); + dev = netdev_ifr_dev(req); if (dev) { netdev_ifdown(dev); @@ -823,7 +824,7 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, #ifdef CONFIG_ARCH_PHY_INTERRUPT case SIOCMIINOTIFY: /* Set up for PHY event notifications */ { - dev = netdev_ifrdev(req); + dev = netdev_ifr_dev(req); if (dev && dev->d_ioctl) { struct mii_iotcl_notify_s *notify = &req->ifr_ifru.ifru_mii_notify; @@ -837,7 +838,7 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, case SIOCGMIIREG: /* Get MII register via MDIO */ case SIOCSMIIREG: /* Set MII register via MDIO */ { - dev = netdev_ifrdev(req); + dev = netdev_ifr_dev(req); if (dev && dev->d_ioctl) { struct mii_ioctl_data_s *mii_data = &req->ifr_ifru.ifru_mii_data; @@ -888,7 +889,7 @@ static FAR struct net_driver_s *netdev_imsfdev(FAR struct ip_msfilter *imsf) #endif /**************************************************************************** - * Name: netdev_imsfioctl + * Name: netdev_imsf_ioctl * * Description: * Perform network device specific operations. @@ -906,8 +907,8 @@ static FAR struct net_driver_s *netdev_imsfdev(FAR struct ip_msfilter *imsf) ****************************************************************************/ #ifdef CONFIG_NET_IGMP -static int netdev_imsfioctl(FAR struct socket *psock, int cmd, - FAR struct ip_msfilter *imsf) +static int netdev_imsf_ioctl(FAR struct socket *psock, int cmd, + FAR struct ip_msfilter *imsf) { FAR struct net_driver_s *dev; int ret = -EINVAL; @@ -947,7 +948,7 @@ static int netdev_imsfioctl(FAR struct socket *psock, int cmd, #endif /**************************************************************************** - * Name: netdev_arpioctl + * Name: netdev_arp_ioctl * * Description: * Perform ARP table specific operations. @@ -965,8 +966,8 @@ static int netdev_imsfioctl(FAR struct socket *psock, int cmd, ****************************************************************************/ #ifdef CONFIG_NET_ARP -static int netdev_arpioctl(FAR struct socket *psock, int cmd, - FAR struct arpreq *req) +static int netdev_arp_ioctl(FAR struct socket *psock, int cmd, + FAR struct arpreq *req) { int ret; @@ -1070,7 +1071,7 @@ static int netdev_arpioctl(FAR struct socket *psock, int cmd, #endif /**************************************************************************** - * Name: netdev_rtioctl + * Name: netdev_rt_ioctl * * Description: * Perform routing table specific operations. @@ -1088,8 +1089,8 @@ static int netdev_arpioctl(FAR struct socket *psock, int cmd, ****************************************************************************/ #ifdef CONFIG_NET_ROUTE -static int netdev_rtioctl(FAR struct socket *psock, int cmd, - FAR struct rtentry *rtentry) +static int netdev_rt_ioctl(FAR struct socket *psock, int cmd, + FAR struct rtentry *rtentry) { int ret = -EAFNOSUPPORT; @@ -1111,7 +1112,7 @@ static int netdev_rtioctl(FAR struct socket *psock, int cmd, if (rtentry->rt_target->ss_family == AF_INET) #endif { - ret = ioctl_addipv4route(rtentry); + ret = ioctl_add_ipv4route(rtentry); } #endif /* CONFIG_NET_IPv4 */ @@ -1140,7 +1141,7 @@ static int netdev_rtioctl(FAR struct socket *psock, int cmd, if (rtentry->rt_target->ss_family == AF_INET) #endif { - ret = ioctl_delipv4route(rtentry); + ret = ioctl_del_ipv4route(rtentry); } #endif /* CONFIG_NET_IPv4 */ @@ -1149,7 +1150,7 @@ static int netdev_rtioctl(FAR struct socket *psock, int cmd, else #endif { - ret = ioctl_delipv6route(rtentry); + ret = ioctl_del_ipv6route(rtentry); } #endif /* CONFIG_NET_IPv6 */ } @@ -1224,14 +1225,15 @@ int psock_ioctl(FAR struct socket *psock, int cmd, unsigned long arg) /* Execute the command. First check for a standard network IOCTL command. */ - ret = netdev_ifrioctl(psock, cmd, (FAR struct ifreq *)((uintptr_t)arg)); + ret = netdev_ifr_ioctl(psock, cmd, (FAR struct ifreq *)((uintptr_t)arg)); #if defined(CONFIG_NETDEV_IOCTL) && defined(CONFIG_NETDEV_WIRELESS_IOCTL) /* Check a wireless network command */ if (ret == -ENOTTY) { - ret = netdev_wifrioctl(psock, cmd, (FAR struct iwreq *)((uintptr_t)arg)); + ret = netdev_wifr_ioctl(psock, cmd, + (FAR struct iwreq *)((uintptr_t)arg)); } #endif @@ -1240,7 +1242,8 @@ int psock_ioctl(FAR struct socket *psock, int cmd, unsigned long arg) if (ret == -ENOTTY) { - ret = netdev_imsfioctl(psock, cmd, (FAR struct ip_msfilter *)((uintptr_t)arg)); + ret = netdev_imsf_ioctl(psock, cmd, + (FAR struct ip_msfilter *)((uintptr_t)arg)); } #endif @@ -1249,7 +1252,8 @@ int psock_ioctl(FAR struct socket *psock, int cmd, unsigned long arg) if (ret == -ENOTTY) { - ret = netdev_arpioctl(psock, cmd, (FAR struct arpreq *)((uintptr_t)arg)); + ret = netdev_arp_ioctl(psock, cmd, + (FAR struct arpreq *)((uintptr_t)arg)); } #endif @@ -1258,7 +1262,8 @@ int psock_ioctl(FAR struct socket *psock, int cmd, unsigned long arg) if (ret == -ENOTTY) { - ret = netdev_rtioctl(psock, cmd, (FAR struct rtentry *)((uintptr_t)arg)); + ret = netdev_rt_ioctl(psock, cmd, + (FAR struct rtentry *)((uintptr_t)arg)); } #endif -- GitLab From d9e2139e46789aac8dfb9f8b7995ddf71a7070c8 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Sat, 15 Apr 2017 13:20:33 -0400 Subject: [PATCH 462/990] wireless/ieee802154/mrf24j40: Renaming, added bind method --- drivers/wireless/ieee802154/mrf24j40.c | 330 ++++++++++++++----------- 1 file changed, 180 insertions(+), 150 deletions(-) diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c index 263de68eeb..32da714bca 100644 --- a/drivers/wireless/ieee802154/mrf24j40.c +++ b/drivers/wireless/ieee802154/mrf24j40.c @@ -3,6 +3,7 @@ * * Copyright (C) 2015-2016 Sebastien Lorquet. All rights reserved. * Author: Sebastien Lorquet + * Author: Anthony Merlino * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -101,10 +102,16 @@ struct mrf24j40_radio_s { - struct ieee802154_radio_s ieee; /* The public device instance */ + struct ieee802154_radio_s radio; /* The public device instance */ + + /* Reference to the bound upper layer via the phyif interface */ + + FAR const struct ieee802154_phyif_s *phyif; + FAR struct spi_dev_s *spi; /* Saved SPI interface instance */ struct work_s irqwork; /* Interrupt continuation work queue support */ FAR const struct mrf24j40_lower_s *lower; /* Low-level MCU-specific support */ + sem_t excl_sem; /* Exclusive access to this struct */ uint16_t panid; /* PAN identifier, FFFF = not set */ uint16_t saddr; /* short address, FFFF = not set */ @@ -115,6 +122,13 @@ struct mrf24j40_radio_s uint8_t rxmode; /* Reception mode: Main, no CRC, promiscuous */ int32_t txpower; /* TX power in mBm = dBm/100 */ struct ieee802154_cca_s cca; /* Clear channel assessement method */ + + /* Buffer Allocations */ + + struct ieee802154_txdesc_s csma_desc; + struct ieee802154_txdesc_s gts_desc[2]; + + uint8_t tx_buf[CONFIG_IEEE802154_MTU]; }; /**************************************************************************** @@ -123,7 +137,7 @@ struct mrf24j40_radio_s /* Internal operations */ -static void mrf24j40_lock(FAR struct spi_dev_s *spi); +static void mrf24j40_spi_lock(FAR struct spi_dev_s *spi); static void mrf24j40_setreg(FAR struct spi_dev_s *spi, uint32_t addr, uint8_t val); @@ -142,48 +156,50 @@ static int mrf24j40_interrupt(int irq, FAR void *context, FAR void *arg); /* IOCTL helpers */ -static int mrf24j40_setchannel(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_setchannel(FAR struct ieee802154_radio_s *radio, uint8_t chan); -static int mrf24j40_getchannel(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_getchannel(FAR struct ieee802154_radio_s *radio, FAR uint8_t *chan); -static int mrf24j40_setpanid(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_setpanid(FAR struct ieee802154_radio_s *radio, uint16_t panid); -static int mrf24j40_getpanid(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_getpanid(FAR struct ieee802154_radio_s *radio, FAR uint16_t *panid); -static int mrf24j40_setsaddr(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_setsaddr(FAR struct ieee802154_radio_s *radio, uint16_t saddr); -static int mrf24j40_getsaddr(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_getsaddr(FAR struct ieee802154_radio_s *radio, FAR uint16_t *saddr); -static int mrf24j40_seteaddr(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_seteaddr(FAR struct ieee802154_radio_s *radio, FAR uint8_t *eaddr); -static int mrf24j40_geteaddr(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_geteaddr(FAR struct ieee802154_radio_s *radio, FAR uint8_t *eaddr); -static int mrf24j40_setpromisc(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_setpromisc(FAR struct ieee802154_radio_s *radio, bool promisc); -static int mrf24j40_getpromisc(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_getpromisc(FAR struct ieee802154_radio_s *radio, FAR bool *promisc); -static int mrf24j40_setdevmode(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_setdevmode(FAR struct ieee802154_radio_s *radio, uint8_t mode); -static int mrf24j40_getdevmode(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_getdevmode(FAR struct ieee802154_radio_s *radio, FAR uint8_t *mode); -static int mrf24j40_settxpower(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_settxpower(FAR struct ieee802154_radio_s *radio, int32_t txpwr); -static int mrf24j40_gettxpower(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_gettxpower(FAR struct ieee802154_radio_s *radio, FAR int32_t *txpwr); -static int mrf24j40_setcca(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_setcca(FAR struct ieee802154_radio_s *radio, FAR struct ieee802154_cca_s *cca); -static int mrf24j40_getcca(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_getcca(FAR struct ieee802154_radio_s *radio, FAR struct ieee802154_cca_s *cca); -static int mrf24j40_energydetect(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_energydetect(FAR struct ieee802154_radio_s *radio, FAR uint8_t *energy); /* Driver operations */ -static int mrf24j40_ioctl(FAR struct ieee802154_radio_s *ieee, int cmd, +static int mrf24j40_bind(FAR struct ieee802154_radio_s *radio, + FAR struct ieee802154_phyif_s *phyif); +static int mrf24j40_ioctl(FAR struct ieee802154_radio_s *radio, int cmd, unsigned long arg); -static int mrf24j40_rxenable(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_rxenable(FAR struct ieee802154_radio_s *radio, bool state, FAR struct ieee802154_packet_s *packet); -static int mrf24j40_transmit(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_transmit(FAR struct ieee802154_radio_s *radio, FAR struct ieee802154_packet_s *packet); /**************************************************************************** @@ -197,10 +213,9 @@ static int mrf24j40_transmit(FAR struct ieee802154_radio_s *ieee, * using the IRQ number. See the ENC28J60 or CC3000 drivers for reference. */ -static struct mrf24j40_radio_s g_mrf24j40_devices[1]; - static const struct ieee802154_radioops_s mrf24j40_devops = { + mrf24j40_bind, mrf24j40_ioctl, mrf24j40_rxenable, mrf24j40_transmit @@ -210,15 +225,73 @@ static const struct ieee802154_radioops_s mrf24j40_devops = * Private Functions ****************************************************************************/ +static void mrf24j40_bind(FAR struct ieee802154_radio_s *radio, + FAR struct ieee802154_phyif_s *phyif) +{ + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)radio; + + DEBUGASSERT(dev != NULL); + dev->phyif = phyif; + return OK; +} + /**************************************************************************** - * Name: mrf24j40_lock + * Function: mrf24j40_txavail + * + * Description: + * Called from the upper layer, this function is to notify the device that + * the upper layer has a pending transaction. This function checks to see + * if there is availability for the corresponding transaction type. If + * there is, the function will call to the MAC layer to get the transaction + * and then start the transmission + * + ****************************************************************************/ + +static void mrf24j40_txavail(FAR struct ieee802154_radio_s *radio, bool gts) +{ + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)radio; + uint8_t gts; + + while (sem_wait(dev->exclsem) < 0) { } + + /* If this a CSMA transaction and we have room in the CSMA fifo */ + + if (!gts && !dev->csma_busy) + { + /* need to somehow allow for a handle to be passed */ + + ret = dev->phyif->poll_csma(dev->phyif, &radio->csma_txdesc, + &dev->tx_buf[0]); + + /* Setup the transmit on the device */ + + } + else + { + for(gts = 0; gts < MRF24J40_GTS_SLOTS, gts++) + { + if(!dev->gts_txdesc[i].busy) + { + ret = dev->phyif->poll_gts(dev->phyif, &radio->gts_txdesc[i], + &dev->tx_buf[0]); + + /* Setup the transmit on the device */ + + break; + } + } + } +} + +/**************************************************************************** + * Name: mrf24j40_spi_lock * * Description: * Acquire exclusive access to the shared SPI bus. * ****************************************************************************/ -static void mrf24j40_lock(FAR struct spi_dev_s *spi) +static void mrf24j40_spi_lock(FAR struct spi_dev_s *spi) { SPI_LOCK(spi, 1); SPI_SETBITS(spi, 8); @@ -227,14 +300,14 @@ static void mrf24j40_lock(FAR struct spi_dev_s *spi) } /**************************************************************************** - * Name: mrf24j40_unlock + * Name: mrf24j40_spi_unlock * * Description: * Release exclusive access to the shared SPI bus. * ****************************************************************************/ -static inline void mrf24j40_unlock(FAR struct spi_dev_s *spi) +static inline void mrf24j40_spi_unlock(FAR struct spi_dev_s *spi) { SPI_LOCK(spi,0); } @@ -484,11 +557,8 @@ static int mrf24j40_setrxmode(FAR struct mrf24j40_radio_s *dev, int mode) * ****************************************************************************/ -static int mrf24j40_setchannel(FAR struct ieee802154_radio_s *ieee, - uint8_t chan) +static int mrf24j40_setchannel(FAR struct mrf24j40_radio_s *dev, uint8_t chan) { - FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; - if (chan < 11 || chan > 26) { wlerr("ERROR: Invalid chan: %d\n",chan); @@ -511,21 +581,11 @@ static int mrf24j40_setchannel(FAR struct ieee802154_radio_s *ieee, return OK; } -/**************************************************************************** - * Name: mrf24j40_getchannel - * - * Description: - * Define the current radio channel the device is operating on. - * - ****************************************************************************/ - -static int mrf24j40_getchannel(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_getchannel(FAR struct mrf24j40_radio_s *dev, FAR uint8_t *chan) { - FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; - - *chan = dev->channel; - + chan = dev->channel; + return OK; } @@ -537,11 +597,9 @@ static int mrf24j40_getchannel(FAR struct ieee802154_radio_s *ieee, * ****************************************************************************/ -static int mrf24j40_setpanid(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_setpanid(FAR struct mrf24j40_radio_s *dev, uint16_t panid) { - FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; - mrf24j40_setreg(dev->spi, MRF24J40_PANIDH, (uint8_t)(panid>>8)); mrf24j40_setreg(dev->spi, MRF24J40_PANIDL, (uint8_t)(panid&0xFF)); @@ -559,11 +617,9 @@ static int mrf24j40_setpanid(FAR struct ieee802154_radio_s *ieee, * ****************************************************************************/ -static int mrf24j40_getpanid(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_getpanid(FAR struct mrf24j40_radio_s *dev, FAR uint16_t *panid) { - FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; - *panid = dev->panid; return OK; @@ -579,11 +635,9 @@ static int mrf24j40_getpanid(FAR struct ieee802154_radio_s *ieee, * ****************************************************************************/ -static int mrf24j40_setsaddr(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_setsaddr(FAR struct mrf24j40_radio_s *dev, uint16_t saddr) { - FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; - mrf24j40_setreg(dev->spi, MRF24J40_SADRH, (uint8_t)(saddr>>8)); mrf24j40_setreg(dev->spi, MRF24J40_SADRL, (uint8_t)(saddr&0xFF)); @@ -600,11 +654,9 @@ static int mrf24j40_setsaddr(FAR struct ieee802154_radio_s *ieee, * ****************************************************************************/ -static int mrf24j40_getsaddr(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_getsaddr(FAR struct mrf24j40_radio_s *dev, FAR uint16_t *saddr) { - FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; - *saddr = dev->saddr; return OK; @@ -619,10 +671,9 @@ static int mrf24j40_getsaddr(FAR struct ieee802154_radio_s *ieee, * ****************************************************************************/ -static int mrf24j40_seteaddr(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_seteaddr(FAR struct mrf24j40_radio_s *dev, FAR uint8_t *eaddr) { - FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; int i; for (i = 0; i < 8; i++) @@ -642,11 +693,9 @@ static int mrf24j40_seteaddr(FAR struct ieee802154_radio_s *ieee, * ****************************************************************************/ -static int mrf24j40_geteaddr(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_geteaddr(FAR struct mrf24j40_radio_s *dev, FAR uint8_t *eaddr) { - FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; - memcpy(eaddr, dev->eaddr, 8); return OK; @@ -661,11 +710,9 @@ static int mrf24j40_geteaddr(FAR struct ieee802154_radio_s *ieee, * ****************************************************************************/ -static int mrf24j40_setpromisc(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_setpromisc(FAR struct mrf24j40_radio_s *dev, bool promisc) { - FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; - return mrf24j40_setrxmode(dev, promisc ? MRF24J40_RXMODE_PROMISC : MRF24J40_RXMODE_NORMAL); } @@ -678,11 +725,9 @@ static int mrf24j40_setpromisc(FAR struct ieee802154_radio_s *ieee, * ****************************************************************************/ -static int mrf24j40_getpromisc(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_getpromisc(FAR struct mrf24j40_radio_s *dev, FAR bool *promisc) { - FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; - *promisc = (dev->rxmode == MRF24J40_RXMODE_PROMISC); return OK; @@ -696,10 +741,9 @@ static int mrf24j40_getpromisc(FAR struct ieee802154_radio_s *ieee, * ****************************************************************************/ -static int mrf24j40_setdevmode(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_setdevmode(FAR struct mrf24j40_radio_s *dev, uint8_t mode) { - FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; int ret = OK; uint8_t reg; @@ -748,11 +792,9 @@ static int mrf24j40_setdevmode(FAR struct ieee802154_radio_s *ieee, * ****************************************************************************/ -static int mrf24j40_getdevmode(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_getdevmode(FAR struct mrf24j40_radio_s *dev, FAR uint8_t *mode) { - FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; - *mode = dev->devmode; return OK; @@ -768,10 +810,9 @@ static int mrf24j40_getdevmode(FAR struct ieee802154_radio_s *ieee, * ****************************************************************************/ -static int mrf24j40_settxpower(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_settxpower(FAR struct mrf24j40_radio_s *dev, int32_t txpwr) { - FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; uint8_t reg; int save_txpwr = txpwr; @@ -851,11 +892,9 @@ static int mrf24j40_settxpower(FAR struct ieee802154_radio_s *ieee, * ****************************************************************************/ -static int mrf24j40_gettxpower(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_gettxpower(FAR struct mrf24j40_radio_s *radio, FAR int32_t *txpwr) { - FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; - *txpwr = dev->txpower; return OK; @@ -869,10 +908,9 @@ static int mrf24j40_gettxpower(FAR struct ieee802154_radio_s *ieee, * ****************************************************************************/ -static int mrf24j40_setcca(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_setcca(FAR struct mrf24j40_radio_s *dev, FAR struct ieee802154_cca_s *cca) { - FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; uint8_t mode; if (!cca->use_ed && !cca->use_cs) @@ -914,11 +952,9 @@ static int mrf24j40_setcca(FAR struct ieee802154_radio_s *ieee, * ****************************************************************************/ -static int mrf24j40_getcca(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_getcca(FAR struct mrf24j40_radio_s *dev, FAR struct ieee802154_cca_s *cca) { - FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; - memcpy(cca, &dev->cca, sizeof(struct ieee802154_cca_s)); return OK; @@ -982,82 +1018,82 @@ static int mrf24j40_regdump(FAR struct mrf24j40_radio_s *dev) * ****************************************************************************/ -static int mrf24j40_ioctl(FAR struct ieee802154_radio_s *ieee, int cmd, +static int mrf24j40_ioctl(FAR struct ieee802154_radio_s *radio, int cmd, unsigned long arg) { - FAR struct mrf24j40_radio_s *dev = - (FAR struct mrf24j40_radio_s *)ieee; + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)radio; + FAR union ieee802154_radioarg_u *u; = (FAR union ieee802154_radioarg_u *)((uintptr_t)arg) switch(cmd) { case PHY802154IOC_SET_CHAN: - ret = mrf24j40_setchannel(ieee, u.channel); + ret = mrf24j40_setchannel(dev, u.channel); break; case PHY802154IOC_GET_CHAN: - ret = mrf24j40_getchannel(ieee, &u.channel); + ret = mrf24j40_getchannel(dev, &u.channel); break; case PHY802154IOC_SET_PANID: - ret = mrf24j40_setpanid(ieee, u.panid); + ret = mrf24j40_setpanid(dev, u.panid); break; case PHY802154IOC_GET_PANID: - ret = mrf24j40_getpanid(ieee, &u.panid); + ret = mrf24j40_getpanid(dev, &u.panid); break; case PHY802154IOC_SET_SADDR: - ret = mrf24j40_setsaddr(ieee, u.saddr); + ret = mrf24j40_setsaddr(dev, u.saddr); break; case PHY802154IOC_GET_SADDR: - ret = mrf24j40_getsaddr(ieee, &u.saddr); + ret = mrf24j40_getsaddr(dev, &u.saddr); break; case PHY802154IOC_SET_EADDR: - ret = mrf24j40_seteaddr(ieee, u.eaddr); + ret = mrf24j40_seteaddr(dev, u.eaddr); break; case PHY802154IOC_GET_EADDR: - ret = mrf24j40_geteaddr(ieee, u.eaddr); + ret = mrf24j40_geteaddr(dev, u.eaddr); break; case PHY802154IOC_SET_PROMISC: - ret = mrf24j40_setpromisc(ieee, u.promisc); + ret = mrf24j40_setpromisc(dev, u.promisc); break; case PHY802154IOC_GET_PROMISC: - ret = mrf24j40_getpromisc(ieee, &u.promisc); + ret = mrf24j40_getpromisc(dev, &u.promisc); break; case PHY802154IOC_SET_DEVMODE: - ret = mrf24j40_setdevmode(ieee, u.devmode); + ret = mrf24j40_setdevmode(dev, u.devmode); break; case PHY802154IOC_GET_DEVMODE: - ret = mrf24j40_getdevmode(ieee, &u.devmode); + ret = mrf24j40_getdevmode(dev, &u.devmode); break; case PHY802154IOC_SET_TXPWR: - ret = mrf24j40_settxpower(ieee, u.txpwr); + ret = mrf24j40_settxpower(dev, u.txpwr); break; case PHY802154IOC_GET_TXPWR: - ret = mrf24j40_gettxpower(ieee, &u.txpwr); + ret = mrf24j40_gettxpower(dev, &u.txpwr); break; case PHY802154IOC_SET_CCA: - ret = mrf24j40_setcca(ieee, &u.cca); + ret = mrf24j40_setcca(dev, &u.cca); break; case PHY802154IOC_GET_CCA: - ret = mrf24j40_getcca(ieee, &u.cca); + ret = mrf24j40_getcca(dev, &u.cca); break; case PHY802154IOC_ENERGYDETECT: - ret = mrf24j40_energydetect(ieee, &u.energy); + ret = mrf24j40_energydetect(dev, &u.energy); break; case 1000: @@ -1080,10 +1116,9 @@ static int mrf24j40_ioctl(FAR struct ieee802154_radio_s *ieee, int cmd, * ****************************************************************************/ -static int mrf24j40_energydetect(FAR struct ieee802154_radio_s *ieee, +static int mrf24j40_energydetect(FAR struct mrf24j40_radio_s *dev, FAR uint8_t *energy) { - FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; uint8_t reg; /* Manually enable the LNA*/ @@ -1130,10 +1165,10 @@ static int mrf24j40_energydetect(FAR struct ieee802154_radio_s *ieee, * ****************************************************************************/ -static int mrf24j40_transmit(FAR struct ieee802154_radio_s *ieee, - FAR struct ieee802154_packet_s *packet) +static int mrf24j40_transmit(FAR struct ieee802154_radio_s *radio, + uint8_t *buf, uint16_t buf_len) { - FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)radio; uint32_t addr; uint8_t reg; int ret; @@ -1152,8 +1187,8 @@ static int mrf24j40_transmit(FAR struct ieee802154_radio_s *ieee, /* Analyze frame control to compute header length */ - frame_ctrl = packet->data[0]; - frame_ctrl |= packet->data[1] << 8; + frame_ctrl = buf[0]; + frame_ctrl |= (buf[1] << 8); if ((frame_ctrl & IEEE802154_FRAMECTRL_DADDR)== IEEE802154_ADDRMODE_SHORT) { @@ -1184,11 +1219,11 @@ static int mrf24j40_transmit(FAR struct ieee802154_radio_s *ieee, /* Frame length */ - mrf24j40_setreg(dev->spi, addr++, packet->len); + mrf24j40_setreg(dev->spi, addr++, buflen); /* Frame data */ - for (ret = 0; ret < packet->len; ret++) /* this sets the correct val for ret */ + for (ret = 0; ret < buflen; ret++) /* this sets the correct val for ret */ { mrf24j40_setreg(dev->spi, addr++, packet->data[ret]); } @@ -1208,9 +1243,7 @@ static int mrf24j40_transmit(FAR struct ieee802154_radio_s *ieee, mrf24j40_setreg(dev->spi, MRF24J40_TXNCON, reg); - /* Suspend calling thread until transmit is complete */ - - return sem_wait(&ieee->txsem); + return ret; } /**************************************************************************** @@ -1232,9 +1265,9 @@ static void mrf24j40_irqwork_tx(FAR struct mrf24j40_radio_s *dev) /* 1 means it failed, we want 1 to mean it worked. */ - dev->ieee.txok = (reg & MRF24J40_TXSTAT_TXNSTAT) != MRF24J40_TXSTAT_TXNSTAT; - dev->ieee.txretries = (reg & MRF24J40_TXSTAT_X_MASK) >> MRF24J40_TXSTAT_X_SHIFT; - dev->ieee.txbusy = (reg & MRF24J40_TXSTAT_CCAFAIL) == MRF24J40_TXSTAT_CCAFAIL; + dev->radio.txok = (reg & MRF24J40_TXSTAT_TXNSTAT) != MRF24J40_TXSTAT_TXNSTAT; + dev->radio.txretries = (reg & MRF24J40_TXSTAT_X_MASK) >> MRF24J40_TXSTAT_X_SHIFT; + dev->radio.txbusy = (reg & MRF24J40_TXSTAT_CCAFAIL) == MRF24J40_TXSTAT_CCAFAIL; //wlinfo("TXSTAT%02X!\n", txstat); #warning TODO report errors @@ -1248,7 +1281,8 @@ static void mrf24j40_irqwork_tx(FAR struct mrf24j40_radio_s *dev) /* Wake up the thread that triggered the transmission */ - sem_post(&dev->ieee.txsem); + sem_post(&dev->radio.txsem); + } /**************************************************************************** @@ -1259,16 +1293,16 @@ static void mrf24j40_irqwork_tx(FAR struct mrf24j40_radio_s *dev) * ****************************************************************************/ -static int mrf24j40_rxenable(FAR struct ieee802154_radio_s *ieee, bool state, +static int mrf24j40_rxenable(FAR struct ieee802154_radio_s *radio, bool state, FAR struct ieee802154_packet_s *packet) { - FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)ieee; + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)radio; uint8_t reg; if (state) { mrf24j40_pacontrol(dev, MRF24J40_PA_AUTO); - ieee->rxbuf = packet; + radio->rxbuf = packet; /* Enable rx int */ @@ -1278,7 +1312,7 @@ static int mrf24j40_rxenable(FAR struct ieee802154_radio_s *ieee, bool state, } else { - ieee->rxbuf = NULL; + radio->rxbuf = NULL; } return OK; @@ -1313,20 +1347,20 @@ static void mrf24j40_irqwork_rx(FAR struct mrf24j40_radio_s *dev) /* Read packet */ addr = MRF24J40_RXBUF_BASE; - dev->ieee.rxbuf->len = mrf24j40_getreg(dev->spi, addr++); - /* wlinfo("len %3d\n", dev->ieee.rxbuf->len); */ + dev->radio.rxbuf->len = mrf24j40_getreg(dev->spi, addr++); + /* wlinfo("len %3d\n", dev->radio.rxbuf->len); */ - for (index = 0; index < dev->ieee.rxbuf->len; index++) + for (index = 0; index < dev->radio.rxbuf->len; index++) { - dev->ieee.rxbuf->data[index] = mrf24j40_getreg(dev->spi, addr++); + dev->radio.rxbuf->data[index] = mrf24j40_getreg(dev->spi, addr++); } - dev->ieee.rxbuf->lqi = mrf24j40_getreg(dev->spi, addr++); - dev->ieee.rxbuf->rssi = mrf24j40_getreg(dev->spi, addr++); + dev->radio.rxbuf->lqi = mrf24j40_getreg(dev->spi, addr++); + dev->radio.rxbuf->rssi = mrf24j40_getreg(dev->spi, addr++); /* Reduce len by 2, we only receive frames with correct crc, no check required */ - dev->ieee.rxbuf->len -= 2; + dev->radio.rxbuf->len -= 2; /* Enable reception of next packet by flushing the fifo. * This is an MRF24J40 errata (no. 1). @@ -1338,7 +1372,7 @@ static void mrf24j40_irqwork_rx(FAR struct mrf24j40_radio_s *dev) mrf24j40_setreg(dev->spi, MRF24J40_BBREG1, 0); - sem_post(&dev->ieee.rxsem); + sem_post(&dev->radio.rxsem); } /**************************************************************************** @@ -1446,21 +1480,17 @@ static int mrf24j40_interrupt(int irq, FAR void *context, FAR void *arg) ****************************************************************************/ FAR struct ieee802154_radio_s *mrf24j40_init(FAR struct spi_dev_s *spi, - FAR const struct mrf24j40_lower_s *lower) + FAR const struct mrf24j40_lower_s *lower) { FAR struct mrf24j40_radio_s *dev; struct ieee802154_cca_s cca; -#if 0 dev = kmm_zalloc(sizeof(struct mrf24j40_radio_s)); if (dev == NULL) { return NULL; } -#else - dev = &g_mrf24j40_devices[0]; -#endif - + /* Attach irq */ if (lower->attach(lower, mrf24j40_interrupt, dev) != OK) @@ -1471,43 +1501,43 @@ FAR struct ieee802154_radio_s *mrf24j40_init(FAR struct spi_dev_s *spi, return NULL; } - dev->ieee.ops = &mrf24j40_devops; + dev->radio.ops = &mrf24j40_devops; /* Initialize semaphores */ - sem_init(&dev->ieee.rxsem, 0, 0); - sem_init(&dev->ieee.txsem, 0, 0); + sem_init(&dev->radio.rxsem, 0, 0); + sem_init(&dev->radio.txsem, 0, 0); /* These semaphores are all used for signaling and, hence, should * not have priority inheritance enabled. */ - sem_setprotocol(&dev->ieee.rxsem, SEM_PRIO_NONE); - sem_setprotocol(&dev->ieee.txsem, SEM_PRIO_NONE); + sem_setprotocol(&dev->radio.rxsem, SEM_PRIO_NONE); + sem_setprotocol(&dev->radio.txsem, SEM_PRIO_NONE); dev->lower = lower; dev->spi = spi; mrf24j40_initialize(dev); - mrf24j40_setchannel(&dev->ieee, 11); - mrf24j40_setpanid (&dev->ieee, 0xFFFF); - mrf24j40_setsaddr (&dev->ieee, 0xFFFF); - mrf24j40_seteaddr (&dev->ieee, (uint8_t*)"\xFF\xFF\xFF\xFF\xFF\xFF\xFF\xFF"); + mrf24j40_setchannel(&dev->radio, 11); + mrf24j40_setpanid (&dev->radio, 0xFFFF); + mrf24j40_setsaddr (&dev->radio, 0xFFFF); + mrf24j40_seteaddr (&dev->radio, (uint8_t*)"\xFF\xFF\xFF\xFF\xFF\xFF\xFF\xFF"); /* Default device params */ cca.use_ed = 1; cca.use_cs = 0; cca.edth = 0x60; /* CCA mode ED, no carrier sense, recommenced ED threshold -69 dBm */ - mrf24j40_setcca(&dev->ieee, &cca); + mrf24j40_setcca(&dev->radio, &cca); mrf24j40_setrxmode(dev, MRF24J40_RXMODE_NORMAL); - mrf24j40_settxpower(&dev->ieee, 0); /*16. Set transmitter power .*/ + mrf24j40_settxpower(&dev->radio, 0); /*16. Set transmitter power .*/ mrf24j40_pacontrol(dev, MRF24J40_PA_AUTO); - dev->lower->enable(dev->lower, true); - return &dev->ieee; + dev->lower->enable(dev->radio, true); + return &dev->radio; } -- GitLab From 2aaec20bbb73709842d2364d5341e7d6e09c46c1 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Sat, 15 Apr 2017 13:21:07 -0400 Subject: [PATCH 463/990] wireless/ieee802154: Minor formatting and new macros --- .../wireless/ieee802154/ieee802154_mac.h | 82 ++++++------------- 1 file changed, 23 insertions(+), 59 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index d26bda9529..838f7fcafd 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -146,19 +146,19 @@ #define IEEE802154_FRAMECTRL_VERSION 0x3000 /* Source addressing mode, bits 12-13 */ #define IEEE802154_FRAMECTRL_SADDR 0xC000 /* Source addressing mode, bits 14-15 */ -#define IEEE802154_FRAMECTRL_SHIFT_FTYPE 0 /* Frame type, bits 0-2 */ -#define IEEE802154_FRAMECTRL_SHIFT_SEC 3 /* Security Enabled, bit 3 */ -#define IEEE802154_FRAMECTRL_SHIFT_PEND 4 /* Frame pending, bit 4 */ -#define IEEE802154_FRAMECTRL_SHIFT_ACKREQ 5 /* Acknowledge request, bit 5 */ -#define IEEE802154_FRAMECTRL_SHIFT_PANIDCOMP 6 /* PAN ID Compression, bit 6 */ -#define IEEE802154_FRAMECTRL_SHIFT_DADDR 10 /* Dest addressing mode, bits 10-11 */ -#define IEEE802154_FRAMECTRL_SHIFT_VERSION 12 /* Source addressing mode, bits 12-13 */ -#define IEEE802154_FRAMECTRL_SHIFT_SADDR 14 /* Source addressing mode, bits 14-15 */ +#define IEEE802154_FRAMECTRL_SHIFT_FTYPE 0 /* Frame type, bits 0-2 */ +#define IEEE802154_FRAMECTRL_SHIFT_SEC 3 /* Security Enabled, bit 3 */ +#define IEEE802154_FRAMECTRL_SHIFT_PEND 4 /* Frame pending, bit 4 */ +#define IEEE802154_FRAMECTRL_SHIFT_ACKREQ 5 /* Acknowledge request, bit 5 */ +#define IEEE802154_FRAMECTRL_SHIFT_PANIDCOMP 6 /* PAN ID Compression, bit 6 */ +#define IEEE802154_FRAMECTRL_SHIFT_DADDR 10 /* Dest addressing mode, bits 10-11 */ +#define IEEE802154_FRAMECTRL_SHIFT_VERSION 12 /* Source addressing mode, bits 12-13 */ +#define IEEE802154_FRAMECTRL_SHIFT_SADDR 14 /* Source addressing mode, bits 14-15 */ /* IEEE 802.15.4 PHY constants */ #define IEEE802154_MAX_PHY_PACKET_SIZE 127 -#define IEEE802154_TURN_AROUND_TIME 12 /*symbol periods*/ +#define IEEE802154_TURN_AROUND_TIME 12 /*symbol periods*/ /* IEEE 802.15.4 MAC constants */ @@ -175,8 +175,13 @@ (IEEE802154_MAX_PHY_PACKET_SIZE - IEEE802154_MAX_BEACON_OVERHEAD) #define IEEE802154_MAX_LOST_BEACONS 4 -#define IEEE802514_MIN_MPDU_OVERHEAD 9 -#define IEEE802154_MAX_MPDU_UNSEC_OVERHEAD 25 +#define IEEE802154_MIN_MPDU_OVERHEAD 9 +#define IEEE802154_MAX_UNSEC_MHR_OVERHEAD 23 +#define IEEE802154_MFR_LENGTH 2 + +#define IEEE802154_MAX_MPDU_UNSEC_OVERHEAD \ + (IEEE802154_MAX_UNSEC_MHR_OVERHEAD + IEEE802154_MFR_LENGTH) + #define IEEE802154_MAX_SAFE_MAC_PAYLOAD_SIZE \ (IEEE802154_MAX_PHY_PACKET_SIZE - IEEE802154_MAX_MPDU_UNSEC_OVERHEAD) @@ -344,59 +349,18 @@ struct ieee802154_addr_s { /* Address mode. Short or Extended */ - enum ieee802154_addr_mode_e ia_mode; + enum ieee802154_addr_mode_e mode; - uint16_t ia_panid; /* PAN identifier, can be IEEE802154_PAN_UNSPEC */ + uint16_t panid; /* PAN identifier, can be IEEE802154_PAN_UNSPEC */ union { - uint16_t _ia_saddr; /* short address */ - uint8_t _ia_eaddr[8]; /* extended address */ - } ia_addr; - -#define ia_saddr ia_addr._ia_saddr -#define ia_eaddr ia_addr._ia_eaddr + uint16_t saddr; /* short address */ + uint8_t eaddr[8]; /* extended address */ + }; }; #define IEEE802154_ADDRSTRLEN 22 /* (2*2+1+8*2, PPPP/EEEEEEEEEEEEEEEE) */ -struct ieee802154_framecontrol_s -{ - /* Frame type - * - * Should be a value from: ieee802154_frametype_e - * - * Bits 0-1 - */ - - uint16_t frame_type : 3; - - uint16_t security_en : 1; /* Security Enabled flag, bit 3 */ - uint16_t frame_pending : 1; /* Frame Pending flag, bit 4 */ - uint16_t ack_req : 1; /* Acknowledge Request flag, bit 5 */ - uint16_t panid_comp : 1; /* PAN ID Compression flag, bit 6 */ - uint16_t reserved : 3; /* Reserved, bits 7-9 */ - - /* Destination Addressing Mode - * - * Should be a value from: ieee802154_addr_mode_e - * - * Bits 10-11 - */ - - uint16_t dest_addr_mode : 2; - - uint16_t frame_version : 2; /* Frame Version, bits 12-13 */ - - /* Source Addressing Mode - * - * Should be a value from: ieee802154_addr_mode_e - * - * Bits 14-15 - */ - - uint16_t src_addr_mode : 2; -}; - #ifdef CONFIG_IEEE802154_SECURITY struct ieee802154_security_s { @@ -449,7 +413,7 @@ struct ieee802154_frame_s struct ieee802154_data_req_s { enum ieee802154_addr_mode_e src_addr_mode; /* Source Address Mode */ - struct ieee802154_addr_s dest__addr; /* Destination Address */ + struct ieee802154_addr_s dest_addr; /* Destination Address */ /* Number of bytes contained in the MAC Service Data Unit (MSDU) * to be transmitted by the MAC sublayer enitity @@ -502,7 +466,7 @@ struct ieee802154_data_req_s }; #define SIZEOF_IEEE802154_DATA_REQ_S(n) \ - (sizeof(struct ieee802154_data_req_s) + (n)) + (sizeof(struct ieee802154_data_req_s) + (n) - 1) struct ieee802154_data_conf_s { -- GitLab From 36a6bda755b0a7a78fb370b6a4d4ffadcd0fdc4a Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Sat, 15 Apr 2017 13:22:36 -0400 Subject: [PATCH 464/990] wireless/ieee802154: Starts adding MAC request data functionality --- wireless/ieee802154/mac802154.c | 505 +++++++++++++++++++++++++++----- 1 file changed, 432 insertions(+), 73 deletions(-) diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index e8f046f284..f223f8836e 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -68,49 +68,191 @@ struct ieee802154_privmac_s FAR struct ieee802154_radio_s *radio; /* Contained IEEE802.15.4 radio dev */ FAR const struct ieee802154_maccb_s *cb; /* Contained MAC callbacks */ - /* MIB attributes, grouped to save memory */ - /* 0x40 */ uint8_t macAckWaitDuration : 1; /* 55 or 120(true) */ - /* 0x41 */ uint8_t macAssociationPermit : 1; - /* 0x42 */ uint8_t macAutoRequest : 1; - /* 0x43 */ uint8_t macBattLifeExt : 1; - /* 0x44 */ uint8_t macBattLifeExtPeriods : 1; /* 6 or 8(true) */ - /* 0x4E */ uint8_t macMaxCSMABackoffs : 3; /* 0-5 */ - - /* 0x47 */ uint8_t macBeaconOrder : 4; - /* 0x54 */ uint8_t macSuperframeOrder : 4; - - /* 0x4F */ uint32_t macMinBE : 2; - /* 0x4D */ uint32_t macGTSPermit : 1; - /* 0x51 */ uint32_t macPromiscuousMode : 1; - /* 0x52 */ uint32_t macRxOnWhenIdle : 1; - uint32_t macPad : 3; - /* 0x48 */ uint32_t macBeaconTxTime : 24; - - /* 0x45 */ uint8_t macBeaconPayload[IEEE802154_MAX_BEACON_PAYLOAD_LENGTH]; - /* 0x46 */ uint8_t macBeaconPayloadLength; - /* 0x49 */ uint8_t macBSN; - /* 0x4A */ uint8_t macCoordExtendedAddress[8]; - /* 0x4B */ uint16_t macCoordShortAddress; - /* 0x4C */ uint8_t macDSN; - /* 0x50 */ uint16_t macPANId; - /* 0x53 */ uint16_t macShortAddress; - /* 0x55 */ uint16_t macTransactionPersistenceTime; -#if 0 - /* Security MIB */ - /* 0x70 */ macACLEntryDescriptorSet - /* 0x71 */ macACLEntryDescriptorSetSize - /* 0x74 */ macDefaultSecurityMaterial - /* 0x72 */ macDefaultSecurity:1 - /* 0x75 */ macDefaultSecuritySuite:3 - /* 0x73 */ macDefaultSecurityMaterialLength:6 - /* 0x76 */ macSecurityMode:2 -#endif + sem_t excl_sem; /* Support exclusive access */ + + /* Support a singly linked list of transactions that will be sent using the + * CSMA algorithm. On a non-beacon enabled PAN, these transactions will be + * sent whenever. On a beacon-enabled PAN, these transactions will be sent + * during the CAP of the Coordinator's superframe. */ + + FAR struct mac802154_trans_s *csma_head; + FAR struct mac802154_trans_s *csma_tail; + + struct mac802154_trans_s csma_buf[5]; + + /* Support a singly linked list of transactions that will be sent indirectly. + * This list should only be used by a MAC acting as a coordinator. These + * transactions will stay here until the data is extracted by the destination + * device sending a Data Request MAC command or if too much time passes. This + * list should also be used to populate the address list of the outgoing + * beacon frame */ + + FAR struct mac802154_trans_s *indirect_head; + FAR struct mac802154_trans_s *indirect_tail; + + FAR struct mac802154_trans_s *active_trans; + + /* MAC PIB attributes, grouped to save memory */ + + /* Holds all address information (Extended, Short, and PAN ID) for the MAC */ + + struct ieee802154_addr_s addr; + + /* Holds all address information (Extended, Short) for Coordinator */ + + struct ieee802154_addr_s coord_addr; + + /* The maximum number of symbols to wait for an acknowledgement frame to + * arrive following a transmitted data frame. [1] pg. 126 + * + * NOTE: This may be able to be a 16-bit or even an 8-bit number. I wasn't + * sure at the time what the range of reasonable values was */ + + uint32_t ack_wait_dur; + + /* The maximum time to wait either for a frame intended as a response to a + * data request frame or for a broadcast frame following a beacon with the + * Frame Pending field set to one. [1] pg. 127 + * + * NOTE: This may be able to be a 16-bit or even an 8-bit number. I wasn't + * sure at the time what the range of reasonable values was */ + + uint32_t max_frame_wait_time; + + /* The maximum time (in unit periods) that a transaction is stored by a + * coordinator and indicated in its beacon. */ + + uint16_t trans_persist_time; + + /* Contents of beacon payload */ + + uint8_t beacon_payload[IEEE802154_MAX_BEACON_PAYLOAD_LENGTH]; + uint8_t beacon_payload_len; /* Length of beacon payload */ + + uint8_t batt_life_ext_periods; /* # of backoff periods during which rx is + * enabled after the IFS following beacon */ + + uint8_t bsn; /* Seq. num added to tx beacon frame */ + uint8_t dsn; /* Seq. num added to tx data or MAC frame */ + uint8_t max_retries; /* Max # of retries alloed after tx failure */ + + /* The maximum time, in multiples of aBaseSuperframeDuration, a device shall + * wait for a response command frame to be available following a request + * command frame. [1] 128 */ + + uint8_t resp_wait_time; + + /* The total transmit duration (including PHY header and FCS) specified in + * symbols. [1] pg. 129 */ + + uint32_t tx_total_dur; + + struct + { + uint32_t is_assoc : 1; /* Are we associated to the PAN */ + uint32_t assoc_permit : 1; /* Are we allowing assoc. as a coord. */ + uint32_t auto_req : 1; /* Automatically send data req. if addr + * addr is in the beacon frame */ + + uint32_t batt_life_ext : 1; /* Is BLE enabled */ + uint32_t gts_permit : 1; /* Is PAN Coord. accepting GTS reqs. */ + uint32_t promiscuous_mode : 1; /* Is promiscuous mode on? */ + uint32_t ranging_supported : 1; /* Does MAC sublayer support ranging */ + uint32_t rx_when_idle : 1; /* Recvr. on during idle periods */ + uint32_t sec_enabled : 1; /* Does MAC sublayer have security en. */ + + uint32_t max_csma_backoffs : 3; /* Max num backoffs for CSMA algorithm + * before declaring ch access failure */ + + uint32_t beacon_order : 4; /* Freq. that beacon is transmitted */ + + uint32_t superframe_order : 4; /* Length of active portion of outgoing + * superframe, including the beacon */ + + /* The offset, measured is symbols, between the symbol boundary at which the + * MLME captures the timestamp of each transmitted and received frame, and + * the onset of the first symbol past the SFD, namely the first symbol of + * the frames [1] pg. 129 */ + + uint32_t sync_symb_offset : 12; + } + + struct + { + uint32_t beacon_tx_time : 24; /* Time of last beacon transmit */ + uint32_t min_be : 4; /* Min value of backoff exponent (BE) */ + uint32_t max_be : 4; /* Max value of backoff exponent (BE) */ + } + + struct + { + uint32_t tx_ctrl_active_dur : 17; /* Duration for which tx is permitted to + * be active */ + + uint32_t tx_ctrl_pause_dur : 1; /* Duration after tx before another tx is + * permitted. 0=2000, 1= 10000 */ + + uint32_t timestamp_support : 1; /* Does MAC layer supports timestamping */ + } + + /* TODO: Add Security-related MAC PIB attributes */ + +}; + +struct mac802154_trans_s +{ + /* Supports a singly linked list */ + + FAR struct mac802154_trans_s *flink; + + uint8_t msdu_handle; + + uint8_t *mhr_buf; + uint8_t mhr_len; + + uint8_t *d_buf; + uint8_t d_len; + + sem_t sem; +}; + +struct mac802154_unsec_mhr_s +{ + uint8_t length; + union { + uint16_t frame_control; + uint8_t data[IEEE802154_MAX_UNSEC_MHR_OVERHEAD]; + }; }; /**************************************************************************** * Private Functions ****************************************************************************/ +/**************************************************************************** + * Name: mac802154_semtake + * + * Description: + * Acquire the semaphore used for access serialization. + * + ****************************************************************************/ + +static inline int mac802154_takesem(sem_t *sem) +{ + /* Take a count from the semaphore, possibly waiting */ + + if (sem_wait(sem) < 0) + { + /* EINTR is the only error that we expect */ + + int errcode = get_errno(); + DEBUGASSERT(errcode == EINTR); + return -errcode; + } + + return OK; +} + /**************************************************************************** * Name: mac802154_defaultmib * @@ -121,41 +263,7 @@ struct ieee802154_privmac_s static int mac802154_defaultmib(FAR struct ieee802154_privmac_s *priv) { - priv->macAckWaitDuration = 0; - priv->macAssociationPermit = 0; - priv->macAutoRequest = 1; - priv->macBattLifeExt = 0; - priv->macBattLifeExtPeriods = 0; - priv->macMaxCSMABackoffs = 4; - - priv->macBeaconOrder = 15; - priv->macSuperframeOrder = 15; - - priv->macMinBE = 3; - priv->macGTSPermit = 1; - priv->macPromiscuousMode = 0; - priv->macRxOnWhenIdle = 0; - priv->macBeaconTxTime = 0x000000; - - priv->macBeaconPayloadLength = 0; - priv->macBSN = 0; /* Shall be random */ - //priv->macCoordExtendedAddress[8]; - priv->macCoordShortAddress = 0xffff; - priv->macDSN = 0; /* Shall be random */ - priv->macPANId = 0xffff; - priv->macShortAddress = 0xffff; - priv->macTransactionPersistenceTime = 0x01f4; - -#if 0 - /* Security MIB */ - - priv->macACLEntryDescriptorSetSize = 0; - priv->macDefaultSecurity = 0; - priv->macDefaultSecuritySuite = 0; - priv->macDefaultSecurityMaterialLength = 0x15; - priv->macSecurityMode = 0; -#endif - + /* TODO: Set all MAC fields to default values */ return OK; } @@ -314,7 +422,258 @@ int mac802154_ioctl(MACHANDLE mac, int cmd, unsigned long arg) int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; - return -ENOTTY; + FAR struct mac802154_trans_s *trans; + struct mac802154_unsec_mhr_s mhr; + int ret; + + /* Start off assuming there is only the frame_control field in the MHR */ + + mhr.length = 2; + + /* Do a preliminary check to make sure the MSDU isn't too long for even the + * best case */ + + if (req->msdu_length > IEEE802154_MAX_MAC_PAYLOAD_SIZE) + { + return -EINVAL; + } + + /* Ensure we start with a clear frame control field */ + + mhr.frame_control = 0; + + /* Set the frame type to Data */ + + mhr.frame_control |= IEEE802154_FRAME_DATA << IEEE802154_FRAMECTRL_SHIFT_FTYPE; + + /* If the msduLength is greater than aMaxMACSafePayloadSize, the MAC sublayer + * will set the Frame Version to one. [1] pg. 118 */ + + if (req->msdu_length > IEEE802154_MAX_SAFE_MAC_PAYLOAD_SIZE) + { + mhr.frame_ctrl |= IEEE802154_FRAMECTRL_VERSION; + } + + /* If the TXOptions parameter specifies that an acknowledged transmission is + * required, the AR field will be set appropriately, as described in + * 5.1.6.4 [1] pg. 118 */ + + mhr.frame_ctrl |= (req->ack_tx << IEEE802154_FRAMECTRL_SHIFT_ACKREQ); + + /* If the destination address is present, copy the PAN ID and one of the + * addresses, depending on mode, into the MHR */ + + if (req->dest_addr.mode != IEEE802154_ADDRMODE_NONE) + { + memcpy(&mhr.data[mhr.length], req->dest_addr.panid, 2); + mhr.length += 2; + + if (req->dest_addr.mode == IEEE802154_ADDRMODE_SHORT) + { + memcpy(&mhr.data[mhr.length], req->dest_addr.saddr, 2); + mhr.length += 2; + } + else if (req->dest_addr.mode == IEEE802154_ADDRMODE_EXTENDED) + { + memcpy(&mhr.data[mhr.length], req->dest_addr.eaddr, 8); + mhr.length += 8; + } + } + + /* Set the destination addr mode inside the frame contorl field */ + + mhr.frame_ctrl |= (req->dest_addr.mode << IEEE802154_FRAMECTRL_SHIFT_DADDR); + + /* From this point on, we need exclusive access to the privmac struct */ + + ret = mac802154dev_takesem(&dev->md_exclsem); + if (ret < 0) + { + wlerr("ERROR: mac802154_takesem failed: %d\n", ret); + return ret; + } + + /* If both destination and source addressing information is present, the MAC + * sublayer shall compare the destination and source PAN identifiers. + * [1] pg. 41 */ + + if (req->src_addr_mode != IEEE802154_ADDRMODE_NONE && + req->dest_addr.mode != IEEE802154_ADDRMODE_NONE) + { + /* If the PAN identifiers are identical, the PAN ID Compression field + * shall be set to one, and the source PAN identifier shall be omitted + * from the transmitted frame. [1] pg. 41 */ + + if(req->dest_addr.panid == priv->addr.panid) + { + mhr.frame_control |= IEEE802154_FRAMECTRL_PANIDCOMP; + } + } + + if (req->src_addr_mode != IEEE802154_ADDRMODE_NONE) + { + /* If the destination address is not included, or if PAN ID Compression + * is off, we need to include the Source PAN ID */ + + if (req->dest_addr.mode == IEEE802154_ADDRMODE_NONE || + (mhr.frame_control & IEEE802154_FRAMECTRL_PANIDCOMP) + { + memcpy(&mhr.data[mhr.length], priv->addr.panid, 2); + mhr.length += 2; + } + + if (req->src_addr_mode == IEEE802154_ADDRMODE_SHORT) + { + memcpy(&mhr.data[mhr.length], priv->addr.saddr, 2); + mhr.length += 2; + } + else if (req->src_addr_mode == IEEE802154_ADDRMODE_EXTENDED) + { + memcpy(&mhr.data[mhr.length], priv->addr.eaddr, 8); + mhr.length += 8; + } + } + + /* Set the source addr mode inside the frame contorl field */ + + mhr.frame_ctrl |= (req->src_addr_mode << IEEE802154_FRAMECTRL_SHIFT_SADDR); + + /* Each time a data or a MAC command frame is generated, the MAC sublayer + * shall copy the value of macDSN into the Sequence Number field of the MHR + * of the outgoing frame and then increment it by one. [1] pg. 40 */ + + mhr.data[mhr.length++] = priv.dsn++; + + /* Now that we know which fields are included in the header, we can make + * sure we actually have enough room in the PSDU */ + + if (mhr.length + req->msdu_length + IEEE802154_MFR_LENGTH > + IEEE802154_MAX_PHY_PACKET_SIZE) + { + return -E2BIG; + } + + trans->mhr_buf = &mhr.data[0]; + trans->mhr_len = mhr.length; + + trans->d_buf = &req->msdu[0]; + trans->d_len = req->msdu_length; + + trans->msdu_handle = req->msdu_handle; + + /* If the TxOptions parameter specifies that a GTS transmission is required, + * the MAC sublayer will determine whether it has a valid GTS as described + * 5.1.7.3. If a valid GTS could not be found, the MAC sublayer will discard + * the MSDU. If a valid GTS was found, the MAC sublayer will defer, if + * necessary, until the GTS. If the TxOptions parameter specifies that a GTS + * transmission is not required, the MAC sublayer will transmit the MSDU using + * either slotted CSMA-CA in the CAP for a beacon-enabled PAN or unslotted + * CSMA-CA for a nonbeacon-enabled PAN. Specifying a GTS transmission in the + * TxOptions parameter overrides an indirect transmission request. + * [1] pg. 118 */ + + if (req->gts_tx) + { + /* TODO: Support GTS transmission. This should just change where we link + * the transaction. Instead of going in the CSMA transaction list, it + * should be linked to the GTS' transaction list. We'll need to check if + * the GTS is valid, and then find the GTS, before linking. Note, we also + * don't have to try and kick-off any transmission here. */ + + return -ENOTSUP; + } + else + { + /* If the TxOptions parameter specifies that an indirect transmission is + * required and this primitive is received by the MAC sublayer of a + * coordinator, the data frame is sent using indirect transmission, as + * described in 5.1.5 and 5.1.6.3. [1] */ + + if (req->indirect_tx) + { + /* If the TxOptions parameter specifies that an indirect transmission + * is required and if the device receiving this primitive is not a + * coordinator, the destination address is not present, or the + * TxOptions parameter also specifies a GTS transmission, the indirect + * transmission option will be ignored. [1] */ + + if (priv->is_coord && req->dest_addr.mode != IEEE802154_ADDRMODE_NONE) + { + /* Link the transaction into the indirect_trans list */ + + priv->indirect_tail->flink = trans; + priv->indirect_tail = trans; + } + else + { + /* Override the setting since it wasn't valid */ + + req->indirect_tx = 0; + } + } + + /* If this is a direct transmission not during a GTS */ + + if (!req->indirect_tx) + { + /* Link the transaction into the CSMA transaction list */ + + priv->csma_tail->flink = trans; + priv->csma_tail = trans; + + /* Notify the radio driver that there is data available */ + + priv->radio->tx_notify(priv->radio); + + sem_wait(&trans->sem); + } + } + + return OK; +} + + +/* Called from interrupt level or worker thread with interrupts disabled */ + +static uint16_t mac802154_poll_csma(FAR struct ieee802154_phyif_s *phyif, + FAR struct ieee802154_txdesc_s *tx_desc, + uint8_t *buf) +{ + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)&phyif->priv; + + FAR struct mac802154_trans_s *trans; + + /* Check to see if there are any CSMA transactions waiting */ + + if (mac->csma_head) + { + /* Pop a CSMA transaction off the list */ + + trans = mac->csma_head; + mac->csma_head = mac->csma_head.flink; + + /* Setup the transmit descriptor */ + + tx_desc->psdu_handle = trans->msdu_handle; + tx_desc->psdu_length = trans->mhr_len + trans->d_len; + + /* Copy the frame into the buffer */ + + memcpy(&buf[0], trans->mhr_buf, trans->mhr_len); + memcpy(&buf[trans->mhr_len], trans->d_buf, trans->d_len); + + /* Now that we've passed off the data, notify the waiting thread. + * NOTE: The transaction was allocated on the waiting thread's stack so + * it will be automatically deallocated when that thread awakens and + * returns */ + + sem_post(trans->sem); + + return txdesc->psdu_length; + } + + return 0; } /**************************************************************************** -- GitLab From 141d5574f88677cbc869f72cb2d7547bf86c4072 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Sat, 15 Apr 2017 13:24:25 -0400 Subject: [PATCH 465/990] wireless/ieee802154: Starts defining interface between PHY layer and next highest layer --- .../wireless/ieee802154/ieee802154_radio.h | 36 +++++++++++++++++-- 1 file changed, 34 insertions(+), 2 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_radio.h b/include/nuttx/wireless/ieee802154/ieee802154_radio.h index eef94e328f..0a38ed0402 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_radio.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_radio.h @@ -157,19 +157,51 @@ struct ieee802154_netradio_s #endif /* IEEE802.15.4 Radio Interface Operations **********************************/ +struct ieee802154_trans_s +{ + uint8_t retry_count; /* The number of retries remaining */ + uint8_t msdu_handle; /* The msdu handle identifying the transaction */ + + uint16_t psdu_length; /* The length of the PSDU */ + + /* The PHY Service Data Unit (PSDU) buffer representing the frame to be + * transmitted. This must be at the end of the struct to allow the array + * to continue and make the struct "variable length". Users should allocate + * memory using the SIZEOF_MAC802154_TRANSACTION_S macro below */ + + uint8_t psdu[CONFIG_IEEE802154_MTU]; +}; struct ieee802154_radio_s; /* Forward reference */ +struct ieee802154_phyif_s +{ + CODE int (*poll_csma) (FAR struct ieee802154_phyif_s *phyif, + FAR struct ieee802154_txdesc_s *tx_desc, + uint8_t *buf); + + CODE int (*poll_gts) (FAR struct ieee802154_phyif_s *phyif, + FAR struct ieee802154_txdesc_s *tx_desc, + uint8_t *buf); + + /* Driver-specific information */ + + void * priv; +}; + struct ieee802154_radioops_s { + CODE int (*bind) (FAR struct ieee802154_radio_s *dev, + FAR const struct ieee802154_phyif_s *phyif); + CODE int (*ioctl)(FAR struct ieee802154_radio_s *ieee, int cmd, unsigned long arg); + CODE int (*rxenable)(FAR struct ieee802154_radio_s *dev, bool state, FAR struct ieee802154_packet_s *packet); + CODE int (*transmit)(FAR struct ieee802154_radio_s *dev, FAR struct ieee802154_packet_s *packet); - - /* TODO beacon/sf order */ }; struct ieee802154_radio_s -- GitLab From 16edc77965fffc0446ff9904bd1fc03f83420ef3 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Sat, 15 Apr 2017 13:26:03 -0400 Subject: [PATCH 466/990] wireless/ieee802154: Skeleton code for request associate --- wireless/ieee802154/mac802154.c | 23 +++++++++++++++++++++++ 1 file changed, 23 insertions(+) diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index f223f8836e..99e3f27d8a 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -706,6 +706,29 @@ int mac802154_req_associate(MACHANDLE mac, FAR struct ieee802154_assoc_req_s *req) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; + + /* Set the channel of the PHY layer */ + + /* Set the channel page of the PHY layer */ + + /* Set the macPANId */ + + /* Set either the macCoordExtendedAddress and macCoordShortAddress + * depending on the CoordAddrMode in the primitive */ + + if (req->coord_addr.mode == IEEE802154_ADDRMODE_EXTENDED) + { + + } + else if (req->coord_addr.mode == IEEE802154_ADDRMODE_EXTENDED) + { + + } + else + { + return -EINVAL; + } + return -ENOTTY; } -- GitLab From 2bc758c3ebd0ddccee736e8d166fedcaeb9126ec Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Sat, 15 Apr 2017 13:44:15 -0400 Subject: [PATCH 467/990] wireless/ieee802154: Bind MAC phyif to radio --- .../wireless/ieee802154/ieee802154_radio.h | 12 ++++++++++-- wireless/ieee802154/mac802154.c | 18 ++++++++++++++++++ 2 files changed, 28 insertions(+), 2 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_radio.h b/include/nuttx/wireless/ieee802154/ieee802154_radio.h index 0a38ed0402..a26e3321d6 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_radio.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_radio.h @@ -172,9 +172,10 @@ struct ieee802154_trans_s uint8_t psdu[CONFIG_IEEE802154_MTU]; }; -struct ieee802154_radio_s; /* Forward reference */ -struct ieee802154_phyif_s +struct ieee802154_phyif_s; /* Forward Reference */ + +struct ieee802154_phyifops_s { CODE int (*poll_csma) (FAR struct ieee802154_phyif_s *phyif, FAR struct ieee802154_txdesc_s *tx_desc, @@ -183,12 +184,19 @@ struct ieee802154_phyif_s CODE int (*poll_gts) (FAR struct ieee802154_phyif_s *phyif, FAR struct ieee802154_txdesc_s *tx_desc, uint8_t *buf); +}; + +struct ieee802154_phyif_s +{ + FAR const struct ieee802154_phyifops_s *ops; /* Driver-specific information */ void * priv; }; +struct ieee802154_radio_s; /* Forward reference */ + struct ieee802154_radioops_s { CODE int (*bind) (FAR struct ieee802154_radio_s *dev, diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index 99e3f27d8a..ffae80579f 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -67,6 +67,7 @@ struct ieee802154_privmac_s { FAR struct ieee802154_radio_s *radio; /* Contained IEEE802.15.4 radio dev */ FAR const struct ieee802154_maccb_s *cb; /* Contained MAC callbacks */ + FAR struct ieee802154_phyif_s phyif; /* Interface to bind to radio */ sem_t excl_sem; /* Support exclusive access */ @@ -225,6 +226,16 @@ struct mac802154_unsec_mhr_s }; }; +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const struct ieee802154_phyifops_s mac802154_phyifops = +{ + mac802154_poll_csma, + mac802154_poll_gts +}; + /**************************************************************************** * Private Functions ****************************************************************************/ @@ -330,6 +341,13 @@ MACHANDLE mac802154_create(FAR struct ieee802154_radio_s *radiodev) mac802154_defaultmib(mac); mac802154_applymib(mac); + + mac->phyif.ops = &mac802154_phyifops; + mac->phyif.priv = mac; + + /* Bind our PHY interface to the radio */ + + radiodev->ops->bind(radiodev, mac->phyif); return (MACHANDLE)mac; } -- GitLab From eac049222c80894b288a682b8a8f655776f16e4f Mon Sep 17 00:00:00 2001 From: phreakuencies Date: Sat, 15 Apr 2017 12:10:42 -0600 Subject: [PATCH 468/990] STM32: Provide TIM5 definition for STM32F429 --- arch/arm/src/stm32/Kconfig | 1 + 1 file changed, 1 insertion(+) diff --git a/arch/arm/src/stm32/Kconfig b/arch/arm/src/stm32/Kconfig index 86b5b71435..1aa55388f7 100644 --- a/arch/arm/src/stm32/Kconfig +++ b/arch/arm/src/stm32/Kconfig @@ -1625,6 +1625,7 @@ config STM32_STM32F429 select STM32_HAVE_UART7 select STM32_HAVE_UART8 select STM32_HAVE_TIM1 + select STM32_HAVE_TIM5 select STM32_HAVE_TIM6 select STM32_HAVE_TIM7 select STM32_HAVE_TIM8 -- GitLab From db54821287ca6fde8ae17b3745b811cb83e82dc6 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 15 Apr 2017 12:11:00 -0600 Subject: [PATCH 469/990] Update TODO list --- TODO | 15 +++------------ 1 file changed, 3 insertions(+), 12 deletions(-) diff --git a/TODO b/TODO index b85d480335..ed6d93238b 100644 --- a/TODO +++ b/TODO @@ -19,7 +19,7 @@ nuttx/: (8) Kernel/Protected Build (3) C++ Support (6) Binary loaders (binfmt/) - (15) Network (net/, drivers/net) + (14) Network (net/, drivers/net) (4) USB (drivers/usbdev, drivers/usbhost) (0) Other drivers (drivers/) (12) Libraries (libc/, libm/) @@ -1006,8 +1006,8 @@ o Network (net/, drivers/net) however. Others support the address filtering interfaces but have never been verifed: - C5471, LM3X, ez80, DM0x90 NIC, PIC: Do not support address - filteringing. + C5471, LM3S, ez80, DM0x90 NIC, PIC: Do not support address + filtering. Kinetis, LPC17xx, LPC43xx: Untested address filter support Status: Open @@ -1089,15 +1089,6 @@ o Network (net/, drivers/net) Status: Open Priority: Low - Title: REMOVE CONFIG_NET_MULTIBUFFER - Description: The CONFIG_NET_MULTIBUFFER controls some details in the layout - of the network device structure. This is really a unnecessary - complexity and should be removed. The cost for those network - drivers that currently do not support CONFIG_NET_MULTIBUFFER - is the size of one pointer. - Status: Open - Priority: Low - Title: ETHERNET WITH MULTIPLE LPWORK THREADS Description: Recently, Ethernet drivers were modified to support multiple work queue structures. The question was raised: "My only -- GitLab From 8786770d7d3eb52140cbf416639cdc7fcdd9967f Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 15 Apr 2017 15:59:00 -0600 Subject: [PATCH 470/990] Costmetic change from review of last PR --- wireless/ieee802154/mac802154.c | 191 +++++++++++++---------- wireless/ieee802154/mac802154.h | 48 +++--- wireless/ieee802154/mac802154_device.c | 64 ++++---- wireless/ieee802154/radio802154_device.c | 2 +- 4 files changed, 168 insertions(+), 137 deletions(-) diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index ffae80579f..c4f99480bf 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -74,11 +74,11 @@ struct ieee802154_privmac_s /* Support a singly linked list of transactions that will be sent using the * CSMA algorithm. On a non-beacon enabled PAN, these transactions will be * sent whenever. On a beacon-enabled PAN, these transactions will be sent - * during the CAP of the Coordinator's superframe. */ + * during the CAP of the Coordinator's superframe. + */ FAR struct mac802154_trans_s *csma_head; FAR struct mac802154_trans_s *csma_tail; - struct mac802154_trans_s csma_buf[5]; /* Support a singly linked list of transactions that will be sent indirectly. @@ -86,16 +86,16 @@ struct ieee802154_privmac_s * transactions will stay here until the data is extracted by the destination * device sending a Data Request MAC command or if too much time passes. This * list should also be used to populate the address list of the outgoing - * beacon frame */ - + * beacon frame. + */ + FAR struct mac802154_trans_s *indirect_head; FAR struct mac802154_trans_s *indirect_tail; - FAR struct mac802154_trans_s *active_trans; /* MAC PIB attributes, grouped to save memory */ - /* Holds all address information (Extended, Short, and PAN ID) for the MAC */ + /* Holds all address information (Extended, Short, and PAN ID) for the MAC. */ struct ieee802154_addr_s addr; @@ -107,8 +107,9 @@ struct ieee802154_privmac_s * arrive following a transmitted data frame. [1] pg. 126 * * NOTE: This may be able to be a 16-bit or even an 8-bit number. I wasn't - * sure at the time what the range of reasonable values was */ - + * sure at the time what the range of reasonable values was. + */ + uint32_t ack_wait_dur; /* The maximum time to wait either for a frame intended as a response to a @@ -116,19 +117,21 @@ struct ieee802154_privmac_s * Frame Pending field set to one. [1] pg. 127 * * NOTE: This may be able to be a 16-bit or even an 8-bit number. I wasn't - * sure at the time what the range of reasonable values was */ + * sure at the time what the range of reasonable values was. + */ uint32_t max_frame_wait_time; /* The maximum time (in unit periods) that a transaction is stored by a - * coordinator and indicated in its beacon. */ + * coordinator and indicated in its beacon. + */ uint16_t trans_persist_time; - /* Contents of beacon payload */ + /* Contents of beacon payload */ - uint8_t beacon_payload[IEEE802154_MAX_BEACON_PAYLOAD_LENGTH]; - uint8_t beacon_payload_len; /* Length of beacon payload */ + uint8_t beacon_payload[IEEE802154_MAX_BEACON_PAYLOAD_LENGTH]; + uint8_t beacon_payload_len; /* Length of beacon payload */ uint8_t batt_life_ext_periods; /* # of backoff periods during which rx is * enabled after the IFS following beacon */ @@ -138,21 +141,23 @@ struct ieee802154_privmac_s uint8_t max_retries; /* Max # of retries alloed after tx failure */ /* The maximum time, in multiples of aBaseSuperframeDuration, a device shall - * wait for a response command frame to be available following a request - * command frame. [1] 128 */ + * wait for a response command frame to be available following a request + * command frame. [1] 128. + */ uint8_t resp_wait_time; /* The total transmit duration (including PHY header and FCS) specified in - * symbols. [1] pg. 129 */ + * symbols. [1] pg. 129. + */ uint32_t tx_total_dur; struct - { + { uint32_t is_assoc : 1; /* Are we associated to the PAN */ uint32_t assoc_permit : 1; /* Are we allowing assoc. as a coord. */ - uint32_t auto_req : 1; /* Automatically send data req. if addr + uint32_t auto_req : 1; /* Automatically send data req. if addr * addr is in the beacon frame */ uint32_t batt_life_ext : 1; /* Is BLE enabled */ @@ -170,11 +175,12 @@ struct ieee802154_privmac_s uint32_t superframe_order : 4; /* Length of active portion of outgoing * superframe, including the beacon */ - /* The offset, measured is symbols, between the symbol boundary at which the + /* The offset, measured is symbols, between the symbol boundary at which the * MLME captures the timestamp of each transmitted and received frame, and * the onset of the first symbol past the SFD, namely the first symbol of - * the frames [1] pg. 129 */ - + * the frames [1] pg. 129. + */ + uint32_t sync_symb_offset : 12; } @@ -187,17 +193,14 @@ struct ieee802154_privmac_s struct { - uint32_t tx_ctrl_active_dur : 17; /* Duration for which tx is permitted to + uint32_t tx_ctrl_active_dur : 17; /* Duration for which tx is permitted to * be active */ - uint32_t tx_ctrl_pause_dur : 1; /* Duration after tx before another tx is * permitted. 0=2000, 1= 10000 */ - uint32_t timestamp_support : 1; /* Does MAC layer supports timestamping */ } /* TODO: Add Security-related MAC PIB attributes */ - }; struct mac802154_trans_s @@ -220,7 +223,8 @@ struct mac802154_trans_s struct mac802154_unsec_mhr_s { uint8_t length; - union { + union + { uint16_t frame_control; uint8_t data[IEEE802154_MAX_UNSEC_MHR_OVERHEAD]; }; @@ -309,9 +313,9 @@ static int mac802154_applymib(FAR struct ieee802154_privmac_s *priv) * should register a set of callbacks with the MAC layer by setting the * mac->cbs member. * - * NOTE: This API does not create any device accessible to userspace. If you - * want to call these APIs from userspace, you have to wrap your mac in a - * character device via mac802154_device.c. + * NOTE: This API does not create any device accessible to userspace. If + * you want to call these APIs from userspace, you have to wrap your mac + * in a character device via mac802154_device.c. * * Input Parameters: * radiodev - an instance of an IEEE 802.15.4 radio @@ -341,7 +345,7 @@ MACHANDLE mac802154_create(FAR struct ieee802154_radio_s *radiodev) mac802154_defaultmib(mac); mac802154_applymib(mac); - + mac->phyif.ops = &mac802154_phyifops; mac->phyif.priv = mac; @@ -431,7 +435,7 @@ int mac802154_ioctl(MACHANDLE mac, int cmd, unsigned long arg) * * Description: * The MCPS-DATA.request primitive requests the transfer of a data SPDU - * (i.e., MSDU) from a local SSCS entity to a single peer SSCS entity. + * (i.e., MSDU) from a local SSCS entity to a single peer SSCS entity. * Confirmation is returned via the * struct ieee802154_maccb_s->conf_data callback. * @@ -439,7 +443,8 @@ int mac802154_ioctl(MACHANDLE mac, int cmd, unsigned long arg) int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) { - FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; FAR struct mac802154_trans_s *trans; struct mac802154_unsec_mhr_s mhr; int ret; @@ -450,7 +455,7 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) /* Do a preliminary check to make sure the MSDU isn't too long for even the * best case */ - + if (req->msdu_length > IEEE802154_MAX_MAC_PAYLOAD_SIZE) { return -EINVAL; @@ -465,7 +470,8 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) mhr.frame_control |= IEEE802154_FRAME_DATA << IEEE802154_FRAMECTRL_SHIFT_FTYPE; /* If the msduLength is greater than aMaxMACSafePayloadSize, the MAC sublayer - * will set the Frame Version to one. [1] pg. 118 */ + * will set the Frame Version to one. [1] pg. 118. + */ if (req->msdu_length > IEEE802154_MAX_SAFE_MAC_PAYLOAD_SIZE) { @@ -474,13 +480,15 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) /* If the TXOptions parameter specifies that an acknowledged transmission is * required, the AR field will be set appropriately, as described in - * 5.1.6.4 [1] pg. 118 */ + * 5.1.6.4 [1] pg. 118. + */ mhr.frame_ctrl |= (req->ack_tx << IEEE802154_FRAMECTRL_SHIFT_ACKREQ); - /* If the destination address is present, copy the PAN ID and one of the - * addresses, depending on mode, into the MHR */ - + /* If the destination address is present, copy the PAN ID and one of the + * addresses, depending on mode, into the MHR . + */ + if (req->dest_addr.mode != IEEE802154_ADDRMODE_NONE) { memcpy(&mhr.data[mhr.length], req->dest_addr.panid, 2); @@ -497,7 +505,7 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) mhr.length += 8; } } - + /* Set the destination addr mode inside the frame contorl field */ mhr.frame_ctrl |= (req->dest_addr.mode << IEEE802154_FRAMECTRL_SHIFT_DADDR); @@ -512,15 +520,17 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) } /* If both destination and source addressing information is present, the MAC - * sublayer shall compare the destination and source PAN identifiers. - * [1] pg. 41 */ + * sublayer shall compare the destination and source PAN identifiers. + * [1] pg. 41. + */ if (req->src_addr_mode != IEEE802154_ADDRMODE_NONE && req->dest_addr.mode != IEEE802154_ADDRMODE_NONE) { /* If the PAN identifiers are identical, the PAN ID Compression field * shall be set to one, and the source PAN identifier shall be omitted - * from the transmitted frame. [1] pg. 41 */ + * from the transmitted frame. [1] pg. 41. + */ if(req->dest_addr.panid == priv->addr.panid) { @@ -531,7 +541,8 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) if (req->src_addr_mode != IEEE802154_ADDRMODE_NONE) { /* If the destination address is not included, or if PAN ID Compression - * is off, we need to include the Source PAN ID */ + * is off, we need to include the Source PAN ID. + */ if (req->dest_addr.mode == IEEE802154_ADDRMODE_NONE || (mhr.frame_control & IEEE802154_FRAMECTRL_PANIDCOMP) @@ -558,13 +569,15 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) /* Each time a data or a MAC command frame is generated, the MAC sublayer * shall copy the value of macDSN into the Sequence Number field of the MHR - * of the outgoing frame and then increment it by one. [1] pg. 40 */ + * of the outgoing frame and then increment it by one. [1] pg. 40. + */ mhr.data[mhr.length++] = priv.dsn++; /* Now that we know which fields are included in the header, we can make - * sure we actually have enough room in the PSDU */ - + * sure we actually have enough room in the PSDU. + */ + if (mhr.length + req->msdu_length + IEEE802154_MFR_LENGTH > IEEE802154_MAX_PHY_PACKET_SIZE) { @@ -579,16 +592,17 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) trans->msdu_handle = req->msdu_handle; - /* If the TxOptions parameter specifies that a GTS transmission is required, - * the MAC sublayer will determine whether it has a valid GTS as described + /* If the TxOptions parameter specifies that a GTS transmission is required, + * the MAC sublayer will determine whether it has a valid GTS as described * 5.1.7.3. If a valid GTS could not be found, the MAC sublayer will discard - * the MSDU. If a valid GTS was found, the MAC sublayer will defer, if + * the MSDU. If a valid GTS was found, the MAC sublayer will defer, if * necessary, until the GTS. If the TxOptions parameter specifies that a GTS * transmission is not required, the MAC sublayer will transmit the MSDU using * either slotted CSMA-CA in the CAP for a beacon-enabled PAN or unslotted * CSMA-CA for a nonbeacon-enabled PAN. Specifying a GTS transmission in the * TxOptions parameter overrides an indirect transmission request. - * [1] pg. 118 */ + * [1] pg. 118. + */ if (req->gts_tx) { @@ -596,7 +610,8 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) * the transaction. Instead of going in the CSMA transaction list, it * should be linked to the GTS' transaction list. We'll need to check if * the GTS is valid, and then find the GTS, before linking. Note, we also - * don't have to try and kick-off any transmission here. */ + * don't have to try and kick-off any transmission here. + */ return -ENOTSUP; } @@ -605,17 +620,19 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) /* If the TxOptions parameter specifies that an indirect transmission is * required and this primitive is received by the MAC sublayer of a * coordinator, the data frame is sent using indirect transmission, as - * described in 5.1.5 and 5.1.6.3. [1] */ + * described in 5.1.5 and 5.1.6.3. [1] + */ if (req->indirect_tx) { /* If the TxOptions parameter specifies that an indirect transmission * is required and if the device receiving this primitive is not a - * coordinator, the destination address is not present, or the + * coordinator, the destination address is not present, or the * TxOptions parameter also specifies a GTS transmission, the indirect - * transmission option will be ignored. [1] */ + * transmission option will be ignored. [1] + */ - if (priv->is_coord && req->dest_addr.mode != IEEE802154_ADDRMODE_NONE) + if (priv->is_coord && req->dest_addr.mode != IEEE802154_ADDRMODE_NONE) { /* Link the transaction into the indirect_trans list */ @@ -653,11 +670,11 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) /* Called from interrupt level or worker thread with interrupts disabled */ -static uint16_t mac802154_poll_csma(FAR struct ieee802154_phyif_s *phyif, +static uint16_t mac802154_poll_csma(FAR struct ieee802154_phyif_s *phyif, FAR struct ieee802154_txdesc_s *tx_desc, uint8_t *buf) { - FAR struct ieee802154_privmac_s *priv = + FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)&phyif->priv; FAR struct mac802154_trans_s *trans; @@ -684,7 +701,8 @@ static uint16_t mac802154_poll_csma(FAR struct ieee802154_phyif_s *phyif, /* Now that we've passed off the data, notify the waiting thread. * NOTE: The transaction was allocated on the waiting thread's stack so * it will be automatically deallocated when that thread awakens and - * returns */ + * returns. + */ sem_post(trans->sem); @@ -698,15 +716,16 @@ static uint16_t mac802154_poll_csma(FAR struct ieee802154_phyif_s *phyif, * Name: mac802154_req_purge * * Description: - * The MCPS-PURGE.request primitive allows the next higher layer to purge an - * MSDU from the transaction queue. Confirmation is returned via + * The MCPS-PURGE.request primitive allows the next higher layer to purge + * an MSDU from the transaction queue. Confirmation is returned via * the struct ieee802154_maccb_s->conf_purge callback. * ****************************************************************************/ int mac802154_req_purge(MACHANDLE mac, uint8_t handle) { - FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } @@ -714,7 +733,7 @@ int mac802154_req_purge(MACHANDLE mac, uint8_t handle) * Name: mac802154_req_associate * * Description: - * The MLME-ASSOCIATE.request primitive allows a device to request an + * The MLME-ASSOCIATE.request primitive allows a device to request an * association with a coordinator. Confirmation is returned via the * struct ieee802154_maccb_s->conf_associate callback. * @@ -723,7 +742,8 @@ int mac802154_req_purge(MACHANDLE mac, uint8_t handle) int mac802154_req_associate(MACHANDLE mac, FAR struct ieee802154_assoc_req_s *req) { - FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; /* Set the channel of the PHY layer */ @@ -737,12 +757,12 @@ int mac802154_req_associate(MACHANDLE mac, if (req->coord_addr.mode == IEEE802154_ADDRMODE_EXTENDED) { - } + } else if (req->coord_addr.mode == IEEE802154_ADDRMODE_EXTENDED) { } - else + else { return -EINVAL; } @@ -765,7 +785,8 @@ int mac802154_req_associate(MACHANDLE mac, int mac802154_req_disassociate(MACHANDLE mac, FAR struct ieee802154_disassoc_req_s *req) { - FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } @@ -781,7 +802,8 @@ int mac802154_req_disassociate(MACHANDLE mac, int mac802154_req_get(MACHANDLE mac, enum ieee802154_pib_attr_e attr) { - FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } @@ -798,7 +820,8 @@ int mac802154_req_get(MACHANDLE mac, enum ieee802154_pib_attr_e attr) int mac802154_req_gts(MACHANDLE mac, FAR uint8_t *characteristics) { - FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } @@ -814,7 +837,8 @@ int mac802154_req_gts(MACHANDLE mac, FAR uint8_t *characteristics) int mac802154_req_reset(MACHANDLE mac, bool setdefaults) { - FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; + FAR struct ieee802154_privmac_s * priv = + (FAR struct ieee802154_privmac_s *) mac; return -ENOTTY; } @@ -832,7 +856,8 @@ int mac802154_req_reset(MACHANDLE mac, bool setdefaults) int mac802154_req_rxenable(MACHANDLE mac, bool deferrable, int ontime, int duration) { - FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *)mac; + FAR struct ieee802154_privmac_s * priv = + (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } @@ -854,7 +879,8 @@ int mac802154_req_rxenable(MACHANDLE mac, bool deferrable, int ontime, int mac802154_req_scan(MACHANDLE mac, uint8_t type, uint32_t channels, int duration) { - FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } @@ -871,7 +897,8 @@ int mac802154_req_scan(MACHANDLE mac, uint8_t type, uint32_t channels, int mac802154_req_set(MACHANDLE mac, int attribute, FAR uint8_t *value, int valuelen) { - FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } @@ -889,7 +916,8 @@ int mac802154_req_start(MACHANDLE mac, uint16_t panid, int channel, uint8_t bo, uint8_t fo, bool coord, bool batext, bool realign) { - FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } @@ -906,7 +934,8 @@ int mac802154_req_start(MACHANDLE mac, uint16_t panid, int channel, int mac802154_req_sync(MACHANDLE mac, int channel, bool track) { - FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } @@ -914,8 +943,8 @@ int mac802154_req_sync(MACHANDLE mac, int channel, bool track) * Name: mac802154_req_poll * * Description: - * The MLME-POLL.request primitive prompts the device to request data from the - * coordinator. Confirmation is returned via the + * The MLME-POLL.request primitive prompts the device to request data from + * the coordinator. Confirmation is returned via the * struct ieee802154_maccb_s->conf_poll callback, followed by a * struct ieee802154_maccb_s->ind_data callback. * @@ -923,7 +952,8 @@ int mac802154_req_sync(MACHANDLE mac, int channel, bool track) int mac802154_req_poll(MACHANDLE mac, FAR uint8_t *coordaddr) { - FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } @@ -931,15 +961,16 @@ int mac802154_req_poll(MACHANDLE mac, FAR uint8_t *coordaddr) * Name: mac802154_rsp_associate * * Description: - * The MLME-ASSOCIATE.response primitive is used to initiate a response to an - * MLME-ASSOCIATE.indication primitive. + * The MLME-ASSOCIATE.response primitive is used to initiate a response to + * an MLME-ASSOCIATE.indication primitive. * ****************************************************************************/ int mac802154_rsp_associate(MACHANDLE mac, uint8_t eadr, uint16_t saddr, int status) { - FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } diff --git a/wireless/ieee802154/mac802154.h b/wireless/ieee802154/mac802154.h index 8321e905ea..3b2cd1de5a 100644 --- a/wireless/ieee802154/mac802154.h +++ b/wireless/ieee802154/mac802154.h @@ -102,7 +102,7 @@ int mac802154_ioctl(MACHANDLE mac, int cmd, unsigned long arg); * * Description: * The MCPS-DATA.request primitive requests the transfer of a data SPDU - * (i.e., MSDU) from a local SSCS entity to a single peer SSCS entity. + * (i.e., MSDU) from a local SSCS entity to a single peer SSCS entity. * Confirmation is returned via the * struct ieee802154_maccb_s->conf_data callback. * @@ -114,8 +114,8 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req); * Name: mac802154_req_purge * * Description: - * The MCPS-PURGE.request primitive allows the next higher layer to purge an - * MSDU from the transaction queue. Confirmation is returned via + * The MCPS-PURGE.request primitive allows the next higher layer to purge + * an MSDU from the transaction queue. Confirmation is returned via * the struct ieee802154_maccb_s->conf_purge callback. * ****************************************************************************/ @@ -126,7 +126,7 @@ int mac802154_req_purge(MACHANDLE mac, uint8_t handle); * Name: mac802154_req_associate * * Description: - * The MLME-ASSOCIATE.request primitive allows a device to request an + * The MLME-ASSOCIATE.request primitive allows a device to request an * association with a coordinator. Confirmation is returned via the * struct ieee802154_maccb_s->conf_associate callback. * @@ -139,9 +139,11 @@ int mac802154_req_associate(MACHANDLE mac, * Name: mac802154_req_disassociate * * Description: - * The MLME-DISASSOCIATE.request primitive is used by an associated device to - * notify the coordinator of its intent to leave the PAN. It is also used by - * the coordinator to instruct an associated device to leave the PAN. + * The MLME-DISASSOCIATE.request primitive is used by an associated device + * to notify the coordinator of its intent to leave the PAN. It is also + * used by the coordinator to instruct an associated device to leave the + * PAN. + * * Confirmation is returned via the * struct ieee802154_maccb_s->conf_disassociate callback. * @@ -166,8 +168,8 @@ int mac802154_req_get(MACHANDLE mac, enum ieee802154_pib_attr_e attr); * Name: mac802154_req_gts * * Description: - * The MLME-GTS.request primitive allows a device to send a request to the PAN - * coordinator to allocate a new GTS or to deallocate an existing GTS. + * The MLME-GTS.request primitive allows a device to send a request to the + * PAN coordinator to allocate a new GTS or to deallocate an existing GTS. * Confirmation is returned via the * struct ieee802154_maccb_s->conf_gts callback. * @@ -205,14 +207,14 @@ int mac802154_req_rxenable(MACHANDLE mac, bool deferrable, int ontime, * Name: mac802154_req_scan * * Description: - * The MLME-SCAN.request primitive is used to initiate a channel scan over a - * given list of channels. A device can use a channel scan to measure the - * energy on the channel, search for the coordinator with which it associated, - * or search for all coordinators transmitting beacon frames within the POS of - * the scanning device. Scan results are returned - * via MULTIPLE calls to the struct ieee802154_maccb_s->conf_scan callback. - * This is a difference with the official 802.15.4 specification, implemented - * here to save memory. + * The MLME-SCAN.request primitive is used to initiate a channel scan over + * a given list of channels. A device can use a channel scan to measure + * the energy on the channel, search for the coordinator with which it + * associated, or search for all coordinators transmitting beacon frames + * within the POS of the scanning device. Scan results are returned + * via MULTIPLE calls to the struct ieee802154_maccb_s->conf_scan + * callback. This is a difference with the official 802.15.4 + * specification, implemented here to save memory. * ****************************************************************************/ @@ -236,8 +238,8 @@ int mac802154_req_set(MACHANDLE mac, int attribute, FAR uint8_t *value, * Name: mac802154_req_start * * Description: - * The MLME-START.request primitive makes a request for the device to start - * using a new superframe configuration. Confirmation is returned + * The MLME-START.request primitive makes a request for the device to + * start using a new superframe configuration. Confirmation is returned * via the struct ieee802154_maccb_s->conf_start callback. * ****************************************************************************/ @@ -263,8 +265,8 @@ int mac802154_req_sync(MACHANDLE mac, int channel, bool track); * Name: mac802154_req_poll * * Description: - * The MLME-POLL.request primitive prompts the device to request data from the - * coordinator. Confirmation is returned via the + * The MLME-POLL.request primitive prompts the device to request data from + * the coordinator. Confirmation is returned via the * struct ieee802154_maccb_s->conf_poll callback, followed by a * struct ieee802154_maccb_s->ind_data callback. * @@ -276,8 +278,8 @@ int mac802154_req_poll(MACHANDLE mac, FAR uint8_t *coordaddr); * Name: mac802154_rsp_associate * * Description: - * The MLME-ASSOCIATE.response primitive is used to initiate a response to an - * MLME-ASSOCIATE.indication primitive. + * The MLME-ASSOCIATE.response primitive is used to initiate a response to + * an MLME-ASSOCIATE.indication primitive. * ****************************************************************************/ diff --git a/wireless/ieee802154/mac802154_device.c b/wireless/ieee802154/mac802154_device.c index 67631e7c63..b35049e9ac 100644 --- a/wireless/ieee802154/mac802154_device.c +++ b/wireless/ieee802154/mac802154_device.c @@ -83,12 +83,11 @@ struct mac802154_devwrapper_s struct mac802154dev_notify_s md_mcps_notify; pid_t md_mcps_pid; - + /* MLME Service notification information */ struct mac802154dev_notify_s md_mlme_notify; pid_t md_mlme_pid; - #endif }; @@ -228,7 +227,7 @@ static int mac802154dev_open(FAR struct file *filep) ret = -ENOMEM; goto errout_with_sem; } - + /* Attach the open struct to the device */ opriv->md_flink = dev->md_open; @@ -413,7 +412,7 @@ static ssize_t mac802154dev_write(FAR struct file *filep, wlerr("ERROR: buffer too small: %lu\n", (unsigned long)len); return -EINVAL; } - + DEBUGASSERT(buffer != NULL); frame = (FAR struct ieee802154_frame_s *)buffer; @@ -441,7 +440,7 @@ static ssize_t mac802154dev_write(FAR struct file *filep, mac802154dev_givesem(&dev->md_exclsem); - if (ret < 0) + if (ret < 0) { wlerr("ERROR: req_data failed %d\n", ret); return ret; @@ -449,7 +448,7 @@ static ssize_t mac802154dev_write(FAR struct file *filep, /* Wait for the DATA.confirm callback to be called for our handle */ - if(sem_wait(dwait.mw_sem) < 0) + if (sem_wait(dwait.mw_sem) < 0) { /* This should only happen if the wait was canceled by an signal */ @@ -522,10 +521,11 @@ static int mac802154dev_ioctl(FAR struct file *filep, int cmd, dev->md_mlme_notify.mn_signo = notify->mn_signo; dev->md_mlme_pid = getpid(); - return OK; + return OK; } } break; + case MAC802154IOC_MCPS_REGISTER: { FAR struct mac802154dev_notify_s *notify = @@ -538,19 +538,19 @@ static int mac802154dev_ioctl(FAR struct file *filep, int cmd, dev->md_mcps_notify.mn_signo = notify->mn_signo; dev->md_mcps_pid = getpid(); - return OK; + return OK; } } break; #endif + case MAC802154IOC_MLME_ASSOC_REQUEST: { FAR struct ieee802154_assoc_req_s *req = (FAR struct ieee802154_assoc_req_s *)((uintptr_t)arg); - - } break; + default: wlerr("ERROR: Unrecognized command %ld\n", cmd); ret = -EINVAL; @@ -578,7 +578,7 @@ void mac802154dev_conf_data(MACHANDLE mac, /* Get exclusive access to the driver structure. We don't care about any * signals so if we see one, just go back to trying to get access again */ - + while(mac802154dev_takesem(&dev->md_exclsem) != OK); /* Search to see if there is a dwait pending for this transaction */ @@ -586,37 +586,36 @@ void mac802154dev_conf_data(MACHANDLE mac, for (prev = NULL, curr = dev->md_dwait; curr && curr->mw_handle != conf->msdu_handle; prev = curr, curr = curr->mw_flink); - + /* If a dwait is found */ if (curr) - { - /* Unlink the structure from the list. The struct should be allocated on - * the calling write's stack, so we don't need to worry about deallocating - * here */ + { + /* Unlink the structure from the list. The struct should be allocated on + * the calling write's stack, so we don't need to worry about deallocating + * here */ - if (prev) - { - prev->mw_flink = curr->mw_flink; - } - else - { - dev->md_dwait = curr->mw_flink; - } - - /* Copy the transmission status into the dwait struct */ + if (prev) + { + prev->mw_flink = curr->mw_flink; + } + else + { + dev->md_dwait = curr->mw_flink; + } - curr->mw_status = conf->msdu_handle; + /* Copy the transmission status into the dwait struct */ - /* Wake the thread waiting for the data transmission */ + curr->mw_status = conf->msdu_handle; - sem_post(&curr->mw_sem); + /* Wake the thread waiting for the data transmission */ - /* Release the driver */ + sem_post(&curr->mw_sem); - mac802154dev_givesem(&dev->md_exclsem); - } + /* Release the driver */ + mac802154dev_givesem(&dev->md_exclsem); + } #ifndef CONFIG_DISABLE_SIGNALS /* Send a signal to the registered application */ @@ -631,7 +630,6 @@ void mac802154dev_conf_data(MACHANDLE mac, (void)sigqueue(dev->md_mcps_pid, dev->md_mcps_notify.mn_signo, value.sival_ptr); #endif - #endif } diff --git a/wireless/ieee802154/radio802154_device.c b/wireless/ieee802154/radio802154_device.c index ac76283c7d..15f4d1d84e 100644 --- a/wireless/ieee802154/radio802154_device.c +++ b/wireless/ieee802154/radio802154_device.c @@ -261,7 +261,7 @@ static ssize_t radio802154dev_read(FAR struct file *filep, FAR char *buffer, siz goto done; } #endif - + /* if no packet is received, this will produce -EAGAIN * The user is responsible for sleeping until sth arrives */ -- GitLab From d646bde1f87d3aa2d70ebb355350248bc3c10c02 Mon Sep 17 00:00:00 2001 From: Simon Piriou Date: Sun, 16 Apr 2017 11:28:08 +0200 Subject: [PATCH 471/990] photon: add sdpcm tx basic support --- drivers/wireless/ieee80211/Make.defs | 1 + .../wireless/ieee80211/bcm43362_constants.h | 4 - drivers/wireless/ieee80211/bcmf_driver.h | 11 +- drivers/wireless/ieee80211/bcmf_hexdump.c | 36 ++ drivers/wireless/ieee80211/bcmf_sdio.c | 82 ++++- drivers/wireless/ieee80211/bcmf_sdio.h | 2 + drivers/wireless/ieee80211/bcmf_sdio_core.h | 4 + drivers/wireless/ieee80211/bcmf_sdpcm.c | 331 +++++++++++++++++- drivers/wireless/ieee80211/bcmf_sdpcm.h | 31 +- 9 files changed, 442 insertions(+), 60 deletions(-) create mode 100644 drivers/wireless/ieee80211/bcmf_hexdump.c diff --git a/drivers/wireless/ieee80211/Make.defs b/drivers/wireless/ieee80211/Make.defs index 440e5a9f23..1fa0d3b091 100644 --- a/drivers/wireless/ieee80211/Make.defs +++ b/drivers/wireless/ieee80211/Make.defs @@ -44,6 +44,7 @@ ifeq ($(CONFIG_IEEE80211_BROADCOM_FULLMAC_SDIO),y) CSRCS += bcmf_sdio.c CSRCS += bcmf_core.c CSRCS += bcmf_sdpcm.c + CSRCS += bcmf_hexdump.c CSRCS += mmc_sdio.c endif diff --git a/drivers/wireless/ieee80211/bcm43362_constants.h b/drivers/wireless/ieee80211/bcm43362_constants.h index 0911bdfbe8..4144c049b6 100644 --- a/drivers/wireless/ieee80211/bcm43362_constants.h +++ b/drivers/wireless/ieee80211/bcm43362_constants.h @@ -51,10 +51,6 @@ #define SOCSRAM_BASE_ADDRESS 0x18004000 /* SOCSRAM core register region */ #define BACKPLANE_ADDRESS_MASK 0x7FFF -#define CHIP_STA_INTERFACE 0 -#define CHIP_AP_INTERFACE 1 -#define CHIP_P2P_INTERFACE 2 - /* Maximum value of bus data credit difference */ #define CHIP_MAX_BUS_DATA_CREDIT_DIFF 7 diff --git a/drivers/wireless/ieee80211/bcmf_driver.h b/drivers/wireless/ieee80211/bcmf_driver.h index 6225f7396e..bf870bf9d6 100644 --- a/drivers/wireless/ieee80211/bcmf_driver.h +++ b/drivers/wireless/ieee80211/bcmf_driver.h @@ -51,7 +51,7 @@ struct bcmf_dev_s uint32_t (*get_core_base_address)(unsigned int core); /* Get chip specific base address for evey cores */ - sem_t sem; /* Semaphore for processing thread event */ + sem_t thread_signal; /* Semaphore for processing thread event */ struct wdog_s *waitdog; /* Processing thread waitdog */ bool ready; /* Current device status */ bool sleeping; /* Current sleep status */ @@ -61,6 +61,15 @@ struct bcmf_dev_s uint8_t max_seq; /* Maximum transmit sequence allowed */ uint8_t tx_seq; /* Transmit sequence number (next) */ uint8_t rx_seq; /* Receive sequence number (expected) */ + + // FIXME use mutex instead of semaphore + sem_t control_mutex; /* Cannot handle multiple control requests */ + sem_t control_timeout; /* Semaphore to wait for control frame rsp */ + uint16_t control_reqid; /* Current control request id */ + + // FIXME use mutex instead of semaphore + sem_t tx_queue_mutex; /* Lock for transmit queue */ + dq_queue_t tx_queue; /* Queue of frames to tramsmit */ }; #endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_DRIVER_H */ diff --git a/drivers/wireless/ieee80211/bcmf_hexdump.c b/drivers/wireless/ieee80211/bcmf_hexdump.c new file mode 100644 index 0000000000..d1f29b02ff --- /dev/null +++ b/drivers/wireless/ieee80211/bcmf_hexdump.c @@ -0,0 +1,36 @@ +#include +#include +#include + +#include + +#define LINE_LEN 16 + +void bcmf_hexdump(uint8_t *data, unsigned int len, unsigned long offset) +{ + unsigned int i; + unsigned int char_count = 0; + char char_line[20]; + char hex_line[64]; + + for(i = 0; i < len; i++) + { + if (char_count >= LINE_LEN) { + /* Flush line */ + _info("%08x: %s%s\n", offset+i-char_count, hex_line, char_line); + char_count = 0; + } + + sprintf(hex_line+3*char_count, "%02x ", data[i]); + sprintf(char_line+char_count, "%c", + data[i] < 0x20 || data[i] >= 0x7f? '.': data[i]); + char_count ++; + } + + if (char_count > 0) { + /* Flush last line */ + memset(hex_line+3*char_count, ' ', 3*(LINE_LEN-char_count)); + hex_line[3*LINE_LEN] = 0; + _info("%08x: %s%s\n", offset+i-char_count, hex_line, char_line); + } +} \ No newline at end of file diff --git a/drivers/wireless/ieee80211/bcmf_sdio.c b/drivers/wireless/ieee80211/bcmf_sdio.c index 9d5a26377c..96778a7d7c 100644 --- a/drivers/wireless/ieee80211/bcmf_sdio.c +++ b/drivers/wireless/ieee80211/bcmf_sdio.c @@ -45,6 +45,7 @@ #include #include #include +#include #include #include @@ -59,6 +60,9 @@ #include "bcmf_core.h" #include "bcmf_sdpcm.h" +// TODO remove +#include "bcmf_ioctl.h" + /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ @@ -114,7 +118,7 @@ int bcmf_oob_irq(int irq, FAR void *context, FAR void *arg) /* Signal bmcf thread */ priv->irq_pending = true; - sem_post(&priv->sem); + sem_post(&priv->thread_signal); } return OK; } @@ -362,8 +366,8 @@ int bcmf_bus_setup_interrupts(FAR struct bcmf_dev_s *priv) /* Redirect, configure and enable io for out-of-band interrupt signal */ - ret = sdio_io_rw_direct(priv->sdio_dev, true, 0, SDIO_CCCR_BRCM_SEPINT, - SDIO_SEPINT_MASK | SDIO_SEPINT_OE | SDIO_SEPINT_ACT_HI, NULL); + ret = bcmf_write_reg(priv, 0, SDIO_CCCR_BRCM_SEPINT, + SDIO_SEPINT_MASK | SDIO_SEPINT_OE | SDIO_SEPINT_ACT_HI); if (ret != OK) { return ret; @@ -527,6 +531,29 @@ int bcmf_write_reg(FAR struct bcmf_dev_s *priv, uint8_t function, return bcmf_transfer_bytes(priv, true, function, address, ®, 1); } +/**************************************************************************** + * Name: bcmf_sem_wait + ****************************************************************************/ + +int bcmf_sem_wait(sem_t *sem, unsigned int timeout_ms) +{ + struct timespec abstime; + + /* Get the current time */ + + (void)clock_gettime(CLOCK_REALTIME, &abstime); + + abstime.tv_nsec += 1000 * 1000* timeout_ms; + + if (abstime.tv_nsec >= 1000 * 1000 * 1000) + { + abstime.tv_sec++; + abstime.tv_nsec -= 1000 * 1000 * 1000; + } + + return sem_timedwait(sem, &abstime); +} + /**************************************************************************** * Name: bcmf_sdio_initialize ****************************************************************************/ @@ -555,11 +582,11 @@ int bcmf_sdio_initialize(int minor, FAR struct sdio_dev_s *dev) priv->ready = false; priv->sleeping = true; - if ((ret = sem_init(&priv->sem, 0, 0)) != OK) + if ((ret = sem_init(&priv->thread_signal, 0, 0)) != OK) { goto exit_free_priv; } - if ((ret = sem_setprotocol(&priv->sem, SEM_PRIO_NONE)) != OK) + if ((ret = sem_setprotocol(&priv->thread_signal, SEM_PRIO_NONE)) != OK) { goto exit_free_priv; } @@ -571,6 +598,27 @@ int bcmf_sdio_initialize(int minor, FAR struct sdio_dev_s *dev) goto exit_free_priv; } + if ((ret = sem_init(&priv->control_mutex, 0, 1)) != OK) + { + goto exit_free_waitdog; + } + + if ((ret = sem_init(&priv->control_timeout, 0, 0)) != OK) + { + goto exit_free_waitdog; + } + if ((ret = sem_setprotocol(&priv->control_timeout, SEM_PRIO_NONE)) != OK) + { + goto exit_free_waitdog; + } + /* Init transmit frames queue */ + + if ((ret = sem_init(&priv->tx_queue_mutex, 0, 1)) != OK) + { + goto exit_free_waitdog; + } + sq_init(&priv->tx_queue); + /* Initialize device hardware */ ret = bcmf_hwinitialize(priv); @@ -632,6 +680,15 @@ int bcmf_sdio_initialize(int minor, FAR struct sdio_dev_s *dev) /* Device is up and running TODO Create a wlan device name and register network driver here */ + // TODO remove: basic iovar test + up_mdelay(2000); + char fw_version[64]; + ret = bcmf_sdpcm_iovar_request(priv, CHIP_STA_INTERFACE, false, + IOVAR_STR_VERSION, fw_version, + sizeof(fw_version)); + _info("fw version %d\n", ret); + + return OK; exit_uninit_hw: @@ -675,7 +732,8 @@ void bcmf_sdio_waitdog_timeout(int argc, wdparm_t arg1, ...) FAR struct bcmf_dev_s *priv = g_sdio_priv; /* Notify bcmf thread */ - sem_post(&priv->sem); + + sem_post(&priv->thread_signal); } int bcmf_sdio_thread(int argc, char **argv) @@ -693,7 +751,7 @@ int bcmf_sdio_thread(int argc, char **argv) { /* Wait for event (device interrupt, user request or waitdog timer) */ - ret = sem_wait(&priv->sem); + ret = sem_wait(&priv->thread_signal); if (ret != OK) { _err("Error while waiting for semaphore\n"); @@ -715,8 +773,6 @@ int bcmf_sdio_thread(int argc, char **argv) priv->irq_pending = false; - _info("process irq\n"); - bcmf_read_sbregw(priv, CORE_BUS_REG(priv->get_core_base_address(SDIOD_CORE_ID), intstatus), &priv->intstatus); @@ -748,10 +804,16 @@ int bcmf_sdio_thread(int argc, char **argv) } } - // TODO send all queued frames + /* Send all queued frames */ + + do + { + ret = bcmf_sdpcm_sendframe(priv); + } while (ret == OK); /* If we're done for now, turn off clock request. */ + // TODO add wakelock bcmf_sdio_bus_sleep(priv, true); } return 0; diff --git a/drivers/wireless/ieee80211/bcmf_sdio.h b/drivers/wireless/ieee80211/bcmf_sdio.h index bb66daca25..0645d23c92 100644 --- a/drivers/wireless/ieee80211/bcmf_sdio.h +++ b/drivers/wireless/ieee80211/bcmf_sdio.h @@ -24,4 +24,6 @@ int bcmf_read_reg(FAR struct bcmf_dev_s *priv, uint8_t function, int bcmf_write_reg(FAR struct bcmf_dev_s *priv, uint8_t function, uint32_t address, uint8_t reg); +int bcmf_sem_wait(sem_t *sem, unsigned int timeout_ms); + #endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_SDIO_H */ \ No newline at end of file diff --git a/drivers/wireless/ieee80211/bcmf_sdio_core.h b/drivers/wireless/ieee80211/bcmf_sdio_core.h index c6ad612c11..fa592adc9e 100644 --- a/drivers/wireless/ieee80211/bcmf_sdio_core.h +++ b/drivers/wireless/ieee80211/bcmf_sdio_core.h @@ -61,6 +61,10 @@ #define I_HMB_SW_MASK ( (uint32_t) 0x000000F0 ) #define I_HMB_FRAME_IND ( 1<<6 ) +#define CHIP_STA_INTERFACE 0 +#define CHIP_AP_INTERFACE 1 +#define CHIP_P2P_INTERFACE 2 + enum { CHIPCOMMON_CORE_ID, DOT11MAC_CORE_ID, diff --git a/drivers/wireless/ieee80211/bcmf_sdpcm.c b/drivers/wireless/ieee80211/bcmf_sdpcm.c index c7c3facc57..39d2f29e09 100644 --- a/drivers/wireless/ieee80211/bcmf_sdpcm.c +++ b/drivers/wireless/ieee80211/bcmf_sdpcm.c @@ -45,10 +45,18 @@ #include #include +#include +#include +#include #include "bcmf_sdio.h" #include "bcmf_core.h" #include "bcmf_sdpcm.h" +#include "bcmf_ioctl.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ /* SDA_FRAMECTRL */ #define SFC_RF_TERM (1 << 0) /* Read Frame Terminate */ @@ -57,25 +65,78 @@ #define SFC_ABORTALL (1 << 3) /* Abort all in-progress frames */ /* tosbmailbox bits corresponding to intstatus bits */ -#define SMB_NAK (1 << 0) /* Frame NAK */ +#define SMB_NAK (1 << 0) /* Frame NAK */ #define SMB_INT_ACK (1 << 1) /* Host Interrupt ACK */ #define SMB_USE_OOB (1 << 2) /* Use OOB Wakeup */ #define SMB_DEV_INT (1 << 3) /* Miscellaneous Interrupt */ -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ +/* CDC flag definitions */ +#define CDC_DCMD_ERROR 0x01 /* 1=cmd failed */ +#define CDC_DCMD_SET 0x02 /* 0=get, 1=set cmd */ +#define CDC_DCMD_IF_MASK 0xF000 /* I/F index */ +#define CDC_DCMD_IF_SHIFT 12 +#define CDC_DCMD_ID_MASK 0xFFFF0000 /* id an cmd pairing */ +#define CDC_DCMD_ID_SHIFT 16 /* ID Mask shift bits */ +#define CDC_DCMD_ID(flags) \ + (((flags) & CDC_DCMD_ID_MASK) >> CDC_DCMD_ID_SHIFT) + +#define SDPCM_CONTROL_CHANNEL 0 /* Control */ +#define SDPCM_EVENT_CHANNEL 1 /* Asyc Event Indication */ +#define SDPCM_DATA_CHANNEL 2 /* Data Xmit/Recv */ +#define SDPCM_GLOM_CHANNEL 3 /* Coalesced packets */ +#define SDPCM_TEST_CHANNEL 15 /* Test/debug packets */ + +#define SDPCM_CONTROL_TIMEOUT_MS 1000 + +// TODO remove +void bcmf_hexdump(uint8_t *data, unsigned int len, unsigned long offset); /**************************************************************************** * Private Types ****************************************************************************/ +struct bcmf_sdpcm_header { + uint16_t size; + uint16_t checksum; + uint8_t sequence; + uint8_t channel; + uint8_t next_length; + uint8_t data_offset; + uint8_t flow_control; + uint8_t credit; + uint16_t padding; +}; + +struct bcmf_sdpcm_cdc_header { + uint32_t cmd; /* dongle command value */ + uint32_t len; /* lower 16: output buflen; + * upper 16: input buflen (excludes header) */ + uint32_t flags; /* flag defns given below */ + uint32_t status; /* status code returned from the device */ +}; + +struct bcmf_sdpcm_frame { + dq_entry_t list_entry; + struct bcmf_sdpcm_header header; + uint8_t data[0]; +}; + +struct bcmf_sdpcm_cdc_dcmd { + dq_entry_t list_entry; + struct bcmf_sdpcm_header header; + struct bcmf_sdpcm_cdc_header cdc_header; + uint8_t data[0]; +}; + /**************************************************************************** * Private Function Prototypes ****************************************************************************/ static int bcmf_sdpcm_rxfail(FAR struct bcmf_dev_s *priv, bool retry); +static int bcmf_sdpcm_process_header(FAR struct bcmf_dev_s *priv, + struct bcmf_sdpcm_header *header); + /**************************************************************************** * Private Data ****************************************************************************/ @@ -105,19 +166,11 @@ int bcmf_sdpcm_rxfail(FAR struct bcmf_dev_s *priv, bool retry) return 0; } -/**************************************************************************** - * Public Functions - ****************************************************************************/ - int bcmf_sdpcm_process_header(FAR struct bcmf_dev_s *priv, struct bcmf_sdpcm_header *header) { - uint16_t len; - - len = header->frametag[0]; - if (header->data_offset < sizeof(struct bcmf_sdpcm_header) || - header->data_offset > len) + header->data_offset > header->size) { _err("Invalid data offset\n"); bcmf_sdpcm_rxfail(priv, false); @@ -142,6 +195,10 @@ int bcmf_sdpcm_process_header(FAR struct bcmf_dev_s *priv, return OK; } +/**************************************************************************** + * Public Functions + ****************************************************************************/ + // FIXME remove uint8_t tmp_buffer[512]; int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv) @@ -160,8 +217,8 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv) goto exit_abort; } - len = header->frametag[0]; - checksum = header->frametag[1]; + len = header->size; + checksum = header->checksum; /* All zero means no more to read */ @@ -194,6 +251,9 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv) goto exit_abort; } + _info("Receive frame\n"); + bcmf_hexdump((uint8_t*)header, len, (unsigned int)header); + /* Process and validate header */ ret = bcmf_sdpcm_process_header(priv, header); @@ -209,9 +269,242 @@ exit_abort: return ret; } -int bcmf_sdpcm_iovar_data_get(FAR struct bcmf_dev_s *priv, char *name, - void *data, unsigned int len) +int bcmf_sdpcm_sendframe(FAR struct bcmf_dev_s *priv) { - // TODO implement - return -EINVAL; + int ret; + struct bcmf_sdpcm_frame *frame; + + if (priv->tx_queue.tail == NULL) + { + /* No more frames to send */ + + return -ENODATA; + } + + if (priv->tx_seq == priv->max_seq) + { + // TODO handle this case + _err("No credit to send frame\n"); + return -EAGAIN; + } + + + if ((ret = sem_wait(&priv->tx_queue_mutex)) != OK) + { + return ret; + } + + frame = (struct bcmf_sdpcm_frame*)priv->tx_queue.tail; + + /* Set frame sequence id */ + + frame->header.sequence = priv->tx_seq++; + + _info("Send frame\n"); + bcmf_hexdump((uint8_t*)&frame->header, frame->header.size, + (unsigned int)&frame->header); + + ret = bcmf_transfer_bytes(priv, true, 2, 0, (uint8_t*)&frame->header, + frame->header.size); + if (ret != OK) + { + _info("fail send frame %d\n", ret); + ret = -EIO; + goto exit_abort; + // TODO handle retry count and remove frame from queue + abort TX + } + + /* Frame sent, remove it from queue */ + + if (priv->tx_queue.head == &frame->list_entry) + { + /* List is empty */ + + priv->tx_queue.head = NULL; + priv->tx_queue.tail = NULL; + } + else + { + priv->tx_queue.tail = frame->list_entry.blink; + frame->list_entry.blink->flink = priv->tx_queue.head; + } + + /* TODO free frame buffer */ + + goto exit_post_sem; + +exit_abort: + // bcmf_sdpcm_txfail(priv, false); +exit_post_sem: + sem_post(&priv->tx_queue_mutex); + return ret; } + +// FIXME remove +uint8_t tmp_buffer2[512]; +uint8_t* bcmf_sdpcm_allocate_iovar(FAR struct bcmf_dev_s *priv, char *name, + char *data, uint32_t *len) +{ + uint32_t data_len; + uint16_t name_len = strlen(name) + 1; + + if (!data) + { + data_len = 0; + } + else + { + data_len = *len; + } + + // FIXME allocate buffer and use max_size instead of 512 + if (data_len > 512-sizeof(struct bcmf_sdpcm_cdc_dcmd) || + (data_len + name_len) > 512-sizeof(struct bcmf_sdpcm_cdc_dcmd)) + { + *len = 0; + return NULL; + } + + // TODO allocate buffer + + /* Copy name string and data */ + + memcpy(tmp_buffer2+sizeof(struct bcmf_sdpcm_cdc_dcmd), name, name_len); + memcpy(tmp_buffer2+sizeof(struct bcmf_sdpcm_cdc_dcmd)+name_len, + data, data_len); + + *len = sizeof(struct bcmf_sdpcm_cdc_dcmd)+name_len+data_len; + return tmp_buffer2; +} + +int bcmf_sdpcm_queue_frame(FAR struct bcmf_dev_s *priv, uint8_t channel, + uint8_t *data, uint32_t len) +{ + int ret; + struct bcmf_sdpcm_frame *frame = (struct bcmf_sdpcm_frame*)data; + uint16_t frame_size = len - sizeof(frame->list_entry); + + /* Prepare sw header */ + + memset(&frame->header, 0, sizeof(struct bcmf_sdpcm_header)); + frame->header.size = frame_size; + frame->header.checksum = ~frame_size; + frame->header.channel = channel; + frame->header.data_offset = sizeof(struct bcmf_sdpcm_header); + + /* Add frame in tx queue */ + + if ((ret = sem_wait(&priv->tx_queue_mutex)) != OK) + { + return ret; + } + + if (priv->tx_queue.head == NULL) + { + /* List is empty */ + + priv->tx_queue.head = &frame->list_entry; + priv->tx_queue.tail = &frame->list_entry; + + frame->list_entry.flink = &frame->list_entry; + frame->list_entry.blink = &frame->list_entry; + } + else + { + /* Insert entry at list head */ + + frame->list_entry.flink = priv->tx_queue.head; + frame->list_entry.blink = priv->tx_queue.tail; + + priv->tx_queue.head->blink = &frame->list_entry; + priv->tx_queue.head = &frame->list_entry; + } + + sem_post(&priv->tx_queue_mutex); + + /* Notify bcmf thread tx frame is ready */ + + sem_post(&priv->thread_signal); + + return OK; +} + +int bcmf_sdpcm_send_dcmd(FAR struct bcmf_dev_s *priv, uint32_t cmd, + int ifidx, bool set, uint8_t *data, uint32_t len) +{ + struct bcmf_sdpcm_cdc_dcmd *msg = (struct bcmf_sdpcm_cdc_dcmd*)data; + + /* Setup cdc_dcmd header */ + + msg->cdc_header.cmd = cmd; + msg->cdc_header.len = len-sizeof(struct bcmf_sdpcm_cdc_dcmd); + msg->cdc_header.status = 0; + msg->cdc_header.flags = ++priv->control_reqid << CDC_DCMD_ID_SHIFT; + msg->cdc_header.flags |= ifidx << CDC_DCMD_IF_SHIFT; + + if (set) + { + msg->cdc_header.flags |= CDC_DCMD_SET; + } + + /* Queue frame */ + + return bcmf_sdpcm_queue_frame(priv, SDPCM_CONTROL_CHANNEL, data, len); +} + +int bcmf_sdpcm_iovar_request(FAR struct bcmf_dev_s *priv, + uint32_t ifidx, bool set, char *name, + char *data, uint32_t len) +{ + int ret; + uint8_t *iovar_buf; + uint32_t iovar_buf_len = len; + + /* Take device control mutex */ + + if ((ret = sem_wait(&priv->control_mutex)) !=OK) + { + return ret; + } + + /* Prepare control frame */ + + iovar_buf = bcmf_sdpcm_allocate_iovar(priv, name, data, &iovar_buf_len); + if (!iovar_buf) + { + _err("Cannot allocate iovar buf\n"); + ret = -ENOMEM; + goto exit_sem_post; + } + + /* Send control frame */ + + ret = bcmf_sdpcm_send_dcmd(priv, set ? WLC_SET_VAR : WLC_GET_VAR, + ifidx, set, iovar_buf, iovar_buf_len); + if (ret != OK) + { + goto exit_free_iovar; + } + + /* Wait for response */ + + ret = bcmf_sem_wait(&priv->control_timeout, SDPCM_CONTROL_TIMEOUT_MS); + if (ret != OK) + { + _err("Error while waiting for control response %d\n", ret); + goto exit_free_iovar; + } + + if (!set) + { + /* Request sent, copy received data back */ + + memcpy(data, iovar_buf+sizeof(struct bcmf_sdpcm_cdc_dcmd), len); + } + +exit_free_iovar: + // TODO free allocated buffer here +exit_sem_post: + sem_post(&priv->control_mutex); + return ret; +} \ No newline at end of file diff --git a/drivers/wireless/ieee80211/bcmf_sdpcm.h b/drivers/wireless/ieee80211/bcmf_sdpcm.h index 2f2844e651..537321e9fa 100644 --- a/drivers/wireless/ieee80211/bcmf_sdpcm.h +++ b/drivers/wireless/ieee80211/bcmf_sdpcm.h @@ -2,34 +2,13 @@ #define __DRIVERS_WIRELESS_IEEE80211_BCMF_SDPCM_H #include "bcmf_driver.h" -#include - -struct bcmf_sdpcm_header { - uint16_t frametag[2]; - uint8_t sequence; - uint8_t channel_flags; - uint8_t next_length; - uint8_t data_offset; - uint8_t flow_control; - uint8_t credit; - uint16_t padding; -}; - -struct bcmf_sdpcm_cdc_dcmd { - struct bcmf_sdpcm_header header; - uint32_t cmd; /* dongle command value */ - uint32_t len; /* lower 16: output buflen; - * upper 16: input buflen (excludes header) */ - uint32_t flags; /* flag defns given below */ - uint32_t status; /* status code returned from the device */ -}; - -int bcmf_sdpcm_process_header(FAR struct bcmf_dev_s *priv, - struct bcmf_sdpcm_header *header); int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv); -int bcmf_sdpcm_iovar_data_get(FAR struct bcmf_dev_s *priv, char *name, - void *data, unsigned int len); +int bcmf_sdpcm_sendframe(FAR struct bcmf_dev_s *priv); + +int bcmf_sdpcm_iovar_request(FAR struct bcmf_dev_s *priv, + uint32_t ifidx, bool set, char *name, + char *data, uint32_t len); #endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_SDPCM_H */ \ No newline at end of file -- GitLab From 043452873274ba2dc8410f44eb45006648d32cb5 Mon Sep 17 00:00:00 2001 From: Simon Piriou Date: Sun, 16 Apr 2017 13:13:11 +0200 Subject: [PATCH 472/990] photon: request firmware version and MAC address --- drivers/wireless/ieee80211/bcmf_driver.h | 7 ++ drivers/wireless/ieee80211/bcmf_sdio.c | 27 +++-- drivers/wireless/ieee80211/bcmf_sdpcm.c | 127 ++++++++++++++++++++--- drivers/wireless/ieee80211/bcmf_sdpcm.h | 2 +- 4 files changed, 137 insertions(+), 26 deletions(-) diff --git a/drivers/wireless/ieee80211/bcmf_driver.h b/drivers/wireless/ieee80211/bcmf_driver.h index bf870bf9d6..0d6e664d2c 100644 --- a/drivers/wireless/ieee80211/bcmf_driver.h +++ b/drivers/wireless/ieee80211/bcmf_driver.h @@ -39,6 +39,12 @@ #include #include +#define BCMF_STATUS_BUS_UP (1<<0) /* Chip is flashed and running */ +#define BCMF_STATUS_READY (1<<1) /* Chip is ready to receive requests */ + +#define BCMF_STATUS_SLEEP (1<<2) /* Chip is in low power mode */ +#define BCMF_STATUS_WAIT_CONTROL (1<<3) /* Waiting for control response */ + /* This structure contains the unique state of the Broadcom FullMAC driver */ struct bcmf_dev_s @@ -66,6 +72,7 @@ struct bcmf_dev_s sem_t control_mutex; /* Cannot handle multiple control requests */ sem_t control_timeout; /* Semaphore to wait for control frame rsp */ uint16_t control_reqid; /* Current control request id */ + uint8_t *control_rxframe; /* Received control frame response */ // FIXME use mutex instead of semaphore sem_t tx_queue_mutex; /* Lock for transmit queue */ diff --git a/drivers/wireless/ieee80211/bcmf_sdio.c b/drivers/wireless/ieee80211/bcmf_sdio.c index 96778a7d7c..9f7a125915 100644 --- a/drivers/wireless/ieee80211/bcmf_sdio.c +++ b/drivers/wireless/ieee80211/bcmf_sdio.c @@ -129,10 +129,6 @@ int bcmf_sdio_bus_sleep(FAR struct bcmf_dev_s *priv, bool sleep) int loops; uint8_t value; - _info("request %s currently %s\n", - (sleep ? "SLEEP" : "WAKE"), - (priv->sleeping ? "SLEEP" : "WAKE")); - if (priv->sleeping == sleep) { return OK; @@ -681,13 +677,28 @@ int bcmf_sdio_initialize(int minor, FAR struct sdio_dev_s *dev) TODO Create a wlan device name and register network driver here */ // TODO remove: basic iovar test - up_mdelay(2000); + up_mdelay(1000); char fw_version[64]; + uint32_t out_len = sizeof(fw_version); ret = bcmf_sdpcm_iovar_request(priv, CHIP_STA_INTERFACE, false, IOVAR_STR_VERSION, fw_version, - sizeof(fw_version)); - _info("fw version %d\n", ret); + &out_len); + if (ret == OK) + { + _info("fw version %d <%s>\n", out_len, fw_version); + } + up_mdelay(100); + out_len = 6; + ret = bcmf_sdpcm_iovar_request(priv, CHIP_STA_INTERFACE, false, + IOVAR_STR_CUR_ETHERADDR, fw_version, + &out_len); + if (ret == OK) + { + _info("MAC address %d %02X:%02X:%02X:%02X:%02X:%02X\n", out_len, + fw_version[0], fw_version[1], fw_version[2], + fw_version[3], fw_version[4], fw_version[5]); + } return OK; @@ -799,7 +810,7 @@ int bcmf_sdio_thread(int argc, char **argv) if (ret == -ENODATA) { /* All frames processed */ - _info("All frames processed\n"); + priv->intstatus &= ~I_HMB_FRAME_IND; } } diff --git a/drivers/wireless/ieee80211/bcmf_sdpcm.c b/drivers/wireless/ieee80211/bcmf_sdpcm.c index 39d2f29e09..1336efef97 100644 --- a/drivers/wireless/ieee80211/bcmf_sdpcm.c +++ b/drivers/wireless/ieee80211/bcmf_sdpcm.c @@ -115,13 +115,19 @@ struct bcmf_sdpcm_cdc_header { uint32_t status; /* status code returned from the device */ }; +struct bcmf_sdpcm_cdc_dcmd { + struct bcmf_sdpcm_header header; + struct bcmf_sdpcm_cdc_header cdc_header; + uint8_t data[0]; +}; + struct bcmf_sdpcm_frame { dq_entry_t list_entry; struct bcmf_sdpcm_header header; uint8_t data[0]; }; -struct bcmf_sdpcm_cdc_dcmd { +struct bcmf_sdpcm_cdc_frame { dq_entry_t list_entry; struct bcmf_sdpcm_header header; struct bcmf_sdpcm_cdc_header cdc_header; @@ -230,7 +236,7 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv) if (((~len & 0xffff) ^ checksum) || len < sizeof(struct bcmf_sdpcm_header)) { _err("Invalid header checksum or len %x %x\n", len, checksum); - ret = -EIO; + ret = -EINVAL; goto exit_abort; } @@ -243,12 +249,13 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv) } /* Read remaining frame data */ + // TODO allocate buffer ret = bcmf_transfer_bytes(priv, false, 2, 0, (uint8_t*)header+4, len - 4); if (ret != OK) { ret = -EIO; - goto exit_abort; + goto exit_free_abort; } _info("Receive frame\n"); @@ -260,10 +267,83 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv) if (ret != OK) { _err("Error while processing header %d\n", ret); + ret = -EINVAL; + goto exit_free_frame; } + /* Process received frame content */ + + switch (header->channel & 0x0f) + { + case SDPCM_CONTROL_CHANNEL: + _info("Control message\n"); + + /* Check frame */ + + if (header->size < sizeof(struct bcmf_sdpcm_header) + + sizeof(struct bcmf_sdpcm_cdc_header)) + { + _err("Control frame too small\n"); + ret = -EINVAL; + goto exit_free_frame; + + } + + struct bcmf_sdpcm_cdc_header *cdc_header = + (struct bcmf_sdpcm_cdc_header*)&header[1]; + + if (header->size < sizeof(struct bcmf_sdpcm_header) + + sizeof(struct bcmf_sdpcm_cdc_header) + + cdc_header->len || + cdc_header->len > 512 - + sizeof(struct bcmf_sdpcm_header) - + sizeof(struct bcmf_sdpcm_cdc_header)) + { + _err("Invalid control frame size\n"); + ret = -EINVAL; + goto exit_free_frame; + } + + // TODO check interface ? + + if (cdc_header->flags >> CDC_DCMD_ID_SHIFT == priv->control_reqid) + { + /* Expected frame received, send it back to user */ + + priv->control_rxframe = (uint8_t*)header; + + sem_post(&priv->control_timeout); + return OK; + } + else + { + _info("Got unexpected control frame\n"); + ret = -EINVAL; + goto exit_free_frame; + } + break; + + case SDPCM_EVENT_CHANNEL: + _info("Event message\n"); + ret = OK; + break; + + case SDPCM_DATA_CHANNEL: + _info("Data message\n"); + ret = OK; + break; + + default: + _err("Got unexpected message type %d\n", header->channel); + ret = OK; + } + +exit_free_frame: + // TODO free frame buffer return ret; +exit_free_abort: + // TODO free frame buffer exit_abort: bcmf_sdpcm_rxfail(priv, false); return ret; @@ -358,8 +438,8 @@ uint8_t* bcmf_sdpcm_allocate_iovar(FAR struct bcmf_dev_s *priv, char *name, } // FIXME allocate buffer and use max_size instead of 512 - if (data_len > 512-sizeof(struct bcmf_sdpcm_cdc_dcmd) || - (data_len + name_len) > 512-sizeof(struct bcmf_sdpcm_cdc_dcmd)) + if (data_len > 512-sizeof(struct bcmf_sdpcm_cdc_frame) || + (data_len + name_len) > 512-sizeof(struct bcmf_sdpcm_cdc_frame)) { *len = 0; return NULL; @@ -369,11 +449,11 @@ uint8_t* bcmf_sdpcm_allocate_iovar(FAR struct bcmf_dev_s *priv, char *name, /* Copy name string and data */ - memcpy(tmp_buffer2+sizeof(struct bcmf_sdpcm_cdc_dcmd), name, name_len); - memcpy(tmp_buffer2+sizeof(struct bcmf_sdpcm_cdc_dcmd)+name_len, + memcpy(tmp_buffer2+sizeof(struct bcmf_sdpcm_cdc_frame), name, name_len); + memcpy(tmp_buffer2+sizeof(struct bcmf_sdpcm_cdc_frame)+name_len, data, data_len); - *len = sizeof(struct bcmf_sdpcm_cdc_dcmd)+name_len+data_len; + *len = sizeof(struct bcmf_sdpcm_cdc_frame)+name_len+data_len; return tmp_buffer2; } @@ -429,15 +509,15 @@ int bcmf_sdpcm_queue_frame(FAR struct bcmf_dev_s *priv, uint8_t channel, return OK; } -int bcmf_sdpcm_send_dcmd(FAR struct bcmf_dev_s *priv, uint32_t cmd, +int bcmf_sdpcm_send_cdc_frame(FAR struct bcmf_dev_s *priv, uint32_t cmd, int ifidx, bool set, uint8_t *data, uint32_t len) { - struct bcmf_sdpcm_cdc_dcmd *msg = (struct bcmf_sdpcm_cdc_dcmd*)data; + struct bcmf_sdpcm_cdc_frame *msg = (struct bcmf_sdpcm_cdc_frame*)data; /* Setup cdc_dcmd header */ msg->cdc_header.cmd = cmd; - msg->cdc_header.len = len-sizeof(struct bcmf_sdpcm_cdc_dcmd); + msg->cdc_header.len = len-sizeof(struct bcmf_sdpcm_cdc_frame); msg->cdc_header.status = 0; msg->cdc_header.flags = ++priv->control_reqid << CDC_DCMD_ID_SHIFT; msg->cdc_header.flags |= ifidx << CDC_DCMD_IF_SHIFT; @@ -454,11 +534,13 @@ int bcmf_sdpcm_send_dcmd(FAR struct bcmf_dev_s *priv, uint32_t cmd, int bcmf_sdpcm_iovar_request(FAR struct bcmf_dev_s *priv, uint32_t ifidx, bool set, char *name, - char *data, uint32_t len) + char *data, uint32_t *len) { int ret; uint8_t *iovar_buf; - uint32_t iovar_buf_len = len; + uint32_t iovar_buf_len = *len; + + *len = 0; /* Take device control mutex */ @@ -477,9 +559,9 @@ int bcmf_sdpcm_iovar_request(FAR struct bcmf_dev_s *priv, goto exit_sem_post; } - /* Send control frame */ + /* Send control frame. Frame buffer is freed when sent */ - ret = bcmf_sdpcm_send_dcmd(priv, set ? WLC_SET_VAR : WLC_GET_VAR, + ret = bcmf_sdpcm_send_cdc_frame(priv, set ? WLC_SET_VAR : WLC_GET_VAR, ifidx, set, iovar_buf, iovar_buf_len); if (ret != OK) { @@ -488,20 +570,31 @@ int bcmf_sdpcm_iovar_request(FAR struct bcmf_dev_s *priv, /* Wait for response */ + priv->control_rxframe = NULL; + ret = bcmf_sem_wait(&priv->control_timeout, SDPCM_CONTROL_TIMEOUT_MS); if (ret != OK) { _err("Error while waiting for control response %d\n", ret); - goto exit_free_iovar; + goto exit_sem_post; } if (!set) { /* Request sent, copy received data back */ - memcpy(data, iovar_buf+sizeof(struct bcmf_sdpcm_cdc_dcmd), len); + struct bcmf_sdpcm_cdc_dcmd *rxframe = + (struct bcmf_sdpcm_cdc_dcmd*)priv->control_rxframe; + + memcpy(data, rxframe->data, rxframe->cdc_header.len); + + *len = rxframe->cdc_header.len; } + // TODO free rxframe buffer */ + + goto exit_sem_post; + exit_free_iovar: // TODO free allocated buffer here exit_sem_post: diff --git a/drivers/wireless/ieee80211/bcmf_sdpcm.h b/drivers/wireless/ieee80211/bcmf_sdpcm.h index 537321e9fa..324970f2aa 100644 --- a/drivers/wireless/ieee80211/bcmf_sdpcm.h +++ b/drivers/wireless/ieee80211/bcmf_sdpcm.h @@ -9,6 +9,6 @@ int bcmf_sdpcm_sendframe(FAR struct bcmf_dev_s *priv); int bcmf_sdpcm_iovar_request(FAR struct bcmf_dev_s *priv, uint32_t ifidx, bool set, char *name, - char *data, uint32_t len); + char *data, uint32_t *len); #endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_SDPCM_H */ \ No newline at end of file -- GitLab From bbeadc2274e4a2d6717b414e0d418ca14d888898 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 16 Apr 2017 07:50:11 -0600 Subject: [PATCH 473/990] 6loWPAN network driver: Still only a skeleton but has some added though experimentation. --- wireless/ieee802154/mac802154_netdev.c | 120 ++++++++++++++++++++----- 1 file changed, 96 insertions(+), 24 deletions(-) diff --git a/wireless/ieee802154/mac802154_netdev.c b/wireless/ieee802154/mac802154_netdev.c index d27daf3ef3..8768c3ee74 100644 --- a/wireless/ieee802154/mac802154_netdev.c +++ b/wireless/ieee802154/mac802154_netdev.c @@ -130,16 +130,26 @@ struct macnet_driver_s /* This holds the information visible to the NuttX network */ struct ieee802154_driver_s md_dev; /* Interface understood by the network */ - struct macnet_callback_s md_cb; /* Callback information */ - MACHANDLE md_mac; /* Contained MAC interface */ /* For internal use by this driver */ - bool md_bifup; /* true:ifup false:ifdown */ - WDOG_ID md_txpoll; /* TX poll timer */ - WDOG_ID md_txtimeout; /* TX timeout timer */ - struct work_s md_irqwork; /* For deferring interupt work to the work queue */ - struct work_s md_pollwork; /* For deferring poll work to the work queue */ + struct macnet_callback_s md_cb; /* Callback information */ + MACHANDLE md_mac; /* Contained MAC interface */ + bool md_bifup; /* true:ifup false:ifdown */ + WDOG_ID md_txpoll; /* TX poll timer */ + WDOG_ID md_txtimeout; /* TX timeout timer */ + struct work_s md_irqwork; /* Defer interupt work to the work queue */ + struct work_s md_pollwork; /* Defer poll work to the work queue */ + + /* This is queue of outgoing, ready-to-send frames that will be sent + * indirectly. This list should only be used by a MAC acting as a + * coordinator. These transactions will stay here until the data is + * extracted by the destination device sending a Data Request MAC + * command or if too much time passes. + */ + + FAR volatile struct iob_s *md_head; + FAR volatile struct iob_s *md_tail; }; /**************************************************************************** @@ -583,8 +593,9 @@ static void macnet_ind_syncloss(MACHANDLE mac, int reason) * Name: macnet_transmit * * Description: - * Start hardware transmission. Called either from the txdone interrupt - * handling or from watchdog based polling. + * This function is called from the lower MAC layer when thre radio device + * is ready to accept another outgoing frame. It removes one of the + * previously queued fram IOBs and provides that to the MAC layer. * * Parameters: * priv - Reference to the driver state structure @@ -593,25 +604,28 @@ static void macnet_ind_syncloss(MACHANDLE mac, int reason) * OK on success; a negated errno on failure * * Assumptions: - * May or may not be called from an interrupt handler. In either case, - * the network is locked. + * May or may not be called from an interrupt handler. * ****************************************************************************/ static int macnet_transmit(FAR struct macnet_driver_s *priv) { - /* Verify that the hardware is ready to send another packet. If we get - * here, then we are committed to sending a packet; Higher level logic - * must have assured that there is no transmission in progress. + /* Cancel the TX timeout watchdog + * + * REVISIT: Is there not a race condition here? Might the TX timeout + * already be queued?. */ + wd_cancel(priv->md_txtimeout); + /* Increment statistics */ NETDEV_TXPACKETS(priv->md_dev); - /* Send the packet: address=priv->md_dev.d_buf, length=priv->md_dev.d_len */ - - /* Enable Tx interrupts */ + /* Provide the pre-formatted packet to the radio device (via the lower MAC + * layer). + */ +#warning Missing logic /* Setup the TX timeout watchdog (perhaps restarting the timer) */ @@ -620,6 +634,57 @@ static int macnet_transmit(FAR struct macnet_driver_s *priv) return OK; } +/**************************************************************************** + * Name: macnet_txqueue + * + * Description: + * Add new frames from the network to the list of outgoing frames. + * + * Parameters: + * dev - Reference to the NuttX driver state structure + * + * Returned Value: + * OK on success; a negated errno on failure + * + * Assumptions: + * May or may not be called from an interrupt handler. In either case, + * the network is locked. + * + ****************************************************************************/ + +static void macnet_txqueue(FAR struct net_driver_s *dev) +{ + /* Check if there is a new list of outgoing frames from the network. */ + + if (priv->lo_ieee.i_framelist != NULL) + { + /* Yes.. Remove the frame list from the driver structure */ + + iob = priv->lo_ieee.i_framelist; + priv->lo_ieee.i_framelist = NULL; + + /* Append the new list to the tail of the queue of outgoing frames. */ + + if (priv->md_tail == NULL) + { + priv->md_head = iob; + } + else + { + priv->md_tail->io_flink = iob; + } + + /* Find the new tail of the outgoing frame queue */ + + for (priv->md_tail = iob, iob = iob->io_flink; + iob != NULL; + priv->md_tail = iob, iob = iob->io_flink); + + /* Notify the radio driver that there is data available */ +#warning Missing logic + } +} + /**************************************************************************** * Name: macnet_txpoll * @@ -646,17 +711,21 @@ static int macnet_transmit(FAR struct macnet_driver_s *priv) static int macnet_txpoll(FAR struct net_driver_s *dev) { - FAR struct macnet_driver_s *priv = (FAR struct macnet_driver_s *)dev->d_private; + FAR struct macnet_driver_s *priv = + (FAR struct macnet_driver_s *)dev->d_private; + FAR struct iob_s *iob; /* If the polling resulted in data that should be sent out, the field * i_framelist will set to a new, outgoing list of frames. */ - if (priv->md_dev.i_framelist != NULL) + if (priv->lo_ieee.i_framelist != NULL) { - /* And send the packet */ + /* Remove the frame list from the driver structure and append it to + * the tail of the ist of outgoing frames. + */ - macnet_transmit(priv); + macnet_txqueue(priv); } /* If zero is returned, the polling will continue until all connections have @@ -711,14 +780,17 @@ static void macnet_receive(FAR struct macnet_driver_s *priv) sixlowpan_input(&priv->md_dev); /* If the above function invocation resulted in data that should be sent - * out, the field i_framelist will set to a new, outgoing list of frames. + * out, the field i_framelist will have been set to a new, outgoing list + * of frames. */ if (priv->md_dev.i_framelist != NULL) { - /* And send the packet */ + /* Remove the frame list from the driver structure and append it to + * the tail of the ist of outgoing frames. + */ - macnet_transmit(priv); + macnet_txqueue(priv); } } -- GitLab From 57dd302227c2c700f78caa99143d5fbf1e303f13 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 16 Apr 2017 10:28:31 -0600 Subject: [PATCH 474/990] Fix typos in comments and debug statement. --- net/sixlowpan/sixlowpan_hc06.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/net/sixlowpan/sixlowpan_hc06.c b/net/sixlowpan/sixlowpan_hc06.c index d449f82936..093d3ddc24 100644 --- a/net/sixlowpan/sixlowpan_hc06.c +++ b/net/sixlowpan/sixlowpan_hc06.c @@ -223,7 +223,7 @@ static FAR struct sixlowpan_addrcontext_s * } /**************************************************************************** - * Name: uncompress_addr + * Name: compress_addr_64 * * Description: * Uncompress addresses based on a prefix and a postfix with zeroes in @@ -1019,7 +1019,7 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, * * DAM 00: 128 bits * DAM 01: 48 bits FFXX::00XX:XXXX:XXXX - * DAM 0: 32 bits FFXX::00XX:XXXX + * DAM 10: 32 bits FFXX::00XX:XXXX * DAM 11: 8 bits FF02::00XX */ @@ -1049,7 +1049,7 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, if (addrcontext == NULL) { - ninfo("ERROR: Address context not found\n"); + nerr("ERROR: Address context not found\n"); return; } -- GitLab From 41f3f1ced7f3cd7cb7509cdbf95fcc7bc30f3575 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 16 Apr 2017 12:18:42 -0600 Subject: [PATCH 475/990] 6loWPAN: Correct ordering of headers. fragmentation header was coming out before FCF. --- include/nuttx/net/sixlowpan.h | 18 ++-- net/sixlowpan/README.txt | 45 ++++++---- net/sixlowpan/sixlowpan_framelist.c | 44 ++++++---- net/sixlowpan/sixlowpan_hc06.c | 17 ++-- net/sixlowpan/sixlowpan_hc1.c | 33 +++---- net/sixlowpan/sixlowpan_input.c | 128 ++++++++++++++++++---------- net/sixlowpan/sixlowpan_internal.h | 29 ++++--- 7 files changed, 186 insertions(+), 128 deletions(-) diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index e2f3eaf1f7..eb3a4580eb 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -160,14 +160,22 @@ /* 6lowpan dispatches */ -#define SIXLOWPAN_DISPATCH_IPV6 0x41 /* 01000001 = 65 */ -#define SIXLOWPAN_DISPATCH_HC1 0x42 /* 01000010 = 66 */ +#define SIXLOWPAN_DISPATCH_NALP 0x00 /* 00xxxxxx Not a LoWPAN packet */ +#define SIXLOWPAN_DISPATCH_NALP_MASK 0xc0 /* 11000000 */ -#define SIXLOWPAN_DISPATCH_IPHC 0x60 /* 011xxxxx */ +#define SIXLOWPAN_DISPATCH_IPV6 0x41 /* 01000001 Uncompressed IPv6 addresses */ +#define SIXLOWPAN_DISPATCH_HC1 0x42 /* 01000010 HC1 Compressed IPv6 header */ +#define SIXLOWPAN_DISPATCH_BC0 0x50 /* 01010000 BC0 Broadcast header */ +#define SIXLOWPAN_DISPATCH_ESC 0x7f /* 01111111 Additional Dispatch octet follows */ + +#define SIXLOWPAN_DISPATCH_IPHC 0x60 /* 011xxxxx IP Header Compression (IPHC)*/ #define SIXLOWPAN_DISPATCH_IPHC_MASK 0xe0 /* 11100000 */ -#define SIXLOWPAN_DISPATCH_FRAG1 0xc0 /* 11000xxx */ -#define SIXLOWPAN_DISPATCH_FRAGN 0xe0 /* 11100xxx */ +#define SIXLOWPAN_DISPATCH_MESH 0x80 /* 10xxxxxx Mesh routing header */ +#define SIXLOWPAN_DISPATCH_MESH_MASK 0xc0 /* 11000000 */ + +#define SIXLOWPAN_DISPATCH_FRAG1 0xc0 /* 11000xxx Fragmentation header (ï¬rst) */ +#define SIXLOWPAN_DISPATCH_FRAGN 0xe0 /* 11100xxx Fragmentation header (subsequent) */ #define SIXLOWPAN_DISPATCH_FRAG_MASK 0xf8 /* 11111000 */ /* HC1 encoding */ diff --git a/net/sixlowpan/README.txt b/net/sixlowpan/README.txt index 643735dd86..e325533474 100644 --- a/net/sixlowpan/README.txt +++ b/net/sixlowpan/README.txt @@ -32,10 +32,10 @@ Optimal 6loWPAN Configuration Fragmentation Headers --------------------- -A fragment header is placed at the beginning of the outgoing packet when the -payload is too large to fit in a single IEEE 802.15.4 frame. The fragment -header contains three fields: Datagram size, datagram tag and datagram -offset. +A fragment header is placed at the beginning of the outgoing packet just +after the FCF when the payload is too large to fit in a single IEEE 802.15.4 +frame. The fragment header contains three fields: Datagram size, datagram tag +and datagram offset. 1. Datagram size describes the total (un-fragmented) payload. 2. Datagram tag identifies the set of fragments and is used to match @@ -47,25 +47,36 @@ The length of the fragment header length is four bytes for the first header (FRAG1) and five bytes for all subsequent headers (FRAGN). For example, this is a HC1 compressed first frame of a packet - c50e 000b ### 4-byte FRAG1 header - 01 08 01 0000 3412 ### 7-byte FCF header - 42 ### SIXLOWPAN_DISPATCH_HC1 - fb ### RIME_HC1_HC_UDP_HC1_ENCODING - e0 ### RIME_HC1_HC_UDP_UDP_ENCODING - 00 ### RIME_HC1_HC_UDP_TTL - 10 ### RIME_HC1_HC_UDP_PORTS - 0000 ### RIME_HC1_HC_UDP_CHKSUM - 4f4e452064617920 48656e6e792d7065 6e6e792077617320 7069636b696e6720 ### 80 byte payload + 01 08 01 0000 3412 ### 7-byte FCF header + c50e 000b ### 4-byte FRAG1 header + 42 ### SIXLOWPAN_DISPATCH_HC1 + fb ### RIME_HC1_HC_UDP_HC1_ENCODING + e0 ### RIME_HC1_HC_UDP_UDP_ENCODING + 00 ### RIME_HC1_HC_UDP_TTL + 10 ### RIME_HC1_HC_UDP_PORTS + 0000 ### RIME_HC1_HC_UDP_CHKSUM + + 80 byte Payload follows: + 4f4e452064617920 48656e6e792d7065 6e6e792077617320 7069636b696e6720 757020636f726e20 696e207468652063 6f726e7961726420 7768656e2d2d7768 61636b212d2d736f 6d657468696e6720 g This is the second frame of the same transfer: - e50e 000b 0a ### 5 byte FRAGN header - 01 08 01 0000 3412 ### 7-byte FCF header - 6869742068657220 75706f6e20746865 20686561642e2027 476f6f646e657373 ### 88 byte payload + 01 08 01 0000 3412 ### 7-byte FCF header + e50e 000b 0a ### 5 byte FRAGN header + 42 ### SIXLOWPAN_DISPATCH_HC1 + fb ### RIME_HC1_HC_UDP_HC1_ENCODING + e0 ### RIME_HC1_HC_UDP_UDP_ENCODING + 00 ### RIME_HC1_HC_UDP_TTL + 10 ### RIME_HC1_HC_UDP_PORTS + 0000 ### RIME_HC1_HC_UDP_CHKSUM + + 80 byte Payload follows: + 6869742068657220 75706f6e20746865 20686561642e2027 476f6f646e657373 2067726163696f75 73206d6521272073 6169642048656e6e 792d70656e6e793b - 202774686520736b 79277320612d676f 696e6720746f2066 + 202774686520736b 79277320612d676f + The payload length is encoded in the LS 11-bits of the first 16-bit value: In this example the payload size is 0x050e or 1,294. The tag is 0x000b. In diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c index d8b751e8a7..23969c09f3 100644 --- a/net/sixlowpan/sixlowpan_framelist.c +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -330,6 +330,8 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, FAR struct iob_s *qtail; FAR uint8_t *frame1; + FAR uint8_t *fragptr; + uint16_t frag1_hdrlen; int verify; /* The outbound IPv6 packet is too large to fit into a single 15.4 @@ -352,7 +354,9 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, * beginning of the frame. */ - memmove(fptr + SIXLOWPAN_FRAG1_HDR_LEN, fptr, g_frame_hdrlen); + fragptr = fptr + framer_hdrlen; + memmove(fragptr + SIXLOWPAN_FRAG1_HDR_LEN, fragptr, + g_frame_hdrlen - framer_hdrlen); /* Setup up the fragment header. * @@ -370,9 +374,9 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, */ pktlen = buflen + g_uncomp_hdrlen; - PUTINT16(fptr, RIME_FRAG_DISPATCH_SIZE, + PUTINT16(fragptr, RIME_FRAG_DISPATCH_SIZE, ((SIXLOWPAN_DISPATCH_FRAG1 << 8) | pktlen)); - PUTINT16(fptr, RIME_FRAG_TAG, ieee->i_dgramtag); + PUTINT16(fragptr, RIME_FRAG_TAG, ieee->i_dgramtag); g_frame_hdrlen += SIXLOWPAN_FRAG1_HDR_LEN; @@ -385,8 +389,8 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, /* Set outlen to what we already sent from the IP payload */ - iob->io_len = paysize + g_frame_hdrlen; - outlen = paysize; + iob->io_len = paysize + g_frame_hdrlen; + outlen = paysize; ninfo("First fragment: length %d, tag %d\n", paysize, ieee->i_dgramtag); @@ -404,7 +408,9 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, /* Create following fragments */ - frame1 = iob->io_data; + frame1 = iob->io_data; + frag1_hdrlen = g_frame_hdrlen; + while (outlen < buflen) { uint16_t fragn_hdrlen; @@ -424,21 +430,27 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, iob->io_pktlen = 0; fptr = iob->io_data; - /* Copy the frame header from first frame, into the correct - * location after the FRAGN header. + /* Copy the frame header at the beginning of the frame. */ + + memcpy(fptr, frame1, framer_hdrlen); + + /* Move HC1/HC06/IPv6 header the frame header from first + * frame, into the correct location after the FRAGN header + * of subsequent frames. */ - memmove(fptr + SIXLOWPAN_FRAGN_HDR_LEN, - frame1 + SIXLOWPAN_FRAG1_HDR_LEN, - framer_hdrlen); - fragn_hdrlen = framer_hdrlen; + fragptr = fptr + framer_hdrlen; + memcpy(fragptr + SIXLOWPAN_FRAGN_HDR_LEN, + frame1 + framer_hdrlen + SIXLOWPAN_FRAG1_HDR_LEN, + frag1_hdrlen - framer_hdrlen); + fragn_hdrlen = frag1_hdrlen - SIXLOWPAN_FRAG1_HDR_LEN; - /* Setup up the FRAGN header at the beginning of the frame */ + /* Setup up the FRAGN header after the frame header. */ - PUTINT16(fptr, RIME_FRAG_DISPATCH_SIZE, + PUTINT16(fragptr, RIME_FRAG_DISPATCH_SIZE, ((SIXLOWPAN_DISPATCH_FRAGN << 8) | pktlen)); - PUTINT16(fptr, RIME_FRAG_TAG, ieee->i_dgramtag); - fptr[RIME_FRAG_OFFSET] = outlen >> 3; + PUTINT16(fragptr, RIME_FRAG_TAG, ieee->i_dgramtag); + fragptr[RIME_FRAG_OFFSET] = outlen >> 3; fragn_hdrlen += SIXLOWPAN_FRAGN_HDR_LEN; diff --git a/net/sixlowpan/sixlowpan_hc06.c b/net/sixlowpan/sixlowpan_hc06.c index 093d3ddc24..8a4999579e 100644 --- a/net/sixlowpan/sixlowpan_hc06.c +++ b/net/sixlowpan/sixlowpan_hc06.c @@ -68,13 +68,10 @@ #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 - /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ -#define IPv6BUF(ieee) \ - ((FAR struct ipv6_hdr_s *)((ieee)->i_dev.d_buf)) #define UDPIPv6BUF(ieee) \ ((FAR struct udp_hdr_s *)&((ieee)->i_dev.d_buf[IPv6_HDRLEN])) @@ -835,23 +832,23 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, * appropriate values * * Input Parmeters: - * ieee - A reference to the IEE802.15.4 network device state * iplen - Equal to 0 if the packet is not a fragment (IP length is then * inferred from the L2 length), non 0 if the packet is a first * fragment. * iob - Pointer to the IOB containing the received frame. * fptr - Pointer to frame to be compressed. + * bptr - Output goes here. Normally this is a known offset into d_buf, + * may be redirected to a "bitbucket" on the case of FRAGN frames. * * Returned Value: * None * ****************************************************************************/ -void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, - uint16_t iplen, FAR struct iob_s *iob, - FAR uint8_t *fptr) +void sixlowpan_uncompresshdr_hc06(uint16_t iplen, FAR struct iob_s *iob, + FAR uint8_t *fptr, FAR uint8_t *bptr) { - FAR struct ipv6_hdr_s *ipv6 = IPv6BUF(ieee); + FAR struct ipv6_hdr_s *ipv6 = (FAR struct ipv6_hdr_s *)bptr; FAR uint8_t *iphc; uint8_t iphc0; uint8_t iphc1; @@ -1071,7 +1068,7 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, if ((iphc0 & SIXLOWPAN_IPHC_NH) != 0) { - FAR struct udp_hdr_s *udp = UDPIPv6BUF(ieee); + FAR struct udp_hdr_s *udp = (FAR struct udp_hdr_s *)(bptr + IPv6_HDRLEN); /* The next header is compressed, NHC is following */ @@ -1195,7 +1192,7 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, if (ipv6->proto == IP_PROTO_UDP) { - FAR struct udp_hdr_s *udp = UDPIPv6BUF(ieee); + FAR struct udp_hdr_s *udp = (FAR struct udp_hdr_s *)(bptr + IPv6_HDRLEN); memcpy(&udp->udplen, &ipv6->len[0], 2); } } diff --git a/net/sixlowpan/sixlowpan_hc1.c b/net/sixlowpan/sixlowpan_hc1.c index 9f657a12dc..313fc388ab 100644 --- a/net/sixlowpan/sixlowpan_hc1.c +++ b/net/sixlowpan/sixlowpan_hc1.c @@ -57,15 +57,6 @@ #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC1 -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/* Buffer access helpers */ - -#define IPv6BUF(dev) ((FAR struct ipv6_hdr_s *)((dev)->d_buf)) -#define UDPIPv6BUF(dev) ((FAR struct udp_hdr_s *)&(dev)->d_buf[IPv6_HDRLEN]) - /**************************************************************************** * Public Functions ****************************************************************************/ @@ -253,12 +244,13 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, * are set to the appropriate values * * Input Parameters: - * ieee - A reference to the IEE802.15.4 network device state - * iplen - Equal to 0 if the packet is not a fragment (IP length is then - * inferred from the L2 length), non 0 if the packet is a 1st - * fragment. - * iob - Pointer to the IOB containing the received frame. - * fptr - Pointer to frame to be uncompressed. + * iplen - Equal to 0 if the packet is not a fragment (IP length is then + * inferred from the L2 length), non 0 if the packet is a 1st + * fragment. + * iob - Pointer to the IOB containing the received frame. + * fptr - Pointer to frame to be uncompressed. + * bptr - Output goes here. Normally this is a known offset into d_buf, + * may be redirected to a "bitbucket" on the case of FRAGN frames. * * Returned Value: * Zero (OK) is returned on success, on failure a negater errno value is @@ -266,11 +258,10 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, * ****************************************************************************/ -int sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, - uint16_t iplen, FAR struct iob_s *iob, - FAR uint8_t *fptr) +int sixlowpan_uncompresshdr_hc1(uint16_t iplen, FAR struct iob_s *iob, + FAR uint8_t *fptr, FAR uint8_t *bptr) { - FAR struct ipv6_hdr_s *ipv6 = IPv6BUF(&ieee->i_dev); + FAR struct ipv6_hdr_s *ipv6 = (FAR struct ipv6_hdr_s *)bptr; FAR uint8_t *hc1 = fptr + g_frame_hdrlen; /* Format the IPv6 header in the device d_buf */ @@ -311,7 +302,7 @@ int sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, #if CONFIG_NET_UDP case SIXLOWPAN_HC1_NH_UDP: { - FAR struct udp_hdr_s *udp = UDPIPv6BUF(&ieee->i_dev); + FAR struct udp_hdr_s *udp = (FAR struct udp_hdr_s *)(bptr + IPv6_HDRLEN); FAR uint8_t *hcudp = fptr + g_frame_hdrlen; ipv6->proto = IP_PROTO_UDP; @@ -377,7 +368,7 @@ int sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, if (ipv6->proto == IP_PROTO_UDP) { - FAR struct udp_hdr_s *udp = UDPIPv6BUF(&ieee->i_dev); + FAR struct udp_hdr_s *udp = (FAR struct udp_hdr_s *)(bptr + IPv6_HDRLEN); memcpy(&udp->udplen, &ipv6->len[0], 2); } #endif diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index b19fa8ffba..119dd4dfd2 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -83,11 +83,48 @@ #define NET_6LOWPAN_TIMEOUT SEC2TICK(CONFIG_NET_6LOWPAN_MAXAGE) +/* This is the size of a buffer large enough to hold the largest uncompressed + * HC06 or HC1 headers. + */ + +#ifdef CONFIG_NET_TCP +/* The basic TCP header length is TCP_HDRLEN but could include up to 16 + * additional 32-bit words of optional data. + */ + +# define UNCOMP_MAXHDR (IPv6_HDRLEN + TCP_HDRLEN + 16*sizeof(uint32_t)) + +#elif defined(CONFIG_NET_UDP) +/* The UDP header length is always 8 bytes */ + +# define UNCOMP_MAXHDR (IPv6_HDRLEN + TCP_HDRLEN) + +#elif defined(CONFIG_NET_ICMPv6) +/* The ICMPv6 header length is a mere 4 bytes */ + +# define UNCOMP_MAXHDR (IPv6_HDRLEN + ICMPv6_HDRLEN) + +#else +/* No other header type is handled. */ + +# define UNCOMP_MAXHDR IPv6_HDRLEN +#endif + /* Buffer access helpers */ #define IPv6BUF(dev) ((FAR struct ipv6_hdr_s *)((dev)->d_buf)) #define TCPBUF(dev) ((FAR struct tcp_hdr_s *)&(dev)->d_buf[IPv6_HDRLEN]) +/**************************************************************************** + * Private Data + ****************************************************************************/ + +#ifdef CONFIG_NET_6LOWPAN_FRAG +/* This big buffer could be avoided with a little more effort */ + +static uint8_t g_bitbucket[UNCOMP_MAXHDR]; +#endif + /**************************************************************************** * Private Functions ****************************************************************************/ @@ -96,7 +133,7 @@ * Name: sixlowpan_recv_hdrlen * * Description: - * Get the length of the IEEE802.15.4 header on the received frame. + * Get the length of the IEEE802.15.4 FCF header on the received frame. * * Input Parameters: * ieee - The IEEE802.15.4 MAC network driver interface. @@ -112,26 +149,12 @@ int sixlowpan_recv_hdrlen(FAR const uint8_t *fptr) { - uint16_t hdrlen = 0; + uint16_t hdrlen; uint8_t addrmode; - uint8_t tmp; - - /* Check for a fragment header preceding the IEEE802.15.4 FCF */ - - tmp = *fptr & SIXLOWPAN_DISPATCH_FRAG_MASK; - if (tmp == SIXLOWPAN_DISPATCH_FRAG1) - { - hdrlen += SIXLOWPAN_FRAG1_HDR_LEN; - } - else if (tmp == SIXLOWPAN_DISPATCH_FRAGN) - { - hdrlen += SIXLOWPAN_FRAGN_HDR_LEN; - } /* Minimum header: 2 byte FCF + 1 byte sequence number */ - fptr += hdrlen; - hdrlen += 3; + hdrlen = 3; /* Account for destination address size */ @@ -207,18 +230,18 @@ int sixlowpan_recv_hdrlen(FAR const uint8_t *fptr) * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ * * Input Parameters: - * ieee - The IEEE802.15.4 MAC network driver interface. * fptr - Pointer to the beginning of the frame under construction + * bptr - Output goes here. Normally this is a known offset into d_buf, + * may be redirected to g_bitbucket on the case of FRAGN frames. * * Returned Value: * None * ****************************************************************************/ -static void sixlowpan_uncompress_ipv6hdr(FAR struct ieee802154_driver_s *ieee, - FAR uint8_t *fptr) +static void sixlowpan_uncompress_ipv6hdr(FAR uint8_t *fptr, FAR uint8_t *bptr) { - FAR struct ipv6_hdr_s *ipv6 = IPv6BUF(&ieee->i_dev); + FAR struct ipv6_hdr_s *ipv6 = (FAR struct ipv6_hdr_s *)bptr; uint16_t protosize; /* Put uncompressed IPv6 header in d_buf. */ @@ -310,6 +333,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, FAR struct iob_s *iob) { FAR uint8_t *fptr; /* Convenience pointer to beginning of the frame */ + FAR uint8_t *bptr; /* Used to redirect uncompressed header to the bitbucket */ FAR uint8_t *hc1; /* Convenience pointer to HC1 data */ uint16_t fragsize = 0; /* Size of the IP packet (read from fragment) */ uint16_t paysize; /* Size of the data payload */ @@ -318,6 +342,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, int hdrsize; /* Size of the IEEE802.15.4 header */ #ifdef CONFIG_NET_6LOWPAN_FRAG + FAR uint8_t *fragptr; /* Pointer to the fragmentation header */ bool isfrag = false; bool isfirstfrag = false; uint16_t fragtag = 0; /* Tag of the fragment */ @@ -349,7 +374,8 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, * already includes the fragementation header, if presetn. */ - switch ((GETINT16(fptr, RIME_FRAG_DISPATCH_SIZE) & 0xf800) >> 8) + fragptr = fptr + hdrsize; + switch ((GETINT16(fragptr, RIME_FRAG_DISPATCH_SIZE) & 0xf800) >> 8) { /* First fragment of new reassembly */ @@ -357,16 +383,17 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, { /* Set up for the reassembly */ - fragsize = GETINT16(fptr, RIME_FRAG_DISPATCH_SIZE) & 0x07ff; - fragtag = GETINT16(fptr, RIME_FRAG_TAG); + fragsize = GETINT16(fragptr, RIME_FRAG_DISPATCH_SIZE) & 0x07ff; + fragtag = GETINT16(fragptr, RIME_FRAG_TAG); + g_frame_hdrlen += SIXLOWPAN_FRAG1_HDR_LEN; ninfo("FRAG1: fragsize=%d fragtag=%d fragoffset=%d\n", fragsize, fragtag, fragoffset); /* Indicate the first fragment of the reassembly */ - isfirstfrag = true; - isfrag = true; + isfirstfrag = true; + isfrag = true; } break; @@ -374,9 +401,10 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, { /* Set offset, tag, size. Offset is in units of 8 bytes. */ - fragoffset = fptr[RIME_FRAG_OFFSET]; - fragtag = GETINT16(fptr, RIME_FRAG_TAG); - fragsize = GETINT16(fptr, RIME_FRAG_DISPATCH_SIZE) & 0x07ff; + fragoffset = fragptr[RIME_FRAG_OFFSET]; + fragtag = GETINT16(fragptr, RIME_FRAG_TAG); + fragsize = GETINT16(fragptr, RIME_FRAG_DISPATCH_SIZE) & 0x07ff; + g_frame_hdrlen += SIXLOWPAN_FRAGN_HDR_LEN; ninfo("FRAGN: fragsize=%d fragtag=%d fragoffset=%d\n", fragsize, fragtag, fragoffset); @@ -385,7 +413,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, /* Indicate that this frame is a another fragment for reassembly */ - isfrag = true; + isfrag = true; } break; @@ -397,6 +425,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, /* Check if we are currently reassembling a packet */ + bptr = ieee->i_dev.d_buf; if (ieee->i_accumlen > 0) { /* If reassembly timed out, cancel it */ @@ -470,12 +499,11 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, else { /* Looks good. We are currently processing a reassembling sequence - * and we recieved a valid FRAGN fragment. Skip the header - * compression dispatch logic. + * and we recieved a valid FRAGN fragment. Redirect the header + * uncompression to our bitbucket. */ - g_uncomp_hdrlen = ieee->i_boffset; - goto copypayload; + bptr = g_bitbucket; } } @@ -522,7 +550,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, if ((hc1[RIME_HC1_DISPATCH] & SIXLOWPAN_DISPATCH_IPHC_MASK) == SIXLOWPAN_DISPATCH_IPHC) { ninfo("IPHC Dispatch\n"); - sixlowpan_uncompresshdr_hc06(ieee, fragsize, iob, fptr); + sixlowpan_uncompresshdr_hc06(fragsize, iob, fptr, bptr); } else #endif /* CONFIG_NET_6LOWPAN_COMPRESSION_HC06 */ @@ -531,7 +559,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, if (hc1[RIME_HC1_DISPATCH] == SIXLOWPAN_DISPATCH_HC1) { ninfo("HC1 Dispatch\n"); - sixlowpan_uncompresshdr_hc1(ieee, fragsize, iob, fptr); + sixlowpan_uncompresshdr_hc1(fragsize, iob, fptr, bptr); } else #endif /* CONFIG_NET_6LOWPAN_COMPRESSION_HC1 */ @@ -539,30 +567,40 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, if (hc1[RIME_HC1_DISPATCH] == SIXLOWPAN_DISPATCH_IPV6) { ninfo("IPv6 Dispatch\n"); - sixlowpan_uncompress_ipv6hdr(ieee, fptr); + sixlowpan_uncompress_ipv6hdr(fptr, bptr); } else { /* Unknown or unsupported header */ - nwarn("WARNING unknown dispatch: %u\n", hc1[RIME_HC1_DISPATCH]); + nwarn("WARNING: Unknown dispatch: %u\n", hc1[RIME_HC1_DISPATCH]); return OK; } #ifdef CONFIG_NET_6LOWPAN_FRAG - /* Non-fragmented and FRAG1 frames pass through here. Remember the - * offset from the beginning of d_buf where be begin placing the data - * payload. - */ + /* Is this the first fragment is a sequence? */ + if (isfirstfrag) { + /* Yes.. Remember the offset from the beginning of d_buf where we + * begin placing the data payload. + */ + ieee->i_boffset = g_uncomp_hdrlen; } - /* We branch to here on all good FRAGN frames */ + /* No.. is this a subsequent fragment in the same sequence? */ + + else if (isfrag) + { + /* Yes, recover the offset from the beginning of the d_buf where + * we began placing payload data. + */ + + g_uncomp_hdrlen = ieee->i_boffset; + } -copypayload: #endif /* CONFIG_NET_6LOWPAN_FRAG */ /* Copy "payload" from the rime buffer to the IEEE802.15.4 MAC driver's @@ -584,7 +622,7 @@ copypayload: reqsize = g_uncomp_hdrlen + (fragoffset << 3) + paysize; if (reqsize > CONFIG_NET_6LOWPAN_MTU) { - ninfo("Required buffer size: %u+%u+%u=%u Available=%u\n", + nwarn("WARNING: Required buffer size: %u+%u+%u=%u Available=%u\n", g_uncomp_hdrlen, (fragoffset << 3), paysize, reqsize, CONFIG_NET_6LOWPAN_MTU); return -ENOMEM; diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index be29abc8ca..deede9d3b8 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -497,12 +497,13 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, * appropriate values * * Input Parmeters: - * ieee - A reference to the IEE802.15.4 network device state * iplen - Equal to 0 if the packet is not a fragment (IP length is then * inferred from the L2 length), non 0 if the packet is a first * fragment. * iob - Pointer to the IOB containing the received frame. - * fptr - Pointer to frame to be uncompressed. + * fptr - Pointer to frame to be compressed. + * bptr - Output goes here. Normally this is a known offset into d_buf, + * may be redirected to a "bitbucket" on the case of FRAGN frames. * * Returned Value: * None @@ -510,9 +511,8 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, ****************************************************************************/ #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 -void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, - uint16_t iplen, FAR struct iob_s *iob, - FAR uint8_t *fptr); +void sixlowpan_uncompresshdr_hc06(uint16_t iplen, FAR struct iob_s *iob, + FAR uint8_t *fptr, FAR uint8_t *bptr); #endif /**************************************************************************** @@ -530,7 +530,7 @@ void sixlowpan_uncompresshdr_hc06(FAR struct ieee802154_driver_s *ieee, * ipv6 - The IPv6 header to be compressed * destmac - L2 destination address, needed to compress the IP * destination field - * fptr - Pointer to frame to be compressed. + * fptr - Pointer to frame to be compressed. * * Returned Value: * None @@ -557,22 +557,23 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, * are set to the appropriate values * * Input Parameters: - * ieee - A reference to the IEE802.15.4 network device state * iplen - Equal to 0 if the packet is not a fragment (IP length is then - * inferred from the L2 length), non 0 if the packet is a first + * inferred from the L2 length), non 0 if the packet is a 1st * fragment. - * iob - Pointer to the IOB containing the received frame. - * fptr - Pointer to frame to be uncompressed. + * iob - Pointer to the IOB containing the received frame. + * fptr - Pointer to frame to be uncompressed. + * bptr - Output goes here. Normally this is a known offset into d_buf, + * may be redirected to a "bitbucket" on the case of FRAGN frames. * * Returned Value: - * None + * Zero (OK) is returned on success, on failure a negater errno value is + * returned. * ****************************************************************************/ #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC1 -int sixlowpan_uncompresshdr_hc1(FAR struct ieee802154_driver_s *ieee, - uint16_t ip_len, FAR struct iob_s *iob, - FAR uint8_t *fptr); +int sixlowpan_uncompresshdr_hc1(uint16_t iplen, FAR struct iob_s *iob, + FAR uint8_t *fptr, FAR uint8_t *bptr); #endif /**************************************************************************** -- GitLab From 0d9395588b4e609521883952eda3ba67f430c8f5 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 17 Apr 2017 08:50:03 -0600 Subject: [PATCH 476/990] STM32F0: Fix an error in clockconfig() --- arch/arm/src/stm32f0/stm32f0_clockconfig.c | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/arch/arm/src/stm32f0/stm32f0_clockconfig.c b/arch/arm/src/stm32f0/stm32f0_clockconfig.c index 4fa56e37d4..f8a8a59c9b 100644 --- a/arch/arm/src/stm32f0/stm32f0_clockconfig.c +++ b/arch/arm/src/stm32f0/stm32f0_clockconfig.c @@ -81,7 +81,7 @@ void stm32f0_clockconfig(void) regval &= (uint32_t) (~RCC_CFGR_SW_MASK); putreg32(regval, STM32F0_RCC_CFGR); - while ((getreg32(STM32F0_RCC_CFGR) & RCC_CFGR_SWS_MASK) != RCC_CFGR_SWS_HSI) ; + while ((getreg32(STM32F0_RCC_CFGR) & RCC_CFGR_SWS_MASK) != RCC_CFGR_SWS_HSI); } /* Disable the PLL */ @@ -89,12 +89,13 @@ void stm32f0_clockconfig(void) regval = getreg32(STM32F0_RCC_CR); regval &= (uint32_t)(~RCC_CR_PLLON); putreg32(regval, STM32F0_RCC_CR); - while ((getreg32(STM32F0_RCC_CR) & RCC_CR_PLLRDY) != 0) ; + while ((getreg32(STM32F0_RCC_CR) & RCC_CR_PLLRDY) != 0); /* Configure the PLL. Multiple x6 to get 48MHz */ regval = getreg32(STM32F0_RCC_CFGR); - regval &= (RCC_CFGR_PLLMUL_CLKx6 | ~RCC_CFGR_PLLMUL_MASK); + regval &= ~RCC_CFGR_PLLMUL_MASK; + regval |= RCC_CFGR_PLLMUL_CLKx6 putreg32(regval, STM32F0_RCC_CFGR); /* Enable the PLL */ @@ -102,12 +103,12 @@ void stm32f0_clockconfig(void) regval = getreg32(STM32F0_RCC_CR); regval |= RCC_CR_PLLON; putreg32(regval, STM32F0_RCC_CR); - while ((getreg32(STM32F0_RCC_CR) & RCC_CR_PLLRDY) == 0) ; + while ((getreg32(STM32F0_RCC_CR) & RCC_CR_PLLRDY) == 0); /* Configure to use the PLL */ regval = getreg32(STM32F0_RCC_CFGR); - regval |= (uint32_t) (RCC_CFGR_SW_PLL); + regval |= (uint32_t)(RCC_CFGR_SW_PLL); putreg32(regval, STM32F0_RCC_CFGR); - while ((getreg32(STM32F0_RCC_CFGR) & RCC_CFGR_SW_MASK) != RCC_CFGR_SW_PLL) ; + while ((getreg32(STM32F0_RCC_CFGR) & RCC_CFGR_SW_MASK) != RCC_CFGR_SW_PLL); } -- GitLab From 55faedb40dd053146a5285c2f0ebe4b9a022bafe Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 17 Apr 2017 08:57:00 -0600 Subject: [PATCH 477/990] STM32F0: Ooops Missing semicolon --- arch/arm/src/stm32f0/stm32f0_clockconfig.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/arch/arm/src/stm32f0/stm32f0_clockconfig.c b/arch/arm/src/stm32f0/stm32f0_clockconfig.c index f8a8a59c9b..4a9407e706 100644 --- a/arch/arm/src/stm32f0/stm32f0_clockconfig.c +++ b/arch/arm/src/stm32f0/stm32f0_clockconfig.c @@ -95,7 +95,7 @@ void stm32f0_clockconfig(void) regval = getreg32(STM32F0_RCC_CFGR); regval &= ~RCC_CFGR_PLLMUL_MASK; - regval |= RCC_CFGR_PLLMUL_CLKx6 + regval |= RCC_CFGR_PLLMUL_CLKx6; putreg32(regval, STM32F0_RCC_CFGR); /* Enable the PLL */ -- GitLab From cd62425433129064e3aba6c5230cea784f7e13ae Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 17 Apr 2017 09:17:31 -0600 Subject: [PATCH 478/990] STM32F0: type of regval should be uint32_t in clockconfig(). Fix a warning from __start(). --- arch/arm/src/stm32f0/stm32f0_clockconfig.c | 10 +-- arch/arm/src/stm32f0/stm32f0_start.c | 5 +- arch/arm/src/stm32f0/stm32f0_start.h | 76 ++++++++++++++++++++++ configs/stm32f0discovery/nsh/setenv.sh | 19 ++++-- 4 files changed, 94 insertions(+), 16 deletions(-) create mode 100644 arch/arm/src/stm32f0/stm32f0_start.h diff --git a/arch/arm/src/stm32f0/stm32f0_clockconfig.c b/arch/arm/src/stm32f0/stm32f0_clockconfig.c index 4a9407e706..9d54e6133b 100644 --- a/arch/arm/src/stm32f0/stm32f0_clockconfig.c +++ b/arch/arm/src/stm32f0/stm32f0_clockconfig.c @@ -69,16 +69,16 @@ void stm32f0_clockconfig(void) { - int regval; + uint32_t regval; - /* Verify if PLL is already setup, if so define to use HSI mode */ + /* Verify if PLL is already setup. If so configure to use HSI mode */ if ((getreg32(STM32F0_RCC_CFGR) & RCC_CFGR_SWS_MASK) == RCC_CFGR_SWS_PLL) { /* Select HSI mode */ regval = getreg32(STM32F0_RCC_CFGR); - regval &= (uint32_t) (~RCC_CFGR_SW_MASK); + regval &= ~RCC_CFGR_SW_MASK; putreg32(regval, STM32F0_RCC_CFGR); while ((getreg32(STM32F0_RCC_CFGR) & RCC_CFGR_SWS_MASK) != RCC_CFGR_SWS_HSI); @@ -87,7 +87,7 @@ void stm32f0_clockconfig(void) /* Disable the PLL */ regval = getreg32(STM32F0_RCC_CR); - regval &= (uint32_t)(~RCC_CR_PLLON); + regval &= ~RCC_CR_PLLON; putreg32(regval, STM32F0_RCC_CR); while ((getreg32(STM32F0_RCC_CR) & RCC_CR_PLLRDY) != 0); @@ -108,7 +108,7 @@ void stm32f0_clockconfig(void) /* Configure to use the PLL */ regval = getreg32(STM32F0_RCC_CFGR); - regval |= (uint32_t)(RCC_CFGR_SW_PLL); + regval |= RCC_CFGR_SW_PLL; putreg32(regval, STM32F0_RCC_CFGR); while ((getreg32(STM32F0_RCC_CFGR) & RCC_CFGR_SW_MASK) != RCC_CFGR_SW_PLL); } diff --git a/arch/arm/src/stm32f0/stm32f0_start.c b/arch/arm/src/stm32f0/stm32f0_start.c index a02fb464c7..6482dd47aa 100644 --- a/arch/arm/src/stm32f0/stm32f0_start.c +++ b/arch/arm/src/stm32f0/stm32f0_start.c @@ -52,10 +52,7 @@ #include "stm32f0_clockconfig.h" #include "stm32f0_lowputc.h" - -#ifdef CONFIG_ARCH_FPU -# include "nvic.h" -#endif +#include "stm32f0_start.h" /**************************************************************************** * Pre-processor Definitions diff --git a/arch/arm/src/stm32f0/stm32f0_start.h b/arch/arm/src/stm32f0/stm32f0_start.h new file mode 100644 index 0000000000..dc1779a5d1 --- /dev/null +++ b/arch/arm/src/stm32f0/stm32f0_start.h @@ -0,0 +1,76 @@ +/************************************************************************************ + * arch/arm/src/stm32f0/stm32f0_start.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32F0_STM32F0_START_H +#define __ARCH_ARM_SRC_STM32F0_STM32F0_START_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +#ifndef __ASSEMBLY__ +#ifdef __cplusplus +extern "C" +{ +#endif + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32f0_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry + * point is called early in the intitialization -- after all memory has been + * configured and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +void stm32f0_boardinitialize(void); + +#ifdef __cplusplus +} +#endif +#endif /* __ASSEMBLY__ */ + +#endif /* __ARCH_ARM_SRC_STM32F0_STM32F0_START_H */ diff --git a/configs/stm32f0discovery/nsh/setenv.sh b/configs/stm32f0discovery/nsh/setenv.sh index f131c7cefb..b8584be9c3 100644 --- a/configs/stm32f0discovery/nsh/setenv.sh +++ b/configs/stm32f0discovery/nsh/setenv.sh @@ -48,15 +48,20 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}" fi -# This is the Cygwin path to the location where I installed the RIDE -# toolchain under windows. You will also have to edit this if you install -# the RIDE toolchain in any other location -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" - # This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin" +# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin" + +# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors" +# You can this free toolchain here https://launchpad.net/gcc-arm-embedded +export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin" + +# This is the path to the location where I installed the devkitARM toolchain +# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/ +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin" # These are the Cygwin paths to the locations where I installed the Atollic # toolchain under windows. You will also have to edit this if you install @@ -68,7 +73,7 @@ export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ # This is the Cygwin path to the location where I build the buildroot # toolchain. -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" # Add the path to the toolchain to the PATH varialble export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" -- GitLab From 46d7a4bb0389db061579d2c6f554136d28c34a1d Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Mon, 17 Apr 2017 11:27:14 -0400 Subject: [PATCH 479/990] wireless/ieee802154: Continues development on transmit structure --- drivers/wireless/ieee802154/mrf24j40.c | 121 +++++++++++++----- .../wireless/ieee802154/ieee802154_radio.h | 28 +--- wireless/ieee802154/mac802154.c | 65 +++++----- 3 files changed, 130 insertions(+), 84 deletions(-) diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c index 32da714bca..3659fe1651 100644 --- a/drivers/wireless/ieee802154/mrf24j40.c +++ b/drivers/wireless/ieee802154/mrf24j40.c @@ -125,12 +125,19 @@ struct mrf24j40_radio_s /* Buffer Allocations */ - struct ieee802154_txdesc_s csma_desc; - struct ieee802154_txdesc_s gts_desc[2]; + struct mrf24j40_txdesc_s csma_desc; + struct mrf24j40_txdesc_s gts_desc[2]; uint8_t tx_buf[CONFIG_IEEE802154_MTU]; }; +struct mrf24j40_txdesc_s +{ + struct ieee802154_txdesc_s ieee_desc; + + uint8_t busy : 1; /* Is this txdesc being used */ +}; + /**************************************************************************** * Private Function Prototypes ****************************************************************************/ @@ -218,7 +225,8 @@ static const struct ieee802154_radioops_s mrf24j40_devops = mrf24j40_bind, mrf24j40_ioctl, mrf24j40_rxenable, - mrf24j40_transmit + mrf24j40_txnotify_csma, + mrf24j40_txnotify_gts, }; /**************************************************************************** @@ -236,51 +244,104 @@ static void mrf24j40_bind(FAR struct ieee802154_radio_s *radio, } /**************************************************************************** - * Function: mrf24j40_txavail + * Function: mrf24j40_dopoll_csma * * Description: - * Called from the upper layer, this function is to notify the device that - * the upper layer has a pending transaction. This function checks to see - * if there is availability for the corresponding transaction type. If - * there is, the function will call to the MAC layer to get the transaction - * and then start the transmission + * This function is called in order to preform an out-of-sequence TX poll. + * This is done: + * + * 1. After completion of a CSMA transmission + * 2. When the upper layer calls txnotify_csma + * + * Parameters: + * radio - Reference to the radio driver state structure + * + * Returned Value: + * None + * + * Assumptions: * ****************************************************************************/ -static void mrf24j40_txavail(FAR struct ieee802154_radio_s *radio, bool gts) +static void mrf24j40_dopoll_csma(FAR struct ieee802154_radio_s *radio) { FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)radio; - uint8_t gts; - while (sem_wait(dev->exclsem) < 0) { } + /* Need to get exlusive access to the device so that we can use the copy + * buffer */ + + while (sem_wait(&dev->exclsem) < 0) { } /* If this a CSMA transaction and we have room in the CSMA fifo */ - if (!gts && !dev->csma_busy) + if (!dev->csma_txdesc.busy) { /* need to somehow allow for a handle to be passed */ ret = dev->phyif->poll_csma(dev->phyif, &radio->csma_txdesc, &dev->tx_buf[0]); + if (ret > 0) + { + /* Now the txdesc is in use */ + + dev->cmsa_desc.busy = 1; + + /* Setup the transaction on the device in the CSMA FIFO */ + + mrf24j40_csma_setup(radio, &dev->tx_buf[0], + dev->gts_desc[i].psdu_length); + } + /* Setup the transmit on the device */ + break; } - else - { - for(gts = 0; gts < MRF24J40_GTS_SLOTS, gts++) + + sem_post(&dev->exclsem); +} + +/**************************************************************************** + * Function: mrf24j40_txnotify_gts + * + * Description: + * Called from the upper layer, this function is to notify the device that + * the upper layer has a pending transaction for one of it's GTS'. This + * function checks to see if there is availability for the corresponding + * transaction type. If there is, the function will call to the MAC layer + * to get the transaction and then start the transmission + * + ****************************************************************************/ + +static void mrf24j40_txnotify_gts(FAR struct ieee802154_radio_s *radio) +{ + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)radio; + + /* Need to get exclusive access to the device so that we can use the copy + * buffer */ + + while (sem_wait(dev->exclsem) < 0) { } + + for(gts = 0; gts < MRF24J40_GTS_SLOTS, gts++) + { + if(!dev->gts_txdesc[i].busy) { - if(!dev->gts_txdesc[i].busy) + ret = dev->phyif->poll_gts(dev->phyif, &radio->gts_txdesc[i], + &dev->tx_buf[0]); + + if (ret > 0) { - ret = dev->phyif->poll_gts(dev->phyif, &radio->gts_txdesc[i], - &dev->tx_buf[0]); + /* Now the txdesc is in use */ + + dev->gts_txdesc[i].busy = 1; - /* Setup the transmit on the device */ + /* Setup the transaction on the device in the open GTS FIFO */ - break; + mrf24j40_gts_setup(radio, i, &dev->tx_buf[0], + dev->gts_desc[i].psdu_length); } } - } + } } /**************************************************************************** @@ -1506,38 +1567,36 @@ FAR struct ieee802154_radio_s *mrf24j40_init(FAR struct spi_dev_s *spi, /* Initialize semaphores */ sem_init(&dev->radio.rxsem, 0, 0); - sem_init(&dev->radio.txsem, 0, 0); /* These semaphores are all used for signaling and, hence, should * not have priority inheritance enabled. */ sem_setprotocol(&dev->radio.rxsem, SEM_PRIO_NONE); - sem_setprotocol(&dev->radio.txsem, SEM_PRIO_NONE); dev->lower = lower; dev->spi = spi; mrf24j40_initialize(dev); - mrf24j40_setchannel(&dev->radio, 11); - mrf24j40_setpanid (&dev->radio, 0xFFFF); - mrf24j40_setsaddr (&dev->radio, 0xFFFF); - mrf24j40_seteaddr (&dev->radio, (uint8_t*)"\xFF\xFF\xFF\xFF\xFF\xFF\xFF\xFF"); + mrf24j40_setchannel(dev, 11); + mrf24j40_setpanid (dev, 0xFFFF); + mrf24j40_setsaddr (dev, 0xFFFF); + mrf24j40_seteaddr (dev, (uint8_t*)"\xFF\xFF\xFF\xFF\xFF\xFF\xFF\xFF"); /* Default device params */ cca.use_ed = 1; cca.use_cs = 0; cca.edth = 0x60; /* CCA mode ED, no carrier sense, recommenced ED threshold -69 dBm */ - mrf24j40_setcca(&dev->radio, &cca); + mrf24j40_setcca(dev, &cca); mrf24j40_setrxmode(dev, MRF24J40_RXMODE_NORMAL); - mrf24j40_settxpower(&dev->radio, 0); /*16. Set transmitter power .*/ + mrf24j40_settxpower(dev, 0); /*16. Set transmitter power .*/ mrf24j40_pacontrol(dev, MRF24J40_PA_AUTO); - dev->lower->enable(dev->radio, true); + dev->lower->enable(dev->lower, true); return &dev->radio; } diff --git a/include/nuttx/wireless/ieee802154/ieee802154_radio.h b/include/nuttx/wireless/ieee802154/ieee802154_radio.h index a26e3321d6..bd7c725b15 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_radio.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_radio.h @@ -157,22 +157,15 @@ struct ieee802154_netradio_s #endif /* IEEE802.15.4 Radio Interface Operations **********************************/ -struct ieee802154_trans_s +struct ieee802154_txdesc_s { - uint8_t retry_count; /* The number of retries remaining */ - uint8_t msdu_handle; /* The msdu handle identifying the transaction */ + uint8_t psdu_handle; /* The psdu handle identifying the transaction */ uint16_t psdu_length; /* The length of the PSDU */ - /* The PHY Service Data Unit (PSDU) buffer representing the frame to be - * transmitted. This must be at the end of the struct to allow the array - * to continue and make the struct "variable length". Users should allocate - * memory using the SIZEOF_MAC802154_TRANSACTION_S macro below */ - - uint8_t psdu[CONFIG_IEEE802154_MTU]; + /* TODO: Add slotting information for GTS transactions */ }; - struct ieee802154_phyif_s; /* Forward Reference */ struct ieee802154_phyifops_s @@ -208,8 +201,8 @@ struct ieee802154_radioops_s CODE int (*rxenable)(FAR struct ieee802154_radio_s *dev, bool state, FAR struct ieee802154_packet_s *packet); - CODE int (*transmit)(FAR struct ieee802154_radio_s *dev, - FAR struct ieee802154_packet_s *packet); + CODE int (*txnotify_csma)(FAR struct ieee802154_radio_s *dev); + CODE int (*txnotify_gts)(FAR struct ieee802154_radio_s *dev); }; struct ieee802154_radio_s @@ -222,17 +215,6 @@ struct ieee802154_radio_s * rx interrupt, NULL if rx not enabled */ sem_t rxsem; /* Semaphore posted after reception of * a packet */ - - /* Packet transmission management */ - - bool txok; /* Last transmission status, filled by - * tx interrupt */ - bool txbusy; /* Last transmission failed because - * channel busy */ - uint8_t txretries; /* Last transmission required this much - * retries */ - sem_t txsem; /* Semaphore posted after transmission - * of a packet */ }; #ifdef __cplusplus diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index c4f99480bf..32e78dd916 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -57,6 +57,32 @@ /**************************************************************************** * Private Types ****************************************************************************/ + +struct mac802154_trans_s +{ + /* Supports a singly linked list */ + + FAR struct mac802154_trans_s *flink; + + uint8_t msdu_handle; + + uint8_t *mhr_buf; + uint8_t mhr_len; + + uint8_t *d_buf; + uint8_t d_len; + + sem_t sem; +}; + +struct mac802154_unsec_mhr_s +{ + uint8_t length; + union { + uint16_t frame_control; + uint8_t data[IEEE802154_MAX_UNSEC_MHR_OVERHEAD]; + }; +}; /* The privmac structure holds the internal state of the MAC and is the * underlying represention of the opaque MACHANDLE. It contains storage for @@ -79,7 +105,6 @@ struct ieee802154_privmac_s FAR struct mac802154_trans_s *csma_head; FAR struct mac802154_trans_s *csma_tail; - struct mac802154_trans_s csma_buf[5]; /* Support a singly linked list of transactions that will be sent indirectly. * This list should only be used by a MAC acting as a coordinator. These @@ -91,7 +116,6 @@ struct ieee802154_privmac_s FAR struct mac802154_trans_s *indirect_head; FAR struct mac802154_trans_s *indirect_tail; - FAR struct mac802154_trans_s *active_trans; /* MAC PIB attributes, grouped to save memory */ @@ -203,32 +227,6 @@ struct ieee802154_privmac_s /* TODO: Add Security-related MAC PIB attributes */ }; -struct mac802154_trans_s -{ - /* Supports a singly linked list */ - - FAR struct mac802154_trans_s *flink; - - uint8_t msdu_handle; - - uint8_t *mhr_buf; - uint8_t mhr_len; - - uint8_t *d_buf; - uint8_t d_len; - - sem_t sem; -}; - -struct mac802154_unsec_mhr_s -{ - uint8_t length; - union - { - uint16_t frame_control; - uint8_t data[IEEE802154_MAX_UNSEC_MHR_OVERHEAD]; - }; -}; /**************************************************************************** * Private Data @@ -563,7 +561,7 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) } } - /* Set the source addr mode inside the frame contorl field */ + /* Set the source addr mode inside the frame control field */ mhr.frame_ctrl |= (req->src_addr_mode << IEEE802154_FRAMECTRL_SHIFT_SADDR); @@ -658,7 +656,7 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) /* Notify the radio driver that there is data available */ - priv->radio->tx_notify(priv->radio); + priv->radio->ops->tx_notify(priv->radio); sem_wait(&trans->sem); } @@ -712,6 +710,13 @@ static uint16_t mac802154_poll_csma(FAR struct ieee802154_phyif_s *phyif, return 0; } +static uint16_t mac802154_poll_gts(FAR struct ieee802154_phyif_s *phyif, + FAR struct ieee802154_txdesc_s *tx_desc, + uint8_t *buf) +{ + return 0; +} + /**************************************************************************** * Name: mac802154_req_purge * -- GitLab From 6d3ec6e4a43fbad9305ffb520c8977899c401387 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 17 Apr 2017 09:53:58 -0600 Subject: [PATCH 480/990] ieee802.15.4: Changes from review of last PR --- drivers/wireless/ieee802154/mrf24j40.c | 38 ++++++++++--------- .../wireless/ieee802154/ieee802154_radio.h | 15 +++----- wireless/ieee802154/mac802154.c | 11 +++--- 3 files changed, 31 insertions(+), 33 deletions(-) diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c index 3659fe1651..2cb3300e5a 100644 --- a/drivers/wireless/ieee802154/mrf24j40.c +++ b/drivers/wireless/ieee802154/mrf24j40.c @@ -268,7 +268,8 @@ static void mrf24j40_dopoll_csma(FAR struct ieee802154_radio_s *radio) FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)radio; /* Need to get exlusive access to the device so that we can use the copy - * buffer */ + * buffer. + */ while (sem_wait(&dev->exclsem) < 0) { } @@ -318,30 +319,31 @@ static void mrf24j40_txnotify_gts(FAR struct ieee802154_radio_s *radio) FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)radio; /* Need to get exclusive access to the device so that we can use the copy - * buffer */ + * buffer. + */ while (sem_wait(dev->exclsem) < 0) { } - for(gts = 0; gts < MRF24J40_GTS_SLOTS, gts++) - { - if(!dev->gts_txdesc[i].busy) - { - ret = dev->phyif->poll_gts(dev->phyif, &radio->gts_txdesc[i], - &dev->tx_buf[0]); + for (gts = 0; gts < MRF24J40_GTS_SLOTS, gts++) + { + if (!dev->gts_txdesc[i].busy) + { + ret = dev->phyif->poll_gts(dev->phyif, &radio->gts_txdesc[i], + &dev->tx_buf[0]); - if (ret > 0) - { - /* Now the txdesc is in use */ + if (ret > 0) + { + /* Now the txdesc is in use */ - dev->gts_txdesc[i].busy = 1; + dev->gts_txdesc[i].busy = 1; - /* Setup the transaction on the device in the open GTS FIFO */ + /* Setup the transaction on the device in the open GTS FIFO */ - mrf24j40_gts_setup(radio, i, &dev->tx_buf[0], - dev->gts_desc[i].psdu_length); - } - } - } + mrf24j40_gts_setup(radio, i, &dev->tx_buf[0], + dev->gts_desc[i].psdu_length); + } + } + } } /**************************************************************************** diff --git a/include/nuttx/wireless/ieee802154/ieee802154_radio.h b/include/nuttx/wireless/ieee802154/ieee802154_radio.h index bd7c725b15..d48b0d4e12 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_radio.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_radio.h @@ -157,6 +157,7 @@ struct ieee802154_netradio_s #endif /* IEEE802.15.4 Radio Interface Operations **********************************/ + struct ieee802154_txdesc_s { uint8_t psdu_handle; /* The psdu handle identifying the transaction */ @@ -171,12 +172,9 @@ struct ieee802154_phyif_s; /* Forward Reference */ struct ieee802154_phyifops_s { CODE int (*poll_csma) (FAR struct ieee802154_phyif_s *phyif, - FAR struct ieee802154_txdesc_s *tx_desc, - uint8_t *buf); - + FAR struct ieee802154_txdesc_s *tx_desc, FAR uint8_t *buf); CODE int (*poll_gts) (FAR struct ieee802154_phyif_s *phyif, - FAR struct ieee802154_txdesc_s *tx_desc, - uint8_t *buf); + FAR struct ieee802154_txdesc_s *tx_desc, FAR uint8_t *buf); }; struct ieee802154_phyif_s @@ -185,7 +183,7 @@ struct ieee802154_phyif_s /* Driver-specific information */ - void * priv; + FAR void * priv; }; struct ieee802154_radio_s; /* Forward reference */ @@ -193,14 +191,11 @@ struct ieee802154_radio_s; /* Forward reference */ struct ieee802154_radioops_s { CODE int (*bind) (FAR struct ieee802154_radio_s *dev, - FAR const struct ieee802154_phyif_s *phyif); - + FAR const struct ieee802154_phyif_s *phyif); CODE int (*ioctl)(FAR struct ieee802154_radio_s *ieee, int cmd, unsigned long arg); - CODE int (*rxenable)(FAR struct ieee802154_radio_s *dev, bool state, FAR struct ieee802154_packet_s *packet); - CODE int (*txnotify_csma)(FAR struct ieee802154_radio_s *dev); CODE int (*txnotify_gts)(FAR struct ieee802154_radio_s *dev); }; diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index 32e78dd916..8dc2e87b3f 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -66,10 +66,10 @@ struct mac802154_trans_s uint8_t msdu_handle; - uint8_t *mhr_buf; + FAR uint8_t *mhr_buf; uint8_t mhr_len; - uint8_t *d_buf; + FAR uint8_t *d_buf; uint8_t d_len; sem_t sem; @@ -78,10 +78,11 @@ struct mac802154_trans_s struct mac802154_unsec_mhr_s { uint8_t length; - union { + union + { uint16_t frame_control; uint8_t data[IEEE802154_MAX_UNSEC_MHR_OVERHEAD]; - }; + } u; }; /* The privmac structure holds the internal state of the MAC and is the @@ -530,7 +531,7 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) * from the transmitted frame. [1] pg. 41. */ - if(req->dest_addr.panid == priv->addr.panid) + if (req->dest_addr.panid == priv->addr.panid) { mhr.frame_control |= IEEE802154_FRAMECTRL_PANIDCOMP; } -- GitLab From 735f4d6ea55a6cbeee80700fd03a7e1e3e05de5e Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Mon, 17 Apr 2017 09:58:04 -0600 Subject: [PATCH 481/990] STM32F0: Enable the clock for all GPIO ports --- arch/arm/src/stm32f0/stm32f0_lowputc.c | 11 +++++++---- 1 file changed, 7 insertions(+), 4 deletions(-) diff --git a/arch/arm/src/stm32f0/stm32f0_lowputc.c b/arch/arm/src/stm32f0/stm32f0_lowputc.c index 566dc14bf9..8dfe8e0820 100644 --- a/arch/arm/src/stm32f0/stm32f0_lowputc.c +++ b/arch/arm/src/stm32f0/stm32f0_lowputc.c @@ -296,6 +296,7 @@ void stm32f0_lowsetup(void) #if defined(HAVE_UART) #if defined(HAVE_CONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG) uint32_t cr; + uint32_t clken; #endif #if defined(HAVE_CONSOLE) @@ -304,10 +305,12 @@ void stm32f0_lowsetup(void) modifyreg32(STM32F0_CONSOLE_APBREG, 0, STM32F0_CONSOLE_APBEN); #endif - /* Enable the console USART and configure GPIO pins needed for rx/tx. - * - * NOTE: Clocking for selected U[S]ARTs was already provided in stm32f0_rcc.c - */ + /* Enable the console USART and configure GPIO pins needed for rx/tx. */ + + clken = getreg32(STM32F0_RCC_AHBENR); + clken |= RCC_AHBENR_IOPAEN | RCC_AHBENR_IOPAEN | RCC_AHBENR_IOPAEN |\ + RCC_AHBENR_IOPAEN | RCC_AHBENR_IOPAEN | RCC_AHBENR_IOPAEN; + putreg32(clken, STM32F0_RCC_AHBENR); #ifdef STM32F0_CONSOLE_TX stm32f0_configgpio(STM32F0_CONSOLE_TX); -- GitLab From 3249da6557c6ccd100fb987a7906b7ecbfd8eac6 Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Mon, 17 Apr 2017 11:14:24 -0600 Subject: [PATCH 482/990] STM32F0: Fix HSI clock definition --- configs/stm32f0discovery/include/board.h | 83 ++++++++++++------------ 1 file changed, 41 insertions(+), 42 deletions(-) diff --git a/configs/stm32f0discovery/include/board.h b/configs/stm32f0discovery/include/board.h index 4840067e96..de4410b148 100644 --- a/configs/stm32f0discovery/include/board.h +++ b/configs/stm32f0discovery/include/board.h @@ -55,10 +55,10 @@ /* Four different clock sources can be used to drive the system clock (SYSCLK): * * - HSI high-speed internal oscillator clock - * Generated from an internal 16 MHz RC oscillator + * Generated from an internal 8 MHz RC oscillator * - HSE high-speed external oscillator clock - * Normally driven by an external crystal (X3). However, this crystal is not fitted - * on the STM32L-Discovery board. + * Normally driven by an external crystal (X3). However, this crystal is not + * fitted on the STM32F0-Discovery board. * - PLL clock * - MSI multispeed internal oscillator clock * The MSI clock signal is generated from an internal RC oscillator. Seven frequency @@ -74,7 +74,7 @@ #define STM32F0_BOARD_XTAL 8000000ul /* X3 on board (not fitted)*/ -#define STM32F0_HSI_FREQUENCY 16000000ul /* Approximately 16MHz */ +#define STM32F0_HSI_FREQUENCY 8000000ul /* Approximately 8MHz */ #define STM32F0_HSE_FREQUENCY STM32F0_BOARD_XTAL #define STM32F0_MSI_FREQUENCY 2097000 /* Default is approximately 2.097Mhz */ #define STM32F0_LSI_FREQUENCY 37000 /* Approximately 37KHz */ @@ -82,20 +82,20 @@ /* This is the clock setup we configure for: * - * SYSCLK = BOARD_OSCCLK_FREQUENCY = 12MHz -> Select Main oscillator for source + * SYSCLK = BOARD_OSCCLK_FREQUENCY = 12MHz -> Select Main oscillator for source * PLL0CLK = (2 * 20 * SYSCLK) / 1 = 480MHz -> PLL0 multipler=20, pre-divider=1 - * MCLK = 480MHz / 6 = 80MHz -> MCLK divider = 6 + * MCLK = 480MHz / 6 = 80MHz -> MCLK divider = 6 */ -#define STM32F0_MCLK 48000000 /* 48Mhz */ +#define STM32F0_MCLK 48000000 /* 48Mhz */ /* PLL Configuration * - * - PLL source is HSI -> 16MHz input (nominal) - * - PLL multipler is 6 -> 96MHz PLL VCO clock output (for USB) - * - PLL output divider 3 -> 32MHz divided down PLL VCO clock output + * - PLL source is HSI -> 8MHz input (nominal) + * - PLL multipler is 6 -> 48MHz PLL VCO clock output (for USB) + * - PLL output divider 1 -> 48MHz divided down PLL VCO clock output * - * Resulting SYSCLK frequency is 16MHz x 6 / 3 = 32MHz + * Resulting SYSCLK frequency is 16MHz x 6 / 1 = 48MHz * * USB/SDIO: * If the USB or SDIO interface is used in the application, the PLL VCO @@ -112,15 +112,15 @@ * The minimum input clock frequency for PLL is 2 MHz (when using HSE as PLL source). */ -#define STM32F0_CFGR_PLLSRC 0 /* Source is 16MHz HSI */ +#define STM32F0_CFGR_PLLSRC 0 /* Source is 16MHz HSI */ #ifdef CONFIG_STM32F0_USB -# define STM32F0_CFGR_PLLMUL RCC_CFGR_PLLMUL_CLKx6 /* PLLMUL = 6 */ -# define STM32F0_CFGR_PLLDIV RCC_CFGR_PLLDIV_3 /* PLLDIV = 3 */ +# define STM32F0_CFGR_PLLMUL RCC_CFGR_PLLMUL_CLKx6 /* PLLMUL = 6 */ +# define STM32F0_CFGR_PLLDIV RCC_CFGR_PLLDIV_3 /* PLLDIV = 3 */ # define STM32F0_PLL_FREQUENCY (6*STM32F0_HSI_FREQUENCY) /* PLL VCO Frequency is 96MHz */ #else -# define STM32F0_CFGR_PLLMUL RCC_CFGR_PLLMUL_CLKx4 /* PLLMUL = 4 */ -# define STM32F0_CFGR_PLLDIV RCC_CFGR_PLLDIV_2 /* PLLDIV = 2 */ -# define STM32F0_PLL_FREQUENCY (4*STM32F0_HSI_FREQUENCY) /* PLL VCO Frequency is 64MHz */ +# define STM32F0_CFGR_PLLMUL RCC_CFGR_PLLMUL_CLKx6 /* PLLMUL = 6 */ +# define STM32F0_CFGR_PLLDIV RCC_CFGR_PLLDIV_1 /* PLLDIV = 1 */ +# define STM32F0_PLL_FREQUENCY (6*STM32F0_HSI_FREQUENCY) /* PLL VCO Frequency is 48MHz */ #endif /* Use the PLL and set the SYSCLK source to be the divided down PLL VCO output @@ -130,45 +130,44 @@ #define STM32F0_SYSCLK_SW RCC_CFGR_SW_PLL /* Use the PLL as the SYSCLK */ #define STM32F0_SYSCLK_SWS RCC_CFGR_SWS_PLL #ifdef CONFIG_STM32F0_USB -# define STM32F0_SYSCLK_FREQUENCY (STM32F0_PLL_FREQUENCY/3) /* SYSCLK frequence is 96MHz/PLLDIV = 32MHz */ +# define STM32F0_SYSCLK_FREQUENCY (STM32F0_PLL_FREQUENCY/3) /* SYSCLK frequency is 96MHz/PLLDIV = 32MHz */ #else -# define STM32F0_SYSCLK_FREQUENCY (STM32F0_PLL_FREQUENCY/2) /* SYSCLK frequence is 64MHz/PLLDIV = 32MHz */ +# define STM32F0_SYSCLK_FREQUENCY (STM32F0_PLL_FREQUENCY/2) /* SYSCLK frequency is 48MHz/PLLDIV = 24MHz */ #endif -/* AHB clock (HCLK) is SYSCLK (32MHz) */ +/* AHB clock (HCLK) is SYSCLK (24MHz) */ #define STM32F0_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK #define STM32F0_HCLK_FREQUENCY STM32F0_SYSCLK_FREQUENCY #define STM32F0_BOARD_HCLK STM32F0_HCLK_FREQUENCY /* Same as above, to satisfy compiler */ -/* APB2 clock (PCLK2) is HCLK (32MHz) */ +/* APB1 clock (PCLK1) is HCLK (24MHz) */ + +#define STM32F0_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLK +#define STM32F0_PCLK1_FREQUENCY (STM32F0_HCLK_FREQUENCY) + +/* APB2 clock (PCLK2) is HCLK (24MHz) */ #define STM32F0_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK #define STM32F0_PCLK2_FREQUENCY STM32F0_HCLK_FREQUENCY #define STM32F0_APB2_CLKIN (STM32F0_PCLK2_FREQUENCY) -/* APB2 timers 9, 10, and 11 will receive PCLK2. */ - -#define STM32F0_APB2_TIM9_CLKIN (STM32F0_PCLK2_FREQUENCY) -#define STM32F0_APB2_TIM10_CLKIN (STM32F0_PCLK2_FREQUENCY) -#define STM32F0_APB2_TIM11_CLKIN (STM32F0_PCLK2_FREQUENCY) - -/* APB1 clock (PCLK1) is HCLK (32MHz) */ - -#define STM32F0_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLK -#define STM32F0_PCLK1_FREQUENCY (STM32F0_HCLK_FREQUENCY) - -/* APB1 timers 2-7 will receive PCLK1 */ +/* APB1 timers 1-3, 6-7, and 14-17 will receive PCLK1 */ +#define STM32F0_APB1_TIM1_CLKIN (STM32F0_PCLK1_FREQUENCY) #define STM32F0_APB1_TIM2_CLKIN (STM32F0_PCLK1_FREQUENCY) #define STM32F0_APB1_TIM3_CLKIN (STM32F0_PCLK1_FREQUENCY) -#define STM32F0_APB1_TIM4_CLKIN (STM32F0_PCLK1_FREQUENCY) -#define STM32F0_APB1_TIM5_CLKIN (STM32F0_PCLK1_FREQUENCY) + #define STM32F0_APB1_TIM6_CLKIN (STM32F0_PCLK1_FREQUENCY) #define STM32F0_APB1_TIM7_CLKIN (STM32F0_PCLK1_FREQUENCY) +#define STM32F0_APB1_TIM14_CLKIN (STM32F0_PCLK1_FREQUENCY) +#define STM32F0_APB1_TIM15_CLKIN (STM32F0_PCLK1_FREQUENCY) +#define STM32F0_APB1_TIM16_CLKIN (STM32F0_PCLK1_FREQUENCY) +#define STM32F0_APB1_TIM17_CLKIN (STM32F0_PCLK1_FREQUENCY) + /* LED definitions ******************************************************************/ -/* The STM32L-Discovery board has four LEDs. Two of these are controlled by +/* The STM32F0-Discovery board has four LEDs. Two of these are controlled by * logic on the board and are not available for software control: * * LD1 COM: LD2 default status is red. LD2 turns to green to indicate that @@ -177,9 +176,9 @@ * * And two LEDs can be controlled by software: * - * User LD3: Green LED is a user LED connected to the I/O PB7 of the STM32L152 + * User LD3: Green LED is a user LED connected to the I/O PB7 of the STM32F0152 * MCU. - * User LD4: Blue LED is a user LED connected to the I/O PB6 of the STM32L152 + * User LD4: Blue LED is a user LED connected to the I/O PB6 of the STM32F0152 * MCU. * * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any @@ -198,7 +197,7 @@ #define BOARD_LED2_BIT (1 << BOARD_LED2) /* If CONFIG_ARCH_LEDs is defined, then NuttX will control the 8 LEDs on board the - * STM32L-Discovery. The following definitions describe how NuttX controls the LEDs: + * STM32F0-Discovery. The following definitions describe how NuttX controls the LEDs: * * SYMBOL Meaning LED state * LED1 LED2 @@ -224,11 +223,11 @@ #define LED_PANIC 3 /* Button definitions ***************************************************************/ -/* The STM32L-Discovery supports two buttons; only one button is controllable by +/* The STM32F0-Discovery supports two buttons; only one button is controllable by * software: * - * B1 USER: user and wake-up button connected to the I/O PA0 of the STM32L152RBT6. - * B2 RESET: pushbutton connected to NRST is used to RESET the STM32L152RBT6. + * B1 USER: user and wake-up button connected to the I/O PA0 of the STM32F0152RBT6. + * B2 RESET: pushbutton connected to NRST is used to RESET the STM32F0152RBT6. */ #define BUTTON_USER 0 -- GitLab From 8df9e7f8ce0a5d40caee33497fa9bfa420ab198d Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 17 Apr 2017 11:18:13 -0600 Subject: [PATCH 483/990] STM32F0-Discovery: Correct part number in board.h --- configs/stm32f0discovery/include/board.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/configs/stm32f0discovery/include/board.h b/configs/stm32f0discovery/include/board.h index de4410b148..6822d19d0b 100644 --- a/configs/stm32f0discovery/include/board.h +++ b/configs/stm32f0discovery/include/board.h @@ -176,9 +176,9 @@ * * And two LEDs can be controlled by software: * - * User LD3: Green LED is a user LED connected to the I/O PB7 of the STM32F0152 + * User LD3: Green LED is a user LED connected to the I/O PB7 of the STM32F051R8 * MCU. - * User LD4: Blue LED is a user LED connected to the I/O PB6 of the STM32F0152 + * User LD4: Blue LED is a user LED connected to the I/O PB6 of the STM32F051R8 * MCU. * * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any @@ -226,8 +226,8 @@ /* The STM32F0-Discovery supports two buttons; only one button is controllable by * software: * - * B1 USER: user and wake-up button connected to the I/O PA0 of the STM32F0152RBT6. - * B2 RESET: pushbutton connected to NRST is used to RESET the STM32F0152RBT6. + * B1 USER: user and wake-up button connected to the I/O PA0 of the STM32F051R8. + * B2 RESET: pushbutton connected to NRST is used to RESET the STM32F051R8. */ #define BUTTON_USER 0 -- GitLab From 1d1d633e6f02f836bfa36032c866231905283897 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 17 Apr 2017 11:47:33 -0600 Subject: [PATCH 484/990] ieee802.15.4: Fix some forbidden C11 syntax. --- include/nuttx/wireless/ieee802154/ieee802154_mac.h | 8 ++++---- wireless/ieee802154/mac802154.c | 10 +++++----- 2 files changed, 9 insertions(+), 9 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index 838f7fcafd..76880ebf29 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -356,7 +356,7 @@ struct ieee802154_addr_s { uint16_t saddr; /* short address */ uint8_t eaddr[8]; /* extended address */ - }; + } u; }; #define IEEE802154_ADDRSTRLEN 22 /* (2*2+1+8*2, PPPP/EEEEEEEEEEEEEEEE) */ @@ -430,7 +430,7 @@ struct ieee802154_data_req_s uint8_t ack_tx : 1; /* Acknowledge TX? */ uint8_t gts_tx : 1; /* 1=GTS used for TX, 0=CAP used for TX */ uint8_t indirect_tx : 1; /* Should indirect transmission be used? */ - }; + } msdu_flags; #ifdef CONFIG_IEEE802154_SECURITY /* Security information if enabled */ @@ -566,8 +566,8 @@ struct ieee802154_pend_addr_s uint8_t reserved_3 : 1; /* Reserved bit */ uint8_t num_ext_addr : 3; /* Number of extended addresses pending */ uint8_t reserved_7 : 1; /* Reserved bit */ - }; - }; + } pa_addr; + } u; struct ieee802154_addr_s addr[7]; /* Array of at most 7 addresses */ }; diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index 8dc2e87b3f..ee057dcec1 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -482,7 +482,7 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) * 5.1.6.4 [1] pg. 118. */ - mhr.frame_ctrl |= (req->ack_tx << IEEE802154_FRAMECTRL_SHIFT_ACKREQ); + mhr.frame_ctrl |= (req->msdu_flags.ack_tx << IEEE802154_FRAMECTRL_SHIFT_ACKREQ); /* If the destination address is present, copy the PAN ID and one of the * addresses, depending on mode, into the MHR . @@ -603,7 +603,7 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) * [1] pg. 118. */ - if (req->gts_tx) + if (req->msdu_flags.gts_tx) { /* TODO: Support GTS transmission. This should just change where we link * the transaction. Instead of going in the CSMA transaction list, it @@ -622,7 +622,7 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) * described in 5.1.5 and 5.1.6.3. [1] */ - if (req->indirect_tx) + if (req->msdu_flags.indirect_tx) { /* If the TxOptions parameter specifies that an indirect transmission * is required and if the device receiving this primitive is not a @@ -642,13 +642,13 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) { /* Override the setting since it wasn't valid */ - req->indirect_tx = 0; + req->msgu_flags.indirect_tx = 0; } } /* If this is a direct transmission not during a GTS */ - if (!req->indirect_tx) + if (!req->msdu_flags.indirect_tx) { /* Link the transaction into the CSMA transaction list */ -- GitLab From efd674e09f38bbd52312920d92b6dbc8824f00c5 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 17 Apr 2017 12:24:23 -0600 Subject: [PATCH 485/990] STM32F0-Discovery: Clarifie clock calculations in board.h --- configs/stm32f0discovery/include/board.h | 27 ++++++++++++------------ 1 file changed, 14 insertions(+), 13 deletions(-) diff --git a/configs/stm32f0discovery/include/board.h b/configs/stm32f0discovery/include/board.h index 6822d19d0b..09892bef0d 100644 --- a/configs/stm32f0discovery/include/board.h +++ b/configs/stm32f0discovery/include/board.h @@ -91,11 +91,11 @@ /* PLL Configuration * - * - PLL source is HSI -> 8MHz input (nominal) - * - PLL multipler is 6 -> 48MHz PLL VCO clock output (for USB) - * - PLL output divider 1 -> 48MHz divided down PLL VCO clock output + * - PLL source is HSI -> 8MHz input (nominal) + * - PLL source pre-divider 2 -> 4MHz divided down PLL VCO clock output + * - PLL multipler is 6 -> 24MHz PLL VCO clock output (for USB) * - * Resulting SYSCLK frequency is 16MHz x 6 / 1 = 48MHz + * Resulting SYSCLK frequency is 8MHz x 6 / 2 = 24MHz * * USB/SDIO: * If the USB or SDIO interface is used in the application, the PLL VCO @@ -112,15 +112,16 @@ * The minimum input clock frequency for PLL is 2 MHz (when using HSE as PLL source). */ -#define STM32F0_CFGR_PLLSRC 0 /* Source is 16MHz HSI */ +#define STM32F0_CFGR_PLLSRC RCC_CFGR_PLLSRC_HSId2 /* Source is HSI/2 */ +#define STM32F0_PLLSRC_FREQUENCY (STM32F0_HSI_FREQUENCY/2) #ifdef CONFIG_STM32F0_USB -# define STM32F0_CFGR_PLLMUL RCC_CFGR_PLLMUL_CLKx6 /* PLLMUL = 6 */ -# define STM32F0_CFGR_PLLDIV RCC_CFGR_PLLDIV_3 /* PLLDIV = 3 */ -# define STM32F0_PLL_FREQUENCY (6*STM32F0_HSI_FREQUENCY) /* PLL VCO Frequency is 96MHz */ +# undef STM32F0_CFGR2_PREDIV /* Not used with source HSI/2 */ +# define STM32F0_CFGR_PLLMUL RCC_CFGR_PLLMUL_CLKx6 /* PLLMUL = 6 */ +# define STM32F0_PLL_FREQUENCY (6*STM32F0_PLLSRC_FREQUENCY) /* PLL VCO Frequency is 24MHz */ #else -# define STM32F0_CFGR_PLLMUL RCC_CFGR_PLLMUL_CLKx6 /* PLLMUL = 6 */ -# define STM32F0_CFGR_PLLDIV RCC_CFGR_PLLDIV_1 /* PLLDIV = 1 */ -# define STM32F0_PLL_FREQUENCY (6*STM32F0_HSI_FREQUENCY) /* PLL VCO Frequency is 48MHz */ +# undef STM32F0_CFGR2_PREDIV /* Not used with source HSI/2 */ +# define STM32F0_CFGR_PLLMUL RCC_CFGR_PLLMUL_CLKx6 /* PLLMUL = 6 */ +# define STM32F0_PLL_FREQUENCY (6*STM32F0_PLLSRC_FREQUENCY) /* PLL VCO Frequency is 24MHz */ #endif /* Use the PLL and set the SYSCLK source to be the divided down PLL VCO output @@ -130,9 +131,9 @@ #define STM32F0_SYSCLK_SW RCC_CFGR_SW_PLL /* Use the PLL as the SYSCLK */ #define STM32F0_SYSCLK_SWS RCC_CFGR_SWS_PLL #ifdef CONFIG_STM32F0_USB -# define STM32F0_SYSCLK_FREQUENCY (STM32F0_PLL_FREQUENCY/3) /* SYSCLK frequency is 96MHz/PLLDIV = 32MHz */ +# define STM32F0_SYSCLK_FREQUENCY STM32F0_PLL_FREQUENCY /* SYSCLK frequency is PLL VCO = 24MHz */ #else -# define STM32F0_SYSCLK_FREQUENCY (STM32F0_PLL_FREQUENCY/2) /* SYSCLK frequency is 48MHz/PLLDIV = 24MHz */ +# define STM32F0_SYSCLK_FREQUENCY STM32F0_PLL_FREQUENCY /* SYSCLK frequency is PLL VCO = 24MHz */ #endif /* AHB clock (HCLK) is SYSCLK (24MHz) */ -- GitLab From b0597583da340e7f8559854f1f5fc48e1ccff003 Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Mon, 17 Apr 2017 12:48:07 -0600 Subject: [PATCH 486/990] Fix System Clock value to 48MHz and remove MCLK definition --- arch/arm/src/stm32f0/stm32f0_clockconfig.c | 4 +- arch/arm/src/stm32f0/stm32f0_timerisr.c | 4 +- configs/stm32f0discovery/include/board.h | 48 +++++++++------------- 3 files changed, 23 insertions(+), 33 deletions(-) diff --git a/arch/arm/src/stm32f0/stm32f0_clockconfig.c b/arch/arm/src/stm32f0/stm32f0_clockconfig.c index 9d54e6133b..20acb55804 100644 --- a/arch/arm/src/stm32f0/stm32f0_clockconfig.c +++ b/arch/arm/src/stm32f0/stm32f0_clockconfig.c @@ -91,11 +91,11 @@ void stm32f0_clockconfig(void) putreg32(regval, STM32F0_RCC_CR); while ((getreg32(STM32F0_RCC_CR) & RCC_CR_PLLRDY) != 0); - /* Configure the PLL. Multiple x6 to get 48MHz */ + /* Configure the PLL. Multiply the HSI to get System Clock */ regval = getreg32(STM32F0_RCC_CFGR); regval &= ~RCC_CFGR_PLLMUL_MASK; - regval |= RCC_CFGR_PLLMUL_CLKx6; + regval |= STM32F0_CFGR_PLLMUL; putreg32(regval, STM32F0_RCC_CFGR); /* Enable the PLL */ diff --git a/arch/arm/src/stm32f0/stm32f0_timerisr.c b/arch/arm/src/stm32f0/stm32f0_timerisr.c index 3887b24a71..d6cb231539 100644 --- a/arch/arm/src/stm32f0/stm32f0_timerisr.c +++ b/arch/arm/src/stm32f0/stm32f0_timerisr.c @@ -63,9 +63,9 @@ */ #if defined(CONFIG_STM32F0_SYSTICK_CORECLK) -# define SYSTICK_CLOCK STM32F0_MCLK /* Core clock */ +# define SYSTICK_CLOCK STM32F0_SYSCLK_FREQUENCY /* Core clock */ #elif defined(CONFIG_STM32F0_SYSTICK_CORECLK_DIV16) -# define SYSTICK_CLOCK (STM32F0_MCLK / 16) /* Core clock divided by 16 */ +# define SYSTICK_CLOCK (STM32F0_SYSCLK_FREQUENCY / 16) /* Core clock divided by 16 */ #endif /* The desired timer interrupt frequency is provided by the definition diff --git a/configs/stm32f0discovery/include/board.h b/configs/stm32f0discovery/include/board.h index 09892bef0d..e2ca4de903 100644 --- a/configs/stm32f0discovery/include/board.h +++ b/configs/stm32f0discovery/include/board.h @@ -75,27 +75,19 @@ #define STM32F0_BOARD_XTAL 8000000ul /* X3 on board (not fitted)*/ #define STM32F0_HSI_FREQUENCY 8000000ul /* Approximately 8MHz */ +#define STM32F0_HSI14_FREQUENCY 14000000ul /* HSI14 for ADC */ +#define STM32F0_HSI48_FREQUENCY 48000000ul /* HSI48 for USB, only some STM32F0xx */ #define STM32F0_HSE_FREQUENCY STM32F0_BOARD_XTAL -#define STM32F0_MSI_FREQUENCY 2097000 /* Default is approximately 2.097Mhz */ -#define STM32F0_LSI_FREQUENCY 37000 /* Approximately 37KHz */ +#define STM32F0_LSI_FREQUENCY 40000 /* Approximately 40KHz */ #define STM32F0_LSE_FREQUENCY 32768 /* X2 on board */ -/* This is the clock setup we configure for: - * - * SYSCLK = BOARD_OSCCLK_FREQUENCY = 12MHz -> Select Main oscillator for source - * PLL0CLK = (2 * 20 * SYSCLK) / 1 = 480MHz -> PLL0 multipler=20, pre-divider=1 - * MCLK = 480MHz / 6 = 80MHz -> MCLK divider = 6 - */ - -#define STM32F0_MCLK 48000000 /* 48Mhz */ - /* PLL Configuration * - * - PLL source is HSI -> 8MHz input (nominal) - * - PLL source pre-divider 2 -> 4MHz divided down PLL VCO clock output - * - PLL multipler is 6 -> 24MHz PLL VCO clock output (for USB) + * - PLL source is HSI -> 8MHz input (nominal) + * - PLL source predivider 2 -> 4MHz divided down PLL VCO clock output + * - PLL multipler is 12 -> 48MHz PLL VCO clock output (for USB) * - * Resulting SYSCLK frequency is 8MHz x 6 / 2 = 24MHz + * Resulting SYSCLK frequency is 8MHz x 12 / 2 = 48MHz * * USB/SDIO: * If the USB or SDIO interface is used in the application, the PLL VCO @@ -112,16 +104,16 @@ * The minimum input clock frequency for PLL is 2 MHz (when using HSE as PLL source). */ -#define STM32F0_CFGR_PLLSRC RCC_CFGR_PLLSRC_HSId2 /* Source is HSI/2 */ -#define STM32F0_PLLSRC_FREQUENCY (STM32F0_HSI_FREQUENCY/2) +#define STM32F0_CFGR_PLLSRC RCC_CFGR_PLLSRC_HSId2 /* Source is HSI/2 */ +#define STM32F0_PLLSRC_FREQUENCY (STM32F0_HSI_FREQUENCY/2) /* 8MHz / 2 = 4MHz */ #ifdef CONFIG_STM32F0_USB -# undef STM32F0_CFGR2_PREDIV /* Not used with source HSI/2 */ -# define STM32F0_CFGR_PLLMUL RCC_CFGR_PLLMUL_CLKx6 /* PLLMUL = 6 */ -# define STM32F0_PLL_FREQUENCY (6*STM32F0_PLLSRC_FREQUENCY) /* PLL VCO Frequency is 24MHz */ +# undef STM32F0_CFGR2_PREDIV /* Not used with source HSI/2 */ +# define STM32F0_CFGR_PLLMUL RCC_CFGR_PLLMUL_CLKx12 /* PLLMUL = 12 */ +# define STM32F0_PLL_FREQUENCY (12*STM32F0_PLLSRC_FREQUENCY) /* PLL VCO Frequency is 48MHz */ #else -# undef STM32F0_CFGR2_PREDIV /* Not used with source HSI/2 */ -# define STM32F0_CFGR_PLLMUL RCC_CFGR_PLLMUL_CLKx6 /* PLLMUL = 6 */ -# define STM32F0_PLL_FREQUENCY (6*STM32F0_PLLSRC_FREQUENCY) /* PLL VCO Frequency is 24MHz */ +# undef STM32F0_CFGR2_PREDIV /* Not used with source HSI/2 */ +# define STM32F0_CFGR_PLLMUL RCC_CFGR_PLLMUL_CLKx12 /* PLLMUL = 12 */ +# define STM32F0_PLL_FREQUENCY (12*STM32F0_PLLSRC_FREQUENCY) /* PLL VCO Frequency is 48MHz */ #endif /* Use the PLL and set the SYSCLK source to be the divided down PLL VCO output @@ -131,23 +123,21 @@ #define STM32F0_SYSCLK_SW RCC_CFGR_SW_PLL /* Use the PLL as the SYSCLK */ #define STM32F0_SYSCLK_SWS RCC_CFGR_SWS_PLL #ifdef CONFIG_STM32F0_USB -# define STM32F0_SYSCLK_FREQUENCY STM32F0_PLL_FREQUENCY /* SYSCLK frequency is PLL VCO = 24MHz */ +# define STM32F0_SYSCLK_FREQUENCY STM32F0_PLL_FREQUENCY /* SYSCLK frequency is PLL VCO = 48MHz */ #else -# define STM32F0_SYSCLK_FREQUENCY STM32F0_PLL_FREQUENCY /* SYSCLK frequency is PLL VCO = 24MHz */ +# define STM32F0_SYSCLK_FREQUENCY STM32F0_PLL_FREQUENCY /* SYSCLK frequency is PLL VCO = 48MHz */ #endif -/* AHB clock (HCLK) is SYSCLK (24MHz) */ - #define STM32F0_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK #define STM32F0_HCLK_FREQUENCY STM32F0_SYSCLK_FREQUENCY #define STM32F0_BOARD_HCLK STM32F0_HCLK_FREQUENCY /* Same as above, to satisfy compiler */ -/* APB1 clock (PCLK1) is HCLK (24MHz) */ +/* APB1 clock (PCLK1) is HCLK (48MHz) */ #define STM32F0_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLK #define STM32F0_PCLK1_FREQUENCY (STM32F0_HCLK_FREQUENCY) -/* APB2 clock (PCLK2) is HCLK (24MHz) */ +/* APB2 clock (PCLK2) is HCLK (48MHz) */ #define STM32F0_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK #define STM32F0_PCLK2_FREQUENCY STM32F0_HCLK_FREQUENCY -- GitLab From 13e3e79183c75f02806200c6efab4d1f20db7803 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 17 Apr 2017 13:17:35 -0600 Subject: [PATCH 487/990] Update coding standard document to discuss un-named structure fields. --- Documentation/NuttXCCodingStandard.html | 72 +++++++++++++++++++------ 1 file changed, 55 insertions(+), 17 deletions(-) diff --git a/Documentation/NuttXCCodingStandard.html b/Documentation/NuttXCCodingStandard.html index 977af36225..98c878a296 100644 --- a/Documentation/NuttXCCodingStandard.html +++ b/Documentation/NuttXCCodingStandard.html @@ -12,7 +12,7 @@

NuttX C Coding Standard

-

Last Updated: February 9, 2017

+

Last Updated: April 17, 2017

@@ -1291,14 +1291,23 @@ typedef int myinteger_t;
  • No un-named structures. All structures must be named, even if they are part of a type definition. + That is, a structure name must follow the reserved word struct in all structure definitions. The exception to this rule is for structures that are defined within another union or structure. In those cases, the structure name should always be omitted.
  • +
  • + No un-named structure fields. + Structure may contain other structures as fields. + This this case, the structure field must be named. + C11 permits such un-named structure fields within structure. + NuttX generally follows C89 and all code outside of architecture specific directories must be compatible with C89.
  • No structure definitions within Type Definition. The practice of defining a structure within a type definition is discouraged. It is preferred that the structure definition and the type definition be separate definitions. In general, the NuttX coding style discourages any typdef-ing of structures; normally the full structure name is used as types throughout the code. + The reason for this is that is structure pointers may be forward referenced in header files without having to include the file the provides the type definition. + This greatly reduces header file coupling.
  • Short structure names. @@ -1373,7 +1382,7 @@ typedef int myinteger_t;

    Incorrect

      -typedef struct
      +typedef struct       /* Un-named structure */
       {
         ...
         int val1, val2, val3; /* Values 1-3 */
      @@ -1388,6 +1397,18 @@ struct xyz_information
                 bitc : 1;  /* Bit C */
         ...
       };
      +
      +struct abc_s
      +{
      +  ...
      +  struct
      +  {
      +    int a;           /* Value A */
      +    int b;           /* Value B */
      +    int c;           /* Value C */
      +  };                 /* Un-named structure field */
      +  ...
      +};
       
    @@ -1396,23 +1417,35 @@ struct xyz_information struct xyz_info_s { ... - int val1; /* Value 1. */ - int val2; /* Value 2. */ - int val3; /* Value 3. */ + int val1; /* Value 1 */ + int val2; /* Value 2 */ + int val3; /* Value 3 */ ... };
    -typdef struct xyz_info_s xzy_info_t;
    +typedef struct xyz_info_s xzy_info_t;
     

    (The use of typedef'ed structures is acceptable but discouraged)

     struct xyz_info_s
     {
       ...
    -  uint8_t bita : 1,  /* Bit A. */
    -  uint8_t bitb : 1,  /* Bit B. */
    -  uint8_t bitc : 1,  /* Bit C. */
    +  uint8_t bita : 1,  /* Bit A */
    +  uint8_t bitb : 1,  /* Bit B */
    +  uint8_t bitc : 1,  /* Bit C */
    +  ...
    +};
    +
    +struct abc_s
    +{
    +  ...
    +  struct
    +  {
    +    int a;           /* Value A */
    +    int b;           /* Value B */
    +    int c;           /* Value C */
    +  } abc;
       ...
     };
     
    @@ -1433,13 +1466,18 @@ struct xyz_info_s

    Example

      -union xyz_union_u
      +union xyz_union_u  /* All unions must be named */
       {
      -  uint8_t  b[4]; /* Byte values. */
      -  uint16_t h[2]; /* Half word values. */
      -  uint32_t w;    /* Word Value. */
      +  uint8_t  b[4];   /* Byte values. */
      +  uint16_t h[2];   /* Half word values. */
      +  uint32_t w;      /* Word Value. */
       };
      -
      +
      +
      +typedef union xyz_union_u xzy_union_t;
      +
      +

      (The use of typedef'ed unions is acceptable but discouraged)

      +
       struct xyz_info_s
       {
         ...
      @@ -1448,7 +1486,7 @@ struct xyz_info_s
           uint8_t  b[4]; /* Byte values. */
           uint16_t h[2]; /* Half word values. */
           uint32_t w;    /* Word Value. */
      -  } u;
      +  } u;             /* All union fields must be named */
         ...
       };
       
    @@ -1456,9 +1494,9 @@ struct xyz_info_s

    NOTE: - Note that the union name u is used often. + Note that the union fields within structures are often named u. This is another exception to the prohibition against using single character variable and field names. - The short field name u clearly identifies a union field and prevents the full name to the union value from being excessively long. + The short field name u clearly identifies a union field and prevents the full name of the union value from being excessively long.

    2.7 Enumerations

    -- GitLab From 0ef4e37c9e3074e954c3c669649fa094f017e714 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 17 Apr 2017 14:28:19 -0600 Subject: [PATCH 488/990] Upate some comments. --- configs/stm32f0discovery/include/board.h | 17 +++++++++++------ 1 file changed, 11 insertions(+), 6 deletions(-) diff --git a/configs/stm32f0discovery/include/board.h b/configs/stm32f0discovery/include/board.h index e2ca4de903..b5c66a2b41 100644 --- a/configs/stm32f0discovery/include/board.h +++ b/configs/stm32f0discovery/include/board.h @@ -89,11 +89,16 @@ * * Resulting SYSCLK frequency is 8MHz x 12 / 2 = 48MHz * - * USB/SDIO: - * If the USB or SDIO interface is used in the application, the PLL VCO - * clock (defined by STM32F0_CFGR_PLLMUL) must be programmed to output a 96 - * MHz frequency. This is required to provide a 48 MHz clock to the USB or - * SDIO (SDIOCLK or USBCLK = PLLVCO/2). + * USB: + * If the USB interface is used in the application, it requires a precise + * 48MHz clock which can be generated from either the (1) the internal + * main PLL with the HSE clock source using an HSE crystal oscillator. In + * this case, the PLL VCO clock (defined by STM32F0_CFGR_PLLMUL) must be + * programmed to output a 96 MHz frequency. This is required to provide a + * 48MHz clock to the (USBCLK = PLLVCO/2). Or (2) by using the internal + * 48MHz oscillator in automatic trimming mode. The synchronization for + * this oscillator can be taken from the USB data stream itself (SOF + * signalization) which allows crystal-less operation. * SYSCLK * The system clock is derived from the PLL VCO divided by the output division factor. * Limitations: @@ -120,7 +125,7 @@ * frequency (STM32F0_PLL_FREQUENCY divided by the PLLDIV value). */ -#define STM32F0_SYSCLK_SW RCC_CFGR_SW_PLL /* Use the PLL as the SYSCLK */ +#define STM32F0_SYSCLK_SW RCC_CFGR_SW_PLL /* Use the PLL as the SYSCLK */ #define STM32F0_SYSCLK_SWS RCC_CFGR_SWS_PLL #ifdef CONFIG_STM32F0_USB # define STM32F0_SYSCLK_FREQUENCY STM32F0_PLL_FREQUENCY /* SYSCLK frequency is PLL VCO = 48MHz */ -- GitLab From 2c01aaad595416a45d1887c171865e8919d56b4f Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 17 Apr 2017 16:54:07 -0600 Subject: [PATCH 489/990] STM32F0: Add basic support for STM32F07x family --- arch/arm/include/stm32f0/chip.h | 116 ++++- ...stm32f05xr_pinmap.h => stm32f05x_pinmap.h} | 70 +-- ..._memorymap.h => stm32f05xf07x_memorymap.h} | 10 +- arch/arm/src/stm32f0/chip/stm32f07x_pinmap.h | 400 ++++++++++++++++++ arch/arm/src/stm32f0/chip/stm32f0_memorymap.h | 4 +- arch/arm/src/stm32f0/chip/stm32f0_pinmap.h | 2 +- configs/stm32f0discovery/include/board.h | 14 +- 7 files changed, 556 insertions(+), 60 deletions(-) rename arch/arm/src/stm32f0/chip/{stm32f05xr_pinmap.h => stm32f05x_pinmap.h} (59%) rename arch/arm/src/stm32f0/chip/{stm32f05xxx_memorymap.h => stm32f05xf07x_memorymap.h} (96%) create mode 100644 arch/arm/src/stm32f0/chip/stm32f07x_pinmap.h diff --git a/arch/arm/include/stm32f0/chip.h b/arch/arm/include/stm32f0/chip.h index 754cfce616..1c980b851e 100644 --- a/arch/arm/include/stm32f0/chip.h +++ b/arch/arm/include/stm32f0/chip.h @@ -51,22 +51,116 @@ #if defined(CONFIG_ARCH_CHIP_STM32F051R8) # define STM32F051x 1 /* STM32F051x family */ +# undef STM32F072x /* Not STM32F072x family */ + # define STM32F0_FLASH_SIZE (64*1024) /* 64Kb */ # define STM32F0_SRAM_SIZE (8*1024) /* 8Kb */ -# define STM32F0_CPUSRAM_SIZE (8*1024) -# undef STM32F0_HAVE_BANK0 /* No AHB SRAM bank 0 */ -# undef STM32F0_HAVE_BANK1 /* No AHB SRAM bank 1 */ -# define STM32F0_NETHCONTROLLERS 0 /* No Ethernet controller */ -# define STM32F0_NUSBHOST 0 /* No USB host controller */ -# define STM32F0_NUSBOTG 0 /* No USB OTG controller */ + +# define STM32F0_NSPI 2 /* Two SPI modules (SPI or I2S) */ +# define STM32F0_NI2S 2 /* Two I2S modules (SPI or I2S) */ +# define STM32F0_NI2C 2 /* Two I2C modules */ +# define STM32F0_NUSART 2 /* Two USARTs modules */ +# define STM32F0_NCAN 0 /* No CAN controllers */ +# define STM32F0_NUSBDEV 1 /* One USB device controller */ +# define STM32F0_NDAC 1 /* One DAC module */ +# define STM32F0_NDACCHAN 1 /* One DAC channels */ +# define STM32F0_NCOMP 2 /* Two Analog Comparators */ +# define STM32F0_NCAP 13 /* Capacitive sensing channels (14 on UFQFPN32)) */ +# define STM32F0_NPORTS 6 /* Six GPIO ports, GPIOA-F */ + +#if defined(CONFIG_ARCH_CHIP_SSTM32F072C8) || defined(CONFIG_ARCH_CHIP_SSTM32F072CB) +# undef STM32F051x /* Not STM32F051x family */ +# define STM32F072x 1 /* STM32F072x family */ + +# ifdef CONFIG_ARCH_CHIP_SSTM32F072C8 +# define STM32F0_FLASH_SIZE (64*1024) /* 64Kb */ +# else +# define STM32F0_FLASH_SIZE (128*1024) /* 128Kb */ +# endif +# define STM32F0_SRAM_SIZE (16*1024) /* 16Kb */ + +# define STM32F0_NATIM 1 /* One advanced timer TIM1 */ +# define STM32F0_NGTIM16 5 /* 16-bit general up/down timers TIM3, TIM14-17 */ +# define STM32F0_NGTIM32 1 /* 32-bit general up/down timers TIM2 */ +# define STM32F0_NBTIM 2 /* 2 basic timers: TIM6, TIM7 */ +# define STM32F0_NSPI 2 /* Two SPI modules (SPI or I2S) */ +# define STM32F0_NI2S 2 /* Two I2S modules (SPI or I2S) */ +# define STM32F0_NI2C 2 /* Two I2C modules */ +# define STM32F0_NUSART 4 /* Four USARTs module */ +# define STM32F0_NCAN 1 /* One CAN controller */ +# define STM32F0_NUSBDEV 1 /* One USB device controller */ +# deifne STM32F0_NCEC 1 /* One HDMI-CEC controller */ +# define STM32F0_NADC16 1 /* One 16-bit module */ +# define STM32F0_NADCCHAN 10 /* Ten external channels */ +# define STM32F0_NADCEXT 3 /* Three external channels */ +# define STM32F0_NDAC 1 /* One DAC module */ +# define STM32F0_NDACCHAN 2 /* Two DAC channels */ +# define STM32F0_NCOMP 2 /* Two Analog Comparators */ +# define STM32F0_NCAP 17 /* Capacitive sensing channels */ +# define STM32F0_NPORTS 6 /* Six GPIO ports, GPIOA-F */ + +#if defined(CONFIG_ARCH_CHIP_SSTM32F072R8) || defined(CONFIG_ARCH_CHIP_SSTM32F072RB) +# undef STM32F051x /* Not STM32F051x family */ +# define STM32F072x 1 /* STM32F072x family */ + +# ifdef CONFIG_ARCH_CHIP_SSTM32F072C8 +# define STM32F0_FLASH_SIZE (64*1024) /* 64Kb */ +# else +# define STM32F0_FLASH_SIZE (128*1024) /* 128Kb */ +# endif +# define STM32F0_SRAM_SIZE (16*1024) /* 16Kb */ + +# define STM32F0_NATIM 1 /* One advanced timer TIM1 */ +# define STM32F0_NGTIM16 5 /* 16-bit general up/down timers TIM3, TIM14-17 */ +# define STM32F0_NGTIM32 1 /* 32-bit general up/down timers TIM2 */ +# define STM32F0_NBTIM 2 /* 2 basic timers: TIM6, TIM7 */ +# define STM32F0_NSPI 2 /* Two SPI modules (SPI or I2S) */ +# define STM32F0_NI2S 2 /* Two I2S modules (SPI or I2S) */ +# define STM32F0_NI2C 2 /* Two I2C modules */ +# define STM32F0_NUSART 4 /* Four USARTs module */ +# define STM32F0_NCAN 1 /* One CAN controller */ # define STM32F0_NUSBDEV 1 /* One USB device controller */ -# define STM32F0_NUSART 2 /* Two USARTs module */ -# define STM32F0_NPORTS 6 /* 6 GPIO ports, GPIOA-F */ +# deifne STM32F0_NCEC 1 /* One HDMI-CEC controller */ +# define STM32F0_NADC16 1 /* One 16-bit module */ +# define STM32F0_NADCCHAN 16 /* 16 external channels */ +# define STM32F0_NADCEXT 3 /* Three external channels */ +# define STM32F0_NDAC 1 /* One DAC module */ +# define STM32F0_NDACCHAN 2 /* Two DAC channels */ +# define STM32F0_NCOMP 2 /* Two Analog Comparators */ +# define STM32F0_NCAP 18 /* Capacitive sensing channels */ +# define STM32F0_NPORTS 6 /* Six GPIO ports, GPIOA-F */ + +#if defined(CONFIG_ARCH_CHIP_SSTM32F072V8) || defined(CONFIG_ARCH_CHIP_SSTM32F072VB) +# undef STM32F051x /* Not STM32F051x family */ +# define STM32F072x 1 /* STM32F072x family */ + +# ifdef CONFIG_ARCH_CHIP_SSTM32F072C8 +# define STM32F0_FLASH_SIZE (64*1024) /* 64Kb */ +# else +# define STM32F0_FLASH_SIZE (128*1024) /* 128Kb */ +# endif +# define STM32F0_SRAM_SIZE (16*1024) /* 16Kb */ + +# define STM32F0_NATIM 1 /* One advanced timer TIM1 */ +# define STM32F0_NGTIM16 5 /* 16-bit general up/down timers TIM3, TIM14-17 */ +# define STM32F0_NGTIM32 1 /* 32-bit general up/down timers TIM2 */ +# define STM32F0_NBTIM 2 /* 2 basic timers: TIM6, TIM7 */ +# define STM32F0_NSPI 2 /* Two SPI modules (SPI or I2S) */ +# define STM32F0_NI2S 2 /* Two I2S modules (SPI or I2S) */ +# define STM32F0_NI2C 2 /* Two I2C modules */ +# define STM32F0_NUSART 4 /* Four USARTs module */ # define STM32F0_NCAN 1 /* One CAN controller */ -# define STM32F0_NI2C 2 /* Two I2C module */ -# define STM32F0_NI2S 1 /* One I2S module */ +# define STM32F0_NUSBDEV 1 /* One USB device controller */ +# deifne STM32F0_NCEC 1 /* One HDMI-CEC controller */ +# define STM32F0_NADC16 1 /* One 16-bit module */ +# define STM32F0_NADCCHAN 16 /* 16 external channels */ +# define STM32F0_NADCEXT 3 /* Three external channels */ # define STM32F0_NDAC 1 /* One DAC module */ -# define STM32F0_NSPI 2 /* Two DAC module */ +# define STM32F0_NDACCHAN 2 /* Two DAC channels */ +# define STM32F0_NCOMP 2 /* Two Analog Comparators */ +# define STM32F0_NCAP 24 /* Capacitive sensing channels */ +# define STM32F0_NPORTS 6 /* Six GPIO ports, GPIOA-F */ + #else # error "Unsupported STM32F0xx chip" #endif diff --git a/arch/arm/src/stm32f0/chip/stm32f05xr_pinmap.h b/arch/arm/src/stm32f0/chip/stm32f05x_pinmap.h similarity index 59% rename from arch/arm/src/stm32f0/chip/stm32f05xr_pinmap.h rename to arch/arm/src/stm32f0/chip/stm32f05x_pinmap.h index 63b2c51f0b..9bf1a3aa30 100644 --- a/arch/arm/src/stm32f0/chip/stm32f05xr_pinmap.h +++ b/arch/arm/src/stm32f0/chip/stm32f05x_pinmap.h @@ -1,5 +1,5 @@ /************************************************************************************ - * arch/arm/src/stm32f0/chip/stm32f0_pinmap.h + * arch/arm/src/stm32f0/chip/stm32f05x_pinmap.h * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -34,8 +34,8 @@ * ************************************************************************************/ -#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_PINMMAP_H -#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_PINMMAP_H +#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F05X_PINMAP_H +#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F05X_PINMAP_H /************************************************************************************ * Included Files @@ -75,53 +75,53 @@ /* USART */ #if defined(CONFIG_STM32F0_USART1_REMAP) -# define GPIO_USART1_TX (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN6) -# define GPIO_USART1_RX (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN7) +# define GPIO_USART1_TX (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN6) +# define GPIO_USART1_RX (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN7) #else -# define GPIO_USART1_TX (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN9) -# define GPIO_USART1_RX (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN10) +# define GPIO_USART1_TX (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN9) +# define GPIO_USART1_RX (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN10) #endif -#define GPIO_USART1_CTS (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN11) -#define GPIO_USART1_RTS (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN12) -#define GPIO_USART1_CK (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN8) +#define GPIO_USART1_CTS (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN11) +#define GPIO_USART1_RTS (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN12) +#define GPIO_USART1_CK (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN8) -#define GPIO_USART2_CTS (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN0) -#define GPIO_USART2_RTS (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN1) -#define GPIO_USART2_TX (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN2) -#define GPIO_USART2_RX (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN3) -#define GPIO_USART2_CK (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN4) +#define GPIO_USART2_CTS (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN0) +#define GPIO_USART2_RTS (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN1) +#define GPIO_USART2_TX (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN2) +#define GPIO_USART2_RX (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN3) +#define GPIO_USART2_CK (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN4) /* SPI */ #if defined(CONFIG_STM32F0_SPI1_REMAP) -# define GPIO_SPI1_NSS (GPIO_ALT|GPIO_AF0 |GPIO_PORTA|GPIO_PIN15) -# define GPIO_SPI1_SCK (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN3) -# define GPIO_SPI1_MISO (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN4) -# define GPIO_SPI1_MOSI (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN5) +# define GPIO_SPI1_NSS (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN15) +# define GPIO_SPI1_SCK (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN3) +# define GPIO_SPI1_MISO (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN4) +# define GPIO_SPI1_MOSI (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN5) #else -# define GPIO_SPI1_NSS (GPIO_ALT|GPIO_AF0 |GPIO_PORTA|GPIO_PIN4) -# define GPIO_SPI1_SCK (GPIO_ALT|GPIO_AF0 |GPIO_PORTA|GPIO_PIN5) -# define GPIO_SPI1_MISO (GPIO_ALT|GPIO_AF0 |GPIO_PORTA|GPIO_PIN6) -# define GPIO_SPI1_MOSI (GPIO_ALT|GPIO_AF0 |GPIO_PORTA|GPIO_PIN7) +# define GPIO_SPI1_NSS (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN4) +# define GPIO_SPI1_SCK (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN5) +# define GPIO_SPI1_MISO (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN6) +# define GPIO_SPI1_MOSI (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN7) #endif -#define GPIO_SPI2_NSS (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN12) -#define GPIO_SPI2_SCK (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN13) -#define GPIO_SPI2_MISO (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN14) -#define GPIO_SPI2_MOSI (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN15) +#define GPIO_SPI2_NSS (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN12) +#define GPIO_SPI2_SCK (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN13) +#define GPIO_SPI2_MISO (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN14) +#define GPIO_SPI2_MOSI (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN15) /* I2C */ #if defined(CONFIG_STM32F0_I2C1_REMAP) -# define GPIO_I2C1_SCL (GPIO_ALT|GPIO_AF1 |GPIO_PORTB|GPIO_PIN8) -# define GPIO_I2C1_SDA (GPIO_ALT|GPIO_AF1 |GPIO_PORTB|GPIO_PIN9) +# define GPIO_I2C1_SCL (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN8) +# define GPIO_I2C1_SDA (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN9) #else -# define GPIO_I2C1_SCL (GPIO_ALT|GPIO_AF1 |GPIO_PORTB|GPIO_PIN6) -# define GPIO_I2C1_SDA (GPIO_ALT|GPIO_AF1 |GPIO_PORTB|GPIO_PIN7) +# define GPIO_I2C1_SCL (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN6) +# define GPIO_I2C1_SDA (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN7) #endif -#define GPIO_I2C1_SMBA (GPIO_ALT|GPIO_AF3 |GPIO_PORTB|GPIO_PIN5) +#define GPIO_I2C1_SMBA (GPIO_ALT|GPIO_AF3|GPIO_PORTB|GPIO_PIN5) -#define GPIO_I2C2_SCL (GPIO_ALT|GPIO_AF1 |GPIO_PORTB|GPIO_PIN10) -#define GPIO_I2C2_SDA (GPIO_ALT|GPIO_AF1 |GPIO_PORTB|GPIO_PIN11) +#define GPIO_I2C2_SCL (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN10) +#define GPIO_I2C2_SDA (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN11) -#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_PINMMAP_H */ +#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F05X_PINMAP_H */ diff --git a/arch/arm/src/stm32f0/chip/stm32f05xxx_memorymap.h b/arch/arm/src/stm32f0/chip/stm32f05xf07x_memorymap.h similarity index 96% rename from arch/arm/src/stm32f0/chip/stm32f05xxx_memorymap.h rename to arch/arm/src/stm32f0/chip/stm32f05xf07x_memorymap.h index fc85a81fd7..178773b087 100644 --- a/arch/arm/src/stm32f0/chip/stm32f05xxx_memorymap.h +++ b/arch/arm/src/stm32f0/chip/stm32f05xf07x_memorymap.h @@ -1,5 +1,5 @@ /************************************************************************************ - * arch/arm/src/stm32f0/chip/stm32f05xxx_memorymap.h + * arch/arm/src/stm32f0/chip/stm32f05xf07x_memorymap.h * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -34,14 +34,14 @@ * ************************************************************************************/ -#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F05XXX_MEMORYMAP_H -#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F05XXX_MEMORYMAP_H +#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_ST32F05XF07X_MEMORYMAP_H +#define __ARCH_ARM_SRC_STM32F0_CHIP_ST32F05XF07X_MEMORYMAP_H /************************************************************************************ * Pre-processor Definitions ************************************************************************************/ -/* STM32F050XXX Address Blocks *******************************************************/ +/* ST32F05XF07X Address Blocks ******************************************************/ #define STM32F0_CODE_BASE 0x00000000 /* 0x00000000-0x1fffffff: 512Mb code block */ #define STM32F0_SRAM_BASE 0x20000000 /* 0x20000000-0x3fffffff: 512Mb sram block */ @@ -154,4 +154,4 @@ #define STM32F0_SCS_BASE 0xe000e000 #define STM32F0_DEBUGMCU_BASE 0xe0042000 -#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F30XXX_MEMORYMAP_H */ +#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_ST32F05XF07X_MEMORYMAP_H */ diff --git a/arch/arm/src/stm32f0/chip/stm32f07x_pinmap.h b/arch/arm/src/stm32f0/chip/stm32f07x_pinmap.h new file mode 100644 index 0000000000..85beb6b326 --- /dev/null +++ b/arch/arm/src/stm32f0/chip/stm32f07x_pinmap.h @@ -0,0 +1,400 @@ +/************************************************************************************ + * arch/arm/src/stm32f0/chip/stm32f07x_pinmap.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Alan Carvalho de Assis + * + * 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 __ARCH_ARM_SRC_STM32F0_CHIP_STM32F07X_PINMAP_H +#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F07X_PINMAP_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include "stm32f0_gpio.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* Alternate Pin Functions. + * + * Alternative pin selections are provided with a numeric suffix like _1, _2, etc. + * Drivers, however, will use the pin selection without the numeric suffix. + * Additional definitions are required in the board.h file. For example, if + * CAN1_RX connects vis PD0 on some board, then the following definition should + * appear inthe board.h header file for that board: + * + * #define GPIO_CAN1_RX GPIO_CAN1_RX_1 + * + * The driver will then automatically configre PD0 as the CAN1 RX pin. + */ + +/* WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!! + * Additional effort is required to select specific GPIO options such as frequency, + * open-drain/push-pull, and pull-up/down! Just the basics are defined for most + * pins in this file. + */ + +/* ADC */ + +#define GPIO_ADC_IN0 (GPIO_ANALOG | GPIO_PORTA | GPIO_PIN0) +#define GPIO_ADC_IN1 (GPIO_ANALOG | GPIO_PORTA | GPIO_PIN1) +#define GPIO_ADC_IN2 (GPIO_ANALOG | GPIO_PORTA | GPIO_PIN2) +#define GPIO_ADC_IN3 (GPIO_ANALOG | GPIO_PORTA | GPIO_PIN3) +#define GPIO_ADC_IN4 (GPIO_ANALOG | GPIO_PORTA | GPIO_PIN4) +#define GPIO_ADC_IN5 (GPIO_ANALOG | GPIO_PORTA | GPIO_PIN5) +#define GPIO_ADC_IN6 (GPIO_ANALOG | GPIO_PORTA | GPIO_PIN6) +#define GPIO_ADC_IN7 (GPIO_ANALOG | GPIO_PORTA | GPIO_PIN7) +#define GPIO_ADC_IN8 (GPIO_ANALOG | GPIO_PORTB | GPIO_PIN0) +#define GPIO_ADC_IN9 (GPIO_ANALOG | GPIO_PORTB | GPIO_PIN1) +#define GPIO_ADC_IN10 (GPIO_ANALOG | GPIO_PORTC | GPIO_PIN0) +#define GPIO_ADC_IN11 (GPIO_ANALOG | GPIO_PORTC | GPIO_PIN1) +#define GPIO_ADC_IN12 (GPIO_ANALOG | GPIO_PORTC | GPIO_PIN2) +#define GPIO_ADC_IN13 (GPIO_ANALOG | GPIO_PORTC | GPIO_PIN3) +#define GPIO_ADC_IN14 (GPIO_ANALOG | GPIO_PORTC | GPIO_PIN4) +#define GPIO_ADC_IN15 (GPIO_ANALOG | GPIO_PORTC | GPIO_PIN5) + +/* CAN */ + +#define GPIO_CAN_RX_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTD | GPIO_PIN0) +#define GPIO_CAN_RX_2 (GPIO_ALT | GPIO_AF4 | GPIO_PORTA | GPIO_PIN11) +#define GPIO_CAN_RX_3 (GPIO_ALT | GPIO_AF4 | GPIO_PORTB | GPIO_PIN8) +#define GPIO_CAN_TX_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTD | GPIO_PIN1) +#define GPIO_CAN_TX_3 (GPIO_ALT | GPIO_AF4 | GPIO_PORTA | GPIO_PIN12) +#define GPIO_CAN_TX_4 (GPIO_ALT | GPIO_AF4 | GPIO_PORTB | GPIO_PIN9) + +/* HDMI-CEC */ + +#define GPIO_CEC_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN10) +#define GPIO_CEC_2 (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN8) +#define GPIO_CEC_3 (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN5) + +/* Analog Comparators */ + +#define GPIO_COMP1_OUT_1 (GPIO_ALT | GPIO_AF7 | GPIO_PORTA | GPIO_PIN0) +#define GPIO_COMP1_OUT_2 (GPIO_ALT | GPIO_AF7 | GPIO_PORTA | GPIO_PIN11) +#define GPIO_COMP1_OUT_3 (GPIO_ALT | GPIO_AF7 | GPIO_PORTA | GPIO_PIN6) + +#define GPIO_COMP2_OUT_1 (GPIO_ALT | GPIO_AF7 | GPIO_PORTA | GPIO_PIN12) +#define GPIO_COMP2_OUT_2 (GPIO_ALT | GPIO_AF7 | GPIO_PORTA | GPIO_PIN2) +#define GPIO_COMP2_OUT_3 (GPIO_ALT | GPIO_AF7 | GPIO_PORTA | GPIO_PIN7) + +/* CRS */ + +#define GPIO_CRS_SYNC_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTD | GPIO_PIN15) +#define GPIO_CRS_SYNC_2 (GPIO_ALT | GPIO_AF0 | GPIO_PORTF | GPIO_PIN0) +#define GPIO_CRS_SYNC_3 (GPIO_ALT | GPIO_AF4 | GPIO_PORTA | GPIO_PIN8) + +/* Events */ + +#define GPIO_EVENTOUT_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN1) +#define GPIO_EVENTOUT_2 (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN11) +#define GPIO_EVENTOUT_3 (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN12) +#define GPIO_EVENTOUT_4 (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN0) +#define GPIO_EVENTOUT_5 (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN11) +#define GPIO_EVENTOUT_6 (GPIO_ALT | GPIO_AF0 | GPIO_PORTC | GPIO_PIN0) +#define GPIO_EVENTOUT_7 (GPIO_ALT | GPIO_AF0 | GPIO_PORTC | GPIO_PIN1) +#define GPIO_EVENTOUT_8 (GPIO_ALT | GPIO_AF0 | GPIO_PORTC | GPIO_PIN2) +#define GPIO_EVENTOUT_9 (GPIO_ALT | GPIO_AF0 | GPIO_PORTC | GPIO_PIN3) +#define GPIO_EVENTOUT_10 (GPIO_ALT | GPIO_AF0 | GPIO_PORTC | GPIO_PIN4) +#define GPIO_EVENTOUT_11 (GPIO_ALT | GPIO_AF0 | GPIO_PORTF | GPIO_PIN2) +#define GPIO_EVENTOUT_12 (GPIO_ALT | GPIO_AF0 | GPIO_PORTF | GPIO_PIN3) +#define GPIO_EVENTOUT_13 (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN12) +#define GPIO_EVENTOUT_14 (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN3) +#define GPIO_EVENTOUT_15 (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN0) +#define GPIO_EVENTOUT_16 (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN1) +#define GPIO_EVENTOUT_17 (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN4) +#define GPIO_EVENTOUT_18 (GPIO_ALT | GPIO_AF3 | GPIO_PORTA | GPIO_PIN15) +#define GPIO_EVENTOUT_19 (GPIO_ALT | GPIO_AF3 | GPIO_PORTA | GPIO_PIN8) +#define GPIO_EVENTOUT_10 (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN9) +#define GPIO_EVENTOUT_21 (GPIO_ALT | GPIO_AF6 | GPIO_PORTA | GPIO_PIN6) +#define GPIO_EVENTOUT_22 (GPIO_ALT | GPIO_AF6 | GPIO_PORTA | GPIO_PIN7) + +/* I2C */ + +#define GPIO_I2C1_SCL_1 (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN6) +#define GPIO_I2C1_SCL_2 (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN8) +#define GPIO_I2C1_SDA_1 (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN7) +#define GPIO_I2C1_SDA_2 (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN9) +#define GPIO_I2C1_SMBA (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN5) + +#define GPIO_I2C2_SCL_1 (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN10) +#define GPIO_I2C2_SCL_2 (GPIO_ALT | GPIO_AF5 | GPIO_PORTB | GPIO_PIN13) +#define GPIO_I2C2_SDA_1 (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN11) +#define GPIO_I2C2_SDA_2 (GPIO_ALT | GPIO_AF5 | GPIO_PORTB | GPIO_PIN14) + +/* I2S */ + +#define GPIO_I2S1_CK_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN5) +#define GPIO_I2S1_CK_2 (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN3) +#define GPIO_I2S1_CK_3 (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN13) +#define GPIO_I2S1_MCK_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN6) +#define GPIO_I2S1_MCK_2 (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN4) +#define GPIO_I2S1_MCK_3 (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN14) +#define GPIO_I2S1_SD_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN7) +#define GPIO_I2S1_SD_2 (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN5) +#define GPIO_I2S1_SD_3 (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN15) +#define GPIO_I2S1_WS_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN15) +#define GPIO_I2S1_WS_2 (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN4) +#define GPIO_I2S1_WS_3 (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN12) + +#define GPIO_I2S2_CK_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN13) +#define GPIO_I2S2_CK_2 (GPIO_ALT | GPIO_AF1 | GPIO_PORTD | GPIO_PIN1) +#define GPIO_I2S2_CK_3 (GPIO_ALT | GPIO_AF5 | GPIO_PORTB | GPIO_PIN10) +#define GPIO_I2S2_MCK_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN14) +#define GPIO_I2S2_MCK_2 (GPIO_ALT | GPIO_AF1 | GPIO_PORTC | GPIO_PIN2) +#define GPIO_I2S2_MCK_3 (GPIO_ALT | GPIO_AF1 | GPIO_PORTD | GPIO_PIN3) +#define GPIO_I2S2_SD_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN15) +#define GPIO_I2S2_SD_2 (GPIO_ALT | GPIO_AF1 | GPIO_PORTC | GPIO_PIN3) +#define GPIO_I2S2_SD_3 (GPIO_ALT | GPIO_AF1 | GPIO_PORTD | GPIO_PIN4) +#define GPIO_I2S2_WS_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN12) +#define GPIO_I2S2_WS_2 (GPIO_ALT | GPIO_AF1 | GPIO_PORTD | GPIO_PIN0) +#define GPIO_I2S2_WS_3 (GPIO_ALT | GPIO_AF5 | GPIO_PORTB | GPIO_PIN9) + +/* IR */ + +#define GPIO_IR_OUT_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN9) +#define GPIO_IR_OUT_2 (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN13) + +/* Clock output */ + +#define GPIO_MCO (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN8) + +/* SPI */ + +#define GPIO_SPI1_MISO_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN6) +#define GPIO_SPI1_MISO_2 (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN4) +#define GPIO_SPI1_MISO_3 (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN14) +#define GPIO_SPI1_MOSI_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN7) +#define GPIO_SPI1_MOSI_2 (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN5) +#define GPIO_SPI1_MOSI_3 (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN15) +#define GPIO_SPI1_NSS_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN15) +#define GPIO_SPI1_NSS_2 (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN4) +#define GPIO_SPI1_NSS_3 (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN12) +#define GPIO_SPI1_SCK_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN5) +#define GPIO_SPI1_SCK_2 (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN3) +#define GPIO_SPI1_SCK_3 (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN13) + +#define GPIO_SPI2_MISO_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN14) +#define GPIO_SPI2_MISO_2 (GPIO_ALT | GPIO_AF1 | GPIO_PORTC | GPIO_PIN2) +#define GPIO_SPI2_MISO_3 (GPIO_ALT | GPIO_AF1 | GPIO_PORTD | GPIO_PIN3) +#define GPIO_SPI2_MOSI_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN15) +#define GPIO_SPI2_MOSI_2 (GPIO_ALT | GPIO_AF1 | GPIO_PORTC | GPIO_PIN3) +#define GPIO_SPI2_MOSI_3 (GPIO_ALT | GPIO_AF1 | GPIO_PORTD | GPIO_PIN4) +#define GPIO_SPI2_NSS_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN12) +#define GPIO_SPI2_NSS_2 (GPIO_ALT | GPIO_AF1 | GPIO_PORTD | GPIO_PIN0) +#define GPIO_SPI2_NSS_3 (GPIO_ALT | GPIO_AF5 | GPIO_PORTB | GPIO_PIN9) +#define GPIO_SPI2_SCK_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN13) +#define GPIO_SPI2_SCK_2 (GPIO_ALT | GPIO_AF1 | GPIO_PORTD | GPIO_PIN1) +#define GPIO_SPI2_SCK_3 (GPIO_ALT | GPIO_AF5 | GPIO_PORTB | GPIO_PIN10) + +/* SWD */ + +#define GPIO_SWCLK (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN14) +#define GPIO_SWDIO (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN13) + +/* Timers */ + +#define GPIO_TIM1_BKIN_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN15) +#define GPIO_TIM1_BKIN_2 (GPIO_ALT | GPIO_AF2 | GPIO_PORTA | GPIO_PIN6) +#define GPIO_TIM1_BKIN_3 (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN12) +#define GPIO_TIM1_CH1_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN9) +#define GPIO_TIM1_CH1_2 (GPIO_ALT | GPIO_AF2 | GPIO_PORTA | GPIO_PIN8) +#define GPIO_TIM1_CH1N_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN8) +#define GPIO_TIM1_CH1N_2 (GPIO_ALT | GPIO_AF2 | GPIO_PORTA | GPIO_PIN7) +#define GPIO_TIM1_CH1N_3 (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN13) +#define GPIO_TIM1_CH2_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN11) +#define GPIO_TIM1_CH2_2 (GPIO_ALT | GPIO_AF2 | GPIO_PORTA | GPIO_PIN9) +#define GPIO_TIM1_CH2N_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN10) +#define GPIO_TIM1_CH2N_2 (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN0) +#define GPIO_TIM1_CH2N_3 (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN14) +#define GPIO_TIM1_CH3_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN13) +#define GPIO_TIM1_CH3_2 (GPIO_ALT | GPIO_AF2 | GPIO_PORTA | GPIO_PIN10) +#define GPIO_TIM1_CH3N_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN12) +#define GPIO_TIM1_CH3N_2 (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN1) +#define GPIO_TIM1_CH3N_3 (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN15) +#define GPIO_TIM1_CH4_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN14) +#define GPIO_TIM1_CH4_2 (GPIO_ALT | GPIO_AF2 | GPIO_PORTA | GPIO_PIN11) +#define GPIO_TIM1_ETR_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN7) +#define GPIO_TIM1_ETR_2 (GPIO_ALT | GPIO_AF2 | GPIO_PORTA | GPIO_PIN12) + +#define GPIO_TIM2_CH1_ETR_1 (GPIO_ALT | GPIO_AF2 | GPIO_PORTA | GPIO_PIN0) +#define GPIO_TIM2_CH1_ETR_2 (GPIO_ALT | GPIO_AF2 | GPIO_PORTA | GPIO_PIN15) +#define GPIO_TIM2_CH1_ETR_3 (GPIO_ALT | GPIO_AF2 | GPIO_PORTA | GPIO_PIN5) +#define GPIO_TIM2_CH2_1 (GPIO_ALT | GPIO_AF2 | GPIO_PORTA | GPIO_PIN1) +#define GPIO_TIM2_CH2_2 (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN3) +#define GPIO_TIM2_CH3_1 (GPIO_ALT | GPIO_AF2 | GPIO_PORTA | GPIO_PIN2) +#define GPIO_TIM2_CH3_2 (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN10) +#define GPIO_TIM2_CH4_1 (GPIO_ALT | GPIO_AF2 | GPIO_PORTA | GPIO_PIN3) +#define GPIO_TIM2_CH4_2 (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN11) + +#define GPIO_TIM3_CH1_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTC | GPIO_PIN6) +#define GPIO_TIM3_CH1_2 (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN3) +#define GPIO_TIM3_CH1_3 (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN6) +#define GPIO_TIM3_CH1_4 (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN4) +#define GPIO_TIM3_CH2_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTC | GPIO_PIN7) +#define GPIO_TIM3_CH2_2 (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN4) +#define GPIO_TIM3_CH2_3 (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN7) +#define GPIO_TIM3_CH2_4 (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN5) +#define GPIO_TIM3_CH3_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTC | GPIO_PIN8) +#define GPIO_TIM3_CH3_2 (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN5) +#define GPIO_TIM3_CH3_3 (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN0) +#define GPIO_TIM3_CH4_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTC | GPIO_PIN9) +#define GPIO_TIM3_CH4_2 (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN6) +#define GPIO_TIM3_CH4_3 (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN1) +#define GPIO_TIM3_ETR_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTD | GPIO_PIN2) +#define GPIO_TIM3_ETR_2 (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN2) + +#define GPIO_TIM14_CH1_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN1) +#define GPIO_TIM14_CH1_2 (GPIO_ALT | GPIO_AF4 | GPIO_PORTA | GPIO_PIN4) +#define GPIO_TIM14_CH1_3 (GPIO_ALT | GPIO_AF4 | GPIO_PORTA | GPIO_PIN7) + +#define GPIO_TIM15_BKIN_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN9) +#define GPIO_TIM15_BKIN_2 (GPIO_ALT | GPIO_AF5 | GPIO_PORTB | GPIO_PIN12) +#define GPIO_TIM15_CH1_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN2) +#define GPIO_TIM15_CH1_2 (GPIO_ALT | GPIO_AF0 | GPIO_PORTF | GPIO_PIN9) +#define GPIO_TIM15_CH1_3 (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN14) +#define GPIO_TIM15_CH1N_1 (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN15) +#define GPIO_TIM15_CH1N_2 (GPIO_ALT | GPIO_AF5 | GPIO_PORTA | GPIO_PIN1) +#define GPIO_TIM15_CH2_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN3) +#define GPIO_TIM15_CH2_2 (GPIO_ALT | GPIO_AF0 | GPIO_PORTF | GPIO_PIN10) +#define GPIO_TIM15_CH2_3 (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN15) + +#define GPIO_TIM16_BKIN (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN5) +#define GPIO_TIM16_CH1_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN0) +#define GPIO_TIM16_CH1_2 (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN8) +#define GPIO_TIM16_CH1_3 (GPIO_ALT | GPIO_AF5 | GPIO_PORTA | GPIO_PIN6) +#define GPIO_TIM16_CH1N (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN6) + +#define GPIO_TIM17_BKIN_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN10) +#define GPIO_TIM17_BKIN_2 (GPIO_ALT | GPIO_AF5 | GPIO_PORTB | GPIO_PIN4) +#define GPIO_TIM17_CH1_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN1) +#define GPIO_TIM17_CH1_2 (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN9) +#define GPIO_TIM17_CH1_3 (GPIO_ALT | GPIO_AF5 | GPIO_PORTA | GPIO_PIN7) +#define GPIO_TIM17_CH1N (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN7) + +/* TSC */ + +#define GPIO_TSC_G1_IO1 (GPIO_ALT | GPIO_AF3 | GPIO_PORTA | GPIO_PIN0) +#define GPIO_TSC_G1_IO2 (GPIO_ALT | GPIO_AF3 | GPIO_PORTA | GPIO_PIN1) +#define GPIO_TSC_G1_IO3 (GPIO_ALT | GPIO_AF3 | GPIO_PORTA | GPIO_PIN2) +#define GPIO_TSC_G1_IO4 (GPIO_ALT | GPIO_AF3 | GPIO_PORTA | GPIO_PIN3) +#define GPIO_TSC_G2_IO1 (GPIO_ALT | GPIO_AF3 | GPIO_PORTA | GPIO_PIN4) +#define GPIO_TSC_G2_IO2 (GPIO_ALT | GPIO_AF3 | GPIO_PORTA | GPIO_PIN5) +#define GPIO_TSC_G2_IO3 (GPIO_ALT | GPIO_AF3 | GPIO_PORTA | GPIO_PIN6) +#define GPIO_TSC_G2_IO4 (GPIO_ALT | GPIO_AF3 | GPIO_PORTA | GPIO_PIN7) +#define GPIO_TSC_G3_IO1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTC | GPIO_PIN5) +#define GPIO_TSC_G3_IO2 (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN0) +#define GPIO_TSC_G3_IO3 (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN1) +#define GPIO_TSC_G3_IO4 (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN2) +#define GPIO_TSC_G4_IO1 (GPIO_ALT | GPIO_AF3 | GPIO_PORTA | GPIO_PIN9) +#define GPIO_TSC_G4_IO2 (GPIO_ALT | GPIO_AF3 | GPIO_PORTA | GPIO_PIN10) +#define GPIO_TSC_G4_IO3 (GPIO_ALT | GPIO_AF3 | GPIO_PORTA | GPIO_PIN11) +#define GPIO_TSC_G4_IO4 (GPIO_ALT | GPIO_AF3 | GPIO_PORTA | GPIO_PIN12) +#define GPIO_TSC_G5_IO1 (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN3) +#define GPIO_TSC_G5_IO2 (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN4) +#define GPIO_TSC_G5_IO3 (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN6) +#define GPIO_TSC_G5_IO4 (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN7) +#define GPIO_TSC_G6_IO1 (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN11) +#define GPIO_TSC_G6_IO2 (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN12) +#define GPIO_TSC_G6_IO3 (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN13) +#define GPIO_TSC_G6_IO4 (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN14) +#define GPIO_TSC_G7_IO1 (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN2) +#define GPIO_TSC_G7_IO2 (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN3) +#define GPIO_TSC_G7_IO3 (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN4) +#define GPIO_TSC_G7_IO4 (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN5) +#define GPIO_TSC_G8_IO1 (GPIO_ALT | GPIO_AF1 | GPIO_PORTD | GPIO_PIN12) +#define GPIO_TSC_G8_IO2 (GPIO_ALT | GPIO_AF1 | GPIO_PORTD | GPIO_PIN13) +#define GPIO_TSC_G8_IO3 (GPIO_ALT | GPIO_AF1 | GPIO_PORTD | GPIO_PIN14) +#define GPIO_TSC_G8_IO4 (GPIO_ALT | GPIO_AF1 | GPIO_PORTD | GPIO_PIN15) +#define GPIO_TSC_SYNC_1 (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN10) +#define GPIO_TSC_SYNC_1 (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN8) + +/* USARTs */ + +#define GPIO_USART1_CK (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN8) +#define GPIO_USART1_CTS (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN11) +#define GPIO_USART1_RTS (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN12) +#define GPIO_USART1_RX_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN7) +#define GPIO_USART1_RX_2 (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN10) +#define GPIO_USART1_TX_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN6) +#define GPIO_USART1_TX_2 (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN9) + +#define GPIO_USART2_CK_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTD | GPIO_PIN7) +#define GPIO_USART2_CK_2 (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN4) +#define GPIO_USART2_CTS_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTD | GPIO_PIN3) +#define GPIO_USART2_CTS_2 (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN0) +#define GPIO_USART2_RTS_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTD | GPIO_PIN4) +#define GPIO_USART2_RTS_2 (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN1) +#define GPIO_USART2_RX_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTD | GPIO_PIN6) +#define GPIO_USART2_RX_2 (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN15) +#define GPIO_USART2_RX_3 (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN3) +#define GPIO_USART2_TX_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTD | GPIO_PIN5) +#define GPIO_USART2_TX_2 (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN14) +#define GPIO_USART2_TX_3 (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN2) + +#define GPIO_USART3_CK_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTD | GPIO_PIN10) +#define GPIO_USART3_CK_2 (GPIO_ALT | GPIO_AF1 | GPIO_PORTC | GPIO_PIN12) +#define GPIO_USART3_CK_3 (GPIO_ALT | GPIO_AF4 | GPIO_PORTB | GPIO_PIN0) +#define GPIO_USART3_CK_4 (GPIO_ALT | GPIO_AF4 | GPIO_PORTB | GPIO_PIN12) +#define GPIO_USART3_CTS_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTD | GPIO_PIN11) +#define GPIO_USART3_CTS_2 (GPIO_ALT | GPIO_AF4 | GPIO_PORTA | GPIO_PIN6) +#define GPIO_USART3_CTS_3 (GPIO_ALT | GPIO_AF4 | GPIO_PORTB | GPIO_PIN13) +#define GPIO_USART3_RTS_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTD | GPIO_PIN12) +#define GPIO_USART3_RTS_2 (GPIO_ALT | GPIO_AF1 | GPIO_PORTD | GPIO_PIN2) +#define GPIO_USART3_RTS_3 (GPIO_ALT | GPIO_AF4 | GPIO_PORTB | GPIO_PIN1) +#define GPIO_USART3_RTS_4 (GPIO_ALT | GPIO_AF4 | GPIO_PORTB | GPIO_PIN14) +#define GPIO_USART3_RX_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTD | GPIO_PIN9) +#define GPIO_USART3_RX_2 (GPIO_ALT | GPIO_AF1 | GPIO_PORTC | GPIO_PIN11) +#define GPIO_USART3_RX_3 (GPIO_ALT | GPIO_AF1 | GPIO_PORTC | GPIO_PIN5) +#define GPIO_USART3_RX_4 (GPIO_ALT | GPIO_AF4 | GPIO_PORTB | GPIO_PIN11) +#define GPIO_USART3_TX_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTD | GPIO_PIN8) +#define GPIO_USART3_TX_2 (GPIO_ALT | GPIO_AF1 | GPIO_PORTC | GPIO_PIN10) +#define GPIO_USART3_TX_3 (GPIO_ALT | GPIO_AF1 | GPIO_PORTC | GPIO_PIN4) +#define GPIO_USART3_TX_4 (GPIO_ALT | GPIO_AF4 | GPIO_PORTB | GPIO_PIN10) + +#define GPIO_USART4_CK (GPIO_ALT | GPIO_AF0 | GPIO_PORTC | GPIO_PIN12) +#define GPIO_USART4_CTS (GPIO_ALT | GPIO_AF4 | GPIO_PORTB | GPIO_PIN7) +#define GPIO_USART4_RTS (GPIO_ALT | GPIO_AF4 | GPIO_PORTA | GPIO_PIN15) +#define GPIO_USART4_RX_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTC | GPIO_PIN11) +#define GPIO_USART4_RX_2 (GPIO_ALT | GPIO_AF4 | GPIO_PORTA | GPIO_PIN1) +#define GPIO_USART4_TX_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTC | GPIO_PIN10) +#define GPIO_USART4_TX_2 (GPIO_ALT | GPIO_AF4 | GPIO_PORTA | GPIO_PIN0) + +/* USB */ + +#define GPIO_USB_NOE (GPIO_ALT | GPIO_AF2 | GPIO_PORTA | GPIO_PIN13) + +#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F07X_PINMAP_H */ diff --git a/arch/arm/src/stm32f0/chip/stm32f0_memorymap.h b/arch/arm/src/stm32f0/chip/stm32f0_memorymap.h index 704b3466aa..7ff37fcdcd 100644 --- a/arch/arm/src/stm32f0/chip/stm32f0_memorymap.h +++ b/arch/arm/src/stm32f0/chip/stm32f0_memorymap.h @@ -44,8 +44,8 @@ #include #include "chip.h" -#if defined(CONFIG_STM32F0_STM32F05X) -# include "chip/stm32f05xxx_memorymap.h" +#if defined(CONFIG_STM32F0_STM32F05X) || defined(CONFIG_STM32F0_STM32F07X) +# include "chip/stm32f05xf07x_memorymap.h" #else # error "Unsupported STM32 memory map" #endif diff --git a/arch/arm/src/stm32f0/chip/stm32f0_pinmap.h b/arch/arm/src/stm32f0/chip/stm32f0_pinmap.h index a586cbdbc7..69193b619f 100644 --- a/arch/arm/src/stm32f0/chip/stm32f0_pinmap.h +++ b/arch/arm/src/stm32f0/chip/stm32f0_pinmap.h @@ -43,7 +43,7 @@ #include #include "chip.h" -#if defined(CONFIG_STM32F0_STM32F05X) +#if defined(CONFIG_STM32F0_STM32F05X) || defined(CONFIG_STM32F0_STM32F07X) # include "chip/stm32f05xr_pinmap.h" #else # error "Unsupported STM32F0 pin map" diff --git a/configs/stm32f0discovery/include/board.h b/configs/stm32f0discovery/include/board.h index b5c66a2b41..445cd068cd 100644 --- a/configs/stm32f0discovery/include/board.h +++ b/configs/stm32f0discovery/include/board.h @@ -100,13 +100,15 @@ * this oscillator can be taken from the USB data stream itself (SOF * signalization) which allows crystal-less operation. * SYSCLK - * The system clock is derived from the PLL VCO divided by the output division factor. + * The system clock is derived from the PLL VCO divided by the output + * division factor. * Limitations: - * 96 MHz as PLLVCO when the product is in range 1 (1.8V), - * 48 MHz as PLLVCO when the product is in range 2 (1.5V), - * 24 MHz when the product is in range 3 (1.2V). - * Output division to avoid exceeding 32 MHz as SYSCLK. - * The minimum input clock frequency for PLL is 2 MHz (when using HSE as PLL source). + * - 96 MHz as PLLVCO when the product is in range 1 (1.8V), + * - 48 MHz as PLLVCO when the product is in range 2 (1.5V), + * - 24 MHz when the product is in range 3 (1.2V). + * - Output division to avoid exceeding 32 MHz as SYSCLK. + * - The minimum input clock frequency for PLL is 2 MHz (when using HSE as + * PLL source). */ #define STM32F0_CFGR_PLLSRC RCC_CFGR_PLLSRC_HSId2 /* Source is HSI/2 */ -- GitLab From 8b157b034dfe4dedde8a932791eb040798f885b7 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 17 Apr 2017 17:13:32 -0600 Subject: [PATCH 490/990] STM32F0: Fixes to get STM32F0-Discovery build again after changes to support the STM32F07x --- arch/arm/include/stm32f0/chip.h | 6 +++--- arch/arm/src/stm32f0/chip/stm32f0_pinmap.h | 6 ++++-- arch/arm/src/stm32f0/stm32f0_gpio.h | 25 +++++----------------- arch/arm/src/stm32f0/stm32f0_lowputc.c | 4 ++-- 4 files changed, 14 insertions(+), 27 deletions(-) diff --git a/arch/arm/include/stm32f0/chip.h b/arch/arm/include/stm32f0/chip.h index 1c980b851e..3dd656ffa5 100644 --- a/arch/arm/include/stm32f0/chip.h +++ b/arch/arm/include/stm32f0/chip.h @@ -68,7 +68,7 @@ # define STM32F0_NCAP 13 /* Capacitive sensing channels (14 on UFQFPN32)) */ # define STM32F0_NPORTS 6 /* Six GPIO ports, GPIOA-F */ -#if defined(CONFIG_ARCH_CHIP_SSTM32F072C8) || defined(CONFIG_ARCH_CHIP_SSTM32F072CB) +#elif defined(CONFIG_ARCH_CHIP_SSTM32F072C8) || defined(CONFIG_ARCH_CHIP_SSTM32F072CB) # undef STM32F051x /* Not STM32F051x family */ # define STM32F072x 1 /* STM32F072x family */ @@ -99,7 +99,7 @@ # define STM32F0_NCAP 17 /* Capacitive sensing channels */ # define STM32F0_NPORTS 6 /* Six GPIO ports, GPIOA-F */ -#if defined(CONFIG_ARCH_CHIP_SSTM32F072R8) || defined(CONFIG_ARCH_CHIP_SSTM32F072RB) +#elif defined(CONFIG_ARCH_CHIP_SSTM32F072R8) || defined(CONFIG_ARCH_CHIP_SSTM32F072RB) # undef STM32F051x /* Not STM32F051x family */ # define STM32F072x 1 /* STM32F072x family */ @@ -130,7 +130,7 @@ # define STM32F0_NCAP 18 /* Capacitive sensing channels */ # define STM32F0_NPORTS 6 /* Six GPIO ports, GPIOA-F */ -#if defined(CONFIG_ARCH_CHIP_SSTM32F072V8) || defined(CONFIG_ARCH_CHIP_SSTM32F072VB) +#elif defined(CONFIG_ARCH_CHIP_SSTM32F072V8) || defined(CONFIG_ARCH_CHIP_SSTM32F072VB) # undef STM32F051x /* Not STM32F051x family */ # define STM32F072x 1 /* STM32F072x family */ diff --git a/arch/arm/src/stm32f0/chip/stm32f0_pinmap.h b/arch/arm/src/stm32f0/chip/stm32f0_pinmap.h index 69193b619f..37893a4c12 100644 --- a/arch/arm/src/stm32f0/chip/stm32f0_pinmap.h +++ b/arch/arm/src/stm32f0/chip/stm32f0_pinmap.h @@ -43,8 +43,10 @@ #include #include "chip.h" -#if defined(CONFIG_STM32F0_STM32F05X) || defined(CONFIG_STM32F0_STM32F07X) -# include "chip/stm32f05xr_pinmap.h" +#if defined(CONFIG_STM32F0_STM32F05X) +# include "chip/stm32f05x_pinmap.h" +#elif defined(CONFIG_STM32F0_STM32F07X) +# include "chip/stm32f07x_pinmap.h" #else # error "Unsupported STM32F0 pin map" #endif diff --git a/arch/arm/src/stm32f0/stm32f0_gpio.h b/arch/arm/src/stm32f0/stm32f0_gpio.h index 6f3220a69e..4cbe0a40df 100644 --- a/arch/arm/src/stm32f0/stm32f0_gpio.h +++ b/arch/arm/src/stm32f0/stm32f0_gpio.h @@ -54,12 +54,7 @@ #include #include "chip.h" - -#if defined(CONFIG_STM32F0_STM32F05X) -# include "chip/stm32f05xr_pinmap.h" -#else -# error "Unsupported STM32F0 chip" -#endif +#include "chip/stm32f0_pinmap.h" /************************************************************************************ * Pre-Processor Declarations @@ -84,7 +79,7 @@ * ---- ---- ---- ---- ---- * Inputs: MMUU .... ...X PPPP BBBB * Outputs: MMUU .... FFOV PPPP BBBB - * Alternate Functions: MMUU AAAA FFO. PPPP BBBB + * Alternate Functions: MMUU .AAA FFO. PPPP BBBB * Analog: MM.. .... .... PPPP BBBB */ @@ -122,11 +117,11 @@ * 1111 1111 1100 0000 0000 * 9876 5432 1098 7654 3210 * ---- ---- ---- ---- ---- - * .... AAAA .... .... .... + * .... .AAA .... .... .... */ -#define GPIO_AF_SHIFT (12) /* Bits 12-15: Alternate function */ -#define GPIO_AF_MASK (15 << GPIO_AF_SHIFT) +#define GPIO_AF_SHIFT (12) /* Bits 12-14: Alternate function */ +#define GPIO_AF_MASK (7 << GPIO_AF_SHIFT) # define GPIO_AF(n) ((n) << GPIO_AF_SHIFT) # define GPIO_AF0 (0 << GPIO_AF_SHIFT) # define GPIO_AF1 (1 << GPIO_AF_SHIFT) @@ -136,14 +131,6 @@ # define GPIO_AF5 (5 << GPIO_AF_SHIFT) # define GPIO_AF6 (6 << GPIO_AF_SHIFT) # define GPIO_AF7 (7 << GPIO_AF_SHIFT) -# define GPIO_AF8 (8 << GPIO_AF_SHIFT) -# define GPIO_AF9 (9 << GPIO_AF_SHIFT) -# define GPIO_AF10 (10 << GPIO_AF_SHIFT) -# define GPIO_AF11 (11 << GPIO_AF_SHIFT) -# define GPIO_AF12 (12 << GPIO_AF_SHIFT) -# define GPIO_AF13 (13 << GPIO_AF_SHIFT) -# define GPIO_AF14 (14 << GPIO_AF_SHIFT) -# define GPIO_AF15 (15 << GPIO_AF_SHIFT) /* Output/Alt function frequency selection: * @@ -209,8 +196,6 @@ # define GPIO_PORTD (3 << GPIO_PORT_SHIFT) /* GPIOD */ # define GPIO_PORTE (4 << GPIO_PORT_SHIFT) /* GPIOE */ # define GPIO_PORTF (5 << GPIO_PORT_SHIFT) /* GPIOF */ -# define GPIO_PORTG (6 << GPIO_PORT_SHIFT) /* GPIOG */ -# define GPIO_PORTH (7 << GPIO_PORT_SHIFT) /* GPIOH */ /* This identifies the bit in the port: * diff --git a/arch/arm/src/stm32f0/stm32f0_lowputc.c b/arch/arm/src/stm32f0/stm32f0_lowputc.c index 8dfe8e0820..51d9f6a06e 100644 --- a/arch/arm/src/stm32f0/stm32f0_lowputc.c +++ b/arch/arm/src/stm32f0/stm32f0_lowputc.c @@ -296,8 +296,8 @@ void stm32f0_lowsetup(void) #if defined(HAVE_UART) #if defined(HAVE_CONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG) uint32_t cr; - uint32_t clken; #endif + uint32_t clken; #if defined(HAVE_CONSOLE) /* Enable USART APB1/2 clock */ @@ -305,7 +305,7 @@ void stm32f0_lowsetup(void) modifyreg32(STM32F0_CONSOLE_APBREG, 0, STM32F0_CONSOLE_APBEN); #endif - /* Enable the console USART and configure GPIO pins needed for rx/tx. */ + /* Enable all GPIO modules */ clken = getreg32(STM32F0_RCC_AHBENR); clken |= RCC_AHBENR_IOPAEN | RCC_AHBENR_IOPAEN | RCC_AHBENR_IOPAEN |\ -- GitLab From 639bf31eb446bb867567307c7506cbe7d3ddb257 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 17 Apr 2017 17:20:55 -0600 Subject: [PATCH 491/990] Move enabling of GPIO peripherals form UART setup to clockconfig. This is not a UART function. It is needed by all periphrals. --- arch/arm/src/stm32f0/stm32f0_clockconfig.c | 8 ++++++++ arch/arm/src/stm32f0/stm32f0_lowputc.c | 8 -------- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/arch/arm/src/stm32f0/stm32f0_clockconfig.c b/arch/arm/src/stm32f0/stm32f0_clockconfig.c index 20acb55804..ca8736bb23 100644 --- a/arch/arm/src/stm32f0/stm32f0_clockconfig.c +++ b/arch/arm/src/stm32f0/stm32f0_clockconfig.c @@ -111,4 +111,12 @@ void stm32f0_clockconfig(void) regval |= RCC_CFGR_SW_PLL; putreg32(regval, STM32F0_RCC_CFGR); while ((getreg32(STM32F0_RCC_CFGR) & RCC_CFGR_SW_MASK) != RCC_CFGR_SW_PLL); + + /* Enable basic peripheral support */ + /* Enable all GPIO modules */ + + regval = getreg32(STM32F0_RCC_AHBENR); + regval |= RCC_AHBENR_IOPAEN | RCC_AHBENR_IOPAEN | RCC_AHBENR_IOPAEN |\ + RCC_AHBENR_IOPAEN | RCC_AHBENR_IOPAEN | RCC_AHBENR_IOPAEN; + putreg32(regval, STM32F0_RCC_AHBENR); } diff --git a/arch/arm/src/stm32f0/stm32f0_lowputc.c b/arch/arm/src/stm32f0/stm32f0_lowputc.c index 51d9f6a06e..16de07e8f2 100644 --- a/arch/arm/src/stm32f0/stm32f0_lowputc.c +++ b/arch/arm/src/stm32f0/stm32f0_lowputc.c @@ -297,7 +297,6 @@ void stm32f0_lowsetup(void) #if defined(HAVE_CONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG) uint32_t cr; #endif - uint32_t clken; #if defined(HAVE_CONSOLE) /* Enable USART APB1/2 clock */ @@ -305,13 +304,6 @@ void stm32f0_lowsetup(void) modifyreg32(STM32F0_CONSOLE_APBREG, 0, STM32F0_CONSOLE_APBEN); #endif - /* Enable all GPIO modules */ - - clken = getreg32(STM32F0_RCC_AHBENR); - clken |= RCC_AHBENR_IOPAEN | RCC_AHBENR_IOPAEN | RCC_AHBENR_IOPAEN |\ - RCC_AHBENR_IOPAEN | RCC_AHBENR_IOPAEN | RCC_AHBENR_IOPAEN; - putreg32(clken, STM32F0_RCC_AHBENR); - #ifdef STM32F0_CONSOLE_TX stm32f0_configgpio(STM32F0_CONSOLE_TX); #endif -- GitLab From acdc26f9723b282c3f343e0c00b3af930e909ebc Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 17 Apr 2017 17:51:05 -0600 Subject: [PATCH 492/990] STM32F0: Add logic to enable other USARTs. No UART4/5. Rather USART4/5. --- arch/arm/src/stm32f0/chip/stm32f0_dma.h | 10 +- arch/arm/src/stm32f0/chip/stm32f0_rcc.h | 8 +- arch/arm/src/stm32f0/chip/stm32f0_uart.h | 86 ++++---------- arch/arm/src/stm32f0/stm32f0_lowputc.c | 140 +++++++++++++++-------- arch/arm/src/stm32f0/stm32f0_serial.c | 50 ++++---- arch/arm/src/stm32f0/stm32f0_uart.h | 12 +- 6 files changed, 154 insertions(+), 152 deletions(-) diff --git a/arch/arm/src/stm32f0/chip/stm32f0_dma.h b/arch/arm/src/stm32f0/chip/stm32f0_dma.h index b362d24d59..a0d82628fb 100644 --- a/arch/arm/src/stm32f0/chip/stm32f0_dma.h +++ b/arch/arm/src/stm32f0/chip/stm32f0_dma.h @@ -434,7 +434,7 @@ #define DMACHAN_TIM17_UP_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN1, 5) #define DMACHAN_TIM17_UP_2 DMACHAN_SETTING(STM32F0_DMA1_CHAN7, 5) -/* UART */ +/* USARTs */ #define DMACHAN_USART1_RX_1 DMACHAN_SETTING(STM32F0_DMA1_CHAN5, 2) #define DMACHAN_USART1_RX_2 DMACHAN_SETTING(STM32F0_DMA2_CHAN7, 2) @@ -447,10 +447,10 @@ #define DMACHAN_USART3_RX DMACHAN_SETTING(STM32F0_DMA1_CHAN3, 1) #define DMACHAN_USART3_TX DMACHAN_SETTING(STM32F0_DMA1_CHAN2, 2) -#define DMACHAN_UART5_RX DMACHAN_SETTING(STM32F0_DMA2_CHAN2, 2) -#define DMACHAN_UART5_TX DMACHAN_SETTING(STM32F0_DMA2_CHAN1, 2) +#define DMACHAN_USART4_RX DMACHAN_SETTING(STM32F0_DMA2_CHAN5, 2) +#define DMACHAN_USART4_TX DMACHAN_SETTING(STM32F0_DMA2_CHAN3, 2) -#define DMACHAN_UART4_RX DMACHAN_SETTING(STM32F0_DMA2_CHAN5, 2) -#define DMACHAN_UART4_TX DMACHAN_SETTING(STM32F0_DMA2_CHAN3, 2) +#define DMACHAN_USART5_RX DMACHAN_SETTING(STM32F0_DMA2_CHAN2, 2) +#define DMACHAN_USART5_TX DMACHAN_SETTING(STM32F0_DMA2_CHAN1, 2) #endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_DMA_H */ diff --git a/arch/arm/src/stm32f0/chip/stm32f0_rcc.h b/arch/arm/src/stm32f0/chip/stm32f0_rcc.h index aed20d1608..613020b830 100644 --- a/arch/arm/src/stm32f0/chip/stm32f0_rcc.h +++ b/arch/arm/src/stm32f0/chip/stm32f0_rcc.h @@ -222,8 +222,8 @@ #define RCC_APB1RSTR_SPI2RST (1 << 14) /* Bit 14: SPI 2 reset */ #define RCC_APB1RSTR_USART2RST (1 << 17) /* Bit 17: USART 2 reset */ #define RCC_APB1RSTR_USART3RST (1 << 18) /* Bit 18: USART 3 reset */ -#define RCC_APB1RSTR_UART4RST (1 << 19) /* Bit 19: UART 4 reset */ -#define RCC_APB1RSTR_UART5RST (1 << 20) /* Bit 20: UART 5 reset */ +#define RCC_APB1RSTR_USART4RST (1 << 19) /* Bit 19: USART 4 reset */ +#define RCC_APB1RSTR_USART5RST (1 << 20) /* Bit 20: USART 5 reset */ #define RCC_APB1RSTR_I2C1RST (1 << 21) /* Bit 21: I2C 1 reset */ #define RCC_APB1RSTR_I2C2RST (1 << 22) /* Bit 22: I2C 2 reset */ #define RCC_APB1RSTR_USBRST (1 << 23) /* Bit 23: USB reset */ @@ -275,8 +275,8 @@ #define RCC_APB1ENR_SPI2EN (1 << 14) /* Bit 14: SPI 2 clock enable */ #define RCC_APB1ENR_USART2EN (1 << 17) /* Bit 17: USART 2 clock enable */ #define RCC_APB1ENR_USART3EN (1 << 18) /* Bit 18: USART 3 clock enable */ -#define RCC_APB1ENR_UART4EN (1 << 19) /* Bit 19: UART 4 clock enable */ -#define RCC_APB1ENR_UART5EN (1 << 20) /* Bit 20: UART 5 clock enable */ +#define RCC_APB1ENR_USART4EN (1 << 19) /* Bit 19: USART 4 clock enable */ +#define RCC_APB1ENR_USART5EN (1 << 20) /* Bit 20: USART 5 clock enable */ #define RCC_APB1ENR_I2C1EN (1 << 21) /* Bit 21: I2C 1 clock enable */ #define RCC_APB1ENR_I2C2EN (1 << 22) /* Bit 22: I2C 2 clock enable */ #define RCC_APB1ENR_USBEN (1 << 23) /* Bit 23: USB clock enable */ diff --git a/arch/arm/src/stm32f0/chip/stm32f0_uart.h b/arch/arm/src/stm32f0/chip/stm32f0_uart.h index 3b7ff61da9..62af4d5ca1 100644 --- a/arch/arm/src/stm32f0/chip/stm32f0_uart.h +++ b/arch/arm/src/stm32f0/chip/stm32f0_uart.h @@ -108,73 +108,31 @@ #endif #if STM32F0_NUSART > 3 -# define STM32F0_UART4_CR1 (STM32F0_UART4_BASE+STM32F0_USART_CR1_OFFSET) -# define STM32F0_UART4_CR2 (STM32F0_UART4_BASE+STM32F0_USART_CR2_OFFSET) -# define STM32F0_UART4_CR3 (STM32F0_UART4_BASE+STM32F0_USART_CR3_OFFSET) -# define STM32F0_UART4_BRR (STM32F0_UART4_BASE+STM32F0_USART_BRR_OFFSET) -# define STM32F0_UART4_GTPR (STM32F0_UART4_BASE+STM32F0_USART_GTPR_OFFSET) -# define STM32F0_UART4_RTOR (STM32F0_UART4_BASE+STM32F0_USART_RTOR_OFFSET) -# define STM32F0_UART4_RQR (STM32F0_UART4_BASE+STM32F0_USART_RQR_OFFSET) -# define STM32F0_UART4_ISR (STM32F0_UART4_BASE+STM32F0_USART_ISR_OFFSET) -# define STM32F0_UART4_ICR (STM32F0_UART4_BASE+STM32F0_USART_ICR_OFFSET) -# define STM32F0_UART4_RDR (STM32F0_UART4_BASE+STM32F0_USART_RDR_OFFSET) -# define STM32F0_UART4_TDR (STM32F0_UART4_BASE+STM32F0_USART_TDR_OFFSET) +# define STM32F0_USART4_CR1 (STM32F0_USART4_BASE+STM32F0_USART_CR1_OFFSET) +# define STM32F0_USART4_CR2 (STM32F0_USART4_BASE+STM32F0_USART_CR2_OFFSET) +# define STM32F0_USART4_CR3 (STM32F0_USART4_BASE+STM32F0_USART_CR3_OFFSET) +# define STM32F0_USART4_BRR (STM32F0_USART4_BASE+STM32F0_USART_BRR_OFFSET) +# define STM32F0_USART4_GTPR (STM32F0_USART4_BASE+STM32F0_USART_GTPR_OFFSET) +# define STM32F0_USART4_RTOR (STM32F0_USART4_BASE+STM32F0_USART_RTOR_OFFSET) +# define STM32F0_USART4_RQR (STM32F0_USART4_BASE+STM32F0_USART_RQR_OFFSET) +# define STM32F0_USART4_ISR (STM32F0_USART4_BASE+STM32F0_USART_ISR_OFFSET) +# define STM32F0_USART4_ICR (STM32F0_USART4_BASE+STM32F0_USART_ICR_OFFSET) +# define STM32F0_USART4_RDR (STM32F0_USART4_BASE+STM32F0_USART_RDR_OFFSET) +# define STM32F0_USART4_TDR (STM32F0_USART4_BASE+STM32F0_USART_TDR_OFFSET) #endif #if STM32F0_NUSART > 4 -# define STM32F0_UART5_CR1 (STM32F0_UART5_BASE+STM32F0_USART_CR1_OFFSET) -# define STM32F0_UART5_CR2 (STM32F0_UART5_BASE+STM32F0_USART_CR2_OFFSET) -# define STM32F0_UART5_CR3 (STM32F0_UART5_BASE+STM32F0_USART_CR3_OFFSET) -# define STM32F0_UART5_BRR (STM32F0_UART5_BASE+STM32F0_USART_BRR_OFFSET) -# define STM32F0_UART5_GTPR (STM32F0_UART5_BASE+STM32F0_USART_GTPR_OFFSET) -# define STM32F0_UART5_RTOR (STM32F0_UART5_BASE+STM32F0_USART_RTOR_OFFSET) -# define STM32F0_UART5_RQR (STM32F0_UART5_BASE+STM32F0_USART_RQR_OFFSET) -# define STM32F0_UART5_ISR (STM32F0_UART5_BASE+STM32F0_USART_ISR_OFFSET) -# define STM32F0_UART5_ICR (STM32F0_UART5_BASE+STM32F0_USART_ICR_OFFSET) -# define STM32F0_UART5_RDR (STM32F0_UART5_BASE+STM32F0_USART_RDR_OFFSET) -# define STM32F0_UART5_TDR (STM32F0_UART5_BASE+STM32F0_USART_TDR_OFFSET) -#endif - -#if STM32F0_NUSART > 5 -# define STM32F0_UART6_CR1 (STM32F0_UART6_BASE+STM32F0_USART_CR1_OFFSET) -# define STM32F0_UART6_CR2 (STM32F0_UART6_BASE+STM32F0_USART_CR2_OFFSET) -# define STM32F0_UART6_CR3 (STM32F0_UART6_BASE+STM32F0_USART_CR3_OFFSET) -# define STM32F0_UART6_BRR (STM32F0_UART6_BASE+STM32F0_USART_BRR_OFFSET) -# define STM32F0_UART6_GTPR (STM32F0_UART6_BASE+STM32F0_USART_GTPR_OFFSET) -# define STM32F0_UART6_RTOR (STM32F0_UART6_BASE+STM32F0_USART_RTOR_OFFSET) -# define STM32F0_UART6_RQR (STM32F0_UART6_BASE+STM32F0_USART_RQR_OFFSET) -# define STM32F0_UART6_ISR (STM32F0_UART6_BASE+STM32F0_USART_ISR_OFFSET) -# define STM32F0_UART6_ICR (STM32F0_UART6_BASE+STM32F0_USART_ICR_OFFSET) -# define STM32F0_UART6_RDR (STM32F0_UART6_BASE+STM32F0_USART_RDR_OFFSET) -# define STM32F0_UART6_TDR (STM32F0_UART6_BASE+STM32F0_USART_TDR_OFFSET) -#endif - -#if STM32F0_NUSART > 6 -# define STM32F0_UART7_CR1 (STM32F0_UART7_BASE+STM32F0_USART_CR1_OFFSET) -# define STM32F0_UART7_CR2 (STM32F0_UART7_BASE+STM32F0_USART_CR2_OFFSET) -# define STM32F0_UART7_CR3 (STM32F0_UART7_BASE+STM32F0_USART_CR3_OFFSET) -# define STM32F0_UART7_BRR (STM32F0_UART7_BASE+STM32F0_USART_BRR_OFFSET) -# define STM32F0_UART7_GTPR (STM32F0_UART7_BASE+STM32F0_USART_GTPR_OFFSET) -# define STM32F0_UART7_RTOR (STM32F0_UART7_BASE+STM32F0_USART_RTOR_OFFSET) -# define STM32F0_UART7_RQR (STM32F0_UART7_BASE+STM32F0_USART_RQR_OFFSET) -# define STM32F0_UART7_ISR (STM32F0_UART7_BASE+STM32F0_USART_ISR_OFFSET) -# define STM32F0_UART7_ICR (STM32F0_UART7_BASE+STM32F0_USART_ICR_OFFSET) -# define STM32F0_UART7_RDR (STM32F0_UART7_BASE+STM32F0_USART_RDR_OFFSET) -# define STM32F0_UART7_TDR (STM32F0_UART7_BASE+STM32F0_USART_TDR_OFFSET) -#endif - -#if STM32F0_NUSART > 7 -# define STM32F0_UART8_CR1 (STM32F0_UART8_BASE+STM32F0_USART_CR1_OFFSET) -# define STM32F0_UART8_CR2 (STM32F0_UART8_BASE+STM32F0_USART_CR2_OFFSET) -# define STM32F0_UART8_CR3 (STM32F0_UART8_BASE+STM32F0_USART_CR3_OFFSET) -# define STM32F0_UART8_BRR (STM32F0_UART8_BASE+STM32F0_USART_BRR_OFFSET) -# define STM32F0_UART8_GTPR (STM32F0_UART8_BASE+STM32F0_USART_GTPR_OFFSET) -# define STM32F0_UART8_RTOR (STM32F0_UART8_BASE+STM32F0_USART_RTOR_OFFSET) -# define STM32F0_UART8_RQR (STM32F0_UART8_BASE+STM32F0_USART_RQR_OFFSET) -# define STM32F0_UART8_ISR (STM32F0_UART8_BASE+STM32F0_USART_ISR_OFFSET) -# define STM32F0_UART8_ICR (STM32F0_UART8_BASE+STM32F0_USART_ICR_OFFSET) -# define STM32F0_UART8_RDR (STM32F0_UART8_BASE+STM32F0_USART_RDR_OFFSET) -# define STM32F0_UART8_TDR (STM32F0_UART8_BASE+STM32F0_USART_TDR_OFFSET) +# define STM32F0_USART5_CR1 (STM32F0_USART5_BASE+STM32F0_USART_CR1_OFFSET) +# define STM32F0_USART5_CR2 (STM32F0_USART5_BASE+STM32F0_USART_CR2_OFFSET) +# define STM32F0_USART5_CR3 (STM32F0_USART5_BASE+STM32F0_USART_CR3_OFFSET) +# define STM32F0_USART5_BRR (STM32F0_USART5_BASE+STM32F0_USART_BRR_OFFSET) +# define STM32F0_USART5_GTPR (STM32F0_USART5_BASE+STM32F0_USART_GTPR_OFFSET) +# define STM32F0_USART5_RTOR (STM32F0_USART5_BASE+STM32F0_USART_RTOR_OFFSET) +# define STM32F0_USART5_RQR (STM32F0_USART5_BASE+STM32F0_USART_RQR_OFFSET) +# define STM32F0_USART5_ISR (STM32F0_USART5_BASE+STM32F0_USART_ISR_OFFSET) +# define STM32F0_USART5_ICR (STM32F0_USART5_BASE+STM32F0_USART_ICR_OFFSET) +# define STM32F0_USART5_RDR (STM32F0_USART5_BASE+STM32F0_USART_RDR_OFFSET) +# define STM32F0_USART5_TDR (STM32F0_USART5_BASE+STM32F0_USART_TDR_OFFSET) #endif /* Register Bitfield Definitions ****************************************************/ diff --git a/arch/arm/src/stm32f0/stm32f0_lowputc.c b/arch/arm/src/stm32f0/stm32f0_lowputc.c index 16de07e8f2..3fbfe67d24 100644 --- a/arch/arm/src/stm32f0/stm32f0_lowputc.c +++ b/arch/arm/src/stm32f0/stm32f0_lowputc.c @@ -63,14 +63,10 @@ # if defined(CONFIG_USART1_SERIAL_CONSOLE) # define STM32F0_CONSOLE_BASE STM32F0_USART1_BASE # define STM32F0_APBCLOCK STM32F0_PCLK2_FREQUENCY -# define STM32F0_CONSOLE_APBREG STM32F0_RCC_APB2ENR -# define STM32F0_CONSOLE_APBEN RCC_APB2ENR_USART1EN # define STM32F0_CONSOLE_BAUD CONFIG_USART1_BAUD # define STM32F0_CONSOLE_BITS CONFIG_USART1_BITS # define STM32F0_CONSOLE_PARITY CONFIG_USART1_PARITY # define STM32F0_CONSOLE_2STOP CONFIG_USART1_2STOP -# define STM32F0_CONSOLE_TX GPIO_USART1_TX -# define STM32F0_CONSOLE_RX GPIO_USART1_RX # ifdef CONFIG_USART1_RS485 # define STM32F0_CONSOLE_RS485_DIR GPIO_USART1_RS485_DIR # if (CONFIG_USART1_RS485_DIR_POLARITY == 0) @@ -82,14 +78,10 @@ # elif defined(CONFIG_USART2_SERIAL_CONSOLE) # define STM32F0_CONSOLE_BASE STM32F0_USART2_BASE # define STM32F0_APBCLOCK STM32F0_PCLK1_FREQUENCY -# define STM32F0_CONSOLE_APBREG STM32F0_RCC_APB1ENR1 -# define STM32F0_CONSOLE_APBEN RCC_APB1ENR1_USART2EN # define STM32F0_CONSOLE_BAUD CONFIG_USART2_BAUD # define STM32F0_CONSOLE_BITS CONFIG_USART2_BITS # define STM32F0_CONSOLE_PARITY CONFIG_USART2_PARITY # define STM32F0_CONSOLE_2STOP CONFIG_USART2_2STOP -# define STM32F0_CONSOLE_TX GPIO_USART2_TX -# define STM32F0_CONSOLE_RX GPIO_USART2_RX # ifdef CONFIG_USART2_RS485 # define STM32F0_CONSOLE_RS485_DIR GPIO_USART2_RS485_DIR # if (CONFIG_USART2_RS485_DIR_POLARITY == 0) @@ -101,14 +93,10 @@ # elif defined(CONFIG_USART3_SERIAL_CONSOLE) # define STM32F0_CONSOLE_BASE STM32F0_USART3_BASE # define STM32F0_APBCLOCK STM32F0_PCLK1_FREQUENCY -# define STM32F0_CONSOLE_APBREG STM32F0_RCC_APB1ENR1 -# define STM32F0_CONSOLE_APBEN RCC_APB1ENR1_USART3EN # define STM32F0_CONSOLE_BAUD CONFIG_USART3_BAUD # define STM32F0_CONSOLE_BITS CONFIG_USART3_BITS # define STM32F0_CONSOLE_PARITY CONFIG_USART3_PARITY # define STM32F0_CONSOLE_2STOP CONFIG_USART3_2STOP -# define STM32F0_CONSOLE_TX GPIO_USART3_TX -# define STM32F0_CONSOLE_RX GPIO_USART3_RX # ifdef CONFIG_USART3_RS485 # define STM32F0_CONSOLE_RS485_DIR GPIO_USART3_RS485_DIR # if (CONFIG_USART3_RS485_DIR_POLARITY == 0) @@ -117,39 +105,31 @@ # define STM32F0_CONSOLE_RS485_DIR_POLARITY true # endif # endif -# elif defined(CONFIG_UART4_SERIAL_CONSOLE) -# define STM32F0_CONSOLE_BASE STM32F0_UART4_BASE +# elif defined(CONFIG_USART4_SERIAL_CONSOLE) +# define STM32F0_CONSOLE_BASE STM32F0_USART4_BASE # define STM32F0_APBCLOCK STM32F0_PCLK1_FREQUENCY -# define STM32F0_CONSOLE_APBREG STM32F0_RCC_APB1ENR1 -# define STM32F0_CONSOLE_APBEN RCC_APB1ENR1_UART4EN -# define STM32F0_CONSOLE_BAUD CONFIG_UART4_BAUD -# define STM32F0_CONSOLE_BITS CONFIG_UART4_BITS -# define STM32F0_CONSOLE_PARITY CONFIG_UART4_PARITY -# define STM32F0_CONSOLE_2STOP CONFIG_UART4_2STOP -# define STM32F0_CONSOLE_TX GPIO_UART4_TX -# define STM32F0_CONSOLE_RX GPIO_UART4_RX -# ifdef CONFIG_UART4_RS485 -# define STM32F0_CONSOLE_RS485_DIR GPIO_UART4_RS485_DIR -# if (CONFIG_UART4_RS485_DIR_POLARITY == 0) +# define STM32F0_CONSOLE_BAUD CONFIG_USART4_BAUD +# define STM32F0_CONSOLE_BITS CONFIG_USART4_BITS +# define STM32F0_CONSOLE_PARITY CONFIG_USART4_PARITY +# define STM32F0_CONSOLE_2STOP CONFIG_USART4_2STOP +# ifdef CONFIG_USART4_RS485 +# define STM32F0_CONSOLE_RS485_DIR GPIO_USART4_RS485_DIR +# if (CONFIG_USART4_RS485_DIR_POLARITY == 0) # define STM32F0_CONSOLE_RS485_DIR_POLARITY false # else # define STM32F0_CONSOLE_RS485_DIR_POLARITY true # endif # endif -# elif defined(CONFIG_UART5_SERIAL_CONSOLE) -# define STM32F0_CONSOLE_BASE STM32F0_UART5_BASE +# elif defined(CONFIG_USART5_SERIAL_CONSOLE) +# define STM32F0_CONSOLE_BASE STM32F0_USART5_BASE # define STM32F0_APBCLOCK STM32F0_PCLK1_FREQUENCY -# define STM32F0_CONSOLE_APBREG STM32F0_RCC_APB1ENR1 -# define STM32F0_CONSOLE_APBEN RCC_APB1ENR1_UART5EN -# define STM32F0_CONSOLE_BAUD CONFIG_UART5_BAUD -# define STM32F0_CONSOLE_BITS CONFIG_UART5_BITS -# define STM32F0_CONSOLE_PARITY CONFIG_UART5_PARITY -# define STM32F0_CONSOLE_2STOP CONFIG_UART5_2STOP -# define STM32F0_CONSOLE_TX GPIO_UART5_TX -# define STM32F0_CONSOLE_RX GPIO_UART5_RX -# ifdef CONFIG_UART5_RS485 -# define STM32F0_CONSOLE_RS485_DIR GPIO_UART5_RS485_DIR -# if (CONFIG_UART5_RS485_DIR_POLARITY == 0) +# define STM32F0_CONSOLE_BAUD CONFIG_USART5_BAUD +# define STM32F0_CONSOLE_BITS CONFIG_USART5_BITS +# define STM32F0_CONSOLE_PARITY CONFIG_USART5_PARITY +# define STM32F0_CONSOLE_2STOP CONFIG_USART5_2STOP +# ifdef CONFIG_USART5_RS485 +# define STM32F0_CONSOLE_RS485_DIR GPIO_USART5_RS485_DIR +# if (CONFIG_USART5_RS485_DIR_POLARITY == 0) # define STM32F0_CONSOLE_RS485_DIR_POLARITY false # else # define STM32F0_CONSOLE_RS485_DIR_POLARITY true @@ -298,22 +278,86 @@ void stm32f0_lowsetup(void) uint32_t cr; #endif -#if defined(HAVE_CONSOLE) - /* Enable USART APB1/2 clock */ + /* Setup clocking and GPIO pins for all configured USARTs */ - modifyreg32(STM32F0_CONSOLE_APBREG, 0, STM32F0_CONSOLE_APBEN); +#ifdef CONFIG_STM32F0_USART1 + /* Enable USART APB2 clock */ + + modifyreg32(STM32F0_RCC_APB2ENR, 0, RCC_APB2ENR_USART1EN); + + /* Configure RX/TX pins */ + + stm32f0_configgpio(GPIO_USART1_TX); + stm32f0_configgpio(GPIO_USART1_RX); + +#ifdef CONFIG_USART1_RS485 + stm32f0_configgpio(GPIO_USART1_RS485_DIR); + stm32f0_gpiowrite(GPIO_USART1_RS485_DIR, !CONFIG_USART1_RS485_DIR_POLARITY); #endif +#endif + +#ifdef CONFIG_STM32F0_USART2 + /* Enable USART APB1 clock */ + + modifyreg32(STM32F0_RCC_APB1ENR1, 0, RCC_APB1ENR1_USART2EN); + + /* Configure RX/TX pins */ -#ifdef STM32F0_CONSOLE_TX - stm32f0_configgpio(STM32F0_CONSOLE_TX); + stm32f0_configgpio(GPIO_USART2_TX); + stm32f0_configgpio(GPIO_USART2_RX); + +#ifdef CONFIG_USART2_RS485 + stm32f0_configgpio(GPIO_USART2_RS485_DIR); + stm32f0_gpiowrite(GPIO_USART2_RS485_DIR, !CONFIG_USART2_RS485_DIR_POLARITY); #endif -#ifdef STM32F0_CONSOLE_RX - stm32f0_configgpio(STM32F0_CONSOLE_RX); #endif -#ifdef STM32F0_CONSOLE_RS485_DIR - stm32f0_configgpio(STM32F0_CONSOLE_RS485_DIR); - stm32f0_gpiowrite(STM32F0_CONSOLE_RS485_DIR, !STM32F0_CONSOLE_RS485_DIR_POLARITY); +#ifdef CONFIG_STM32F0_USART3 + /* Enable USART APB1 clock */ + + modifyreg32(STM32F0_RCC_APB1ENR1, 0, RCC_APB1ENR1_USART3EN); + + /* Configure RX/TX pins */ + + stm32f0_configgpio(GPIO_USART3_TX); + stm32f0_configgpio(GPIO_USART3_RX); + +#ifdef CONFIG_USART3_RS485 + stm32f0_configgpio(GPIO_USART3_RS485_DIR); + stm32f0_gpiowrite(GPIO_USART3_RS485_DIR, !CONFIG_USART3_RS485_DIR_POLARITY); +#endif +#endif + +#ifdef CONFIG_STM32F0_USART4 + /* Enable USART APB1 clock */ + + modifyreg32(STM32F0_RCC_APB1ENR1, 0, RCC_APB1ENR1_USART4EN); + + /* Configure RX/TX pins */ + + stm32f0_configgpio(GPIO_USART4_TX); + stm32f0_configgpio(GPIO_USART4_RX); + +#ifdef CONFIG_USART4_RS485 + stm32f0_configgpio(GPIO_USART4_RS485_DIR); + stm32f0_gpiowrite(GPIO_USART4_RS485_DIR, !CONFIG_USART4_RS485_DIR_POLARITY); +#endif +#endif + +#ifdef CONFIG_STM32F0_USART5 + /* Enable USART APB1 clock */ + + modifyreg32(STM32F0_RCC_APB1ENR1, 0, RCC_APB1ENR1_USART5EN); + + /* Configure RX/TX pins */ + + stm32f0_configgpio(GPIO_USART5_TX); + stm32f0_configgpio(GPIO_USART5_RX); + +#ifdef CONFIG_USART5_RS485 + stm32f0_configgpio(GPIO_USART5_RS485_DIR); + stm32f0_gpiowrite(GPIO_USART5_RS485_DIR, !CONFIG_USART5_RS485_DIR_POLARITY); +#endif #endif /* Enable and configure the selected console device */ diff --git a/arch/arm/src/stm32f0/stm32f0_serial.c b/arch/arm/src/stm32f0/stm32f0_serial.c index 0423b9ff94..2d5cd1b996 100644 --- a/arch/arm/src/stm32f0/stm32f0_serial.c +++ b/arch/arm/src/stm32f0/stm32f0_serial.c @@ -105,7 +105,7 @@ # if defined(CONFIG_USART4_RXDMA) || defined(CONFIG_USART5_RXDMA) # ifndef CONFIG_STM32F0_DMA2 -# error STM32F0 UART4/5 receive DMA requires CONFIG_STM32F0_DMA2 +# error STM32F0 USART4/5 receive DMA requires CONFIG_STM32F0_DMA2 # endif # endif @@ -387,18 +387,18 @@ static char g_usart3rxfifo[RXDMA_BUFFER_SIZE]; #endif #ifdef CONFIG_STM32F0_USART4 -static char g_uart4rxbuffer[CONFIG_USART4_RXBUFSIZE]; -static char g_uart4txbuffer[CONFIG_USART4_TXBUFSIZE]; +static char g_usart4rxbuffer[CONFIG_USART4_RXBUFSIZE]; +static char g_usart4txbuffer[CONFIG_USART4_TXBUFSIZE]; # ifdef CONFIG_USART4_RXDMA -static char g_uart4rxfifo[RXDMA_BUFFER_SIZE]; +static char g_usart4rxfifo[RXDMA_BUFFER_SIZE]; # endif #endif #ifdef CONFIG_STM32F0_USART5 -static char g_uart5rxbuffer[CONFIG_USART5_RXBUFSIZE]; -static char g_uart5txbuffer[CONFIG_USART5_TXBUFSIZE]; +static char g_usart5rxbuffer[CONFIG_USART5_RXBUFSIZE]; +static char g_usart5txbuffer[CONFIG_USART5_TXBUFSIZE]; # ifdef CONFIG_USART5_RXDMA -static char g_uart5rxfifo[RXDMA_BUFFER_SIZE]; +static char g_usart5rxfifo[RXDMA_BUFFER_SIZE]; # endif #endif @@ -585,10 +585,10 @@ static struct stm32f0_serial_s g_usart3priv = }; #endif -/* This describes the state of the STM32 UART4 port. */ +/* This describes the state of the STM32 USART4 port. */ #ifdef CONFIG_STM32F0_USART4 -static struct stm32f0_serial_s g_uart4priv = +static struct stm32f0_serial_s g_usart4priv = { .dev = { @@ -598,19 +598,19 @@ static struct stm32f0_serial_s g_uart4priv = .recv = { .size = CONFIG_USART4_RXBUFSIZE, - .buffer = g_uart4rxbuffer, + .buffer = g_usart4rxbuffer, }, .xmit = { .size = CONFIG_USART4_TXBUFSIZE, - .buffer = g_uart4txbuffer, + .buffer = g_usart4txbuffer, }, #ifdef CONFIG_USART4_RXDMA .ops = &g_uart_dma_ops, #else .ops = &g_uart_ops, #endif - .priv = &g_uart4priv, + .priv = &g_usart4priv, }, .irq = STM32F0_IRQ_USART4, @@ -636,7 +636,7 @@ static struct stm32f0_serial_s g_uart4priv = #endif #ifdef CONFIG_USART4_RXDMA .rxdma_channel = DMAMAP_USART4_RX, - .rxfifo = g_uart4rxfifo, + .rxfifo = g_usart4rxfifo, #endif #ifdef CONFIG_USART4_RS485 @@ -650,10 +650,10 @@ static struct stm32f0_serial_s g_uart4priv = }; #endif -/* This describes the state of the STM32 UART5 port. */ +/* This describes the state of the STM32 USART5 port. */ #ifdef CONFIG_STM32F0_USART5 -static struct stm32f0_serial_s g_uart5priv = +static struct stm32f0_serial_s g_usart5priv = { .dev = { @@ -663,19 +663,19 @@ static struct stm32f0_serial_s g_uart5priv = .recv = { .size = CONFIG_USART5_RXBUFSIZE, - .buffer = g_uart5rxbuffer, + .buffer = g_usart5rxbuffer, }, .xmit = { .size = CONFIG_USART5_TXBUFSIZE, - .buffer = g_uart5txbuffer, + .buffer = g_usart5txbuffer, }, #ifdef CONFIG_USART5_RXDMA .ops = &g_uart_dma_ops, #else .ops = &g_uart_ops, #endif - .priv = &g_uart5priv, + .priv = &g_usart5priv, }, .irq = STM32F0_IRQ_USART5, @@ -701,7 +701,7 @@ static struct stm32f0_serial_s g_uart5priv = #endif #ifdef CONFIG_USART5_RXDMA .rxdma_channel = DMAMAP_USART5_RX, - .rxfifo = g_uart5rxfifo, + .rxfifo = g_usart5rxfifo, #endif #ifdef CONFIG_USART5_RS485 @@ -729,10 +729,10 @@ FAR static struct stm32f0_serial_s * const uart_devs[STM32F0_NUSART] = [2] = &g_usart3priv, #endif #ifdef CONFIG_STM32F0_USART4 - [3] = &g_uart4priv, + [3] = &g_usart4priv, #endif #ifdef CONFIG_STM32F0_USART5 - [4] = &g_uart5priv, + [4] = &g_usart5priv, #endif }; @@ -2489,16 +2489,16 @@ void stm32f0serial_dmapoll(void) #endif #ifdef CONFIG_USART4_RXDMA - if (g_uart4priv.rxdma != NULL) + if (g_usart4priv.rxdma != NULL) { - stm32f0serial_dmarxcallback(g_uart4priv.rxdma, 0, &g_uart4priv); + stm32f0serial_dmarxcallback(g_usart4priv.rxdma, 0, &g_usart4priv); } #endif #ifdef CONFIG_USART5_RXDMA - if (g_uart5priv.rxdma != NULL) + if (g_usart5priv.rxdma != NULL) { - stm32f0serial_dmarxcallback(g_uart5priv.rxdma, 0, &g_uart5priv); + stm32f0serial_dmarxcallback(g_usart5priv.rxdma, 0, &g_usart5priv); } #endif diff --git a/arch/arm/src/stm32f0/stm32f0_uart.h b/arch/arm/src/stm32f0/stm32f0_uart.h index 80229a2831..9785d5e94a 100644 --- a/arch/arm/src/stm32f0/stm32f0_uart.h +++ b/arch/arm/src/stm32f0/stm32f0_uart.h @@ -54,22 +54,22 @@ * device. */ -#if STM32F0_NUSART < 8 || !defined(CONFIG_STM32F0_HAVE_UART8) +#if STM32F0_NUSART < 8 || !defined(CONFIG_STM32F0_HAVE_USART8) # undef CONFIG_STM32F0_USART8 #endif -#if STM32F0_NUSART < 7 || !defined(CONFIG_STM32F0_HAVE_UART7) +#if STM32F0_NUSART < 7 || !defined(CONFIG_STM32F0_HAVE_USART7) # undef CONFIG_STM32F0_USART7 #endif -#if STM32F0_NUSART < 6 || !defined(CONFIG_STM32F0_HAVE_UART6) +#if STM32F0_NUSART < 6 || !defined(CONFIG_STM32F0_HAVE_USART6) # undef CONFIG_STM32F0_USART6 #endif -#if STM32F0_NUSART < 5 || !defined(CONFIG_STM32F0_HAVE_UART5) +#if STM32F0_NUSART < 5 || !defined(CONFIG_STM32F0_HAVE_USART5) # undef CONFIG_STM32F0_USART5 #endif -#if STM32F0_NUSART < 4 || !defined(CONFIG_STM32F0_HAVE_UART4) +#if STM32F0_NUSART < 4 || !defined(CONFIG_STM32F0_HAVE_USART4) # undef CONFIG_STM32F0_USART4 #endif -#if STM32F0_NUSART < 3 || !defined(CONFIG_STM32F0_HAVE_UART3) +#if STM32F0_NUSART < 3 || !defined(CONFIG_STM32F0_HAVE_USART3) # undef CONFIG_STM32F0_USART3 #endif #if STM32F0_NUSART < 2 -- GitLab From 924f58fb2b3a9858282820a7b7dc0b11354cdb9b Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 17 Apr 2017 17:53:04 -0600 Subject: [PATCH 493/990] STM32F0: Change HAVE_UART to HAVE_USART --- arch/arm/src/stm32f0/stm32f0_lowputc.c | 4 ++-- arch/arm/src/stm32f0/stm32f0_serial.c | 8 ++++---- arch/arm/src/stm32f0/stm32f0_serial.h | 4 ++-- arch/arm/src/stm32f0/stm32f0_uart.h | 2 +- 4 files changed, 9 insertions(+), 9 deletions(-) diff --git a/arch/arm/src/stm32f0/stm32f0_lowputc.c b/arch/arm/src/stm32f0/stm32f0_lowputc.c index 3fbfe67d24..b62d6ecb4c 100644 --- a/arch/arm/src/stm32f0/stm32f0_lowputc.c +++ b/arch/arm/src/stm32f0/stm32f0_lowputc.c @@ -273,7 +273,7 @@ void up_lowputc(char ch) void stm32f0_lowsetup(void) { -#if defined(HAVE_UART) +#if defined(HAVE_USART) #if defined(HAVE_CONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG) uint32_t cr; #endif @@ -402,5 +402,5 @@ void stm32f0_lowsetup(void) putreg32(cr, STM32F0_CONSOLE_BASE + STM32F0_USART_CR1_OFFSET); #endif /* HAVE_CONSOLE && !CONFIG_SUPPRESS_UART_CONFIG */ -#endif /* HAVE_UART */ +#endif /* HAVE_USART */ } diff --git a/arch/arm/src/stm32f0/stm32f0_serial.c b/arch/arm/src/stm32f0/stm32f0_serial.c index 2d5cd1b996..2d78772d81 100644 --- a/arch/arm/src/stm32f0/stm32f0_serial.c +++ b/arch/arm/src/stm32f0/stm32f0_serial.c @@ -196,7 +196,7 @@ #endif #ifdef USE_SERIALDRIVER -#ifdef HAVE_UART +#ifdef HAVE_USART /**************************************************************************** * Private Types @@ -2327,7 +2327,7 @@ static int stm32f0serial_pmprepare(FAR struct pm_callback_s *cb, int domain, return OK; } #endif -#endif /* HAVE_UART */ +#endif /* HAVE_USART */ #endif /* USE_SERIALDRIVER */ /**************************************************************************** @@ -2349,7 +2349,7 @@ static int stm32f0serial_pmprepare(FAR struct pm_callback_s *cb, int domain, #ifdef USE_EARLYSERIALINIT void up_earlyserialinit(void) { -#ifdef HAVE_UART +#ifdef HAVE_USART unsigned i; /* Disable all USART interrupts */ @@ -2382,7 +2382,7 @@ void up_earlyserialinit(void) void up_serialinit(void) { -#ifdef HAVE_UART +#ifdef HAVE_USART char devname[16]; unsigned i; unsigned minor = 0; diff --git a/arch/arm/src/stm32f0/stm32f0_serial.h b/arch/arm/src/stm32f0/stm32f0_serial.h index d3f032953b..c850b47f3c 100644 --- a/arch/arm/src/stm32f0/stm32f0_serial.h +++ b/arch/arm/src/stm32f0/stm32f0_serial.h @@ -57,9 +57,9 @@ /* Are any UARTs enabled? */ -#undef HAVE_UART +#undef HAVE_USART #if defined(CONFIG_STM32F0_UART0) -# define HAVE_UART 1 +# define HAVE_USART 1 #endif /* Is there a serial console? There should be at most one defined. It could be on diff --git a/arch/arm/src/stm32f0/stm32f0_uart.h b/arch/arm/src/stm32f0/stm32f0_uart.h index 9785d5e94a..4fb7b1c05f 100644 --- a/arch/arm/src/stm32f0/stm32f0_uart.h +++ b/arch/arm/src/stm32f0/stm32f0_uart.h @@ -84,7 +84,7 @@ #if defined(CONFIG_STM32F0_USART1) || defined(CONFIG_STM32F0_USART2) || \ defined(CONFIG_STM32F0_USART3) || defined(CONFIG_STM32F0_USART4) || \ defined(CONFIG_STM32F0_USART5) -# define HAVE_UART 1 +# define HAVE_USART 1 #endif /* Sanity checks */ -- GitLab From 363fe88dbd60e66ed7f858ee554d34259c1a6e2a Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Mon, 17 Apr 2017 17:59:33 -0600 Subject: [PATCH 494/990] Fix stm32f0discovery defconfig to use standard serial --- configs/stm32f0discovery/nsh/defconfig | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/configs/stm32f0discovery/nsh/defconfig b/configs/stm32f0discovery/nsh/defconfig index da5233fe02..e74c51cb41 100644 --- a/configs/stm32f0discovery/nsh/defconfig +++ b/configs/stm32f0discovery/nsh/defconfig @@ -140,6 +140,8 @@ CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV6M_TOOLCHAIN_CODEREDL is not set # CONFIG_ARMV6M_TOOLCHAIN_CODESOURCERYL is not set CONFIG_ARMV6M_TOOLCHAIN_GNU_EABIL=y +# CONFIG_SERIAL_TERMIOS is not set +# CONFIG_USART1_RS485 is not set # # STM32F0xx Configuration Options @@ -341,7 +343,7 @@ CONFIG_STM32F0_SERIALDRIVER=y # # U[S]ART Device Configuration # -CONFIG_STM32F0_USART1F0_SERIALDRIVER=y +CONFIG_STM32F0_USART1_SERIALDRIVER=y # CONFIG_STM32F0_USART1_1WIREDRIVER is not set # @@ -592,9 +594,9 @@ CONFIG_DEV_NULL=y # CONFIG_POWER is not set # CONFIG_SENSORS is not set CONFIG_SERIAL=y -CONFIG_DEV_LOWCONSOLE=y +# CONFIG_DEV_LOWCONSOLE is not set # CONFIG_SERIAL_REMOVABLE is not set -# CONFIG_SERIAL_CONSOLE is not set +CONFIG_SERIAL_CONSOLE=y # CONFIG_16550_UART is not set # CONFIG_UART_SERIALDRIVER is not set # CONFIG_UART0_SERIALDRIVER is not set @@ -619,13 +621,14 @@ CONFIG_USART1_SERIALDRIVER=y # CONFIG_USART8_SERIALDRIVER is not set # CONFIG_OTHER_UART_SERIALDRIVER is not set CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y # CONFIG_SERIAL_IFLOWCONTROL is not set # CONFIG_SERIAL_OFLOWCONTROL is not set # CONFIG_SERIAL_DMA is not set CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y -# CONFIG_USART1_SERIAL_CONSOLE is not set +CONFIG_USART1_SERIAL_CONSOLE=y # CONFIG_OTHER_SERIAL_CONSOLE is not set -CONFIG_NO_SERIAL_CONSOLE=y +# CONFIG_NO_SERIAL_CONSOLE is not set # # USART1 Configuration @@ -654,7 +657,7 @@ CONFIG_USART1_2STOP=0 # CONFIG_RAMLOG is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set -# CONFIG_SYSLOG_SERIAL_CONSOLE is not set +CONFIG_SYSLOG_SERIAL_CONSOLE=y # CONFIG_SYSLOG_CHAR is not set CONFIG_SYSLOG_CONSOLE=y # CONFIG_SYSLOG_NONE is not set -- GitLab From de22d24f8ef1bcba3a556495b4881999ff3a85a4 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 17 Apr 2017 18:37:52 -0600 Subject: [PATCH 495/990] More changes UART to USART. Fix garbage code in stm32f0_serial.h that was clearing HAVE_USART --- arch/arm/src/stm32f0/stm32f0_serial.c | 28 +++++++++++----------- arch/arm/src/stm32f0/stm32f0_serial.h | 33 -------------------------- arch/arm/src/stm32f0/stm32f0_start.c | 2 +- configs/stm32f0discovery/nsh/defconfig | 2 +- 4 files changed, 16 insertions(+), 49 deletions(-) diff --git a/arch/arm/src/stm32f0/stm32f0_serial.c b/arch/arm/src/stm32f0/stm32f0_serial.c index 2d78772d81..673387d7ba 100644 --- a/arch/arm/src/stm32f0/stm32f0_serial.c +++ b/arch/arm/src/stm32f0/stm32f0_serial.c @@ -84,7 +84,7 @@ /* If DMA is enabled on any USART, then very that other pre-requisites * have also been selected. - * UART DMA1 DMA2 + * USART DMA1 DMA2 * 1 X X * 2 X * 3 X @@ -130,7 +130,7 @@ # error "USART1 DMA channel not defined (DMAMAP_USART1_RX)" # endif -/* UART2-5 have no alternate channels */ +/* USART2-5 have no alternate channels */ # define DMAMAP_USART2_RX DMACHAN_USART2_RX # define DMAMAP_USART3_RX DMACHAN_USART3_RX @@ -204,7 +204,7 @@ struct stm32f0_serial_s { - struct uart_dev_s dev; /* Generic UART device */ + struct uart_dev_s dev; /* Generic USART device */ uint16_t ie; /* Saved interrupt mask bits value */ uint16_t sr; /* Saved status bits */ @@ -1010,7 +1010,7 @@ static void stm32f0serial_setformat(FAR struct uart_dev_s *dev) * Enable or disable APB clock for the USART peripheral * * Input parameters: - * dev - A reference to the UART driver state structure + * dev - A reference to the USART driver state structure * on - Enable clock if 'on' is 'true' and disable if 'false' * ****************************************************************************/ @@ -1196,7 +1196,7 @@ static int stm32f0serial_dmasetup(FAR struct uart_dev_s *dev) int result; uint32_t regval; - /* Do the basic UART setup first, unless we are the console */ + /* Do the basic USART setup first, unless we are the console */ if (!dev->isconsole) { @@ -1240,7 +1240,7 @@ static int stm32f0serial_dmasetup(FAR struct uart_dev_s *dev) priv->rxdmanext = 0; - /* Enable receive DMA for the UART */ + /* Enable receive DMA for the USART */ regval = stm32f0serial_getreg(priv, STM32F0_USART_CR3_OFFSET); regval |= USART_CR3_DMAR; @@ -1295,7 +1295,7 @@ static void stm32f0serial_shutdown(FAR struct uart_dev_s *dev) stm32f0serial_setapbclock(dev, false); - /* Disable Rx, Tx, and the UART */ + /* Disable Rx, Tx, and the USART */ regval = stm32f0serial_getreg(priv, STM32F0_USART_CR1_OFFSET); regval &= ~(USART_CR1_UE | USART_CR1_TE | USART_CR1_RE); @@ -1348,7 +1348,7 @@ static void stm32f0serial_dmashutdown(FAR struct uart_dev_s *dev) { FAR struct stm32f0_serial_s *priv = (FAR struct stm32f0_serial_s *)dev->priv; - /* Perform the normal UART shutdown */ + /* Perform the normal USART shutdown */ stm32f0serial_shutdown(dev); @@ -1880,11 +1880,11 @@ static bool stm32f0serial_rxavailable(FAR struct uart_dev_s *dev) * Description: * Called when Rx buffer is full (or exceeds configured watermark levels * if CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS is defined). - * Return true if UART activated RX flow control to block more incoming + * Return true if USART activated RX flow control to block more incoming * data * * Input parameters: - * dev - UART device instance + * dev - USART device instance * nbuffered - the number of characters currently buffered * (if CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS is * not defined the value will be 0 for an empty buffer or the @@ -1924,7 +1924,7 @@ static bool stm32f0serial_rxflowcontrol(FAR struct uart_dev_s *dev, * peripheral. When hardware RTS is enabled, this will * prevent more data from coming in. * - * This function is only called when UART recv buffer is full, + * This function is only called when USART recv buffer is full, * that is: "dev->recv.head + 1 == dev->recv.tail". * * Logic in "uart_read" will automatically toggle Rx interrupts @@ -2367,7 +2367,7 @@ void up_earlyserialinit(void) #if CONSOLE_USART > 0 stm32f0serial_setup(&uart_devs[CONSOLE_USART - 1]->dev); #endif -#endif /* HAVE UART */ +#endif /* HAVE USART */ } #endif @@ -2404,7 +2404,7 @@ void up_serialinit(void) (void)uart_register("/dev/console", &uart_devs[CONSOLE_USART - 1]->dev); #ifndef CONFIG_SERIAL_DISABLE_REORDERING - /* If not disabled, register the console UART to ttyS0 and exclude + /* If not disabled, register the console USART to ttyS0 and exclude * it from initializing it further down */ @@ -2446,7 +2446,7 @@ void up_serialinit(void) devname[9] = '0' + minor++; (void)uart_register(devname, &uart_devs[i]->dev); } -#endif /* HAVE UART */ +#endif /* HAVE USART */ } /**************************************************************************** diff --git a/arch/arm/src/stm32f0/stm32f0_serial.h b/arch/arm/src/stm32f0/stm32f0_serial.h index c850b47f3c..c3922c6201 100644 --- a/arch/arm/src/stm32f0/stm32f0_serial.h +++ b/arch/arm/src/stm32f0/stm32f0_serial.h @@ -42,42 +42,9 @@ ************************************************************************************/ #include -#include - -#include "chip/stm32f0_uart.h" -#include "chip/stm32f0_syscfg.h" - -#include "stm32f0_gpio.h" /************************************************************************************ * Pre-processor Definitions ************************************************************************************/ -/* Configuration *********************************************************************/ - -/* Are any UARTs enabled? */ - -#undef HAVE_USART -#if defined(CONFIG_STM32F0_UART0) -# define HAVE_USART 1 -#endif - -/* Is there a serial console? There should be at most one defined. It could be on - * any UARTn, n=0,1,2,3 - */ - -#if defined(CONFIG_UART0_SERIAL_CONSOLE) && defined(CONFIG_STM32F0_UART0) -# define HAVE_SERIAL_CONSOLE 1 -#else -# undef CONFIG_UART0_SERIAL_CONSOLE -# undef HAVE_SERIAL_CONSOLE -#endif - -/* We cannot allow the DLM/DLL divisor to become to small or will will lose too - * much accuracy. This following is a "fudge factor" that represents the minimum - * value of the divisor that we will permit. - */ - -#define UART_MINDL 32 - #endif /* __ARCH_ARM_SRC_STM32F0_STM32F0_SERIAL_H */ diff --git a/arch/arm/src/stm32f0/stm32f0_start.c b/arch/arm/src/stm32f0/stm32f0_start.c index 6482dd47aa..f175430c28 100644 --- a/arch/arm/src/stm32f0/stm32f0_start.c +++ b/arch/arm/src/stm32f0/stm32f0_start.c @@ -75,7 +75,7 @@ const uint32_t g_idle_topstack = IDLE_STACK; * Name: showprogress * * Description: - * Print a character on the UART to show boot status. + * Print a character on the CONSOLE USART to show boot status. * ****************************************************************************/ diff --git a/configs/stm32f0discovery/nsh/defconfig b/configs/stm32f0discovery/nsh/defconfig index e74c51cb41..6c34641ae8 100644 --- a/configs/stm32f0discovery/nsh/defconfig +++ b/configs/stm32f0discovery/nsh/defconfig @@ -856,10 +856,10 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512 # CONFIG_EXAMPLES_MOUNT is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NX is not set # CONFIG_EXAMPLES_NXFFS is not set # CONFIG_EXAMPLES_NXHELLO is not set # CONFIG_EXAMPLES_NXIMAGE is not set -# CONFIG_EXAMPLES_NX is not set # CONFIG_EXAMPLES_NXLINES is not set # CONFIG_EXAMPLES_NXTERM is not set # CONFIG_EXAMPLES_NXTEXT is not set -- GitLab From 54eae7dcde8e2e13f144d31f1fd0531df1531a2a Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Tue, 18 Apr 2017 06:49:51 -0600 Subject: [PATCH 496/990] STM32F7: warn if no DMA2 configured when using ADC with DMA. Also correct ADC channel numbers that DMA callback passes to upper half driver. --- arch/arm/src/stm32f7/Kconfig | 4 +--- arch/arm/src/stm32f7/chip/stm32_adc.h | 4 ---- arch/arm/src/stm32f7/stm32_adc.c | 10 ++++++++-- arch/arm/src/stm32f7/stm32_adc.h | 6 +++--- arch/arm/src/stm32f7/stm32_dma.c | 2 +- 5 files changed, 13 insertions(+), 13 deletions(-) diff --git a/arch/arm/src/stm32f7/Kconfig b/arch/arm/src/stm32f7/Kconfig index 2c21fadf61..3ed2341a4b 100644 --- a/arch/arm/src/stm32f7/Kconfig +++ b/arch/arm/src/stm32f7/Kconfig @@ -1014,7 +1014,6 @@ config STM32F7_ADC1 bool "ADC1" default n select STM32F7_ADC - select STM32F7_HAVE_ADC1_DMA if STM32F7_DMA1 select STM32F7_HAVE_ADC1_DMA if STM32F7_DMA2 config STM32F7_ADC2 @@ -1027,8 +1026,7 @@ config STM32F7_ADC3 bool "ADC3" default n select STM32F7_ADC - select STM32F7_HAVE_ADC1_DMA if STM32F7_DMA1 - select STM32F7_HAVE_ADC1_DMA if STM32F7_DMA2 + select STM32F7_HAVE_ADC3_DMA if STM32F7_DMA2 config STM32F7_BKPSRAM bool "Enable BKP RAM Domain" diff --git a/arch/arm/src/stm32f7/chip/stm32_adc.h b/arch/arm/src/stm32f7/chip/stm32_adc.h index 7b0861d77e..9ac5f68107 100644 --- a/arch/arm/src/stm32f7/chip/stm32_adc.h +++ b/arch/arm/src/stm32f7/chip/stm32_adc.h @@ -41,10 +41,6 @@ * Included Files ****************************************************************************************************/ -#include - -#include "chip.h" - #include #include "chip.h" diff --git a/arch/arm/src/stm32f7/stm32_adc.c b/arch/arm/src/stm32f7/stm32_adc.c index df3ab7028e..55593a5d19 100644 --- a/arch/arm/src/stm32f7/stm32_adc.c +++ b/arch/arm/src/stm32f7/stm32_adc.c @@ -131,6 +131,12 @@ #define ADC_MAX_CHANNELS_DMA 16 #define ADC_MAX_CHANNELS_NODMA 1 +#ifdef ADC_HAVE_DMA +# ifndef CONFIG_STM32F7_DMA2 +# error "STM32F7 ADC DMA support requires CONFIG_STM32F7_DMA2" +# endif +#endif + #ifdef ADC_HAVE_DMA # define ADC_MAX_SAMPLES ADC_MAX_CHANNELS_DMA #else @@ -1133,7 +1139,7 @@ static void adc_dmaconvcallback(DMA_HANDLE handle, uint8_t isr, FAR void *arg) for (i = 0; i < priv->nchannels; i++) { - priv->cb->au_receive(dev, priv->current, priv->dmabuffer[priv->current]); + priv->cb->au_receive(dev, priv->chanlist[priv->current], priv->dmabuffer[priv->current]); priv->current++; if (priv->current >= priv->nchannels) { @@ -1721,7 +1727,7 @@ static int adc123_interrupt(int irq, FAR void *context, FAR void *arg) * cchannels - Number of channels * * Returned Value: - * Valid ADC device structure reference on succcess; a NULL on failure + * Valid ADC device structure reference on success; a NULL on failure * ****************************************************************************/ diff --git a/arch/arm/src/stm32f7/stm32_adc.h b/arch/arm/src/stm32f7/stm32_adc.h index f07afe42db..fa1c0bb2ec 100644 --- a/arch/arm/src/stm32f7/stm32_adc.h +++ b/arch/arm/src/stm32f7/stm32_adc.h @@ -750,14 +750,14 @@ extern "C" * nchannels - Number of channels * * Returned Value: - * Valid can device structure reference on succcess; a NULL on failure + * Valid ADC device structure reference on success; a NULL on failure * ****************************************************************************/ struct adc_dev_s; struct adc_dev_s *stm32_adc_initialize(int intf, - FAR const uint8_t *chanlist, - int nchannels); + FAR const uint8_t *chanlist, + int nchannels); #undef EXTERN #ifdef __cplusplus } diff --git a/arch/arm/src/stm32f7/stm32_dma.c b/arch/arm/src/stm32f7/stm32_dma.c index e1d8256f09..4ff9274004 100644 --- a/arch/arm/src/stm32f7/stm32_dma.c +++ b/arch/arm/src/stm32f7/stm32_dma.c @@ -80,7 +80,7 @@ /* Convert the DMA stream base address to the DMA register block address */ -#define DMA_BASE(ch) (ch & 0xfffffc00) +#define DMA_BASE(ch) ((ch) & 0xfffffc00) /**************************************************************************** * Private Types -- GitLab From 3c0f3ea35bdf0695a792bc5ef776ed4eb2406090 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Tue, 18 Apr 2017 06:51:20 -0600 Subject: [PATCH 497/990] STM32F7: stm32_adc: Do not override ADCPRE_DIV when measuring internal voltage --- arch/arm/src/stm32f7/stm32_adc.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/arch/arm/src/stm32f7/stm32_adc.c b/arch/arm/src/stm32f7/stm32_adc.c index 55593a5d19..626e053c11 100644 --- a/arch/arm/src/stm32f7/stm32_adc.c +++ b/arch/arm/src/stm32f7/stm32_adc.c @@ -1277,12 +1277,12 @@ static void adc_reset(FAR struct adc_dev_s *dev) /* ADC CCR configuration */ - clrbits = ADC_CCR_ADCPRE_MASK | ADC_CCR_TSVREFE; - setbits = ADC_CCR_ADCPRE_DIV; + clrbits = ADC_CCR_ADCPRE_MASK | ADC_CCR_TSVREFE; + setbits = ADC_CCR_ADCPRE_DIV; if (adc_internal(priv)) { - setbits = ADC_CCR_TSVREFE; + setbits |= ADC_CCR_TSVREFE; } clrbits |= ADC_CCR_MULTI_MASK | ADC_CCR_DELAY_MASK | ADC_CCR_DDS | -- GitLab From 04ebdbb336d3aa1ab0c86ee232e9700b39c944a0 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 18 Apr 2017 07:16:35 -0600 Subject: [PATCH 498/990] Move: CONFIG_ADC_NO_START_CONV from drivers/adc/Kconfig to arch/arm/src/stm32[f7]/Kconfig as STM32[F7]_ADC_NO_START_CONV. Refresh all configurations with any reference to CONFIG_ADC_NO_START_CONV. --- arch/arm/src/stm32/Kconfig | 6 ++++ arch/arm/src/stm32/stm32_adc.c | 4 +-- arch/arm/src/stm32f7/Kconfig | 6 ++++ arch/arm/src/stm32f7/stm32_adc.c | 4 +-- configs/nucleo-f303re/adc/defconfig | 28 ++++++++++++--- configs/nucleo-f303re/serialrx/defconfig | 27 +++++++++++--- configs/olimex-stm32-h405/usbnsh/defconfig | 28 ++++++++++++--- configs/olimex-stm32-p207/nsh/defconfig | 37 +++++++++++++++++--- configs/stm32butterfly2/nsh/defconfig | 32 ++++++++++++++--- configs/stm32butterfly2/nshnet/defconfig | 37 +++++++++++++++++--- configs/stm32butterfly2/nshusbdev/defconfig | 29 ++++++++++++--- configs/stm32butterfly2/nshusbhost/defconfig | 32 ++++++++++++++--- drivers/analog/Kconfig | 7 ---- net/sixlowpan/Kconfig | 2 +- 14 files changed, 233 insertions(+), 46 deletions(-) diff --git a/arch/arm/src/stm32/Kconfig b/arch/arm/src/stm32/Kconfig index 1aa55388f7..79c103ea9c 100644 --- a/arch/arm/src/stm32/Kconfig +++ b/arch/arm/src/stm32/Kconfig @@ -5627,6 +5627,12 @@ endmenu # Timer Configuration menu "ADC Configuration" depends on STM32_ADC +config STM32_ADC_NO_STARTUP_CONV + bool "Do not start conversion when opening ADC device" + default n + ---help--- + Do not start conversion when opening ADC device. + config STM32_ADC1_DMA bool "ADC1 DMA" depends on STM32_ADC1 && STM32_HAVE_ADC1_DMA diff --git a/arch/arm/src/stm32/stm32_adc.c b/arch/arm/src/stm32/stm32_adc.c index 66ae2ce8b0..43e349eff0 100644 --- a/arch/arm/src/stm32/stm32_adc.c +++ b/arch/arm/src/stm32/stm32_adc.c @@ -2054,11 +2054,11 @@ static void adc_reset(FAR struct adc_dev_s *dev) aerr("ERROR: adc_timinit failed: %d\n", ret); } } -#ifndef CONFIG_ADC_NO_STARTUP_CONV +#ifndef CONFIG_STM32_ADC_NO_STARTUP_CONV else #endif #endif -#ifndef CONFIG_ADC_NO_STARTUP_CONV +#ifndef CONFIG_STM32_ADC_NO_STARTUP_CONV { adc_startconv(priv, true); } diff --git a/arch/arm/src/stm32f7/Kconfig b/arch/arm/src/stm32f7/Kconfig index 3ed2341a4b..8e9904a0ab 100644 --- a/arch/arm/src/stm32f7/Kconfig +++ b/arch/arm/src/stm32f7/Kconfig @@ -4396,6 +4396,12 @@ endmenu # Timer Configuration menu "ADC Configuration" depends on STM32F7_ADC +config STM32F7_ADC_NO_STARTUP_CONV + bool "Do not start conversion when opening ADC device" + default n + ---help--- + Do not start conversion when opening ADC device. + config STM32F7_ADC1_DMA bool "ADC1 DMA" depends on STM32F7_ADC1 && STM32F7_HAVE_ADC1_DMA diff --git a/arch/arm/src/stm32f7/stm32_adc.c b/arch/arm/src/stm32f7/stm32_adc.c index 626e053c11..8695a6a8e0 100644 --- a/arch/arm/src/stm32f7/stm32_adc.c +++ b/arch/arm/src/stm32f7/stm32_adc.c @@ -1331,11 +1331,11 @@ static void adc_reset(FAR struct adc_dev_s *dev) aerr("ERROR: adc_timinit failed: %d\n", ret); } } -#ifndef CONFIG_ADC_NO_STARTUP_CONV +#ifndef CONFIG_STM32F7_ADC_NO_STARTUP_CONV else #endif #endif -#ifndef CONFIG_ADC_NO_STARTUP_CONV +#ifndef CONFIG_STM32F7_ADC_NO_STARTUP_CONV { adc_startconv(priv, true); } diff --git a/configs/nucleo-f303re/adc/defconfig b/configs/nucleo-f303re/adc/defconfig index e5357a746b..ee469d2e8d 100644 --- a/configs/nucleo-f303re/adc/defconfig +++ b/configs/nucleo-f303re/adc/defconfig @@ -90,6 +90,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +98,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -371,9 +373,13 @@ CONFIG_STM32_HAVE_ADC1_DMA=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y # CONFIG_STM32_HAVE_CAN2 is not set +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y # CONFIG_STM32_HAVE_RNG is not set @@ -387,7 +393,10 @@ CONFIG_STM32_HAVE_SPI4=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set CONFIG_STM32_ADC1=y # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -401,6 +410,7 @@ CONFIG_STM32_DMA2=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set # CONFIG_STM32_PWR is not set # CONFIG_STM32_SDIO is not set # CONFIG_STM32_SPI1 is not set @@ -433,6 +443,7 @@ CONFIG_STM32_ADC=y # # Alternate Pin Mapping # +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -456,6 +467,7 @@ CONFIG_STM32_CCMEXCLUDE=y # # ADC Configuration # +# CONFIG_STM32_ADC_NO_STARTUP_CONV is not set # CONFIG_STM32_ADC1_DMA is not set # CONFIG_STM32_HAVE_RTC_COUNTER is not set # CONFIG_STM32_HAVE_RTC_SUBSECONDS is not set @@ -611,6 +623,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -709,10 +723,11 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y CONFIG_ANALOG=y CONFIG_ADC=y CONFIG_ADC_FIFOSIZE=8 -# CONFIG_ADC_NO_STARTUP_CONV is not set # CONFIG_ADC_ADS1242 is not set # CONFIG_ADC_ADS125X is not set +# CONFIG_ADC_LTC1867L is not set # CONFIG_ADC_PGA11X is not set +# CONFIG_COMP is not set # CONFIG_DAC is not set # CONFIG_AUDIO_DEVICES is not set # CONFIG_VIDEO_DEVICES is not set @@ -749,6 +764,7 @@ CONFIG_ADC_FIFOSIZE=8 # CONFIG_SERIAL is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -979,7 +995,6 @@ CONFIG_EXAMPLES_ADC_SWTRIG=y # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set # CONFIG_EXAMPLES_NSH is not set # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -1010,6 +1025,7 @@ CONFIG_EXAMPLES_ADC_SWTRIG=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1080,3 +1096,7 @@ CONFIG_EXAMPLES_ADC_SWTRIG=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# diff --git a/configs/nucleo-f303re/serialrx/defconfig b/configs/nucleo-f303re/serialrx/defconfig index b4ff9650dc..1565a99eca 100644 --- a/configs/nucleo-f303re/serialrx/defconfig +++ b/configs/nucleo-f303re/serialrx/defconfig @@ -90,6 +90,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +98,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -372,9 +374,13 @@ CONFIG_STM32_HAVE_ADC4=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y # CONFIG_STM32_HAVE_CAN2 is not set +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y # CONFIG_STM32_HAVE_RNG is not set @@ -388,7 +394,10 @@ CONFIG_STM32_HAVE_SPI4=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -402,6 +411,7 @@ CONFIG_STM32_HAVE_SPI4=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set # CONFIG_STM32_PWR is not set # CONFIG_STM32_SDIO is not set # CONFIG_STM32_SPI1 is not set @@ -433,6 +443,7 @@ CONFIG_STM32_UART4=y # # Alternate Pin Mapping # +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -626,6 +637,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -724,10 +737,11 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y CONFIG_ANALOG=y CONFIG_ADC=y CONFIG_ADC_FIFOSIZE=8 -# CONFIG_ADC_NO_STARTUP_CONV is not set # CONFIG_ADC_ADS1242 is not set # CONFIG_ADC_ADS125X is not set +# CONFIG_ADC_LTC1867L is not set # CONFIG_ADC_PGA11X is not set +# CONFIG_COMP is not set # CONFIG_DAC is not set # CONFIG_AUDIO_DEVICES is not set # CONFIG_VIDEO_DEVICES is not set @@ -812,6 +826,7 @@ CONFIG_UART4_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -1038,7 +1053,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set # CONFIG_EXAMPLES_NSH is not set # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -1077,6 +1091,7 @@ CONFIG_EXAMPLES_SERIALRX_PRINTSTR=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1147,3 +1162,7 @@ CONFIG_EXAMPLES_SERIALRX_PRINTSTR=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# diff --git a/configs/olimex-stm32-h405/usbnsh/defconfig b/configs/olimex-stm32-h405/usbnsh/defconfig index 5d02b51b90..60a9d7d2e8 100644 --- a/configs/olimex-stm32-h405/usbnsh/defconfig +++ b/configs/olimex-stm32-h405/usbnsh/defconfig @@ -90,6 +90,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +98,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -378,9 +380,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -394,7 +400,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set CONFIG_STM32_ADC1=y # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -414,6 +423,7 @@ CONFIG_STM32_CAN1=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set CONFIG_STM32_OTGFS=y # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -453,6 +463,7 @@ CONFIG_STM32_CAN=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -488,6 +499,7 @@ CONFIG_STM32_ADC1_TIMTRIG=0 # # ADC Configuration # +# CONFIG_STM32_ADC_NO_STARTUP_CONV is not set CONFIG_STM32_USART=y CONFIG_STM32_SERIALDRIVER=y @@ -668,6 +680,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -777,10 +791,11 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y CONFIG_ANALOG=y CONFIG_ADC=y CONFIG_ADC_FIFOSIZE=8 -# CONFIG_ADC_NO_STARTUP_CONV is not set # CONFIG_ADC_ADS1242 is not set # CONFIG_ADC_ADS125X is not set +# CONFIG_ADC_LTC1867L is not set # CONFIG_ADC_PGA11X is not set +# CONFIG_COMP is not set # CONFIG_DAC is not set # CONFIG_AUDIO_DEVICES is not set # CONFIG_VIDEO_DEVICES is not set @@ -905,6 +920,7 @@ CONFIG_CDCACM_VENDORSTR="NuttX" CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial" # CONFIG_USBMSC is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -1161,7 +1177,6 @@ CONFIG_EXAMPLES_CAN_READWRITE=y # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1194,6 +1209,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1363,3 +1379,7 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# diff --git a/configs/olimex-stm32-p207/nsh/defconfig b/configs/olimex-stm32-p207/nsh/defconfig index 6f9a15d88f..ad40ad6b83 100644 --- a/configs/olimex-stm32-p207/nsh/defconfig +++ b/configs/olimex-stm32-p207/nsh/defconfig @@ -90,6 +90,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +98,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -380,9 +382,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -396,7 +402,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set CONFIG_STM32_ADC1=y # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -416,6 +425,7 @@ CONFIG_STM32_ETHMAC=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set CONFIG_STM32_OTGFS=y # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -455,6 +465,7 @@ CONFIG_STM32_CAN=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -489,6 +500,7 @@ CONFIG_STM32_ADC1_TIMTRIG=0 # # ADC Configuration # +# CONFIG_STM32_ADC_NO_STARTUP_CONV is not set CONFIG_STM32_USART=y CONFIG_STM32_SERIALDRIVER=y @@ -694,6 +706,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -803,10 +817,11 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y CONFIG_ANALOG=y CONFIG_ADC=y CONFIG_ADC_FIFOSIZE=8 -# CONFIG_ADC_NO_STARTUP_CONV is not set # CONFIG_ADC_ADS1242 is not set # CONFIG_ADC_ADS125X is not set +# CONFIG_ADC_LTC1867L is not set # CONFIG_ADC_PGA11X is not set +# CONFIG_COMP is not set # CONFIG_DAC is not set # CONFIG_AUDIO_DEVICES is not set # CONFIG_VIDEO_DEVICES is not set @@ -940,7 +955,9 @@ CONFIG_USBHOST_HAVE_ASYNCH=y # CONFIG_USBHOST_HIDKBD is not set # CONFIG_USBHOST_HIDMOUSE is not set # CONFIG_USBHOST_RTL8187 is not set +# CONFIG_USBHOST_XBOXCONTROLLER is not set # CONFIG_USBHOST_TRACE is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -981,10 +998,12 @@ CONFIG_NET_GUARDSIZE=2 CONFIG_NET_ETHERNET=y # CONFIG_NET_LOOPBACK is not set # CONFIG_NET_TUN is not set +# CONFIG_NET_USRSOCK is not set # # Network Device Operations # +# CONFIG_NETDEV_IOCTL is not set # CONFIG_NETDEV_PHY_IOCTL is not set # @@ -1015,6 +1034,7 @@ CONFIG_NET_SOCKOPTS=y # TCP/IP Networking # CONFIG_NET_TCP=y +# CONFIG_NET_TCP_NO_STACK is not set # CONFIG_NET_TCPURGDATA is not set CONFIG_NET_TCP_CONNS=8 CONFIG_NET_MAX_LISTENPORTS=20 @@ -1029,6 +1049,7 @@ CONFIG_NET_TCP_RECVDELAY=0 # UDP Networking # CONFIG_NET_UDP=y +# CONFIG_NET_UDP_NO_STACK is not set # CONFIG_NET_UDP_CHECKSUMS is not set CONFIG_NET_UDP_CONNS=8 # CONFIG_NET_BROADCAST is not set @@ -1062,6 +1083,10 @@ CONFIG_NET_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 + +# +# User-space networking stack API +# # CONFIG_NET_ARCH_INCR32 is not set # CONFIG_NET_ARCH_CHKSUM is not set CONFIG_NET_STATISTICS=y @@ -1309,7 +1334,6 @@ CONFIG_EXAMPLES_ADC_GROUPSIZE=1 # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set # CONFIG_EXAMPLES_NETTEST is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1344,6 +1368,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1547,3 +1572,7 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# diff --git a/configs/stm32butterfly2/nsh/defconfig b/configs/stm32butterfly2/nsh/defconfig index cc58d6dc2f..9d8bc5eb15 100644 --- a/configs/stm32butterfly2/nsh/defconfig +++ b/configs/stm32butterfly2/nsh/defconfig @@ -90,6 +90,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +98,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -375,9 +377,13 @@ CONFIG_STM32_HAVE_ADC2=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y # CONFIG_STM32_HAVE_RNG is not set @@ -391,7 +397,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set CONFIG_STM32_ADC1=y # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_BKP is not set @@ -404,6 +413,7 @@ CONFIG_STM32_ADC1=y # CONFIG_STM32_DAC2 is not set # CONFIG_STM32_ETHMAC is not set # CONFIG_STM32_I2C1 is not set +# CONFIG_STM32_OPAMP is not set CONFIG_STM32_OTGFS=y CONFIG_STM32_PWR=y CONFIG_STM32_SPI1=y @@ -433,6 +443,7 @@ CONFIG_STM32_SPI=y # # CONFIG_STM32_SPI1_REMAP is not set CONFIG_STM32_USART2_REMAP=y +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set CONFIG_STM32_JTAG_FULL_ENABLE=y # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -455,6 +466,7 @@ CONFIG_STM32_JTAG_FULL_ENABLE=y # # ADC Configuration # +# CONFIG_STM32_ADC_NO_STARTUP_CONV is not set CONFIG_STM32_USART=y CONFIG_STM32_SERIALDRIVER=y @@ -637,6 +649,9 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -751,10 +766,11 @@ CONFIG_SPI_CALLBACK=y CONFIG_ANALOG=y CONFIG_ADC=y CONFIG_ADC_FIFOSIZE=8 -# CONFIG_ADC_NO_STARTUP_CONV is not set # CONFIG_ADC_ADS1242 is not set # CONFIG_ADC_ADS125X is not set +# CONFIG_ADC_LTC1867L is not set # CONFIG_ADC_PGA11X is not set +# CONFIG_COMP is not set # CONFIG_DAC is not set # CONFIG_AUDIO_DEVICES is not set # CONFIG_VIDEO_DEVICES is not set @@ -869,7 +885,9 @@ CONFIG_HIDKBD_NPOLLWAITERS=2 # CONFIG_HIDKBD_ALLSCANCODES is not set # CONFIG_HIDKBD_NODEBOUNCE is not set # CONFIG_USBHOST_HIDMOUSE is not set +# CONFIG_USBHOST_XBOXCONTROLLER is not set # CONFIG_USBHOST_TRACE is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -1120,8 +1138,8 @@ CONFIG_EXAMPLES_ADC_SWTRIG=y # CONFIG_EXAMPLES_FTPD is not set # CONFIG_EXAMPLES_HELLO is not set CONFIG_EXAMPLES_HIDKBD=y -CONFIG_EXAMPLES_HIDKBD_DEFPRIO=50 CONFIG_EXAMPLES_HIDKBD_STACKSIZE=1024 +CONFIG_EXAMPLES_HIDKBD_DEFPRIO=50 CONFIG_EXAMPLES_HIDKBD_DEVNAME="/dev/kbda" # CONFIG_EXAMPLES_IGMP is not set # CONFIG_EXAMPLES_JSON is not set @@ -1134,7 +1152,6 @@ CONFIG_EXAMPLES_MOUNT=y CONFIG_EXAMPLES_MOUNT_NSECTORS=2048 CONFIG_EXAMPLES_MOUNT_SECTORSIZE=512 CONFIG_EXAMPLES_MOUNT_RAMDEVNO=0 -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -1166,6 +1183,7 @@ CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1350,3 +1368,7 @@ CONFIG_SYSTEM_VI_DEBUGLEVEL=0 CONFIG_SYSTEM_VI_STACKSIZE=2048 CONFIG_SYSTEM_VI_PRIORITY=100 # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# diff --git a/configs/stm32butterfly2/nshnet/defconfig b/configs/stm32butterfly2/nshnet/defconfig index 018450beca..c2794486b2 100644 --- a/configs/stm32butterfly2/nshnet/defconfig +++ b/configs/stm32butterfly2/nshnet/defconfig @@ -90,6 +90,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +98,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -372,9 +374,13 @@ CONFIG_STM32_HAVE_ADC2=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y # CONFIG_STM32_HAVE_RNG is not set @@ -388,7 +394,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set CONFIG_STM32_ADC1=y # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_BKP is not set @@ -401,6 +410,7 @@ CONFIG_STM32_ADC1=y # CONFIG_STM32_DAC2 is not set CONFIG_STM32_ETHMAC=y # CONFIG_STM32_I2C1 is not set +# CONFIG_STM32_OPAMP is not set CONFIG_STM32_OTGFS=y CONFIG_STM32_PWR=y CONFIG_STM32_SPI1=y @@ -431,6 +441,7 @@ CONFIG_STM32_SPI=y CONFIG_STM32_ETH_REMAP=y # CONFIG_STM32_SPI1_REMAP is not set CONFIG_STM32_USART2_REMAP=y +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set CONFIG_STM32_JTAG_FULL_ENABLE=y # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -453,6 +464,7 @@ CONFIG_STM32_JTAG_FULL_ENABLE=y # # ADC Configuration # +# CONFIG_STM32_ADC_NO_STARTUP_CONV is not set CONFIG_STM32_USART=y CONFIG_STM32_SERIALDRIVER=y @@ -645,6 +657,9 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -759,10 +774,11 @@ CONFIG_SPI_CALLBACK=y CONFIG_ANALOG=y CONFIG_ADC=y CONFIG_ADC_FIFOSIZE=8 -# CONFIG_ADC_NO_STARTUP_CONV is not set # CONFIG_ADC_ADS1242 is not set # CONFIG_ADC_ADS125X is not set +# CONFIG_ADC_LTC1867L is not set # CONFIG_ADC_PGA11X is not set +# CONFIG_COMP is not set # CONFIG_DAC is not set # CONFIG_AUDIO_DEVICES is not set # CONFIG_VIDEO_DEVICES is not set @@ -935,6 +951,7 @@ CONFIG_PL2303_PRODUCTSTR="PL2303 Emulation" # CONFIG_CDCACM is not set # CONFIG_USBMSC is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -975,10 +992,12 @@ CONFIG_NET_GUARDSIZE=2 CONFIG_NET_ETHERNET=y # CONFIG_NET_LOOPBACK is not set # CONFIG_NET_TUN is not set +# CONFIG_NET_USRSOCK is not set # # Network Device Operations # +# CONFIG_NETDEV_IOCTL is not set # CONFIG_NETDEV_PHY_IOCTL is not set # @@ -1010,6 +1029,7 @@ CONFIG_NET_LOCAL_DGRAM=y # TCP/IP Networking # CONFIG_NET_TCP=y +# CONFIG_NET_TCP_NO_STACK is not set # CONFIG_NET_TCPURGDATA is not set CONFIG_NET_TCP_CONNS=8 CONFIG_NET_MAX_LISTENPORTS=20 @@ -1025,6 +1045,7 @@ CONFIG_NET_TCP_SPLIT_SIZE=40 # UDP Networking # CONFIG_NET_UDP=y +# CONFIG_NET_UDP_NO_STACK is not set # CONFIG_NET_UDP_CHECKSUMS is not set CONFIG_NET_UDP_CONNS=8 # CONFIG_NET_BROADCAST is not set @@ -1058,6 +1079,10 @@ CONFIG_NET_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 + +# +# User-space networking stack API +# # CONFIG_NET_ARCH_INCR32 is not set # CONFIG_NET_ARCH_CHKSUM is not set # CONFIG_NET_STATISTICS is not set @@ -1309,7 +1334,6 @@ CONFIG_EXAMPLES_MOUNT_NSECTORS=2048 CONFIG_EXAMPLES_MOUNT_SECTORSIZE=512 CONFIG_EXAMPLES_MOUNT_RAMDEVNO=0 # CONFIG_EXAMPLES_NETTEST is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -1347,6 +1371,7 @@ CONFIG_EXAMPLES_USBSERIAL_BUFSIZE=512 # CONFIG_EXAMPLES_USTREAM is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # CONFIG_EXAMPLES_XMLRPC is not set # @@ -1568,3 +1593,7 @@ CONFIG_SYSTEM_VI_DEBUGLEVEL=0 CONFIG_SYSTEM_VI_STACKSIZE=2048 CONFIG_SYSTEM_VI_PRIORITY=100 # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# diff --git a/configs/stm32butterfly2/nshusbdev/defconfig b/configs/stm32butterfly2/nshusbdev/defconfig index cef7a6a75b..8fd69ba946 100644 --- a/configs/stm32butterfly2/nshusbdev/defconfig +++ b/configs/stm32butterfly2/nshusbdev/defconfig @@ -90,6 +90,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +98,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -372,9 +374,13 @@ CONFIG_STM32_HAVE_ADC2=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y # CONFIG_STM32_HAVE_RNG is not set @@ -388,7 +394,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set CONFIG_STM32_ADC1=y # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_BKP is not set @@ -401,6 +410,7 @@ CONFIG_STM32_ADC1=y # CONFIG_STM32_DAC2 is not set # CONFIG_STM32_ETHMAC is not set # CONFIG_STM32_I2C1 is not set +# CONFIG_STM32_OPAMP is not set CONFIG_STM32_OTGFS=y CONFIG_STM32_PWR=y CONFIG_STM32_SPI1=y @@ -430,6 +440,7 @@ CONFIG_STM32_SPI=y # # CONFIG_STM32_SPI1_REMAP is not set CONFIG_STM32_USART2_REMAP=y +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set CONFIG_STM32_JTAG_FULL_ENABLE=y # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -452,6 +463,7 @@ CONFIG_STM32_JTAG_FULL_ENABLE=y # # ADC Configuration # +# CONFIG_STM32_ADC_NO_STARTUP_CONV is not set CONFIG_STM32_USART=y CONFIG_STM32_SERIALDRIVER=y @@ -630,6 +642,9 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -744,10 +759,11 @@ CONFIG_SPI_CALLBACK=y CONFIG_ANALOG=y CONFIG_ADC=y CONFIG_ADC_FIFOSIZE=8 -# CONFIG_ADC_NO_STARTUP_CONV is not set # CONFIG_ADC_ADS1242 is not set # CONFIG_ADC_ADS125X is not set +# CONFIG_ADC_LTC1867L is not set # CONFIG_ADC_PGA11X is not set +# CONFIG_COMP is not set # CONFIG_DAC is not set # CONFIG_AUDIO_DEVICES is not set # CONFIG_VIDEO_DEVICES is not set @@ -879,6 +895,7 @@ CONFIG_PL2303_PRODUCTSTR="PL2303 Emulation" # CONFIG_CDCACM is not set # CONFIG_USBMSC is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -1140,7 +1157,6 @@ CONFIG_EXAMPLES_MOUNT=y CONFIG_EXAMPLES_MOUNT_NSECTORS=2048 CONFIG_EXAMPLES_MOUNT_SECTORSIZE=512 CONFIG_EXAMPLES_MOUNT_RAMDEVNO=0 -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -1173,6 +1189,7 @@ CONFIG_EXAMPLES_USBSERIAL=y CONFIG_EXAMPLES_USBSERIAL_BUFSIZE=512 # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1357,3 +1374,7 @@ CONFIG_SYSTEM_VI_DEBUGLEVEL=0 CONFIG_SYSTEM_VI_STACKSIZE=2048 CONFIG_SYSTEM_VI_PRIORITY=100 # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# diff --git a/configs/stm32butterfly2/nshusbhost/defconfig b/configs/stm32butterfly2/nshusbhost/defconfig index cc58d6dc2f..9d8bc5eb15 100644 --- a/configs/stm32butterfly2/nshusbhost/defconfig +++ b/configs/stm32butterfly2/nshusbhost/defconfig @@ -90,6 +90,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +98,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -375,9 +377,13 @@ CONFIG_STM32_HAVE_ADC2=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y # CONFIG_STM32_HAVE_RNG is not set @@ -391,7 +397,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set CONFIG_STM32_ADC1=y # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_BKP is not set @@ -404,6 +413,7 @@ CONFIG_STM32_ADC1=y # CONFIG_STM32_DAC2 is not set # CONFIG_STM32_ETHMAC is not set # CONFIG_STM32_I2C1 is not set +# CONFIG_STM32_OPAMP is not set CONFIG_STM32_OTGFS=y CONFIG_STM32_PWR=y CONFIG_STM32_SPI1=y @@ -433,6 +443,7 @@ CONFIG_STM32_SPI=y # # CONFIG_STM32_SPI1_REMAP is not set CONFIG_STM32_USART2_REMAP=y +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set CONFIG_STM32_JTAG_FULL_ENABLE=y # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -455,6 +466,7 @@ CONFIG_STM32_JTAG_FULL_ENABLE=y # # ADC Configuration # +# CONFIG_STM32_ADC_NO_STARTUP_CONV is not set CONFIG_STM32_USART=y CONFIG_STM32_SERIALDRIVER=y @@ -637,6 +649,9 @@ CONFIG_MAX_TASKS=16 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -751,10 +766,11 @@ CONFIG_SPI_CALLBACK=y CONFIG_ANALOG=y CONFIG_ADC=y CONFIG_ADC_FIFOSIZE=8 -# CONFIG_ADC_NO_STARTUP_CONV is not set # CONFIG_ADC_ADS1242 is not set # CONFIG_ADC_ADS125X is not set +# CONFIG_ADC_LTC1867L is not set # CONFIG_ADC_PGA11X is not set +# CONFIG_COMP is not set # CONFIG_DAC is not set # CONFIG_AUDIO_DEVICES is not set # CONFIG_VIDEO_DEVICES is not set @@ -869,7 +885,9 @@ CONFIG_HIDKBD_NPOLLWAITERS=2 # CONFIG_HIDKBD_ALLSCANCODES is not set # CONFIG_HIDKBD_NODEBOUNCE is not set # CONFIG_USBHOST_HIDMOUSE is not set +# CONFIG_USBHOST_XBOXCONTROLLER is not set # CONFIG_USBHOST_TRACE is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -1120,8 +1138,8 @@ CONFIG_EXAMPLES_ADC_SWTRIG=y # CONFIG_EXAMPLES_FTPD is not set # CONFIG_EXAMPLES_HELLO is not set CONFIG_EXAMPLES_HIDKBD=y -CONFIG_EXAMPLES_HIDKBD_DEFPRIO=50 CONFIG_EXAMPLES_HIDKBD_STACKSIZE=1024 +CONFIG_EXAMPLES_HIDKBD_DEFPRIO=50 CONFIG_EXAMPLES_HIDKBD_DEVNAME="/dev/kbda" # CONFIG_EXAMPLES_IGMP is not set # CONFIG_EXAMPLES_JSON is not set @@ -1134,7 +1152,6 @@ CONFIG_EXAMPLES_MOUNT=y CONFIG_EXAMPLES_MOUNT_NSECTORS=2048 CONFIG_EXAMPLES_MOUNT_SECTORSIZE=512 CONFIG_EXAMPLES_MOUNT_RAMDEVNO=0 -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -1166,6 +1183,7 @@ CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1350,3 +1368,7 @@ CONFIG_SYSTEM_VI_DEBUGLEVEL=0 CONFIG_SYSTEM_VI_STACKSIZE=2048 CONFIG_SYSTEM_VI_PRIORITY=100 # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# diff --git a/drivers/analog/Kconfig b/drivers/analog/Kconfig index ec14bdcd05..c1c7dce031 100644 --- a/drivers/analog/Kconfig +++ b/drivers/analog/Kconfig @@ -33,13 +33,6 @@ config ADC_FIFOSIZE this is a ring buffer, the actual number of bytes that can be retained in buffer is (ADC_FIFOSIZE - 1). -config ADC_NO_STARTUP_CONV - bool "Do not start conversion when opening ADC device" - default n - depends on ARCH_CHIP_STM32 - ---help--- - Do not start conversion when opening ADC device. - config ADC_ADS1242 bool "TI ADS1242 support" default n diff --git a/net/sixlowpan/Kconfig b/net/sixlowpan/Kconfig index a5eed25dd7..ad59e29055 100644 --- a/net/sixlowpan/Kconfig +++ b/net/sixlowpan/Kconfig @@ -134,7 +134,7 @@ endif # NET_6LOWPAN_MAXADDRCONTEXT_PREINIT_0 endif # NET_6LOWPAN_COMPRESSION_HC06 config NET_6LOWPAN_RIMEADDR_EXTENDED - int "Extended Rime address" + bool "Extended Rime address" default n ---help--- By default, a 2-byte Rime address is used for the IEEE802.15.4 MAC -- GitLab From 8a5ed57262d2aa7ee7be2107b5c3bfde7ad9e361 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 18 Apr 2017 08:16:21 -0600 Subject: [PATCH 499/990] Nucleo-F072RB: Add directory and README file. --- Documentation/README.html | 5 +- README.txt | 2 + configs/nucleo-f072rb/README.txt | 284 +++++++++++++++++++++++++++++++ 3 files changed, 290 insertions(+), 1 deletion(-) create mode 100644 configs/nucleo-f072rb/README.txt diff --git a/Documentation/README.html b/Documentation/README.html index 2fb8e115e1..727b2f3684 100644 --- a/Documentation/README.html +++ b/Documentation/README.html @@ -8,7 +8,7 @@

    NuttX README Files

    -

    Last Updated: April 15, 2017

    +

    Last Updated: April 18, 2017

    @@ -161,6 +161,9 @@ nuttx/ | | `- README.txt | |- nucleo-144/ | | `- README.txt + | | `- README.txt + | |- nucleo-f072rb/ + | | `- README.txt | |- nucleo-f303re/ | | `- README.txt | |- nucleo-f334r8/ diff --git a/README.txt b/README.txt index fc318715b3..de771d53c7 100644 --- a/README.txt +++ b/README.txt @@ -1548,6 +1548,8 @@ nuttx/ | | `- README.txt | |- nucleo-144/ | | `- README.txt + | |- nucleo-f072rb/ + | | `- README.txt | |- nucleo-f303re/ | | `- README.txt | |- nucleo-f334r8/ diff --git a/configs/nucleo-f072rb/README.txt b/configs/nucleo-f072rb/README.txt new file mode 100644 index 0000000000..fb35cac2d3 --- /dev/null +++ b/configs/nucleo-f072rb/README.txt @@ -0,0 +1,284 @@ +Nucleo-F072RB README +==================== + + This README file discusess the port of NuttX to the STMicro Nucleo-F4072RB + board. That board features the STM32F072RBT6 MCU with 128KiB with 128KiB + of FLASH and 16KiB of SRAM. + +Contents +======== + + - Nucleo-64 Boards + - LEDs + - Buttons + - Serial Console + - Configurations + +Nucleo-64 Boards +================ + + The Nucleo-F072RB is a member of the Nucleo-64 board family. The Nucleo-64 + is a standard board for use with several STM32 parts in the LQFP64 package. + Variants including: + + Order code Targeted STM32 + ------------- -------------- + NUCLEO-F030R8 STM32F030R8T6 + NUCLEO-F070RB STM32F070RBT6 + NUCLEO-F072RB STM32F072RBT6 + NUCLEO-F091RC STM32F091RCT6 + NUCLEO-F103RB STM32F103RBT6 + NUCLEO-F302R8 STM32F302R8T6 + NUCLEO-F303RE STM32F303RET6 + NUCLEO-F334R8 STM32F334R8T6 + NUCLEO-F401RE STM32F401RET6 + NUCLEO-F410RB STM32F410RBT6 + NUCLEO-F411RE STM32F411RET6 + NUCLEO-F446RE STM32F446RET6 + NUCLEO-L053R8 STM32L053R8T6 + NUCLEO-L073RZ STM32L073RZT6 + NUCLEO-L152RE STM32L152RET6 + NUCLEO-L452RE STM32L452RET6 + NUCLEO-L476RG STM32L476RGT6 + +LEDs +==== + + The Nucleo-64 board has one user controlable LED, User LD2. This green + LED is a user LED connected to Arduino signal D13 corresponding to STM32 + I/O PA5 (PB13 on other some other Nucleo-64 boards). + + - When the I/O is HIGH value, the LED is on + - When the I/O is LOW, the LED is off + + These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is + defined. In that case, the usage by the board port is defined in + include/board.h and src/sam_leds.c. The LEDs are used to encode OS-related + events as follows when the red LED (PE24) is available: + + SYMBOL Meaning LD2 + ------------------- ----------------------- ----------- + LED_STARTED NuttX has been started OFF + LED_HEAPALLOCATE Heap has been allocated OFF + LED_IRQSENABLED Interrupts enabled OFF + LED_STACKCREATED Idle stack created ON + LED_INIRQ In an interrupt No change + LED_SIGNAL In a signal handler No change + LED_ASSERTION An assertion failed No change + LED_PANIC The system has crashed Blinking + LED_IDLE MCU is is sleep mode Not used + + Thus if LD2, NuttX has successfully booted and is, apparently, running + normally. If LD2 is flashing at approximately 2Hz, then a fatal error + has been detected and the system has halted. + +Buttons +======= + + B1 USER: the user button is connected to the I/O PC13 (pin 2) of the STM32 + microcontroller. + +Serial Console +============== + + USART1 + ------ + Pins and Connectors: + + RXD: PA10 D3 CN9 pin 3, CN10 pin 33 + PB7 CN7 pin 21 + TXD: PA9 D8 CN5 pin 1, CN10 pin 21 + PB6 D10 CN5 pin 3, CN10 pin 17 + + NOTE: You may need to edit the include/board.h to select different USART1 + pin selections. + + TTL to RS-232 converter connection: + + Nucleo CN10 STM32F072RB + ----------- ------------ + Pin 21 PA9 USART1_TX *Warning you make need to reverse RX/TX on + Pin 33 PA10 USART1_RX some RS-232 converters + Pin 20 GND + Pin 8 U5V + + To configure USART1 as the console: + + CONFIG_STM32_USART1=y + CONFIG_USART1_SERIALDRIVER=y + CONFIG_USART1_SERIAL_CONSOLE=y + CONFIG_USART1_RXBUFSIZE=256 + CONFIG_USART1_TXBUFSIZE=256 + CONFIG_USART1_BAUD=115200 + CONFIG_USART1_BITS=8 + CONFIG_USART1_PARITY=0 + CONFIG_USART1_2STOP=0 + + USART2 + ------ + Pins and Connectors: + + RXD: PA3 To be provided + PA15 + PD6 + TXD: PA2 + PA14 + PD5 + + USART3 + ------ + Pins and Connectors: + + RXD: PB11 To be provided + PC5 + PC11 + D9 + TXD: PB10 + PC4 + PC10 + D8 + + See "Virtual COM Port" and "RS-232 Shield" below. + + USART3 + ------ + Pins and Connectors: + + RXD: PA1 To be provided + PC11 + TXD: PA0 + PC10 + + Virtual COM Port + ---------------- + Yet another option is to use UART2 and the USB virtual COM port. This + option may be more convenient for long term development, but is painful + to use during board bring-up. + + Solder Bridges. This configuration requires: + + - SB62 and SB63 Open: PA2 and PA3 on STM32 MCU are disconnected to D1 + and D0 (pin 7 and pin 8) on Arduino connector CN9 and ST Morpho + connector CN10. + + - SB13 and SB14 Closed: PA2 and PA3 on STM32F103C8T6 (ST-LINK MCU) are + connected to PA3 and PA2 on STM32 MCU to have USART communication + between them. Thus SB61, SB62 and SB63 should be OFF. + + Configuring USART2 is the same as given above. + + Question: What BAUD should be configure to interface with the Virtual + COM port? 115200 8N1? + + Default + ------- + As shipped, SB62 and SB63 are open and SB13 and SB14 closed, so the + virtual COM port is enabled. + + RS-232 Shield + ------------- + Supports a single RS-232 connected via + + Nucleo STM32F4x1RE Shield + --------- --------------- -------- + CN9 Pin 1 PA3 USART2_RXD RXD + CN9 Pin 2 PA2 USART2_TXD TXD + + Support for this shield is enabled by selecting USART2 and configuring + SB13, 14, 62, and 63 as described above under "Virtual COM Port" + +Configurations +============== + + Information Common to All Configurations + ---------------------------------------- + Each Clicker2 configuration is maintained in a sub-directory and can be + selected as follow: + + cd tools + ./configure.sh nucleo-f702rb/ + cd - + . ./setenv.sh + + Before sourcing the setenv.sh file above, you should examine it and + perform edits as necessary so that TOOLCHAIN_BIN is the correct path + to the directory than holds your toolchain binaries. + + And then build NuttX by simply typing the following. At the conclusion of + the make, the nuttx binary will reside in an ELF file called, simply, nuttx. + + make oldconfig + make + + The that is provided above as an argument to the tools/configure.sh + must be is one of the following. + + NOTES: + + 1. These configurations use the mconf-based configuration tool. To + change any of these configurations using that tool, you should: + + a. Build and install the kconfig-mconf tool. See nuttx/README.txt + see additional README.txt files in the NuttX tools repository. + + b. Execute 'make menuconfig' in nuttx/ in order to start the + reconfiguration process. + + 2. Unless stated otherwise, all configurations generate console + output on USART2, as described above under "Serial Console". The + elevant configuration settings are listed below: + + CONFIG_STM32_USART2=y + CONFIG_STM32_USART2_SERIALDRIVER=y + CONFIG_STM32_USART=y + + CONFIG_USART2_SERIALDRIVER=y + CONFIG_USART2_SERIAL_CONSOLE=y + + CONFIG_USART2_RXBUFSIZE=256 + CONFIG_USART2_TXBUFSIZE=256 + CONFIG_USART2_BAUD=115200 + CONFIG_USART2_BITS=8 + CONFIG_USART2_PARITY=0 + CONFIG_USART2_2STOP=0 + + 3. All of these configurations are set up to build under Linux using the + "GNU Tools for ARM Embedded Processors" that is maintained by ARM + (unless stated otherwise in the description of the configuration). + + https://launchpad.net/gcc-arm-embedded + + That toolchain selection can easily be reconfigured using + 'make menuconfig'. Here are the relevant current settings: + + Build Setup: + CONFIG_HOST_LINUX=y : Linux environment + + System Type -> Toolchain: + CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL=y : GNU ARM EABI toolchain + + Configuration sub-directories + ----------------------------- + + nsh: + + Configures the NuttShell (nsh) located at examples/nsh. This + configuration is focused on low level, command-line driver testing. + + NOTES: + + 1. Support for NSH built-in applications is provided: + + Binary Formats: + CONFIG_BUILTIN=y : Enable support for built-in programs + + Application Configuration: + CONFIG_NSH_BUILTIN_APPS=y : Enable starting apps from NSH command line + + No built applications are enabled in the base configuration, however. + + 2. C++ support for applications is enabled: + + CONFIG_HAVE_CXX=y + CONFIG_HAVE_CXXINITIALIZE=y + CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y -- GitLab From 8420e68a9bca877d8390adac8c518d748dbe1ed4 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 18 Apr 2017 08:40:14 -0600 Subject: [PATCH 500/990] STM32F0: The STM32F2 does not have use alternate function groupings as does the F1. Rather, it is like other members of the STM32 family with An alternate setting AF0-AF7 for each pin. --- arch/arm/src/stm32f0/chip/stm32f05x_pinmap.h | 61 +++++++++++--------- arch/arm/src/stm32f0/chip/stm32f07x_pinmap.h | 2 +- configs/stm32f0discovery/include/board.h | 4 ++ 3 files changed, 40 insertions(+), 27 deletions(-) diff --git a/arch/arm/src/stm32f0/chip/stm32f05x_pinmap.h b/arch/arm/src/stm32f0/chip/stm32f05x_pinmap.h index 9bf1a3aa30..969e4e4c42 100644 --- a/arch/arm/src/stm32f0/chip/stm32f05x_pinmap.h +++ b/arch/arm/src/stm32f0/chip/stm32f05x_pinmap.h @@ -49,6 +49,25 @@ * Pre-processor Definitions ************************************************************************************/ +/* Alternate Pin Functions. + * + * Alternative pin selections are provided with a numeric suffix like _1, + * _2, etc. Drivers, however, will use the pin selection without the numeric + * suffix. Additional definitions are required in the board.h file. For + * example, if USART1_TX connects vis PA9 on some board, then the following + * definition should appear inthe board.h header file for that board: + * + * #define GPIO_USART1_TX GPIO_USART1_TX_1 + * + * The driver will then automatically configre PD0 as the CAN1 RX pin. + */ + +/* WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!! + * Additional effort is required to select specific GPIO options such as frequency, + * open-drain/push-pull, and pull-up/down! Just the basics are defined for most + * pins in this file. + */ + /* ADC */ #define GPIO_ADC_IN0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN0) @@ -74,13 +93,10 @@ /* USART */ -#if defined(CONFIG_STM32F0_USART1_REMAP) -# define GPIO_USART1_TX (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN6) -# define GPIO_USART1_RX (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN7) -#else -# define GPIO_USART1_TX (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN9) -# define GPIO_USART1_RX (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN10) -#endif +#define GPIO_USART1_TX_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN9) +#define GPIO_USART1_TX_2 (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN6) +#define GPIO_USART1_RX_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN10) +#define GPIO_USART1_RX_2 (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN7) #define GPIO_USART1_CTS (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN11) #define GPIO_USART1_RTS (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN12) #define GPIO_USART1_CK (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN8) @@ -93,18 +109,14 @@ /* SPI */ -#if defined(CONFIG_STM32F0_SPI1_REMAP) -# define GPIO_SPI1_NSS (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN15) -# define GPIO_SPI1_SCK (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN3) -# define GPIO_SPI1_MISO (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN4) -# define GPIO_SPI1_MOSI (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN5) -#else -# define GPIO_SPI1_NSS (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN4) -# define GPIO_SPI1_SCK (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN5) -# define GPIO_SPI1_MISO (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN6) -# define GPIO_SPI1_MOSI (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN7) -#endif - +#define GPIO_SPI1_NSS_1 (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN4) +#define GPIO_SPI1_NSS_2 (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN15) +#define GPIO_SPI1_SCK_1 (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN5) +#define GPIO_SPI1_SCK_2 (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN3) +#define GPIO_SPI1_MISO_1 (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN6) +#define GPIO_SPI1_MISO_2 (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN4) +#define GPIO_SPI1_MOSI_1 (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN7) +#define GPIO_SPI1_MOSI_2 (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN5) #define GPIO_SPI2_NSS (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN12) #define GPIO_SPI2_SCK (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN13) #define GPIO_SPI2_MISO (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN14) @@ -112,13 +124,10 @@ /* I2C */ -#if defined(CONFIG_STM32F0_I2C1_REMAP) -# define GPIO_I2C1_SCL (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN8) -# define GPIO_I2C1_SDA (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN9) -#else -# define GPIO_I2C1_SCL (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN6) -# define GPIO_I2C1_SDA (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN7) -#endif +#define GPIO_I2C1_SCL_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN6) +#define GPIO_I2C1_SCL_2 (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN8) +#define GPIO_I2C1_SDA_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN7) +#define GPIO_I2C1_SDA_2 (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN9) #define GPIO_I2C1_SMBA (GPIO_ALT|GPIO_AF3|GPIO_PORTB|GPIO_PIN5) #define GPIO_I2C2_SCL (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN10) diff --git a/arch/arm/src/stm32f0/chip/stm32f07x_pinmap.h b/arch/arm/src/stm32f0/chip/stm32f07x_pinmap.h index 85beb6b326..5a2a67fa8e 100644 --- a/arch/arm/src/stm32f0/chip/stm32f07x_pinmap.h +++ b/arch/arm/src/stm32f0/chip/stm32f07x_pinmap.h @@ -48,7 +48,7 @@ /************************************************************************************ * Pre-processor Definitions ************************************************************************************/ -/* Alternate Pin Functions. +/* Alternate Pin Functions. * * Alternative pin selections are provided with a numeric suffix like _1, _2, etc. * Drivers, however, will use the pin selection without the numeric suffix. diff --git a/configs/stm32f0discovery/include/board.h b/configs/stm32f0discovery/include/board.h index 445cd068cd..5829650c5b 100644 --- a/configs/stm32f0discovery/include/board.h +++ b/configs/stm32f0discovery/include/board.h @@ -234,5 +234,9 @@ #define BUTTON_USER_BIT (1 << BUTTON_USER) /* Alternate Pin Functions **********************************************************/ +/* USART 1 */ + +#define GPIO_USART1_TX GPIO_USART1_TX_1 +#define GPIO_USART1_RX GPIO_USART1_RX_1 #endif /* __CONFIG_STM32F0DISCOVERY_INCLUDE_BOARD_H */ -- GitLab From b45472baf8077cea9cd592240f65adce72dcb9d4 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 18 Apr 2017 10:07:03 -0600 Subject: [PATCH 501/990] Nucleo-F072RB: Add board configuration --- arch/arm/src/stm32f0/Kconfig | 136 +-- configs/Kconfig | 13 + configs/README.txt | 3 + configs/nucleo-f072rb/Kconfig | 8 + configs/nucleo-f072rb/include/board.h | 241 +++++ configs/nucleo-f072rb/nsh/Make.defs | 113 +++ configs/nucleo-f072rb/nsh/defconfig | 1043 ++++++++++++++++++++ configs/nucleo-f072rb/nsh/setenv.sh | 81 ++ configs/nucleo-f072rb/scripts/flash.ld | 127 +++ configs/nucleo-f072rb/src/.gitignore | 2 + configs/nucleo-f072rb/src/Makefile | 56 ++ configs/nucleo-f072rb/src/nucleo-f072rb.h | 123 +++ configs/nucleo-f072rb/src/stm32_appinit.c | 87 ++ configs/nucleo-f072rb/src/stm32_autoleds.c | 96 ++ configs/nucleo-f072rb/src/stm32_boot.c | 94 ++ configs/nucleo-f072rb/src/stm32_bringup.c | 81 ++ configs/nucleo-f072rb/src/stm32_buttons.c | 126 +++ configs/nucleo-f072rb/src/stm32_userleds.c | 217 ++++ 18 files changed, 2539 insertions(+), 108 deletions(-) create mode 100644 configs/nucleo-f072rb/Kconfig create mode 100644 configs/nucleo-f072rb/include/board.h create mode 100644 configs/nucleo-f072rb/nsh/Make.defs create mode 100644 configs/nucleo-f072rb/nsh/defconfig create mode 100644 configs/nucleo-f072rb/nsh/setenv.sh create mode 100644 configs/nucleo-f072rb/scripts/flash.ld create mode 100644 configs/nucleo-f072rb/src/.gitignore create mode 100644 configs/nucleo-f072rb/src/Makefile create mode 100644 configs/nucleo-f072rb/src/nucleo-f072rb.h create mode 100644 configs/nucleo-f072rb/src/stm32_appinit.c create mode 100644 configs/nucleo-f072rb/src/stm32_autoleds.c create mode 100644 configs/nucleo-f072rb/src/stm32_boot.c create mode 100644 configs/nucleo-f072rb/src/stm32_bringup.c create mode 100644 configs/nucleo-f072rb/src/stm32_buttons.c create mode 100644 configs/nucleo-f072rb/src/stm32_userleds.c diff --git a/arch/arm/src/stm32f0/Kconfig b/arch/arm/src/stm32f0/Kconfig index 08e7f6c85c..746d9e40ec 100644 --- a/arch/arm/src/stm32f0/Kconfig +++ b/arch/arm/src/stm32f0/Kconfig @@ -474,11 +474,10 @@ config STM32F0_VALUELINE select STM32F0_HAVE_USART4 select STM32F0_HAVE_USART5 select STM32F0_HAVE_TIM1 - select STM32F0_HAVE_TIM5 + select STM32F0_HAVE_TIM2 + select STM32F0_HAVE_TIM3 select STM32F0_HAVE_TIM6 select STM32F0_HAVE_TIM7 - select STM32F0_HAVE_TIM12 - select STM32F0_HAVE_TIM13 select STM32F0_HAVE_TIM14 select STM32F0_HAVE_TIM15 select STM32F0_HAVE_TIM16 @@ -489,46 +488,62 @@ config STM32F0_VALUELINE config STM32F0_ACCESSLINE bool default n - select STM32F0_HAVE_OTGFS select STM32F0_HAVE_USART3 select STM32F0_HAVE_USART4 select STM32F0_HAVE_USART5 select STM32F0_HAVE_TIM1 - select STM32F0_HAVE_TIM5 + select STM32F0_HAVE_TIM2 + select STM32F0_HAVE_TIM3 select STM32F0_HAVE_TIM6 select STM32F0_HAVE_TIM7 + select STM32F0_HAVE_TIM14 + select STM32F0_HAVE_TIM15 + select STM32F0_HAVE_TIM16 + select STM32F0_HAVE_TIM17 select STM32F0_HAVE_ADC2 select STM32F0_HAVE_CAN1 - select STM32F0_HAVE_CAN2 - select STM32F0_HAVE_ETHMAC select STM32F0_HAVE_SPI2 select STM32F0_HAVE_SPI3 config STM32F0_LOWVOLTLINE bool default n - select STM32F0_HAVE_OTGFS select STM32F0_HAVE_USART3 select STM32F0_HAVE_USART4 select STM32F0_HAVE_USART5 select STM32F0_HAVE_TIM1 - select STM32F0_HAVE_TIM5 + select STM32F0_HAVE_TIM2 + select STM32F0_HAVE_TIM3 select STM32F0_HAVE_TIM6 select STM32F0_HAVE_TIM7 + select STM32F0_HAVE_TIM14 + select STM32F0_HAVE_TIM15 + select STM32F0_HAVE_TIM16 + select STM32F0_HAVE_TIM17 select STM32F0_HAVE_ADC2 select STM32F0_HAVE_CAN1 - select STM32F0_HAVE_CAN2 - select STM32F0_HAVE_ETHMAC select STM32F0_HAVE_SPI2 select STM32F0_HAVE_SPI3 config STM32F0_USBLINE bool default n - select STM32F0_HAVE_USBDEV - select STM32F0_HAVE_FSMC select STM32F0_HAVE_USART3 + select STM32F0_HAVE_USART4 + select STM32F0_HAVE_TIM1 + select STM32F0_HAVE_TIM2 + select STM32F0_HAVE_TIM3 + select STM32F0_HAVE_TIM6 + select STM32F0_HAVE_TIM7 + select STM32F0_HAVE_TIM14 + select STM32F0_HAVE_TIM15 + select STM32F0_HAVE_TIM16 + select STM32F0_HAVE_TIM17 + select STM32F0_HAVE_ADC2 + select STM32F0_HAVE_CAN1 select STM32F0_HAVE_SPI2 + select STM32F0_HAVE_SPI3 + select STM32F0_HAVE_USBDEV config STM32F0_DFU bool "DFU bootloader" @@ -565,10 +580,6 @@ config STM32F0_HAVE_USBDEV bool default n -config STM32F0_HAVE_OTGFS - bool - default n - config STM32F0_HAVE_FSMC bool default n @@ -617,14 +628,6 @@ config STM32F0_HAVE_TIM3 bool default n -config STM32F0_HAVE_TIM4 - bool - default n - -config STM32F0_HAVE_TIM5 - bool - default n - config STM32F0_HAVE_TIM6 bool default n @@ -633,30 +636,6 @@ config STM32F0_HAVE_TIM7 bool default n -config STM32F0_HAVE_TIM8 - bool - default n - -config STM32F0_HAVE_TIM9 - bool - default n - -config STM32F0_HAVE_TIM10 - bool - default n - -config STM32F0_HAVE_TIM11 - bool - default n - -config STM32F0_HAVE_TIM12 - bool - default n - -config STM32F0_HAVE_TIM13 - bool - default n - config STM32F0_HAVE_TIM14 bool default n @@ -733,10 +712,6 @@ config STM32F0_HAVE_CAN1 bool default n -config STM32F0_HAVE_CAN2 - bool - default n - config STM32F0_HAVE_COMP1 bool default n @@ -777,10 +752,6 @@ config STM32F0_HAVE_RNG bool default n -config STM32F0_HAVE_ETHMAC - bool - default n - config STM32F0_HAVE_I2C2 bool default n @@ -930,13 +901,6 @@ config STM32F0_CAN1 select STM32F0_CAN depends on STM32F0_HAVE_CAN1 -config STM32F0_CAN2 - bool "CAN2" - default n - select CAN - select STM32F0_CAN - depends on STM32F0_HAVE_CAN2 - config STM32F0_CEC bool "CEC" default n @@ -1083,16 +1047,6 @@ config STM32F0_TIM3 default n depends on STM32F0_HAVE_TIM3 -config STM32F0_TIM4 - bool "TIM4" - default n - depends on STM32F0_HAVE_TIM4 - -config STM32F0_TIM5 - bool "TIM5" - default n - depends on STM32F0_HAVE_TIM5 - config STM32F0_TIM6 bool "TIM6" default n @@ -1103,36 +1057,6 @@ config STM32F0_TIM7 default n depends on STM32F0_HAVE_TIM7 -config STM32F0_TIM8 - bool "TIM8" - default n - depends on STM32F0_HAVE_TIM8 - -config STM32F0_TIM9 - bool "TIM9" - default n - depends on STM32F0_HAVE_TIM9 - -config STM32F0_TIM10 - bool "TIM10" - default n - depends on STM32F0_HAVE_TIM10 - -config STM32F0_TIM11 - bool "TIM11" - default n - depends on STM32F0_HAVE_TIM11 - -config STM32F0_TIM12 - bool "TIM12" - default n - depends on STM32F0_HAVE_TIM12 - -config STM32F0_TIM13 - bool "TIM13" - default n - depends on STM32F0_HAVE_TIM13 - config STM32F0_TIM14 bool "TIM14" default n @@ -1291,7 +1215,6 @@ config USART1_RS485_DIR_POLARITY endif # STM32F0_USART1_SERIALDRIVER - choice prompt "USART2 Driver Configuration" default STM32F0_USART2_SERIALDRIVER @@ -1329,7 +1252,6 @@ config USART2_RS485_DIR_POLARITY endif # STM32F0_USART2_SERIALDRIVER - choice prompt "USART3 Driver Configuration" default STM32F0_USART3_SERIALDRIVER @@ -1481,7 +1403,6 @@ config USART6_RS485_DIR_POLARITY endif # STM32F0_USART6_SERIALDRIVER - choice prompt "USART7 Driver Configuration" default STM32F0_USART7_SERIALDRIVER @@ -1519,7 +1440,6 @@ config USART7_RS485_DIR_POLARITY endif # STM32F0_USART7_SERIALDRIVER - choice prompt "USART8 Driver Configuration" default STM32F0_USART8_SERIALDRIVER diff --git a/configs/Kconfig b/configs/Kconfig index 6467bafe1e..24632785d3 100644 --- a/configs/Kconfig +++ b/configs/Kconfig @@ -724,6 +724,15 @@ config ARCH_BOARD_NUCLEO_144 NUCLEO-F767ZI - STM32F767ZIT6 a 216MHz Cortex-M7, w/DPFPU - 2048KiB Flash memory and 512KiB SRAM. +config ARCH_BOARD_NUCLEO_F072RB + bool "STM32F072 Nucleo F072RB" + depends on ARCH_CHIP_STM32F072RB + select ARCH_HAVE_LEDS + select ARCH_HAVE_BUTTONS + select ARCH_HAVE_IRQBUTTONS + ---help--- + STMicro Nucleo F072RB board based on the STMicro STM32F072RBT6 MCU. + config ARCH_BOARD_NUCLEO_F303RE bool "STM32F303 Nucleo F303RE" depends on ARCH_CHIP_STM32F303RE @@ -1504,6 +1513,7 @@ config ARCH_BOARD default "pic32mx7mmb" if ARCH_BOARD_PIC32MX7MMB default "pic32mz-starterkit" if ARCH_BOARD_PIC32MZ_STARTERKIT default "nucleo-144" if ARCH_BOARD_NUCLEO_144 + default "nucleo-f072rb" if ARCH_BOARD_NUCLEO_F072RB default "nucleo-f303re" if ARCH_BOARD_NUCLEO_F303RE default "nucleo-f334r8" if ARCH_BOARD_NUCLEO_F334R8 default "nucleo-f4x1re" if ARCH_BOARD_NUCLEO_F401RE || ARCH_BOARD_NUCLEO_F411RE @@ -1810,6 +1820,9 @@ endif if ARCH_BOARD_NUCLEO_144 source "configs/nucleo-144/Kconfig" endif +if ARCH_BOARD_NUCLEO_F072RB +source "configs/nucleo-f072rb/Kconfig" +endif if ARCH_BOARD_NUCLEO_F303RE source "configs/nucleo-f303re/Kconfig" endif diff --git a/configs/README.txt b/configs/README.txt index dea227d8a7..cbdb3d0072 100644 --- a/configs/README.txt +++ b/configs/README.txt @@ -411,6 +411,9 @@ configs/nucleo-144 STM32F767ZIT6 is a 216MHz Cortex-M7 operation with 2048Kb Flash memory and 512Kb SRAM. +configs/nucleo-f072rb + STMicro Nucleo F072RB board based on the STMicro STM32F072RBT6 MCU. + configs/nucleo-f4x1re STMicro ST Nucleo F401RE and F411RE boards. See http://mbed.org/platforms/ST-Nucleo-F401RE and diff --git a/configs/nucleo-f072rb/Kconfig b/configs/nucleo-f072rb/Kconfig new file mode 100644 index 0000000000..163902742b --- /dev/null +++ b/configs/nucleo-f072rb/Kconfig @@ -0,0 +1,8 @@ +# +# For a description of the syntax of this configuration file, +# see the file kconfig-language.txt in the NuttX tools repository. +# + +if ARCH_BOARD_NUCLEO_F072RB + +endif diff --git a/configs/nucleo-f072rb/include/board.h b/configs/nucleo-f072rb/include/board.h new file mode 100644 index 0000000000..50493e09da --- /dev/null +++ b/configs/nucleo-f072rb/include/board.h @@ -0,0 +1,241 @@ +/************************************************************************************ + * configs/nucleo-f072rb/include/board.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Alan Carvalho de Assis + * + * 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 __CONFIG_NUCLEO_F072RB_INCLUDE_BOARD_H +#define __CONFIG_NUCLEO_F072RB_INCLUDE_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#ifndef __ASSEMBLY__ +# include +#endif + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ +/* Four different clock sources can be used to drive the system clock (SYSCLK): + * + * - HSI high-speed internal oscillator clock + * Generated from an internal 8 MHz RC oscillator + * - HSE high-speed external oscillator clock + * Normally driven by an external crystal (X3). However, this crystal is not + * fitted on the Nucleo-F072RB board. + * - PLL clock + * - MSI multispeed internal oscillator clock + * The MSI clock signal is generated from an internal RC oscillator. Seven frequency + * ranges are available: 65.536 kHz, 131.072 kHz, 262.144 kHz, 524.288 kHz, 1.048 MHz, + * 2.097 MHz (default value) and 4.194 MHz. + * + * The devices have the following two secondary clock sources + * - LSI low-speed internal RC clock + * Drives the watchdog and RTC. Approximately 37KHz + * - LSE low-speed external oscillator clock + * Driven by 32.768KHz crystal (X2) on the OSC32_IN and OSC32_OUT pins. + */ + +#define STM32F0_BOARD_XTAL 8000000ul /* X3 on board (not fitted)*/ + +#define STM32F0_HSI_FREQUENCY 8000000ul /* Approximately 8MHz */ +#define STM32F0_HSI14_FREQUENCY 14000000ul /* HSI14 for ADC */ +#define STM32F0_HSI48_FREQUENCY 48000000ul /* HSI48 for USB, only some STM32F0xx */ +#define STM32F0_HSE_FREQUENCY STM32F0_BOARD_XTAL +#define STM32F0_LSI_FREQUENCY 40000 /* Approximately 40KHz */ +#define STM32F0_LSE_FREQUENCY 32768 /* X2 on board */ + +/* PLL Configuration + * + * - PLL source is HSI -> 8MHz input (nominal) + * - PLL source predivider 2 -> 4MHz divided down PLL VCO clock output + * - PLL multipler is 12 -> 48MHz PLL VCO clock output (for USB) + * + * Resulting SYSCLK frequency is 8MHz x 12 / 2 = 48MHz + * + * USB: + * If the USB interface is used in the application, it requires a precise + * 48MHz clock which can be generated from either the (1) the internal + * main PLL with the HSE clock source using an HSE crystal oscillator. In + * this case, the PLL VCO clock (defined by STM32F0_CFGR_PLLMUL) must be + * programmed to output a 96 MHz frequency. This is required to provide a + * 48MHz clock to the (USBCLK = PLLVCO/2). Or (2) by using the internal + * 48MHz oscillator in automatic trimming mode. The synchronization for + * this oscillator can be taken from the USB data stream itself (SOF + * signalization) which allows crystal-less operation. + * SYSCLK + * The system clock is derived from the PLL VCO divided by the output + * division factor. + * Limitations: + * - 96 MHz as PLLVCO when the product is in range 1 (1.8V), + * - 48 MHz as PLLVCO when the product is in range 2 (1.5V), + * - 24 MHz when the product is in range 3 (1.2V). + * - Output division to avoid exceeding 32 MHz as SYSCLK. + * - The minimum input clock frequency for PLL is 2 MHz (when using HSE as + * PLL source). + */ + +#define STM32F0_CFGR_PLLSRC RCC_CFGR_PLLSRC_HSId2 /* Source is HSI/2 */ +#define STM32F0_PLLSRC_FREQUENCY (STM32F0_HSI_FREQUENCY/2) /* 8MHz / 2 = 4MHz */ +#ifdef CONFIG_STM32F0_USB +# undef STM32F0_CFGR2_PREDIV /* Not used with source HSI/2 */ +# define STM32F0_CFGR_PLLMUL RCC_CFGR_PLLMUL_CLKx12 /* PLLMUL = 12 */ +# define STM32F0_PLL_FREQUENCY (12*STM32F0_PLLSRC_FREQUENCY) /* PLL VCO Frequency is 48MHz */ +#else +# undef STM32F0_CFGR2_PREDIV /* Not used with source HSI/2 */ +# define STM32F0_CFGR_PLLMUL RCC_CFGR_PLLMUL_CLKx12 /* PLLMUL = 12 */ +# define STM32F0_PLL_FREQUENCY (12*STM32F0_PLLSRC_FREQUENCY) /* PLL VCO Frequency is 48MHz */ +#endif + +/* Use the PLL and set the SYSCLK source to be the divided down PLL VCO output + * frequency (STM32F0_PLL_FREQUENCY divided by the PLLDIV value). + */ + +#define STM32F0_SYSCLK_SW RCC_CFGR_SW_PLL /* Use the PLL as the SYSCLK */ +#define STM32F0_SYSCLK_SWS RCC_CFGR_SWS_PLL +#ifdef CONFIG_STM32F0_USB +# define STM32F0_SYSCLK_FREQUENCY STM32F0_PLL_FREQUENCY /* SYSCLK frequency is PLL VCO = 48MHz */ +#else +# define STM32F0_SYSCLK_FREQUENCY STM32F0_PLL_FREQUENCY /* SYSCLK frequency is PLL VCO = 48MHz */ +#endif + +#define STM32F0_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK +#define STM32F0_HCLK_FREQUENCY STM32F0_SYSCLK_FREQUENCY +#define STM32F0_BOARD_HCLK STM32F0_HCLK_FREQUENCY /* Same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK (48MHz) */ + +#define STM32F0_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLK +#define STM32F0_PCLK1_FREQUENCY (STM32F0_HCLK_FREQUENCY) + +/* APB2 clock (PCLK2) is HCLK (48MHz) */ + +#define STM32F0_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK +#define STM32F0_PCLK2_FREQUENCY STM32F0_HCLK_FREQUENCY +#define STM32F0_APB2_CLKIN (STM32F0_PCLK2_FREQUENCY) + +/* APB1 timers 1-3, 6-7, and 14-17 will receive PCLK1 */ + +#define STM32F0_APB1_TIM1_CLKIN (STM32F0_PCLK1_FREQUENCY) +#define STM32F0_APB1_TIM2_CLKIN (STM32F0_PCLK1_FREQUENCY) +#define STM32F0_APB1_TIM3_CLKIN (STM32F0_PCLK1_FREQUENCY) + +#define STM32F0_APB1_TIM6_CLKIN (STM32F0_PCLK1_FREQUENCY) +#define STM32F0_APB1_TIM7_CLKIN (STM32F0_PCLK1_FREQUENCY) + +#define STM32F0_APB1_TIM14_CLKIN (STM32F0_PCLK1_FREQUENCY) +#define STM32F0_APB1_TIM15_CLKIN (STM32F0_PCLK1_FREQUENCY) +#define STM32F0_APB1_TIM16_CLKIN (STM32F0_PCLK1_FREQUENCY) +#define STM32F0_APB1_TIM17_CLKIN (STM32F0_PCLK1_FREQUENCY) + +/* LED definitions ******************************************************************/ +/* LEDs + * + * The Nucleo-64 board has one user controlable LED, User LD2. This green + * LED is a user LED connected to Arduino signal D13 corresponding to STM32 + * I/O PA5 (PB13 on other some other Nucleo-64 boards). + * + * - When the I/O is HIGH value, the LED is on + * - When the I/O is LOW, the LED is off + */ + +/* LED index values for use with board_userled() */ + +#define BOARD_LD2 0 +#define BOARD_NLEDS 1 + +/* LED bits for use with board_userled_all() */ + +#define BOARD_LD2_BIT (1 << BOARD_LD2) + +/* These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is + * defined. In that case, the usage by the board port is defined in + * include/board.h and src/sam_leds.c. The LEDs are used to encode OS-related + * events as follows when the red LED (PE24) is available: + * + * SYMBOL Meaning LD2 + * ------------------- ----------------------- ----------- + * LED_STARTED NuttX has been started OFF + * LED_HEAPALLOCATE Heap has been allocated OFF + * LED_IRQSENABLED Interrupts enabled OFF + * LED_STACKCREATED Idle stack created ON + * LED_INIRQ In an interrupt No change + * LED_SIGNAL In a signal handler No change + * LED_ASSERTION An assertion failed No change + * LED_PANIC The system has crashed Blinking + * LED_IDLE MCU is is sleep mode Not used + * + * Thus if LD2, NuttX has successfully booted and is, apparently, running + * normally. If LD2 is flashing at approximately 2Hz, then a fatal error + * has been detected and the system has halted. + */ + +#define LED_STARTED 0 +#define LED_HEAPALLOCATE 0 +#define LED_IRQSENABLED 0 +#define LED_STACKCREATED 1 +#define LED_INIRQ 2 +#define LED_SIGNAL 2 +#define LED_ASSERTION 2 +#define LED_PANIC 1 + +/* Button definitions ***************************************************************/ +/* Buttons + * + * B1 USER: the user button is connected to the I/O PC13 (pin 2) of the STM32 + * microcontroller. + */ + +#define BUTTON_USER 0 +#define NUM_BUTTONS 1 + +#define BUTTON_USER_BIT (1 << BUTTON_USER) + +/* Alternate Pin Functions **********************************************************/ +/* USART 1 */ + +#define GPIO_USART1_TX GPIO_USART1_TX_2 +#define GPIO_USART1_RX GPIO_USART1_RX_2 + +/* USART 2 */ + +#define GPIO_USART2_TX GPIO_USART2_TX_3 +#define GPIO_USART2_RX GPIO_USART2_RX_3 + +#endif /* __CONFIG_NUCLEO_F072RB_INCLUDE_BOARD_H */ diff --git a/configs/nucleo-f072rb/nsh/Make.defs b/configs/nucleo-f072rb/nsh/Make.defs new file mode 100644 index 0000000000..d4573469db --- /dev/null +++ b/configs/nucleo-f072rb/nsh/Make.defs @@ -0,0 +1,113 @@ +############################################################################ +# configs/nucleo-f072rb/nsh/Make.defs +# +# Copyright (C) 2017 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# Alan Carvalho de Assis +# +# 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. +# +############################################################################ + +include ${TOPDIR}/.config +include ${TOPDIR}/tools/Config.mk +include ${TOPDIR}/arch/arm/src/armv6-m/Toolchain.defs + +LDSCRIPT = flash.ld + +ifeq ($(WINTOOL),y) + # Windows-native toolchains + DIRLINK = $(TOPDIR)/tools/copydir.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mkwindeps.sh + ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" + ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" +else + # Linux/Cygwin-native toolchain + MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT) + ARCHINCLUDES = -I. -isystem $(TOPDIR)/include + ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) +endif + +CC = $(CROSSDEV)gcc +CXX = $(CROSSDEV)g++ +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(ARCROSSDEV)ar rcs +NM = $(ARCROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump + +ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} +ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} + +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + ARCHOPTIMIZATION = -g +endif + +ifneq ($(CONFIG_DEBUG_NOOPT),y) + ARCHOPTIMIZATION += $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer +endif + +ARCHCFLAGS = -fno-builtin +ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fcheck-new -fno-rtti +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow -Wundef +ARCHWARNINGSXX = -Wall -Wshadow -Wundef +ARCHDEFINES = +ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 + +CFLAGS = $(ARCHCFLAGS) $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) +CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +NXFLATLDFLAGS1 = -r -d -warn-common +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections +LDNXFLATFLAGS = -e main -s 2048 + +ASMEXT = .S +OBJEXT = .o +LIBEXT = .a +EXEEXT = + +ifneq ($(CROSSDEV),arm-nuttx-elf-) + LDFLAGS += -nostartfiles -nodefaultlibs +endif +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + LDFLAGS += -g +endif + + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -Wundef -g -pipe +HOSTLDFLAGS = diff --git a/configs/nucleo-f072rb/nsh/defconfig b/configs/nucleo-f072rb/nsh/defconfig new file mode 100644 index 0000000000..48868af124 --- /dev/null +++ b/configs/nucleo-f072rb/nsh/defconfig @@ -0,0 +1,1043 @@ +# +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# + +# +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set +CONFIG_DEFAULT_SMALL=y +CONFIG_HOST_LINUX=y +# CONFIG_HOST_OSX is not set +# CONFIG_HOST_WINDOWS is not set +# CONFIG_HOST_OTHER is not set + +# +# Build Configuration +# +# CONFIG_APPS_DIR="../apps" +CONFIG_BUILD_FLAT=y +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +# CONFIG_INTELHEX_BINARY is not set +# CONFIG_MOTOROLA_SREC is not set +CONFIG_RAW_BINARY=y +# CONFIG_UBOOT_UIMAGE is not set + +# +# Customize Header Files +# +# CONFIG_ARCH_STDINT_H is not set +# CONFIG_ARCH_STDBOOL_H is not set +# CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_FLOAT_H is not set +# CONFIG_ARCH_STDARG_H is not set +# CONFIG_ARCH_DEBUG_H is not set + +# +# Debug Options +# +CONFIG_DEBUG_ALERT=y +# CONFIG_DEBUG_FEATURES is not set +CONFIG_ARCH_HAVE_STACKCHECK=y +# CONFIG_STACK_COLORATION is not set +# CONFIG_ARCH_HAVE_HEAPCHECK is not set +# CONFIG_DEBUG_SYMBOLS is not set +CONFIG_ARCH_HAVE_CUSTOMOPT=y +# CONFIG_DEBUG_NOOPT is not set +# CONFIG_DEBUG_CUSTOMOPT is not set +CONFIG_DEBUG_FULLOPT=y + +# +# System Type +# +CONFIG_ARCH_ARM=y +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_MISOC is not set +# CONFIG_ARCH_RENESAS is not set +# CONFIG_ARCH_RISCV is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_XTENSA is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="arm" + +# +# ARM Options +# +# CONFIG_ARCH_CHIP_A1X is not set +# CONFIG_ARCH_CHIP_C5471 is not set +# CONFIG_ARCH_CHIP_DM320 is not set +# CONFIG_ARCH_CHIP_EFM32 is not set +# CONFIG_ARCH_CHIP_IMX1 is not set +# CONFIG_ARCH_CHIP_IMX6 is not set +# CONFIG_ARCH_CHIP_KINETIS is not set +# CONFIG_ARCH_CHIP_KL is not set +# CONFIG_ARCH_CHIP_LM is not set +# CONFIG_ARCH_CHIP_TIVA is not set +# CONFIG_ARCH_CHIP_LPC11XX is not set +# CONFIG_ARCH_CHIP_LPC17XX is not set +# CONFIG_ARCH_CHIP_LPC214X is not set +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_NUC1XX is not set +# CONFIG_ARCH_CHIP_SAMA5 is not set +# CONFIG_ARCH_CHIP_SAMD is not set +# CONFIG_ARCH_CHIP_SAML is not set +# CONFIG_ARCH_CHIP_SAM34 is not set +# CONFIG_ARCH_CHIP_SAMV7 is not set +# CONFIG_ARCH_CHIP_STM32 is not set +CONFIG_ARCH_CHIP_STM32F0=y +# CONFIG_ARCH_CHIP_STM32F7 is not set +# CONFIG_ARCH_CHIP_STM32L4 is not set +# CONFIG_ARCH_CHIP_STR71X is not set +# CONFIG_ARCH_CHIP_TMS570 is not set +# CONFIG_ARCH_CHIP_XMC4 is not set +# CONFIG_ARCH_ARM7TDMI is not set +# CONFIG_ARCH_ARM926EJS is not set +# CONFIG_ARCH_ARM920T is not set +CONFIG_ARCH_CORTEXM0=y +# CONFIG_ARCH_CORTEXM23 is not set +# CONFIG_ARCH_CORTEXM3 is not set +# CONFIG_ARCH_CORTEXM33 is not set +# CONFIG_ARCH_CORTEXM4 is not set +# CONFIG_ARCH_CORTEXM7 is not set +# CONFIG_ARCH_CORTEXA5 is not set +# CONFIG_ARCH_CORTEXA8 is not set +# CONFIG_ARCH_CORTEXA9 is not set +# CONFIG_ARCH_CORTEXR4 is not set +# CONFIG_ARCH_CORTEXR4F is not set +# CONFIG_ARCH_CORTEXR5 is not set +# CONFIG_ARCH_CORTEX5F is not set +# CONFIG_ARCH_CORTEXR7 is not set +# CONFIG_ARCH_CORTEXR7F is not set +CONFIG_ARCH_FAMILY="armv6-m" +CONFIG_ARCH_CHIP="stm32f0" +# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARM_TOOLCHAIN_GNU is not set +CONFIG_ARCH_HAVE_CMNVECTOR=y +# CONFIG_ARMV7M_CMNVECTOR is not set +# CONFIG_ARMV7M_LAZYFPU is not set +# CONFIG_ARCH_HAVE_FPU is not set +# CONFIG_ARCH_HAVE_DPFPU is not set +# CONFIG_ARCH_HAVE_TRUSTZONE is not set +# CONFIG_ARM_HAVE_MPU_UNIFIED is not set + +# +# ARMV6M Configuration Options +# +# CONFIG_ARMV6M_TOOLCHAIN_BUILDROOT is not set +# CONFIG_ARMV6M_TOOLCHAIN_CODEREDL is not set +# CONFIG_ARMV6M_TOOLCHAIN_CODESOURCERYL is not set +CONFIG_ARMV6M_TOOLCHAIN_GNU_EABIL=y +# CONFIG_SERIAL_TERMIOS is not set +# CONFIG_USART2_RS485 is not set + +# +# STM32F0xx Configuration Options +# +# CONFIG_ARCH_CHIP_STM32F030C6 is not set +# CONFIG_ARCH_CHIP_STM32F030C8 is not set +# CONFIG_ARCH_CHIP_STM32F030CC is not set +# CONFIG_ARCH_CHIP_STM32F030F4 is not set +# CONFIG_ARCH_CHIP_STM32F030K6 is not set +# CONFIG_ARCH_CHIP_STM32F030R8 is not set +# CONFIG_ARCH_CHIP_STM32F030RC is not set +# CONFIG_ARCH_CHIP_STM32F031C4 is not set +# CONFIG_ARCH_CHIP_STM32F031C6 is not set +# CONFIG_ARCH_CHIP_STM32F031E6 is not set +# CONFIG_ARCH_CHIP_STM32F031F4 is not set +# CONFIG_ARCH_CHIP_STM32F031F6 is not set +# CONFIG_ARCH_CHIP_STM32F031G4 is not set +# CONFIG_ARCH_CHIP_STM32F031G6 is not set +# CONFIG_ARCH_CHIP_STM32F031K4 is not set +# CONFIG_ARCH_CHIP_STM32F031K6 is not set +# CONFIG_ARCH_CHIP_STM32F038C6 is not set +# CONFIG_ARCH_CHIP_STM32F038E6 is not set +# CONFIG_ARCH_CHIP_STM32F038F6 is not set +# CONFIG_ARCH_CHIP_STM32F038G6 is not set +# CONFIG_ARCH_CHIP_STM32F038K6 is not set +# CONFIG_ARCH_CHIP_STM32F042C4 is not set +# CONFIG_ARCH_CHIP_STM32F042C6 is not set +# CONFIG_ARCH_CHIP_STM32F042F4 is not set +# CONFIG_ARCH_CHIP_STM32F042F6 is not set +# CONFIG_ARCH_CHIP_STM32F042G4 is not set +# CONFIG_ARCH_CHIP_STM32F042G6 is not set +# CONFIG_ARCH_CHIP_STM32F042K4 is not set +# CONFIG_ARCH_CHIP_STM32F042K6 is not set +# CONFIG_ARCH_CHIP_STM32F042T6 is not set +# CONFIG_ARCH_CHIP_STM32F048C6 is not set +# CONFIG_ARCH_CHIP_STM32F048G6 is not set +# CONFIG_ARCH_CHIP_STM32F048T6 is not set +# CONFIG_ARCH_CHIP_STM32F051C4 is not set +# CONFIG_ARCH_CHIP_STM32F051C6 is not set +# CONFIG_ARCH_CHIP_STM32F051C8 is not set +# CONFIG_ARCH_CHIP_STM32F051K4 is not set +# CONFIG_ARCH_CHIP_STM32F051K6 is not set +# CONFIG_ARCH_CHIP_STM32F051K8 is not set +# CONFIG_ARCH_CHIP_STM32F051R4 is not set +# CONFIG_ARCH_CHIP_STM32F051R6 is not set +# CONFIG_ARCH_CHIP_STM32F051R8 is not set +# CONFIG_ARCH_CHIP_STM32F051T8 is not set +# CONFIG_ARCH_CHIP_STM32F058C8 is not set +# CONFIG_ARCH_CHIP_STM32F058R8 is not set +# CONFIG_ARCH_CHIP_STM32F058T8 is not set +# CONFIG_ARCH_CHIP_STM32F070C6 is not set +# CONFIG_ARCH_CHIP_STM32F070CB is not set +# CONFIG_ARCH_CHIP_STM32F070F6 is not set +# CONFIG_ARCH_CHIP_STM32F070RB is not set +# CONFIG_ARCH_CHIP_STM32F071C8 is not set +# CONFIG_ARCH_CHIP_STM32F071CB is not set +# CONFIG_ARCH_CHIP_STM32F071RB is not set +# CONFIG_ARCH_CHIP_STM32F071V8 is not set +# CONFIG_ARCH_CHIP_STM32F071VB is not set +# CONFIG_ARCH_CHIP_STM32F072C8 is not set +# CONFIG_ARCH_CHIP_STM32F072CB is not set +# CONFIG_ARCH_CHIP_STM32F072R8 is not set +CONFIG_ARCH_CHIP_STM32F072RB=y +# CONFIG_ARCH_CHIP_STM32F072V8 is not set +# CONFIG_ARCH_CHIP_STM32F072VB is not set +# CONFIG_ARCH_CHIP_STM32F078CB is not set +# CONFIG_ARCH_CHIP_STM32F078RB is not set +# CONFIG_ARCH_CHIP_STM32F078VB is not set +# CONFIG_ARCH_CHIP_STM32F091CB is not set +# CONFIG_ARCH_CHIP_STM32F091CC is not set +# CONFIG_ARCH_CHIP_STM32F091RB is not set +# CONFIG_ARCH_CHIP_STM32F091RC is not set +# CONFIG_ARCH_CHIP_STM32F091VB is not set +# CONFIG_ARCH_CHIP_STM32F091VC is not set +# CONFIG_ARCH_CHIP_STM32F098CC is not set +# CONFIG_ARCH_CHIP_STM32F098RC is not set +# CONFIG_ARCH_CHIP_STM32F098VC is not set +# CONFIG_STM32F0_STM32F03X is not set +# CONFIG_STM32F0_STM32F04X is not set +# CONFIG_STM32F0_STM32F05X is not set +CONFIG_STM32F0_STM32F07X=y +# CONFIG_STM32F0_STM32F09X is not set +# CONFIG_STM32F0_VALUELINE is not set +# CONFIG_STM32F0_ACCESSLINE is not set +# CONFIG_STM32F0_LOWVOLTLINE is not set +CONFIG_STM32F0_USBLINE=y +# CONFIG_STM32F0_DFU is not set +CONFIG_STM32F0_SYSTICK_CORECLK=y +# CONFIG_STM32F0_SYSTICK_CORECLK_DIV16 is not set + +# +# STM32 Peripheral Support +# +# CONFIG_STM32F0_HAVE_CCM is not set +CONFIG_STM32F0_HAVE_USBDEV=y +# CONFIG_STM32F0_HAVE_FSMC is not set +# CONFIG_STM32F0_HAVE_HRTIM1 is not set +# CONFIG_STM32F0_HAVE_LTDC is not set +CONFIG_STM32F0_HAVE_USART3=y +CONFIG_STM32F0_HAVE_USART4=y +# CONFIG_STM32F0_HAVE_USART5 is not set +# CONFIG_STM32F0_HAVE_USART6 is not set +# CONFIG_STM32F0_HAVE_USART7 is not set +# CONFIG_STM32F0_HAVE_USART8 is not set +CONFIG_STM32F0_HAVE_TIM1=y +CONFIG_STM32F0_HAVE_TIM2=y +CONFIG_STM32F0_HAVE_TIM3=y +CONFIG_STM32F0_HAVE_TIM6=y +CONFIG_STM32F0_HAVE_TIM7=y +CONFIG_STM32F0_HAVE_TIM14=y +CONFIG_STM32F0_HAVE_TIM15=y +CONFIG_STM32F0_HAVE_TIM16=y +CONFIG_STM32F0_HAVE_TIM17=y +# CONFIG_STM32F0_HAVE_TSC is not set +CONFIG_STM32F0_HAVE_ADC2=y +# CONFIG_STM32F0_HAVE_ADC3 is not set +# CONFIG_STM32F0_HAVE_ADC4 is not set +# CONFIG_STM32F0_HAVE_ADC1_DMA is not set +# CONFIG_STM32F0_HAVE_ADC2_DMA is not set +# CONFIG_STM32F0_HAVE_ADC3_DMA is not set +# CONFIG_STM32F0_HAVE_ADC4_DMA is not set +# CONFIG_STM32F0_HAVE_SDADC1 is not set +# CONFIG_STM32F0_HAVE_SDADC2 is not set +# CONFIG_STM32F0_HAVE_SDADC3 is not set +# CONFIG_STM32F0_HAVE_SDADC1_DMA is not set +# CONFIG_STM32F0_HAVE_SDADC2_DMA is not set +# CONFIG_STM32F0_HAVE_SDADC3_DMA is not set +CONFIG_STM32F0_HAVE_CAN1=y +# CONFIG_STM32F0_HAVE_COMP1 is not set +# CONFIG_STM32F0_HAVE_COMP2 is not set +# CONFIG_STM32F0_HAVE_COMP3 is not set +# CONFIG_STM32F0_HAVE_COMP4 is not set +# CONFIG_STM32F0_HAVE_COMP5 is not set +# CONFIG_STM32F0_HAVE_COMP6 is not set +# CONFIG_STM32F0_HAVE_COMP7 is not set +# CONFIG_STM32F0_HAVE_DAC1 is not set +# CONFIG_STM32F0_HAVE_DAC2 is not set +# CONFIG_STM32F0_HAVE_RNG is not set +# CONFIG_STM32F0_HAVE_I2C2 is not set +# CONFIG_STM32F0_HAVE_I2C3 is not set +CONFIG_STM32F0_HAVE_SPI2=y +CONFIG_STM32F0_HAVE_SPI3=y +# CONFIG_STM32F0_HAVE_SPI4 is not set +# CONFIG_STM32F0_HAVE_SPI5 is not set +# CONFIG_STM32F0_HAVE_SPI6 is not set +# CONFIG_STM32F0_HAVE_SAIPLL is not set +# CONFIG_STM32F0_HAVE_I2SPLL is not set +# CONFIG_STM32F0_HAVE_OPAMP1 is not set +# CONFIG_STM32F0_HAVE_OPAMP2 is not set +# CONFIG_STM32F0_HAVE_OPAMP3 is not set +# CONFIG_STM32F0_HAVE_OPAMP4 is not set +# CONFIG_STM32F0_ADC1 is not set +# CONFIG_STM32F0_ADC2 is not set +# CONFIG_STM32F0_COMP is not set +# CONFIG_STM32F0_BKP is not set +# CONFIG_STM32F0_BKPSRAM is not set +# CONFIG_STM32F0_CAN1 is not set +# CONFIG_STM32F0_CRC is not set +# CONFIG_STM32F0_DMA1 is not set +# CONFIG_STM32F0_DMA2 is not set +# CONFIG_STM32F0_I2C1 is not set +CONFIG_STM32F0_PWR=y +# CONFIG_STM32F0_SDIO is not set +# CONFIG_STM32F0_SPI1 is not set +# CONFIG_STM32F0_SPI2 is not set +# CONFIG_STM32F0_SPI3 is not set +CONFIG_STM32F0_SYSCFG=y +# CONFIG_STM32F0_TIM1 is not set +# CONFIG_STM32F0_TIM2 is not set +# CONFIG_STM32F0_TIM3 is not set +# CONFIG_STM32F0_TIM6 is not set +# CONFIG_STM32F0_TIM7 is not set +# CONFIG_STM32F0_TIM14 is not set +# CONFIG_STM32F0_TIM15 is not set +# CONFIG_STM32F0_TIM16 is not set +# CONFIG_STM32F0_TIM17 is not set +# CONFIG_STM32F0_USART1 is not set +CONFIG_STM32F0_USART2=y +# CONFIG_STM32F0_USART3 is not set +# CONFIG_STM32F0_USART4 is not set +# CONFIG_STM32F0_USB is not set +# CONFIG_STM32F0_IWDG is not set +# CONFIG_STM32F0_WWDG is not set +CONFIG_STM32F0_USART=y +CONFIG_STM32F0_SERIALDRIVER=y + +# +# U[S]ART Configuration +# + +# +# U[S]ART Device Configuration +# +CONFIG_STM32F0_USART2_SERIALDRIVER=y +# CONFIG_STM32F0_USART2_1WIREDRIVER is not set + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_VECNOTIRQ is not set +# CONFIG_ARCH_DMA is not set +CONFIG_ARCH_HAVE_IRQPRIO=y +# CONFIG_ARCH_L2CACHE is not set +# CONFIG_ARCH_HAVE_COHERENT_DCACHE is not set +# CONFIG_ARCH_HAVE_ADDRENV is not set +# CONFIG_ARCH_NEED_ADDRENV_MAPPING is not set +# CONFIG_ARCH_HAVE_MULTICPU is not set +CONFIG_ARCH_HAVE_VFORK=y +# CONFIG_ARCH_HAVE_MMU is not set +# CONFIG_ARCH_HAVE_MPU is not set +# CONFIG_ARCH_NAND_HWECC is not set +# CONFIG_ARCH_HAVE_EXTCLK is not set +# CONFIG_ARCH_HAVE_POWEROFF is not set +CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_IRQPRIO is not set +CONFIG_ARCH_STACKDUMP=y +# CONFIG_ENDIAN_BIG is not set +# CONFIG_ARCH_IDLE_CUSTOM is not set +# CONFIG_ARCH_HAVE_RAMFUNCS is not set +# CONFIG_ARCH_HAVE_RAMVECTORS is not set +# CONFIG_ARCH_MINIMAL_VECTORTABLE is not set + +# +# Board Settings +# +CONFIG_BOARD_LOOPSPERMSEC=2796 +# CONFIG_ARCH_CALIBRATION is not set + +# +# Interrupt options +# +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y +CONFIG_ARCH_INTERRUPTSTACK=0 +# CONFIG_ARCH_HAVE_HIPRI_INTERRUPT is not set + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Boot Memory Configuration +# +CONFIG_RAM_START=0x20000000 +CONFIG_RAM_SIZE=8192 +# CONFIG_ARCH_HAVE_SDRAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_NUCLEO_F072RB=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="nucleo-f072rb" + +# +# Common Board Options +# +CONFIG_ARCH_HAVE_LEDS=y +CONFIG_ARCH_LEDS=y +CONFIG_ARCH_HAVE_BUTTONS=y +# CONFIG_ARCH_BUTTONS is not set +CONFIG_ARCH_HAVE_IRQBUTTONS=y + +# +# Board-Specific Options +# +# CONFIG_BOARD_CRASHDUMP is not set +# CONFIG_LIB_BOARDCTL is not set + +# +# RTOS Features +# +CONFIG_DISABLE_OS_API=y +CONFIG_DISABLE_POSIX_TIMERS=y +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_DISABLE_SIGNALS is not set +CONFIG_DISABLE_MQUEUE=y +CONFIG_DISABLE_ENVIRON=y + +# +# Clocks and Timers +# +CONFIG_USEC_PER_TICK=10000 +# CONFIG_SYSTEM_TIME64 is not set +# CONFIG_CLOCK_MONOTONIC is not set +# CONFIG_ARCH_HAVE_TIMEKEEPING is not set +# CONFIG_JULIAN_TIME is not set +CONFIG_START_YEAR=2013 +CONFIG_START_MONTH=5 +CONFIG_START_DAY=19 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=4 +CONFIG_WDOG_INTRESERVE=0 +CONFIG_PREALLOC_TIMERS=0 + +# +# Tasks and Scheduling +# +# CONFIG_SPINLOCK is not set +# CONFIG_INIT_NONE is not set +CONFIG_INIT_ENTRYPOINT=y +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_RR_INTERVAL=200 +# CONFIG_SCHED_SPORADIC is not set +CONFIG_TASK_NAME_SIZE=0 +CONFIG_MAX_TASKS=8 +# CONFIG_SCHED_HAVE_PARENT is not set +CONFIG_SCHED_WAITPID=y + +# +# Pthread Options +# +# CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set +CONFIG_NPTHREAD_KEYS=0 +# CONFIG_PTHREAD_CLEANUP is not set +# CONFIG_CANCELLATION_POINTS is not set + +# +# Performance Monitoring +# +# CONFIG_SCHED_CPULOAD is not set +# CONFIG_SCHED_INSTRUMENTATION is not set + +# +# Files and I/O +# +CONFIG_DEV_CONSOLE=y +# CONFIG_FDCLONE_DISABLE is not set +# CONFIG_FDCLONE_STDIO is not set +CONFIG_SDCLONE_DISABLE=y +CONFIG_NFILE_DESCRIPTORS=6 +CONFIG_NFILE_STREAMS=6 +CONFIG_NAME_MAX=32 +# CONFIG_PRIORITY_INHERITANCE is not set + +# +# RTOS hooks +# +# CONFIG_BOARD_INITIALIZE is not set +# CONFIG_SCHED_STARTHOOK is not set +# CONFIG_SCHED_ATEXIT is not set +# CONFIG_SCHED_ONEXIT is not set + +# +# Signal Numbers +# +CONFIG_SIG_SIGUSR1=1 +CONFIG_SIG_SIGUSR2=2 +CONFIG_SIG_SIGALARM=3 +CONFIG_SIG_SIGCONDTIMEDOUT=16 +# CONFIG_MODULE is not set + +# +# Work queue support +# +# CONFIG_SCHED_WORKQUEUE is not set +# CONFIG_SCHED_HPWORK is not set +# CONFIG_SCHED_LPWORK is not set + +# +# Stack and heap information +# +CONFIG_IDLETHREAD_STACKSIZE=1024 +CONFIG_USERMAIN_STACKSIZE=1536 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=1536 +# CONFIG_LIB_SYSCALL is not set + +# +# Device Drivers +# +CONFIG_DISABLE_POLL=y +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_DEV_URANDOM is not set +# CONFIG_DEV_LOOP is not set + +# +# Buffering +# +# CONFIG_DRVR_WRITEBUFFER is not set +# CONFIG_DRVR_READAHEAD is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_ARCH_HAVE_PWM_PULSECOUNT is not set +# CONFIG_ARCH_HAVE_PWM_MULTICHAN is not set +# CONFIG_PWM is not set +# CONFIG_ARCH_HAVE_I2CRESET is not set +# CONFIG_I2C is not set +# CONFIG_ARCH_HAVE_SPI_CRCGENERATION is not set +# CONFIG_ARCH_HAVE_SPI_CS_CONTROL is not set +# CONFIG_ARCH_HAVE_SPI_BITORDER is not set +# CONFIG_SPI is not set +# CONFIG_I2S is not set + +# +# Timer Driver Support +# +# CONFIG_TIMER is not set +# CONFIG_ONESHOT is not set +# CONFIG_RTC is not set +# CONFIG_WATCHDOG is not set +# CONFIG_ANALOG is not set +# CONFIG_AUDIO_DEVICES is not set +# CONFIG_VIDEO_DEVICES is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set + +# +# IO Expander/GPIO Support +# +# CONFIG_IOEXPANDER is not set +# CONFIG_DEV_GPIO is not set + +# +# LCD Driver Support +# +# CONFIG_LCD is not set +# CONFIG_SLCD is not set + +# +# LED Support +# +# CONFIG_USERLED is not set +# CONFIG_RGBLED is not set +# CONFIG_PCA9635PW is not set +# CONFIG_NCP5623C is not set +# CONFIG_MMCSD is not set +# CONFIG_MODEM is not set +# CONFIG_MTD is not set +# CONFIG_EEPROM is not set +# CONFIG_PIPES is not set +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +CONFIG_SERIAL=y +# CONFIG_DEV_LOWCONSOLE is not set +# CONFIG_SERIAL_REMOVABLE is not set +CONFIG_SERIAL_CONSOLE=y +# CONFIG_16550_UART is not set +# CONFIG_UART_SERIALDRIVER is not set +# CONFIG_UART0_SERIALDRIVER is not set +# CONFIG_UART1_SERIALDRIVER is not set +# CONFIG_UART2_SERIALDRIVER is not set +# CONFIG_UART3_SERIALDRIVER is not set +# CONFIG_UART4_SERIALDRIVER is not set +# CONFIG_UART5_SERIALDRIVER is not set +# CONFIG_UART6_SERIALDRIVER is not set +# CONFIG_UART7_SERIALDRIVER is not set +# CONFIG_UART8_SERIALDRIVER is not set +# CONFIG_SCI0_SERIALDRIVER is not set +# CONFIG_SCI1_SERIALDRIVER is not set +# CONFIG_USART0_SERIALDRIVER is not set +# CONFIG_USART1_SERIALDRIVER is not set +CONFIG_USART2_SERIALDRIVER=y +# CONFIG_USART3_SERIALDRIVER is not set +# CONFIG_USART4_SERIALDRIVER is not set +# CONFIG_USART5_SERIALDRIVER is not set +# CONFIG_USART6_SERIALDRIVER is not set +# CONFIG_USART7_SERIALDRIVER is not set +# CONFIG_USART8_SERIALDRIVER is not set +# CONFIG_OTHER_UART_SERIALDRIVER is not set +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +# CONFIG_SERIAL_IFLOWCONTROL is not set +# CONFIG_SERIAL_OFLOWCONTROL is not set +# CONFIG_SERIAL_DMA is not set +CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y +CONFIG_USART2_SERIAL_CONSOLE=y +# CONFIG_OTHER_SERIAL_CONSOLE is not set +# CONFIG_NO_SERIAL_CONSOLE is not set + +# +# USART2 Configuration +# +CONFIG_USART2_RXBUFSIZE=32 +CONFIG_USART2_TXBUFSIZE=32 +CONFIG_USART2_BAUD=115200 +CONFIG_USART2_BITS=8 +CONFIG_USART2_PARITY=0 +CONFIG_USART2_2STOP=0 +# CONFIG_USART2_IFLOWCONTROL is not set +# CONFIG_USART2_OFLOWCONTROL is not set +# CONFIG_USART2_DMA is not set +# CONFIG_PSEUDOTERM is not set +# CONFIG_USBDEV is not set +# CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set +# CONFIG_HAVE_USBTRACE is not set +# CONFIG_DRIVERS_WIRELESS is not set +# CONFIG_DRIVERS_CONTACTLESS is not set + +# +# System Logging +# +# CONFIG_ARCH_SYSLOG is not set +# CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_INTBUFFER is not set +# CONFIG_SYSLOG_TIMESTAMP is not set +CONFIG_SYSLOG_SERIAL_CONSOLE=y +# CONFIG_SYSLOG_CHAR is not set +CONFIG_SYSLOG_CONSOLE=y +# CONFIG_SYSLOG_NONE is not set +# CONFIG_SYSLOG_FILE is not set +# CONFIG_SYSLOG_CHARDEV is not set + +# +# Networking Support +# +# CONFIG_ARCH_HAVE_NET is not set +# CONFIG_ARCH_HAVE_PHY is not set +# CONFIG_NET is not set + +# +# Crypto API +# +# CONFIG_CRYPTO is not set + +# +# File Systems +# + +# +# File system configuration +# +CONFIG_DISABLE_MOUNTPOINT=y +CONFIG_DISABLE_PSEUDOFS_OPERATIONS=y +# CONFIG_FS_READABLE is not set +# CONFIG_FS_WRITABLE is not set +# CONFIG_FS_NAMED_SEMAPHORES is not set +# CONFIG_FS_RAMMAP is not set +# CONFIG_FS_PROCFS is not set +# CONFIG_FS_UNIONFS is not set + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +CONFIG_MM_SMALL=y +CONFIG_MM_REGIONS=1 +# CONFIG_ARCH_HAVE_HEAP2 is not set +# CONFIG_GRAN is not set + +# +# Audio Support +# +# CONFIG_AUDIO is not set + +# +# Wireless Support +# + +# +# Binary Loader +# +CONFIG_BINFMT_DISABLE=y +# CONFIG_PIC is not set +# CONFIG_SYMTAB_ORDEREDBYNAME is not set + +# +# Library Routines +# + +# +# Standard C Library Options +# + +# +# Standard C I/O +# +CONFIG_STDIO_DISABLE_BUFFERING=y +CONFIG_NUNGET_CHARS=0 +# CONFIG_NOPRINTF_FIELDWIDTH is not set +# CONFIG_LIBC_FLOATINGPOINT is not set +# CONFIG_LIBC_LONG_LONG is not set +# CONFIG_LIBC_SCANSET is not set +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_MEMCPY_VIK is not set +# CONFIG_LIBM is not set + +# +# Architecture-Specific Support +# +CONFIG_ARCH_LOWPUTC=y +# CONFIG_ARCH_ROMGETC is not set +# CONFIG_LIBC_ARCH_MEMCPY is not set +# CONFIG_LIBC_ARCH_MEMCMP is not set +# CONFIG_LIBC_ARCH_MEMMOVE is not set +# CONFIG_LIBC_ARCH_MEMSET is not set +# CONFIG_LIBC_ARCH_STRCHR is not set +# CONFIG_LIBC_ARCH_STRCMP is not set +# CONFIG_LIBC_ARCH_STRCPY is not set +# CONFIG_LIBC_ARCH_STRNCPY is not set +# CONFIG_LIBC_ARCH_STRLEN is not set +# CONFIG_LIBC_ARCH_STRNLEN is not set +# CONFIG_LIBC_ARCH_ELF is not set + +# +# stdlib Options +# +CONFIG_LIB_RAND_ORDER=1 + +# +# Program Execution Options +# +CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024 +CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=1536 + +# +# errno Decode Support +# +# CONFIG_LIBC_STRERROR is not set +# CONFIG_LIBC_PERROR_STDOUT is not set + +# +# memcpy/memset Options +# +# CONFIG_MEMSET_OPTSPEED is not set +# CONFIG_LIBC_DLLFCN is not set +# CONFIG_LIBC_MODLIB is not set +# CONFIG_LIBC_WCHAR is not set +# CONFIG_LIBC_LOCALE is not set + +# +# Time/Time Zone Support +# +# CONFIG_TIME_EXTENDED is not set +CONFIG_ARCH_HAVE_TLS=y + +# +# Thread Local Storage (TLS) +# +# CONFIG_TLS is not set + +# +# Network-Related Options +# +# CONFIG_LIBC_IPv4_ADDRCONV is not set +# CONFIG_LIBC_IPv6_ADDRCONV is not set +# CONFIG_LIBC_NETDB is not set + +# +# NETDB Support +# +# CONFIG_LIBC_IOCTL_VARIADIC is not set +CONFIG_LIB_SENDFILE_BUFSIZE=512 + +# +# Non-standard Library Support +# +# CONFIG_LIB_CRC64_FAST is not set +# CONFIG_LIB_KBDCODEC is not set +# CONFIG_LIB_SLCDCODEC is not set +# CONFIG_LIB_HEX2BIN is not set + +# +# Basic CXX Support +# +# CONFIG_C99_BOOL8 is not set +# CONFIG_HAVE_CXX is not set + +# +# Application Configuration +# + +# +# CAN Utilities +# + +# +# Examples +# +# CONFIG_EXAMPLES_BUTTONS is not set +# CONFIG_EXAMPLES_CCTYPE is not set +# CONFIG_EXAMPLES_CHAT is not set +# CONFIG_EXAMPLES_CONFIGDATA is not set +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HIDKBD is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_JSON is not set +# CONFIG_EXAMPLES_KEYPADTEST is not set +# CONFIG_EXAMPLES_MEDIA is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MODBUS is not set +# CONFIG_EXAMPLES_MOUNT is not set +CONFIG_EXAMPLES_NSH=y +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NXLINES is not set +# CONFIG_EXAMPLES_NXTERM is not set +# CONFIG_EXAMPLES_NXTEXT is not set +# CONFIG_EXAMPLES_OSTEST is not set +# CONFIG_EXAMPLES_PCA9635 is not set +# CONFIG_EXAMPLES_POSIXSPAWN is not set +# CONFIG_EXAMPLES_PPPD is not set +# CONFIG_EXAMPLES_RFID_READUID is not set +# CONFIG_EXAMPLES_RGBLED is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERIALBLASTER is not set +# CONFIG_EXAMPLES_SERIALRX is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_SLCD is not set +# CONFIG_EXAMPLES_SMART is not set +# CONFIG_EXAMPLES_SMP is not set +# CONFIG_EXAMPLES_STAT is not set +# CONFIG_EXAMPLES_TCPECHO is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_WATCHDOG is not set +# CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set + +# +# File System Utilities +# +# CONFIG_FSUTILS_INIFILE is not set + +# +# GPS Utilities +# +# CONFIG_GPSUTILS_MINMEA_LIB is not set + +# +# Graphics Support +# +# CONFIG_TIFF is not set +# CONFIG_GRAPHICS_TRAVELER is not set + +# +# Interpreters +# +# CONFIG_INTERPRETERS_FICL is not set +# CONFIG_INTERPRETERS_MICROPYTHON is not set +# CONFIG_INTERPRETERS_MINIBASIC is not set +# CONFIG_INTERPRETERS_PCODE is not set + +# +# FreeModBus +# +# CONFIG_MODBUS is not set + +# +# Network Utilities +# +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_ESP8266 is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_JSON is not set +# CONFIG_NETUTILS_SMTP is not set + +# +# NSH Library +# +CONFIG_NSH_LIBRARY=y +# CONFIG_NSH_MOTD is not set + +# +# Command Line Configuration +# +CONFIG_NSH_READLINE=y +# CONFIG_NSH_CLE is not set +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_DISABLE_SEMICOLON=y +CONFIG_NSH_MAXARGUMENTS=6 +# CONFIG_NSH_ARGCAT is not set +CONFIG_NSH_NESTDEPTH=3 +# CONFIG_NSH_DISABLEBG is not set + +# +# Disable Individual commands +# +CONFIG_NSH_DISABLE_ADDROUTE=y +CONFIG_NSH_DISABLE_BASENAME=y +# CONFIG_NSH_DISABLE_CAT is not set +CONFIG_NSH_DISABLE_CD=y +CONFIG_NSH_DISABLE_CP=y +CONFIG_NSH_DISABLE_CMP=y +CONFIG_NSH_DISABLE_DATE=y +CONFIG_NSH_DISABLE_DD=y +CONFIG_NSH_DISABLE_DF=y +CONFIG_NSH_DISABLE_DELROUTE=y +CONFIG_NSH_DISABLE_DIRNAME=y +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_FREE is not set +CONFIG_NSH_DISABLE_GET=y +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_HEXDUMP is not set +CONFIG_NSH_DISABLE_IFCONFIG=y +CONFIG_NSH_DISABLE_IFUPDOWN=y +# CONFIG_NSH_DISABLE_KILL is not set +CONFIG_NSH_DISABLE_LOSETUP=y +CONFIG_NSH_DISABLE_LOSMART=y +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MB is not set +CONFIG_NSH_DISABLE_MKDIR=y +CONFIG_NSH_DISABLE_MKRD=y +# CONFIG_NSH_DISABLE_MH is not set +CONFIG_NSH_DISABLE_MOUNT=y +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_MW is not set +CONFIG_NSH_DISABLE_PRINTF=y +# CONFIG_NSH_DISABLE_PS is not set +CONFIG_NSH_DISABLE_PUT=y +# CONFIG_NSH_DISABLE_PWD is not set +CONFIG_NSH_DISABLE_RM=y +CONFIG_NSH_DISABLE_RMDIR=y +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SH is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +CONFIG_NSH_DISABLE_TIME=y +# CONFIG_NSH_DISABLE_TEST is not set +CONFIG_NSH_DISABLE_UMOUNT=y +CONFIG_NSH_DISABLE_UNAME=y +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_NSH_DISABLE_WGET=y +# CONFIG_NSH_DISABLE_XD is not set +CONFIG_NSH_MMCSDMINOR=0 + +# +# Configure Command Options +# +CONFIG_NSH_CODECS_BUFSIZE=128 +# CONFIG_NSH_CMDOPT_HEXDUMP is not set +CONFIG_NSH_FILEIOSIZE=64 + +# +# Scripting Support +# +CONFIG_NSH_DISABLESCRIPT=y + +# +# Console Configuration +# +CONFIG_NSH_CONSOLE=y +# CONFIG_NSH_ALTCONDEV is not set +# CONFIG_NSH_ARCHINIT is not set +# CONFIG_NSH_LOGIN is not set +# CONFIG_NSH_CONSOLE_LOGIN is not set + +# +# NxWidgets/NxWM +# + +# +# Platform-specific Support +# +# CONFIG_PLATFORM_CONFIGDATA is not set + +# +# System Libraries and NSH Add-Ons +# +# CONFIG_SYSTEM_CLE is not set +# CONFIG_SYSTEM_CUTERM is not set +# CONFIG_SYSTEM_FREE is not set +# CONFIG_SYSTEM_HEX2BIN is not set +# CONFIG_SYSTEM_HEXED is not set +# CONFIG_SYSTEM_INSTALL is not set +# CONFIG_SYSTEM_RAMTEST is not set +CONFIG_READLINE_HAVE_EXTMATCH=y +CONFIG_SYSTEM_READLINE=y +CONFIG_READLINE_ECHO=y +# CONFIG_READLINE_TABCOMPLETION is not set +# CONFIG_READLINE_CMD_HISTORY is not set +# CONFIG_SYSTEM_SUDOKU is not set +# CONFIG_SYSTEM_SYSTEM is not set +# CONFIG_SYSTEM_TEE is not set +# CONFIG_SYSTEM_UBLOXMODEM is not set +# CONFIG_SYSTEM_VI is not set +# CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# diff --git a/configs/nucleo-f072rb/nsh/setenv.sh b/configs/nucleo-f072rb/nsh/setenv.sh new file mode 100644 index 0000000000..9a1e879f87 --- /dev/null +++ b/configs/nucleo-f072rb/nsh/setenv.sh @@ -0,0 +1,81 @@ +#!/bin/bash +# configs/nucleo-f072rb/nsh/setenv.sh +# +# Copyright (C) 2017 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# Alan Carvalho de Assis +# +# 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. +# + +if [ "$_" = "$0" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +fi + +WD=`pwd` +if [ ! -x "setenv.sh" ]; then + echo "This script must be executed from the top-level NuttX build directory" + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then + export PATH_ORIG="${PATH}" +fi + +# This is the Cygwin path to the location where I installed the CodeSourcery +# toolchain under windows. You will also have to edit this if you install +# the CodeSourcery toolchain in any other location +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin" +# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin" + +# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors" +# You can this free toolchain here https://launchpad.net/gcc-arm-embedded +export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin" + +# This is the path to the location where I installed the devkitARM toolchain +# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/ +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin" + +# These are the Cygwin paths to the locations where I installed the Atollic +# toolchain under windows. You will also have to edit this if you install +# the Atollic toolchain in any other location. /usr/bin is added before +# the Atollic bin path because there is are binaries named gcc.exe and g++.exe +# at those locations as well. +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" + +# This is the Cygwin path to the location where I build the buildroot +# toolchain. +# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" + +# Add the path to the toolchain to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" + +echo "PATH : ${PATH}" diff --git a/configs/nucleo-f072rb/scripts/flash.ld b/configs/nucleo-f072rb/scripts/flash.ld new file mode 100644 index 0000000000..6c880d9d27 --- /dev/null +++ b/configs/nucleo-f072rb/scripts/flash.ld @@ -0,0 +1,127 @@ +/**************************************************************************** + * configs/nucleo-f072rb/scripts/flash.ld + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Alan Carvalho de Assis + * + * 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. + * + ****************************************************************************/ + +/* The STM32F072RBT6 has 128KB of FLASH beginning at address 0x0800:0000 and + * 16Kb of SRAM at address 0x20000000. + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x08000000, LENGTH = 128K + sram (rwx) : ORIGIN = 0x20000000, LENGTH = 16K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +SECTIONS +{ + .text : + { + _stext = ABSOLUTE(.); + *(.vectors) + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + } > flash + + .init_section : + { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : + { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : + { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : + { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : + { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/configs/nucleo-f072rb/src/.gitignore b/configs/nucleo-f072rb/src/.gitignore new file mode 100644 index 0000000000..726d936e1e --- /dev/null +++ b/configs/nucleo-f072rb/src/.gitignore @@ -0,0 +1,2 @@ +/.depend +/Make.dep diff --git a/configs/nucleo-f072rb/src/Makefile b/configs/nucleo-f072rb/src/Makefile new file mode 100644 index 0000000000..c985180e74 --- /dev/null +++ b/configs/nucleo-f072rb/src/Makefile @@ -0,0 +1,56 @@ +############################################################################ +# configs/nucleo-f072rb/src/Makefile +# +# Copyright (C) 2017 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# Alan Carvalho de Assis +# +# 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. +# +############################################################################ + +-include $(TOPDIR)/Make.defs + +ASRCS = +CSRCS = stm32_boot.c stm32_bringup.c + +ifeq ($(CONFIG_ARCH_LEDS),y) +CSRCS += stm32_autoleds.c +else +CSRCS += stm32_userleds.c +endif + +ifeq ($(CONFIG_ARCH_BUTTONS),y) +CSRCS += stm32_buttons.c +endif + +ifeq ($(CONFIG_LIB_BOARDCTL),y) +CSRCS += stm32_appinit.c +endif + +include $(TOPDIR)/configs/Board.mk diff --git a/configs/nucleo-f072rb/src/nucleo-f072rb.h b/configs/nucleo-f072rb/src/nucleo-f072rb.h new file mode 100644 index 0000000000..04d7bc6ffc --- /dev/null +++ b/configs/nucleo-f072rb/src/nucleo-f072rb.h @@ -0,0 +1,123 @@ +/**************************************************************************** + * configs/nucleo-f072rb/src/nucleo-f072rb.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Alan Carvalho de Assis + * + * 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 __CONFIGS_NUCLEO_F072RB_SRC_NUCLEO_F072RB_H +#define __CONFIGS_NUCLEO_F072RB_SRC_NUCLEO_F072RB_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +#include "stm32f0_gpio.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ +/* How many SPI modules does this chip support? */ + +#if STM32F0_NSPI < 1 +# undef CONFIG_STM32F0_SPI1 +# undef CONFIG_STM32F0_SPI2 +# undef CONFIG_STM32F0_SPI3 +#elif STM32F0_NSPI < 2 +# undef CONFIG_STM32F0_SPI2 +# undef CONFIG_STM32F0_SPI3 +#elif STM32F0_NSPI < 3 +# undef CONFIG_STM32F0_SPI3 +#endif + +/* Nucleo-F072RB GPIOs ******************************************************/ +/* LED. User LD2: the green LED is a user LED connected to Arduino signal + * D13 corresponding to MCU I/O PA5 (pin 21) or PB13 (pin 34) depending on + * the STM32 target. + * + * - When the I/O is HIGH value, the LED is on. + * - When the I/O is LOW, the LED is off. + */ + +#define GPIO_LD2 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_10MHz | \ + GPIO_OUTPUT_CLEAR | GPIO_PORTA | GPIO_PIN5) + +/* Button definitions *******************************************************/ +/* B1 USER: the user button is connected to the I/O PC13 (pin 2) of the STM32 + * microcontroller. + */ + +#define MIN_IRQBUTTON BUTTON_USER +#define MAX_IRQBUTTON BUTTON_USER +#define NUM_IRQBUTTONS 1 + +#define GPIO_BTN_USER (GPIO_INPUT | GPIO_FLOAT | GPIO_EXTI | \ + GPIO_PORTC | GPIO_PIN13) + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/**************************************************************************** + * Public data + ****************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_bringup + * + * Description: + * Perform architecture-specific initialization + * + * CONFIG_BOARD_INITIALIZE=y : + * Called from board_initialize(). + * + * CONFIG_BOARD_INITIALIZE=n && CONFIG_LIB_BOARDCTL=y : + * Called from the NSH library + * + ****************************************************************************/ + +int stm32_bringup(void); + +#endif /* __ASSEMBLY__ */ +#endif /* __CONFIGS_NUCLEO_F072RB_SRC_NUCLEO_F072RB_H */ diff --git a/configs/nucleo-f072rb/src/stm32_appinit.c b/configs/nucleo-f072rb/src/stm32_appinit.c new file mode 100644 index 0000000000..0ce7ce4d66 --- /dev/null +++ b/configs/nucleo-f072rb/src/stm32_appinit.c @@ -0,0 +1,87 @@ +/**************************************************************************** + * config/nucleo-f072rb/src/stm32_appinit.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Alan Carvalho de Assis + * + * 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 "nucleo-f072rb.h" + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; the meaning of the argument is a contract + * between the board-specific initalization logic and the the + * matching application logic. The value cold be such things as a + * mode enumeration value, a set of DIP switch switch settings, a + * pointer to configuration data read from a file or serial FLASH, + * or whatever you would like to do with it. Every implementation + * should accept zero/NULL as a default configuration. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ + +int board_app_initialize(uintptr_t arg) +{ + /* Did we already initialize via board_initialize()? */ + +#ifndef CONFIG_BOARD_INITIALIZE + return stm32_bringup(); +#else + return OK; +#endif +} diff --git a/configs/nucleo-f072rb/src/stm32_autoleds.c b/configs/nucleo-f072rb/src/stm32_autoleds.c new file mode 100644 index 0000000000..d03a41cfad --- /dev/null +++ b/configs/nucleo-f072rb/src/stm32_autoleds.c @@ -0,0 +1,96 @@ +/**************************************************************************** + * configs/nucleo-f072rb/src/stm32_autoleds.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "up_arch.h" +#include "up_internal.h" +#include "stm32.h" +#include "nucleo-f072rb.h" + +#ifdef CONFIG_ARCH_LEDS + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_autoled_initialize + ****************************************************************************/ + +void board_autoled_initialize(void) +{ + /* Configure LD2 GPIO for output */ + + stm32_configgpio(GPIO_LD2); +} + +/**************************************************************************** + * Name: board_autoled_on + ****************************************************************************/ + +void board_autoled_on(int led) +{ + if (led == 1) + { + stm32_gpiowrite(GPIO_LD2, true); + } +} + +/**************************************************************************** + * Name: board_autoled_off + ****************************************************************************/ + +void board_autoled_off(int led) +{ + if (led == 1) + { + stm32_gpiowrite(GPIO_LD2, false); + } +} + +#endif /* CONFIG_ARCH_LEDS */ diff --git a/configs/nucleo-f072rb/src/stm32_boot.c b/configs/nucleo-f072rb/src/stm32_boot.c new file mode 100644 index 0000000000..0655e5b0b6 --- /dev/null +++ b/configs/nucleo-f072rb/src/stm32_boot.c @@ -0,0 +1,94 @@ +/************************************************************************************ + * configs/nucleo-f072rb/src/stm32f0_boot.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Alan Carvalho de Assis + * + * 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 "up_arch.h" +#include "nucleo-f072rb.h" + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32f0_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the intitialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +void stm32f0_boardinitialize(void) +{ +#ifdef CONFIG_ARCH_LEDS + /* Configure on-board LEDs if LED support has been selected. */ + + board_autoled_initialize(); +#endif +} + +/**************************************************************************** + * Name: board_initialize + * + * Description: + * If CONFIG_BOARD_INITIALIZE is selected, then an additional + * initialization call will be performed in the boot-up sequence to a + * function called board_initialize(). board_initialize() will be + * called immediately after up_initialize() is called and just before the + * initial application is started. This additional initialization phase + * may be used, for example, to initialize board-specific device drivers. + * + ****************************************************************************/ + +#ifdef CONFIG_BOARD_INITIALIZE +void board_initialize(void) +{ + /* Perform board-specific initialization here if so configured */ + + (void)stm32_bringup(); +} +#endif diff --git a/configs/nucleo-f072rb/src/stm32_bringup.c b/configs/nucleo-f072rb/src/stm32_bringup.c new file mode 100644 index 0000000000..0c9c7f89df --- /dev/null +++ b/configs/nucleo-f072rb/src/stm32_bringup.c @@ -0,0 +1,81 @@ +/**************************************************************************** + * config/nucleo-f072rb/src/stm32_bringup.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include "nucleo-f072rb.h" + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_bringup + * + * Description: + * Perform architecture-specific initialization + * + * CONFIG_BOARD_INITIALIZE=y : + * Called from board_initialize(). + * + * CONFIG_BOARD_INITIALIZE=n && CONFIG_LIB_BOARDCTL=y : + * Called from the NSH library + * + ****************************************************************************/ + +int stm32_bringup(void) +{ + int ret; + +#ifdef CONFIG_FS_PROCFS + /* Mount the procfs file system */ + + ret = mount(NULL, "/proc", "procfs", 0, NULL); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: Failed to mount procfs at /proc: %d\n", ret); + } +#endif + + UNUSED(ret); + return OK; +} diff --git a/configs/nucleo-f072rb/src/stm32_buttons.c b/configs/nucleo-f072rb/src/stm32_buttons.c new file mode 100644 index 0000000000..b4aed6807a --- /dev/null +++ b/configs/nucleo-f072rb/src/stm32_buttons.c @@ -0,0 +1,126 @@ +/**************************************************************************** + * configs/nucleo-f072rb/src/stm32_buttons.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include +#include +#include + +#include "nucleo-f072rb.h" + +#ifdef CONFIG_ARCH_BUTTONS + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_button_initialize + * + * Description: + * board_button_initialize() must be called to initialize button resources. + * After that, board_buttons() may be called to collect the current state + * of all buttons or board_button_irq() may be called to register button + * interrupt handlers. + * + ****************************************************************************/ + +void board_button_initialize(void) +{ + /* Configure the single button as an input. NOTE that EXTI interrupts are + * also configured for the pin. + */ + + stm32_configgpio(GPIO_BTN_USER); +} + +/**************************************************************************** + * Name: board_buttons + ****************************************************************************/ + +uint32_t board_buttons(void) +{ + /* Check that state of each USER button. A LOW value means that the key is + * pressed. + */ + + bool released = stm32_gpioread(GPIO_BTN_USER); + return !released; +} + +/************************************************************************************ + * Button support. + * + * Description: + * board_button_initialize() must be called to initialize button resources. After + * that, board_buttons() may be called to collect the current state of all + * buttons or board_button_irq() may be called to register button interrupt + * handlers. + * + * After board_button_initialize() has been called, board_buttons() may be called to + * collect the state of all buttons. board_buttons() returns an 32-bit bit set + * with each bit associated with a button. See the BUTTON_*_BIT + * definitions in board.h for the meaning of each bit. + * + * board_button_irq() may be called to register an interrupt handler that will + * be called when a button is depressed or released. The ID value is a + * button enumeration value that uniquely identifies a button resource. See the + * BUTTON_* definitions in board.h for the meaning of enumeration + * value. + * + ************************************************************************************/ + +#ifdef CONFIG_ARCH_IRQBUTTONS +int board_button_irq(int id, xcpt_t irqhandler, FAR void *arg) +{ + int ret = -EINVAL; + + if (id == BUTTON_USER) + { + ret = stm32_gpiosetevent(GPIO_BTN_USER, true, true, true, irqhandler, arg); + } + + return ret; +} +#endif +#endif /* CONFIG_ARCH_BUTTONS */ diff --git a/configs/nucleo-f072rb/src/stm32_userleds.c b/configs/nucleo-f072rb/src/stm32_userleds.c new file mode 100644 index 0000000000..08ccef5b8f --- /dev/null +++ b/configs/nucleo-f072rb/src/stm32_userleds.c @@ -0,0 +1,217 @@ +/**************************************************************************** + * configs/nucleo-f072rb/src/stm32_userleds.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "up_arch.h" +#include "up_internal.h" +#include "stm32.h" +#include "nucleo-f072rb.h" + +#ifndef CONFIG_ARCH_LEDS + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* LED Power Management */ + +#ifdef CONFIG_PM +static void led_pm_notify(struct pm_callback_s *cb, int domain, + enum pm_state_e pmstate); +static int led_pm_prepare(struct pm_callback_s *cb, int domain, + enum pm_state_e pmstate); +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +#ifdef CONFIG_PM +static struct pm_callback_s g_ledscb = +{ + .notify = led_pm_notify, + .prepare = led_pm_prepare, +}; +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: led_pm_notify + * + * Description: + * Notify the driver of new power state. This callback is called after + * all drivers have had the opportunity to prepare for the new power state. + * + ****************************************************************************/ + +#ifdef CONFIG_PM +static void led_pm_notify(struct pm_callback_s *cb, int domain, + enum pm_state_e pmstate) +{ + switch (pmstate) + { + case(PM_NORMAL): + { + /* Restore normal LEDs operation */ + + } + break; + + case(PM_IDLE): + { + /* Entering IDLE mode - Turn leds off */ + + } + break; + + case(PM_STANDBY): + { + /* Entering STANDBY mode - Logic for PM_STANDBY goes here */ + + } + break; + + case(PM_SLEEP): + { + /* Entering SLEEP mode - Logic for PM_SLEEP goes here */ + + } + break; + + default: + { + /* Should not get here */ + + } + break; + } +} +#endif + +/**************************************************************************** + * Name: led_pm_prepare + * + * Description: + * Request the driver to prepare for a new power state. This is a warning + * that the system is about to enter into a new power state. The driver + * should begin whatever operations that may be required to enter power + * state. The driver may abort the state change mode by returning a + * non-zero value from the callback function. + * + ****************************************************************************/ + +#ifdef CONFIG_PM +static int led_pm_prepare(struct pm_callback_s *cb, int domain, + enum pm_state_e pmstate) +{ + /* No preparation to change power modes is required by the LEDs driver. + * We always accept the state change by returning OK. + */ + + return OK; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_userled_initialize + ****************************************************************************/ + +void board_userled_initialize(void) +{ + /* Configure LD2 GPIO for output */ + + stm32_configgpio(GPIO_LD2); +} + +/**************************************************************************** + * Name: board_userled + ****************************************************************************/ + +void board_userled(int led, bool ledon) +{ + if (led == 1) + { + stm32_gpiowrite(GPIO_LD2, ldeon); + } +} + +/**************************************************************************** + * Name: board_userled_all + ****************************************************************************/ + +void board_userled_all(uint8_t ledset) +{ + if (led == 1) + { + stm32_gpiowrite(GPIO_LD2, (ledset & BOARD_LD2_BIT) != 0); + } +} + +/**************************************************************************** + * Name: stm32_led_pminitialize + ****************************************************************************/ + +#ifdef CONFIG_PM +void stm32_led_pminitialize(void) +{ + /* Register to receive power management callbacks */ + + int ret = pm_register(&g_ledscb); + DEBUGASSERT(ret == OK); + UNUSED(ret); +} +#endif /* CONFIG_PM */ + +#endif /* !CONFIG_ARCH_LEDS */ -- GitLab From 27e212a2918ec144931f5301d0d5564f5a2af087 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 18 Apr 2017 10:37:05 -0600 Subject: [PATCH 502/990] Nucleo-F072RB: Various fixes to get the first clean build. --- arch/arm/include/stm32f0/chip.h | 18 +++++++++--------- arch/arm/src/stm32f0/chip/stm32f07x_pinmap.h | 4 ++-- arch/arm/src/stm32f0/stm32f0_lowputc.c | 8 ++++---- arch/arm/src/stm32f0/stm32f0_serial.c | 16 ++++++++-------- configs/nucleo-f072rb/src/stm32_autoleds.c | 8 ++++---- configs/nucleo-f072rb/src/stm32_userleds.c | 12 ++++++------ 6 files changed, 33 insertions(+), 33 deletions(-) diff --git a/arch/arm/include/stm32f0/chip.h b/arch/arm/include/stm32f0/chip.h index 3dd656ffa5..a50902d462 100644 --- a/arch/arm/include/stm32f0/chip.h +++ b/arch/arm/include/stm32f0/chip.h @@ -68,11 +68,11 @@ # define STM32F0_NCAP 13 /* Capacitive sensing channels (14 on UFQFPN32)) */ # define STM32F0_NPORTS 6 /* Six GPIO ports, GPIOA-F */ -#elif defined(CONFIG_ARCH_CHIP_SSTM32F072C8) || defined(CONFIG_ARCH_CHIP_SSTM32F072CB) +#elif defined(CONFIG_ARCH_CHIP_STM32F072C8) || defined(CONFIG_ARCH_CHIP_STM32F072CB) # undef STM32F051x /* Not STM32F051x family */ # define STM32F072x 1 /* STM32F072x family */ -# ifdef CONFIG_ARCH_CHIP_SSTM32F072C8 +# ifdef CONFIG_ARCH_CHIP_STM32F072C8 # define STM32F0_FLASH_SIZE (64*1024) /* 64Kb */ # else # define STM32F0_FLASH_SIZE (128*1024) /* 128Kb */ @@ -89,7 +89,7 @@ # define STM32F0_NUSART 4 /* Four USARTs module */ # define STM32F0_NCAN 1 /* One CAN controller */ # define STM32F0_NUSBDEV 1 /* One USB device controller */ -# deifne STM32F0_NCEC 1 /* One HDMI-CEC controller */ +# define STM32F0_NCEC 1 /* One HDMI-CEC controller */ # define STM32F0_NADC16 1 /* One 16-bit module */ # define STM32F0_NADCCHAN 10 /* Ten external channels */ # define STM32F0_NADCEXT 3 /* Three external channels */ @@ -99,11 +99,11 @@ # define STM32F0_NCAP 17 /* Capacitive sensing channels */ # define STM32F0_NPORTS 6 /* Six GPIO ports, GPIOA-F */ -#elif defined(CONFIG_ARCH_CHIP_SSTM32F072R8) || defined(CONFIG_ARCH_CHIP_SSTM32F072RB) +#elif defined(CONFIG_ARCH_CHIP_STM32F072R8) || defined(CONFIG_ARCH_CHIP_STM32F072RB) # undef STM32F051x /* Not STM32F051x family */ # define STM32F072x 1 /* STM32F072x family */ -# ifdef CONFIG_ARCH_CHIP_SSTM32F072C8 +# ifdef CONFIG_ARCH_CHIP_STM32F072R8 # define STM32F0_FLASH_SIZE (64*1024) /* 64Kb */ # else # define STM32F0_FLASH_SIZE (128*1024) /* 128Kb */ @@ -120,7 +120,7 @@ # define STM32F0_NUSART 4 /* Four USARTs module */ # define STM32F0_NCAN 1 /* One CAN controller */ # define STM32F0_NUSBDEV 1 /* One USB device controller */ -# deifne STM32F0_NCEC 1 /* One HDMI-CEC controller */ +# define STM32F0_NCEC 1 /* One HDMI-CEC controller */ # define STM32F0_NADC16 1 /* One 16-bit module */ # define STM32F0_NADCCHAN 16 /* 16 external channels */ # define STM32F0_NADCEXT 3 /* Three external channels */ @@ -130,11 +130,11 @@ # define STM32F0_NCAP 18 /* Capacitive sensing channels */ # define STM32F0_NPORTS 6 /* Six GPIO ports, GPIOA-F */ -#elif defined(CONFIG_ARCH_CHIP_SSTM32F072V8) || defined(CONFIG_ARCH_CHIP_SSTM32F072VB) +#elif defined(CONFIG_ARCH_CHIP_STM32F072V8) || defined(CONFIG_ARCH_CHIP_STM32F072VB) # undef STM32F051x /* Not STM32F051x family */ # define STM32F072x 1 /* STM32F072x family */ -# ifdef CONFIG_ARCH_CHIP_SSTM32F072C8 +# ifdef CONFIG_ARCH_CHIP_STM32F072V8 # define STM32F0_FLASH_SIZE (64*1024) /* 64Kb */ # else # define STM32F0_FLASH_SIZE (128*1024) /* 128Kb */ @@ -151,7 +151,7 @@ # define STM32F0_NUSART 4 /* Four USARTs module */ # define STM32F0_NCAN 1 /* One CAN controller */ # define STM32F0_NUSBDEV 1 /* One USB device controller */ -# deifne STM32F0_NCEC 1 /* One HDMI-CEC controller */ +# define STM32F0_NCEC 1 /* One HDMI-CEC controller */ # define STM32F0_NADC16 1 /* One 16-bit module */ # define STM32F0_NADCCHAN 16 /* 16 external channels */ # define STM32F0_NADCEXT 3 /* Three external channels */ diff --git a/arch/arm/src/stm32f0/chip/stm32f07x_pinmap.h b/arch/arm/src/stm32f0/chip/stm32f07x_pinmap.h index 5a2a67fa8e..213d8902b8 100644 --- a/arch/arm/src/stm32f0/chip/stm32f07x_pinmap.h +++ b/arch/arm/src/stm32f0/chip/stm32f07x_pinmap.h @@ -138,7 +138,7 @@ #define GPIO_EVENTOUT_17 (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN4) #define GPIO_EVENTOUT_18 (GPIO_ALT | GPIO_AF3 | GPIO_PORTA | GPIO_PIN15) #define GPIO_EVENTOUT_19 (GPIO_ALT | GPIO_AF3 | GPIO_PORTA | GPIO_PIN8) -#define GPIO_EVENTOUT_10 (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN9) +#define GPIO_EVENTOUT_20 (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN9) #define GPIO_EVENTOUT_21 (GPIO_ALT | GPIO_AF6 | GPIO_PORTA | GPIO_PIN6) #define GPIO_EVENTOUT_22 (GPIO_ALT | GPIO_AF6 | GPIO_PORTA | GPIO_PIN7) @@ -340,7 +340,7 @@ #define GPIO_TSC_G8_IO3 (GPIO_ALT | GPIO_AF1 | GPIO_PORTD | GPIO_PIN14) #define GPIO_TSC_G8_IO4 (GPIO_ALT | GPIO_AF1 | GPIO_PORTD | GPIO_PIN15) #define GPIO_TSC_SYNC_1 (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN10) -#define GPIO_TSC_SYNC_1 (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN8) +#define GPIO_TSC_SYNC_2 (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN8) /* USARTs */ diff --git a/arch/arm/src/stm32f0/stm32f0_lowputc.c b/arch/arm/src/stm32f0/stm32f0_lowputc.c index b62d6ecb4c..12e20197bc 100644 --- a/arch/arm/src/stm32f0/stm32f0_lowputc.c +++ b/arch/arm/src/stm32f0/stm32f0_lowputc.c @@ -299,7 +299,7 @@ void stm32f0_lowsetup(void) #ifdef CONFIG_STM32F0_USART2 /* Enable USART APB1 clock */ - modifyreg32(STM32F0_RCC_APB1ENR1, 0, RCC_APB1ENR1_USART2EN); + modifyreg32(STM32F0_RCC_APB1ENR, 0, RCC_APB1ENR_USART2EN); /* Configure RX/TX pins */ @@ -315,7 +315,7 @@ void stm32f0_lowsetup(void) #ifdef CONFIG_STM32F0_USART3 /* Enable USART APB1 clock */ - modifyreg32(STM32F0_RCC_APB1ENR1, 0, RCC_APB1ENR1_USART3EN); + modifyreg32(STM32F0_RCC_APB1ENR, 0, RCC_APB1ENR_USART3EN); /* Configure RX/TX pins */ @@ -331,7 +331,7 @@ void stm32f0_lowsetup(void) #ifdef CONFIG_STM32F0_USART4 /* Enable USART APB1 clock */ - modifyreg32(STM32F0_RCC_APB1ENR1, 0, RCC_APB1ENR1_USART4EN); + modifyreg32(STM32F0_RCC_APB1ENR, 0, RCC_APB1ENR_USART4EN); /* Configure RX/TX pins */ @@ -347,7 +347,7 @@ void stm32f0_lowsetup(void) #ifdef CONFIG_STM32F0_USART5 /* Enable USART APB1 clock */ - modifyreg32(STM32F0_RCC_APB1ENR1, 0, RCC_APB1ENR1_USART5EN); + modifyreg32(STM32F0_RCC_APB1ENR, 0, RCC_APB1ENR_USART5EN); /* Configure RX/TX pins */ diff --git a/arch/arm/src/stm32f0/stm32f0_serial.c b/arch/arm/src/stm32f0/stm32f0_serial.c index 673387d7ba..632ccab4d6 100644 --- a/arch/arm/src/stm32f0/stm32f0_serial.c +++ b/arch/arm/src/stm32f0/stm32f0_serial.c @@ -1035,26 +1035,26 @@ static void stm32f0serial_setapbclock(FAR struct uart_dev_s *dev, bool on) #endif #ifdef CONFIG_STM32F0_USART2 case STM32F0_USART2_BASE: - rcc_en = RCC_APB1ENR1_USART2EN; - regaddr = STM32F0_RCC_APB1ENR1; + rcc_en = RCC_APB1ENR_USART2EN; + regaddr =STM32F0_RCC_APB1ENR; break; #endif #ifdef CONFIG_STM32F0_USART3 case STM32F0_USART3_BASE: - rcc_en = RCC_APB1ENR1_USART3EN; - regaddr = STM32F0_RCC_APB1ENR1; + rcc_en = RCC_APB1ENR_USART3EN; + regaddr =STM32F0_RCC_APB1ENR; break; #endif #ifdef CONFIG_STM32F0_USART4 case STM32F0_USART4_BASE: - rcc_en = RCC_APB1ENR1_USART4EN; - regaddr = STM32F0_RCC_APB1ENR1; + rcc_en = RCC_APB1ENR_USART4EN; + regaddr =STM32F0_RCC_APB1ENR; break; #endif #ifdef CONFIG_STM32F0_USART5 case STM32F0_USART5_BASE: - rcc_en = RCC_APB1ENR1_USART5EN; - regaddr = STM32F0_RCC_APB1ENR1; + rcc_en = RCC_APB1ENR_USART5EN; + regaddr =STM32F0_RCC_APB1ENR; break; #endif } diff --git a/configs/nucleo-f072rb/src/stm32_autoleds.c b/configs/nucleo-f072rb/src/stm32_autoleds.c index d03a41cfad..ee3779dec5 100644 --- a/configs/nucleo-f072rb/src/stm32_autoleds.c +++ b/configs/nucleo-f072rb/src/stm32_autoleds.c @@ -49,7 +49,7 @@ #include "chip.h" #include "up_arch.h" #include "up_internal.h" -#include "stm32.h" +#include "stm32f0_gpio.h" #include "nucleo-f072rb.h" #ifdef CONFIG_ARCH_LEDS @@ -66,7 +66,7 @@ void board_autoled_initialize(void) { /* Configure LD2 GPIO for output */ - stm32_configgpio(GPIO_LD2); + stm32f0_configgpio(GPIO_LD2); } /**************************************************************************** @@ -77,7 +77,7 @@ void board_autoled_on(int led) { if (led == 1) { - stm32_gpiowrite(GPIO_LD2, true); + stm32f0_gpiowrite(GPIO_LD2, true); } } @@ -89,7 +89,7 @@ void board_autoled_off(int led) { if (led == 1) { - stm32_gpiowrite(GPIO_LD2, false); + stm32f0_gpiowrite(GPIO_LD2, false); } } diff --git a/configs/nucleo-f072rb/src/stm32_userleds.c b/configs/nucleo-f072rb/src/stm32_userleds.c index 08ccef5b8f..0b967fc662 100644 --- a/configs/nucleo-f072rb/src/stm32_userleds.c +++ b/configs/nucleo-f072rb/src/stm32_userleds.c @@ -49,7 +49,7 @@ #include "chip.h" #include "up_arch.h" #include "up_internal.h" -#include "stm32.h" +#include "stm32f0_gpio.h" #include "nucleo-f072rb.h" #ifndef CONFIG_ARCH_LEDS @@ -172,7 +172,7 @@ void board_userled_initialize(void) { /* Configure LD2 GPIO for output */ - stm32_configgpio(GPIO_LD2); + stm32f0_configgpio(GPIO_LD2); } /**************************************************************************** @@ -183,7 +183,7 @@ void board_userled(int led, bool ledon) { if (led == 1) { - stm32_gpiowrite(GPIO_LD2, ldeon); + stm32f0_gpiowrite(GPIO_LD2, ldeon); } } @@ -195,16 +195,16 @@ void board_userled_all(uint8_t ledset) { if (led == 1) { - stm32_gpiowrite(GPIO_LD2, (ledset & BOARD_LD2_BIT) != 0); + stm32f0_gpiowrite(GPIO_LD2, (ledset & BOARD_LD2_BIT) != 0); } } /**************************************************************************** - * Name: stm32_led_pminitialize + * Name: stm32f0_led_pminitialize ****************************************************************************/ #ifdef CONFIG_PM -void stm32_led_pminitialize(void) +void stm32f0_led_pminitialize(void) { /* Register to receive power management callbacks */ -- GitLab From 9ad3b375e59c673749d70dfc7cecc59802c9e4c7 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Tue, 18 Apr 2017 15:34:13 -0400 Subject: [PATCH 503/990] wireless/ieee802154: Lots of small fixes to eliminate build issues. Generally cleans things up and fixes lots of small issues preventing a successful build. Does not completely build, but there are significantly less errors --- drivers/wireless/ieee802154/mrf24j40.c | 345 +++++++++++++----- .../wireless/ieee802154/ieee802154_mac.h | 27 +- .../wireless/ieee802154/ieee802154_radio.h | 12 +- wireless/ieee802154/mac802154.c | 129 ++++--- wireless/ieee802154/mac802154_device.c | 138 ++++--- 5 files changed, 418 insertions(+), 233 deletions(-) diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c index 2cb3300e5a..655871eb94 100644 --- a/drivers/wireless/ieee802154/mrf24j40.c +++ b/drivers/wireless/ieee802154/mrf24j40.c @@ -94,10 +94,19 @@ #define MRF24J40_PA_ED 2 #define MRF24J40_PA_SLEEP 3 +#define MRF24J40_GTS_SLOTS 2 + /**************************************************************************** * Private Types ****************************************************************************/ +struct mrf24j40_txdesc_s +{ + struct ieee802154_txdesc_s pub; + + uint8_t busy : 1; /* Is this txdesc being used */ +}; + /* A MRF24J40 device instance */ struct mrf24j40_radio_s @@ -106,36 +115,33 @@ struct mrf24j40_radio_s /* Reference to the bound upper layer via the phyif interface */ - FAR const struct ieee802154_phyif_s *phyif; + FAR struct ieee802154_phyif_s *phyif; - FAR struct spi_dev_s *spi; /* Saved SPI interface instance */ - struct work_s irqwork; /* Interrupt continuation work queue support */ - FAR const struct mrf24j40_lower_s *lower; /* Low-level MCU-specific support */ - sem_t excl_sem; /* Exclusive access to this struct */ + /* Low-level MCU-specific support */ - uint16_t panid; /* PAN identifier, FFFF = not set */ - uint16_t saddr; /* short address, FFFF = not set */ - uint8_t eaddr[8]; /* extended address, FFFFFFFFFFFFFFFF = not set */ - uint8_t channel; /* 11 to 26 for the 2.4 GHz band */ - uint8_t devmode; /* device mode: device, coord, pancoord */ - uint8_t paenabled; /* enable usage of PA */ - uint8_t rxmode; /* Reception mode: Main, no CRC, promiscuous */ - int32_t txpower; /* TX power in mBm = dBm/100 */ - struct ieee802154_cca_s cca; /* Clear channel assessement method */ + FAR const struct mrf24j40_lower_s *lower; + FAR struct spi_dev_s *spi; /* Saved SPI interface instance */ - /* Buffer Allocations */ + struct work_s irqwork; /* For deferring interrupt work to work queue */ + struct work_s pollwork; /* For deferring poll work to the work queue */ + sem_t exclsem; /* Exclusive access to this struct */ - struct mrf24j40_txdesc_s csma_desc; - struct mrf24j40_txdesc_s gts_desc[2]; + uint16_t panid; /* PAN identifier, FFFF = not set */ + uint16_t saddr; /* short address, FFFF = not set */ + uint8_t eaddr[8]; /* extended address, FFFFFFFFFFFFFFFF = not set */ + uint8_t channel; /* 11 to 26 for the 2.4 GHz band */ + uint8_t devmode; /* device mode: device, coord, pancoord */ + uint8_t paenabled; /* enable usage of PA */ + uint8_t rxmode; /* Reception mode: Main, no CRC, promiscuous */ + int32_t txpower; /* TX power in mBm = dBm/100 */ + struct ieee802154_cca_s cca; /* Clear channel assessement method */ - uint8_t tx_buf[CONFIG_IEEE802154_MTU]; -}; + /* Buffer Allocations */ -struct mrf24j40_txdesc_s -{ - struct ieee802154_txdesc_s ieee_desc; + struct mrf24j40_txdesc_s csma_desc; + struct mrf24j40_txdesc_s gts_desc[MRF24J40_GTS_SLOTS]; - uint8_t busy : 1; /* Is this txdesc being used */ + uint8_t tx_buf[IEEE802154_MAX_PHY_PACKET_SIZE]; }; /**************************************************************************** @@ -161,41 +167,49 @@ static void mrf24j40_irqwork_tx(FAR struct mrf24j40_radio_s *dev); static void mrf24j40_irqworker(FAR void *arg); static int mrf24j40_interrupt(int irq, FAR void *context, FAR void *arg); +static void mrf24j40_dopoll_csma(FAR void *arg); +static void mrf24j40_dopoll_gts(FAR void *arg); + +static int mrf24j40_csma_setup(FAR struct mrf24j40_radio_s *dev, + uint8_t *buf, uint16_t buf_len); +static int mrf24j40_gts_setup(FAR struct mrf24j40_radio_s *dev, uint8_t gts, + uint8_t *buf, uint16_t buf_len); + /* IOCTL helpers */ -static int mrf24j40_setchannel(FAR struct ieee802154_radio_s *radio, +static int mrf24j40_setchannel(FAR struct mrf24j40_radio_s *radio, uint8_t chan); -static int mrf24j40_getchannel(FAR struct ieee802154_radio_s *radio, +static int mrf24j40_getchannel(FAR struct mrf24j40_radio_s *radio, FAR uint8_t *chan); -static int mrf24j40_setpanid(FAR struct ieee802154_radio_s *radio, +static int mrf24j40_setpanid(FAR struct mrf24j40_radio_s *radio, uint16_t panid); -static int mrf24j40_getpanid(FAR struct ieee802154_radio_s *radio, +static int mrf24j40_getpanid(FAR struct mrf24j40_radio_s *radio, FAR uint16_t *panid); -static int mrf24j40_setsaddr(FAR struct ieee802154_radio_s *radio, +static int mrf24j40_setsaddr(FAR struct mrf24j40_radio_s *radio, uint16_t saddr); -static int mrf24j40_getsaddr(FAR struct ieee802154_radio_s *radio, +static int mrf24j40_getsaddr(FAR struct mrf24j40_radio_s *radio, FAR uint16_t *saddr); -static int mrf24j40_seteaddr(FAR struct ieee802154_radio_s *radio, +static int mrf24j40_seteaddr(FAR struct mrf24j40_radio_s *radio, FAR uint8_t *eaddr); -static int mrf24j40_geteaddr(FAR struct ieee802154_radio_s *radio, +static int mrf24j40_geteaddr(FAR struct mrf24j40_radio_s *radio, FAR uint8_t *eaddr); -static int mrf24j40_setpromisc(FAR struct ieee802154_radio_s *radio, +static int mrf24j40_setpromisc(FAR struct mrf24j40_radio_s *radio, bool promisc); -static int mrf24j40_getpromisc(FAR struct ieee802154_radio_s *radio, +static int mrf24j40_getpromisc(FAR struct mrf24j40_radio_s *radio, FAR bool *promisc); -static int mrf24j40_setdevmode(FAR struct ieee802154_radio_s *radio, +static int mrf24j40_setdevmode(FAR struct mrf24j40_radio_s *radio, uint8_t mode); -static int mrf24j40_getdevmode(FAR struct ieee802154_radio_s *radio, +static int mrf24j40_getdevmode(FAR struct mrf24j40_radio_s *radio, FAR uint8_t *mode); -static int mrf24j40_settxpower(FAR struct ieee802154_radio_s *radio, +static int mrf24j40_settxpower(FAR struct mrf24j40_radio_s *radio, int32_t txpwr); -static int mrf24j40_gettxpower(FAR struct ieee802154_radio_s *radio, +static int mrf24j40_gettxpower(FAR struct mrf24j40_radio_s *radio, FAR int32_t *txpwr); -static int mrf24j40_setcca(FAR struct ieee802154_radio_s *radio, +static int mrf24j40_setcca(FAR struct mrf24j40_radio_s *radio, FAR struct ieee802154_cca_s *cca); -static int mrf24j40_getcca(FAR struct ieee802154_radio_s *radio, +static int mrf24j40_getcca(FAR struct mrf24j40_radio_s *radio, FAR struct ieee802154_cca_s *cca); -static int mrf24j40_energydetect(FAR struct ieee802154_radio_s *radio, +static int mrf24j40_energydetect(FAR struct mrf24j40_radio_s *radio, FAR uint8_t *energy); /* Driver operations */ @@ -207,7 +221,9 @@ static int mrf24j40_ioctl(FAR struct ieee802154_radio_s *radio, int cmd, static int mrf24j40_rxenable(FAR struct ieee802154_radio_s *radio, bool state, FAR struct ieee802154_packet_s *packet); static int mrf24j40_transmit(FAR struct ieee802154_radio_s *radio, - FAR struct ieee802154_packet_s *packet); + uint8_t *buf, uint16_t buf_len); +static int mrf24j40_txnotify_csma(FAR struct ieee802154_radio_s *radio); +static int mrf24j40_txnotify_gts(FAR struct ieee802154_radio_s *radio); /**************************************************************************** * Private Data @@ -233,8 +249,8 @@ static const struct ieee802154_radioops_s mrf24j40_devops = * Private Functions ****************************************************************************/ -static void mrf24j40_bind(FAR struct ieee802154_radio_s *radio, - FAR struct ieee802154_phyif_s *phyif) +static int mrf24j40_bind(FAR struct ieee802154_radio_s *radio, + FAR struct ieee802154_phyif_s *phyif) { FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)radio; @@ -243,6 +259,43 @@ static void mrf24j40_bind(FAR struct ieee802154_radio_s *radio, return OK; } +/**************************************************************************** + * Function: mrf24j40_txnotify_csma + * + * Description: + * Driver callback invoked when new TX data is available. This is a + * stimulus perform an out-of-cycle poll and, thereby, reduce the TX + * latency. + * + * Parameters: + * radio - Reference to the radio driver state structure + * + * Returned Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +static int mrf24j40_txnotify_csma(FAR struct ieee802154_radio_s *radio) +{ + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)radio; + + /* Is our single work structure available? It may not be if there are + * pending interrupt actions and we will have to ignore the Tx + * availability action. + */ + + if (work_available(&dev->pollwork)) + { + /* Schedule to serialize the poll on the worker thread. */ + + work_queue(HPWORK, &dev->pollwork, mrf24j40_dopoll_csma, dev, 0); + } + + return OK; +} + /**************************************************************************** * Function: mrf24j40_dopoll_csma * @@ -250,8 +303,10 @@ static void mrf24j40_bind(FAR struct ieee802154_radio_s *radio, * This function is called in order to preform an out-of-sequence TX poll. * This is done: * - * 1. After completion of a CSMA transmission - * 2. When the upper layer calls txnotify_csma + * 1. After completion of a transmission (mrf24j40_txdone_csma), + * 2. When new TX data is available (mrf24j40_txnotify_csma), and + * 3. After a TX timeout to restart the sending process + * (mrf24j40_txtimeout_csma). * * Parameters: * radio - Reference to the radio driver state structure @@ -263,40 +318,41 @@ static void mrf24j40_bind(FAR struct ieee802154_radio_s *radio, * ****************************************************************************/ -static void mrf24j40_dopoll_csma(FAR struct ieee802154_radio_s *radio) +static void mrf24j40_dopoll_csma(FAR void *arg) { - FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)radio; + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)arg; + int ret = 0; /* Need to get exlusive access to the device so that we can use the copy * buffer. */ - while (sem_wait(&dev->exclsem) < 0) { } + while (sem_wait(&dev->exclsem) != 0) { } /* If this a CSMA transaction and we have room in the CSMA fifo */ - if (!dev->csma_txdesc.busy) + if (!dev->csma_desc.busy) { /* need to somehow allow for a handle to be passed */ - ret = dev->phyif->poll_csma(dev->phyif, &radio->csma_txdesc, - &dev->tx_buf[0]); + ret = dev->phyif->ops->poll_csma(dev->phyif, + &dev->csma_desc.pub, + &dev->tx_buf[0]); if (ret > 0) { /* Now the txdesc is in use */ - dev->cmsa_desc.busy = 1; + dev->csma_desc.busy = 1; /* Setup the transaction on the device in the CSMA FIFO */ - mrf24j40_csma_setup(radio, &dev->tx_buf[0], - dev->gts_desc[i].psdu_length); + mrf24j40_csma_setup(dev, &dev->tx_buf[0], + dev->csma_desc.pub.psdu_length); } /* Setup the transmit on the device */ - break; } sem_post(&dev->exclsem); @@ -306,44 +362,95 @@ static void mrf24j40_dopoll_csma(FAR struct ieee802154_radio_s *radio) * Function: mrf24j40_txnotify_gts * * Description: - * Called from the upper layer, this function is to notify the device that - * the upper layer has a pending transaction for one of it's GTS'. This - * function checks to see if there is availability for the corresponding - * transaction type. If there is, the function will call to the MAC layer - * to get the transaction and then start the transmission + * Driver callback invoked when new TX data is available. This is a + * stimulus perform an out-of-cycle poll and, thereby, reduce the TX + * latency. + * + * Parameters: + * radio - Reference to the radio driver state structure + * + * Returned Value: + * None + * + * Assumptions: * ****************************************************************************/ -static void mrf24j40_txnotify_gts(FAR struct ieee802154_radio_s *radio) +static int mrf24j40_txnotify_gts(FAR struct ieee802154_radio_s *radio) { FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)radio; + /* Is our single work structure available? It may not be if there are + * pending interrupt actions and we will have to ignore the Tx + * availability action. + */ + + if (work_available(&dev->pollwork)) + { + /* Schedule to serialize the poll on the worker thread. */ + + work_queue(HPWORK, &dev->pollwork, mrf24j40_dopoll_gts, dev, 0); + } + + return OK; +} + +/**************************************************************************** + * Function: mrf24j40_dopoll_gts + * + * Description: + * This function is called in order to preform an out-of-sequence TX poll. + * This is done: + * + * 1. After completion of a transmission (mrf24j40_txdone_gts), + * 2. When new TX data is available (mrf24j40_txnotify_gts), and + * 3. After a TX timeout to restart the sending process + * (mrf24j40_txtimeout_gts). + * + * Parameters: + * arg - Reference to the radio driver state structure + * + * Returned Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +static void mrf24j40_dopoll_gts(FAR void *arg) +{ + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)arg; + int gts = 0; + int ret = 0; + /* Need to get exclusive access to the device so that we can use the copy * buffer. */ - while (sem_wait(dev->exclsem) < 0) { } + while (sem_wait(&dev->exclsem) != 0) { } - for (gts = 0; gts < MRF24J40_GTS_SLOTS, gts++) + for (gts = 0; gts < MRF24J40_GTS_SLOTS; gts++) { - if (!dev->gts_txdesc[i].busy) + if (!dev->gts_desc[gts].busy) { - ret = dev->phyif->poll_gts(dev->phyif, &radio->gts_txdesc[i], - &dev->tx_buf[0]); + ret = dev->phyif->ops->poll_gts(dev->phyif, &dev->gts_desc[gts].pub, + &dev->tx_buf[0]); if (ret > 0) { /* Now the txdesc is in use */ - dev->gts_txdesc[i].busy = 1; + dev->gts_desc[gts].busy = 1; /* Setup the transaction on the device in the open GTS FIFO */ - mrf24j40_gts_setup(radio, i, &dev->tx_buf[0], - dev->gts_desc[i].psdu_length); + mrf24j40_gts_setup(dev, gts, &dev->tx_buf[0], + dev->gts_desc[gts].pub.psdu_length); } } } + + sem_post(&dev->exclsem); } /**************************************************************************** @@ -409,11 +516,11 @@ static void mrf24j40_setreg(FAR struct spi_dev_s *spi, uint32_t addr, buf[len++] = val; - mrf24j40_lock(spi); + mrf24j40_spi_lock(spi); SPI_SELECT(spi, SPIDEV_IEEE802154, true); SPI_SNDBLOCK(spi, buf, len); SPI_SELECT(spi, SPIDEV_IEEE802154, false); - mrf24j40_unlock(spi); + mrf24j40_spi_unlock(spi); } /**************************************************************************** @@ -453,11 +560,11 @@ static uint8_t mrf24j40_getreg(FAR struct spi_dev_s *spi, uint32_t addr) buf[len++] = 0xFF; /* dummy */ - mrf24j40_lock (spi); + mrf24j40_spi_lock (spi); SPI_SELECT (spi, SPIDEV_IEEE802154, true); SPI_EXCHANGE (spi, buf, rx, len); SPI_SELECT (spi, SPIDEV_IEEE802154, false); - mrf24j40_unlock(spi); + mrf24j40_spi_unlock(spi); /* wlinfo("r[%04X]=%02X\n", addr, rx[len - 1]); */ return rx[len - 1]; @@ -644,10 +751,18 @@ static int mrf24j40_setchannel(FAR struct mrf24j40_radio_s *dev, uint8_t chan) return OK; } +/**************************************************************************** + * Name: mrf24j40_getchannel + * + * Description: + * Get the channel the device is operating on. + * + ****************************************************************************/ + static int mrf24j40_getchannel(FAR struct mrf24j40_radio_s *dev, FAR uint8_t *chan) { - chan = dev->channel; + *chan = dev->channel; return OK; } @@ -955,7 +1070,7 @@ static int mrf24j40_settxpower(FAR struct mrf24j40_radio_s *dev, * ****************************************************************************/ -static int mrf24j40_gettxpower(FAR struct mrf24j40_radio_s *radio, +static int mrf24j40_gettxpower(FAR struct mrf24j40_radio_s *dev, FAR int32_t *txpwr) { *txpwr = dev->txpower; @@ -1085,78 +1200,78 @@ static int mrf24j40_ioctl(FAR struct ieee802154_radio_s *radio, int cmd, unsigned long arg) { FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)radio; - - FAR union ieee802154_radioarg_u *u; = - (FAR union ieee802154_radioarg_u *)((uintptr_t)arg) + FAR union ieee802154_radioarg_u *u = + (FAR union ieee802154_radioarg_u *)((uintptr_t)arg); + int ret; switch(cmd) { case PHY802154IOC_SET_CHAN: - ret = mrf24j40_setchannel(dev, u.channel); + ret = mrf24j40_setchannel(dev, u->channel); break; case PHY802154IOC_GET_CHAN: - ret = mrf24j40_getchannel(dev, &u.channel); + ret = mrf24j40_getchannel(dev, &u->channel); break; case PHY802154IOC_SET_PANID: - ret = mrf24j40_setpanid(dev, u.panid); + ret = mrf24j40_setpanid(dev, u->panid); break; case PHY802154IOC_GET_PANID: - ret = mrf24j40_getpanid(dev, &u.panid); + ret = mrf24j40_getpanid(dev, &u->panid); break; case PHY802154IOC_SET_SADDR: - ret = mrf24j40_setsaddr(dev, u.saddr); + ret = mrf24j40_setsaddr(dev, u->saddr); break; case PHY802154IOC_GET_SADDR: - ret = mrf24j40_getsaddr(dev, &u.saddr); + ret = mrf24j40_getsaddr(dev, &u->saddr); break; case PHY802154IOC_SET_EADDR: - ret = mrf24j40_seteaddr(dev, u.eaddr); + ret = mrf24j40_seteaddr(dev, u->eaddr); break; case PHY802154IOC_GET_EADDR: - ret = mrf24j40_geteaddr(dev, u.eaddr); + ret = mrf24j40_geteaddr(dev, u->eaddr); break; case PHY802154IOC_SET_PROMISC: - ret = mrf24j40_setpromisc(dev, u.promisc); + ret = mrf24j40_setpromisc(dev, u->promisc); break; case PHY802154IOC_GET_PROMISC: - ret = mrf24j40_getpromisc(dev, &u.promisc); + ret = mrf24j40_getpromisc(dev, &u->promisc); break; case PHY802154IOC_SET_DEVMODE: - ret = mrf24j40_setdevmode(dev, u.devmode); + ret = mrf24j40_setdevmode(dev, u->devmode); break; case PHY802154IOC_GET_DEVMODE: - ret = mrf24j40_getdevmode(dev, &u.devmode); + ret = mrf24j40_getdevmode(dev, &u->devmode); break; case PHY802154IOC_SET_TXPWR: - ret = mrf24j40_settxpower(dev, u.txpwr); + ret = mrf24j40_settxpower(dev, u->txpwr); break; case PHY802154IOC_GET_TXPWR: - ret = mrf24j40_gettxpower(dev, &u.txpwr); + ret = mrf24j40_gettxpower(dev, &u->txpwr); break; case PHY802154IOC_SET_CCA: - ret = mrf24j40_setcca(dev, &u.cca); + ret = mrf24j40_setcca(dev, &u->cca); break; case PHY802154IOC_GET_CCA: - ret = mrf24j40_getcca(dev, &u.cca); + ret = mrf24j40_getcca(dev, &u->cca); break; case PHY802154IOC_ENERGYDETECT: - ret = mrf24j40_energydetect(dev, &u.energy); + ret = mrf24j40_energydetect(dev, &u->energy); break; case 1000: @@ -1169,6 +1284,8 @@ static int mrf24j40_ioctl(FAR struct ieee802154_radio_s *radio, int cmd, default: return -ENOTTY; } + + return ret; } /**************************************************************************** @@ -1282,13 +1399,13 @@ static int mrf24j40_transmit(FAR struct ieee802154_radio_s *radio, /* Frame length */ - mrf24j40_setreg(dev->spi, addr++, buflen); + mrf24j40_setreg(dev->spi, addr++, buf_len); /* Frame data */ - for (ret = 0; ret < buflen; ret++) /* this sets the correct val for ret */ + for (ret = 0; ret < buf_len; ret++) /* this sets the correct val for ret */ { - mrf24j40_setreg(dev->spi, addr++, packet->data[ret]); + mrf24j40_setreg(dev->spi, addr++, buf[ret]); } /* If the frame control field contains @@ -1309,6 +1426,34 @@ static int mrf24j40_transmit(FAR struct ieee802154_radio_s *radio, return ret; } +/**************************************************************************** + * Name: mrf24j40_csma_setup + * + * Description: + * Setup a CSMA transaction in the normal TX FIFO + * + ****************************************************************************/ + +static int mrf24j40_csma_setup(FAR struct mrf24j40_radio_s *dev, + uint8_t *buf, uint16_t buf_len) +{ + return -ENOTTY; +} + +/**************************************************************************** + * Name: mrf24j40_gts_setup + * + * Description: + * Setup a GTS transaction in one of the GTS FIFOs + * + ****************************************************************************/ + +static int mrf24j40_gts_setup(FAR struct mrf24j40_radio_s *dev, uint8_t fifo, + uint8_t *buf, uint16_t buf_len) +{ + return -ENOTTY; +} + /**************************************************************************** * Name: mrf24j40_irqwork_tx * @@ -1328,9 +1473,11 @@ static void mrf24j40_irqwork_tx(FAR struct mrf24j40_radio_s *dev) /* 1 means it failed, we want 1 to mean it worked. */ + /* dev->radio.txok = (reg & MRF24J40_TXSTAT_TXNSTAT) != MRF24J40_TXSTAT_TXNSTAT; dev->radio.txretries = (reg & MRF24J40_TXSTAT_X_MASK) >> MRF24J40_TXSTAT_X_SHIFT; dev->radio.txbusy = (reg & MRF24J40_TXSTAT_CCAFAIL) == MRF24J40_TXSTAT_CCAFAIL; + */ //wlinfo("TXSTAT%02X!\n", txstat); #warning TODO report errors @@ -1344,7 +1491,7 @@ static void mrf24j40_irqwork_tx(FAR struct mrf24j40_radio_s *dev) /* Wake up the thread that triggered the transmission */ - sem_post(&dev->radio.txsem); + /* sem_post(&dev->radio.txsem); */ } diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index 76880ebf29..800436de78 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -85,7 +85,7 @@ #define MAC802154IOC_MCPS_REGISTER _MAC802154IOC(0x0001) -#define MAC802154IOC_MLME_REGISER _MAC802154IOC(0x0002); +#define MAC802154IOC_MLME_REGISTER _MAC802154IOC(0x0002) #define MAC802154IOC_MLME_ASSOC_REQUEST _MAC802154IOC(0x0003) #define MAC802154IOC_MLME_ASSOC_RESPONSE _MAC802154IOC(0x0004) #define MAC802154IOC_MLME_DISASSOC_REQUEST _MAC802154IOC(0x0005) @@ -103,8 +103,6 @@ #define MAC802154IOC_MLME_SOUNDING_REQUEST _MAC802154IOC(0x0011) #define MAC802154IOC_MLME_CALIBRATE_REQUEST _MAC802154IOC(0x0012) - - /* IEEE 802.15.4 MAC Interface **********************************************/ /* Frame Type */ @@ -351,12 +349,9 @@ struct ieee802154_addr_s enum ieee802154_addr_mode_e mode; - uint16_t panid; /* PAN identifier, can be IEEE802154_PAN_UNSPEC */ - union - { - uint16_t saddr; /* short address */ - uint8_t eaddr[8]; /* extended address */ - } u; + uint16_t panid; /* PAN identifier, can be IEEE802154_PAN_UNSPEC */ + uint16_t saddr; /* short address */ + uint8_t eaddr[8]; /* extended address */ }; #define IEEE802154_ADDRSTRLEN 22 /* (2*2+1+8*2, PPPP/EEEEEEEEEEEEEEEE) */ @@ -397,19 +392,6 @@ enum ieee802154_ranging_e IEEE802154_PHY_HEADER_ONLY }; -struct ieee802154_frame_s -{ - struct ieee802154_framecontrol_s frame_control; - uint8_t seq_num; - struct ieee802154_addr_s dest_addr; - struct ieee802154_addr_s src_addr; -#ifdef CONFIG_IEEE802154_SECURITY - struct ieee802154_auxsec_s aux_sec_hdr; -#endif - void *payload; - uint16_t fcs; -}; - struct ieee802154_data_req_s { enum ieee802154_addr_mode_e src_addr_mode; /* Source Address Mode */ @@ -464,7 +446,6 @@ struct ieee802154_data_req_s uint8_t msdu[1]; }; - #define SIZEOF_IEEE802154_DATA_REQ_S(n) \ (sizeof(struct ieee802154_data_req_s) + (n) - 1) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_radio.h b/include/nuttx/wireless/ieee802154/ieee802154_radio.h index d48b0d4e12..638760f356 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_radio.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_radio.h @@ -190,14 +190,14 @@ struct ieee802154_radio_s; /* Forward reference */ struct ieee802154_radioops_s { - CODE int (*bind) (FAR struct ieee802154_radio_s *dev, - FAR const struct ieee802154_phyif_s *phyif); - CODE int (*ioctl)(FAR struct ieee802154_radio_s *ieee, int cmd, + CODE int (*bind) (FAR struct ieee802154_radio_s *radio, + FAR struct ieee802154_phyif_s *phyif); + CODE int (*ioctl)(FAR struct ieee802154_radio_s *radio, int cmd, unsigned long arg); - CODE int (*rxenable)(FAR struct ieee802154_radio_s *dev, bool state, + CODE int (*rxenable)(FAR struct ieee802154_radio_s *radio, bool state, FAR struct ieee802154_packet_s *packet); - CODE int (*txnotify_csma)(FAR struct ieee802154_radio_s *dev); - CODE int (*txnotify_gts)(FAR struct ieee802154_radio_s *dev); + CODE int (*txnotify_csma)(FAR struct ieee802154_radio_s *radio); + CODE int (*txnotify_gts)(FAR struct ieee802154_radio_s *radio); }; struct ieee802154_radio_s diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index ee057dcec1..671e67b6e2 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -43,6 +43,7 @@ #include #include #include +#include #include #include @@ -96,7 +97,7 @@ struct ieee802154_privmac_s FAR const struct ieee802154_maccb_s *cb; /* Contained MAC callbacks */ FAR struct ieee802154_phyif_s phyif; /* Interface to bind to radio */ - sem_t excl_sem; /* Support exclusive access */ + sem_t exclsem; /* Support exclusive access */ /* Support a singly linked list of transactions that will be sent using the * CSMA algorithm. On a non-beacon enabled PAN, these transactions will be @@ -207,14 +208,14 @@ struct ieee802154_privmac_s */ uint32_t sync_symb_offset : 12; - } + }; struct { uint32_t beacon_tx_time : 24; /* Time of last beacon transmit */ uint32_t min_be : 4; /* Min value of backoff exponent (BE) */ uint32_t max_be : 4; /* Max value of backoff exponent (BE) */ - } + }; struct { @@ -223,11 +224,33 @@ struct ieee802154_privmac_s uint32_t tx_ctrl_pause_dur : 1; /* Duration after tx before another tx is * permitted. 0=2000, 1= 10000 */ uint32_t timestamp_support : 1; /* Does MAC layer supports timestamping */ - } + uint32_t is_coord : 1; /* Is this device acting as coordinator */ + }; /* TODO: Add Security-related MAC PIB attributes */ }; +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static inline int mac802154_takesem(sem_t *sem); +#define mac802154_givesem(s) sem_post(s); + +/* Internal Functions */ + +static int mac802154_defaultmib(FAR struct ieee802154_privmac_s *priv); +static int mac802154_applymib(FAR struct ieee802154_privmac_s *priv); + +/* IEEE 802.15.4 PHY Interface OPs */ + +static int mac802154_poll_csma(FAR struct ieee802154_phyif_s *phyif, + FAR struct ieee802154_txdesc_s *tx_desc, + uint8_t *buf); + +static int mac802154_poll_gts(FAR struct ieee802154_phyif_s *phyif, + FAR struct ieee802154_txdesc_s *tx_desc, + uint8_t *buf); /**************************************************************************** * Private Data @@ -350,7 +373,7 @@ MACHANDLE mac802154_create(FAR struct ieee802154_radio_s *radiodev) /* Bind our PHY interface to the radio */ - radiodev->ops->bind(radiodev, mac->phyif); + radiodev->ops->bind(radiodev, &mac->phyif); return (MACHANDLE)mac; } @@ -444,7 +467,7 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; - FAR struct mac802154_trans_s *trans; + FAR struct mac802154_trans_s trans; struct mac802154_unsec_mhr_s mhr; int ret; @@ -462,11 +485,12 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) /* Ensure we start with a clear frame control field */ - mhr.frame_control = 0; + mhr.u.frame_control = 0; /* Set the frame type to Data */ - mhr.frame_control |= IEEE802154_FRAME_DATA << IEEE802154_FRAMECTRL_SHIFT_FTYPE; + mhr.u.frame_control |= IEEE802154_FRAME_DATA << + IEEE802154_FRAMECTRL_SHIFT_FTYPE; /* If the msduLength is greater than aMaxMACSafePayloadSize, the MAC sublayer * will set the Frame Version to one. [1] pg. 118. @@ -474,7 +498,7 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) if (req->msdu_length > IEEE802154_MAX_SAFE_MAC_PAYLOAD_SIZE) { - mhr.frame_ctrl |= IEEE802154_FRAMECTRL_VERSION; + mhr.u.frame_control |= IEEE802154_FRAMECTRL_VERSION; } /* If the TXOptions parameter specifies that an acknowledged transmission is @@ -482,7 +506,8 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) * 5.1.6.4 [1] pg. 118. */ - mhr.frame_ctrl |= (req->msdu_flags.ack_tx << IEEE802154_FRAMECTRL_SHIFT_ACKREQ); + mhr.u.frame_control |= (req->msdu_flags.ack_tx << + IEEE802154_FRAMECTRL_SHIFT_ACKREQ); /* If the destination address is present, copy the PAN ID and one of the * addresses, depending on mode, into the MHR . @@ -490,28 +515,29 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) if (req->dest_addr.mode != IEEE802154_ADDRMODE_NONE) { - memcpy(&mhr.data[mhr.length], req->dest_addr.panid, 2); + memcpy(&mhr.u.data[mhr.length], &req->dest_addr.panid, 2); mhr.length += 2; if (req->dest_addr.mode == IEEE802154_ADDRMODE_SHORT) { - memcpy(&mhr.data[mhr.length], req->dest_addr.saddr, 2); + memcpy(&mhr.u.data[mhr.length], &req->dest_addr.saddr, 2); mhr.length += 2; } else if (req->dest_addr.mode == IEEE802154_ADDRMODE_EXTENDED) { - memcpy(&mhr.data[mhr.length], req->dest_addr.eaddr, 8); + memcpy(&mhr.u.data[mhr.length], &req->dest_addr.eaddr, 8); mhr.length += 8; } } /* Set the destination addr mode inside the frame contorl field */ - mhr.frame_ctrl |= (req->dest_addr.mode << IEEE802154_FRAMECTRL_SHIFT_DADDR); + mhr.u.frame_control |= (req->dest_addr.mode << + IEEE802154_FRAMECTRL_SHIFT_DADDR); /* From this point on, we need exclusive access to the privmac struct */ - ret = mac802154dev_takesem(&dev->md_exclsem); + ret = mac802154_takesem(&priv->exclsem); if (ret < 0) { wlerr("ERROR: mac802154_takesem failed: %d\n", ret); @@ -533,7 +559,7 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) if (req->dest_addr.panid == priv->addr.panid) { - mhr.frame_control |= IEEE802154_FRAMECTRL_PANIDCOMP; + mhr.u.frame_control |= IEEE802154_FRAMECTRL_PANIDCOMP; } } @@ -543,35 +569,36 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) * is off, we need to include the Source PAN ID. */ - if (req->dest_addr.mode == IEEE802154_ADDRMODE_NONE || - (mhr.frame_control & IEEE802154_FRAMECTRL_PANIDCOMP) + if ((req->dest_addr.mode == IEEE802154_ADDRMODE_NONE) || + (mhr.u.frame_control & IEEE802154_FRAMECTRL_PANIDCOMP)) { - memcpy(&mhr.data[mhr.length], priv->addr.panid, 2); + memcpy(&mhr.u.data[mhr.length], &priv->addr.panid, 2); mhr.length += 2; } if (req->src_addr_mode == IEEE802154_ADDRMODE_SHORT) { - memcpy(&mhr.data[mhr.length], priv->addr.saddr, 2); + memcpy(&mhr.u.data[mhr.length], &priv->addr.saddr, 2); mhr.length += 2; } else if (req->src_addr_mode == IEEE802154_ADDRMODE_EXTENDED) { - memcpy(&mhr.data[mhr.length], priv->addr.eaddr, 8); + memcpy(&mhr.u.data[mhr.length], &priv->addr.eaddr, 8); mhr.length += 8; } } /* Set the source addr mode inside the frame control field */ - mhr.frame_ctrl |= (req->src_addr_mode << IEEE802154_FRAMECTRL_SHIFT_SADDR); + mhr.u.frame_control |= (req->src_addr_mode << + IEEE802154_FRAMECTRL_SHIFT_SADDR); /* Each time a data or a MAC command frame is generated, the MAC sublayer * shall copy the value of macDSN into the Sequence Number field of the MHR * of the outgoing frame and then increment it by one. [1] pg. 40. */ - mhr.data[mhr.length++] = priv.dsn++; + mhr.u.data[mhr.length++] = priv->dsn++; /* Now that we know which fields are included in the header, we can make * sure we actually have enough room in the PSDU. @@ -583,13 +610,13 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) return -E2BIG; } - trans->mhr_buf = &mhr.data[0]; - trans->mhr_len = mhr.length; + trans.mhr_buf = &mhr.u.data[0]; + trans.mhr_len = mhr.length; - trans->d_buf = &req->msdu[0]; - trans->d_len = req->msdu_length; + trans.d_buf = &req->msdu[0]; + trans.d_len = req->msdu_length; - trans->msdu_handle = req->msdu_handle; + trans.msdu_handle = req->msdu_handle; /* If the TxOptions parameter specifies that a GTS transmission is required, * the MAC sublayer will determine whether it has a valid GTS as described @@ -635,14 +662,14 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) { /* Link the transaction into the indirect_trans list */ - priv->indirect_tail->flink = trans; - priv->indirect_tail = trans; + priv->indirect_tail->flink = &trans; + priv->indirect_tail = &trans; } else { /* Override the setting since it wasn't valid */ - req->msgu_flags.indirect_tx = 0; + req->msdu_flags.indirect_tx = 0; } } @@ -652,40 +679,50 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) { /* Link the transaction into the CSMA transaction list */ - priv->csma_tail->flink = trans; - priv->csma_tail = trans; + priv->csma_tail->flink = &trans; + priv->csma_tail = &trans; + + /* We no longer need to have the MAC layer locked. */ + + mac802154_givesem(&priv->exclsem); /* Notify the radio driver that there is data available */ - priv->radio->ops->tx_notify(priv->radio); + priv->radio->ops->txnotify_csma(priv->radio); - sem_wait(&trans->sem); + sem_wait(&trans.sem); } } return OK; } - /* Called from interrupt level or worker thread with interrupts disabled */ -static uint16_t mac802154_poll_csma(FAR struct ieee802154_phyif_s *phyif, +static int mac802154_poll_csma(FAR struct ieee802154_phyif_s *phyif, FAR struct ieee802154_txdesc_s *tx_desc, uint8_t *buf) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)&phyif->priv; - FAR struct mac802154_trans_s *trans; + int ret = 0; + + DEBUGASSERT(priv != 0); + + /* Get exclusive access to the driver structure. We don't care about any + * signals so if we see one, just go back to trying to get access again */ + + while (mac802154_takesem(&priv->exclsem) != 0); /* Check to see if there are any CSMA transactions waiting */ - if (mac->csma_head) + if (priv->csma_head) { /* Pop a CSMA transaction off the list */ - trans = mac->csma_head; - mac->csma_head = mac->csma_head.flink; + trans = priv->csma_head; + priv->csma_head = priv->csma_head->flink; /* Setup the transmit descriptor */ @@ -703,15 +740,17 @@ static uint16_t mac802154_poll_csma(FAR struct ieee802154_phyif_s *phyif, * returns. */ - sem_post(trans->sem); + sem_post(&trans->sem); - return txdesc->psdu_length; + ret = tx_desc->psdu_length; } - return 0; + mac802154_givesem(&priv->exclsem); + + return ret; } -static uint16_t mac802154_poll_gts(FAR struct ieee802154_phyif_s *phyif, +static int mac802154_poll_gts(FAR struct ieee802154_phyif_s *phyif, FAR struct ieee802154_txdesc_s *tx_desc, uint8_t *buf) { diff --git a/wireless/ieee802154/mac802154_device.c b/wireless/ieee802154/mac802154_device.c index b35049e9ac..8e9250a218 100644 --- a/wireless/ieee802154/mac802154_device.c +++ b/wireless/ieee802154/mac802154_device.c @@ -45,6 +45,7 @@ #include #include #include +#include #include #include @@ -66,31 +67,6 @@ * Private Types ****************************************************************************/ -struct mac802154_devwrapper_s -{ - MACHANDLE md_mac; /* Saved binding to the mac layer */ - sem_t md_exclsem; /* Exclusive device access */ - - /* The following is a singly linked list of open references to the - * MAC device. - */ - - FAR struct mac802154_open_s *md_open; - FAR struct mac802154dev_dwait_s *md_dwait; - -#ifndef CONFIG_DISABLE_SIGNALS - /* MCPS Service notification information */ - - struct mac802154dev_notify_s md_mcps_notify; - pid_t md_mcps_pid; - - /* MLME Service notification information */ - - struct mac802154dev_notify_s md_mlme_notify; - pid_t md_mlme_pid; -#endif -}; - struct mac802154dev_notify_s { uint8_t mn_signo; /* Signal number to use in the notification */ @@ -120,6 +96,31 @@ struct mac802154dev_dwait_s FAR struct mac802154dev_dwait_s *mw_flink; }; +struct mac802154_devwrapper_s +{ + MACHANDLE md_mac; /* Saved binding to the mac layer */ + sem_t md_exclsem; /* Exclusive device access */ + + /* The following is a singly linked list of open references to the + * MAC device. + */ + + FAR struct mac802154dev_open_s *md_open; + FAR struct mac802154dev_dwait_s *md_dwait; + +#ifndef CONFIG_DISABLE_SIGNALS + /* MCPS Service notification information */ + + struct mac802154dev_notify_s md_mcps_notify; + pid_t md_mcps_pid; + + /* MLME Service notification information */ + + struct mac802154dev_notify_s md_mlme_notify; + pid_t md_mlme_pid; +#endif +}; + /**************************************************************************** * Private Function Prototypes ****************************************************************************/ @@ -358,7 +359,8 @@ static ssize_t mac802154dev_read(FAR struct file *filep, FAR char *buffer, * packet. */ - if (len < sizeof(struct ieee802154_frame_s)) + if ((len >= SIZEOF_IEEE802154_DATA_REQ_S(1)) && + (len <= SIZEOF_IEEE802154_DATA_REQ_S(IEEE802154_MAX_MAC_PAYLOAD_SIZE))) { wlerr("ERROR: buffer too small: %lu\n", (unsigned long)len); return -EINVAL; @@ -394,7 +396,6 @@ static ssize_t mac802154dev_write(FAR struct file *filep, FAR struct inode *inode; FAR struct mac802154_devwrapper_s *dev; FAR struct ieee802154_data_req_s *req; - FAR struct ieee802154_frame_s *frame; struct mac802154dev_dwait_s dwait; int ret; @@ -404,64 +405,82 @@ static ssize_t mac802154dev_write(FAR struct file *filep, dev = (FAR struct mac802154_devwrapper_s *)inode->i_private; /* Check to make sure that the buffer is big enough to hold at least one - * packet. - */ + * packet. */ - if (len < sizeof(struct ieee802154_frame_s)) + if ((len >= SIZEOF_IEEE802154_DATA_REQ_S(1)) && + (len <= SIZEOF_IEEE802154_DATA_REQ_S(IEEE802154_MAX_MAC_PAYLOAD_SIZE))) { - wlerr("ERROR: buffer too small: %lu\n", (unsigned long)len); + wlerr("ERROR: buffer isn't an ieee802154_data_req_s: %lu\n", + (unsigned long)len); + return -EINVAL; } DEBUGASSERT(buffer != NULL); - frame = (FAR struct ieee802154_frame_s *)buffer; + req = (FAR struct ieee802154_data_req_s *)buffer; - /* Get exclusive access to the driver structure */ + /* If this is a blocking operation, we need to setup a wait struct so we + * can unblock when the packet transmission has finished. If this is a + * non-blocking write, we pass off the data and then move along. Technically + * we stil have to wait for the transaction to get put into the buffer, but we + * won't wait for the transaction to actually finish. */ - ret = mac802154dev_takesem(&dev->md_exclsem); - if (ret < 0) + if (!(filep->f_oflags & O_NONBLOCK)) { - wlerr("ERROR: mac802154dev_takesem failed: %d\n", ret); - return ret; - } + /* Get exclusive access to the driver structure */ + + ret = mac802154dev_takesem(&dev->md_exclsem); + if (ret < 0) + { + wlerr("ERROR: mac802154dev_takesem failed: %d\n", ret); + return ret; + } + + /* Setup the wait struct */ - /* Setup the wait struct */ + dwait.mw_handle = req->msdu_handle; - dwait.mw_handle = req->msdu_handle; + /* Link the wait struct */ - /* Link the wait struct */ + dwait.mw_flink = dev->md_dwait; + dev->md_dwait = &dwait; - dwait.mw_flink = dev->md_dwait; - dev->md_dwait = &dwait; + mac802154dev_givesem(&dev->md_exclsem); + } + /* Pass the request to the MAC layer */ ret = mac802154_req_data(dev->md_mac, req); - mac802154dev_givesem(&dev->md_exclsem); - if (ret < 0) { wlerr("ERROR: req_data failed %d\n", ret); return ret; } - /* Wait for the DATA.confirm callback to be called for our handle */ - if (sem_wait(dwait.mw_sem) < 0) + if (!(filep->f_oflags & O_NONBLOCK)) { - /* This should only happen if the wait was canceled by an signal */ + /* Wait for the DATA.confirm callback to be called for our handle */ - DEBUGASSERT(errno == EINTR); - return -EINTR; - } + if (sem_wait(&dwait.mw_sem) < 0) + { + /* This should only happen if the wait was canceled by an signal */ - /* The unlinking of the wait struct happens inside the callback. This - * is more efficient since it will already have to find the struct in - * the list in order to perform the sem_post. - */ + DEBUGASSERT(errno == EINTR); + return -EINTR; + } - return dwait.status; + /* The unlinking of the wait struct happens inside the callback. This + * is more efficient since it will already have to find the struct in + * the list in order to perform the sem_post. + */ + + return dwait.mw_status; + } + + return OK; } /**************************************************************************** @@ -477,7 +496,6 @@ static int mac802154dev_ioctl(FAR struct file *filep, int cmd, { FAR struct inode *inode; FAR struct mac802154_devwrapper_s *dev; - MACHANDLE mac; int ret; DEBUGASSERT(filep != NULL && filep->f_priv != NULL && @@ -564,10 +582,10 @@ static int mac802154dev_ioctl(FAR struct file *filep, int cmd, void mac802154dev_conf_data(MACHANDLE mac, FAR struct ieee802154_data_conf_s *conf) { - FAR struct mac802154_devwrapper_s *dev; + FAR struct mac802154_devwrapper_s *dev = + (FAR struct mac802154_devwrapper_s *)mac; FAR struct mac802154dev_dwait_s *curr; FAR struct mac802154dev_dwait_s *prev; - int ret; /* Get the dev from the callback context. This should have been set when * the char driver was registered. @@ -579,7 +597,7 @@ void mac802154dev_conf_data(MACHANDLE mac, /* Get exclusive access to the driver structure. We don't care about any * signals so if we see one, just go back to trying to get access again */ - while(mac802154dev_takesem(&dev->md_exclsem) != OK); + while (mac802154dev_takesem(&dev->md_exclsem) != 0); /* Search to see if there is a dwait pending for this transaction */ -- GitLab From a0c4254168feca8b26d1efa77a7198b7a61a5bc0 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Tue, 18 Apr 2017 10:04:54 -1000 Subject: [PATCH 504/990] Kinetis:Fixed warning --- arch/arm/src/kinetis/kinetis_serial.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/arch/arm/src/kinetis/kinetis_serial.c b/arch/arm/src/kinetis/kinetis_serial.c index 63873ecab5..79f0030b78 100644 --- a/arch/arm/src/kinetis/kinetis_serial.c +++ b/arch/arm/src/kinetis/kinetis_serial.c @@ -592,6 +592,7 @@ static void up_restoreuartint(struct up_dev_s *priv, uint8_t ie) * Name: up_disableuartint ****************************************************************************/ +#ifdef HAVE_UART_CONSOLE static void up_disableuartint(struct up_dev_s *priv, uint8_t *ie) { irqstate_t flags; @@ -605,6 +606,7 @@ static void up_disableuartint(struct up_dev_s *priv, uint8_t *ie) up_restoreuartint(priv, 0); leave_critical_section(flags); } +#endif /**************************************************************************** * Name: up_setup -- GitLab From 0d83fce263a4f9cc5c31a26879805b312f567b87 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 18 Apr 2017 14:11:54 -0600 Subject: [PATCH 505/990] Really trivial change in spacing. --- configs/nucleo-f072rb/include/board.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/configs/nucleo-f072rb/include/board.h b/configs/nucleo-f072rb/include/board.h index 50493e09da..1b45a24a51 100644 --- a/configs/nucleo-f072rb/include/board.h +++ b/configs/nucleo-f072rb/include/board.h @@ -218,8 +218,8 @@ /* Button definitions ***************************************************************/ /* Buttons * - * B1 USER: the user button is connected to the I/O PC13 (pin 2) of the STM32 - * microcontroller. + * B1 USER: the user button is connected to the I/O PC13 (pin 2) of the STM32 + * microcontroller. */ #define BUTTON_USER 0 -- GitLab From 35756d62950ee6d2e5f7b5e594ad3796e8dbeb7c Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 18 Apr 2017 14:25:23 -0600 Subject: [PATCH 506/990] ieee802.15.4: Cosmetic changes from review of last PR. --- drivers/wireless/ieee802154/mrf24j40.c | 38 ++++++++----------- .../wireless/ieee802154/ieee802154_mac.h | 6 ++- wireless/ieee802154/mac802154.c | 36 ++++++++++-------- 3 files changed, 40 insertions(+), 40 deletions(-) diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c index 655871eb94..1b00a67e15 100644 --- a/drivers/wireless/ieee802154/mrf24j40.c +++ b/drivers/wireless/ieee802154/mrf24j40.c @@ -90,9 +90,9 @@ /* Definitions for PA control on high power modules */ -#define MRF24J40_PA_AUTO 1 -#define MRF24J40_PA_ED 2 -#define MRF24J40_PA_SLEEP 3 +#define MRF24J40_PA_AUTO 1 +#define MRF24J40_PA_ED 2 +#define MRF24J40_PA_SLEEP 3 #define MRF24J40_GTS_SLOTS 2 @@ -111,7 +111,7 @@ struct mrf24j40_txdesc_s struct mrf24j40_radio_s { - struct ieee802154_radio_s radio; /* The public device instance */ + struct ieee802154_radio_s radio; /* The public device instance */ /* Reference to the bound upper layer via the phyif interface */ @@ -120,11 +120,11 @@ struct mrf24j40_radio_s /* Low-level MCU-specific support */ FAR const struct mrf24j40_lower_s *lower; - FAR struct spi_dev_s *spi; /* Saved SPI interface instance */ + FAR struct spi_dev_s *spi; /* Saved SPI interface instance */ struct work_s irqwork; /* For deferring interrupt work to work queue */ struct work_s pollwork; /* For deferring poll work to the work queue */ - sem_t exclsem; /* Exclusive access to this struct */ + sem_t exclsem; /* Exclusive access to this struct */ uint16_t panid; /* PAN identifier, FFFF = not set */ uint16_t saddr; /* short address, FFFF = not set */ @@ -134,7 +134,7 @@ struct mrf24j40_radio_s uint8_t paenabled; /* enable usage of PA */ uint8_t rxmode; /* Reception mode: Main, no CRC, promiscuous */ int32_t txpower; /* TX power in mBm = dBm/100 */ - struct ieee802154_cca_s cca; /* Clear channel assessement method */ + struct ieee802154_cca_s cca; /* Clear channel assessement method */ /* Buffer Allocations */ @@ -171,9 +171,9 @@ static void mrf24j40_dopoll_csma(FAR void *arg); static void mrf24j40_dopoll_gts(FAR void *arg); static int mrf24j40_csma_setup(FAR struct mrf24j40_radio_s *dev, - uint8_t *buf, uint16_t buf_len); + uint8_t *buf, uint16_t buf_len); static int mrf24j40_gts_setup(FAR struct mrf24j40_radio_s *dev, uint8_t gts, - uint8_t *buf, uint16_t buf_len); + uint8_t *buf, uint16_t buf_len); /* IOCTL helpers */ @@ -338,7 +338,6 @@ static void mrf24j40_dopoll_csma(FAR void *arg) ret = dev->phyif->ops->poll_csma(dev->phyif, &dev->csma_desc.pub, &dev->tx_buf[0]); - if (ret > 0) { /* Now the txdesc is in use */ @@ -352,7 +351,6 @@ static void mrf24j40_dopoll_csma(FAR void *arg) } /* Setup the transmit on the device */ - } sem_post(&dev->exclsem); @@ -435,7 +433,6 @@ static void mrf24j40_dopoll_gts(FAR void *arg) { ret = dev->phyif->ops->poll_gts(dev->phyif, &dev->gts_desc[gts].pub, &dev->tx_buf[0]); - if (ret > 0) { /* Now the txdesc is in use */ @@ -953,12 +950,11 @@ static int mrf24j40_setdevmode(FAR struct mrf24j40_radio_s *dev, } else { - return -EINVAL; + return -EINVAL; } mrf24j40_setreg(dev->spi, MRF24J40_RXMCR, reg); dev->devmode = mode; - return ret; } @@ -974,7 +970,6 @@ static int mrf24j40_getdevmode(FAR struct mrf24j40_radio_s *dev, FAR uint8_t *mode) { *mode = dev->devmode; - return OK; } @@ -1074,7 +1069,6 @@ static int mrf24j40_gettxpower(FAR struct mrf24j40_radio_s *dev, FAR int32_t *txpwr) { *txpwr = dev->txpower; - return OK; } @@ -1134,7 +1128,6 @@ static int mrf24j40_getcca(FAR struct mrf24j40_radio_s *dev, FAR struct ieee802154_cca_s *cca) { memcpy(cca, &dev->cca, sizeof(struct ieee802154_cca_s)); - return OK; } @@ -1285,7 +1278,7 @@ static int mrf24j40_ioctl(FAR struct ieee802154_radio_s *radio, int cmd, return -ENOTTY; } - return ret; + return ret; } /**************************************************************************** @@ -1422,7 +1415,6 @@ static int mrf24j40_transmit(FAR struct ieee802154_radio_s *radio, /* Trigger packet emission */ mrf24j40_setreg(dev->spi, MRF24J40_TXNCON, reg); - return ret; } @@ -1473,11 +1465,11 @@ static void mrf24j40_irqwork_tx(FAR struct mrf24j40_radio_s *dev) /* 1 means it failed, we want 1 to mean it worked. */ - /* +#if 0 dev->radio.txok = (reg & MRF24J40_TXSTAT_TXNSTAT) != MRF24J40_TXSTAT_TXNSTAT; dev->radio.txretries = (reg & MRF24J40_TXSTAT_X_MASK) >> MRF24J40_TXSTAT_X_SHIFT; dev->radio.txbusy = (reg & MRF24J40_TXSTAT_CCAFAIL) == MRF24J40_TXSTAT_CCAFAIL; - */ +#endif //wlinfo("TXSTAT%02X!\n", txstat); #warning TODO report errors @@ -1568,7 +1560,9 @@ static void mrf24j40_irqwork_rx(FAR struct mrf24j40_radio_s *dev) dev->radio.rxbuf->lqi = mrf24j40_getreg(dev->spi, addr++); dev->radio.rxbuf->rssi = mrf24j40_getreg(dev->spi, addr++); - /* Reduce len by 2, we only receive frames with correct crc, no check required */ + /* Reduce len by 2, we only receive frames with correct crc, no check + * required. + */ dev->radio.rxbuf->len -= 2; diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index 800436de78..6486129d61 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -401,7 +401,8 @@ struct ieee802154_data_req_s * to be transmitted by the MAC sublayer enitity * Note: This could be a uint8_t but if anyone ever wants to use * non-standard frame lengths, they may want a length larger than - * a uint8_t */ + * a uint8_t. + */ uint16_t msdu_length; @@ -611,7 +612,8 @@ struct ieee802154_assoc_rsp_s struct ieee802154_assoc_conf_s { /* Associated device address ALWAYS passed in short address mode. The - * address will be IEEE802154_SADDR_UNSPEC if association was unsuccessful. + * address will be IEEE802154_SADDR_UNSPEC if association was + * unsuccessful. */ struct ieee802154_addr_s dev_addr; diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index 671e67b6e2..a23128820d 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -245,12 +245,12 @@ static int mac802154_applymib(FAR struct ieee802154_privmac_s *priv); /* IEEE 802.15.4 PHY Interface OPs */ static int mac802154_poll_csma(FAR struct ieee802154_phyif_s *phyif, - FAR struct ieee802154_txdesc_s *tx_desc, - uint8_t *buf); + FAR struct ieee802154_txdesc_s *tx_desc, + FAR uint8_t *buf); static int mac802154_poll_gts(FAR struct ieee802154_phyif_s *phyif, - FAR struct ieee802154_txdesc_s *tx_desc, - uint8_t *buf); + FAR struct ieee802154_txdesc_s *tx_desc, + FAR uint8_t *buf); /**************************************************************************** * Private Data @@ -301,6 +301,7 @@ static inline int mac802154_takesem(sem_t *sem) static int mac802154_defaultmib(FAR struct ieee802154_privmac_s *priv) { /* TODO: Set all MAC fields to default values */ + return OK; } @@ -475,8 +476,9 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) mhr.length = 2; - /* Do a preliminary check to make sure the MSDU isn't too long for even the - * best case */ + /* Do a preliminary check to make sure the MSDU isn't too long for even + * the best case. + */ if (req->msdu_length > IEEE802154_MAX_MAC_PAYLOAD_SIZE) { @@ -492,8 +494,8 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) mhr.u.frame_control |= IEEE802154_FRAME_DATA << IEEE802154_FRAMECTRL_SHIFT_FTYPE; - /* If the msduLength is greater than aMaxMACSafePayloadSize, the MAC sublayer - * will set the Frame Version to one. [1] pg. 118. + /* If the msduLength is greater than aMaxMACSafePayloadSize, the MAC + * sublayer will set the Frame Version to one. [1] pg. 118. */ if (req->msdu_length > IEEE802154_MAX_SAFE_MAC_PAYLOAD_SIZE) @@ -501,8 +503,8 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) mhr.u.frame_control |= IEEE802154_FRAMECTRL_VERSION; } - /* If the TXOptions parameter specifies that an acknowledged transmission is - * required, the AR field will be set appropriately, as described in + /* If the TXOptions parameter specifies that an acknowledged transmission + * is required, the AR field will be set appropriately, as described in * 5.1.6.4 [1] pg. 118. */ @@ -700,8 +702,8 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) /* Called from interrupt level or worker thread with interrupts disabled */ static int mac802154_poll_csma(FAR struct ieee802154_phyif_s *phyif, - FAR struct ieee802154_txdesc_s *tx_desc, - uint8_t *buf) + FAR struct ieee802154_txdesc_s *tx_desc, + FAR uint8_t *buf) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)&phyif->priv; @@ -711,7 +713,8 @@ static int mac802154_poll_csma(FAR struct ieee802154_phyif_s *phyif, DEBUGASSERT(priv != 0); /* Get exclusive access to the driver structure. We don't care about any - * signals so if we see one, just go back to trying to get access again */ + * signals so if we see one, just go back to trying to get access again. + */ while (mac802154_takesem(&priv->exclsem) != 0); @@ -751,8 +754,8 @@ static int mac802154_poll_csma(FAR struct ieee802154_phyif_s *phyif, } static int mac802154_poll_gts(FAR struct ieee802154_phyif_s *phyif, - FAR struct ieee802154_txdesc_s *tx_desc, - uint8_t *buf) + FAR struct ieee802154_txdesc_s *tx_desc, + FAR uint8_t *buf) { return 0; } @@ -797,7 +800,8 @@ int mac802154_req_associate(MACHANDLE mac, /* Set the macPANId */ /* Set either the macCoordExtendedAddress and macCoordShortAddress - * depending on the CoordAddrMode in the primitive */ + * depending on the CoordAddrMode in the primitive. + */ if (req->coord_addr.mode == IEEE802154_ADDRMODE_EXTENDED) { -- GitLab From 4844011b9c7cf63e35ec8cb28419cce554602431 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Tue, 18 Apr 2017 11:51:56 -1000 Subject: [PATCH 507/990] stm32:stm32_serial fixed warning --- arch/arm/src/stm32/stm32_serial.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/arch/arm/src/stm32/stm32_serial.c b/arch/arm/src/stm32/stm32_serial.c index a6a2d07b51..6b6161f0ce 100644 --- a/arch/arm/src/stm32/stm32_serial.c +++ b/arch/arm/src/stm32/stm32_serial.c @@ -2250,7 +2250,9 @@ static bool up_rxflowcontrol(struct uart_dev_s *dev, unsigned int nbuffered, bool upper) { struct up_dev_s *priv = (struct up_dev_s *)dev->priv; +#if !(defined(CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS) && defined(CONFIG_STM32_FLOWCONTROL_BROKEN)) uint16_t ie; +#endif #if defined(CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS) && defined(CONFIG_STM32_FLOWCONTROL_BROKEN) if (priv->iflow && (priv->rts_gpio != 0)) -- GitLab From 0a457a1b204dd188f726aff0a72ba4c0e6312513 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 18 Apr 2017 16:29:25 -0600 Subject: [PATCH 508/990] Coding standard: Defining structures within the scope of another structure is discouraged. --- Documentation/NuttXCCodingStandard.html | 66 ++++++++++++++++++++++--- 1 file changed, 58 insertions(+), 8 deletions(-) diff --git a/Documentation/NuttXCCodingStandard.html b/Documentation/NuttXCCodingStandard.html index 98c878a296..ae06f040fb 100644 --- a/Documentation/NuttXCCodingStandard.html +++ b/Documentation/NuttXCCodingStandard.html @@ -12,7 +12,7 @@

    NuttX C Coding Standard

    -

    Last Updated: April 17, 2017

    +

    Last Updated: April 18, 2017

    @@ -1292,13 +1292,18 @@ typedef int myinteger_t; No un-named structures. All structures must be named, even if they are part of a type definition. That is, a structure name must follow the reserved word struct in all structure definitions. - The exception to this rule is for structures that are defined within another union or structure. In those cases, the structure name should always be omitted. + The exception to this rule is for structures that are defined within another union or structure (discouraged). In those cases, the structure name should always be omitted. +
  • +
  • + Structured defined with structures discouraged. + Fields within a structure may be another structure that is defined only with the scope of the containing structure. + This practice is acceptable, but discouraged.
  • No un-named structure fields. Structure may contain other structures as fields. This this case, the structure field must be named. - C11 permits such un-named structure fields within structure. + C11 permits such un-named structure fields within a structure. NuttX generally follows C89 and all code outside of architecture specific directories must be compatible with C89.
  • No structure definitions within Type Definition. @@ -1412,8 +1417,12 @@ struct abc_s -

    Correct

    -
      +
        + +

        + Correct +

        +
         struct xyz_info_s
         {
           ...
        @@ -1423,10 +1432,20 @@ struct xyz_info_s
           ...
         };
         
        -
        +
        +

        + Discouraged +

        +
         typedef struct xyz_info_s xzy_info_t;
         
        -

        (The use of typedef'ed structures is acceptable but discouraged)

        +

        + The use of typedef'ed structures is acceptable but discouraged. +

        +
        +

        + Correct +

         struct xyz_info_s
         {
        @@ -1436,16 +1455,47 @@ struct xyz_info_s
           uint8_t bitc : 1,  /* Bit C */
           ...
         };
        -
        +
        + +

        + Discouraged +

        +
        +
         struct abc_s
         {
           ...
        +
        + +
           struct
           {
             int a;           /* Value A */
             int b;           /* Value B */
             int c;           /* Value C */
           } abc;
        +
        +
        +
        +  ...
        +};
        +
        + +

        + The use of structures defined within other structures is acceptable but discouraged. + The following is preferred: +

        +
        +

        + Correct +

        +
        +struct abc_s
        +{
        +  ...
        +  int a;             /* Value A */
        +  int b;             /* Value B */
        +  int c;             /* Value C */
           ...
         };
         
      -- GitLab From e7a1847d082a5fb4f4a362d52a519fed661b9026 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 18 Apr 2017 16:46:23 -0600 Subject: [PATCH 509/990] Coding style: Minor updates to last commit. --- Documentation/NuttXCCodingStandard.html | 16 ++++++---------- 1 file changed, 6 insertions(+), 10 deletions(-) diff --git a/Documentation/NuttXCCodingStandard.html b/Documentation/NuttXCCodingStandard.html index ae06f040fb..8689ef8058 100644 --- a/Documentation/NuttXCCodingStandard.html +++ b/Documentation/NuttXCCodingStandard.html @@ -1414,6 +1414,7 @@ struct abc_s }; /* Un-named structure field */ ... }; +
    @@ -1460,29 +1461,22 @@ struct xyz_info_s

    Discouraged

    -
     struct abc_s
     {
       ...
    -
    - -
       struct
       {
         int a;           /* Value A */
         int b;           /* Value B */
         int c;           /* Value C */
       } abc;
    -
    -
    -
       ...
     };
     
    -

    - The use of structures defined within other structures is acceptable but discouraged. + The use of structures defined within other structures is acceptable provided that they define named fields. + The general practice of defining a structure within the scope of another structure, however, is still but discouraged in any case. The following is preferred:

    @@ -1498,6 +1492,7 @@ struct abc_s int c; /* Value C */ ... }; + @@ -1526,7 +1521,7 @@ union xyz_union_u /* All unions must be named */
     typedef union xyz_union_u xzy_union_t;
     
    -

    (The use of typedef'ed unions is acceptable but discouraged)

    +

    The use of typedef'ed unions is acceptable but discouraged.

     struct xyz_info_s
     {
    @@ -1539,6 +1534,7 @@ struct xyz_info_s
       } u;             /* All union fields must be named */
       ...
     };
    +
     
    -- GitLab From d9c266c71ba1a8f174d730d77dfca4dd539f4ab8 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 19 Apr 2017 06:23:13 -0600 Subject: [PATCH 510/990] Trivial change to document. --- Documentation/NuttXCCodingStandard.html | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Documentation/NuttXCCodingStandard.html b/Documentation/NuttXCCodingStandard.html index 8689ef8058..f867fb3782 100644 --- a/Documentation/NuttXCCodingStandard.html +++ b/Documentation/NuttXCCodingStandard.html @@ -1481,7 +1481,7 @@ struct abc_s

    - Correct + Preferred

     struct abc_s
    -- 
    GitLab
    
    
    From 575fb0acbfb9702de0d0e5933ab5c8329622e4a7 Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Wed, 19 Apr 2017 07:26:51 -0600
    Subject: [PATCH 511/990] Nucleo-F072RB: Enable board_app_inititalize, procfs,
     and built-in functions.
    
    ---
     configs/nucleo-f072rb/nsh/defconfig       | 55 +++++++++++++++++++----
     configs/nucleo-f072rb/src/stm32_bringup.c |  3 +-
     configs/nucleo-f072rb/src/stm32_buttons.c |  8 ++--
     3 files changed, 54 insertions(+), 12 deletions(-)
    
    diff --git a/configs/nucleo-f072rb/nsh/defconfig b/configs/nucleo-f072rb/nsh/defconfig
    index 48868af124..946a2edad2 100644
    --- a/configs/nucleo-f072rb/nsh/defconfig
    +++ b/configs/nucleo-f072rb/nsh/defconfig
    @@ -407,14 +407,20 @@ CONFIG_ARCH_BOARD="nucleo-f072rb"
     CONFIG_ARCH_HAVE_LEDS=y
     CONFIG_ARCH_LEDS=y
     CONFIG_ARCH_HAVE_BUTTONS=y
    -# CONFIG_ARCH_BUTTONS is not set
    +CONFIG_ARCH_BUTTONS=y
     CONFIG_ARCH_HAVE_IRQBUTTONS=y
    +CONFIG_ARCH_IRQBUTTONS=y
     
     #
     # Board-Specific Options
     #
     # CONFIG_BOARD_CRASHDUMP is not set
    -# CONFIG_LIB_BOARDCTL is not set
    +CONFIG_LIB_BOARDCTL=y
    +# CONFIG_BOARDCTL_RESET is not set
    +# CONFIG_BOARDCTL_UNIQUEID is not set
    +# CONFIG_BOARDCTL_TSCTEST is not set
    +# CONFIG_BOARDCTL_GRAPHICS is not set
    +# CONFIG_BOARDCTL_IOCTL is not set
     
     #
     # RTOS Features
    @@ -448,6 +454,7 @@ CONFIG_PREALLOC_TIMERS=0
     # CONFIG_SPINLOCK is not set
     # CONFIG_INIT_NONE is not set
     CONFIG_INIT_ENTRYPOINT=y
    +# CONFIG_INIT_FILEPATH is not set
     CONFIG_USER_ENTRYPOINT="nsh_main"
     CONFIG_RR_INTERVAL=200
     # CONFIG_SCHED_SPORADIC is not set
    @@ -675,13 +682,28 @@ CONFIG_SYSLOG_CONSOLE=y
     #
     # File system configuration
     #
    -CONFIG_DISABLE_MOUNTPOINT=y
    +# CONFIG_DISABLE_MOUNTPOINT is not set
    +# CONFIG_FS_AUTOMOUNTER is not set
     CONFIG_DISABLE_PSEUDOFS_OPERATIONS=y
    -# CONFIG_FS_READABLE is not set
    +CONFIG_FS_READABLE=y
     # CONFIG_FS_WRITABLE is not set
     # CONFIG_FS_NAMED_SEMAPHORES is not set
     # CONFIG_FS_RAMMAP is not set
    -# CONFIG_FS_PROCFS is not set
    +# CONFIG_FS_FAT is not set
    +# CONFIG_FS_NXFFS is not set
    +# CONFIG_FS_ROMFS is not set
    +# CONFIG_FS_TMPFS is not set
    +# CONFIG_FS_SMARTFS is not set
    +# CONFIG_FS_BINFS is not set
    +CONFIG_FS_PROCFS=y
    +# CONFIG_FS_PROCFS_REGISTER is not set
    +
    +#
    +# Exclude individual procfs entries
    +#
    +# CONFIG_FS_PROCFS_EXCLUDE_PROCESS is not set
    +# CONFIG_FS_PROCFS_EXCLUDE_UPTIME is not set
    +# CONFIG_FS_PROCFS_EXCLUDE_MOUNTS is not set
     # CONFIG_FS_UNIONFS is not set
     
     #
    @@ -709,7 +731,10 @@ CONFIG_MM_REGIONS=1
     #
     # Binary Loader
     #
    -CONFIG_BINFMT_DISABLE=y
    +# CONFIG_BINFMT_DISABLE is not set
    +# CONFIG_NXFLAT is not set
    +# CONFIG_ELF is not set
    +CONFIG_BUILTIN=y
     # CONFIG_PIC is not set
     # CONFIG_SYMTAB_ORDEREDBYNAME is not set
     
    @@ -762,6 +787,7 @@ CONFIG_LIB_RAND_ORDER=1
     #
     # Program Execution Options
     #
    +# CONFIG_LIBC_EXECFUNCS is not set
     CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024
     CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=1536
     
    @@ -801,6 +827,7 @@ CONFIG_ARCH_HAVE_TLS=y
     #
     # NETDB Support
     #
    +# CONFIG_NETDB_HOSTFILE is not set
     # CONFIG_LIBC_IOCTL_VARIADIC is not set
     CONFIG_LIB_SENDFILE_BUFSIZE=512
     
    @@ -822,6 +849,11 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # Application Configuration
     #
     
    +#
    +# Built-In Applications
    +#
    +CONFIG_BUILTIN_PROXY_STACKSIZE=1024
    +
     #
     # CAN Utilities
     #
    @@ -867,12 +899,14 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_SERLOOP is not set
     # CONFIG_EXAMPLES_SLCD is not set
     # CONFIG_EXAMPLES_SMART is not set
    +# CONFIG_EXAMPLES_SMART_TEST is not set
     # CONFIG_EXAMPLES_SMP is not set
     # CONFIG_EXAMPLES_STAT is not set
     # CONFIG_EXAMPLES_TCPECHO is not set
     # CONFIG_EXAMPLES_TELNETD is not set
     # CONFIG_EXAMPLES_TIFF is not set
     # CONFIG_EXAMPLES_TOUCHSCREEN is not set
    +# CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_XBC_TEST is not set
    @@ -881,6 +915,7 @@ CONFIG_EXAMPLES_NSH=y
     # File System Utilities
     #
     # CONFIG_FSUTILS_INIFILE is not set
    +# CONFIG_FSUTILS_PASSWD is not set
     
     #
     # GPS Utilities
    @@ -896,6 +931,7 @@ CONFIG_EXAMPLES_NSH=y
     #
     # Interpreters
     #
    +# CONFIG_INTERPRETERS_BAS is not set
     # CONFIG_INTERPRETERS_FICL is not set
     # CONFIG_INTERPRETERS_MICROPYTHON is not set
     # CONFIG_INTERPRETERS_MINIBASIC is not set
    @@ -928,10 +964,12 @@ CONFIG_NSH_READLINE=y
     # CONFIG_NSH_CLE is not set
     CONFIG_NSH_LINELEN=64
     CONFIG_NSH_DISABLE_SEMICOLON=y
    +# CONFIG_NSH_CMDPARMS is not set
     CONFIG_NSH_MAXARGUMENTS=6
     # CONFIG_NSH_ARGCAT is not set
     CONFIG_NSH_NESTDEPTH=3
     # CONFIG_NSH_DISABLEBG is not set
    +CONFIG_NSH_BUILTIN_APPS=y
     
     #
     # Disable Individual commands
    @@ -939,7 +977,7 @@ CONFIG_NSH_NESTDEPTH=3
     CONFIG_NSH_DISABLE_ADDROUTE=y
     CONFIG_NSH_DISABLE_BASENAME=y
     # CONFIG_NSH_DISABLE_CAT is not set
    -CONFIG_NSH_DISABLE_CD=y
    +# CONFIG_NSH_DISABLE_CD is not set
     CONFIG_NSH_DISABLE_CP=y
     CONFIG_NSH_DISABLE_CMP=y
     CONFIG_NSH_DISABLE_DATE=y
    @@ -991,6 +1029,7 @@ CONFIG_NSH_MMCSDMINOR=0
     #
     CONFIG_NSH_CODECS_BUFSIZE=128
     # CONFIG_NSH_CMDOPT_HEXDUMP is not set
    +CONFIG_NSH_PROC_MOUNTPOINT="/proc"
     CONFIG_NSH_FILEIOSIZE=64
     
     #
    @@ -1003,7 +1042,7 @@ CONFIG_NSH_DISABLESCRIPT=y
     #
     CONFIG_NSH_CONSOLE=y
     # CONFIG_NSH_ALTCONDEV is not set
    -# CONFIG_NSH_ARCHINIT is not set
    +CONFIG_NSH_ARCHINIT=y
     # CONFIG_NSH_LOGIN is not set
     # CONFIG_NSH_CONSOLE_LOGIN is not set
     
    diff --git a/configs/nucleo-f072rb/src/stm32_bringup.c b/configs/nucleo-f072rb/src/stm32_bringup.c
    index 0c9c7f89df..137e458e78 100644
    --- a/configs/nucleo-f072rb/src/stm32_bringup.c
    +++ b/configs/nucleo-f072rb/src/stm32_bringup.c
    @@ -41,6 +41,7 @@
     
     #include 
     #include 
    +#include 
     
     #include "nucleo-f072rb.h"
     
    @@ -72,7 +73,7 @@ int stm32_bringup(void)
       ret = mount(NULL, "/proc", "procfs", 0, NULL);
       if (ret < 0)
         {
    -      syslog(LOG_ERR, "ERROR: Failed to mount procfs at /proc: %d\n", ret);
    +      ferr("ERROR: Failed to mount procfs at /proc: %d\n", ret);
         }
     #endif
     
    diff --git a/configs/nucleo-f072rb/src/stm32_buttons.c b/configs/nucleo-f072rb/src/stm32_buttons.c
    index b4aed6807a..f8574e47b3 100644
    --- a/configs/nucleo-f072rb/src/stm32_buttons.c
    +++ b/configs/nucleo-f072rb/src/stm32_buttons.c
    @@ -40,12 +40,14 @@
     #include 
     
     #include 
    +#include 
     #include 
     
     #include 
     #include 
     #include 
     
    +#include "stm32f0_gpio.h"
     #include "nucleo-f072rb.h"
     
     #ifdef CONFIG_ARCH_BUTTONS
    @@ -71,7 +73,7 @@ void board_button_initialize(void)
        * also configured for the pin.
        */
     
    -  stm32_configgpio(GPIO_BTN_USER);
    +  stm32f0_configgpio(GPIO_BTN_USER);
     }
     
     /****************************************************************************
    @@ -84,7 +86,7 @@ uint32_t board_buttons(void)
        * pressed.
        */
     
    -  bool released = stm32_gpioread(GPIO_BTN_USER);
    +  bool released = stm32f0_gpioread(GPIO_BTN_USER);
       return !released;
     }
     
    @@ -117,7 +119,7 @@ int board_button_irq(int id, xcpt_t irqhandler, FAR void *arg)
     
       if (id == BUTTON_USER)
         {
    -      ret = stm32_gpiosetevent(GPIO_BTN_USER, true, true, true, irqhandler, arg);
    +      ret = stm32f0_gpiosetevent(GPIO_BTN_USER, true, true, true, irqhandler, arg);
         }
     
       return ret;
    -- 
    GitLab
    
    
    From de4e2d84c42fbacf48f614cc58e85b5688a5cfe8 Mon Sep 17 00:00:00 2001
    From: Anthony Merlino 
    Date: Wed, 19 Apr 2017 11:30:39 -0400
    Subject: [PATCH 512/990] wireless/ieee802154: Simplifies MAC callback
     interface.  Adds missing data type definitions
    
    ---
     .../wireless/ieee802154/ieee802154_mac.h      | 850 ++++++++++++++----
     wireless/ieee802154/mac802154_device.c        |  98 +-
     wireless/ieee802154/mac802154_netdev.c        | 325 ++++---
     wireless/ieee802154/radio802154_device.c      |   3 +
     4 files changed, 901 insertions(+), 375 deletions(-)
    
    diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h
    index 6486129d61..4bdbdde876 100644
    --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h
    +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h
    @@ -115,7 +115,7 @@
     /* MAC commands */
     
     #define IEEE802154_CMD_ASSOC_REQ      0x01
    -#define IEEE802154_CMD_ASSOC_RSP      0x02
    +#define IEEE802154_CMD_ASSOC_RESP     0x02
     #define IEEE802154_CMD_DISASSOC_NOT   0x03
     #define IEEE802154_CMD_DATA_REQ       0x04
     #define IEEE802154_CMD_PANID_CONF_NOT 0x05
    @@ -392,6 +392,99 @@ enum ieee802154_ranging_e
       IEEE802154_PHY_HEADER_ONLY
     };
     
    +struct ieee802154_capability_info_s
    +{
    +  uint8_t reserved_0 : 1;     /* Reserved */
    +  uint8_t device_type : 1;    /* 0=RFD, 1=FFD */
    +  uint8_t power_source : 1;   /* 1=AC, 0=Other */
    +  uint8_t rx_on_idle : 1;     /* 0=Receiver off when idle
    +                               * 1=Receiver on when idle */
    +  uint8_t reserved_45 : 2;    /* Reserved */
    +  uint8_t security : 1;       /* 0=disabled, 1=enabled */
    +  uint8_t allocate_addr : 1;  /* 1=Coordinator allocates short address
    +                               * 0=otherwise */
    +};
    +
    +struct ieee802154_superframe_spec_s
    +{
    +  uint16_t beacon_order     : 4;  /* Transmission interval of beacon */
    +  uint16_t superframe_order : 4;  /* Length of superframe */
    +  uint16_t final_cap_slot   : 4;  /* Last slot utilized by CAP */
    +  uint16_t ble              : 1;  /* Battery Life Extension (BLE) */
    +  uint16_t reserved         : 1;  /* Reserved bit */
    +  uint16_t pan_coordinator  : 1;  /* 1 if beacon sent by pan coordinator */
    +  uint16_t assoc_permit     : 1;  /* 1 if coordinator is accepting associaton */
    +};
    +
    +struct ieee802154_pan_desc_s
    +{
    +  /* The coordinator address of the received beacon frame */
    +
    +  struct ieee802154_addr_s coord_addr;
    +
    +  uint8_t channel;          /* current channel occupied by the network */
    +  uint8_t channel_page;     /* current channel page occupied by the network */
    +
    +  /* The superframe specifications received in the beacon frame */
    +
    +  struct ieee802154_superframe_spec_s superframe_spec;
    +
    +  uint8_t gts_permit;       /* 0=No GTS requests allowed
    +                             * 1=GTS request allowed */
    +  uint8_t lqi;              /* Link Quality Indication of the beacon */
    +  uint32_t timestamp;       /* Time at which the beacon frame was received
    +                             * in symbols */
    +};
    +
    +struct ieee802154_pend_addr_s
    +{
    +  union
    +  {
    +    uint8_t pa_spec;
    +    struct
    +    {
    +      uint8_t num_short_addr  : 3;  /* Number of short addresses pending */
    +      uint8_t reserved_3      : 1;  /* Reserved bit */
    +      uint8_t num_ext_addr    : 3;  /* Number of extended addresses pending */       
    +      uint8_t reserved_7      : 1;  /* Reserved bit */
    +    } pa_addr;
    +  } u;
    +  struct ieee802154_addr_s addr[7]; /* Array of at most 7 addresses */
    +};
    +
    +/* Primitive Support Types ***************************************************/
    +
    +union ieee802154_attr_val_u
    +{
    +  /* TODO: Finish this */
    +};
    +
    +struct ieee802154_gts_info_s
    +{
    +  uint8_t length      : 4; /* Number of SF slots for GTS */
    +  uint8_t direction   : 1; /* 0=transmit-only, 1=receive-only */
    +  uint8_t type        : 1; /* 0=GTS deallocation, 1= GTS allocation */
    +  uint8_t reserved    : 2;
    +};
    +
    +enum ieee802154_scantype_e
    +{
    +  IEEE802154_SCANTYPE_ED,
    +  IEEE802154_SCANTYPE_ACTIVE,
    +  IEEE802154_SCANTYPE_PASSIVE,
    +  IEEE802154_SCANTYPE_ORPHAN
    +};
    +
    +/* Primitive Semantics *******************************************************/
    +
    +/*****************************************************************************
    + * Primitive: MCPS-DATA.request 
    + *
    + * Description:
    + *    Requests the transfer of data to another device.  
    + * 
    + *****************************************************************************/
    +
     struct ieee802154_data_req_s
     {
       enum ieee802154_addr_mode_e src_addr_mode;  /* Source Address Mode */
    @@ -406,7 +499,6 @@ struct ieee802154_data_req_s
     
       uint16_t msdu_length;
     
    -
       uint8_t msdu_handle;    /* Handle assoc. with MSDU */
       struct
       {
    @@ -447,9 +539,18 @@ struct ieee802154_data_req_s
     
       uint8_t msdu[1];
     };
    +
     #define SIZEOF_IEEE802154_DATA_REQ_S(n) \
             (sizeof(struct ieee802154_data_req_s) + (n) - 1)
     
    +/*****************************************************************************
    + * Primitive: MCPS-DATA.confirm 
    + *
    + * Description:
    + *    Reports the results of a request to transfer data to another device.
    + * 
    + *****************************************************************************/
    +
     struct ieee802154_data_conf_s
     {
       uint8_t msdu_handle;              /* Handle assoc. with MSDU */
    @@ -493,67 +594,92 @@ struct ieee802154_data_conf_s
     #endif
     };
     
    -struct ieee802154_capability_info_s
    -{
    -  uint8_t reserved_0 : 1;     /* Reserved */
    -  uint8_t device_type : 1;    /* 0=RFD, 1=FFD */
    -  uint8_t power_source : 1;   /* 1=AC, 0=Other */
    -  uint8_t rx_on_idle : 1;     /* 0=Receiver off when idle
    -                               * 1=Receiver on when idle */
    -  uint8_t reserved_45 : 2;    /* Reserved */
    -  uint8_t security : 1;       /* 0=disabled, 1=enabled */
    -  uint8_t allocate_addr : 1;  /* 1=Coordinator allocates short address
    -                               * 0=otherwise */
    -};
    +/*****************************************************************************
    + * Primitive: MCPS-DATA.indication 
    + *
    + * Description:
    + *    Indicates the reception of data from another device.
    + * 
    + *****************************************************************************/
     
    -struct ieee802154_superframe_spec_s
    +struct ieee802154_data_ind_s
     {
    -  uint16_t beacon_order     : 4;  /* Transmission interval of beacon */
    -  uint16_t superframe_order : 4;  /* Length of superframe */
    -  uint16_t final_cap_slot   : 4;  /* Last slot utilized by CAP */
    -  uint16_t ble              : 1;  /* Battery Life Extension (BLE) */
    -  uint16_t reserved         : 1;  /* Reserved bit */
    -  uint16_t pan_coordinator  : 1;  /* 1 if beacon sent by pan coordinator */
    -  uint16_t assoc_permit     : 1;  /* 1 if coordinator is accepting associaton */
    -};
    +  uint8_t msdu_handle;              /* Handle assoc. with MSDU */
     
    -struct ieee802154_pan_desc_s
    -{
    -  /* The coordinator address of the received beacon frame */
    +  /* The time, in symbols, at which the data were transmitted */
     
    -  struct ieee802154_addr_s coord_addr;
    +  uint32_t timestamp;
     
    -  uint8_t channel;          /* current channel occupied by the network */
    -  uint8_t channel_page;     /* current channel page occupied by the network */
    +  enum ieee802154_status_e status;  /* The status of the MSDU transmission */
     
    -  /* The superframe specifications received in the beacon frame */
    +#ifdef CONFIG_IEEE802154_RANGING
    +  bool rng_rcvd;                    /* Ranging indicated by MSDU */
     
    -  struct ieee802154_superframe_spec_s superframe_spec;
    +  /* A count of the time units corresponding to an RMARKER at the antenna at
    +   * the beginning of the ranging exchange
    +   */
     
    -  uint8_t gts_permit;       /* 0=No GTS requests allowed
    -                             * 1=GTS request allowed */
    -  uint8_t lqi;              /* Link Quality Indication of the beacon */
    -  uint32_t timestamp;       /* Time at which the beacon frame was received
    -                             * in symbols */
    +  uint32_t rng_counter_start; 
    +
    +  /* A count of the time units corresponding to an RMARKER at the antenna at
    +   * end of the ranging exchange
    +   */
    +
    +  uint32_t rng_counter_stop; 
    +
    +  /* A count of the time units in a message exchange over which the tracking
    +   * offset was measured
    +   */
    +
    +  uint34_t rng_tracking_interval;
    +
    +  /* A count of the time units slipped or advanced by the radio tracking
    +   * system over the course of the entire tracking interval
    +   */
    +
    +  uint32_t rng_offset;
    +
    +  /* The Figure of Merit (FoM) characterizing the ranging measurement */ 
    +
    +  uint8_t rng_fom; 
    +#endif
     };
     
    -struct ieee802154_pend_addr_s
    +/*****************************************************************************
    + * Primitive: MCPS-PURGE.request 
    + *
    + * Description:
    + *    Allows the next higher layer to purge an MSDU from the transaction queue.
    + * 
    + *****************************************************************************/
    +
    +struct ieee802154_purge_req_s
     {
    -  union
    -  {
    -    uint8_t pa_spec;
    -    struct
    -    {
    -      uint8_t num_short_addr  : 3;  /* Number of short addresses pending */
    -      uint8_t reserved_3      : 1;  /* Reserved bit */
    -      uint8_t num_ext_addr    : 3;  /* Number of extended addresses pending */       
    -      uint8_t reserved_7      : 1;  /* Reserved bit */
    -    } pa_addr;
    -  } u;
    -  struct ieee802154_addr_s addr[7]; /* Array of at most 7 addresses */
    +  uint8_t msdu_handle;              /* Handle assoc. with MSDU */
     };
     
    -/* Primitive Semantics */
    +/*****************************************************************************
    + * Primitive: MCPS-PURGE.confirm 
    + *
    + * Description:
    + *    Allows the MAC sublayer to notify the next higher layer of the success of
    + *    its request to purge an MSDU from the transaction queue.
    + * 
    + *****************************************************************************/
    +
    +struct ieee802154_purge_conf_s
    +{
    +  uint8_t msdu_handle;              /* Handle assoc. with MSDU */
    +  enum ieee802154_status_e status;  /* The status of the MSDU transmission */
    +};
    +
    +/*****************************************************************************
    + * Primitive: MLME-ASSOCIATE.request 
    + *
    + * Description:
    + *    Used by a device to request an association with a coordinator.
    + * 
    + *****************************************************************************/
     
     struct ieee802154_assoc_req_s
     {
    @@ -575,6 +701,14 @@ struct ieee802154_assoc_req_s
     #endif
     };
     
    +/*****************************************************************************
    + * Primitive: MLME-ASSOCIATE.indication 
    + *
    + * Description:
    + *    Used to indicate the reception of an association request command.
    + * 
    + *****************************************************************************/
    +
     struct ieee802154_assoc_ind_s
     {
       /* Address of device requesting association. Always in extended mode */
    @@ -592,7 +726,15 @@ struct ieee802154_assoc_ind_s
     #endif
     };
     
    -struct ieee802154_assoc_rsp_s
    +/*****************************************************************************
    + * Primitive: MLME-ASSOCIATE.response 
    + *
    + * Description:
    + *    Used to initiate a response to an MLME-ASSOCIATE.indication primitive.
    + * 
    + *****************************************************************************/
    +
    +struct ieee802154_assoc_resp_s
     {
       /* Address of device requesting association. Always in extended mode */
     
    @@ -609,6 +751,15 @@ struct ieee802154_assoc_rsp_s
     #endif
     };
     
    +/*****************************************************************************
    + * Primitive: MLME-ASSOCIATE.confirm 
    + *
    + * Description:
    + *    Used to inform the next higher layer of the initiating device whether its
    + *    request to associate was successful or unsuccessful.
    + * 
    + *****************************************************************************/
    +
     struct ieee802154_assoc_conf_s
     {
       /* Associated device address ALWAYS passed in short address mode. The
    @@ -629,6 +780,16 @@ struct ieee802154_assoc_conf_s
     #endif
     };
     
    +/*****************************************************************************
    + * Primitive: MLME-DISASSOCIATE.request 
    + *
    + * Description:
    + *    Used by an associated device to notify the coordinator of its intent to
    + *    leave the PAN. It is also used by the coordinator to instruct an
    + *    associated device to leave the PAN.
    + * 
    + *****************************************************************************/
    +
     struct ieee802154_disassoc_req_s
     {
       /* Address of device to send disassociation notification */
    @@ -648,6 +809,14 @@ struct ieee802154_disassoc_req_s
     #endif
     };
     
    +/*****************************************************************************
    + * Primitive: MLME-DISASSOCIATE.indication 
    + *
    + * Description:
    + *    Used to indicate the reception of a disassociation notification command.
    + * 
    + *****************************************************************************/
    +
     struct ieee802154_disassoc_ind_s
     {
       /* Address of device requesting disassociation. Always extended mode */
    @@ -665,6 +834,14 @@ struct ieee802154_disassoc_ind_s
     #endif
     };
     
    +/*****************************************************************************
    + * Primitive: MLME-DISASSOCIATE.confirm 
    + *
    + * Description:
    + *    Reports the results of an MLME-DISASSOCIATE.request primitive.
    + * 
    + *****************************************************************************/
    +
     struct ieee802154_disassoc_conf_s
     {
       /* Status of the disassociation attempt */
    @@ -676,6 +853,18 @@ struct ieee802154_disassoc_conf_s
       struct ieee802154_addr_s dev_addr;
     };
     
    +/*****************************************************************************
    + * Primitive: MLME-BEACONNOTIFY.indication 
    + *
    + * Description:
    + *    Used to send parameters contained within a beacon frame received by the
    + *    MAC sublayer to the next higher layer when either macAutoRequest is set to
    + *    FALSE or when the beacon frame contains one or more octets of payload. The
    + *    primitive also sends a measure of the LQI and the time the beacon frame
    + *    was received.
    + * 
    + *****************************************************************************/
    +
     struct ieee802154_beaconnotify_ind_s
     {
       uint8_t bsn;        /* Beacon sequence number */
    @@ -700,231 +889,522 @@ struct ieee802154_beaconnotify_ind_s
       (sizeof(struct ieee802154_beaconnotify_ind_s) \
       - IEEE802154_MAX_BEACON_PAYLOAD_LENGTH + (n))
     
    -/* IOCTL data arguments *****************************************************/
    +/*****************************************************************************
    + * Primitive: MLME-COMM-STATUS.indication 
    + *
    + * Description:
    + *    Allows the MLME to indicate a communications status.
    + * 
    + *****************************************************************************/
    +
    +struct ieee802154_commstatus_ind_s
    +{
    +  struct ieee802154_addr_s src_addr;
    +  struct ieee802154_addr_s dest_addr;
    +  enum ieee802154_status_e status;
    +#ifdef CONFIG_IEEE802154_SECURITY
    +  /* Security information if enabled */
    +
    +  struct ieee802154_security_s security;
    +#endif
    +};
     
    -/* Data returned with MAC802154IOC_MLME_ASSOC_RESPONSE */
    +/*****************************************************************************
    + * Primitive: MLME-GET.request 
    + *
    + * Description:
    + *    Requests information about a given PIB attribute.
    + * 
    + *****************************************************************************/
     
    -struct ieee802154_assocresp_s
    +struct ieee802154_get_req_s
     {
    -  uint8_t eadr;
    -  uint16_t saddr;
    -  int status;
    +  enum ieee802154_pib_attr_e pib_attr;
     };
     
    -/* Data provided to MAC802154IOC_MLME_GET_REQUEST */
    +/*****************************************************************************
    + * Primitive: MLME-GET.confirm 
    + *
    + * Description:
    + *    Reports the results of an information request from the PIB.
    + * 
    + *****************************************************************************/
     
    -struct ieee802154_getreq_s
    +struct ieee802154_get_conf_s
     {
    -  enum ieee802154_pib_attr_e attr;
    +  enum ieee802154_status_e status;
    +  enum ieee802154_pib_attr_e pib_attr;
    +  union ieee802154_attr_val_u attr_value;
     };
     
    -/* Data provided to MAC802154IOC_MLME_GTS_REQUEST */
    +/*****************************************************************************
    + * Primitive: MLME-GTS.request
    + *
    + * Description:
    + *    Allows a device to send a request to the PAN coordinator to allocate a new
    + *    GTS or to deallocate an existing GTS. This primitive is also used by the
    + *    PAN coordinator to initiate a GTS deallocation.
    + * 
    + *****************************************************************************/
     
    -struct ieee802154_gtsreq_s
    +struct ieee802154_gts_req_s
     {
    -  uint8_t characteristics;
    +  struct ieee802154_gts_info_s gts_info;
    +
    +#ifdef CONFIG_IEEE802154_SECURITY
    +  /* Security information if enabled */
    +
    +  struct ieee802154_security_s security;
    +#endif
     };
     
    -/* Data returned with MAC802154IOC_MLME_ORPHAN_RESPONSE */
    +/*****************************************************************************
    + * Primitive: MLME-GTS.confirm
    + *
    + * Description:
    + *    Reports the results of a request to allocate a new GTS or to deallocate an
    + *    existing GTS.
    + * 
    + *****************************************************************************/
     
    -struct ieee802154_orphanresp_s
    +struct ieee802154_gts_conf_s
     {
    -  uint8_t orphanaddr[MAX_ORPHAN_ADDR];
    -  uint16_t saddr;
    -  bool associated;
    +  struct ieee802154_gts_info_s gts_info;
    +  enum ieee802154_status_e status;
     };
     
    -/* Data provided with MAC802154IOC_MLME_RESET_REQUEST */
    +/*****************************************************************************
    + * Primitive: MLME-GTS.indication
    + *
    + * Description:
    + *    Indicates that a GTS has been allocated or that a previously allocated
    + *    GTS has been deallocated.
    + * 
    + *****************************************************************************/
     
    -struct ieee802154_resetreq_s
    +struct ieee802154_gts_ind_s
     {
    -  bool setdefaults;
    +  uint16_t dev_addr;
    +  struct ieee802154_gts_info_s gts_info;
    +#ifdef CONFIG_IEEE802154_SECURITY
    +  /* Security information if enabled */
    +
    +  struct ieee802154_security_s security;
    +#endif
     };
     
    -/* Data provided with MAC802154IOC_MLME_RXENABLE_REQUEST */
    +/*****************************************************************************
    + * Primitive: MLME-ORPHAN.indication
    + *
    + * Description:
    + *    Generated by the MLME of a coordinator and issued to its next higher layer
    + *    on receipt of an orphan notification command.
    + * 
    + *****************************************************************************/
     
    -struct ieee802154_rxenabreq_s
    +struct ieee802154_orphan_ind_s
     {
    -  bool deferrable;
    -  int ontime;
    -  int duration;
    +  uint8_t orphan_addr[8];
    +#ifdef CONFIG_IEEE802154_SECURITY
    +  /* Security information if enabled */
    +
    +  struct ieee802154_security_s security;
    +#endif
     };
     
    -/* Data provided with MAC802154IOC_MLME_SCAN_REQUEST */
    +/*****************************************************************************
    + * Primitive: MLME-ORPHAN.response
    + *
    + * Description:
    + *    Allows the next higher layer of a coordinator to respond to the
    + *    MLME-ORPHAN.indication primitive.
    + * 
    + *****************************************************************************/
     
    -struct ieee802154_scanreq_s
    +struct ieee802154_orphan_resp_s
     {
    -  uint8_t type;
    -  uint32_t channels;
    -  int duration;
    +  uint8_t orphan_addr[8];
    +#ifdef CONFIG_IEEE802154_SECURITY
    +  /* Security information if enabled */
    +
    +  struct ieee802154_security_s security;
    +#endif
     };
     
    -/* Data provided with MAC802154IOC_MLME_SET_REQUEST */
    +/*****************************************************************************
    + * Primitive: MLME-RESET.request
    + *
    + * Description:
    + *    Used by the next higher layer to request that the MLME performs a reset
    + *    operation.
    + * 
    + *****************************************************************************/
     
    -struct ieee802154_setreq_s
    +struct ieee802154_reset_req_s
     {
    -  FAR uint8_t *value;
    -  int valuelen;
    -  int attribute;
    +  bool rst_pibattr;
     };
     
    -/* Data provided with MAC802154IOC_MLME_START_REQUEST */
    +/*****************************************************************************
    + * Primitive: MLME-RESET.confirm
    + *
    + * Description:
    + *    Reports the results of the reset operation.
    + * 
    + *****************************************************************************/
     
    -struct ieee802154_startreq_s
    +struct ieee802154_reset_conf_s
     {
    -  int channel;
    -  uint16_t panid;
    -  uint8_t bo;
    -  uint8_t fo;
    -  bool coord;
    -  bool batext;
    -  bool realign;
    +  enum ieee802154_status_e status;
     };
     
    -/* Data provided with MAC802154IOC_MLME_SYNC_REQUEST */
    +/*****************************************************************************
    + * Primitive: MLME-RXENABLE.request
    + *
    + * Description:
    + *    Allows the next higher layer to request that the receiver is either
    + *    enabled for a finite period of time or disabled.
    + * 
    + *****************************************************************************/
     
    -struct ieee802154_syncreq_s
    +struct ieee802154_rxenable_req_s
     {
    -  int channel;
    -  bool track;
    +  /* Number of symbols measured from the start of the superframe before the
    +   * receiver is to be enabled or disabled. */
    +
    +  uint32_t rxon_time;        
    +
    +  /* Number of symbols for which the receiver is to be enabled */
    +
    +  uint32_t rxon_dur;
    +
    +  uint8_t defer_permit  : 1; /* 0=Only attempt operation on current superframe
    +                              * 1=Operation can be deferred to next superframe */
    +  uint8_t rng_rxctrl    : 1; /* 0=RANGING_OFF, 1=RANGING_OFF */
     };
     
    -/* Data provided with MAC802154IOC_MLME_POLL_REQUEST */
    +/*****************************************************************************
    + * Primitive: MLME-RXENABLE.confirm
    + *
    + * Description:
    + *    Reports the results of the attempt to enable or disable the receiver.
    + * 
    + *****************************************************************************/
     
    -struct ieee802154_pollreq_s
    +struct ieee802154_rxenable_conf_s
     {
    -  FAR uint8_t *coordaddr;
    +  enum ieee802154_status_e status;
     };
     
    -/* A pointer to this structure is passed as the argument of each IOCTL
    - * command.
    - */
    +/*****************************************************************************
    + * Primitive: MLME-SCAN.request
    + *
    + * Description:
    + *    Used to initiate a channel scan over a given list of channels.
    + * 
    + *****************************************************************************/
     
    -union ieee802154_macarg_u
    +struct ieee802154_scan_req_s
     {
    -  struct ieee802154_assoc_req_s    assocreq;    /* MAC802154IOC_MLME_ASSOC_REQUEST */
    -  struct ieee802154_assocresp_s    assocresp;   /* MAC802154IOC_MLME_ASSOC_RESPONSE */
    -  struct ieee802154_disassoc_req_s disassocreq; /* MAC802154IOC_MLME_DISASSOC_REQUEST */
    -  struct ieee802154_getreq_s       getreq;      /* MAC802154IOC_MLME_GET_REQUEST */
    -  struct ieee802154_gtsreq_s       gtsreq;      /* MAC802154IOC_MLME_GTS_REQUEST */
    -  struct ieee802154_orphanresp_s   orphanresp;  /* MAC802154IOC_MLME_ORPHAN_RESPONSE */
    -  struct ieee802154_resetreq_s     resetreq;    /* MAC802154IOC_MLME_RESET_REQUEST */
    -  struct ieee802154_rxenabreq_s    rxenabreq;   /* MAC802154IOC_MLME_RXENABLE_REQUEST */
    -  struct ieee802154_scanreq_s      scanreq;     /* MAC802154IOC_MLME_SCAN_REQUEST */
    -  struct ieee802154_setreq_s       setreq;      /* MAC802154IOC_MLME_SET_REQUEST */
    -  struct ieee802154_startreq_s     startreq;    /* MAC802154IOC_MLME_START_REQUEST */
    -  struct ieee802154_syncreq_s      syncreq;     /* MAC802154IOC_MLME_SYNC_REQUEST */
    -  struct ieee802154_pollreq_s      pollreq;     /* MAC802154IOC_MLME_POLL_REQUEST */
    -  /* To be determined */                        /* MAC802154IOC_MLME_DPS_REQUEST */
    -  /* To be determined */                        /* MAC802154IOC_MLME_SOUNDING_REQUEST */
    -  /* To be determined */                        /* MAC802154IOC_MLME_CALIBRATE_REQUEST */
    +
    +  enum ieee802154_scantype_e type;
    +  uint8_t duration;
    +  uint8_t ch_page;
    +
    +#ifdef CONFIG_IEEE802154_SECURITY
    +  /* Security information if enabled */
    +
    +  struct ieee802154_security_s security;
    +#endif
    +
    +  uint8_t channels[1];
     };
     
    -#ifdef CONFIG_NET_6LOWPAN
    -/* For the case of network IOCTLs, the network IOCTL to the MAC network
    - * driver will include a device name like "wpan0" as the destination of
    - * the IOCTL command.
    - */
    +#define SIZEOF_IEEE802154_SCAN_REQ_S(n) \
    +  (sizeof(struct ieee802154_scan_req_s) + (n) - 1)
     
    -struct ieee802154_netmac_s
    +/*****************************************************************************
    + * Primitive: MLME-SCAN.confirm
    + *
    + * Description:
    + *    Reports the result of the channel scan request.
    + * 
    + *****************************************************************************/
    +
    +struct ieee802154_scan_conf_s
     {
    -  char ifr_name[IFNAMSIZ];     /* Interface name, e.g. "wpan0" */
    -  union ieee802154_macarg_u u; /* Data payload */
    +  enum ieee802154_status_e status;
    +  enum ieee802154_scantype_e type;
    +  uint8_t ch_page;
    +  uint8_t num_channels;
    +
    +#warning Figure out how to handle missing primitive semantics. See standard.
     };
    -#endif
     
    -/* This is an opaque reference to the MAC's internal private state.  It is
    - * returned by mac802154_create() when it is created.  It may then be used
    - * at other interfaces in order to interact with the MAC.
    - */
    +/*****************************************************************************
    + * Primitive: MLME-SET.request
    + *
    + * Description:
    + *    Attempts to write the given value to the indicated PIB attribute.
    + * 
    + *****************************************************************************/
     
    -typedef FAR void *MACHANDLE;
    +struct ieee802154_set_req_s
    +{
    +  enum ieee802154_pib_attr_e pib_attr;
    +  union ieee802154_attr_val_u attr_value;
    +};
     
    -/* Notifications */
    +/*****************************************************************************
    + * Primitive: MLME-SET.confirm
    + *
    + * Description:
    + *    Reports the results of an attempt to write a value to a PIB attribute.
    + * 
    + *****************************************************************************/
     
    -struct ieee802154_maccb_s
    +struct ieee802154_set_conf_s
     {
    -  /* Asynchronous confirmations to requests */
    +  enum ieee802154_status_e status;
    +  enum ieee802154_pib_attr_e pib_attr;
    +};
     
    -  /* Data frame was received by remote device */
    +/*****************************************************************************
    + * Primitive: MLME-START.request
    + *
    + * Description:
    + *    Used by the PAN coordinator to initiate a new PAN or to begin using a new
    + *    superframe configuration. This primitive is also used by a device already
    + *    associated with an existing PAN to begin using a new superframe
    + *    configuration.
    + * 
    + *****************************************************************************/
     
    -  CODE void (*conf_data)(MACHANDLE mac,
    -                         FAR struct ieee802154_data_conf_s *conf);
    +struct ieee802154_start_req_s
    +{
    +  uint16_t pan_id;
    +  uint8_t ch_num;
    +  uint8_t ch_page;
     
    -  /* Data frame was purged */
    +  uint32_t start_time   : 24; 
    +  uint32_t beacon_order : 8;
     
    -  CODE void (*conf_purge)(MACHANDLE mac, uint8_t handle, int status);
    +  uint8_t sf_order;
     
    -  /* Association request completed */
    +  uint8_t pan_coord     : 1;
    +  uint8_t batt_life_ext : 1;
    +  uint8_t coord_realign : 1;
     
    -  CODE void (*conf_associate)(MACHANDLE mac, uint16_t saddr, int status);
    +#ifdef CONFIG_IEEE802154_SECURITY
    +  /* Security information if enabled */
     
    -  /* Disassociation request completed */
    +  struct ieee802154_security_s coord_realign;
    +  struct ieee802154_security_s beacon;
    +#endif
    +};
     
    -  CODE void (*conf_disassociate)(MACHANDLE mac, int status);
    +/*****************************************************************************
    + * Primitive: MLME-START.confirm
    + *
    + * Description:
    + *    Reports the results of the attempt to start using a new superframe
    + *    configuration.
    + * 
    + *****************************************************************************/
     
    -  /* PIB data returned */
    +struct ieee802154_start_conf_s
    +{
    +  enum ieee802154_status_e status;
    +};
     
    -  CODE void (*conf_get)(MACHANDLE mac, int status, int attribute,
    -                        FAR uint8_t *value, int valuelen);
    +/*****************************************************************************
    + * Primitive: MLME-SYNC.request
    + *
    + * Description:
    + *    Requests to synchronize with the coordinator by acquiring and, if
    + *    specified, tracking its beacons.
    + * 
    + *****************************************************************************/
     
    -  /* GTS management completed */
    +struct ieee802154_sync_req_s
    +{
    +  uint8_t ch_num;
    +  uint8_t ch_page;
    +  bool track_beacon;
    +};
     
    -  CODE void (*conf_gts)(MACHANDLE mac, FAR uint8_t *characteristics,
    -                        int status);
    +/*****************************************************************************
    + * Primitive: MLME-SYNC-LOSS.indication
    + *
    + * Description:
    + *    Indicates the loss of synchronization with a coordinator.
    + * 
    + *****************************************************************************/
     
    -  /* MAC reset completed */
    +struct ieee802154_syncloss_ind_s
    +{
    +  enum ieee802154_status_e loss_reason;
    +  uint16_t pan_id;
    +  uint8_t ch_num;
    +  uint8_t ch_page;
     
    -  CODE void (*conf_reset)(MACHANDLE mac, int status);
    +#ifdef CONFIG_IEEE802154_SECURITY
    +  /* Security information if enabled */
     
    -  CODE void (*conf_rxenable)(MACHANDLE mac, int status);
    +  struct ieee802154_security_s security;
    +#endif
    +};
     
    -  CODE void (*conf_scan)(MACHANDLE mac, int status, uint8_t type,
    -                         uint32_t unscanned, int rsltsize,
    -                         FAR uint8_t *edlist, FAR uint8_t *pandescs);
    +/*****************************************************************************
    + * Primitive: MLME-POLL.request
    + *
    + * Description:
    + *    Prompts the device to request data from the coordinator. 
    + * 
    + *****************************************************************************/
     
    -  CODE void (*conf_set)(MACHANDLE mac, int status, int attribute);
    +struct ieee802154_poll_req_s
    +{
    +  struct ieee802154_addr_s coord_addr;
     
    -  CODE void (*conf_start)(MACHANDLE mac, int status);
    +#ifdef CONFIG_IEEE802154_SECURITY
    +  /* Security information if enabled */
     
    -  CODE void (*conf_poll)(MACHANDLE mac, int status);
    +  struct ieee802154_security_s security;
    +#endif
    +};
     
    -  /* Asynchronous event indications, replied to synchronously with responses */
    +/*****************************************************************************
    + * Primitive: MLME-POLL.confirm
    + *
    + * Description:
    + *    Reports the results of a request to poll the coordinator for data.
    + * 
    + *****************************************************************************/
     
    -  /* Data frame received */
    +struct ieee802154_poll_conf_s
    +{
    +  enum ieee802154_status_e status;
    +};
     
    -  CODE void (*ind_data)(MACHANDLE mac, FAR uint8_t *buf, int len);
    +/* A pointer to this structure is passed as the argument of each IOCTL
    + * command.
    + */
     
    -  /* Association request received */
    +union ieee802154_macarg_u
    +{
    +  struct ieee802154_assoc_req_s    assocreq;    /* MAC802154IOC_MLME_ASSOC_REQUEST */
    +  struct ieee802154_assoc_resp_s   assocresp;   /* MAC802154IOC_MLME_ASSOC_RESPONSE */
    +  struct ieee802154_disassoc_req_s disassocreq; /* MAC802154IOC_MLME_DISASSOC_REQUEST */
    +  struct ieee802154_get_req_s      getreq;      /* MAC802154IOC_MLME_GET_REQUEST */
    +  struct ieee802154_gts_req_s      gtsreq;      /* MAC802154IOC_MLME_GTS_REQUEST */
    +  struct ieee802154_orphan_resp_s  orphanresp;  /* MAC802154IOC_MLME_ORPHAN_RESPONSE */
    +  struct ieee802154_reset_req_s    resetreq;    /* MAC802154IOC_MLME_RESET_REQUEST */
    +  struct ieee802154_rxenable_req_s rxenabreq;   /* MAC802154IOC_MLME_RXENABLE_REQUEST */
    +  struct ieee802154_scan_req_s     scanreq;     /* MAC802154IOC_MLME_SCAN_REQUEST */
    +  struct ieee802154_set_req_s      setreq;      /* MAC802154IOC_MLME_SET_REQUEST */
    +  struct ieee802154_start_req_s    startreq;    /* MAC802154IOC_MLME_START_REQUEST */
    +  struct ieee802154_sync_req_s     syncreq;     /* MAC802154IOC_MLME_SYNC_REQUEST */
    +  struct ieee802154_poll_req_s     pollreq;     /* MAC802154IOC_MLME_POLL_REQUEST */
    +  /* To be determined */                        /* MAC802154IOC_MLME_DPS_REQUEST */
    +  /* To be determined */                        /* MAC802154IOC_MLME_SOUNDING_REQUEST */
    +  /* To be determined */                        /* MAC802154IOC_MLME_CALIBRATE_REQUEST */
    +};
     
    -  CODE void (*ind_associate)(MACHANDLE mac, uint16_t clipanid,
    -                             FAR uint8_t *clieaddr);
    +union ieee802154_mlme_notify_u
    +{
    +  struct ieee802154_assoc_conf_s       assocconf;
    +  struct ieee802154_disassoc_conf_s    disassocconf;
    +  struct ieee802154_get_conf_s         getconf;
    +  struct ieee802154_gts_conf_s         gtsconf;
    +  struct ieee802154_reset_conf_s       resetconf;
    +  struct ieee802154_rxenable_conf_s    rxenableconf;
    +  struct ieee802154_scan_conf_s        scanconf;
    +  struct ieee802154_set_conf_s         setconf;
    +  struct ieee802154_start_conf_s       startconf;
    +  struct ieee802154_poll_conf_s        pollconf;
    +
    +  struct ieee802154_assoc_ind_s        assocind;
    +  struct ieee802154_disassoc_ind_s     disassocind;
    +  struct ieee802154_beaconnotify_ind_s beaconnotifyind;
    +  struct ieee802154_gts_ind_s          gtsind;
    +  struct ieee802154_orphan_ind_s       orphanind;
    +  struct ieee802154_commstatus_ind_s   commstatusind;
    +  struct ieee802154_syncloss_ind_s     synclossind;
    +};
     
    -   /* Disassociation request received */
    +union ieee802154_mcps_notify_u
    +{
    +  struct ieee802154_data_conf_s        dataconf;
    +  struct ieee802154_purge_conf_s       purgeconf;
    +  struct ieee802154_data_ind_s         dataind;
    +};
     
    -  CODE void (*ind_disassociate)(MACHANDLE mac, FAR uint8_t *eadr,
    -                                uint8_t reason);
    +#ifdef CONFIG_NET_6LOWPAN
    +/* For the case of network IOCTLs, the network IOCTL to the MAC network
    + * driver will include a device name like "wpan0" as the destination of
    + * the IOCTL command.
    + */
     
    -  /* Beacon notification */
    +struct ieee802154_netmac_s
    +{
    +  char ifr_name[IFNAMSIZ];     /* Interface name, e.g. "wpan0" */
    +  union ieee802154_macarg_u u; /* Data payload */
    +};
    +#endif
     
    -  CODE void (*ind_beaconnotify)(MACHANDLE mac, FAR uint8_t *bsn,
    -                                FAR struct ieee802154_pan_desc_s *pandesc,
    -                                FAR uint8_t *sdu, int sdulen);
    +/* This is an opaque reference to the MAC's internal private state.  It is
    + * returned by mac802154_create() when it is created.  It may then be used
    + * at other interfaces in order to interact with the MAC.
    + */
     
    -  /* GTS management request received */
    +typedef FAR void *MACHANDLE;
     
    -  CODE void (*ind_gts)(MACHANDLE mac, FAR uint8_t *devaddr,
    -                       FAR uint8_t *characteristics);
    +/* MAC Service Notifications */
     
    -  /* Orphan device detected */
    +enum ieee802154_macnotify_e
    +{
    +  /* MCPS Notifications */
    +
    +  IEEE802154_NOTIFY_CONF_DATA = 0x00,
    +  IEEE802154_NOTIFY_CONF_PURGE,
    +  IEEE802154_NOTIFY_IND_DATA,
    +
    +  /* MLME Notifications */
    +
    +  IEEE802154_NOTIFY_CONF_ASSOC,
    +  IEEE802154_NOTIFY_CONF_DISASSOC,
    +  IEEE802154_NOTIFY_CONF_GET,
    +  IEEE802154_NOTIFY_CONF_GTS,
    +  IEEE802154_NOTIFY_CONF_RESET,
    +  IEEE802154_NOTIFY_CONF_RXENABLE,
    +  IEEE802154_NOTIFY_CONF_SCAN,
    +  IEEE802154_NOTIFY_CONF_SET,
    +  IEEE802154_NOTIFY_CONF_START,
    +  IEEE802154_NOTIFY_CONF_POLL,
    +
    +  IEEE802154_NOTIFY_IND_ASSOC,
    +  IEEE802154_NOTIFY_IND_DISASSOC,
    +  IEEE802154_NOTIFY_IND_BEACONNOTIFY,
    +  IEEE802154_NOTIFY_IND_GTS,
    +  IEEE802154_NOTIFY_IND_ORPHAN,
    +  IEEE802154_NOTIFY_IND_COMMSTATUS,
    +  IEEE802154_NOTIFY_IND_SYNCLOSS
    +};
     
    -  CODE void (*ind_orphan)(MACHANDLE mac, FAR uint8_t *orphanaddr);
    +/* Callback operations to notify the next highest layer of various asynchronous
    + * events, usually triggered by some previous request or response invoked by the
    + * upper layer */
     
    -  CODE void (*ind_commstatus)(MACHANDLE mac, uint16_t panid,
    -                              FAR uint8_t *src, FAR uint8_t *dst,
    -                              int status);
    +struct ieee802154_maccb_s
    +{
    +  CODE void (*mlme_notify) (FAR struct ieee802154_maccb_s *maccb,
    +                            enum ieee802154_macnotify_e notif,
    +                            FAR union ieee802154_mlme_notify_u *arg);
     
    -  CODE void (*ind_syncloss)(MACHANDLE mac, int reason);
    +  CODE void (*mcps_notify) (FAR struct ieee802154_maccb_s *maccb,
    +                            enum ieee802154_macnotify_e notif,
    +                            FAR union ieee802154_mcps_notify_u *arg);
     };
     
     #ifdef __cplusplus
    diff --git a/wireless/ieee802154/mac802154_device.c b/wireless/ieee802154/mac802154_device.c
    index 8e9250a218..52a3e5b4e3 100644
    --- a/wireless/ieee802154/mac802154_device.c
    +++ b/wireless/ieee802154/mac802154_device.c
    @@ -96,10 +96,19 @@ struct mac802154dev_dwait_s
       FAR struct mac802154dev_dwait_s *mw_flink;
     };
     
    +struct mac802154dev_callback_s
    +{
    +  /* This holds the information visible to the MAC layer */
    +
    +  struct ieee802154_maccb_s mc_cb;     /* Interface understood by the MAC layer */
    +  FAR struct mac802154_devwrapper_s *mc_priv;    /* Our priv data */
    +};
    +
     struct mac802154_devwrapper_s
     {
    -  MACHANDLE md_mac;    /* Saved binding to the mac layer */
    -  sem_t md_exclsem;    /* Exclusive device access */
    +  MACHANDLE md_mac;                     /* Saved binding to the mac layer */
    +  struct mac802154dev_callback_s md_cb; /* Callback information */
    +  sem_t md_exclsem;                     /* Exclusive device access */
     
       /* The following is a singly linked list of open references to the
        * MAC device.
    @@ -139,6 +148,11 @@ static ssize_t mac802154dev_write(FAR struct file *filep,
     static int  mac802154dev_ioctl(FAR struct file *filep, int cmd,
                   unsigned long arg);
     
    +/* MAC callback helpers */
    +
    +static void mac802154dev_conf_data(FAR struct mac802154_devwrapper_s *dev,
    +                                   FAR struct ieee802154_data_conf_s *conf);
    +
     /****************************************************************************
      * Private Data
      ****************************************************************************/
    @@ -579,21 +593,54 @@ static int mac802154dev_ioctl(FAR struct file *filep, int cmd,
       return ret;
     }
     
    -void mac802154dev_conf_data(MACHANDLE mac,
    -                            FAR struct ieee802154_data_conf_s *conf)
    +static void mac802154dev_mlme_notify(FAR struct ieee802154_maccb_s *maccb,
    +                                     enum ieee802154_macnotify_e notif,
    +                                     FAR union ieee802154_mlme_notify_u *arg)
    +{
    +  FAR struct mac802154dev_callback_s *cb =
    +    (FAR struct mac802154dev_callback_s *)maccb;
    +  FAR struct mac802154_devwrapper_s *dev;
    +
    +  DEBUGASSERT(cb != NULL && cb->mc_priv != NULL);
    +  dev = cb->mc_priv;
    +
    +  switch (notif)
    +    {
    +#warning Handle MLME notifications
    +      default:
    +        break;
    +    }
    +}
    +
    +static void mac802154dev_mcps_notify(FAR struct ieee802154_maccb_s *maccb,
    +                                     enum ieee802154_macnotify_e notif,
    +                                     FAR union ieee802154_mcps_notify_u *arg)
    +{
    +  FAR struct mac802154dev_callback_s *cb =
    +    (FAR struct mac802154dev_callback_s *)maccb;
    +  FAR struct mac802154_devwrapper_s *dev;
    +
    +  DEBUGASSERT(cb != NULL && cb->mc_priv != NULL);
    +  dev = cb->mc_priv;
    +
    +  switch (notif)
    +    {
    +      case IEEE802154_NOTIFY_CONF_DATA:
    +        {
    +          mac802154dev_conf_data(dev, &arg->dataconf);
    +        }
    +        break;
    +      default:
    +        break;
    +    }
    +}
    +
    +static void mac802154dev_conf_data(FAR struct mac802154_devwrapper_s *dev,
    +                                   FAR struct ieee802154_data_conf_s *conf)
     {
    -  FAR struct mac802154_devwrapper_s *dev = 
    -    (FAR struct mac802154_devwrapper_s *)mac;
       FAR struct mac802154dev_dwait_s *curr;
       FAR struct mac802154dev_dwait_s *prev;
     
    -  /* Get the dev from the callback context.  This should have been set when
    -   * the char driver was registered.
    -   *
    -   * REVISIT: See mac802154_netdev.c
    -   */
    -#warning Missing logic
    -
       /* Get exclusive access to the driver structure.  We don't care about any
        * signals so if we see one, just go back to trying to get access again */
     
    @@ -676,6 +723,7 @@ void mac802154dev_conf_data(MACHANDLE mac,
     int mac802154dev_register(MACHANDLE mac, int minor)
     {
       FAR struct mac802154_devwrapper_s *dev;
    +  FAR struct ieee802154_maccb_s *maccb;
       char devname[DEVNAME_FMTLEN];
       int ret;
     
    @@ -692,11 +740,25 @@ int mac802154dev_register(MACHANDLE mac, int minor)
       sem_init(&dev->md_exclsem, 0, 1); /* Allow the device to be opened once
                                          * before blocking */
     
    -  /* Initialize the callbacks and bind them to the radio
    -   *
    -   * REVISIT: See mac802154_netdev.c
    -   */
    -#warning Missing logic
    +  /* Initialize the MAC callbacks */
    +
    +  dev->md_cb.mc_priv  = dev;
    +
    +  maccb               = &dev->md_cb.mc_cb;
    +  maccb->mlme_notify  = mac802154dev_mlme_notify;
    +  maccb->mcps_notify  = mac802154dev_mcps_notify;
    +
    +  /* Bind the callback structure */
    +
    +  ret = mac802154_bind(mac, maccb);
    +  if (ret < 0)
    +    {
    +      nerr("ERROR: Failed to bind the MAC callbacks: %d\n", ret);
    +
    +      /* Free memory and return the error */
    +      kmm_free(dev);
    +      return ret;
    +    }
     
       /* Create the character device name */
     
    diff --git a/wireless/ieee802154/mac802154_netdev.c b/wireless/ieee802154/mac802154_netdev.c
    index 8768c3ee74..7965578f38 100644
    --- a/wireless/ieee802154/mac802154_netdev.c
    +++ b/wireless/ieee802154/mac802154_netdev.c
    @@ -157,42 +157,60 @@ struct macnet_driver_s
      ****************************************************************************/
     
     /* IEE802.15.4 MAC callback functions ***************************************/
    +
    +static void macnet_mlme_notify(FAR struct ieee802154_maccb_s *maccb,
    +                               enum ieee802154_macnotify_e notif,
    +                               FAR union ieee802154_mlme_notify_u *arg);
    +
    +static void macnet_mcps_notify(FAR struct ieee802154_maccb_s *maccb,
    +                               enum ieee802154_macnotify_e notif,
    +                               FAR union ieee802154_mcps_notify_u *arg);
    +
     /* Asynchronous confirmations to requests */
     
    -static void macnet_conf_data(MACHANDLE mac,
    +static void macnet_conf_data(FAR struct macnet_driver_s *priv,
                  FAR struct ieee802154_data_conf_s *conf);
    -static void macnet_conf_purge(MACHANDLE mac, uint8_t handle, int status);
    -static void macnet_conf_associate(MACHANDLE mac, uint16_t saddr, int status);
    -static void macnet_conf_disassociate(MACHANDLE mac, int status);
    -static void macnet_conf_get(MACHANDLE mac, int status, int attribute,
    -             FAR uint8_t *value, int valuelen);
    -static void macnet_conf_gts(MACHANDLE mac, FAR uint8_t *characteristics,
    -             int status);
    -static void macnet_conf_reset(MACHANDLE mac, int status);
    -static void macnet_conf_rxenable(MACHANDLE mac, int status);
    -static void macnet_conf_scan(MACHANDLE mac, int status, uint8_t type,
    -             uint32_t unscanned, int rsltsize, FAR uint8_t *edlist,
    -             FAR uint8_t *pandescs);
    -static void macnet_conf_set(MACHANDLE mac, int status, int attribute);
    -static void macnet_conf_start(MACHANDLE mac, int status);
    -static void macnet_conf_poll(MACHANDLE mac, int status);
    +static void macnet_conf_purge(FAR struct macnet_driver_s *priv,
    +             FAR struct ieee802154_purge_conf_s *conf);
    +static void macnet_conf_associate(FAR struct macnet_driver_s *priv,
    +             FAR struct ieee802154_assoc_conf_s *conf);
    +static void macnet_conf_disassociate(FAR struct macnet_driver_s *priv,
    +             FAR struct ieee802154_disassoc_conf_s *conf);
    +static void macnet_conf_get(FAR struct macnet_driver_s *priv,
    +             FAR struct ieee802154_get_conf_s *conf);
    +static void macnet_conf_gts(FAR struct macnet_driver_s *priv,
    +             FAR struct ieee802154_gts_conf_s *conf);
    +static void macnet_conf_reset(FAR struct macnet_driver_s *priv,
    +             FAR struct ieee802154_reset_conf_s *conf); 
    +static void macnet_conf_rxenable(FAR struct macnet_driver_s *priv,
    +             FAR struct ieee802154_rxenable_conf_s *conf); 
    +static void macnet_conf_scan(FAR struct macnet_driver_s *priv,
    +             FAR struct ieee802154_scan_conf_s *conf); 
    +static void macnet_conf_set(FAR struct macnet_driver_s *priv,
    +             FAR struct ieee802154_set_conf_s *conf); 
    +static void macnet_conf_start(FAR struct macnet_driver_s *priv,
    +             FAR struct ieee802154_start_conf_s *conf); 
    +static void macnet_conf_poll(FAR struct macnet_driver_s *priv,
    +             FAR struct ieee802154_poll_conf_s *conf); 
     
       /* Asynchronous event indications, replied to synchronously with responses */
     
    -static void macnet_ind_data(MACHANDLE mac, FAR uint8_t *buf, int len);
    -static void macnet_ind_associate(MACHANDLE mac, uint16_t clipanid,
    -              FAR uint8_t *clieaddr);
    -static void macnet_ind_disassociate(MACHANDLE mac, FAR uint8_t *eadr,
    -              uint8_t reason);
    -static void macnet_ind_beaconnotify(MACHANDLE mac, FAR uint8_t *bsn,
    -              FAR struct ieee802154_pan_desc_s *pandesc, FAR uint8_t *sdu,
    -              int sdulen);
    -static void macnet_ind_gts(MACHANDLE mac, FAR uint8_t *devaddr,
    -              FAR uint8_t *characteristics);
    -static void macnet_ind_orphan(MACHANDLE mac, FAR uint8_t *orphanaddr);
    -static void macnet_ind_commstatus(MACHANDLE mac, uint16_t panid,
    -              FAR uint8_t *src, FAR uint8_t *dst, int status);
    -static void macnet_ind_syncloss(MACHANDLE mac, int reason);
    +static void macnet_ind_data(FAR struct macnet_driver_s *priv,
    +             FAR struct ieee802154_data_ind_s *conf); 
    +static void macnet_ind_associate(FAR struct macnet_driver_s *priv,
    +             FAR struct ieee802154_assoc_ind_s *conf); 
    +static void macnet_ind_disassociate(FAR struct macnet_driver_s *priv,
    +             FAR struct ieee802154_disassoc_ind_s *conf); 
    +static void macnet_ind_beaconnotify(FAR struct macnet_driver_s *priv,
    +             FAR struct ieee802154_beaconnotify_ind_s *conf); 
    +static void macnet_ind_gts(FAR struct macnet_driver_s *priv,
    +             FAR struct ieee802154_gts_ind_s *conf); 
    +static void macnet_ind_orphan(FAR struct macnet_driver_s *priv,
    +             FAR struct ieee802154_orphan_ind_s *conf); 
    +static void macnet_ind_commstatus(FAR struct macnet_driver_s *priv,
    +             FAR struct ieee802154_commstatus_ind_s *conf); 
    +static void macnet_ind_syncloss(FAR struct macnet_driver_s *priv,
    +             FAR struct ieee802154_syncloss_ind_s *conf); 
     
     /* Network interface support ************************************************/
     /* Common TX logic */
    @@ -244,6 +262,58 @@ static int  macnet_ioctl(FAR struct net_driver_s *dev, int cmd,
      * Private Functions
      ****************************************************************************/
     
    +static void macnet_mlme_notify(FAR struct ieee802154_maccb_s *maccb,
    +                               enum ieee802154_macnotify_e notif,
    +                               FAR union ieee802154_mlme_notify_u *arg)
    +{
    +  FAR struct macdev_callback_s *cb =
    +    (FAR struct macdev_callback_s *)maccb;
    +  FAR struct macnet_driver_s *priv;
    +
    +  DEBUGASSERT(cb != NULL && cb->mc_priv != NULL);
    +  priv = cb->mc_priv;
    +
    +  switch (notif)
    +    {
    +
    +      default:
    +        break;
    +    }
    +}
    +
    +static void macnet_mcps_notify(FAR struct ieee802154_maccb_s *maccb,
    +                               enum ieee802154_macnotify_e notif,
    +                               FAR union ieee802154_mcps_notify_u *arg)
    +{
    +  FAR struct macdev_callback_s *cb =
    +    (FAR struct macdev_callback_s *)maccb;
    +  FAR struct macdev_driver_s *priv;
    +
    +  DEBUGASSERT(cb != NULL && cb->mc_priv != NULL);
    +  priv = cb->mc_priv;
    +
    +  switch (notif)
    +    {
    +      case IEEE802154_NOTIFY_CONF_DATA:
    +        {
    +          macnet_conf_data(priv, &arg->dataconf);
    +        }
    +        break;
    +      case IEEE802154_NOTIFY_CONF_PURGE:
    +        {
    +          macnet_conf_purge(priv, &arg->purgeconf);
    +        }
    +        break;
    +      case IEEE802154_NOTIFY_IND_DATA:
    +        {
    +          macnet_ind_data(priv, &arg->dataind);
    +        }
    +        break;
    +      default:
    +        break;
    +    }
    +}
    +
     /****************************************************************************
      * Name: macnet_conf_data
      *
    @@ -252,14 +322,10 @@ static int  macnet_ioctl(FAR struct net_driver_s *dev, int cmd,
      *
      ****************************************************************************/
     
    -static void macnet_conf_data(MACHANDLE mac,
    +static void macnet_conf_data(FAR struct macnet_driver_s *priv,
                                  FAR struct ieee802154_data_conf_s *conf)
     {
    -  FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac;
    -  FAR struct macnet_driver_s *priv;
     
    -  DEBUGASSERT(cb != NULL && cb->mc_priv != NULL);
    -  priv = cb->mc_priv;
     }
     
     /****************************************************************************
    @@ -270,13 +336,10 @@ static void macnet_conf_data(MACHANDLE mac,
      *
      ****************************************************************************/
     
    -static void macnet_conf_purge(MACHANDLE mac, uint8_t handle, int status)
    +static void macnet_conf_purge(FAR struct macnet_driver_s *priv,
    +                             FAR struct ieee802154_purge_conf_s *conf)
     {
    -  FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac;
    -  FAR struct macnet_driver_s *priv;
     
    -  DEBUGASSERT(cb != NULL && cb->mc_priv != NULL);
    -  priv = cb->mc_priv;
     }
     
     /****************************************************************************
    @@ -287,13 +350,10 @@ static void macnet_conf_purge(MACHANDLE mac, uint8_t handle, int status)
      *
      ****************************************************************************/
     
    -static void macnet_conf_associate(MACHANDLE mac, uint16_t saddr, int status)
    +static void macnet_conf_associate(FAR struct macnet_driver_s *priv,
    +                                  FAR struct ieee802154_assoc_conf_s *conf)
     {
    -  FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac;
    -  FAR struct macnet_driver_s *priv;
     
    -  DEBUGASSERT(cb != NULL && cb->mc_priv != NULL);
    -  priv = cb->mc_priv;
     }
     
     /****************************************************************************
    @@ -304,66 +364,52 @@ static void macnet_conf_associate(MACHANDLE mac, uint16_t saddr, int status)
      *
      ****************************************************************************/
     
    -static void macnet_conf_disassociate(MACHANDLE mac, int status)
    +static void macnet_conf_disassociate(FAR struct macnet_driver_s *priv,
    +                                     FAR struct ieee802154_disassoc_conf_s *conf)
     {
    -  FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac;
    -  FAR struct macnet_driver_s *priv;
     
    -  DEBUGASSERT(cb != NULL && cb->mc_priv != NULL);
    -  priv = cb->mc_priv;
     }
     
     /****************************************************************************
      * Name: macnet_conf_get
      *
      * Description:
    - *   PIvoata returned
    + *   PIB data returned
      *
      ****************************************************************************/
     
    -static void macnet_conf_get(MACHANDLE mac, int status, int attribute,
    -                            FAR uint8_t *value, int valuelen)
    +static void macnet_conf_get(FAR struct macnet_driver_s *priv,
    +                            FAR struct ieee802154_get_conf_s *conf)
     {
    -  FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac;
    -  FAR struct macnet_driver_s *priv;
     
    -  DEBUGASSERT(cb != NULL && cb->mc_priv != NULL);
    -  priv = cb->mc_priv;
     }
     
     /****************************************************************************
      * Name: macnet_conf_gts
      *
      * Description:
    - *   GTvoanagement completed
    + *   GTS management completed
      *
      ****************************************************************************/
     
    -static void macnet_conf_gts(MACHANDLE mac, FAR uint8_t *characteristics,
    -                            int status)
    +static void macnet_conf_gts(FAR struct macnet_driver_s *priv,
    +                            FAR struct ieee802154_gts_conf_s *conf)
     {
    -  FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac;
    -  FAR struct macnet_driver_s *priv;
     
    -  DEBUGASSERT(cb != NULL && cb->mc_priv != NULL);
    -  priv = cb->mc_priv;
     }
     
     /****************************************************************************
      * Name: macnet_conf_reset
      *
      * Description:
    - *   MAveset completed
    + *   MAC reset completed
      *
      ****************************************************************************/
     
    -static void macnet_conf_reset(MACHANDLE mac, int status)
    +static void macnet_conf_reset(FAR struct macnet_driver_s *priv,
    +                              FAR struct ieee802154_reset_conf_s *conf)
     {
    -  FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac;
    -  FAR struct macnet_driver_s *priv;
     
    -  DEBUGASSERT(cb != NULL && cb->mc_priv != NULL);
    -  priv = cb->mc_priv;
     }
     
     /****************************************************************************
    @@ -373,13 +419,10 @@ static void macnet_conf_reset(MACHANDLE mac, int status)
      *
      ****************************************************************************/
     
    -static void macnet_conf_rxenable(MACHANDLE mac, int status)
    +static void macnet_conf_rxenable(FAR struct macnet_driver_s *priv,
    +                                 FAR struct ieee802154_rxenable_conf_s *conf)
     {
    -  FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac;
    -  FAR struct macnet_driver_s *priv;
     
    -  DEBUGASSERT(cb != NULL && cb->mc_priv != NULL);
    -  priv = cb->mc_priv;
     }
     
     /****************************************************************************
    @@ -389,15 +432,10 @@ static void macnet_conf_rxenable(MACHANDLE mac, int status)
      *
      ****************************************************************************/
     
    -static void macnet_conf_scan(MACHANDLE mac, int status, uint8_t type,
    -                             uint32_t unscanned, int rsltsize,
    -                             FAR uint8_t *edlist, FAR uint8_t *pandescs)
    +static void macnet_conf_scan(FAR struct macnet_driver_s *priv,
    +                             FAR struct ieee802154_scan_conf_s *conf)
     {
    -  FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac;
    -  FAR struct macnet_driver_s *priv;
     
    -  DEBUGASSERT(cb != NULL && cb->mc_priv != NULL);
    -  priv = cb->mc_priv;
     }
     
     /****************************************************************************
    @@ -407,13 +445,10 @@ static void macnet_conf_scan(MACHANDLE mac, int status, uint8_t type,
      *
      ****************************************************************************/
     
    -static void macnet_conf_set(MACHANDLE mac, int status, int attribute)
    +static void macnet_conf_set(FAR struct macnet_driver_s *priv,
    +                            FAR struct ieee802154_set_conf_s *conf)
     {
    -  FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac;
    -  FAR struct macnet_driver_s *priv;
     
    -  DEBUGASSERT(cb != NULL && cb->mc_priv != NULL);
    -  priv = cb->mc_priv;
     }
     
     /****************************************************************************
    @@ -423,13 +458,10 @@ static void macnet_conf_set(MACHANDLE mac, int status, int attribute)
      *
      ****************************************************************************/
     
    -static void macnet_conf_start(MACHANDLE mac, int status)
    +static void macnet_conf_start(FAR struct macnet_driver_s *priv,
    +                              FAR struct ieee802154_start_conf_s *conf)
     {
    -  FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac;
    -  FAR struct macnet_driver_s *priv;
     
    -  DEBUGASSERT(cb != NULL && cb->mc_priv != NULL);
    -  priv = cb->mc_priv;
     }
     
     /****************************************************************************
    @@ -439,13 +471,10 @@ static void macnet_conf_start(MACHANDLE mac, int status)
      *
      ****************************************************************************/
     
    -static void macnet_conf_poll(MACHANDLE mac, int status)
    +static void macnet_conf_poll(FAR struct macnet_driver_s *priv,
    +                             FAR struct ieee802154_poll_conf_s *conf)
     {
    -  FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac;
    -  FAR struct macnet_driver_s *priv;
     
    -  DEBUGASSERT(cb != NULL && cb->mc_priv != NULL);
    -  priv = cb->mc_priv;
     }
     
     /****************************************************************************
    @@ -456,13 +485,10 @@ static void macnet_conf_poll(MACHANDLE mac, int status)
      *
      ****************************************************************************/
     
    -static void macnet_ind_data(MACHANDLE mac, FAR uint8_t *buf, int len)
    +static void macnet_ind_data(FAR struct macnet_driver_s *priv,
    +                            FAR struct ieee802154_data_ind_s *ind)
     {
    -  FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac;
    -  FAR struct macnet_driver_s *priv;
     
    -  DEBUGASSERT(cb != NULL && cb->mc_priv != NULL);
    -  priv = cb->mc_priv;
     }
     
     /****************************************************************************
    @@ -473,14 +499,10 @@ static void macnet_ind_data(MACHANDLE mac, FAR uint8_t *buf, int len)
      *
      ****************************************************************************/
     
    -static void macnet_ind_associate(MACHANDLE mac, uint16_t clipanid,
    -                                 FAR uint8_t *clieaddr)
    +static void macnet_ind_associate(FAR struct macnet_driver_s *priv,
    +                                 FAR struct ieee802154_assoc_ind_s *ind)
     {
    -  FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac;
    -  FAR struct macnet_driver_s *priv;
     
    -  DEBUGASSERT(cb != NULL && cb->mc_priv != NULL);
    -  priv = cb->mc_priv;
     }
     
     /****************************************************************************
    @@ -491,14 +513,10 @@ static void macnet_ind_associate(MACHANDLE mac, uint16_t clipanid,
      *
      ****************************************************************************/
     
    -static void macnet_ind_disassociate(MACHANDLE mac, FAR uint8_t *eadr,
    -                                    uint8_t reason)
    +static void macnet_ind_disassociate(FAR struct macnet_driver_s *priv,
    +                                    FAR struct ieee802154_disassoc_ind_s *ind)
     {
    -  FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac;
    -  FAR struct macnet_driver_s *priv;
     
    -  DEBUGASSERT(cb != NULL && cb->mc_priv != NULL);
    -  priv = cb->mc_priv;
     }
     
     /****************************************************************************
    @@ -509,15 +527,10 @@ static void macnet_ind_disassociate(MACHANDLE mac, FAR uint8_t *eadr,
      *
      ****************************************************************************/
     
    -static void macnet_ind_beaconnotify(MACHANDLE mac, FAR uint8_t *bsn,
    -                                    FAR struct ieee802154_pan_desc_s *pandesc,
    -                                    FAR uint8_t *sdu, int sdulen)
    +static void macnet_ind_beaconnotify(FAR struct macnet_driver_s *priv,
    +                                    FAR struct ieee802154_beaconnotify_ind_s *ind)
     {
    -  FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac;
    -  FAR struct macnet_driver_s *priv;
     
    -  DEBUGASSERT(cb != NULL && cb->mc_priv != NULL);
    -  priv = cb->mc_priv;
     }
     
     /****************************************************************************
    @@ -528,14 +541,10 @@ static void macnet_ind_beaconnotify(MACHANDLE mac, FAR uint8_t *bsn,
      *
      ****************************************************************************/
     
    -static void macnet_ind_gts(MACHANDLE mac, FAR uint8_t *devaddr,
    -                           FAR uint8_t *characteristics)
    +static void macnet_ind_gts(FAR struct macnet_driver_s *priv,
    +                           FAR struct ieee802154_gts_ind_s *ind)
     {
    -  FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac;
    -  FAR struct macnet_driver_s *priv;
     
    -  DEBUGASSERT(cb != NULL && cb->mc_priv != NULL);
    -  priv = cb->mc_priv;
     }
     
     /****************************************************************************
    @@ -546,13 +555,10 @@ static void macnet_ind_gts(MACHANDLE mac, FAR uint8_t *devaddr,
      *
      ****************************************************************************/
     
    -static void macnet_ind_orphan(MACHANDLE mac, FAR uint8_t *orphanaddr)
    +static void macnet_ind_orphan(FAR struct macnet_driver_s *priv,
    +                              FAR struct ieee802154_orphan_ind_s *ind)
     {
    -  FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac;
    -  FAR struct macnet_driver_s *priv;
     
    -  DEBUGASSERT(cb != NULL && cb->mc_priv != NULL);
    -  priv = cb->mc_priv;
     }
     
     /****************************************************************************
    @@ -562,15 +568,10 @@ static void macnet_ind_orphan(MACHANDLE mac, FAR uint8_t *orphanaddr)
      *
      ****************************************************************************/
     
    -static void macnet_ind_commstatus(MACHANDLE mac, uint16_t panid,
    -                                  FAR uint8_t *src, FAR uint8_t *dst,
    -                                  int status)
    +static void macnet_ind_commstatus(FAR struct macnet_driver_s *priv,
    +                                  FAR struct ieee802154_commstatus_ind_s *ind)
     {
    -  FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac;
    -  FAR struct macnet_driver_s *priv;
     
    -  DEBUGASSERT(cb != NULL && cb->mc_priv != NULL);
    -  priv = cb->mc_priv;
     }
     
     /****************************************************************************
    @@ -580,13 +581,10 @@ static void macnet_ind_commstatus(MACHANDLE mac, uint16_t panid,
      *
      ****************************************************************************/
     
    -static void macnet_ind_syncloss(MACHANDLE mac, int reason)
    +static void macnet_ind_syncloss(FAR struct macnet_driver_s *priv,
    +                                FAR struct ieee802154_syncloss_ind_s *ind)
     {
    -  FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)mac;
    -  FAR struct macnet_driver_s *priv;
     
    -  DEBUGASSERT(cb != NULL && cb->mc_priv != NULL);
    -  priv = cb->mc_priv;
     }
     
     /****************************************************************************
    @@ -1503,10 +1501,11 @@ int mac802154netdev_register(MACHANDLE mac)
     {
       FAR struct macnet_driver_s *priv;
       FAR struct net_driver_s *dev;
    +  FAR struct ieee802154_maccb_s *maccb;
       FAR uint8_t *pktbuf;
       int ret;
     
    -  DEBUGASSERT(radio != NULL);
    +  DEBUGASSERT(mac != NULL);
     
       /* Get the interface structure associated with this interface number. */
     
    @@ -1533,7 +1532,7 @@ int mac802154netdev_register(MACHANDLE mac)
     
       /* Initialize the driver structure */
     
    -  dev                = &ieee->md_dev.i_dev;
    +  dev                = &priv->md_dev.i_dev;
       dev->d_buf         = pktbuf;            /* Single packet buffer */
       dev->d_ifup        = macnet_ifup;       /* I/F up (new IP address) callback */
       dev->d_ifdown      = macnet_ifdown;     /* I/F down callback */
    @@ -1557,34 +1556,16 @@ int mac802154netdev_register(MACHANDLE mac)
     
       /* Initialize the MAC callbacks */
     
    -  priv->md_cb.mc_priv      = priv;
    -
    -  maccb                    = &priv->md_cb.mc_cb;
    -  maccb->conf_data         = macnet_conf_data;
    -  maccb->conf_purge        = macnet_conf_purge;
    -  maccb->conf_associate    = macnet_conf_associate;
    -  maccb->conf_disassociate = macnet_conf_disassociate;
    -  maccb->conf_get          = macnet_conf_get;
    -  maccb->conf_gts          = macnet_conf_gts;
    -  maccb->conf_reset        = macnet_conf_reset;
    -  maccb->conf_rxenable     = macnet_conf_rxenable;
    -  maccb->conf_scan         = macnet_conf_scan;
    -  maccb->conf_set          = macnet_conf_set;
    -  maccb->conf_start        = macnet_conf_start;
    -  maccb->conf_poll         = macnet_conf_poll;
    -  maccb->ind_data          = macnet_ind_data;
    -  maccb->ind_associate     = macnet_ind_associate;
    -  maccb->ind_disassociate  = macnet_ind_disassociate;
    -  maccb->ind_beaconnotify  = macnet_ind_beaconnotify;
    -  maccb->ind_gts           = macnet_ind_gts;
    -  maccb->ind_orphan        = macnet_ind_orphan;
    -  maccb->ind_commstatus    = macnet_ind_commstatus;
    -  maccb->ind_syncloss      = macnet_ind_syncloss;
    +  priv->md_cb.mc_priv = priv;
    +
    +  maccb               = &priv->md_cb.mc_cb;
    +  maccb->mlme_notify  = macdev_mlme_notify;       
    +  maccb->mcps_notify  = macdev_mcps_notify;       
     
       /* Bind the callback structure */
     
    -  ret = mac->ops->bind(mac, *priv->md_cb.mc_cb);
    -  if (ret < 0)
    +  ret = mac802154_bind(mac, maccb);
    +  if (ret < 0
         {
           nerr("ERROR: Failed to bind the MAC callbacks: %d\n", ret);
     
    @@ -1596,7 +1577,7 @@ int mac802154netdev_register(MACHANDLE mac)
           /* Free memory and return the error */
           kmm_free(pktbuf);
           kmm_free(priv);
    -      return ret
    +      return ret;
         }
     
       /* Put the interface in the down state. */
    diff --git a/wireless/ieee802154/radio802154_device.c b/wireless/ieee802154/radio802154_device.c
    index 15f4d1d84e..247570de8a 100644
    --- a/wireless/ieee802154/radio802154_device.c
    +++ b/wireless/ieee802154/radio802154_device.c
    @@ -346,6 +346,8 @@ static ssize_t radio802154dev_write(FAR struct file *filep,
        * Beacons and GTS transmission will be handled via IOCTLs
        */
     
    +#warning Fix this when transmit interface is complete
    +  /*
       ret = dev->child->ops->transmit(dev->child, packet);
       if (ret != packet->len)
         {
    @@ -357,6 +359,7 @@ static ssize_t radio802154dev_write(FAR struct file *filep,
         {
           wlerr("Radio Device timedout on Tx\n");
         }
    +  */
     
     done:
     
    -- 
    GitLab
    
    
    From dbafc0fc492b9a2df7611a8eeb2e62534cc1ebd5 Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Wed, 19 Apr 2017 09:53:32 -0600
    Subject: [PATCH 513/990] ieee802154: Purely cosmetic changes from review of
     last PR.
    
    ---
     .../wireless/ieee802154/ieee802154_mac.h      | 28 +++++++++++--------
     wireless/ieee802154/mac802154_netdev.c        | 17 +++++++++++
     wireless/ieee802154/radio802154_device.c      |  6 ++--
     3 files changed, 37 insertions(+), 14 deletions(-)
    
    diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h
    index 4bdbdde876..dfc5aa7696 100644
    --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h
    +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h
    @@ -394,15 +394,15 @@ enum ieee802154_ranging_e
     
     struct ieee802154_capability_info_s
     {
    -  uint8_t reserved_0 : 1;     /* Reserved */
    -  uint8_t device_type : 1;    /* 0=RFD, 1=FFD */
    -  uint8_t power_source : 1;   /* 1=AC, 0=Other */
    -  uint8_t rx_on_idle : 1;     /* 0=Receiver off when idle
    -                               * 1=Receiver on when idle */
    -  uint8_t reserved_45 : 2;    /* Reserved */
    -  uint8_t security : 1;       /* 0=disabled, 1=enabled */
    -  uint8_t allocate_addr : 1;  /* 1=Coordinator allocates short address
    -                               * 0=otherwise */
    +  uint8_t reserved_0        : 1;  /* Reserved */
    +  uint8_t device_type       : 1;  /* 0=RFD, 1=FFD */
    +  uint8_t power_source      : 1;  /* 1=AC, 0=Other */
    +  uint8_t rx_on_idle        : 1;  /* 0=Receiver off when idle
    +                                   * 1=Receiver on when idle */
    +  uint8_t reserved_45       : 2;  /* Reserved */
    +  uint8_t security          : 1;  /* 0=disabled, 1=enabled */
    +  uint8_t allocate_addr     : 1;  /* 1=Coordinator allocates short address
    +                                   * 0=otherwise */
     };
     
     struct ieee802154_superframe_spec_s
    @@ -902,6 +902,7 @@ struct ieee802154_commstatus_ind_s
       struct ieee802154_addr_s src_addr;
       struct ieee802154_addr_s dest_addr;
       enum ieee802154_status_e status;
    +
     #ifdef CONFIG_IEEE802154_SECURITY
       /* Security information if enabled */
     
    @@ -986,6 +987,7 @@ struct ieee802154_gts_ind_s
     {
       uint16_t dev_addr;
       struct ieee802154_gts_info_s gts_info;
    +
     #ifdef CONFIG_IEEE802154_SECURITY
       /* Security information if enabled */
     
    @@ -1005,6 +1007,7 @@ struct ieee802154_gts_ind_s
     struct ieee802154_orphan_ind_s
     {
       uint8_t orphan_addr[8];
    +
     #ifdef CONFIG_IEEE802154_SECURITY
       /* Security information if enabled */
     
    @@ -1024,6 +1027,7 @@ struct ieee802154_orphan_ind_s
     struct ieee802154_orphan_resp_s
     {
       uint8_t orphan_addr[8];
    +
     #ifdef CONFIG_IEEE802154_SECURITY
       /* Security information if enabled */
     
    @@ -1070,7 +1074,8 @@ struct ieee802154_reset_conf_s
     struct ieee802154_rxenable_req_s
     {
       /* Number of symbols measured from the start of the superframe before the
    -   * receiver is to be enabled or disabled. */
    +   * receiver is to be enabled or disabled.
    +   */
     
       uint32_t rxon_time;        
     
    @@ -1394,7 +1399,8 @@ enum ieee802154_macnotify_e
     
     /* Callback operations to notify the next highest layer of various asynchronous
      * events, usually triggered by some previous request or response invoked by the
    - * upper layer */
    + * upper layer.
    + */
     
     struct ieee802154_maccb_s
     {
    diff --git a/wireless/ieee802154/mac802154_netdev.c b/wireless/ieee802154/mac802154_netdev.c
    index 7965578f38..adc433aa65 100644
    --- a/wireless/ieee802154/mac802154_netdev.c
    +++ b/wireless/ieee802154/mac802154_netdev.c
    @@ -262,6 +262,13 @@ static int  macnet_ioctl(FAR struct net_driver_s *dev, int cmd,
      * Private Functions
      ****************************************************************************/
     
    +/****************************************************************************
    + * Name: macnet_mlme_notify
    + *
    + * Description:
    + *
    + ****************************************************************************/
    +
     static void macnet_mlme_notify(FAR struct ieee802154_maccb_s *maccb,
                                    enum ieee802154_macnotify_e notif,
                                    FAR union ieee802154_mlme_notify_u *arg)
    @@ -281,6 +288,13 @@ static void macnet_mlme_notify(FAR struct ieee802154_maccb_s *maccb,
         }
     }
     
    +/****************************************************************************
    + * Name: macnet_mcps_notify
    + *
    + * Description:
    + *
    + ****************************************************************************/
    +
     static void macnet_mcps_notify(FAR struct ieee802154_maccb_s *maccb,
                                    enum ieee802154_macnotify_e notif,
                                    FAR union ieee802154_mcps_notify_u *arg)
    @@ -299,16 +313,19 @@ static void macnet_mcps_notify(FAR struct ieee802154_maccb_s *maccb,
               macnet_conf_data(priv, &arg->dataconf);
             }
             break;
    +
           case IEEE802154_NOTIFY_CONF_PURGE:
             {
               macnet_conf_purge(priv, &arg->purgeconf);
             }
             break;
    +
           case IEEE802154_NOTIFY_IND_DATA:
             {
               macnet_ind_data(priv, &arg->dataind);
             }
             break;
    +
           default:
             break;
         }
    diff --git a/wireless/ieee802154/radio802154_device.c b/wireless/ieee802154/radio802154_device.c
    index 247570de8a..a1fe8dc515 100644
    --- a/wireless/ieee802154/radio802154_device.c
    +++ b/wireless/ieee802154/radio802154_device.c
    @@ -298,7 +298,7 @@ done:
      ****************************************************************************/
     
     static ssize_t radio802154dev_write(FAR struct file *filep,
    -                                   FAR const char *buffer, size_t len)
    +                                    FAR const char *buffer, size_t len)
     {
       FAR struct inode *inode;
       FAR struct radio802154_devwrapper_s *dev;
    @@ -347,7 +347,7 @@ static ssize_t radio802154dev_write(FAR struct file *filep,
        */
     
     #warning Fix this when transmit interface is complete
    -  /*
    +#if 0
       ret = dev->child->ops->transmit(dev->child, packet);
       if (ret != packet->len)
         {
    @@ -359,7 +359,7 @@ static ssize_t radio802154dev_write(FAR struct file *filep,
         {
           wlerr("Radio Device timedout on Tx\n");
         }
    -  */
    +#endif
     
     done:
     
    -- 
    GitLab
    
    
    From d3e1ea84f60556cd16440ced7601614532356ead Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Wed, 19 Apr 2017 11:19:40 -0600
    Subject: [PATCH 514/990] Update README
    
    ---
     configs/nucleo-f072rb/README.txt | 57 ++++++++++++++++++++++++++------
     1 file changed, 47 insertions(+), 10 deletions(-)
    
    diff --git a/configs/nucleo-f072rb/README.txt b/configs/nucleo-f072rb/README.txt
    index fb35cac2d3..033b7b7560 100644
    --- a/configs/nucleo-f072rb/README.txt
    +++ b/configs/nucleo-f072rb/README.txt
    @@ -267,18 +267,55 @@ Configurations
     
         NOTES:
     
    -    1. Support for NSH built-in applications is provided:
    +    1. This initial release of this configuration was very minimal, but
    +       also very small:
     
    -       Binary Formats:
    -         CONFIG_BUILTIN=y           : Enable support for built-in programs
    +       $ size nuttx
    +          text    data     bss     dec     hex filename
    +         32000      92    1172   33264    81f0 nuttx
     
    -       Application Configuration:
    -         CONFIG_NSH_BUILTIN_APPS=y  : Enable starting apps from NSH command line
    +       The current version, additional features have been enabled:  board
    +       bring-up initialization, button support, the procfs file system,
    +       and NSH built-in application support.  The size increased as follows:
     
    -       No built applications are enabled in the base configuration, however.
    +       $ size nuttx
    +          text    data     bss     dec     hex filename
    +         40231      92    1208   41531    a23b nuttx
     
    -    2. C++ support for applications is enabled:
    +       Those additional features cost about 8KiB FLASH.  I believe that is a
    +       good use of the STM32F072RB's FLASH, but if you interested in the
    +       more minimal configuration, here is what was changed:
     
    -      CONFIG_HAVE_CXX=y
    -      CONFIG_HAVE_CXXINITIALIZE=y
    -      CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y
    +       Removed
    +
    +         CONFIG_BINFMT_DISABLE=y
    +         CONFIG_DISABLE_MOUNTPOINT=y
    +         CONFIG_NSH_DISABLE_CD=y
    +
    +       Added:
    +
    +         CONFIG_ARCH_BUTTONS=y
    +         CONFIG_ARCH_IRQBUTTONS=y
    +
    +         CONFIG_BUILTIN=y
    +         CONFIG_BUILTIN_PROXY_STACKSIZE=1024
    +
    +         CONFIG_FS_PROCFS=y
    +         CONFIG_NSH_PROC_MOUNTPOINT="/proc"
    +
    +         CONFIG_LIB_BOARDCTL=y
    +         CONFIG_NSH_ARCHINIT=y
    +         CONFIG_NSH_BUILTIN_APPS=y
    +
    +       Support for NSH built-in applications is enabled for future use. 
    +       However, no built applications are enabled in this base configuration.
    +
    +    2. C++ support for applications is NOT enabled.  That could be enabled
    +       with the following configuration changes:
    +
    +         CONFIG_HAVE_CXX=y
    +         CONFIG_HAVE_CXXINITIALIZE=y
    +         CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y
    +
    +       And also support fo C++ constructors under
    +       apps/platform/nucleo-stm32f072rb.
    -- 
    GitLab
    
    
    From 395054113680660c7d074c3fb95ed05ea79f93d9 Mon Sep 17 00:00:00 2001
    From: Anthony Merlino 
    Date: Wed, 19 Apr 2017 12:56:43 -0400
    Subject: [PATCH 515/990] wireless/ieee802154: Renames mac802154_devwrapper_s
     to mac802154_chardevice_s
    
    ---
     wireless/ieee802154/mac802154_device.c | 36 ++++++++++++--------------
     1 file changed, 17 insertions(+), 19 deletions(-)
    
    diff --git a/wireless/ieee802154/mac802154_device.c b/wireless/ieee802154/mac802154_device.c
    index 52a3e5b4e3..3b7dc49309 100644
    --- a/wireless/ieee802154/mac802154_device.c
    +++ b/wireless/ieee802154/mac802154_device.c
    @@ -101,10 +101,10 @@ struct mac802154dev_callback_s
       /* This holds the information visible to the MAC layer */
     
       struct ieee802154_maccb_s mc_cb;     /* Interface understood by the MAC layer */
    -  FAR struct mac802154_devwrapper_s *mc_priv;    /* Our priv data */
    +  FAR struct mac802154_chardevice_s *mc_priv;    /* Our priv data */
     };
     
    -struct mac802154_devwrapper_s
    +struct mac802154_chardevice_s
     {
       MACHANDLE md_mac;                     /* Saved binding to the mac layer */
       struct mac802154dev_callback_s md_cb; /* Callback information */
    @@ -150,7 +150,7 @@ static int  mac802154dev_ioctl(FAR struct file *filep, int cmd,
     
     /* MAC callback helpers */
     
    -static void mac802154dev_conf_data(FAR struct mac802154_devwrapper_s *dev,
    +static void mac802154dev_conf_data(FAR struct mac802154_chardevice_s *dev,
                                        FAR struct ieee802154_data_conf_s *conf);
     
     /****************************************************************************
    @@ -212,7 +212,7 @@ static inline int mac802154dev_takesem(sem_t *sem)
     static int mac802154dev_open(FAR struct file *filep)
     {
       FAR struct inode *inode;
    -  FAR struct mac802154_devwrapper_s *dev;
    +  FAR struct mac802154_chardevice_s *dev;
       FAR struct mac802154dev_open_s *opriv;
       int ret;
     
    @@ -269,7 +269,7 @@ errout_with_sem:
     static int mac802154dev_close(FAR struct file *filep)
     {
       FAR struct inode *inode;
    -  FAR struct mac802154_devwrapper_s *dev;
    +  FAR struct mac802154_chardevice_s *dev;
       FAR struct mac802154dev_open_s *opriv;
       FAR struct mac802154dev_open_s *curr;
       FAR struct mac802154dev_open_s *prev;
    @@ -281,7 +281,7 @@ static int mac802154dev_close(FAR struct file *filep)
       opriv = filep->f_priv;
       inode = filep->f_inode;
       DEBUGASSERT(inode->i_private);
    -  dev = (FAR struct mac802154_devwrapper_s *)inode->i_private;
    +  dev = (FAR struct mac802154_chardevice_s *)inode->i_private;
     
       /* Handle an improbable race conditions with the following atomic test
        * and set.
    @@ -361,13 +361,13 @@ static ssize_t mac802154dev_read(FAR struct file *filep, FAR char *buffer,
                                      size_t len)
     {
       FAR struct inode *inode;
    -  FAR struct mac802154_devwrapper_s *dev;
    +  FAR struct mac802154_chardevice_s *dev;
       int ret;
     
       DEBUGASSERT(filep && filep->f_inode);
       inode = filep->f_inode;
       DEBUGASSERT(inode->i_private);
    -  dev = (FAR struct mac802154_devwrapper_s *)inode->i_private;
    +  dev = (FAR struct mac802154_chardevice_s *)inode->i_private;
     
       /* Check to make sure that the buffer is big enough to hold at least one
        * packet.
    @@ -408,7 +408,7 @@ static ssize_t mac802154dev_write(FAR struct file *filep,
                                       FAR const char *buffer, size_t len)
     {
       FAR struct inode *inode;
    -  FAR struct mac802154_devwrapper_s *dev;
    +  FAR struct mac802154_chardevice_s *dev;
       FAR struct ieee802154_data_req_s *req;
       struct mac802154dev_dwait_s dwait;
       int ret;
    @@ -416,7 +416,7 @@ static ssize_t mac802154dev_write(FAR struct file *filep,
       DEBUGASSERT(filep && filep->f_inode);
       inode = filep->f_inode;
       DEBUGASSERT(inode->i_private);
    -  dev  = (FAR struct mac802154_devwrapper_s *)inode->i_private;
    +  dev  = (FAR struct mac802154_chardevice_s *)inode->i_private;
     
       /* Check to make sure that the buffer is big enough to hold at least one
        * packet. */
    @@ -460,7 +460,6 @@ static ssize_t mac802154dev_write(FAR struct file *filep,
           dev->md_dwait = &dwait;
     
           mac802154dev_givesem(&dev->md_exclsem);
    -
       }
      
       /* Pass the request to the MAC layer */
    @@ -473,7 +472,6 @@ static ssize_t mac802154dev_write(FAR struct file *filep,
           return ret;
         }
     
    -
       if (!(filep->f_oflags & O_NONBLOCK))
         {
           /* Wait for the DATA.confirm callback to be called for our handle */
    @@ -509,14 +507,14 @@ static int mac802154dev_ioctl(FAR struct file *filep, int cmd,
                                        unsigned long arg)
     {
       FAR struct inode *inode;
    -  FAR struct mac802154_devwrapper_s *dev;
    +  FAR struct mac802154_chardevice_s *dev;
       int ret;
     
       DEBUGASSERT(filep != NULL && filep->f_priv != NULL &&
                   filep->f_inode != NULL);
       inode = filep->f_inode;
       DEBUGASSERT(inode->i_private);
    -  dev = (FAR struct mac802154_devwrapper_s *)inode->i_private;
    +  dev = (FAR struct mac802154_chardevice_s *)inode->i_private;
     
       /* Get exclusive access to the driver structure */
     
    @@ -599,7 +597,7 @@ static void mac802154dev_mlme_notify(FAR struct ieee802154_maccb_s *maccb,
     {
       FAR struct mac802154dev_callback_s *cb =
         (FAR struct mac802154dev_callback_s *)maccb;
    -  FAR struct mac802154_devwrapper_s *dev;
    +  FAR struct mac802154_chardevice_s *dev;
     
       DEBUGASSERT(cb != NULL && cb->mc_priv != NULL);
       dev = cb->mc_priv;
    @@ -618,7 +616,7 @@ static void mac802154dev_mcps_notify(FAR struct ieee802154_maccb_s *maccb,
     {
       FAR struct mac802154dev_callback_s *cb =
         (FAR struct mac802154dev_callback_s *)maccb;
    -  FAR struct mac802154_devwrapper_s *dev;
    +  FAR struct mac802154_chardevice_s *dev;
     
       DEBUGASSERT(cb != NULL && cb->mc_priv != NULL);
       dev = cb->mc_priv;
    @@ -635,7 +633,7 @@ static void mac802154dev_mcps_notify(FAR struct ieee802154_maccb_s *maccb,
         }
     }
     
    -static void mac802154dev_conf_data(FAR struct mac802154_devwrapper_s *dev,
    +static void mac802154dev_conf_data(FAR struct mac802154_chardevice_s *dev,
                                        FAR struct ieee802154_data_conf_s *conf)
     {
       FAR struct mac802154dev_dwait_s *curr;
    @@ -722,12 +720,12 @@ static void mac802154dev_conf_data(FAR struct mac802154_devwrapper_s *dev,
     
     int mac802154dev_register(MACHANDLE mac, int minor)
     {
    -  FAR struct mac802154_devwrapper_s *dev;
    +  FAR struct mac802154_chardevice_s *dev;
       FAR struct ieee802154_maccb_s *maccb;
       char devname[DEVNAME_FMTLEN];
       int ret;
     
    -  dev = kmm_zalloc(sizeof(struct mac802154_devwrapper_s));
    +  dev = kmm_zalloc(sizeof(struct mac802154_chardevice_s));
       if (!dev)
         {
           wlerr("ERROR: Failed to allocate device structure\n");
    -- 
    GitLab
    
    
    From 37e7c673733e7f2e3800320e708d07548bccf6e1 Mon Sep 17 00:00:00 2001
    From: Anthony Merlino 
    Date: Wed, 19 Apr 2017 13:26:30 -0400
    Subject: [PATCH 516/990] wireless/ieee802154: Changes radio interface to match
     MAC callback design
    
    ---
     drivers/wireless/ieee802154/mrf24j40.c        | 20 +++---
     .../wireless/ieee802154/ieee802154_radio.h    | 19 ++----
     wireless/ieee802154/mac802154.c               | 62 ++++++++++++++-----
     3 files changed, 57 insertions(+), 44 deletions(-)
    
    diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c
    index 1b00a67e15..b1c0c67218 100644
    --- a/drivers/wireless/ieee802154/mrf24j40.c
    +++ b/drivers/wireless/ieee802154/mrf24j40.c
    @@ -112,10 +112,7 @@ struct mrf24j40_txdesc_s
     struct mrf24j40_radio_s
     {
       struct ieee802154_radio_s radio;  /* The public device instance */
    -
    -  /* Reference to the bound upper layer via the phyif interface */
    -
    -  FAR struct ieee802154_phyif_s *phyif;      
    +  FAR struct ieee802154_radiocb_s *radiocb; /* Registered callbacks */      
     
       /* Low-level MCU-specific support */
     
    @@ -215,7 +212,7 @@ static int  mrf24j40_energydetect(FAR struct mrf24j40_radio_s *radio,
     /* Driver operations */
     
     static int  mrf24j40_bind(FAR struct ieee802154_radio_s *radio,
    -              FAR struct ieee802154_phyif_s *phyif);
    +              FAR struct ieee802154_radiocb_s *radiocb);
     static int  mrf24j40_ioctl(FAR struct ieee802154_radio_s *radio, int cmd,
                   unsigned long arg);
     static int  mrf24j40_rxenable(FAR struct ieee802154_radio_s *radio,
    @@ -250,12 +247,12 @@ static const struct ieee802154_radioops_s mrf24j40_devops =
      ****************************************************************************/
     
     static int mrf24j40_bind(FAR struct ieee802154_radio_s *radio,
    -                         FAR struct ieee802154_phyif_s *phyif)
    +                         FAR struct ieee802154_radiocb_s *radiocb)
     {
       FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)radio;
     
       DEBUGASSERT(dev != NULL);
    -  dev->phyif = phyif;
    +  dev->radiocb = radiocb;
       return OK;
     }
     
    @@ -335,9 +332,8 @@ static void mrf24j40_dopoll_csma(FAR void *arg)
         {
           /* need to somehow allow for a handle to be passed */
     
    -      ret = dev->phyif->ops->poll_csma(dev->phyif, 
    -                                       &dev->csma_desc.pub,
    -                                       &dev->tx_buf[0]);
    +      ret = dev->radiocb->poll_csma(dev->radiocb, &dev->csma_desc.pub,
    +                                    &dev->tx_buf[0]);
           if (ret > 0)
             {
               /* Now the txdesc is in use */
    @@ -431,8 +427,8 @@ static void mrf24j40_dopoll_gts(FAR void *arg)
         {
           if (!dev->gts_desc[gts].busy)
             {
    -          ret = dev->phyif->ops->poll_gts(dev->phyif, &dev->gts_desc[gts].pub,
    -                                          &dev->tx_buf[0]);
    +          ret = dev->radiocb->poll_gts(dev->radiocb, &dev->gts_desc[gts].pub,
    +                                       &dev->tx_buf[0]);
               if (ret > 0)
                 {
                   /* Now the txdesc is in use */
    diff --git a/include/nuttx/wireless/ieee802154/ieee802154_radio.h b/include/nuttx/wireless/ieee802154/ieee802154_radio.h
    index 638760f356..e1c0ff3aea 100644
    --- a/include/nuttx/wireless/ieee802154/ieee802154_radio.h
    +++ b/include/nuttx/wireless/ieee802154/ieee802154_radio.h
    @@ -167,31 +167,20 @@ struct ieee802154_txdesc_s
       /* TODO: Add slotting information for GTS transactions */
     };
     
    -struct ieee802154_phyif_s; /* Forward Reference */
    -
    -struct ieee802154_phyifops_s
    +struct ieee802154_radiocb_s
     {
    -  CODE int (*poll_csma) (FAR struct ieee802154_phyif_s *phyif,
    +  CODE int (*poll_csma) (FAR struct ieee802154_radiocb_s *radiocb,
                  FAR struct ieee802154_txdesc_s *tx_desc, FAR uint8_t *buf);
    -  CODE int (*poll_gts) (FAR struct ieee802154_phyif_s *phyif,
    +  CODE int (*poll_gts) (FAR struct ieee802154_radiocb_s *radiocb,
                  FAR struct ieee802154_txdesc_s *tx_desc, FAR uint8_t *buf);
     };
     
    -struct ieee802154_phyif_s
    -{
    -  FAR const struct ieee802154_phyifops_s *ops;
    -
    -  /* Driver-specific information */
    -
    -  FAR void * priv;
    -};
    -
     struct ieee802154_radio_s; /* Forward reference */
     
     struct ieee802154_radioops_s
     {
       CODE int (*bind) (FAR struct ieee802154_radio_s *radio,
    -             FAR struct ieee802154_phyif_s *phyif);
    +             FAR struct ieee802154_radiocb_s *radiocb);
       CODE int (*ioctl)(FAR struct ieee802154_radio_s *radio, int cmd,
                  unsigned long arg);
       CODE int (*rxenable)(FAR struct ieee802154_radio_s *radio, bool state,
    diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c
    index a23128820d..beec54f711 100644
    --- a/wireless/ieee802154/mac802154.c
    +++ b/wireless/ieee802154/mac802154.c
    @@ -86,6 +86,12 @@ struct mac802154_unsec_mhr_s
       } u;
     };
     
    +struct mac802154_radiocb_s
    +{
    +  struct ieee802154_radiocb_s cb;
    +  FAR struct ieee802154_privmac_s *priv;
    +};
    +
     /* The privmac structure holds the internal state of the MAC and is the
      * underlying represention of the opaque MACHANDLE.  It contains storage for
      * the IEEE802.15.4 MIB attributes.
    @@ -95,7 +101,7 @@ struct ieee802154_privmac_s
     {
       FAR struct ieee802154_radio_s *radio;     /* Contained IEEE802.15.4 radio dev */
       FAR const struct ieee802154_maccb_s *cb;  /* Contained MAC callbacks */
    -  FAR struct ieee802154_phyif_s phyif;      /* Interface to bind to radio */
    +  FAR struct mac802154_radiocb_s radiocb;   /* Interface to bind to radio */
     
       sem_t exclsem; /* Support exclusive access */
     
    @@ -244,11 +250,11 @@ static int mac802154_applymib(FAR struct ieee802154_privmac_s *priv);
     
     /* IEEE 802.15.4 PHY Interface OPs */
     
    -static int mac802154_poll_csma(FAR struct ieee802154_phyif_s *phyif,
    +static int mac802154_poll_csma(FAR struct ieee802154_radiocb_s *radiocb,
                                    FAR struct ieee802154_txdesc_s *tx_desc,
                                    FAR uint8_t *buf);
     
    -static int mac802154_poll_gts(FAR struct ieee802154_phyif_s *phyif, 
    +static int mac802154_poll_gts(FAR struct ieee802154_radiocb_s *radiocb, 
                                   FAR struct ieee802154_txdesc_s *tx_desc,
                                   FAR uint8_t *buf);
     
    @@ -256,11 +262,6 @@ static int mac802154_poll_gts(FAR struct ieee802154_phyif_s *phyif,
      * Private Data
      ****************************************************************************/
     
    -static const struct ieee802154_phyifops_s mac802154_phyifops =
    -{
    -  mac802154_poll_csma,
    -  mac802154_poll_gts
    -};
     
     /****************************************************************************
      * Private Functions
    @@ -351,6 +352,7 @@ static int mac802154_applymib(FAR struct ieee802154_privmac_s *priv)
     MACHANDLE mac802154_create(FAR struct ieee802154_radio_s *radiodev)
     {
       FAR struct ieee802154_privmac_s *mac;
    +  FAR struct ieee802154_radiocb_s *radiocb;
     
       /* Allocate object */
     
    @@ -369,12 +371,17 @@ MACHANDLE mac802154_create(FAR struct ieee802154_radio_s *radiodev)
       mac802154_defaultmib(mac);
       mac802154_applymib(mac);
     
    -  mac->phyif.ops = &mac802154_phyifops;
    -  mac->phyif.priv = mac;
    +  /* Initialize the Radio callbacks */
    +
    +  mac->radiocb.priv = mac;
     
    -  /* Bind our PHY interface to the radio */
    +  radiocb             = &mac->radiocb.cb;
    +  radiocb->poll_cmsa  = mac802154_poll_csma;
    +  radiocb->poll_gts   = mac802154_poll_gts;
     
    -  radiodev->ops->bind(radiodev, &mac->phyif);
    +  /* Bind our callback structure */
    +
    +  radiodev->ops->bind(radiodev, &mac->radiocb.cb);
     
       return (MACHANDLE)mac;
     }
    @@ -701,16 +708,18 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req)
     
     /* Called from interrupt level or worker thread with interrupts disabled */
     
    -static int mac802154_poll_csma(FAR struct ieee802154_phyif_s *phyif,
    +static int mac802154_poll_csma(FAR struct ieee802154_radiocb_s *radiocb,
                                    FAR struct ieee802154_txdesc_s *tx_desc,
                                    FAR uint8_t *buf)
     {
    -  FAR struct ieee802154_privmac_s *priv =
    -      (FAR struct ieee802154_privmac_s *)&phyif->priv;
    +  FAR struct mac802154_radiocb_s *cb =
    +    (FAR struct mac802154_radiocb_s *)radiocb;
    +  FAR struct ieee802154_privmac_s *priv;
       FAR struct mac802154_trans_s *trans;
       int ret = 0;
     
    -  DEBUGASSERT(priv != 0);
    +  DEBUGASSERT(cb != NULL && cb->priv != NULL);
    +  priv = cb->priv;
     
       /* Get exclusive access to the driver structure.  We don't care about any
        * signals so if we see one, just go back to trying to get access again.
    @@ -753,10 +762,29 @@ static int mac802154_poll_csma(FAR struct ieee802154_phyif_s *phyif,
       return ret;
     }
     
    -static int mac802154_poll_gts(FAR struct ieee802154_phyif_s *phyif, 
    +static int mac802154_poll_gts(FAR struct ieee802154_radiocb_s *radiocb, 
                                   FAR struct ieee802154_txdesc_s *tx_desc,
                                   FAR uint8_t *buf)
     {
    +  FAR struct mac802154_radiocb_s *cb =
    +    (FAR struct mac802154_radiocb_s *)radiocb;
    +  FAR struct ieee802154_privmac_s *priv;
    +  FAR struct mac802154_trans_s *trans;
    +  int ret = 0;
    +
    +  DEBUGASSERT(cb != NULL && cb->priv != NULL);
    +  priv = cb->priv;
    +
    +  /* Get exclusive access to the driver structure.  We don't care about any
    +   * signals so if we see one, just go back to trying to get access again.
    +   */
    +
    +  while (mac802154_takesem(&priv->exclsem) != 0);
    +
    +#warning Missing logic.
    +
    +  mac802154_givesem(&priv->exclsem);
    +
       return 0;
     }
     
    -- 
    GitLab
    
    
    From 3b5f350656aa658978eb0fcd8b6f73ed68d40ed1 Mon Sep 17 00:00:00 2001
    From: Anthony Merlino 
    Date: Wed, 19 Apr 2017 14:47:35 -0400
    Subject: [PATCH 517/990] wireless/ieee802154: Removes uneccessary structs
     surrounding bit-fields in mac802154.c
    
    ---
     wireless/ieee802154/mac802154.c | 72 +++++++++++++++++----------------
     1 file changed, 38 insertions(+), 34 deletions(-)
    
    diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c
    index beec54f711..ad702dc535 100644
    --- a/wireless/ieee802154/mac802154.c
    +++ b/wireless/ieee802154/mac802154.c
    @@ -185,27 +185,27 @@ struct ieee802154_privmac_s
     
       uint32_t tx_total_dur;
     
    -  struct
    -  {
    -    uint32_t is_assoc           : 1;  /* Are we associated to the PAN */
    -    uint32_t assoc_permit       : 1;  /* Are we allowing assoc. as a coord. */
    -    uint32_t auto_req           : 1;  /* Automatically send data req. if addr
    -                                       * addr is in the beacon frame */
    +  /* Start of 32-bit bitfield */
    +
    +  uint32_t is_assoc           : 1;  /* Are we associated to the PAN */
    +  uint32_t assoc_permit       : 1;  /* Are we allowing assoc. as a coord. */
    +  uint32_t auto_req           : 1;  /* Automatically send data req. if addr
    +                                     * addr is in the beacon frame */
     
    -    uint32_t batt_life_ext      : 1;  /* Is BLE enabled */
    -    uint32_t gts_permit         : 1;  /* Is PAN Coord. accepting GTS reqs. */
    -    uint32_t promiscuous_mode   : 1;  /* Is promiscuous mode on? */
    -    uint32_t ranging_supported  : 1;  /* Does MAC sublayer support ranging */
    -    uint32_t rx_when_idle       : 1;  /* Recvr. on during idle periods */
    -    uint32_t sec_enabled        : 1;  /* Does MAC sublayer have security en. */
    +  uint32_t batt_life_ext      : 1;  /* Is BLE enabled */
    +  uint32_t gts_permit         : 1;  /* Is PAN Coord. accepting GTS reqs. */
    +  uint32_t promiscuous_mode   : 1;  /* Is promiscuous mode on? */
    +  uint32_t ranging_supported  : 1;  /* Does MAC sublayer support ranging */
    +  uint32_t rx_when_idle       : 1;  /* Recvr. on during idle periods */
    +  uint32_t sec_enabled        : 1;  /* Does MAC sublayer have security en. */
     
    -    uint32_t max_csma_backoffs  : 3;  /* Max num backoffs for CSMA algorithm
    -                                       * before declaring ch access failure */
    +  uint32_t max_csma_backoffs  : 3;  /* Max num backoffs for CSMA algorithm
    +                                     * before declaring ch access failure */
     
    -    uint32_t beacon_order       : 4;  /* Freq. that beacon is transmitted */
    +  uint32_t beacon_order       : 4;  /* Freq. that beacon is transmitted */
     
    -    uint32_t superframe_order   : 4;  /* Length of active portion of outgoing
    -                                       * superframe, including the beacon */
    +  uint32_t superframe_order   : 4;  /* Length of active portion of outgoing
    +                                     * superframe, including the beacon */
     
         /* The offset, measured is symbols, between the symbol boundary at which the
          * MLME captures the timestamp of each transmitted and received frame, and
    @@ -213,25 +213,29 @@ struct ieee802154_privmac_s
          * the frames [1] pg. 129.
          */
     
    -    uint32_t sync_symb_offset   : 12;
    -  };
    +  uint32_t sync_symb_offset   : 12;
     
    -  struct
    -  {
    -    uint32_t beacon_tx_time     : 24; /* Time of last beacon transmit */
    -    uint32_t min_be             : 4;  /* Min value of backoff exponent (BE) */
    -    uint32_t max_be             : 4;  /* Max value of backoff exponent (BE) */
    -  };
    +  /* End of 32-bit bitfield */
     
    -  struct
    -  {
    -    uint32_t tx_ctrl_active_dur : 17; /* Duration for which tx is permitted to
    -                                       * be active */
    -    uint32_t tx_ctrl_pause_dur  : 1;  /* Duration after tx before another tx is
    -                                       * permitted. 0=2000, 1= 10000 */
    -    uint32_t timestamp_support  : 1;  /* Does MAC layer supports timestamping */
    -    uint32_t is_coord           : 1;  /* Is this device acting as coordinator */
    -  };
    +  /* Start of 32-bit bitfield */
    +
    +  uint32_t beacon_tx_time     : 24; /* Time of last beacon transmit */
    +  uint32_t min_be             : 4;  /* Min value of backoff exponent (BE) */
    +  uint32_t max_be             : 4;  /* Max value of backoff exponent (BE) */
    +
    +  /* End of 32-bit bitfield */
    +
    +  /* Start of 32-bit bitfield */
    +
    +  uint32_t tx_ctrl_active_dur : 17; /* Duration for which tx is permitted to
    +                                     * be active */
    +  uint32_t tx_ctrl_pause_dur  : 1;  /* Duration after tx before another tx is
    +                                     * permitted. 0=2000, 1= 10000 */
    +  uint32_t timestamp_support  : 1;  /* Does MAC layer supports timestamping */
    +  uint32_t is_coord           : 1;  /* Is this device acting as coordinator */
    +  /* 12-bits remaining */
    +
    +  /* End of 32-bit bitfield. 
     
       /* TODO: Add Security-related MAC PIB attributes */
     };
    -- 
    GitLab
    
    
    From 50fda0d748acaacba14e126749f79e1a09af4a2c Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Wed, 19 Apr 2017 13:33:20 -0600
    Subject: [PATCH 518/990] 6loWPAN: Fix a missing source address in header. 
     Correct calculation of payload size.
    
    ---
     include/nuttx/net/netconfig.h       |  4 ++--
     net/sixlowpan/Kconfig               |  9 --------
     net/sixlowpan/README.txt            | 21 +++++++++---------
     net/sixlowpan/sixlowpan_framelist.c | 13 +++++++-----
     net/sixlowpan/sixlowpan_framer.c    | 33 +++++++++++++++++++++--------
     net/sixlowpan/sixlowpan_input.c     |  4 +++-
     net/sixlowpan/sixlowpan_internal.h  |  6 +++---
     7 files changed, 51 insertions(+), 39 deletions(-)
    
    diff --git a/include/nuttx/net/netconfig.h b/include/nuttx/net/netconfig.h
    index 99f00e3856..fbdd2772d5 100644
    --- a/include/nuttx/net/netconfig.h
    +++ b/include/nuttx/net/netconfig.h
    @@ -309,7 +309,7 @@
     #endif
     
     #ifdef CONFIG_NET_6LOWPAN
    -#  define IEEE802154_UDP_MSS(h) (CONFIG_NET_6LOWPAN_MAXPAYLOAD - UDP_HDRLEN - (h))
    +#  define IEEE802154_UDP_MSS(h) (CONFIG_NET_6LOWPAN_MTU - UDP_HDRLEN - (h))
     #  ifndef CONFIG_NET_MULTILINK
     #    define __MIN_UDP_MSS(h)    IEEE802154_UDP_MSS(h)
     #    define __MAX_UDP_MSS(h)    IEEE802154_UDP_MSS(h)
    @@ -484,7 +484,7 @@
     #endif
     
     #ifdef CONFIG_NET_6LOWPAN
    -#  define IEEE802154_TCP_MSS(h) (CONFIG_NET_6LOWPAN_MAXPAYLOAD - TCP_HDRLEN - (h))
    +#  define IEEE802154_TCP_MSS(h) (CONFIG_NET_6LOWPAN_MTU - TCP_HDRLEN - (h))
     #  ifndef CONFIG_NET_MULTILINK
     #    define __MIN_TCP_MSS(h)    IEEE802154_TCP_MSS(h)
     #    define __MAX_TCP_MSS(h)    IEEE802154_TCP_MSS(h)
    diff --git a/net/sixlowpan/Kconfig b/net/sixlowpan/Kconfig
    index ad59e29055..021571fbd0 100644
    --- a/net/sixlowpan/Kconfig
    +++ b/net/sixlowpan/Kconfig
    @@ -156,15 +156,6 @@ config NET_6LOWPAN_MAX_MACTRANSMITS
     		layer should resend packets if no link-layer ACK wasreceived. This
     		only makes sense with the csma_driver.
     
    -config NET_6LOWPAN_MAXPAYLOAD
    -	int "Max packet size"
    -	default 102
    -	---help---
    -		NET_6LOWPAN_MAXPAYLOAD specifies the maximum size of packets
    -		before they get fragmented. The default is 127 bytes (the maximum size
    -		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
    diff --git a/net/sixlowpan/README.txt b/net/sixlowpan/README.txt
    index e325533474..7a65c77ade 100644
    --- a/net/sixlowpan/README.txt
    +++ b/net/sixlowpan/README.txt
    @@ -33,7 +33,7 @@ Optimal 6loWPAN Configuration
     Fragmentation Headers
     ---------------------
     A fragment header is placed at the beginning of the outgoing packet just
    -after the FCF when the payload is too large to fit in a single IEEE 802.15.4
    +after the MAC when the payload is too large to fit in a single IEEE 802.15.4
     frame. The fragment header contains three fields: Datagram size, datagram tag
     and datagram offset.
     
    @@ -47,7 +47,7 @@ The length of the fragment header length is four bytes for the first header
     (FRAG1) and five bytes for all subsequent headers (FRAGN).  For example,
     this is a HC1 compressed first frame of a packet
     
    -  01 08 01 0000 3412                            ### 7-byte FCF header
    +  41 88 01 0000 3412 cdab                       ### 9-byte MAC header
       c50e 000b                                     ### 4-byte FRAG1 header
       42                                            ### SIXLOWPAN_DISPATCH_HC1
         fb                                          ### RIME_HC1_HC_UDP_HC1_ENCODING
    @@ -56,14 +56,15 @@ this is a HC1 compressed first frame of a packet
         10                                          ### RIME_HC1_HC_UDP_PORTS
         0000                                        ### RIME_HC1_HC_UDP_CHKSUM
     
    -  80 byte Payload follows:
    +  104 byte Payload follows:
       4f4e452064617920 48656e6e792d7065 6e6e792077617320 7069636b696e6720
       757020636f726e20 696e207468652063 6f726e7961726420 7768656e2d2d7768
    -  61636b212d2d736f 6d657468696e6720                                                              g
    +  61636b212d2d736f 6d657468696e6720 6869742068657220 75706f6e20746865
    +  20686561642e2027
     
     This is the second frame of the same transfer:
     
    -  01 08 01 0000 3412                            ### 7-byte FCF header
    +  41 88 01 0000 3412 cdab                       ### 9-byte MAC header
       e50e 000b 0a                                  ### 5 byte FRAGN header
       42                                            ### SIXLOWPAN_DISPATCH_HC1
         fb                                          ### RIME_HC1_HC_UDP_HC1_ENCODING
    @@ -72,11 +73,11 @@ This is the second frame of the same transfer:
         10                                          ### RIME_HC1_HC_UDP_PORTS
         0000                                        ### RIME_HC1_HC_UDP_CHKSUM
     
    -  80 byte Payload follows:
    -  6869742068657220 75706f6e20746865 20686561642e2027 476f6f646e657373
    -  2067726163696f75 73206d6521272073 6169642048656e6e 792d70656e6e793b
    -  202774686520736b 79277320612d676f
    -
    +  104 byte Payload follows:
    +  476f6f646e657373 2067726163696f75 73206d6521272073 6169642048656e6e
    +  792d70656e6e793b 202774686520736b 79277320612d676f 696e6720746f2066
    +  616c6c3b2049206d 75737420676f2061 6e642074656c6c20 746865206b696e67
    +  2e270a0a536f2073
     
     The payload length is encoded in the LS 11-bits of the first 16-bit value:
     In this example the payload size is 0x050e or 1,294.  The tag is 0x000b.  In
    diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c
    index 23969c09f3..79e653d10b 100644
    --- a/net/sixlowpan/sixlowpan_framelist.c
    +++ b/net/sixlowpan/sixlowpan_framelist.c
    @@ -281,6 +281,11 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee,
     
       ninfo("Sending packet length %d\n", buflen);
     
    +  /* Set the source and destinatino address */
    +
    +  rimeaddr_copy(&g_pktaddrs[PACKETBUF_ADDR_SENDER], &ieee->i_nodeaddr);
    +  rimeaddr_copy(&g_pktaddrs[PACKETBUF_ADDR_RECEIVER], destmac);
    +
       /* Pre-calculate frame header length. */
     
       framer_hdrlen = sixlowpan_send_hdrlen(ieee, ieee->i_panid);
    @@ -317,11 +322,9 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee,
     
       ninfo("Header of length %d\n", g_frame_hdrlen);
     
    -  rimeaddr_copy(&g_pktaddrs[PACKETBUF_ADDR_RECEIVER], destmac);
    -
       /* Check if we need to fragment the packet into several frames */
     
    -  if (buflen > (CONFIG_NET_6LOWPAN_MAXPAYLOAD - g_frame_hdrlen))
    +  if (buflen > (CONFIG_NET_6LOWPAN_FRAMELEN - g_frame_hdrlen))
         {
     #ifdef CONFIG_NET_6LOWPAN_FRAG
           /* ieee->i_framelist will hold the generated frames; frames will be
    @@ -384,7 +387,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee,
            * bytes.
            */
     
    -      paysize = (CONFIG_NET_6LOWPAN_MAXPAYLOAD - g_frame_hdrlen) & ~7;
    +      paysize = (CONFIG_NET_6LOWPAN_FRAMELEN - g_frame_hdrlen) & ~7;
           memcpy(fptr + g_frame_hdrlen, buf,  paysize);
     
           /* Set outlen to what we already sent from the IP payload */
    @@ -457,7 +460,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee,
               /* Copy payload and enqueue */
               /* Check for the last fragment */
     
    -          paysize = (CONFIG_NET_6LOWPAN_MAXPAYLOAD - fragn_hdrlen) &
    +          paysize = (CONFIG_NET_6LOWPAN_FRAMELEN - fragn_hdrlen) &
                         SIXLOWPAN_DISPATCH_FRAG_MASK;
               if (buflen - outlen < paysize)
                 {
    diff --git a/net/sixlowpan/sixlowpan_framer.c b/net/sixlowpan/sixlowpan_framer.c
    index 746d6dc113..66f8a1c3fb 100644
    --- a/net/sixlowpan/sixlowpan_framer.c
    +++ b/net/sixlowpan/sixlowpan_framer.c
    @@ -70,11 +70,11 @@
     
     struct field_length_s
     {
    -  uint8_t dest_pid_len;    /**<  Length (in bytes) of destination PAN ID field */
    -  uint8_t dest_addr_len;   /**<  Length (in bytes) of destination address field */
    -  uint8_t src_pid_len;     /**<  Length (in bytes) of source PAN ID field */
    -  uint8_t src_addr_len;    /**<  Length (in bytes) of source address field */
    -  uint8_t aux_sec_len;     /**<  Length (in bytes) of aux security header field */
    +  uint8_t dest_pid_len;    /* Length (in bytes) of destination PAN ID field */
    +  uint8_t dest_addr_len;   /* Length (in bytes) of destination address field */
    +  uint8_t src_pid_len;     /* Length (in bytes) of source PAN ID field */
    +  uint8_t src_addr_len;    /* Length (in bytes) of source address field */
    +  uint8_t aux_sec_len;     /* Length (in bytes) of aux security header field */
     };
     
     /****************************************************************************
    @@ -179,10 +179,17 @@ static void sixlowpan_fieldlengths(FAR struct frame802154_s *finfo,
           (finfo->fcf.src_addr_mode & 3) != 0 &&
           finfo->src_pid == finfo->dest_pid)
         {
    +      /* Indicate source PANID compression */
    +
           finfo->fcf.panid_compression = 1;
     
    -      /* Compressed header, only do dest pid */
    -      /* flen->src_pid_len = 0; */
    +      /* Compressed header, only do dest pid.
    +       *
    +       * REVISIT:  This was commented out in corresponding Contiki logic, but
    +       * is needed to match sixlowpan_recv_hdrlen().
    +       */
    +
    +      flen->src_pid_len = 0;
         }
     
       /* Determine address lengths */
    @@ -348,7 +355,7 @@ static void sixlowpan_setup_params(FAR struct ieee802154_driver_s *ieee,
           rimeaddr_copy((struct rimeaddr_s *)¶ms->dest_addr,
                         g_pktaddrs[PACKETBUF_ADDR_RECEIVER].u8);
     
    -      /* Use short address mode if so configured */
    +      /* Use short destination address mode if so configured */
     
     #ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED
           params->fcf.dest_addr_mode = FRAME802154_LONGADDRMODE;
    @@ -359,7 +366,15 @@ static void sixlowpan_setup_params(FAR struct ieee802154_driver_s *ieee,
     
       /* Set the source address to the node address assigned to the device */
     
    -  rimeaddr_copy((struct rimeaddr_s *)¶ms->src_addr, &ieee->i_nodeaddr.u8);
    +  rimeaddr_copy((struct rimeaddr_s *)¶ms->src_addr, &ieee->i_nodeaddr);
    +
    +  /* Use short soruce address mode if so configured */
    +
    +#ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED
    +  params->fcf.src_addr_mode = FRAME802154_LONGADDRMODE;
    +#else
    +  params->fcf.src_addr_mode = FRAME802154_SHORTADDRMODE;
    +#endif
     }
     
     /****************************************************************************
    diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c
    index 119dd4dfd2..bfa74da13a 100644
    --- a/net/sixlowpan/sixlowpan_input.c
    +++ b/net/sixlowpan/sixlowpan_input.c
    @@ -167,7 +167,7 @@ int sixlowpan_recv_hdrlen(FAR const uint8_t *fptr)
         }
       else if (addrmode == FRAME802154_LONGADDRMODE)
         {
    -      /* 2 byte dest PAN + 6 byte dest long address */
    +      /* 2 byte dest PAN + 8 byte dest long address */
     
           hdrlen += 10;
         }
    @@ -193,6 +193,8 @@ int sixlowpan_recv_hdrlen(FAR const uint8_t *fptr)
         }
       else
         {
    +      /* Add source PANID if PANIDs are not compressed */
    +
           if ((fptr[0] & (1 << FRAME802154_PANIDCOMP_SHIFT)) == 0)
             {
               hdrlen += 2;
    diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h
    index deede9d3b8..392bc376b7 100644
    --- a/net/sixlowpan/sixlowpan_internal.h
    +++ b/net/sixlowpan/sixlowpan_internal.h
    @@ -221,9 +221,9 @@ struct frame802154_fcf_s
     
     struct frame802154_scf_s
     {
    -  uint8_t  security_level;   /* 3 bit. security level      */
    -  uint8_t  key_id_mode;      /* 2 bit. Key identifier mode */
    -  uint8_t  reserved;         /* 3 bit. Reserved bits       */
    +  uint8_t security_level;    /* 3 bit. security level      */
    +  uint8_t key_id_mode;       /* 2 bit. Key identifier mode */
    +  uint8_t reserved;          /* 3 bit. Reserved bits       */
     };
     
     /* 802.15.4 Aux security header */
    -- 
    GitLab
    
    
    From ec5b0a0ef3d8caffb82cd1302fd78788a8ef6c81 Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Wed, 19 Apr 2017 13:40:52 -0600
    Subject: [PATCH 519/990] Minor changes to spacing only from review of last PR
    
    ---
     wireless/ieee802154/mac802154.c | 24 ++++++++++++------------
     1 file changed, 12 insertions(+), 12 deletions(-)
    
    diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c
    index ad702dc535..5ea09c2546 100644
    --- a/wireless/ieee802154/mac802154.c
    +++ b/wireless/ieee802154/mac802154.c
    @@ -163,14 +163,14 @@ struct ieee802154_privmac_s
       /* Contents of beacon payload */
     
       uint8_t beacon_payload[IEEE802154_MAX_BEACON_PAYLOAD_LENGTH];
    -  uint8_t beacon_payload_len;     /* Length of beacon payload */
    +  uint8_t beacon_payload_len;       /* Length of beacon payload */
     
    -  uint8_t batt_life_ext_periods;  /* # of backoff periods during which rx is
    -                                   * enabled after the IFS following beacon */
    +  uint8_t batt_life_ext_periods;    /* # of backoff periods during which rx is
    +                                     * enabled after the IFS following beacon */
     
    -  uint8_t bsn;          /* Seq. num added to tx beacon frame */
    -  uint8_t dsn;          /* Seq. num added to tx data or MAC frame */
    -  uint8_t max_retries;  /* Max # of retries alloed after tx failure */
    +  uint8_t bsn;                      /* Seq. num added to tx beacon frame */
    +  uint8_t dsn;                      /* Seq. num added to tx data or MAC frame */
    +  uint8_t max_retries;              /* Max # of retries alloed after tx failure */
     
       /* The maximum time, in multiples of aBaseSuperframeDuration, a device shall
        * wait for a response command frame to be available following a request
    @@ -207,11 +207,11 @@ struct ieee802154_privmac_s
       uint32_t superframe_order   : 4;  /* Length of active portion of outgoing
                                          * superframe, including the beacon */
     
    -    /* The offset, measured is symbols, between the symbol boundary at which the
    -     * MLME captures the timestamp of each transmitted and received frame, and
    -     * the onset of the first symbol past the SFD, namely the first symbol of
    -     * the frames [1] pg. 129.
    -     */
    +  /* The offset, measured is symbols, between the symbol boundary at which the
    +   * MLME captures the timestamp of each transmitted and received frame, and
    +   * the onset of the first symbol past the SFD, namely the first symbol of
    +   * the frames [1] pg. 129.
    +   */
     
       uint32_t sync_symb_offset   : 12;
     
    @@ -233,7 +233,7 @@ struct ieee802154_privmac_s
                                          * permitted. 0=2000, 1= 10000 */
       uint32_t timestamp_support  : 1;  /* Does MAC layer supports timestamping */
       uint32_t is_coord           : 1;  /* Is this device acting as coordinator */
    -  /* 12-bits remaining */
    +                                    /* 12-bits remaining */
     
       /* End of 32-bit bitfield. 
     
    -- 
    GitLab
    
    
    From 6a2c43b0c1abedb437ffbafaeb58bf31d7d3dc15 Mon Sep 17 00:00:00 2001
    From: Ian McAfee 
    Date: Wed, 19 Apr 2017 14:32:28 -0600
    Subject: [PATCH 520/990] SAMV7 EMAC:  Add conditional logic to account the
     fact that the SAMV71 has 6 rather than 3 queues after version 1.
    
    ---
     arch/arm/src/samv7/sam_emac.c | 97 ++++++++++++++++++++++++++++++++++-
     include/nuttx/net/ioctl.h     |  2 +-
     2 files changed, 96 insertions(+), 3 deletions(-)
    
    diff --git a/arch/arm/src/samv7/sam_emac.c b/arch/arm/src/samv7/sam_emac.c
    index 4432570c78..4760577b8b 100644
    --- a/arch/arm/src/samv7/sam_emac.c
    +++ b/arch/arm/src/samv7/sam_emac.c
    @@ -86,6 +86,7 @@
     #include "cache.h"
     
     #include "chip/sam_pinmap.h"
    +#include "chip/sam_chipid.h"
     #include "sam_gpio.h"
     #include "sam_periphclks.h"
     #include "sam_ethernet.h"
    @@ -331,7 +332,19 @@
     #define EMAC_QUEUE_0        0
     #define EMAC_QUEUE_1        1
     #define EMAC_QUEUE_2        2
    -#define EMAC_NQUEUES        3
    +
    +#if defined(CONFIG_ARCH_CHIP_SAMV71)
    +  /* After chip version 1, the SAMV71 increased from 3 to 6 queue */
    +
    +#  define EMAC_QUEUE_3      3
    +#  define EMAC_QUEUE_4      4
    +#  define EMAC_QUEUE_5      5
    +#  define EMAC_NQUEUES      (g_emac_nqueues)
    +#  define EMAC_MAX_NQUEUES  6
    +#else
    +#  define EMAC_NQUEUES      3
    +#  define EMAC_MAX_NQUEUES  3
    +#endif
     
     /* Interrupt settings */
     
    @@ -537,7 +550,7 @@ struct sam_emac_s
     
       /* Transfer queues */
     
    -  struct sam_queue_s    xfrq[EMAC_NQUEUES];
    +  struct sam_queue_s    xfrq[EMAC_MAX_NQUEUES];
     
         /* Debug stuff */
     
    @@ -924,6 +937,16 @@ static uint8_t g_pktbuf1[MAX_NET_DEV_MTU + CONFIG_NET_GUARDSIZE];
     /* EMAC1 peripheral state */
     
     static struct sam_emac_s g_emac1;
    +
    +#endif /* CONFIG_SAMV7_EMAC1 */
    +
    +/* The SAMV71 may support from 3 to 6 queue, depending upon the chip
    + * revision.  NOTE that this is a global setting and applies to both
    + * EMAC peripherals.
    + */
    +
    +#if defined(CONFIG_ARCH_CHIP_SAMV71)
    +static uint8_t g_emac_nqueues = 3;
     #endif
     
     /****************************************************************************
    @@ -2677,6 +2700,16 @@ static int sam_ifup(struct net_driver_s *dev)
       sam_emac_configure(priv);
       sam_queue_configure(priv, EMAC_QUEUE_1);
       sam_queue_configure(priv, EMAC_QUEUE_2);
    +
    +#if defined(CONFIG_ARCH_CHIP_SAMV71)
    +  if (g_emac_nqueues > 3)
    +    {
    +      sam_queue_configure(priv, EMAC_QUEUE_3);
    +      sam_queue_configure(priv, EMAC_QUEUE_4);
    +      sam_queue_configure(priv, EMAC_QUEUE_5);
    +    }
    +#endif
    +
       sam_queue0_configure(priv);
     
       /* Set the MAC address (should have been configured while we were down) */
    @@ -4540,10 +4573,28 @@ static void sam_emac_reset(struct sam_emac_s *priv)
       sam_rxreset(priv, EMAC_QUEUE_1);
       sam_rxreset(priv, EMAC_QUEUE_2);
     
    +#if defined(CONFIG_ARCH_CHIP_SAMV71)
    +  if (g_emac_nqueues > 3)
    +    {
    +      sam_rxreset(priv, EMAC_QUEUE_3);
    +      sam_rxreset(priv, EMAC_QUEUE_4);
    +      sam_rxreset(priv, EMAC_QUEUE_5);
    +    }
    +#endif
    +
       sam_txreset(priv, EMAC_QUEUE_0);
       sam_txreset(priv, EMAC_QUEUE_1);
       sam_txreset(priv, EMAC_QUEUE_2);
     
    +#if defined(CONFIG_ARCH_CHIP_SAMV71)
    +  if (g_emac_nqueues > 3)
    +    {
    +      sam_txreset(priv, EMAC_QUEUE_3);
    +      sam_txreset(priv, EMAC_QUEUE_4);
    +      sam_txreset(priv, EMAC_QUEUE_5);
    +    }
    +#endif
    +
       /* Disable Rx and Tx, plus the statistics registers. */
     
       regval  = sam_getreg(priv, SAM_EMAC_NCR_OFFSET);
    @@ -4561,10 +4612,28 @@ static void sam_emac_reset(struct sam_emac_s *priv)
       sam_rxreset(priv, EMAC_QUEUE_1);
       sam_rxreset(priv, EMAC_QUEUE_2);
     
    +#if defined(CONFIG_ARCH_CHIP_SAMV71)
    +  if (g_emac_nqueues > 3)
    +    {
    +      sam_rxreset(priv, EMAC_QUEUE_3);
    +      sam_rxreset(priv, EMAC_QUEUE_4);
    +      sam_rxreset(priv, EMAC_QUEUE_5);
    +    }
    +#endif
    +
       sam_txreset(priv, EMAC_QUEUE_0);
       sam_txreset(priv, EMAC_QUEUE_1);
       sam_txreset(priv, EMAC_QUEUE_2);
     
    +#if defined(CONFIG_ARCH_CHIP_SAMV71)
    +  if (g_emac_nqueues > 3)
    +    {
    +      sam_txreset(priv, EMAC_QUEUE_3);
    +      sam_txreset(priv, EMAC_QUEUE_4);
    +      sam_txreset(priv, EMAC_QUEUE_5);
    +    }
    +#endif
    +
       /* Make sure that RX and TX are disabled; clear statistics registers */
     
       sam_putreg(priv, SAM_EMAC_NCR_OFFSET, EMAC_NCR_CLRSTAT);
    @@ -4875,12 +4944,36 @@ int sam_emac_initialize(int intf)
     {
       struct sam_emac_s *priv;
       const struct sam_emacattr_s *attr;
    +#if defined(CONFIG_ARCH_CHIP_SAMV71)
    +  uint32_t regval;
    +#endif
       uint8_t *pktbuf;
     #if defined(CONFIG_NETDEV_PHY_IOCTL) && defined(CONFIG_ARCH_PHY_INTERRUPT)
       uint8_t phytype;
     #endif
       int ret;
     
    +#if defined(CONFIG_ARCH_CHIP_SAMV71)
    +  /* Determine if the chip has 3 or 6 queues.  This logic is for the
    +   * V71 only -- if you are using a different chip in the family,
    +   * the version number at which to switch from 3 to 6 queues may
    +   * be different.  For the V71, versions 1 and higher have 6 queues.
    +   *
    +   * If both emacs are enabled, this code will be run twice, which
    +   * should not be a problem as the result will be the same each time
    +   * it is run.
    +   */
    +
    +  regval = getreg32(SAM_CHIPID_CIDR);
    +  if ((regval & CHIPID_CIDR_ARCH_MASK) == CHIPID_CIDR_ARCH_SAMV71)
    +    {
    +      if (((regval & CHIPID_CIDR_VERSION_MASK) >> CHIPID_CIDR_VERSION_SHIFT) > 0)
    +        {
    +          g_emac_nqueues = 6;
    +        }
    +    }
    +#endif
    +
     #if defined(CONFIG_SAMV7_EMAC0)
       if (intf == EMAC0_INTF)
         {
    diff --git a/include/nuttx/net/ioctl.h b/include/nuttx/net/ioctl.h
    index c618028405..2c31e63428 100644
    --- a/include/nuttx/net/ioctl.h
    +++ b/include/nuttx/net/ioctl.h
    @@ -128,7 +128,7 @@
                                              * See include/nuttx/net/telnet.h */
     
     /****************************************************************************
    - * Pulbic Type Definitions
    + * Public Type Definitions
      ****************************************************************************/
     
     /* See include/net/if.h, include/net/route.h, and include/net/arp.h */
    -- 
    GitLab
    
    
    From 1abe4ae4da7dbd6e8ef34291ff51c8173c5cf704 Mon Sep 17 00:00:00 2001
    From: Anthony Merlino 
    Date: Wed, 19 Apr 2017 16:34:34 -0400
    Subject: [PATCH 521/990] wireless/ieee802154: Starts structuring transmission
     completion handling
    
    ---
     drivers/wireless/ieee802154/mrf24j40.c        | 224 +++++++++++++-----
     drivers/wireless/ieee802154/mrf24j40.h        |  13 +-
     .../wireless/ieee802154/ieee802154_radio.h    |   7 +
     wireless/ieee802154/mac802154.c               |   4 +-
     4 files changed, 180 insertions(+), 68 deletions(-)
    
    diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c
    index b1c0c67218..ffdd0689d4 100644
    --- a/drivers/wireless/ieee802154/mrf24j40.c
    +++ b/drivers/wireless/ieee802154/mrf24j40.c
    @@ -159,8 +159,12 @@ static int  mrf24j40_initialize(FAR struct mrf24j40_radio_s *dev);
     
     static int  mrf24j40_setrxmode(FAR struct mrf24j40_radio_s *dev, int mode);
     static int  mrf24j40_regdump(FAR struct mrf24j40_radio_s *dev);
    +
     static void mrf24j40_irqwork_rx(FAR struct mrf24j40_radio_s *dev);
    -static void mrf24j40_irqwork_tx(FAR struct mrf24j40_radio_s *dev);
    +static void mrf24j40_irqwork_txnorm(FAR struct mrf24j40_radio_s *dev);
    +static void mrf24j40_irqwork_txgts(FAR struct mrf24j40_radio_s *dev,
    +                                   uint8_t gts_num);
    +
     static void mrf24j40_irqworker(FAR void *arg);
     static int  mrf24j40_interrupt(int irq, FAR void *context, FAR void *arg);
     
    @@ -171,6 +175,9 @@ static int mrf24j40_csma_setup(FAR struct mrf24j40_radio_s *dev,
                  uint8_t *buf, uint16_t buf_len);
     static int mrf24j40_gts_setup(FAR struct mrf24j40_radio_s *dev, uint8_t gts,
                  uint8_t *buf, uint16_t buf_len);
    +static int mrf24j40_setup_fifo(FAR struct mrf24j40_radio_s *dev,
    +                               uint8_t *buf, uint16_t buf_len,
    +                               uint32_t fifo_addr);
     
     /* IOCTL helpers */
     
    @@ -345,8 +352,6 @@ static void mrf24j40_dopoll_csma(FAR void *arg)
               mrf24j40_csma_setup(dev, &dev->tx_buf[0],
                                   dev->csma_desc.pub.psdu_length);
             }
    -
    -      /* Setup the transmit on the device */
         }
     
       sem_post(&dev->exclsem);
    @@ -1338,15 +1343,53 @@ static int mrf24j40_transmit(FAR struct ieee802154_radio_s *radio,
                                  uint8_t *buf, uint16_t buf_len)
     {
       FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)radio;
    -  uint32_t addr;
       uint8_t  reg;
       int      ret;
    -  int      hlen = 3; /* Include frame control and seq number */
    -  uint16_t frame_ctrl;
     
       mrf24j40_pacontrol(dev, MRF24J40_PA_AUTO);
     
    -  addr = MRF24J40_TXBUF_BASE;
    +  /* Enable tx int */
    +
    +  reg  = mrf24j40_getreg(dev->spi, MRF24J40_INTCON);
    +  reg &= ~MRF24J40_INTCON_TXNIE;
    +  mrf24j40_setreg(dev->spi, MRF24J40_INTCON, reg);
    +
    +  /* Setup the FIFO */
    +
    +  ret = mrf24j40_setup_fifo(dev, buf, buf_len, MRF24J40_TXNORM_FIFO);
    +
    +  /* If the frame control field contains
    +   * an acknowledgment request, set the TXNACKREQ bit.
    +   * See IEEE 802.15.4/2003 7.2.1.1 page 112 for info.
    +   */
    +
    +  reg = MRF24J40_TXNCON_TXNTRIG;
    +  if (buf[0] & IEEE802154_FRAMECTRL_ACKREQ)
    +    {
    +      reg |= MRF24J40_TXNCON_TXNACKREQ;
    +    }
    +
    +  /* Trigger packet emission */
    +
    +  mrf24j40_setreg(dev->spi, MRF24J40_TXNCON, reg);
    +  return ret;
    +}
    +
    +/****************************************************************************
    + * Name: mrf24j40_csma_setup
    + *
    + * Description:
    + *   Setup a CSMA transaction in the normal TX FIFO
    + *
    + ****************************************************************************/
    +
    +static int mrf24j40_csma_setup(FAR struct mrf24j40_radio_s *dev,
    +                               uint8_t *buf, uint16_t buf_len)
    +{
    +  uint8_t  reg;
    +  int      ret;
    +
    +  mrf24j40_pacontrol(dev, MRF24J40_PA_AUTO);
     
       /* Enable tx int */
     
    @@ -1354,6 +1397,49 @@ static int mrf24j40_transmit(FAR struct ieee802154_radio_s *radio,
       reg &= ~MRF24J40_INTCON_TXNIE;
       mrf24j40_setreg(dev->spi, MRF24J40_INTCON, reg);
     
    +  /* Setup the FIFO */
    +
    +  ret = mrf24j40_setup_fifo(dev, buf, buf_len, MRF24J40_TXNORM_FIFO);
    +
    +  /* If the frame control field contains
    +   * an acknowledgment request, set the TXNACKREQ bit.
    +   * See IEEE 802.15.4/2003 7.2.1.1 page 112 for info.
    +   */
    +
    +  reg = MRF24J40_TXNCON_TXNTRIG;
    +  if (buf[0] & IEEE802154_FRAMECTRL_ACKREQ)
    +    {
    +      reg |= MRF24J40_TXNCON_TXNACKREQ;
    +    }
    +
    +  /* Trigger packet emission */
    +
    +  mrf24j40_setreg(dev->spi, MRF24J40_TXNCON, reg);
    +  return ret;
    +}
    +
    +/****************************************************************************
    + * Name: mrf24j40_gts_setup
    + *
    + * Description:
    + *   Setup a GTS transaction in one of the GTS FIFOs 
    + *
    + ****************************************************************************/
    +
    +static int mrf24j40_gts_setup(FAR struct mrf24j40_radio_s *dev, uint8_t fifo,
    +                              uint8_t *buf, uint16_t buf_len)
    +{
    +  return -ENOTTY;
    +}
    +
    +static int mrf24j40_setup_fifo(FAR struct mrf24j40_radio_s *dev,
    +                               uint8_t *buf, uint16_t buf_len,
    +                               uint32_t fifo_addr)
    +{
    +  int      ret;
    +  int      hlen = 3; /* Include frame control and seq number */
    +  uint16_t frame_ctrl;
    +
       /* Analyze frame control to compute header length */
     
       frame_ctrl = buf[0];
    @@ -1384,103 +1470,101 @@ static int mrf24j40_transmit(FAR struct ieee802154_radio_s *radio,
     
       /* Header len, 0, TODO for security modes */
     
    -  mrf24j40_setreg(dev->spi, addr++, hlen);
    +  mrf24j40_setreg(dev->spi, fifo_addr++, hlen);
     
       /* Frame length */
     
    -  mrf24j40_setreg(dev->spi, addr++, buf_len);
    +  mrf24j40_setreg(dev->spi, fifo_addr++, buf_len);
     
       /* Frame data */
     
       for (ret = 0; ret < buf_len; ret++) /* this sets the correct val for ret */
         {
    -      mrf24j40_setreg(dev->spi, addr++, buf[ret]);
    +      mrf24j40_setreg(dev->spi, fifo_addr++, buf[ret]);
         }
    -
    -  /* If the frame control field contains
    -   * an acknowledgment request, set the TXNACKREQ bit.
    -   * See IEEE 802.15.4/2003 7.2.1.1 page 112 for info.
    -   */
    -
    -  reg = MRF24J40_TXNCON_TXNTRIG;
    -  if (frame_ctrl & IEEE802154_FRAMECTRL_ACKREQ)
    -    {
    -      reg |= MRF24J40_TXNCON_TXNACKREQ;
    -    }
    -
    -  /* Trigger packet emission */
    -
    -  mrf24j40_setreg(dev->spi, MRF24J40_TXNCON, reg);
    +  
       return ret;
     }
     
     /****************************************************************************
    - * Name: mrf24j40_csma_setup
    + * Name: mrf24j40_irqwork_txnorm
      *
      * Description:
    - *   Setup a CSMA transaction in the normal TX FIFO
    + *   Manage completion of packet transmission.
      *
      ****************************************************************************/
     
    -static int mrf24j40_csma_setup(FAR struct mrf24j40_radio_s *dev,
    -                             uint8_t *buf, uint16_t buf_len)
    +static void mrf24j40_irqwork_txnorm(FAR struct mrf24j40_radio_s *dev)
     {
    -  return -ENOTTY;
    -}
    +  uint8_t txstat;
     
    -/****************************************************************************
    - * Name: mrf24j40_gts_setup
    - *
    - * Description:
    - *   Setup a GTS transaction in one of the GTS FIFOs 
    - *
    - ****************************************************************************/
    +  /* Disable tx int */
     
    -static int mrf24j40_gts_setup(FAR struct mrf24j40_radio_s *dev, uint8_t fifo,
    -                              uint8_t *buf, uint16_t buf_len)
    -{
    -  return -ENOTTY;
    +  txstat  = mrf24j40_getreg(dev->spi, MRF24J40_INTCON);
    +  txstat |= MRF24J40_INTCON_TXNIE;
    +  mrf24j40_setreg(dev->spi, MRF24J40_INTCON, txstat);
    +
    +  /* Get the status from the device and copy the status into the tx desc.
    +   * The status for the normal FIFO is represented with bit TXNSTAT where
    +   * 0=success, 1= failure */
    +
    +  txstat = mrf24j40_getreg(dev->spi, MRF24J40_TXSTAT);
    +  dev->csma_desc.pub.status = txstat & MRF24J40_TXSTAT_TXNSTAT;
    +
    +  /* Inform the next layer of the transmission success/failure */
    +
    +  dev->radiocb->txdone_csma(dev->radiocb, dev->csma_desc.pub);
    +
    +  /* We are now done with the transaction */
    +
    +  dev->csma_desc.busy = 0;
    +
    +  mrf24j40_dopoll_csma(dev);
     }
     
     /****************************************************************************
    - * Name: mrf24j40_irqwork_tx
    + * Name: mrf24j40_irqwork_gts
      *
      * Description:
      *   Manage completion of packet transmission.
      *
      ****************************************************************************/
     
    -static void mrf24j40_irqwork_tx(FAR struct mrf24j40_radio_s *dev)
    +static void mrf24j40_irqwork_txgts(FAR struct mrf24j40_radio_s *dev,
    +                                   uint8_t gts)
     {
       uint8_t txstat;
    -  uint8_t reg;
     
    -  txstat = mrf24j40_getreg(dev->spi, MRF24J40_TXSTAT);
    +  /* Disable tx int */
     
    -  reg = mrf24j40_getreg(dev->spi, MRF24J40_TXSTAT);
    +  txstat  = mrf24j40_getreg(dev->spi, MRF24J40_INTCON);
    +  txstat |= MRF24J40_INTCON_TXNIE;
    +  mrf24j40_setreg(dev->spi, MRF24J40_INTCON, txstat);
     
    -  /* 1 means it failed, we want 1 to mean it worked. */
    +  /* Get the status from the device and copy the status into the tx desc.
    +   * The status for the normal FIFO is represented with bit TXNSTAT where
    +   * 0=success, 1= failure */
     
    -#if 0
    -  dev->radio.txok      = (reg & MRF24J40_TXSTAT_TXNSTAT) != MRF24J40_TXSTAT_TXNSTAT;
    -  dev->radio.txretries = (reg & MRF24J40_TXSTAT_X_MASK) >> MRF24J40_TXSTAT_X_SHIFT;
    -  dev->radio.txbusy    = (reg & MRF24J40_TXSTAT_CCAFAIL) == MRF24J40_TXSTAT_CCAFAIL;
    -#endif
    +  txstat = mrf24j40_getreg(dev->spi, MRF24J40_TXSTAT);
     
    -  //wlinfo("TXSTAT%02X!\n", txstat);
    -#warning TODO report errors
    -  UNUSED(txstat);
    +  if (gts == 0)
    +    {
    +      dev->csma_desc.pub.status = txstat & MRF24J40_TXSTAT_TXG1STAT;
    +    }
    +  else if (gts == 1)
    +    {
    +      dev->csma_desc.pub.status = txstat & MRF24J40_TXSTAT_TXG2STAT;
    +    }
     
    -  /* Disable tx int */
    +  /* Inform the next layer of the transmission success/failure */
     
    -  reg  = mrf24j40_getreg(dev->spi, MRF24J40_INTCON);
    -  reg |= MRF24J40_INTCON_TXNIE;
    -  mrf24j40_setreg(dev->spi, MRF24J40_INTCON, reg);
    +  dev->radiocb->txdone_gts(dev->radiocb, dev->gts_desc[gts].pub);
     
    -  /* Wake up the thread that triggered the transmission */
    +  /* We are now done with the transaction */
     
    -  /* sem_post(&dev->radio.txsem); */
    +  dev->gts_desc[gts].busy = 0;
     
    +  mrf24j40_dopoll_gts(dev);
     }
     
     /****************************************************************************
    @@ -1618,7 +1702,21 @@ static void mrf24j40_irqworker(FAR void *arg)
         {
           /* A packet was transmitted or failed*/
     
    -      mrf24j40_irqwork_tx(dev);
    +      mrf24j40_irqwork_txnorm(dev);
    +    }
    +
    +  if ((intstat & MRF24J40_INTSTAT_TXG1IF))
    +    {
    +      /* A packet was transmitted or failed*/
    +
    +      mrf24j40_irqwork_txgts(dev, 0);
    +    }
    +
    +  if ((intstat & MRF24J40_INTSTAT_TXG1IF))
    +    {
    +      /* A packet was transmitted or failed*/
    +
    +      mrf24j40_irqwork_txgts(dev, 1);
         }
     
       /* Re-enable GPIO interrupts */
    diff --git a/drivers/wireless/ieee802154/mrf24j40.h b/drivers/wireless/ieee802154/mrf24j40.h
    index 62b2bee888..96d00691d2 100644
    --- a/drivers/wireless/ieee802154/mrf24j40.h
    +++ b/drivers/wireless/ieee802154/mrf24j40.h
    @@ -97,9 +97,14 @@
     #define MRF24J40_BBREG6    0x3E
     #define MRF24J40_CCAEDTH   0x3F
     
    -#define MRF24J40_TXBUF_BASE     0x80000000
    -#define MRF24J40_LONGREG_BASE   0x80000200
    -#define MRF24J40_RXBUF_BASE     0x80000300
    +#define MRF24J40_FIFO_BASE     0x80000000
    +#define MRF24J40_LONGREG_BASE  0x80000200
    +#define MRF24J40_RXBUF_BASE    0x80000300
    +
    +#define MRF24J40_TXNORM_FIFO    (MRF24J40_FIFO_BASE + 0x000)
    +#define MRF24J40_BEACON_FIFO    (MRF24J40_FIFO_BASE + 0x080)
    +#define MRF24J40_GTS1_FIFO      (MRF24J40_FIFO_BASE + 0x100)
    +#define MRF24J40_GTS2_FIFO      (MRF24J40_FIFO_BASE + 0x180)
     
     #define MRF24J40_RFCON0    (MRF24J40_LONGREG_BASE + 0x00)
     #define MRF24J40_RFCON1    (MRF24J40_LONGREG_BASE + 0x01)
    @@ -210,6 +215,8 @@
     /* TXSTAT bits */
     
     #define MRF24J40_TXSTAT_TXNSTAT    (1 << 0)
    +#define MRF24J40_TXSTAT_TXG1STAT   (1 << 1)
    +#define MRF24J40_TXSTAT_TXG2STAT   (1 << 2)
     #define MRF24J40_TXSTAT_CCAFAIL    (1 << 5)
     #define MRF24J40_TXSTAT_X_SHIFT    6
     #define MRF24J40_TXSTAT_X_MASK     (3 << MRF24J40_TXSTAT_X_SHIFT)
    diff --git a/include/nuttx/wireless/ieee802154/ieee802154_radio.h b/include/nuttx/wireless/ieee802154/ieee802154_radio.h
    index e1c0ff3aea..ea22b6f1c1 100644
    --- a/include/nuttx/wireless/ieee802154/ieee802154_radio.h
    +++ b/include/nuttx/wireless/ieee802154/ieee802154_radio.h
    @@ -164,6 +164,9 @@ struct ieee802154_txdesc_s
     
       uint16_t psdu_length; /* The length of the PSDU */
     
    +  uint8_t status;       /* The status of the transaction.  This is set by the
    +                         * radio layer prior to calling txdone_csma */
    +
       /* TODO: Add slotting information for GTS transactions */
     };
     
    @@ -173,6 +176,10 @@ struct ieee802154_radiocb_s
                  FAR struct ieee802154_txdesc_s *tx_desc, FAR uint8_t *buf);
       CODE int (*poll_gts) (FAR struct ieee802154_radiocb_s *radiocb,
                  FAR struct ieee802154_txdesc_s *tx_desc, FAR uint8_t *buf);
    +  CODE int (*txdone_csma) (FAR struct ieee802154_radiocb_s *radiocb,
    +             FAR struct ieee802154_txdesc_s tx_desc);
    +  CODE int (*txdone_gts) (FAR struct ieee802154_radiocb_s *radiocb,
    +             FAR struct ieee802154_txdesc_s tx_desc);
     };
     
     struct ieee802154_radio_s; /* Forward reference */
    diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c
    index 5ea09c2546..0977c72b92 100644
    --- a/wireless/ieee802154/mac802154.c
    +++ b/wireless/ieee802154/mac802154.c
    @@ -235,7 +235,7 @@ struct ieee802154_privmac_s
       uint32_t is_coord           : 1;  /* Is this device acting as coordinator */
                                         /* 12-bits remaining */
     
    -  /* End of 32-bit bitfield. 
    +  /* End of 32-bit bitfield. */
     
       /* TODO: Add Security-related MAC PIB attributes */
     };
    @@ -380,7 +380,7 @@ MACHANDLE mac802154_create(FAR struct ieee802154_radio_s *radiodev)
       mac->radiocb.priv = mac;
     
       radiocb             = &mac->radiocb.cb;
    -  radiocb->poll_cmsa  = mac802154_poll_csma;
    +  radiocb->poll_csma  = mac802154_poll_csma;
       radiocb->poll_gts   = mac802154_poll_gts;
     
       /* Bind our callback structure */
    -- 
    GitLab
    
    
    From 9a1fe0b9719c756d11d74c0f57d17ae56b8d2bde Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Wed, 19 Apr 2017 14:52:45 -0600
    Subject: [PATCH 522/990] ieee802154:  Cosmetic changes from review of last PR.
    
    ---
     drivers/wireless/ieee802154/mrf24j40.c        | 42 +++++++++++--------
     drivers/wireless/ieee802154/mrf24j40.h        |  8 ++--
     .../wireless/ieee802154/ieee802154_radio.h    |  2 -
     3 files changed, 29 insertions(+), 23 deletions(-)
    
    diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c
    index ffdd0689d4..bd773e8aaa 100644
    --- a/drivers/wireless/ieee802154/mrf24j40.c
    +++ b/drivers/wireless/ieee802154/mrf24j40.c
    @@ -163,7 +163,7 @@ static int  mrf24j40_regdump(FAR struct mrf24j40_radio_s *dev);
     static void mrf24j40_irqwork_rx(FAR struct mrf24j40_radio_s *dev);
     static void mrf24j40_irqwork_txnorm(FAR struct mrf24j40_radio_s *dev);
     static void mrf24j40_irqwork_txgts(FAR struct mrf24j40_radio_s *dev,
    -                                   uint8_t gts_num);
    +              uint8_t gts_num);
     
     static void mrf24j40_irqworker(FAR void *arg);
     static int  mrf24j40_interrupt(int irq, FAR void *context, FAR void *arg);
    @@ -171,13 +171,12 @@ static int  mrf24j40_interrupt(int irq, FAR void *context, FAR void *arg);
     static void mrf24j40_dopoll_csma(FAR void *arg);
     static void mrf24j40_dopoll_gts(FAR void *arg);
     
    -static int mrf24j40_csma_setup(FAR struct mrf24j40_radio_s *dev,
    -             uint8_t *buf, uint16_t buf_len);
    -static int mrf24j40_gts_setup(FAR struct mrf24j40_radio_s *dev, uint8_t gts,
    -             uint8_t *buf, uint16_t buf_len);
    -static int mrf24j40_setup_fifo(FAR struct mrf24j40_radio_s *dev,
    -                               uint8_t *buf, uint16_t buf_len,
    -                               uint32_t fifo_addr);
    +static int  mrf24j40_csma_setup(FAR struct mrf24j40_radio_s *dev,
    +              FAR uint8_t *buf, uint16_t buf_len);
    +static int  mrf24j40_gts_setup(FAR struct mrf24j40_radio_s *dev, uint8_t gts,
    +              FAR uint8_t *buf, uint16_t buf_len);
    +static int  mrf24j40_setup_fifo(FAR struct mrf24j40_radio_s *dev,
    +              FAR uint8_t *buf, uint16_t buf_len, uint32_t fifo_addr);
     
     /* IOCTL helpers */
     
    @@ -225,7 +224,7 @@ static int  mrf24j40_ioctl(FAR struct ieee802154_radio_s *radio, int cmd,
     static int  mrf24j40_rxenable(FAR struct ieee802154_radio_s *radio,
                   bool state, FAR struct ieee802154_packet_s *packet);
     static int  mrf24j40_transmit(FAR struct ieee802154_radio_s *radio,
    -              uint8_t *buf, uint16_t buf_len);
    +              FAR uint8_t *buf, uint16_t buf_len);
     static int mrf24j40_txnotify_csma(FAR struct ieee802154_radio_s *radio);
     static int mrf24j40_txnotify_gts(FAR struct ieee802154_radio_s *radio);
     
    @@ -1340,7 +1339,7 @@ static int mrf24j40_energydetect(FAR struct mrf24j40_radio_s *dev,
      ****************************************************************************/
     
     static int mrf24j40_transmit(FAR struct ieee802154_radio_s *radio,
    -                             uint8_t *buf, uint16_t buf_len)
    +                             FAR uint8_t *buf, uint16_t buf_len)
     {
       FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)radio;
       uint8_t  reg;
    @@ -1384,10 +1383,10 @@ static int mrf24j40_transmit(FAR struct ieee802154_radio_s *radio,
      ****************************************************************************/
     
     static int mrf24j40_csma_setup(FAR struct mrf24j40_radio_s *dev,
    -                               uint8_t *buf, uint16_t buf_len)
    +                               FAR uint8_t *buf, uint16_t buf_len)
     {
    -  uint8_t  reg;
    -  int      ret;
    +  uint8_t reg;
    +  int     ret;
     
       mrf24j40_pacontrol(dev, MRF24J40_PA_AUTO);
     
    @@ -1427,13 +1426,20 @@ static int mrf24j40_csma_setup(FAR struct mrf24j40_radio_s *dev,
      ****************************************************************************/
     
     static int mrf24j40_gts_setup(FAR struct mrf24j40_radio_s *dev, uint8_t fifo,
    -                              uint8_t *buf, uint16_t buf_len)
    +                              FAR uint8_t *buf, uint16_t buf_len)
     {
       return -ENOTTY;
     }
     
    +/****************************************************************************
    + * Name: mrf24j40_setup_fifo
    + *
    + * Description:
    + *
    + ****************************************************************************/
    +
     static int mrf24j40_setup_fifo(FAR struct mrf24j40_radio_s *dev,
    -                               uint8_t *buf, uint16_t buf_len,
    +                               FAR uint8_t *buf, uint16_t buf_len,
                                    uint32_t fifo_addr)
     {
       int      ret;
    @@ -1506,7 +1512,8 @@ static void mrf24j40_irqwork_txnorm(FAR struct mrf24j40_radio_s *dev)
     
       /* Get the status from the device and copy the status into the tx desc.
        * The status for the normal FIFO is represented with bit TXNSTAT where
    -   * 0=success, 1= failure */
    +   * 0=success, 1= failure.
    +   */
     
       txstat = mrf24j40_getreg(dev->spi, MRF24J40_TXSTAT);
       dev->csma_desc.pub.status = txstat & MRF24J40_TXSTAT_TXNSTAT;
    @@ -1543,7 +1550,8 @@ static void mrf24j40_irqwork_txgts(FAR struct mrf24j40_radio_s *dev,
     
       /* Get the status from the device and copy the status into the tx desc.
        * The status for the normal FIFO is represented with bit TXNSTAT where
    -   * 0=success, 1= failure */
    +   * 0=success, 1= failure.
    +   */
     
       txstat = mrf24j40_getreg(dev->spi, MRF24J40_TXSTAT);
     
    diff --git a/drivers/wireless/ieee802154/mrf24j40.h b/drivers/wireless/ieee802154/mrf24j40.h
    index 96d00691d2..585fae513a 100644
    --- a/drivers/wireless/ieee802154/mrf24j40.h
    +++ b/drivers/wireless/ieee802154/mrf24j40.h
    @@ -101,10 +101,10 @@
     #define MRF24J40_LONGREG_BASE  0x80000200
     #define MRF24J40_RXBUF_BASE    0x80000300
     
    -#define MRF24J40_TXNORM_FIFO    (MRF24J40_FIFO_BASE + 0x000)
    -#define MRF24J40_BEACON_FIFO    (MRF24J40_FIFO_BASE + 0x080)
    -#define MRF24J40_GTS1_FIFO      (MRF24J40_FIFO_BASE + 0x100)
    -#define MRF24J40_GTS2_FIFO      (MRF24J40_FIFO_BASE + 0x180)
    +#define MRF24J40_TXNORM_FIFO   (MRF24J40_FIFO_BASE + 0x000)
    +#define MRF24J40_BEACON_FIFO   (MRF24J40_FIFO_BASE + 0x080)
    +#define MRF24J40_GTS1_FIFO     (MRF24J40_FIFO_BASE + 0x100)
    +#define MRF24J40_GTS2_FIFO     (MRF24J40_FIFO_BASE + 0x180)
     
     #define MRF24J40_RFCON0    (MRF24J40_LONGREG_BASE + 0x00)
     #define MRF24J40_RFCON1    (MRF24J40_LONGREG_BASE + 0x01)
    diff --git a/include/nuttx/wireless/ieee802154/ieee802154_radio.h b/include/nuttx/wireless/ieee802154/ieee802154_radio.h
    index ea22b6f1c1..af1281e36a 100644
    --- a/include/nuttx/wireless/ieee802154/ieee802154_radio.h
    +++ b/include/nuttx/wireless/ieee802154/ieee802154_radio.h
    @@ -161,9 +161,7 @@ struct ieee802154_netradio_s
     struct ieee802154_txdesc_s
     {
       uint8_t psdu_handle;  /* The psdu handle identifying the transaction */
    -
       uint16_t psdu_length; /* The length of the PSDU */
    -
       uint8_t status;       /* The status of the transaction.  This is set by the
                              * radio layer prior to calling txdone_csma */
     
    -- 
    GitLab
    
    
    From a5d73e42cdcc1ccb916bd728c15550a9dcb2f756 Mon Sep 17 00:00:00 2001
    From: Anthony Merlino 
    Date: Wed, 19 Apr 2017 18:15:09 -0400
    Subject: [PATCH 523/990] wireless/ieee802154: Fixes radio callback arguments
    
    ---
     drivers/wireless/ieee802154/mrf24j40.c               | 4 ++--
     include/nuttx/wireless/ieee802154/ieee802154_radio.h | 4 ++--
     2 files changed, 4 insertions(+), 4 deletions(-)
    
    diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c
    index bd773e8aaa..fe34ab1259 100644
    --- a/drivers/wireless/ieee802154/mrf24j40.c
    +++ b/drivers/wireless/ieee802154/mrf24j40.c
    @@ -1520,7 +1520,7 @@ static void mrf24j40_irqwork_txnorm(FAR struct mrf24j40_radio_s *dev)
     
       /* Inform the next layer of the transmission success/failure */
     
    -  dev->radiocb->txdone_csma(dev->radiocb, dev->csma_desc.pub);
    +  dev->radiocb->txdone_csma(dev->radiocb, &dev->csma_desc.pub);
     
       /* We are now done with the transaction */
     
    @@ -1566,7 +1566,7 @@ static void mrf24j40_irqwork_txgts(FAR struct mrf24j40_radio_s *dev,
     
       /* Inform the next layer of the transmission success/failure */
     
    -  dev->radiocb->txdone_gts(dev->radiocb, dev->gts_desc[gts].pub);
    +  dev->radiocb->txdone_gts(dev->radiocb, &dev->gts_desc[gts].pub);
     
       /* We are now done with the transaction */
     
    diff --git a/include/nuttx/wireless/ieee802154/ieee802154_radio.h b/include/nuttx/wireless/ieee802154/ieee802154_radio.h
    index af1281e36a..3dcde47e83 100644
    --- a/include/nuttx/wireless/ieee802154/ieee802154_radio.h
    +++ b/include/nuttx/wireless/ieee802154/ieee802154_radio.h
    @@ -175,9 +175,9 @@ struct ieee802154_radiocb_s
       CODE int (*poll_gts) (FAR struct ieee802154_radiocb_s *radiocb,
                  FAR struct ieee802154_txdesc_s *tx_desc, FAR uint8_t *buf);
       CODE int (*txdone_csma) (FAR struct ieee802154_radiocb_s *radiocb,
    -             FAR struct ieee802154_txdesc_s tx_desc);
    +             FAR const struct ieee802154_txdesc_s *tx_desc);
       CODE int (*txdone_gts) (FAR struct ieee802154_radiocb_s *radiocb,
    -             FAR struct ieee802154_txdesc_s tx_desc);
    +             FAR const struct ieee802154_txdesc_s *tx_desc);
     };
     
     struct ieee802154_radio_s; /* Forward reference */
    -- 
    GitLab
    
    
    From 9281cd558eb68a190b261bdd831fe1f6397d8b2a Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Wed, 19 Apr 2017 18:06:43 -0600
    Subject: [PATCH 524/990] 6loWPAN: Add an IOCTL to set the IEEE802.15.4 PAN ID
    
    ---
     include/nuttx/fs/ioctl.h          |  6 ++
     include/nuttx/net/ioctl.h         |  3 -
     include/nuttx/wireless/wireless.h | 71 +++++++++++++++++++----
     net/netdev/netdev_ioctl.c         | 94 +++++++++++++++++++++++++------
     net/sixlowpan/README.txt          |  4 +-
     5 files changed, 144 insertions(+), 34 deletions(-)
    
    diff --git a/include/nuttx/fs/ioctl.h b/include/nuttx/fs/ioctl.h
    index 86aaefae18..ce31d599ce 100644
    --- a/include/nuttx/fs/ioctl.h
    +++ b/include/nuttx/fs/ioctl.h
    @@ -233,6 +233,12 @@
     #define _MTDIOCVALID(c)   (_IOC_TYPE(c)==_MTDIOCBASE)
     #define _MTDIOC(nr)       _IOC(_MTDIOCBASE,nr)
     
    +/* Socket IOCTLs ************************************************************/
    +/* See include/nuttx/net/ioctl.h */
    +
    +#define _SIOCVALID(c)    (_IOC_TYPE(c)==_SIOCBASE)
    +#define _SIOC(nr)        _IOC(_SIOCBASE,nr)
    +
     /* NuttX ARP driver ioctl definitions (see netinet/arp.h) *******************/
     
     #define _ARPIOCVALID(c)   (_IOC_TYPE(c)==_ARPIOCBASE)
    diff --git a/include/nuttx/net/ioctl.h b/include/nuttx/net/ioctl.h
    index 2c31e63428..69c513b489 100644
    --- a/include/nuttx/net/ioctl.h
    +++ b/include/nuttx/net/ioctl.h
    @@ -51,9 +51,6 @@
      * masks, and hardware address, and a few others
      */
     
    -#define _SIOCVALID(c)   (_IOC_TYPE(c)==_SIOCBASE)
    -#define _SIOC(nr)       _IOC(_SIOCBASE,nr)
    -
     /* IPv4 interface control operations */
     
     #define SIOCGIFADDR      _SIOC(0x0001)  /* Get IP address */
    diff --git a/include/nuttx/wireless/wireless.h b/include/nuttx/wireless/wireless.h
    index bd9f93ba8f..0b67366e79 100644
    --- a/include/nuttx/wireless/wireless.h
    +++ b/include/nuttx/wireless/wireless.h
    @@ -37,8 +37,8 @@
      * (when applicable).
      */
     
    -#ifndef __INCLUDE_NUTTX_WIRELESS_H
    -#define __INCLUDE_NUTTX_WIRELESS_H
    +#ifndef __INCLUDE_NUTTX_WIRELESS_WIRELESS_H
    +#define __INCLUDE_NUTTX_WIRELESS_WIRELESS_H
     
     /************************************************************************************
      * Included Files
    @@ -63,6 +63,7 @@
      * interface.
      */
     
    +/* IEEE802.11 */
     /* Wireless identification */
     
     #define SIOCSIWCOMMIT       _WLIOC(0x0001)  /* Commit pending changes to driver */
    @@ -153,8 +154,24 @@
     
     #define SIOCSIWPMKSA        _WLIOC(0x0032)  /* PMKSA cache operation */
     
    -#define WL_FIRSTCHAR        0x0033
    -#define WL_NNETCMDS         0x0032
    +/* IEEE802.15.4 6loWPAN
    + *
    + *  IEEE802.15.4 IOCTLs may be directed at one of three layers:
    + *
    + *  1. To the 6loWPAN network layer, as documented here,
    + *  2. To the IEEE802.15.4 MAC layer, as documented in,
    + *     include/nuttx/wireless/ieee802154/ioeee802154_mac.h, or to
    + *  3. To the IEEE802.15.4 radio device layer, as documented in,
    + *     include/nuttx/wireless/ieee802154/ioeee802154_radio.h.
    + *
    + * SIOCSWPANID - Join the specified PAN ID
    + */
    +
    +#define SIOCSWPANID         _WLIOC(0x0033)  /* Join PAN ID */
    +#define SIOCGWPANID         _WLIOC(0x0034)  /* Return PAN ID */
    +
    +#define WL_FIRSTCHAR        0x0035
    +#define WL_NNETCMDS         0x0034
     
     /* Character Driver IOCTL commands *************************************************/
     /* Non-compatible, NuttX only IOCTL definitions for use with low-level wireless
    @@ -162,23 +179,23 @@
      * requires a file descriptor created by the open() interface.
      */
     
    -#define WLIOC_SETRADIOFREQ  _WLIOC(0x0033)  /* arg: Pointer to uint32_t, frequency
    +#define WLIOC_SETRADIOFREQ  _WLIOC(0x0035)  /* arg: Pointer to uint32_t, frequency
                                                  * value (in Mhz) */
    -#define WLIOC_GETRADIOFREQ  _WLIOC(0x0034)  /* arg: Pointer to uint32_t, frequency
    +#define WLIOC_GETRADIOFREQ  _WLIOC(0x0036)  /* arg: Pointer to uint32_t, frequency
                                                  * value (in Mhz) */
    -#define WLIOC_SETADDR       _WLIOC(0x0035)  /* arg: Pointer to address value, format
    +#define WLIOC_SETADDR       _WLIOC(0x0037)  /* arg: Pointer to address value, format
                                                  * of the address is driver specific */
    -#define WLIOC_GETADDR       _WLIOC(0x0036)  /* arg: Pointer to address value, format
    +#define WLIOC_GETADDR       _WLIOC(0x0038)  /* arg: Pointer to address value, format
                                                  * of the address is driver specific */
    -#define WLIOC_SETTXPOWER    _WLIOC(0x0037)  /* arg: Pointer to int32_t, output power
    +#define WLIOC_SETTXPOWER    _WLIOC(0x0039)  /* arg: Pointer to int32_t, output power
                                                  * (in dBm) */
    -#define WLIOC_GETTXPOWER    _WLIOC(0x0038)  /* arg: Pointer to int32_t, output power
    +#define WLIOC_GETTXPOWER    _WLIOC(0x003a)  /* arg: Pointer to int32_t, output power
                                                  * (in dBm) */
     
     /* Device-specific IOCTL commands **************************************************/
     
     #define WL_FIRST            0x0001          /* First common command */
    -#define WL_NCMDS            0x0038          /* Number of common commands */
    +#define WL_NCMDS            0x003a          /* Number of common commands */
     
     /* User defined ioctl commands are also supported. These will be forwarded
      * by the upper-half QE driver to the lower-half QE driver via the ioctl()
    @@ -355,5 +372,35 @@ struct iw_event
       union iwreq_data   u;     /* Fixed IOCTL payload */
     };
     
    +/* 6loWPAN */
    +/* This structure is used with the SIOCSWPANID IOCTL command to select the
    + * PAN ID to join.
    + */
    +
    +struct sixlowpan_panid_s
    +{
    +  uint16_t           panid; /* The PAN ID to join */
    +};
    +
    +/* This union defines the data payload of an 6loWPAN or SIOCGWPANID ioctl
    + * command and is used in struct sixlowpan_req_s below.
    + */
    +
    +union sixlowpan_data
    +{
    +  struct sixlowpan_panid_s panid;  /* PAN ID to join */
    +};
    +
    +/* This is the structure used to exchange data in wireless IOCTLs.  This
    + * structure is the same as 'struct ifreq', but defined for use with
    + * 6loWPAN IOCTLs.
    + */
    +
    +struct sixlowpan_req_s
    +{
    +  char ifr_name[IFNAMSIZ];  /* Interface name, e.g. "wpan0" */
    +  union sixlowpan_data u;   /* Data payload */
    +};
    +
     #endif /* CONFIG_DRIVERS_WIRELESS */
    -#endif /* __INCLUDE_NUTTX_WIRELESS_H */
    +#endif /* __INCLUDE_NUTTX_WIRELESS_WIRELESS_H */
    diff --git a/net/netdev/netdev_ioctl.c b/net/netdev/netdev_ioctl.c
    index a0c58491df..7f2efbf982 100644
    --- a/net/netdev/netdev_ioctl.c
    +++ b/net/netdev/netdev_ioctl.c
    @@ -61,6 +61,7 @@
     
     #ifdef CONFIG_NET_6LOWPAN
     #  include 
    +#  include 
     #endif
     
     #ifdef CONFIG_NET_IGMP
    @@ -321,32 +322,73 @@ static void ioctl_set_ipv6addr(FAR net_ipv6addr_t outaddr,
     #endif
     
     /****************************************************************************
    - * Name: netdev_wifr_dev
    + * Name: netdev_sixlowpan_ioctl
      *
      * Description:
    - *   Verify the struct iwreq and get the Wireless device.
    + *   Perform 6loWPAN network device specific operations.
      *
      * Parameters:
    - *   req - The argument of the ioctl cmd
    + *   psock    Socket structure
    + *   dev      Ethernet driver device structure
    + *   cmd      The ioctl command
    + *   req      The argument of the ioctl cmd
      *
      * Return:
    - *  A pointer to the driver structure on success; NULL on failure.
    + *   >=0 on success (positive non-zero values are cmd-specific)
    + *   Negated errno returned on failure.
      *
      ****************************************************************************/
     
    -#if defined(CONFIG_NETDEV_IOCTL) && defined(CONFIG_NETDEV_WIRELESS_IOCTL)
    -static FAR struct net_driver_s *netdev_wifr_dev(FAR struct iwreq *req)
    +#if defined(CONFIG_NETDEV_IOCTL) && defined(CONFIG_NET_6LOWPAN)
    +static int netdev_sixlowpan_ioctl(FAR struct socket *psock, int cmd,
    +                                  FAR struct sixlowpan_req_s *req)
     {
    -  if (req != NULL)
    +  FAR struct ieee802154_driver_s *ieee;
    +  int ret = -ENOTTY;
    +
    +  /* Verify that this is a valid wireless network IOCTL command */
    +
    +  if (_WLIOCVALID(cmd) && (unsigned)_IOC_NR(cmd) <= WL_NNETCMDS)
         {
    -      /* Find the network device associated with the device name
    -       * in the request data.
    -       */
    +      switch (cmd)
    +        {
     
    -      return netdev_findbyname(req->ifrn_name);
    +          case SIOCSWPANID:  /* Join PAN ID */
    +            {
    +              ieee = (FAR struct ieee802154_driver_s *)netdev_findbyname(req->ifr_name);
    +              if (ieee == NULL)
    +                {
    +                  ret = -ENODEV;
    +                }
    +              else
    +                {
    +                  ieee->i_panid = req->u.panid.panid;
    +                  ret = OK;
    +                }
    +            }
    +            break;
    +
    +          case SIOCGWPANID:   /* Return PAN ID */
    +            {
    +              ieee = (FAR struct ieee802154_driver_s *)netdev_findbyname(req->ifr_name);
    +              if (ieee == NULL)
    +                {
    +                  ret = -ENODEV;
    +                }
    +              else
    +                {
    +                  req->u.panid.panid = ieee->i_panid;
    +                  ret = OK;
    +                }
    +            }
    +            break;
    +
    +          default:
    +            return -ENOTTY;
    +        }
         }
     
    -  return NULL;
    +  return ret;
     }
     #endif
     
    @@ -381,8 +423,8 @@ static int netdev_wifr_ioctl(FAR struct socket *psock, int cmd,
         {
           /* Get the wireless device associated with the IOCTL command */
     
    -      dev = netdev_wifr_dev(req);
    -      if (dev)
    +      dev = netdev_findbyname(req->ifrn_name);
    +      if (dev != NULL)
             {
               /* Just forward the IOCTL to the wireless driver */
     
    @@ -1209,7 +1251,11 @@ int psock_ioctl(FAR struct socket *psock, int cmd, unsigned long arg)
        * non-NULL.
        */
     
    +#ifdef CONFIG_DRIVERS_WIRELESS
    +  if (!_SIOCVALID(cmd) && !_WLIOCVALID(cmd))
    +#else
       if (!_SIOCVALID(cmd))
    +#endif
         {
           ret = -ENOTTY;
           goto errout;
    @@ -1227,13 +1273,27 @@ int psock_ioctl(FAR struct socket *psock, int cmd, unsigned long arg)
     
       ret = netdev_ifr_ioctl(psock, cmd, (FAR struct ifreq *)((uintptr_t)arg));
     
    +#if defined(CONFIG_NETDEV_IOCTL) && defined(CONFIG_NET_6LOWPAN)
    +  /* Check for a 6loWPAN network command */
    +
    +  if (ret == -ENOTTY)
    +    {
    +      FAR struct sixlowpan_req_s *slpreq;
    +
    +      slpreq = (FAR struct sixlowpan_req_s *)((uintptr_t)arg);
    +      ret    = netdev_sixlowpan_ioctl(psock, cmd, slpreq);
    +    }
    +#endif
    +
     #if defined(CONFIG_NETDEV_IOCTL) && defined(CONFIG_NETDEV_WIRELESS_IOCTL)
    -  /* Check a wireless network command */
    +  /* Check for a wireless network command */
     
       if (ret == -ENOTTY)
         {
    -      ret = netdev_wifr_ioctl(psock, cmd,
    -                              (FAR struct iwreq *)((uintptr_t)arg));
    +      FAR struct iwreq *wifrreq;
    +
    +      wifrreq = (FAR struct sixlowpan_req_s *)((uintptr_t)arg);
    +      ret     = netdev_wifr_ioctl(psock, cmd, wifrreq);
         }
     #endif
     
    diff --git a/net/sixlowpan/README.txt b/net/sixlowpan/README.txt
    index 7a65c77ade..a311f5408d 100644
    --- a/net/sixlowpan/README.txt
    +++ b/net/sixlowpan/README.txt
    @@ -47,7 +47,7 @@ The length of the fragment header length is four bytes for the first header
     (FRAG1) and five bytes for all subsequent headers (FRAGN).  For example,
     this is a HC1 compressed first frame of a packet
     
    -  41 88 01 0000 3412 cdab                       ### 9-byte MAC header
    +  41 88 01 cefa 3412 cdab                       ### 9-byte MAC header
       c50e 000b                                     ### 4-byte FRAG1 header
       42                                            ### SIXLOWPAN_DISPATCH_HC1
         fb                                          ### RIME_HC1_HC_UDP_HC1_ENCODING
    @@ -64,7 +64,7 @@ this is a HC1 compressed first frame of a packet
     
     This is the second frame of the same transfer:
     
    -  41 88 01 0000 3412 cdab                       ### 9-byte MAC header
    +  41 88 01 cefa 3412 cdab                       ### 9-byte MAC header
       e50e 000b 0a                                  ### 5 byte FRAGN header
       42                                            ### SIXLOWPAN_DISPATCH_HC1
         fb                                          ### RIME_HC1_HC_UDP_HC1_ENCODING
    -- 
    GitLab
    
    
    From e97108344907c6a47548ee0f5872c881662ca2fd Mon Sep 17 00:00:00 2001
    From: "Nobutaka.Toyoshima" 
    Date: Mon, 28 Apr 2014 11:07:10 +0900
    Subject: [PATCH 525/990] procfs: Fix wrong member IDs are displayed when 'cat
     /proc//group/stasus'.
    
    Jira: PDFW15IS-259
    Signed-off-by: Masayuki Ishikawa 
    ---
     fs/procfs/fs_procfsproc.c | 2 +-
     1 file changed, 1 insertion(+), 1 deletion(-)
    
    diff --git a/fs/procfs/fs_procfsproc.c b/fs/procfs/fs_procfsproc.c
    index c8824b9ca0..2cf0b7de0e 100644
    --- a/fs/procfs/fs_procfsproc.c
    +++ b/fs/procfs/fs_procfsproc.c
    @@ -871,7 +871,7 @@ static ssize_t proc_groupstatus(FAR struct proc_file_s *procfile,
     
       for (i = 0; i < group->tg_nmembers; i++)
         {
    -      linesize   = snprintf(procfile->line, STATUS_LINELEN, " %d");
    +      linesize   = snprintf(procfile->line, STATUS_LINELEN, " %d", group->tg_members[i]);
           copysize   = procfs_memcpy(procfile->line, linesize, buffer, remaining, &offset);
     
           totalsize += copysize;
    -- 
    GitLab
    
    
    From e631ee4582f3060090951fa89aa48e07ac66c826 Mon Sep 17 00:00:00 2001
    From: Juha Niskanen 
    Date: Thu, 20 Apr 2017 06:28:01 -0600
    Subject: [PATCH 526/990] STM32 L1: stm32l15xx_rcc: Allow board to configure
     HSE clock in bypass-mode.  Allows using MCO output from ST-link chip (on
     Nucleo and Discovery boards) as HSE input.
    
    ---
     arch/arm/src/stm32/stm32l15xxx_rcc.c | 4 ++++
     1 file changed, 4 insertions(+)
    
    diff --git a/arch/arm/src/stm32/stm32l15xxx_rcc.c b/arch/arm/src/stm32/stm32l15xxx_rcc.c
    index 2624fade10..8640934e99 100644
    --- a/arch/arm/src/stm32/stm32l15xxx_rcc.c
    +++ b/arch/arm/src/stm32/stm32l15xxx_rcc.c
    @@ -480,7 +480,11 @@ static inline bool stm32_rcc_enablehse(void)
       /* Enable External High-Speed Clock (HSE) */
     
       regval  = getreg32(STM32_RCC_CR);
    +#ifdef STM32_HSEBYP_ENABLE          /* May be defined in board.h header file */
    +  regval |= RCC_CR_HSEBYP;          /* Enable HSE clock bypass */
    +#else
       regval &= ~RCC_CR_HSEBYP;         /* Disable HSE clock bypass */
    +#endif
       regval |= RCC_CR_HSEON;           /* Enable HSE */
       putreg32(regval, STM32_RCC_CR);
     
    -- 
    GitLab
    
    
    From 9d0ecedf7de8d0333b49fcf57eafbf96a0a22e8e Mon Sep 17 00:00:00 2001
    From: Juha Niskanen 
    Date: Thu, 20 Apr 2017 06:30:26 -0600
    Subject: [PATCH 527/990] Add support for STM32L152CC, STM32L152RC and
     STM32L152VC.  Update some bits and comments for other STM32L1 parts in chip.h
    
    ---
     arch/arm/include/stm32/chip.h | 107 ++++++++++++++++++++++++----
     arch/arm/src/stm32/Kconfig    | 130 +++++++++++++++++++++-------------
     2 files changed, 175 insertions(+), 62 deletions(-)
    
    diff --git a/arch/arm/include/stm32/chip.h b/arch/arm/include/stm32/chip.h
    index df921df4b8..b56a6b3d61 100644
    --- a/arch/arm/include/stm32/chip.h
    +++ b/arch/arm/include/stm32/chip.h
    @@ -108,7 +108,7 @@
     #  define STM32_NLCD                     0   /* No LCD */
     #  define STM32_NUSBOTG                  0   /* No USB OTG FS/HS (only USB 2.0 device) */
     #  define STM32_NGPIO                    37  /* GPIOA-E,H */
    -#  define STM32_NADC                     1   /* ADC1, 16-channels */
    +#  define STM32_NADC                     1   /* ADC1, 14-channels */
     #  define STM32_NDAC                     2   /* DAC 1-2, 2 channels */
                                                  /* (2) Comparators */
     #  define STM32_NCAPSENSE                13  /* Capacitive sensing channels */
    @@ -228,10 +228,10 @@
     #  define STM32_NI2C                     2   /* I2C1-2 */
     #  define STM32_NCAN                     0   /* No CAN */
     #  define STM32_NSDIO                    0   /* No SDIO */
    -#  define STM32_NLCD                     1   /* LCD 4x16 */
    +#  define STM32_NLCD                     1   /* LCD 4x18 */
     #  define STM32_NUSBOTG                  0   /* No USB OTG FS/HS (only USB 2.0 device) */
     #  define STM32_NGPIO                    37  /* GPIOA-E,H */
    -#  define STM32_NADC                     1   /* ADC1, 16-channels */
    +#  define STM32_NADC                     1   /* ADC1, 14-channels */
     #  define STM32_NDAC                     2   /* DAC 1-2, 2 channels */
                                                  /* (2) Comparators */
     #  define STM32_NCAPSENSE                13  /* Capacitive sensing channels */
    @@ -310,7 +310,7 @@
     #  define STM32_NI2C                     2   /* I2C1-2 */
     #  define STM32_NCAN                     0   /* No CAN */
     #  define STM32_NSDIO                    0   /* No SDIO */
    -#  define STM32_NLCD                     1   /* LCD 4x44, 8x40*/
    +#  define STM32_NLCD                     1   /* LCD 4x44, 8x40 */
     #  define STM32_NUSBOTG                  0   /* No USB OTG FS/HS (only USB 2.0 device) */
     #  define STM32_NGPIO                    83  /* GPIOA-E,H */
     #  define STM32_NADC                     1   /* ADC1, 24-channels */
    @@ -322,6 +322,46 @@
     #  define STM32_NRNG                     0   /* No random number generator (RNG) */
     #  define STM32_NDCMI                    0   /* No digital camera interface (DCMI) */
     
    +#elif defined(CONFIG_ARCH_CHIP_STM32L152CC)
    +#  define CONFIG_STM32_STM32L15XX        1   /* STM32L151xx and STM32L152xx family */
    +#  define CONFIG_STM32_ENERGYLITE        1   /* STM32L EnergyLite family */
    +#  undef  CONFIG_STM32_STM32F10XX            /* STM32F10xxx family */
    +#  undef  CONFIG_STM32_LOWDENSITY            /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes
    +                                              * and STM32L15xxx */
    +#  undef  CONFIG_STM32_MEDIUMDENSITY         /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
    +#  define CONFIG_STM32_MEDIUMPLUSDENSITY 1   /* STM32L15xxC w/ 32/256 Kbytes */
    +#  undef  CONFIG_STM32_HIGHDENSITY           /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */
    +#  undef  CONFIG_STM32_VALUELINE             /* STM32F100x */
    +#  undef  CONFIG_STM32_CONNECTIVITYLINE      /* STM32F105x and STM32F107x */
    +#  undef  CONFIG_STM32_STM32F20XX            /* STM32F205x and STM32F207x */
    +#  undef  CONFIG_STM32_STM32F30XX            /* STM32F30xxx family */
    +#  undef  CONFIG_STM32_STM32F33XX            /* STM32F33xxx family */
    +#  undef  CONFIG_STM32_STM32F37XX            /* STM32F37xxx family */
    +#  undef  CONFIG_STM32_STM32F40XX            /* STM32F405xx and STM32407xx families */
    +#  define STM32_NFSMC                    0   /* No FSMC */
    +#  define STM32_NATIM                    0   /* No advanced timers */
    +#  define STM32_NGTIM                    3   /* 16-bit general up/down timers TIM2-4 with DMA */
    +#  define STM32_NGTIMNDMA                3   /* 16-bit general timers TIM9-11 without DMA */
    +#  define STM32_NBTIM                    2   /* 2 basic timers: TIM6, TIM7 with DMA */
    +#  define STM32_NDMA                     2   /* DMA1, 7-channels, DMA2 (5 channels) */
    +#  define STM32_NSPI                     3   /* SPI1-3 */
    +#  define STM32_NI2S                     2   /* I2S1-2, overlapping with SPI2-3 */
    +#  define STM32_NUSART                   3   /* USART1-3 */
    +#  define STM32_NI2C                     2   /* I2C1-2 */
    +#  define STM32_NCAN                     0   /* No CAN */
    +#  define STM32_NSDIO                    0   /* No SDIO */
    +#  define STM32_NLCD                     1   /* LCD 4x18 */
    +#  define STM32_NUSBOTG                  1   /* USB OTG FS/HS (only USB 2.0 device) */
    +#  define STM32_NGPIO                    37  /* GPIOA-E,H */
    +#  define STM32_NADC                     1   /* ADC1, 14-channels */
    +#  define STM32_NDAC                     2   /* DAC 1-2, 2 channels */
    +                                             /* (2) Comparators */
    +#  define STM32_NCAPSENSE                16  /* Capacitive sensing channels */
    +#  define STM32_NCRC                     1   /* CRC */
    +#  define STM32_NETHERNET                0   /* No ethernet */
    +#  define STM32_NRNG                     0   /* No random number generator (RNG) */
    +#  define STM32_NDCMI                    0   /* No digital camera interface (DCMI) */
    +
     #elif defined(CONFIG_ARCH_CHIP_STM32L152RC)
     #  define CONFIG_STM32_STM32L15XX        1   /* STM32L151xx and STM32L152xx family */
     #  define CONFIG_STM32_ENERGYLITE        1   /* STM32L EnergyLite family */
    @@ -336,6 +376,7 @@
     #  undef  CONFIG_STM32_STM32F20XX            /* STM32F205x and STM32F207x */
     #  undef  CONFIG_STM32_STM32F30XX            /* STM32F30xxx family */
     #  undef  CONFIG_STM32_STM32F33XX            /* STM32F33xxx family */
    +#  undef  CONFIG_STM32_STM32F37XX            /* STM32F37xxx family */
     #  undef  CONFIG_STM32_STM32F40XX            /* STM32F405xx and STM32407xx families */
     #  define STM32_NFSMC                    0   /* No FSMC */
     #  define STM32_NATIM                    0   /* No advanced timers */
    @@ -349,13 +390,53 @@
     #  define STM32_NI2C                     2   /* I2C1-2 */
     #  define STM32_NCAN                     0   /* No CAN */
     #  define STM32_NSDIO                    0   /* No SDIO */
    -#  define STM32_NLCD                     1   /* LCD 4x44, 8x40*/
    +#  define STM32_NLCD                     1   /* LCD 4x32, 8x28 */
    +#  define STM32_NUSBOTG                  1   /* USB OTG FS/HS (only USB 2.0 device) */
    +#  define STM32_NGPIO                    51  /* GPIOA-E,H */
    +#  define STM32_NADC                     1   /* ADC1, 21-channels */
    +#  define STM32_NDAC                     2   /* DAC 1-2, 2 channels */
    +                                             /* (2) Comparators */
    +#  define STM32_NCAPSENSE                23  /* Capacitive sensing channels */
    +#  define STM32_NCRC                     1   /* CRC */
    +#  define STM32_NETHERNET                0   /* No ethernet */
    +#  define STM32_NRNG                     0   /* No random number generator (RNG) */
    +#  define STM32_NDCMI                    0   /* No digital camera interface (DCMI) */
    +
    +#elif defined(CONFIG_ARCH_CHIP_STM32L152VC)
    +#  define CONFIG_STM32_STM32L15XX        1   /* STM32L151xx and STM32L152xx family */
    +#  define CONFIG_STM32_ENERGYLITE        1   /* STM32L EnergyLite family */
    +#  undef  CONFIG_STM32_STM32F10XX            /* STM32F10xxx family */
    +#  undef  CONFIG_STM32_LOWDENSITY            /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes
    +                                              * and STM32L15xxx */
    +#  undef  CONFIG_STM32_MEDIUMDENSITY         /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
    +#  define CONFIG_STM32_MEDIUMPLUSDENSITY 1   /* STM32L15xxC w/ 32/256 Kbytes */
    +#  undef  CONFIG_STM32_HIGHDENSITY           /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */
    +#  undef  CONFIG_STM32_VALUELINE             /* STM32F100x */
    +#  undef  CONFIG_STM32_CONNECTIVITYLINE      /* STM32F105x and STM32F107x */
    +#  undef  CONFIG_STM32_STM32F20XX            /* STM32F205x and STM32F207x */
    +#  undef  CONFIG_STM32_STM32F30XX            /* STM32F30xxx family */
    +#  undef  CONFIG_STM32_STM32F33XX            /* STM32F33xxx family */
    +#  undef  CONFIG_STM32_STM32F37XX            /* STM32F37xxx family */
    +#  undef  CONFIG_STM32_STM32F40XX            /* STM32F405xx and STM32407xx families */
    +#  define STM32_NFSMC                    0   /* No FSMC */
    +#  define STM32_NATIM                    0   /* No advanced timers */
    +#  define STM32_NGTIM                    3   /* 16-bit general up/down timers TIM2-4 with DMA */
    +#  define STM32_NGTIMNDMA                3   /* 16-bit general timers TIM9-11 without DMA */
    +#  define STM32_NBTIM                    2   /* 2 basic timers: TIM6, TIM7 with DMA */
    +#  define STM32_NDMA                     2   /* DMA1, 7-channels, DMA2 (5 channels) */
    +#  define STM32_NSPI                     3   /* SPI1-3 */
    +#  define STM32_NI2S                     2   /* I2S1-2, overlapping with SPI2-3 */
    +#  define STM32_NUSART                   3   /* USART1-3 */
    +#  define STM32_NI2C                     2   /* I2C1-2 */
    +#  define STM32_NCAN                     0   /* No CAN */
    +#  define STM32_NSDIO                    0   /* No SDIO */
    +#  define STM32_NLCD                     1   /* LCD 4x44, 8x40 */
     #  define STM32_NUSBOTG                  1   /* USB OTG FS/HS (only USB 2.0 device) */
     #  define STM32_NGPIO                    83  /* GPIOA-E,H */
    -#  define STM32_NADC                     1   /* ADC1, 24-channels */
    +#  define STM32_NADC                     1   /* ADC1, 25-channels */
     #  define STM32_NDAC                     2   /* DAC 1-2, 2 channels */
                                                  /* (2) Comparators */
    -#  define STM32_NCAPSENSE                20  /* Capacitive sensing channels */
    +#  define STM32_NCAPSENSE                23  /* Capacitive sensing channels */
     #  define STM32_NCRC                     1   /* CRC */
     #  define STM32_NETHERNET                0   /* No ethernet */
     #  define STM32_NRNG                     0   /* No random number generator (RNG) */
    @@ -375,6 +456,7 @@
     #  undef  CONFIG_STM32_STM32F20XX            /* STM32F205x and STM32F207x */
     #  undef  CONFIG_STM32_STM32F30XX            /* STM32F30xxx family */
     #  undef  CONFIG_STM32_STM32F33XX            /* STM32F33xxx family */
    +#  undef  CONFIG_STM32_STM32F37XX            /* STM32F37xxx family */
     #  undef  CONFIG_STM32_STM32F40XX            /* STM32F405xx and STM32407xx families */
     #  define STM32_NFSMC                    1   /* FSMC */
     #  define STM32_NATIM                    0   /* No advanced timers */
    @@ -389,13 +471,13 @@
     #  define STM32_NI2C                     2   /* I2C1-2 */
     #  define STM32_NCAN                     0   /* No CAN */
     #  define STM32_NSDIO                    1   /* SDIO */
    -#  define STM32_NLCD                     1   /* LCD 4x44, 8x40*/
    +#  define STM32_NLCD                     1   /* LCD 4x44, 8x40 */
     #  define STM32_NUSBOTG                  1   /* USB OTG FS/HS (only USB 2.0 device) */
     #  define STM32_NGPIO                    115 /* GPIOA-G,H */
    -#  define STM32_NADC                     1   /* ADC1, 24-channels */
    +#  define STM32_NADC                     1   /* ADC1, 40-channels */
     #  define STM32_NDAC                     2   /* DAC 1-2, 2 channels */
                                                  /* (2) Comparators */
    -#  define STM32_NCAPSENSE                20  /* Capacitive sensing channels */
    +#  define STM32_NCAPSENSE                34  /* Capacitive sensing channels */
     #  define STM32_NCRC                     1   /* CRC */
     #  define STM32_NETHERNET                0   /* No ethernet */
     #  define STM32_NRNG                     0   /* No random number generator (RNG) */
    @@ -415,6 +497,7 @@
     #  undef  CONFIG_STM32_STM32F20XX            /* STM32F205x and STM32F207x */
     #  undef  CONFIG_STM32_STM32F30XX            /* STM32F30xxx family */
     #  undef  CONFIG_STM32_STM32F33XX            /* STM32F33xxx family */
    +#  undef  CONFIG_STM32_STM32F37XX            /* STM32F37xxx family */
     #  undef  CONFIG_STM32_STM32F40XX            /* STM32F405xx and STM32407xx families */
     #  define STM32_NFSMC                    0   /* No FSMC */
     #  define STM32_NATIM                    0   /* No advanced timers */
    @@ -433,8 +516,8 @@
     #  define STM32_NUSBOTG                  1   /* USB OTG FS/HS (only USB 2.0 device) */
     #  define STM32_NGPIO                    83  /* GPIOA-G,H */
     
    -#  define STM32_NADC                     1   /* ADC1, up to 40-channels (medium+ and high density). See for more information RM0038 Reference manual  */
    -#  define STM32_NDAC                     1   /* DAC 1, 2 channels. See for more information RM0038 Reference manual */
    +#  define STM32_NADC                     1   /* ADC1, 25-channels */
    +#  define STM32_NDAC                     2   /* DAC 1-2, 2 channels */
                                                  /* (2) Comparators */
     #  define STM32_NCAPSENSE                23  /* Capacitive sensing channels */
     #  define STM32_NCRC                     1   /* CRC */
    diff --git a/arch/arm/src/stm32/Kconfig b/arch/arm/src/stm32/Kconfig
    index 79c103ea9c..262017a34b 100644
    --- a/arch/arm/src/stm32/Kconfig
    +++ b/arch/arm/src/stm32/Kconfig
    @@ -16,7 +16,7 @@ config ARCH_CHIP_STM32L151C6
     	select STM32_STM32L15XX
     	select STM32_ENERGYLITE
     	---help---
    -		STM32L 48-pin EnergyLite, 32KB FLASH, 10KB SRAM, 4KB EEPRROM
    +		STM32L 48-pin EnergyLite, 32KB FLASH, 10KB SRAM, 4KB EEPROM
     
     config ARCH_CHIP_STM32L151C8
     	bool "STM32L151C8"
    @@ -24,7 +24,7 @@ config ARCH_CHIP_STM32L151C8
     	select STM32_STM32L15XX
     	select STM32_ENERGYLITE
     	---help---
    -		STM32L 48-pin EnergyLite, 64KB FLASH, 10KB SRAM, 4KB EEPRROM
    +		STM32L 48-pin EnergyLite, 64KB FLASH, 10KB SRAM, 4KB EEPROM
     
     config ARCH_CHIP_STM32L151CB
     	bool "STM32L151CB"
    @@ -32,7 +32,7 @@ config ARCH_CHIP_STM32L151CB
     	select STM32_STM32L15XX
     	select STM32_ENERGYLITE
     	---help---
    -		STM32L 48-pin EnergyLite, 128KB FLASH, 16KB SRAM, 4KB EEPRROM
    +		STM32L 48-pin EnergyLite, 128KB FLASH, 16KB SRAM, 4KB EEPROM
     
     config ARCH_CHIP_STM32L151R6
     	bool "STM32L151R6"
    @@ -40,7 +40,7 @@ config ARCH_CHIP_STM32L151R6
     	select STM32_STM32L15XX
     	select STM32_ENERGYLITE
     	---help---
    -		STM32L 64-pin EnergyLite, 32KB FLASH, 10KB SRAM, 4KB EEPRROM
    +		STM32L 64-pin EnergyLite, 32KB FLASH, 10KB SRAM, 4KB EEPROM
     
     config ARCH_CHIP_STM32L151R8
     	bool "STM32L151R8"
    @@ -48,7 +48,7 @@ config ARCH_CHIP_STM32L151R8
     	select STM32_STM32L15XX
     	select STM32_ENERGYLITE
     	---help---
    -		STM32L 64-pin EnergyLite, 64KB FLASH, 10KB SRAM, 4KB EEPRROM
    +		STM32L 64-pin EnergyLite, 64KB FLASH, 10KB SRAM, 4KB EEPROM
     
     config ARCH_CHIP_STM32L151RB
     	bool "STM32L151RB"
    @@ -56,7 +56,7 @@ config ARCH_CHIP_STM32L151RB
     	select STM32_STM32L15XX
     	select STM32_ENERGYLITE
     	---help---
    -		STM32L 64-pin EnergyLite, 128KB FLASH, 16KB SRAM, 4KB EEPRROM
    +		STM32L 64-pin EnergyLite, 128KB FLASH, 16KB SRAM, 4KB EEPROM
     
     config ARCH_CHIP_STM32L151V6
     	bool "STM32L151V6"
    @@ -64,7 +64,7 @@ config ARCH_CHIP_STM32L151V6
     	select STM32_STM32L15XX
     	select STM32_ENERGYLITE
     	---help---
    -		STM32L 100-pin EnergyLite, 32KB FLASH, 10KB SRAM, 4KB EEPRROM
    +		STM32L 100-pin EnergyLite, 32KB FLASH, 10KB SRAM, 4KB EEPROM
     
     config ARCH_CHIP_STM32L151V8
     	bool "STM32L151V8"
    @@ -72,7 +72,7 @@ config ARCH_CHIP_STM32L151V8
     	select STM32_STM32L15XX
     	select STM32_ENERGYLITE
     	---help---
    -		STM32L 100-pin EnergyLite, 64KB FLASH, 10KB SRAM, 4KB EEPRROM
    +		STM32L 100-pin EnergyLite, 64KB FLASH, 10KB SRAM, 4KB EEPROM
     
     config ARCH_CHIP_STM32L151VB
     	bool "STM32L151VB"
    @@ -80,7 +80,7 @@ config ARCH_CHIP_STM32L151VB
     	select STM32_STM32L15XX
     	select STM32_ENERGYLITE
     	---help---
    -		STM32L 100-pin EnergyLite, 128KB FLASH, 16KB SRAM, 4KB EEPRROM
    +		STM32L 100-pin EnergyLite, 128KB FLASH, 16KB SRAM, 4KB EEPROM
     
     config ARCH_CHIP_STM32L152C6
     	bool "STM32L152C6"
    @@ -88,8 +88,8 @@ config ARCH_CHIP_STM32L152C6
     	select STM32_STM32L15XX
     	select STM32_ENERGYLITE
     	---help---
    -		STM32L 48-pin EnergyLite, 32KB FLASH, 10KB SRAM, 4KB EEPRROM with
    -		4x16 LCD interface
    +		STM32L 48-pin EnergyLite, 32KB FLASH, 10KB SRAM, 4KB EEPROM with
    +		4x18 LCD interface
     
     config ARCH_CHIP_STM32L152C8
     	bool "STM32L152C8"
    @@ -97,8 +97,8 @@ config ARCH_CHIP_STM32L152C8
     	select STM32_STM32L15XX
     	select STM32_ENERGYLITE
     	---help---
    -		STM32L 48-pin EnergyLite, 64KB FLASH, 10KB SRAM, 4KB EEPRROM with
    -		4x16 LCD interface
    +		STM32L 48-pin EnergyLite, 64KB FLASH, 10KB SRAM, 4KB EEPROM with
    +		4x18 LCD interface
     
     config ARCH_CHIP_STM32L152CB
     	bool "STM32L152CB"
    @@ -106,8 +106,8 @@ config ARCH_CHIP_STM32L152CB
     	select STM32_STM32L15XX
     	select STM32_ENERGYLITE
     	---help---
    -		STM32L 48-pin EnergyLite, 128KB FLASH, 16KB SRAM, 4KB EEPRROM with
    -		4x16 LCD interface
    +		STM32L 48-pin EnergyLite, 128KB FLASH, 16KB SRAM, 4KB EEPROM with
    +		4x18 LCD interface
     
     config ARCH_CHIP_STM32L152R6
     	bool "STM32L152R6"
    @@ -115,7 +115,7 @@ config ARCH_CHIP_STM32L152R6
     	select STM32_STM32L15XX
     	select STM32_ENERGYLITE
     	---help---
    -		STM32L 64-pin EnergyLite, 32KB FLASH, 10KB SRAM, 4KB EEPRROM with
    +		STM32L 64-pin EnergyLite, 32KB FLASH, 10KB SRAM, 4KB EEPROM with
     		4x32/8x28 LCD interface
     
     config ARCH_CHIP_STM32L152R8
    @@ -124,7 +124,7 @@ config ARCH_CHIP_STM32L152R8
     	select STM32_STM32L15XX
     	select STM32_ENERGYLITE
     	---help---
    -		STM32L 64-pin EnergyLite, 64KB FLASH, 10KB SRAM, 4KB EEPRROM with
    +		STM32L 64-pin EnergyLite, 64KB FLASH, 10KB SRAM, 4KB EEPROM with
     		4x32/8x28 LCD interface
     
     config ARCH_CHIP_STM32L152RB
    @@ -133,7 +133,7 @@ config ARCH_CHIP_STM32L152RB
     	select STM32_STM32L15XX
     	select STM32_ENERGYLITE
     	---help---
    -		STM32L 64-pin EnergyLite, 128KB FLASH, 16KB SRAM, 4KB EEPRROM with
    +		STM32L 64-pin EnergyLite, 128KB FLASH, 16KB SRAM, 4KB EEPROM with
     		4x32/8x28 LCD interface
     
     config ARCH_CHIP_STM32L152V6
    @@ -142,7 +142,7 @@ config ARCH_CHIP_STM32L152V6
     	select STM32_STM32L15XX
     	select STM32_ENERGYLITE
     	---help---
    -		STM32L 100-pin EnergyLite, 32KB FLASH, 10KB SRAM, 4KB EEPRROM with
    +		STM32L 100-pin EnergyLite, 32KB FLASH, 10KB SRAM, 4KB EEPROM with
     		4x44/8x40 LCD interface
     
     config ARCH_CHIP_STM32L152V8
    @@ -151,7 +151,7 @@ config ARCH_CHIP_STM32L152V8
     	select STM32_STM32L15XX
     	select STM32_ENERGYLITE
     	---help---
    -		STM32L 100-pin EnergyLite, 64KB FLASH, 10KB SRAM, 4KB EEPRROM with
    +		STM32L 100-pin EnergyLite, 64KB FLASH, 10KB SRAM, 4KB EEPROM with
     		4x44/8x40 LCD interface
     
     config ARCH_CHIP_STM32L152VB
    @@ -160,7 +160,37 @@ config ARCH_CHIP_STM32L152VB
     	select STM32_STM32L15XX
     	select STM32_ENERGYLITE
     	---help---
    -		STM32L 100-pin EnergyLite, 128KB FLASH, 16KB SRAM, 4KB EEPRROM with
    +		STM32L 100-pin EnergyLite, 128KB FLASH, 16KB SRAM, 4KB EEPROM with
    +		4x44/8x40 LCD interface
    +
    +config ARCH_CHIP_STM32L152CC
    +	bool "STM32L152CC"
    +	select ARCH_CORTEXM3
    +	select STM32_STM32L15XX
    +	select STM32_ENERGYLITE
    +	select STM32_MEDIUMPLUSDENSITY
    +	---help---
    +		STM32L 48-pin EnergyLite, 256KB FLASH, 32KB SRAM, 8KB EEPROM with
    +		4x18 LCD interface
    +
    +config ARCH_CHIP_STM32L152RC
    +	bool "STM32L152RC"
    +	select ARCH_CORTEXM3
    +	select STM32_STM32L15XX
    +	select STM32_ENERGYLITE
    +	select STM32_MEDIUMPLUSDENSITY
    +	---help---
    +		STM32L 64-pin EnergyLite, 256KB FLASH, 32KB SRAM, 8KB EEPROM with
    +		4x32/8x28 LCD interface
    +
    +config ARCH_CHIP_STM32L152VC
    +	bool "STM32L152VC"
    +	select ARCH_CORTEXM3
    +	select STM32_STM32L15XX
    +	select STM32_ENERGYLITE
    +	select STM32_MEDIUMPLUSDENSITY
    +	---help---
    +		STM32L 100-pin EnergyLite, 256KB FLASH, 32KB SRAM, 8KB EEPROM with
     		4x44/8x40 LCD interface
     
     config ARCH_CHIP_STM32L162ZD
    @@ -171,8 +201,8 @@ config ARCH_CHIP_STM32L162ZD
     	select STM32_HIGHDENSITY
     	select STM32_HAVE_AES
     	---help---
    -		STM32L 144-pin EnergyLite, 384KB FLASH, 48KB SRAM, 12KB EEPRROM with
    -		8x40 LCD interface
    +		STM32L 144-pin EnergyLite, 384KB FLASH, 48KB SRAM, 12KB EEPROM with
    +		4x44/8x40 LCD interface
     
     config ARCH_CHIP_STM32L162VE
     	bool "STM32L162VE"
    @@ -182,8 +212,8 @@ config ARCH_CHIP_STM32L162VE
     	select STM32_HIGHDENSITY
     	select STM32_HAVE_AES
     	---help---
    -		STM32L 100-pin EnergyLite, 512KB FLASH, 80KB SRAM, 16KB EEPRROM with
    -		8x40 LCD interface
    +		STM32L 100-pin EnergyLite, 512KB FLASH, 80KB SRAM, 16KB EEPROM with
    +		4x44/8x40 LCD interface
     
     config ARCH_CHIP_STM32F100C8
     	bool "STM32F100C8"
    @@ -1445,7 +1475,7 @@ config STM32_STM32F303
     
     config STM32_STM32F33XX
     	bool
    -       	default n
    +	default n
     	select STM32_HAVE_HRTIM1
     	select STM32_HAVE_COMP2
     	select STM32_HAVE_COMP4
    @@ -1715,8 +1745,8 @@ config STM32_STM32F469
     	select STM32_HAVE_SPI4
     	select STM32_HAVE_SPI5
     	select STM32_HAVE_SPI6
    -        select STM32_HAVE_SAIPLL
    -        select STM32_HAVE_I2SPLL
    +	select STM32_HAVE_SAIPLL
    +	select STM32_HAVE_I2SPLL
     
     
     config STM32_DFU
    @@ -1909,32 +1939,32 @@ config STM32_HAVE_CAN2
     	default n
     
     config STM32_HAVE_COMP1
    -       bool
    -       default n
    +	bool
    +	default n
     
     config STM32_HAVE_COMP2
    -       bool
    -       default n
    +	bool
    +	default n
     
     config STM32_HAVE_COMP3
    -       bool
    -       default n
    +	bool
    +	default n
     
     config STM32_HAVE_COMP4
    -       bool
    -       default n
    +	bool
    +	default n
     
     config STM32_HAVE_COMP5
    -       bool
    -       default n
    +	bool
    +	default n
     
     config STM32_HAVE_COMP6
    -       bool
    -       default n
    +	bool
    +	default n
     
     config STM32_HAVE_COMP7
    -       bool
    -       default n
    +	bool
    +	default n
     
     config STM32_HAVE_DAC1
     	bool
    @@ -1989,20 +2019,20 @@ config STM32_HAVE_I2SPLL
     	default n
     
     config STM32_HAVE_OPAMP1
    -       bool
    -       default n
    +	bool
    +	default n
     
     config STM32_HAVE_OPAMP2
    -       bool
    -       default n
    +	bool
    +	default n
     
     config STM32_HAVE_OPAMP3
    -       bool
    -       default n
    +	bool
    +	default n
     
     config STM32_HAVE_OPAMP4
    -       bool
    -       default n
    +	bool
    +	default n
     
     # These are the peripheral selections proper
     
    -- 
    GitLab
    
    
    From e3c9e9e0b8cc29b8555a2a20959c8f7031936129 Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Thu, 20 Apr 2017 06:50:01 -0600
    Subject: [PATCH 528/990] UART 16550: Missing left parenthesis in function
     prototype.  This is Bitbucket Issue #41.
    
    ---
     drivers/serial/uart_16550.c | 2 +-
     1 file changed, 1 insertion(+), 1 deletion(-)
    
    diff --git a/drivers/serial/uart_16550.c b/drivers/serial/uart_16550.c
    index ab532a49db..49d10eaac7 100644
    --- a/drivers/serial/uart_16550.c
    +++ b/drivers/serial/uart_16550.c
    @@ -90,7 +90,7 @@ struct u16550_s
     static int  u16550_setup(FAR struct uart_dev_s *dev);
     static void u16550_shutdown(FAR struct uart_dev_s *dev);
     static int  u16550_attach(FAR struct uart_dev_s *dev);
    -static void u16550_detachFAR struct uart_dev_s *dev);
    +static void u16550_detach(FAR struct uart_dev_s *dev);
     static int  u16550_interrupt(int irq, FAR void *context, FAR void *arg);
     static int  u16550_ioctl(FAR struct file *filep, int cmd, unsigned long arg);
     static int  u16550_receive(FAR struct uart_dev_s *dev, uint32_t *status);
    -- 
    GitLab
    
    
    From 547f6c7cc3575c367536e9c7e7dc9fc5d7cbebe1 Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Thu, 20 Apr 2017 07:50:55 -0600
    Subject: [PATCH 529/990] SIM: Fix some bad naming changes associated with the
     simulated touchscreen.
    
    ---
     arch/sim/src/up_internal.h        | 13 +++++++++----
     arch/sim/src/up_touchscreen.c     | 14 +++++---------
     configs/sim/src/sim_touchscreen.c | 12 ++++++++----
     3 files changed, 22 insertions(+), 17 deletions(-)
    
    diff --git a/arch/sim/src/up_internal.h b/arch/sim/src/up_internal.h
    index 7ca32a479e..9b26f11041 100644
    --- a/arch/sim/src/up_internal.h
    +++ b/arch/sim/src/up_internal.h
    @@ -1,7 +1,7 @@
     /****************************************************************************
      * arch/sim/src/up_internal.h
      *
    - *   Copyright (C) 2007, 2009, 2011-2012, 2014, 2016 Gregory Nutt. All rights reserved.
    + *   Copyright (C) 2007, 2009, 2011-2012, 2014, 2016-2017 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
      *
      * Redistribution and use in source and binary forms, with or without
    @@ -230,7 +230,7 @@ void up_longjmp(xcpt_reg_t *jb, int val) noreturn_function;
     /* up_simsmp.c ************************************************************/
     
     #ifdef CONFIG_SMP
    -int sim_cpu0_initialize(void);
    +int  sim_cpu0_initialize(void);
     void sim_cpu0_start(void);
     #endif
     
    @@ -261,8 +261,8 @@ void up_registerblockdevice(void);
     /* up_simuart.c ***********************************************************/
     
     void simuart_start(void);
    -int simuart_putc(int ch);
    -int simuart_getc(void);
    +int  simuart_putc(int ch);
    +int  simuart_getc(void);
     bool simuart_checkc(void);
     void simuart_terminate(void);
     
    @@ -295,6 +295,11 @@ int up_x11cmap(unsigned short first, unsigned short len,
     #endif
     #endif
     
    +/* up_touchscreen.c *******************************************************/
    +
    +int  sim_tsc_initialize(int minor);
    +void sim_tsc_uninitialize(void);
    +
     /* up_eventloop.c *********************************************************/
     
     #if defined(CONFIG_SIM_X11FB) && \
    diff --git a/arch/sim/src/up_touchscreen.c b/arch/sim/src/up_touchscreen.c
    index 4c327bb683..b8b864c89b 100644
    --- a/arch/sim/src/up_touchscreen.c
    +++ b/arch/sim/src/up_touchscreen.c
    @@ -1,7 +1,7 @@
     /****************************************************************************
      * arch/sim/src/up_touchscreen.c
      *
    - *   Copyright (C) 2011-2012, 2016 Gregory Nutt. All rights reserved.
    + *   Copyright (C) 2011-2012, 2016-2017 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
      *
      * Redistribution and use in source and binary forms, with or without
    @@ -624,11 +624,7 @@ errout:
      ****************************************************************************/
     
     /****************************************************************************
    - * Public Functions
    - ****************************************************************************/
    -
    -/****************************************************************************
    - * Name: board_tsc_setup
    + * Name: sim_tsc_initialize
      *
      * Description:
      *   Configure the simulated touchscreen.  This will register the driver as
    @@ -643,7 +639,7 @@ errout:
      *
      ****************************************************************************/
     
    -int board_tsc_setup(int minor)
    +int sim_tsc_initialize(int minor)
     {
       FAR struct up_dev_s *priv = (FAR struct up_dev_s *)&g_simtouchscreen;
       char devname[DEV_NAMELEN];
    @@ -699,7 +695,7 @@ errout_with_priv:
     }
     
     /****************************************************************************
    - * Name: board_tsc_teardown
    + * Name: sim_tsc_uninitialize
      *
      * Description:
      *   Uninitialized the simulated touchscreen
    @@ -712,7 +708,7 @@ errout_with_priv:
      *
      ****************************************************************************/
     
    -void board_tsc_teardown(void)
    +void sim_tsc_uninitialize(void)
     {
       FAR struct up_dev_s *priv = (FAR struct up_dev_s *)&g_simtouchscreen;
       char devname[DEV_NAMELEN];
    diff --git a/configs/sim/src/sim_touchscreen.c b/configs/sim/src/sim_touchscreen.c
    index c81c88325e..54a9921606 100644
    --- a/configs/sim/src/sim_touchscreen.c
    +++ b/configs/sim/src/sim_touchscreen.c
    @@ -1,7 +1,7 @@
     /****************************************************************************
      * config/sim/src/sim_touchscreen.c
      *
    - *   Copyright (C) 2011, 2016 Gregory Nutt. All rights reserved.
    + *   Copyright (C) 2011, 2016-2017 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
      *
      * Redistribution and use in source and binary forms, with or without
    @@ -54,6 +54,8 @@
     #  include 
     #endif
     
    +#include "up_internal.h"
    +
     /****************************************************************************
      * Pre-processor Definitions
      ****************************************************************************/
    @@ -159,17 +161,19 @@ int board_tsc_setup(int minor)
     
       /* Finally, initialize the touchscreen simulation on the X window */
     
    -  ret = board_tsc_setup(minor);
    +  ret = sim_tsc_initialize(minor);
       if (ret < 0)
         {
    -      ierr("ERROR: board_tsc_setup failed: %d\n", ret);
    +      ierr("ERROR: sim_tsc_initialize failed: %d\n", ret);
           goto errout_with_nx;
         }
    +
       return OK;
     
     errout_with_nx:
       nx_close(g_simtc.hnx);
       goto errout;
    +
     errout_with_fb:
       up_fbuninitialize(0);
     errout:
    @@ -190,7 +194,7 @@ void board_tsc_teardown(void)
     {
       /* Shut down the touchscreen driver */
     
    -  sim_tcuninitialize();
    +  sim_tsc_uninitialize();
     
       /* Close NX */
     
    -- 
    GitLab
    
    
    From a98cdc7a45fda8c3d7b7a71af3c591004ee03fbc Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Thu, 20 Apr 2017 09:31:12 -0600
    Subject: [PATCH 530/990] Add STM32F0 USB device header file; Update TODO list.
    
    ---
     TODO                                       |  24 +---
     arch/arm/src/stm32f0/chip/stm32f0_usbdev.h | 156 +++++++++++----------
     2 files changed, 85 insertions(+), 95 deletions(-)
    
    diff --git a/TODO b/TODO
    index ed6d93238b..24ef691747 100644
    --- a/TODO
    +++ b/TODO
    @@ -14,7 +14,7 @@ nuttx/:
       (1)  Memory Management (mm/)
       (0)  Power Management (drivers/pm)
       (3)  Signals (sched/signal, arch/)
    -  (4)  pthreads (sched/pthread)
    +  (3)  pthreads (sched/pthread)
       (0)  Message Queues (sched/mqueue)
       (8)  Kernel/Protected Build
       (3)  C++ Support
    @@ -47,8 +47,8 @@ o Task/Scheduler (sched/)
       Priority:    Medium, required for good emulation of process/pthread model.
     
       Title:       pause() NON-COMPLIANCE
    -  Description: In the POSIX description of this function is the pause() function
    -               will suspend the calling thread until delivery of a signal whose
    +  Description: In the POSIX description of this function the pause() function
    +               must suspend the calling thread until delivery of a signal whose
                    action is either to execute a signal-catching function or to
                    terminate the process.  The current implementation only waits for
                    any non-blocked signal to be received.  It should only wake up if
    @@ -500,20 +500,6 @@ o pthreads (sched/pthreads)
       Priority:    Medium-low. Priority may be higher if system call overheade becomes
                    an issue.
     
    -  Title:       ROBUST MUTEX ATTRIBUTE NOT SUPPORTED
    -  Description: In NuttX, all mutexes are 'robust' in the sense that an attmpt
    -               to lock a mutex will return EOWNDERDEAD if the holder of the
    -               mutex has died.  Unlocking of a mutex will fail if the caller
    -               is not the holder of the mutex.
    -
    -               POSIX, however, requires that there be a mutex attribute called
    -               robust that determines which behavior is supported.  non-robust
    -               should be the default.  NuttX does not support this attribute
    -               and robust behavior is the default and only supported behavior.
    -  Status:      Open
    -  Priority:    Low.  The non-robust behavior is dangerous and really should never
    -               be used.
    -
     o Message Queues (sched/mqueue)
       ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
     
    @@ -1092,7 +1078,8 @@ o Network (net/, drivers/net)
       Title:       ETHERNET WITH MULTIPLE LPWORK THREADS
       Description: Recently, Ethernet drivers were modified to support multiple
                    work queue structures.  The question was raised: "My only
    -               reservation would be, how would this interact in the case of having CONFIG_STM32_ETHMAC_LPWORK and CONFIG_SCHED_LPNTHREADS
    +               reservation would be, how would this interact in the case of
    +               having CONFIG_STM32_ETHMAC_LPWORK and CONFIG_SCHED_LPNTHREADS
                    > 1? Can it be guaranteed that one work item won't be
                    interrupted and execution switched to another? I think so but
                    am not 100% confident."
    @@ -2124,4 +2111,3 @@ o Other Applications & Tests (apps/examples/)
                    the artifact is larger.
       Status:      Open
       Priority:    Medium.
    -
    diff --git a/arch/arm/src/stm32f0/chip/stm32f0_usbdev.h b/arch/arm/src/stm32f0/chip/stm32f0_usbdev.h
    index a809c45172..2c48f1809e 100644
    --- a/arch/arm/src/stm32f0/chip/stm32f0_usbdev.h
    +++ b/arch/arm/src/stm32f0/chip/stm32f0_usbdev.h
    @@ -3,7 +3,6 @@
      *
      *   Copyright (C) 2017 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
    - *           Alan Carvalho de Assis 
      *
      * Redistribution and use in source and binary forms, with or without
      * modification, are permitted provided that the following conditions
    @@ -44,6 +43,9 @@
     #include 
     #include 
     
    +#if defined(CONFIG_STM32_STM32L15XX) || defined(CONFIG_STM32_STM32F10XX) || defined(CONFIG_STM32_STM32F30XX) \
    +    || defined(CONFIG_STM32_STM32F37XX)
    +
     /************************************************************************************
      * Pre-processor Definitions
      ************************************************************************************/
    @@ -52,70 +54,72 @@
     
     /* Endpoint Registers */
     
    -#define STM32F0_USB_EPR_OFFSET(n)      ((n) << 2) /* USB endpoint n register (16-bits) */
    -#define STM32F0_USB_EP0R_OFFSET        0x0000  /* USB endpoint 0 register (16-bits) */
    -#define STM32F0_USB_EP1R_OFFSET        0x0004  /* USB endpoint 1 register (16-bits) */
    -#define STM32F0_USB_EP2R_OFFSET        0x0008  /* USB endpoint 2 register (16-bits) */
    -#define STM32F0_USB_EP3R_OFFSET        0x000c  /* USB endpoint 3 register (16-bits) */
    -#define STM32F0_USB_EP4R_OFFSET        0x0010  /* USB endpoint 4 register (16-bits) */
    -#define STM32F0_USB_EP5R_OFFSET        0x0014  /* USB endpoint 5 register (16-bits) */
    -#define STM32F0_USB_EP6R_OFFSET        0x0018  /* USB endpoint 6 register (16-bits) */
    -#define STM32F0_USB_EP7R_OFFSET        0x001c  /* USB endpoint 7 register (16-bits) */
    +#define STM32_USB_EPR_OFFSET(n)      ((n) << 2) /* USB endpoint n register (16-bits) */
    +#define STM32_USB_EP0R_OFFSET        0x0000  /* USB endpoint 0 register (16-bits) */
    +#define STM32_USB_EP1R_OFFSET        0x0004  /* USB endpoint 1 register (16-bits) */
    +#define STM32_USB_EP2R_OFFSET        0x0008  /* USB endpoint 2 register (16-bits) */
    +#define STM32_USB_EP3R_OFFSET        0x000c  /* USB endpoint 3 register (16-bits) */
    +#define STM32_USB_EP4R_OFFSET        0x0010  /* USB endpoint 4 register (16-bits) */
    +#define STM32_USB_EP5R_OFFSET        0x0014  /* USB endpoint 5 register (16-bits) */
    +#define STM32_USB_EP6R_OFFSET        0x0018  /* USB endpoint 6 register (16-bits) */
    +#define STM32_USB_EP7R_OFFSET        0x001c  /* USB endpoint 7 register (16-bits) */
     
     /* Common Registers */
     
    -#define STM32F0_USB_CNTR_OFFSET        0x0040  /* USB control register (16-bits) */
    -#define STM32F0_USB_ISTR_OFFSET        0x0044  /* USB interrupt status register (16-bits) */
    -#define STM32F0_USB_FNR_OFFSET         0x0048  /* USB frame number register (16-bits) */
    -#define STM32F0_USB_DADDR_OFFSET       0x004c  /* USB device address (16-bits) */
    -#define STM32F0_USB_BTABLE_OFFSET      0x0050  /* Buffer table address (16-bits) */
    -#define STM32F0_USB_LPMCSR_OFFSET      0x0054  /* LPM control and status register */
    -#define STM32F0_USB_BCDR_OFFSET        0x0058  /* Battery charging detector */
    +#define STM32_USB_CNTR_OFFSET        0x0040  /* USB control register (16-bits) */
    +#define STM32_USB_ISTR_OFFSET        0x0044  /* USB interrupt status register (16-bits) */
    +#define STM32_USB_FNR_OFFSET         0x0048  /* USB frame number register (16-bits) */
    +#define STM32_USB_DADDR_OFFSET       0x004c  /* USB device address (16-bits) */
    +#define STM32_USB_BTABLE_OFFSET      0x0050  /* Buffer table address (16-bits) */
    +#define STM32_USB_LPMCSR_OFFSET      0x0054  /* LPM control and status register (16-bits) */
    +#define STM32_USB_BCDR_OFFSET        0x0058  /* Battery charging detector (16-bits) */
     
     /* Buffer Descriptor Table (Relatative to BTABLE address) */
     
    -#define STM32F0_USB_ADDR_TX_WOFFSET   (0)     /* Transmission buffer address n (16-bits) */
    -#define STM32F0_USB_COUNT_TX_WOFFSET  (2)     /* Transmission byte count n (16-bits) */
    -#define STM32F0_USB_ADDR_RX_WOFFSET   (4)     /* Reception buffer address n (16-bits) */
    -#define STM32F0_USB_COUNT_RX_WOFFSET  (6)     /* Reception byte count n (16-bits) */
    +#define STM32_USB_ADDR_TX_WOFFSET   (0)     /* Transmission buffer address n (16-bits) */
    +#define STM32_USB_COUNT_TX_WOFFSET  (2)     /* Transmission byte count n (16-bits) */
    +#define STM32_USB_ADDR_RX_WOFFSET   (4)     /* Reception buffer address n (16-bits) */
    +#define STM32_USB_COUNT_RX_WOFFSET  (6)     /* Reception byte count n (16-bits) */
     
    -#define STM32F0_USB_BTABLE_RADDR(ep,o) ((((uint32_t)getreg16(STM32F0_USB_BTABLE) + ((ep) << 3)) + (o))  << 1)
    -#define STM32F0_USB_ADDR_TX_OFFSET(ep)  STM32F0_USB_BTABLE_RADDR(ep,STM32F0_USB_ADDR_TX_WOFFSET)
    -#define STM32F0_USB_COUNT_TX_OFFSET(ep) STM32F0_USB_BTABLE_RADDR(ep,STM32F0_USB_COUNT_TX_WOFFSET)
    -#define STM32F0_USB_ADDR_RX_OFFSET(ep)  STM32F0_USB_BTABLE_RADDR(ep,STM32F0_USB_ADDR_RX_WOFFSET)
    -#define STM32F0_USB_COUNT_RX_OFFSET(ep) STM32F0_USB_BTABLE_RADDR(ep,STM32F0_USB_COUNT_RX_WOFFSET)
    +#define STM32_USB_BTABLE_RADDR(ep,o) ((((uint32_t)getreg16(STM32_USB_BTABLE) + ((ep) << 3)) + (o))  << 1)
    +#define STM32_USB_ADDR_TX_OFFSET(ep)  STM32_USB_BTABLE_RADDR(ep,STM32_USB_ADDR_TX_WOFFSET)
    +#define STM32_USB_COUNT_TX_OFFSET(ep) STM32_USB_BTABLE_RADDR(ep,STM32_USB_COUNT_TX_WOFFSET)
    +#define STM32_USB_ADDR_RX_OFFSET(ep)  STM32_USB_BTABLE_RADDR(ep,STM32_USB_ADDR_RX_WOFFSET)
    +#define STM32_USB_COUNT_RX_OFFSET(ep) STM32_USB_BTABLE_RADDR(ep,STM32_USB_COUNT_RX_WOFFSET)
     
     /* Register Addresses ***************************************************************/
     
     /* Endpoint Registers */
     
    -#define STM32F0_USB_EPR(n)             (STM32F0_USB_BASE+STM32F0_USB_EPR_OFFSET(n))
    -#define STM32F0_USB_EP0R               (STM32F0_USB_BASE+STM32F0_USB_EP0R_OFFSET)
    -#define STM32F0_USB_EP1R               (STM32F0_USB_BASE+STM32F0_USB_EP1R_OFFSET)
    -#define STM32F0_USB_EP2R               (STM32F0_USB_BASE+STM32F0_USB_EP2R_OFFSET)
    -#define STM32F0_USB_EP3R               (STM32F0_USB_BASE+STM32F0_USB_EP3R_OFFSET)
    -#define STM32F0_USB_EP4R               (STM32F0_USB_BASE+STM32F0_USB_EP4R_OFFSET)
    -#define STM32F0_USB_EP5R               (STM32F0_USB_BASE+STM32F0_USB_EP5R_OFFSET)
    -#define STM32F0_USB_EP6R               (STM32F0_USB_BASE+STM32F0_USB_EP6R_OFFSET)
    -#define STM32F0_USB_EP7R               (STM32F0_USB_BASE+STM32F0_USB_EP7R_OFFSET)
    +#define STM32_USB_EPR(n)             (STM32_USB_BASE+STM32_USB_EPR_OFFSET(n))
    +#define STM32_USB_EP0R               (STM32_USB_BASE+STM32_USB_EP0R_OFFSET)
    +#define STM32_USB_EP1R               (STM32_USB_BASE+STM32_USB_EP1R_OFFSET)
    +#define STM32_USB_EP2R               (STM32_USB_BASE+STM32_USB_EP2R_OFFSET)
    +#define STM32_USB_EP3R               (STM32_USB_BASE+STM32_USB_EP3R_OFFSET)
    +#define STM32_USB_EP4R               (STM32_USB_BASE+STM32_USB_EP4R_OFFSET)
    +#define STM32_USB_EP5R               (STM32_USB_BASE+STM32_USB_EP5R_OFFSET)
    +#define STM32_USB_EP6R               (STM32_USB_BASE+STM32_USB_EP6R_OFFSET)
    +#define STM32_USB_EP7R               (STM32_USB_BASE+STM32_USB_EP7R_OFFSET)
     
     /* Common Registers */
     
    -#define STM32F0_USB_CNTR               (STM32F0_USB_BASE+STM32F0_USB_CNTR_OFFSET)
    -#define STM32F0_USB_ISTR               (STM32F0_USB_BASE+STM32F0_USB_ISTR_OFFSET)
    -#define STM32F0_USB_FNR                (STM32F0_USB_BASE+STM32F0_USB_FNR_OFFSET)
    -#define STM32F0_USB_DADDR              (STM32F0_USB_BASE+STM32F0_USB_DADDR_OFFSET)
    -#define STM32F0_USB_BTABLE             (STM32F0_USB_BASE+STM32F0_USB_BTABLE_OFFSET)
    -#define STM32F0_USB_LPMCSR_OFFSET      (STM32F0_USB_BASE+STM32F0_USB_LPMCSR_OFFSET)
    -#define STM32F0_USB_BCDR_OFFSET        (STM32F0_USB_BASE+STM32F0_USB_BCDR_OFFSET)
    +#define STM32_USB_CNTR               (STM32_USB_BASE+STM32_USB_CNTR_OFFSET)
    +#define STM32_USB_ISTR               (STM32_USB_BASE+STM32_USB_ISTR_OFFSET)
    +#define STM32_USB_FNR                (STM32_USB_BASE+STM32_USB_FNR_OFFSET)
    +#define STM32_USB_DADDR              (STM32_USB_BASE+STM32_USB_DADDR_OFFSET)
    +#define STM32_USB_BTABLE             (STM32_USB_BASE+STM32_USB_BTABLE_OFFSET)
    +#define STM32_USB_LPMCSR_OFFSET      0x0054  /* LPM control and status register (16-bits) */
    +#define STM32_USB_LPMCSR_OFFSET      0x0054  /* LPM control and status register (16-bits) */
    +#define STM32_USB_BCDR_OFFSET        0x0058  /* Battery charging detector (16-bits) */
    +#define STM32_USB_BCDR_OFFSET        0x0058  /* Battery charging detector (16-bits) */
     
     /* Buffer Descriptor Table (Relatative to BTABLE address) */
     
    -#define STM32F0_USB_BTABLE_ADDR(ep,o)  (STM32F0_USBRAM_BASE+STM32F0_USB_BTABLE_RADDR(ep,o))
    -#define STM32F0_USB_ADDR_TX(ep)        STM32F0_USB_BTABLE_ADDR(ep,STM32F0_USB_ADDR_TX_WOFFSET)
    -#define STM32F0_USB_COUNT_TX(ep)       STM32F0_USB_BTABLE_ADDR(ep,STM32F0_USB_COUNT_TX_WOFFSET)
    -#define STM32F0_USB_ADDR_RX(ep)        STM32F0_USB_BTABLE_ADDR(ep,STM32F0_USB_ADDR_RX_WOFFSET)
    -#define STM32F0_USB_COUNT_RX(ep)       STM32F0_USB_BTABLE_ADDR(ep,STM32F0_USB_COUNT_RX_WOFFSET)
    +#define STM32_USB_BTABLE_ADDR(ep,o)  (STM32_USBRAM_BASE+STM32_USB_BTABLE_RADDR(ep,o))
    +#define STM32_USB_ADDR_TX(ep)        STM32_USB_BTABLE_ADDR(ep,STM32_USB_ADDR_TX_WOFFSET)
    +#define STM32_USB_COUNT_TX(ep)       STM32_USB_BTABLE_ADDR(ep,STM32_USB_COUNT_TX_WOFFSET)
    +#define STM32_USB_ADDR_RX(ep)        STM32_USB_BTABLE_ADDR(ep,STM32_USB_ADDR_RX_WOFFSET)
    +#define STM32_USB_COUNT_RX(ep)       STM32_USB_BTABLE_ADDR(ep,STM32_USB_COUNT_RX_WOFFSET)
     
     /* Register Bitfield Definitions ****************************************************/
     
    @@ -160,27 +164,28 @@
     #define USB_CNTR_FSUSP               (1 << 3)  /* Bit 3: Force suspend */
     #define USB_CNTR_RESUME              (1 << 4)  /* Bit 4: Resume request */
     #define USB_CNTR_L1RESUME            (1 << 5)  /* Bit 5: LPM L1 Resume request */
    -#define USB_CNTR_L1REQM              (1 << 7)  /* Bit 6: LPM L1 state request interrupt mask */
    +#define USB_CNTR_L1REQ               (1 << 7)  /* Bit 7: LPM L1 state request interrupt mask */
     #define USB_CNTR_ESOFM               (1 << 8)  /* Bit 8: Expected Start Of Frame Interrupt Mask */
     #define USB_CNTR_SOFM                (1 << 9)  /* Bit 9: Start Of Frame Interrupt Mask */
     #define USB_CNTR_RESETM              (1 << 10) /* Bit 10: USB Reset Interrupt Mask */
     #define USB_CNTR_SUSPM               (1 << 11) /* Bit 11: Suspend mode Interrupt Mask */
     #define USB_CNTR_WKUPM               (1 << 12) /* Bit 12: Wakeup Interrupt Mask */
     #define USB_CNTR_ERRM                (1 << 13) /* Bit 13: Error Interrupt Mask */
    -#define USB_CNTR_PMAOVRNM            (1 << 14) /* Bit 14: Packet Memory Area Over / Underrun Interrupt Mask */
    +#define USB_CNTR_PMAOVRM             (1 << 14) /* Bit 14: Packet Memory Area Over / Underrun Interrupt Mask */
     #define USB_CNTR_CTRM                (1 << 15) /* Bit 15: Correct Transfer Interrupt Mask */
     
    -#define USB_CNTR_ALLINTS             (USB_CNTR_ESOFM|USB_CNTR_SOFM|USB_CNTR_RESETM|USB_CNTR_SUSPM|\
    -                                      USB_CNTR_WKUPM|USB_CNTR_ERRM|USB_CNTR_DMAOVRNM|USB_CNTR_CTRM)
    +#define USB_CNTR_ALLINTS             (USB_CNTR_L1REQ|USB_CNTR_ESOFM|USB_CNTR_SOFM|USB_CNTR_RESETM|\
    +                                      USB_CNTR_SUSPM|USB_CNTR_WKUPM|USB_CNTR_ERRM|USB_CNTR_PMAOVRNM|\
    +                                      USB_CNTR_CTRM)
     
     /* USB interrupt status register */
     
     #define USB_ISTR_EPID_SHIFT          (0)       /* Bits 3-0: Endpoint Identifier */
     #define USB_ISTR_EPID_MASK           (0x0f << USB_ISTR_EPID_SHIFT)
    -#define USB_ISTR_DIR                 (1 << 4)  /* Bit 4: Direction of transaction */
    -#define USB_ISTR_L1REQ               (1 << 7)  /* Bit 7: LPM L1 state request */
    -#define USB_ISTR_ESOF                (1 << 8)  /* Bit 8: Expected Start Of Frame */
    -#define USB_ISTR_SOF                 (1 << 9)  /* Bit 9: Start Of Frame */
    +#define USB_ISTR_DIR                 (1 << 4)  /* Bit 4:  Direction of transaction */
    +#define USB_ISTR_L1REQ               (1 << 7)  /* Bit 7:  LPM L1 state request */
    +#define USB_ISTR_ESOF                (1 << 8)  /* Bit 8:  Expected Start Of Frame */
    +#define USB_ISTR_SOF                 (1 << 9)  /* Bit 9:  Start Of Frame */
     #define USB_ISTR_RESET               (1 << 10) /* Bit 10: USB RESET request */
     #define USB_ISTR_SUSP                (1 << 11) /* Bit 11: Suspend mode request */
     #define USB_ISTR_WKUP                (1 << 12) /* Bit 12: Wake up */
    @@ -188,8 +193,9 @@
     #define USB_ISTR_PMAOVRN             (1 << 14) /* Bit 14: Packet Memory Area Over / Underrun */
     #define USB_ISTR_CTR                 (1 << 15) /* Bit 15: Correct Transfer */
     
    -#define USB_ISTR_ALLINTS             (USB_ISTR_ESOF|USB_ISTR_SOF|USB_ISTR_RESET|USB_ISTR_SUSP|\
    -                                      USB_ISTR_WKUP|USB_ISTR_ERR|USB_ISTR_DMAOVRN|USB_ISTR_CTR)
    +#define USB_ISTR_ALLINTS             (USB_ISTR_L1REQ|USB_ISTR_ESOF|USB_ISTR_SOF|USB_ISTR_RESET|\
    +                                      USB_ISTR_SUSP|USB_ISTR_WKUP|USB_ISTR_ERR|USB_ISTR_PMAOVRN|\
    +                                      USB_ISTR_CTR)
     
     /* USB frame number register */
     
    @@ -212,24 +218,24 @@
     #define USB_BTABLE_SHIFT             (3)       /* Bits 15:3: Buffer Table */
     #define USB_BTABLE_MASK              (0x1fff << USB_BTABLE_SHIFT)
     
    -/* LPM control and status register */
    +/* LPM control and status register (16-bits) */
     
    -#define USB_LPMCSR_LPMEN             (1 << 0)  /* Bit 0: LPM support enable */
    -#define USB_LPMCSR_LPMACK            (1 << 1)  /* Bit 1: LPM Token acknowledge enable */
    -#define USB_LPMCSR_REMWAKE           (1 << 3)  /* Bit 3: bRemoteWake value */
    -#define USB_LPMCSR_BESL_OFFSET       (4)       /* Bits 4-7: BESL value */
    -#define USB_LPMCSR_BESL_MASK         (0xf << USB_LPMCSR_BESL_OFFSET)
    +#define USB_LPMCSR_LPMEN             (1 << 0)  /* Bit 0:  LPM support enable */
    +#define USB_LPMCSR_LPMACK            (1 << 1)  /* Bit 1:  LPM Token acknowledge enable */
    +#define USB_LPMCSR_REMWAKE           (1 << 3)  /* Bit 3:  bRemoteWake value */
    +#define USB_LPMCSR_BESL_SHIFT        (4)       /* Bits 4-7: BESL value */
    +#define USB_LPMCSR_BESL_MASK         (15 << USB_LPMCSR_BESL_SHIFT)
     
    -/* Battery charging detector */
    +/* Battery charging detector (16-bits) */
     
    -#define USB_BCDR_BCDEN               (1 << 0)  /* Bit 0: Battery charging detector (BCD) enable */
    -#define USB_BCDR_DCDEN               (1 << 1)  /* Bit 1: Data contact detection (DCD) mode enable */
    -#define USB_BCDR_PDEN                (1 << 2)  /* Bit 2: Primary detection (PD) mode enable */
    -#define USB_BCDR_SDEN                (1 << 3)  /* Bit 3: Secondary detection (SD) mode enable */
    -#define USB_BCDR_DCDET               (1 << 4)  /* Bit 4: Data contact detection (DCD) status */
    -#define USB_BCDR_PDET                (1 << 5)  /* Bit 5: Primary detection (PD) status */
    -#define USB_BCDR_SDET                (1 << 6)  /* Bit 6: Secondary detection (SD) status */
    -#define USB_BCDR_PS2DET              (1 << 7)  /* Bit 7: DM pull-up detection status */
    +#define USB_BCDR_BCDEN               (1 << 0)  /* Bit 0:  Battery charging detector (BCD) enable */
    +#define USB_BCDR_DCDEN               (1 << 1)  /* Bit 1:  Data contact detection (DCD) mode enable */
    +#define USB_BCDR_PDEN                (1 << 2)  /* Bit 2:  Primary detection (PD) mode enable */
    +#define USB_BCDR_SDEN                (1 << 3)  /* Bit 3:  Secondary detection (SD) mode enable */
    +#define USB_BCDR_DCDET               (1 << 4)  /* Bit 4:  Data contact detection (DCD) status */
    +#define USB_BCDR_PDET                (1 << 5)  /* Bit 5:  Primary detection (PD) status */
    +#define USB_BCDR_SDET                (1 << 6)  /* Bit 6:  Secondary detection (SD) status */
    +#define USB_BCDR_PS2DET              (1 << 7)  /* Bit 7:  DM pull-up detection status */
     #define USB_BCDR_DPPU                (1 << 15) /* Bit 15: DP pull-up control */
     
     /* Transmission buffer address */
    @@ -240,11 +246,8 @@
     
     /* Transmission byte count */
     
    -#define USB_COUNT_TX_SHIFT           (0)       /* Bits 0-9: Transmission Byte Count */
    +#define USB_COUNT_TX_SHIFT           (0)       /* Bits 9-0: Transmission Byte Count */
     #define USB_COUNT_TX_MASK            (0x03ff << USB_COUNT_COUNT_TX_SHIFT)
    -#define USB_COUNT_NUMBLOCK_OFFSET    (10)      /* Bits 10-14: Number of blocks */
    -#define USB_COUNT_NUMBLOCK_MASK      (1 << USB_COUNT_NUMBLOCK_OFFSET)
    -#define USB_COUNT_BLSIZE             (1 << 15) /* Bit 15: Block size */
     
     /* Reception buffer address */
     
    @@ -260,4 +263,5 @@
     #define USB_COUNT_RX_SHIFT           (0)       /* Bits 9-0: Reception Byte Count */
     #define USB_COUNT_RX_MASK            (0x03ff << USB_COUNT_RX_SHIFT)
     
    +#endif /* CONFIG_STM32_STM32F10XX || CONFIG_STM32_STM32F30XX || CONFIG_STM32_STM32F37XX */
     #endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_USBDEV_H */
    -- 
    GitLab
    
    
    From 20ddbd7368d5d098ea059cf1a148bf8dc3526f46 Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Thu, 20 Apr 2017 11:08:23 -0600
    Subject: [PATCH 531/990] STM32F0:  Add support for HSI48
    
    ---
     arch/arm/src/stm32f0/Kconfig               |  10 +-
     arch/arm/src/stm32f0/Make.defs             |   4 +
     arch/arm/src/stm32f0/chip/stm32f0_rcc.h    |  64 +++++--
     arch/arm/src/stm32f0/chip/stm32f0_usbdev.h |   6 +-
     arch/arm/src/stm32f0/stm32f0_hsi48.c       | 183 +++++++++++++++++++++
     arch/arm/src/stm32f0/stm32f0_hsi48.h       | 109 ++++++++++++
     arch/arm/src/stm32f0/stm32f0_rcc.h         |   4 +-
     7 files changed, 360 insertions(+), 20 deletions(-)
     create mode 100644 arch/arm/src/stm32f0/stm32f0_hsi48.c
     create mode 100644 arch/arm/src/stm32f0/stm32f0_hsi48.h
    
    diff --git a/arch/arm/src/stm32f0/Kconfig b/arch/arm/src/stm32f0/Kconfig
    index 746d9e40ec..a330dda624 100644
    --- a/arch/arm/src/stm32f0/Kconfig
    +++ b/arch/arm/src/stm32f0/Kconfig
    @@ -466,6 +466,7 @@ config STM32F0_STM32F07X
     config STM32F0_STM32F09X
     	bool
     	default n
    +	select STM32F0_HAVE_HSI48
     
     config STM32F0_VALUELINE
     	bool
    @@ -528,6 +529,7 @@ config STM32F0_LOWVOLTLINE
     config STM32F0_USBLINE
     	bool
     	default n
    +	select STM32F0_HAVE_HSI48
     	select STM32F0_HAVE_USART3
     	select STM32F0_HAVE_USART4
     	select STM32F0_HAVE_TIM1
    @@ -576,19 +578,19 @@ config STM32F0_HAVE_CCM
     	bool
     	default n
     
    -config STM32F0_HAVE_USBDEV
    +config STM32F0_HAVE_HSI48
     	bool
     	default n
     
    -config STM32F0_HAVE_FSMC
    +config STM32F0_HAVE_USBDEV
     	bool
     	default n
     
    -config STM32F0_HAVE_HRTIM1
    +config STM32F0_HAVE_FSMC
     	bool
     	default n
     
    -config STM32F0_HAVE_LTDC
    +config STM32F0_HAVE_HRTIM1
     	bool
     	default n
     
    diff --git a/arch/arm/src/stm32f0/Make.defs b/arch/arm/src/stm32f0/Make.defs
    index ada01348f7..3aadfbfaae 100644
    --- a/arch/arm/src/stm32f0/Make.defs
    +++ b/arch/arm/src/stm32f0/Make.defs
    @@ -87,6 +87,10 @@ ifeq ($(CONFIG_ARCH_IRQPRIO),y)
     CHIP_CSRCS += stm32f0_irqprio.c
     endif
     
    +ifeq ($(CONFIG_STM32F0_HAVE_HSI48),y)
    +CHIP_CSRCS += stm32f0_hsi48.c
    +endif
    +
     ifeq ($(CONFIG_STM32F0_SPI0),y)
     CHIP_CSRCS += stm32f0_spi.c
     else
    diff --git a/arch/arm/src/stm32f0/chip/stm32f0_rcc.h b/arch/arm/src/stm32f0/chip/stm32f0_rcc.h
    index 613020b830..89464aa682 100644
    --- a/arch/arm/src/stm32f0/chip/stm32f0_rcc.h
    +++ b/arch/arm/src/stm32f0/chip/stm32f0_rcc.h
    @@ -55,6 +55,8 @@
     #define STM32F0_RCC_CSR_OFFSET      0x0024  /* Control/status register */
     #define STM32F0_RCC_AHBRSTR_OFFSET  0x0028  /* AHB Reset register */
     #define STM32F0_RCC_CFGR2_OFFSET    0x002c  /* Clock configuration register 2 */
    +#define STM32F0_RCC_CFGR3_OFFSET    0x0030  /* Clock configuration register 3 */
    +#define STM32F0_RCC_CR2_OFFSET      0x0034  /* Clock control register 2 */
     
     /* Register Addresses ***************************************************************/
     
    @@ -70,6 +72,8 @@
     #define STM32F0_RCC_CSR             (STM32F0_RCC_BASE+STM32F0_RCC_CSR_OFFSET)
     #define STM32F0_RCC_AHBRSTR         (STM32F0_RCC_BASE+STM32F0_RCC_AHBRSTR_OFFSET)
     #define STM32F0_RCC_CFGR2           (STM32F0_RCC_BASE+STM32F0_RCC_CFGR2_OFFSET)
    +#define STM32F0_RCC_CFGR3           (STM32F0_RCC_BASE+STM32F0_RCC_CFGR3_OFFSET)
    +#define STM32F0_RCC_CR2             (STM32F0_RCC_BASE+STM32F0_RCC_CR2_OFFSET)
     
     /* Register Bitfield Definitions ****************************************************/
     
    @@ -149,16 +153,18 @@
                                         /* Bit 22-23: Reserved */
     #define RCC_CFGR_MCO_SHIFT          (24)      /* Bits 27-24: Microcontroller Clock Output */
     #define RCC_CFGR_MCO_MASK           (15 << RCC_CFGR_MCO_SHIFT)
    -#  define RCC_CFGR_NOCLK            (0 << RCC_CFGR_MCO_SHIFT)  /* 0000: No clock */
    -#  define RCC_CFGR_HSI14            (1 << RCC_CFGR_MCO_SHIFT)  /* 0001: Internal RC 14MHz oscillator */
    -#  define RCC_CFGR_LSI              (2 << RCC_CFGR_MCO_SHIFT)  /* 0010: Internal Low Speed (LSI) oscillator */
    -#  define RCC_CFGR_LSE              (2 << RCC_CFGR_MCO_SHIFT)  /* 0011: External Low Speed (LSE) oscillator */
    -#  define RCC_CFGR_SYSCLK           (4 << RCC_CFGR_MCO_SHIFT)  /* 0100: System clock selected */
    -#  define RCC_CFGR_INTCLK           (5 << RCC_CFGR_MCO_SHIFT)  /* 0101: Internal 8 MHz RC oscillator clock selected */
    -#  define RCC_CFGR_EXTCLK           (6 << RCC_CFGR_MCO_SHIFT)  /* 0110: External 4-32 MHz oscillator clock selected */
    -#  define RCC_CFGR_PLLCLKd2         (7 << RCC_CFGR_MCO_SHIFT)  /* 0111: PLL clock selected (divided by 1 or 2 depending on PLLNODIV */
    -#  define RCC_CFGR_PLL2CLK          (8 << RCC_CFGR_MCO_SHIFT)  /* 1000: Internal RC 48MHz (HSI48) oscillator */
    -#define RCC_CFGR_MCOPRE_SHIFT       (28)      /* Bits 28-30: Microcontroller Clock Output Prescaler, not available on STM32F05x */
    +#  define RCC_CFGR_NOCLK            (0 << RCC_CFGR_MCO_SHIFT)    /* 0000: No clock */
    +#  define RCC_CFGR_HSI14            (1 << RCC_CFGR_MCO_SHIFT)    /* 0001: Internal RC 14MHz oscillator */
    +#  define RCC_CFGR_LSI              (2 << RCC_CFGR_MCO_SHIFT)    /* 0010: Internal Low Speed (LSI) oscillator */
    +#  define RCC_CFGR_LSE              (2 << RCC_CFGR_MCO_SHIFT)    /* 0011: External Low Speed (LSE) oscillator */
    +#  define RCC_CFGR_SYSCLK           (4 << RCC_CFGR_MCO_SHIFT)    /* 0100: System clock selected */
    +#  define RCC_CFGR_INTCLK           (5 << RCC_CFGR_MCO_SHIFT)    /* 0101: Internal 8 MHz RC oscillator clock selected */
    +#  define RCC_CFGR_EXTCLK           (6 << RCC_CFGR_MCO_SHIFT)    /* 0110: External 4-32 MHz oscillator clock selected */
    +#  define RCC_CFGR_PLLCLKd2         (7 << RCC_CFGR_MCO_SHIFT)    /* 0111: PLL clock selected (divided by 1 or 2
    +                                                                  * depending on PLLNODIV) */
    +#  define RCC_CFGR_PLL2CLK          (8 << RCC_CFGR_MCO_SHIFT)    /* 1000: Internal RC 48MHz (HSI48) oscillator */
    +#define RCC_CFGR_MCOPRE_SHIFT       (28)                         /* Bits 28-30: Microcontroller Clock Output Prescaler,
    +                                                                  * not available on STM32F05x */
     #define RCC_CFGR_MCOPRE_MASK        (3 << RCC_CFGR_MCOPRE_SHIFT)
     #  define RCC_CFGR_MCOPRE_div1      (0 << RCC_CFGR_MCOPRE_SHIFT) /* 000: MCO is divided by 1 */
     #  define RCC_CFGR_MCOPRE_div2      (1 << RCC_CFGR_MCOPRE_SHIFT) /* 001: MCO is divided by 2 */
    @@ -345,4 +351,42 @@
     #  define RCC_CFGR2_PREDIV1d15      (14 << RCC_CFGR2_PREDIV1_SHIFT)
     #  define RCC_CFGR2_PREDIV1d16      (15 << RCC_CFGR2_PREDIV1_SHIFT)
     
    +/* Clock configuration register 3 */
    +
    +#define RCC_CFGR3_USART1SW_SHIFT    (0)       /* Bits 0-1: USART1 clock source selection */
    +#define RCC_CFGR3_USART1SW_MASK     (3 << RCC_CFGR3_USART1SW_SHIFT)
    +#  define RCC_CFGR3_USART1SW_PCLK   (0 << RCC_CFGR3_USART1SW_SHIFT) /* PCLK is USART1 clock source */
    +#  define RCC_CFGR3_USART1SW_SYSCLK (1 << RCC_CFGR3_USART1SW_SHIFT) /* SYSCLK is USART1 clock */
    +#  define RCC_CFGR3_USART1SW_LSE    (2 << RCC_CFGR3_USART1SW_SHIFT) /* LSE is USART1 clock */
    +#  define RCC_CFGR3_USART1SW_HSI    (3 << RCC_CFGR3_USART1SW_SHIFT) /* HSI is USART1 clock */
    +#define RCC_CFGR3_CECSW             (1 << 6)  /* Bit 6: HDMI CEC clock source selection */
    +#define RCC_CFGR3_USBSW             (1 << 7)  /* Bit 7: USB clock source selection */
    +#define RCC_CFGR3_ADCSW             (1 << 8)  /* Bit 8: ADC clock source selection */
    +#define RCC_CFGR3_USART2SW_SHIFT    (16)      /* Bits 16-17: USART2 clock source selection */
    +#define RCC_CFGR3_USART2SW_MASK     (3 << RCC_CFGR3_USART2SW_SHIFT)
    +#  define RCC_CFGR3_USART2SW_PCLK   (0 << RCC_CFGR3_USART2SW_SHIFT) /* PCLK is USART2 clock source */
    +#  define RCC_CFGR3_USART2SW_SYSCLK (1 << RCC_CFGR3_USART2SW_SHIFT) /* SYSCLK is USART2 clock */
    +#  define RCC_CFGR3_USART2SW_LSE    (2 << RCC_CFGR3_USART2SW_SHIFT) /* LSE is USART2 clock */
    +#  define RCC_CFGR3_USART2SW_HSI    (3 << RCC_CFGR3_USART2SW_SHIFT) /* HSI is USART2 clock */
    +#define RCC_CFGR3_USART3SW_SHIFT    (18)      /* Bits 18-19: USART3 clock source selection */
    +#define RCC_CFGR3_USART3SW_MASK     (3 << RCC_CFGR3_USART3SW_SHIFT)
    +#  define RCC_CFGR3_USART3SW_PCLK   (0 << RCC_CFGR3_USART3SW_SHIFT) /* PCLK is USART3 clock source */
    +#  define RCC_CFGR3_USART3SW_SYSCLK (1 << RCC_CFGR3_USART3SW_SHIFT) /* SYSCLK is USART3 clock */
    +#  define RCC_CFGR3_USART3SW_LSE    (2 << RCC_CFGR3_USART3SW_SHIFT) /* LSE is USART3 clock */
    +#  define RCC_CFGR3_USART3SW_HSI    (3 << RCC_CFGR3_USART3SW_SHIFT) /* HSI is USART3 clock */
    +
    +/* Clock control register 2 */
    +
    +#define RCC_CR2_HSI14ON             (1 << 0)  /* Bit 0: HSI14 clock enable */
    +#define RCC_CR2_HSI14RDY            (1 << 1)  /* Bit 1: HSI14 clock ready flag */
    +#define RCC_CR2_HSI14DIS            (1 << 2)  /* Bit 2: HSI14 clock request from ADC disable */
    +#define RCC_CR2_HSI14TRIM_SHIFT     (3)       /* Bits 3-7: HSI14 clock trimming */
    +#define RCC_CR2_HSI14TRIM_MASK      (31 << RCC_CR2_HSI14TRIM_SHIFT)
    +#define RCC_CR2_HSI14CAL_SHIFT      (8)       /* Bits 8-15: HSI14 clock calibration */
    +#define RCC_CR2_HSI14CAL_MASK       (0xff << RCC_CR2_HSI14CAL_SHIFT)
    +#define RCC_CR2_HSI48ON             (1 << 16) /* Bit 16: HSI48 clock enable */
    +#define RCC_CR2_HSI48RDY            (1 << 17) /* Bit 17: HSI48 clock ready flag */
    +#define RCC_CR2_HSI48CAL_SHIFT      (24)      /* Bits 24-31: HSI48 factory clock calibration */
    +#define RCC_CR2_HSI48CAL_MASK       (0xff << RCC_CR2_HSI48CAL_SHIFT)
    +
     #endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_RCC_H */
    diff --git a/arch/arm/src/stm32f0/chip/stm32f0_usbdev.h b/arch/arm/src/stm32f0/chip/stm32f0_usbdev.h
    index 2c48f1809e..dabcc37fc5 100644
    --- a/arch/arm/src/stm32f0/chip/stm32f0_usbdev.h
    +++ b/arch/arm/src/stm32f0/chip/stm32f0_usbdev.h
    @@ -108,10 +108,8 @@
     #define STM32_USB_FNR                (STM32_USB_BASE+STM32_USB_FNR_OFFSET)
     #define STM32_USB_DADDR              (STM32_USB_BASE+STM32_USB_DADDR_OFFSET)
     #define STM32_USB_BTABLE             (STM32_USB_BASE+STM32_USB_BTABLE_OFFSET)
    -#define STM32_USB_LPMCSR_OFFSET      0x0054  /* LPM control and status register (16-bits) */
    -#define STM32_USB_LPMCSR_OFFSET      0x0054  /* LPM control and status register (16-bits) */
    -#define STM32_USB_BCDR_OFFSET        0x0058  /* Battery charging detector (16-bits) */
    -#define STM32_USB_BCDR_OFFSET        0x0058  /* Battery charging detector (16-bits) */
    +#define STM32_USB_LPMCSR             (STM32_USB_BASE+STM32_USB_LPMCSR_OFFSET)
    +#define STM32_USB_BCDR               (STM32_USB_BASE+STM32_USB_BCDR_OFFSET)
     
     /* Buffer Descriptor Table (Relatative to BTABLE address) */
     
    diff --git a/arch/arm/src/stm32f0/stm32f0_hsi48.c b/arch/arm/src/stm32f0/stm32f0_hsi48.c
    new file mode 100644
    index 0000000000..73c46e5f63
    --- /dev/null
    +++ b/arch/arm/src/stm32f0/stm32f0_hsi48.c
    @@ -0,0 +1,183 @@
    +/****************************************************************************
    + *  arch/arm/src/stm32f0/stm32f0_hsi48.c
    + *
    + *   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.
    + *
    + ****************************************************************************/
    +
    +/****************************************************************************
    + * Included Files
    + ****************************************************************************/
    +
    +#include 
    +
    +#include "up_arch.h"
    +#include "chip.h"
    +#include "chip/stm32f0_rcc.h"
    +#include "chip/stm32f0_crs.h"
    +
    +#include "stm32f0_hsi48.h"
    +
    +/****************************************************************************
    + * Public Functions
    + ****************************************************************************/
    +
    +/****************************************************************************
    + * Name: stm32f0_enable_hsi48
    + *
    + * Description:
    + *   On STM32F04x, STM32F07x and STM32F09x devices only, the HSI48 clock
    + *   signal is generated from an internal 48 MHz RC oscillator and can be
    + *   used directly as a system clock or divided and be used as PLL input.
    + *
    + *   The internal 48MHz RC oscillator is mainly dedicated to provide a high
    + *   precision clock to the USB peripheral by means of a special Clock
    + *   Recovery System (CRS) circuitry, which could use the USB SOF signal or
    + *   the LSE or an external signal to automatically adjust the oscillator
    + *   frequency on-fly, in a very small steps. This oscillator can also be
    + *   used as a system clock source when the system is in run mode; it will
    + *   be disabled as soon as the system enters in Stop or Standby mode. When
    + *   the CRS is not used, the HSI48 RC oscillator runs on its default
    + *   frequency which is subject to manufacturing process variations.
    + *
    + * Input Parameters:
    + *   Identifies the syncrhonization source for the HSI48.  When used as the
    + *   USB source clock, this must be set to SYNCSRC_USB.
    + *
    + * Returned Value:
    + *   None
    + *
    + ****************************************************************************/
    +
    +void stm32f0_enable_hsi48(enum syncsrc_e syncsrc)
    +{
    +  uint32_t regval;
    +
    +  /* Enable the HSI48 clock.
    +   *
    +   * The HSI48 RC can be switched on and off using the HSI48ON bit in the
    +   * Clock control register (RCC_CR).
    +   *
    +   * The USB clock may be derived from either the PLL clock or from the
    +   * HSI48 clock.  This oscillator will be also automatically enabled (by
    +   * hardware forcing HSI48ON bit to one) as soon as it is chosen as a clock
    +   * source for the USB and the peripheral is
    +   * enabled.
    +   */
    +
    +  regval  = getreg32(STM32F0_RCC_CR2);
    +  regval |= RCC_CR2_HSI48ON;
    +  putreg32(regval, STM32F0_RCC_CR2);
    +
    +  if (syncsrc == SYNCSRC_USB)
    +    {
    +      /* Select the HSI48 as the USB clock source */
    +
    +      regval = getreg32(STM32F0_RCC_CFGR3);
    +      regval &= ~RCC_CFGR3_USBSW;
    +      putreg32(regval, STM32F0_RCC_CFGR3);
    +    }
    +
    +  /* Wait for the HSI48 clock to stabilize */
    +
    +  while ((getreg32(STM32F0_RCC_CR2) & RCC_CR2_HSI48RDY) == 0);
    +
    +
    +  /* The CRS synchronization (SYNC) source, selectable through the CRS_CFGR
    +   * register, can be the signal from the external CRS_SYNC pin, the LSE
    +   * clock or the USB SOF signal.
    +   */
    +
    +  regval = getreg32(STM32F0_CRS_CFGR);
    +  regval &= ~CRS_CFGR_SYNCSRC_MASK;
    +
    +  switch (syncsrc)
    +    {
    +      default:
    +      case SYNCSRC_GPIO: /* GPIO selected as SYNC signal source */
    +        regval |= CRS_CFGR_SYNCSRC_GPIO;
    +        break;
    +
    +      case SYNCSRC_LSE:  /* LSE selected as SYNC signal source */
    +        regval |= CRS_CFGR_SYNCSRC_LSE;
    +        break;
    +
    +      case SYNCSRC_USB:  /* USB SOF selected as SYNC signal source */
    +        regval |= CRS_CFGR_SYNCSRC_USBSOF;
    +        break;
    +    }
    +
    +  putreg32(regval, STM32F0_CRS_CFGR);
    +
    +  /* Set the AUTOTRIMEN bit the the CRS_CR register to enables the automatic
    +   * hardware adjustment of TRIM bits according to the measured frequency
    +   * error between the selected SYNC event.
    +   */
    +
    +  regval  = getreg32(STM32F0_CRS_CR);
    +  regval |= CRS_CR_AUTOTRIMEN;
    +  putreg32(regval, STM32F0_CRS_CR);
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_disable_hsi48
    + *
    + * Description:
    + *   Disable the HSI48 clock.
    + *
    + * Input Parameters:
    + *   None
    + *
    + * Returned Value:
    + *   None
    + *
    + ****************************************************************************/
    +
    +void stm32f0_disable_hsi48(void)
    +{
    +  uint32_t regval;
    +
    +  /* Disable the HSI48 clock */
    +
    +  regval  = getreg32(STM32F0_RCC_CR2);
    +  regval &= ~RCC_CR2_HSI48ON;
    +  putreg32(regval, STM32F0_RCC_CR2);
    +
    +  /* Set other registers to the default settings. */
    +
    +  regval = getreg32(STM32F0_CRS_CFGR);
    +  regval &= ~CRS_CFGR_SYNCSRC_MASK;
    +  putreg32(regval, STM32F0_CRS_CFGR);
    +  
    +  regval  = getreg32(STM32F0_CRS_CR);
    +  regval &= ~CRS_CR_AUTOTRIMEN;
    +  putreg32(regval, STM32F0_CRS_CR);
    +}
    diff --git a/arch/arm/src/stm32f0/stm32f0_hsi48.h b/arch/arm/src/stm32f0/stm32f0_hsi48.h
    new file mode 100644
    index 0000000000..d299db13e1
    --- /dev/null
    +++ b/arch/arm/src/stm32f0/stm32f0_hsi48.h
    @@ -0,0 +1,109 @@
    +/************************************************************************************
    + * arch/arm/src/stm32f0/stm32f0_rcc.h
    + *
    + *   Copyright (C) 2017 Gregory Nutt. All rights reserved.
    + *   Author: Gregory Nutt 
    + *           Alan Carvalho de Assis 
    + *
    + * 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 __ARCH_ARM_SRC_STM32F0_STM32F0_HSI48_H
    +#define __ARCH_ARM_SRC_STM32F0_STM32F0_HSI48_H
    +
    +/************************************************************************************
    + * Included Files
    + ************************************************************************************/
    +
    +#include 
    +
    +#ifdef CONFIG_STM32F0_HAVE_HSI48
    +
    +/************************************************************************************
    + * Public Types
    + ************************************************************************************/
    +
    +enum syncsrc_e
    +{
    +  SYNCSRC_GPIO = 0, /* GPIO selected as SYNC signal source */
    +  SYNCSRC_LSE,      /* LSE selected as SYNC signal source */
    +  SYNCSRC_USB,      /* USB SOF selected as SYNC signal source */   
    +};
    +
    +/************************************************************************************
    + * Public Functions
    + ************************************************************************************/
    +
    +/****************************************************************************
    + * Name: stm32f0_enable_hsi48
    + *
    + * Description:
    + *   On STM32F04x, STM32F07x and STM32F09x devices only, the HSI48 clock
    + *   signal is generated from an internal 48 MHz RC oscillator and can be
    + *   used directly as a system clock or divided and be used as PLL input.
    + *
    + *   The internal 48MHz RC oscillator is mainly dedicated to provide a high
    + *   precision clock to the USB peripheral by means of a special Clock
    + *   Recovery System (CRS) circuitry, which could use the USB SOF signal or
    + *   the LSE or an external signal to automatically adjust the oscillator
    + *   frequency on-fly, in a very small steps. This oscillator can also be
    + *   used as a system clock source when the system is in run mode; it will
    + *   be disabled as soon as the system enters in Stop or Standby mode. When
    + *   the CRS is not used, the HSI48 RC oscillator runs on its default
    + *   frequency which is subject to manufacturing process variations.
    + *
    + * Input Parameters:
    + *   Identifies the syncrhonization source for the HSI48.  When used as the
    + *   USB source clock, this must be set to SYNCSRC_USB.
    + *
    + * Returned Value:
    + *   None
    + *
    + ****************************************************************************/
    +
    +void stm32f0_enable_hsi48(enum syncsrc_e syncsrc);
    +
    +/****************************************************************************
    + * Name: stm32f0_disable_hsi48
    + *
    + * Description:
    + *   Disable the HSI48 clock.
    + *
    + * Input Parameters:
    + *   None
    + *
    + * Returned Value:
    + *   None
    + *
    + ****************************************************************************/
    +
    +void stm32f0_disable_hsi48(void);
    +
    +#endif /* CONFIG_STM32F0_HAVE_HSI48 */
    +#endif /* __ARCH_ARM_SRC_STM32F0_STM32F0_HSI48_H */
    diff --git a/arch/arm/src/stm32f0/stm32f0_rcc.h b/arch/arm/src/stm32f0/stm32f0_rcc.h
    index ca8f537059..e23484ae43 100644
    --- a/arch/arm/src/stm32f0/stm32f0_rcc.h
    +++ b/arch/arm/src/stm32f0/stm32f0_rcc.h
    @@ -34,8 +34,8 @@
      *
      ************************************************************************************/
     
    -#ifndef __ARCH_ARM_SRC_STM32F0_STM32F0_RRC_H
    -#define __ARCH_ARM_SRC_STM32F0_STM32F0_RRC_H
    +#ifndef __ARCH_ARM_SRC_STM32F0_STM32F0_RCC_H
    +#define __ARCH_ARM_SRC_STM32F0_STM32F0_RCC_H
     
     /************************************************************************************
      * Included Files
    -- 
    GitLab
    
    
    From bb54449889498c912edfc614bcc9caa096d70d89 Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Thu, 20 Apr 2017 11:50:58 -0600
    Subject: [PATCH 532/990] STM32F0: Add an untested port of the F1 USB device to
     the STM32F0
    
    ---
     arch/arm/src/stm32f0/Make.defs             |    4 +
     arch/arm/src/stm32f0/chip/stm32f0_usbdev.h |  305 +-
     arch/arm/src/stm32f0/stm32f0_usbdev.c      | 3881 ++++++++++++++++++++
     arch/arm/src/stm32f0/stm32f0_usbdev.h      |   96 +
     4 files changed, 4133 insertions(+), 153 deletions(-)
     create mode 100644 arch/arm/src/stm32f0/stm32f0_usbdev.c
     create mode 100644 arch/arm/src/stm32f0/stm32f0_usbdev.h
    
    diff --git a/arch/arm/src/stm32f0/Make.defs b/arch/arm/src/stm32f0/Make.defs
    index 3aadfbfaae..27fb354774 100644
    --- a/arch/arm/src/stm32f0/Make.defs
    +++ b/arch/arm/src/stm32f0/Make.defs
    @@ -91,6 +91,10 @@ ifeq ($(CONFIG_STM32F0_HAVE_HSI48),y)
     CHIP_CSRCS += stm32f0_hsi48.c
     endif
     
    +ifeq ($(CONFIG_STM32F0_USB),y)
    +CHIP_CSRCS += stm32f0_usbdev.c
    +endif
    +
     ifeq ($(CONFIG_STM32F0_SPI0),y)
     CHIP_CSRCS += stm32f0_spi.c
     else
    diff --git a/arch/arm/src/stm32f0/chip/stm32f0_usbdev.h b/arch/arm/src/stm32f0/chip/stm32f0_usbdev.h
    index dabcc37fc5..19ea51787f 100644
    --- a/arch/arm/src/stm32f0/chip/stm32f0_usbdev.h
    +++ b/arch/arm/src/stm32f0/chip/stm32f0_usbdev.h
    @@ -43,8 +43,7 @@
     #include 
     #include 
     
    -#if defined(CONFIG_STM32_STM32L15XX) || defined(CONFIG_STM32_STM32F10XX) || defined(CONFIG_STM32_STM32F30XX) \
    -    || defined(CONFIG_STM32_STM32F37XX)
    +#ifdef CONFIG_STM32F0_HAVE_USBDEV
     
     /************************************************************************************
      * Pre-processor Definitions
    @@ -54,212 +53,212 @@
     
     /* Endpoint Registers */
     
    -#define STM32_USB_EPR_OFFSET(n)      ((n) << 2) /* USB endpoint n register (16-bits) */
    -#define STM32_USB_EP0R_OFFSET        0x0000  /* USB endpoint 0 register (16-bits) */
    -#define STM32_USB_EP1R_OFFSET        0x0004  /* USB endpoint 1 register (16-bits) */
    -#define STM32_USB_EP2R_OFFSET        0x0008  /* USB endpoint 2 register (16-bits) */
    -#define STM32_USB_EP3R_OFFSET        0x000c  /* USB endpoint 3 register (16-bits) */
    -#define STM32_USB_EP4R_OFFSET        0x0010  /* USB endpoint 4 register (16-bits) */
    -#define STM32_USB_EP5R_OFFSET        0x0014  /* USB endpoint 5 register (16-bits) */
    -#define STM32_USB_EP6R_OFFSET        0x0018  /* USB endpoint 6 register (16-bits) */
    -#define STM32_USB_EP7R_OFFSET        0x001c  /* USB endpoint 7 register (16-bits) */
    +#define STM32F0_USB_EPR_OFFSET(n)      ((n) << 2) /* USB endpoint n register (16-bits) */
    +#define STM32F0_USB_EP0R_OFFSET        0x0000  /* USB endpoint 0 register (16-bits) */
    +#define STM32F0_USB_EP1R_OFFSET        0x0004  /* USB endpoint 1 register (16-bits) */
    +#define STM32F0_USB_EP2R_OFFSET        0x0008  /* USB endpoint 2 register (16-bits) */
    +#define STM32F0_USB_EP3R_OFFSET        0x000c  /* USB endpoint 3 register (16-bits) */
    +#define STM32F0_USB_EP4R_OFFSET        0x0010  /* USB endpoint 4 register (16-bits) */
    +#define STM32F0_USB_EP5R_OFFSET        0x0014  /* USB endpoint 5 register (16-bits) */
    +#define STM32F0_USB_EP6R_OFFSET        0x0018  /* USB endpoint 6 register (16-bits) */
    +#define STM32F0_USB_EP7R_OFFSET        0x001c  /* USB endpoint 7 register (16-bits) */
     
     /* Common Registers */
     
    -#define STM32_USB_CNTR_OFFSET        0x0040  /* USB control register (16-bits) */
    -#define STM32_USB_ISTR_OFFSET        0x0044  /* USB interrupt status register (16-bits) */
    -#define STM32_USB_FNR_OFFSET         0x0048  /* USB frame number register (16-bits) */
    -#define STM32_USB_DADDR_OFFSET       0x004c  /* USB device address (16-bits) */
    -#define STM32_USB_BTABLE_OFFSET      0x0050  /* Buffer table address (16-bits) */
    -#define STM32_USB_LPMCSR_OFFSET      0x0054  /* LPM control and status register (16-bits) */
    -#define STM32_USB_BCDR_OFFSET        0x0058  /* Battery charging detector (16-bits) */
    +#define STM32F0_USB_CNTR_OFFSET        0x0040  /* USB control register (16-bits) */
    +#define STM32F0_USB_ISTR_OFFSET        0x0044  /* USB interrupt status register (16-bits) */
    +#define STM32F0_USB_FNR_OFFSET         0x0048  /* USB frame number register (16-bits) */
    +#define STM32F0_USB_DADDR_OFFSET       0x004c  /* USB device address (16-bits) */
    +#define STM32F0_USB_BTABLE_OFFSET      0x0050  /* Buffer table address (16-bits) */
    +#define STM32F0_USB_LPMCSR_OFFSET      0x0054  /* LPM control and status register (16-bits) */
    +#define STM32F0_USB_BCDR_OFFSET        0x0058  /* Battery charging detector (16-bits) */
     
     /* Buffer Descriptor Table (Relatative to BTABLE address) */
     
    -#define STM32_USB_ADDR_TX_WOFFSET   (0)     /* Transmission buffer address n (16-bits) */
    -#define STM32_USB_COUNT_TX_WOFFSET  (2)     /* Transmission byte count n (16-bits) */
    -#define STM32_USB_ADDR_RX_WOFFSET   (4)     /* Reception buffer address n (16-bits) */
    -#define STM32_USB_COUNT_RX_WOFFSET  (6)     /* Reception byte count n (16-bits) */
    +#define STM32F0_USB_ADDR_TX_WOFFSET    (0)     /* Transmission buffer address n (16-bits) */
    +#define STM32F0_USB_COUNT_TX_WOFFSET   (2)     /* Transmission byte count n (16-bits) */
    +#define STM32F0_USB_ADDR_RX_WOFFSET    (4)     /* Reception buffer address n (16-bits) */
    +#define STM32F0_USB_COUNT_RX_WOFFSET   (6)     /* Reception byte count n (16-bits) */
     
    -#define STM32_USB_BTABLE_RADDR(ep,o) ((((uint32_t)getreg16(STM32_USB_BTABLE) + ((ep) << 3)) + (o))  << 1)
    -#define STM32_USB_ADDR_TX_OFFSET(ep)  STM32_USB_BTABLE_RADDR(ep,STM32_USB_ADDR_TX_WOFFSET)
    -#define STM32_USB_COUNT_TX_OFFSET(ep) STM32_USB_BTABLE_RADDR(ep,STM32_USB_COUNT_TX_WOFFSET)
    -#define STM32_USB_ADDR_RX_OFFSET(ep)  STM32_USB_BTABLE_RADDR(ep,STM32_USB_ADDR_RX_WOFFSET)
    -#define STM32_USB_COUNT_RX_OFFSET(ep) STM32_USB_BTABLE_RADDR(ep,STM32_USB_COUNT_RX_WOFFSET)
    +#define STM32F0_USB_BTABLE_RADDR(ep,o) ((((uint32_t)getreg16(STM32F0_USB_BTABLE) + ((ep) << 3)) + (o))  << 1)
    +#define STM32F0_USB_ADDR_TX_OFFSET(ep)  STM32F0_USB_BTABLE_RADDR(ep,STM32F0_USB_ADDR_TX_WOFFSET)
    +#define STM32F0_USB_COUNT_TX_OFFSET(ep) STM32F0_USB_BTABLE_RADDR(ep,STM32F0_USB_COUNT_TX_WOFFSET)
    +#define STM32F0_USB_ADDR_RX_OFFSET(ep)  STM32F0_USB_BTABLE_RADDR(ep,STM32F0_USB_ADDR_RX_WOFFSET)
    +#define STM32F0_USB_COUNT_RX_OFFSET(ep) STM32F0_USB_BTABLE_RADDR(ep,STM32F0_USB_COUNT_RX_WOFFSET)
     
     /* Register Addresses ***************************************************************/
     
     /* Endpoint Registers */
     
    -#define STM32_USB_EPR(n)             (STM32_USB_BASE+STM32_USB_EPR_OFFSET(n))
    -#define STM32_USB_EP0R               (STM32_USB_BASE+STM32_USB_EP0R_OFFSET)
    -#define STM32_USB_EP1R               (STM32_USB_BASE+STM32_USB_EP1R_OFFSET)
    -#define STM32_USB_EP2R               (STM32_USB_BASE+STM32_USB_EP2R_OFFSET)
    -#define STM32_USB_EP3R               (STM32_USB_BASE+STM32_USB_EP3R_OFFSET)
    -#define STM32_USB_EP4R               (STM32_USB_BASE+STM32_USB_EP4R_OFFSET)
    -#define STM32_USB_EP5R               (STM32_USB_BASE+STM32_USB_EP5R_OFFSET)
    -#define STM32_USB_EP6R               (STM32_USB_BASE+STM32_USB_EP6R_OFFSET)
    -#define STM32_USB_EP7R               (STM32_USB_BASE+STM32_USB_EP7R_OFFSET)
    +#define STM32F0_USB_EPR(n)             (STM32F0_USB_BASE+STM32F0_USB_EPR_OFFSET(n))
    +#define STM32F0_USB_EP0R               (STM32F0_USB_BASE+STM32F0_USB_EP0R_OFFSET)
    +#define STM32F0_USB_EP1R               (STM32F0_USB_BASE+STM32F0_USB_EP1R_OFFSET)
    +#define STM32F0_USB_EP2R               (STM32F0_USB_BASE+STM32F0_USB_EP2R_OFFSET)
    +#define STM32F0_USB_EP3R               (STM32F0_USB_BASE+STM32F0_USB_EP3R_OFFSET)
    +#define STM32F0_USB_EP4R               (STM32F0_USB_BASE+STM32F0_USB_EP4R_OFFSET)
    +#define STM32F0_USB_EP5R               (STM32F0_USB_BASE+STM32F0_USB_EP5R_OFFSET)
    +#define STM32F0_USB_EP6R               (STM32F0_USB_BASE+STM32F0_USB_EP6R_OFFSET)
    +#define STM32F0_USB_EP7R               (STM32F0_USB_BASE+STM32F0_USB_EP7R_OFFSET)
     
     /* Common Registers */
     
    -#define STM32_USB_CNTR               (STM32_USB_BASE+STM32_USB_CNTR_OFFSET)
    -#define STM32_USB_ISTR               (STM32_USB_BASE+STM32_USB_ISTR_OFFSET)
    -#define STM32_USB_FNR                (STM32_USB_BASE+STM32_USB_FNR_OFFSET)
    -#define STM32_USB_DADDR              (STM32_USB_BASE+STM32_USB_DADDR_OFFSET)
    -#define STM32_USB_BTABLE             (STM32_USB_BASE+STM32_USB_BTABLE_OFFSET)
    -#define STM32_USB_LPMCSR             (STM32_USB_BASE+STM32_USB_LPMCSR_OFFSET)
    -#define STM32_USB_BCDR               (STM32_USB_BASE+STM32_USB_BCDR_OFFSET)
    +#define STM32F0_USB_CNTR               (STM32F0_USB_BASE+STM32F0_USB_CNTR_OFFSET)
    +#define STM32F0_USB_ISTR               (STM32F0_USB_BASE+STM32F0_USB_ISTR_OFFSET)
    +#define STM32F0_USB_FNR                (STM32F0_USB_BASE+STM32F0_USB_FNR_OFFSET)
    +#define STM32F0_USB_DADDR              (STM32F0_USB_BASE+STM32F0_USB_DADDR_OFFSET)
    +#define STM32F0_USB_BTABLE             (STM32F0_USB_BASE+STM32F0_USB_BTABLE_OFFSET)
    +#define STM32F0_USB_LPMCSR             (STM32F0_USB_BASE+STM32F0_USB_LPMCSR_OFFSET)
    +#define STM32F0_USB_BCDR               (STM32F0_USB_BASE+STM32F0_USB_BCDR_OFFSET)
     
     /* Buffer Descriptor Table (Relatative to BTABLE address) */
     
    -#define STM32_USB_BTABLE_ADDR(ep,o)  (STM32_USBRAM_BASE+STM32_USB_BTABLE_RADDR(ep,o))
    -#define STM32_USB_ADDR_TX(ep)        STM32_USB_BTABLE_ADDR(ep,STM32_USB_ADDR_TX_WOFFSET)
    -#define STM32_USB_COUNT_TX(ep)       STM32_USB_BTABLE_ADDR(ep,STM32_USB_COUNT_TX_WOFFSET)
    -#define STM32_USB_ADDR_RX(ep)        STM32_USB_BTABLE_ADDR(ep,STM32_USB_ADDR_RX_WOFFSET)
    -#define STM32_USB_COUNT_RX(ep)       STM32_USB_BTABLE_ADDR(ep,STM32_USB_COUNT_RX_WOFFSET)
    +#define STM32F0_USB_BTABLE_ADDR(ep,o)  (STM32F0_USBRAM_BASE+STM32F0_USB_BTABLE_RADDR(ep,o))
    +#define STM32F0_USB_ADDR_TX(ep)        STM32F0_USB_BTABLE_ADDR(ep,STM32F0_USB_ADDR_TX_WOFFSET)
    +#define STM32F0_USB_COUNT_TX(ep)       STM32F0_USB_BTABLE_ADDR(ep,STM32F0_USB_COUNT_TX_WOFFSET)
    +#define STM32F0_USB_ADDR_RX(ep)        STM32F0_USB_BTABLE_ADDR(ep,STM32F0_USB_ADDR_RX_WOFFSET)
    +#define STM32F0_USB_COUNT_RX(ep)       STM32F0_USB_BTABLE_ADDR(ep,STM32F0_USB_COUNT_RX_WOFFSET)
     
     /* Register Bitfield Definitions ****************************************************/
     
     /* USB endpoint register */
     
    -#define USB_EPR_EA_SHIFT             (0)       /* Bits 3:0 [3:0]: Endpoint Address */
    -#define USB_EPR_EA_MASK              (0X0f << USB_EPR_EA_SHIFT)
    -#define USB_EPR_STATTX_SHIFT         (4)       /* Bits 5-4: Status bits, for transmission transfers */
    -#define USB_EPR_STATTX_MASK          (3 << USB_EPR_STATTX_SHIFT)
    -#  define USB_EPR_STATTX_DIS         (0 << USB_EPR_STATTX_SHIFT) /* EndPoint TX DISabled */
    -#  define USB_EPR_STATTX_STALL       (1 << USB_EPR_STATTX_SHIFT) /* EndPoint TX STALLed */
    -#  define USB_EPR_STATTX_NAK         (2 << USB_EPR_STATTX_SHIFT) /* EndPoint TX NAKed */
    -#  define USB_EPR_STATTX_VALID       (3 << USB_EPR_STATTX_SHIFT) /* EndPoint TX VALID */
    -#  define USB_EPR_STATTX_DTOG1       (1 << USB_EPR_STATTX_SHIFT) /* EndPoint TX Data Toggle bit1 */
    -#  define USB_EPR_STATTX_DTOG2       (2 << USB_EPR_STATTX_SHIFT) /* EndPoint TX Data Toggle bit2 */
    -#define USB_EPR_DTOG_TX              (1 << 6)  /* Bit 6: Data Toggle, for transmission transfers */
    -#define USB_EPR_CTR_TX               (1 << 7)  /* Bit 7: Correct Transfer for transmission */
    -#define USB_EPR_EP_KIND              (1 << 8)  /* Bit 8: Endpoint Kind */
    -#define USB_EPR_EPTYPE_SHIFT         (9)       /* Bits 10-9: Endpoint type */
    -#define USB_EPR_EPTYPE_MASK          (3 << USB_EPR_EPTYPE_SHIFT)
    -#  define USB_EPR_EPTYPE_BULK        (0 << USB_EPR_EPTYPE_SHIFT) /* EndPoint BULK */
    -#  define USB_EPR_EPTYPE_CONTROL     (1 << USB_EPR_EPTYPE_SHIFT) /* EndPoint CONTROL */
    -#  define USB_EPR_EPTYPE_ISOC        (2 << USB_EPR_EPTYPE_SHIFT) /* EndPoint ISOCHRONOUS */
    -#  define USB_EPR_EPTYPE_INTERRUPT   (3 << USB_EPR_EPTYPE_SHIFT) /* EndPoint INTERRUPT */
    -#define USB_EPR_SETUP                (1 << 11) /* Bit 11: Setup transaction completed */
    -#define USB_EPR_STATRX_SHIFT         (12)      /* Bits 13-12: Status bits, for reception transfers */
    -#define USB_EPR_STATRX_MASK          (3 << USB_EPR_STATRX_SHIFT)
    -#  define USB_EPR_STATRX_DIS         (0 << USB_EPR_STATRX_SHIFT) /* EndPoint RX DISabled */
    -#  define USB_EPR_STATRX_STALL       (1 << USB_EPR_STATRX_SHIFT) /* EndPoint RX STALLed */
    -#  define USB_EPR_STATRX_NAK         (2 << USB_EPR_STATRX_SHIFT) /* EndPoint RX NAKed */
    -#  define USB_EPR_STATRX_VALID       (3 << USB_EPR_STATRX_SHIFT) /* EndPoint RX VALID */
    -#  define USB_EPR_STATRX_DTOG1       (1 << USB_EPR_STATRX_SHIFT) /* EndPoint RX Data TOGgle bit1 */
    -#  define USB_EPR_STATRX_DTOG2       (2 << USB_EPR_STATRX_SHIFT) /* EndPoint RX Data TOGgle bit1 */
    -#define USB_EPR_DTOG_RX              (1 << 14) /* Bit 14: Data Toggle, for reception transfers */
    -#define USB_EPR_CTR_RX               (1 << 15) /* Bit 15: Correct Transfer for reception */
    +#define USB_EPR_EA_SHIFT               (0)       /* Bits 3:0 [3:0]: Endpoint Address */
    +#define USB_EPR_EA_MASK                (0X0f << USB_EPR_EA_SHIFT)
    +#define USB_EPR_STATTX_SHIFT           (4)       /* Bits 5-4: Status bits, for transmission transfers */
    +#define USB_EPR_STATTX_MASK            (3 << USB_EPR_STATTX_SHIFT)
    +#  define USB_EPR_STATTX_DIS           (0 << USB_EPR_STATTX_SHIFT) /* EndPoint TX DISabled */
    +#  define USB_EPR_STATTX_STALL         (1 << USB_EPR_STATTX_SHIFT) /* EndPoint TX STALLed */
    +#  define USB_EPR_STATTX_NAK           (2 << USB_EPR_STATTX_SHIFT) /* EndPoint TX NAKed */
    +#  define USB_EPR_STATTX_VALID         (3 << USB_EPR_STATTX_SHIFT) /* EndPoint TX VALID */
    +#  define USB_EPR_STATTX_DTOG1         (1 << USB_EPR_STATTX_SHIFT) /* EndPoint TX Data Toggle bit1 */
    +#  define USB_EPR_STATTX_DTOG2         (2 << USB_EPR_STATTX_SHIFT) /* EndPoint TX Data Toggle bit2 */
    +#define USB_EPR_DTOG_TX                (1 << 6)  /* Bit 6: Data Toggle, for transmission transfers */
    +#define USB_EPR_CTR_TX                 (1 << 7)  /* Bit 7: Correct Transfer for transmission */
    +#define USB_EPR_EP_KIND                (1 << 8)  /* Bit 8: Endpoint Kind */
    +#define USB_EPR_EPTYPE_SHIFT           (9)       /* Bits 10-9: Endpoint type */
    +#define USB_EPR_EPTYPE_MASK            (3 << USB_EPR_EPTYPE_SHIFT)
    +#  define USB_EPR_EPTYPE_BULK          (0 << USB_EPR_EPTYPE_SHIFT) /* EndPoint BULK */
    +#  define USB_EPR_EPTYPE_CONTROL       (1 << USB_EPR_EPTYPE_SHIFT) /* EndPoint CONTROL */
    +#  define USB_EPR_EPTYPE_ISOC          (2 << USB_EPR_EPTYPE_SHIFT) /* EndPoint ISOCHRONOUS */
    +#  define USB_EPR_EPTYPE_INTERRUPT     (3 << USB_EPR_EPTYPE_SHIFT) /* EndPoint INTERRUPT */
    +#define USB_EPR_SETUP                  (1 << 11) /* Bit 11: Setup transaction completed */
    +#define USB_EPR_STATRX_SHIFT           (12)      /* Bits 13-12: Status bits, for reception transfers */
    +#define USB_EPR_STATRX_MASK            (3 << USB_EPR_STATRX_SHIFT)
    +#  define USB_EPR_STATRX_DIS           (0 << USB_EPR_STATRX_SHIFT) /* EndPoint RX DISabled */
    +#  define USB_EPR_STATRX_STALL         (1 << USB_EPR_STATRX_SHIFT) /* EndPoint RX STALLed */
    +#  define USB_EPR_STATRX_NAK           (2 << USB_EPR_STATRX_SHIFT) /* EndPoint RX NAKed */
    +#  define USB_EPR_STATRX_VALID         (3 << USB_EPR_STATRX_SHIFT) /* EndPoint RX VALID */
    +#  define USB_EPR_STATRX_DTOG1         (1 << USB_EPR_STATRX_SHIFT) /* EndPoint RX Data TOGgle bit1 */
    +#  define USB_EPR_STATRX_DTOG2         (2 << USB_EPR_STATRX_SHIFT) /* EndPoint RX Data TOGgle bit1 */
    +#define USB_EPR_DTOG_RX                (1 << 14) /* Bit 14: Data Toggle, for reception transfers */
    +#define USB_EPR_CTR_RX                 (1 << 15) /* Bit 15: Correct Transfer for reception */
     
     /* USB control register */
     
    -#define USB_CNTR_FRES                (1 << 0)  /* Bit 0: Force USB Reset */
    -#define USB_CNTR_PDWN                (1 << 1)  /* Bit 1: Power down */
    -#define USB_CNTR_LPMODE              (1 << 2)  /* Bit 2: Low-power mode */
    -#define USB_CNTR_FSUSP               (1 << 3)  /* Bit 3: Force suspend */
    -#define USB_CNTR_RESUME              (1 << 4)  /* Bit 4: Resume request */
    -#define USB_CNTR_L1RESUME            (1 << 5)  /* Bit 5: LPM L1 Resume request */
    -#define USB_CNTR_L1REQ               (1 << 7)  /* Bit 7: LPM L1 state request interrupt mask */
    -#define USB_CNTR_ESOFM               (1 << 8)  /* Bit 8: Expected Start Of Frame Interrupt Mask */
    -#define USB_CNTR_SOFM                (1 << 9)  /* Bit 9: Start Of Frame Interrupt Mask */
    -#define USB_CNTR_RESETM              (1 << 10) /* Bit 10: USB Reset Interrupt Mask */
    -#define USB_CNTR_SUSPM               (1 << 11) /* Bit 11: Suspend mode Interrupt Mask */
    -#define USB_CNTR_WKUPM               (1 << 12) /* Bit 12: Wakeup Interrupt Mask */
    -#define USB_CNTR_ERRM                (1 << 13) /* Bit 13: Error Interrupt Mask */
    -#define USB_CNTR_PMAOVRM             (1 << 14) /* Bit 14: Packet Memory Area Over / Underrun Interrupt Mask */
    -#define USB_CNTR_CTRM                (1 << 15) /* Bit 15: Correct Transfer Interrupt Mask */
    -
    -#define USB_CNTR_ALLINTS             (USB_CNTR_L1REQ|USB_CNTR_ESOFM|USB_CNTR_SOFM|USB_CNTR_RESETM|\
    -                                      USB_CNTR_SUSPM|USB_CNTR_WKUPM|USB_CNTR_ERRM|USB_CNTR_PMAOVRNM|\
    -                                      USB_CNTR_CTRM)
    +#define USB_CNTR_FRES                  (1 << 0)  /* Bit 0: Force USB Reset */
    +#define USB_CNTR_PDWN                  (1 << 1)  /* Bit 1: Power down */
    +#define USB_CNTR_LPMODE                (1 << 2)  /* Bit 2: Low-power mode */
    +#define USB_CNTR_FSUSP                 (1 << 3)  /* Bit 3: Force suspend */
    +#define USB_CNTR_RESUME                (1 << 4)  /* Bit 4: Resume request */
    +#define USB_CNTR_L1RESUME              (1 << 5)  /* Bit 5: LPM L1 Resume request */
    +#define USB_CNTR_L1REQ                 (1 << 7)  /* Bit 7: LPM L1 state request interrupt mask */
    +#define USB_CNTR_ESOFM                 (1 << 8)  /* Bit 8: Expected Start Of Frame Interrupt Mask */
    +#define USB_CNTR_SOFM                  (1 << 9)  /* Bit 9: Start Of Frame Interrupt Mask */
    +#define USB_CNTR_RESETM                (1 << 10) /* Bit 10: USB Reset Interrupt Mask */
    +#define USB_CNTR_SUSPM                 (1 << 11) /* Bit 11: Suspend mode Interrupt Mask */
    +#define USB_CNTR_WKUPM                 (1 << 12) /* Bit 12: Wakeup Interrupt Mask */
    +#define USB_CNTR_ERRM                  (1 << 13) /* Bit 13: Error Interrupt Mask */
    +#define USB_CNTR_PMAOVRN               (1 << 14) /* Bit 14: Packet Memory Area Over / Underrun Interrupt Mask */
    +#define USB_CNTR_CTRM                  (1 << 15) /* Bit 15: Correct Transfer Interrupt Mask */
    +
    +#define USB_CNTR_ALLINTS               (USB_CNTR_L1REQ|USB_CNTR_ESOFM|USB_CNTR_SOFM|USB_CNTR_RESETM|\
    +                                        USB_CNTR_SUSPM|USB_CNTR_WKUPM|USB_CNTR_ERRM|USB_CNTR_PMAOVRN|\
    +                                        USB_CNTR_CTRM)
     
     /* USB interrupt status register */
     
    -#define USB_ISTR_EPID_SHIFT          (0)       /* Bits 3-0: Endpoint Identifier */
    -#define USB_ISTR_EPID_MASK           (0x0f << USB_ISTR_EPID_SHIFT)
    -#define USB_ISTR_DIR                 (1 << 4)  /* Bit 4:  Direction of transaction */
    -#define USB_ISTR_L1REQ               (1 << 7)  /* Bit 7:  LPM L1 state request */
    -#define USB_ISTR_ESOF                (1 << 8)  /* Bit 8:  Expected Start Of Frame */
    -#define USB_ISTR_SOF                 (1 << 9)  /* Bit 9:  Start Of Frame */
    -#define USB_ISTR_RESET               (1 << 10) /* Bit 10: USB RESET request */
    -#define USB_ISTR_SUSP                (1 << 11) /* Bit 11: Suspend mode request */
    -#define USB_ISTR_WKUP                (1 << 12) /* Bit 12: Wake up */
    -#define USB_ISTR_ERR                 (1 << 13) /* Bit 13: Error */
    -#define USB_ISTR_PMAOVRN             (1 << 14) /* Bit 14: Packet Memory Area Over / Underrun */
    -#define USB_ISTR_CTR                 (1 << 15) /* Bit 15: Correct Transfer */
    -
    -#define USB_ISTR_ALLINTS             (USB_ISTR_L1REQ|USB_ISTR_ESOF|USB_ISTR_SOF|USB_ISTR_RESET|\
    -                                      USB_ISTR_SUSP|USB_ISTR_WKUP|USB_ISTR_ERR|USB_ISTR_PMAOVRN|\
    -                                      USB_ISTR_CTR)
    +#define USB_ISTR_EPID_SHIFT            (0)       /* Bits 3-0: Endpoint Identifier */
    +#define USB_ISTR_EPID_MASK             (0x0f << USB_ISTR_EPID_SHIFT)
    +#define USB_ISTR_DIR                   (1 << 4)  /* Bit 4:  Direction of transaction */
    +#define USB_ISTR_L1REQ                 (1 << 7)  /* Bit 7:  LPM L1 state request */
    +#define USB_ISTR_ESOF                  (1 << 8)  /* Bit 8:  Expected Start Of Frame */
    +#define USB_ISTR_SOF                   (1 << 9)  /* Bit 9:  Start Of Frame */
    +#define USB_ISTR_RESET                 (1 << 10) /* Bit 10: USB RESET request */
    +#define USB_ISTR_SUSP                  (1 << 11) /* Bit 11: Suspend mode request */
    +#define USB_ISTR_WKUP                  (1 << 12) /* Bit 12: Wake up */
    +#define USB_ISTR_ERR                   (1 << 13) /* Bit 13: Error */
    +#define USB_ISTR_PMAOVRN               (1 << 14) /* Bit 14: Packet Memory Area Over / Underrun */
    +#define USB_ISTR_CTR                   (1 << 15) /* Bit 15: Correct Transfer */
    +
    +#define USB_ISTR_ALLINTS               (USB_ISTR_L1REQ|USB_ISTR_ESOF|USB_ISTR_SOF|USB_ISTR_RESET|\
    +                                        USB_ISTR_SUSP|USB_ISTR_WKUP|USB_ISTR_ERR|USB_ISTR_PMAOVRN|\
    +                                       USB_ISTR_CTR)
     
     /* USB frame number register */
     
    -#define USB_FNR_FN_SHIFT             (0)       /* Bits 10-0: Frame Number */
    -#define USB_FNR_FN_MASK              (0x07ff << USB_FNR_FN_SHIFT)
    -#define USB_FNR_LSOF_SHIFT           (11)      /* Bits 12-11: Lost SOF */
    -#define USB_FNR_LSOF_MASK            (3 << USB_FNR_LSOF_SHIFT)
    -#define USB_FNR_LCK                  (1 << 13) /* Bit 13: Locked */
    -#define USB_FNR_RXDM                 (1 << 14) /* Bit 14: Receive Data - Line Status */
    -#define USB_FNR_RXDP                 (1 << 15) /* Bit 15: Receive Data + Line Status */
    +#define USB_FNR_FN_SHIFT               (0)       /* Bits 10-0: Frame Number */
    +#define USB_FNR_FN_MASK                (0x07ff << USB_FNR_FN_SHIFT)
    +#define USB_FNR_LSOF_SHIFT             (11)      /* Bits 12-11: Lost SOF */
    +#define USB_FNR_LSOF_MASK              (3 << USB_FNR_LSOF_SHIFT)
    +#define USB_FNR_LCK                    (1 << 13) /* Bit 13: Locked */
    +#define USB_FNR_RXDM                   (1 << 14) /* Bit 14: Receive Data - Line Status */
    +#define USB_FNR_RXDP                   (1 << 15) /* Bit 15: Receive Data + Line Status */
     
     /* USB device address */
     
    -#define USB_DADDR_ADD_SHIFT          (0)       /* Bits 6-0: Device Address */
    -#define USB_DADDR_ADD_MASK           (0x7f << USB_DADDR_ADD_SHIFT)
    -#define USB_DADDR_EF                 (1 << 7)  /* Bit 7: Enable Function */
    +#define USB_DADDR_ADD_SHIFT            (0)       /* Bits 6-0: Device Address */
    +#define USB_DADDR_ADD_MASK             (0x7f << USB_DADDR_ADD_SHIFT)
    +#define USB_DADDR_EF                   (1 << 7)  /* Bit 7: Enable Function */
     
     /* Buffer table address */
     
    -#define USB_BTABLE_SHIFT             (3)       /* Bits 15:3: Buffer Table */
    -#define USB_BTABLE_MASK              (0x1fff << USB_BTABLE_SHIFT)
    +#define USB_BTABLE_SHIFT               (3)       /* Bits 15:3: Buffer Table */
    +#define USB_BTABLE_MASK                (0x1fff << USB_BTABLE_SHIFT)
     
     /* LPM control and status register (16-bits) */
     
    -#define USB_LPMCSR_LPMEN             (1 << 0)  /* Bit 0:  LPM support enable */
    -#define USB_LPMCSR_LPMACK            (1 << 1)  /* Bit 1:  LPM Token acknowledge enable */
    -#define USB_LPMCSR_REMWAKE           (1 << 3)  /* Bit 3:  bRemoteWake value */
    -#define USB_LPMCSR_BESL_SHIFT        (4)       /* Bits 4-7: BESL value */
    -#define USB_LPMCSR_BESL_MASK         (15 << USB_LPMCSR_BESL_SHIFT)
    +#define USB_LPMCSR_LPMEN               (1 << 0)  /* Bit 0:  LPM support enable */
    +#define USB_LPMCSR_LPMACK              (1 << 1)  /* Bit 1:  LPM Token acknowledge enable */
    +#define USB_LPMCSR_REMWAKE             (1 << 3)  /* Bit 3:  bRemoteWake value */
    +#define USB_LPMCSR_BESL_SHIFT          (4)       /* Bits 4-7: BESL value */
    +#define USB_LPMCSR_BESL_MASK           (15 << USB_LPMCSR_BESL_SHIFT)
     
     /* Battery charging detector (16-bits) */
     
    -#define USB_BCDR_BCDEN               (1 << 0)  /* Bit 0:  Battery charging detector (BCD) enable */
    -#define USB_BCDR_DCDEN               (1 << 1)  /* Bit 1:  Data contact detection (DCD) mode enable */
    -#define USB_BCDR_PDEN                (1 << 2)  /* Bit 2:  Primary detection (PD) mode enable */
    -#define USB_BCDR_SDEN                (1 << 3)  /* Bit 3:  Secondary detection (SD) mode enable */
    -#define USB_BCDR_DCDET               (1 << 4)  /* Bit 4:  Data contact detection (DCD) status */
    -#define USB_BCDR_PDET                (1 << 5)  /* Bit 5:  Primary detection (PD) status */
    -#define USB_BCDR_SDET                (1 << 6)  /* Bit 6:  Secondary detection (SD) status */
    -#define USB_BCDR_PS2DET              (1 << 7)  /* Bit 7:  DM pull-up detection status */
    -#define USB_BCDR_DPPU                (1 << 15) /* Bit 15: DP pull-up control */
    +#define USB_BCDR_BCDEN                 (1 << 0)  /* Bit 0:  Battery charging detector (BCD) enable */
    +#define USB_BCDR_DCDEN                 (1 << 1)  /* Bit 1:  Data contact detection (DCD) mode enable */
    +#define USB_BCDR_PDEN                  (1 << 2)  /* Bit 2:  Primary detection (PD) mode enable */
    +#define USB_BCDR_SDEN                  (1 << 3)  /* Bit 3:  Secondary detection (SD) mode enable */
    +#define USB_BCDR_DCDET                 (1 << 4)  /* Bit 4:  Data contact detection (DCD) status */
    +#define USB_BCDR_PDET                  (1 << 5)  /* Bit 5:  Primary detection (PD) status */
    +#define USB_BCDR_SDET                  (1 << 6)  /* Bit 6:  Secondary detection (SD) status */
    +#define USB_BCDR_PS2DET                (1 << 7)  /* Bit 7:  DM pull-up detection status */
    +#define USB_BCDR_DPPU                  (1 << 15) /* Bit 15: DP pull-up control */
     
     /* Transmission buffer address */
     
    -#define USB_ADDR_TX_ZERO             (1 << 0)  /* Bit 0 Must always be written as ‘0’ */
    -#define USB_ADDR_TX_SHIFT            (1)       /* Bits 15-1: Transmission Buffer Address */
    -#define USB_ADDR_TX_MASK             (0x7fff << USB_ADDR_ADDR_TX_SHIFT)
    +#define USB_ADDR_TX_ZERO               (1 << 0)  /* Bit 0 Must always be written as ‘0’ */
    +#define USB_ADDR_TX_SHIFT              (1)       /* Bits 15-1: Transmission Buffer Address */
    +#define USB_ADDR_TX_MASK               (0x7fff << USB_ADDR_ADDR_TX_SHIFT)
     
     /* Transmission byte count */
     
    -#define USB_COUNT_TX_SHIFT           (0)       /* Bits 9-0: Transmission Byte Count */
    -#define USB_COUNT_TX_MASK            (0x03ff << USB_COUNT_COUNT_TX_SHIFT)
    +#define USB_COUNT_TX_SHIFT             (0)       /* Bits 9-0: Transmission Byte Count */
    +#define USB_COUNT_TX_MASK              (0x03ff << USB_COUNT_COUNT_TX_SHIFT)
     
     /* Reception buffer address */
     
    -#define USB_ADDR_RX_ZERO             (1 << 0)  /* Bit 0 This bit must always be written as ‘0’ */
    -#define USB_ADDR_RX_SHIFT            (1)       /* Bits 15:1 ADDRn_RX[15:1]: Reception Buffer Address */
    -#define USB_ADDR_RX_MASK             (0x7fff << USB_ADDR_RX_SHIFT)
    +#define USB_ADDR_RX_ZERO               (1 << 0)  /* Bit 0 This bit must always be written as ‘0’ */
    +#define USB_ADDR_RX_SHIFT              (1)       /* Bits 15:1 ADDRn_RX[15:1]: Reception Buffer Address */
    +#define USB_ADDR_RX_MASK               (0x7fff << USB_ADDR_RX_SHIFT)
     
     /* Reception byte count */
     
    -#define USB_COUNT_RX_BL_SIZE         (1 << 15) /* Bit 15: BLock SIZE. */
    -#define USB_COUNT_RX_NUM_BLOCK_SHIFT (10)      /* Bits 14-10: Number of blocks */
    -#define USB_COUNT_RX_NUM_BLOCK_MASK  (0x1f << USB_COUNT_RX_NUM_BLOCK_SHIFT)
    -#define USB_COUNT_RX_SHIFT           (0)       /* Bits 9-0: Reception Byte Count */
    -#define USB_COUNT_RX_MASK            (0x03ff << USB_COUNT_RX_SHIFT)
    +#define USB_COUNT_RX_BL_SIZE           (1 << 15) /* Bit 15: BLock SIZE. */
    +#define USB_COUNT_RX_NUM_BLOCK_SHIFT   (10)      /* Bits 14-10: Number of blocks */
    +#define USB_COUNT_RX_NUM_BLOCK_MASK    (0x1f << USB_COUNT_RX_NUM_BLOCK_SHIFT)
    +#define USB_COUNT_RX_SHIFT             (0)       /* Bits 9-0: Reception Byte Count */
    +#define USB_COUNT_RX_MASK              (0x03ff << USB_COUNT_RX_SHIFT)
     
    -#endif /* CONFIG_STM32_STM32F10XX || CONFIG_STM32_STM32F30XX || CONFIG_STM32_STM32F37XX */
    +#endif /* CONFIG_STM32F0_HAVE_USBDEV */
     #endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_USBDEV_H */
    diff --git a/arch/arm/src/stm32f0/stm32f0_usbdev.c b/arch/arm/src/stm32f0/stm32f0_usbdev.c
    new file mode 100644
    index 0000000000..cf263a3573
    --- /dev/null
    +++ b/arch/arm/src/stm32f0/stm32f0_usbdev.c
    @@ -0,0 +1,3881 @@
    +/****************************************************************************
    + * arch/arm/src/stm32f0/stm32f0_usbdev.c
    + *
    + *   Copyright (C) 2017 Gregory Nutt. All rights reserved.
    + *   Author: Gregory Nutt 
    + *
    + * Ported from the STM32 F1 implmentation.  References:
    + *   - RM0008 Reference manual, STMicro document ID 13902
    + *   - STM32F10xxx USB development kit, UM0424, STMicro
    + *
    + * 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 
    +#include 
    +#include 
    +
    +#include 
    +
    +#include "up_arch.h"
    +#include "up_internal.h"
    +#include "chip/stm32f0_rcc.h"
    +#include "chip/stm32f0_usbdev.h"
    +#include "stm32f0_hsi48.h"
    +#include "stm32f0_gpio.h"
    +#include "stm32f0_usbdev.h"
    +
    +#if defined(CONFIG_USBDEV) && defined(CONFIG_STM32F0_USB)
    +
    +/****************************************************************************
    + * Pre-processor Definitions
    + ****************************************************************************/
    +
    +/* Configuration ************************************************************/
    +
    +#ifndef CONFIG_USBDEV_EP0_MAXSIZE
    +#  define CONFIG_USBDEV_EP0_MAXSIZE 64
    +#endif
    +
    +#ifndef CONFIG_USBDEV_SETUP_MAXDATASIZE
    +#  define CONFIG_USBDEV_SETUP_MAXDATASIZE CONFIG_USBDEV_EP0_MAXSIZE
    +#endif
    +
    +#ifndef CONFIG_USB_PRI
    +#  define CONFIG_USB_PRI NVIC_SYSH_PRIORITY_DEFAULT
    +#endif
    +
    +/* Extremely detailed register debug that you would normally never want
    + * enabled.
    + */
    +
    +#ifndef CONFIG_DEBUG_USB_INFO
    +#  undef CONFIG_STM32F0_USBDEV_REGDEBUG
    +#endif
    +
    +/* Initial interrupt mask: Reset + Suspend + Correct Transfer */
    +
    +#define STM32F0_CNTR_SETUP     (USB_CNTR_RESETM|USB_CNTR_SUSPM|USB_CNTR_CTRM)
    +
    +/* Endpoint identifiers. The STM32 supports up to 16 mono-directional or 8
    + * bidirectional endpoints.  However, when you take into account PMA buffer
    + * usage (see below) and the fact that EP0 is bidirectional, then there is
    + * a functional limitation of EP0 + 5 mono-directional endpoints = 6.  We'll
    + * define STM32F0_NENDPOINTS to be 8, however, because that is how many
    + * endpoint register sets there are.
    + */
    +
    +#define STM32F0_NENDPOINTS      (8)
    +#define EP0                   (0)
    +#define EP1                   (1)
    +#define EP2                   (2)
    +#define EP3                   (3)
    +#define EP4                   (4)
    +#define EP5                   (5)
    +#define EP6                   (6)
    +#define EP7                   (7)
    +
    +#define STM32F0_ENDP_BIT(ep)    (1 << (ep))
    +#define STM32F0_ENDP_ALLSET     0xff
    +
    +/* Packet sizes.  We us a fixed 64 max packet size for all endpoint types */
    +
    +#define STM32F0_MAXPACKET_SHIFT (6)
    +#define STM32F0_MAXPACKET_SIZE  (1 << (STM32F0_MAXPACKET_SHIFT))
    +#define STM32F0_MAXPACKET_MASK  (STM32F0_MAXPACKET_SIZE-1)
    +
    +#define STM32F0_EP0MAXPACKET    STM32F0_MAXPACKET_SIZE
    +
    +/* Buffer descriptor table.  We assume that USB has exclusive use of CAN/USB
    + * memory.  The buffer table is positioned at the beginning of the 512-byte
    + * CAN/USB memory.  We will use the first STM32F0_NENDPOINTS*4 words for the buffer
    + * table.  That is exactly 64 bytes, leaving 7*64 bytes for endpoint buffers.
    + */
    +
    +#define STM32F0_BTABLE_ADDRESS  (0x00)   /* Start at the beginning of USB/CAN RAM */
    +#define STM32F0_DESC_SIZE       (8)      /* Each descriptor is 4*2=8 bytes in size */
    +#define STM32F0_BTABLE_SIZE     (STM32F0_NENDPOINTS*STM32F0_DESC_SIZE)
    +
    +/* Buffer layout.  Assume that all buffers are 64-bytes (maxpacketsize), then
    + * we have space for only 7 buffers; endpoint 0 will require two buffers, leaving
    + * 5 for other endpoints.
    + */
    +
    +#define STM32F0_BUFFER_START    STM32F0_BTABLE_SIZE
    +#define STM32F0_EP0_RXADDR      STM32F0_BUFFER_START
    +#define STM32F0_EP0_TXADDR      (STM32F0_EP0_RXADDR+STM32F0_EP0MAXPACKET)
    +
    +#define STM32F0_BUFFER_EP0      0x03
    +#define STM32F0_NBUFFERS        7
    +#define STM32F0_BUFFER_BIT(bn)  (1 << (bn))
    +#define STM32F0_BUFFER_ALLSET   0x7f
    +#define STM32F0_BUFNO2BUF(bn)   (STM32F0_BUFFER_START+((bn)<head == NULL)
    +#define stm32f0_rqpeek(ep)      ((ep)->head)
    +
    +/* USB trace ****************************************************************/
    +/* Trace error codes */
    +
    +#define STM32F0_TRACEERR_ALLOCFAIL            0x0001
    +#define STM32F0_TRACEERR_BADCLEARFEATURE      0x0002
    +#define STM32F0_TRACEERR_BADDEVGETSTATUS      0x0003
    +#define STM32F0_TRACEERR_BADEPGETSTATUS       0x0004
    +#define STM32F0_TRACEERR_BADEPNO              0x0005
    +#define STM32F0_TRACEERR_BADEPTYPE            0x0006
    +#define STM32F0_TRACEERR_BADGETCONFIG         0x0007
    +#define STM32F0_TRACEERR_BADGETSETDESC        0x0008
    +#define STM32F0_TRACEERR_BADGETSTATUS         0x0009
    +#define STM32F0_TRACEERR_BADSETADDRESS        0x000a
    +#define STM32F0_TRACEERR_BADSETCONFIG         0x000b
    +#define STM32F0_TRACEERR_BADSETFEATURE        0x000c
    +#define STM32F0_TRACEERR_BINDFAILED           0x000d
    +#define STM32F0_TRACEERR_DISPATCHSTALL        0x000e
    +#define STM32F0_TRACEERR_DRIVER               0x000f
    +#define STM32F0_TRACEERR_DRIVERREGISTERED     0x0010
    +#define STM32F0_TRACEERR_EP0BADCTR            0x0011
    +#define STM32F0_TRACEERR_EP0SETUPSTALLED      0x0012
    +#define STM32F0_TRACEERR_EPBUFFER             0x0013
    +#define STM32F0_TRACEERR_EPDISABLED           0x0014
    +#define STM32F0_TRACEERR_EPOUTNULLPACKET      0x0015
    +#define STM32F0_TRACEERR_EPRESERVE            0x0016
    +#define STM32F0_TRACEERR_INVALIDCTRLREQ       0x0017
    +#define STM32F0_TRACEERR_INVALIDPARMS         0x0018
    +#define STM32F0_TRACEERR_IRQREGISTRATION      0x0019
    +#define STM32F0_TRACEERR_NOTCONFIGURED        0x001a
    +#define STM32F0_TRACEERR_REQABORTED           0x001b
    +
    +/* Trace interrupt codes */
    +
    +#define STM32F0_TRACEINTID_CLEARFEATURE       0x0001
    +#define STM32F0_TRACEINTID_DEVGETSTATUS       0x0002
    +#define STM32F0_TRACEINTID_DISPATCH           0x0003
    +#define STM32F0_TRACEINTID_EP0IN              0x0004
    +#define STM32F0_TRACEINTID_EP0INDONE          0x0005
    +#define STM32F0_TRACEINTID_EP0OUTDONE         0x0006
    +#define STM32F0_TRACEINTID_EP0SETUPDONE       0x0007
    +#define STM32F0_TRACEINTID_EP0SETUPSETADDRESS 0x0008
    +#define STM32F0_TRACEINTID_EPGETSTATUS        0x0009
    +#define STM32F0_TRACEINTID_EPINDONE           0x000a
    +#define STM32F0_TRACEINTID_EPINQEMPTY         0x000b
    +#define STM32F0_TRACEINTID_EPOUTDONE          0x000c
    +#define STM32F0_TRACEINTID_EPOUTPENDING       0x000d
    +#define STM32F0_TRACEINTID_EPOUTQEMPTY        0x000e
    +#define STM32F0_TRACEINTID_ESOF               0x000f
    +#define STM32F0_TRACEINTID_GETCONFIG          0x0010
    +#define STM32F0_TRACEINTID_GETSETDESC         0x0011
    +#define STM32F0_TRACEINTID_GETSETIF           0x0012
    +#define STM32F0_TRACEINTID_GETSTATUS          0x0013
    +#define STM32F0_TRACEINTID_INTERRUPT          0x0014
    +#define STM32F0_TRACEINTID_IFGETSTATUS        0x0015
    +#define STM32F0_TRACEINTID_LPCTR              0x0016
    +#define STM32F0_TRACEINTID_NOSTDREQ           0x0017
    +#define STM32F0_TRACEINTID_RESET              0x0018
    +#define STM32F0_TRACEINTID_SETCONFIG          0x0019
    +#define STM32F0_TRACEINTID_SETFEATURE         0x001a
    +#define STM32F0_TRACEINTID_SUSP               0x001b
    +#define STM32F0_TRACEINTID_SYNCHFRAME         0x001c
    +#define STM32F0_TRACEINTID_WKUP               0x001d
    +#define STM32F0_TRACEINTID_EP0SETUPOUT        0x001e
    +#define STM32F0_TRACEINTID_EP0SETUPOUTDATA    0x001f
    +
    +/* Ever-present MIN and MAX macros */
    +
    +#ifndef MIN
    +#  define MIN(a,b) (a < b ? a : b)
    +#endif
    +
    +#ifndef MAX
    +#  define MAX(a,b) (a > b ? a : b)
    +#endif
    +
    +/* Byte ordering in host-based values */
    +
    +#ifdef CONFIG_ENDIAN_BIG
    +#  define LSB 1
    +#  define MSB 0
    +#else
    +#  define LSB 0
    +#  define MSB 1
    +#endif
    +
    +/****************************************************************************
    + * Private Type Definitions
    + ****************************************************************************/
    +
    +/* The various states of a control pipe */
    +
    +enum stm32f0_ep0state_e
    +{
    +  EP0STATE_IDLE = 0,        /* No request in progress */
    +  EP0STATE_SETUP_OUT,       /* Set up recived with data for device OUT in progress */
    +  EP0STATE_SETUP_READY,     /* Set up was recived prior and is in ctrl,
    +                             * now the data has arrived */
    +  EP0STATE_WRREQUEST,       /* Write request in progress */
    +  EP0STATE_RDREQUEST,       /* Read request in progress */
    +  EP0STATE_STALLED          /* We are stalled */
    +};
    +
    +/* Resume states */
    +
    +enum stm32f0_rsmstate_e
    +{
    +  RSMSTATE_IDLE = 0,        /* Device is either fully suspended or running */
    +  RSMSTATE_STARTED,         /* Resume sequence has been started */
    +  RSMSTATE_WAITING          /* Waiting (on ESOFs) for end of sequence */
    +};
    +
    +union wb_u
    +{
    +  uint16_t w;
    +  uint8_t  b[2];
    +};
    +
    +/* A container for a request so that the request make be retained in a list */
    +
    +struct stm32f0_req_s
    +{
    +  struct usbdev_req_s    req;           /* Standard USB request */
    +  struct stm32f0_req_s    *flink;         /* Supports a singly linked list */
    +};
    +
    +/* This is the internal representation of an endpoint */
    +
    +struct stm32f0_ep_s
    +{
    +  /* Common endpoint fields.  This must be the first thing defined in the
    +   * structure so that it is possible to simply cast from struct usbdev_ep_s
    +   * to struct stm32f0_ep_s.
    +   */
    +
    +  struct usbdev_ep_s     ep;            /* Standard endpoint structure */
    +
    +  /* STR71X-specific fields */
    +
    +  struct stm32f0_usbdev_s *dev;           /* Reference to private driver data */
    +  struct stm32f0_req_s    *head;          /* Request list for this endpoint */
    +  struct stm32f0_req_s    *tail;
    +  uint8_t                bufno;         /* Allocated buffer number */
    +  uint8_t                stalled:1;     /* true: Endpoint is stalled */
    +  uint8_t                halted:1;      /* true: Endpoint feature halted */
    +  uint8_t                txbusy:1;      /* true: TX endpoint FIFO full */
    +  uint8_t                txnullpkt:1;   /* Null packet needed at end of transfer */
    +};
    +
    +struct stm32f0_usbdev_s
    +{
    +  /* Common device fields.  This must be the first thing defined in the
    +   * structure so that it is possible to simply cast from struct usbdev_s
    +   * to structstm32f0_usbdev_s.
    +   */
    +
    +  struct usbdev_s usbdev;
    +
    +  /* The bound device class driver */
    +
    +  struct usbdevclass_driver_s *driver;
    +
    +  /* STM32-specific fields */
    +
    +  uint8_t                ep0state;      /* State of EP0 (see enum stm32f0_ep0state_e) */
    +  uint8_t                rsmstate;      /* Resume state (see enum stm32f0_rsmstate_e) */
    +  uint8_t                nesofs;        /* ESOF counter (for resume support) */
    +  uint8_t                rxpending:1;   /* 1: OUT data in PMA, but no read requests */
    +  uint8_t                selfpowered:1; /* 1: Device is self powered */
    +  uint8_t                epavail;       /* Bitset of available endpoints */
    +  uint8_t                bufavail;      /* Bitset of available buffers */
    +  uint16_t               rxstatus;      /* Saved during interrupt processing */
    +  uint16_t               txstatus;      /* "   " "    " "       " "        " */
    +  uint16_t               imask;         /* Current interrupt mask */
    +
    +  /* E0 SETUP data buffering.
    +   *
    +   * ctrl
    +   *   The 8-byte SETUP request is received on the EP0 OUT endpoint and is
    +   *   saved.
    +   *
    +   * ep0data
    +   *   For OUT SETUP requests, the SETUP data phase must also complete before
    +   *   the SETUP command can be processed.  The ep0 packet receipt logic
    +   *   stm32f0_ep0_rdrequest will save the accompanying EP0 OUT data in
    +   *   ep0data[] before the SETUP command is re-processed.
    +   *
    +   * ep0datlen
    +   *   Lenght of OUT DATA received in ep0data[]
    +   */
    +
    +  struct usb_ctrlreq_s   ctrl;          /* Last EP0 request */
    +
    +  uint8_t                ep0data[CONFIG_USBDEV_SETUP_MAXDATASIZE];
    +  uint16_t               ep0datlen;
    +
    +  /* The endpoint list */
    +
    +  struct stm32f0_ep_s      eplist[STM32F0_NENDPOINTS];
    +};
    +
    +/****************************************************************************
    + * Private Function Prototypes
    + ****************************************************************************/
    +
    +/* Register operations ******************************************************/
    +
    +#ifdef CONFIG_STM32F0_USBDEV_REGDEBUG
    +static uint16_t stm32f0_getreg(uint32_t addr);
    +static void stm32f0_putreg(uint16_t val, uint32_t addr);
    +static void stm32f0_dumpep(int epno);
    +#else
    +# define stm32f0_getreg(addr)      getreg16(addr)
    +# define stm32f0_putreg(val,addr)  putreg16(val,addr)
    +# define stm32f0_dumpep(epno)
    +#endif
    +
    +/* Low-Level Helpers ********************************************************/
    +
    +static inline void
    +              stm32f0_seteptxcount(uint8_t epno, uint16_t count);
    +static inline void
    +              stm32f0_seteptxaddr(uint8_t epno, uint16_t addr);
    +static inline uint16_t
    +              stm32f0_geteptxaddr(uint8_t epno);
    +static void   stm32f0_seteprxcount(uint8_t epno, uint16_t count);
    +static inline uint16_t
    +              stm32f0_geteprxcount(uint8_t epno);
    +static inline void
    +              stm32f0_seteprxaddr(uint8_t epno, uint16_t addr);
    +static inline uint16_t
    +              stm32f0_geteprxaddr(uint8_t epno);
    +static inline void
    +              stm32f0_setepaddress(uint8_t epno, uint16_t addr);
    +static inline void
    +              stm32f0_seteptype(uint8_t epno, uint16_t type);
    +static inline void
    +              stm32f0_seteptxaddr(uint8_t epno, uint16_t addr);
    +static inline void
    +              stm32f0_setstatusout(uint8_t epno);
    +static inline void
    +              stm32f0_clrstatusout(uint8_t epno);
    +static void   stm32f0_clrrxdtog(uint8_t epno);
    +static void   stm32f0_clrtxdtog(uint8_t epno);
    +static void   stm32f0_clrepctrrx(uint8_t epno);
    +static void   stm32f0_clrepctrtx(uint8_t epno);
    +static void   stm32f0_seteptxstatus(uint8_t epno, uint16_t state);
    +static void   stm32f0_seteprxstatus(uint8_t epno, uint16_t state);
    +static inline uint16_t
    +              stm32f0_geteptxstatus(uint8_t epno);
    +static inline uint16_t
    +              stm32f0_geteprxstatus(uint8_t epno);
    +static bool   stm32f0_eptxstalled(uint8_t epno);
    +static bool   stm32f0_eprxstalled(uint8_t epno);
    +static void   stm32f0_setimask(struct stm32f0_usbdev_s *priv, uint16_t setbits,
    +                uint16_t clrbits);
    +
    +/* Suspend/Resume Helpers ***************************************************/
    +
    +static void   stm32f0_suspend(struct stm32f0_usbdev_s *priv);
    +static void   stm32f0_initresume(struct stm32f0_usbdev_s *priv);
    +static void   stm32f0_esofpoll(struct stm32f0_usbdev_s *priv) ;
    +
    +/* Request Helpers **********************************************************/
    +
    +static void   stm32f0_copytopma(const uint8_t *buffer, uint16_t pma,
    +                uint16_t nbytes);
    +static inline void
    +              stm32f0_copyfrompma(uint8_t *buffer, uint16_t pma, uint16_t nbytes);
    +static struct stm32f0_req_s *
    +              stm32f0_rqdequeue(struct stm32f0_ep_s *privep);
    +static void   stm32f0_rqenqueue(struct stm32f0_ep_s *privep,
    +                struct stm32f0_req_s *req);
    +static inline void
    +              stm32f0_abortrequest(struct stm32f0_ep_s *privep,
    +                struct stm32f0_req_s *privreq, int16_t result);
    +static void   stm32f0_reqcomplete(struct stm32f0_ep_s *privep, int16_t result);
    +static void   stm32f0_epwrite(struct stm32f0_usbdev_s *buf,
    +                struct stm32f0_ep_s *privep, const uint8_t *data, uint32_t nbytes);
    +static int    stm32f0_wrrequest(struct stm32f0_usbdev_s *priv,
    +                struct stm32f0_ep_s *privep);
    +inline static int
    +              stm32f0_wrrequest_ep0(struct stm32f0_usbdev_s *priv,
    +                struct stm32f0_ep_s *privep);
    +static inline int
    +              stm32f0_ep0_rdrequest(struct stm32f0_usbdev_s *priv);
    +static int    stm32f0_rdrequest(struct stm32f0_usbdev_s *priv,
    +                struct stm32f0_ep_s *privep);
    +static void   stm32f0_cancelrequests(struct stm32f0_ep_s *privep);
    +
    +/* Interrupt level processing ***********************************************/
    +
    +static void   stm32f0_dispatchrequest(struct stm32f0_usbdev_s *priv);
    +static void   stm32f0_epdone(struct stm32f0_usbdev_s *priv, uint8_t epno);
    +static void   stm32f0_setdevaddr(struct stm32f0_usbdev_s *priv, uint8_t value);
    +static void   stm32f0_ep0setup(struct stm32f0_usbdev_s *priv);
    +static void   stm32f0_ep0out(struct stm32f0_usbdev_s *priv);
    +static void   stm32f0_ep0in(struct stm32f0_usbdev_s *priv);
    +static inline void
    +              stm32f0_ep0done(struct stm32f0_usbdev_s *priv, uint16_t istr);
    +static void   stm32f0_lptransfer(struct stm32f0_usbdev_s *priv);
    +static int    stm32f0_usb_interrupt(int irq, void *context, FAR void *arg);
    +
    +/* Endpoint helpers *********************************************************/
    +
    +static inline struct stm32f0_ep_s *
    +              stm32f0_epreserve(struct stm32f0_usbdev_s *priv, uint8_t epset);
    +static inline void
    +              stm32f0_epunreserve(struct stm32f0_usbdev_s *priv,
    +                struct stm32f0_ep_s *privep);
    +static inline bool
    +              stm32f0_epreserved(struct stm32f0_usbdev_s *priv, int epno);
    +static int    stm32f0_epallocpma(struct stm32f0_usbdev_s *priv);
    +static inline void
    +              stm32f0_epfreepma(struct stm32f0_usbdev_s *priv,
    +                struct stm32f0_ep_s *privep);
    +
    +/* Endpoint operations ******************************************************/
    +
    +static int    stm32f0_epconfigure(struct usbdev_ep_s *ep,
    +                const struct usb_epdesc_s *desc, bool last);
    +static int    stm32f0_epdisable(struct usbdev_ep_s *ep);
    +static struct usbdev_req_s *
    +              stm32f0_epallocreq(struct usbdev_ep_s *ep);
    +static void   stm32f0_epfreereq(struct usbdev_ep_s *ep,
    +                struct usbdev_req_s *);
    +static int    stm32f0_epsubmit(struct usbdev_ep_s *ep,
    +                struct usbdev_req_s *req);
    +static int    stm32f0_epcancel(struct usbdev_ep_s *ep,
    +                struct usbdev_req_s *req);
    +static int    stm32f0_epstall(struct usbdev_ep_s *ep, bool resume);
    +
    +/* USB device controller operations *****************************************/
    +
    +static struct usbdev_ep_s *
    +              stm32f0_allocep(struct usbdev_s *dev, uint8_t epno, bool in,
    +                uint8_t eptype);
    +static void   stm32f0_freeep(struct usbdev_s *dev, struct usbdev_ep_s *ep);
    +static int    stm32f0_getframe(struct usbdev_s *dev);
    +static int    stm32f0_wakeup(struct usbdev_s *dev);
    +static int    stm32f0_selfpowered(struct usbdev_s *dev, bool selfpowered);
    +
    +/* Initialization/Reset *****************************************************/
    +
    +static void   stm32f0_reset(struct stm32f0_usbdev_s *priv);
    +static void   stm32f0_hwreset(struct stm32f0_usbdev_s *priv);
    +static void   stm32f0_hwsetup(struct stm32f0_usbdev_s *priv);
    +static void   stm32f0_hwshutdown(struct stm32f0_usbdev_s *priv);
    +
    +/****************************************************************************
    + * Private Data
    + ****************************************************************************/
    +
    +/* Since there is only a single USB interface, all status information can be
    + * be simply retained in a single global instance.
    + */
    +
    +static struct stm32f0_usbdev_s g_usbdev;
    +
    +static const struct usbdev_epops_s g_epops =
    +{
    +  .configure   = stm32f0_epconfigure,
    +  .disable     = stm32f0_epdisable,
    +  .allocreq    = stm32f0_epallocreq,
    +  .freereq     = stm32f0_epfreereq,
    +  .submit      = stm32f0_epsubmit,
    +  .cancel      = stm32f0_epcancel,
    +  .stall       = stm32f0_epstall,
    +};
    +
    +static const struct usbdev_ops_s g_devops =
    +{
    +  .allocep     = stm32f0_allocep,
    +  .freeep      = stm32f0_freeep,
    +  .getframe    = stm32f0_getframe,
    +  .wakeup      = stm32f0_wakeup,
    +  .selfpowered = stm32f0_selfpowered,
    +  .pullup      = stm32f0_usbpullup,
    +};
    +
    +/****************************************************************************
    + * Public Data
    + ****************************************************************************/
    +
    +#ifdef CONFIG_USBDEV_TRACE_STRINGS
    +const struct trace_msg_t g_usb_trace_strings_intdecode[] =
    +{
    +  TRACE_STR(STM32F0_TRACEINTID_CLEARFEATURE       ),
    +  TRACE_STR(STM32F0_TRACEINTID_DEVGETSTATUS       ),
    +  TRACE_STR(STM32F0_TRACEINTID_DISPATCH           ),
    +  TRACE_STR(STM32F0_TRACEINTID_EP0IN              ),
    +  TRACE_STR(STM32F0_TRACEINTID_EP0INDONE          ),
    +  TRACE_STR(STM32F0_TRACEINTID_EP0OUTDONE         ),
    +  TRACE_STR(STM32F0_TRACEINTID_EP0SETUPDONE       ),
    +  TRACE_STR(STM32F0_TRACEINTID_EP0SETUPSETADDRESS ),
    +  TRACE_STR(STM32F0_TRACEINTID_EPGETSTATUS        ),
    +  TRACE_STR(STM32F0_TRACEINTID_EPINDONE           ),
    +  TRACE_STR(STM32F0_TRACEINTID_EPINQEMPTY         ),
    +  TRACE_STR(STM32F0_TRACEINTID_EPOUTDONE          ),
    +  TRACE_STR(STM32F0_TRACEINTID_EPOUTPENDING       ),
    +  TRACE_STR(STM32F0_TRACEINTID_EPOUTQEMPTY        ),
    +  TRACE_STR(STM32F0_TRACEINTID_ESOF               ),
    +  TRACE_STR(STM32F0_TRACEINTID_GETCONFIG          ),
    +  TRACE_STR(STM32F0_TRACEINTID_GETSETDESC         ),
    +  TRACE_STR(STM32F0_TRACEINTID_GETSETIF           ),
    +  TRACE_STR(STM32F0_TRACEINTID_GETSTATUS          ),
    +  TRACE_STR(STM32F0_TRACEINTID_INTERRUPT          ),
    +  TRACE_STR(STM32F0_TRACEINTID_IFGETSTATUS        ),
    +  TRACE_STR(STM32F0_TRACEINTID_LPCTR              ),
    +  TRACE_STR(STM32F0_TRACEINTID_NOSTDREQ           ),
    +  TRACE_STR(STM32F0_TRACEINTID_RESET              ),
    +  TRACE_STR(STM32F0_TRACEINTID_SETCONFIG          ),
    +  TRACE_STR(STM32F0_TRACEINTID_SETFEATURE         ),
    +  TRACE_STR(STM32F0_TRACEINTID_SUSP               ),
    +  TRACE_STR(STM32F0_TRACEINTID_SYNCHFRAME         ),
    +  TRACE_STR(STM32F0_TRACEINTID_WKUP               ),
    +  TRACE_STR(STM32F0_TRACEINTID_EP0SETUPOUT        ),
    +  TRACE_STR(STM32F0_TRACEINTID_EP0SETUPOUTDATA    ),
    +  TRACE_STR_END
    +};
    +#endif
    +
    +#ifdef CONFIG_USBDEV_TRACE_STRINGS
    +const struct trace_msg_t g_usb_trace_strings_deverror[] =
    +{
    +  TRACE_STR(STM32F0_TRACEERR_ALLOCFAIL            ),
    +  TRACE_STR(STM32F0_TRACEERR_BADCLEARFEATURE      ),
    +  TRACE_STR(STM32F0_TRACEERR_BADDEVGETSTATUS      ),
    +  TRACE_STR(STM32F0_TRACEERR_BADEPGETSTATUS       ),
    +  TRACE_STR(STM32F0_TRACEERR_BADEPNO              ),
    +  TRACE_STR(STM32F0_TRACEERR_BADEPTYPE            ),
    +  TRACE_STR(STM32F0_TRACEERR_BADGETCONFIG         ),
    +  TRACE_STR(STM32F0_TRACEERR_BADGETSETDESC        ),
    +  TRACE_STR(STM32F0_TRACEERR_BADGETSTATUS         ),
    +  TRACE_STR(STM32F0_TRACEERR_BADSETADDRESS        ),
    +  TRACE_STR(STM32F0_TRACEERR_BADSETCONFIG         ),
    +  TRACE_STR(STM32F0_TRACEERR_BADSETFEATURE        ),
    +  TRACE_STR(STM32F0_TRACEERR_BINDFAILED           ),
    +  TRACE_STR(STM32F0_TRACEERR_DISPATCHSTALL        ),
    +  TRACE_STR(STM32F0_TRACEERR_DRIVER               ),
    +  TRACE_STR(STM32F0_TRACEERR_DRIVERREGISTERED     ),
    +  TRACE_STR(STM32F0_TRACEERR_EP0BADCTR            ),
    +  TRACE_STR(STM32F0_TRACEERR_EP0SETUPSTALLED      ),
    +  TRACE_STR(STM32F0_TRACEERR_EPBUFFER             ),
    +  TRACE_STR(STM32F0_TRACEERR_EPDISABLED           ),
    +  TRACE_STR(STM32F0_TRACEERR_EPOUTNULLPACKET      ),
    +  TRACE_STR(STM32F0_TRACEERR_EPRESERVE            ),
    +  TRACE_STR(STM32F0_TRACEERR_INVALIDCTRLREQ       ),
    +  TRACE_STR(STM32F0_TRACEERR_INVALIDPARMS         ),
    +  TRACE_STR(STM32F0_TRACEERR_IRQREGISTRATION      ),
    +  TRACE_STR(STM32F0_TRACEERR_NOTCONFIGURED        ),
    +  TRACE_STR(STM32F0_TRACEERR_REQABORTED           ),
    +  TRACE_STR_END
    +};
    +#endif
    +
    +/****************************************************************************
    + * Private Private Functions
    + ****************************************************************************/
    +
    +/****************************************************************************
    + * Register Operations
    + ****************************************************************************/
    +
    +/****************************************************************************
    + * Name: stm32f0_getreg
    + ****************************************************************************/
    +
    +#ifdef CONFIG_STM32F0_USBDEV_REGDEBUG
    +static uint16_t stm32f0_getreg(uint32_t addr)
    +{
    +  static uint32_t prevaddr = 0;
    +  static uint16_t preval = 0;
    +  static uint32_t count = 0;
    +
    +  /* Read the value from the register */
    +
    +  uint16_t val = getreg16(addr);
    +
    +  /* Is this the same value that we read from the same register last time?
    +   * Are we polling the register?  If so, suppress some of the output.
    +   */
    +
    +  if (addr == prevaddr && val == preval)
    +    {
    +      if (count == 0xffffffff || ++count > 3)
    +        {
    +           if (count == 4)
    +             {
    +               uinfo("...\n");
    +             }
    +          return val;
    +        }
    +    }
    +
    +  /* No this is a new address or value */
    +
    +  else
    +    {
    +       /* Did we print "..." for the previous value? */
    +
    +       if (count > 3)
    +         {
    +           /* Yes.. then show how many times the value repeated */
    +
    +           uinfo("[repeats %d more times]\n", count-3);
    +         }
    +
    +       /* Save the new address, value, and count */
    +
    +       prevaddr = addr;
    +       preval   = val;
    +       count    = 1;
    +    }
    +
    +  /* Show the register value read */
    +
    +  uinfo("%08x->%04x\n", addr, val);
    +  return val;
    +}
    +#endif
    +
    +/****************************************************************************
    + * Name: stm32f0_putreg
    + ****************************************************************************/
    +
    +#ifdef CONFIG_STM32F0_USBDEV_REGDEBUG
    +static void stm32f0_putreg(uint16_t val, uint32_t addr)
    +{
    +  /* Show the register value being written */
    +
    +  uinfo("%08x<-%04x\n", addr, val);
    +
    +  /* Write the value */
    +
    +  putreg16(val, addr);
    +}
    +#endif
    +
    +/****************************************************************************
    + * Name: stm32f0_dumpep
    + ****************************************************************************/
    +
    +#ifdef CONFIG_STM32F0_USBDEV_REGDEBUG
    +static void stm32f0_dumpep(int epno)
    +{
    +  uint32_t addr;
    +
    +  /* Common registers */
    +
    +  uinfo("CNTR:   %04x\n", getreg16(STM32F0_USB_CNTR));
    +  uinfo("ISTR:   %04x\n", getreg16(STM32F0_USB_ISTR));
    +  uinfo("FNR:    %04x\n", getreg16(STM32F0_USB_FNR));
    +  uinfo("DADDR:  %04x\n", getreg16(STM32F0_USB_DADDR));
    +  uinfo("BTABLE: %04x\n", getreg16(STM32F0_USB_BTABLE));
    +
    +  /* Endpoint register */
    +
    +  addr = STM32F0_USB_EPR(epno);
    +  uinfo("EPR%d:   [%08x] %04x\n", epno, addr, getreg16(addr));
    +
    +  /* Endpoint descriptor */
    +
    +  addr = STM32F0_USB_BTABLE_ADDR(epno, 0);
    +  uinfo("DESC:   %08x\n", addr);
    +
    +  /* Endpoint buffer descriptor */
    +
    +  addr = STM32F0_USB_ADDR_TX(epno);
    +  uinfo("  TX ADDR:  [%08x] %04x\n",  addr, getreg16(addr));
    +
    +  addr = STM32F0_USB_COUNT_TX(epno);
    +  uinfo("     COUNT: [%08x] %04x\n",  addr, getreg16(addr));
    +
    +  addr = STM32F0_USB_ADDR_RX(epno);
    +  uinfo("  RX ADDR:  [%08x] %04x\n",  addr, getreg16(addr));
    +
    +  addr = STM32F0_USB_COUNT_RX(epno);
    +  uinfo("     COUNT: [%08x] %04x\n",  addr, getreg16(addr));
    +}
    +#endif
    +
    +/****************************************************************************
    + * Low-Level Helpers
    + ****************************************************************************/
    +/****************************************************************************
    + * Name: stm32f0_seteptxcount
    + ****************************************************************************/
    +
    +static inline void stm32f0_seteptxcount(uint8_t epno, uint16_t count)
    +{
    +  volatile uint32_t *epaddr = (uint32_t *)STM32F0_USB_COUNT_TX(epno);
    +  *epaddr = count;
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_seteptxaddr
    + ****************************************************************************/
    +
    +static inline void stm32f0_seteptxaddr(uint8_t epno, uint16_t addr)
    +{
    +  volatile uint32_t *txaddr = (uint32_t *)STM32F0_USB_ADDR_TX(epno);
    +  *txaddr = addr;
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_geteptxaddr
    + ****************************************************************************/
    +
    +static inline uint16_t stm32f0_geteptxaddr(uint8_t epno)
    +{
    +  volatile uint32_t *txaddr = (uint32_t *)STM32F0_USB_ADDR_TX(epno);
    +  return (uint16_t)*txaddr;
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_seteprxcount
    + ****************************************************************************/
    +
    +static void stm32f0_seteprxcount(uint8_t epno, uint16_t count)
    +{
    +  volatile uint32_t *epaddr = (uint32_t *)STM32F0_USB_COUNT_RX(epno);
    +  uint32_t rxcount = 0;
    +  uint16_t nblocks;
    +
    +  /* The upper bits of the RX COUNT value contain the size of allocated
    +   * RX buffer.  This is based on a block size of 2 or 32:
    +   *
    +   * USB_COUNT_RX_BL_SIZE not set:
    +   *   nblocks is in units of 2 bytes.
    +   *     00000 - not allowed
    +   *     00001 - 2 bytes
    +   *     ....
    +   *     11111 - 62 bytes
    +   *
    +   * USB_COUNT_RX_BL_SIZE set:
    +   *     00000 - 32 bytes
    +   *     00001 - 64 bytes
    +   *     ...
    +   *     01111 - 512 bytes
    +   *     1xxxx - Not allowed
    +   */
    +
    +  if (count > 62)
    +    {
    +      /* Blocks of 32 (with 0 meaning one block of 32) */
    +
    +      nblocks = (count >> 5) - 1 ;
    +      DEBUGASSERT(nblocks <= 0x0f);
    +      rxcount = (uint32_t)((nblocks << USB_COUNT_RX_NUM_BLOCK_SHIFT) | USB_COUNT_RX_BL_SIZE);
    +    }
    +  else if (count > 0)
    +    {
    +      /* Blocks of 2 (with 1 meaning one block of 2) */
    +
    +      nblocks = (count + 1) >> 1;
    +      DEBUGASSERT(nblocks > 0 && nblocks < 0x1f);
    +      rxcount = (uint32_t)(nblocks << USB_COUNT_RX_NUM_BLOCK_SHIFT);
    +    }
    +  *epaddr = rxcount;
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_geteprxcount
    + ****************************************************************************/
    +
    +static inline uint16_t stm32f0_geteprxcount(uint8_t epno)
    +{
    +  volatile uint32_t *epaddr = (uint32_t *)STM32F0_USB_COUNT_RX(epno);
    +  return (*epaddr) & USB_COUNT_RX_MASK;
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_seteprxaddr
    + ****************************************************************************/
    +
    +static inline void stm32f0_seteprxaddr(uint8_t epno, uint16_t addr)
    +{
    +  volatile uint32_t *rxaddr = (uint32_t *)STM32F0_USB_ADDR_RX(epno);
    +  *rxaddr = addr;
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_seteprxaddr
    + ****************************************************************************/
    +
    +static inline uint16_t stm32f0_geteprxaddr(uint8_t epno)
    +{
    +  volatile uint32_t *rxaddr = (uint32_t *)STM32F0_USB_ADDR_RX(epno);
    +  return (uint16_t)*rxaddr;
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_setepaddress
    + ****************************************************************************/
    +
    +static inline void stm32f0_setepaddress(uint8_t epno, uint16_t addr)
    +{
    +  uint32_t epaddr = STM32F0_USB_EPR(epno);
    +  uint16_t regval;
    +
    +  regval  = stm32f0_getreg(epaddr);
    +  regval &= EPR_NOTOG_MASK;
    +  regval &= ~USB_EPR_EA_MASK;
    +  regval |= (addr << USB_EPR_EA_SHIFT);
    +  stm32f0_putreg(regval, epaddr);
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_seteptype
    + ****************************************************************************/
    +
    +static inline void stm32f0_seteptype(uint8_t epno, uint16_t type)
    +{
    +  uint32_t epaddr = STM32F0_USB_EPR(epno);
    +  uint16_t regval;
    +
    +  regval  = stm32f0_getreg(epaddr);
    +  regval &= EPR_NOTOG_MASK;
    +  regval &= ~USB_EPR_EPTYPE_MASK;
    +  regval |= type;
    +  stm32f0_putreg(regval, epaddr);
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_setstatusout
    + ****************************************************************************/
    +
    +static inline void stm32f0_setstatusout(uint8_t epno)
    +{
    +  uint32_t epaddr = STM32F0_USB_EPR(epno);
    +  uint16_t regval;
    +
    +  /* For a BULK endpoint the EP_KIND bit is used to enabled double buffering;
    +   * for a CONTROL endpoint, it is set to indicate that a status OUT
    +   * transaction is expected.  The bit is not used with out endpoint types.
    +   */
    +
    +  regval  = stm32f0_getreg(epaddr);
    +  regval &= EPR_NOTOG_MASK;
    +  regval |= USB_EPR_EP_KIND;
    +  stm32f0_putreg(regval, epaddr);
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_clrstatusout
    + ****************************************************************************/
    +
    +static inline void stm32f0_clrstatusout(uint8_t epno)
    +{
    +  uint32_t epaddr = STM32F0_USB_EPR(epno);
    +  uint16_t regval;
    +
    +  /* For a BULK endpoint the EP_KIND bit is used to enabled double buffering;
    +   * for a CONTROL endpoint, it is set to indicate that a status OUT
    +   * transaction is expected.  The bit is not used with out endpoint types.
    +   */
    +
    +  regval  = stm32f0_getreg(epaddr);
    +  regval &= EPR_NOTOG_MASK;
    +  regval &= ~USB_EPR_EP_KIND;
    +  stm32f0_putreg(regval, epaddr);
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_clrrxdtog
    + ****************************************************************************/
    +
    +static void stm32f0_clrrxdtog(uint8_t epno)
    +{
    +  uint32_t epaddr = STM32F0_USB_EPR(epno);
    +  uint16_t regval;
    +
    +  regval = stm32f0_getreg(epaddr);
    +  if ((regval & USB_EPR_DTOG_RX) != 0)
    +    {
    +      regval &= EPR_NOTOG_MASK;
    +      regval |= USB_EPR_DTOG_RX;
    +      stm32f0_putreg(regval, epaddr);
    +    }
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_clrtxdtog
    + ****************************************************************************/
    +
    +static void stm32f0_clrtxdtog(uint8_t epno)
    +{
    +  uint32_t epaddr = STM32F0_USB_EPR(epno);
    +  uint16_t regval;
    +
    +  regval = stm32f0_getreg(epaddr);
    +  if ((regval & USB_EPR_DTOG_TX) != 0)
    +    {
    +      regval &= EPR_NOTOG_MASK;
    +      regval |= USB_EPR_DTOG_TX;
    +      stm32f0_putreg(regval, epaddr);
    +    }
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_clrepctrrx
    + ****************************************************************************/
    +
    +static void stm32f0_clrepctrrx(uint8_t epno)
    +{
    +  uint32_t epaddr = STM32F0_USB_EPR(epno);
    +  uint16_t regval;
    +
    +  regval  = stm32f0_getreg(epaddr);
    +  regval &= EPR_NOTOG_MASK;
    +  regval &= ~USB_EPR_CTR_RX;
    +  stm32f0_putreg(regval, epaddr);
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_clrepctrtx
    + ****************************************************************************/
    +
    +static void stm32f0_clrepctrtx(uint8_t epno)
    +{
    +  uint32_t epaddr = STM32F0_USB_EPR(epno);
    +  uint16_t regval;
    +
    +  regval  = stm32f0_getreg(epaddr);
    +  regval &= EPR_NOTOG_MASK;
    +  regval &= ~USB_EPR_CTR_TX;
    +  stm32f0_putreg(regval, epaddr);
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_geteptxstatus
    + ****************************************************************************/
    +
    +static inline uint16_t stm32f0_geteptxstatus(uint8_t epno)
    +{
    +  return (uint16_t)(stm32f0_getreg(STM32F0_USB_EPR(epno)) & USB_EPR_STATTX_MASK);
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_geteprxstatus
    + ****************************************************************************/
    +
    +static inline uint16_t stm32f0_geteprxstatus(uint8_t epno)
    +{
    +  return (stm32f0_getreg(STM32F0_USB_EPR(epno)) & USB_EPR_STATRX_MASK);
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_seteptxstatus
    + ****************************************************************************/
    +
    +static void stm32f0_seteptxstatus(uint8_t epno, uint16_t state)
    +{
    +  uint32_t epaddr = STM32F0_USB_EPR(epno);
    +  uint16_t regval;
    +
    +  /* The bits in the STAT_TX field can be toggled by software to set their
    +   * value. When set to 0, the value remains unchanged; when set to one,
    +   * value toggles.
    +   */
    +
    +  regval = stm32f0_getreg(epaddr);
    +
    +  /* The exclusive OR will set STAT_TX bits to 1 if there value is different
    +   * from the bits requested in 'state'
    +   */
    +
    +  regval ^= state;
    +  regval &= EPR_TXDTOG_MASK;
    +  stm32f0_putreg(regval, epaddr);
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_seteprxstatus
    + ****************************************************************************/
    +
    +static void stm32f0_seteprxstatus(uint8_t epno, uint16_t state)
    +{
    +  uint32_t epaddr = STM32F0_USB_EPR(epno);
    +  uint16_t regval;
    +
    +  /* The bits in the STAT_RX field can be toggled by software to set their
    +   * value. When set to 0, the value remains unchanged; when set to one,
    +   * value toggles.
    +   */
    +
    +  regval = stm32f0_getreg(epaddr);
    +
    +  /* The exclusive OR will set STAT_RX bits to 1 if there value is different
    +   * from the bits requested in 'state'
    +   */
    +
    +  regval ^= state;
    +  regval &= EPR_RXDTOG_MASK;
    +  stm32f0_putreg(regval, epaddr);
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_eptxstalled
    + ****************************************************************************/
    +
    +static inline bool stm32f0_eptxstalled(uint8_t epno)
    +{
    +  return (stm32f0_geteptxstatus(epno) == USB_EPR_STATTX_STALL);
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_eprxstalled
    + ****************************************************************************/
    +
    +static inline bool stm32f0_eprxstalled(uint8_t epno)
    +{
    +  return (stm32f0_geteprxstatus(epno) == USB_EPR_STATRX_STALL);
    +}
    +
    +/****************************************************************************
    + * Request Helpers
    + ****************************************************************************/
    +/****************************************************************************
    + * Name: stm32f0_copytopma
    + ****************************************************************************/
    +
    +static void stm32f0_copytopma(const uint8_t *buffer, uint16_t pma, uint16_t nbytes)
    +{
    +  uint16_t *dest;
    +  uint16_t  ms;
    +  uint16_t  ls;
    +  int     nwords = (nbytes + 1) >> 1;
    +  int     i;
    +
    +  /* Copy loop.  Source=user buffer, Dest=packet memory */
    +
    +  dest = (uint16_t *)(STM32F0_USBRAM_BASE + ((uint32_t)pma << 1));
    +  for (i = nwords; i != 0; i--)
    +    {
    +      /* Read two bytes and pack into on 16-bit word */
    +
    +      ls = (uint16_t)(*buffer++);
    +      ms = (uint16_t)(*buffer++);
    +      *dest = ms << 8 | ls;
    +
    +      /* Source address increments by 2*sizeof(uint8_t) = 2; Dest address
    +       * increments by 2*sizeof(uint16_t) = 4.
    +       */
    +
    +      dest += 2;
    +    }
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_copyfrompma
    + ****************************************************************************/
    +
    +static inline void
    +stm32f0_copyfrompma(uint8_t *buffer, uint16_t pma, uint16_t nbytes)
    +{
    +  uint32_t *src;
    +  int     nwords = (nbytes + 1) >> 1;
    +  int     i;
    +
    +  /* Copy loop.  Source=packet memory, Dest=user buffer */
    +
    +  src = (uint32_t *)(STM32F0_USBRAM_BASE + ((uint32_t)pma << 1));
    +  for (i = nwords; i != 0; i--)
    +    {
    +      /* Copy 16-bits from packet memory to user buffer. */
    +
    +      *(uint16_t *)buffer = *src++;
    +
    +      /* Source address increments by 1*sizeof(uint32_t) = 4; Dest address
    +       * increments by 2*sizeof(uint8_t) = 2.
    +       */
    +
    +      buffer += 2;
    +    }
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_rqdequeue
    + ****************************************************************************/
    +
    +static struct stm32f0_req_s *stm32f0_rqdequeue(struct stm32f0_ep_s *privep)
    +{
    +  struct stm32f0_req_s *ret = privep->head;
    +
    +  if (ret)
    +    {
    +      privep->head = ret->flink;
    +      if (!privep->head)
    +        {
    +          privep->tail = NULL;
    +        }
    +
    +      ret->flink = NULL;
    +    }
    +
    +  return ret;
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_rqenqueue
    + ****************************************************************************/
    +
    +static void stm32f0_rqenqueue(struct stm32f0_ep_s *privep, struct stm32f0_req_s *req)
    +{
    +  req->flink = NULL;
    +  if (!privep->head)
    +    {
    +      privep->head = req;
    +      privep->tail = req;
    +    }
    +  else
    +    {
    +      privep->tail->flink = req;
    +      privep->tail        = req;
    +    }
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_abortrequest
    + ****************************************************************************/
    +
    +static inline void
    +stm32f0_abortrequest(struct stm32f0_ep_s *privep, struct stm32f0_req_s *privreq, int16_t result)
    +{
    +  usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_REQABORTED), (uint16_t)USB_EPNO(privep->ep.eplog));
    +
    +  /* Save the result in the request structure */
    +
    +  privreq->req.result = result;
    +
    +  /* Callback to the request completion handler */
    +
    +  privreq->req.callback(&privep->ep, &privreq->req);
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_reqcomplete
    + ****************************************************************************/
    +
    +static void stm32f0_reqcomplete(struct stm32f0_ep_s *privep, int16_t result)
    +{
    +  struct stm32f0_req_s *privreq;
    +  irqstate_t flags;
    +
    +  /* Remove the completed request at the head of the endpoint request list */
    +
    +  flags = enter_critical_section();
    +  privreq = stm32f0_rqdequeue(privep);
    +  leave_critical_section(flags);
    +
    +  if (privreq)
    +    {
    +      /* If endpoint 0, temporarily reflect the state of protocol stalled
    +       * in the callback.
    +       */
    +
    +      bool stalled = privep->stalled;
    +      if (USB_EPNO(privep->ep.eplog) == EP0)
    +        {
    +          privep->stalled = (privep->dev->ep0state == EP0STATE_STALLED);
    +        }
    +
    +      /* Save the result in the request structure */
    +
    +      privreq->req.result = result;
    +
    +      /* Callback to the request completion handler */
    +
    +      privreq->flink = NULL;
    +      privreq->req.callback(&privep->ep, &privreq->req);
    +
    +      /* Restore the stalled indication */
    +
    +      privep->stalled = stalled;
    +    }
    +}
    +
    +/****************************************************************************
    + * Name: tm32_epwrite
    + ****************************************************************************/
    +
    +static void stm32f0_epwrite(struct stm32f0_usbdev_s *priv,
    +                          struct stm32f0_ep_s *privep,
    +                          const uint8_t *buf, uint32_t nbytes)
    +{
    +  uint8_t epno = USB_EPNO(privep->ep.eplog);
    +  usbtrace(TRACE_WRITE(epno), nbytes);
    +
    +  /* Check for a zero-length packet */
    +
    +  if (nbytes > 0)
    +    {
    +      /* Copy the data from the user buffer into packet memory for this
    +       * endpoint
    +       */
    +
    +      stm32f0_copytopma(buf, stm32f0_geteptxaddr(epno), nbytes);
    +    }
    +
    +  /* Send the packet (might be a null packet nbytes == 0) */
    +
    +  stm32f0_seteptxcount(epno, nbytes);
    +  priv->txstatus = USB_EPR_STATTX_VALID;
    +
    +  /* Indicate that there is data in the TX packet memory.  This will be cleared
    +   * when the next data out interrupt is received.
    +   */
    +
    +  privep->txbusy = true;
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_wrrequest_ep0
    + *
    + * Description:
    + *   Handle the ep0 state on writes.
    + *
    + ****************************************************************************/
    +
    +inline static int stm32f0_wrrequest_ep0(struct stm32f0_usbdev_s *priv,
    +                                      struct stm32f0_ep_s *privep)
    +{
    +  int ret;
    +  ret = stm32f0_wrrequest(priv, privep);
    +  priv->ep0state = ((ret == OK) ? EP0STATE_WRREQUEST : EP0STATE_IDLE);
    +  return ret;
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_wrrequest
    + ****************************************************************************/
    +
    +static int stm32f0_wrrequest(struct stm32f0_usbdev_s *priv, struct stm32f0_ep_s *privep)
    +{
    +  struct stm32f0_req_s *privreq;
    +  uint8_t *buf;
    +  uint8_t epno;
    +  int nbytes;
    +  int bytesleft;
    +
    +  /* We get here when an IN endpoint interrupt occurs.  So now we know that
    +   * there is no TX transfer in progress.
    +   */
    +
    +  privep->txbusy = false;
    +
    +  /* Check the request from the head of the endpoint request queue */
    +
    +  privreq = stm32f0_rqpeek(privep);
    +  if (!privreq)
    +    {
    +      /* There is no TX transfer in progress and no new pending TX
    +       * requests to send.
    +       */
    +
    +      usbtrace(TRACE_INTDECODE(STM32F0_TRACEINTID_EPINQEMPTY), 0);
    +      return -ENOENT;
    +    }
    +
    +  epno = USB_EPNO(privep->ep.eplog);
    +  uinfo("epno=%d req=%p: len=%d xfrd=%d nullpkt=%d\n",
    +        epno, privreq, privreq->req.len, privreq->req.xfrd, privep->txnullpkt);
    +  UNUSED(epno);
    +
    +  /* Get the number of bytes left to be sent in the packet */
    +
    +  bytesleft         = privreq->req.len - privreq->req.xfrd;
    +  nbytes            = bytesleft;
    +
    +#warning "REVISIT: If the EP supports double buffering, then we can do better"
    +
    +  /* Either (1) we are committed to sending the null packet (because txnullpkt == 1
    +   * && nbytes == 0), or (2) we have not yet send the last packet (nbytes > 0).
    +   * In either case, it is appropriate to clearn txnullpkt now.
    +   */
    +
    +  privep->txnullpkt = 0;
    +
    +  /* If we are not sending a NULL packet, then clip the size to maxpacket
    +   * and check if we need to send a following NULL packet.
    +   */
    +
    +  if (nbytes > 0)
    +    {
    +      /* Either send the maxpacketsize or all of the remaining data in
    +       * the request.
    +       */
    +
    +      if (nbytes >= privep->ep.maxpacket)
    +        {
    +          nbytes =  privep->ep.maxpacket;
    +
    +          /* Handle the case where this packet is exactly the
    +           * maxpacketsize.  Do we need to send a zero-length packet
    +           * in this case?
    +           */
    +
    +          if (bytesleft ==  privep->ep.maxpacket &&
    +             (privreq->req.flags & USBDEV_REQFLAGS_NULLPKT) != 0)
    +            {
    +              privep->txnullpkt = 1;
    +            }
    +        }
    +    }
    +
    +  /* Send the packet (might be a null packet nbytes == 0) */
    +
    +  buf = privreq->req.buf + privreq->req.xfrd;
    +  stm32f0_epwrite(priv, privep, buf, nbytes);
    +
    +  /* Update for the next data IN interrupt */
    +
    +  privreq->req.xfrd += nbytes;
    +  bytesleft          = privreq->req.len - privreq->req.xfrd;
    +
    +  /* If all of the bytes were sent (including any final null packet)
    +   * then we are finished with the request buffer).
    +   */
    +
    +  if (bytesleft == 0 && !privep->txnullpkt)
    +    {
    +      /* Return the write request to the class driver */
    +
    +      usbtrace(TRACE_COMPLETE(USB_EPNO(privep->ep.eplog)), privreq->req.xfrd);
    +      privep->txnullpkt = 0;
    +      stm32f0_reqcomplete(privep, OK);
    +    }
    +
    +  return OK;
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_ep0_rdrequest
    + *
    + * Description:
    + *   This function is called from the stm32f0_ep0out handler when the ep0state
    + *   is EP0STATE_SETUP_OUT and uppon new incoming data is available in the endpoint
    + *   0's buffer.  This function will simply copy the OUT data into ep0data.
    + *
    + ****************************************************************************/
    +
    +static inline int stm32f0_ep0_rdrequest(struct stm32f0_usbdev_s *priv)
    +{
    +  uint32_t src;
    +  int pmalen;
    +  int readlen;
    +
    +  /* Get the number of bytes to read from packet memory */
    +
    +  pmalen  = stm32f0_geteprxcount(EP0);
    +
    +  uinfo("EP0: pmalen=%d\n", pmalen);
    +  usbtrace(TRACE_READ(EP0), pmalen);
    +
    +  /* Read the data into our special buffer for SETUP data */
    +
    +  readlen = MIN(CONFIG_USBDEV_SETUP_MAXDATASIZE, pmalen);
    +  src     = stm32f0_geteprxaddr(EP0);
    +
    +  /* Receive the next packet */
    +
    +  stm32f0_copyfrompma(&priv->ep0data[0], src, readlen);
    +
    +  /* Now we can process the setup command */
    +
    +  priv->ep0state  = EP0STATE_SETUP_READY;
    +  priv->ep0datlen = readlen;
    +  usbtrace(TRACE_INTDECODE(STM32F0_TRACEINTID_EP0SETUPOUTDATA), readlen);
    +
    +  stm32f0_ep0setup(priv);
    +  priv->ep0datlen = 0; /* mark the date consumed */
    +
    +  return OK;
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_rdrequest
    + ****************************************************************************/
    +
    +static int stm32f0_rdrequest(struct stm32f0_usbdev_s *priv, struct stm32f0_ep_s *privep)
    +{
    +  struct stm32f0_req_s *privreq;
    +  uint32_t src;
    +  uint8_t *dest;
    +  uint8_t epno;
    +  int pmalen;
    +  int readlen;
    +
    +  /* Check the request from the head of the endpoint request queue */
    +
    +  epno    = USB_EPNO(privep->ep.eplog);
    +  privreq = stm32f0_rqpeek(privep);
    +  if (!privreq)
    +    {
    +      /* Incoming data available in PMA, but no packet to receive the data.
    +       * Mark that the RX data is pending and hope that a packet is returned
    +       * soon.
    +       */
    +
    +      usbtrace(TRACE_INTDECODE(STM32F0_TRACEINTID_EPOUTQEMPTY), epno);
    +      return -ENOENT;
    +    }
    +
    +  uinfo("EP%d: len=%d xfrd=%d\n", epno, privreq->req.len, privreq->req.xfrd);
    +
    +  /* Ignore any attempt to receive a zero length packet */
    +
    +  if (privreq->req.len == 0)
    +    {
    +      usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_EPOUTNULLPACKET), 0);
    +      stm32f0_reqcomplete(privep, OK);
    +      return OK;
    +    }
    +
    +  usbtrace(TRACE_READ(USB_EPNO(privep->ep.eplog)), privreq->req.xfrd);
    +
    +  /* Get the source and destination transfer addresses */
    +
    +  dest    = privreq->req.buf + privreq->req.xfrd;
    +  src     = stm32f0_geteprxaddr(epno);
    +
    +  /* Get the number of bytes to read from packet memory */
    +
    +  pmalen  = stm32f0_geteprxcount(epno);
    +  readlen = MIN(privreq->req.len, pmalen);
    +
    +  /* Receive the next packet */
    +
    +  stm32f0_copyfrompma(dest, src, readlen);
    +
    +  /* If the receive buffer is full or this is a partial packet,
    +   * then we are finished with the request buffer).
    +   */
    +
    +  privreq->req.xfrd += readlen;
    +  if (pmalen < privep->ep.maxpacket || privreq->req.xfrd >= privreq->req.len)
    +    {
    +      /* Return the read request to the class driver. */
    +
    +      usbtrace(TRACE_COMPLETE(epno), privreq->req.xfrd);
    +      stm32f0_reqcomplete(privep, OK);
    +    }
    +
    +  return OK;
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_cancelrequests
    + ****************************************************************************/
    +
    +static void stm32f0_cancelrequests(struct stm32f0_ep_s *privep)
    +{
    +  while (!stm32f0_rqempty(privep))
    +    {
    +      usbtrace(TRACE_COMPLETE(USB_EPNO(privep->ep.eplog)),
    +               (stm32f0_rqpeek(privep))->req.xfrd);
    +      stm32f0_reqcomplete(privep, -ESHUTDOWN);
    +    }
    +}
    +
    +/****************************************************************************
    + * Interrupt Level Processing
    + ****************************************************************************/
    +/****************************************************************************
    + * Name: stm32f0_dispatchrequest
    + ****************************************************************************/
    +
    +static void stm32f0_dispatchrequest(struct stm32f0_usbdev_s *priv)
    +{
    +  int ret;
    +
    +  usbtrace(TRACE_INTDECODE(STM32F0_TRACEINTID_DISPATCH), 0);
    +  if (priv && priv->driver)
    +    {
    +      /* Forward to the control request to the class driver implementation */
    +
    +      ret = CLASS_SETUP(priv->driver, &priv->usbdev, &priv->ctrl,
    +                        priv->ep0data, priv->ep0datlen);
    +      if (ret < 0)
    +        {
    +          /* Stall on failure */
    +
    +          usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_DISPATCHSTALL), 0);
    +          priv->ep0state = EP0STATE_STALLED;
    +        }
    +    }
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_epdone
    + ****************************************************************************/
    +
    +static void stm32f0_epdone(struct stm32f0_usbdev_s *priv, uint8_t epno)
    +{
    +  struct stm32f0_ep_s *privep;
    +  uint16_t epr;
    +
    +  /* Decode and service non control endpoints interrupt */
    +
    +  epr    = stm32f0_getreg(STM32F0_USB_EPR(epno));
    +  privep = &priv->eplist[epno];
    +
    +  /* OUT: host-to-device
    +   * CTR_RX is set by the hardware when an OUT/SETUP transaction
    +   * successfully completed on this endpoint.
    +   */
    +
    +  if ((epr & USB_EPR_CTR_RX) != 0)
    +    {
    +      usbtrace(TRACE_INTDECODE(STM32F0_TRACEINTID_EPOUTDONE), epr);
    +
    +      /* Handle read requests.  First check if a read request is available to
    +       * accept the host data.
    +       */
    +
    +      if (!stm32f0_rqempty(privep))
    +        {
    +          /* Read host data into the current read request */
    +
    +          (void)stm32f0_rdrequest(priv, privep);
    +
    +          /* "After the received data is processed, the application software
    +           *  should set the STAT_RX bits to '11' (Valid) in the USB_EPnR,
    +           *  enabling further transactions. "
    +           */
    +
    +          priv->rxstatus  = USB_EPR_STATRX_VALID;
    +        }
    +
    +      /* NAK further OUT packets if there there no more read requests */
    +
    +      if (stm32f0_rqempty(privep))
    +        {
    +          usbtrace(TRACE_INTDECODE(STM32F0_TRACEINTID_EPOUTPENDING), (uint16_t)epno);
    +
    +          /* Mark the RX processing as pending and NAK any OUT actions
    +           * on this endpoint.  "While the STAT_RX bits are equal to '10'
    +           * (NAK), any OUT request addressed to that endpoint is NAKed,
    +           * indicating a flow control condition: the USB host will retry
    +           * the transaction until it succeeds."
    +           */
    +
    +          priv->rxstatus  = USB_EPR_STATRX_NAK;
    +          priv->rxpending = true;
    +        }
    +
    +      /* Clear the interrupt status and set the new RX status */
    +
    +      stm32f0_clrepctrrx(epno);
    +      stm32f0_seteprxstatus(epno, priv->rxstatus);
    +    }
    +
    +  /* IN: device-to-host
    +   * CTR_TX is set when an IN transaction successfully completes on
    +   * an endpoint
    +   */
    +
    +  else if ((epr & USB_EPR_CTR_TX) != 0)
    +    {
    +      /* Clear interrupt status */
    +
    +      stm32f0_clrepctrtx(epno);
    +      usbtrace(TRACE_INTDECODE(STM32F0_TRACEINTID_EPINDONE), epr);
    +
    +      /* Handle write requests */
    +
    +      priv->txstatus = USB_EPR_STATTX_NAK;
    +      if (epno == EP0)
    +        {
    +          (void)stm32f0_wrrequest_ep0(priv, privep);
    +        }
    +      else
    +        {
    +          (void)stm32f0_wrrequest(priv, privep);
    +        }
    +
    +      /* Set the new TX status */
    +
    +      stm32f0_seteptxstatus(epno, priv->txstatus);
    +    }
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_setdevaddr
    + ****************************************************************************/
    +
    +static void stm32f0_setdevaddr(struct stm32f0_usbdev_s *priv, uint8_t value)
    +{
    +  int epno;
    +
    +  /* Set address in every allocated endpoint */
    +
    +  for (epno = 0; epno < STM32F0_NENDPOINTS; epno++)
    +    {
    +      if (stm32f0_epreserved(priv, epno))
    +        {
    +          stm32f0_setepaddress((uint8_t)epno, (uint8_t)epno);
    +        }
    +    }
    +
    +  /* Set the device address and enable function */
    +
    +  stm32f0_putreg(value | USB_DADDR_EF, STM32F0_USB_DADDR);
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_ep0setup
    + ****************************************************************************/
    +
    +static void stm32f0_ep0setup(struct stm32f0_usbdev_s *priv)
    +{
    +  struct stm32f0_ep_s   *ep0     = &priv->eplist[EP0];
    +  struct stm32f0_req_s  *privreq = stm32f0_rqpeek(ep0);
    +  struct stm32f0_ep_s   *privep;
    +  union wb_u           value;
    +  union wb_u           index;
    +  union wb_u           len;
    +  union wb_u           response;
    +  bool                 handled = false;
    +  uint8_t              epno;
    +  int                  nbytes = 0; /* Assume zero-length packet */
    +
    +  /* Terminate any pending requests (doesn't work if the pending request
    +   * was a zero-length transfer!)
    +   */
    +
    +  while (!stm32f0_rqempty(ep0))
    +    {
    +      int16_t result = OK;
    +      if (privreq->req.xfrd != privreq->req.len)
    +        {
    +          result = -EPROTO;
    +        }
    +
    +      usbtrace(TRACE_COMPLETE(ep0->ep.eplog), privreq->req.xfrd);
    +      stm32f0_reqcomplete(ep0, result);
    +    }
    +
    +  /* Assume NOT stalled; no TX in progress */
    +
    +  ep0->stalled  = 0;
    +  ep0->txbusy   = 0;
    +
    +  /* Check to see if called from the DATA phase of a SETUP Transfer */
    +
    +  if (priv->ep0state != EP0STATE_SETUP_READY)
    +    {
    +      /* Not the data phase */
    +      /* Get a 32-bit PMA address and use that to get the 8-byte setup
    +       * request
    +       */
    +
    +      stm32f0_copyfrompma((uint8_t *)&priv->ctrl, stm32f0_geteprxaddr(EP0),
    +                        USB_SIZEOF_CTRLREQ);
    +
    +      /* And extract the little-endian 16-bit values to host order */
    +
    +      value.w = GETUINT16(priv->ctrl.value);
    +      index.w = GETUINT16(priv->ctrl.index);
    +      len.w   = GETUINT16(priv->ctrl.len);
    +
    +      uinfo("SETUP: type=%02x req=%02x value=%04x index=%04x len=%04x\n",
    +            priv->ctrl.type, priv->ctrl.req, value.w, index.w, len.w);
    +
    +      /* Is this an setup with OUT and data of length > 0 */
    +
    +      if (USB_REQ_ISOUT(priv->ctrl.type) && len.w > 0)
    +        {
    +
    +          usbtrace(TRACE_INTDECODE(STM32F0_TRACEINTID_EP0SETUPOUT), len.w);
    +
    +          /* At this point priv->ctrl is the setup packet. */
    +
    +          priv->ep0state = EP0STATE_SETUP_OUT;
    +          return;
    +        }
    +      else
    +        {
    +          priv->ep0state = EP0STATE_SETUP_READY;
    +        }
    +    }
    +
    +  /* Dispatch any non-standard requests */
    +
    +  if ((priv->ctrl.type & USB_REQ_TYPE_MASK) != USB_REQ_TYPE_STANDARD)
    +    {
    +      usbtrace(TRACE_INTDECODE(STM32F0_TRACEINTID_NOSTDREQ), priv->ctrl.type);
    +
    +      /* Let the class implementation handle all non-standar requests */
    +
    +      stm32f0_dispatchrequest(priv);
    +      return;
    +    }
    +
    +  /* Handle standard request.  Pick off the things of interest to the
    +   * USB device controller driver; pass what is left to the class driver
    +   */
    +
    +  switch (priv->ctrl.req)
    +    {
    +    case USB_REQ_GETSTATUS:
    +      {
    +        /* type:  device-to-host; recipient = device, interface, endpoint
    +         * value: 0
    +         * index: zero interface endpoint
    +         * len:   2; data = status
    +         */
    +
    +        usbtrace(TRACE_INTDECODE(STM32F0_TRACEINTID_GETSTATUS), priv->ctrl.type);
    +        if (len.w != 2 || (priv->ctrl.type & USB_REQ_DIR_IN) == 0 ||
    +            index.b[MSB] != 0 || value.w != 0)
    +          {
    +            usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_BADEPGETSTATUS), 0);
    +            priv->ep0state = EP0STATE_STALLED;
    +          }
    +        else
    +          {
    +            switch (priv->ctrl.type & USB_REQ_RECIPIENT_MASK)
    +              {
    +               case USB_REQ_RECIPIENT_ENDPOINT:
    +                {
    +                  epno = USB_EPNO(index.b[LSB]);
    +                  usbtrace(TRACE_INTDECODE(STM32F0_TRACEINTID_EPGETSTATUS), epno);
    +                  if (epno >= STM32F0_NENDPOINTS)
    +                    {
    +                      usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_BADEPGETSTATUS), epno);
    +                      priv->ep0state = EP0STATE_STALLED;
    +                    }
    +                  else
    +                    {
    +                      response.w = 0; /* Not stalled */
    +                      nbytes     = 2; /* Response size: 2 bytes */
    +
    +                      if (USB_ISEPIN(index.b[LSB]))
    +                        {
    +                          /* IN endpoint */
    +
    +                          if (stm32f0_eptxstalled(epno))
    +                            {
    +                              /* IN Endpoint stalled */
    +
    +                              response.b[LSB] = 1; /* Stalled */
    +                            }
    +                          }
    +                      else
    +                        {
    +                          /* OUT endpoint */
    +
    +                          if (stm32f0_eprxstalled(epno))
    +                            {
    +                              /* OUT Endpoint stalled */
    +
    +                              response.b[LSB] = 1; /* Stalled */
    +                            }
    +                        }
    +                    }
    +                }
    +                break;
    +
    +              case USB_REQ_RECIPIENT_DEVICE:
    +                {
    +                 if (index.w == 0)
    +                    {
    +                      usbtrace(TRACE_INTDECODE(STM32F0_TRACEINTID_DEVGETSTATUS), 0);
    +
    +                      /* Features:  Remote Wakeup=YES; selfpowered=? */
    +
    +                      response.w      = 0;
    +                      response.b[LSB] = (priv->selfpowered << USB_FEATURE_SELFPOWERED) |
    +                                        (1 << USB_FEATURE_REMOTEWAKEUP);
    +                      nbytes          = 2; /* Response size: 2 bytes */
    +                    }
    +                  else
    +                    {
    +                      usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_BADDEVGETSTATUS), 0);
    +                      priv->ep0state = EP0STATE_STALLED;
    +                    }
    +                }
    +                break;
    +
    +              case USB_REQ_RECIPIENT_INTERFACE:
    +                {
    +                  usbtrace(TRACE_INTDECODE(STM32F0_TRACEINTID_IFGETSTATUS), 0);
    +                  response.w = 0;
    +                  nbytes     = 2; /* Response size: 2 bytes */
    +                }
    +                break;
    +
    +              default:
    +                {
    +                  usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_BADGETSTATUS), 0);
    +                  priv->ep0state = EP0STATE_STALLED;
    +                }
    +                break;
    +              }
    +          }
    +      }
    +      break;
    +
    +    case USB_REQ_CLEARFEATURE:
    +      {
    +        /* type:  host-to-device; recipient = device, interface or endpoint
    +         * value: feature selector
    +         * index: zero interface endpoint;
    +         * len:   zero, data = none
    +         */
    +
    +        usbtrace(TRACE_INTDECODE(STM32F0_TRACEINTID_CLEARFEATURE), priv->ctrl.type);
    +        if ((priv->ctrl.type & USB_REQ_RECIPIENT_MASK) != USB_REQ_RECIPIENT_ENDPOINT)
    +          {
    +            /* Let the class implementation handle all recipients (except for the
    +             * endpoint recipient)
    +             */
    +
    +            stm32f0_dispatchrequest(priv);
    +            handled = true;
    +          }
    +        else
    +          {
    +            /* Endpoint recipient */
    +
    +            epno = USB_EPNO(index.b[LSB]);
    +            if (epno < STM32F0_NENDPOINTS && index.b[MSB] == 0 &&
    +                value.w == USB_FEATURE_ENDPOINTHALT && len.w == 0)
    +              {
    +                privep         = &priv->eplist[epno];
    +                privep->halted = 0;
    +                (void)stm32f0_epstall(&privep->ep, true);
    +              }
    +            else
    +              {
    +                usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_BADCLEARFEATURE), 0);
    +                priv->ep0state = EP0STATE_STALLED;
    +              }
    +          }
    +      }
    +      break;
    +
    +    case USB_REQ_SETFEATURE:
    +      {
    +        /* type:  host-to-device; recipient = device, interface, endpoint
    +         * value: feature selector
    +         * index: zero interface endpoint;
    +         * len:   0; data = none
    +         */
    +
    +        usbtrace(TRACE_INTDECODE(STM32F0_TRACEINTID_SETFEATURE), priv->ctrl.type);
    +        if (((priv->ctrl.type & USB_REQ_RECIPIENT_MASK) == USB_REQ_RECIPIENT_DEVICE) &&
    +            value.w == USB_FEATURE_TESTMODE)
    +          {
    +            /* Special case recipient=device test mode */
    +
    +            uinfo("test mode: %d\n", index.w);
    +          }
    +        else if ((priv->ctrl.type & USB_REQ_RECIPIENT_MASK) != USB_REQ_RECIPIENT_ENDPOINT)
    +          {
    +            /* The class driver handles all recipients except recipient=endpoint */
    +
    +            stm32f0_dispatchrequest(priv);
    +            handled = true;
    +          }
    +        else
    +          {
    +            /* Handler recipient=endpoint */
    +
    +            epno = USB_EPNO(index.b[LSB]);
    +            if (epno < STM32F0_NENDPOINTS && index.b[MSB] == 0 &&
    +                value.w == USB_FEATURE_ENDPOINTHALT && len.w == 0)
    +              {
    +                privep         = &priv->eplist[epno];
    +                privep->halted = 1;
    +                (void)stm32f0_epstall(&privep->ep, false);
    +              }
    +            else
    +              {
    +                usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_BADSETFEATURE), 0);
    +                priv->ep0state = EP0STATE_STALLED;
    +              }
    +          }
    +      }
    +      break;
    +
    +    case USB_REQ_SETADDRESS:
    +      {
    +        /* type:  host-to-device; recipient = device
    +         * value: device address
    +         * index: 0
    +         * len:   0; data = none
    +         */
    +
    +        usbtrace(TRACE_INTDECODE(STM32F0_TRACEINTID_EP0SETUPSETADDRESS), value.w);
    +        if ((priv->ctrl.type & USB_REQ_RECIPIENT_MASK) != USB_REQ_RECIPIENT_DEVICE ||
    +            index.w != 0 || len.w != 0 || value.w > 127)
    +          {
    +            usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_BADSETADDRESS), 0);
    +            priv->ep0state = EP0STATE_STALLED;
    +          }
    +
    +        /* Note that setting of the device address will be deferred.  A zero-length
    +         * packet will be sent and the device address will be set when the zero-
    +         * length packet transfer completes.
    +         */
    +      }
    +      break;
    +
    +    case USB_REQ_GETDESCRIPTOR:
    +      /* type:  device-to-host; recipient = device
    +       * value: descriptor type and index
    +       * index: 0 or language ID;
    +       * len:   descriptor len; data = descriptor
    +       */
    +    case USB_REQ_SETDESCRIPTOR:
    +      /* type:  host-to-device; recipient = device
    +       * value: descriptor type and index
    +       * index: 0 or language ID;
    +       * len:   descriptor len; data = descriptor
    +       */
    +
    +      {
    +        usbtrace(TRACE_INTDECODE(STM32F0_TRACEINTID_GETSETDESC), priv->ctrl.type);
    +        if ((priv->ctrl.type & USB_REQ_RECIPIENT_MASK) == USB_REQ_RECIPIENT_DEVICE)
    +          {
    +            /* The request seems valid... let the class implementation handle it */
    +
    +            stm32f0_dispatchrequest(priv);
    +            handled = true;
    +          }
    +        else
    +          {
    +            usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_BADGETSETDESC), 0);
    +            priv->ep0state = EP0STATE_STALLED;
    +          }
    +      }
    +      break;
    +
    +    case USB_REQ_GETCONFIGURATION:
    +      /* type:  device-to-host; recipient = device
    +       * value: 0;
    +       * index: 0;
    +       * len:   1; data = configuration value
    +       */
    +
    +      {
    +        usbtrace(TRACE_INTDECODE(STM32F0_TRACEINTID_GETCONFIG), priv->ctrl.type);
    +        if ((priv->ctrl.type & USB_REQ_RECIPIENT_MASK) == USB_REQ_RECIPIENT_DEVICE &&
    +            value.w == 0 && index.w == 0 && len.w == 1)
    +          {
    +            /* The request seems valid... let the class implementation handle it */
    +
    +            stm32f0_dispatchrequest(priv);
    +            handled = true;
    +          }
    +        else
    +          {
    +            usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_BADGETCONFIG), 0);
    +            priv->ep0state = EP0STATE_STALLED;
    +          }
    +      }
    +      break;
    +
    +    case USB_REQ_SETCONFIGURATION:
    +      /* type:  host-to-device; recipient = device
    +       * value: configuration value
    +       * index: 0;
    +       * len:   0; data = none
    +       */
    +
    +      {
    +        usbtrace(TRACE_INTDECODE(STM32F0_TRACEINTID_SETCONFIG), priv->ctrl.type);
    +        if ((priv->ctrl.type & USB_REQ_RECIPIENT_MASK) == USB_REQ_RECIPIENT_DEVICE &&
    +            index.w == 0 && len.w == 0)
    +          {
    +             /* The request seems valid... let the class implementation handle it */
    +
    +             stm32f0_dispatchrequest(priv);
    +             handled = true;
    +          }
    +        else
    +          {
    +            usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_BADSETCONFIG), 0);
    +            priv->ep0state = EP0STATE_STALLED;
    +          }
    +      }
    +      break;
    +
    +    case USB_REQ_GETINTERFACE:
    +      /* type:  device-to-host; recipient = interface
    +       * value: 0
    +       * index: interface;
    +       * len:   1; data = alt interface
    +       */
    +    case USB_REQ_SETINTERFACE:
    +      /* type:  host-to-device; recipient = interface
    +       * value: alternate setting
    +       * index: interface;
    +       * len:   0; data = none
    +       */
    +
    +      {
    +        /* Let the class implementation handle the request */
    +
    +        usbtrace(TRACE_INTDECODE(STM32F0_TRACEINTID_GETSETIF), priv->ctrl.type);
    +        stm32f0_dispatchrequest(priv);
    +        handled = true;
    +      }
    +      break;
    +
    +    case USB_REQ_SYNCHFRAME:
    +      /* type:  device-to-host; recipient = endpoint
    +       * value: 0
    +       * index: endpoint;
    +       * len:   2; data = frame number
    +       */
    +
    +      {
    +        usbtrace(TRACE_INTDECODE(STM32F0_TRACEINTID_SYNCHFRAME), 0);
    +      }
    +      break;
    +
    +    default:
    +      {
    +        usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_INVALIDCTRLREQ), priv->ctrl.req);
    +        priv->ep0state = EP0STATE_STALLED;
    +      }
    +      break;
    +    }
    +
    +  /* At this point, the request has been handled and there are three possible
    +   * outcomes:
    +   *
    +   * 1. The setup request was successfully handled above and a response packet
    +   *    must be sent (may be a zero length packet).
    +   * 2. The request was successfully handled by the class implementation.  In
    +   *    case, the EP0 IN response has already been queued and the local variable
    +   *    'handled' will be set to true and ep0state != EP0STATE_STALLED;
    +   * 3. An error was detected in either the above logic or by the class implementation
    +   *    logic.  In either case, priv->state will be set EP0STATE_STALLED
    +   *    to indicate this case.
    +   *
    +   * NOTE: Non-standard requests are a special case.  They are handled by the
    +   * class implementation and this function returned early above, skipping this
    +   * logic altogether.
    +   */
    +
    +  if (priv->ep0state != EP0STATE_STALLED && !handled)
    +    {
    +      /* We will response.  First, restrict the data length to the length
    +       * requested in the setup packet
    +       */
    +
    +      if (nbytes > len.w)
    +        {
    +          nbytes = len.w;
    +        }
    +
    +      /* Send the response (might be a zero-length packet) */
    +
    +      stm32f0_epwrite(priv, ep0, response.b, nbytes);
    +      priv->ep0state = EP0STATE_IDLE;
    +    }
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_ep0in
    + ****************************************************************************/
    +
    +static void stm32f0_ep0in(struct stm32f0_usbdev_s *priv)
    +{
    +  /* There is no longer anything in the EP0 TX packet memory */
    +
    +  priv->eplist[EP0].txbusy = false;
    +
    +  /* Are we processing the completion of one packet of an outgoing request
    +   * from the class driver?
    +   */
    +
    +  if (priv->ep0state == EP0STATE_WRREQUEST)
    +    {
    +      stm32f0_wrrequest_ep0(priv, &priv->eplist[EP0]);
    +    }
    +
    +  /* No.. Are we processing the completion of a status response? */
    +
    +  else if (priv->ep0state == EP0STATE_IDLE)
    +    {
    +      /* Look at the saved SETUP command.  Was it a SET ADDRESS request?
    +       * If so, then now is the time to set the address.
    +       */
    +
    +      if (priv->ctrl.req == USB_REQ_SETADDRESS &&
    +          (priv->ctrl.type & REQRECIPIENT_MASK) ==
    +           (USB_REQ_TYPE_STANDARD | USB_REQ_RECIPIENT_DEVICE))
    +        {
    +          union wb_u value;
    +          value.w = GETUINT16(priv->ctrl.value);
    +          stm32f0_setdevaddr(priv, value.b[LSB]);
    +        }
    +    }
    +  else
    +    {
    +      priv->ep0state = EP0STATE_STALLED;
    +    }
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_ep0out
    + ****************************************************************************/
    +
    +static void stm32f0_ep0out(struct stm32f0_usbdev_s *priv)
    +{
    +  int ret;
    +
    +  struct stm32f0_ep_s *privep = &priv->eplist[EP0];
    +  switch (priv->ep0state)
    +    {
    +      case EP0STATE_RDREQUEST:           /* Read request in progress */
    +      case EP0STATE_IDLE:                /* No transfer in progress */
    +        ret = stm32f0_rdrequest(priv, privep);
    +        priv->ep0state = ((ret == OK) ? EP0STATE_RDREQUEST : EP0STATE_IDLE);
    +        break;
    +
    +      case EP0STATE_SETUP_OUT:           /* SETUP was waiting for data */
    +        ret = stm32f0_ep0_rdrequest(priv); /* Off load the data and run the
    +                                          * last set up command with the OUT
    +                                          * data
    +                                          */
    +        priv->ep0state = EP0STATE_IDLE;  /* There is no notion of reciving OUT
    +                                          * data greater then the length of
    +                                          * CONFIG_USBDEV_SETUP_MAXDATASIZE
    +                                          * so we are done
    +                                          */
    +        break;
    +
    +      default:
    +        /* Unexpected state OR host aborted the OUT transfer before it
    +         * completed, STALL the endpoint in either case
    +         */
    +
    +        priv->ep0state = EP0STATE_STALLED;
    +        break;
    +    }
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_ep0done
    + ****************************************************************************/
    +
    +static inline void stm32f0_ep0done(struct stm32f0_usbdev_s *priv, uint16_t istr)
    +{
    +  uint16_t epr;
    +
    +  /* Initialize RX and TX status.  We shouldn't have to actually look at the
    +   * status because the hardware is supposed to set the both RX and TX status
    +   * to NAK when an EP0 SETUP occurs (of course, this might not be a setup)
    +   */
    +
    +  priv->rxstatus = USB_EPR_STATRX_NAK;
    +  priv->txstatus = USB_EPR_STATTX_NAK;
    +
    +  /* Set both RX and TX status to NAK  */
    +
    +  stm32f0_seteprxstatus(EP0, USB_EPR_STATRX_NAK);
    +  stm32f0_seteptxstatus(EP0, USB_EPR_STATTX_NAK);
    +
    +  /* Check the direction bit to determine if this the completion of an EP0
    +   * packet sent to or received from the host PC.
    +   */
    +
    +  if ((istr & USB_ISTR_DIR) == 0)
    +    {
    +      /* EP0 IN: device-to-host (DIR=0) */
    +
    +      usbtrace(TRACE_INTDECODE(STM32F0_TRACEINTID_EP0IN), istr);
    +      stm32f0_clrepctrtx(EP0);
    +      stm32f0_ep0in(priv);
    +    }
    +  else
    +    {
    +      /* EP0 OUT: host-to-device (DIR=1) */
    +
    +      epr = stm32f0_getreg(STM32F0_USB_EPR(EP0));
    +
    +      /* CTR_TX is set when an IN transaction successfully
    +       * completes on an endpoint
    +       */
    +
    +      if ((epr & USB_EPR_CTR_TX) != 0)
    +        {
    +          usbtrace(TRACE_INTDECODE(STM32F0_TRACEINTID_EP0INDONE), epr);
    +          stm32f0_clrepctrtx(EP0);
    +          stm32f0_ep0in(priv);
    +        }
    +
    +      /* SETUP is set by the hardware when the last completed
    +       * transaction was a control endpoint SETUP
    +       */
    +
    +      else if ((epr & USB_EPR_SETUP) != 0)
    +        {
    +          usbtrace(TRACE_INTDECODE(STM32F0_TRACEINTID_EP0SETUPDONE), epr);
    +          stm32f0_clrepctrrx(EP0);
    +          stm32f0_ep0setup(priv);
    +        }
    +
    +      /* Set by the hardware when an OUT/SETUP transaction successfully
    +       * completed on this endpoint.
    +       */
    +
    +      else if ((epr & USB_EPR_CTR_RX) != 0)
    +        {
    +          usbtrace(TRACE_INTDECODE(STM32F0_TRACEINTID_EP0OUTDONE), epr);
    +          stm32f0_clrepctrrx(EP0);
    +          stm32f0_ep0out(priv);
    +        }
    +
    +      /* None of the above */
    +
    +      else
    +        {
    +          usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_EP0BADCTR), epr);
    +          return; /* Does this ever happen? */
    +        }
    +    }
    +
    +  /* Make sure that the EP0 packet size is still OK (superstitious?) */
    +
    +  stm32f0_seteprxcount(EP0, STM32F0_EP0MAXPACKET);
    +
    +  /* Now figure out the new RX/TX status.  Here are all possible
    +   * consequences of the above EP0 operations:
    +   *
    +   * rxstatus txstatus ep0state  MEANING
    +   * -------- -------- --------- ---------------------------------
    +   * NAK      NAK      IDLE      Nothing happened
    +   * NAK      VALID    IDLE      EP0 response sent from USBDEV driver
    +   * NAK      VALID    WRREQUEST EP0 response sent from class driver
    +   * NAK      ---      STALL     Some protocol error occurred
    +   *
    +   * First handle the STALL condition:
    +   */
    +
    +  if (priv->ep0state == EP0STATE_STALLED)
    +    {
    +      usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_EP0SETUPSTALLED), priv->ep0state);
    +      priv->rxstatus = USB_EPR_STATRX_STALL;
    +      priv->txstatus = USB_EPR_STATTX_STALL;
    +    }
    +
    +  /* Was a transmission started?  If so, txstatus will be VALID.  The
    +   * only special case to handle is when both are set to NAK.  In that
    +   * case, we need to set RX status to VALID in order to accept the next
    +   * SETUP request.
    +   */
    +
    +  else if (priv->rxstatus == USB_EPR_STATRX_NAK &&
    +           priv->txstatus == USB_EPR_STATTX_NAK)
    +    {
    +      priv->rxstatus = USB_EPR_STATRX_VALID;
    +    }
    +
    +  /* Now set the new TX and RX status */
    +
    +  stm32f0_seteprxstatus(EP0, priv->rxstatus);
    +  stm32f0_seteptxstatus(EP0, priv->txstatus);
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_lptransfer
    + ****************************************************************************/
    +
    +static void stm32f0_lptransfer(struct stm32f0_usbdev_s *priv)
    +{
    +  uint8_t  epno;
    +  uint16_t istr;
    +
    +  /* Stay in loop while LP interrupts are pending */
    +
    +  while (((istr = stm32f0_getreg(STM32F0_USB_ISTR)) & USB_ISTR_CTR) != 0)
    +    {
    +      stm32f0_putreg((uint16_t)~USB_ISTR_CTR, STM32F0_USB_ISTR);
    +
    +      /* Extract highest priority endpoint number */
    +
    +      epno = (uint8_t)(istr & USB_ISTR_EPID_MASK);
    +
    +      /* Handle EP0 completion events */
    +
    +      if (epno == 0)
    +        {
    +          stm32f0_ep0done(priv, istr);
    +        }
    +
    +      /* Handle other endpoint completion events */
    +
    +      else
    +        {
    +          stm32f0_epdone(priv, epno);
    +        }
    +    }
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_usb_interrupt
    + ****************************************************************************/
    +
    +static int stm32f0_usb_interrupt(int irq, void *context, FAR void *arg)
    +{
    +  struct stm32f0_usbdev_s *priv = (struct stm32f0_usbdev_s *)arg;
    +  uint16_t istr;
    +  uint8_t  epno;
    +
    +  DEBUGASSERT(priv != NULL);
    +
    +  /* High priority interrupts are only triggered by a correct transfer event
    +   * for isochronous and double-buffer bulk transfers.
    +   */
    +
    +  istr = stm32f0_getreg(STM32F0_USB_ISTR);
    +  usbtrace(TRACE_INTENTRY(STM32F0_TRACEINTID_INTERRUPT), istr);
    +  while ((istr & USB_ISTR_CTR) != 0)
    +    {
    +      stm32f0_putreg((uint16_t)~USB_ISTR_CTR, STM32F0_USB_ISTR);
    +
    +      /* Extract highest priority endpoint number */
    +
    +      epno = (uint8_t)(istr & USB_ISTR_EPID_MASK);
    +
    +      /* And handle the completion event */
    +
    +      stm32f0_epdone(priv, epno);
    +
    +      /* Fetch the status again for the next time through the loop */
    +
    +      istr = stm32f0_getreg(STM32F0_USB_ISTR);
    +    }
    +
    +  /* Handle Reset interrupts.  When this event occurs, the peripheral is left
    +   * in the same conditions it is left by the system reset (but with the
    +   * USB controller enabled).
    +   */
    +
    +  if ((istr & USB_ISTR_RESET) != 0)
    +    {
    +      /* Reset interrupt received. Clear the RESET interrupt status. */
    +
    +      stm32f0_putreg(~USB_ISTR_RESET, STM32F0_USB_ISTR);
    +      usbtrace(TRACE_INTDECODE(STM32F0_TRACEINTID_RESET), istr);
    +
    +      /* Restore our power-up state and exit now because istr is no longer
    +       * valid.
    +       */
    +
    +      stm32f0_reset(priv);
    +      goto exit_interrupt;
    +    }
    +
    +  /* Handle Wakeup interrupts.  This interrupt is only enable while the USB is
    +   * suspended.
    +   */
    +
    +  if ((istr & USB_ISTR_WKUP & priv->imask) != 0)
    +    {
    +      /* Wakeup interrupt received. Clear the WKUP interrupt status.  The
    +       * cause of the resume is indicated in the FNR register
    +       */
    +
    +      stm32f0_putreg(~USB_ISTR_WKUP, STM32F0_USB_ISTR);
    +      usbtrace(TRACE_INTDECODE(STM32F0_TRACEINTID_WKUP), stm32f0_getreg(STM32F0_USB_FNR));
    +
    +      /* Perform the wakeup action */
    +
    +      stm32f0_initresume(priv);
    +      priv->rsmstate = RSMSTATE_IDLE;
    +
    +      /* Disable ESOF polling, disable the wakeup interrupt, and
    +       * re-enable the suspend interrupt.  Clear any pending SUSP
    +       * interrupts.
    +       */
    +
    +      stm32f0_setimask(priv, USB_CNTR_SUSPM, USB_CNTR_ESOFM | USB_CNTR_WKUPM);
    +      stm32f0_putreg(~USB_CNTR_SUSPM, STM32F0_USB_ISTR);
    +    }
    +
    +  if ((istr & USB_ISTR_SUSP & priv->imask) != 0)
    +    {
    +        usbtrace(TRACE_INTDECODE(STM32F0_TRACEINTID_SUSP), 0);
    +        stm32f0_suspend(priv);
    +
    +        /* Clear of the ISTR bit must be done after setting of USB_CNTR_FSUSP */
    +
    +        stm32f0_putreg(~USB_ISTR_SUSP, STM32F0_USB_ISTR);
    +    }
    +
    +  if ((istr & USB_ISTR_ESOF & priv->imask) != 0)
    +    {
    +      stm32f0_putreg(~USB_ISTR_ESOF, STM32F0_USB_ISTR);
    +
    +      /* Resume handling timing is made with ESOFs */
    +
    +      usbtrace(TRACE_INTDECODE(STM32F0_TRACEINTID_ESOF), 0);
    +      stm32f0_esofpoll(priv);
    +    }
    +
    +  if ((istr & USB_ISTR_CTR & priv->imask) != 0)
    +    {
    +      /* Low priority endpoint correct transfer interrupt */
    +
    +      usbtrace(TRACE_INTDECODE(STM32F0_TRACEINTID_LPCTR), istr);
    +      stm32f0_lptransfer(priv);
    +    }
    +
    +exit_interrupt:
    +  usbtrace(TRACE_INTEXIT(STM32F0_TRACEINTID_INTERRUPT), 0);
    +  return OK;
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_setimask
    + ****************************************************************************/
    +
    +static void
    +stm32f0_setimask(struct stm32f0_usbdev_s *priv, uint16_t setbits, uint16_t clrbits)
    +{
    +  uint16_t regval;
    +
    +  /* Adjust the interrupt mask bits in the shadow copy first */
    +
    +  priv->imask &= ~clrbits;
    +  priv->imask |= setbits;
    +
    +  /* Then make the interrupt mask bits in the CNTR register match the shadow
    +   * register (Hmmm... who is shadowing whom?)
    +   */
    +
    +  regval  = stm32f0_getreg(STM32F0_USB_CNTR);
    +  regval &= ~USB_CNTR_ALLINTS;
    +  regval |= priv->imask;
    +  stm32f0_putreg(regval, STM32F0_USB_CNTR);
    +}
    +
    +/****************************************************************************
    + * Suspend/Resume Helpers
    + ****************************************************************************/
    +/****************************************************************************
    + * Name: stm32f0_suspend
    + ****************************************************************************/
    +
    +static void stm32f0_suspend(struct stm32f0_usbdev_s *priv)
    +{
    +  uint16_t regval;
    +
    +  /* Notify the class driver of the suspend event */
    +
    +  if (priv->driver)
    +    {
    +      CLASS_SUSPEND(priv->driver, &priv->usbdev);
    +    }
    +
    +  /* Disable ESOF polling, disable the SUSP interrupt, and enable the WKUP
    +   * interrupt.  Clear any pending WKUP interrupt.
    +   */
    +
    +  stm32f0_setimask(priv, USB_CNTR_WKUPM, USB_CNTR_ESOFM | USB_CNTR_SUSPM);
    +  stm32f0_putreg(~USB_ISTR_WKUP, STM32F0_USB_ISTR);
    +
    +  /* Set the FSUSP bit in the CNTR register.  This activates suspend mode
    +   * within the USB peripheral and disables further SUSP interrupts.
    +   */
    +
    +  regval  = stm32f0_getreg(STM32F0_USB_CNTR);
    +  regval |= USB_CNTR_FSUSP;
    +  stm32f0_putreg(regval, STM32F0_USB_CNTR);
    +
    +  /* If we are not a self-powered device, the got to low-power mode */
    +
    +  if (!priv->selfpowered)
    +    {
    +      /* Setting LPMODE in the CNTR register removes static power
    +       * consumption in the USB analog transceivers but keeps them
    +       * able to detect resume activity
    +       */
    +
    +      regval = stm32f0_getreg(STM32F0_USB_CNTR);
    +      regval |= USB_CNTR_LPMODE;
    +      stm32f0_putreg(regval, STM32F0_USB_CNTR);
    +    }
    +
    +  /* Let the board-specific logic know that we have entered the suspend
    +   * state
    +   */
    +
    +  stm32f0_usbsuspend((struct usbdev_s *)priv, false);
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_initresume
    + ****************************************************************************/
    +
    +static void stm32f0_initresume(struct stm32f0_usbdev_s *priv)
    +{
    +  uint16_t regval;
    +
    +  /* This function is called when either (1) a WKUP interrupt is received from
    +   * the host PC, or (2) the class device implementation calls the wakeup()
    +   * method.
    +   */
    +
    +  /* Clear the USB low power mode (lower power mode was not set if this is
    +   * a self-powered device.  Also, low power mode is automatically cleared by
    +   * hardware when a WKUP interrupt event occurs).
    +   */
    +
    +  regval = stm32f0_getreg(STM32F0_USB_CNTR);
    +  regval &= (~USB_CNTR_LPMODE);
    +  stm32f0_putreg(regval, STM32F0_USB_CNTR);
    +
    +  /* Restore full power -- whatever that means for this particular board */
    +
    +  stm32f0_usbsuspend((struct usbdev_s *)priv, true);
    +
    +  /* Reset FSUSP bit and enable normal interrupt handling */
    +
    +  stm32f0_putreg(STM32F0_CNTR_SETUP, STM32F0_USB_CNTR);
    +
    +  /* Notify the class driver of the resume event */
    +
    +  if (priv->driver)
    +    {
    +      CLASS_RESUME(priv->driver, &priv->usbdev);
    +    }
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_esofpoll
    + ****************************************************************************/
    +
    +static void stm32f0_esofpoll(struct stm32f0_usbdev_s *priv)
    +{
    +  uint16_t regval;
    +
    +    /* Called periodically from ESOF interrupt after RSMSTATE_STARTED */
    +
    +  switch (priv->rsmstate)
    +    {
    +    /* One ESOF after internal resume requested */
    +
    +    case RSMSTATE_STARTED:
    +      regval         = stm32f0_getreg(STM32F0_USB_CNTR);
    +      regval        |= USB_CNTR_RESUME;
    +      stm32f0_putreg(regval, STM32F0_USB_CNTR);
    +      priv->rsmstate = RSMSTATE_WAITING;
    +      priv->nesofs   = 10;
    +      break;
    +
    +    /* Countdown before completing the operation */
    +
    +    case RSMSTATE_WAITING:
    +      priv->nesofs--;
    +      if (priv->nesofs == 0)
    +        {
    +          /* Okay.. we are ready to resume normal operation */
    +
    +          regval         = stm32f0_getreg(STM32F0_USB_CNTR);
    +          regval        &= (~USB_CNTR_RESUME);
    +          stm32f0_putreg(regval, STM32F0_USB_CNTR);
    +          priv->rsmstate = RSMSTATE_IDLE;
    +
    +          /* Disable ESOF polling, disable the SUSP interrupt, and enable
    +           * the WKUP interrupt.  Clear any pending WKUP interrupt.
    +           */
    +
    +          stm32f0_setimask(priv, USB_CNTR_WKUPM, USB_CNTR_ESOFM | USB_CNTR_SUSPM);
    +          stm32f0_putreg(~USB_ISTR_WKUP, STM32F0_USB_ISTR);
    +        }
    +      break;
    +
    +    case RSMSTATE_IDLE:
    +    default:
    +      priv->rsmstate = RSMSTATE_IDLE;
    +      break;
    +    }
    +}
    +
    +/****************************************************************************
    + * Endpoint Helpers
    + ****************************************************************************/
    +/****************************************************************************
    + * Name: stm32f0_epreserve
    + ****************************************************************************/
    +
    +static inline struct stm32f0_ep_s *
    +stm32f0_epreserve(struct stm32f0_usbdev_s *priv, uint8_t epset)
    +{
    +  struct stm32f0_ep_s *privep = NULL;
    +  irqstate_t flags;
    +  int epndx = 0;
    +
    +  flags = enter_critical_section();
    +  epset &= priv->epavail;
    +  if (epset)
    +    {
    +      /* Select the lowest bit in the set of matching, available endpoints
    +       * (skipping EP0)
    +       */
    +
    +      for (epndx = 1; epndx < STM32F0_NENDPOINTS; epndx++)
    +        {
    +          uint8_t bit = STM32F0_ENDP_BIT(epndx);
    +          if ((epset & bit) != 0)
    +            {
    +              /* Mark the endpoint no longer available */
    +
    +              priv->epavail &= ~bit;
    +
    +              /* And return the pointer to the standard endpoint structure */
    +
    +              privep = &priv->eplist[epndx];
    +              break;
    +            }
    +        }
    +    }
    +
    +  leave_critical_section(flags);
    +  return privep;
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_epunreserve
    + ****************************************************************************/
    +
    +static inline void
    +stm32f0_epunreserve(struct stm32f0_usbdev_s *priv, struct stm32f0_ep_s *privep)
    +{
    +  irqstate_t flags = enter_critical_section();
    +  priv->epavail   |= STM32F0_ENDP_BIT(USB_EPNO(privep->ep.eplog));
    +  leave_critical_section(flags);
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_epreserved
    + ****************************************************************************/
    +
    +static inline bool
    +stm32f0_epreserved(struct stm32f0_usbdev_s *priv, int epno)
    +{
    +  return ((priv->epavail & STM32F0_ENDP_BIT(epno)) == 0);
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_epallocpma
    + ****************************************************************************/
    +
    +static int stm32f0_epallocpma(struct stm32f0_usbdev_s *priv)
    +{
    +  irqstate_t flags;
    +  int bufno = ERROR;
    +  int bufndx;
    +
    +  flags = enter_critical_section();
    +  for (bufndx = 2; bufndx < STM32F0_NBUFFERS; bufndx++)
    +    {
    +      /* Check if this buffer is available */
    +
    +      uint8_t bit = STM32F0_BUFFER_BIT(bufndx);
    +      if ((priv->bufavail & bit) != 0)
    +        {
    +          /* Yes.. Mark the endpoint no longer available */
    +
    +          priv->bufavail &= ~bit;
    +
    +          /* And return the index of the allocated buffer */
    +
    +          bufno = bufndx;
    +          break;
    +        }
    +    }
    +
    +  leave_critical_section(flags);
    +  return bufno;
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_epfreepma
    + ****************************************************************************/
    +
    +static inline void
    +stm32f0_epfreepma(struct stm32f0_usbdev_s *priv, struct stm32f0_ep_s *privep)
    +{
    +  irqstate_t flags = enter_critical_section();
    +  priv->epavail   |= STM32F0_ENDP_BIT(privep->bufno);
    +  leave_critical_section(flags);
    +}
    +
    +/****************************************************************************
    + * Endpoint operations
    + ****************************************************************************/
    +/****************************************************************************
    + * Name: stm32f0_epconfigure
    + ****************************************************************************/
    +
    +static int stm32f0_epconfigure(struct usbdev_ep_s *ep,
    +                             const struct usb_epdesc_s *desc,
    +                             bool last)
    +{
    +  struct stm32f0_ep_s *privep = (struct stm32f0_ep_s *)ep;
    +  uint16_t pma;
    +  uint16_t setting;
    +  uint16_t maxpacket;
    +  uint8_t  epno;
    +
    +#ifdef CONFIG_DEBUG_FEATURES
    +  if (!ep || !desc)
    +    {
    +      usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_INVALIDPARMS), 0);
    +      uerr("ERROR: ep=%p desc=%p\n");
    +      return -EINVAL;
    +    }
    +#endif
    +
    +  /* Get the unadorned endpoint address */
    +
    +  epno = USB_EPNO(desc->addr);
    +  usbtrace(TRACE_EPCONFIGURE, (uint16_t)epno);
    +  DEBUGASSERT(epno == USB_EPNO(ep->eplog));
    +
    +  /* Set the requested type */
    +
    +  switch (desc->attr & USB_EP_ATTR_XFERTYPE_MASK)
    +   {
    +    case USB_EP_ATTR_XFER_INT: /* Interrupt endpoint */
    +      setting = USB_EPR_EPTYPE_INTERRUPT;
    +      break;
    +
    +    case USB_EP_ATTR_XFER_BULK: /* Bulk endpoint */
    +      setting = USB_EPR_EPTYPE_BULK;
    +      break;
    +
    +    case USB_EP_ATTR_XFER_ISOC: /* Isochronous endpoint */
    +#warning "REVISIT: Need to review isochronous EP setup"
    +      setting = USB_EPR_EPTYPE_ISOC;
    +      break;
    +
    +    case USB_EP_ATTR_XFER_CONTROL: /* Control endpoint */
    +      setting = USB_EPR_EPTYPE_CONTROL;
    +      break;
    +
    +    default:
    +      usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_BADEPTYPE), (uint16_t)desc->type);
    +      return -EINVAL;
    +    }
    +
    +  stm32f0_seteptype(epno, setting);
    +
    +  /* Get the address of the PMA buffer allocated for this endpoint */
    +
    +#warning "REVISIT: Should configure BULK EPs using double buffer feature"
    +  pma = STM32F0_BUFNO2BUF(privep->bufno);
    +
    +  /* Get the maxpacket size of the endpoint. */
    +
    +  maxpacket = GETUINT16(desc->mxpacketsize);
    +  DEBUGASSERT(maxpacket <= STM32F0_MAXPACKET_SIZE);
    +  ep->maxpacket = maxpacket;
    +
    +  /* Get the subset matching the requested direction */
    +
    +  if (USB_ISEPIN(desc->addr))
    +    {
    +      /* The full, logical EP number includes direction */
    +
    +      ep->eplog = USB_EPIN(epno);
    +
    +      /* Set up TX; disable RX */
    +
    +      stm32f0_seteptxaddr(epno, pma);
    +      stm32f0_seteptxstatus(epno, USB_EPR_STATTX_NAK);
    +      stm32f0_seteprxstatus(epno, USB_EPR_STATRX_DIS);
    +    }
    +  else
    +    {
    +      /* The full, logical EP number includes direction */
    +
    +      ep->eplog = USB_EPOUT(epno);
    +
    +      /* Set up RX; disable TX */
    +
    +      stm32f0_seteprxaddr(epno, pma);
    +      stm32f0_seteprxcount(epno, maxpacket);
    +      stm32f0_seteprxstatus(epno, USB_EPR_STATRX_VALID);
    +      stm32f0_seteptxstatus(epno, USB_EPR_STATTX_DIS);
    +    }
    +
    +   stm32f0_dumpep(epno);
    +   return OK;
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_epdisable
    + ****************************************************************************/
    +
    +static int stm32f0_epdisable(struct usbdev_ep_s *ep)
    +{
    +  struct stm32f0_ep_s *privep = (struct stm32f0_ep_s *)ep;
    +  irqstate_t flags;
    +  uint8_t epno;
    +
    +#ifdef CONFIG_DEBUG_FEATURES
    +  if (!ep)
    +    {
    +      usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_INVALIDPARMS), 0);
    +      uerr("ERROR: ep=%p\n", ep);
    +      return -EINVAL;
    +    }
    +#endif
    +
    +  epno = USB_EPNO(ep->eplog);
    +  usbtrace(TRACE_EPDISABLE, epno);
    +
    +  /* Cancel any ongoing activity */
    +
    +  flags = enter_critical_section();
    +  stm32f0_cancelrequests(privep);
    +
    +  /* Disable TX; disable RX */
    +
    +  stm32f0_seteprxcount(epno, 0);
    +  stm32f0_seteprxstatus(epno, USB_EPR_STATRX_DIS);
    +  stm32f0_seteptxstatus(epno, USB_EPR_STATTX_DIS);
    +
    +  leave_critical_section(flags);
    +  return OK;
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_epallocreq
    + ****************************************************************************/
    +
    +static struct usbdev_req_s *stm32f0_epallocreq(struct usbdev_ep_s *ep)
    +{
    +  struct stm32f0_req_s *privreq;
    +
    +#ifdef CONFIG_DEBUG_FEATURES
    +  if (!ep)
    +    {
    +      usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_INVALIDPARMS), 0);
    +      return NULL;
    +    }
    +#endif
    +  usbtrace(TRACE_EPALLOCREQ, USB_EPNO(ep->eplog));
    +
    +  privreq = (struct stm32f0_req_s *)kmm_malloc(sizeof(struct stm32f0_req_s));
    +  if (!privreq)
    +    {
    +      usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_ALLOCFAIL), 0);
    +      return NULL;
    +    }
    +
    +  memset(privreq, 0, sizeof(struct stm32f0_req_s));
    +  return &privreq->req;
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_epfreereq
    + ****************************************************************************/
    +
    +static void stm32f0_epfreereq(struct usbdev_ep_s *ep, struct usbdev_req_s *req)
    +{
    +  struct stm32f0_req_s *privreq = (struct stm32f0_req_s *)req;
    +
    +#ifdef CONFIG_DEBUG_FEATURES
    +  if (!ep || !req)
    +    {
    +      usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_INVALIDPARMS), 0);
    +      return;
    +    }
    +#endif
    +  usbtrace(TRACE_EPFREEREQ, USB_EPNO(ep->eplog));
    +
    +  kmm_free(privreq);
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_epsubmit
    + ****************************************************************************/
    +
    +static int stm32f0_epsubmit(struct usbdev_ep_s *ep, struct usbdev_req_s *req)
    +{
    +  struct stm32f0_req_s *privreq = (struct stm32f0_req_s *)req;
    +  struct stm32f0_ep_s *privep = (struct stm32f0_ep_s *)ep;
    +  struct stm32f0_usbdev_s *priv;
    +  irqstate_t flags;
    +  uint8_t epno;
    +  int ret = OK;
    +
    +#ifdef CONFIG_DEBUG_FEATURES
    +  if (!req || !req->callback || !req->buf || !ep)
    +    {
    +      usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_INVALIDPARMS), 0);
    +      uerr("ERROR: req=%p callback=%p buf=%p ep=%p\n",
    +           req, req->callback, req->buf, ep);
    +      return -EINVAL;
    +    }
    +#endif
    +
    +  usbtrace(TRACE_EPSUBMIT, USB_EPNO(ep->eplog));
    +  priv = privep->dev;
    +
    +#ifdef CONFIG_DEBUG_FEATURES
    +  if (!priv->driver)
    +    {
    +      usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_NOTCONFIGURED), priv->usbdev.speed);
    +      uerr("ERROR: driver=%p\n", priv->driver);
    +      return -ESHUTDOWN;
    +    }
    +#endif
    +
    +  /* Handle the request from the class driver */
    +
    +  epno        = USB_EPNO(ep->eplog);
    +  req->result = -EINPROGRESS;
    +  req->xfrd   = 0;
    +  flags       = enter_critical_section();
    +
    +  /* If we are stalled, then drop all requests on the floor */
    +
    +  if (privep->stalled)
    +    {
    +      stm32f0_abortrequest(privep, privreq, -EBUSY);
    +      uerr("ERROR: stalled\n");
    +      ret = -EBUSY;
    +    }
    +
    +  /* Handle IN (device-to-host) requests.  NOTE:  If the class device is
    +   * using the bi-directional EP0, then we assume that they intend the EP0
    +   * IN functionality.
    +   */
    +
    +  else if (USB_ISEPIN(ep->eplog) || epno == EP0)
    +    {
    +      /* Add the new request to the request queue for the IN endpoint */
    +
    +      stm32f0_rqenqueue(privep, privreq);
    +      usbtrace(TRACE_INREQQUEUED(epno), req->len);
    +
    +      /* If the IN endpoint FIFO is available, then transfer the data now */
    +
    +      if (!privep->txbusy)
    +        {
    +          priv->txstatus = USB_EPR_STATTX_NAK;
    +          if (epno == EP0)
    +            {
    +              ret = stm32f0_wrrequest_ep0(priv, privep);
    +            }
    +          else
    +            {
    +              ret = stm32f0_wrrequest(priv, privep);
    +            }
    +
    +          /* Set the new TX status */
    +
    +          stm32f0_seteptxstatus(epno, priv->txstatus);
    +        }
    +    }
    +
    +  /* Handle OUT (host-to-device) requests */
    +
    +  else
    +    {
    +      /* Add the new request to the request queue for the OUT endpoint */
    +
    +      privep->txnullpkt = 0;
    +      stm32f0_rqenqueue(privep, privreq);
    +      usbtrace(TRACE_OUTREQQUEUED(epno), req->len);
    +
    +      /* This there a incoming data pending the availability of a request? */
    +
    +      if (priv->rxpending)
    +        {
    +          /* Set STAT_RX bits to '11' in the USB_EPnR, enabling further
    +           * transactions. "While the STAT_RX bits are equal to '10'
    +           * (NAK), any OUT request addressed to that endpoint is NAKed,
    +           * indicating a flow control condition: the USB host will retry
    +           * the transaction until it succeeds."
    +           */
    +
    +          priv->rxstatus  = USB_EPR_STATRX_VALID;
    +          stm32f0_seteprxstatus(epno, priv->rxstatus);
    +
    +          /* Data is no longer pending */
    +
    +          priv->rxpending = false;
    +        }
    +    }
    +
    +  leave_critical_section(flags);
    +  return ret;
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_epcancel
    + ****************************************************************************/
    +
    +static int stm32f0_epcancel(struct usbdev_ep_s *ep, struct usbdev_req_s *req)
    +{
    +  struct stm32f0_ep_s *privep = (struct stm32f0_ep_s *)ep;
    +  irqstate_t flags;
    +
    +#ifdef CONFIG_DEBUG_USB
    +  if (!ep || !req)
    +    {
    +      usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_INVALIDPARMS), 0);
    +      return -EINVAL;
    +    }
    +#endif
    +  usbtrace(TRACE_EPCANCEL, USB_EPNO(ep->eplog));
    +
    +  flags = enter_critical_section();
    +  stm32f0_cancelrequests(privep);
    +  leave_critical_section(flags);
    +  return OK;
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_epstall
    + ****************************************************************************/
    +
    +static int stm32f0_epstall(struct usbdev_ep_s *ep, bool resume)
    +{
    +  struct stm32f0_ep_s *privep;
    +  struct stm32f0_usbdev_s *priv;
    +  uint8_t epno;
    +  uint16_t status;
    +  irqstate_t flags;
    +
    +#ifdef CONFIG_DEBUG_USB
    +  if (!ep)
    +    {
    +      usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_INVALIDPARMS), 0);
    +      return -EINVAL;
    +    }
    +#endif
    +
    +  privep = (struct stm32f0_ep_s *)ep;
    +  priv   = (struct stm32f0_usbdev_s *)privep->dev;
    +  epno   = USB_EPNO(ep->eplog);
    +
    +  /* STALL or RESUME the endpoint */
    +
    +  flags = enter_critical_section();
    +  usbtrace(resume ? TRACE_EPRESUME : TRACE_EPSTALL, USB_EPNO(ep->eplog));
    +
    +  /* Get status of the endpoint; stall the request if the endpoint is
    +   * disabled
    +   */
    +
    +  if (USB_ISEPIN(ep->eplog))
    +    {
    +      status = stm32f0_geteptxstatus(epno);
    +    }
    +  else
    +    {
    +      status = stm32f0_geteprxstatus(epno);
    +    }
    +
    +  if (status == 0)
    +    {
    +      usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_EPDISABLED), 0);
    +
    +      if (epno == 0)
    +        {
    +          priv->ep0state = EP0STATE_STALLED;
    +        }
    +
    +      return -ENODEV;
    +    }
    +
    +  /* Handle the resume condition */
    +
    +  if (resume)
    +    {
    +      /* Resuming a stalled endpoint */
    +
    +      usbtrace(TRACE_EPRESUME, epno);
    +      privep->stalled = false;
    +
    +      if (USB_ISEPIN(ep->eplog))
    +        {
    +          /* IN endpoint */
    +
    +          if (stm32f0_eptxstalled(epno))
    +            {
    +              stm32f0_clrtxdtog(epno);
    +
    +              /* Restart any queued write requests */
    +
    +              priv->txstatus = USB_EPR_STATTX_NAK;
    +              if (epno == EP0)
    +                {
    +                  (void)stm32f0_wrrequest_ep0(priv, privep);
    +                }
    +              else
    +                {
    +                  (void)stm32f0_wrrequest(priv, privep);
    +                }
    +
    +              /* Set the new TX status */
    +
    +              stm32f0_seteptxstatus(epno, priv->txstatus);
    +            }
    +        }
    +      else
    +        {
    +          /* OUT endpoint */
    +
    +          if (stm32f0_eprxstalled(epno))
    +            {
    +              if (epno == EP0)
    +                {
    +                  /* After clear the STALL, enable the default endpoint receiver */
    +
    +                  stm32f0_seteprxcount(epno, ep->maxpacket);
    +                }
    +              else
    +                {
    +                  stm32f0_clrrxdtog(epno);
    +                }
    +
    +              priv->rxstatus = USB_EPR_STATRX_VALID;
    +              stm32f0_seteprxstatus(epno, USB_EPR_STATRX_VALID);
    +            }
    +        }
    +    }
    +
    +  /* Handle the stall condition */
    +
    +  else
    +    {
    +      usbtrace(TRACE_EPSTALL, epno);
    +      privep->stalled = true;
    +
    +      if (USB_ISEPIN(ep->eplog))
    +        {
    +          /* IN endpoint */
    +
    +          priv->txstatus = USB_EPR_STATTX_STALL;
    +          stm32f0_seteptxstatus(epno, USB_EPR_STATTX_STALL);
    +        }
    +      else
    +        {
    +          /* OUT endpoint */
    +
    +          priv->rxstatus = USB_EPR_STATRX_STALL;
    +          stm32f0_seteprxstatus(epno, USB_EPR_STATRX_STALL);
    +        }
    +    }
    +
    +  leave_critical_section(flags);
    +  return OK;
    +}
    +
    +/****************************************************************************
    + * Device Controller Operations
    + ****************************************************************************/
    +/****************************************************************************
    + * Name: stm32f0_allocep
    + ****************************************************************************/
    +
    +static struct usbdev_ep_s *stm32f0_allocep(struct usbdev_s *dev, uint8_t epno,
    +                                         bool in, uint8_t eptype)
    +{
    +  struct stm32f0_usbdev_s *priv = (struct stm32f0_usbdev_s *)dev;
    +  struct stm32f0_ep_s *privep = NULL;
    +  uint8_t epset = STM32F0_ENDP_ALLSET;
    +  int bufno;
    +
    +  usbtrace(TRACE_DEVALLOCEP, (uint16_t)epno);
    +#ifdef CONFIG_DEBUG_USB
    +  if (!dev)
    +    {
    +      usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_INVALIDPARMS), 0);
    +      return NULL;
    +    }
    +#endif
    +
    +  /* Ignore any direction bits in the logical address */
    +
    +  epno = USB_EPNO(epno);
    +
    +  /* A logical address of 0 means that any endpoint will do */
    +
    +  if (epno > 0)
    +    {
    +      /* Otherwise, we will return the endpoint structure only for the requested
    +       * 'logical' endpoint.  All of the other checks will still be performed.
    +       *
    +       * First, verify that the logical endpoint is in the range supported by
    +       * by the hardware.
    +       */
    +
    +      if (epno >= STM32F0_NENDPOINTS)
    +        {
    +          usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_BADEPNO), (uint16_t)epno);
    +          return NULL;
    +        }
    +
    +      /* Convert the logical address to a physical OUT endpoint address and
    +       * remove all of the candidate endpoints from the bitset except for the
    +       * the IN/OUT pair for this logical address.
    +       */
    +
    +      epset = STM32F0_ENDP_BIT(epno);
    +    }
    +
    +  /* Check if the selected endpoint number is available */
    +
    +  privep = stm32f0_epreserve(priv, epset);
    +  if (!privep)
    +    {
    +      usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_EPRESERVE), (uint16_t)epset);
    +      goto errout;
    +    }
    +
    +  /* Allocate a PMA buffer for this endpoint */
    +
    +#warning "REVISIT: Should configure BULK EPs using double buffer feature"
    +  bufno = stm32f0_epallocpma(priv);
    +  if (bufno < 0)
    +    {
    +      usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_EPBUFFER), 0);
    +      goto errout_with_ep;
    +    }
    +
    +  privep->bufno = (uint8_t)bufno;
    +  return &privep->ep;
    +
    +errout_with_ep:
    +  stm32f0_epunreserve(priv, privep);
    +errout:
    +  return NULL;
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_freeep
    + ****************************************************************************/
    +
    +static void stm32f0_freeep(struct usbdev_s *dev, struct usbdev_ep_s *ep)
    +{
    +  struct stm32f0_usbdev_s *priv;
    +  struct stm32f0_ep_s *privep;
    +
    +#ifdef CONFIG_DEBUG_USB
    +  if (!dev || !ep)
    +    {
    +      usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_INVALIDPARMS), 0);
    +      return;
    +    }
    +#endif
    +  priv   = (struct stm32f0_usbdev_s *)dev;
    +  privep = (struct stm32f0_ep_s *)ep;
    +  usbtrace(TRACE_DEVFREEEP, (uint16_t)USB_EPNO(ep->eplog));
    +
    +  if (priv && privep)
    +    {
    +      /* Free the PMA buffer assigned to this endpoint */
    +
    +      stm32f0_epfreepma(priv, privep);
    +
    +      /* Mark the endpoint as available */
    +
    +      stm32f0_epunreserve(priv, privep);
    +    }
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_getframe
    + ****************************************************************************/
    +
    +static int stm32f0_getframe(struct usbdev_s *dev)
    +{
    +  uint16_t fnr;
    +
    +#ifdef CONFIG_DEBUG_USB
    +  if (!dev)
    +    {
    +      usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_INVALIDPARMS), 0);
    +      return -EINVAL;
    +    }
    +#endif
    +
    +  /* Return the last frame number detected by the hardware */
    +
    +  fnr = stm32f0_getreg(STM32F0_USB_FNR);
    +  usbtrace(TRACE_DEVGETFRAME, fnr);
    +  return (fnr & USB_FNR_FN_MASK);
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_wakeup
    + ****************************************************************************/
    +
    +static int stm32f0_wakeup(struct usbdev_s *dev)
    +{
    +  struct stm32f0_usbdev_s *priv = (struct stm32f0_usbdev_s *)dev;
    +  irqstate_t flags;
    +
    +  usbtrace(TRACE_DEVWAKEUP, 0);
    +#ifdef CONFIG_DEBUG_USB
    +  if (!dev)
    +    {
    +      usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_INVALIDPARMS), 0);
    +      return -EINVAL;
    +    }
    +#endif
    +
    +  /* Start the resume sequence.  The actual resume steps will be driven
    +   * by the ESOF interrupt.
    +   */
    +
    +  flags = enter_critical_section();
    +  stm32f0_initresume(priv);
    +  priv->rsmstate = RSMSTATE_STARTED;
    +
    +  /* Disable the SUSP interrupt (until we are fully resumed), disable
    +   * the WKUP interrupt (we are already waking up), and enable the
    +   * ESOF interrupt that will drive the resume operations.  Clear any
    +   * pending ESOF interrupt.
    +   */
    +
    +  stm32f0_setimask(priv, USB_CNTR_ESOFM, USB_CNTR_WKUPM | USB_CNTR_SUSPM);
    +  stm32f0_putreg(~USB_ISTR_ESOF, STM32F0_USB_ISTR);
    +  leave_critical_section(flags);
    +  return OK;
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_selfpowered
    + ****************************************************************************/
    +
    +static int stm32f0_selfpowered(struct usbdev_s *dev, bool selfpowered)
    +{
    +  struct stm32f0_usbdev_s *priv = (struct stm32f0_usbdev_s *)dev;
    +
    +  usbtrace(TRACE_DEVSELFPOWERED, (uint16_t)selfpowered);
    +
    +#ifdef CONFIG_DEBUG_USB
    +  if (!dev)
    +    {
    +      usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_INVALIDPARMS), 0);
    +      return -ENODEV;
    +    }
    +#endif
    +
    +  priv->selfpowered = selfpowered;
    +  return OK;
    +}
    +
    +/****************************************************************************
    + * Initialization/Reset
    + ****************************************************************************/
    +
    +/****************************************************************************
    + * Name: stm32f0_reset
    + ****************************************************************************/
    +
    +static void stm32f0_reset(struct stm32f0_usbdev_s *priv)
    +{
    +  int epno;
    +
    +  /* Put the USB controller in reset, disable all interrupts */
    +
    +  stm32f0_putreg(USB_CNTR_FRES, STM32F0_USB_CNTR);
    +
    +  /* Tell the class driver that we are disconnected.  The class driver
    +   * should then accept any new configurations.
    +   */
    +
    +  CLASS_DISCONNECT(priv->driver, &priv->usbdev);
    +
    +  /* Reset the device state structure */
    +
    +  priv->ep0state  = EP0STATE_IDLE;
    +  priv->rsmstate  = RSMSTATE_IDLE;
    +  priv->rxpending = false;
    +
    +  /* Reset endpoints */
    +
    +  for (epno = 0; epno < STM32F0_NENDPOINTS; epno++)
    +    {
    +      struct stm32f0_ep_s *privep = &priv->eplist[epno];
    +
    +      /* Cancel any queued requests.  Since they are canceled
    +       * with status -ESHUTDOWN, then will not be requeued
    +       * until the configuration is reset.  NOTE:  This should
    +       * not be necessary... the CLASS_DISCONNECT above should
    +       * result in the class implementation calling stm32f0_epdisable
    +       * for each of its configured endpoints.
    +       */
    +
    +      stm32f0_cancelrequests(privep);
    +
    +      /* Reset endpoint status */
    +
    +      privep->stalled   = false;
    +      privep->halted    = false;
    +      privep->txbusy    = false;
    +      privep->txnullpkt = false;
    +    }
    +
    +  /* Re-configure the USB controller in its initial, unconnected state */
    +
    +  stm32f0_hwreset(priv);
    +  priv->usbdev.speed = USB_SPEED_FULL;
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_hwreset
    + ****************************************************************************/
    +
    +static void stm32f0_hwreset(struct stm32f0_usbdev_s *priv)
    +{
    +  /* Put the USB controller into reset, clear all interrupt enables */
    +
    +  stm32f0_putreg(USB_CNTR_FRES, STM32F0_USB_CNTR);
    +
    +  /* Disable interrupts (and perhaps take the USB controller out of reset) */
    +
    +  priv->imask = 0;
    +  stm32f0_putreg(priv->imask, STM32F0_USB_CNTR);
    +
    +  /* Set the STM32 BTABLE address */
    +
    +  stm32f0_putreg(STM32F0_BTABLE_ADDRESS & 0xfff8, STM32F0_USB_BTABLE);
    +
    +  /* Initialize EP0 */
    +
    +  stm32f0_seteptype(EP0, USB_EPR_EPTYPE_CONTROL);
    +  stm32f0_seteptxstatus(EP0, USB_EPR_STATTX_NAK);
    +  stm32f0_seteprxaddr(EP0, STM32F0_EP0_RXADDR);
    +  stm32f0_seteprxcount(EP0, STM32F0_EP0MAXPACKET);
    +  stm32f0_seteptxaddr(EP0, STM32F0_EP0_TXADDR);
    +  stm32f0_clrstatusout(EP0);
    +  stm32f0_seteprxstatus(EP0, USB_EPR_STATRX_VALID);
    +
    +  /* Set the device to respond on default address */
    +
    +  stm32f0_setdevaddr(priv, 0);
    +
    +  /* Clear any pending interrupts */
    +
    +  stm32f0_putreg(0, STM32F0_USB_ISTR);
    +
    +  /* Enable interrupts at the USB controller */
    +
    +  stm32f0_setimask(priv, STM32F0_CNTR_SETUP, (USB_CNTR_ALLINTS & ~STM32F0_CNTR_SETUP));
    +  stm32f0_dumpep(EP0);
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_hwsetup
    + ****************************************************************************/
    +
    +static void stm32f0_hwsetup(struct stm32f0_usbdev_s *priv)
    +{
    +  int epno;
    +
    +  /* Power the USB controller, put the USB controller into reset, disable
    +   * all USB interrupts
    +   */
    +
    +  stm32f0_putreg(USB_CNTR_FRES | USB_CNTR_PDWN, STM32F0_USB_CNTR);
    +
    +  /* Disconnect the device / disable the pull-up.  We don't want the
    +   * host to enumerate us until the class driver is registered.
    +   */
    +
    +  stm32f0_usbpullup(&priv->usbdev, false);
    +
    +  /* Initialize the device state structure.  NOTE: many fields
    +   * have the initial value of zero and, hence, are not explicitly
    +   * initialized here.
    +   */
    +
    +  memset(priv, 0, sizeof(struct stm32f0_usbdev_s));
    +  priv->usbdev.ops   = &g_devops;
    +  priv->usbdev.ep0   = &priv->eplist[EP0].ep;
    +  priv->epavail      = STM32F0_ENDP_ALLSET & ~STM32F0_ENDP_BIT(EP0);
    +  priv->bufavail     = STM32F0_BUFFER_ALLSET & ~STM32F0_BUFFER_EP0;
    +
    +  /* Initialize the endpoint list */
    +
    +  for (epno = 0; epno < STM32F0_NENDPOINTS; epno++)
    +    {
    +      /* Set endpoint operations, reference to driver structure (not
    +       * really necessary because there is only one controller), and
    +       * the (physical) endpoint number which is just the index to the
    +       * endpoint.
    +       */
    +
    +      priv->eplist[epno].ep.ops    = &g_epops;
    +      priv->eplist[epno].dev       = priv;
    +      priv->eplist[epno].ep.eplog  = epno;
    +
    +      /* We will use a fixed maxpacket size for all endpoints (perhaps
    +       * ISOC endpoints could have larger maxpacket???).  A smaller
    +       * packet size can be selected when the endpoint is configured.
    +       */
    +
    +      priv->eplist[epno].ep.maxpacket = STM32F0_MAXPACKET_SIZE;
    +    }
    +
    +  /* Select a smaller endpoint size for EP0 */
    +
    +#if STM32F0_EP0MAXPACKET < STM32F0_MAXPACKET_SIZE
    +  priv->eplist[EP0].ep.maxpacket = STM32F0_EP0MAXPACKET;
    +#endif
    +
    +  /* Configure the USB controller.  USB uses the following GPIO pins:
    +   *
    +   *   PA9  - VBUS
    +   *   PA10 - ID
    +   *   PA11 - DM
    +   *   PA12 - DP
    +   *
    +   * "As soon as the USB is enabled, these pins [DM and DP] are connected to
    +   * the USB internal transceiver automatically."
    +   */
    +
    +  /* Power up the USB controller, holding it in reset.  There is a delay of
    +   * about 1uS after applying power before the USB will behave predictably.
    +   * A 5MS delay is more than enough.  NOTE that we leave the USB controller
    +   * in the reset state; the hardware will not be initialized until the
    +   * class driver has been bound.
    +   */
    +
    +  stm32f0_putreg(USB_CNTR_FRES, STM32F0_USB_CNTR);
    +  up_mdelay(5);
    +}
    +
    +/****************************************************************************
    + * Name: stm32f0_hwshutdown
    + ****************************************************************************/
    +
    +static void stm32f0_hwshutdown(struct stm32f0_usbdev_s *priv)
    +{
    +  priv->usbdev.speed = USB_SPEED_UNKNOWN;
    +
    +  /* Disable all interrupts and force the USB controller into reset */
    +
    +  stm32f0_putreg(USB_CNTR_FRES, STM32F0_USB_CNTR);
    +
    +  /* Clear any pending interrupts */
    +
    +  stm32f0_putreg(0, STM32F0_USB_ISTR);
    +
    +  /* Disconnect the device / disable the pull-up */
    +
    +  stm32f0_usbpullup(&priv->usbdev, false);
    +
    +  /* Power down the USB controller */
    +
    +  stm32f0_putreg(USB_CNTR_FRES | USB_CNTR_PDWN, STM32F0_USB_CNTR);
    +}
    +
    +/****************************************************************************
    + * Public Functions
    + ****************************************************************************/
    +
    +/****************************************************************************
    + * Name: up_usbinitialize
    + * Description:
    + *   Initialize the USB driver
    + * Input Parameters:
    + *   None
    + *
    + * Returned Value:
    + *   None
    + *
    + ****************************************************************************/
    +
    +void up_usbinitialize(void)
    +{
    +  /* For now there is only one USB controller, but we will always refer to
    +   * it using a pointer to make any future ports to multiple USB controllers
    +   * easier.
    +   */
    +
    +  struct stm32f0_usbdev_s *priv = &g_usbdev;
    +  uint32_t regval;
    +
    +  usbtrace(TRACE_DEVINIT, 0);
    +
    +  /* Configure USB GPIO alternate function pins */
    +
    +#ifdef CONFIG_STM32F0_STM32F30XX
    +  (void)stm32f0_configgpio(GPIO_USB_DM);
    +  (void)stm32f0_configgpio(GPIO_USB_DP);
    +#endif
    +
    +  /* Enable clocking to the USB peripheral */
    +
    +  regval  = getreg32(STM32F0_RCC_APB1RSTR);
    +  regval &= ~RCC_APB1ENR_USBEN;
    +  putreg32(regval, STM32F0_RCC_APB1RSTR);
    +
    +  /* Enable HSI48 clocking to to support USB transfers */
    +
    +  stm32f0_enable_hsi48(SYNCSRC_USB);
    +
    +  /* Power up the USB controller, but leave it in the reset state */
    +
    +  stm32f0_hwsetup(priv);
    +
    +  /* Attach USB controller interrupt handlers.  The hardware will not be
    +   * initialized and interrupts will not be enabled until the class device
    +   * driver is bound.  Getting the IRQs here only makes sure that we have
    +   * them when we need them later.
    +   */
    +
    +  if (irq_attach(STM32F0_IRQ_USB, stm32f0_usb_interrupt, priv) != 0)
    +    {
    +      usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_IRQREGISTRATION),
    +               (uint16_t)STM32F0_IRQ_USB);
    +      goto errout;
    +    }
    +
    +  return;
    +
    +errout:
    +  up_usbuninitialize();
    +}
    +
    +/****************************************************************************
    + * Name: up_usbuninitialize
    + * Description:
    + *   Initialize the USB driver
    + * Input Parameters:
    + *   None
    + *
    + * Returned Value:
    + *   None
    + *
    + ****************************************************************************/
    +
    +void up_usbuninitialize(void)
    +{
    +  /* For now there is only one USB controller, but we will always refer to
    +   * it using a pointer to make any future ports to multiple USB controllers
    +   * easier.
    +   */
    +
    +  struct stm32f0_usbdev_s *priv = &g_usbdev;
    +  irqstate_t flags;
    +
    +  flags = enter_critical_section();
    +  usbtrace(TRACE_DEVUNINIT, 0);
    +
    +  /* Disable and detach the USB IRQs */
    +
    +  up_disable_irq(STM32F0_IRQ_USB);
    +  irq_detach(STM32F0_IRQ_USB);
    +
    +  if (priv->driver)
    +    {
    +      usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_DRIVERREGISTERED), 0);
    +      usbdev_unregister(priv->driver);
    +    }
    +
    +  /* Put the hardware in an inactive state */
    +
    +  stm32f0_hwshutdown(priv);
    +  leave_critical_section(flags);
    +}
    +
    +/****************************************************************************
    + * Name: usbdev_register
    + *
    + * Description:
    + *   Register a USB device class driver. The class driver's bind() method will be
    + *   called to bind it to a USB device driver.
    + *
    + ****************************************************************************/
    +
    +int usbdev_register(struct usbdevclass_driver_s *driver)
    +{
    +  /* For now there is only one USB controller, but we will always refer to
    +   * it using a pointer to make any future ports to multiple USB controllers
    +   * easier.
    +   */
    +
    +  struct stm32f0_usbdev_s *priv = &g_usbdev;
    +  int ret;
    +
    +  usbtrace(TRACE_DEVREGISTER, 0);
    +
    +#ifdef CONFIG_DEBUG_USB
    +  if (!driver || !driver->ops->bind || !driver->ops->unbind ||
    +      !driver->ops->disconnect || !driver->ops->setup)
    +    {
    +      usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_INVALIDPARMS), 0);
    +      return -EINVAL;
    +    }
    +
    +  if (priv->driver)
    +    {
    +      usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_DRIVER), 0);
    +      return -EBUSY;
    +    }
    +#endif
    +
    +  /* First hook up the driver */
    +
    +  priv->driver = driver;
    +
    +  /* Then bind the class driver */
    +
    +  ret = CLASS_BIND(driver, &priv->usbdev);
    +  if (ret)
    +    {
    +      usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_BINDFAILED), (uint16_t)-ret);
    +    }
    +  else
    +    {
    +      /* Setup the USB controller -- enabling interrupts at the USB controller */
    +
    +      stm32f0_hwreset(priv);
    +
    +      /* Enable USB controller interrupts at the NVIC */
    +
    +      up_enable_irq(STM32F0_IRQ_USB);
    +
    +#ifdef CONFIG_ARCH_IRQPRIO
    +      /* Set the interrupt priority */
    +
    +      up_prioritize_irq(STM32F0_IRQ_USB, CONFIG_USB_PRI);
    +#endif
    +
    +      /* Enable pull-up to connect the device.  The host should enumerate us
    +       * some time after this
    +       */
    +
    +      stm32f0_usbpullup(&priv->usbdev, true);
    +      priv->usbdev.speed = USB_SPEED_FULL;
    +    }
    +
    +  return ret;
    +}
    +
    +/****************************************************************************
    + * Name: usbdev_unregister
    + *
    + * Description:
    + *   Un-register usbdev class driver. If the USB device is connected to a
    + *   USB host, it will first disconnect().  The driver is also requested to
    + *   unbind() and clean up any device state, before this procedure finally
    + *   returns.
    + *
    + ****************************************************************************/
    +
    +int usbdev_unregister(struct usbdevclass_driver_s *driver)
    +{
    +  /* For now there is only one USB controller, but we will always refer to
    +   * it using a pointer to make any future ports to multiple USB controllers
    +   * easier.
    +   */
    +
    +  struct stm32f0_usbdev_s *priv = &g_usbdev;
    +  irqstate_t flags;
    +
    +  usbtrace(TRACE_DEVUNREGISTER, 0);
    +
    +#ifdef CONFIG_DEBUG_USB
    +  if (driver != priv->driver)
    +    {
    +      usbtrace(TRACE_DEVERROR(STM32F0_TRACEERR_INVALIDPARMS), 0);
    +      return -EINVAL;
    +    }
    +#endif
    +
    +  /* Reset the hardware and cancel all requests.  All requests must be
    +   * canceled while the class driver is still bound.
    +   */
    +
    +  flags = enter_critical_section();
    +  stm32f0_reset(priv);
    +
    +  /* Unbind the class driver */
    +
    +  CLASS_UNBIND(driver, &priv->usbdev);
    +
    +  /* Disable USB controller interrupts (but keep them attached) */
    +
    +  up_disable_irq(STM32F0_IRQ_USB);
    +
    +  /* Put the hardware in an inactive state.  Then bring the hardware back up
    +   * in the reset state (this is probably not necessary, the stm32f0_reset()
    +   * call above was probably sufficient).
    +   */
    +
    +  stm32f0_hwshutdown(priv);
    +  stm32f0_hwsetup(priv);
    +
    +  /* Unhook the driver */
    +
    +  priv->driver = NULL;
    +  leave_critical_section(flags);
    +  return OK;
    +}
    +
    +#endif /* CONFIG_USBDEV && CONFIG_STM32F0_USB */
    diff --git a/arch/arm/src/stm32f0/stm32f0_usbdev.h b/arch/arm/src/stm32f0/stm32f0_usbdev.h
    new file mode 100644
    index 0000000000..fb0398158c
    --- /dev/null
    +++ b/arch/arm/src/stm32f0/stm32f0_usbdev.h
    @@ -0,0 +1,96 @@
    +/************************************************************************************
    + * arch/arm/src/stm32f0/stm32f0_usbdev.h
    + *
    + *   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.
    + *
    + ************************************************************************************/
    +
    +#ifndef __ARCH_ARM_SRC_STM32F0_STM32F0_USBDEV_H
    +#define __ARCH_ARM_SRC_STM32F0_STM32F0_USBDEV_H
    +
    +/************************************************************************************
    + * Included Files
    + ************************************************************************************/
    +
    +#include 
    +#include 
    +#include 
    +
    +#include "chip.h"
    +#include "chip/stm32f0_usbdev.h"
    +
    +/************************************************************************************
    + * Public Functions
    + ************************************************************************************/
    +
    +#ifndef __ASSEMBLY__
    +
    +#undef EXTERN
    +#if defined(__cplusplus)
    +#define EXTERN extern "C"
    +extern "C"
    +{
    +#else
    +#define EXTERN extern
    +#endif
    +
    +/************************************************************************************
    + * Name:  stm32f0_usbpullup
    + *
    + * Description:
    + *   If USB is supported and the board supports a pullup via GPIO (for USB software
    + *   connect and disconnect), then the board software must provide stm32f0_pullup.
    + *   See include/nuttx/usb/usbdev.h for additional description of this method.
    + *
    + ************************************************************************************/
    +
    +int stm32f0_usbpullup(FAR struct usbdev_s *dev,  bool enable);
    +
    +/************************************************************************************
    + * Name:  stm32f0_usbsuspend
    + *
    + * Description:
    + *   Board logic must provide the stm32f0_usbsuspend logic if the USBDEV driver is
    + *   used.  This function is called whenever the USB enters or leaves suspend mode.
    + *   This is an opportunity for the board logic to shutdown clocks, power, etc.
    + *   while the USB is suspended.
    + *
    + ************************************************************************************/
    +
    +void stm32f0_usbsuspend(FAR struct usbdev_s *dev, bool resume);
    +
    +#undef EXTERN
    +#if defined(__cplusplus)
    +}
    +#endif
    +
    +#endif /* __ASSEMBLY__ */
    +#endif /* __ARCH_ARM_SRC_STM32F0_STM32F0_USBDEV_H */
    -- 
    GitLab
    
    
    From d0ec395c4282330749e6191535d8391f8de078e1 Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Thu, 20 Apr 2017 12:39:21 -0600
    Subject: [PATCH 533/990] Correct some spacing and some unused definition in
     some irq.h header files.
    
    ---
     arch/arm/include/lpc11xx/irq.h      |  4 ++--
     arch/arm/include/samdl/samd20_irq.h | 32 ++++++++++++++---------------
     arch/arm/include/samdl/samd21_irq.h | 32 ++++++++++++++---------------
     arch/arm/include/samdl/saml21_irq.h | 32 ++++++++++++++---------------
     arch/arm/include/stm32f0/irq.h      | 12 +++++------
     5 files changed, 56 insertions(+), 56 deletions(-)
    
    diff --git a/arch/arm/include/lpc11xx/irq.h b/arch/arm/include/lpc11xx/irq.h
    index 46ff7d27ca..dad551e5d8 100644
    --- a/arch/arm/include/lpc11xx/irq.h
    +++ b/arch/arm/include/lpc11xx/irq.h
    @@ -109,8 +109,8 @@
     #define LPC11_IRQ_PIO0          (47) /* Vector 47: PIO0 */
     #endif
     
    -#define NR_VECTORS           (64) /* 64 vectors */
    -#define NR_IRQS              (48) /* 64 interrupts but 48 IRQ numbers */
    +#define NR_VECTORS              (48) /* 48 vectors */
    +#define NR_IRQS                 (48) /* 32 interrupts plus 16 exceptions */
     
     /****************************************************************************
      * Public Types
    diff --git a/arch/arm/include/samdl/samd20_irq.h b/arch/arm/include/samdl/samd20_irq.h
    index 709fddaeac..9524b3650c 100644
    --- a/arch/arm/include/samdl/samd20_irq.h
    +++ b/arch/arm/include/samdl/samd20_irq.h
    @@ -82,22 +82,22 @@
     /* GPIO interrupts.  Up to 16 pins may be configured to support interrupts */
     
     #ifdef CONFIG_SAMDL_GPIOIRQ
    -#  define SAM_IRQ_EXTINT0  (SAM_IRQ_NIRQS+0)    /* External interrupt 0 */
    -#  define SAM_IRQ_EXTINT1  (SAM_IRQ_NIRQS+1)    /* External interrupt 1 */
    -#  define SAM_IRQ_EXTINT2  (SAM_IRQ_NIRQS+2)    /* External interrupt 2 */
    -#  define SAM_IRQ_EXTINT3  (SAM_IRQ_NIRQS+3)    /* External interrupt 3 */
    -#  define SAM_IRQ_EXTINT4  (SAM_IRQ_NIRQS+4)    /* External interrupt 4 */
    -#  define SAM_IRQ_EXTINT5  (SAM_IRQ_NIRQS+5)    /* External interrupt 5 */
    -#  define SAM_IRQ_EXTINT6  (SAM_IRQ_NIRQS+6)    /* External interrupt 6 */
    -#  define SAM_IRQ_EXTINT7  (SAM_IRQ_NIRQS+7)    /* External interrupt 7 */
    -#  define SAM_IRQ_EXTINT8  (SAM_IRQ_NIRQS+8)    /* External interrupt 8 */
    -#  define SAM_IRQ_EXTINT9  (SAM_IRQ_NIRQS+9)    /* External interrupt 9 */
    -#  define SAM_IRQ_EXTINT10 (SAM_IRQ_NIRQS+10)   /* External interrupt 10 */
    -#  define SAM_IRQ_EXTINT11 (SAM_IRQ_NIRQS+11)   /* External interrupt 11 */
    -#  define SAM_IRQ_EXTINT12 (SAM_IRQ_NIRQS+12)   /* External interrupt 12 */
    -#  define SAM_IRQ_EXTINT13 (SAM_IRQ_NIRQS+13)   /* External interrupt 13 */
    -#  define SAM_IRQ_EXTINT14 (SAM_IRQ_NIRQS+14)   /* External interrupt 14 */
    -#  define SAM_IRQ_EXTINT15 (SAM_IRQ_NIRQS+15)   /* External interrupt 15 */
    +#  define SAM_IRQ_EXTINT0  (SAM_IRQ_NIRQS+0)       /* External interrupt 0 */
    +#  define SAM_IRQ_EXTINT1  (SAM_IRQ_NIRQS+1)       /* External interrupt 1 */
    +#  define SAM_IRQ_EXTINT2  (SAM_IRQ_NIRQS+2)       /* External interrupt 2 */
    +#  define SAM_IRQ_EXTINT3  (SAM_IRQ_NIRQS+3)       /* External interrupt 3 */
    +#  define SAM_IRQ_EXTINT4  (SAM_IRQ_NIRQS+4)       /* External interrupt 4 */
    +#  define SAM_IRQ_EXTINT5  (SAM_IRQ_NIRQS+5)       /* External interrupt 5 */
    +#  define SAM_IRQ_EXTINT6  (SAM_IRQ_NIRQS+6)       /* External interrupt 6 */
    +#  define SAM_IRQ_EXTINT7  (SAM_IRQ_NIRQS+7)       /* External interrupt 7 */
    +#  define SAM_IRQ_EXTINT8  (SAM_IRQ_NIRQS+8)       /* External interrupt 8 */
    +#  define SAM_IRQ_EXTINT9  (SAM_IRQ_NIRQS+9)       /* External interrupt 9 */
    +#  define SAM_IRQ_EXTINT10 (SAM_IRQ_NIRQS+10)      /* External interrupt 10 */
    +#  define SAM_IRQ_EXTINT11 (SAM_IRQ_NIRQS+11)      /* External interrupt 11 */
    +#  define SAM_IRQ_EXTINT12 (SAM_IRQ_NIRQS+12)      /* External interrupt 12 */
    +#  define SAM_IRQ_EXTINT13 (SAM_IRQ_NIRQS+13)      /* External interrupt 13 */
    +#  define SAM_IRQ_EXTINT14 (SAM_IRQ_NIRQS+14)      /* External interrupt 14 */
    +#  define SAM_IRQ_EXTINT15 (SAM_IRQ_NIRQS+15)      /* External interrupt 15 */
     #  define SAM_IRQ_NEXTINTS 16
     #else
     #  define SAM_IRQ_NEXTINTS 0
    diff --git a/arch/arm/include/samdl/samd21_irq.h b/arch/arm/include/samdl/samd21_irq.h
    index 7b5c633ef6..e0b26bf962 100644
    --- a/arch/arm/include/samdl/samd21_irq.h
    +++ b/arch/arm/include/samdl/samd21_irq.h
    @@ -89,22 +89,22 @@
     /* GPIO interrupts.  Up to 16 pins may be configured to support interrupts */
     
     #ifdef CONFIG_SAMDL_GPIOIRQ
    -#  define SAM_IRQ_EXTINT0  (SAM_IRQ_NIRQS+0)    /* External interrupt 0 */
    -#  define SAM_IRQ_EXTINT1  (SAM_IRQ_NIRQS+1)    /* External interrupt 1 */
    -#  define SAM_IRQ_EXTINT2  (SAM_IRQ_NIRQS+2)    /* External interrupt 2 */
    -#  define SAM_IRQ_EXTINT3  (SAM_IRQ_NIRQS+3)    /* External interrupt 3 */
    -#  define SAM_IRQ_EXTINT4  (SAM_IRQ_NIRQS+4)    /* External interrupt 4 */
    -#  define SAM_IRQ_EXTINT5  (SAM_IRQ_NIRQS+5)    /* External interrupt 5 */
    -#  define SAM_IRQ_EXTINT6  (SAM_IRQ_NIRQS+6)    /* External interrupt 6 */
    -#  define SAM_IRQ_EXTINT7  (SAM_IRQ_NIRQS+7)    /* External interrupt 7 */
    -#  define SAM_IRQ_EXTINT8  (SAM_IRQ_NIRQS+8)    /* External interrupt 8 */
    -#  define SAM_IRQ_EXTINT9  (SAM_IRQ_NIRQS+9)    /* External interrupt 9 */
    -#  define SAM_IRQ_EXTINT10 (SAM_IRQ_NIRQS+10)   /* External interrupt 10 */
    -#  define SAM_IRQ_EXTINT11 (SAM_IRQ_NIRQS+11)   /* External interrupt 11 */
    -#  define SAM_IRQ_EXTINT12 (SAM_IRQ_NIRQS+12)   /* External interrupt 12 */
    -#  define SAM_IRQ_EXTINT13 (SAM_IRQ_NIRQS+13)   /* External interrupt 13 */
    -#  define SAM_IRQ_EXTINT14 (SAM_IRQ_NIRQS+14)   /* External interrupt 14 */
    -#  define SAM_IRQ_EXTINT15 (SAM_IRQ_NIRQS+15)   /* External interrupt 15 */
    +#  define SAM_IRQ_EXTINT0  (SAM_IRQ_NIRQS+0)       /* External interrupt 0 */
    +#  define SAM_IRQ_EXTINT1  (SAM_IRQ_NIRQS+1)       /* External interrupt 1 */
    +#  define SAM_IRQ_EXTINT2  (SAM_IRQ_NIRQS+2)       /* External interrupt 2 */
    +#  define SAM_IRQ_EXTINT3  (SAM_IRQ_NIRQS+3)       /* External interrupt 3 */
    +#  define SAM_IRQ_EXTINT4  (SAM_IRQ_NIRQS+4)       /* External interrupt 4 */
    +#  define SAM_IRQ_EXTINT5  (SAM_IRQ_NIRQS+5)       /* External interrupt 5 */
    +#  define SAM_IRQ_EXTINT6  (SAM_IRQ_NIRQS+6)       /* External interrupt 6 */
    +#  define SAM_IRQ_EXTINT7  (SAM_IRQ_NIRQS+7)       /* External interrupt 7 */
    +#  define SAM_IRQ_EXTINT8  (SAM_IRQ_NIRQS+8)       /* External interrupt 8 */
    +#  define SAM_IRQ_EXTINT9  (SAM_IRQ_NIRQS+9)       /* External interrupt 9 */
    +#  define SAM_IRQ_EXTINT10 (SAM_IRQ_NIRQS+10)      /* External interrupt 10 */
    +#  define SAM_IRQ_EXTINT11 (SAM_IRQ_NIRQS+11)      /* External interrupt 11 */
    +#  define SAM_IRQ_EXTINT12 (SAM_IRQ_NIRQS+12)      /* External interrupt 12 */
    +#  define SAM_IRQ_EXTINT13 (SAM_IRQ_NIRQS+13)      /* External interrupt 13 */
    +#  define SAM_IRQ_EXTINT14 (SAM_IRQ_NIRQS+14)      /* External interrupt 14 */
    +#  define SAM_IRQ_EXTINT15 (SAM_IRQ_NIRQS+15)      /* External interrupt 15 */
     #  define SAM_IRQ_NEXTINTS 16
     #else
     #  define SAM_IRQ_NEXTINTS 0
    diff --git a/arch/arm/include/samdl/saml21_irq.h b/arch/arm/include/samdl/saml21_irq.h
    index 24c774dbd0..467708baa9 100644
    --- a/arch/arm/include/samdl/saml21_irq.h
    +++ b/arch/arm/include/samdl/saml21_irq.h
    @@ -90,22 +90,22 @@
     /* GPIO interrupts.  Up to 16 pins may be configured to support interrupts */
     
     #ifdef CONFIG_SAMDL_GPIOIRQ
    -#  define SAM_IRQ_EXTINT0  (SAM_IRQ_NIRQS+0)    /* External interrupt 0 */
    -#  define SAM_IRQ_EXTINT1  (SAM_IRQ_NIRQS+1)    /* External interrupt 1 */
    -#  define SAM_IRQ_EXTINT2  (SAM_IRQ_NIRQS+2)    /* External interrupt 2 */
    -#  define SAM_IRQ_EXTINT3  (SAM_IRQ_NIRQS+3)    /* External interrupt 3 */
    -#  define SAM_IRQ_EXTINT4  (SAM_IRQ_NIRQS+4)    /* External interrupt 4 */
    -#  define SAM_IRQ_EXTINT5  (SAM_IRQ_NIRQS+5)    /* External interrupt 5 */
    -#  define SAM_IRQ_EXTINT6  (SAM_IRQ_NIRQS+6)    /* External interrupt 6 */
    -#  define SAM_IRQ_EXTINT7  (SAM_IRQ_NIRQS+7)    /* External interrupt 7 */
    -#  define SAM_IRQ_EXTINT8  (SAM_IRQ_NIRQS+8)    /* External interrupt 8 */
    -#  define SAM_IRQ_EXTINT9  (SAM_IRQ_NIRQS+9)    /* External interrupt 9 */
    -#  define SAM_IRQ_EXTINT10 (SAM_IRQ_NIRQS+10)   /* External interrupt 10 */
    -#  define SAM_IRQ_EXTINT11 (SAM_IRQ_NIRQS+11)   /* External interrupt 11 */
    -#  define SAM_IRQ_EXTINT12 (SAM_IRQ_NIRQS+12)   /* External interrupt 12 */
    -#  define SAM_IRQ_EXTINT13 (SAM_IRQ_NIRQS+13)   /* External interrupt 13 */
    -#  define SAM_IRQ_EXTINT14 (SAM_IRQ_NIRQS+14)   /* External interrupt 14 */
    -#  define SAM_IRQ_EXTINT15 (SAM_IRQ_NIRQS+15)   /* External interrupt 15 */
    +#  define SAM_IRQ_EXTINT0  (SAM_IRQ_NIRQS+0)       /* External interrupt 0 */
    +#  define SAM_IRQ_EXTINT1  (SAM_IRQ_NIRQS+1)       /* External interrupt 1 */
    +#  define SAM_IRQ_EXTINT2  (SAM_IRQ_NIRQS+2)       /* External interrupt 2 */
    +#  define SAM_IRQ_EXTINT3  (SAM_IRQ_NIRQS+3)       /* External interrupt 3 */
    +#  define SAM_IRQ_EXTINT4  (SAM_IRQ_NIRQS+4)       /* External interrupt 4 */
    +#  define SAM_IRQ_EXTINT5  (SAM_IRQ_NIRQS+5)       /* External interrupt 5 */
    +#  define SAM_IRQ_EXTINT6  (SAM_IRQ_NIRQS+6)       /* External interrupt 6 */
    +#  define SAM_IRQ_EXTINT7  (SAM_IRQ_NIRQS+7)       /* External interrupt 7 */
    +#  define SAM_IRQ_EXTINT8  (SAM_IRQ_NIRQS+8)       /* External interrupt 8 */
    +#  define SAM_IRQ_EXTINT9  (SAM_IRQ_NIRQS+9)       /* External interrupt 9 */
    +#  define SAM_IRQ_EXTINT10 (SAM_IRQ_NIRQS+10)      /* External interrupt 10 */
    +#  define SAM_IRQ_EXTINT11 (SAM_IRQ_NIRQS+11)      /* External interrupt 11 */
    +#  define SAM_IRQ_EXTINT12 (SAM_IRQ_NIRQS+12)      /* External interrupt 12 */
    +#  define SAM_IRQ_EXTINT13 (SAM_IRQ_NIRQS+13)      /* External interrupt 13 */
    +#  define SAM_IRQ_EXTINT14 (SAM_IRQ_NIRQS+14)      /* External interrupt 14 */
    +#  define SAM_IRQ_EXTINT15 (SAM_IRQ_NIRQS+15)      /* External interrupt 15 */
     #  define SAM_IRQ_NEXTINTS 16
     #else
     #  define SAM_IRQ_NEXTINTS 0
    diff --git a/arch/arm/include/stm32f0/irq.h b/arch/arm/include/stm32f0/irq.h
    index 298def1fa0..196a3f294b 100644
    --- a/arch/arm/include/stm32f0/irq.h
    +++ b/arch/arm/include/stm32f0/irq.h
    @@ -61,13 +61,13 @@
     /* Common Processor Exceptions (vectors 0-15) */
     
     #define STM32F0_IRQ_RESERVED       (0) /* Reserved vector (only used with CONFIG_DEBUG_FEATURES) */
    -                                        /* Vector  0: Reset stack pointer value */
    -                                        /* Vector  1: Reset (not handler as an IRQ) */
    +                                       /* Vector  0: Reset stack pointer value */
    +                                       /* Vector  1: Reset (not handler as an IRQ) */
     #define STM32F0_IRQ_NMI            (2) /* Vector  2: Non-Maskable Interrupt (NMI) */
     #define STM32F0_IRQ_HARDFAULT      (3) /* Vector  3: Hard fault */
    -                                        /* Vectors 4-10: Reserved */
    +                                       /* Vectors 4-10: Reserved */
     #define STM32F0_IRQ_SVCALL        (11) /* Vector 11: SVC call */
    -                                        /* Vector 12-13: Reserved */
    +                                       /* Vector 12-13: Reserved */
     #define STM32F0_IRQ_PENDSV        (14) /* Vector 14: Pendable system service request */
     #define STM32F0_IRQ_SYSTICK       (15) /* Vector 15: System tick */
     
    @@ -108,8 +108,8 @@
     #define STM32F0_IRQ_CEC_CAN       (46) /* Vector 46: HDMI CEC and CAN */
     #define STM32F0_IRQ_USB           (47) /* Vector 47: USB */
     
    -#define NR_VECTORS           (64) /* 64 vectors */
    -#define NR_IRQS              (48) /* 64 interrupts but 48 IRQ numbers */
    +#define NR_VECTORS                (48) /* 48 vectors */
    +#define NR_IRQS                   (48) /* 32 interrupts plus 16 exceptions */
     
     /****************************************************************************
      * Public Types
    -- 
    GitLab
    
    
    From 73c7f05a3cf68e00444494a497c7a7c6697100c5 Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Thu, 20 Apr 2017 14:08:08 -0600
    Subject: [PATCH 534/990] Cosmetic changes to spacing and comments.
    
    ---
     arch/arm/include/nuc1xx/nuc120_irq.h | 8 ++++----
     arch/arm/src/stm32f0/stm32f0_hsi48.c | 2 +-
     2 files changed, 5 insertions(+), 5 deletions(-)
    
    diff --git a/arch/arm/include/nuc1xx/nuc120_irq.h b/arch/arm/include/nuc1xx/nuc120_irq.h
    index 5310b2cd8e..fa287c05d3 100644
    --- a/arch/arm/include/nuc1xx/nuc120_irq.h
    +++ b/arch/arm/include/nuc1xx/nuc120_irq.h
    @@ -52,10 +52,10 @@
     
     #define NUC_IRQ_BOD    (16) /* Brown-out low voltage detected */
     #define NUC_IRQ_WDT    (17) /* Watchdog Timer */
    -#define NUC_IRQ_EINT0  (18) /* Eternal interrupt from PB.14 */
    -#define NUC_IRQ_EINT1  (19) /* Eternal interrupt from PB.15 */
    -#define NUC_IRQ_GPAB   (20) /* Eternal interrupt from PA[15:0]/PB[13:0] */
    -#define NUC_IRQ_GPCDE  (21) /* Eternal interrupt from PC[15:0]/PD[15:0]/PE[15:0] */
    +#define NUC_IRQ_EINT0  (18) /* External interrupt from PB.14 */
    +#define NUC_IRQ_EINT1  (19) /* External interrupt from PB.15 */
    +#define NUC_IRQ_GPAB   (20) /* External interrupt from PA[15:0]/PB[13:0] */
    +#define NUC_IRQ_GPCDE  (21) /* External interrupt from PC[15:0]/PD[15:0]/PE[15:0] */
     #define NUC_IRQ_PWMA   (22) /* PWM0-3 */
     #define NUC_IRQ_PWMB   (23) /* PWM4-7 */
     #define NUC_IRQ_TMR0   (24) /* Timer 0 */
    diff --git a/arch/arm/src/stm32f0/stm32f0_hsi48.c b/arch/arm/src/stm32f0/stm32f0_hsi48.c
    index 73c46e5f63..f9d4c52cf6 100644
    --- a/arch/arm/src/stm32f0/stm32f0_hsi48.c
    +++ b/arch/arm/src/stm32f0/stm32f0_hsi48.c
    @@ -101,7 +101,7 @@ void stm32f0_enable_hsi48(enum syncsrc_e syncsrc)
         {
           /* Select the HSI48 as the USB clock source */
     
    -      regval = getreg32(STM32F0_RCC_CFGR3);
    +      regval  = getreg32(STM32F0_RCC_CFGR3);
           regval &= ~RCC_CFGR3_USBSW;
           putreg32(regval, STM32F0_RCC_CFGR3);
         }
    -- 
    GitLab
    
    
    From bcc6b61fc1977177ca3e4115cb3bf3aa6c77f895 Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Thu, 20 Apr 2017 14:53:30 -0600
    Subject: [PATCH 535/990] Move include/nuttx/net/iob.h to
     include/drivers/iob.h; rename CONFIG_NET_IOB to CONFIG_DRIVERS_IOB
    
    ---
     configs/bambino-200e/netnsh/defconfig         | 23 +++++++++--
     configs/c5471evm/httpd/defconfig              | 23 +++++++++--
     configs/c5471evm/nettest/defconfig            | 24 +++++++++--
     configs/c5471evm/nsh/defconfig                | 23 +++++++++--
     configs/cloudctrl/nsh/defconfig               | 37 +++++++++++++++--
     configs/dk-tm4c129x/ipv6/defconfig            | 24 ++++++++++-
     configs/dk-tm4c129x/nsh/defconfig             | 24 ++++++++++-
     configs/eagle100/httpd/defconfig              | 23 +++++++++--
     configs/eagle100/nettest/defconfig            | 24 +++++++++--
     configs/eagle100/nsh/defconfig                | 23 +++++++++--
     configs/eagle100/thttpd/defconfig             | 22 ++++++++--
     configs/ekk-lm3s9b96/nsh/defconfig            | 23 +++++++++--
     configs/ez80f910200zco/dhcpd/defconfig        | 18 +++++++--
     configs/ez80f910200zco/httpd/defconfig        | 19 ++++++++-
     configs/ez80f910200zco/nettest/defconfig      | 20 ++++++++--
     configs/ez80f910200zco/nsh/defconfig          | 19 ++++++++-
     configs/ez80f910200zco/poll/defconfig         | 19 ++++++++-
     configs/fire-stm32v2/nsh/defconfig            | 37 +++++++++++++++--
     configs/freedom-k64f/netnsh/defconfig         | 21 +++++++++-
     configs/freedom-k66f/netnsh/defconfig         | 21 +++++++++-
     configs/lincoln60/netnsh/defconfig            | 23 +++++++++--
     configs/lincoln60/thttpd-binfs/defconfig      | 22 ++++++++--
     configs/lm3s6432-s2e/nsh/defconfig            | 23 +++++++++--
     configs/lm3s6965-ek/discover/defconfig        | 23 +++++++++--
     configs/lm3s6965-ek/nsh/defconfig             | 23 +++++++++--
     configs/lm3s6965-ek/tcpecho/defconfig         | 24 +++++++++--
     configs/lm3s8962-ek/nsh/defconfig             | 23 +++++++++--
     configs/lpcxpresso-lpc1768/dhcpd/defconfig    | 22 ++++++++--
     configs/lpcxpresso-lpc1768/nsh/defconfig      | 23 +++++++++--
     configs/lpcxpresso-lpc1768/thttpd/defconfig   | 22 ++++++++--
     configs/misoc/hello/defconfig                 | 21 +++++++++-
     configs/moxa/nsh/defconfig                    | 23 +++++++++--
     configs/ntosd-dm320/nettest/defconfig         | 24 +++++++++--
     configs/ntosd-dm320/nsh/defconfig             | 23 +++++++++--
     configs/ntosd-dm320/poll/defconfig            | 23 +++++++++--
     configs/ntosd-dm320/thttpd/defconfig          | 22 ++++++++--
     configs/ntosd-dm320/udp/defconfig             | 22 ++++++++--
     configs/ntosd-dm320/webserver/defconfig       | 23 +++++++++--
     configs/olimex-lpc1766stk/ftpc/defconfig      | 23 +++++++++--
     configs/olimex-lpc1766stk/hidmouse/defconfig  | 24 +++++++++--
     configs/olimex-lpc1766stk/nettest/defconfig   | 24 +++++++++--
     configs/olimex-lpc1766stk/nsh/defconfig       | 23 +++++++++--
     .../olimex-lpc1766stk/slip-httpd/defconfig    | 22 ++++++++--
     .../olimex-lpc1766stk/thttpd-binfs/defconfig  | 22 ++++++++--
     .../olimex-lpc1766stk/thttpd-nxflat/defconfig | 22 ++++++++--
     configs/olimex-lpc1766stk/zmodem/defconfig    | 23 +++++++++--
     configs/olimex-stm32-e407/discover/defconfig  | 37 +++++++++++++++--
     configs/olimex-stm32-e407/netnsh/defconfig    | 37 +++++++++++++++--
     configs/olimex-stm32-e407/telnetd/defconfig   | 37 +++++++++++++++--
     configs/olimex-stm32-e407/webserver/defconfig | 37 +++++++++++++++--
     configs/olimex-stm32-p107/nsh/defconfig       | 37 +++++++++++++++--
     configs/olimex-stm32-p207/nsh/defconfig       |  5 ++-
     configs/olimex-strp711/nettest/defconfig      | 25 ++++++++++--
     configs/pic32mx-starterkit/nsh2/defconfig     | 19 ++++++++-
     configs/pic32mx7mmb/nsh/defconfig             | 19 ++++++++-
     configs/sam4e-ek/nsh/defconfig                | 23 +++++++++--
     configs/sam4e-ek/nxwm/defconfig               | 24 +++++++++--
     configs/sam4e-ek/usbnsh/defconfig             | 23 +++++++++--
     configs/sama5d3-xplained/bridge/defconfig     | 23 +++++++++--
     configs/sama5d4-ek/bridge/defconfig           | 23 +++++++++--
     configs/sama5d4-ek/ipv6/defconfig             | 24 +++++++++--
     configs/sama5d4-ek/nsh/defconfig              | 24 +++++++++--
     configs/sama5d4-ek/nxwm/defconfig             | 24 +++++++++--
     configs/same70-xplained/netnsh/defconfig      | 21 +++++++++-
     configs/samv71-xult/netnsh/defconfig          | 15 ++++++-
     configs/samv71-xult/vnc/defconfig             | 21 +++++++++-
     configs/samv71-xult/vnxwm/defconfig           | 21 +++++++++-
     configs/shenzhou/nsh/defconfig                | 37 +++++++++++++++--
     configs/shenzhou/nxwm/defconfig               | 37 +++++++++++++++--
     configs/shenzhou/thttpd/defconfig             | 37 +++++++++++++++--
     configs/sim/nettest/defconfig                 |  8 +++-
     configs/sim/sixlowpan/defconfig               | 10 +++--
     configs/sim/udgram/defconfig                  |  6 ++-
     configs/sim/ustream/defconfig                 |  6 ++-
     configs/stm3220g-eval/dhcpd/defconfig         | 36 ++++++++++++++---
     configs/stm3220g-eval/nettest/defconfig       | 38 +++++++++++++++---
     configs/stm3220g-eval/nsh/defconfig           | 38 ++++++++++++++++--
     configs/stm3220g-eval/nsh2/defconfig          | 38 ++++++++++++++++--
     configs/stm3220g-eval/nxwm/defconfig          | 38 ++++++++++++++++--
     configs/stm3220g-eval/telnetd/defconfig       | 36 ++++++++++++++---
     configs/stm3240g-eval/dhcpd/defconfig         | 36 ++++++++++++++---
     configs/stm3240g-eval/discover/defconfig      | 37 +++++++++++++++--
     configs/stm3240g-eval/nettest/defconfig       | 38 +++++++++++++++---
     configs/stm3240g-eval/nsh/defconfig           | 38 ++++++++++++++++--
     configs/stm3240g-eval/nsh2/defconfig          | 38 ++++++++++++++++--
     configs/stm3240g-eval/nxterm/defconfig        | 38 ++++++++++++++++--
     configs/stm3240g-eval/nxwm/defconfig          | 38 ++++++++++++++++--
     configs/stm3240g-eval/telnetd/defconfig       | 36 ++++++++++++++---
     configs/stm3240g-eval/webserver/defconfig     | 40 +++++++++++++++++--
     configs/stm3240g-eval/xmlrpc/defconfig        | 38 ++++++++++++++++--
     configs/stm32butterfly2/nshnet/defconfig      |  5 ++-
     configs/stm32f4discovery/ipv6/defconfig       | 38 ++++++++++++++++--
     configs/stm32f4discovery/netnsh/defconfig     | 36 +++++++++++++++--
     configs/tm4c1294-launchpad/ipv6/defconfig     | 21 +++++++++-
     configs/tm4c1294-launchpad/nsh/defconfig      | 21 +++++++++-
     configs/twr-k64f120m/netnsh/defconfig         | 23 +++++++++--
     configs/u-blox-c027/nsh/defconfig             | 23 +++++++++--
     configs/viewtool-stm32f107/netnsh/defconfig   | 37 +++++++++++++++--
     configs/zkit-arm-1769/hello/defconfig         | 22 ++++++++--
     configs/zkit-arm-1769/nsh/defconfig           | 23 +++++++++--
     configs/zkit-arm-1769/nxhello/defconfig       | 23 +++++++++--
     configs/zkit-arm-1769/thttpd/defconfig        | 22 ++++++++--
     include/nuttx/{net => drivers}/iob.h          | 32 ++++++---------
     include/nuttx/net/sixlowpan.h                 |  4 +-
     net/devif/Make.defs                           |  2 +-
     net/devif/devif.h                             |  2 +-
     net/devif/devif_iobsend.c                     |  6 +--
     net/iob/Kconfig                               |  6 +--
     net/iob/Make.defs                             |  2 +-
     net/iob/iob.h                                 |  6 +--
     net/iob/iob_add_queue.c                       |  2 +-
     net/iob/iob_alloc.c                           |  2 +-
     net/iob/iob_alloc_qentry.c                    |  2 +-
     net/iob/iob_clone.c                           |  2 +-
     net/iob/iob_concat.c                          |  2 +-
     net/iob/iob_contig.c                          |  2 +-
     net/iob/iob_copyin.c                          |  2 +-
     net/iob/iob_copyout.c                         |  2 +-
     net/iob/iob_dump.c                            |  2 +-
     net/iob/iob_free.c                            |  2 +-
     net/iob/iob_free_chain.c                      |  2 +-
     net/iob/iob_free_qentry.c                     |  2 +-
     net/iob/iob_free_queue.c                      |  2 +-
     net/iob/iob_initialize.c                      |  2 +-
     net/iob/iob_pack.c                            |  2 +-
     net/iob/iob_peek_queue.c                      |  2 +-
     net/iob/iob_remove_queue.c                    |  2 +-
     net/iob/iob_trimhead.c                        |  2 +-
     net/iob/iob_trimhead_queue.c                  |  2 +-
     net/iob/iob_trimtail.c                        |  2 +-
     net/net_initialize.c                          |  4 +-
     net/socket/recvfrom.c                         |  2 +-
     net/tcp/Kconfig                               |  4 +-
     net/tcp/tcp.h                                 |  2 +-
     net/tcp/tcp_send_buffered.c                   |  2 +-
     net/tcp/tcp_wrbuffer.c                        |  2 +-
     net/tcp/tcp_wrbuffer_dump.c                   |  2 +-
     net/udp/Kconfig                               |  2 +-
     net/udp/udp.h                                 |  2 +-
     139 files changed, 2343 insertions(+), 393 deletions(-)
     rename include/nuttx/{net => drivers}/iob.h (95%)
    
    diff --git a/configs/bambino-200e/netnsh/defconfig b/configs/bambino-200e/netnsh/defconfig
    index a064c25486..5461560e92 100644
    --- a/configs/bambino-200e/netnsh/defconfig
    +++ b/configs/bambino-200e/netnsh/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     CONFIG_ARCH_CHIP_LPC43XX=y
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_LPC43XX=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -402,6 +404,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -628,6 +632,7 @@ CONFIG_UART1_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -668,10 +673,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -702,6 +709,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=40
     CONFIG_NET_MAX_LISTENPORTS=40
    @@ -716,6 +724,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -745,10 +754,14 @@ CONFIG_NET_ARP_IPIN=y
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -986,7 +999,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1020,6 +1032,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -1251,3 +1264,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/c5471evm/httpd/defconfig b/configs/c5471evm/httpd/defconfig
    index d72ae45b16..384749cd6e 100644
    --- a/configs/c5471evm/httpd/defconfig
    +++ b/configs/c5471evm/httpd/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_C5471=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_C5471=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     CONFIG_ARCH_ARM7TDMI=y
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -290,6 +292,8 @@ CONFIG_MAX_TASKS=64
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -458,6 +462,7 @@ CONFIG_OTHER_SERIAL_CONSOLE=y
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -498,10 +503,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -532,6 +539,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=16
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -546,6 +554,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     # CONFIG_NET_UDP is not set
    +# CONFIG_NET_UDP_NO_STACK is not set
     
     #
     # ICMP Networking Support
    @@ -570,10 +579,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -773,7 +786,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -808,6 +820,7 @@ CONFIG_EXAMPLES_WEBSERVER_DRIPADDR=0x0a000001
     CONFIG_EXAMPLES_WEBSERVER_NETMASK=0xffffff00
     CONFIG_EXAMPLES_WEBSERVER_NOMAC=y
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -894,3 +907,7 @@ CONFIG_NETUTILS_HTTPD_KEEPALIVE_DISABLE=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/c5471evm/nettest/defconfig b/configs/c5471evm/nettest/defconfig
    index 4bb2fcdcdd..5e09afbe28 100644
    --- a/configs/c5471evm/nettest/defconfig
    +++ b/configs/c5471evm/nettest/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_C5471=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_C5471=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     CONFIG_ARCH_ARM7TDMI=y
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -284,7 +286,6 @@ CONFIG_TASK_NAME_SIZE=0
     CONFIG_MAX_TASKS=64
     # CONFIG_SCHED_HAVE_PARENT is not set
     # CONFIG_SCHED_WAITPID is not set
    -# CONFIG_CANCELLATION_POINTS is not set
     
     #
     # Performance Monitoring
    @@ -449,6 +450,7 @@ CONFIG_OTHER_SERIAL_CONSOLE=y
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -489,10 +491,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -523,6 +527,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -537,6 +542,7 @@ CONFIG_NET_TCP_RECVDELAY=0
     # UDP Networking
     #
     # CONFIG_NET_UDP is not set
    +# CONFIG_NET_UDP_NO_STACK is not set
     
     #
     # ICMP Networking Support
    @@ -561,10 +567,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -764,6 +774,8 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     CONFIG_EXAMPLES_NETTEST=y
    +CONFIG_EXAMPLES_NETTEST_STACKSIZE=2048
    +CONFIG_EXAMPLES_NETTEST_PRIORITY=100
     # CONFIG_EXAMPLES_NETTEST_SERVER is not set
     # CONFIG_EXAMPLES_NETTEST_PERFORMANCE is not set
     CONFIG_EXAMPLES_NETTEST_IPv4=y
    @@ -777,7 +789,6 @@ CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002
     CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001
     CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00
     CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -808,6 +819,7 @@ CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -883,3 +895,7 @@ CONFIG_NETUTILS_NETLIB=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/c5471evm/nsh/defconfig b/configs/c5471evm/nsh/defconfig
    index 014118ad61..c00123dcc9 100644
    --- a/configs/c5471evm/nsh/defconfig
    +++ b/configs/c5471evm/nsh/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_C5471=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_C5471=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     CONFIG_ARCH_ARM7TDMI=y
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -290,6 +292,8 @@ CONFIG_MAX_TASKS=16
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -459,6 +463,7 @@ CONFIG_OTHER_SERIAL_CONSOLE=y
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -499,10 +504,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -533,6 +540,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -547,6 +555,7 @@ CONFIG_NET_TCP_RECVDELAY=0
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -576,10 +585,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -787,7 +800,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -820,6 +832,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1034,3 +1047,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/cloudctrl/nsh/defconfig b/configs/cloudctrl/nsh/defconfig
    index 9f9139982a..1ee28dce24 100644
    --- a/configs/cloudctrl/nsh/defconfig
    +++ b/configs/cloudctrl/nsh/defconfig
    @@ -96,6 +96,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -103,11 +104,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     CONFIG_ARCH_CHIP_STM32=y
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -182,6 +184,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -381,9 +386,13 @@ CONFIG_STM32_HAVE_ADC2=y
     # CONFIG_STM32_HAVE_SDADC3_DMA is not set
     CONFIG_STM32_HAVE_CAN1=y
     CONFIG_STM32_HAVE_CAN2=y
    +# CONFIG_STM32_HAVE_COMP1 is not set
     # CONFIG_STM32_HAVE_COMP2 is not set
    +# CONFIG_STM32_HAVE_COMP3 is not set
     # CONFIG_STM32_HAVE_COMP4 is not set
    +# CONFIG_STM32_HAVE_COMP5 is not set
     # CONFIG_STM32_HAVE_COMP6 is not set
    +# CONFIG_STM32_HAVE_COMP7 is not set
     CONFIG_STM32_HAVE_DAC1=y
     CONFIG_STM32_HAVE_DAC2=y
     # CONFIG_STM32_HAVE_RNG is not set
    @@ -397,7 +406,10 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_HAVE_SPI6 is not set
     # CONFIG_STM32_HAVE_SAIPLL is not set
     # CONFIG_STM32_HAVE_I2SPLL is not set
    -# CONFIG_STM32_HAVE_OPAMP is not set
    +# CONFIG_STM32_HAVE_OPAMP1 is not set
    +# CONFIG_STM32_HAVE_OPAMP2 is not set
    +# CONFIG_STM32_HAVE_OPAMP3 is not set
    +# CONFIG_STM32_HAVE_OPAMP4 is not set
     # CONFIG_STM32_ADC1 is not set
     # CONFIG_STM32_ADC2 is not set
     CONFIG_STM32_BKP=y
    @@ -410,6 +422,7 @@ CONFIG_STM32_BKP=y
     # CONFIG_STM32_DAC2 is not set
     CONFIG_STM32_ETHMAC=y
     # CONFIG_STM32_I2C1 is not set
    +# CONFIG_STM32_OPAMP is not set
     # CONFIG_STM32_OTGFS is not set
     CONFIG_STM32_PWR=y
     CONFIG_STM32_SPI1=y
    @@ -439,6 +452,7 @@ CONFIG_STM32_SPI=y
     CONFIG_STM32_ETH_REMAP=y
     # CONFIG_STM32_SPI1_REMAP is not set
     CONFIG_STM32_USART2_REMAP=y
    +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set
     # CONFIG_STM32_JTAG_DISABLE is not set
     CONFIG_STM32_JTAG_FULL_ENABLE=y
     # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
    @@ -663,6 +677,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -914,6 +930,7 @@ CONFIG_USART2_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -954,10 +971,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -988,6 +1007,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=40
     CONFIG_NET_MAX_LISTENPORTS=40
    @@ -1002,6 +1022,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     # CONFIG_NET_BROADCAST is not set
    @@ -1031,10 +1052,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1287,7 +1312,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1321,6 +1345,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -1545,3 +1570,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/dk-tm4c129x/ipv6/defconfig b/configs/dk-tm4c129x/ipv6/defconfig
    index 36d1a16a75..4b327ef4d0 100644
    --- a/configs/dk-tm4c129x/ipv6/defconfig
    +++ b/configs/dk-tm4c129x/ipv6/defconfig
    @@ -95,6 +95,7 @@ CONFIG_ARCH_CHIP_TIVA=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -102,11 +103,12 @@ CONFIG_ARCH_CHIP_TIVA=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -420,6 +422,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -582,11 +586,14 @@ CONFIG_SENSORS=y
     # CONFIG_BH1750FVI is not set
     # CONFIG_BMG160 is not set
     # CONFIG_BMP180 is not set
    +# CONFIG_HTS221 is not set
     # CONFIG_SENSORS_L3GD20 is not set
     # CONFIG_SENSOR_KXTJ9 is not set
    +# CONFIG_LIS2DH is not set
     # CONFIG_LIS3DSH is not set
     # CONFIG_LIS331DL is not set
     # CONFIG_SN_LSM9DS1 is not set
    +# CONFIG_LPS25H is not set
     # CONFIG_MB7040 is not set
     # CONFIG_MLX90393 is not set
     # CONFIG_MCP9844 is not set
    @@ -657,6 +664,7 @@ CONFIG_UART0_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -697,6 +705,7 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
    @@ -733,6 +742,7 @@ CONFIG_NET_SOLINGER=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=20
    @@ -747,6 +757,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -776,11 +787,15 @@ CONFIG_ICMPv6_NEIGHBOR_DELAYMSEC=20
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=36
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
     CONFIG_IOB_THROTTLE=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1033,6 +1048,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1277,3 +1293,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/dk-tm4c129x/nsh/defconfig b/configs/dk-tm4c129x/nsh/defconfig
    index 6e33f59d6d..617b987820 100644
    --- a/configs/dk-tm4c129x/nsh/defconfig
    +++ b/configs/dk-tm4c129x/nsh/defconfig
    @@ -95,6 +95,7 @@ CONFIG_ARCH_CHIP_TIVA=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -102,11 +103,12 @@ CONFIG_ARCH_CHIP_TIVA=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -420,6 +422,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -584,11 +588,14 @@ CONFIG_SENSORS=y
     # CONFIG_BH1750FVI is not set
     # CONFIG_BMG160 is not set
     # CONFIG_BMP180 is not set
    +# CONFIG_HTS221 is not set
     # CONFIG_SENSORS_L3GD20 is not set
     # CONFIG_SENSOR_KXTJ9 is not set
    +# CONFIG_LIS2DH is not set
     # CONFIG_LIS3DSH is not set
     # CONFIG_LIS331DL is not set
     # CONFIG_SN_LSM9DS1 is not set
    +# CONFIG_LPS25H is not set
     # CONFIG_MB7040 is not set
     # CONFIG_MLX90393 is not set
     # CONFIG_MCP9844 is not set
    @@ -659,6 +666,7 @@ CONFIG_UART0_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -699,6 +707,7 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
    @@ -734,6 +743,7 @@ CONFIG_NET_SOLINGER=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=20
    @@ -748,6 +758,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     # CONFIG_NET_UDP_CHECKSUMS is not set
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -779,11 +790,15 @@ CONFIG_ARP_SEND_DELAYMSEC=20
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=36
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
     CONFIG_IOB_THROTTLE=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1043,6 +1058,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1277,3 +1293,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/eagle100/httpd/defconfig b/configs/eagle100/httpd/defconfig
    index d12c0f1530..7d8d5fba78 100644
    --- a/configs/eagle100/httpd/defconfig
    +++ b/configs/eagle100/httpd/defconfig
    @@ -95,6 +95,7 @@ CONFIG_ARCH_CHIP_LM=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -102,11 +103,12 @@ CONFIG_ARCH_CHIP_LM=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -394,6 +396,8 @@ CONFIG_MAX_TASKS=8
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=0
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -592,6 +596,7 @@ CONFIG_UART0_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -632,10 +637,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -666,6 +673,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=16
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -680,6 +688,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     # CONFIG_NET_UDP is not set
    +# CONFIG_NET_UDP_NO_STACK is not set
     
     #
     # ICMP Networking Support
    @@ -704,10 +713,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -908,7 +921,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -943,6 +955,7 @@ CONFIG_EXAMPLES_WEBSERVER_DRIPADDR=0x0a000001
     CONFIG_EXAMPLES_WEBSERVER_NETMASK=0xffffff00
     CONFIG_EXAMPLES_WEBSERVER_NOMAC=y
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1029,3 +1042,7 @@ CONFIG_NETUTILS_HTTPD_KEEPALIVE_DISABLE=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/eagle100/nettest/defconfig b/configs/eagle100/nettest/defconfig
    index 0598b1e641..443f3ecbac 100644
    --- a/configs/eagle100/nettest/defconfig
    +++ b/configs/eagle100/nettest/defconfig
    @@ -95,6 +95,7 @@ CONFIG_ARCH_CHIP_LM=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -102,11 +103,12 @@ CONFIG_ARCH_CHIP_LM=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -388,7 +390,6 @@ CONFIG_TASK_NAME_SIZE=0
     CONFIG_MAX_TASKS=8
     # CONFIG_SCHED_HAVE_PARENT is not set
     # CONFIG_SCHED_WAITPID is not set
    -# CONFIG_CANCELLATION_POINTS is not set
     
     #
     # Performance Monitoring
    @@ -582,6 +583,7 @@ CONFIG_UART0_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -622,10 +624,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -656,6 +660,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -670,6 +675,7 @@ CONFIG_NET_TCP_RECVDELAY=0
     # UDP Networking
     #
     # CONFIG_NET_UDP is not set
    +# CONFIG_NET_UDP_NO_STACK is not set
     
     #
     # ICMP Networking Support
    @@ -694,10 +700,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -896,6 +906,8 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     CONFIG_EXAMPLES_NETTEST=y
    +CONFIG_EXAMPLES_NETTEST_STACKSIZE=2048
    +CONFIG_EXAMPLES_NETTEST_PRIORITY=100
     # CONFIG_EXAMPLES_NETTEST_SERVER is not set
     # CONFIG_EXAMPLES_NETTEST_PERFORMANCE is not set
     CONFIG_EXAMPLES_NETTEST_IPv4=y
    @@ -909,7 +921,6 @@ CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002
     CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001
     CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00
     CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -940,6 +951,7 @@ CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1015,3 +1027,7 @@ CONFIG_NETUTILS_NETLIB=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/eagle100/nsh/defconfig b/configs/eagle100/nsh/defconfig
    index 77155e25bc..f890cdbc10 100644
    --- a/configs/eagle100/nsh/defconfig
    +++ b/configs/eagle100/nsh/defconfig
    @@ -95,6 +95,7 @@ CONFIG_ARCH_CHIP_LM=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -102,11 +103,12 @@ CONFIG_ARCH_CHIP_LM=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -399,6 +401,8 @@ CONFIG_MAX_TASKS=16
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -625,6 +629,7 @@ CONFIG_UART0_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -665,10 +670,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -699,6 +706,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -713,6 +721,7 @@ CONFIG_NET_TCP_RECVDELAY=0
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -742,10 +751,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -976,7 +989,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1010,6 +1022,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1228,3 +1241,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/eagle100/thttpd/defconfig b/configs/eagle100/thttpd/defconfig
    index 5d7386f50e..bf7e936ec7 100644
    --- a/configs/eagle100/thttpd/defconfig
    +++ b/configs/eagle100/thttpd/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_LM=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_LM=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -379,7 +381,6 @@ CONFIG_TASK_NAME_SIZE=0
     CONFIG_MAX_TASKS=16
     # CONFIG_SCHED_HAVE_PARENT is not set
     # CONFIG_SCHED_WAITPID is not set
    -# CONFIG_CANCELLATION_POINTS is not set
     
     #
     # Performance Monitoring
    @@ -576,6 +577,7 @@ CONFIG_UART0_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -616,10 +618,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -650,6 +654,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=16
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -664,6 +669,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     # CONFIG_NET_UDP is not set
    +# CONFIG_NET_UDP_NO_STACK is not set
     
     #
     # ICMP Networking Support
    @@ -688,10 +694,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -903,7 +913,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -943,6 +952,7 @@ CONFIG_EXAMPLES_THTTPD_NETMASK=0xffffff00
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -1055,3 +1065,7 @@ CONFIG_THTTPD_TILDE_MAP_NONE=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/ekk-lm3s9b96/nsh/defconfig b/configs/ekk-lm3s9b96/nsh/defconfig
    index dc7faf5968..979386f809 100644
    --- a/configs/ekk-lm3s9b96/nsh/defconfig
    +++ b/configs/ekk-lm3s9b96/nsh/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_LM=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_LM=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -386,6 +388,8 @@ CONFIG_MAX_TASKS=16
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -612,6 +616,7 @@ CONFIG_UART0_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -652,10 +657,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -686,6 +693,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -700,6 +708,7 @@ CONFIG_NET_TCP_RECVDELAY=0
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     # CONFIG_NET_BROADCAST is not set
    @@ -729,10 +738,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -964,7 +977,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -998,6 +1010,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1218,3 +1231,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/ez80f910200zco/dhcpd/defconfig b/configs/ez80f910200zco/dhcpd/defconfig
    index 3c6bb897e9..ad915adc28 100644
    --- a/configs/ez80f910200zco/dhcpd/defconfig
    +++ b/configs/ez80f910200zco/dhcpd/defconfig
    @@ -269,7 +269,6 @@ CONFIG_TASK_NAME_SIZE=0
     CONFIG_MAX_TASKS=8
     # CONFIG_SCHED_HAVE_PARENT is not set
     # CONFIG_SCHED_WAITPID is not set
    -# CONFIG_CANCELLATION_POINTS is not set
     
     #
     # Performance Monitoring
    @@ -481,6 +480,7 @@ CONFIG_UART0_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -520,10 +520,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -554,11 +556,13 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     # CONFIG_NET_TCP is not set
    +# CONFIG_NET_TCP_NO_STACK is not set
     
     #
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -588,10 +592,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=8
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -792,7 +800,6 @@ CONFIG_EXAMPLES_DHCPD_NETMASK=0xffffff00
     # CONFIG_EXAMPLES_MM is not set
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -824,6 +831,7 @@ CONFIG_EXAMPLES_DHCPD_NETMASK=0xffffff00
     # CONFIG_EXAMPLES_UDPBLASTER is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -913,3 +921,7 @@ CONFIG_NETUTILS_NETLIB=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/ez80f910200zco/httpd/defconfig b/configs/ez80f910200zco/httpd/defconfig
    index 3985af46a6..30dee6ec58 100644
    --- a/configs/ez80f910200zco/httpd/defconfig
    +++ b/configs/ez80f910200zco/httpd/defconfig
    @@ -275,6 +275,8 @@ CONFIG_MAX_TASKS=8
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=0
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -492,6 +494,7 @@ CONFIG_UART0_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -532,10 +535,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -566,6 +571,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=16
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -580,6 +586,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     # CONFIG_NET_UDP is not set
    +# CONFIG_NET_UDP_NO_STACK is not set
     
     #
     # ICMP Networking Support
    @@ -604,10 +611,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -803,7 +814,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -838,6 +848,7 @@ CONFIG_EXAMPLES_WEBSERVER_DRIPADDR=0x0a000001
     CONFIG_EXAMPLES_WEBSERVER_NETMASK=0xffffff00
     CONFIG_EXAMPLES_WEBSERVER_NOMAC=y
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -924,3 +935,7 @@ CONFIG_NETUTILS_HTTPD_KEEPALIVE_DISABLE=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/ez80f910200zco/nettest/defconfig b/configs/ez80f910200zco/nettest/defconfig
    index bcd5d86a64..8d6a8b3dd0 100644
    --- a/configs/ez80f910200zco/nettest/defconfig
    +++ b/configs/ez80f910200zco/nettest/defconfig
    @@ -269,7 +269,6 @@ CONFIG_TASK_NAME_SIZE=0
     CONFIG_MAX_TASKS=8
     # CONFIG_SCHED_HAVE_PARENT is not set
     # CONFIG_SCHED_WAITPID is not set
    -# CONFIG_CANCELLATION_POINTS is not set
     
     #
     # Performance Monitoring
    @@ -482,6 +481,7 @@ CONFIG_UART0_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -522,10 +522,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -556,6 +558,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -570,6 +573,7 @@ CONFIG_NET_TCP_RECVDELAY=0
     # UDP Networking
     #
     # CONFIG_NET_UDP is not set
    +# CONFIG_NET_UDP_NO_STACK is not set
     
     #
     # ICMP Networking Support
    @@ -594,10 +598,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -793,6 +801,8 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     CONFIG_EXAMPLES_NETTEST=y
    +CONFIG_EXAMPLES_NETTEST_STACKSIZE=2048
    +CONFIG_EXAMPLES_NETTEST_PRIORITY=100
     # CONFIG_EXAMPLES_NETTEST_SERVER is not set
     # CONFIG_EXAMPLES_NETTEST_PERFORMANCE is not set
     CONFIG_EXAMPLES_NETTEST_IPv4=y
    @@ -806,7 +816,6 @@ CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002
     CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001
     CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00
     CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -837,6 +846,7 @@ CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -912,3 +922,7 @@ CONFIG_NETUTILS_NETLIB=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/ez80f910200zco/nsh/defconfig b/configs/ez80f910200zco/nsh/defconfig
    index 87f8bffe92..f1271c3d19 100644
    --- a/configs/ez80f910200zco/nsh/defconfig
    +++ b/configs/ez80f910200zco/nsh/defconfig
    @@ -275,6 +275,8 @@ CONFIG_MAX_TASKS=16
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -495,6 +497,7 @@ CONFIG_UART0_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -535,10 +538,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -569,6 +574,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -583,6 +589,7 @@ CONFIG_NET_TCP_RECVDELAY=0
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -612,10 +619,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -831,7 +842,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -864,6 +874,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1079,3 +1090,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/ez80f910200zco/poll/defconfig b/configs/ez80f910200zco/poll/defconfig
    index 26cc069f33..521e76d910 100644
    --- a/configs/ez80f910200zco/poll/defconfig
    +++ b/configs/ez80f910200zco/poll/defconfig
    @@ -275,6 +275,8 @@ CONFIG_MAX_TASKS=8
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=0
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -494,6 +496,7 @@ CONFIG_UART0_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -534,10 +537,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -568,6 +573,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -582,6 +588,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     # CONFIG_NET_UDP is not set
    +# CONFIG_NET_UDP_NO_STACK is not set
     
     #
     # ICMP Networking Support
    @@ -606,10 +613,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -806,7 +817,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -843,6 +853,7 @@ CONFIG_EXAMPLES_POLL_NETMASK=0xffffff00
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -921,3 +932,7 @@ CONFIG_NETUTILS_NETLIB=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/fire-stm32v2/nsh/defconfig b/configs/fire-stm32v2/nsh/defconfig
    index e7d49f2a4d..8cada6692f 100644
    --- a/configs/fire-stm32v2/nsh/defconfig
    +++ b/configs/fire-stm32v2/nsh/defconfig
    @@ -96,6 +96,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -103,11 +104,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     CONFIG_ARCH_CHIP_STM32=y
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -182,6 +184,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -381,9 +386,13 @@ CONFIG_STM32_HAVE_ADC3=y
     # CONFIG_STM32_HAVE_SDADC3_DMA is not set
     CONFIG_STM32_HAVE_CAN1=y
     # CONFIG_STM32_HAVE_CAN2 is not set
    +# CONFIG_STM32_HAVE_COMP1 is not set
     # CONFIG_STM32_HAVE_COMP2 is not set
    +# CONFIG_STM32_HAVE_COMP3 is not set
     # CONFIG_STM32_HAVE_COMP4 is not set
    +# CONFIG_STM32_HAVE_COMP5 is not set
     # CONFIG_STM32_HAVE_COMP6 is not set
    +# CONFIG_STM32_HAVE_COMP7 is not set
     CONFIG_STM32_HAVE_DAC1=y
     CONFIG_STM32_HAVE_DAC2=y
     # CONFIG_STM32_HAVE_RNG is not set
    @@ -397,7 +406,10 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_HAVE_SPI6 is not set
     # CONFIG_STM32_HAVE_SAIPLL is not set
     # CONFIG_STM32_HAVE_I2SPLL is not set
    -# CONFIG_STM32_HAVE_OPAMP is not set
    +# CONFIG_STM32_HAVE_OPAMP1 is not set
    +# CONFIG_STM32_HAVE_OPAMP2 is not set
    +# CONFIG_STM32_HAVE_OPAMP3 is not set
    +# CONFIG_STM32_HAVE_OPAMP4 is not set
     # CONFIG_STM32_ADC1 is not set
     # CONFIG_STM32_ADC2 is not set
     # CONFIG_STM32_ADC3 is not set
    @@ -411,6 +423,7 @@ CONFIG_STM32_DMA2=y
     # CONFIG_STM32_FSMC is not set
     CONFIG_STM32_I2C1=y
     # CONFIG_STM32_I2C2 is not set
    +# CONFIG_STM32_OPAMP is not set
     CONFIG_STM32_PWR=y
     CONFIG_STM32_SDIO=y
     CONFIG_STM32_SPI1=y
    @@ -443,6 +456,7 @@ CONFIG_STM32_I2C=y
     # CONFIG_STM32_SPI1_REMAP is not set
     # CONFIG_STM32_USART1_REMAP is not set
     # CONFIG_STM32_USART2_REMAP is not set
    +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set
     # CONFIG_STM32_JTAG_DISABLE is not set
     CONFIG_STM32_JTAG_FULL_ENABLE=y
     # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
    @@ -672,6 +686,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -971,6 +987,7 @@ CONFIG_USBMSC_REMOVABLE=y
     CONFIG_USBMSC_SCSI_PRIO=128
     CONFIG_USBMSC_SCSI_STACKSIZE=2048
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -1011,10 +1028,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -1045,6 +1064,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=16
     CONFIG_NET_MAX_LISTENPORTS=16
    @@ -1059,6 +1079,7 @@ CONFIG_NET_TCP_RECVDELAY=0
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -1088,10 +1109,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1330,7 +1355,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1364,6 +1388,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1604,3 +1629,7 @@ CONFIG_SYSTEM_USBMSC_CMD_STACKSIZE=768
     CONFIG_SYSTEM_USBMSC_CMD_PRIORITY=100
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/freedom-k64f/netnsh/defconfig b/configs/freedom-k64f/netnsh/defconfig
    index d546e3cdf8..6634ed2337 100644
    --- a/configs/freedom-k64f/netnsh/defconfig
    +++ b/configs/freedom-k64f/netnsh/defconfig
    @@ -95,6 +95,7 @@ CONFIG_ARCH_CHIP_KINETIS=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -102,11 +103,12 @@ CONFIG_ARCH_CHIP_KINETIS=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -415,6 +417,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -641,6 +645,7 @@ CONFIG_UART3_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -681,6 +686,7 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
    @@ -716,6 +722,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=20
    @@ -730,6 +737,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     # CONFIG_NET_UDP_CHECKSUMS is not set
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -761,11 +769,15 @@ CONFIG_ARP_SEND_DELAYMSEC=20
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=36
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
     CONFIG_IOB_THROTTLE=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1046,6 +1058,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1270,3 +1283,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/freedom-k66f/netnsh/defconfig b/configs/freedom-k66f/netnsh/defconfig
    index 3ed87ae329..0dffbe5d56 100644
    --- a/configs/freedom-k66f/netnsh/defconfig
    +++ b/configs/freedom-k66f/netnsh/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_KINETIS=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_KINETIS=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -416,6 +418,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -669,6 +673,7 @@ CONFIG_UART4_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -709,6 +714,7 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
    @@ -744,6 +750,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=20
    @@ -758,6 +765,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     # CONFIG_NET_UDP_CHECKSUMS is not set
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -789,11 +797,15 @@ CONFIG_ARP_SEND_DELAYMSEC=20
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=36
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
     CONFIG_IOB_THROTTLE=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1075,6 +1087,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1304,3 +1317,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/lincoln60/netnsh/defconfig b/configs/lincoln60/netnsh/defconfig
    index 4e1fad4b0d..bb7a78a93c 100644
    --- a/configs/lincoln60/netnsh/defconfig
    +++ b/configs/lincoln60/netnsh/defconfig
    @@ -95,6 +95,7 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -102,11 +103,12 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -377,6 +379,8 @@ CONFIG_MAX_TASKS=16
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -603,6 +607,7 @@ CONFIG_UART0_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -643,10 +648,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -677,6 +684,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -691,6 +699,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -722,11 +731,15 @@ CONFIG_ARP_SEND_DELAYMSEC=20
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=36
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
     CONFIG_IOB_THROTTLE=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -958,7 +971,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -992,6 +1004,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1211,3 +1224,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/lincoln60/thttpd-binfs/defconfig b/configs/lincoln60/thttpd-binfs/defconfig
    index aed4b73dc9..0f3690c7fd 100644
    --- a/configs/lincoln60/thttpd-binfs/defconfig
    +++ b/configs/lincoln60/thttpd-binfs/defconfig
    @@ -95,6 +95,7 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -102,11 +103,12 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -366,7 +368,6 @@ CONFIG_TASK_NAME_SIZE=0
     CONFIG_MAX_TASKS=16
     # CONFIG_SCHED_HAVE_PARENT is not set
     # CONFIG_SCHED_WAITPID is not set
    -# CONFIG_CANCELLATION_POINTS is not set
     
     #
     # Performance Monitoring
    @@ -582,6 +583,7 @@ CONFIG_UART0_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -622,10 +624,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -656,6 +660,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=12
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -670,6 +675,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     # CONFIG_NET_UDP is not set
    +# CONFIG_NET_UDP_NO_STACK is not set
     
     #
     # ICMP Networking Support
    @@ -696,11 +702,15 @@ CONFIG_ARP_SEND_DELAYMSEC=20
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
     CONFIG_IOB_THROTTLE=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -919,7 +929,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -958,6 +967,7 @@ CONFIG_EXAMPLES_THTTPD_NETMASK=0xffffff00
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -1070,3 +1080,7 @@ CONFIG_THTTPD_TILDE_MAP_NONE=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/lm3s6432-s2e/nsh/defconfig b/configs/lm3s6432-s2e/nsh/defconfig
    index 11925f4139..27f1e85a50 100644
    --- a/configs/lm3s6432-s2e/nsh/defconfig
    +++ b/configs/lm3s6432-s2e/nsh/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_LM=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_LM=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -381,6 +383,8 @@ CONFIG_MAX_TASKS=16
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -602,6 +606,7 @@ CONFIG_UART1_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -642,10 +647,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -676,6 +683,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -690,6 +698,7 @@ CONFIG_NET_TCP_RECVDELAY=0
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -719,10 +728,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -942,7 +955,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -976,6 +988,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1189,3 +1202,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/lm3s6965-ek/discover/defconfig b/configs/lm3s6965-ek/discover/defconfig
    index d8f8639ebf..cc4fc1715d 100644
    --- a/configs/lm3s6965-ek/discover/defconfig
    +++ b/configs/lm3s6965-ek/discover/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_LM=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_LM=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -391,6 +393,8 @@ CONFIG_MAX_TASKS=16
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -617,6 +621,7 @@ CONFIG_UART0_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -657,10 +662,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -691,6 +698,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -705,6 +713,7 @@ CONFIG_NET_TCP_RECVDELAY=0
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -734,10 +743,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -968,7 +981,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1002,6 +1014,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1223,3 +1236,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/lm3s6965-ek/nsh/defconfig b/configs/lm3s6965-ek/nsh/defconfig
    index d8f8639ebf..cc4fc1715d 100644
    --- a/configs/lm3s6965-ek/nsh/defconfig
    +++ b/configs/lm3s6965-ek/nsh/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_LM=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_LM=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -391,6 +393,8 @@ CONFIG_MAX_TASKS=16
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -617,6 +621,7 @@ CONFIG_UART0_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -657,10 +662,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -691,6 +698,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -705,6 +713,7 @@ CONFIG_NET_TCP_RECVDELAY=0
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -734,10 +743,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -968,7 +981,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1002,6 +1014,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1223,3 +1236,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/lm3s6965-ek/tcpecho/defconfig b/configs/lm3s6965-ek/tcpecho/defconfig
    index f790652e65..c3b2d038cb 100644
    --- a/configs/lm3s6965-ek/tcpecho/defconfig
    +++ b/configs/lm3s6965-ek/tcpecho/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_LM=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_LM=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -379,6 +381,9 @@ CONFIG_MAX_TASKS=16
     # Pthread Options
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
    +CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -587,6 +592,7 @@ CONFIG_UART0_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -627,10 +633,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -661,6 +669,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=16
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -675,6 +684,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -704,10 +714,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -938,7 +952,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -979,6 +992,7 @@ CONFIG_EXAMPLES_TCPECHO_NETMASK=0xffffff00
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -1070,3 +1084,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/lm3s8962-ek/nsh/defconfig b/configs/lm3s8962-ek/nsh/defconfig
    index 1c62f37b57..5d1599a47d 100644
    --- a/configs/lm3s8962-ek/nsh/defconfig
    +++ b/configs/lm3s8962-ek/nsh/defconfig
    @@ -95,6 +95,7 @@ CONFIG_ARCH_CHIP_LM=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -102,11 +103,12 @@ CONFIG_ARCH_CHIP_LM=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -403,6 +405,8 @@ CONFIG_MAX_TASKS=16
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -629,6 +633,7 @@ CONFIG_UART0_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -669,10 +674,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -703,6 +710,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -717,6 +725,7 @@ CONFIG_NET_TCP_RECVDELAY=0
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -746,10 +755,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -980,7 +993,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1014,6 +1026,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1234,3 +1247,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/lpcxpresso-lpc1768/dhcpd/defconfig b/configs/lpcxpresso-lpc1768/dhcpd/defconfig
    index 555842818a..599b3001a0 100644
    --- a/configs/lpcxpresso-lpc1768/dhcpd/defconfig
    +++ b/configs/lpcxpresso-lpc1768/dhcpd/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -356,7 +358,6 @@ CONFIG_TASK_NAME_SIZE=0
     CONFIG_MAX_TASKS=8
     # CONFIG_SCHED_HAVE_PARENT is not set
     # CONFIG_SCHED_WAITPID is not set
    -# CONFIG_CANCELLATION_POINTS is not set
     
     #
     # Performance Monitoring
    @@ -569,6 +570,7 @@ CONFIG_UART3_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -608,10 +610,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -642,11 +646,13 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     # CONFIG_NET_TCP is not set
    +# CONFIG_NET_TCP_NO_STACK is not set
     
     #
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -676,10 +682,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=8
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -883,7 +893,6 @@ CONFIG_EXAMPLES_DHCPD_NETMASK=0xffffff00
     # CONFIG_EXAMPLES_MM is not set
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -915,6 +924,7 @@ CONFIG_EXAMPLES_DHCPD_NETMASK=0xffffff00
     # CONFIG_EXAMPLES_UDPBLASTER is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1004,3 +1014,7 @@ CONFIG_NETUTILS_NETLIB=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/lpcxpresso-lpc1768/nsh/defconfig b/configs/lpcxpresso-lpc1768/nsh/defconfig
    index 06ceda8cc1..fdf6ac732e 100644
    --- a/configs/lpcxpresso-lpc1768/nsh/defconfig
    +++ b/configs/lpcxpresso-lpc1768/nsh/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -367,6 +369,8 @@ CONFIG_MAX_TASKS=16
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -642,6 +646,7 @@ CONFIG_UART3_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -682,10 +687,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -716,6 +723,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -730,6 +738,7 @@ CONFIG_NET_TCP_RECVDELAY=0
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -759,10 +768,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -993,7 +1006,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1027,6 +1039,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1248,3 +1261,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/lpcxpresso-lpc1768/thttpd/defconfig b/configs/lpcxpresso-lpc1768/thttpd/defconfig
    index ba77ddba70..6eedaf96c6 100644
    --- a/configs/lpcxpresso-lpc1768/thttpd/defconfig
    +++ b/configs/lpcxpresso-lpc1768/thttpd/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -356,7 +358,6 @@ CONFIG_TASK_NAME_SIZE=0
     CONFIG_MAX_TASKS=16
     # CONFIG_SCHED_HAVE_PARENT is not set
     # CONFIG_SCHED_WAITPID is not set
    -# CONFIG_CANCELLATION_POINTS is not set
     
     #
     # Performance Monitoring
    @@ -572,6 +573,7 @@ CONFIG_UART3_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -612,10 +614,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -646,6 +650,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=16
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -660,6 +665,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     # CONFIG_NET_UDP is not set
    +# CONFIG_NET_UDP_NO_STACK is not set
     
     #
     # ICMP Networking Support
    @@ -684,10 +690,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -899,7 +909,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -939,6 +948,7 @@ CONFIG_EXAMPLES_THTTPD_NETMASK=0xffffff00
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -1051,3 +1061,7 @@ CONFIG_THTTPD_TILDE_MAP_NONE=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/misoc/hello/defconfig b/configs/misoc/hello/defconfig
    index cf0c955efc..da8283d9ff 100644
    --- a/configs/misoc/hello/defconfig
    +++ b/configs/misoc/hello/defconfig
    @@ -238,6 +238,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -465,6 +467,7 @@ CONFIG_UART1_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -505,10 +508,12 @@ CONFIG_NET_GUARDSIZE=648
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -534,6 +539,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=40
     CONFIG_NET_MAX_LISTENPORTS=40
    @@ -549,6 +555,7 @@ CONFIG_NET_TCP_RECVDELAY=0
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -580,12 +587,16 @@ CONFIG_ARP_SEND_DELAYMSEC=20
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
     CONFIG_IOB_THROTTLE=8
     # CONFIG_IOB_DEBUG is not set
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -814,6 +825,8 @@ CONFIG_EXAMPLES_HELLO_STACKSIZE=2048
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     CONFIG_EXAMPLES_NETTEST=y
    +CONFIG_EXAMPLES_NETTEST_STACKSIZE=2048
    +CONFIG_EXAMPLES_NETTEST_PRIORITY=100
     # CONFIG_EXAMPLES_NETTEST_SERVER is not set
     CONFIG_EXAMPLES_NETTEST_PERFORMANCE=y
     CONFIG_EXAMPLES_NETTEST_IPv4=y
    @@ -827,7 +840,6 @@ CONFIG_EXAMPLES_NETTEST_IPADDR=0xc0a80132
     CONFIG_EXAMPLES_NETTEST_DRIPADDR=0xc0a80101
     CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00
     CONFIG_EXAMPLES_NETTEST_CLIENTIP=0xc0a8023b
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -877,6 +889,7 @@ CONFIG_EXAMPLES_TELNETD_CLIENTSTACKSIZE=2048
     # CONFIG_EXAMPLES_UDPBLASTER is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -1101,3 +1114,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/moxa/nsh/defconfig b/configs/moxa/nsh/defconfig
    index 6cd8e330c1..a368f1171a 100644
    --- a/configs/moxa/nsh/defconfig
    +++ b/configs/moxa/nsh/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +CONFIG_ARCH_CHIP_MOXART=y
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -CONFIG_ARCH_CHIP_MOXART=y
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     CONFIG_ARCH_ARM7TDMI=y
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -270,6 +272,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -491,6 +495,7 @@ CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -532,10 +537,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -566,6 +573,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     # CONFIG_NET_TCP_REASSEMBLY is not set
     CONFIG_NET_TCP_CONNS=8
    @@ -581,6 +589,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     # CONFIG_NET_UDP is not set
    +# CONFIG_NET_UDP_NO_STACK is not set
     
     #
     # ICMP Networking Support
    @@ -607,11 +616,15 @@ CONFIG_ARP_SEND_DELAYMSEC=20
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
     CONFIG_IOB_THROTTLE=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -844,7 +857,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -879,6 +891,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -1099,3 +1112,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/ntosd-dm320/nettest/defconfig b/configs/ntosd-dm320/nettest/defconfig
    index 8a54acd2ed..a7bafa1d08 100644
    --- a/configs/ntosd-dm320/nettest/defconfig
    +++ b/configs/ntosd-dm320/nettest/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_DM320=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_DM320=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     CONFIG_ARCH_ARM926EJS=y
     # CONFIG_ARCH_ARM920T is not set
    @@ -266,7 +268,6 @@ CONFIG_TASK_NAME_SIZE=0
     CONFIG_MAX_TASKS=64
     # CONFIG_SCHED_HAVE_PARENT is not set
     # CONFIG_SCHED_WAITPID is not set
    -# CONFIG_CANCELLATION_POINTS is not set
     
     #
     # Performance Monitoring
    @@ -488,6 +489,7 @@ CONFIG_UART1_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -528,10 +530,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -562,6 +566,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -576,6 +581,7 @@ CONFIG_NET_TCP_RECVDELAY=0
     # UDP Networking
     #
     # CONFIG_NET_UDP is not set
    +# CONFIG_NET_UDP_NO_STACK is not set
     
     #
     # ICMP Networking Support
    @@ -600,10 +606,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -804,6 +814,8 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     CONFIG_EXAMPLES_NETTEST=y
    +CONFIG_EXAMPLES_NETTEST_STACKSIZE=2048
    +CONFIG_EXAMPLES_NETTEST_PRIORITY=100
     # CONFIG_EXAMPLES_NETTEST_SERVER is not set
     # CONFIG_EXAMPLES_NETTEST_PERFORMANCE is not set
     CONFIG_EXAMPLES_NETTEST_IPv4=y
    @@ -817,7 +829,6 @@ CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002
     CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001
     CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00
     CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -848,6 +859,7 @@ CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -923,3 +935,7 @@ CONFIG_NETUTILS_NETLIB=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/ntosd-dm320/nsh/defconfig b/configs/ntosd-dm320/nsh/defconfig
    index 02ff89e1cc..a40c5d29f9 100644
    --- a/configs/ntosd-dm320/nsh/defconfig
    +++ b/configs/ntosd-dm320/nsh/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_DM320=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_DM320=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     CONFIG_ARCH_ARM926EJS=y
     # CONFIG_ARCH_ARM920T is not set
    @@ -272,6 +274,8 @@ CONFIG_MAX_TASKS=64
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -507,6 +511,7 @@ CONFIG_UART1_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -547,10 +552,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -581,6 +588,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -595,6 +603,7 @@ CONFIG_NET_TCP_RECVDELAY=0
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -624,10 +633,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -858,7 +871,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -894,6 +906,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1124,3 +1137,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/ntosd-dm320/poll/defconfig b/configs/ntosd-dm320/poll/defconfig
    index 943fd679dc..17b6151dea 100644
    --- a/configs/ntosd-dm320/poll/defconfig
    +++ b/configs/ntosd-dm320/poll/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_DM320=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_DM320=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     CONFIG_ARCH_ARM926EJS=y
     # CONFIG_ARCH_ARM920T is not set
    @@ -272,6 +274,8 @@ CONFIG_MAX_TASKS=64
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -501,6 +505,7 @@ CONFIG_UART1_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -541,10 +546,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -575,6 +582,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -589,6 +597,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     # CONFIG_NET_UDP is not set
    +# CONFIG_NET_UDP_NO_STACK is not set
     
     #
     # ICMP Networking Support
    @@ -613,10 +622,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -819,7 +832,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -856,6 +868,7 @@ CONFIG_EXAMPLES_POLL_NETMASK=0xffffff00
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -934,3 +947,7 @@ CONFIG_NETUTILS_NETLIB=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/ntosd-dm320/thttpd/defconfig b/configs/ntosd-dm320/thttpd/defconfig
    index 46da53caf1..3bdeaf23ac 100644
    --- a/configs/ntosd-dm320/thttpd/defconfig
    +++ b/configs/ntosd-dm320/thttpd/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_DM320=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_DM320=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     CONFIG_ARCH_ARM926EJS=y
     # CONFIG_ARCH_ARM920T is not set
    @@ -266,7 +268,6 @@ CONFIG_TASK_NAME_SIZE=0
     CONFIG_MAX_TASKS=64
     # CONFIG_SCHED_HAVE_PARENT is not set
     # CONFIG_SCHED_WAITPID is not set
    -# CONFIG_CANCELLATION_POINTS is not set
     
     #
     # Performance Monitoring
    @@ -492,6 +493,7 @@ CONFIG_UART1_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -532,10 +534,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -566,6 +570,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=16
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -580,6 +585,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     # CONFIG_NET_UDP is not set
    +# CONFIG_NET_UDP_NO_STACK is not set
     
     #
     # ICMP Networking Support
    @@ -604,10 +610,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -820,7 +830,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -860,6 +869,7 @@ CONFIG_EXAMPLES_THTTPD_NETMASK=0xffffff00
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -972,3 +982,7 @@ CONFIG_THTTPD_TILDE_MAP_NONE=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/ntosd-dm320/udp/defconfig b/configs/ntosd-dm320/udp/defconfig
    index e6b5bebcb8..fbf8eb5185 100644
    --- a/configs/ntosd-dm320/udp/defconfig
    +++ b/configs/ntosd-dm320/udp/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_DM320=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_DM320=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     CONFIG_ARCH_ARM926EJS=y
     # CONFIG_ARCH_ARM920T is not set
    @@ -266,7 +268,6 @@ CONFIG_TASK_NAME_SIZE=0
     CONFIG_MAX_TASKS=64
     # CONFIG_SCHED_HAVE_PARENT is not set
     # CONFIG_SCHED_WAITPID is not set
    -# CONFIG_CANCELLATION_POINTS is not set
     
     #
     # Performance Monitoring
    @@ -487,6 +488,7 @@ CONFIG_UART1_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -526,10 +528,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -560,11 +564,13 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     # CONFIG_NET_TCP is not set
    +# CONFIG_NET_TCP_NO_STACK is not set
     
     #
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -594,10 +600,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=8
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -800,7 +810,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MM is not set
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -842,6 +851,7 @@ CONFIG_EXAMPLES_UDP_SERVERIP=0x0a000001
     # CONFIG_EXAMPLES_UDPBLASTER is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -919,3 +929,7 @@ CONFIG_NETUTILS_NETLIB=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/ntosd-dm320/webserver/defconfig b/configs/ntosd-dm320/webserver/defconfig
    index 4c6f2635f5..a35c7abb37 100644
    --- a/configs/ntosd-dm320/webserver/defconfig
    +++ b/configs/ntosd-dm320/webserver/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_DM320=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_DM320=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     CONFIG_ARCH_ARM926EJS=y
     # CONFIG_ARCH_ARM920T is not set
    @@ -272,6 +274,8 @@ CONFIG_MAX_TASKS=16
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -497,6 +501,7 @@ CONFIG_UART1_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -537,10 +542,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -571,6 +578,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -585,6 +593,7 @@ CONFIG_NET_TCP_RECVDELAY=0
     # UDP Networking
     #
     # CONFIG_NET_UDP is not set
    +# CONFIG_NET_UDP_NO_STACK is not set
     
     #
     # ICMP Networking Support
    @@ -609,10 +618,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -814,7 +827,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -849,6 +861,7 @@ CONFIG_EXAMPLES_WEBSERVER_DRIPADDR=0x0a000001
     CONFIG_EXAMPLES_WEBSERVER_NETMASK=0xffffff00
     CONFIG_EXAMPLES_WEBSERVER_NOMAC=y
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -935,3 +948,7 @@ CONFIG_NETUTILS_HTTPD_KEEPALIVE_DISABLE=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/olimex-lpc1766stk/ftpc/defconfig b/configs/olimex-lpc1766stk/ftpc/defconfig
    index 63cec7f15e..a68e6d292e 100644
    --- a/configs/olimex-lpc1766stk/ftpc/defconfig
    +++ b/configs/olimex-lpc1766stk/ftpc/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -367,6 +369,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -609,6 +613,7 @@ CONFIG_UART0_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -649,10 +654,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -683,6 +690,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=16
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -697,6 +705,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -726,10 +735,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -969,7 +982,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1004,6 +1016,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -1217,3 +1230,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/olimex-lpc1766stk/hidmouse/defconfig b/configs/olimex-lpc1766stk/hidmouse/defconfig
    index f6cb6524a7..aecd251b1e 100644
    --- a/configs/olimex-lpc1766stk/hidmouse/defconfig
    +++ b/configs/olimex-lpc1766stk/hidmouse/defconfig
    @@ -95,6 +95,7 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -102,11 +103,12 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -381,6 +383,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -600,7 +604,9 @@ CONFIG_HIDMOUSE_YSCALE=0x00010000
     CONFIG_HIDMOUSE_XTHRESH=12
     CONFIG_HIDMOUSE_THRESHY=12
     # CONFIG_USBHOST_RTL8187 is not set
    +# CONFIG_USBHOST_XBOXCONTROLLER is not set
     # CONFIG_USBHOST_TRACE is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -641,10 +647,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -675,6 +683,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -690,6 +699,7 @@ CONFIG_NET_TCP_SPLIT_SIZE=40
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -719,10 +729,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -961,7 +975,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1000,6 +1013,7 @@ CONFIG_EXAMPLES_TOUCHSCREEN_ARCHINIT=y
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1221,3 +1235,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/olimex-lpc1766stk/nettest/defconfig b/configs/olimex-lpc1766stk/nettest/defconfig
    index f56d9b3d5f..e38fcf7f16 100644
    --- a/configs/olimex-lpc1766stk/nettest/defconfig
    +++ b/configs/olimex-lpc1766stk/nettest/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -357,7 +359,6 @@ CONFIG_TASK_NAME_SIZE=0
     CONFIG_MAX_TASKS=8
     # CONFIG_SCHED_HAVE_PARENT is not set
     # CONFIG_SCHED_WAITPID is not set
    -# CONFIG_CANCELLATION_POINTS is not set
     
     #
     # Performance Monitoring
    @@ -570,6 +571,7 @@ CONFIG_UART0_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -610,10 +612,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -644,6 +648,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -658,6 +663,7 @@ CONFIG_NET_TCP_RECVDELAY=0
     # UDP Networking
     #
     # CONFIG_NET_UDP is not set
    +# CONFIG_NET_UDP_NO_STACK is not set
     
     #
     # ICMP Networking Support
    @@ -682,10 +688,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -885,6 +895,8 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     CONFIG_EXAMPLES_NETTEST=y
    +CONFIG_EXAMPLES_NETTEST_STACKSIZE=2048
    +CONFIG_EXAMPLES_NETTEST_PRIORITY=100
     # CONFIG_EXAMPLES_NETTEST_SERVER is not set
     # CONFIG_EXAMPLES_NETTEST_PERFORMANCE is not set
     CONFIG_EXAMPLES_NETTEST_IPv4=y
    @@ -898,7 +910,6 @@ CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002
     CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001
     CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00
     CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -929,6 +940,7 @@ CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1004,3 +1016,7 @@ CONFIG_NETUTILS_NETLIB=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/olimex-lpc1766stk/nsh/defconfig b/configs/olimex-lpc1766stk/nsh/defconfig
    index 8d7473910d..8bbff74d8e 100644
    --- a/configs/olimex-lpc1766stk/nsh/defconfig
    +++ b/configs/olimex-lpc1766stk/nsh/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -368,6 +370,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -611,6 +615,7 @@ CONFIG_UART0_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -651,10 +656,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -685,6 +692,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -700,6 +708,7 @@ CONFIG_NET_TCP_SPLIT_SIZE=40
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -729,10 +738,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -980,7 +993,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1015,6 +1027,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1239,3 +1252,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/olimex-lpc1766stk/slip-httpd/defconfig b/configs/olimex-lpc1766stk/slip-httpd/defconfig
    index e49f0b7629..0259bd572a 100644
    --- a/configs/olimex-lpc1766stk/slip-httpd/defconfig
    +++ b/configs/olimex-lpc1766stk/slip-httpd/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -346,7 +348,6 @@ CONFIG_TASK_NAME_SIZE=0
     CONFIG_MAX_TASKS=16
     # CONFIG_SCHED_HAVE_PARENT is not set
     # CONFIG_SCHED_WAITPID is not set
    -# CONFIG_CANCELLATION_POINTS is not set
     
     #
     # Performance Monitoring
    @@ -537,6 +538,7 @@ CONFIG_UART1_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -580,10 +582,12 @@ CONFIG_SLIP_NINTERFACES=1
     CONFIG_SLIP_STACKSIZE=2048
     CONFIG_SLIP_DEFPRIO=128
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -614,6 +618,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=16
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -628,6 +633,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     # CONFIG_NET_UDP is not set
    +# CONFIG_NET_UDP_NO_STACK is not set
     
     #
     # ICMP Networking Support
    @@ -647,10 +653,14 @@ CONFIG_NET_ICMP=y
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -863,7 +873,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -903,6 +912,7 @@ CONFIG_EXAMPLES_THTTPD_NETMASK=0xffffff00
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -1015,3 +1025,7 @@ CONFIG_THTTPD_TILDE_MAP_NONE=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/olimex-lpc1766stk/thttpd-binfs/defconfig b/configs/olimex-lpc1766stk/thttpd-binfs/defconfig
    index 07e390c15c..5e83771e75 100644
    --- a/configs/olimex-lpc1766stk/thttpd-binfs/defconfig
    +++ b/configs/olimex-lpc1766stk/thttpd-binfs/defconfig
    @@ -95,6 +95,7 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -102,11 +103,12 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -366,7 +368,6 @@ CONFIG_TASK_NAME_SIZE=0
     CONFIG_MAX_TASKS=16
     # CONFIG_SCHED_HAVE_PARENT is not set
     # CONFIG_SCHED_WAITPID is not set
    -# CONFIG_CANCELLATION_POINTS is not set
     
     #
     # Performance Monitoring
    @@ -582,6 +583,7 @@ CONFIG_UART0_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -622,10 +624,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -656,6 +660,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=16
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -670,6 +675,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     # CONFIG_NET_UDP is not set
    +# CONFIG_NET_UDP_NO_STACK is not set
     
     #
     # ICMP Networking Support
    @@ -694,10 +700,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -916,7 +926,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -955,6 +964,7 @@ CONFIG_EXAMPLES_THTTPD_NETMASK=0xffffff00
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -1067,3 +1077,7 @@ CONFIG_THTTPD_TILDE_MAP_NONE=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/olimex-lpc1766stk/thttpd-nxflat/defconfig b/configs/olimex-lpc1766stk/thttpd-nxflat/defconfig
    index e62efd7894..22e39cf274 100644
    --- a/configs/olimex-lpc1766stk/thttpd-nxflat/defconfig
    +++ b/configs/olimex-lpc1766stk/thttpd-nxflat/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -357,7 +359,6 @@ CONFIG_TASK_NAME_SIZE=0
     CONFIG_MAX_TASKS=16
     # CONFIG_SCHED_HAVE_PARENT is not set
     # CONFIG_SCHED_WAITPID is not set
    -# CONFIG_CANCELLATION_POINTS is not set
     
     #
     # Performance Monitoring
    @@ -573,6 +574,7 @@ CONFIG_UART0_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -613,10 +615,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -647,6 +651,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=16
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -661,6 +666,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     # CONFIG_NET_UDP is not set
    +# CONFIG_NET_UDP_NO_STACK is not set
     
     #
     # ICMP Networking Support
    @@ -685,10 +691,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -901,7 +911,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -941,6 +950,7 @@ CONFIG_EXAMPLES_THTTPD_NETMASK=0xffffff00
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -1053,3 +1063,7 @@ CONFIG_THTTPD_TILDE_MAP_NONE=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/olimex-lpc1766stk/zmodem/defconfig b/configs/olimex-lpc1766stk/zmodem/defconfig
    index b1faa163ca..d430891207 100644
    --- a/configs/olimex-lpc1766stk/zmodem/defconfig
    +++ b/configs/olimex-lpc1766stk/zmodem/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -369,6 +371,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -626,6 +630,7 @@ CONFIG_UART1_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -666,10 +671,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -700,6 +707,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -715,6 +723,7 @@ CONFIG_NET_TCP_SPLIT_SIZE=40
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     # CONFIG_NET_BROADCAST is not set
    @@ -744,10 +753,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -986,7 +999,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1021,6 +1033,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1257,3 +1270,7 @@ CONFIG_SYSTEM_ZMODEM_SERIALNO=0
     CONFIG_SYSTEM_ZMODEM_MAXERRORS=20
     CONFIG_SYSTEM_ZMODEM_WRITESIZE=512
     # CONFIG_DEBUG_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/olimex-stm32-e407/discover/defconfig b/configs/olimex-stm32-e407/discover/defconfig
    index 6258b571f7..dca0ba9c65 100644
    --- a/configs/olimex-stm32-e407/discover/defconfig
    +++ b/configs/olimex-stm32-e407/discover/defconfig
    @@ -90,6 +90,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -97,11 +98,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     CONFIG_ARCH_CHIP_STM32=y
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -174,6 +176,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -373,9 +378,13 @@ CONFIG_STM32_HAVE_ADC3=y
     # CONFIG_STM32_HAVE_SDADC3_DMA is not set
     CONFIG_STM32_HAVE_CAN1=y
     CONFIG_STM32_HAVE_CAN2=y
    +# CONFIG_STM32_HAVE_COMP1 is not set
     # CONFIG_STM32_HAVE_COMP2 is not set
    +# CONFIG_STM32_HAVE_COMP3 is not set
     # CONFIG_STM32_HAVE_COMP4 is not set
    +# CONFIG_STM32_HAVE_COMP5 is not set
     # CONFIG_STM32_HAVE_COMP6 is not set
    +# CONFIG_STM32_HAVE_COMP7 is not set
     CONFIG_STM32_HAVE_DAC1=y
     CONFIG_STM32_HAVE_DAC2=y
     CONFIG_STM32_HAVE_RNG=y
    @@ -389,7 +398,10 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_HAVE_SPI6 is not set
     # CONFIG_STM32_HAVE_SAIPLL is not set
     # CONFIG_STM32_HAVE_I2SPLL is not set
    -# CONFIG_STM32_HAVE_OPAMP is not set
    +# CONFIG_STM32_HAVE_OPAMP1 is not set
    +# CONFIG_STM32_HAVE_OPAMP2 is not set
    +# CONFIG_STM32_HAVE_OPAMP3 is not set
    +# CONFIG_STM32_HAVE_OPAMP4 is not set
     # CONFIG_STM32_ADC1 is not set
     # CONFIG_STM32_ADC2 is not set
     # CONFIG_STM32_ADC3 is not set
    @@ -410,6 +422,7 @@ CONFIG_STM32_ETHMAC=y
     # CONFIG_STM32_I2C1 is not set
     # CONFIG_STM32_I2C2 is not set
     # CONFIG_STM32_I2C3 is not set
    +# CONFIG_STM32_OPAMP is not set
     # CONFIG_STM32_OTGFS is not set
     # CONFIG_STM32_OTGHS is not set
     CONFIG_STM32_PWR=y
    @@ -447,6 +460,7 @@ CONFIG_STM32_USART2=y
     # Alternate Pin Mapping
     #
     # CONFIG_STM32_FLASH_PREFETCH is not set
    +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set
     # CONFIG_STM32_JTAG_DISABLE is not set
     CONFIG_STM32_JTAG_FULL_ENABLE=y
     # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
    @@ -666,6 +680,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -899,6 +915,7 @@ CONFIG_USART2_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -939,10 +956,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -973,6 +992,7 @@ CONFIG_NET_SOLINGER=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=40
     CONFIG_NET_MAX_LISTENPORTS=40
    @@ -987,6 +1007,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -1016,10 +1037,14 @@ CONFIG_NET_ARP_IPIN=y
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1265,7 +1290,6 @@ CONFIG_EXAMPLES_DISCOVER_NETMASK=0xffffff00
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1298,6 +1322,7 @@ CONFIG_EXAMPLES_DISCOVER_NETMASK=0xffffff00
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -1389,3 +1414,7 @@ CONFIG_NETUTILS_NETLIB=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/olimex-stm32-e407/netnsh/defconfig b/configs/olimex-stm32-e407/netnsh/defconfig
    index 5b545509a9..34486378ca 100644
    --- a/configs/olimex-stm32-e407/netnsh/defconfig
    +++ b/configs/olimex-stm32-e407/netnsh/defconfig
    @@ -90,6 +90,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -97,11 +98,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     CONFIG_ARCH_CHIP_STM32=y
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -174,6 +176,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -373,9 +378,13 @@ CONFIG_STM32_HAVE_ADC3=y
     # CONFIG_STM32_HAVE_SDADC3_DMA is not set
     CONFIG_STM32_HAVE_CAN1=y
     CONFIG_STM32_HAVE_CAN2=y
    +# CONFIG_STM32_HAVE_COMP1 is not set
     # CONFIG_STM32_HAVE_COMP2 is not set
    +# CONFIG_STM32_HAVE_COMP3 is not set
     # CONFIG_STM32_HAVE_COMP4 is not set
    +# CONFIG_STM32_HAVE_COMP5 is not set
     # CONFIG_STM32_HAVE_COMP6 is not set
    +# CONFIG_STM32_HAVE_COMP7 is not set
     CONFIG_STM32_HAVE_DAC1=y
     CONFIG_STM32_HAVE_DAC2=y
     CONFIG_STM32_HAVE_RNG=y
    @@ -389,7 +398,10 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_HAVE_SPI6 is not set
     # CONFIG_STM32_HAVE_SAIPLL is not set
     # CONFIG_STM32_HAVE_I2SPLL is not set
    -# CONFIG_STM32_HAVE_OPAMP is not set
    +# CONFIG_STM32_HAVE_OPAMP1 is not set
    +# CONFIG_STM32_HAVE_OPAMP2 is not set
    +# CONFIG_STM32_HAVE_OPAMP3 is not set
    +# CONFIG_STM32_HAVE_OPAMP4 is not set
     # CONFIG_STM32_ADC1 is not set
     # CONFIG_STM32_ADC2 is not set
     # CONFIG_STM32_ADC3 is not set
    @@ -410,6 +422,7 @@ CONFIG_STM32_ETHMAC=y
     # CONFIG_STM32_I2C1 is not set
     # CONFIG_STM32_I2C2 is not set
     # CONFIG_STM32_I2C3 is not set
    +# CONFIG_STM32_OPAMP is not set
     # CONFIG_STM32_OTGFS is not set
     # CONFIG_STM32_OTGHS is not set
     CONFIG_STM32_PWR=y
    @@ -447,6 +460,7 @@ CONFIG_STM32_USART2=y
     # Alternate Pin Mapping
     #
     # CONFIG_STM32_FLASH_PREFETCH is not set
    +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set
     # CONFIG_STM32_JTAG_DISABLE is not set
     CONFIG_STM32_JTAG_FULL_ENABLE=y
     # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
    @@ -666,6 +680,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -901,6 +917,7 @@ CONFIG_USART2_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -941,10 +958,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -975,6 +994,7 @@ CONFIG_NET_SOLINGER=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=40
     CONFIG_NET_MAX_LISTENPORTS=40
    @@ -989,6 +1009,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -1018,10 +1039,14 @@ CONFIG_NET_ARP_IPIN=y
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1263,7 +1288,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y
     # CONFIG_EXAMPLES_NULL is not set
    @@ -1297,6 +1321,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y
     # CONFIG_EXAMPLES_UDPBLASTER is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -1522,3 +1547,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/olimex-stm32-e407/telnetd/defconfig b/configs/olimex-stm32-e407/telnetd/defconfig
    index 95cd79b059..9768cb9553 100644
    --- a/configs/olimex-stm32-e407/telnetd/defconfig
    +++ b/configs/olimex-stm32-e407/telnetd/defconfig
    @@ -90,6 +90,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -97,11 +98,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     CONFIG_ARCH_CHIP_STM32=y
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -174,6 +176,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -373,9 +378,13 @@ CONFIG_STM32_HAVE_ADC3=y
     # CONFIG_STM32_HAVE_SDADC3_DMA is not set
     CONFIG_STM32_HAVE_CAN1=y
     CONFIG_STM32_HAVE_CAN2=y
    +# CONFIG_STM32_HAVE_COMP1 is not set
     # CONFIG_STM32_HAVE_COMP2 is not set
    +# CONFIG_STM32_HAVE_COMP3 is not set
     # CONFIG_STM32_HAVE_COMP4 is not set
    +# CONFIG_STM32_HAVE_COMP5 is not set
     # CONFIG_STM32_HAVE_COMP6 is not set
    +# CONFIG_STM32_HAVE_COMP7 is not set
     CONFIG_STM32_HAVE_DAC1=y
     CONFIG_STM32_HAVE_DAC2=y
     CONFIG_STM32_HAVE_RNG=y
    @@ -389,7 +398,10 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_HAVE_SPI6 is not set
     # CONFIG_STM32_HAVE_SAIPLL is not set
     # CONFIG_STM32_HAVE_I2SPLL is not set
    -# CONFIG_STM32_HAVE_OPAMP is not set
    +# CONFIG_STM32_HAVE_OPAMP1 is not set
    +# CONFIG_STM32_HAVE_OPAMP2 is not set
    +# CONFIG_STM32_HAVE_OPAMP3 is not set
    +# CONFIG_STM32_HAVE_OPAMP4 is not set
     # CONFIG_STM32_ADC1 is not set
     # CONFIG_STM32_ADC2 is not set
     # CONFIG_STM32_ADC3 is not set
    @@ -410,6 +422,7 @@ CONFIG_STM32_ETHMAC=y
     # CONFIG_STM32_I2C1 is not set
     # CONFIG_STM32_I2C2 is not set
     # CONFIG_STM32_I2C3 is not set
    +# CONFIG_STM32_OPAMP is not set
     # CONFIG_STM32_OTGFS is not set
     # CONFIG_STM32_OTGHS is not set
     CONFIG_STM32_PWR=y
    @@ -447,6 +460,7 @@ CONFIG_STM32_USART2=y
     # Alternate Pin Mapping
     #
     # CONFIG_STM32_FLASH_PREFETCH is not set
    +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set
     # CONFIG_STM32_JTAG_DISABLE is not set
     CONFIG_STM32_JTAG_FULL_ENABLE=y
     # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
    @@ -666,6 +680,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -901,6 +917,7 @@ CONFIG_USART2_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -941,10 +958,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -975,6 +994,7 @@ CONFIG_NET_SOLINGER=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=40
     CONFIG_NET_MAX_LISTENPORTS=40
    @@ -989,6 +1009,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -1018,10 +1039,14 @@ CONFIG_NET_ARP_IPIN=y
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1263,7 +1288,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1304,6 +1328,7 @@ CONFIG_EXAMPLES_TELNETD_CLIENTSTACKSIZE=2048
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -1395,3 +1420,7 @@ CONFIG_NETUTILS_TELNETD=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/olimex-stm32-e407/webserver/defconfig b/configs/olimex-stm32-e407/webserver/defconfig
    index 9c68bf47a3..4257b4218f 100644
    --- a/configs/olimex-stm32-e407/webserver/defconfig
    +++ b/configs/olimex-stm32-e407/webserver/defconfig
    @@ -90,6 +90,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -97,11 +98,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     CONFIG_ARCH_CHIP_STM32=y
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -174,6 +176,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -373,9 +378,13 @@ CONFIG_STM32_HAVE_ADC3=y
     # CONFIG_STM32_HAVE_SDADC3_DMA is not set
     CONFIG_STM32_HAVE_CAN1=y
     CONFIG_STM32_HAVE_CAN2=y
    +# CONFIG_STM32_HAVE_COMP1 is not set
     # CONFIG_STM32_HAVE_COMP2 is not set
    +# CONFIG_STM32_HAVE_COMP3 is not set
     # CONFIG_STM32_HAVE_COMP4 is not set
    +# CONFIG_STM32_HAVE_COMP5 is not set
     # CONFIG_STM32_HAVE_COMP6 is not set
    +# CONFIG_STM32_HAVE_COMP7 is not set
     CONFIG_STM32_HAVE_DAC1=y
     CONFIG_STM32_HAVE_DAC2=y
     CONFIG_STM32_HAVE_RNG=y
    @@ -389,7 +398,10 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_HAVE_SPI6 is not set
     # CONFIG_STM32_HAVE_SAIPLL is not set
     # CONFIG_STM32_HAVE_I2SPLL is not set
    -# CONFIG_STM32_HAVE_OPAMP is not set
    +# CONFIG_STM32_HAVE_OPAMP1 is not set
    +# CONFIG_STM32_HAVE_OPAMP2 is not set
    +# CONFIG_STM32_HAVE_OPAMP3 is not set
    +# CONFIG_STM32_HAVE_OPAMP4 is not set
     # CONFIG_STM32_ADC1 is not set
     # CONFIG_STM32_ADC2 is not set
     # CONFIG_STM32_ADC3 is not set
    @@ -410,6 +422,7 @@ CONFIG_STM32_ETHMAC=y
     # CONFIG_STM32_I2C1 is not set
     # CONFIG_STM32_I2C2 is not set
     # CONFIG_STM32_I2C3 is not set
    +# CONFIG_STM32_OPAMP is not set
     # CONFIG_STM32_OTGFS is not set
     # CONFIG_STM32_OTGHS is not set
     CONFIG_STM32_PWR=y
    @@ -447,6 +460,7 @@ CONFIG_STM32_USART2=y
     # Alternate Pin Mapping
     #
     # CONFIG_STM32_FLASH_PREFETCH is not set
    +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set
     # CONFIG_STM32_JTAG_DISABLE is not set
     CONFIG_STM32_JTAG_FULL_ENABLE=y
     # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
    @@ -666,6 +680,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -899,6 +915,7 @@ CONFIG_USART2_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -939,10 +956,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -973,6 +992,7 @@ CONFIG_NET_SOLINGER=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=40
     CONFIG_NET_MAX_LISTENPORTS=40
    @@ -987,6 +1007,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -1016,10 +1037,14 @@ CONFIG_NET_ARP_IPIN=y
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1261,7 +1286,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1298,6 +1322,7 @@ CONFIG_EXAMPLES_WEBSERVER_DRIPADDR=0xc0a80101
     CONFIG_EXAMPLES_WEBSERVER_NETMASK=0xffffff00
     CONFIG_EXAMPLES_WEBSERVER_NOMAC=y
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -1400,3 +1425,7 @@ CONFIG_NETUTILS_HTTPD_KEEPALIVE_DISABLE=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/olimex-stm32-p107/nsh/defconfig b/configs/olimex-stm32-p107/nsh/defconfig
    index 65d116da37..4df7a5586d 100644
    --- a/configs/olimex-stm32-p107/nsh/defconfig
    +++ b/configs/olimex-stm32-p107/nsh/defconfig
    @@ -90,6 +90,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -97,11 +98,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     CONFIG_ARCH_CHIP_STM32=y
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -174,6 +176,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -373,9 +378,13 @@ CONFIG_STM32_HAVE_ADC2=y
     # CONFIG_STM32_HAVE_SDADC3_DMA is not set
     CONFIG_STM32_HAVE_CAN1=y
     CONFIG_STM32_HAVE_CAN2=y
    +# CONFIG_STM32_HAVE_COMP1 is not set
     # CONFIG_STM32_HAVE_COMP2 is not set
    +# CONFIG_STM32_HAVE_COMP3 is not set
     # CONFIG_STM32_HAVE_COMP4 is not set
    +# CONFIG_STM32_HAVE_COMP5 is not set
     # CONFIG_STM32_HAVE_COMP6 is not set
    +# CONFIG_STM32_HAVE_COMP7 is not set
     CONFIG_STM32_HAVE_DAC1=y
     CONFIG_STM32_HAVE_DAC2=y
     # CONFIG_STM32_HAVE_RNG is not set
    @@ -389,7 +398,10 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_HAVE_SPI6 is not set
     # CONFIG_STM32_HAVE_SAIPLL is not set
     # CONFIG_STM32_HAVE_I2SPLL is not set
    -# CONFIG_STM32_HAVE_OPAMP is not set
    +# CONFIG_STM32_HAVE_OPAMP1 is not set
    +# CONFIG_STM32_HAVE_OPAMP2 is not set
    +# CONFIG_STM32_HAVE_OPAMP3 is not set
    +# CONFIG_STM32_HAVE_OPAMP4 is not set
     # CONFIG_STM32_ADC1 is not set
     # CONFIG_STM32_ADC2 is not set
     # CONFIG_STM32_BKP is not set
    @@ -402,6 +414,7 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_DAC2 is not set
     CONFIG_STM32_ETHMAC=y
     # CONFIG_STM32_I2C1 is not set
    +# CONFIG_STM32_OPAMP is not set
     # CONFIG_STM32_OTGFS is not set
     CONFIG_STM32_PWR=y
     # CONFIG_STM32_SPI1 is not set
    @@ -429,6 +442,7 @@ CONFIG_STM32_USART2=y
     #
     # CONFIG_STM32_ETH_REMAP is not set
     CONFIG_STM32_USART2_REMAP=y
    +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set
     # CONFIG_STM32_JTAG_DISABLE is not set
     CONFIG_STM32_JTAG_FULL_ENABLE=y
     # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
    @@ -633,6 +647,8 @@ CONFIG_MAX_TASKS=16
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -901,6 +917,7 @@ CONFIG_USART2_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -941,10 +958,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -975,6 +994,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=40
     CONFIG_NET_MAX_LISTENPORTS=40
    @@ -989,6 +1009,7 @@ CONFIG_NET_TCP_RECVDELAY=0
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     # CONFIG_NET_UDP_CHECKSUMS is not set
     CONFIG_NET_UDP_CONNS=8
     # CONFIG_NET_BROADCAST is not set
    @@ -1018,10 +1039,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -1250,7 +1275,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1283,6 +1307,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_UDPBLASTER is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -1493,3 +1518,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/olimex-stm32-p207/nsh/defconfig b/configs/olimex-stm32-p207/nsh/defconfig
    index ad40ad6b83..315f0dba73 100644
    --- a/configs/olimex-stm32-p207/nsh/defconfig
    +++ b/configs/olimex-stm32-p207/nsh/defconfig
    @@ -183,6 +183,9 @@ CONFIG_CAN_TSEG2=8
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -1079,7 +1082,7 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    diff --git a/configs/olimex-strp711/nettest/defconfig b/configs/olimex-strp711/nettest/defconfig
    index 80f439771a..55e048aacd 100644
    --- a/configs/olimex-strp711/nettest/defconfig
    +++ b/configs/olimex-strp711/nettest/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     CONFIG_ARCH_CHIP_STR71X=y
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     CONFIG_ARCH_ARM7TDMI=y
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -300,6 +302,8 @@ CONFIG_MAX_TASKS=16
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -531,6 +535,7 @@ CONFIG_UART1_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -571,10 +576,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -605,6 +612,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -619,6 +627,7 @@ CONFIG_NET_TCP_RECVDELAY=0
     # UDP Networking
     #
     # CONFIG_NET_UDP is not set
    +# CONFIG_NET_UDP_NO_STACK is not set
     
     #
     # ICMP Networking Support
    @@ -643,10 +652,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -848,6 +861,8 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     CONFIG_EXAMPLES_NETTEST=y
    +CONFIG_EXAMPLES_NETTEST_STACKSIZE=2048
    +CONFIG_EXAMPLES_NETTEST_PRIORITY=100
     # CONFIG_EXAMPLES_NETTEST_SERVER is not set
     # CONFIG_EXAMPLES_NETTEST_PERFORMANCE is not set
     CONFIG_EXAMPLES_NETTEST_IPv4=y
    @@ -861,7 +876,6 @@ CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002
     CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001
     CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00
     CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -892,6 +906,7 @@ CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -967,3 +982,7 @@ CONFIG_NETUTILS_NETLIB=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/pic32mx-starterkit/nsh2/defconfig b/configs/pic32mx-starterkit/nsh2/defconfig
    index 97f66c82f1..12de402bbf 100644
    --- a/configs/pic32mx-starterkit/nsh2/defconfig
    +++ b/configs/pic32mx-starterkit/nsh2/defconfig
    @@ -399,6 +399,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -647,6 +649,7 @@ CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -694,10 +697,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -728,6 +733,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=40
     CONFIG_NET_MAX_LISTENPORTS=40
    @@ -742,6 +748,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -771,10 +778,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -1006,7 +1017,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1040,6 +1050,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -1264,3 +1275,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/pic32mx7mmb/nsh/defconfig b/configs/pic32mx7mmb/nsh/defconfig
    index 929fecc497..4cfed72604 100644
    --- a/configs/pic32mx7mmb/nsh/defconfig
    +++ b/configs/pic32mx7mmb/nsh/defconfig
    @@ -408,6 +408,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -717,6 +719,7 @@ CONFIG_USBMSC_REMOVABLE=y
     CONFIG_USBMSC_SCSI_PRIO=128
     CONFIG_USBMSC_SCSI_STACKSIZE=2048
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -757,10 +760,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -791,6 +796,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=40
     CONFIG_NET_MAX_LISTENPORTS=40
    @@ -805,6 +811,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -834,10 +841,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -1069,7 +1080,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1103,6 +1113,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1336,3 +1347,7 @@ CONFIG_SYSTEM_USBMSC_CMD_STACKSIZE=768
     CONFIG_SYSTEM_USBMSC_CMD_PRIORITY=100
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/sam4e-ek/nsh/defconfig b/configs/sam4e-ek/nsh/defconfig
    index 7eff414e3d..18a8cc7fd0 100644
    --- a/configs/sam4e-ek/nsh/defconfig
    +++ b/configs/sam4e-ek/nsh/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH="arm"
     CONFIG_ARCH_CHIP_SAM34=y
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -435,6 +437,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -715,6 +719,7 @@ CONFIG_USART1_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -755,10 +760,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -789,6 +796,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=16
     CONFIG_NET_MAX_LISTENPORTS=16
    @@ -803,6 +811,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -834,11 +843,15 @@ CONFIG_ARP_SEND_DELAYMSEC=20
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
     CONFIG_IOB_THROTTLE=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -1077,7 +1090,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1111,6 +1123,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1333,3 +1346,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/sam4e-ek/nxwm/defconfig b/configs/sam4e-ek/nxwm/defconfig
    index 27ee8c8d62..6280d4b140 100644
    --- a/configs/sam4e-ek/nxwm/defconfig
    +++ b/configs/sam4e-ek/nxwm/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH="arm"
     CONFIG_ARCH_CHIP_SAM34=y
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -442,6 +444,9 @@ CONFIG_SCHED_WAITPID=y
     # Pthread Options
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
    +CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -773,6 +778,7 @@ CONFIG_USART1_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -813,10 +819,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -847,6 +855,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=16
     CONFIG_NET_MAX_LISTENPORTS=16
    @@ -861,6 +870,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -892,10 +902,14 @@ CONFIG_ARP_SEND_DELAYMSEC=20
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -1260,7 +1274,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1294,6 +1307,7 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1692,3 +1706,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/sam4e-ek/usbnsh/defconfig b/configs/sam4e-ek/usbnsh/defconfig
    index 68f8fe5e1f..197e6519a4 100644
    --- a/configs/sam4e-ek/usbnsh/defconfig
    +++ b/configs/sam4e-ek/usbnsh/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH="arm"
     CONFIG_ARCH_CHIP_SAM34=y
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -441,6 +443,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -760,6 +764,7 @@ CONFIG_CDCACM_VENDORSTR="NuttX"
     CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial"
     # CONFIG_USBMSC is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -801,10 +806,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -835,6 +842,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=16
     CONFIG_NET_MAX_LISTENPORTS=16
    @@ -849,6 +857,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -878,10 +887,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -1120,7 +1133,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1154,6 +1166,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1378,3 +1391,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/sama5d3-xplained/bridge/defconfig b/configs/sama5d3-xplained/bridge/defconfig
    index 832bcc3d95..ab2ee2b39d 100644
    --- a/configs/sama5d3-xplained/bridge/defconfig
    +++ b/configs/sama5d3-xplained/bridge/defconfig
    @@ -95,6 +95,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     CONFIG_ARCH_CHIP_SAMA5=y
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -102,11 +103,12 @@ CONFIG_ARCH_CHIP_SAMA5=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -462,6 +464,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -681,6 +685,7 @@ CONFIG_OTHER_SERIAL_CONSOLE=y
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -720,10 +725,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -754,11 +761,13 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     # CONFIG_NET_TCP is not set
    +# CONFIG_NET_TCP_NO_STACK is not set
     
     #
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     # CONFIG_NET_UDP_CHECKSUMS is not set
     CONFIG_NET_UDP_CONNS=16
     CONFIG_NET_BROADCAST=y
    @@ -790,7 +799,11 @@ CONFIG_ARP_SEND_DELAYMSEC=20
     #
     # Network I/O Buffer Support
     #
    -# CONFIG_NET_IOB is not set
    +# CONFIG_DRIVERS_IOB is not set
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -1071,7 +1084,6 @@ CONFIG_EXAMPLES_BRIDGE_NET2_PRIORITY=100
     # CONFIG_EXAMPLES_MM is not set
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1103,6 +1115,7 @@ CONFIG_EXAMPLES_BRIDGE_NET2_PRIORITY=100
     # CONFIG_EXAMPLES_UDPBLASTER is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1186,3 +1199,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/sama5d4-ek/bridge/defconfig b/configs/sama5d4-ek/bridge/defconfig
    index 231ddb7907..9f463640df 100644
    --- a/configs/sama5d4-ek/bridge/defconfig
    +++ b/configs/sama5d4-ek/bridge/defconfig
    @@ -95,6 +95,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     CONFIG_ARCH_CHIP_SAMA5=y
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -102,11 +103,12 @@ CONFIG_ARCH_CHIP_SAMA5=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -480,6 +482,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -713,6 +717,7 @@ CONFIG_USART3_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -752,10 +757,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -786,11 +793,13 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     # CONFIG_NET_TCP is not set
    +# CONFIG_NET_TCP_NO_STACK is not set
     
     #
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     # CONFIG_NET_UDP_CHECKSUMS is not set
     CONFIG_NET_UDP_CONNS=16
     CONFIG_NET_BROADCAST=y
    @@ -822,7 +831,11 @@ CONFIG_ARP_SEND_DELAYMSEC=20
     #
     # Network I/O Buffer Support
     #
    -# CONFIG_NET_IOB is not set
    +# CONFIG_DRIVERS_IOB is not set
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -1103,7 +1116,6 @@ CONFIG_EXAMPLES_BRIDGE_NET2_PRIORITY=100
     # CONFIG_EXAMPLES_MM is not set
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1135,6 +1147,7 @@ CONFIG_EXAMPLES_BRIDGE_NET2_PRIORITY=100
     # CONFIG_EXAMPLES_UDPBLASTER is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1218,3 +1231,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/sama5d4-ek/ipv6/defconfig b/configs/sama5d4-ek/ipv6/defconfig
    index d83898fe04..e0c7c271e0 100644
    --- a/configs/sama5d4-ek/ipv6/defconfig
    +++ b/configs/sama5d4-ek/ipv6/defconfig
    @@ -95,6 +95,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     CONFIG_ARCH_CHIP_SAMA5=y
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -102,11 +103,12 @@ CONFIG_ARCH_CHIP_SAMA5=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -579,6 +581,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -884,7 +888,9 @@ CONFIG_HIDKBD_NPOLLWAITERS=2
     # CONFIG_HIDKBD_NODEBOUNCE is not set
     # CONFIG_USBHOST_HIDMOUSE is not set
     # CONFIG_USBHOST_RTL8187 is not set
    +# CONFIG_USBHOST_XBOXCONTROLLER is not set
     # CONFIG_USBHOST_TRACE is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -932,10 +938,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -967,6 +975,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=20
    @@ -981,6 +990,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -1010,11 +1020,15 @@ CONFIG_ICMPv6_NEIGHBOR_DELAYMSEC=20
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=36
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
     CONFIG_IOB_THROTTLE=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1389,7 +1403,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y
     # CONFIG_EXAMPLES_NULL is not set
    @@ -1440,6 +1453,7 @@ CONFIG_EXAMPLES_TOUCHSCREEN_ARCHINIT=y
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -1711,3 +1725,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/sama5d4-ek/nsh/defconfig b/configs/sama5d4-ek/nsh/defconfig
    index 67627b5567..e323ec55fa 100644
    --- a/configs/sama5d4-ek/nsh/defconfig
    +++ b/configs/sama5d4-ek/nsh/defconfig
    @@ -95,6 +95,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     CONFIG_ARCH_CHIP_SAMA5=y
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -102,11 +103,12 @@ CONFIG_ARCH_CHIP_SAMA5=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -579,6 +581,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -886,7 +890,9 @@ CONFIG_HIDKBD_NPOLLWAITERS=2
     # CONFIG_HIDKBD_NODEBOUNCE is not set
     # CONFIG_USBHOST_HIDMOUSE is not set
     # CONFIG_USBHOST_RTL8187 is not set
    +# CONFIG_USBHOST_XBOXCONTROLLER is not set
     # CONFIG_USBHOST_TRACE is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -934,10 +940,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -968,6 +976,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=20
    @@ -982,6 +991,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     # CONFIG_NET_UDP_CHECKSUMS is not set
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -1013,11 +1023,15 @@ CONFIG_ARP_SEND_DELAYMSEC=20
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=36
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
     CONFIG_IOB_THROTTLE=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1400,7 +1414,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y
     # CONFIG_EXAMPLES_NULL is not set
    @@ -1451,6 +1464,7 @@ CONFIG_EXAMPLES_TOUCHSCREEN_ARCHINIT=y
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -1712,3 +1726,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/sama5d4-ek/nxwm/defconfig b/configs/sama5d4-ek/nxwm/defconfig
    index f2dbc256a6..81b25c7dd1 100644
    --- a/configs/sama5d4-ek/nxwm/defconfig
    +++ b/configs/sama5d4-ek/nxwm/defconfig
    @@ -95,6 +95,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     CONFIG_ARCH_CHIP_SAMA5=y
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -102,11 +103,12 @@ CONFIG_ARCH_CHIP_SAMA5=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -551,6 +553,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -855,7 +859,9 @@ CONFIG_HIDKBD_NPOLLWAITERS=2
     # CONFIG_HIDKBD_NODEBOUNCE is not set
     # CONFIG_USBHOST_HIDMOUSE is not set
     # CONFIG_USBHOST_RTL8187 is not set
    +# CONFIG_USBHOST_XBOXCONTROLLER is not set
     # CONFIG_USBHOST_TRACE is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -903,10 +909,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -937,6 +945,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=20
    @@ -951,6 +960,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     # CONFIG_NET_UDP_CHECKSUMS is not set
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -980,11 +990,15 @@ CONFIG_NET_ARP_IPIN=y
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=36
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
     CONFIG_IOB_THROTTLE=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1392,7 +1406,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1430,6 +1443,7 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -1901,3 +1915,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/same70-xplained/netnsh/defconfig b/configs/same70-xplained/netnsh/defconfig
    index 804f41e4fc..db58645eab 100644
    --- a/configs/same70-xplained/netnsh/defconfig
    +++ b/configs/same70-xplained/netnsh/defconfig
    @@ -95,6 +95,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -102,11 +103,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     CONFIG_ARCH_CHIP_SAMV7=y
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -454,6 +456,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -750,6 +754,7 @@ CONFIG_USART1_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -790,6 +795,7 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
    @@ -825,6 +831,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=20
    @@ -839,6 +846,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     # CONFIG_NET_UDP_CHECKSUMS is not set
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -870,11 +878,15 @@ CONFIG_ARP_SEND_DELAYMSEC=20
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
     CONFIG_IOB_THROTTLE=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1156,6 +1168,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1391,3 +1404,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/samv71-xult/netnsh/defconfig b/configs/samv71-xult/netnsh/defconfig
    index 395fe4df82..06ea511773 100644
    --- a/configs/samv71-xult/netnsh/defconfig
    +++ b/configs/samv71-xult/netnsh/defconfig
    @@ -104,6 +104,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     CONFIG_ARCH_CHIP_SAMV7=y
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
    @@ -756,6 +757,7 @@ CONFIG_UART3_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -796,6 +798,7 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
    @@ -831,6 +834,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=20
    @@ -845,6 +849,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     # CONFIG_NET_UDP_CHECKSUMS is not set
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -876,11 +881,15 @@ CONFIG_ARP_SEND_DELAYMSEC=20
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=36
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
     CONFIG_IOB_THROTTLE=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1399,3 +1408,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/samv71-xult/vnc/defconfig b/configs/samv71-xult/vnc/defconfig
    index b547b6f685..f5afccc5f9 100644
    --- a/configs/samv71-xult/vnc/defconfig
    +++ b/configs/samv71-xult/vnc/defconfig
    @@ -95,6 +95,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -102,11 +103,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     CONFIG_ARCH_CHIP_SAMV7=y
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -456,6 +458,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -753,6 +757,7 @@ CONFIG_UART3_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -794,6 +799,7 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
    @@ -829,6 +835,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     # CONFIG_NET_TCP_REASSEMBLY is not set
     CONFIG_NET_TCP_CONNS=8
    @@ -844,6 +851,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     # CONFIG_NET_UDP is not set
    +# CONFIG_NET_UDP_NO_STACK is not set
     
     #
     # ICMP Networking Support
    @@ -870,11 +878,15 @@ CONFIG_ARP_SEND_DELAYMSEC=20
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=72
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
     CONFIG_IOB_THROTTLE=32
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1261,6 +1273,7 @@ CONFIG_EXAMPLES_NXIMAGE_YSCALE1p0=y
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1481,3 +1494,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/samv71-xult/vnxwm/defconfig b/configs/samv71-xult/vnxwm/defconfig
    index d8c8863cb6..84584c52df 100644
    --- a/configs/samv71-xult/vnxwm/defconfig
    +++ b/configs/samv71-xult/vnxwm/defconfig
    @@ -95,6 +95,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -102,11 +103,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     CONFIG_ARCH_CHIP_SAMV7=y
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -457,6 +459,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -756,6 +760,7 @@ CONFIG_UART3_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -797,6 +802,7 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
    @@ -832,6 +838,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     # CONFIG_NET_TCP_REASSEMBLY is not set
     CONFIG_NET_TCP_CONNS=8
    @@ -847,6 +854,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     # CONFIG_NET_UDP is not set
    +# CONFIG_NET_UDP_NO_STACK is not set
     
     #
     # ICMP Networking Support
    @@ -873,11 +881,15 @@ CONFIG_ARP_SEND_DELAYMSEC=20
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=72
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
     CONFIG_IOB_THROTTLE=32
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1291,6 +1303,7 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1678,3 +1691,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/shenzhou/nsh/defconfig b/configs/shenzhou/nsh/defconfig
    index 1f26e5a9ca..e163798cf0 100644
    --- a/configs/shenzhou/nsh/defconfig
    +++ b/configs/shenzhou/nsh/defconfig
    @@ -90,6 +90,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -97,11 +98,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     CONFIG_ARCH_CHIP_STM32=y
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -172,6 +174,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -371,9 +376,13 @@ CONFIG_STM32_HAVE_ADC2=y
     # CONFIG_STM32_HAVE_SDADC3_DMA is not set
     CONFIG_STM32_HAVE_CAN1=y
     CONFIG_STM32_HAVE_CAN2=y
    +# CONFIG_STM32_HAVE_COMP1 is not set
     # CONFIG_STM32_HAVE_COMP2 is not set
    +# CONFIG_STM32_HAVE_COMP3 is not set
     # CONFIG_STM32_HAVE_COMP4 is not set
    +# CONFIG_STM32_HAVE_COMP5 is not set
     # CONFIG_STM32_HAVE_COMP6 is not set
    +# CONFIG_STM32_HAVE_COMP7 is not set
     CONFIG_STM32_HAVE_DAC1=y
     CONFIG_STM32_HAVE_DAC2=y
     # CONFIG_STM32_HAVE_RNG is not set
    @@ -387,7 +396,10 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_HAVE_SPI6 is not set
     # CONFIG_STM32_HAVE_SAIPLL is not set
     # CONFIG_STM32_HAVE_I2SPLL is not set
    -# CONFIG_STM32_HAVE_OPAMP is not set
    +# CONFIG_STM32_HAVE_OPAMP1 is not set
    +# CONFIG_STM32_HAVE_OPAMP2 is not set
    +# CONFIG_STM32_HAVE_OPAMP3 is not set
    +# CONFIG_STM32_HAVE_OPAMP4 is not set
     # CONFIG_STM32_ADC1 is not set
     # CONFIG_STM32_ADC2 is not set
     CONFIG_STM32_BKP=y
    @@ -400,6 +412,7 @@ CONFIG_STM32_BKP=y
     # CONFIG_STM32_DAC2 is not set
     CONFIG_STM32_ETHMAC=y
     # CONFIG_STM32_I2C1 is not set
    +# CONFIG_STM32_OPAMP is not set
     # CONFIG_STM32_OTGFS is not set
     CONFIG_STM32_PWR=y
     CONFIG_STM32_SPI1=y
    @@ -429,6 +442,7 @@ CONFIG_STM32_SPI=y
     CONFIG_STM32_ETH_REMAP=y
     # CONFIG_STM32_SPI1_REMAP is not set
     CONFIG_STM32_USART2_REMAP=y
    +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set
     # CONFIG_STM32_JTAG_DISABLE is not set
     CONFIG_STM32_JTAG_FULL_ENABLE=y
     # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
    @@ -653,6 +667,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -903,6 +919,7 @@ CONFIG_USART2_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -943,10 +960,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -977,6 +996,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=40
     CONFIG_NET_MAX_LISTENPORTS=40
    @@ -991,6 +1011,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     # CONFIG_NET_BROADCAST is not set
    @@ -1020,10 +1041,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1276,7 +1301,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1310,6 +1334,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1531,3 +1556,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/shenzhou/nxwm/defconfig b/configs/shenzhou/nxwm/defconfig
    index 3fb83b792a..dc29c952d3 100644
    --- a/configs/shenzhou/nxwm/defconfig
    +++ b/configs/shenzhou/nxwm/defconfig
    @@ -96,6 +96,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -103,11 +104,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     CONFIG_ARCH_CHIP_STM32=y
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -182,6 +184,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -381,9 +386,13 @@ CONFIG_STM32_HAVE_ADC2=y
     # CONFIG_STM32_HAVE_SDADC3_DMA is not set
     CONFIG_STM32_HAVE_CAN1=y
     CONFIG_STM32_HAVE_CAN2=y
    +# CONFIG_STM32_HAVE_COMP1 is not set
     # CONFIG_STM32_HAVE_COMP2 is not set
    +# CONFIG_STM32_HAVE_COMP3 is not set
     # CONFIG_STM32_HAVE_COMP4 is not set
    +# CONFIG_STM32_HAVE_COMP5 is not set
     # CONFIG_STM32_HAVE_COMP6 is not set
    +# CONFIG_STM32_HAVE_COMP7 is not set
     CONFIG_STM32_HAVE_DAC1=y
     CONFIG_STM32_HAVE_DAC2=y
     # CONFIG_STM32_HAVE_RNG is not set
    @@ -397,7 +406,10 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_HAVE_SPI6 is not set
     # CONFIG_STM32_HAVE_SAIPLL is not set
     # CONFIG_STM32_HAVE_I2SPLL is not set
    -# CONFIG_STM32_HAVE_OPAMP is not set
    +# CONFIG_STM32_HAVE_OPAMP1 is not set
    +# CONFIG_STM32_HAVE_OPAMP2 is not set
    +# CONFIG_STM32_HAVE_OPAMP3 is not set
    +# CONFIG_STM32_HAVE_OPAMP4 is not set
     # CONFIG_STM32_ADC1 is not set
     # CONFIG_STM32_ADC2 is not set
     # CONFIG_STM32_BKP is not set
    @@ -410,6 +422,7 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_DAC2 is not set
     CONFIG_STM32_ETHMAC=y
     # CONFIG_STM32_I2C1 is not set
    +# CONFIG_STM32_OPAMP is not set
     # CONFIG_STM32_OTGFS is not set
     # CONFIG_STM32_PWR is not set
     # CONFIG_STM32_SPI1 is not set
    @@ -439,6 +452,7 @@ CONFIG_STM32_SPI=y
     CONFIG_STM32_ETH_REMAP=y
     CONFIG_STM32_SPI3_REMAP=y
     CONFIG_STM32_USART2_REMAP=y
    +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set
     # CONFIG_STM32_JTAG_DISABLE is not set
     CONFIG_STM32_JTAG_FULL_ENABLE=y
     # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
    @@ -676,6 +690,8 @@ CONFIG_MAX_TASKS=16
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -963,6 +979,7 @@ CONFIG_USART2_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -1003,10 +1020,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -1037,6 +1056,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=16
     CONFIG_NET_MAX_LISTENPORTS=16
    @@ -1051,6 +1071,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     # CONFIG_NET_BROADCAST is not set
    @@ -1080,10 +1101,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1433,7 +1458,6 @@ CONFIG_HAVE_CXXINITIALIZE=y
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1467,6 +1491,7 @@ CONFIG_HAVE_CXXINITIALIZE=y
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1851,3 +1876,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/shenzhou/thttpd/defconfig b/configs/shenzhou/thttpd/defconfig
    index e005e95bda..8abca6cb9a 100644
    --- a/configs/shenzhou/thttpd/defconfig
    +++ b/configs/shenzhou/thttpd/defconfig
    @@ -90,6 +90,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -97,11 +98,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     CONFIG_ARCH_CHIP_STM32=y
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -173,6 +175,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -372,9 +377,13 @@ CONFIG_STM32_HAVE_ADC2=y
     # CONFIG_STM32_HAVE_SDADC3_DMA is not set
     CONFIG_STM32_HAVE_CAN1=y
     CONFIG_STM32_HAVE_CAN2=y
    +# CONFIG_STM32_HAVE_COMP1 is not set
     # CONFIG_STM32_HAVE_COMP2 is not set
    +# CONFIG_STM32_HAVE_COMP3 is not set
     # CONFIG_STM32_HAVE_COMP4 is not set
    +# CONFIG_STM32_HAVE_COMP5 is not set
     # CONFIG_STM32_HAVE_COMP6 is not set
    +# CONFIG_STM32_HAVE_COMP7 is not set
     CONFIG_STM32_HAVE_DAC1=y
     CONFIG_STM32_HAVE_DAC2=y
     # CONFIG_STM32_HAVE_RNG is not set
    @@ -388,7 +397,10 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_HAVE_SPI6 is not set
     # CONFIG_STM32_HAVE_SAIPLL is not set
     # CONFIG_STM32_HAVE_I2SPLL is not set
    -# CONFIG_STM32_HAVE_OPAMP is not set
    +# CONFIG_STM32_HAVE_OPAMP1 is not set
    +# CONFIG_STM32_HAVE_OPAMP2 is not set
    +# CONFIG_STM32_HAVE_OPAMP3 is not set
    +# CONFIG_STM32_HAVE_OPAMP4 is not set
     # CONFIG_STM32_ADC1 is not set
     # CONFIG_STM32_ADC2 is not set
     CONFIG_STM32_BKP=y
    @@ -401,6 +413,7 @@ CONFIG_STM32_BKP=y
     # CONFIG_STM32_DAC2 is not set
     CONFIG_STM32_ETHMAC=y
     # CONFIG_STM32_I2C1 is not set
    +# CONFIG_STM32_OPAMP is not set
     # CONFIG_STM32_OTGFS is not set
     CONFIG_STM32_PWR=y
     CONFIG_STM32_SPI1=y
    @@ -430,6 +443,7 @@ CONFIG_STM32_SPI=y
     CONFIG_STM32_ETH_REMAP=y
     # CONFIG_STM32_SPI1_REMAP is not set
     CONFIG_STM32_USART2_REMAP=y
    +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set
     # CONFIG_STM32_JTAG_DISABLE is not set
     CONFIG_STM32_JTAG_FULL_ENABLE=y
     # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
    @@ -654,6 +668,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -933,6 +949,7 @@ CONFIG_USART2_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -973,10 +990,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -1007,6 +1026,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=40
     CONFIG_NET_MAX_LISTENPORTS=40
    @@ -1021,6 +1041,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -1050,10 +1071,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1306,7 +1331,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1348,6 +1372,7 @@ CONFIG_EXAMPLES_THTTPD_NETMASK=0xffffff00
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -1606,3 +1631,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/sim/nettest/defconfig b/configs/sim/nettest/defconfig
    index 2c94b1e3a6..27be8a0ebc 100644
    --- a/configs/sim/nettest/defconfig
    +++ b/configs/sim/nettest/defconfig
    @@ -488,7 +488,7 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    @@ -716,6 +716,8 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     CONFIG_EXAMPLES_NETTEST=y
    +CONFIG_EXAMPLES_NETTEST_STACKSIZE=2048
    +CONFIG_EXAMPLES_NETTEST_PRIORITY=100
     # CONFIG_EXAMPLES_NETTEST_SERVER is not set
     # CONFIG_EXAMPLES_NETTEST_PERFORMANCE is not set
     CONFIG_EXAMPLES_NETTEST_IPv4=y
    @@ -837,3 +839,7 @@ CONFIG_NETUTILS_NETLIB=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/sim/sixlowpan/defconfig b/configs/sim/sixlowpan/defconfig
    index 0c6809ad43..5065856d47 100644
    --- a/configs/sim/sixlowpan/defconfig
    +++ b/configs/sim/sixlowpan/defconfig
    @@ -542,7 +542,6 @@ CONFIG_NET_6LOWPAN_MAXADDRCONTEXT_PREFIX_0_1=0xaa
     # CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED is not set
     CONFIG_NET_6LOWPAN_MAXAGE=20
     CONFIG_NET_6LOWPAN_MAX_MACTRANSMITS=4
    -CONFIG_NET_6LOWPAN_MAXPAYLOAD=102
     CONFIG_NET_6LOWPAN_MTU=1294
     CONFIG_NET_6LOWPAN_TCP_RECVWNDO=102
     
    @@ -608,7 +607,7 @@ CONFIG_NET_UDP_READAHEAD=y
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=36
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    @@ -947,7 +946,7 @@ CONFIG_EXAMPLES_UDPBLASTER_TARGETIPv6_7=0xfe00
     CONFIG_EXAMPLES_UDPBLASTER_TARGETIPv6_8=0xa9cd
     
     #
    -# Router IPv6 address
    +# Host IPv6 address
     #
     CONFIG_EXAMPLES_UDPBLASTER_HOSTIPv6_1=0xfe80
     CONFIG_EXAMPLES_UDPBLASTER_HOSTIPv6_2=0x0000
    @@ -1163,6 +1162,7 @@ CONFIG_NSH_IPv6NETMASK_8=0x0000
     CONFIG_NSH_NOMAC=y
     CONFIG_NSH_SWMAC=y
     CONFIG_NSH_MACADDR=0xabcd
    +CONFIG_NSH_PANID=0xface
     CONFIG_NSH_MAX_ROUNDTRIP=20
     # CONFIG_NSH_LOGIN is not set
     # CONFIG_NSH_CONSOLE_LOGIN is not set
    @@ -1207,3 +1207,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/sim/udgram/defconfig b/configs/sim/udgram/defconfig
    index aacb9eb00e..352667b42b 100644
    --- a/configs/sim/udgram/defconfig
    +++ b/configs/sim/udgram/defconfig
    @@ -479,7 +479,7 @@ CONFIG_NET_LOCAL_DGRAM=y
     #
     # Network I/O Buffer Support
     #
    -# CONFIG_NET_IOB is not set
    +# CONFIG_DRIVERS_IOB is not set
     
     #
     # User-space networking stack API
    @@ -973,3 +973,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/sim/ustream/defconfig b/configs/sim/ustream/defconfig
    index 43bb73515d..6b0726a89d 100644
    --- a/configs/sim/ustream/defconfig
    +++ b/configs/sim/ustream/defconfig
    @@ -479,7 +479,7 @@ CONFIG_NET_LOCAL_STREAM=y
     #
     # Network I/O Buffer Support
     #
    -# CONFIG_NET_IOB is not set
    +# CONFIG_DRIVERS_IOB is not set
     
     #
     # User-space networking stack API
    @@ -968,3 +968,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/stm3220g-eval/dhcpd/defconfig b/configs/stm3220g-eval/dhcpd/defconfig
    index bcceb6ba8e..ff770e02cb 100644
    --- a/configs/stm3220g-eval/dhcpd/defconfig
    +++ b/configs/stm3220g-eval/dhcpd/defconfig
    @@ -96,6 +96,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -103,11 +104,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     CONFIG_ARCH_CHIP_STM32=y
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -182,6 +184,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -381,9 +386,13 @@ CONFIG_STM32_HAVE_ADC3=y
     # CONFIG_STM32_HAVE_SDADC3_DMA is not set
     CONFIG_STM32_HAVE_CAN1=y
     CONFIG_STM32_HAVE_CAN2=y
    +# CONFIG_STM32_HAVE_COMP1 is not set
     # CONFIG_STM32_HAVE_COMP2 is not set
    +# CONFIG_STM32_HAVE_COMP3 is not set
     # CONFIG_STM32_HAVE_COMP4 is not set
    +# CONFIG_STM32_HAVE_COMP5 is not set
     # CONFIG_STM32_HAVE_COMP6 is not set
    +# CONFIG_STM32_HAVE_COMP7 is not set
     CONFIG_STM32_HAVE_DAC1=y
     CONFIG_STM32_HAVE_DAC2=y
     CONFIG_STM32_HAVE_RNG=y
    @@ -397,7 +406,10 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_HAVE_SPI6 is not set
     # CONFIG_STM32_HAVE_SAIPLL is not set
     # CONFIG_STM32_HAVE_I2SPLL is not set
    -# CONFIG_STM32_HAVE_OPAMP is not set
    +# CONFIG_STM32_HAVE_OPAMP1 is not set
    +# CONFIG_STM32_HAVE_OPAMP2 is not set
    +# CONFIG_STM32_HAVE_OPAMP3 is not set
    +# CONFIG_STM32_HAVE_OPAMP4 is not set
     # CONFIG_STM32_ADC1 is not set
     # CONFIG_STM32_ADC2 is not set
     # CONFIG_STM32_ADC3 is not set
    @@ -417,6 +429,7 @@ CONFIG_STM32_ETHMAC=y
     # CONFIG_STM32_I2C1 is not set
     # CONFIG_STM32_I2C2 is not set
     # CONFIG_STM32_I2C3 is not set
    +# CONFIG_STM32_OPAMP is not set
     # CONFIG_STM32_OTGFS is not set
     # CONFIG_STM32_OTGHS is not set
     # CONFIG_STM32_PWR is not set
    @@ -454,6 +467,7 @@ CONFIG_STM32_USART3=y
     # Alternate Pin Mapping
     #
     # CONFIG_STM32_FLASH_PREFETCH is not set
    +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set
     # CONFIG_STM32_JTAG_DISABLE is not set
     CONFIG_STM32_JTAG_FULL_ENABLE=y
     # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
    @@ -660,7 +674,6 @@ CONFIG_TASK_NAME_SIZE=0
     CONFIG_MAX_TASKS=8
     # CONFIG_SCHED_HAVE_PARENT is not set
     CONFIG_SCHED_WAITPID=y
    -# CONFIG_CANCELLATION_POINTS is not set
     
     #
     # Performance Monitoring
    @@ -873,6 +886,7 @@ CONFIG_USART3_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -912,10 +926,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -946,11 +962,13 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     # CONFIG_NET_TCP is not set
    +# CONFIG_NET_TCP_NO_STACK is not set
     
     #
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -980,10 +998,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=8
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -1202,7 +1224,6 @@ CONFIG_EXAMPLES_DHCPD_NETMASK=0xffffff00
     # CONFIG_EXAMPLES_MM is not set
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1234,6 +1255,7 @@ CONFIG_EXAMPLES_DHCPD_NETMASK=0xffffff00
     # CONFIG_EXAMPLES_UDPBLASTER is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1323,3 +1345,7 @@ CONFIG_NETUTILS_NETLIB=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/stm3220g-eval/nettest/defconfig b/configs/stm3220g-eval/nettest/defconfig
    index 0ad6a3e847..49adf7c8d8 100644
    --- a/configs/stm3220g-eval/nettest/defconfig
    +++ b/configs/stm3220g-eval/nettest/defconfig
    @@ -96,6 +96,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -103,11 +104,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     CONFIG_ARCH_CHIP_STM32=y
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -182,6 +184,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -381,9 +386,13 @@ CONFIG_STM32_HAVE_ADC3=y
     # CONFIG_STM32_HAVE_SDADC3_DMA is not set
     CONFIG_STM32_HAVE_CAN1=y
     CONFIG_STM32_HAVE_CAN2=y
    +# CONFIG_STM32_HAVE_COMP1 is not set
     # CONFIG_STM32_HAVE_COMP2 is not set
    +# CONFIG_STM32_HAVE_COMP3 is not set
     # CONFIG_STM32_HAVE_COMP4 is not set
    +# CONFIG_STM32_HAVE_COMP5 is not set
     # CONFIG_STM32_HAVE_COMP6 is not set
    +# CONFIG_STM32_HAVE_COMP7 is not set
     CONFIG_STM32_HAVE_DAC1=y
     CONFIG_STM32_HAVE_DAC2=y
     CONFIG_STM32_HAVE_RNG=y
    @@ -397,7 +406,10 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_HAVE_SPI6 is not set
     # CONFIG_STM32_HAVE_SAIPLL is not set
     # CONFIG_STM32_HAVE_I2SPLL is not set
    -# CONFIG_STM32_HAVE_OPAMP is not set
    +# CONFIG_STM32_HAVE_OPAMP1 is not set
    +# CONFIG_STM32_HAVE_OPAMP2 is not set
    +# CONFIG_STM32_HAVE_OPAMP3 is not set
    +# CONFIG_STM32_HAVE_OPAMP4 is not set
     # CONFIG_STM32_ADC1 is not set
     # CONFIG_STM32_ADC2 is not set
     # CONFIG_STM32_ADC3 is not set
    @@ -417,6 +429,7 @@ CONFIG_STM32_ETHMAC=y
     # CONFIG_STM32_I2C1 is not set
     # CONFIG_STM32_I2C2 is not set
     # CONFIG_STM32_I2C3 is not set
    +# CONFIG_STM32_OPAMP is not set
     # CONFIG_STM32_OTGFS is not set
     # CONFIG_STM32_OTGHS is not set
     # CONFIG_STM32_PWR is not set
    @@ -454,6 +467,7 @@ CONFIG_STM32_USART3=y
     # Alternate Pin Mapping
     #
     # CONFIG_STM32_FLASH_PREFETCH is not set
    +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set
     # CONFIG_STM32_JTAG_DISABLE is not set
     CONFIG_STM32_JTAG_FULL_ENABLE=y
     # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
    @@ -660,7 +674,6 @@ CONFIG_TASK_NAME_SIZE=0
     CONFIG_MAX_TASKS=8
     # CONFIG_SCHED_HAVE_PARENT is not set
     CONFIG_SCHED_WAITPID=y
    -# CONFIG_CANCELLATION_POINTS is not set
     
     #
     # Performance Monitoring
    @@ -873,6 +886,7 @@ CONFIG_USART3_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -913,10 +927,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -947,6 +963,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=40
     CONFIG_NET_MAX_LISTENPORTS=40
    @@ -961,6 +978,7 @@ CONFIG_NET_TCP_RECVDELAY=0
     # UDP Networking
     #
     # CONFIG_NET_UDP is not set
    +# CONFIG_NET_UDP_NO_STACK is not set
     
     #
     # ICMP Networking Support
    @@ -985,10 +1003,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -1202,6 +1224,8 @@ CONFIG_HAVE_CXXINITIALIZE=y
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     CONFIG_EXAMPLES_NETTEST=y
    +CONFIG_EXAMPLES_NETTEST_STACKSIZE=2048
    +CONFIG_EXAMPLES_NETTEST_PRIORITY=100
     # CONFIG_EXAMPLES_NETTEST_SERVER is not set
     CONFIG_EXAMPLES_NETTEST_PERFORMANCE=y
     CONFIG_EXAMPLES_NETTEST_IPv4=y
    @@ -1215,7 +1239,6 @@ CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002
     CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001
     CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00
     CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1246,6 +1269,7 @@ CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1321,3 +1345,7 @@ CONFIG_NETUTILS_NETLIB=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/stm3220g-eval/nsh/defconfig b/configs/stm3220g-eval/nsh/defconfig
    index bf70159441..61cc41fe2c 100644
    --- a/configs/stm3220g-eval/nsh/defconfig
    +++ b/configs/stm3220g-eval/nsh/defconfig
    @@ -90,6 +90,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -97,11 +98,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     CONFIG_ARCH_CHIP_STM32=y
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -172,6 +174,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -371,9 +376,13 @@ CONFIG_STM32_HAVE_ADC3=y
     # CONFIG_STM32_HAVE_SDADC3_DMA is not set
     CONFIG_STM32_HAVE_CAN1=y
     CONFIG_STM32_HAVE_CAN2=y
    +# CONFIG_STM32_HAVE_COMP1 is not set
     # CONFIG_STM32_HAVE_COMP2 is not set
    +# CONFIG_STM32_HAVE_COMP3 is not set
     # CONFIG_STM32_HAVE_COMP4 is not set
    +# CONFIG_STM32_HAVE_COMP5 is not set
     # CONFIG_STM32_HAVE_COMP6 is not set
    +# CONFIG_STM32_HAVE_COMP7 is not set
     CONFIG_STM32_HAVE_DAC1=y
     CONFIG_STM32_HAVE_DAC2=y
     CONFIG_STM32_HAVE_RNG=y
    @@ -387,7 +396,10 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_HAVE_SPI6 is not set
     # CONFIG_STM32_HAVE_SAIPLL is not set
     # CONFIG_STM32_HAVE_I2SPLL is not set
    -# CONFIG_STM32_HAVE_OPAMP is not set
    +# CONFIG_STM32_HAVE_OPAMP1 is not set
    +# CONFIG_STM32_HAVE_OPAMP2 is not set
    +# CONFIG_STM32_HAVE_OPAMP3 is not set
    +# CONFIG_STM32_HAVE_OPAMP4 is not set
     # CONFIG_STM32_ADC1 is not set
     # CONFIG_STM32_ADC2 is not set
     # CONFIG_STM32_ADC3 is not set
    @@ -407,6 +419,7 @@ CONFIG_STM32_ETHMAC=y
     CONFIG_STM32_I2C1=y
     # CONFIG_STM32_I2C2 is not set
     # CONFIG_STM32_I2C3 is not set
    +# CONFIG_STM32_OPAMP is not set
     # CONFIG_STM32_OTGFS is not set
     # CONFIG_STM32_OTGHS is not set
     CONFIG_STM32_PWR=y
    @@ -445,6 +458,7 @@ CONFIG_STM32_I2C=y
     # Alternate Pin Mapping
     #
     # CONFIG_STM32_FLASH_PREFETCH is not set
    +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set
     # CONFIG_STM32_JTAG_DISABLE is not set
     CONFIG_STM32_JTAG_FULL_ENABLE=y
     # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
    @@ -504,6 +518,7 @@ CONFIG_STM32_I2CTIMEOTICKS=500
     # CONFIG_STM32_HAVE_RTC_SUBSECONDS is not set
     CONFIG_RTC_MAGIC_REG=0
     CONFIG_RTC_MAGIC=0xfacefeee
    +CONFIG_RTC_MAGIC_TIME_SET=0xfacefeef
     CONFIG_RTC_LSECLOCK=y
     # CONFIG_RTC_LSICLOCK is not set
     # CONFIG_RTC_HSECLOCK is not set
    @@ -672,6 +687,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -944,6 +961,7 @@ CONFIG_USART3_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -984,10 +1002,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -1018,6 +1038,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=40
     CONFIG_NET_MAX_LISTENPORTS=40
    @@ -1032,6 +1053,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -1061,10 +1083,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1318,7 +1344,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y
     # CONFIG_EXAMPLES_NULL is not set
    @@ -1352,6 +1377,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y
     # CONFIG_EXAMPLES_UDPBLASTER is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1563,3 +1589,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/stm3220g-eval/nsh2/defconfig b/configs/stm3220g-eval/nsh2/defconfig
    index a443c30f5c..428488c43e 100644
    --- a/configs/stm3220g-eval/nsh2/defconfig
    +++ b/configs/stm3220g-eval/nsh2/defconfig
    @@ -96,6 +96,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -103,11 +104,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     CONFIG_ARCH_CHIP_STM32=y
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -181,6 +183,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -380,9 +385,13 @@ CONFIG_STM32_HAVE_ADC3=y
     # CONFIG_STM32_HAVE_SDADC3_DMA is not set
     CONFIG_STM32_HAVE_CAN1=y
     CONFIG_STM32_HAVE_CAN2=y
    +# CONFIG_STM32_HAVE_COMP1 is not set
     # CONFIG_STM32_HAVE_COMP2 is not set
    +# CONFIG_STM32_HAVE_COMP3 is not set
     # CONFIG_STM32_HAVE_COMP4 is not set
    +# CONFIG_STM32_HAVE_COMP5 is not set
     # CONFIG_STM32_HAVE_COMP6 is not set
    +# CONFIG_STM32_HAVE_COMP7 is not set
     CONFIG_STM32_HAVE_DAC1=y
     CONFIG_STM32_HAVE_DAC2=y
     CONFIG_STM32_HAVE_RNG=y
    @@ -396,7 +405,10 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_HAVE_SPI6 is not set
     # CONFIG_STM32_HAVE_SAIPLL is not set
     # CONFIG_STM32_HAVE_I2SPLL is not set
    -# CONFIG_STM32_HAVE_OPAMP is not set
    +# CONFIG_STM32_HAVE_OPAMP1 is not set
    +# CONFIG_STM32_HAVE_OPAMP2 is not set
    +# CONFIG_STM32_HAVE_OPAMP3 is not set
    +# CONFIG_STM32_HAVE_OPAMP4 is not set
     # CONFIG_STM32_ADC1 is not set
     # CONFIG_STM32_ADC2 is not set
     # CONFIG_STM32_ADC3 is not set
    @@ -416,6 +428,7 @@ CONFIG_STM32_ETHMAC=y
     CONFIG_STM32_I2C1=y
     # CONFIG_STM32_I2C2 is not set
     # CONFIG_STM32_I2C3 is not set
    +# CONFIG_STM32_OPAMP is not set
     # CONFIG_STM32_OTGFS is not set
     # CONFIG_STM32_OTGHS is not set
     CONFIG_STM32_PWR=y
    @@ -454,6 +467,7 @@ CONFIG_STM32_I2C=y
     # Alternate Pin Mapping
     #
     # CONFIG_STM32_FLASH_PREFETCH is not set
    +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set
     # CONFIG_STM32_JTAG_DISABLE is not set
     CONFIG_STM32_JTAG_FULL_ENABLE=y
     # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
    @@ -500,6 +514,7 @@ CONFIG_STM32_SDIO_DMAPRIO=0x00010000
     # CONFIG_STM32_HAVE_RTC_SUBSECONDS is not set
     CONFIG_RTC_MAGIC_REG=0
     CONFIG_RTC_MAGIC=0xfacefeee
    +CONFIG_RTC_MAGIC_TIME_SET=0xfacefeef
     CONFIG_RTC_LSECLOCK=y
     # CONFIG_RTC_LSICLOCK is not set
     # CONFIG_RTC_HSECLOCK is not set
    @@ -673,6 +688,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -936,6 +953,7 @@ CONFIG_SERIAL=y
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -980,10 +998,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -1014,6 +1034,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=40
     CONFIG_NET_MAX_LISTENPORTS=40
    @@ -1028,6 +1049,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -1057,10 +1079,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1313,7 +1339,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y
     # CONFIG_EXAMPLES_NULL is not set
    @@ -1348,6 +1373,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -1581,3 +1607,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/stm3220g-eval/nxwm/defconfig b/configs/stm3220g-eval/nxwm/defconfig
    index 50cf143791..9962bb6201 100644
    --- a/configs/stm3220g-eval/nxwm/defconfig
    +++ b/configs/stm3220g-eval/nxwm/defconfig
    @@ -96,6 +96,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -103,11 +104,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     CONFIG_ARCH_CHIP_STM32=y
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -182,6 +184,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -381,9 +386,13 @@ CONFIG_STM32_HAVE_ADC3=y
     # CONFIG_STM32_HAVE_SDADC3_DMA is not set
     CONFIG_STM32_HAVE_CAN1=y
     CONFIG_STM32_HAVE_CAN2=y
    +# CONFIG_STM32_HAVE_COMP1 is not set
     # CONFIG_STM32_HAVE_COMP2 is not set
    +# CONFIG_STM32_HAVE_COMP3 is not set
     # CONFIG_STM32_HAVE_COMP4 is not set
    +# CONFIG_STM32_HAVE_COMP5 is not set
     # CONFIG_STM32_HAVE_COMP6 is not set
    +# CONFIG_STM32_HAVE_COMP7 is not set
     CONFIG_STM32_HAVE_DAC1=y
     CONFIG_STM32_HAVE_DAC2=y
     CONFIG_STM32_HAVE_RNG=y
    @@ -397,7 +406,10 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_HAVE_SPI6 is not set
     # CONFIG_STM32_HAVE_SAIPLL is not set
     # CONFIG_STM32_HAVE_I2SPLL is not set
    -# CONFIG_STM32_HAVE_OPAMP is not set
    +# CONFIG_STM32_HAVE_OPAMP1 is not set
    +# CONFIG_STM32_HAVE_OPAMP2 is not set
    +# CONFIG_STM32_HAVE_OPAMP3 is not set
    +# CONFIG_STM32_HAVE_OPAMP4 is not set
     # CONFIG_STM32_ADC1 is not set
     # CONFIG_STM32_ADC2 is not set
     # CONFIG_STM32_ADC3 is not set
    @@ -417,6 +429,7 @@ CONFIG_STM32_FSMC=y
     CONFIG_STM32_I2C1=y
     # CONFIG_STM32_I2C2 is not set
     # CONFIG_STM32_I2C3 is not set
    +# CONFIG_STM32_OPAMP is not set
     # CONFIG_STM32_OTGFS is not set
     # CONFIG_STM32_OTGHS is not set
     CONFIG_STM32_PWR=y
    @@ -455,6 +468,7 @@ CONFIG_STM32_I2C=y
     # Alternate Pin Mapping
     #
     # CONFIG_STM32_FLASH_PREFETCH is not set
    +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set
     # CONFIG_STM32_JTAG_DISABLE is not set
     CONFIG_STM32_JTAG_FULL_ENABLE=y
     # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
    @@ -515,6 +529,7 @@ CONFIG_STM32_I2CTIMEOTICKS=500
     # CONFIG_STM32_HAVE_RTC_SUBSECONDS is not set
     CONFIG_RTC_MAGIC_REG=0
     CONFIG_RTC_MAGIC=0xfacefeee
    +CONFIG_RTC_MAGIC_TIME_SET=0xfacefeef
     CONFIG_RTC_LSECLOCK=y
     # CONFIG_RTC_LSICLOCK is not set
     # CONFIG_RTC_HSECLOCK is not set
    @@ -692,6 +707,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -988,6 +1005,7 @@ CONFIG_USART3_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -1028,10 +1046,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -1062,6 +1082,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=40
     CONFIG_NET_MAX_LISTENPORTS=40
    @@ -1076,6 +1097,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     # CONFIG_NET_BROADCAST is not set
    @@ -1105,10 +1127,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1463,7 +1489,6 @@ CONFIG_HAVE_CXXINITIALIZE=y
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1497,6 +1522,7 @@ CONFIG_HAVE_CXXINITIALIZE=y
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1890,3 +1916,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/stm3220g-eval/telnetd/defconfig b/configs/stm3220g-eval/telnetd/defconfig
    index a26939f39b..2adcd3c46b 100644
    --- a/configs/stm3220g-eval/telnetd/defconfig
    +++ b/configs/stm3220g-eval/telnetd/defconfig
    @@ -96,6 +96,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -103,11 +104,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     CONFIG_ARCH_CHIP_STM32=y
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -182,6 +184,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -381,9 +386,13 @@ CONFIG_STM32_HAVE_ADC3=y
     # CONFIG_STM32_HAVE_SDADC3_DMA is not set
     CONFIG_STM32_HAVE_CAN1=y
     CONFIG_STM32_HAVE_CAN2=y
    +# CONFIG_STM32_HAVE_COMP1 is not set
     # CONFIG_STM32_HAVE_COMP2 is not set
    +# CONFIG_STM32_HAVE_COMP3 is not set
     # CONFIG_STM32_HAVE_COMP4 is not set
    +# CONFIG_STM32_HAVE_COMP5 is not set
     # CONFIG_STM32_HAVE_COMP6 is not set
    +# CONFIG_STM32_HAVE_COMP7 is not set
     CONFIG_STM32_HAVE_DAC1=y
     CONFIG_STM32_HAVE_DAC2=y
     CONFIG_STM32_HAVE_RNG=y
    @@ -397,7 +406,10 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_HAVE_SPI6 is not set
     # CONFIG_STM32_HAVE_SAIPLL is not set
     # CONFIG_STM32_HAVE_I2SPLL is not set
    -# CONFIG_STM32_HAVE_OPAMP is not set
    +# CONFIG_STM32_HAVE_OPAMP1 is not set
    +# CONFIG_STM32_HAVE_OPAMP2 is not set
    +# CONFIG_STM32_HAVE_OPAMP3 is not set
    +# CONFIG_STM32_HAVE_OPAMP4 is not set
     # CONFIG_STM32_ADC1 is not set
     # CONFIG_STM32_ADC2 is not set
     # CONFIG_STM32_ADC3 is not set
    @@ -417,6 +429,7 @@ CONFIG_STM32_ETHMAC=y
     # CONFIG_STM32_I2C1 is not set
     # CONFIG_STM32_I2C2 is not set
     # CONFIG_STM32_I2C3 is not set
    +# CONFIG_STM32_OPAMP is not set
     # CONFIG_STM32_OTGFS is not set
     # CONFIG_STM32_OTGHS is not set
     # CONFIG_STM32_PWR is not set
    @@ -454,6 +467,7 @@ CONFIG_STM32_USART3=y
     # Alternate Pin Mapping
     #
     # CONFIG_STM32_FLASH_PREFETCH is not set
    +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set
     # CONFIG_STM32_JTAG_DISABLE is not set
     CONFIG_STM32_JTAG_FULL_ENABLE=y
     # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
    @@ -660,7 +674,6 @@ CONFIG_TASK_NAME_SIZE=0
     CONFIG_MAX_TASKS=8
     # CONFIG_SCHED_HAVE_PARENT is not set
     CONFIG_SCHED_WAITPID=y
    -# CONFIG_CANCELLATION_POINTS is not set
     
     #
     # Performance Monitoring
    @@ -875,6 +888,7 @@ CONFIG_USART3_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -915,10 +929,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -949,6 +965,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=40
     CONFIG_NET_MAX_LISTENPORTS=40
    @@ -963,6 +980,7 @@ CONFIG_NET_TCP_RECVDELAY=0
     # UDP Networking
     #
     # CONFIG_NET_UDP is not set
    +# CONFIG_NET_UDP_NO_STACK is not set
     
     #
     # ICMP Networking Support
    @@ -987,10 +1005,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -1206,7 +1228,6 @@ CONFIG_HAVE_CXXINITIALIZE=y
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1245,6 +1266,7 @@ CONFIG_EXAMPLES_TELNETD_CLIENTSTACKSIZE=2048
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1320,3 +1342,7 @@ CONFIG_NETUTILS_TELNETD=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/stm3240g-eval/dhcpd/defconfig b/configs/stm3240g-eval/dhcpd/defconfig
    index e841bf6cfe..efe681e3c4 100644
    --- a/configs/stm3240g-eval/dhcpd/defconfig
    +++ b/configs/stm3240g-eval/dhcpd/defconfig
    @@ -96,6 +96,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -103,11 +104,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     CONFIG_ARCH_CHIP_STM32=y
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -183,6 +185,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -382,9 +387,13 @@ CONFIG_STM32_HAVE_ADC3=y
     # CONFIG_STM32_HAVE_SDADC3_DMA is not set
     CONFIG_STM32_HAVE_CAN1=y
     CONFIG_STM32_HAVE_CAN2=y
    +# CONFIG_STM32_HAVE_COMP1 is not set
     # CONFIG_STM32_HAVE_COMP2 is not set
    +# CONFIG_STM32_HAVE_COMP3 is not set
     # CONFIG_STM32_HAVE_COMP4 is not set
    +# CONFIG_STM32_HAVE_COMP5 is not set
     # CONFIG_STM32_HAVE_COMP6 is not set
    +# CONFIG_STM32_HAVE_COMP7 is not set
     CONFIG_STM32_HAVE_DAC1=y
     CONFIG_STM32_HAVE_DAC2=y
     CONFIG_STM32_HAVE_RNG=y
    @@ -398,7 +407,10 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_HAVE_SPI6 is not set
     # CONFIG_STM32_HAVE_SAIPLL is not set
     # CONFIG_STM32_HAVE_I2SPLL is not set
    -# CONFIG_STM32_HAVE_OPAMP is not set
    +# CONFIG_STM32_HAVE_OPAMP1 is not set
    +# CONFIG_STM32_HAVE_OPAMP2 is not set
    +# CONFIG_STM32_HAVE_OPAMP3 is not set
    +# CONFIG_STM32_HAVE_OPAMP4 is not set
     # CONFIG_STM32_ADC1 is not set
     # CONFIG_STM32_ADC2 is not set
     # CONFIG_STM32_ADC3 is not set
    @@ -419,6 +431,7 @@ CONFIG_STM32_ETHMAC=y
     # CONFIG_STM32_I2C1 is not set
     # CONFIG_STM32_I2C2 is not set
     # CONFIG_STM32_I2C3 is not set
    +# CONFIG_STM32_OPAMP is not set
     # CONFIG_STM32_OTGFS is not set
     # CONFIG_STM32_OTGHS is not set
     # CONFIG_STM32_PWR is not set
    @@ -456,6 +469,7 @@ CONFIG_STM32_USART3=y
     # Alternate Pin Mapping
     #
     # CONFIG_STM32_FLASH_PREFETCH is not set
    +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set
     # CONFIG_STM32_JTAG_DISABLE is not set
     CONFIG_STM32_JTAG_FULL_ENABLE=y
     # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
    @@ -664,7 +678,6 @@ CONFIG_TASK_NAME_SIZE=0
     CONFIG_MAX_TASKS=8
     # CONFIG_SCHED_HAVE_PARENT is not set
     CONFIG_SCHED_WAITPID=y
    -# CONFIG_CANCELLATION_POINTS is not set
     
     #
     # Performance Monitoring
    @@ -877,6 +890,7 @@ CONFIG_USART3_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -916,10 +930,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -950,11 +966,13 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     # CONFIG_NET_TCP is not set
    +# CONFIG_NET_TCP_NO_STACK is not set
     
     #
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -984,10 +1002,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=8
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -1206,7 +1228,6 @@ CONFIG_EXAMPLES_DHCPD_NETMASK=0xffffff00
     # CONFIG_EXAMPLES_MM is not set
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1238,6 +1259,7 @@ CONFIG_EXAMPLES_DHCPD_NETMASK=0xffffff00
     # CONFIG_EXAMPLES_UDPBLASTER is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1327,3 +1349,7 @@ CONFIG_NETUTILS_NETLIB=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/stm3240g-eval/discover/defconfig b/configs/stm3240g-eval/discover/defconfig
    index ce7c4a8083..59263438d9 100644
    --- a/configs/stm3240g-eval/discover/defconfig
    +++ b/configs/stm3240g-eval/discover/defconfig
    @@ -90,6 +90,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -97,11 +98,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     CONFIG_ARCH_CHIP_STM32=y
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -173,6 +175,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -372,9 +377,13 @@ CONFIG_STM32_HAVE_ADC3=y
     # CONFIG_STM32_HAVE_SDADC3_DMA is not set
     CONFIG_STM32_HAVE_CAN1=y
     CONFIG_STM32_HAVE_CAN2=y
    +# CONFIG_STM32_HAVE_COMP1 is not set
     # CONFIG_STM32_HAVE_COMP2 is not set
    +# CONFIG_STM32_HAVE_COMP3 is not set
     # CONFIG_STM32_HAVE_COMP4 is not set
    +# CONFIG_STM32_HAVE_COMP5 is not set
     # CONFIG_STM32_HAVE_COMP6 is not set
    +# CONFIG_STM32_HAVE_COMP7 is not set
     CONFIG_STM32_HAVE_DAC1=y
     CONFIG_STM32_HAVE_DAC2=y
     CONFIG_STM32_HAVE_RNG=y
    @@ -388,7 +397,10 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_HAVE_SPI6 is not set
     # CONFIG_STM32_HAVE_SAIPLL is not set
     # CONFIG_STM32_HAVE_I2SPLL is not set
    -# CONFIG_STM32_HAVE_OPAMP is not set
    +# CONFIG_STM32_HAVE_OPAMP1 is not set
    +# CONFIG_STM32_HAVE_OPAMP2 is not set
    +# CONFIG_STM32_HAVE_OPAMP3 is not set
    +# CONFIG_STM32_HAVE_OPAMP4 is not set
     # CONFIG_STM32_ADC1 is not set
     # CONFIG_STM32_ADC2 is not set
     # CONFIG_STM32_ADC3 is not set
    @@ -409,6 +421,7 @@ CONFIG_STM32_ETHMAC=y
     CONFIG_STM32_I2C1=y
     # CONFIG_STM32_I2C2 is not set
     # CONFIG_STM32_I2C3 is not set
    +# CONFIG_STM32_OPAMP is not set
     # CONFIG_STM32_OTGFS is not set
     # CONFIG_STM32_OTGHS is not set
     CONFIG_STM32_PWR=y
    @@ -447,6 +460,7 @@ CONFIG_STM32_I2C=y
     # Alternate Pin Mapping
     #
     # CONFIG_STM32_FLASH_PREFETCH is not set
    +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set
     # CONFIG_STM32_JTAG_DISABLE is not set
     CONFIG_STM32_JTAG_FULL_ENABLE=y
     # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
    @@ -671,6 +685,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -900,6 +916,7 @@ CONFIG_USART3_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -940,10 +957,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -974,6 +993,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=40
     CONFIG_NET_MAX_LISTENPORTS=40
    @@ -988,6 +1008,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -1017,10 +1038,14 @@ CONFIG_NET_ARP_IPIN=y
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1272,7 +1297,6 @@ CONFIG_EXAMPLES_DISCOVER_NETMASK=0xffffff00
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1305,6 +1329,7 @@ CONFIG_EXAMPLES_DISCOVER_NETMASK=0xffffff00
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1396,3 +1421,7 @@ CONFIG_NETUTILS_NETLIB=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/stm3240g-eval/nettest/defconfig b/configs/stm3240g-eval/nettest/defconfig
    index c633a7affc..336084eda6 100644
    --- a/configs/stm3240g-eval/nettest/defconfig
    +++ b/configs/stm3240g-eval/nettest/defconfig
    @@ -96,6 +96,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -103,11 +104,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     CONFIG_ARCH_CHIP_STM32=y
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -183,6 +185,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -382,9 +387,13 @@ CONFIG_STM32_HAVE_ADC3=y
     # CONFIG_STM32_HAVE_SDADC3_DMA is not set
     CONFIG_STM32_HAVE_CAN1=y
     CONFIG_STM32_HAVE_CAN2=y
    +# CONFIG_STM32_HAVE_COMP1 is not set
     # CONFIG_STM32_HAVE_COMP2 is not set
    +# CONFIG_STM32_HAVE_COMP3 is not set
     # CONFIG_STM32_HAVE_COMP4 is not set
    +# CONFIG_STM32_HAVE_COMP5 is not set
     # CONFIG_STM32_HAVE_COMP6 is not set
    +# CONFIG_STM32_HAVE_COMP7 is not set
     CONFIG_STM32_HAVE_DAC1=y
     CONFIG_STM32_HAVE_DAC2=y
     CONFIG_STM32_HAVE_RNG=y
    @@ -398,7 +407,10 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_HAVE_SPI6 is not set
     # CONFIG_STM32_HAVE_SAIPLL is not set
     # CONFIG_STM32_HAVE_I2SPLL is not set
    -# CONFIG_STM32_HAVE_OPAMP is not set
    +# CONFIG_STM32_HAVE_OPAMP1 is not set
    +# CONFIG_STM32_HAVE_OPAMP2 is not set
    +# CONFIG_STM32_HAVE_OPAMP3 is not set
    +# CONFIG_STM32_HAVE_OPAMP4 is not set
     # CONFIG_STM32_ADC1 is not set
     # CONFIG_STM32_ADC2 is not set
     # CONFIG_STM32_ADC3 is not set
    @@ -419,6 +431,7 @@ CONFIG_STM32_ETHMAC=y
     # CONFIG_STM32_I2C1 is not set
     # CONFIG_STM32_I2C2 is not set
     # CONFIG_STM32_I2C3 is not set
    +# CONFIG_STM32_OPAMP is not set
     # CONFIG_STM32_OTGFS is not set
     # CONFIG_STM32_OTGHS is not set
     # CONFIG_STM32_PWR is not set
    @@ -456,6 +469,7 @@ CONFIG_STM32_USART3=y
     # Alternate Pin Mapping
     #
     # CONFIG_STM32_FLASH_PREFETCH is not set
    +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set
     # CONFIG_STM32_JTAG_DISABLE is not set
     CONFIG_STM32_JTAG_FULL_ENABLE=y
     # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
    @@ -664,7 +678,6 @@ CONFIG_TASK_NAME_SIZE=0
     CONFIG_MAX_TASKS=8
     # CONFIG_SCHED_HAVE_PARENT is not set
     CONFIG_SCHED_WAITPID=y
    -# CONFIG_CANCELLATION_POINTS is not set
     
     #
     # Performance Monitoring
    @@ -877,6 +890,7 @@ CONFIG_USART3_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -917,10 +931,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -951,6 +967,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=40
     CONFIG_NET_MAX_LISTENPORTS=40
    @@ -965,6 +982,7 @@ CONFIG_NET_TCP_RECVDELAY=0
     # UDP Networking
     #
     # CONFIG_NET_UDP is not set
    +# CONFIG_NET_UDP_NO_STACK is not set
     
     #
     # ICMP Networking Support
    @@ -989,10 +1007,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -1206,6 +1228,8 @@ CONFIG_HAVE_CXXINITIALIZE=y
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     CONFIG_EXAMPLES_NETTEST=y
    +CONFIG_EXAMPLES_NETTEST_STACKSIZE=2048
    +CONFIG_EXAMPLES_NETTEST_PRIORITY=100
     # CONFIG_EXAMPLES_NETTEST_SERVER is not set
     CONFIG_EXAMPLES_NETTEST_PERFORMANCE=y
     CONFIG_EXAMPLES_NETTEST_IPv4=y
    @@ -1219,7 +1243,6 @@ CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002
     CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001
     CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00
     CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1250,6 +1273,7 @@ CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1325,3 +1349,7 @@ CONFIG_NETUTILS_NETLIB=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/stm3240g-eval/nsh/defconfig b/configs/stm3240g-eval/nsh/defconfig
    index 9b5c354ee7..719a3dbe42 100644
    --- a/configs/stm3240g-eval/nsh/defconfig
    +++ b/configs/stm3240g-eval/nsh/defconfig
    @@ -96,6 +96,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -103,11 +104,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     CONFIG_ARCH_CHIP_STM32=y
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -183,6 +185,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -382,9 +387,13 @@ CONFIG_STM32_HAVE_ADC3=y
     # CONFIG_STM32_HAVE_SDADC3_DMA is not set
     CONFIG_STM32_HAVE_CAN1=y
     CONFIG_STM32_HAVE_CAN2=y
    +# CONFIG_STM32_HAVE_COMP1 is not set
     # CONFIG_STM32_HAVE_COMP2 is not set
    +# CONFIG_STM32_HAVE_COMP3 is not set
     # CONFIG_STM32_HAVE_COMP4 is not set
    +# CONFIG_STM32_HAVE_COMP5 is not set
     # CONFIG_STM32_HAVE_COMP6 is not set
    +# CONFIG_STM32_HAVE_COMP7 is not set
     CONFIG_STM32_HAVE_DAC1=y
     CONFIG_STM32_HAVE_DAC2=y
     CONFIG_STM32_HAVE_RNG=y
    @@ -398,7 +407,10 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_HAVE_SPI6 is not set
     # CONFIG_STM32_HAVE_SAIPLL is not set
     # CONFIG_STM32_HAVE_I2SPLL is not set
    -# CONFIG_STM32_HAVE_OPAMP is not set
    +# CONFIG_STM32_HAVE_OPAMP1 is not set
    +# CONFIG_STM32_HAVE_OPAMP2 is not set
    +# CONFIG_STM32_HAVE_OPAMP3 is not set
    +# CONFIG_STM32_HAVE_OPAMP4 is not set
     # CONFIG_STM32_ADC1 is not set
     # CONFIG_STM32_ADC2 is not set
     # CONFIG_STM32_ADC3 is not set
    @@ -419,6 +431,7 @@ CONFIG_STM32_ETHMAC=y
     CONFIG_STM32_I2C1=y
     # CONFIG_STM32_I2C2 is not set
     # CONFIG_STM32_I2C3 is not set
    +# CONFIG_STM32_OPAMP is not set
     # CONFIG_STM32_OTGFS is not set
     # CONFIG_STM32_OTGHS is not set
     CONFIG_STM32_PWR=y
    @@ -457,6 +470,7 @@ CONFIG_STM32_I2C=y
     # Alternate Pin Mapping
     #
     # CONFIG_STM32_FLASH_PREFETCH is not set
    +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set
     # CONFIG_STM32_JTAG_DISABLE is not set
     CONFIG_STM32_JTAG_FULL_ENABLE=y
     # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
    @@ -518,6 +532,7 @@ CONFIG_STM32_I2CTIMEOTICKS=500
     # CONFIG_STM32_HAVE_RTC_SUBSECONDS is not set
     CONFIG_RTC_MAGIC_REG=0
     CONFIG_RTC_MAGIC=0xfacefeee
    +CONFIG_RTC_MAGIC_TIME_SET=0xfacefeef
     CONFIG_RTC_LSECLOCK=y
     # CONFIG_RTC_LSICLOCK is not set
     # CONFIG_RTC_HSECLOCK is not set
    @@ -686,6 +701,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -923,6 +940,7 @@ CONFIG_USART3_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -963,10 +981,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -997,6 +1017,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=40
     CONFIG_NET_MAX_LISTENPORTS=40
    @@ -1011,6 +1032,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -1040,10 +1062,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1296,7 +1322,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y
     # CONFIG_EXAMPLES_NULL is not set
    @@ -1331,6 +1356,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y
     # CONFIG_EXAMPLES_UDPBLASTER is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1558,3 +1584,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/stm3240g-eval/nsh2/defconfig b/configs/stm3240g-eval/nsh2/defconfig
    index 18727a8f64..dc73b09c20 100644
    --- a/configs/stm3240g-eval/nsh2/defconfig
    +++ b/configs/stm3240g-eval/nsh2/defconfig
    @@ -96,6 +96,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -103,11 +104,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     CONFIG_ARCH_CHIP_STM32=y
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -182,6 +184,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -381,9 +386,13 @@ CONFIG_STM32_HAVE_ADC3=y
     # CONFIG_STM32_HAVE_SDADC3_DMA is not set
     CONFIG_STM32_HAVE_CAN1=y
     CONFIG_STM32_HAVE_CAN2=y
    +# CONFIG_STM32_HAVE_COMP1 is not set
     # CONFIG_STM32_HAVE_COMP2 is not set
    +# CONFIG_STM32_HAVE_COMP3 is not set
     # CONFIG_STM32_HAVE_COMP4 is not set
    +# CONFIG_STM32_HAVE_COMP5 is not set
     # CONFIG_STM32_HAVE_COMP6 is not set
    +# CONFIG_STM32_HAVE_COMP7 is not set
     CONFIG_STM32_HAVE_DAC1=y
     CONFIG_STM32_HAVE_DAC2=y
     CONFIG_STM32_HAVE_RNG=y
    @@ -397,7 +406,10 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_HAVE_SPI6 is not set
     # CONFIG_STM32_HAVE_SAIPLL is not set
     # CONFIG_STM32_HAVE_I2SPLL is not set
    -# CONFIG_STM32_HAVE_OPAMP is not set
    +# CONFIG_STM32_HAVE_OPAMP1 is not set
    +# CONFIG_STM32_HAVE_OPAMP2 is not set
    +# CONFIG_STM32_HAVE_OPAMP3 is not set
    +# CONFIG_STM32_HAVE_OPAMP4 is not set
     # CONFIG_STM32_ADC1 is not set
     # CONFIG_STM32_ADC2 is not set
     # CONFIG_STM32_ADC3 is not set
    @@ -418,6 +430,7 @@ CONFIG_STM32_ETHMAC=y
     CONFIG_STM32_I2C1=y
     # CONFIG_STM32_I2C2 is not set
     # CONFIG_STM32_I2C3 is not set
    +# CONFIG_STM32_OPAMP is not set
     # CONFIG_STM32_OTGFS is not set
     # CONFIG_STM32_OTGHS is not set
     CONFIG_STM32_PWR=y
    @@ -456,6 +469,7 @@ CONFIG_STM32_I2C=y
     # Alternate Pin Mapping
     #
     # CONFIG_STM32_FLASH_PREFETCH is not set
    +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set
     # CONFIG_STM32_JTAG_DISABLE is not set
     CONFIG_STM32_JTAG_FULL_ENABLE=y
     # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
    @@ -504,6 +518,7 @@ CONFIG_STM32_SDIO_DMAPRIO=0x00010000
     # CONFIG_STM32_HAVE_RTC_SUBSECONDS is not set
     CONFIG_RTC_MAGIC_REG=0
     CONFIG_RTC_MAGIC=0xfacefeee
    +CONFIG_RTC_MAGIC_TIME_SET=0xfacefeef
     CONFIG_RTC_LSECLOCK=y
     # CONFIG_RTC_LSICLOCK is not set
     # CONFIG_RTC_HSECLOCK is not set
    @@ -677,6 +692,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -940,6 +957,7 @@ CONFIG_SERIAL=y
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -984,10 +1002,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -1018,6 +1038,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=40
     CONFIG_NET_MAX_LISTENPORTS=40
    @@ -1032,6 +1053,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -1061,10 +1083,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1317,7 +1343,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y
     # CONFIG_EXAMPLES_NULL is not set
    @@ -1352,6 +1377,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -1585,3 +1611,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/stm3240g-eval/nxterm/defconfig b/configs/stm3240g-eval/nxterm/defconfig
    index 6e37ea5759..fefe9b52bb 100644
    --- a/configs/stm3240g-eval/nxterm/defconfig
    +++ b/configs/stm3240g-eval/nxterm/defconfig
    @@ -96,6 +96,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -103,11 +104,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     CONFIG_ARCH_CHIP_STM32=y
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -183,6 +185,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -382,9 +387,13 @@ CONFIG_STM32_HAVE_ADC3=y
     # CONFIG_STM32_HAVE_SDADC3_DMA is not set
     CONFIG_STM32_HAVE_CAN1=y
     CONFIG_STM32_HAVE_CAN2=y
    +# CONFIG_STM32_HAVE_COMP1 is not set
     # CONFIG_STM32_HAVE_COMP2 is not set
    +# CONFIG_STM32_HAVE_COMP3 is not set
     # CONFIG_STM32_HAVE_COMP4 is not set
    +# CONFIG_STM32_HAVE_COMP5 is not set
     # CONFIG_STM32_HAVE_COMP6 is not set
    +# CONFIG_STM32_HAVE_COMP7 is not set
     CONFIG_STM32_HAVE_DAC1=y
     CONFIG_STM32_HAVE_DAC2=y
     CONFIG_STM32_HAVE_RNG=y
    @@ -398,7 +407,10 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_HAVE_SPI6 is not set
     # CONFIG_STM32_HAVE_SAIPLL is not set
     # CONFIG_STM32_HAVE_I2SPLL is not set
    -# CONFIG_STM32_HAVE_OPAMP is not set
    +# CONFIG_STM32_HAVE_OPAMP1 is not set
    +# CONFIG_STM32_HAVE_OPAMP2 is not set
    +# CONFIG_STM32_HAVE_OPAMP3 is not set
    +# CONFIG_STM32_HAVE_OPAMP4 is not set
     # CONFIG_STM32_ADC1 is not set
     # CONFIG_STM32_ADC2 is not set
     # CONFIG_STM32_ADC3 is not set
    @@ -419,6 +431,7 @@ CONFIG_STM32_FSMC=y
     CONFIG_STM32_I2C1=y
     # CONFIG_STM32_I2C2 is not set
     # CONFIG_STM32_I2C3 is not set
    +# CONFIG_STM32_OPAMP is not set
     # CONFIG_STM32_OTGFS is not set
     # CONFIG_STM32_OTGHS is not set
     CONFIG_STM32_PWR=y
    @@ -457,6 +470,7 @@ CONFIG_STM32_I2C=y
     # Alternate Pin Mapping
     #
     # CONFIG_STM32_FLASH_PREFETCH is not set
    +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set
     # CONFIG_STM32_JTAG_DISABLE is not set
     CONFIG_STM32_JTAG_FULL_ENABLE=y
     # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
    @@ -519,6 +533,7 @@ CONFIG_STM32_I2CTIMEOTICKS=500
     # CONFIG_STM32_HAVE_RTC_SUBSECONDS is not set
     CONFIG_RTC_MAGIC_REG=0
     CONFIG_RTC_MAGIC=0xfacefeee
    +CONFIG_RTC_MAGIC_TIME_SET=0xfacefeef
     CONFIG_RTC_LSECLOCK=y
     # CONFIG_RTC_LSICLOCK is not set
     # CONFIG_RTC_HSECLOCK is not set
    @@ -696,6 +711,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -962,6 +979,7 @@ CONFIG_USART3_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -1002,10 +1020,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -1036,6 +1056,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=40
     CONFIG_NET_MAX_LISTENPORTS=40
    @@ -1050,6 +1071,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -1079,10 +1101,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1440,7 +1466,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1474,6 +1499,7 @@ CONFIG_EXAMPLES_NXTERM=y
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1699,3 +1725,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/stm3240g-eval/nxwm/defconfig b/configs/stm3240g-eval/nxwm/defconfig
    index 26bca3feb3..5dd1c02f83 100644
    --- a/configs/stm3240g-eval/nxwm/defconfig
    +++ b/configs/stm3240g-eval/nxwm/defconfig
    @@ -96,6 +96,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -103,11 +104,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     CONFIG_ARCH_CHIP_STM32=y
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -183,6 +185,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -382,9 +387,13 @@ CONFIG_STM32_HAVE_ADC3=y
     # CONFIG_STM32_HAVE_SDADC3_DMA is not set
     CONFIG_STM32_HAVE_CAN1=y
     CONFIG_STM32_HAVE_CAN2=y
    +# CONFIG_STM32_HAVE_COMP1 is not set
     # CONFIG_STM32_HAVE_COMP2 is not set
    +# CONFIG_STM32_HAVE_COMP3 is not set
     # CONFIG_STM32_HAVE_COMP4 is not set
    +# CONFIG_STM32_HAVE_COMP5 is not set
     # CONFIG_STM32_HAVE_COMP6 is not set
    +# CONFIG_STM32_HAVE_COMP7 is not set
     CONFIG_STM32_HAVE_DAC1=y
     CONFIG_STM32_HAVE_DAC2=y
     CONFIG_STM32_HAVE_RNG=y
    @@ -398,7 +407,10 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_HAVE_SPI6 is not set
     # CONFIG_STM32_HAVE_SAIPLL is not set
     # CONFIG_STM32_HAVE_I2SPLL is not set
    -# CONFIG_STM32_HAVE_OPAMP is not set
    +# CONFIG_STM32_HAVE_OPAMP1 is not set
    +# CONFIG_STM32_HAVE_OPAMP2 is not set
    +# CONFIG_STM32_HAVE_OPAMP3 is not set
    +# CONFIG_STM32_HAVE_OPAMP4 is not set
     # CONFIG_STM32_ADC1 is not set
     # CONFIG_STM32_ADC2 is not set
     # CONFIG_STM32_ADC3 is not set
    @@ -419,6 +431,7 @@ CONFIG_STM32_FSMC=y
     CONFIG_STM32_I2C1=y
     # CONFIG_STM32_I2C2 is not set
     # CONFIG_STM32_I2C3 is not set
    +# CONFIG_STM32_OPAMP is not set
     # CONFIG_STM32_OTGFS is not set
     # CONFIG_STM32_OTGHS is not set
     CONFIG_STM32_PWR=y
    @@ -457,6 +470,7 @@ CONFIG_STM32_I2C=y
     # Alternate Pin Mapping
     #
     # CONFIG_STM32_FLASH_PREFETCH is not set
    +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set
     # CONFIG_STM32_JTAG_DISABLE is not set
     CONFIG_STM32_JTAG_FULL_ENABLE=y
     # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
    @@ -519,6 +533,7 @@ CONFIG_STM32_I2CTIMEOTICKS=500
     # CONFIG_STM32_HAVE_RTC_SUBSECONDS is not set
     CONFIG_RTC_MAGIC_REG=0
     CONFIG_RTC_MAGIC=0xfacefeee
    +CONFIG_RTC_MAGIC_TIME_SET=0xfacefeef
     CONFIG_RTC_LSECLOCK=y
     # CONFIG_RTC_LSICLOCK is not set
     # CONFIG_RTC_HSECLOCK is not set
    @@ -696,6 +711,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -984,6 +1001,7 @@ CONFIG_USART3_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -1024,10 +1042,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -1058,6 +1078,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=40
     CONFIG_NET_MAX_LISTENPORTS=40
    @@ -1072,6 +1093,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     # CONFIG_NET_BROADCAST is not set
    @@ -1101,10 +1123,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1466,7 +1492,6 @@ CONFIG_HAVE_CXXINITIALIZE=y
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1500,6 +1525,7 @@ CONFIG_HAVE_CXXINITIALIZE=y
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1894,3 +1920,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/stm3240g-eval/telnetd/defconfig b/configs/stm3240g-eval/telnetd/defconfig
    index 212fec2d7b..dc565ae021 100644
    --- a/configs/stm3240g-eval/telnetd/defconfig
    +++ b/configs/stm3240g-eval/telnetd/defconfig
    @@ -96,6 +96,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -103,11 +104,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     CONFIG_ARCH_CHIP_STM32=y
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -183,6 +185,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -382,9 +387,13 @@ CONFIG_STM32_HAVE_ADC3=y
     # CONFIG_STM32_HAVE_SDADC3_DMA is not set
     CONFIG_STM32_HAVE_CAN1=y
     CONFIG_STM32_HAVE_CAN2=y
    +# CONFIG_STM32_HAVE_COMP1 is not set
     # CONFIG_STM32_HAVE_COMP2 is not set
    +# CONFIG_STM32_HAVE_COMP3 is not set
     # CONFIG_STM32_HAVE_COMP4 is not set
    +# CONFIG_STM32_HAVE_COMP5 is not set
     # CONFIG_STM32_HAVE_COMP6 is not set
    +# CONFIG_STM32_HAVE_COMP7 is not set
     CONFIG_STM32_HAVE_DAC1=y
     CONFIG_STM32_HAVE_DAC2=y
     CONFIG_STM32_HAVE_RNG=y
    @@ -398,7 +407,10 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_HAVE_SPI6 is not set
     # CONFIG_STM32_HAVE_SAIPLL is not set
     # CONFIG_STM32_HAVE_I2SPLL is not set
    -# CONFIG_STM32_HAVE_OPAMP is not set
    +# CONFIG_STM32_HAVE_OPAMP1 is not set
    +# CONFIG_STM32_HAVE_OPAMP2 is not set
    +# CONFIG_STM32_HAVE_OPAMP3 is not set
    +# CONFIG_STM32_HAVE_OPAMP4 is not set
     # CONFIG_STM32_ADC1 is not set
     # CONFIG_STM32_ADC2 is not set
     # CONFIG_STM32_ADC3 is not set
    @@ -419,6 +431,7 @@ CONFIG_STM32_ETHMAC=y
     # CONFIG_STM32_I2C1 is not set
     # CONFIG_STM32_I2C2 is not set
     # CONFIG_STM32_I2C3 is not set
    +# CONFIG_STM32_OPAMP is not set
     # CONFIG_STM32_OTGFS is not set
     # CONFIG_STM32_OTGHS is not set
     # CONFIG_STM32_PWR is not set
    @@ -456,6 +469,7 @@ CONFIG_STM32_USART3=y
     # Alternate Pin Mapping
     #
     # CONFIG_STM32_FLASH_PREFETCH is not set
    +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set
     # CONFIG_STM32_JTAG_DISABLE is not set
     CONFIG_STM32_JTAG_FULL_ENABLE=y
     # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
    @@ -664,7 +678,6 @@ CONFIG_TASK_NAME_SIZE=0
     CONFIG_MAX_TASKS=8
     # CONFIG_SCHED_HAVE_PARENT is not set
     CONFIG_SCHED_WAITPID=y
    -# CONFIG_CANCELLATION_POINTS is not set
     
     #
     # Performance Monitoring
    @@ -879,6 +892,7 @@ CONFIG_USART3_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -919,10 +933,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -953,6 +969,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=40
     CONFIG_NET_MAX_LISTENPORTS=40
    @@ -967,6 +984,7 @@ CONFIG_NET_TCP_RECVDELAY=0
     # UDP Networking
     #
     # CONFIG_NET_UDP is not set
    +# CONFIG_NET_UDP_NO_STACK is not set
     
     #
     # ICMP Networking Support
    @@ -991,10 +1009,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -1210,7 +1232,6 @@ CONFIG_HAVE_CXXINITIALIZE=y
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1249,6 +1270,7 @@ CONFIG_EXAMPLES_TELNETD_CLIENTSTACKSIZE=2048
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1324,3 +1346,7 @@ CONFIG_NETUTILS_TELNETD=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/stm3240g-eval/webserver/defconfig b/configs/stm3240g-eval/webserver/defconfig
    index ee8d9cded9..d4772a437c 100644
    --- a/configs/stm3240g-eval/webserver/defconfig
    +++ b/configs/stm3240g-eval/webserver/defconfig
    @@ -90,6 +90,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -97,11 +98,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     CONFIG_ARCH_CHIP_STM32=y
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -173,6 +175,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -372,9 +377,13 @@ CONFIG_STM32_HAVE_ADC3=y
     # CONFIG_STM32_HAVE_SDADC3_DMA is not set
     CONFIG_STM32_HAVE_CAN1=y
     CONFIG_STM32_HAVE_CAN2=y
    +# CONFIG_STM32_HAVE_COMP1 is not set
     # CONFIG_STM32_HAVE_COMP2 is not set
    +# CONFIG_STM32_HAVE_COMP3 is not set
     # CONFIG_STM32_HAVE_COMP4 is not set
    +# CONFIG_STM32_HAVE_COMP5 is not set
     # CONFIG_STM32_HAVE_COMP6 is not set
    +# CONFIG_STM32_HAVE_COMP7 is not set
     CONFIG_STM32_HAVE_DAC1=y
     CONFIG_STM32_HAVE_DAC2=y
     CONFIG_STM32_HAVE_RNG=y
    @@ -388,7 +397,10 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_HAVE_SPI6 is not set
     # CONFIG_STM32_HAVE_SAIPLL is not set
     # CONFIG_STM32_HAVE_I2SPLL is not set
    -# CONFIG_STM32_HAVE_OPAMP is not set
    +# CONFIG_STM32_HAVE_OPAMP1 is not set
    +# CONFIG_STM32_HAVE_OPAMP2 is not set
    +# CONFIG_STM32_HAVE_OPAMP3 is not set
    +# CONFIG_STM32_HAVE_OPAMP4 is not set
     # CONFIG_STM32_ADC1 is not set
     # CONFIG_STM32_ADC2 is not set
     # CONFIG_STM32_ADC3 is not set
    @@ -409,6 +421,7 @@ CONFIG_STM32_ETHMAC=y
     CONFIG_STM32_I2C1=y
     # CONFIG_STM32_I2C2 is not set
     # CONFIG_STM32_I2C3 is not set
    +# CONFIG_STM32_OPAMP is not set
     # CONFIG_STM32_OTGFS is not set
     # CONFIG_STM32_OTGHS is not set
     CONFIG_STM32_PWR=y
    @@ -447,6 +460,7 @@ CONFIG_STM32_I2C=y
     # Alternate Pin Mapping
     #
     # CONFIG_STM32_FLASH_PREFETCH is not set
    +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set
     # CONFIG_STM32_JTAG_DISABLE is not set
     CONFIG_STM32_JTAG_FULL_ENABLE=y
     # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
    @@ -508,6 +522,7 @@ CONFIG_STM32_I2CTIMEOTICKS=500
     # CONFIG_STM32_HAVE_RTC_SUBSECONDS is not set
     CONFIG_RTC_MAGIC_REG=0
     CONFIG_RTC_MAGIC=0xfacefeee
    +CONFIG_RTC_MAGIC_TIME_SET=0xfacefeef
     CONFIG_RTC_LSECLOCK=y
     # CONFIG_RTC_LSICLOCK is not set
     # CONFIG_RTC_HSECLOCK is not set
    @@ -676,6 +691,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -942,6 +959,7 @@ CONFIG_USART3_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -982,10 +1000,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -1016,6 +1036,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=40
     CONFIG_NET_MAX_LISTENPORTS=40
    @@ -1030,6 +1051,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     # CONFIG_NET_BROADCAST is not set
    @@ -1059,10 +1081,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1302,6 +1328,8 @@ CONFIG_HAVE_CXXINITIALIZE=y
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     CONFIG_EXAMPLES_NETTEST=y
    +CONFIG_EXAMPLES_NETTEST_STACKSIZE=2048
    +CONFIG_EXAMPLES_NETTEST_PRIORITY=100
     # CONFIG_EXAMPLES_NETTEST_SERVER is not set
     # CONFIG_EXAMPLES_NETTEST_PERFORMANCE is not set
     CONFIG_EXAMPLES_NETTEST_IPv4=y
    @@ -1315,7 +1343,6 @@ CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002
     CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001
     CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00
     CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1352,6 +1379,7 @@ CONFIG_EXAMPLES_WEBSERVER_DRIPADDR=0x0a000001
     CONFIG_EXAMPLES_WEBSERVER_NETMASK=0xffffff00
     CONFIG_EXAMPLES_WEBSERVER_NOMAC=y
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1579,3 +1607,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/stm3240g-eval/xmlrpc/defconfig b/configs/stm3240g-eval/xmlrpc/defconfig
    index cd3838b5c7..4e3aa3b290 100644
    --- a/configs/stm3240g-eval/xmlrpc/defconfig
    +++ b/configs/stm3240g-eval/xmlrpc/defconfig
    @@ -90,6 +90,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -97,11 +98,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     CONFIG_ARCH_CHIP_STM32=y
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -173,6 +175,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -372,9 +377,13 @@ CONFIG_STM32_HAVE_ADC3=y
     # CONFIG_STM32_HAVE_SDADC3_DMA is not set
     CONFIG_STM32_HAVE_CAN1=y
     CONFIG_STM32_HAVE_CAN2=y
    +# CONFIG_STM32_HAVE_COMP1 is not set
     # CONFIG_STM32_HAVE_COMP2 is not set
    +# CONFIG_STM32_HAVE_COMP3 is not set
     # CONFIG_STM32_HAVE_COMP4 is not set
    +# CONFIG_STM32_HAVE_COMP5 is not set
     # CONFIG_STM32_HAVE_COMP6 is not set
    +# CONFIG_STM32_HAVE_COMP7 is not set
     CONFIG_STM32_HAVE_DAC1=y
     CONFIG_STM32_HAVE_DAC2=y
     CONFIG_STM32_HAVE_RNG=y
    @@ -388,7 +397,10 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_HAVE_SPI6 is not set
     # CONFIG_STM32_HAVE_SAIPLL is not set
     # CONFIG_STM32_HAVE_I2SPLL is not set
    -# CONFIG_STM32_HAVE_OPAMP is not set
    +# CONFIG_STM32_HAVE_OPAMP1 is not set
    +# CONFIG_STM32_HAVE_OPAMP2 is not set
    +# CONFIG_STM32_HAVE_OPAMP3 is not set
    +# CONFIG_STM32_HAVE_OPAMP4 is not set
     # CONFIG_STM32_ADC1 is not set
     # CONFIG_STM32_ADC2 is not set
     # CONFIG_STM32_ADC3 is not set
    @@ -409,6 +421,7 @@ CONFIG_STM32_ETHMAC=y
     CONFIG_STM32_I2C1=y
     # CONFIG_STM32_I2C2 is not set
     # CONFIG_STM32_I2C3 is not set
    +# CONFIG_STM32_OPAMP is not set
     # CONFIG_STM32_OTGFS is not set
     # CONFIG_STM32_OTGHS is not set
     CONFIG_STM32_PWR=y
    @@ -447,6 +460,7 @@ CONFIG_STM32_I2C=y
     # Alternate Pin Mapping
     #
     # CONFIG_STM32_FLASH_PREFETCH is not set
    +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set
     # CONFIG_STM32_JTAG_DISABLE is not set
     CONFIG_STM32_JTAG_FULL_ENABLE=y
     # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
    @@ -665,6 +679,9 @@ CONFIG_SCHED_WAITPID=y
     # Pthread Options
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
    +CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -895,6 +912,7 @@ CONFIG_USART3_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -935,10 +953,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -969,6 +989,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=40
     CONFIG_NET_MAX_LISTENPORTS=40
    @@ -983,6 +1004,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -1012,10 +1034,14 @@ CONFIG_NET_ARP_IPIN=y
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1263,7 +1289,6 @@ CONFIG_HAVE_CXXINITIALIZE=y
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1296,6 +1321,7 @@ CONFIG_HAVE_CXXINITIALIZE=y
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     CONFIG_EXAMPLES_XMLRPC=y
     CONFIG_EXAMPLES_XMLRPC_BUFFERSIZE=1024
     CONFIG_EXAMPLES_XMLRPC_DHCPC=y
    @@ -1390,3 +1416,7 @@ CONFIG_XMLRPC_STRINGSIZE=64
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/stm32butterfly2/nshnet/defconfig b/configs/stm32butterfly2/nshnet/defconfig
    index c2794486b2..e1e4e1529e 100644
    --- a/configs/stm32butterfly2/nshnet/defconfig
    +++ b/configs/stm32butterfly2/nshnet/defconfig
    @@ -175,6 +175,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -1075,7 +1078,7 @@ CONFIG_NET_ARP_IPIN=y
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    diff --git a/configs/stm32f4discovery/ipv6/defconfig b/configs/stm32f4discovery/ipv6/defconfig
    index 07aec89561..5b8900d674 100644
    --- a/configs/stm32f4discovery/ipv6/defconfig
    +++ b/configs/stm32f4discovery/ipv6/defconfig
    @@ -96,6 +96,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -103,11 +104,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     CONFIG_ARCH_CHIP_STM32=y
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -183,6 +185,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -382,9 +387,13 @@ CONFIG_STM32_HAVE_ADC3=y
     # CONFIG_STM32_HAVE_SDADC3_DMA is not set
     CONFIG_STM32_HAVE_CAN1=y
     CONFIG_STM32_HAVE_CAN2=y
    +# CONFIG_STM32_HAVE_COMP1 is not set
     # CONFIG_STM32_HAVE_COMP2 is not set
    +# CONFIG_STM32_HAVE_COMP3 is not set
     # CONFIG_STM32_HAVE_COMP4 is not set
    +# CONFIG_STM32_HAVE_COMP5 is not set
     # CONFIG_STM32_HAVE_COMP6 is not set
    +# CONFIG_STM32_HAVE_COMP7 is not set
     CONFIG_STM32_HAVE_DAC1=y
     CONFIG_STM32_HAVE_DAC2=y
     CONFIG_STM32_HAVE_RNG=y
    @@ -398,7 +407,10 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_HAVE_SPI6 is not set
     # CONFIG_STM32_HAVE_SAIPLL is not set
     # CONFIG_STM32_HAVE_I2SPLL is not set
    -# CONFIG_STM32_HAVE_OPAMP is not set
    +# CONFIG_STM32_HAVE_OPAMP1 is not set
    +# CONFIG_STM32_HAVE_OPAMP2 is not set
    +# CONFIG_STM32_HAVE_OPAMP3 is not set
    +# CONFIG_STM32_HAVE_OPAMP4 is not set
     # CONFIG_STM32_ADC1 is not set
     # CONFIG_STM32_ADC2 is not set
     # CONFIG_STM32_ADC3 is not set
    @@ -419,6 +431,7 @@ CONFIG_STM32_ETHMAC=y
     # CONFIG_STM32_I2C1 is not set
     # CONFIG_STM32_I2C2 is not set
     # CONFIG_STM32_I2C3 is not set
    +# CONFIG_STM32_OPAMP is not set
     # CONFIG_STM32_OTGFS is not set
     # CONFIG_STM32_OTGHS is not set
     CONFIG_STM32_PWR=y
    @@ -457,6 +470,7 @@ CONFIG_STM32_SPI=y
     # Alternate Pin Mapping
     #
     # CONFIG_STM32_FLASH_PREFETCH is not set
    +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set
     # CONFIG_STM32_JTAG_DISABLE is not set
     # CONFIG_STM32_JTAG_FULL_ENABLE is not set
     # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
    @@ -621,6 +635,7 @@ CONFIG_RAM_SIZE=114688
     #
     # Board Selection
     #
    +# CONFIG_ARCH_BOARD_CLICKER2_STM32 is not set
     CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y
     # CONFIG_ARCH_BOARD_MIKROE_STM32F4 is not set
     # CONFIG_ARCH_BOARD_CUSTOM is not set
    @@ -696,6 +711,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -943,6 +960,7 @@ CONFIG_USART6_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -983,10 +1001,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -1018,6 +1038,7 @@ CONFIG_NET_SOLINGER=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=20
    @@ -1032,6 +1053,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -1061,11 +1083,15 @@ CONFIG_ICMPv6_NEIGHBOR_DELAYMSEC=20
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=36
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
     CONFIG_IOB_THROTTLE=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -1319,7 +1345,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y
     # CONFIG_EXAMPLES_NULL is not set
    @@ -1354,6 +1379,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1586,3 +1612,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/stm32f4discovery/netnsh/defconfig b/configs/stm32f4discovery/netnsh/defconfig
    index b07e47493d..5eec4b26b6 100644
    --- a/configs/stm32f4discovery/netnsh/defconfig
    +++ b/configs/stm32f4discovery/netnsh/defconfig
    @@ -96,6 +96,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -103,11 +104,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     CONFIG_ARCH_CHIP_STM32=y
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -183,6 +185,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -382,9 +387,13 @@ CONFIG_STM32_HAVE_ADC3=y
     # CONFIG_STM32_HAVE_SDADC3_DMA is not set
     CONFIG_STM32_HAVE_CAN1=y
     CONFIG_STM32_HAVE_CAN2=y
    +# CONFIG_STM32_HAVE_COMP1 is not set
     # CONFIG_STM32_HAVE_COMP2 is not set
    +# CONFIG_STM32_HAVE_COMP3 is not set
     # CONFIG_STM32_HAVE_COMP4 is not set
    +# CONFIG_STM32_HAVE_COMP5 is not set
     # CONFIG_STM32_HAVE_COMP6 is not set
    +# CONFIG_STM32_HAVE_COMP7 is not set
     CONFIG_STM32_HAVE_DAC1=y
     CONFIG_STM32_HAVE_DAC2=y
     CONFIG_STM32_HAVE_RNG=y
    @@ -398,7 +407,10 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_HAVE_SPI6 is not set
     # CONFIG_STM32_HAVE_SAIPLL is not set
     # CONFIG_STM32_HAVE_I2SPLL is not set
    -# CONFIG_STM32_HAVE_OPAMP is not set
    +# CONFIG_STM32_HAVE_OPAMP1 is not set
    +# CONFIG_STM32_HAVE_OPAMP2 is not set
    +# CONFIG_STM32_HAVE_OPAMP3 is not set
    +# CONFIG_STM32_HAVE_OPAMP4 is not set
     # CONFIG_STM32_ADC1 is not set
     # CONFIG_STM32_ADC2 is not set
     # CONFIG_STM32_ADC3 is not set
    @@ -419,6 +431,7 @@ CONFIG_STM32_ETHMAC=y
     # CONFIG_STM32_I2C1 is not set
     # CONFIG_STM32_I2C2 is not set
     # CONFIG_STM32_I2C3 is not set
    +# CONFIG_STM32_OPAMP is not set
     # CONFIG_STM32_OTGFS is not set
     # CONFIG_STM32_OTGHS is not set
     CONFIG_STM32_PWR=y
    @@ -457,6 +470,7 @@ CONFIG_STM32_SPI=y
     # Alternate Pin Mapping
     #
     # CONFIG_STM32_FLASH_PREFETCH is not set
    +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set
     # CONFIG_STM32_JTAG_DISABLE is not set
     # CONFIG_STM32_JTAG_FULL_ENABLE is not set
     # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
    @@ -621,6 +635,7 @@ CONFIG_RAM_SIZE=114688
     #
     # Board Selection
     #
    +# CONFIG_ARCH_BOARD_CLICKER2_STM32 is not set
     CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y
     # CONFIG_ARCH_BOARD_MIKROE_STM32F4 is not set
     # CONFIG_ARCH_BOARD_CUSTOM is not set
    @@ -696,6 +711,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -945,6 +962,7 @@ CONFIG_USART6_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -985,6 +1003,7 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
    @@ -1020,6 +1039,7 @@ CONFIG_NET_SOLINGER=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=20
    @@ -1034,6 +1054,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -1065,11 +1086,15 @@ CONFIG_ARP_SEND_DELAYMSEC=20
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=36
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
     CONFIG_IOB_THROTTLE=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -1365,6 +1390,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1592,3 +1618,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/tm4c1294-launchpad/ipv6/defconfig b/configs/tm4c1294-launchpad/ipv6/defconfig
    index 04a6b92547..87e46300c2 100644
    --- a/configs/tm4c1294-launchpad/ipv6/defconfig
    +++ b/configs/tm4c1294-launchpad/ipv6/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_TIVA=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_TIVA=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -408,6 +410,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -618,6 +622,7 @@ CONFIG_UART0_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -658,6 +663,7 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
    @@ -694,6 +700,7 @@ CONFIG_NET_SOLINGER=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=20
    @@ -708,6 +715,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -735,11 +743,15 @@ CONFIG_NET_ICMPv6_PING=y
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=36
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
     CONFIG_IOB_THROTTLE=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -992,6 +1004,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1230,3 +1243,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/tm4c1294-launchpad/nsh/defconfig b/configs/tm4c1294-launchpad/nsh/defconfig
    index 326bd96423..2ef2aece70 100644
    --- a/configs/tm4c1294-launchpad/nsh/defconfig
    +++ b/configs/tm4c1294-launchpad/nsh/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_TIVA=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_TIVA=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -408,6 +410,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -620,6 +624,7 @@ CONFIG_UART0_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -660,6 +665,7 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
    @@ -695,6 +701,7 @@ CONFIG_NET_SOLINGER=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=20
    @@ -709,6 +716,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     # CONFIG_NET_UDP_CHECKSUMS is not set
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -740,11 +748,15 @@ CONFIG_ARP_SEND_DELAYMSEC=20
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=36
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
     CONFIG_IOB_THROTTLE=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1004,6 +1016,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1232,3 +1245,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/twr-k64f120m/netnsh/defconfig b/configs/twr-k64f120m/netnsh/defconfig
    index 22ef478b17..7a3cbb274f 100644
    --- a/configs/twr-k64f120m/netnsh/defconfig
    +++ b/configs/twr-k64f120m/netnsh/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_KINETIS=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_KINETIS=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -423,6 +425,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -661,6 +665,7 @@ CONFIG_UART1_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -701,10 +706,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -734,6 +741,7 @@ CONFIG_NET_NACTIVESOCKETS=16
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=20
    @@ -748,6 +756,7 @@ CONFIG_NET_TCP_RECVDELAY=0
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     # CONFIG_NET_UDP_CHECKSUMS is not set
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -779,11 +788,15 @@ CONFIG_ARP_SEND_DELAYMSEC=20
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=36
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
     CONFIG_IOB_THROTTLE=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -1018,7 +1031,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1052,6 +1064,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1267,3 +1280,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/u-blox-c027/nsh/defconfig b/configs/u-blox-c027/nsh/defconfig
    index 87cb209018..7333497362 100644
    --- a/configs/u-blox-c027/nsh/defconfig
    +++ b/configs/u-blox-c027/nsh/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -374,6 +376,8 @@ CONFIG_MAX_TASKS=16
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -657,6 +661,7 @@ CONFIG_UART3_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -701,10 +706,12 @@ CONFIG_TUN_NINTERFACES=1
     CONFIG_NET_TUN_MTU=296
     CONFIG_NET_TUN_TCP_RECVWNDO=256
     CONFIG_TUN_HPWORK=y
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -735,6 +742,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -749,6 +757,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -780,11 +789,15 @@ CONFIG_ARP_SEND_DELAYMSEC=20
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
     CONFIG_IOB_THROTTLE=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     CONFIG_NET_STATISTICS=y
    @@ -1037,7 +1050,6 @@ CONFIG_EXAMPLES_CHAT_PRESET3="\"\" AT+USOWR=0,5,\\\"NuttX\\\" PAUSE 10 OK AT+USO
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1071,6 +1083,7 @@ CONFIG_EXAMPLES_PPPD=y
     # CONFIG_EXAMPLES_USBSERIAL is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -1323,3 +1336,7 @@ CONFIG_SYSTEM_ZMODEM_SERIALNO=0
     CONFIG_SYSTEM_ZMODEM_MAXERRORS=20
     CONFIG_SYSTEM_ZMODEM_WRITESIZE=0
     # CONFIG_DEBUG_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/viewtool-stm32f107/netnsh/defconfig b/configs/viewtool-stm32f107/netnsh/defconfig
    index 64dfa3c7c5..76a1c45cbc 100644
    --- a/configs/viewtool-stm32f107/netnsh/defconfig
    +++ b/configs/viewtool-stm32f107/netnsh/defconfig
    @@ -96,6 +96,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -103,11 +104,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     CONFIG_ARCH_CHIP_STM32=y
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -182,6 +184,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -381,9 +386,13 @@ CONFIG_STM32_HAVE_ADC2=y
     # CONFIG_STM32_HAVE_SDADC3_DMA is not set
     CONFIG_STM32_HAVE_CAN1=y
     CONFIG_STM32_HAVE_CAN2=y
    +# CONFIG_STM32_HAVE_COMP1 is not set
     # CONFIG_STM32_HAVE_COMP2 is not set
    +# CONFIG_STM32_HAVE_COMP3 is not set
     # CONFIG_STM32_HAVE_COMP4 is not set
    +# CONFIG_STM32_HAVE_COMP5 is not set
     # CONFIG_STM32_HAVE_COMP6 is not set
    +# CONFIG_STM32_HAVE_COMP7 is not set
     CONFIG_STM32_HAVE_DAC1=y
     CONFIG_STM32_HAVE_DAC2=y
     # CONFIG_STM32_HAVE_RNG is not set
    @@ -397,7 +406,10 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_HAVE_SPI6 is not set
     # CONFIG_STM32_HAVE_SAIPLL is not set
     # CONFIG_STM32_HAVE_I2SPLL is not set
    -# CONFIG_STM32_HAVE_OPAMP is not set
    +# CONFIG_STM32_HAVE_OPAMP1 is not set
    +# CONFIG_STM32_HAVE_OPAMP2 is not set
    +# CONFIG_STM32_HAVE_OPAMP3 is not set
    +# CONFIG_STM32_HAVE_OPAMP4 is not set
     # CONFIG_STM32_ADC1 is not set
     # CONFIG_STM32_ADC2 is not set
     # CONFIG_STM32_BKP is not set
    @@ -410,6 +422,7 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_DAC2 is not set
     CONFIG_STM32_ETHMAC=y
     # CONFIG_STM32_I2C1 is not set
    +# CONFIG_STM32_OPAMP is not set
     # CONFIG_STM32_OTGFS is not set
     CONFIG_STM32_PWR=y
     # CONFIG_STM32_SPI1 is not set
    @@ -437,6 +450,7 @@ CONFIG_STM32_USART1=y
     #
     # CONFIG_STM32_ETH_REMAP is not set
     # CONFIG_STM32_USART1_REMAP is not set
    +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set
     # CONFIG_STM32_JTAG_DISABLE is not set
     CONFIG_STM32_JTAG_FULL_ENABLE=y
     # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
    @@ -645,6 +659,8 @@ CONFIG_MAX_TASKS=16
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -871,6 +887,7 @@ CONFIG_USART1_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -911,10 +928,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -945,6 +964,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=40
     CONFIG_NET_MAX_LISTENPORTS=40
    @@ -959,6 +979,7 @@ CONFIG_NET_TCP_RECVDELAY=0
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     # CONFIG_NET_UDP_CHECKSUMS is not set
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -990,11 +1011,15 @@ CONFIG_ARP_SEND_DELAYMSEC=20
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
     CONFIG_IOB_THROTTLE=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -1221,7 +1246,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1254,6 +1278,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_UDPBLASTER is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -1476,3 +1501,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/zkit-arm-1769/hello/defconfig b/configs/zkit-arm-1769/hello/defconfig
    index 15b19a2d77..8566f9cade 100644
    --- a/configs/zkit-arm-1769/hello/defconfig
    +++ b/configs/zkit-arm-1769/hello/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -357,7 +359,6 @@ CONFIG_TASK_NAME_SIZE=0
     CONFIG_MAX_TASKS=16
     # CONFIG_SCHED_HAVE_PARENT is not set
     # CONFIG_SCHED_WAITPID is not set
    -# CONFIG_CANCELLATION_POINTS is not set
     
     #
     # Performance Monitoring
    @@ -570,6 +571,7 @@ CONFIG_UART0_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -610,10 +612,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -644,6 +648,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=16
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -658,6 +663,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     # CONFIG_NET_UDP is not set
    +# CONFIG_NET_UDP_NO_STACK is not set
     
     #
     # ICMP Networking Support
    @@ -682,10 +688,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -898,7 +908,6 @@ CONFIG_EXAMPLES_HELLO_STACKSIZE=2048
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -933,6 +942,7 @@ CONFIG_EXAMPLES_HELLO_STACKSIZE=2048
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -1014,3 +1024,7 @@ CONFIG_EXAMPLES_HELLO_STACKSIZE=2048
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/zkit-arm-1769/nsh/defconfig b/configs/zkit-arm-1769/nsh/defconfig
    index bad8467930..283403c164 100644
    --- a/configs/zkit-arm-1769/nsh/defconfig
    +++ b/configs/zkit-arm-1769/nsh/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -368,6 +370,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -611,6 +615,7 @@ CONFIG_UART0_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -651,10 +656,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -685,6 +692,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -700,6 +708,7 @@ CONFIG_NET_TCP_SPLIT_SIZE=40
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -729,10 +738,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -964,7 +977,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -998,6 +1010,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1220,3 +1233,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/zkit-arm-1769/nxhello/defconfig b/configs/zkit-arm-1769/nxhello/defconfig
    index 48b909ab66..20de0ea354 100644
    --- a/configs/zkit-arm-1769/nxhello/defconfig
    +++ b/configs/zkit-arm-1769/nxhello/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -368,6 +370,8 @@ CONFIG_SCHED_WAITPID=y
     #
     # CONFIG_PTHREAD_MUTEX_TYPES is not set
     CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -649,6 +653,7 @@ CONFIG_UART0_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -689,10 +694,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -723,6 +730,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=8
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -738,6 +746,7 @@ CONFIG_NET_TCP_SPLIT_SIZE=40
     # UDP Networking
     #
     CONFIG_NET_UDP=y
    +# CONFIG_NET_UDP_NO_STACK is not set
     CONFIG_NET_UDP_CHECKSUMS=y
     CONFIG_NET_UDP_CONNS=8
     CONFIG_NET_BROADCAST=y
    @@ -767,10 +776,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -1081,7 +1094,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -1131,6 +1143,7 @@ CONFIG_EXAMPLES_NXHELLO_DEFAULT_FONT=y
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    @@ -1350,3 +1363,7 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/configs/zkit-arm-1769/thttpd/defconfig b/configs/zkit-arm-1769/thttpd/defconfig
    index 789149c18e..2691aaccdb 100644
    --- a/configs/zkit-arm-1769/thttpd/defconfig
    +++ b/configs/zkit-arm-1769/thttpd/defconfig
    @@ -89,6 +89,7 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -96,11 +97,12 @@ CONFIG_ARCH_CHIP_LPC17XX=y
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     # CONFIG_ARCH_CHIP_STM32 is not set
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -357,7 +359,6 @@ CONFIG_TASK_NAME_SIZE=0
     CONFIG_MAX_TASKS=16
     # CONFIG_SCHED_HAVE_PARENT is not set
     # CONFIG_SCHED_WAITPID is not set
    -# CONFIG_CANCELLATION_POINTS is not set
     
     #
     # Performance Monitoring
    @@ -573,6 +574,7 @@ CONFIG_UART0_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     # CONFIG_DRIVERS_WIRELESS is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
    @@ -613,10 +615,12 @@ CONFIG_NET_GUARDSIZE=2
     CONFIG_NET_ETHERNET=y
     # CONFIG_NET_LOOPBACK is not set
     # CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
     
     #
     # Network Device Operations
     #
    +# CONFIG_NETDEV_IOCTL is not set
     # CONFIG_NETDEV_PHY_IOCTL is not set
     
     #
    @@ -647,6 +651,7 @@ CONFIG_NET_SOCKOPTS=y
     # TCP/IP Networking
     #
     CONFIG_NET_TCP=y
    +# CONFIG_NET_TCP_NO_STACK is not set
     # CONFIG_NET_TCPURGDATA is not set
     CONFIG_NET_TCP_CONNS=16
     CONFIG_NET_MAX_LISTENPORTS=8
    @@ -661,6 +666,7 @@ CONFIG_NET_TCPBACKLOG=y
     # UDP Networking
     #
     # CONFIG_NET_UDP is not set
    +# CONFIG_NET_UDP_NO_STACK is not set
     
     #
     # ICMP Networking Support
    @@ -685,10 +691,14 @@ CONFIG_NET_ARP_MAXAGE=120
     #
     # Network I/O Buffer Support
     #
    -CONFIG_NET_IOB=y
    +CONFIG_DRIVERS_IOB=y
     CONFIG_IOB_NBUFFERS=24
     CONFIG_IOB_BUFSIZE=196
     CONFIG_IOB_NCHAINS=8
    +
    +#
    +# User-space networking stack API
    +#
     # CONFIG_NET_ARCH_INCR32 is not set
     # CONFIG_NET_ARCH_CHKSUM is not set
     # CONFIG_NET_STATISTICS is not set
    @@ -900,7 +910,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
     # CONFIG_EXAMPLES_NETTEST is not set
    -# CONFIG_EXAMPLES_NRF24L01TERM is not set
     # CONFIG_EXAMPLES_NSH is not set
     # CONFIG_EXAMPLES_NULL is not set
     # CONFIG_EXAMPLES_NX is not set
    @@ -940,6 +949,7 @@ CONFIG_EXAMPLES_THTTPD_NETMASK=0xffffff00
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
     # CONFIG_EXAMPLES_WGET is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     # CONFIG_EXAMPLES_XMLRPC is not set
     
     #
    @@ -1052,3 +1062,7 @@ CONFIG_THTTPD_TILDE_MAP_NONE=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    diff --git a/include/nuttx/net/iob.h b/include/nuttx/drivers/iob.h
    similarity index 95%
    rename from include/nuttx/net/iob.h
    rename to include/nuttx/drivers/iob.h
    index 2ac74dceb8..52f848db30 100644
    --- a/include/nuttx/net/iob.h
    +++ b/include/nuttx/drivers/iob.h
    @@ -1,5 +1,5 @@
     /****************************************************************************
    - * include/nuttx/net/iob.h
    + * include/nuttx/drivers/iob.h
      *
      *   Copyright (C) 2014 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
    @@ -33,8 +33,8 @@
      *
      ****************************************************************************/
     
    -#ifndef _INCLUDE_NUTTX_NET_IOB_H
    -#define _INCLUDE_NUTTX_NET_IOB_H
    +#ifndef _INCLUDE_NUTTX_DRIVERS_IOB_H
    +#define _INCLUDE_NUTTX_DRIVERS_IOB_H
     
     /****************************************************************************
      * Included Files
    @@ -45,27 +45,19 @@
     #include 
     #include 
     
    -#include 
    -
    -#ifdef CONFIG_NET_IOB
    +#ifdef CONFIG_DRIVERS_IOB
     
     /****************************************************************************
      * Pre-processor Definitions
      ****************************************************************************/
     /* Configuration ************************************************************/
     
    -/* I/O buffer allocation logic supports a throttle value for the TCP
    - * read-ahead buffering to prevent the read-ahead from consuming all
    - * available I/O buffers.  This throttle only applies if both TCP write
    - * buffering and TCP read-ahead buffering are enabled.
    - */
    -
    -#if !defined(CONFIG_NET_TCP_WRITE_BUFFERS) || !defined(CONFIG_NET_TCP_READAHEAD)
    -#  undef CONFIG_IOB_THROTTLE
    -#  define CONFIG_IOB_THROTTLE 0
    -#endif
    -
    -/* The correct way to disable throttling is to the the throttle value to
    +/* I/O buffer allocation logic supports a throttle value for read-ahead
    + * buffering to prevent the read-ahead logic from consuming all available I/O
    + * buffers and blocking the write buffering logic.  This throttle logic
    + * is only needed if both write buffering and read-ahead buffering are used.
    + *
    + * The correct way to disable throttling is to set the throttle value to
      * zero.
      */
     
    @@ -417,6 +409,6 @@ void iob_dump(FAR const char *msg, FAR struct iob_s *iob, unsigned int len,
     #  define iob_dump(wrb)
     #endif
     
    -#endif /* CONFIG_NET_IOB */
    -#endif /* _INCLUDE_NUTTX_NET_IOB_H */
    +#endif /* CONFIG_DRIVERS_IOB */
    +#endif /* _INCLUDE_NUTTX_DRIVERS_IOB_H */
     
    diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h
    index eb3a4580eb..855948b4e8 100644
    --- a/include/nuttx/net/sixlowpan.h
    +++ b/include/nuttx/net/sixlowpan.h
    @@ -54,7 +54,7 @@
     #include 
     
     #include 
    -#include 
    +#include 
     #include 
     
     #ifdef CONFIG_NET_6LOWPAN
    @@ -334,7 +334,7 @@
     /* The IEEE802.15.4 MAC driver structures includes a list of IOB
      * structures, i_framelist, containing frames to be sent by the driver or
      * that were received by the driver.  The IOB structure is defined in
    - * include/nuttx/net/iob.h.  The length of data in the IOB is provided by
    + * include/nuttx/drivers/iob.h.  The length of data in the IOB is provided by
      * the io_len field of the IOB structure.
      *
      * NOTE that IOBs must be configured such that CONFIG_IOB_BUFSIZE >=
    diff --git a/net/devif/Make.defs b/net/devif/Make.defs
    index 743d951531..fb16f653ba 100644
    --- a/net/devif/Make.defs
    +++ b/net/devif/Make.defs
    @@ -50,7 +50,7 @@ endif
     
     # I/O buffer chain support required?
     
    -ifeq ($(CONFIG_NET_IOB),y)
    +ifeq ($(CONFIG_DRIVERS_IOB),y)
     NET_CSRCS += devif_iobsend.c
     endif
     
    diff --git a/net/devif/devif.h b/net/devif/devif.h
    index 28135f4d30..d7574786ec 100644
    --- a/net/devif/devif.h
    +++ b/net/devif/devif.h
    @@ -466,7 +466,7 @@ void devif_send(FAR struct net_driver_s *dev, FAR const void *buf, int len);
      *
      ****************************************************************************/
     
    -#ifdef CONFIG_NET_IOB
    +#ifdef CONFIG_DRIVERS_IOB
     struct iob_s;
     void devif_iob_send(FAR struct net_driver_s *dev, FAR struct iob_s *buf,
                         unsigned int len, unsigned int offset);
    diff --git a/net/devif/devif_iobsend.c b/net/devif/devif_iobsend.c
    index 66194aca91..ff4b4e8433 100644
    --- a/net/devif/devif_iobsend.c
    +++ b/net/devif/devif_iobsend.c
    @@ -43,10 +43,10 @@
     #include 
     #include 
     
    -#include 
    +#include 
     #include 
     
    -#ifdef CONFIG_NET_IOB
    +#ifdef CONFIG_DRIVERS_IOB
     
     /****************************************************************************
      * Pre-processor Definitions
    @@ -113,5 +113,5 @@ void devif_iob_send(FAR struct net_driver_s *dev, FAR struct iob_s *iob,
     #endif
     }
     
    -#endif /* CONFIG_NET_IOB */
    +#endif /* CONFIG_DRIVERS_IOB */
     
    diff --git a/net/iob/Kconfig b/net/iob/Kconfig
    index a5cec7e117..459e144ebb 100644
    --- a/net/iob/Kconfig
    +++ b/net/iob/Kconfig
    @@ -5,14 +5,14 @@
     
     menu "Network I/O Buffer Support"
     
    -config NET_IOB
    +config DRIVERS_IOB
     	bool "Enable generic network I/O buffer support"
     	default n
     	---help---
     		This setting will build the networking I/O buffer (IOB) support
     		library.
     
    -if NET_IOB
    +if DRIVERS_IOB
     
     config IOB_NBUFFERS
     	int "Number of pre-allocated network I/O buffers"
    @@ -71,5 +71,5 @@ config IOB_DEBUG
     		I/O buffer logic and do not want to get overloaded with other
     		network-related debug output.
     
    -endif # NET_IOB
    +endif # DRIVERS_IOB
     endmenu # Network I/O buffer support
    diff --git a/net/iob/Make.defs b/net/iob/Make.defs
    index 7f5f1d665b..ec55eca204 100644
    --- a/net/iob/Make.defs
    +++ b/net/iob/Make.defs
    @@ -33,7 +33,7 @@
     #
     ############################################################################
     
    -ifeq ($(CONFIG_NET_IOB),y)
    +ifeq ($(CONFIG_DRIVERS_IOB),y)
     
     # Include IOB source files
     
    diff --git a/net/iob/iob.h b/net/iob/iob.h
    index cbef08ddc0..d949edecf0 100644
    --- a/net/iob/iob.h
    +++ b/net/iob/iob.h
    @@ -44,9 +44,9 @@
     
     #include 
     
    -#include 
    +#include 
     
    -#ifdef CONFIG_NET_IOB
    +#ifdef CONFIG_DRIVERS_IOB
     
     /****************************************************************************
      * Public Data
    @@ -122,5 +122,5 @@ FAR struct iob_s *iob_tryalloc(bool throttled);
     
     FAR struct iob_qentry_s *iob_free_qentry(FAR struct iob_qentry_s *iobq);
     
    -#endif /* CONFIG_NET_IOB */
    +#endif /* CONFIG_DRIVERS_IOB */
     #endif /* __NET_IOB_IOB_H */
    diff --git a/net/iob/iob_add_queue.c b/net/iob/iob_add_queue.c
    index b59646ef8d..51de43aaae 100644
    --- a/net/iob/iob_add_queue.c
    +++ b/net/iob/iob_add_queue.c
    @@ -50,7 +50,7 @@
     #include 
     #include 
     
    -#include 
    +#include 
     
     #include "iob.h"
     
    diff --git a/net/iob/iob_alloc.c b/net/iob/iob_alloc.c
    index 4b43320fcd..f5210994cd 100644
    --- a/net/iob/iob_alloc.c
    +++ b/net/iob/iob_alloc.c
    @@ -52,7 +52,7 @@
     
     #include 
     #include 
    -#include 
    +#include 
     
     #include "iob.h"
     
    diff --git a/net/iob/iob_alloc_qentry.c b/net/iob/iob_alloc_qentry.c
    index 5ba2e6205a..7b3fda3ee9 100644
    --- a/net/iob/iob_alloc_qentry.c
    +++ b/net/iob/iob_alloc_qentry.c
    @@ -52,7 +52,7 @@
     
     #include 
     #include 
    -#include 
    +#include 
     
     #include "iob.h"
     
    diff --git a/net/iob/iob_clone.c b/net/iob/iob_clone.c
    index 44acbb5f60..15a5b81a87 100644
    --- a/net/iob/iob_clone.c
    +++ b/net/iob/iob_clone.c
    @@ -51,7 +51,7 @@
     #include 
     #include 
     
    -#include 
    +#include 
     
     #include "iob.h"
     
    diff --git a/net/iob/iob_concat.c b/net/iob/iob_concat.c
    index 99fff8e75a..10a74b30b5 100644
    --- a/net/iob/iob_concat.c
    +++ b/net/iob/iob_concat.c
    @@ -48,7 +48,7 @@
     
     #include 
     
    -#include 
    +#include 
     
     #include "iob.h"
     
    diff --git a/net/iob/iob_contig.c b/net/iob/iob_contig.c
    index c7b948f25e..aabbc91352 100644
    --- a/net/iob/iob_contig.c
    +++ b/net/iob/iob_contig.c
    @@ -51,7 +51,7 @@
     #include 
     #include 
     
    -#include 
    +#include 
     
     #include "iob.h"
     
    diff --git a/net/iob/iob_copyin.c b/net/iob/iob_copyin.c
    index 3507bc5004..db2f167669 100644
    --- a/net/iob/iob_copyin.c
    +++ b/net/iob/iob_copyin.c
    @@ -52,7 +52,7 @@
     #include 
     #include 
     
    -#include 
    +#include 
     
     #include "iob.h"
     
    diff --git a/net/iob/iob_copyout.c b/net/iob/iob_copyout.c
    index b250cc5601..9b6df5531d 100644
    --- a/net/iob/iob_copyout.c
    +++ b/net/iob/iob_copyout.c
    @@ -50,7 +50,7 @@
     #include 
     #include 
     
    -#include 
    +#include 
     
     #include "iob.h"
     
    diff --git a/net/iob/iob_dump.c b/net/iob/iob_dump.c
    index 2be0198a5b..eea432d3c2 100644
    --- a/net/iob/iob_dump.c
    +++ b/net/iob/iob_dump.c
    @@ -42,7 +42,7 @@
     #include 
     #include 
     
    -#include 
    +#include 
     
     #ifdef CONFIG_DEBUG_FEATURES
     
    diff --git a/net/iob/iob_free.c b/net/iob/iob_free.c
    index 38eb5fb345..26e3df0cff 100644
    --- a/net/iob/iob_free.c
    +++ b/net/iob/iob_free.c
    @@ -52,7 +52,7 @@
     
     #include 
     #include 
    -#include 
    +#include 
     
     #include "iob.h"
     
    diff --git a/net/iob/iob_free_chain.c b/net/iob/iob_free_chain.c
    index 6f5d4d4ba1..c309fbdafe 100644
    --- a/net/iob/iob_free_chain.c
    +++ b/net/iob/iob_free_chain.c
    @@ -47,7 +47,7 @@
     #endif
     
     #include 
    -#include 
    +#include 
     
     #include "iob.h"
     
    diff --git a/net/iob/iob_free_qentry.c b/net/iob/iob_free_qentry.c
    index 66cccb9947..636b835b87 100644
    --- a/net/iob/iob_free_qentry.c
    +++ b/net/iob/iob_free_qentry.c
    @@ -51,7 +51,7 @@
     
     #include 
     #include 
    -#include 
    +#include 
     
     #include "iob.h"
     
    diff --git a/net/iob/iob_free_queue.c b/net/iob/iob_free_queue.c
    index 5a4a52513d..e559c819b9 100644
    --- a/net/iob/iob_free_queue.c
    +++ b/net/iob/iob_free_queue.c
    @@ -48,7 +48,7 @@
     
     #include 
     
    -#include 
    +#include 
     
     #include "iob.h"
     
    diff --git a/net/iob/iob_initialize.c b/net/iob/iob_initialize.c
    index 9bae90b0e4..03bb96b691 100644
    --- a/net/iob/iob_initialize.c
    +++ b/net/iob/iob_initialize.c
    @@ -49,7 +49,7 @@
     #include 
     #include 
     
    -#include 
    +#include 
     
     #include "iob.h"
     
    diff --git a/net/iob/iob_pack.c b/net/iob/iob_pack.c
    index 2df9300ece..7dc997dc2a 100644
    --- a/net/iob/iob_pack.c
    +++ b/net/iob/iob_pack.c
    @@ -48,7 +48,7 @@
     
     #include 
     
    -#include 
    +#include 
     
     #include "iob.h"
     
    diff --git a/net/iob/iob_peek_queue.c b/net/iob/iob_peek_queue.c
    index 3422d65d60..64c9531184 100644
    --- a/net/iob/iob_peek_queue.c
    +++ b/net/iob/iob_peek_queue.c
    @@ -48,7 +48,7 @@
     
     #include 
     
    -#include 
    +#include 
     
     #include "iob.h"
     
    diff --git a/net/iob/iob_remove_queue.c b/net/iob/iob_remove_queue.c
    index 4d8a45a381..ab02b67a0c 100644
    --- a/net/iob/iob_remove_queue.c
    +++ b/net/iob/iob_remove_queue.c
    @@ -48,7 +48,7 @@
     
     #include 
     
    -#include 
    +#include 
     
     #include "iob.h"
     
    diff --git a/net/iob/iob_trimhead.c b/net/iob/iob_trimhead.c
    index c11cfa43b9..a50ea9283b 100644
    --- a/net/iob/iob_trimhead.c
    +++ b/net/iob/iob_trimhead.c
    @@ -49,7 +49,7 @@
     #include 
     #include 
     
    -#include 
    +#include 
     
     #include "iob.h"
     
    diff --git a/net/iob/iob_trimhead_queue.c b/net/iob/iob_trimhead_queue.c
    index 791892d738..57a1f9637e 100644
    --- a/net/iob/iob_trimhead_queue.c
    +++ b/net/iob/iob_trimhead_queue.c
    @@ -49,7 +49,7 @@
     #include 
     #include 
     
    -#include 
    +#include 
     
     #include "iob.h"
     
    diff --git a/net/iob/iob_trimtail.c b/net/iob/iob_trimtail.c
    index 039e3c6db7..2d297d8547 100644
    --- a/net/iob/iob_trimtail.c
    +++ b/net/iob/iob_trimtail.c
    @@ -49,7 +49,7 @@
     #include 
     #include 
     
    -#include 
    +#include 
     
     #include "iob.h"
     
    diff --git a/net/net_initialize.c b/net/net_initialize.c
    index 3edbd6849b..d792f77a83 100644
    --- a/net/net_initialize.c
    +++ b/net/net_initialize.c
    @@ -42,7 +42,7 @@
     
     #include 
     
    -#include 
    +#include 
     #include 
     
     #include "socket/socket.h"
    @@ -109,7 +109,7 @@ void net_setup(void)
     #endif
     #endif /* CONFIG_NET_IPv6 */
     
    -#ifdef CONFIG_NET_IOB
    +#ifdef CONFIG_DRIVERS_IOB
       /* Initialize I/O buffering */
     
       iob_initialize();
    diff --git a/net/socket/recvfrom.c b/net/socket/recvfrom.c
    index fc713375cb..1bc3e76c1b 100644
    --- a/net/socket/recvfrom.c
    +++ b/net/socket/recvfrom.c
    @@ -59,7 +59,7 @@
     #include 
     #include 
     #include 
    -#include 
    +#include 
     #include 
     #include 
     #include 
    diff --git a/net/tcp/Kconfig b/net/tcp/Kconfig
    index 8ac6aab128..00f2519c3c 100644
    --- a/net/tcp/Kconfig
    +++ b/net/tcp/Kconfig
    @@ -70,7 +70,7 @@ config NET_MAX_LISTENPORTS
     config NET_TCP_READAHEAD
     	bool "Enable TCP/IP read-ahead buffering"
     	default y
    -	select NET_IOB
    +	select DRIVERS_IOB
     	---help---
     		Read-ahead buffers allows buffering of TCP/IP packets when there is no
     		receive in place to catch the TCP packet.  In that case, the packet
    @@ -91,7 +91,7 @@ endif # NET_TCP_READAHEAD
     config NET_TCP_WRITE_BUFFERS
     	bool "Enable TCP/IP write buffering"
     	default n
    -	select NET_IOB
    +	select DRIVERS_IOB
     	---help---
     		Write buffers allows buffering of ongoing TCP/IP packets, providing
     		for higher performance, streamed output.
    diff --git a/net/tcp/tcp.h b/net/tcp/tcp.h
    index f2a5115e53..e6c98a0847 100644
    --- a/net/tcp/tcp.h
    +++ b/net/tcp/tcp.h
    @@ -45,7 +45,7 @@
     #include 
     #include 
     
    -#include 
    +#include 
     #include 
     
     #if defined(CONFIG_NET_TCP) && !defined(CONFIG_NET_TCP_NO_STACK)
    diff --git a/net/tcp/tcp_send_buffered.c b/net/tcp/tcp_send_buffered.c
    index 76941f3a99..52a21d72e9 100644
    --- a/net/tcp/tcp_send_buffered.c
    +++ b/net/tcp/tcp_send_buffered.c
    @@ -64,7 +64,7 @@
     #include 
     #include 
     #include 
    -#include 
    +#include 
     #include 
     #include 
     #include 
    diff --git a/net/tcp/tcp_wrbuffer.c b/net/tcp/tcp_wrbuffer.c
    index 149c83143d..7662df8bbc 100644
    --- a/net/tcp/tcp_wrbuffer.c
    +++ b/net/tcp/tcp_wrbuffer.c
    @@ -55,7 +55,7 @@
     #include 
     
     #include 
    -#include 
    +#include 
     
     #include "tcp/tcp.h"
     
    diff --git a/net/tcp/tcp_wrbuffer_dump.c b/net/tcp/tcp_wrbuffer_dump.c
    index 6d1fbf85f6..7e961278d1 100644
    --- a/net/tcp/tcp_wrbuffer_dump.c
    +++ b/net/tcp/tcp_wrbuffer_dump.c
    @@ -42,7 +42,7 @@
     #include 
     #include 
     
    -#include 
    +#include 
     
     #include "tcp/tcp.h"
     
    diff --git a/net/udp/Kconfig b/net/udp/Kconfig
    index 2c8e85d70b..e8c5d53b2f 100644
    --- a/net/udp/Kconfig
    +++ b/net/udp/Kconfig
    @@ -60,7 +60,7 @@ config NET_RXAVAIL
     config NET_UDP_READAHEAD
     	bool "Enable UDP/IP read-ahead buffering"
     	default y
    -	select NET_IOB
    +	select DRIVERS_IOB
     
     endif # NET_UDP && !NET_UDP_NO_STACK
     endmenu # UDP Networking
    diff --git a/net/udp/udp.h b/net/udp/udp.h
    index 1aac4a8328..c020853109 100644
    --- a/net/udp/udp.h
    +++ b/net/udp/udp.h
    @@ -48,7 +48,7 @@
     #include 
     
     #ifdef CONFIG_NET_UDP_READAHEAD
    -#  include 
    +#  include 
     #endif
     
     #if defined(CONFIG_NET_UDP) && !defined(CONFIG_NET_UDP_NO_STACK)
    -- 
    GitLab
    
    
    From bfb93338f6a39ca02b03af76d9792c4b9b1cf766 Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Thu, 20 Apr 2017 16:08:49 -0600
    Subject: [PATCH 536/990] Move net/iob to drivers/iob so that the I/O buffering
     feature can be available to other drivers when networking is disabled.
    
    ---
     arch/arm/src/common/up_initialize.c           | 10 +++-
     arch/avr/src/common/up_initialize.c           | 10 +++-
     arch/hc/src/common/up_initialize.c            | 10 +++-
     arch/mips/src/common/up_initialize.c          | 10 +++-
     arch/misoc/src/lm32/lm32_initialize.c         | 10 +++-
     arch/renesas/src/common/up_initialize.c       | 10 +++-
     arch/risc-v/src/common/up_initialize.c        | 18 +++---
     arch/sim/src/up_initialize.c                  |  9 ++-
     arch/x86/src/common/up_initialize.c           | 10 +++-
     arch/xtensa/src/common/xtensa_initialize.c    | 12 +++-
     arch/z16/src/common/up_initialize.c           | 10 +++-
     arch/z80/src/common/up_initialize.c           | 10 +++-
     configs/bambino-200e/netnsh/defconfig         | 16 +++---
     configs/c5471evm/httpd/defconfig              | 16 +++---
     configs/c5471evm/nettest/defconfig            | 16 +++---
     configs/c5471evm/nsh/defconfig                | 16 +++---
     configs/cloudctrl/nsh/defconfig               | 16 +++---
     configs/dk-tm4c129x/ipv6/defconfig            | 18 +++---
     configs/dk-tm4c129x/nsh/defconfig             | 18 +++---
     configs/eagle100/httpd/defconfig              | 16 +++---
     configs/eagle100/nettest/defconfig            | 16 +++---
     configs/eagle100/nsh/defconfig                | 16 +++---
     configs/eagle100/thttpd/defconfig             | 16 +++---
     configs/ekk-lm3s9b96/nsh/defconfig            | 16 +++---
     configs/ez80f910200zco/dhcpd/defconfig        | 16 +++---
     configs/ez80f910200zco/httpd/defconfig        | 16 +++---
     configs/ez80f910200zco/nettest/defconfig      | 16 +++---
     configs/ez80f910200zco/nsh/defconfig          | 16 +++---
     configs/ez80f910200zco/poll/defconfig         | 16 +++---
     configs/fire-stm32v2/nsh/defconfig            | 16 +++---
     configs/freedom-k64f/netnsh/defconfig         | 18 +++---
     configs/freedom-k66f/netnsh/defconfig         | 18 +++---
     configs/lincoln60/netnsh/defconfig            | 18 +++---
     configs/lincoln60/thttpd-binfs/defconfig      | 18 +++---
     configs/lm3s6432-s2e/nsh/defconfig            | 16 +++---
     configs/lm3s6965-ek/discover/defconfig        | 16 +++---
     configs/lm3s6965-ek/nsh/defconfig             | 16 +++---
     configs/lm3s6965-ek/tcpecho/defconfig         | 16 +++---
     configs/lm3s8962-ek/nsh/defconfig             | 16 +++---
     configs/lpcxpresso-lpc1768/dhcpd/defconfig    | 16 +++---
     configs/lpcxpresso-lpc1768/nsh/defconfig      | 16 +++---
     configs/lpcxpresso-lpc1768/thttpd/defconfig   | 16 +++---
     configs/misoc/hello/defconfig                 | 20 +++----
     configs/moxa/nsh/defconfig                    | 18 +++---
     configs/ntosd-dm320/nettest/defconfig         | 16 +++---
     configs/ntosd-dm320/nsh/defconfig             | 16 +++---
     configs/ntosd-dm320/poll/defconfig            | 16 +++---
     configs/ntosd-dm320/thttpd/defconfig          | 16 +++---
     configs/ntosd-dm320/udp/defconfig             | 16 +++---
     configs/ntosd-dm320/webserver/defconfig       | 16 +++---
     configs/olimex-lpc1766stk/ftpc/defconfig      | 16 +++---
     configs/olimex-lpc1766stk/hidmouse/defconfig  | 16 +++---
     configs/olimex-lpc1766stk/nettest/defconfig   | 16 +++---
     configs/olimex-lpc1766stk/nsh/defconfig       | 16 +++---
     .../olimex-lpc1766stk/slip-httpd/defconfig    | 16 +++---
     .../olimex-lpc1766stk/thttpd-binfs/defconfig  | 16 +++---
     .../olimex-lpc1766stk/thttpd-nxflat/defconfig | 16 +++---
     configs/olimex-lpc1766stk/zmodem/defconfig    | 16 +++---
     configs/olimex-stm32-e407/discover/defconfig  | 16 +++---
     configs/olimex-stm32-e407/netnsh/defconfig    | 16 +++---
     configs/olimex-stm32-e407/telnetd/defconfig   | 16 +++---
     configs/olimex-stm32-e407/webserver/defconfig | 16 +++---
     configs/olimex-stm32-p107/nsh/defconfig       | 16 +++---
     configs/olimex-stm32-p207/nsh/defconfig       | 16 +++---
     configs/olimex-strp711/nettest/defconfig      | 16 +++---
     configs/pic32mx-starterkit/nsh2/defconfig     | 16 +++---
     configs/pic32mx7mmb/nsh/defconfig             | 16 +++---
     configs/sam4e-ek/nsh/defconfig                | 18 +++---
     configs/sam4e-ek/nxwm/defconfig               | 16 +++---
     configs/sam4e-ek/usbnsh/defconfig             | 16 +++---
     configs/sama5d3-xplained/bridge/defconfig     | 10 ++--
     configs/sama5d4-ek/bridge/defconfig           | 10 ++--
     configs/sama5d4-ek/ipv6/defconfig             | 18 +++---
     configs/sama5d4-ek/nsh/defconfig              | 18 +++---
     configs/sama5d4-ek/nxwm/defconfig             | 18 +++---
     configs/same70-xplained/netnsh/defconfig      | 18 +++---
     configs/samv71-xult/netnsh/defconfig          | 18 +++---
     configs/samv71-xult/vnc/defconfig             | 18 +++---
     configs/samv71-xult/vnxwm/defconfig           | 18 +++---
     configs/shenzhou/nsh/defconfig                | 16 +++---
     configs/shenzhou/nxwm/defconfig               | 16 +++---
     configs/shenzhou/thttpd/defconfig             | 16 +++---
     configs/sim/nettest/defconfig                 | 16 +++---
     configs/sim/sixlowpan/defconfig               | 18 +++---
     configs/sim/udgram/defconfig                  | 10 ++--
     configs/sim/ustream/defconfig                 | 10 ++--
     configs/stm3220g-eval/dhcpd/defconfig         | 16 +++---
     configs/stm3220g-eval/nettest/defconfig       | 16 +++---
     configs/stm3220g-eval/nsh/defconfig           | 16 +++---
     configs/stm3220g-eval/nsh2/defconfig          | 16 +++---
     configs/stm3220g-eval/nxwm/defconfig          | 16 +++---
     configs/stm3220g-eval/telnetd/defconfig       | 16 +++---
     configs/stm3240g-eval/dhcpd/defconfig         | 16 +++---
     configs/stm3240g-eval/discover/defconfig      | 16 +++---
     configs/stm3240g-eval/nettest/defconfig       | 16 +++---
     configs/stm3240g-eval/nsh/defconfig           | 16 +++---
     configs/stm3240g-eval/nsh2/defconfig          | 16 +++---
     configs/stm3240g-eval/nxterm/defconfig        | 16 +++---
     configs/stm3240g-eval/nxwm/defconfig          | 16 +++---
     configs/stm3240g-eval/telnetd/defconfig       | 16 +++---
     configs/stm3240g-eval/webserver/defconfig     | 16 +++---
     configs/stm3240g-eval/xmlrpc/defconfig        | 16 +++---
     configs/stm32butterfly2/nshnet/defconfig      | 16 +++---
     configs/stm32f4discovery/ipv6/defconfig       | 18 +++---
     configs/stm32f4discovery/netnsh/defconfig     | 18 +++---
     configs/tm4c1294-launchpad/ipv6/defconfig     | 18 +++---
     configs/tm4c1294-launchpad/nsh/defconfig      | 18 +++---
     configs/twr-k64f120m/netnsh/defconfig         | 18 +++---
     configs/u-blox-c027/nsh/defconfig             | 18 +++---
     configs/viewtool-stm32f107/netnsh/defconfig   | 18 +++---
     configs/zkit-arm-1769/hello/defconfig         | 16 +++---
     configs/zkit-arm-1769/nsh/defconfig           | 16 +++---
     configs/zkit-arm-1769/nxhello/defconfig       | 16 +++---
     configs/zkit-arm-1769/thttpd/defconfig        | 16 +++---
     drivers/Kconfig                               |  2 +
     drivers/Makefile                              |  1 +
     drivers/README.txt                            |  4 ++
     {net => drivers}/iob/Kconfig                  | 21 ++++---
     {net => drivers}/iob/Make.defs                | 17 +++---
     {net => drivers}/iob/iob.h                    | 56 +++++++++++++------
     {net => drivers}/iob/iob_add_queue.c          | 13 +----
     {net => drivers}/iob/iob_alloc.c              |  9 +--
     {net => drivers}/iob/iob_alloc_qentry.c       |  9 +--
     {net => drivers}/iob/iob_clone.c              | 13 +----
     {net => drivers}/iob/iob_concat.c             |  9 +--
     {net => drivers}/iob/iob_contig.c             | 11 +---
     {net => drivers}/iob/iob_copyin.c             | 27 ++++-----
     {net => drivers}/iob/iob_copyout.c            |  9 +--
     {net => drivers}/iob/iob_dump.c               |  6 +-
     {net => drivers}/iob/iob_free.c               | 19 ++-----
     {net => drivers}/iob/iob_free_chain.c         |  9 +--
     {net => drivers}/iob/iob_free_qentry.c        |  9 +--
     {net => drivers}/iob/iob_free_queue.c         |  9 +--
     {net => drivers}/iob/iob_initialize.c         |  9 +--
     {net => drivers}/iob/iob_pack.c               |  9 +--
     {net => drivers}/iob/iob_peek_queue.c         |  9 +--
     {net => drivers}/iob/iob_remove_queue.c       |  9 +--
     {net => drivers}/iob/iob_test.c               |  2 +-
     {net => drivers}/iob/iob_trimhead.c           | 19 ++-----
     {net => drivers}/iob/iob_trimhead_queue.c     |  9 +--
     {net => drivers}/iob/iob_trimtail.c           | 15 ++---
     include/nuttx/drivers/iob.h                   | 11 ++++
     net/Kconfig                                   |  1 -
     net/Makefile                                  |  1 -
     net/README.txt                                |  3 +-
     net/net_initialize.c                          |  7 ---
     net/tcp/tcp_callback.c                        |  2 +-
     net/udp/udp_callback.c                        |  1 -
     net/udp/udp_conn.c                            |  1 -
     149 files changed, 1055 insertions(+), 1093 deletions(-)
     rename {net => drivers}/iob/Kconfig (79%)
     rename {net => drivers}/iob/Make.defs (77%)
     rename {net => drivers}/iob/iob.h (82%)
     rename {net => drivers}/iob/iob_add_queue.c (93%)
     rename {net => drivers}/iob/iob_alloc.c (97%)
     rename {net => drivers}/iob/iob_alloc_qentry.c (97%)
     rename {net => drivers}/iob/iob_clone.c (94%)
     rename {net => drivers}/iob/iob_concat.c (93%)
     rename {net => drivers}/iob/iob_contig.c (94%)
     rename {net => drivers}/iob/iob_copyin.c (92%)
     rename {net => drivers}/iob/iob_copyout.c (95%)
     rename {net => drivers}/iob/iob_dump.c (97%)
     rename {net => drivers}/iob/iob_free.c (89%)
     rename {net => drivers}/iob/iob_free_chain.c (93%)
     rename {net => drivers}/iob/iob_free_qentry.c (94%)
     rename {net => drivers}/iob/iob_free_queue.c (94%)
     rename {net => drivers}/iob/iob_initialize.c (95%)
     rename {net => drivers}/iob/iob_pack.c (95%)
     rename {net => drivers}/iob/iob_peek_queue.c (94%)
     rename {net => drivers}/iob/iob_remove_queue.c (94%)
     rename {net => drivers}/iob/iob_test.c (99%)
     rename {net => drivers}/iob/iob_trimhead.c (90%)
     rename {net => drivers}/iob/iob_trimhead_queue.c (94%)
     rename {net => drivers}/iob/iob_trimtail.c (91%)
    
    diff --git a/arch/arm/src/common/up_initialize.c b/arch/arm/src/common/up_initialize.c
    index 5182598246..ecf6400d33 100644
    --- a/arch/arm/src/common/up_initialize.c
    +++ b/arch/arm/src/common/up_initialize.c
    @@ -1,7 +1,7 @@
     /****************************************************************************
      * arch/arm/src/common/up_initialize.c
      *
    - *   Copyright (C) 2007-2010, 2012-2016 Gregory Nutt. All rights reserved.
    + *   Copyright (C) 2007-2010, 2012-2017 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
      *
      * Redistribution and use in source and binary forms, with or without
    @@ -44,6 +44,7 @@
     #include 
     #include 
     #include 
    +#include 
     #include 
     #include 
     #include 
    @@ -190,9 +191,14 @@ void up_initialize(void)
       arm_timer_initialize();
     #endif
     
    -  /* Register devices */
    +#ifdef CONFIG_DRIVERS_IOB
    +  /* Initialize IO buffering */
    +
    +  iob_initialize();
    +#endif
     
     #if CONFIG_NFILE_DESCRIPTORS > 0
    +  /* Register devices */
     
     #if defined(CONFIG_DEV_NULL)
       devnull_register();   /* Standard /dev/null */
    diff --git a/arch/avr/src/common/up_initialize.c b/arch/avr/src/common/up_initialize.c
    index 3db612d237..738f9b27d6 100644
    --- a/arch/avr/src/common/up_initialize.c
    +++ b/arch/avr/src/common/up_initialize.c
    @@ -1,7 +1,7 @@
     /****************************************************************************
      * arch/avr/src/common/up_initialize.c
      *
    - *   Copyright (C) 2010, 2012-2013, 2015-2016 Gregory Nutt. All rights reserved.
    + *   Copyright (C) 2010, 2012-2013, 2015-2017 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
      *
      * Redistribution and use in source and binary forms, with or without
    @@ -43,6 +43,7 @@
     
     #include 
     #include 
    +#include 
     #include 
     #include 
     #include 
    @@ -231,9 +232,14 @@ void up_initialize(void)
       avr_timer_initialize();
     #endif
     
    -  /* Register devices */
    +#ifdef CONFIG_DRIVERS_IOB
    +  /* Initialize IO buffering */
    +
    +  iob_initialize();
    +#endif
     
     #if CONFIG_NFILE_DESCRIPTORS > 0
    +  /* Register devices */
     
     #if defined(CONFIG_DEV_NULL)
       devnull_register();   /* Standard /dev/null */
    diff --git a/arch/hc/src/common/up_initialize.c b/arch/hc/src/common/up_initialize.c
    index b4d3fcde07..0484c8ffc3 100644
    --- a/arch/hc/src/common/up_initialize.c
    +++ b/arch/hc/src/common/up_initialize.c
    @@ -1,7 +1,7 @@
     /****************************************************************************
      * arch/hc/src/common/up_initialize.c
      *
    - *   Copyright (C) 2009-2010, 2012-2013, 2015-2016 Gregory Nutt. All rights reserved.
    + *   Copyright (C) 2009-2010, 2012-2013, 2015-2017 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
      *
      * Redistribution and use in source and binary forms, with or without
    @@ -44,6 +44,7 @@
     #include 
     #include 
     #include 
    +#include 
     #include 
     #include 
     #include 
    @@ -157,9 +158,14 @@ void up_initialize(void)
       hc_timer_initialize();
     #endif
     
    -  /* Register devices */
    +#ifdef CONFIG_DRIVERS_IOB
    +  /* Initialize IO buffering */
    +
    +  iob_initialize();
    +#endif
     
     #if CONFIG_NFILE_DESCRIPTORS > 0
    +  /* Register devices */
     
     #if defined(CONFIG_DEV_NULL)
       devnull_register();   /* Standard /dev/null */
    diff --git a/arch/mips/src/common/up_initialize.c b/arch/mips/src/common/up_initialize.c
    index a07c189cf6..7e301be7b0 100644
    --- a/arch/mips/src/common/up_initialize.c
    +++ b/arch/mips/src/common/up_initialize.c
    @@ -1,7 +1,7 @@
     /****************************************************************************
      * arch/mips/src/common/up_initialize.c
      *
    - *   Copyright (C) 2011-2013, 2015-2016 Gregory Nutt. All rights reserved.
    + *   Copyright (C) 2011-2013, 2015-2017 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
      *
      * Redistribution and use in source and binary forms, with or without
    @@ -44,6 +44,7 @@
     #include 
     #include 
     #include 
    +#include 
     #include 
     #include 
     #include 
    @@ -159,9 +160,14 @@ void up_initialize(void)
       mips_timer_initialize();
     #endif
     
    -  /* Register devices */
    +#ifdef CONFIG_DRIVERS_IOB
    +  /* Initialize IO buffering */
    +
    +  iob_initialize();
    +#endif
     
     #if CONFIG_NFILE_DESCRIPTORS > 0
    +  /* Register devices */
     
     #if defined(CONFIG_DEV_NULL)
       devnull_register();   /* Standard /dev/null */
    diff --git a/arch/misoc/src/lm32/lm32_initialize.c b/arch/misoc/src/lm32/lm32_initialize.c
    index 1c4323215a..8371a9a39f 100644
    --- a/arch/misoc/src/lm32/lm32_initialize.c
    +++ b/arch/misoc/src/lm32/lm32_initialize.c
    @@ -1,7 +1,7 @@
     /****************************************************************************
      * arch/misoc/src/lm32/lm32_initialize.c
      *
    - *   Copyright (C) 2016 Gregory Nutt. All rights reserved.
    + *   Copyright (C) 2016-2017 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
      *           Ramtin Amin 
      *
    @@ -44,6 +44,7 @@
     
     #include 
     #include 
    +#include 
     #include 
     #include 
     #include 
    @@ -78,8 +79,13 @@ void up_initialize(void)
     
       misoc_timer_initialize();
     
    +#ifdef CONFIG_DRIVERS_IOB
    +  /* Initialize IO buffering */
    +
    +  iob_initialize();
    +#endif
    +
       /* Initialize the network cores */
     
       misoc_net_initialize(0);
    -
     }
    diff --git a/arch/renesas/src/common/up_initialize.c b/arch/renesas/src/common/up_initialize.c
    index 49fc1f55d1..ad8756e48e 100644
    --- a/arch/renesas/src/common/up_initialize.c
    +++ b/arch/renesas/src/common/up_initialize.c
    @@ -1,7 +1,7 @@
     /****************************************************************************
      * arch/renesas/src/common/up_initialize.c
      *
    - *   Copyright (C) 2008-2010, 2012-2013, 2015-2016 Gregory Nutt. All rights reserved.
    + *   Copyright (C) 2008-2010, 2012-2013, 2015-2017 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
      *
      * Redistribution and use in source and binary forms, with or without
    @@ -44,6 +44,7 @@
     #include 
     #include 
     #include 
    +#include 
     #include 
     #include 
     #include 
    @@ -148,9 +149,14 @@ void up_initialize(void)
       renesas_timer_initialize();
     #endif
     
    -  /* Register devices */
    +#ifdef CONFIG_DRIVERS_IOB
    +  /* Initialize IO buffering */
    +
    +  iob_initialize();
    +#endif
     
     #if CONFIG_NFILE_DESCRIPTORS > 0
    +  /* Register devices */
     
     #if defined(CONFIG_DEV_NULL)
       devnull_register();   /* Standard /dev/null */
    diff --git a/arch/risc-v/src/common/up_initialize.c b/arch/risc-v/src/common/up_initialize.c
    index 205768b00d..f0a86dfd45 100644
    --- a/arch/risc-v/src/common/up_initialize.c
    +++ b/arch/risc-v/src/common/up_initialize.c
    @@ -1,7 +1,7 @@
     /****************************************************************************
      * arch/risc-v/src/common/up_initialize.c
      *
    - *   Copyright (C) 2007-2010, 2012-2015 Gregory Nutt. All rights reserved.
    + *   Copyright (C) 2007-2010, 2012-2015, 2017 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
      *
      * Redistribution and use in source and binary forms, with or without
    @@ -43,20 +43,13 @@
     
     #include 
     #include 
    +#include 
     
     #include 
     
     #include "up_arch.h"
     #include "up_internal.h"
     
    -/****************************************************************************
    - * Pre-processor Definitions
    - ****************************************************************************/
    -
    -/****************************************************************************
    - * Private Types
    - ****************************************************************************/
    -
     /****************************************************************************
      * Private Functions
      ****************************************************************************/
    @@ -158,9 +151,14 @@ void up_initialize(void)
       riscv_timer_initialize();
     #endif
     
    -  /* Register devices */
    +#ifdef CONFIG_DRIVERS_IOB
    +  /* Initialize IO buffering */
    +
    +  iob_initialize();
    +#endif
     
     #if CONFIG_NFILE_DESCRIPTORS > 0
    +  /* Register devices */
     
     #if defined(CONFIG_DEV_NULL)
       devnull_register();   /* Standard /dev/null */
    diff --git a/arch/sim/src/up_initialize.c b/arch/sim/src/up_initialize.c
    index 5b3f1c0e9f..d618ebac70 100644
    --- a/arch/sim/src/up_initialize.c
    +++ b/arch/sim/src/up_initialize.c
    @@ -1,7 +1,7 @@
     /****************************************************************************
      * arch/sim/src/up_initialize.c
      *
    - *   Copyright (C) 2007-2009, 2011-2016 Gregory Nutt. All rights reserved.
    + *   Copyright (C) 2007-2009, 2011-2017 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
      *
      * Redistribution and use in source and binary forms, with or without
    @@ -43,6 +43,7 @@
     
     #include 
     #include 
    +#include 
     #include 
     #include 
     #include 
    @@ -200,6 +201,12 @@ void up_initialize(void)
       up_pminitialize();
     #endif
     
    +#ifdef CONFIG_DRIVERS_IOB
    +  /* Initialize IO buffering */
    +
    +  iob_initialize();
    +#endif
    +
     #if CONFIG_NFILE_DESCRIPTORS > 0
       /* Register devices */
     
    diff --git a/arch/x86/src/common/up_initialize.c b/arch/x86/src/common/up_initialize.c
    index 2817204734..f5f6f7a0e0 100644
    --- a/arch/x86/src/common/up_initialize.c
    +++ b/arch/x86/src/common/up_initialize.c
    @@ -1,7 +1,7 @@
     /****************************************************************************
      * arch/x86/src/common/up_initialize.c
      *
    - *   Copyright (C) 2011-2013, 2015-2016 Gregory Nutt. All rights reserved.
    + *   Copyright (C) 2011-2013, 2015-2017 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
      *
      * Redistribution and use in source and binary forms, with or without
    @@ -44,6 +44,7 @@
     #include 
     #include 
     #include 
    +#include 
     #include 
     #include 
     #include 
    @@ -159,9 +160,14 @@ void up_initialize(void)
       x86_timer_initialize();
     #endif
     
    -  /* Register devices */
    +#ifdef CONFIG_DRIVERS_IOB
    +  /* Initialize IO buffering */
    +
    +  iob_initialize();
    +#endif
     
     #if CONFIG_NFILE_DESCRIPTORS > 0
    +  /* Register devices */
     
     #if defined(CONFIG_DEV_NULL)
       devnull_register();   /* Standard /dev/null */
    diff --git a/arch/xtensa/src/common/xtensa_initialize.c b/arch/xtensa/src/common/xtensa_initialize.c
    index 2041548b17..f3ad78392a 100644
    --- a/arch/xtensa/src/common/xtensa_initialize.c
    +++ b/arch/xtensa/src/common/xtensa_initialize.c
    @@ -1,7 +1,7 @@
     /****************************************************************************
      * arch/xtensa/src/common/xtensa_initialize.c
      *
    - *   Copyright (C) 2016 Gregory Nutt. All rights reserved.
    + *   Copyright (C) 2016-2017 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
      *
      * Redistribution and use in source and binary forms, with or without
    @@ -44,6 +44,7 @@
     #include 
     #include 
     #include 
    +#include 
     #include 
     #include 
     #include 
    @@ -161,15 +162,20 @@ void up_initialize(void)
         }
     #endif
     
    +#if !defined(CONFIG_SUPPRESS_INTERRUPTS) && !defined(CONFIG_SUPPRESS_TIMER_INTS)
       /* Initialize the system timer interrupt */
     
    -#if !defined(CONFIG_SUPPRESS_INTERRUPTS) && !defined(CONFIG_SUPPRESS_TIMER_INTS)
       xtensa_timer_initialize();
     #endif
     
    -  /* Register devices */
    +#ifdef CONFIG_DRIVERS_IOB
    +  /* Initialize IO buffering */
    +
    +  iob_initialize();
    +#endif
     
     #if CONFIG_NFILE_DESCRIPTORS > 0
    +  /* Register devices */
     
     #if defined(CONFIG_DEV_NULL)
       devnull_register();   /* Standard /dev/null */
    diff --git a/arch/z16/src/common/up_initialize.c b/arch/z16/src/common/up_initialize.c
    index 59ee8138cd..c04e342ab9 100644
    --- a/arch/z16/src/common/up_initialize.c
    +++ b/arch/z16/src/common/up_initialize.c
    @@ -1,7 +1,7 @@
     /****************************************************************************
      * arch/z16/src/common/up_initialize.c
      *
    - *   Copyright (C) 2008-2009, 2011-2013, 2015-2016 Gregory Nutt. All rights reserved.
    + *   Copyright (C) 2008-2009, 2011-2013, 2015-2017 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
      *
      * Redistribution and use in source and binary forms, with or without
    @@ -44,6 +44,7 @@
     #include 
     #include 
     #include 
    +#include 
     #include 
     #include 
     #include 
    @@ -159,9 +160,14 @@ void up_initialize(void)
       z16_timer_initialize();
     #endif
     
    -  /* Register devices */
    +#ifdef CONFIG_DRIVERS_IOB
    +  /* Initialize IO buffering */
    +
    +  iob_initialize();
    +#endif
     
     #if CONFIG_NFILE_DESCRIPTORS > 0
    +  /* Register devices */
     
     #if defined(CONFIG_DEV_NULL)
       devnull_register();   /* Standard /dev/null */
    diff --git a/arch/z80/src/common/up_initialize.c b/arch/z80/src/common/up_initialize.c
    index 036ce03b37..bedf28b0b0 100644
    --- a/arch/z80/src/common/up_initialize.c
    +++ b/arch/z80/src/common/up_initialize.c
    @@ -1,7 +1,7 @@
     /****************************************************************************
      * arch/z80/src/common/up_initialize.c
      *
    - *   Copyright (C) 2007-2009, 2012-2013, 2015-2016 Gregory Nutt. All rights reserved.
    + *   Copyright (C) 2007-2009, 2012-2013, 2015-2017 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
      *
      * Redistribution and use in source and binary forms, with or without
    @@ -44,6 +44,7 @@
     #include 
     #include 
     #include 
    +#include 
     #include 
     #include 
     #include 
    @@ -156,9 +157,14 @@ void up_initialize(void)
       (void)up_mmuinit();
     #endif
     
    -  /* Register devices */
    +#ifdef CONFIG_DRIVERS_IOB
    +  /* Initialize IO buffering */
    +
    +  iob_initialize();
    +#endif
     
     #if CONFIG_NFILE_DESCRIPTORS > 0
    +  /* Register devices */
     
     #if defined(CONFIG_DEV_NULL)
       devnull_register();   /* Standard /dev/null */
    diff --git a/configs/bambino-200e/netnsh/defconfig b/configs/bambino-200e/netnsh/defconfig
    index 5461560e92..83ae5fe9a8 100644
    --- a/configs/bambino-200e/netnsh/defconfig
    +++ b/configs/bambino-200e/netnsh/defconfig
    @@ -484,6 +484,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -751,14 +759,6 @@ CONFIG_NET_ARP_MAXAGE=120
     CONFIG_NET_ARP_IPIN=y
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/c5471evm/httpd/defconfig b/configs/c5471evm/httpd/defconfig
    index 384749cd6e..b844eb004a 100644
    --- a/configs/c5471evm/httpd/defconfig
    +++ b/configs/c5471evm/httpd/defconfig
    @@ -366,6 +366,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -576,14 +584,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/c5471evm/nettest/defconfig b/configs/c5471evm/nettest/defconfig
    index 5e09afbe28..d371baf706 100644
    --- a/configs/c5471evm/nettest/defconfig
    +++ b/configs/c5471evm/nettest/defconfig
    @@ -354,6 +354,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -564,14 +572,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/c5471evm/nsh/defconfig b/configs/c5471evm/nsh/defconfig
    index c00123dcc9..9c26f594e8 100644
    --- a/configs/c5471evm/nsh/defconfig
    +++ b/configs/c5471evm/nsh/defconfig
    @@ -366,6 +366,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -582,14 +590,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/cloudctrl/nsh/defconfig b/configs/cloudctrl/nsh/defconfig
    index 1ee28dce24..54f875306e 100644
    --- a/configs/cloudctrl/nsh/defconfig
    +++ b/configs/cloudctrl/nsh/defconfig
    @@ -757,6 +757,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -1049,14 +1057,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/dk-tm4c129x/ipv6/defconfig b/configs/dk-tm4c129x/ipv6/defconfig
    index 4b327ef4d0..3eaecb19c5 100644
    --- a/configs/dk-tm4c129x/ipv6/defconfig
    +++ b/configs/dk-tm4c129x/ipv6/defconfig
    @@ -502,6 +502,15 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=36
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
    +CONFIG_IOB_THROTTLE=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -784,15 +793,6 @@ CONFIG_ICMPv6_NEIGHBOR_DELAYMSEC=20
     # ARP Configuration
     #
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=36
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -CONFIG_IOB_THROTTLE=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/dk-tm4c129x/nsh/defconfig b/configs/dk-tm4c129x/nsh/defconfig
    index 617b987820..6fb8a008ea 100644
    --- a/configs/dk-tm4c129x/nsh/defconfig
    +++ b/configs/dk-tm4c129x/nsh/defconfig
    @@ -502,6 +502,15 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=36
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
    +CONFIG_IOB_THROTTLE=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -787,15 +796,6 @@ CONFIG_NET_ARP_SEND=y
     CONFIG_ARP_SEND_MAXTRIES=5
     CONFIG_ARP_SEND_DELAYMSEC=20
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=36
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -CONFIG_IOB_THROTTLE=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/eagle100/httpd/defconfig b/configs/eagle100/httpd/defconfig
    index 7d8d5fba78..3af19d1584 100644
    --- a/configs/eagle100/httpd/defconfig
    +++ b/configs/eagle100/httpd/defconfig
    @@ -470,6 +470,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -710,14 +718,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/eagle100/nettest/defconfig b/configs/eagle100/nettest/defconfig
    index 443f3ecbac..06adb40d7b 100644
    --- a/configs/eagle100/nettest/defconfig
    +++ b/configs/eagle100/nettest/defconfig
    @@ -458,6 +458,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -697,14 +705,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/eagle100/nsh/defconfig b/configs/eagle100/nsh/defconfig
    index f890cdbc10..22bed91050 100644
    --- a/configs/eagle100/nsh/defconfig
    +++ b/configs/eagle100/nsh/defconfig
    @@ -481,6 +481,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -748,14 +756,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/eagle100/thttpd/defconfig b/configs/eagle100/thttpd/defconfig
    index bf7e936ec7..cdd4eecb3f 100644
    --- a/configs/eagle100/thttpd/defconfig
    +++ b/configs/eagle100/thttpd/defconfig
    @@ -449,6 +449,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -691,14 +699,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/ekk-lm3s9b96/nsh/defconfig b/configs/ekk-lm3s9b96/nsh/defconfig
    index 979386f809..c26cb06d91 100644
    --- a/configs/ekk-lm3s9b96/nsh/defconfig
    +++ b/configs/ekk-lm3s9b96/nsh/defconfig
    @@ -468,6 +468,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -735,14 +743,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/ez80f910200zco/dhcpd/defconfig b/configs/ez80f910200zco/dhcpd/defconfig
    index ad915adc28..0b61941b7a 100644
    --- a/configs/ez80f910200zco/dhcpd/defconfig
    +++ b/configs/ez80f910200zco/dhcpd/defconfig
    @@ -337,6 +337,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=8
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -589,14 +597,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=8
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/ez80f910200zco/httpd/defconfig b/configs/ez80f910200zco/httpd/defconfig
    index 30dee6ec58..77a0e30b06 100644
    --- a/configs/ez80f910200zco/httpd/defconfig
    +++ b/configs/ez80f910200zco/httpd/defconfig
    @@ -349,6 +349,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -608,14 +616,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/ez80f910200zco/nettest/defconfig b/configs/ez80f910200zco/nettest/defconfig
    index 8d6a8b3dd0..15cbb1da5d 100644
    --- a/configs/ez80f910200zco/nettest/defconfig
    +++ b/configs/ez80f910200zco/nettest/defconfig
    @@ -337,6 +337,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -595,14 +603,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/ez80f910200zco/nsh/defconfig b/configs/ez80f910200zco/nsh/defconfig
    index f1271c3d19..3db4c5cc00 100644
    --- a/configs/ez80f910200zco/nsh/defconfig
    +++ b/configs/ez80f910200zco/nsh/defconfig
    @@ -349,6 +349,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -616,14 +624,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/ez80f910200zco/poll/defconfig b/configs/ez80f910200zco/poll/defconfig
    index 521e76d910..53541fe0fb 100644
    --- a/configs/ez80f910200zco/poll/defconfig
    +++ b/configs/ez80f910200zco/poll/defconfig
    @@ -349,6 +349,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -610,14 +618,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/fire-stm32v2/nsh/defconfig b/configs/fire-stm32v2/nsh/defconfig
    index 8cada6692f..a2f7defdf1 100644
    --- a/configs/fire-stm32v2/nsh/defconfig
    +++ b/configs/fire-stm32v2/nsh/defconfig
    @@ -766,6 +766,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -1106,14 +1114,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/freedom-k64f/netnsh/defconfig b/configs/freedom-k64f/netnsh/defconfig
    index 6634ed2337..ac209b3a8b 100644
    --- a/configs/freedom-k64f/netnsh/defconfig
    +++ b/configs/freedom-k64f/netnsh/defconfig
    @@ -497,6 +497,15 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=36
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
    +CONFIG_IOB_THROTTLE=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -766,15 +775,6 @@ CONFIG_NET_ARP_SEND=y
     CONFIG_ARP_SEND_MAXTRIES=5
     CONFIG_ARP_SEND_DELAYMSEC=20
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=36
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -CONFIG_IOB_THROTTLE=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/freedom-k66f/netnsh/defconfig b/configs/freedom-k66f/netnsh/defconfig
    index 0dffbe5d56..dbb26035ea 100644
    --- a/configs/freedom-k66f/netnsh/defconfig
    +++ b/configs/freedom-k66f/netnsh/defconfig
    @@ -506,6 +506,15 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=36
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
    +CONFIG_IOB_THROTTLE=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -794,15 +803,6 @@ CONFIG_NET_ARP_SEND=y
     CONFIG_ARP_SEND_MAXTRIES=5
     CONFIG_ARP_SEND_DELAYMSEC=20
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=36
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -CONFIG_IOB_THROTTLE=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/lincoln60/netnsh/defconfig b/configs/lincoln60/netnsh/defconfig
    index bb7a78a93c..ca17f4e7b4 100644
    --- a/configs/lincoln60/netnsh/defconfig
    +++ b/configs/lincoln60/netnsh/defconfig
    @@ -459,6 +459,15 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=36
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
    +CONFIG_IOB_THROTTLE=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -728,15 +737,6 @@ CONFIG_NET_ARP_SEND=y
     CONFIG_ARP_SEND_MAXTRIES=5
     CONFIG_ARP_SEND_DELAYMSEC=20
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=36
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -CONFIG_IOB_THROTTLE=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/lincoln60/thttpd-binfs/defconfig b/configs/lincoln60/thttpd-binfs/defconfig
    index 0f3690c7fd..c659979d94 100644
    --- a/configs/lincoln60/thttpd-binfs/defconfig
    +++ b/configs/lincoln60/thttpd-binfs/defconfig
    @@ -436,6 +436,15 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
    +CONFIG_IOB_THROTTLE=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -699,15 +708,6 @@ CONFIG_NET_ARP_SEND=y
     CONFIG_ARP_SEND_MAXTRIES=5
     CONFIG_ARP_SEND_DELAYMSEC=20
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -CONFIG_IOB_THROTTLE=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/lm3s6432-s2e/nsh/defconfig b/configs/lm3s6432-s2e/nsh/defconfig
    index 27f1e85a50..675a7b6c17 100644
    --- a/configs/lm3s6432-s2e/nsh/defconfig
    +++ b/configs/lm3s6432-s2e/nsh/defconfig
    @@ -463,6 +463,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -725,14 +733,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/lm3s6965-ek/discover/defconfig b/configs/lm3s6965-ek/discover/defconfig
    index cc4fc1715d..838fbeac02 100644
    --- a/configs/lm3s6965-ek/discover/defconfig
    +++ b/configs/lm3s6965-ek/discover/defconfig
    @@ -473,6 +473,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -740,14 +748,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/lm3s6965-ek/nsh/defconfig b/configs/lm3s6965-ek/nsh/defconfig
    index cc4fc1715d..838fbeac02 100644
    --- a/configs/lm3s6965-ek/nsh/defconfig
    +++ b/configs/lm3s6965-ek/nsh/defconfig
    @@ -473,6 +473,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -740,14 +748,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/lm3s6965-ek/tcpecho/defconfig b/configs/lm3s6965-ek/tcpecho/defconfig
    index c3b2d038cb..ac6fd9a2bd 100644
    --- a/configs/lm3s6965-ek/tcpecho/defconfig
    +++ b/configs/lm3s6965-ek/tcpecho/defconfig
    @@ -462,6 +462,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -711,14 +719,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/lm3s8962-ek/nsh/defconfig b/configs/lm3s8962-ek/nsh/defconfig
    index 5d1599a47d..de5e95e743 100644
    --- a/configs/lm3s8962-ek/nsh/defconfig
    +++ b/configs/lm3s8962-ek/nsh/defconfig
    @@ -485,6 +485,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -752,14 +760,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/lpcxpresso-lpc1768/dhcpd/defconfig b/configs/lpcxpresso-lpc1768/dhcpd/defconfig
    index 599b3001a0..d18c05e9e4 100644
    --- a/configs/lpcxpresso-lpc1768/dhcpd/defconfig
    +++ b/configs/lpcxpresso-lpc1768/dhcpd/defconfig
    @@ -426,6 +426,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=8
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -679,14 +687,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=8
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/lpcxpresso-lpc1768/nsh/defconfig b/configs/lpcxpresso-lpc1768/nsh/defconfig
    index fdf6ac732e..0a2f6da13d 100644
    --- a/configs/lpcxpresso-lpc1768/nsh/defconfig
    +++ b/configs/lpcxpresso-lpc1768/nsh/defconfig
    @@ -449,6 +449,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -765,14 +773,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/lpcxpresso-lpc1768/thttpd/defconfig b/configs/lpcxpresso-lpc1768/thttpd/defconfig
    index 6eedaf96c6..ac12426f49 100644
    --- a/configs/lpcxpresso-lpc1768/thttpd/defconfig
    +++ b/configs/lpcxpresso-lpc1768/thttpd/defconfig
    @@ -426,6 +426,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -687,14 +695,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/misoc/hello/defconfig b/configs/misoc/hello/defconfig
    index da8283d9ff..bb25f3c366 100644
    --- a/configs/misoc/hello/defconfig
    +++ b/configs/misoc/hello/defconfig
    @@ -318,6 +318,16 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
    +CONFIG_IOB_THROTTLE=8
    +# CONFIG_IOB_DEBUG is not set
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -584,16 +594,6 @@ CONFIG_NET_ARP_SEND=y
     CONFIG_ARP_SEND_MAXTRIES=5
     CONFIG_ARP_SEND_DELAYMSEC=20
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -CONFIG_IOB_THROTTLE=8
    -# CONFIG_IOB_DEBUG is not set
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/moxa/nsh/defconfig b/configs/moxa/nsh/defconfig
    index a368f1171a..6a45427b5c 100644
    --- a/configs/moxa/nsh/defconfig
    +++ b/configs/moxa/nsh/defconfig
    @@ -354,6 +354,15 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
    +CONFIG_IOB_THROTTLE=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -613,15 +622,6 @@ CONFIG_NET_ARP_SEND=y
     CONFIG_ARP_SEND_MAXTRIES=5
     CONFIG_ARP_SEND_DELAYMSEC=20
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -CONFIG_IOB_THROTTLE=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/ntosd-dm320/nettest/defconfig b/configs/ntosd-dm320/nettest/defconfig
    index a7bafa1d08..638279f138 100644
    --- a/configs/ntosd-dm320/nettest/defconfig
    +++ b/configs/ntosd-dm320/nettest/defconfig
    @@ -336,6 +336,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -603,14 +611,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/ntosd-dm320/nsh/defconfig b/configs/ntosd-dm320/nsh/defconfig
    index a40c5d29f9..1283565c72 100644
    --- a/configs/ntosd-dm320/nsh/defconfig
    +++ b/configs/ntosd-dm320/nsh/defconfig
    @@ -348,6 +348,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -630,14 +638,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/ntosd-dm320/poll/defconfig b/configs/ntosd-dm320/poll/defconfig
    index 17b6151dea..8f179e8ce8 100644
    --- a/configs/ntosd-dm320/poll/defconfig
    +++ b/configs/ntosd-dm320/poll/defconfig
    @@ -348,6 +348,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -619,14 +627,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/ntosd-dm320/thttpd/defconfig b/configs/ntosd-dm320/thttpd/defconfig
    index 3bdeaf23ac..d146c17293 100644
    --- a/configs/ntosd-dm320/thttpd/defconfig
    +++ b/configs/ntosd-dm320/thttpd/defconfig
    @@ -336,6 +336,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -607,14 +615,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/ntosd-dm320/udp/defconfig b/configs/ntosd-dm320/udp/defconfig
    index fbf8eb5185..24ea1fe49f 100644
    --- a/configs/ntosd-dm320/udp/defconfig
    +++ b/configs/ntosd-dm320/udp/defconfig
    @@ -336,6 +336,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=8
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -597,14 +605,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=8
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/ntosd-dm320/webserver/defconfig b/configs/ntosd-dm320/webserver/defconfig
    index a35c7abb37..4f1b363d1c 100644
    --- a/configs/ntosd-dm320/webserver/defconfig
    +++ b/configs/ntosd-dm320/webserver/defconfig
    @@ -348,6 +348,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -615,14 +623,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/olimex-lpc1766stk/ftpc/defconfig b/configs/olimex-lpc1766stk/ftpc/defconfig
    index a68e6d292e..ed46ca4e7f 100644
    --- a/configs/olimex-lpc1766stk/ftpc/defconfig
    +++ b/configs/olimex-lpc1766stk/ftpc/defconfig
    @@ -449,6 +449,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -732,14 +740,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/olimex-lpc1766stk/hidmouse/defconfig b/configs/olimex-lpc1766stk/hidmouse/defconfig
    index aecd251b1e..0dec1bcdc8 100644
    --- a/configs/olimex-lpc1766stk/hidmouse/defconfig
    +++ b/configs/olimex-lpc1766stk/hidmouse/defconfig
    @@ -463,6 +463,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -726,14 +734,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/olimex-lpc1766stk/nettest/defconfig b/configs/olimex-lpc1766stk/nettest/defconfig
    index e38fcf7f16..15d885ba0e 100644
    --- a/configs/olimex-lpc1766stk/nettest/defconfig
    +++ b/configs/olimex-lpc1766stk/nettest/defconfig
    @@ -427,6 +427,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -685,14 +693,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/olimex-lpc1766stk/nsh/defconfig b/configs/olimex-lpc1766stk/nsh/defconfig
    index 8bbff74d8e..60f4e87f7c 100644
    --- a/configs/olimex-lpc1766stk/nsh/defconfig
    +++ b/configs/olimex-lpc1766stk/nsh/defconfig
    @@ -450,6 +450,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -735,14 +743,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/olimex-lpc1766stk/slip-httpd/defconfig b/configs/olimex-lpc1766stk/slip-httpd/defconfig
    index 0259bd572a..e9a9fcd7f4 100644
    --- a/configs/olimex-lpc1766stk/slip-httpd/defconfig
    +++ b/configs/olimex-lpc1766stk/slip-httpd/defconfig
    @@ -411,6 +411,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -650,14 +658,6 @@ CONFIG_NET_ICMP=y
     # ARP Configuration
     #
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/olimex-lpc1766stk/thttpd-binfs/defconfig b/configs/olimex-lpc1766stk/thttpd-binfs/defconfig
    index 5e83771e75..ec9ade8e7d 100644
    --- a/configs/olimex-lpc1766stk/thttpd-binfs/defconfig
    +++ b/configs/olimex-lpc1766stk/thttpd-binfs/defconfig
    @@ -436,6 +436,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -697,14 +705,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/olimex-lpc1766stk/thttpd-nxflat/defconfig b/configs/olimex-lpc1766stk/thttpd-nxflat/defconfig
    index 22e39cf274..74a3e55d2b 100644
    --- a/configs/olimex-lpc1766stk/thttpd-nxflat/defconfig
    +++ b/configs/olimex-lpc1766stk/thttpd-nxflat/defconfig
    @@ -427,6 +427,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -688,14 +696,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/olimex-lpc1766stk/zmodem/defconfig b/configs/olimex-lpc1766stk/zmodem/defconfig
    index d430891207..51526dd8b5 100644
    --- a/configs/olimex-lpc1766stk/zmodem/defconfig
    +++ b/configs/olimex-lpc1766stk/zmodem/defconfig
    @@ -451,6 +451,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -750,14 +758,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/olimex-stm32-e407/discover/defconfig b/configs/olimex-stm32-e407/discover/defconfig
    index dca0ba9c65..9a2f223de3 100644
    --- a/configs/olimex-stm32-e407/discover/defconfig
    +++ b/configs/olimex-stm32-e407/discover/defconfig
    @@ -760,6 +760,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -1034,14 +1042,6 @@ CONFIG_NET_ARP_MAXAGE=120
     CONFIG_NET_ARP_IPIN=y
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/olimex-stm32-e407/netnsh/defconfig b/configs/olimex-stm32-e407/netnsh/defconfig
    index 34486378ca..1969e3f313 100644
    --- a/configs/olimex-stm32-e407/netnsh/defconfig
    +++ b/configs/olimex-stm32-e407/netnsh/defconfig
    @@ -760,6 +760,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -1036,14 +1044,6 @@ CONFIG_NET_ARP_MAXAGE=120
     CONFIG_NET_ARP_IPIN=y
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/olimex-stm32-e407/telnetd/defconfig b/configs/olimex-stm32-e407/telnetd/defconfig
    index 9768cb9553..349bf77be8 100644
    --- a/configs/olimex-stm32-e407/telnetd/defconfig
    +++ b/configs/olimex-stm32-e407/telnetd/defconfig
    @@ -760,6 +760,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -1036,14 +1044,6 @@ CONFIG_NET_ARP_MAXAGE=120
     CONFIG_NET_ARP_IPIN=y
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/olimex-stm32-e407/webserver/defconfig b/configs/olimex-stm32-e407/webserver/defconfig
    index 4257b4218f..fa179cb794 100644
    --- a/configs/olimex-stm32-e407/webserver/defconfig
    +++ b/configs/olimex-stm32-e407/webserver/defconfig
    @@ -760,6 +760,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -1034,14 +1042,6 @@ CONFIG_NET_ARP_MAXAGE=120
     CONFIG_NET_ARP_IPIN=y
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/olimex-stm32-p107/nsh/defconfig b/configs/olimex-stm32-p107/nsh/defconfig
    index 4df7a5586d..78dcb93ed4 100644
    --- a/configs/olimex-stm32-p107/nsh/defconfig
    +++ b/configs/olimex-stm32-p107/nsh/defconfig
    @@ -727,6 +727,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -1036,14 +1044,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/olimex-stm32-p207/nsh/defconfig b/configs/olimex-stm32-p207/nsh/defconfig
    index 315f0dba73..55de4e0d37 100644
    --- a/configs/olimex-stm32-p207/nsh/defconfig
    +++ b/configs/olimex-stm32-p207/nsh/defconfig
    @@ -790,6 +790,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -1079,14 +1087,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/olimex-strp711/nettest/defconfig b/configs/olimex-strp711/nettest/defconfig
    index 55e048aacd..50d63c8170 100644
    --- a/configs/olimex-strp711/nettest/defconfig
    +++ b/configs/olimex-strp711/nettest/defconfig
    @@ -382,6 +382,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -649,14 +657,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/pic32mx-starterkit/nsh2/defconfig b/configs/pic32mx-starterkit/nsh2/defconfig
    index 12de402bbf..de8c688ac5 100644
    --- a/configs/pic32mx-starterkit/nsh2/defconfig
    +++ b/configs/pic32mx-starterkit/nsh2/defconfig
    @@ -479,6 +479,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -775,14 +783,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/pic32mx7mmb/nsh/defconfig b/configs/pic32mx7mmb/nsh/defconfig
    index 4cfed72604..c1a7d79a6f 100644
    --- a/configs/pic32mx7mmb/nsh/defconfig
    +++ b/configs/pic32mx7mmb/nsh/defconfig
    @@ -488,6 +488,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -838,14 +846,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/sam4e-ek/nsh/defconfig b/configs/sam4e-ek/nsh/defconfig
    index 18a8cc7fd0..1ac7fb3118 100644
    --- a/configs/sam4e-ek/nsh/defconfig
    +++ b/configs/sam4e-ek/nsh/defconfig
    @@ -517,6 +517,15 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
    +CONFIG_IOB_THROTTLE=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -840,15 +849,6 @@ CONFIG_NET_ARP_SEND=y
     CONFIG_ARP_SEND_MAXTRIES=5
     CONFIG_ARP_SEND_DELAYMSEC=20
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -CONFIG_IOB_THROTTLE=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/sam4e-ek/nxwm/defconfig b/configs/sam4e-ek/nxwm/defconfig
    index 6280d4b140..3ab09117e1 100644
    --- a/configs/sam4e-ek/nxwm/defconfig
    +++ b/configs/sam4e-ek/nxwm/defconfig
    @@ -527,6 +527,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -899,14 +907,6 @@ CONFIG_NET_ARP_SEND=y
     CONFIG_ARP_SEND_MAXTRIES=5
     CONFIG_ARP_SEND_DELAYMSEC=20
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/sam4e-ek/usbnsh/defconfig b/configs/sam4e-ek/usbnsh/defconfig
    index 197e6519a4..eebe76056b 100644
    --- a/configs/sam4e-ek/usbnsh/defconfig
    +++ b/configs/sam4e-ek/usbnsh/defconfig
    @@ -523,6 +523,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -884,14 +892,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/sama5d3-xplained/bridge/defconfig b/configs/sama5d3-xplained/bridge/defconfig
    index ab2ee2b39d..01e56ae986 100644
    --- a/configs/sama5d3-xplained/bridge/defconfig
    +++ b/configs/sama5d3-xplained/bridge/defconfig
    @@ -544,6 +544,11 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +# CONFIG_DRIVERS_IOB is not set
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -796,11 +801,6 @@ CONFIG_NET_ARP_SEND=y
     CONFIG_ARP_SEND_MAXTRIES=5
     CONFIG_ARP_SEND_DELAYMSEC=20
     
    -#
    -# Network I/O Buffer Support
    -#
    -# CONFIG_DRIVERS_IOB is not set
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/sama5d4-ek/bridge/defconfig b/configs/sama5d4-ek/bridge/defconfig
    index 9f463640df..ae4d3b8160 100644
    --- a/configs/sama5d4-ek/bridge/defconfig
    +++ b/configs/sama5d4-ek/bridge/defconfig
    @@ -562,6 +562,11 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +# CONFIG_DRIVERS_IOB is not set
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -828,11 +833,6 @@ CONFIG_NET_ARP_SEND=y
     CONFIG_ARP_SEND_MAXTRIES=5
     CONFIG_ARP_SEND_DELAYMSEC=20
     
    -#
    -# Network I/O Buffer Support
    -#
    -# CONFIG_DRIVERS_IOB is not set
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/sama5d4-ek/ipv6/defconfig b/configs/sama5d4-ek/ipv6/defconfig
    index e0c7c271e0..06791816be 100644
    --- a/configs/sama5d4-ek/ipv6/defconfig
    +++ b/configs/sama5d4-ek/ipv6/defconfig
    @@ -663,6 +663,15 @@ CONFIG_DEV_RANDOM=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=36
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
    +CONFIG_IOB_THROTTLE=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -1017,15 +1026,6 @@ CONFIG_ICMPv6_NEIGHBOR_DELAYMSEC=20
     # ARP Configuration
     #
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=36
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -CONFIG_IOB_THROTTLE=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/sama5d4-ek/nsh/defconfig b/configs/sama5d4-ek/nsh/defconfig
    index e323ec55fa..4c72b5f9b9 100644
    --- a/configs/sama5d4-ek/nsh/defconfig
    +++ b/configs/sama5d4-ek/nsh/defconfig
    @@ -663,6 +663,15 @@ CONFIG_DEV_RANDOM=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=36
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
    +CONFIG_IOB_THROTTLE=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -1020,15 +1029,6 @@ CONFIG_NET_ARP_SEND=y
     CONFIG_ARP_SEND_MAXTRIES=5
     CONFIG_ARP_SEND_DELAYMSEC=20
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=36
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -CONFIG_IOB_THROTTLE=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/sama5d4-ek/nxwm/defconfig b/configs/sama5d4-ek/nxwm/defconfig
    index 81b25c7dd1..17907ad732 100644
    --- a/configs/sama5d4-ek/nxwm/defconfig
    +++ b/configs/sama5d4-ek/nxwm/defconfig
    @@ -637,6 +637,15 @@ CONFIG_DEV_RANDOM=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=36
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
    +CONFIG_IOB_THROTTLE=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -987,15 +996,6 @@ CONFIG_NET_ARP_MAXAGE=120
     CONFIG_NET_ARP_IPIN=y
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=36
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -CONFIG_IOB_THROTTLE=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/same70-xplained/netnsh/defconfig b/configs/same70-xplained/netnsh/defconfig
    index db58645eab..2b3cca401d 100644
    --- a/configs/same70-xplained/netnsh/defconfig
    +++ b/configs/same70-xplained/netnsh/defconfig
    @@ -536,6 +536,15 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
    +CONFIG_IOB_THROTTLE=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -875,15 +884,6 @@ CONFIG_NET_ARP_SEND=y
     CONFIG_ARP_SEND_MAXTRIES=5
     CONFIG_ARP_SEND_DELAYMSEC=20
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -CONFIG_IOB_THROTTLE=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/samv71-xult/netnsh/defconfig b/configs/samv71-xult/netnsh/defconfig
    index 06ea511773..ca281528ad 100644
    --- a/configs/samv71-xult/netnsh/defconfig
    +++ b/configs/samv71-xult/netnsh/defconfig
    @@ -539,6 +539,15 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=36
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
    +CONFIG_IOB_THROTTLE=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -878,15 +887,6 @@ CONFIG_NET_ARP_SEND=y
     CONFIG_ARP_SEND_MAXTRIES=5
     CONFIG_ARP_SEND_DELAYMSEC=20
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=36
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -CONFIG_IOB_THROTTLE=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/samv71-xult/vnc/defconfig b/configs/samv71-xult/vnc/defconfig
    index f5afccc5f9..a413da950f 100644
    --- a/configs/samv71-xult/vnc/defconfig
    +++ b/configs/samv71-xult/vnc/defconfig
    @@ -538,6 +538,15 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=72
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
    +CONFIG_IOB_THROTTLE=32
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -875,15 +884,6 @@ CONFIG_NET_ARP_SEND=y
     CONFIG_ARP_SEND_MAXTRIES=5
     CONFIG_ARP_SEND_DELAYMSEC=20
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=72
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -CONFIG_IOB_THROTTLE=32
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/samv71-xult/vnxwm/defconfig b/configs/samv71-xult/vnxwm/defconfig
    index 84584c52df..4632730355 100644
    --- a/configs/samv71-xult/vnxwm/defconfig
    +++ b/configs/samv71-xult/vnxwm/defconfig
    @@ -541,6 +541,15 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=72
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
    +CONFIG_IOB_THROTTLE=32
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -878,15 +887,6 @@ CONFIG_NET_ARP_SEND=y
     CONFIG_ARP_SEND_MAXTRIES=5
     CONFIG_ARP_SEND_DELAYMSEC=20
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=72
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -CONFIG_IOB_THROTTLE=32
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/shenzhou/nsh/defconfig b/configs/shenzhou/nsh/defconfig
    index e163798cf0..6e20d65f44 100644
    --- a/configs/shenzhou/nsh/defconfig
    +++ b/configs/shenzhou/nsh/defconfig
    @@ -747,6 +747,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -1038,14 +1046,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/shenzhou/nxwm/defconfig b/configs/shenzhou/nxwm/defconfig
    index dc29c952d3..2370d5377a 100644
    --- a/configs/shenzhou/nxwm/defconfig
    +++ b/configs/shenzhou/nxwm/defconfig
    @@ -771,6 +771,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -1098,14 +1106,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/shenzhou/thttpd/defconfig b/configs/shenzhou/thttpd/defconfig
    index 8abca6cb9a..ce40c66cca 100644
    --- a/configs/shenzhou/thttpd/defconfig
    +++ b/configs/shenzhou/thttpd/defconfig
    @@ -748,6 +748,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -1068,14 +1076,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/sim/nettest/defconfig b/configs/sim/nettest/defconfig
    index 27be8a0ebc..c1e7c78898 100644
    --- a/configs/sim/nettest/defconfig
    +++ b/configs/sim/nettest/defconfig
    @@ -279,6 +279,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -485,14 +493,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/sim/sixlowpan/defconfig b/configs/sim/sixlowpan/defconfig
    index 5065856d47..5c64eb13e6 100644
    --- a/configs/sim/sixlowpan/defconfig
    +++ b/configs/sim/sixlowpan/defconfig
    @@ -294,6 +294,15 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=36
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
    +CONFIG_IOB_THROTTLE=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -604,15 +613,6 @@ CONFIG_NET_UDP_READAHEAD=y
     # ARP Configuration
     #
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=36
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -CONFIG_IOB_THROTTLE=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/sim/udgram/defconfig b/configs/sim/udgram/defconfig
    index 352667b42b..8586c0b34d 100644
    --- a/configs/sim/udgram/defconfig
    +++ b/configs/sim/udgram/defconfig
    @@ -288,6 +288,11 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +# CONFIG_DRIVERS_IOB is not set
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -476,11 +481,6 @@ CONFIG_NET_LOCAL_DGRAM=y
     # ARP Configuration
     #
     
    -#
    -# Network I/O Buffer Support
    -#
    -# CONFIG_DRIVERS_IOB is not set
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/sim/ustream/defconfig b/configs/sim/ustream/defconfig
    index 6b0726a89d..034f8b83c1 100644
    --- a/configs/sim/ustream/defconfig
    +++ b/configs/sim/ustream/defconfig
    @@ -288,6 +288,11 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +# CONFIG_DRIVERS_IOB is not set
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -476,11 +481,6 @@ CONFIG_NET_LOCAL_STREAM=y
     # ARP Configuration
     #
     
    -#
    -# Network I/O Buffer Support
    -#
    -# CONFIG_DRIVERS_IOB is not set
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/stm3220g-eval/dhcpd/defconfig b/configs/stm3220g-eval/dhcpd/defconfig
    index ff770e02cb..c46030d14b 100644
    --- a/configs/stm3220g-eval/dhcpd/defconfig
    +++ b/configs/stm3220g-eval/dhcpd/defconfig
    @@ -742,6 +742,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=8
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -995,14 +1003,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=8
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/stm3220g-eval/nettest/defconfig b/configs/stm3220g-eval/nettest/defconfig
    index 49adf7c8d8..f69886646f 100644
    --- a/configs/stm3220g-eval/nettest/defconfig
    +++ b/configs/stm3220g-eval/nettest/defconfig
    @@ -742,6 +742,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -1000,14 +1008,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/stm3220g-eval/nsh/defconfig b/configs/stm3220g-eval/nsh/defconfig
    index 61cc41fe2c..253c075c8d 100644
    --- a/configs/stm3220g-eval/nsh/defconfig
    +++ b/configs/stm3220g-eval/nsh/defconfig
    @@ -767,6 +767,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -1080,14 +1088,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/stm3220g-eval/nsh2/defconfig b/configs/stm3220g-eval/nsh2/defconfig
    index 428488c43e..c437849e01 100644
    --- a/configs/stm3220g-eval/nsh2/defconfig
    +++ b/configs/stm3220g-eval/nsh2/defconfig
    @@ -768,6 +768,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -1076,14 +1084,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/stm3220g-eval/nxwm/defconfig b/configs/stm3220g-eval/nxwm/defconfig
    index 9962bb6201..55c3649cb2 100644
    --- a/configs/stm3220g-eval/nxwm/defconfig
    +++ b/configs/stm3220g-eval/nxwm/defconfig
    @@ -788,6 +788,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -1124,14 +1132,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/stm3220g-eval/telnetd/defconfig b/configs/stm3220g-eval/telnetd/defconfig
    index 2adcd3c46b..5a842d7721 100644
    --- a/configs/stm3220g-eval/telnetd/defconfig
    +++ b/configs/stm3220g-eval/telnetd/defconfig
    @@ -742,6 +742,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -1002,14 +1010,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/stm3240g-eval/dhcpd/defconfig b/configs/stm3240g-eval/dhcpd/defconfig
    index efe681e3c4..e972d6303c 100644
    --- a/configs/stm3240g-eval/dhcpd/defconfig
    +++ b/configs/stm3240g-eval/dhcpd/defconfig
    @@ -746,6 +746,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=8
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -999,14 +1007,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=8
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/stm3240g-eval/discover/defconfig b/configs/stm3240g-eval/discover/defconfig
    index 59263438d9..e104292ed2 100644
    --- a/configs/stm3240g-eval/discover/defconfig
    +++ b/configs/stm3240g-eval/discover/defconfig
    @@ -765,6 +765,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -1035,14 +1043,6 @@ CONFIG_NET_ARP_MAXAGE=120
     CONFIG_NET_ARP_IPIN=y
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/stm3240g-eval/nettest/defconfig b/configs/stm3240g-eval/nettest/defconfig
    index 336084eda6..ac3a56be38 100644
    --- a/configs/stm3240g-eval/nettest/defconfig
    +++ b/configs/stm3240g-eval/nettest/defconfig
    @@ -746,6 +746,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -1004,14 +1012,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/stm3240g-eval/nsh/defconfig b/configs/stm3240g-eval/nsh/defconfig
    index 719a3dbe42..4557ee9797 100644
    --- a/configs/stm3240g-eval/nsh/defconfig
    +++ b/configs/stm3240g-eval/nsh/defconfig
    @@ -783,6 +783,14 @@ CONFIG_DEV_RANDOM=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -1059,14 +1067,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/stm3240g-eval/nsh2/defconfig b/configs/stm3240g-eval/nsh2/defconfig
    index dc73b09c20..fc1ab20840 100644
    --- a/configs/stm3240g-eval/nsh2/defconfig
    +++ b/configs/stm3240g-eval/nsh2/defconfig
    @@ -772,6 +772,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -1080,14 +1088,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/stm3240g-eval/nxterm/defconfig b/configs/stm3240g-eval/nxterm/defconfig
    index fefe9b52bb..77847443b9 100644
    --- a/configs/stm3240g-eval/nxterm/defconfig
    +++ b/configs/stm3240g-eval/nxterm/defconfig
    @@ -791,6 +791,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -1098,14 +1106,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/stm3240g-eval/nxwm/defconfig b/configs/stm3240g-eval/nxwm/defconfig
    index 5dd1c02f83..5e9f7a1306 100644
    --- a/configs/stm3240g-eval/nxwm/defconfig
    +++ b/configs/stm3240g-eval/nxwm/defconfig
    @@ -792,6 +792,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -1120,14 +1128,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/stm3240g-eval/telnetd/defconfig b/configs/stm3240g-eval/telnetd/defconfig
    index dc565ae021..742c3f6e6e 100644
    --- a/configs/stm3240g-eval/telnetd/defconfig
    +++ b/configs/stm3240g-eval/telnetd/defconfig
    @@ -746,6 +746,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -1006,14 +1014,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/stm3240g-eval/webserver/defconfig b/configs/stm3240g-eval/webserver/defconfig
    index d4772a437c..3dc8fbb926 100644
    --- a/configs/stm3240g-eval/webserver/defconfig
    +++ b/configs/stm3240g-eval/webserver/defconfig
    @@ -771,6 +771,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -1078,14 +1086,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/stm3240g-eval/xmlrpc/defconfig b/configs/stm3240g-eval/xmlrpc/defconfig
    index 4e3aa3b290..90bd6a6ee4 100644
    --- a/configs/stm3240g-eval/xmlrpc/defconfig
    +++ b/configs/stm3240g-eval/xmlrpc/defconfig
    @@ -760,6 +760,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -1031,14 +1039,6 @@ CONFIG_NET_ARP_MAXAGE=120
     CONFIG_NET_ARP_IPIN=y
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/stm32butterfly2/nshnet/defconfig b/configs/stm32butterfly2/nshnet/defconfig
    index e1e4e1529e..fb61f3a9f6 100644
    --- a/configs/stm32butterfly2/nshnet/defconfig
    +++ b/configs/stm32butterfly2/nshnet/defconfig
    @@ -743,6 +743,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     CONFIG_RAMDISK=y
    @@ -1075,14 +1083,6 @@ CONFIG_NET_ARP_MAXAGE=120
     CONFIG_NET_ARP_IPIN=y
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/stm32f4discovery/ipv6/defconfig b/configs/stm32f4discovery/ipv6/defconfig
    index 5b8900d674..25d5886bbd 100644
    --- a/configs/stm32f4discovery/ipv6/defconfig
    +++ b/configs/stm32f4discovery/ipv6/defconfig
    @@ -791,6 +791,15 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=36
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
    +CONFIG_IOB_THROTTLE=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -1080,15 +1089,6 @@ CONFIG_ICMPv6_NEIGHBOR_DELAYMSEC=20
     # ARP Configuration
     #
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=36
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -CONFIG_IOB_THROTTLE=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/stm32f4discovery/netnsh/defconfig b/configs/stm32f4discovery/netnsh/defconfig
    index 5eec4b26b6..f11c99eb6a 100644
    --- a/configs/stm32f4discovery/netnsh/defconfig
    +++ b/configs/stm32f4discovery/netnsh/defconfig
    @@ -791,6 +791,15 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=36
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
    +CONFIG_IOB_THROTTLE=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -1083,15 +1092,6 @@ CONFIG_NET_ARP_SEND=y
     CONFIG_ARP_SEND_MAXTRIES=5
     CONFIG_ARP_SEND_DELAYMSEC=20
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=36
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -CONFIG_IOB_THROTTLE=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/tm4c1294-launchpad/ipv6/defconfig b/configs/tm4c1294-launchpad/ipv6/defconfig
    index 87e46300c2..e77c8b7e32 100644
    --- a/configs/tm4c1294-launchpad/ipv6/defconfig
    +++ b/configs/tm4c1294-launchpad/ipv6/defconfig
    @@ -490,6 +490,15 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=36
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
    +CONFIG_IOB_THROTTLE=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -740,15 +749,6 @@ CONFIG_NET_ICMPv6_PING=y
     # ARP Configuration
     #
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=36
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -CONFIG_IOB_THROTTLE=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/tm4c1294-launchpad/nsh/defconfig b/configs/tm4c1294-launchpad/nsh/defconfig
    index 2ef2aece70..7ccb18b26c 100644
    --- a/configs/tm4c1294-launchpad/nsh/defconfig
    +++ b/configs/tm4c1294-launchpad/nsh/defconfig
    @@ -490,6 +490,15 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=36
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
    +CONFIG_IOB_THROTTLE=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -745,15 +754,6 @@ CONFIG_NET_ARP_SEND=y
     CONFIG_ARP_SEND_MAXTRIES=5
     CONFIG_ARP_SEND_DELAYMSEC=20
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=36
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -CONFIG_IOB_THROTTLE=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/twr-k64f120m/netnsh/defconfig b/configs/twr-k64f120m/netnsh/defconfig
    index 7a3cbb274f..1bd65b87c2 100644
    --- a/configs/twr-k64f120m/netnsh/defconfig
    +++ b/configs/twr-k64f120m/netnsh/defconfig
    @@ -505,6 +505,15 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=36
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
    +CONFIG_IOB_THROTTLE=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -785,15 +794,6 @@ CONFIG_NET_ARP_SEND=y
     CONFIG_ARP_SEND_MAXTRIES=5
     CONFIG_ARP_SEND_DELAYMSEC=20
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=36
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -CONFIG_IOB_THROTTLE=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/u-blox-c027/nsh/defconfig b/configs/u-blox-c027/nsh/defconfig
    index 7333497362..da3f3a030c 100644
    --- a/configs/u-blox-c027/nsh/defconfig
    +++ b/configs/u-blox-c027/nsh/defconfig
    @@ -457,6 +457,15 @@ CONFIG_DEV_ZERO=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
    +CONFIG_IOB_THROTTLE=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -786,15 +795,6 @@ CONFIG_NET_ARP_SEND=y
     CONFIG_ARP_SEND_MAXTRIES=5
     CONFIG_ARP_SEND_DELAYMSEC=20
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -CONFIG_IOB_THROTTLE=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/viewtool-stm32f107/netnsh/defconfig b/configs/viewtool-stm32f107/netnsh/defconfig
    index 76a1c45cbc..4b16b79f03 100644
    --- a/configs/viewtool-stm32f107/netnsh/defconfig
    +++ b/configs/viewtool-stm32f107/netnsh/defconfig
    @@ -739,6 +739,15 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
    +CONFIG_IOB_THROTTLE=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -1008,15 +1017,6 @@ CONFIG_NET_ARP_SEND=y
     CONFIG_ARP_SEND_MAXTRIES=5
     CONFIG_ARP_SEND_DELAYMSEC=20
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -CONFIG_IOB_THROTTLE=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/zkit-arm-1769/hello/defconfig b/configs/zkit-arm-1769/hello/defconfig
    index 8566f9cade..b8e92733f7 100644
    --- a/configs/zkit-arm-1769/hello/defconfig
    +++ b/configs/zkit-arm-1769/hello/defconfig
    @@ -427,6 +427,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -685,14 +693,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/zkit-arm-1769/nsh/defconfig b/configs/zkit-arm-1769/nsh/defconfig
    index 283403c164..7d896929d8 100644
    --- a/configs/zkit-arm-1769/nsh/defconfig
    +++ b/configs/zkit-arm-1769/nsh/defconfig
    @@ -450,6 +450,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -735,14 +743,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/zkit-arm-1769/nxhello/defconfig b/configs/zkit-arm-1769/nxhello/defconfig
    index 20de0ea354..b0c578902c 100644
    --- a/configs/zkit-arm-1769/nxhello/defconfig
    +++ b/configs/zkit-arm-1769/nxhello/defconfig
    @@ -450,6 +450,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -773,14 +781,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/configs/zkit-arm-1769/thttpd/defconfig b/configs/zkit-arm-1769/thttpd/defconfig
    index 2691aaccdb..2846f29834 100644
    --- a/configs/zkit-arm-1769/thttpd/defconfig
    +++ b/configs/zkit-arm-1769/thttpd/defconfig
    @@ -427,6 +427,14 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -688,14 +696,6 @@ CONFIG_NET_ARP_MAXAGE=120
     # CONFIG_NET_ARP_IPIN is not set
     # CONFIG_NET_ARP_SEND is not set
     
    -#
    -# Network I/O Buffer Support
    -#
    -CONFIG_DRIVERS_IOB=y
    -CONFIG_IOB_NBUFFERS=24
    -CONFIG_IOB_BUFSIZE=196
    -CONFIG_IOB_NCHAINS=8
    -
     #
     # User-space networking stack API
     #
    diff --git a/drivers/Kconfig b/drivers/Kconfig
    index d7bc265374..fa200e17d4 100644
    --- a/drivers/Kconfig
    +++ b/drivers/Kconfig
    @@ -98,6 +98,8 @@ source drivers/loop/Kconfig
     
     menu "Buffering"
     
    +source "drivers/iob/Kconfig"
    +
     config DRVR_WRITEBUFFER
     	bool "Enable write buffer support"
     	default n
    diff --git a/drivers/Makefile b/drivers/Makefile
    index 5946cc123a..1de5f4d133 100644
    --- a/drivers/Makefile
    +++ b/drivers/Makefile
    @@ -54,6 +54,7 @@ include audio$(DELIM)Make.defs
     include bch$(DELIM)Make.defs
     include i2c$(DELIM)Make.defs
     include input$(DELIM)Make.defs
    +include iob$(DELIM)Make.defs
     include ioexpander$(DELIM)Make.defs
     include lcd$(DELIM)Make.defs
     include leds$(DELIM)Make.defs
    diff --git a/drivers/README.txt b/drivers/README.txt
    index f9f23af06f..ad4e25f642 100644
    --- a/drivers/README.txt
    +++ b/drivers/README.txt
    @@ -74,6 +74,10 @@ eeprom/
       interface but instead use the simple character interface provided by
       the EEPROM drivers.
     
    +iob/
    +  Common driver I/O buffer support.  Used primarily by networking and
    +  network-related drivers but available for any usage.
    +
     i2c/
       I2C drivers and support logic.  See include/nuttx/i2c/i2c_master.h
     
    diff --git a/net/iob/Kconfig b/drivers/iob/Kconfig
    similarity index 79%
    rename from net/iob/Kconfig
    rename to drivers/iob/Kconfig
    index 459e144ebb..e5368681d5 100644
    --- a/net/iob/Kconfig
    +++ b/drivers/iob/Kconfig
    @@ -3,19 +3,19 @@
     # see the file kconfig-language.txt in the NuttX tools repository.
     #
     
    -menu "Network I/O Buffer Support"
    +menu "Common  I/O Buffer Support"
     
     config DRIVERS_IOB
    -	bool "Enable generic network I/O buffer support"
    +	bool "Enable generic I/O buffer support"
     	default n
     	---help---
    -		This setting will build the networking I/O buffer (IOB) support
    +		This setting will build the common I/O buffer (IOB) support
     		library.
     
     if DRIVERS_IOB
     
     config IOB_NBUFFERS
    -	int "Number of pre-allocated network I/O buffers"
    +	int "Number of pre-allocated I/O buffers"
     	default 24 if (NET_TCP_WRITE_BUFFERS && !NET_TCP_READAHEAD) || (!NET_TCP_WRITE_BUFFERS && NET_TCP_READAHEAD)
     	default 36 if NET_TCP_WRITE_BUFFERS && NET_TCP_READAHEAD
     	default 8 if !NET_TCP_WRITE_BUFFERS && !NET_TCP_READAHEAD
    @@ -25,7 +25,7 @@ config IOB_NBUFFERS
     		buffers available for packet data.
     
     config IOB_BUFSIZE
    -	int "Payload size of one network I/O buffer"
    +	int "Payload size of one I/O buffer"
     	default 196
     	---help---
     		Each packet is represented by a series of small I/O buffers in a
    @@ -65,11 +65,10 @@ config IOB_DEBUG
     	default n
     	depends on DEBUG_FEATURES
     	---help---
    -		This option will force debug output from I/O buffer logic,
    -		even without network debug output.  This is not normally something
    -		that would want to do but is convenient if you are debugging the
    -		I/O buffer logic and do not want to get overloaded with other
    -		network-related debug output.
    +		This option will force debug output from I/O buffer logic.  This
    +		is not normally something that would want to do but is convenient
    +		if you are debugging the I/O buffer logic and do not want to get
    +		overloaded with other un-related debug output.
     
     endif # DRIVERS_IOB
    -endmenu # Network I/O buffer support
    +endmenu # Common I/O buffer support
    diff --git a/net/iob/Make.defs b/drivers/iob/Make.defs
    similarity index 77%
    rename from net/iob/Make.defs
    rename to drivers/iob/Make.defs
    index ec55eca204..ba74e8e578 100644
    --- a/net/iob/Make.defs
    +++ b/drivers/iob/Make.defs
    @@ -1,7 +1,7 @@
     ############################################################################
    -# net/iob/Make.defs
    +# drivers/iob/Make.defs
     #
    -#   Copyright (C) 2014 Gregory Nutt. All rights reserved.
    +#   Copyright (C) 2014, 2017 Gregory Nutt. All rights reserved.
     #   Author: Gregory Nutt 
     #
     # Redistribution and use in source and binary forms, with or without
    @@ -37,19 +37,20 @@ ifeq ($(CONFIG_DRIVERS_IOB),y)
     
     # Include IOB source files
     
    -NET_CSRCS += iob_add_queue.c iob_alloc.c iob_alloc_qentry.c iob_clone.c
    -NET_CSRCS += iob_concat.c iob_copyin.c iob_copyout.c iob_contig.c iob_free.c
    -NET_CSRCS += iob_free_chain.c iob_free_qentry.c iob_free_queue.c
    -NET_CSRCS += iob_initialize.c iob_pack.c iob_peek_queue.c iob_remove_queue.c
    -NET_CSRCS += iob_trimhead.c iob_trimhead_queue.c iob_trimtail.c
    +CSRCS += iob_add_queue.c iob_alloc.c iob_alloc_qentry.c iob_clone.c
    +CSRCS += iob_concat.c iob_copyin.c iob_copyout.c iob_contig.c iob_free.c
    +CSRCS += iob_free_chain.c iob_free_qentry.c iob_free_queue.c
    +CSRCS += iob_initialize.c iob_pack.c iob_peek_queue.c iob_remove_queue.c
    +CSRCS += iob_trimhead.c iob_trimhead_queue.c iob_trimtail.c
     
     ifeq ($(CONFIG_DEBUG_FEATURES),y)
    -NET_CSRCS += iob_dump.c
    +  CSRCS += iob_dump.c
     endif
     
     # Include iob build support
     
     DEPPATH += --dep-path iob
     VPATH += :iob
    +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)$(DELIM)drivers$(DELIM)iob}
     
     endif
    diff --git a/net/iob/iob.h b/drivers/iob/iob.h
    similarity index 82%
    rename from net/iob/iob.h
    rename to drivers/iob/iob.h
    index d949edecf0..30f2310272 100644
    --- a/net/iob/iob.h
    +++ b/drivers/iob/iob.h
    @@ -1,7 +1,7 @@
     /****************************************************************************
    - * net/iob/iob.h
    + * drivers/iob/iob.h
      *
    - *   Copyright (C) 2014 Gregory Nutt. All rights reserved.
    + *   Copyright (C) 2014, 2017 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
      *
      * Redistribution and use in source and binary forms, with or without
    @@ -33,8 +33,8 @@
      *
      ****************************************************************************/
     
    -#ifndef __NET_IOB_IOB_H
    -#define __NET_IOB_IOB_H 1
    +#ifndef __DRIVERS_IOB_IOB_H
    +#define __DRIVERS_IOB_IOB_H 1
     
     /****************************************************************************
      * Included Files
    @@ -43,11 +43,46 @@
     #include 
     
     #include 
    +#include 
     
     #include 
     
     #ifdef CONFIG_DRIVERS_IOB
     
    +/****************************************************************************
    + * Pre-processor Definitions
    + ****************************************************************************/
    +
    +#if defined(CONFIG_DEBUG_FEATURES) && defined(CONFIG_IOB_DEBUG)
    +#ifdef CONFIG_CPP_HAVE_VARARGS
    +
    +#  define ioberr(format, ...)    _err(format, ##__VA_ARGS__)
    +#  define iobwarn(format, ...)   _warn(format, ##__VA_ARGS__)
    +#  define iobinfo(format, ...)   _info(format, ##__VA_ARGS__)
    +
    +#else
    +    
    +#  define ioberr                 _err
    +#  define iobwarn                _warn
    +#  define iobinfo                _info
    +
    +#endif
    +#else
    +#ifdef CONFIG_CPP_HAVE_VARARGS
    +
    +#  define ioberr(format, ...)
    +#  define iobwarn(format, ...)
    +#  define iobinfo(format, ...)
    +
    +#else
    +    
    +#  define ioberr                 (void)
    +#  define iobwarn                (void)
    +#  define iobinfo                (void)
    +
    +#endif
    +#endif /* CONFIG_DEBUG_FEATURES && CONFIG_IOB_DEBUG */
    +
     /****************************************************************************
      * Public Data
      ****************************************************************************/
    @@ -100,17 +135,6 @@ FAR struct iob_qentry_s *iob_alloc_qentry(void);
     
     FAR struct iob_qentry_s *iob_tryalloc_qentry(void);
     
    -/****************************************************************************
    - * Name: iob_tryalloc
    - *
    - * Description:
    - *   Try to allocate an I/O buffer by taking the buffer at the head of the
    - *   free list without waiting for a buffer to become free.
    - *
    - ****************************************************************************/
    -
    -FAR struct iob_s *iob_tryalloc(bool throttled);
    -
     /****************************************************************************
      * Name: iob_free_qentry
      *
    @@ -123,4 +147,4 @@ FAR struct iob_s *iob_tryalloc(bool throttled);
     FAR struct iob_qentry_s *iob_free_qentry(FAR struct iob_qentry_s *iobq);
     
     #endif /* CONFIG_DRIVERS_IOB */
    -#endif /* __NET_IOB_IOB_H */
    +#endif /* __DRIVERS_IOB_IOB_H */
    diff --git a/net/iob/iob_add_queue.c b/drivers/iob/iob_add_queue.c
    similarity index 93%
    rename from net/iob/iob_add_queue.c
    rename to drivers/iob/iob_add_queue.c
    index 51de43aaae..a2f3376208 100644
    --- a/net/iob/iob_add_queue.c
    +++ b/drivers/iob/iob_add_queue.c
    @@ -1,5 +1,5 @@
     /****************************************************************************
    - * net/iob/iob_add_queue.c
    + * drivers/iob/iob_add_queue.c
      *
      *   Copyright (C) 2014 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
    @@ -39,13 +39,6 @@
     
     #include 
     
    -#if defined(CONFIG_DEBUG_FEATURES) && defined(CONFIG_IOB_DEBUG)
    -/* Force debug output (from this file only) */
    -
    -#  undef  CONFIG_DEBUG_NET
    -#  define CONFIG_DEBUG_NET 1
    -#endif
    -
     #include 
     #include 
     #include 
    @@ -125,7 +118,7 @@ int iob_add_queue(FAR struct iob_s *iob, FAR struct iob_queue_s *iobq)
       qentry = iob_alloc_qentry();
       if (!qentry)
         {
    -      nerr("ERROR: Failed to allocate a container\n");
    +      ioberr("ERROR: Failed to allocate a container\n");
           return -ENOMEM;
         }
     
    @@ -150,7 +143,7 @@ int iob_tryadd_queue(FAR struct iob_s *iob, FAR struct iob_queue_s *iobq)
       qentry = iob_tryalloc_qentry();
       if (!qentry)
         {
    -      nerr("ERROR: Failed to allocate a container\n");
    +      ioberr("ERROR: Failed to allocate a container\n");
           return -ENOMEM;
         }
     
    diff --git a/net/iob/iob_alloc.c b/drivers/iob/iob_alloc.c
    similarity index 97%
    rename from net/iob/iob_alloc.c
    rename to drivers/iob/iob_alloc.c
    index f5210994cd..9fc938d7ed 100644
    --- a/net/iob/iob_alloc.c
    +++ b/drivers/iob/iob_alloc.c
    @@ -1,5 +1,5 @@
     /****************************************************************************
    - * net/iob/iob_alloc.c
    + * drivers/iob/iob_alloc.c
      *
      *   Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
    @@ -39,13 +39,6 @@
     
     #include 
     
    -#if defined(CONFIG_DEBUG_FEATURES) && defined(CONFIG_IOB_DEBUG)
    -/* Force debug output (from this file only) */
    -
    -#  undef  CONFIG_DEBUG_NET
    -#  define CONFIG_DEBUG_NET 1
    -#endif
    -
     #include 
     #include 
     #include 
    diff --git a/net/iob/iob_alloc_qentry.c b/drivers/iob/iob_alloc_qentry.c
    similarity index 97%
    rename from net/iob/iob_alloc_qentry.c
    rename to drivers/iob/iob_alloc_qentry.c
    index 7b3fda3ee9..147f1f8328 100644
    --- a/net/iob/iob_alloc_qentry.c
    +++ b/drivers/iob/iob_alloc_qentry.c
    @@ -1,5 +1,5 @@
     /****************************************************************************
    - * net/iob/iob_alloc_qentry.c
    + * drivers/iob/iob_alloc_qentry.c
      *
      *   Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
    @@ -39,13 +39,6 @@
     
     #include 
     
    -#if defined(CONFIG_DEBUG_FEATURES) && defined(CONFIG_IOB_DEBUG)
    -/* Force debug output (from this file only) */
    -
    -#  undef  CONFIG_DEBUG_NET
    -#  define CONFIG_DEBUG_NET 1
    -#endif
    -
     #include 
     #include 
     #include 
    diff --git a/net/iob/iob_clone.c b/drivers/iob/iob_clone.c
    similarity index 94%
    rename from net/iob/iob_clone.c
    rename to drivers/iob/iob_clone.c
    index 15a5b81a87..bbd2450280 100644
    --- a/net/iob/iob_clone.c
    +++ b/drivers/iob/iob_clone.c
    @@ -1,7 +1,7 @@
     /****************************************************************************
    - * net/iob1/iob_copy.c
    + * drivers/iob/iob_copy.c
      *
    - *   Copyright (C) 2014 Gregory Nutt. All rights reserved.
    + *   Copyright (C) 2014, 2017 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
      *
      * Redistribution and use in source and binary forms, with or without
    @@ -39,13 +39,6 @@
     
     #include 
     
    -#if defined(CONFIG_DEBUG_FEATURES) && defined(CONFIG_IOB_DEBUG)
    -/* Force debug output (from this file only) */
    -
    -#  undef  CONFIG_DEBUG_NET
    -#  define CONFIG_DEBUG_NET 1
    -#endif
    -
     #include 
     #include 
     #include 
    @@ -168,7 +161,7 @@ int iob_clone(FAR struct iob_s *iob1, FAR struct iob_s *iob2, bool throttled)
               next = iob_alloc(throttled);
               if (!next)
                 {
    -              nerr("ERROR: Failed to allocate an I/O buffer/n");
    +              ioberr("ERROR: Failed to allocate an I/O buffer/n");
                   return -ENOMEM;
                 }
     
    diff --git a/net/iob/iob_concat.c b/drivers/iob/iob_concat.c
    similarity index 93%
    rename from net/iob/iob_concat.c
    rename to drivers/iob/iob_concat.c
    index 10a74b30b5..8c9325ee53 100644
    --- a/net/iob/iob_concat.c
    +++ b/drivers/iob/iob_concat.c
    @@ -1,5 +1,5 @@
     /****************************************************************************
    - * net/iob/iob_concat.c
    + * drivers/iob/iob_concat.c
      *
      *   Copyright (C) 2014 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
    @@ -39,13 +39,6 @@
     
     #include 
     
    -#if defined(CONFIG_DEBUG_FEATURES) && defined(CONFIG_IOB_DEBUG)
    -/* Force debug output (from this file only) */
    -
    -#  undef  CONFIG_DEBUG_NET
    -#  define CONFIG_DEBUG_NET 1
    -#endif
    -
     #include 
     
     #include 
    diff --git a/net/iob/iob_contig.c b/drivers/iob/iob_contig.c
    similarity index 94%
    rename from net/iob/iob_contig.c
    rename to drivers/iob/iob_contig.c
    index aabbc91352..af2bc40db7 100644
    --- a/net/iob/iob_contig.c
    +++ b/drivers/iob/iob_contig.c
    @@ -1,5 +1,5 @@
     /****************************************************************************
    - * net/iob/iob_contig.c
    + * drivers/iob/iob_contig.c
      *
      *   Copyright (C) 2014 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
    @@ -39,13 +39,6 @@
     
     #include 
     
    -#if defined(CONFIG_DEBUG_FEATURES) && defined(CONFIG_IOB_DEBUG)
    -/* Force debug output (from this file only) */
    -
    -#  undef  CONFIG_DEBUG_NET
    -#  define CONFIG_DEBUG_NET 1
    -#endif
    -
     #include 
     #include 
     #include 
    @@ -161,7 +154,7 @@ int iob_contig(FAR struct iob_s *iob, unsigned int len)
     
       else
         {
    -      nerr("ERROR: pktlen=%u < requested len=%u\n", iob->io_pktlen, len);
    +      ioberr("ERROR: pktlen=%u < requested len=%u\n", iob->io_pktlen, len);
           return -ENOSPC;
         }
     }
    diff --git a/net/iob/iob_copyin.c b/drivers/iob/iob_copyin.c
    similarity index 92%
    rename from net/iob/iob_copyin.c
    rename to drivers/iob/iob_copyin.c
    index db2f167669..8a5732cb94 100644
    --- a/net/iob/iob_copyin.c
    +++ b/drivers/iob/iob_copyin.c
    @@ -1,7 +1,7 @@
     /****************************************************************************
    - * net/iob/iob_copyin.c
    + * drivers/iob/iob_copyin.c
      *
    - *   Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved.
    + *   Copyright (C) 2014, 2016-2017 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
      *
      * Redistribution and use in source and binary forms, with or without
    @@ -39,13 +39,6 @@
     
     #include 
     
    -#if defined(CONFIG_DEBUG_FEATURES) && defined(CONFIG_IOB_DEBUG)
    -/* Force debug output (from this file only) */
    -
    -#  undef  CONFIG_DEBUG_NET
    -#  define CONFIG_DEBUG_NET 1
    -#endif
    -
     #include 
     #include 
     #include 
    @@ -97,15 +90,15 @@ static int iob_copyin_internal(FAR struct iob_s *iob, FAR const uint8_t *src,
       unsigned int avail;
       unsigned int total = len;
     
    -  ninfo("iob=%p len=%u offset=%u\n", iob, len, offset);
    +  iobinfo("iob=%p len=%u offset=%u\n", iob, len, offset);
       DEBUGASSERT(iob && src);
     
       /* The offset must applied to data that is already in the I/O buffer chain */
     
       if (offset > iob->io_pktlen)
         {
    -      nerr("ERROR: offset is past the end of data: %u > %u\n",
    -           offset, iob->io_pktlen);
    +      ioberr("ERROR: offset is past the end of data: %u > %u\n",
    +             offset, iob->io_pktlen);
           return -ESPIPE;
         }
     
    @@ -130,7 +123,7 @@ static int iob_copyin_internal(FAR struct iob_s *iob, FAR const uint8_t *src,
           dest  = &iob->io_data[iob->io_offset + offset];
           avail = iob->io_len - offset;
     
    -      ninfo("iob=%p avail=%u len=%u next=%p\n", iob, avail, len, next);
    +      iobinfo("iob=%p avail=%u len=%u next=%p\n", iob, avail, len, next);
     
           /* Will the rest of the copy fit into this buffer, overwriting
            * existing data.
    @@ -187,8 +180,8 @@ static int iob_copyin_internal(FAR struct iob_s *iob, FAR const uint8_t *src,
           /* Copy from the user buffer to the I/O buffer.  */
     
           memcpy(dest, src, ncopy);
    -      ninfo("iob=%p Copy %u bytes new len=%u\n",
    -            iob, ncopy, iob->io_len);
    +      iobinfo("iob=%p Copy %u bytes new len=%u\n",
    +              iob, ncopy, iob->io_len);
     
           /* Adjust the total length of the copy and the destination address in
            * the user buffer.
    @@ -220,14 +213,14 @@ static int iob_copyin_internal(FAR struct iob_s *iob, FAR const uint8_t *src,
     
               if (next == NULL)
                 {
    -              nerr("ERROR: Failed to allocate I/O buffer\n");
    +              ioberr("ERROR: Failed to allocate I/O buffer\n");
                   return len;
                 }
     
               /* Add the new, empty I/O buffer to the end of the buffer chain. */
     
               iob->io_flink = next;
    -          ninfo("iob=%p added to the chain\n", iob);
    +          iobinfo("iob=%p added to the chain\n", iob);
             }
     
           iob = next;
    diff --git a/net/iob/iob_copyout.c b/drivers/iob/iob_copyout.c
    similarity index 95%
    rename from net/iob/iob_copyout.c
    rename to drivers/iob/iob_copyout.c
    index 9b6df5531d..4b8c4e243c 100644
    --- a/net/iob/iob_copyout.c
    +++ b/drivers/iob/iob_copyout.c
    @@ -1,5 +1,5 @@
     /****************************************************************************
    - * net/iob/iob_copyout.c
    + * drivers/iob/iob_copyout.c
      *
      *   Copyright (C) 2014 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
    @@ -39,13 +39,6 @@
     
     #include 
     
    -#if defined(CONFIG_DEBUG_FEATURES) && defined(CONFIG_IOB_DEBUG)
    -/* Force debug output (from this file only) */
    -
    -#  undef  CONFIG_DEBUG_NET
    -#  define CONFIG_DEBUG_NET 1
    -#endif
    -
     #include 
     #include 
     #include 
    diff --git a/net/iob/iob_dump.c b/drivers/iob/iob_dump.c
    similarity index 97%
    rename from net/iob/iob_dump.c
    rename to drivers/iob/iob_dump.c
    index eea432d3c2..fce3f2f17e 100644
    --- a/net/iob/iob_dump.c
    +++ b/drivers/iob/iob_dump.c
    @@ -1,5 +1,5 @@
     /****************************************************************************
    - * net/iob/iob_dump.c
    + * drivers/iob/iob_dump.c
      *
      *   Copyright (C) 2014 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
    @@ -83,8 +83,8 @@ void iob_dump(FAR const char *msg, FAR struct iob_s *iob, unsigned int len,
     
       if (offset > head->io_pktlen)
         {
    -      nerr("ERROR: offset is past the end of data: %u > %u\n",
    -           offset, head->io_pktlen);
    +      ioberr("ERROR: offset is past the end of data: %u > %u\n",
    +             offset, head->io_pktlen);
           return;
         }
     
    diff --git a/net/iob/iob_free.c b/drivers/iob/iob_free.c
    similarity index 89%
    rename from net/iob/iob_free.c
    rename to drivers/iob/iob_free.c
    index 26e3df0cff..d2a67d9758 100644
    --- a/net/iob/iob_free.c
    +++ b/drivers/iob/iob_free.c
    @@ -1,7 +1,7 @@
     /****************************************************************************
    - * net/iob/iob_free.c
    + * drivers/iob/iob_free.c
      *
    - *   Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved.
    + *   Copyright (C) 2014, 2016-2017 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
      *
      * Redistribution and use in source and binary forms, with or without
    @@ -39,13 +39,6 @@
     
     #include 
     
    -#if defined(CONFIG_DEBUG_FEATURES) && defined(CONFIG_IOB_DEBUG)
    -/* Force debug output (from this file only) */
    -
    -#  undef  CONFIG_DEBUG_NET
    -#  define CONFIG_DEBUG_NET 1
    -#endif
    -
     #include 
     #include 
     #include 
    @@ -74,8 +67,8 @@ FAR struct iob_s *iob_free(FAR struct iob_s *iob)
       FAR struct iob_s *next = iob->io_flink;
       irqstate_t flags;
     
    -  ninfo("iob=%p io_pktlen=%u io_len=%u next=%p\n",
    -        iob, iob->io_pktlen, iob->io_len, next);
    +  iobinfo("iob=%p io_pktlen=%u io_len=%u next=%p\n",
    +          iob, iob->io_pktlen, iob->io_len, next);
     
       /* Copy the data that only exists in the head of a I/O buffer chain into
        * the next entry.
    @@ -104,8 +97,8 @@ FAR struct iob_s *iob_free(FAR struct iob_s *iob)
               DEBUGASSERT(next->io_len == 0 && next->io_flink == NULL);
             }
     
    -      ninfo("next=%p io_pktlen=%u io_len=%u\n",
    -            next, next->io_pktlen, next->io_len);
    +      iobinfo("next=%p io_pktlen=%u io_len=%u\n",
    +              next, next->io_pktlen, next->io_len);
         }
     
       /* Free the I/O buffer by adding it to the head of the free list. We don't
    diff --git a/net/iob/iob_free_chain.c b/drivers/iob/iob_free_chain.c
    similarity index 93%
    rename from net/iob/iob_free_chain.c
    rename to drivers/iob/iob_free_chain.c
    index c309fbdafe..75c69a3f13 100644
    --- a/net/iob/iob_free_chain.c
    +++ b/drivers/iob/iob_free_chain.c
    @@ -1,5 +1,5 @@
     /****************************************************************************
    - * net/iob/iob_free_chain.c
    + * drivers/iob/iob_free_chain.c
      *
      *   Copyright (C) 2014 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
    @@ -39,13 +39,6 @@
     
     #include 
     
    -#if defined(CONFIG_DEBUG_FEATURES) && defined(CONFIG_IOB_DEBUG)
    -/* Force debug output (from this file only) */
    -
    -#  undef  CONFIG_DEBUG_NET
    -#  define CONFIG_DEBUG_NET 1
    -#endif
    -
     #include 
     #include 
     
    diff --git a/net/iob/iob_free_qentry.c b/drivers/iob/iob_free_qentry.c
    similarity index 94%
    rename from net/iob/iob_free_qentry.c
    rename to drivers/iob/iob_free_qentry.c
    index 636b835b87..402d4e76ac 100644
    --- a/net/iob/iob_free_qentry.c
    +++ b/drivers/iob/iob_free_qentry.c
    @@ -1,5 +1,5 @@
     /****************************************************************************
    - * net/iob/iob_free_qentry.c
    + * drivers/iob/iob_free_qentry.c
      *
      *   Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
    @@ -39,13 +39,6 @@
     
     #include 
     
    -#if defined(CONFIG_DEBUG_FEATURES) && defined(CONFIG_IOB_DEBUG)
    -/* Force debug output (from this file only) */
    -
    -#  undef  CONFIG_DEBUG_NET
    -#  define CONFIG_DEBUG_NET 1
    -#endif
    -
     #include 
     #include 
     
    diff --git a/net/iob/iob_free_queue.c b/drivers/iob/iob_free_queue.c
    similarity index 94%
    rename from net/iob/iob_free_queue.c
    rename to drivers/iob/iob_free_queue.c
    index e559c819b9..953182b5c6 100644
    --- a/net/iob/iob_free_queue.c
    +++ b/drivers/iob/iob_free_queue.c
    @@ -1,5 +1,5 @@
     /****************************************************************************
    - * net/iob/iob_free_queue.c
    + * drivers/iob/iob_free_queue.c
      *
      *   Copyright (C) 2014 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
    @@ -39,13 +39,6 @@
     
     #include 
     
    -#if defined(CONFIG_DEBUG_FEATURES) && defined(CONFIG_IOB_DEBUG)
    -/* Force debug output (from this file only) */
    -
    -#  undef  CONFIG_DEBUG_NET
    -#  define CONFIG_DEBUG_NET 1
    -#endif
    -
     #include 
     
     #include 
    diff --git a/net/iob/iob_initialize.c b/drivers/iob/iob_initialize.c
    similarity index 95%
    rename from net/iob/iob_initialize.c
    rename to drivers/iob/iob_initialize.c
    index 03bb96b691..423f90898c 100644
    --- a/net/iob/iob_initialize.c
    +++ b/drivers/iob/iob_initialize.c
    @@ -1,5 +1,5 @@
     /****************************************************************************
    - * net/iob/iob_initialize.c
    + * drivers/iob/iob_initialize.c
      *
      *   Copyright (C) 2014 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
    @@ -39,13 +39,6 @@
     
     #include 
     
    -#if defined(CONFIG_DEBUG_FEATURES) && defined(CONFIG_IOB_DEBUG)
    -/* Force debug output (from this file only) */
    -
    -#  undef  CONFIG_DEBUG_NET
    -#  define CONFIG_DEBUG_NET 1
    -#endif
    -
     #include 
     #include 
     
    diff --git a/net/iob/iob_pack.c b/drivers/iob/iob_pack.c
    similarity index 95%
    rename from net/iob/iob_pack.c
    rename to drivers/iob/iob_pack.c
    index 7dc997dc2a..0a2b0f66c5 100644
    --- a/net/iob/iob_pack.c
    +++ b/drivers/iob/iob_pack.c
    @@ -1,5 +1,5 @@
     /****************************************************************************
    - * net/iob/iob_pack.c
    + * drivers/iob/iob_pack.c
      *
      *   Copyright (C) 2014 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
    @@ -39,13 +39,6 @@
     
     #include 
     
    -#if defined(CONFIG_DEBUG_FEATURES) && defined(CONFIG_IOB_DEBUG)
    -/* Force debug output (from this file only) */
    -
    -#  undef  CONFIG_DEBUG_NET
    -#  define CONFIG_DEBUG_NET 1
    -#endif
    -
     #include 
     
     #include 
    diff --git a/net/iob/iob_peek_queue.c b/drivers/iob/iob_peek_queue.c
    similarity index 94%
    rename from net/iob/iob_peek_queue.c
    rename to drivers/iob/iob_peek_queue.c
    index 64c9531184..7bc81bfa12 100644
    --- a/net/iob/iob_peek_queue.c
    +++ b/drivers/iob/iob_peek_queue.c
    @@ -1,5 +1,5 @@
     /****************************************************************************
    - * net/iob/iob_peek_queue.c
    + * drivers/iob/iob_peek_queue.c
      *
      *   Copyright (C) 2014 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
    @@ -39,13 +39,6 @@
     
     #include 
     
    -#if defined(CONFIG_DEBUG_FEATURES) && defined(CONFIG_IOB_DEBUG)
    -/* Force debug output (from this file only) */
    -
    -#  undef  CONFIG_DEBUG_NET
    -#  define CONFIG_DEBUG_NET 1
    -#endif
    -
     #include 
     
     #include 
    diff --git a/net/iob/iob_remove_queue.c b/drivers/iob/iob_remove_queue.c
    similarity index 94%
    rename from net/iob/iob_remove_queue.c
    rename to drivers/iob/iob_remove_queue.c
    index ab02b67a0c..4bfbca3056 100644
    --- a/net/iob/iob_remove_queue.c
    +++ b/drivers/iob/iob_remove_queue.c
    @@ -1,5 +1,5 @@
     /****************************************************************************
    - * net/iob/iob_remove_queue.c
    + * drivers/iob/iob_remove_queue.c
      *
      *   Copyright (C) 2014 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
    @@ -39,13 +39,6 @@
     
     #include 
     
    -#if defined(CONFIG_DEBUG_FEATURES) && defined(CONFIG_IOB_DEBUG)
    -/* Force debug output (from this file only) */
    -
    -#  undef  CONFIG_DEBUG_NET
    -#  define CONFIG_DEBUG_NET 1
    -#endif
    -
     #include 
     
     #include 
    diff --git a/net/iob/iob_test.c b/drivers/iob/iob_test.c
    similarity index 99%
    rename from net/iob/iob_test.c
    rename to drivers/iob/iob_test.c
    index 0e13fab793..ee6b90d886 100644
    --- a/net/iob/iob_test.c
    +++ b/drivers/iob/iob_test.c
    @@ -1,5 +1,5 @@
     /****************************************************************************
    - * net/iob/iob_test.c
    + * drivers/iob/iob_test.c
      * Unit test driver.  This is of historical interest only since it requires
      * and custom build setup and modifications to the iob source and header
      * files.
    diff --git a/net/iob/iob_trimhead.c b/drivers/iob/iob_trimhead.c
    similarity index 90%
    rename from net/iob/iob_trimhead.c
    rename to drivers/iob/iob_trimhead.c
    index a50ea9283b..938c040711 100644
    --- a/net/iob/iob_trimhead.c
    +++ b/drivers/iob/iob_trimhead.c
    @@ -1,7 +1,7 @@
     /****************************************************************************
    - * net/iob/iob_trimhead.c
    + * drivers/iob/iob_trimhead.c
      *
    - *   Copyright (C) 2014 Gregory Nutt. All rights reserved.
    + *   Copyright (C) 2014, 2017 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
      *
      * Redistribution and use in source and binary forms, with or without
    @@ -39,13 +39,6 @@
     
     #include 
     
    -#if defined(CONFIG_DEBUG_FEATURES) && defined(CONFIG_IOB_DEBUG)
    -/* Force debug output (from this file only) */
    -
    -#  undef  CONFIG_DEBUG_NET
    -#  define CONFIG_DEBUG_NET 1
    -#endif
    -
     #include 
     #include 
     
    @@ -78,7 +71,7 @@ FAR struct iob_s *iob_trimhead(FAR struct iob_s *iob, unsigned int trimlen)
     {
       uint16_t pktlen;
     
    -  ninfo("iob=%p trimlen=%d\n", iob, trimlen);
    +  iobinfo("iob=%p trimlen=%d\n", iob, trimlen);
     
       if (iob && trimlen > 0)
         {
    @@ -89,8 +82,8 @@ FAR struct iob_s *iob_trimhead(FAR struct iob_s *iob, unsigned int trimlen)
             {
               /* Do we trim this entire I/O buffer away? */
     
    -          ninfo("iob=%p io_len=%d pktlen=%d trimlen=%d\n",
    -                iob, iob->io_len, pktlen, trimlen);
    +          iobinfo("iob=%p io_len=%d pktlen=%d trimlen=%d\n",
    +                  iob, iob->io_len, pktlen, trimlen);
     
               if (iob->io_len <= trimlen)
                 {
    @@ -120,7 +113,7 @@ FAR struct iob_s *iob_trimhead(FAR struct iob_s *iob, unsigned int trimlen)
     
                   /* Free this entry and set the next I/O buffer as the head */
     
    -              ninfo("iob=%p: Freeing\n", iob);
    +              iobinfo("iob=%p: Freeing\n", iob);
                   (void)iob_free(iob);
                   iob = next;
                 }
    diff --git a/net/iob/iob_trimhead_queue.c b/drivers/iob/iob_trimhead_queue.c
    similarity index 94%
    rename from net/iob/iob_trimhead_queue.c
    rename to drivers/iob/iob_trimhead_queue.c
    index 57a1f9637e..7ba393366f 100644
    --- a/net/iob/iob_trimhead_queue.c
    +++ b/drivers/iob/iob_trimhead_queue.c
    @@ -1,5 +1,5 @@
     /****************************************************************************
    - * net/iob/iob_trimhead_queue.c
    + * drivers/iob/iob_trimhead_queue.c
      *
      *   Copyright (C) 2014 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
    @@ -39,13 +39,6 @@
     
     #include 
     
    -#if defined(CONFIG_DEBUG_FEATURES) && defined(CONFIG_IOB_DEBUG)
    -/* Force debug output (from this file only) */
    -
    -#  undef  CONFIG_DEBUG_NET
    -#  define CONFIG_DEBUG_NET 1
    -#endif
    -
     #include 
     #include 
     
    diff --git a/net/iob/iob_trimtail.c b/drivers/iob/iob_trimtail.c
    similarity index 91%
    rename from net/iob/iob_trimtail.c
    rename to drivers/iob/iob_trimtail.c
    index 2d297d8547..b876de1552 100644
    --- a/net/iob/iob_trimtail.c
    +++ b/drivers/iob/iob_trimtail.c
    @@ -1,7 +1,7 @@
     /****************************************************************************
    - * net/iob/iob_trimtail.c
    + * drivers/iob/iob_trimtail.c
      *
    - *   Copyright (C) 2014 Gregory Nutt. All rights reserved.
    + *   Copyright (C) 2014, 2017 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
      *
      * Redistribution and use in source and binary forms, with or without
    @@ -39,13 +39,6 @@
     
     #include 
     
    -#if defined(CONFIG_DEBUG_FEATURES) && defined(CONFIG_IOB_DEBUG)
    -/* Force debug output (from this file only) */
    -
    -#  undef  CONFIG_DEBUG_NET
    -#  define CONFIG_DEBUG_NET 1
    -#endif
    -
     #include 
     #include 
     
    @@ -72,7 +65,7 @@ FAR struct iob_s *iob_trimtail(FAR struct iob_s *iob, unsigned int trimlen)
       FAR struct iob_s *last;
       int len;
     
    -  ninfo("iob=%p pktlen=%d trimlen=%d\n", iob, iob->io_pktlen, trimlen);
    +  iobinfo("iob=%p pktlen=%d trimlen=%d\n", iob, iob->io_pktlen, trimlen);
     
       if (iob && trimlen > 0)
         {
    @@ -101,7 +94,7 @@ FAR struct iob_s *iob_trimtail(FAR struct iob_s *iob, unsigned int trimlen)
                * I/O buffer away?
                */
     
    -          ninfo("iob=%p len=%d vs %d\n", last, last->io_len, len);
    +          iobinfo("iob=%p len=%d vs %d\n", last, last->io_len, len);
               if (last->io_len <= len)
                 {
                   /* Yes.. Consume the entire buffer */
    diff --git a/include/nuttx/drivers/iob.h b/include/nuttx/drivers/iob.h
    index 52f848db30..d6ce3c3025 100644
    --- a/include/nuttx/drivers/iob.h
    +++ b/include/nuttx/drivers/iob.h
    @@ -176,6 +176,17 @@ void iob_initialize(void);
     
     FAR struct iob_s *iob_alloc(bool throttled);
     
    +/****************************************************************************
    + * Name: iob_tryalloc
    + *
    + * Description:
    + *   Try to allocate an I/O buffer by taking the buffer at the head of the
    + *   free list without waiting for a buffer to become free.
    + *
    + ****************************************************************************/
    +
    +FAR struct iob_s *iob_tryalloc(bool throttled);
    +
     /****************************************************************************
      * Name: iob_free
      *
    diff --git a/net/Kconfig b/net/Kconfig
    index da5eab15d2..313f7a05f8 100644
    --- a/net/Kconfig
    +++ b/net/Kconfig
    @@ -295,7 +295,6 @@ source "net/icmpv6/Kconfig"
     source "net/igmp/Kconfig"
     source "net/arp/Kconfig"
     source "net/loopback/Kconfig"
    -source "net/iob/Kconfig"
     source "net/procfs/Kconfig"
     source "net/usrsock/Kconfig"
     source "net/utils/Kconfig"
    diff --git a/net/Makefile b/net/Makefile
    index cd6979a414..25105b0c22 100644
    --- a/net/Makefile
    +++ b/net/Makefile
    @@ -57,7 +57,6 @@ DEPPATH = --dep-path .
     
     include socket/Make.defs
     include netdev/Make.defs
    -include iob/Make.defs
     include arp/Make.defs
     include icmp/Make.defs
     include icmpv6/Make.defs
    diff --git a/net/README.txt b/net/README.txt
    index e87a0889b5..beda522959 100644
    --- a/net/README.txt
    +++ b/net/README.txt
    @@ -12,7 +12,6 @@ Directory Structure
            +- devif    - Stack/device interface layer
            +- icmp     - Internet Control Message Protocol (IPv4)
            +- icmpv6   - Internet Control Message Protocol (IPv6)
    -       +- iob      - I/O buffering logic
            +- local    - Unix domain (local) sockets
            +- loopback - Local loopback
            +- neighbor - Neighbor Discovery Protocol (IPv6)
    @@ -43,4 +42,4 @@ Directory Structure
         +----------------------------------------------------------------+                      +-----+
         +----------------------------------------------------------------+ +--------------------------+
         |                    Networking Hardware                         | |  Hardware TCP/IP Stack   |
    -    +----------------------------------------------------------------+ +--------------------------+
    \ No newline at end of file
    +    +----------------------------------------------------------------+ +--------------------------+
    diff --git a/net/net_initialize.c b/net/net_initialize.c
    index d792f77a83..c37a69c73a 100644
    --- a/net/net_initialize.c
    +++ b/net/net_initialize.c
    @@ -42,7 +42,6 @@
     
     #include 
     
    -#include 
     #include 
     
     #include "socket/socket.h"
    @@ -109,12 +108,6 @@ void net_setup(void)
     #endif
     #endif /* CONFIG_NET_IPv6 */
     
    -#ifdef CONFIG_DRIVERS_IOB
    -  /* Initialize I/O buffering */
    -
    -  iob_initialize();
    -#endif
    -
       /* Initialize the device interface layer */
     
       devif_initialize();
    diff --git a/net/tcp/tcp_callback.c b/net/tcp/tcp_callback.c
    index 2ed5476d4f..0feb41e68a 100644
    --- a/net/tcp/tcp_callback.c
    +++ b/net/tcp/tcp_callback.c
    @@ -45,12 +45,12 @@
     #include 
     #include 
     
    +#include 
     #include 
     #include 
     #include 
     
     #include "devif/devif.h"
    -#include "iob/iob.h"
     #include "tcp/tcp.h"
     
     /****************************************************************************
    diff --git a/net/udp/udp_callback.c b/net/udp/udp_callback.c
    index 74c0527fae..52caaea543 100644
    --- a/net/udp/udp_callback.c
    +++ b/net/udp/udp_callback.c
    @@ -50,7 +50,6 @@
     #include 
     
     #include "devif/devif.h"
    -#include "iob/iob.h"
     #include "udp/udp.h"
     
     /****************************************************************************
    diff --git a/net/udp/udp_conn.c b/net/udp/udp_conn.c
    index 964846e91d..077a840566 100644
    --- a/net/udp/udp_conn.c
    +++ b/net/udp/udp_conn.c
    @@ -62,7 +62,6 @@
     
     #include "devif/devif.h"
     #include "netdev/netdev.h"
    -#include "iob/iob.h"
     #include "udp/udp.h"
     
     /****************************************************************************
    -- 
    GitLab
    
    
    From 356e71850bf404ac0258dcc336b1dd745ea6568b Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Thu, 20 Apr 2017 16:18:57 -0600
    Subject: [PATCH 537/990] IOB: A file needed to include iob.h
    
    ---
     drivers/iob/iob_dump.c | 2 ++
     1 file changed, 2 insertions(+)
    
    diff --git a/drivers/iob/iob_dump.c b/drivers/iob/iob_dump.c
    index fce3f2f17e..470ba740ac 100644
    --- a/drivers/iob/iob_dump.c
    +++ b/drivers/iob/iob_dump.c
    @@ -44,6 +44,8 @@
     
     #include 
     
    +#include "iob.h"
    +
     #ifdef CONFIG_DEBUG_FEATURES
     
     /****************************************************************************
    -- 
    GitLab
    
    
    From 7457875447244037018be8a41f1a368007dcd625 Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Thu, 20 Apr 2017 19:15:17 -0600
    Subject: [PATCH 538/990] VFS poll(): Add some error handling logic
    
    ---
     fs/vfs/fs_select.c | 23 ++++++++++++++---------
     1 file changed, 14 insertions(+), 9 deletions(-)
    
    diff --git a/fs/vfs/fs_select.c b/fs/vfs/fs_select.c
    index acb42b35ae..b3ba38bf42 100644
    --- a/fs/vfs/fs_select.c
    +++ b/fs/vfs/fs_select.c
    @@ -133,14 +133,19 @@ int select(int nfds, FAR fd_set *readfds, FAR fd_set *writefds,
             }
         }
     
    +  if (npfds <= 0)
    +    {
    +      errcode = EINVAL;
    +      goto errout;
    +    }
    +
       /* Allocate the descriptor list for poll() */
     
       pollset = (struct pollfd *)kmm_zalloc(npfds * sizeof(struct pollfd));
       if (!pollset)
         {
    -      set_errno(ENOMEM);
    -      leave_cancellation_point();
    -      return ERROR;
    +      errcode = ENOMEM;
    +      goto errout;
         }
     
       /* Initialize the descriptor list for poll() */
    @@ -279,16 +284,16 @@ int select(int nfds, FAR fd_set *readfds, FAR fd_set *writefds,
     
       /* Did poll() fail above? */
     
    -  if (ret < 0)
    +  if (ret >= 0)
         {
    -      /* Yes.. restore the errno value */
    -
    -      set_errno(errcode);
    +      leave_cancellation_point();
    +      return ret;
         }
     
    +errout:
    +  set_errno(errcode);
       leave_cancellation_point();
    -  return ret;
    +  return ERROR;
     }
     
     #endif /* CONFIG_DISABLE_POLL */
    -
    -- 
    GitLab
    
    
    From c04c49dac0fef9ccb37ead2bf1c79fc8d4922c74 Mon Sep 17 00:00:00 2001
    From: "Juha Niskanen (Haltian)" 
    Date: Fri, 21 Apr 2017 08:23:25 -0600
    Subject: [PATCH 539/990] Add support for the STM32F09X family.
    
    ---
     arch/arm/include/stm32f0/chip.h               |  85 +++-
     ...orymap.h => stm32f05xf07xf09x_memorymap.h} |   8 +-
     arch/arm/src/stm32f0/chip/stm32f09x_pinmap.h  | 430 ++++++++++++++++++
     arch/arm/src/stm32f0/chip/stm32f0_memorymap.h |   5 +-
     arch/arm/src/stm32f0/chip/stm32f0_pinmap.h    |   2 +
     configs/nucleo-f072rb/README.txt              |  14 +-
     6 files changed, 525 insertions(+), 19 deletions(-)
     rename arch/arm/src/stm32f0/chip/{stm32f05xf07x_memorymap.h => stm32f05xf07xf09x_memorymap.h} (97%)
     create mode 100644 arch/arm/src/stm32f0/chip/stm32f09x_pinmap.h
    
    diff --git a/arch/arm/include/stm32f0/chip.h b/arch/arm/include/stm32f0/chip.h
    index a50902d462..196a15e221 100644
    --- a/arch/arm/include/stm32f0/chip.h
    +++ b/arch/arm/include/stm32f0/chip.h
    @@ -52,6 +52,7 @@
     #if defined(CONFIG_ARCH_CHIP_STM32F051R8)
     #  define STM32F051x              1  /* STM32F051x family */
     #  undef  STM32F072x                 /* Not STM32F072x family */
    +#  undef  STM32F091x                 /* Not STM32F091x family */
     
     #  define STM32F0_FLASH_SIZE      (64*1024) /* 64Kb */
     #  define STM32F0_SRAM_SIZE       (8*1024)  /*  8Kb */
    @@ -71,6 +72,7 @@
     #elif defined(CONFIG_ARCH_CHIP_STM32F072C8) || defined(CONFIG_ARCH_CHIP_STM32F072CB)
     #  undef  STM32F051x                 /* Not STM32F051x family */
     #  define STM32F072x              1  /* STM32F072x family */
    +#  undef  STM32F091x                 /* Not STM32F091x family */
     
     #  ifdef CONFIG_ARCH_CHIP_STM32F072C8
     #    define STM32F0_FLASH_SIZE    (64*1024)  /*  64Kb */
    @@ -90,9 +92,9 @@
     #  define STM32F0_NCAN            1  /* One CAN controller */
     #  define STM32F0_NUSBDEV         1  /* One USB device controller */
     #  define STM32F0_NCEC            1  /* One HDMI-CEC controller */
    -#  define STM32F0_NADC16          1  /* One 16-bit module */
    +#  define STM32F0_NADC12          1  /* One 12-bit module */
     #  define STM32F0_NADCCHAN        10 /* Ten external channels */
    -#  define STM32F0_NADCEXT         3  /* Three external channels */
    +#  define STM32F0_NADCINT         3  /* Three internal channels */
     #  define STM32F0_NDAC            1  /* One DAC module */
     #  define STM32F0_NDACCHAN        2  /* Two DAC channels */
     #  define STM32F0_NCOMP           2  /* Two Analog Comparators */
    @@ -102,6 +104,7 @@
     #elif defined(CONFIG_ARCH_CHIP_STM32F072R8) || defined(CONFIG_ARCH_CHIP_STM32F072RB)
     #  undef  STM32F051x                 /* Not STM32F051x family */
     #  define STM32F072x              1  /* STM32F072x family */
    +#  undef  STM32F091x                 /* Not STM32F091x family */
     
     #  ifdef CONFIG_ARCH_CHIP_STM32F072R8
     #    define STM32F0_FLASH_SIZE    (64*1024)  /*  64Kb */
    @@ -121,9 +124,9 @@
     #  define STM32F0_NCAN            1  /* One CAN controller */
     #  define STM32F0_NUSBDEV         1  /* One USB device controller */
     #  define STM32F0_NCEC            1  /* One HDMI-CEC controller */
    -#  define STM32F0_NADC16          1  /* One 16-bit module */
    +#  define STM32F0_NADC12          1  /* One 12-bit module */
     #  define STM32F0_NADCCHAN        16 /* 16 external channels */
    -#  define STM32F0_NADCEXT         3  /* Three external channels */
    +#  define STM32F0_NADCINT         3  /* Three internal channels */
     #  define STM32F0_NDAC            1  /* One DAC module */
     #  define STM32F0_NDACCHAN        2  /* Two DAC channels */
     #  define STM32F0_NCOMP           2  /* Two Analog Comparators */
    @@ -133,6 +136,7 @@
     #elif defined(CONFIG_ARCH_CHIP_STM32F072V8) || defined(CONFIG_ARCH_CHIP_STM32F072VB)
     #  undef  STM32F051x                 /* Not STM32F051x family */
     #  define STM32F072x              1  /* STM32F072x family */
    +#  undef  STM32F091x                 /* Not STM32F091x family */
     
     #  ifdef CONFIG_ARCH_CHIP_STM32F072V8
     #    define STM32F0_FLASH_SIZE    (64*1024)  /*  64Kb */
    @@ -152,15 +156,84 @@
     #  define STM32F0_NCAN            1  /* One CAN controller */
     #  define STM32F0_NUSBDEV         1  /* One USB device controller */
     #  define STM32F0_NCEC            1  /* One HDMI-CEC controller */
    -#  define STM32F0_NADC16          1  /* One 16-bit module */
    +#  define STM32F0_NADC12          1  /* One 12-bit module */
     #  define STM32F0_NADCCHAN        16 /* 16 external channels */
    -#  define STM32F0_NADCEXT         3  /* Three external channels */
    +#  define STM32F0_NADCINT         3  /* Three internal channels */
     #  define STM32F0_NDAC            1  /* One DAC module */
     #  define STM32F0_NDACCHAN        2  /* Two DAC channels */
     #  define STM32F0_NCOMP           2  /* Two Analog Comparators */
     #  define STM32F0_NCAP            24 /* Capacitive sensing channels */
     #  define STM32F0_NPORTS          6  /* Six GPIO ports, GPIOA-F */
     
    +#elif defined(CONFIG_ARCH_CHIP_STM32F091CB) || defined(CONFIG_ARCH_CHIP_STM32F091CC)
    +#  undef  STM32F051x                 /* Not STM32F051x family */
    +#  undef  STM32F072x                 /* Not STM32F072x family */
    +#  define STM32F091x              1  /* STM32F091x family */
    +
    +#  ifdef CONFIG_ARCH_CHIP_STM32F091CB
    +#    define STM32F0_FLASH_SIZE    (128*1024) /* 128Kb */
    +#  else
    +#    define STM32F0_FLASH_SIZE    (256*1024) /* 256Kb */
    +#  endif
    +#  define STM32F0_SRAM_SIZE       (32*1024)  /*  32Kb */
    +
    +#  define STM32F0_NATIM           1  /* One advanced timer TIM1 */
    +#  define STM32F0_NGTIM16         5  /* 16-bit general up/down timers TIM3, TIM14-17 */
    +#  define STM32F0_NGTIM32         1  /* 32-bit general up/down timers TIM2 */
    +#  define STM32F0_NBTIM           2  /* 2 basic timers: TIM6, TIM7 */
    +#  define STM32F0_NSPI            2  /* Two SPI modules (SPI or I2S) */
    +#  define STM32F0_NI2S            2  /* Two I2S modules (SPI or I2S) */
    +#  define STM32F0_NI2C            2  /* Two I2C modules */
    +#  define STM32F0_NUSART          6  /* Six USARTs modules */
    +#  define STM32F0_NCAN            1  /* One CAN controller */
    +#  define STM32F0_NUSBDEV         0  /* No USB device controller */
    +#  define STM32F0_NCEC            1  /* One HDMI-CEC controller */
    +#  define STM32F0_NADC12          1  /* One 12-bit module */
    +#  define STM32F0_NADCCHAN        10 /* 10 external channels */
    +#  define STM32F0_NADCINT         3  /* Three internal channels */
    +#  define STM32F0_NDAC            1  /* One DAC module */
    +#  define STM32F0_NDACCHAN        2  /* Two DAC channels */
    +#  define STM32F0_NCOMP           2  /* Two Analog Comparators */
    +#  define STM32F0_NCAP            17 /* Capacitive sensing channels */
    +#  define STM32F0_NPORTS          6  /* Six GPIO ports, GPIOA-F */
    +
    +#elif defined(CONFIG_ARCH_CHIP_STM32F091RB) || defined(CONFIG_ARCH_CHIP_STM32F091RC) \
    +   || defined(CONFIG_ARCH_CHIP_STM32F091VB) || defined(CONFIG_ARCH_CHIP_STM32F091VC)
    +#  undef  STM32F051x                 /* Not STM32F051x family */
    +#  undef  STM32F072x                 /* Not STM32F072x family */
    +#  define STM32F091x              1  /* STM32F091x family */
    +
    +#  if defined(CONFIG_ARCH_CHIP_STM32F091RB) || defined(CONFIG_ARCH_CHIP_STM32F091VB)
    +#    define STM32F0_FLASH_SIZE    (128*1024) /* 128Kb */
    +#  else
    +#    define STM32F0_FLASH_SIZE    (256*1024) /* 256Kb */
    +#  endif
    +#  define STM32F0_SRAM_SIZE       (32*1024)  /*  32Kb */
    +
    +#  define STM32F0_NATIM           1  /* One advanced timer TIM1 */
    +#  define STM32F0_NGTIM16         5  /* 16-bit general up/down timers TIM3, TIM14-17 */
    +#  define STM32F0_NGTIM32         1  /* 32-bit general up/down timers TIM2 */
    +#  define STM32F0_NBTIM           2  /* 2 basic timers: TIM6, TIM7 */
    +#  define STM32F0_NSPI            2  /* Two SPI modules (SPI or I2S) */
    +#  define STM32F0_NI2S            2  /* Two I2S modules (SPI or I2S) */
    +#  define STM32F0_NI2C            2  /* Two I2C modules */
    +#  define STM32F0_NUSART          8  /* Eight USARTs modules */
    +#  define STM32F0_NCAN            1  /* One CAN controller */
    +#  define STM32F0_NUSBDEV         0  /* No USB device controller */
    +#  define STM32F0_NCEC            1  /* One HDMI-CEC controller */
    +#  define STM32F0_NADC12          1  /* One 12-bit module */
    +#  define STM32F0_NADCCHAN        16 /* 16 external channels */
    +#  define STM32F0_NADCINT         3  /* Three internal channels */
    +#  define STM32F0_NDAC            1  /* One DAC module */
    +#  define STM32F0_NDACCHAN        2  /* Two DAC channels */
    +#  define STM32F0_NCOMP           2  /* Two Analog Comparators */
    +#  if defined(CONFIG_ARCH_CHIP_STM32F091VB) || defined(CONFIG_ARCH_CHIP_STM32F091VC)
    +#    define STM32F0_NCAP          24 /* Capacitive sensing channels */
    +#  else
    +#    define STM32F0_NCAP          18 /* Capacitive sensing channels */
    +#  endif
    +#  define STM32F0_NPORTS          6  /* Six GPIO ports, GPIOA-F */
    +
     #else
     #  error "Unsupported STM32F0xx chip"
     #endif
    diff --git a/arch/arm/src/stm32f0/chip/stm32f05xf07x_memorymap.h b/arch/arm/src/stm32f0/chip/stm32f05xf07xf09x_memorymap.h
    similarity index 97%
    rename from arch/arm/src/stm32f0/chip/stm32f05xf07x_memorymap.h
    rename to arch/arm/src/stm32f0/chip/stm32f05xf07xf09x_memorymap.h
    index 178773b087..84bb978aaf 100644
    --- a/arch/arm/src/stm32f0/chip/stm32f05xf07x_memorymap.h
    +++ b/arch/arm/src/stm32f0/chip/stm32f05xf07xf09x_memorymap.h
    @@ -1,5 +1,5 @@
     /************************************************************************************
    - * arch/arm/src/stm32f0/chip/stm32f05xf07x_memorymap.h
    + * arch/arm/src/stm32f0/chip/stm32f05xf07xf09x_memorymap.h
      *
      *   Copyright (C) 2017 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
    @@ -34,8 +34,8 @@
      *
      ************************************************************************************/
     
    -#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_ST32F05XF07X_MEMORYMAP_H
    -#define __ARCH_ARM_SRC_STM32F0_CHIP_ST32F05XF07X_MEMORYMAP_H
    +#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_ST32F05XF07XF09X_MEMORYMAP_H
    +#define __ARCH_ARM_SRC_STM32F0_CHIP_ST32F05XF07XF09X_MEMORYMAP_H
     
     /************************************************************************************
      * Pre-processor Definitions
    @@ -154,4 +154,4 @@
     #define STM32F0_SCS_BASE      0xe000e000
     #define STM32F0_DEBUGMCU_BASE 0xe0042000
     
    -#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_ST32F05XF07X_MEMORYMAP_H */
    +#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_ST32F05XF07XF09X_MEMORYMAP_H */
    diff --git a/arch/arm/src/stm32f0/chip/stm32f09x_pinmap.h b/arch/arm/src/stm32f0/chip/stm32f09x_pinmap.h
    new file mode 100644
    index 0000000000..b144846d95
    --- /dev/null
    +++ b/arch/arm/src/stm32f0/chip/stm32f09x_pinmap.h
    @@ -0,0 +1,430 @@
    +/************************************************************************************
    + * arch/arm/src/stm32f0/chip/stm32f09x_pinmap.h
    + *
    + *   Copyright (C) 2017 Gregory Nutt. All rights reserved.
    + *   Author: Gregory Nutt 
    + *           Alan Carvalho de Assis 
    + *
    + * 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 __ARCH_ARM_SRC_STM32F0_CHIP_STM32F09X_PINMAP_H
    +#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F09X_PINMAP_H
    +
    +/************************************************************************************
    + * Included Files
    + ************************************************************************************/
    +
    +#include 
    +
    +#include "stm32f0_gpio.h"
    +
    +/************************************************************************************
    + * Pre-processor Definitions
    + ************************************************************************************/
    +/* Alternate Pin Functions.
    + *
    + * Alternative pin selections are provided with a numeric suffix like _1, _2, etc.
    + * Drivers, however, will use the pin selection without the numeric suffix.
    + * Additional definitions are required in the board.h file.  For example, if
    + * CAN1_RX connects vis PD0 on some board, then the following definition should
    + * appear inthe board.h header file for that board:
    + *
    + * #define GPIO_CAN1_RX GPIO_CAN1_RX_1
    + *
    + * The driver will then automatically configre PD0 as the CAN1 RX pin.
    + */
    +
    +/* WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!!
    + * Additional effort is required to select specific GPIO options such as frequency,
    + * open-drain/push-pull, and pull-up/down!  Just the basics are defined for most
    + * pins in this file.
    + */
    +
    +/* ADC */
    +
    +#define GPIO_ADC_IN0             (GPIO_ANALOG | GPIO_PORTA | GPIO_PIN0)
    +#define GPIO_ADC_IN1             (GPIO_ANALOG | GPIO_PORTA | GPIO_PIN1)
    +#define GPIO_ADC_IN2             (GPIO_ANALOG | GPIO_PORTA | GPIO_PIN2)
    +#define GPIO_ADC_IN3             (GPIO_ANALOG | GPIO_PORTA | GPIO_PIN3)
    +#define GPIO_ADC_IN4             (GPIO_ANALOG | GPIO_PORTA | GPIO_PIN4)
    +#define GPIO_ADC_IN5             (GPIO_ANALOG | GPIO_PORTA | GPIO_PIN5)
    +#define GPIO_ADC_IN6             (GPIO_ANALOG | GPIO_PORTA | GPIO_PIN6)
    +#define GPIO_ADC_IN7             (GPIO_ANALOG | GPIO_PORTA | GPIO_PIN7)
    +#define GPIO_ADC_IN8             (GPIO_ANALOG | GPIO_PORTB | GPIO_PIN0)
    +#define GPIO_ADC_IN9             (GPIO_ANALOG | GPIO_PORTB | GPIO_PIN1)
    +#define GPIO_ADC_IN10            (GPIO_ANALOG | GPIO_PORTC | GPIO_PIN0)
    +#define GPIO_ADC_IN11            (GPIO_ANALOG | GPIO_PORTC | GPIO_PIN1)
    +#define GPIO_ADC_IN12            (GPIO_ANALOG | GPIO_PORTC | GPIO_PIN2)
    +#define GPIO_ADC_IN13            (GPIO_ANALOG | GPIO_PORTC | GPIO_PIN3)
    +#define GPIO_ADC_IN14            (GPIO_ANALOG | GPIO_PORTC | GPIO_PIN4)
    +#define GPIO_ADC_IN15            (GPIO_ANALOG | GPIO_PORTC | GPIO_PIN5)
    +
    +/* CAN */
    +
    +#define GPIO_CAN_RX_1            (GPIO_ALT | GPIO_AF0 | GPIO_PORTD | GPIO_PIN0)
    +#define GPIO_CAN_RX_2            (GPIO_ALT | GPIO_AF4 | GPIO_PORTA | GPIO_PIN11)
    +#define GPIO_CAN_RX_3            (GPIO_ALT | GPIO_AF4 | GPIO_PORTB | GPIO_PIN8)
    +#define GPIO_CAN_TX_1            (GPIO_ALT | GPIO_AF0 | GPIO_PORTD | GPIO_PIN1)
    +#define GPIO_CAN_TX_3            (GPIO_ALT | GPIO_AF4 | GPIO_PORTA | GPIO_PIN12)
    +#define GPIO_CAN_TX_4            (GPIO_ALT | GPIO_AF4 | GPIO_PORTB | GPIO_PIN9)
    +
    +/* HDMI-CEC */
    +
    +#define GPIO_CEC_1               (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN10)
    +#define GPIO_CEC_2               (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN8)
    +#define GPIO_CEC_3               (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN5)
    +
    +/* Analog Comparators */
    +
    +#define GPIO_COMP1_OUT_1         (GPIO_ALT | GPIO_AF7 | GPIO_PORTA | GPIO_PIN0)
    +#define GPIO_COMP1_OUT_2         (GPIO_ALT | GPIO_AF7 | GPIO_PORTA | GPIO_PIN11)
    +#define GPIO_COMP1_OUT_3         (GPIO_ALT | GPIO_AF7 | GPIO_PORTA | GPIO_PIN6)
    +
    +#define GPIO_COMP2_OUT_1         (GPIO_ALT | GPIO_AF7 | GPIO_PORTA | GPIO_PIN12)
    +#define GPIO_COMP2_OUT_2         (GPIO_ALT | GPIO_AF7 | GPIO_PORTA | GPIO_PIN2)
    +#define GPIO_COMP2_OUT_3         (GPIO_ALT | GPIO_AF7 | GPIO_PORTA | GPIO_PIN7)
    +
    +/* CRS */
    +
    +#define GPIO_CRS_SYNC_1          (GPIO_ALT | GPIO_AF0 | GPIO_PORTD | GPIO_PIN15)
    +#define GPIO_CRS_SYNC_2          (GPIO_ALT | GPIO_AF0 | GPIO_PORTF | GPIO_PIN0)
    +#define GPIO_CRS_SYNC_3          (GPIO_ALT | GPIO_AF4 | GPIO_PORTA | GPIO_PIN8)
    +
    +/* Events */
    +
    +#define GPIO_EVENTOUT_1          (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN1)
    +#define GPIO_EVENTOUT_2          (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN11)
    +#define GPIO_EVENTOUT_3          (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN12)
    +#define GPIO_EVENTOUT_4          (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN0)
    +#define GPIO_EVENTOUT_5          (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN11)
    +#define GPIO_EVENTOUT_6          (GPIO_ALT | GPIO_AF0 | GPIO_PORTC | GPIO_PIN0)
    +#define GPIO_EVENTOUT_7          (GPIO_ALT | GPIO_AF0 | GPIO_PORTC | GPIO_PIN1)
    +#define GPIO_EVENTOUT_8          (GPIO_ALT | GPIO_AF0 | GPIO_PORTC | GPIO_PIN2)
    +#define GPIO_EVENTOUT_9          (GPIO_ALT | GPIO_AF0 | GPIO_PORTC | GPIO_PIN3)
    +#define GPIO_EVENTOUT_10         (GPIO_ALT | GPIO_AF0 | GPIO_PORTC | GPIO_PIN4)
    +#define GPIO_EVENTOUT_11         (GPIO_ALT | GPIO_AF0 | GPIO_PORTF | GPIO_PIN2)
    +#define GPIO_EVENTOUT_12         (GPIO_ALT | GPIO_AF0 | GPIO_PORTF | GPIO_PIN3)
    +#define GPIO_EVENTOUT_13         (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN12)
    +#define GPIO_EVENTOUT_14         (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN3)
    +#define GPIO_EVENTOUT_15         (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN0)
    +#define GPIO_EVENTOUT_16         (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN1)
    +#define GPIO_EVENTOUT_17         (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN4)
    +#define GPIO_EVENTOUT_18         (GPIO_ALT | GPIO_AF3 | GPIO_PORTA | GPIO_PIN15)
    +#define GPIO_EVENTOUT_19         (GPIO_ALT | GPIO_AF3 | GPIO_PORTA | GPIO_PIN8)
    +#define GPIO_EVENTOUT_20         (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN9)
    +#define GPIO_EVENTOUT_21         (GPIO_ALT | GPIO_AF6 | GPIO_PORTA | GPIO_PIN6)
    +#define GPIO_EVENTOUT_22         (GPIO_ALT | GPIO_AF6 | GPIO_PORTA | GPIO_PIN7)
    +
    +/* I2C */
    +
    +#define GPIO_I2C1_SCL_1          (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN6)
    +#define GPIO_I2C1_SCL_2          (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN8)
    +#define GPIO_I2C1_SDA_1          (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN7)
    +#define GPIO_I2C1_SDA_2          (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN9)
    +#define GPIO_I2C1_SMBA           (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN5)
    +
    +#define GPIO_I2C2_SCL_1          (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN10)
    +#define GPIO_I2C2_SCL_2          (GPIO_ALT | GPIO_AF5 | GPIO_PORTB | GPIO_PIN13)
    +#define GPIO_I2C2_SDA_1          (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN11)
    +#define GPIO_I2C2_SDA_2          (GPIO_ALT | GPIO_AF5 | GPIO_PORTB | GPIO_PIN14)
    +
    +/* I2S */
    +
    +#define GPIO_I2S1_CK_1           (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN5)
    +#define GPIO_I2S1_CK_2           (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN3)
    +#define GPIO_I2S1_CK_3           (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN13)
    +#define GPIO_I2S1_MCK_1          (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN6)
    +#define GPIO_I2S1_MCK_2          (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN4)
    +#define GPIO_I2S1_MCK_3          (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN14)
    +#define GPIO_I2S1_SD_1           (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN7)
    +#define GPIO_I2S1_SD_2           (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN5)
    +#define GPIO_I2S1_SD_3           (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN15)
    +#define GPIO_I2S1_WS_1           (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN15)
    +#define GPIO_I2S1_WS_2           (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN4)
    +#define GPIO_I2S1_WS_3           (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN12)
    +
    +#define GPIO_I2S2_CK_1           (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN13)
    +#define GPIO_I2S2_CK_2           (GPIO_ALT | GPIO_AF1 | GPIO_PORTD | GPIO_PIN1)
    +#define GPIO_I2S2_CK_3           (GPIO_ALT | GPIO_AF5 | GPIO_PORTB | GPIO_PIN10)
    +#define GPIO_I2S2_MCK_1          (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN14)
    +#define GPIO_I2S2_MCK_2          (GPIO_ALT | GPIO_AF1 | GPIO_PORTC | GPIO_PIN2)
    +#define GPIO_I2S2_MCK_3          (GPIO_ALT | GPIO_AF1 | GPIO_PORTD | GPIO_PIN3)
    +#define GPIO_I2S2_SD_1           (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN15)
    +#define GPIO_I2S2_SD_2           (GPIO_ALT | GPIO_AF1 | GPIO_PORTC | GPIO_PIN3)
    +#define GPIO_I2S2_SD_3           (GPIO_ALT | GPIO_AF1 | GPIO_PORTD | GPIO_PIN4)
    +#define GPIO_I2S2_WS_1           (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN12)
    +#define GPIO_I2S2_WS_2           (GPIO_ALT | GPIO_AF1 | GPIO_PORTD | GPIO_PIN0)
    +#define GPIO_I2S2_WS_3           (GPIO_ALT | GPIO_AF5 | GPIO_PORTB | GPIO_PIN9)
    +
    +/* IR */
    +
    +#define GPIO_IR_OUT_1            (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN9)
    +#define GPIO_IR_OUT_2            (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN13)
    +
    +/* Clock output */
    +
    +#define GPIO_MCO                 (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN8)
    +
    +/* SPI */
    +
    +#define GPIO_SPI1_MISO_1         (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN6)
    +#define GPIO_SPI1_MISO_2         (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN4)
    +#define GPIO_SPI1_MISO_3         (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN14)
    +#define GPIO_SPI1_MOSI_1         (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN7)
    +#define GPIO_SPI1_MOSI_2         (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN5)
    +#define GPIO_SPI1_MOSI_3         (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN15)
    +#define GPIO_SPI1_NSS_1          (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN15)
    +#define GPIO_SPI1_NSS_2          (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN4)
    +#define GPIO_SPI1_NSS_3          (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN12)
    +#define GPIO_SPI1_SCK_1          (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN5)
    +#define GPIO_SPI1_SCK_2          (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN3)
    +#define GPIO_SPI1_SCK_3          (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN13)
    +
    +#define GPIO_SPI2_MISO_1         (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN14)
    +#define GPIO_SPI2_MISO_2         (GPIO_ALT | GPIO_AF1 | GPIO_PORTC | GPIO_PIN2)
    +#define GPIO_SPI2_MISO_3         (GPIO_ALT | GPIO_AF1 | GPIO_PORTD | GPIO_PIN3)
    +#define GPIO_SPI2_MOSI_1         (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN15)
    +#define GPIO_SPI2_MOSI_2         (GPIO_ALT | GPIO_AF1 | GPIO_PORTC | GPIO_PIN3)
    +#define GPIO_SPI2_MOSI_3         (GPIO_ALT | GPIO_AF1 | GPIO_PORTD | GPIO_PIN4)
    +#define GPIO_SPI2_NSS_1          (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN12)
    +#define GPIO_SPI2_NSS_2          (GPIO_ALT | GPIO_AF1 | GPIO_PORTD | GPIO_PIN0)
    +#define GPIO_SPI2_NSS_3          (GPIO_ALT | GPIO_AF5 | GPIO_PORTB | GPIO_PIN9)
    +#define GPIO_SPI2_SCK_1          (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN13)
    +#define GPIO_SPI2_SCK_2          (GPIO_ALT | GPIO_AF1 | GPIO_PORTD | GPIO_PIN1)
    +#define GPIO_SPI2_SCK_3          (GPIO_ALT | GPIO_AF5 | GPIO_PORTB | GPIO_PIN10)
    +
    +/* SWD */
    +
    +#define GPIO_SWCLK               (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN14)
    +#define GPIO_SWDIO               (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN13)
    +
    +/* Timers */
    +
    +#define GPIO_TIM1_BKIN_1         (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN15)
    +#define GPIO_TIM1_BKIN_2         (GPIO_ALT | GPIO_AF2 | GPIO_PORTA | GPIO_PIN6)
    +#define GPIO_TIM1_BKIN_3         (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN12)
    +#define GPIO_TIM1_CH1_1          (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN9)
    +#define GPIO_TIM1_CH1_2          (GPIO_ALT | GPIO_AF2 | GPIO_PORTA | GPIO_PIN8)
    +#define GPIO_TIM1_CH1N_1         (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN8)
    +#define GPIO_TIM1_CH1N_2         (GPIO_ALT | GPIO_AF2 | GPIO_PORTA | GPIO_PIN7)
    +#define GPIO_TIM1_CH1N_3         (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN13)
    +#define GPIO_TIM1_CH2_1          (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN11)
    +#define GPIO_TIM1_CH2_2          (GPIO_ALT | GPIO_AF2 | GPIO_PORTA | GPIO_PIN9)
    +#define GPIO_TIM1_CH2N_1         (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN10)
    +#define GPIO_TIM1_CH2N_2         (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN0)
    +#define GPIO_TIM1_CH2N_3         (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN14)
    +#define GPIO_TIM1_CH3_1          (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN13)
    +#define GPIO_TIM1_CH3_2          (GPIO_ALT | GPIO_AF2 | GPIO_PORTA | GPIO_PIN10)
    +#define GPIO_TIM1_CH3N_1         (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN12)
    +#define GPIO_TIM1_CH3N_2         (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN1)
    +#define GPIO_TIM1_CH3N_3         (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN15)
    +#define GPIO_TIM1_CH4_1          (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN14)
    +#define GPIO_TIM1_CH4_2          (GPIO_ALT | GPIO_AF2 | GPIO_PORTA | GPIO_PIN11)
    +#define GPIO_TIM1_ETR_1          (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN7)
    +#define GPIO_TIM1_ETR_2          (GPIO_ALT | GPIO_AF2 | GPIO_PORTA | GPIO_PIN12)
    +
    +#define GPIO_TIM2_CH1_ETR_1      (GPIO_ALT | GPIO_AF2 | GPIO_PORTA | GPIO_PIN0)
    +#define GPIO_TIM2_CH1_ETR_2      (GPIO_ALT | GPIO_AF2 | GPIO_PORTA | GPIO_PIN15)
    +#define GPIO_TIM2_CH1_ETR_3      (GPIO_ALT | GPIO_AF2 | GPIO_PORTA | GPIO_PIN5)
    +#define GPIO_TIM2_CH2_1          (GPIO_ALT | GPIO_AF2 | GPIO_PORTA | GPIO_PIN1)
    +#define GPIO_TIM2_CH2_2          (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN3)
    +#define GPIO_TIM2_CH3_1          (GPIO_ALT | GPIO_AF2 | GPIO_PORTA | GPIO_PIN2)
    +#define GPIO_TIM2_CH3_2          (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN10)
    +#define GPIO_TIM2_CH4_1          (GPIO_ALT | GPIO_AF2 | GPIO_PORTA | GPIO_PIN3)
    +#define GPIO_TIM2_CH4_2          (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN11)
    +
    +#define GPIO_TIM3_CH1_1          (GPIO_ALT | GPIO_AF0 | GPIO_PORTC | GPIO_PIN6)
    +#define GPIO_TIM3_CH1_2          (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN3)
    +#define GPIO_TIM3_CH1_3          (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN6)
    +#define GPIO_TIM3_CH1_4          (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN4)
    +#define GPIO_TIM3_CH2_1          (GPIO_ALT | GPIO_AF0 | GPIO_PORTC | GPIO_PIN7)
    +#define GPIO_TIM3_CH2_2          (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN4)
    +#define GPIO_TIM3_CH2_3          (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN7)
    +#define GPIO_TIM3_CH2_4          (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN5)
    +#define GPIO_TIM3_CH3_1          (GPIO_ALT | GPIO_AF0 | GPIO_PORTC | GPIO_PIN8)
    +#define GPIO_TIM3_CH3_2          (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN5)
    +#define GPIO_TIM3_CH3_3          (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN0)
    +#define GPIO_TIM3_CH4_1          (GPIO_ALT | GPIO_AF0 | GPIO_PORTC | GPIO_PIN9)
    +#define GPIO_TIM3_CH4_2          (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN6)
    +#define GPIO_TIM3_CH4_3          (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN1)
    +#define GPIO_TIM3_ETR_1          (GPIO_ALT | GPIO_AF0 | GPIO_PORTD | GPIO_PIN2)
    +#define GPIO_TIM3_ETR_2          (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN2)
    +
    +#define GPIO_TIM14_CH1_1         (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN1)
    +#define GPIO_TIM14_CH1_2         (GPIO_ALT | GPIO_AF4 | GPIO_PORTA | GPIO_PIN4)
    +#define GPIO_TIM14_CH1_3         (GPIO_ALT | GPIO_AF4 | GPIO_PORTA | GPIO_PIN7)
    +
    +#define GPIO_TIM15_BKIN_1        (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN9)
    +#define GPIO_TIM15_BKIN_2        (GPIO_ALT | GPIO_AF5 | GPIO_PORTB | GPIO_PIN12)
    +#define GPIO_TIM15_CH1_1         (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN2)
    +#define GPIO_TIM15_CH1_2         (GPIO_ALT | GPIO_AF0 | GPIO_PORTF | GPIO_PIN9)
    +#define GPIO_TIM15_CH1_3         (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN14)
    +#define GPIO_TIM15_CH1N_1        (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN15)
    +#define GPIO_TIM15_CH1N_2        (GPIO_ALT | GPIO_AF5 | GPIO_PORTA | GPIO_PIN1)
    +#define GPIO_TIM15_CH2_1         (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN3)
    +#define GPIO_TIM15_CH2_2         (GPIO_ALT | GPIO_AF0 | GPIO_PORTF | GPIO_PIN10)
    +#define GPIO_TIM15_CH2_3         (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN15)
    +
    +#define GPIO_TIM16_BKIN          (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN5)
    +#define GPIO_TIM16_CH1_1         (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN0)
    +#define GPIO_TIM16_CH1_2         (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN8)
    +#define GPIO_TIM16_CH1_3         (GPIO_ALT | GPIO_AF5 | GPIO_PORTA | GPIO_PIN6)
    +#define GPIO_TIM16_CH1N          (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN6)
    +
    +#define GPIO_TIM17_BKIN_1        (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN10)
    +#define GPIO_TIM17_BKIN_2        (GPIO_ALT | GPIO_AF5 | GPIO_PORTB | GPIO_PIN4)
    +#define GPIO_TIM17_CH1_1         (GPIO_ALT | GPIO_AF0 | GPIO_PORTE | GPIO_PIN1)
    +#define GPIO_TIM17_CH1_2         (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN9)
    +#define GPIO_TIM17_CH1_3         (GPIO_ALT | GPIO_AF5 | GPIO_PORTA | GPIO_PIN7)
    +#define GPIO_TIM17_CH1N          (GPIO_ALT | GPIO_AF2 | GPIO_PORTB | GPIO_PIN7)
    +
    +/* TSC */
    +
    +#define GPIO_TSC_G1_IO1          (GPIO_ALT | GPIO_AF3 | GPIO_PORTA | GPIO_PIN0)
    +#define GPIO_TSC_G1_IO2          (GPIO_ALT | GPIO_AF3 | GPIO_PORTA | GPIO_PIN1)
    +#define GPIO_TSC_G1_IO3          (GPIO_ALT | GPIO_AF3 | GPIO_PORTA | GPIO_PIN2)
    +#define GPIO_TSC_G1_IO4          (GPIO_ALT | GPIO_AF3 | GPIO_PORTA | GPIO_PIN3)
    +#define GPIO_TSC_G2_IO1          (GPIO_ALT | GPIO_AF3 | GPIO_PORTA | GPIO_PIN4)
    +#define GPIO_TSC_G2_IO2          (GPIO_ALT | GPIO_AF3 | GPIO_PORTA | GPIO_PIN5)
    +#define GPIO_TSC_G2_IO3          (GPIO_ALT | GPIO_AF3 | GPIO_PORTA | GPIO_PIN6)
    +#define GPIO_TSC_G2_IO4          (GPIO_ALT | GPIO_AF3 | GPIO_PORTA | GPIO_PIN7)
    +#define GPIO_TSC_G3_IO1          (GPIO_ALT | GPIO_AF0 | GPIO_PORTC | GPIO_PIN5)
    +#define GPIO_TSC_G3_IO2          (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN0)
    +#define GPIO_TSC_G3_IO3          (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN1)
    +#define GPIO_TSC_G3_IO4          (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN2)
    +#define GPIO_TSC_G4_IO1          (GPIO_ALT | GPIO_AF3 | GPIO_PORTA | GPIO_PIN9)
    +#define GPIO_TSC_G4_IO2          (GPIO_ALT | GPIO_AF3 | GPIO_PORTA | GPIO_PIN10)
    +#define GPIO_TSC_G4_IO3          (GPIO_ALT | GPIO_AF3 | GPIO_PORTA | GPIO_PIN11)
    +#define GPIO_TSC_G4_IO4          (GPIO_ALT | GPIO_AF3 | GPIO_PORTA | GPIO_PIN12)
    +#define GPIO_TSC_G5_IO1          (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN3)
    +#define GPIO_TSC_G5_IO2          (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN4)
    +#define GPIO_TSC_G5_IO3          (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN6)
    +#define GPIO_TSC_G5_IO4          (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN7)
    +#define GPIO_TSC_G6_IO1          (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN11)
    +#define GPIO_TSC_G6_IO2          (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN12)
    +#define GPIO_TSC_G6_IO3          (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN13)
    +#define GPIO_TSC_G6_IO4          (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN14)
    +#define GPIO_TSC_G7_IO1          (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN2)
    +#define GPIO_TSC_G7_IO2          (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN3)
    +#define GPIO_TSC_G7_IO3          (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN4)
    +#define GPIO_TSC_G7_IO4          (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN5)
    +#define GPIO_TSC_G8_IO1          (GPIO_ALT | GPIO_AF1 | GPIO_PORTD | GPIO_PIN12)
    +#define GPIO_TSC_G8_IO2          (GPIO_ALT | GPIO_AF1 | GPIO_PORTD | GPIO_PIN13)
    +#define GPIO_TSC_G8_IO3          (GPIO_ALT | GPIO_AF1 | GPIO_PORTD | GPIO_PIN14)
    +#define GPIO_TSC_G8_IO4          (GPIO_ALT | GPIO_AF1 | GPIO_PORTD | GPIO_PIN15)
    +#define GPIO_TSC_SYNC_1          (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN10)
    +#define GPIO_TSC_SYNC_2          (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN8)
    +
    +/* USARTs */
    +
    +#define GPIO_USART1_CK           (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN8)
    +#define GPIO_USART1_CTS          (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN11)
    +#define GPIO_USART1_RTS          (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN12)
    +#define GPIO_USART1_RX_1         (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN7)
    +#define GPIO_USART1_RX_2         (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN10)
    +#define GPIO_USART1_TX_1         (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN6)
    +#define GPIO_USART1_TX_2         (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN9)
    +
    +#define GPIO_USART2_CK_1         (GPIO_ALT | GPIO_AF0 | GPIO_PORTD | GPIO_PIN7)
    +#define GPIO_USART2_CK_2         (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN4)
    +#define GPIO_USART2_CTS_1        (GPIO_ALT | GPIO_AF0 | GPIO_PORTD | GPIO_PIN3)
    +#define GPIO_USART2_CTS_2        (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN0)
    +#define GPIO_USART2_RTS_1        (GPIO_ALT | GPIO_AF0 | GPIO_PORTD | GPIO_PIN4)
    +#define GPIO_USART2_RTS_2        (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN1)
    +#define GPIO_USART2_RX_1         (GPIO_ALT | GPIO_AF0 | GPIO_PORTD | GPIO_PIN6)
    +#define GPIO_USART2_RX_2         (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN15)
    +#define GPIO_USART2_RX_3         (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN3)
    +#define GPIO_USART2_TX_1         (GPIO_ALT | GPIO_AF0 | GPIO_PORTD | GPIO_PIN5)
    +#define GPIO_USART2_TX_2         (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN14)
    +#define GPIO_USART2_TX_3         (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN2)
    +
    +#define GPIO_USART3_CK_1         (GPIO_ALT | GPIO_AF0 | GPIO_PORTD | GPIO_PIN10)
    +#define GPIO_USART3_CK_2         (GPIO_ALT | GPIO_AF1 | GPIO_PORTC | GPIO_PIN12)
    +#define GPIO_USART3_CK_3         (GPIO_ALT | GPIO_AF4 | GPIO_PORTB | GPIO_PIN0)
    +#define GPIO_USART3_CK_4         (GPIO_ALT | GPIO_AF4 | GPIO_PORTB | GPIO_PIN12)
    +#define GPIO_USART3_CTS_1        (GPIO_ALT | GPIO_AF0 | GPIO_PORTD | GPIO_PIN11)
    +#define GPIO_USART3_CTS_2        (GPIO_ALT | GPIO_AF4 | GPIO_PORTA | GPIO_PIN6)
    +#define GPIO_USART3_CTS_3        (GPIO_ALT | GPIO_AF4 | GPIO_PORTB | GPIO_PIN13)
    +#define GPIO_USART3_RTS_1        (GPIO_ALT | GPIO_AF0 | GPIO_PORTD | GPIO_PIN12)
    +#define GPIO_USART3_RTS_2        (GPIO_ALT | GPIO_AF1 | GPIO_PORTD | GPIO_PIN2)
    +#define GPIO_USART3_RTS_3        (GPIO_ALT | GPIO_AF4 | GPIO_PORTB | GPIO_PIN1)
    +#define GPIO_USART3_RTS_4        (GPIO_ALT | GPIO_AF4 | GPIO_PORTB | GPIO_PIN14)
    +#define GPIO_USART3_RX_1         (GPIO_ALT | GPIO_AF0 | GPIO_PORTD | GPIO_PIN9)
    +#define GPIO_USART3_RX_2         (GPIO_ALT | GPIO_AF1 | GPIO_PORTC | GPIO_PIN11)
    +#define GPIO_USART3_RX_3         (GPIO_ALT | GPIO_AF1 | GPIO_PORTC | GPIO_PIN5)
    +#define GPIO_USART3_RX_4         (GPIO_ALT | GPIO_AF4 | GPIO_PORTB | GPIO_PIN11)
    +#define GPIO_USART3_TX_1         (GPIO_ALT | GPIO_AF0 | GPIO_PORTD | GPIO_PIN8)
    +#define GPIO_USART3_TX_2         (GPIO_ALT | GPIO_AF1 | GPIO_PORTC | GPIO_PIN10)
    +#define GPIO_USART3_TX_3         (GPIO_ALT | GPIO_AF1 | GPIO_PORTC | GPIO_PIN4)
    +#define GPIO_USART3_TX_4         (GPIO_ALT | GPIO_AF4 | GPIO_PORTB | GPIO_PIN10)
    +
    +#define GPIO_USART4_CK           (GPIO_ALT | GPIO_AF0 | GPIO_PORTC | GPIO_PIN12)
    +#define GPIO_USART4_CTS          (GPIO_ALT | GPIO_AF4 | GPIO_PORTB | GPIO_PIN7)
    +#define GPIO_USART4_RTS          (GPIO_ALT | GPIO_AF4 | GPIO_PORTA | GPIO_PIN15)
    +#define GPIO_USART4_RX_1         (GPIO_ALT | GPIO_AF0 | GPIO_PORTC | GPIO_PIN11)
    +#define GPIO_USART4_RX_2         (GPIO_ALT | GPIO_AF4 | GPIO_PORTA | GPIO_PIN1)
    +#define GPIO_USART4_TX_1         (GPIO_ALT | GPIO_AF0 | GPIO_PORTC | GPIO_PIN10)
    +#define GPIO_USART4_TX_2         (GPIO_ALT | GPIO_AF4 | GPIO_PORTA | GPIO_PIN0)
    +
    +#define GPIO_USART5_CK_RST_1     (GPIO_ALT | GPIO_AF4 | GPIO_PORTB | GPIO_PIN5)
    +#define GPIO_USART5_CK_RST_2     (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN7)
    +#define GPIO_USART5_RX_1         (GPIO_ALT | GPIO_AF4 | GPIO_PORTB | GPIO_PIN4)
    +#define GPIO_USART5_RX_2         (GPIO_ALT | GPIO_AF2 | GPIO_PORTD | GPIO_PIN2)
    +#define GPIO_USART5_RX_3         (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN11)
    +#define GPIO_USART5_TX_1         (GPIO_ALT | GPIO_AF4 | GPIO_PORTB | GPIO_PIN3)
    +#define GPIO_USART5_TX_2         (GPIO_ALT | GPIO_AF2 | GPIO_PORTC | GPIO_PIN12)
    +#define GPIO_USART5_TX_3         (GPIO_ALT | GPIO_AF1 | GPIO_PORTE | GPIO_PIN10)
    +
    +#define GPIO_USART6_TX_1         (GPIO_ALT | GPIO_AF5 | GPIO_PORTA | GPIO_PIN4)
    +#define GPIO_USART6_RX_1         (GPIO_ALT | GPIO_AF5 | GPIO_PORTA | GPIO_PIN5)
    +#define GPIO_USART6_TX_2         (GPIO_ALT | GPIO_AF2 | GPIO_PORTC | GPIO_PIN0)
    +#define GPIO_USART6_RX_2         (GPIO_ALT | GPIO_AF2 | GPIO_PORTC | GPIO_PIN1)
    +#define GPIO_USART6_TX_3         (GPIO_ALT | GPIO_AF1 | GPIO_PORTF | GPIO_PIN9)
    +#define GPIO_USART6_RX_3         (GPIO_ALT | GPIO_AF1 | GPIO_PORTF | GPIO_PIN10)
    +#define GPIO_USART6_CK_RST       (GPIO_ALT | GPIO_AF2 | GPIO_PORTF | GPIO_PIN3)
    +
    +#define GPIO_USART7_TX_1         (GPIO_ALT | GPIO_AF1 | GPIO_PORTC | GPIO_PIN0)
    +#define GPIO_USART7_RX_1         (GPIO_ALT | GPIO_AF1 | GPIO_PORTC | GPIO_PIN1)
    +#define GPIO_USART7_TX_2         (GPIO_ALT | GPIO_AF1 | GPIO_PORTC | GPIO_PIN6)
    +#define GPIO_USART7_RX_2         (GPIO_ALT | GPIO_AF1 | GPIO_PORTC | GPIO_PIN7)
    +#define GPIO_USART7_TX_3         (GPIO_ALT | GPIO_AF1 | GPIO_PORTF | GPIO_PIN2)
    +#define GPIO_USART7_RX_3         (GPIO_ALT | GPIO_AF1 | GPIO_PORTF | GPIO_PIN3)
    +#define GPIO_USART7_CK_RST_1     (GPIO_ALT | GPIO_AF2 | GPIO_PORTD | GPIO_PIN15)
    +#define GPIO_USART7_CK_RST_2     (GPIO_ALT | GPIO_AF2 | GPIO_PORTF | GPIO_PIN2)
    +
    +#define GPIO_USART8_TX_1         (GPIO_ALT | GPIO_AF2 | GPIO_PORTC | GPIO_PIN2)
    +#define GPIO_USART8_RX_1         (GPIO_ALT | GPIO_AF2 | GPIO_PORTC | GPIO_PIN3)
    +#define GPIO_USART8_TX_2         (GPIO_ALT | GPIO_AF1 | GPIO_PORTC | GPIO_PIN8)
    +#define GPIO_USART8_RX_2         (GPIO_ALT | GPIO_AF1 | GPIO_PORTC | GPIO_PIN9)
    +#define GPIO_USART8_TX_3         (GPIO_ALT | GPIO_AF0 | GPIO_PORTD | GPIO_PIN8)
    +#define GPIO_USART8_RX_3         (GPIO_ALT | GPIO_AF0 | GPIO_PORTD | GPIO_PIN13)
    +#define GPIO_USART8_CK_RST       (GPIO_ALT | GPIO_AF2 | GPIO_PORTD | GPIO_PIN14)
    +
    +#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F09X_PINMAP_H */
    diff --git a/arch/arm/src/stm32f0/chip/stm32f0_memorymap.h b/arch/arm/src/stm32f0/chip/stm32f0_memorymap.h
    index 7ff37fcdcd..bc2436f476 100644
    --- a/arch/arm/src/stm32f0/chip/stm32f0_memorymap.h
    +++ b/arch/arm/src/stm32f0/chip/stm32f0_memorymap.h
    @@ -44,8 +44,9 @@
     #include 
     #include "chip.h"
     
    -#if defined(CONFIG_STM32F0_STM32F05X) || defined(CONFIG_STM32F0_STM32F07X)
    -#  include "chip/stm32f05xf07x_memorymap.h"
    +#if defined(CONFIG_STM32F0_STM32F05X) || defined(CONFIG_STM32F0_STM32F07X) \
    + || defined(CONFIG_STM32F0_STM32F09X)
    +#  include "chip/stm32f05xf07xf09x_memorymap.h"
     #else
     #  error "Unsupported STM32 memory map"
     #endif
    diff --git a/arch/arm/src/stm32f0/chip/stm32f0_pinmap.h b/arch/arm/src/stm32f0/chip/stm32f0_pinmap.h
    index 37893a4c12..671264c893 100644
    --- a/arch/arm/src/stm32f0/chip/stm32f0_pinmap.h
    +++ b/arch/arm/src/stm32f0/chip/stm32f0_pinmap.h
    @@ -47,6 +47,8 @@
     #  include "chip/stm32f05x_pinmap.h"
     #elif defined(CONFIG_STM32F0_STM32F07X)
     #  include "chip/stm32f07x_pinmap.h"
    +#elif defined(CONFIG_STM32F0_STM32F09X)
    +#  include "chip/stm32f09x_pinmap.h"
     #else
     #  error "Unsupported STM32F0 pin map"
     #endif
    diff --git a/configs/nucleo-f072rb/README.txt b/configs/nucleo-f072rb/README.txt
    index 033b7b7560..118d24d9af 100644
    --- a/configs/nucleo-f072rb/README.txt
    +++ b/configs/nucleo-f072rb/README.txt
    @@ -1,9 +1,9 @@
     Nucleo-F072RB README
     ====================
     
    -  This README file discusess the port of NuttX to the STMicro Nucleo-F4072RB
    -  board.  That board features the STM32F072RBT6 MCU with 128KiB with 128KiB
    -  of FLASH and 16KiB of SRAM.
    +  This README file discusses the port of NuttX to the STMicro Nucleo-F072RB
    +  board.  That board features the STM32F072RBT6 MCU with 128KiB of FLASH
    +  and 16KiB of SRAM.
     
     Contents
     ========
    @@ -53,8 +53,8 @@ LEDs
     
       These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is
       defined.  In that case, the usage by the board port is defined in
    -  include/board.h and src/sam_leds.c. The LEDs are used to encode OS-related
    -  events as follows when the red LED (PE24) is available:
    +  include/board.h and src/stm32_autoleds.c. The LEDs are used to encode
    +  OS-related events as follows when the red LED (PE24) is available:
     
         SYMBOL                Meaning                   LD2
         -------------------  -----------------------  -----------
    @@ -192,11 +192,11 @@ Configurations
     
       Information Common to All Configurations
       ----------------------------------------
    -  Each Clicker2 configuration is maintained in a sub-directory and can be
    +  Each configuration is maintained in a sub-directory and can be
       selected as follow:
     
         cd tools
    -    ./configure.sh nucleo-f702rb/
    +    ./configure.sh nucleo-f072rb/
         cd -
         . ./setenv.sh
     
    -- 
    GitLab
    
    
    From 325ba1a803e44a9363e954f2e5aa5a754766a421 Mon Sep 17 00:00:00 2001
    From: Jussi Kivilinna 
    Date: Fri, 21 Apr 2017 08:45:57 -0600
    Subject: [PATCH 540/990] clock: add clock_resynchronize and use subseconds RTC
    
    Add clock_resynchronize for better synchronization of CLOCK_REALTIME and CLOCK_MONOTONIC to match RTC after resume from low-power state.
    
    Add up_rtc_getdatetime_with_subseconds under CONFIG_ARCH_HAVE_RTC_SUBSECONDS to allow initializing (and resynchronizing) system clock with subseconds accuracy RTC.
    ---
     arch/Kconfig                     |   4 +
     arch/arm/src/stm32/Kconfig       |   1 +
     arch/arm/src/stm32/stm32_rtcc.c  |  34 ++++++
     arch/arm/src/stm32f7/Kconfig     |   1 +
     arch/arm/src/stm32f7/stm32_rtc.c |  36 +++++-
     include/nuttx/arch.h             |  29 +++++
     include/nuttx/clock.h            |  38 ++++++-
     sched/clock/clock.h              |   6 +-
     sched/clock/clock_gettime.c      |  33 ++++++
     sched/clock/clock_initialize.c   | 188 ++++++++++++++++++++++++++++++-
     10 files changed, 363 insertions(+), 7 deletions(-)
    
    diff --git a/arch/Kconfig b/arch/Kconfig
    index 6fac6fd310..7dbad3d037 100644
    --- a/arch/Kconfig
    +++ b/arch/Kconfig
    @@ -190,6 +190,10 @@ config ARCH_HAVE_RESET
     	bool
     	default n
     
    +config ARCH_HAVE_RTC_SUBSECONDS
    +	bool
    +	default n
    +
     config ARCH_USE_MMU
     	bool "Enable MMU"
     	default n
    diff --git a/arch/arm/src/stm32/Kconfig b/arch/arm/src/stm32/Kconfig
    index 262017a34b..e36b54673e 100644
    --- a/arch/arm/src/stm32/Kconfig
    +++ b/arch/arm/src/stm32/Kconfig
    @@ -6362,6 +6362,7 @@ config STM32_HAVE_RTC_COUNTER
     
     config STM32_HAVE_RTC_SUBSECONDS
     	bool
    +	select ARCH_HAVE_RTC_SUBSECONDS
     	default n
     
     config RTC_MAGIC_REG
    diff --git a/arch/arm/src/stm32/stm32_rtcc.c b/arch/arm/src/stm32/stm32_rtcc.c
    index b1347fd9e7..9adc62433c 100644
    --- a/arch/arm/src/stm32/stm32_rtcc.c
    +++ b/arch/arm/src/stm32/stm32_rtcc.c
    @@ -928,6 +928,40 @@ int up_rtc_getdatetime(FAR struct tm *tp)
     }
     #endif
     
    +/************************************************************************************
    + * Name: up_rtc_getdatetime_with_subseconds
    + *
    + * Description:
    + *   Get the current date and time from the date/time RTC.  This interface
    + *   is only supported by the date/time RTC hardware implementation.
    + *   It is used to replace the system timer.  It is only used by the RTOS during
    + *   initialization to set up the system time when CONFIG_RTC and CONFIG_RTC_DATETIME
    + *   are selected (and CONFIG_RTC_HIRES is not).
    + *
    + *   NOTE: This interface exposes sub-second accuracy capability of RTC hardware.
    + *   This interface allow maintaining timing accuracy when system time needs constant
    + *   resynchronization with RTC, for example on MCU with low-power state that
    + *   stop system timer.
    + *
    + * Input Parameters:
    + *   tp - The location to return the high resolution time value.
    + *   nsec - The location to return the subsecond time value.
    + *
    + * Returned Value:
    + *   Zero (OK) on success; a negated errno on failure
    + *
    + ************************************************************************************/
    +
    +#ifdef CONFIG_ARCH_HAVE_RTC_SUBSECONDS
    +#  ifndef CONFIG_STM32_HAVE_RTC_SUBSECONDS
    +#    error "Invalid config, enable CONFIG_STM32_HAVE_RTC_SUBSECONDS."
    +#  endif
    +int up_rtc_getdatetime_with_subseconds(FAR struct tm *tp, FAR long *nsec)
    +{
    +  return stm32_rtc_getdatetime_with_subseconds(tp, nsec);
    +}
    +#endif
    +
     /************************************************************************************
      * Name: stm32_rtc_setdatetime
      *
    diff --git a/arch/arm/src/stm32f7/Kconfig b/arch/arm/src/stm32f7/Kconfig
    index 8e9904a0ab..ae131dd2f1 100644
    --- a/arch/arm/src/stm32f7/Kconfig
    +++ b/arch/arm/src/stm32f7/Kconfig
    @@ -1821,6 +1821,7 @@ config STM32F7_HAVE_RTC_COUNTER
     
     config STM32F7_HAVE_RTC_SUBSECONDS
     	bool
    +	select ARCH_HAVE_RTC_SUBSECONDS
     	default y
     
     config RTC_MAGIC_REG
    diff --git a/arch/arm/src/stm32f7/stm32_rtc.c b/arch/arm/src/stm32f7/stm32_rtc.c
    index 4583dfaf1e..a314836427 100644
    --- a/arch/arm/src/stm32f7/stm32_rtc.c
    +++ b/arch/arm/src/stm32f7/stm32_rtc.c
    @@ -1178,7 +1178,7 @@ int up_rtc_getdatetime(FAR struct tm *tp)
         }
     
       rtc_dumptime((FAR const struct tm *)tp, &usecs, "Returning");
    -#else /* CONFIG_STM32_HAVE_RTC_SUBSECONDS */
    +#else /* CONFIG_STM32F7_HAVE_RTC_SUBSECONDS */
       rtc_dumptime((FAR const struct tm *)tp, NULL, "Returning");
     #endif
     
    @@ -1215,6 +1215,40 @@ int up_rtc_getdatetime(FAR struct tm *tp)
     }
     #endif
     
    +/************************************************************************************
    + * Name: up_rtc_getdatetime_with_subseconds
    + *
    + * Description:
    + *   Get the current date and time from the date/time RTC.  This interface
    + *   is only supported by the date/time RTC hardware implementation.
    + *   It is used to replace the system timer.  It is only used by the RTOS during
    + *   initialization to set up the system time when CONFIG_RTC and CONFIG_RTC_DATETIME
    + *   are selected (and CONFIG_RTC_HIRES is not).
    + *
    + *   NOTE: This interface exposes sub-second accuracy capability of RTC hardware.
    + *   This interface allow maintaining timing accuracy when system time needs constant
    + *   resynchronization with RTC, for example with board level power-save mode utilizing
    + *   deep-sleep modes such as STOP on STM32 MCUs.
    + *
    + * Input Parameters:
    + *   tp - The location to return the high resolution time value.
    + *   nsec - The location to return the subsecond time value.
    + *
    + * Returned Value:
    + *   Zero (OK) on success; a negated errno on failure
    + *
    + ************************************************************************************/
    +
    +#ifdef CONFIG_ARCH_HAVE_RTC_SUBSECONDS
    +#  ifndef CONFIG_STM32F7_HAVE_RTC_SUBSECONDS
    +#    error "Invalid config, enable CONFIG_STM32F7_HAVE_RTC_SUBSECONDS."
    +#  endif
    +int up_rtc_getdatetime_with_subseconds(FAR struct tm *tp, FAR long *nsec)
    +{
    +  return stm32_rtc_getdatetime_with_subseconds(tp, nsec);
    +}
    +#endif
    +
     /****************************************************************************
      * Name: stm32_rtc_setdatetime
      *
    diff --git a/include/nuttx/arch.h b/include/nuttx/arch.h
    index 05597f6d59..925ae988ed 100644
    --- a/include/nuttx/arch.h
    +++ b/include/nuttx/arch.h
    @@ -2185,6 +2185,35 @@ int up_rtc_gettime(FAR struct timespec *tp);
     int up_rtc_getdatetime(FAR struct tm *tp);
     #endif
     
    +/************************************************************************************
    + * Name: up_rtc_getdatetime_with_subseconds
    + *
    + * Description:
    + *   Get the current date and time from the date/time RTC.  This interface
    + *   is only supported by the date/time RTC hardware implementation.
    + *   It is used to replace the system timer.  It is only used by the RTOS during
    + *   initialization to set up the system time when CONFIG_RTC and CONFIG_RTC_DATETIME
    + *   are selected (and CONFIG_RTC_HIRES is not).
    + *
    + *   NOTE: This interface exposes sub-second accuracy capability of RTC hardware.
    + *   This interface allow maintaining timing accuracy when system time needs constant
    + *   resynchronization with RTC, for example on MCU with low-power state that
    + *   stop system timer.
    + *
    + * Input Parameters:
    + *   tp - The location to return the high resolution time value.
    + *   nsec - The location to return the subsecond time value.
    + *
    + * Returned Value:
    + *   Zero (OK) on success; a negated errno on failure
    + *
    + ************************************************************************************/
    +
    +#if defined(CONFIG_RTC) && defined(CONFIG_RTC_DATETIME) && \
    +    defined(CONFIG_ARCH_HAVE_RTC_SUBSECONDS)
    +int up_rtc_getdatetime_with_subseconds(FAR struct tm *tp, FAR long *nsec);
    +#endif
    +
     /************************************************************************************
      * Name: up_rtc_settime
      *
    diff --git a/include/nuttx/clock.h b/include/nuttx/clock.h
    index 5684fef938..ea418ee8c8 100644
    --- a/include/nuttx/clock.h
    +++ b/include/nuttx/clock.h
    @@ -1,7 +1,7 @@
     /****************************************************************************
      * include/nuttx/clock.h
      *
    - *   Copyright (C) 2007-2009, 2011-2012, 2014, 2016 Gregory Nutt.
    + *   Copyright (C) 2007-2009, 2011-2012, 2014, 2016-2017 Gregory Nutt.
                  All rights reserved.
      *   Author: Gregory Nutt 
      *
    @@ -50,6 +50,7 @@
     /****************************************************************************
      * Pre-processor Definitions
      ****************************************************************************/
    +
     /* Configuration ************************************************************/
     /* Efficient, direct access to OS global timer variables will be supported
      * if the execution environment has direct access to kernel global data.
    @@ -71,12 +72,12 @@
        /* Case 1: There is no global timer data */
     
     #elif defined(CONFIG_BUILD_PROTECTED) && defined(__KERNEL__)
    -     /* Case 3: Kernel mode of protected kernel build */
    +   /* Case 3: Kernel mode of protected kernel build */
     
     #    define __HAVE_KERNEL_GLOBALS 1
     
     #elif defined(CONFIG_BUILD_KERNEL) && defined(__KERNEL__)
    -     /* Case 3: Kernel only build */
    +   /* Case 3: Kernel only build */
     
     #    define __HAVE_KERNEL_GLOBALS 1
     
    @@ -261,6 +262,37 @@ EXTERN volatile systime_t g_system_timer;
     void clock_synchronize(void);
     #endif
     
    +/****************************************************************************
    + * Name: clock_resynchronize
    + *
    + * Description:
    + *   Resynchronize the system timer to a hardware RTC.  The user can
    + *   explicitly re-synchronize the system timer to the RTC under certain
    + *   conditions where the system timer is known to be in error.  For example,
    + *   in certain low-power states, the system timer may be stopped but the
    + *   RTC will continue keep correct time.  After recovering from such
    + *   low-power state, this function should be called to restore the correct
    + *   system time. Function also keeps monotonic clock at rate of RTC.
    + *
    + *   Calling this function will not result in system time going "backward" in
    + *   time. If setting system time with RTC would result time going "backward"
    + *   then resynchronization is not performed.
    + *
    + * Parameters:
    + *   diff:  amount of time system-time is adjusted forward with RTC
    + *
    + * Return Value:
    + *   None
    + *
    + * Assumptions:
    + *
    + ****************************************************************************/
    +
    +#if defined(CONFIG_RTC) && !defined(CONFIG_SCHED_TICKLESS) && \
    +    !defined(CONFIG_CLOCK_TIMEKEEPING)
    +void clock_resynchronize(FAR struct timespec *rtc_diff);
    +#endif
    +
     /****************************************************************************
      * Function:  clock_systimer
      *
    diff --git a/sched/clock/clock.h b/sched/clock/clock.h
    index cd8066615b..fb6e588e8c 100644
    --- a/sched/clock/clock.h
    +++ b/sched/clock/clock.h
    @@ -1,7 +1,7 @@
     /****************************************************************************
      * sched/clock/clock.h
      *
    - *   Copyright (C) 2007-2009, 2014 Gregory Nutt. All rights reserved.
    + *   Copyright (C) 2007-2009, 2014, 2017 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
      *
      * Redistribution and use in source and binary forms, with or without
    @@ -81,6 +81,10 @@ extern volatile uint32_t g_system_timer;
     
     #ifndef CONFIG_CLOCK_TIMEKEEPING
     extern struct timespec   g_basetime;
    +
    +#ifdef CONFIG_CLOCK_MONOTONIC
    +extern struct timespec   g_monotonic_basetime;
    +#endif
     #endif
     
     /****************************************************************************
    diff --git a/sched/clock/clock_gettime.c b/sched/clock/clock_gettime.c
    index 74ffea5be8..731c6a2ae3 100644
    --- a/sched/clock/clock_gettime.c
    +++ b/sched/clock/clock_gettime.c
    @@ -100,6 +100,33 @@ int clock_gettime(clockid_t clock_id, struct timespec *tp)
     #else
           ret = clock_systimespec(tp);
     #endif
    +
    +#ifndef CONFIG_CLOCK_TIMEKEEPING
    +      if (ret == OK)
    +        {
    +          irqstate_t flags;
    +
    +          /* Add the offset time to this. The offset time allows
    +           * CLOCK_MONOTONIC be introduced additional increases to systime.
    +           */
    +
    +          flags = enter_critical_section();
    +
    +          tp->tv_sec  += (uint32_t)g_monotonic_basetime.tv_sec;
    +          tp->tv_nsec += (uint32_t)g_monotonic_basetime.tv_nsec;
    +
    +          leave_critical_section(flags);
    +
    +          /* Handle carry to seconds. */
    +
    +          if (tp->tv_nsec >= NSEC_PER_SEC)
    +            {
    +              carry        = tp->tv_nsec / NSEC_PER_SEC;
    +              tp->tv_sec  += carry;
    +              tp->tv_nsec -= (carry * NSEC_PER_SEC);
    +            }
    +        }
    +#endif /* CONFIG_CLOCK_TIMEKEEPING */
         }
       else
     #endif
    @@ -129,14 +156,20 @@ int clock_gettime(clockid_t clock_id, struct timespec *tp)
     #ifndef CONFIG_CLOCK_TIMEKEEPING
           if (ret == OK)
             {
    +          irqstate_t flags;
    +
               /* Add the base time to this.  The base time is the time-of-day
                * setting.  When added to the elapsed time since the time-of-day
                * was last set, this gives us the current time.
                */
     
    +          flags = enter_critical_section();
    +
               ts.tv_sec  += (uint32_t)g_basetime.tv_sec;
               ts.tv_nsec += (uint32_t)g_basetime.tv_nsec;
     
    +          leave_critical_section(flags);
    +
               /* Handle carry to seconds. */
     
               if (ts.tv_nsec >= NSEC_PER_SEC)
    diff --git a/sched/clock/clock_initialize.c b/sched/clock/clock_initialize.c
    index 0113e5e0fc..82bf02b985 100644
    --- a/sched/clock/clock_initialize.c
    +++ b/sched/clock/clock_initialize.c
    @@ -1,7 +1,7 @@
     /****************************************************************************
      * sched/clock/clock_initialize.c
      *
    - *   Copyright (C) 2007, 2009, 2011-2012 Gregory Nutt. All rights reserved.
    + *   Copyright (C) 2007, 2009, 2011-2012, 2017 Gregory Nutt. All rights reserved.
      *   Author: Gregory Nutt 
      *
      * Redistribution and use in source and binary forms, with or without
    @@ -80,8 +80,14 @@ volatile uint32_t g_system_timer;
     #endif
     #endif
     
    +#ifndef CONFIG_CLOCK_TIMEKEEPING
     struct timespec   g_basetime;
     
    +#ifdef CONFIG_CLOCK_MONOTONIC
    +struct timespec   g_monotonic_basetime;
    +#endif
    +#endif
    +
     /****************************************************************************
      * Private Functions
      ****************************************************************************/
    @@ -101,17 +107,22 @@ struct timespec   g_basetime;
     static inline int clock_basetime(FAR struct timespec *tp)
     {
       struct tm rtctime;
    +  long nsecs = 0;
       int ret;
     
       /* Get the broken-out time from the date/time RTC. */
     
    +#ifdef CONFIG_ARCH_HAVE_RTC_SUBSECONDS
    +  ret = up_rtc_getdatetime_with_subseconds(&rtctime, &nsecs);
    +#else
       ret = up_rtc_getdatetime(&rtctime);
    +#endif
       if (ret >= 0)
         {
           /* And use the broken-out time to initialize the system time */
     
           tp->tv_sec  = mktime(&rtctime);
    -      tp->tv_nsec = 0;
    +      tp->tv_nsec = nsecs;
         }
     
       return ret;
    @@ -256,6 +267,179 @@ void clock_synchronize(void)
     }
     #endif
     
    +/****************************************************************************
    + * Name: clock_resynchronize
    + *
    + * Description:
    + *   Resynchronize the system timer to a hardware RTC.  The user can
    + *   explicitly re-synchronize the system timer to the RTC under certain
    + *   conditions where the system timer is known to be in error.  For example,
    + *   in certain low-power states, the system timer may be stopped but the
    + *   RTC will continue keep correct time.  After recovering from such
    + *   low-power state, this function should be called to restore the correct
    + *   system time. Function also keeps monotonic clock at rate of RTC.
    + *
    + *   Calling this function will not result in system time going "backward" in
    + *   time. If setting system time with RTC would result time going "backward"
    + *   then resynchronization is not performed.
    + *
    + * Parameters:
    + *   rtc_diff:  amount of time system-time is adjusted forward with RTC
    + *
    + * Return Value:
    + *   None
    + *
    + * Assumptions:
    + *
    + ****************************************************************************/
    +
    +#if defined(CONFIG_RTC) && !defined(CONFIG_SCHED_TICKLESS) && \
    +    !defined(CONFIG_CLOCK_TIMEKEEPING)
    +void clock_resynchronize(FAR struct timespec *rtc_diff)
    +{
    +  struct timespec rtc_time, bias, curr_ts;
    +  struct timespec rtc_diff_tmp;
    +  irqstate_t flags;
    +  int32_t carry;
    +  int ret;
    +
    +  if (rtc_diff == NULL)
    +    {
    +      rtc_diff = &rtc_diff_tmp;
    +    }
    +
    +  /* Set the time value to match the RTC */
    +
    +  flags = enter_critical_section();
    +
    +  /* Get RTC time */
    +
    +  ret = clock_basetime(&rtc_time);
    +  if (ret < 0)
    +    {
    +      /* Error reading RTC, skip resynchronization. */
    +
    +      sinfo("rtc error %d, skip resync\n", ret);
    +
    +      rtc_diff->tv_sec = 0;
    +      rtc_diff->tv_nsec = 0;
    +      goto skip;
    +    }
    +
    +  /* Get the elapsed time since power up (in milliseconds).  This is a
    +   * bias value that we need to use to correct the base time.
    +   */
    +
    +  (void)clock_systimespec(&bias);
    +
    +  /* Add the base time to this.  The base time is the time-of-day
    +   * setting.  When added to the elapsed time since the time-of-day
    +   * was last set, this gives us the current time.
    +   */
    +
    +  curr_ts.tv_sec  = bias.tv_sec + g_basetime.tv_sec;
    +  curr_ts.tv_nsec = bias.tv_nsec + g_basetime.tv_nsec;
    +
    +  /* Handle carry to seconds. */
    +
    +  if (curr_ts.tv_nsec >= NSEC_PER_SEC)
    +    {
    +      carry            = curr_ts.tv_nsec / NSEC_PER_SEC;
    +      curr_ts.tv_sec  += carry;
    +      curr_ts.tv_nsec -= (carry * NSEC_PER_SEC);
    +    }
    +
    +  /* Check if RTC has advanced past system time. */
    +
    +  if (curr_ts.tv_sec > rtc_time.tv_sec ||
    +      (curr_ts.tv_sec == rtc_time.tv_sec && curr_ts.tv_nsec >= rtc_time.tv_nsec))
    +    {
    +      /* Setting system time with RTC now would result time going
    +       * backwards. Skip resynchronization.
    +       */
    +
    +      sinfo("skip resync\n");
    +
    +      rtc_diff->tv_sec = 0;
    +      rtc_diff->tv_nsec = 0;
    +    }
    +  else
    +    {
    +      /* Save RTC time as the new base time. */
    +
    +      g_basetime.tv_sec  = rtc_time.tv_sec;
    +      g_basetime.tv_nsec = rtc_time.tv_nsec;
    +
    +      /* Subtract that bias from the basetime so that when the system
    +       * timer is again added to the base time, the result is the current
    +       * time relative to basetime.
    +       */
    +
    +      if (g_basetime.tv_nsec < bias.tv_nsec)
    +        {
    +          g_basetime.tv_nsec += NSEC_PER_SEC;
    +          g_basetime.tv_sec--;
    +        }
    +
    +      /* Result could be negative seconds */
    +
    +      g_basetime.tv_nsec -= bias.tv_nsec;
    +      g_basetime.tv_sec  -= bias.tv_sec;
    +
    +      sinfo("basetime=(%ld,%lu) bias=(%ld,%lu)\n",
    +            (long)g_basetime.tv_sec, (unsigned long)g_basetime.tv_nsec,
    +            (long)bias.tv_sec, (unsigned long)bias.tv_nsec);
    +
    +      /* Output difference between time at entry and new current time. */
    +
    +      rtc_diff->tv_sec = (bias.tv_sec + g_basetime.tv_sec) - curr_ts.tv_sec;
    +      rtc_diff->tv_nsec = (bias.tv_nsec + g_basetime.tv_nsec) - curr_ts.tv_nsec;
    +
    +      /* Handle carry to seconds. */
    +
    +      if (rtc_diff->tv_nsec < 0)
    +        {
    +          carry = -((-(rtc_diff->tv_nsec + 1)) / NSEC_PER_SEC + 1);
    +        }
    +      else if (rtc_diff->tv_nsec >= NSEC_PER_SEC)
    +        {
    +          carry = rtc_diff->tv_nsec / NSEC_PER_SEC;
    +        }
    +      else
    +        {
    +          carry = 0;
    +        }
    +
    +      if (carry)
    +        {
    +          rtc_diff->tv_sec  += carry;
    +          rtc_diff->tv_nsec -= (carry * NSEC_PER_SEC);
    +        }
    +
    +#ifdef CONFIG_CLOCK_MONOTONIC
    +      /* Monotonic clock follows wall time since system start-up. Adjust
    +       * CLOCK_MONOTONIC same amount as CLOCK_REALTIME.
    +       */
    +
    +      g_monotonic_basetime.tv_sec  += (uint32_t)rtc_diff->tv_sec;
    +      g_monotonic_basetime.tv_nsec += (uint32_t)rtc_diff->tv_nsec;
    +
    +      /* Handle carry to seconds. */
    +
    +      if (g_monotonic_basetime.tv_nsec >= NSEC_PER_SEC)
    +        {
    +          carry = g_monotonic_basetime.tv_nsec / NSEC_PER_SEC;
    +          g_monotonic_basetime.tv_sec += carry;
    +          g_monotonic_basetime.tv_nsec -= (carry * NSEC_PER_SEC);
    +        }
    +#endif
    +    }
    +
    +skip:
    +  leave_critical_section(flags);
    +}
    +#endif
    +
     /****************************************************************************
      * Name: clock_timer
      *
    -- 
    GitLab
    
    
    From c57d49f420c5f00098384ca9ceb7c6b4a65b3fc7 Mon Sep 17 00:00:00 2001
    From: Jussi Kivilinna 
    Date: Fri, 21 Apr 2017 08:51:31 -0600
    Subject: [PATCH 541/990] clock: Add new type ssystime_t for relative 64-bit
     ticks, change ticks<->time conversion functions to use ssystime_t
    
    ---
     include/nuttx/clock.h                 |  8 ++++++++
     sched/clock/clock.h                   |  7 ++++---
     sched/clock/clock_abstime2ticks.c     |  2 +-
     sched/clock/clock_ticks2time.c        |  4 ++--
     sched/clock/clock_time2ticks.c        |  7 ++++---
     sched/mqueue/mq_timedreceive.c        |  2 +-
     sched/mqueue/mq_timedsend.c           |  2 +-
     sched/pthread/pthread_condtimedwait.c |  2 +-
     sched/pthread/pthread_create.c        |  4 ++--
     sched/sched/sched_getparam.c          |  6 ++++--
     sched/sched/sched_setparam.c          |  4 ++--
     sched/sched/sched_setscheduler.c      |  4 ++--
     sched/semaphore/sem_timedwait.c       |  2 +-
     sched/signal/sig_nanosleep.c          |  8 ++++----
     sched/timer/timer_gettime.c           |  2 +-
     sched/timer/timer_settime.c           | 12 ++++++++++--
     16 files changed, 48 insertions(+), 28 deletions(-)
    
    diff --git a/include/nuttx/clock.h b/include/nuttx/clock.h
    index ea418ee8c8..c6a1deafc5 100644
    --- a/include/nuttx/clock.h
    +++ b/include/nuttx/clock.h
    @@ -199,6 +199,14 @@ typedef uint64_t systime_t;
     typedef uint32_t systime_t;
     #endif
     
    +/* This type used to hold relative ticks that may have negative value */
    +
    +#ifdef CONFIG_SYSTEM_TIME64
    +typedef int64_t ssystime_t;
    +#else
    +typedef int32_t ssystime_t;
    +#endif
    +
     /****************************************************************************
      * Public Data
      ****************************************************************************/
    diff --git a/sched/clock/clock.h b/sched/clock/clock.h
    index fb6e588e8c..7e6a1c0933 100644
    --- a/sched/clock/clock.h
    +++ b/sched/clock/clock.h
    @@ -98,9 +98,10 @@ void weak_function clock_timer(void);
     
     int  clock_abstime2ticks(clockid_t clockid,
                              FAR const struct timespec *abstime,
    -                         FAR int *ticks);
    -int  clock_time2ticks(FAR const struct timespec *reltime, FAR int *ticks);
    -int  clock_ticks2time(int ticks, FAR struct timespec *reltime);
    +                         FAR ssystime_t *ticks);
    +int  clock_time2ticks(FAR const struct timespec *reltime,
    +                      FAR ssystime_t *ticks);
    +int  clock_ticks2time(ssystime_t ticks, FAR struct timespec *reltime);
     void clock_timespec_add(FAR const struct timespec *ts1,
                             FAR const struct timespec *ts2,
                             FAR struct timespec *ts3);
    diff --git a/sched/clock/clock_abstime2ticks.c b/sched/clock/clock_abstime2ticks.c
    index d21e706e39..5ac7081a20 100644
    --- a/sched/clock/clock_abstime2ticks.c
    +++ b/sched/clock/clock_abstime2ticks.c
    @@ -99,7 +99,7 @@ static long compare_timespec(FAR const struct timespec *a,
      ****************************************************************************/
     
     int clock_abstime2ticks(clockid_t clockid, FAR const struct timespec *abstime,
    -                        FAR int *ticks)
    +                        FAR ssystime_t *ticks)
     {
       struct timespec currtime;
       struct timespec reltime;
    diff --git a/sched/clock/clock_ticks2time.c b/sched/clock/clock_ticks2time.c
    index 33353193a8..899ecd9818 100644
    --- a/sched/clock/clock_ticks2time.c
    +++ b/sched/clock/clock_ticks2time.c
    @@ -63,9 +63,9 @@
      *
      ****************************************************************************/
     
    -int clock_ticks2time(int ticks, FAR struct timespec *reltime)
    +int clock_ticks2time(ssystime_t ticks, FAR struct timespec *reltime)
     {
    -  int remainder;
    +  ssystime_t remainder;
     
       reltime->tv_sec  = ticks / TICK_PER_SEC;
       remainder        = ticks - TICK_PER_SEC * reltime->tv_sec;
    diff --git a/sched/clock/clock_time2ticks.c b/sched/clock/clock_time2ticks.c
    index 5bb613b61d..5f0bc28c40 100644
    --- a/sched/clock/clock_time2ticks.c
    +++ b/sched/clock/clock_time2ticks.c
    @@ -67,7 +67,8 @@
      *
      ****************************************************************************/
     
    -int clock_time2ticks(FAR const struct timespec *reltime, FAR int *ticks)
    +int clock_time2ticks(FAR const struct timespec *reltime,
    +                     FAR ssystime_t *ticks)
     {
     #ifdef CONFIG_HAVE_LONG_LONG
       int64_t relnsec;
    @@ -83,7 +84,7 @@ int clock_time2ticks(FAR const struct timespec *reltime, FAR int *ticks)
        * that is greater than or equal to the exact number of tick.
        */
     
    -  *ticks = (int)((relnsec + NSEC_PER_TICK - 1) / NSEC_PER_TICK);
    +  *ticks = (ssystime_t)((relnsec + NSEC_PER_TICK - 1) / NSEC_PER_TICK);
       return OK;
     #else
       int32_t relusec;
    @@ -110,7 +111,7 @@ int clock_time2ticks(FAR const struct timespec *reltime, FAR int *ticks)
        * that is greater than or equal to the exact number of tick.
        */
     
    -  *ticks = (int)((relusec + USEC_PER_TICK - 1) / USEC_PER_TICK);
    +  *ticks = (ssystime_t)((relusec + USEC_PER_TICK - 1) / USEC_PER_TICK);
       return OK;
     #endif
     }
    diff --git a/sched/mqueue/mq_timedreceive.c b/sched/mqueue/mq_timedreceive.c
    index 9df2a6ab61..096f057c59 100644
    --- a/sched/mqueue/mq_timedreceive.c
    +++ b/sched/mqueue/mq_timedreceive.c
    @@ -230,7 +230,7 @@ ssize_t mq_timedreceive(mqd_t mqdes, FAR char *msg, size_t msglen,
     
       if (mqdes->msgq->msglist.head == NULL)
         {
    -      int ticks;
    +      ssystime_t ticks;
     
           /* Convert the timespec to clock ticks.  We must have interrupts
            * disabled here so that this time stays valid until the wait begins.
    diff --git a/sched/mqueue/mq_timedsend.c b/sched/mqueue/mq_timedsend.c
    index 83e25515eb..98f3221082 100644
    --- a/sched/mqueue/mq_timedsend.c
    +++ b/sched/mqueue/mq_timedsend.c
    @@ -173,7 +173,7 @@ int mq_timedsend(mqd_t mqdes, FAR const char *msg, size_t msglen, int prio,
       FAR struct mqueue_inode_s *msgq;
       FAR struct mqueue_msg_s *mqmsg = NULL;
       irqstate_t flags;
    -  int ticks;
    +  ssystime_t ticks;
       int result;
       int ret = ERROR;
     
    diff --git a/sched/pthread/pthread_condtimedwait.c b/sched/pthread/pthread_condtimedwait.c
    index 22ce470770..98521665fd 100644
    --- a/sched/pthread/pthread_condtimedwait.c
    +++ b/sched/pthread/pthread_condtimedwait.c
    @@ -169,7 +169,7 @@ int pthread_cond_timedwait(FAR pthread_cond_t *cond, FAR pthread_mutex_t *mutex,
       FAR struct tcb_s *rtcb = this_task();
       irqstate_t flags;
       uint16_t oldstate;
    -  int ticks;
    +  ssystime_t ticks;
       int mypid = (int)getpid();
       int ret = OK;
       int status;
    diff --git a/sched/pthread/pthread_create.c b/sched/pthread/pthread_create.c
    index 4fbf646424..23ebd95489 100644
    --- a/sched/pthread/pthread_create.c
    +++ b/sched/pthread/pthread_create.c
    @@ -358,8 +358,8 @@ int pthread_create(FAR pthread_t *thread, FAR const pthread_attr_t *attr,
       if (policy == SCHED_SPORADIC)
         {
           FAR struct sporadic_s *sporadic;
    -      int repl_ticks;
    -      int budget_ticks;
    +      ssystime_t repl_ticks;
    +      ssystime_t budget_ticks;
     
           /* Convert timespec values to system clock ticks */
     
    diff --git a/sched/sched/sched_getparam.c b/sched/sched/sched_getparam.c
    index 155049ff1f..72833d9471 100644
    --- a/sched/sched/sched_getparam.c
    +++ b/sched/sched/sched_getparam.c
    @@ -127,8 +127,10 @@ int sched_getparam (pid_t pid, FAR struct sched_param *param)
                   param->sched_ss_low_priority = (int)sporadic->low_priority;
                   param->sched_ss_max_repl     = (int)sporadic->max_repl;
     
    -              clock_ticks2time((int)sporadic->repl_period, ¶m->sched_ss_repl_period);
    -              clock_ticks2time((int)sporadic->budget, ¶m->sched_ss_init_budget);
    +              clock_ticks2time((ssystime_t)sporadic->repl_period,
    +                               ¶m->sched_ss_repl_period);
    +              clock_ticks2time((ssystime_t)sporadic->budget,
    +                               ¶m->sched_ss_init_budget);
                 }
               else
                 {
    diff --git a/sched/sched/sched_setparam.c b/sched/sched/sched_setparam.c
    index 824d51b53b..93bfccfe43 100644
    --- a/sched/sched/sched_setparam.c
    +++ b/sched/sched/sched_setparam.c
    @@ -134,8 +134,8 @@ int sched_setparam(pid_t pid, FAR const struct sched_param *param)
         {
           FAR struct sporadic_s *sporadic;
           irqstate_t flags;
    -      int repl_ticks;
    -      int budget_ticks;
    +      ssystime_t repl_ticks;
    +      ssystime_t budget_ticks;
     
           if (param->sched_ss_max_repl < 1 ||
               param->sched_ss_max_repl > CONFIG_SCHED_SPORADIC_MAXREPL)
    diff --git a/sched/sched/sched_setscheduler.c b/sched/sched/sched_setscheduler.c
    index 20026e7ec9..58fb3d0969 100644
    --- a/sched/sched/sched_setscheduler.c
    +++ b/sched/sched/sched_setscheduler.c
    @@ -180,8 +180,8 @@ int sched_setscheduler(pid_t pid, int policy,
           case SCHED_SPORADIC:
             {
               FAR struct sporadic_s *sporadic;
    -          int repl_ticks;
    -          int budget_ticks;
    +          ssystime_t repl_ticks;
    +          ssystime_t budget_ticks;
     
               if (param->sched_ss_max_repl < 1 ||
                   param->sched_ss_max_repl > CONFIG_SCHED_SPORADIC_MAXREPL)
    diff --git a/sched/semaphore/sem_timedwait.c b/sched/semaphore/sem_timedwait.c
    index 23c16cc2d5..2ab32f6b86 100644
    --- a/sched/semaphore/sem_timedwait.c
    +++ b/sched/semaphore/sem_timedwait.c
    @@ -98,7 +98,7 @@ int sem_timedwait(FAR sem_t *sem, FAR const struct timespec *abstime)
     {
       FAR struct tcb_s *rtcb = this_task();
       irqstate_t flags;
    -  int        ticks;
    +  ssystime_t ticks;
       int        errcode;
       int        ret = ERROR;
     
    diff --git a/sched/signal/sig_nanosleep.c b/sched/signal/sig_nanosleep.c
    index 5b3a461b53..1e8163e8a3 100644
    --- a/sched/signal/sig_nanosleep.c
    +++ b/sched/signal/sig_nanosleep.c
    @@ -170,7 +170,7 @@ int nanosleep(FAR const struct timespec *rqtp, FAR struct timespec *rmtp)
         {
           systime_t elapsed;
           systime_t remaining;
    -      int ticks;
    +      ssystime_t ticks;
     
           /* REVISIT: The conversion from time to ticks and back could
            * be avoided.  clock_timespec_subtract() would be used instead
    @@ -192,16 +192,16 @@ int nanosleep(FAR const struct timespec *rqtp, FAR struct timespec *rmtp)
            * amount of time that we failed to wait.
            */
     
    -      if (elapsed >= (uint32_t)ticks)
    +      if (elapsed >= (systime_t)ticks)
             {
               remaining = 0;
             }
           else
             {
    -          remaining = (uint32_t)ticks - elapsed;
    +          remaining = (systime_t)ticks - elapsed;
             }
     
    -      (void)clock_ticks2time((int)remaining, rmtp);
    +      (void)clock_ticks2time((ssystime_t)remaining, rmtp);
         }
     
       leave_critical_section(flags);
    diff --git a/sched/timer/timer_gettime.c b/sched/timer/timer_gettime.c
    index c1e58899b4..25e0168765 100644
    --- a/sched/timer/timer_gettime.c
    +++ b/sched/timer/timer_gettime.c
    @@ -86,7 +86,7 @@
     int timer_gettime(timer_t timerid, FAR struct itimerspec *value)
     {
       FAR struct posix_timer_s *timer = (FAR struct posix_timer_s *)timerid;
    -  int ticks;
    +  ssystime_t ticks;
     
       if (!timer || !value)
         {
    diff --git a/sched/timer/timer_settime.c b/sched/timer/timer_settime.c
    index aa6007f95a..9e1fb5d4b2 100644
    --- a/sched/timer/timer_settime.c
    +++ b/sched/timer/timer_settime.c
    @@ -304,7 +304,7 @@ int timer_settime(timer_t timerid, int flags,
     {
       FAR struct posix_timer_s *timer = (FAR struct posix_timer_s *)timerid;
       irqstate_t intflags;
    -  int delay;
    +  ssystime_t delay;
       int ret = OK;
     
       /* Some sanity checks */
    @@ -332,7 +332,11 @@ int timer_settime(timer_t timerid, int flags,
     
       if (value->it_interval.tv_sec > 0 || value->it_interval.tv_nsec > 0)
         {
    -       (void)clock_time2ticks(&value->it_interval, &timer->pt_delay);
    +       (void)clock_time2ticks(&value->it_interval, &delay);
    +
    +       /* REVISIT: Should pt_delay be ssystime_t? */
    +
    +       timer->pt_delay = (int)delay;
         }
       else
         {
    @@ -379,6 +383,10 @@ int timer_settime(timer_t timerid, int flags,
     
       if (delay > 0)
         {
    +      /* REVISIT: Should pt_last be ssystime_t? Should wd_start delay be
    +       *          ssystime_t?
    +       */
    +
           timer->pt_last = delay;
           ret = wd_start(timer->pt_wdog, delay, (wdentry_t)timer_timeout,
                          1, (uint32_t)((wdparm_t)timer));
    -- 
    GitLab
    
    
    From 33ddaa0b10dc59e89a261697a1f39325f0ad7fb4 Mon Sep 17 00:00:00 2001
    From: Jussi Kivilinna 
    Date: Fri, 21 Apr 2017 08:55:07 -0600
    Subject: [PATCH 542/990] clock: add testing for 32-bit overflow of 64-bit
     system timer
    
    ---
     sched/clock/clock_initialize.c | 44 ++++++++++++++++++++++++++++++++--
     1 file changed, 42 insertions(+), 2 deletions(-)
    
    diff --git a/sched/clock/clock_initialize.c b/sched/clock/clock_initialize.c
    index 82bf02b985..d8a7b13497 100644
    --- a/sched/clock/clock_initialize.c
    +++ b/sched/clock/clock_initialize.c
    @@ -68,6 +68,18 @@
     #define SEC_PER_HOUR ((time_t)60 * SEC_PER_MIN)
     #define SEC_PER_DAY  ((time_t)24 * SEC_PER_HOUR)
     
    +#if defined(CONFIG_DEBUG_FEATURES) && defined(CONFIG_SYSTEM_TIME64)
    +/* Initial system timer ticks value close to maximum 32-bit value, to test
    + * 64-bit system-timer after going over 32-bit value. This is to make errors
    + * of casting 64-bit system-timer to 32-bit variables more visible.
    + */
    +
    +#  define INITIAL_SYSTEM_TIMER_TICKS \
    +          ((uint64_t)(UINT32_MAX - (TICK_PER_SEC * 5)))
    +#else
    +#  define INITIAL_SYSTEM_TIMER_TICKS 0
    +#endif
    +
     /****************************************************************************
      * Public Data
      ****************************************************************************/
    @@ -192,8 +204,36 @@ static void clock_inittime(void)
       clock_basetime(&g_basetime);
     #endif
     #ifndef CONFIG_SCHED_TICKLESS
    -  g_system_timer = 0;
    -#endif
    +  g_system_timer = INITIAL_SYSTEM_TIMER_TICKS;
    +  if (g_system_timer > 0)
    +    {
    +      struct timespec ts;
    +
    +      (void)clock_ticks2time((ssystime_t)g_system_timer, &ts);
    +
    +      /* Adjust base time to hide initial timer ticks. */
    +
    +      g_basetime.tv_sec  -= ts.tv_sec;
    +      g_basetime.tv_nsec -= ts.tv_nsec;
    +      while (g_basetime.tv_nsec < 0)
    +        {
    +          g_basetime.tv_nsec += NSEC_PER_SEC;
    +          g_basetime.tv_sec--;
    +        }
    +
    +#ifdef CONFIG_CLOCK_MONOTONIC
    +      /* Adjust monotonic clock offset to hide initial timer ticks. */
    +
    +      g_monotonic_basetime.tv_sec  -= ts.tv_sec;
    +      g_monotonic_basetime.tv_nsec -= ts.tv_nsec;
    +      while (g_monotonic_basetime.tv_nsec < 0)
    +        {
    +          g_monotonic_basetime.tv_nsec += NSEC_PER_SEC;
    +          g_monotonic_basetime.tv_sec--;
    +        }
    +#endif /* CONFIG_CLOCK_MONOTONIC */
    +    }
    +#endif /* !CONFIG_SCHED_TICKLESS */
     #else
       clock_inittimekeeping();
     #endif
    -- 
    GitLab
    
    
    From 7ed8e4166b7af4a1c9474e165f59cb552bbf5504 Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Fri, 21 Apr 2017 10:33:24 -0600
    Subject: [PATCH 543/990] MAC header: Keep IOCTL-related structures together.
    
    ---
     .../wireless/ieee802154/ieee802154_mac.h      | 48 +++++++++----------
     .../wireless/ieee802154/ieee802154_radio.h    |  2 +-
     2 files changed, 25 insertions(+), 25 deletions(-)
    
    diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h
    index dfc5aa7696..f4fc2b7d18 100644
    --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h
    +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h
    @@ -1292,30 +1292,6 @@ struct ieee802154_poll_conf_s
       enum ieee802154_status_e status;
     };
     
    -/* A pointer to this structure is passed as the argument of each IOCTL
    - * command.
    - */
    -
    -union ieee802154_macarg_u
    -{
    -  struct ieee802154_assoc_req_s    assocreq;    /* MAC802154IOC_MLME_ASSOC_REQUEST */
    -  struct ieee802154_assoc_resp_s   assocresp;   /* MAC802154IOC_MLME_ASSOC_RESPONSE */
    -  struct ieee802154_disassoc_req_s disassocreq; /* MAC802154IOC_MLME_DISASSOC_REQUEST */
    -  struct ieee802154_get_req_s      getreq;      /* MAC802154IOC_MLME_GET_REQUEST */
    -  struct ieee802154_gts_req_s      gtsreq;      /* MAC802154IOC_MLME_GTS_REQUEST */
    -  struct ieee802154_orphan_resp_s  orphanresp;  /* MAC802154IOC_MLME_ORPHAN_RESPONSE */
    -  struct ieee802154_reset_req_s    resetreq;    /* MAC802154IOC_MLME_RESET_REQUEST */
    -  struct ieee802154_rxenable_req_s rxenabreq;   /* MAC802154IOC_MLME_RXENABLE_REQUEST */
    -  struct ieee802154_scan_req_s     scanreq;     /* MAC802154IOC_MLME_SCAN_REQUEST */
    -  struct ieee802154_set_req_s      setreq;      /* MAC802154IOC_MLME_SET_REQUEST */
    -  struct ieee802154_start_req_s    startreq;    /* MAC802154IOC_MLME_START_REQUEST */
    -  struct ieee802154_sync_req_s     syncreq;     /* MAC802154IOC_MLME_SYNC_REQUEST */
    -  struct ieee802154_poll_req_s     pollreq;     /* MAC802154IOC_MLME_POLL_REQUEST */
    -  /* To be determined */                        /* MAC802154IOC_MLME_DPS_REQUEST */
    -  /* To be determined */                        /* MAC802154IOC_MLME_SOUNDING_REQUEST */
    -  /* To be determined */                        /* MAC802154IOC_MLME_CALIBRATE_REQUEST */
    -};
    -
     union ieee802154_mlme_notify_u
     {
       struct ieee802154_assoc_conf_s       assocconf;
    @@ -1345,6 +1321,30 @@ union ieee802154_mcps_notify_u
       struct ieee802154_data_ind_s         dataind;
     };
     
    +/* A pointer to this structure is passed as the argument of each IOCTL
    + * command.
    + */
    +
    +union ieee802154_macarg_u
    +{
    +  struct ieee802154_assoc_req_s    assocreq;    /* MAC802154IOC_MLME_ASSOC_REQUEST */
    +  struct ieee802154_assoc_resp_s   assocresp;   /* MAC802154IOC_MLME_ASSOC_RESPONSE */
    +  struct ieee802154_disassoc_req_s disassocreq; /* MAC802154IOC_MLME_DISASSOC_REQUEST */
    +  struct ieee802154_get_req_s      getreq;      /* MAC802154IOC_MLME_GET_REQUEST */
    +  struct ieee802154_gts_req_s      gtsreq;      /* MAC802154IOC_MLME_GTS_REQUEST */
    +  struct ieee802154_orphan_resp_s  orphanresp;  /* MAC802154IOC_MLME_ORPHAN_RESPONSE */
    +  struct ieee802154_reset_req_s    resetreq;    /* MAC802154IOC_MLME_RESET_REQUEST */
    +  struct ieee802154_rxenable_req_s rxenabreq;   /* MAC802154IOC_MLME_RXENABLE_REQUEST */
    +  struct ieee802154_scan_req_s     scanreq;     /* MAC802154IOC_MLME_SCAN_REQUEST */
    +  struct ieee802154_set_req_s      setreq;      /* MAC802154IOC_MLME_SET_REQUEST */
    +  struct ieee802154_start_req_s    startreq;    /* MAC802154IOC_MLME_START_REQUEST */
    +  struct ieee802154_sync_req_s     syncreq;     /* MAC802154IOC_MLME_SYNC_REQUEST */
    +  struct ieee802154_poll_req_s     pollreq;     /* MAC802154IOC_MLME_POLL_REQUEST */
    +  /* To be determined */                        /* MAC802154IOC_MLME_DPS_REQUEST */
    +  /* To be determined */                        /* MAC802154IOC_MLME_SOUNDING_REQUEST */
    +  /* To be determined */                        /* MAC802154IOC_MLME_CALIBRATE_REQUEST */
    +};
    +
     #ifdef CONFIG_NET_6LOWPAN
     /* For the case of network IOCTLs, the network IOCTL to the MAC network
      * driver will include a device name like "wpan0" as the destination of
    diff --git a/include/nuttx/wireless/ieee802154/ieee802154_radio.h b/include/nuttx/wireless/ieee802154/ieee802154_radio.h
    index 3dcde47e83..be2876468b 100644
    --- a/include/nuttx/wireless/ieee802154/ieee802154_radio.h
    +++ b/include/nuttx/wireless/ieee802154/ieee802154_radio.h
    @@ -99,7 +99,7 @@
     
     #define PHY802154IOC_ENERGYDETECT     _PHY802154IOC(0x0011)
     
    -#define EADDR_SIZE                    8  /* REVISIT */
    +#define EADDR_SIZE                    8  /* Extended address size */
     
     /****************************************************************************
      * Public Types
    -- 
    GitLab
    
    
    From 795e70a9522231b1c1a5e8c0bbcbcef2b803f276 Mon Sep 17 00:00:00 2001
    From: Anthony Merlino 
    Date: Fri, 21 Apr 2017 13:06:18 -0400
    Subject: [PATCH 544/990] wireless/ieee802154: Work on packet reception at
     radio layer (MRF24J40)
    
    ---
     drivers/wireless/ieee802154/mrf24j40.c        | 36 +++++++++++++++----
     .../wireless/ieee802154/ieee802154_radio.h    | 16 +++++----
     net/sixlowpan/sixlowpan_framelist.c           |  2 +-
     3 files changed, 39 insertions(+), 15 deletions(-)
    
    diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c
    index fe34ab1259..b6e155bd93 100644
    --- a/drivers/wireless/ieee802154/mrf24j40.c
    +++ b/drivers/wireless/ieee802154/mrf24j40.c
    @@ -1618,6 +1618,8 @@ static int mrf24j40_rxenable(FAR struct ieee802154_radio_s *radio, bool state,
     
     static void mrf24j40_irqwork_rx(FAR struct mrf24j40_radio_s *dev)
     {
    +  FAR struct iob_s *iob;
    +  struct ieee802154_txdesc_s rxdesc;
       uint32_t addr;
       uint32_t index;
       uint8_t  reg;
    @@ -1634,25 +1636,46 @@ static void mrf24j40_irqwork_rx(FAR struct mrf24j40_radio_s *dev)
     
       mrf24j40_setreg(dev->spi, MRF24J40_BBREG1, MRF24J40_BBREG1_RXDECINV);
     
    +
    +  /* Allocate an IOB to put the packet in */
    +
    +  iob = iob_alloc(true);
    +  DEBUGASSERT(iob != NULL);
    +
    +  iob->io_flink  = NULL;
    +  iob->io_len    = 0;
    +  iob->io_offset = 0;
    +  iob->io_pktlen = 0;
    +
       /* Read packet */
     
       addr = MRF24J40_RXBUF_BASE;
    -  dev->radio.rxbuf->len = mrf24j40_getreg(dev->spi, addr++);
    +
    +  iob->io_len= mrf24j40_getreg(dev->spi, addr++);
       /* wlinfo("len %3d\n", dev->radio.rxbuf->len); */
     
    -  for (index = 0; index < dev->radio.rxbuf->len; index++)
    +  /* TODO: This needs to be changed.  It is inefficient to do the SPI read byte
    +   * by byte */
    +
    +  for (index = 0; index < iob->io_len; index++)
         {
    -      dev->radio.rxbuf->data[index] = mrf24j40_getreg(dev->spi, addr++);
    +      iob->io_data[index] = mrf24j40_getreg(dev->spi, addr++);
         }
     
    -  dev->radio.rxbuf->lqi  = mrf24j40_getreg(dev->spi, addr++);
    -  dev->radio.rxbuf->rssi = mrf24j40_getreg(dev->spi, addr++);
    +  /* Copy meta-data into RX descriptor */
    +
    +  rxdesc.lqi  = mrf24j40_getreg(dev->spi, addr++);
    +  rxdesc.rssi = mrf24j40_getreg(dev->spi, addr++);
     
       /* Reduce len by 2, we only receive frames with correct crc, no check
        * required.
        */
     
    -  dev->radio.rxbuf->len -= 2;
    +  iob->io_len -= 2;
    +
    +  /* Callback the receiver in the next highest layer */
    +
    +  dev->radiocb->rx_frame(dev->radiocb, &rxdesc, iob);
     
       /* Enable reception of next packet by flushing the fifo.
        * This is an MRF24J40 errata (no. 1).
    @@ -1664,7 +1687,6 @@ static void mrf24j40_irqwork_rx(FAR struct mrf24j40_radio_s *dev)
     
       mrf24j40_setreg(dev->spi, MRF24J40_BBREG1, 0);
     
    -  sem_post(&dev->radio.rxsem);
     }
     
     /****************************************************************************
    diff --git a/include/nuttx/wireless/ieee802154/ieee802154_radio.h b/include/nuttx/wireless/ieee802154/ieee802154_radio.h
    index be2876468b..272d5fdf2c 100644
    --- a/include/nuttx/wireless/ieee802154/ieee802154_radio.h
    +++ b/include/nuttx/wireless/ieee802154/ieee802154_radio.h
    @@ -168,6 +168,12 @@ struct ieee802154_txdesc_s
       /* TODO: Add slotting information for GTS transactions */
     };
     
    +struct ieee802154_rxdesc_s
    +{
    +  uint8_t lqi;
    +  uint8_t rssi;
    +};
    +
     struct ieee802154_radiocb_s
     {
       CODE int (*poll_csma) (FAR struct ieee802154_radiocb_s *radiocb,
    @@ -178,6 +184,9 @@ struct ieee802154_radiocb_s
                  FAR const struct ieee802154_txdesc_s *tx_desc);
       CODE int (*txdone_gts) (FAR struct ieee802154_radiocb_s *radiocb,
                  FAR const struct ieee802154_txdesc_s *tx_desc);
    +  CODE int (*rx_frame) (FAR struct ieee802154_radiocb_s *radiocb,
    +             FAR const struct ieee8021254_rxdesc_s *rx_desc,
    +             FAR struct iob_s *frame);
     };
     
     struct ieee802154_radio_s; /* Forward reference */
    @@ -197,13 +206,6 @@ struct ieee802154_radioops_s
     struct ieee802154_radio_s
     {
       FAR const struct ieee802154_radioops_s *ops;
    -
    -  /* Packet reception management */
    -
    -  struct ieee802154_packet_s *rxbuf; /* packet reception buffer, filled by
    -                                      * rx interrupt, NULL if rx not enabled */
    -  sem_t rxsem;                       /* Semaphore posted after reception of
    -                                      * a packet */
     };
     
     #ifdef __cplusplus
    diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c
    index 79e653d10b..ee9487a101 100644
    --- a/net/sixlowpan/sixlowpan_framelist.c
    +++ b/net/sixlowpan/sixlowpan_framelist.c
    @@ -77,7 +77,7 @@
      */
     
     #if CONFIG_NET_6LOWPAN_MTU > (CONFIG_IOB_BUFSIZE * CONFIG_IOB_NBUFFERS)
    -#  error Not enough IOBs to hold one full IEEE802.14.5 packet
    +#  error Not enough IOBs to hold one full 6LoWPAN packet
     #endif
     
     /****************************************************************************
    -- 
    GitLab
    
    
    From c071cde2204161963e06ab6cc495adbdb4885d63 Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Fri, 21 Apr 2017 12:29:38 -0600
    Subject: [PATCH 545/990] Cosmetic changes to some comments.
    
    ---
     include/nuttx/wireless/ieee802154/ieee802154_mac.h | 2 ++
     1 file changed, 2 insertions(+)
    
    diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h
    index f4fc2b7d18..2f78ec443f 100644
    --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h
    +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h
    @@ -1327,6 +1327,8 @@ union ieee802154_mcps_notify_u
     
     union ieee802154_macarg_u
     {
    +  /* To be determined */                        /* MAC802154IOC_MCPS_REGISTER */
    +  /* To be determined */                        /* MAC802154IOC_MLME_REGISTER */
       struct ieee802154_assoc_req_s    assocreq;    /* MAC802154IOC_MLME_ASSOC_REQUEST */
       struct ieee802154_assoc_resp_s   assocresp;   /* MAC802154IOC_MLME_ASSOC_RESPONSE */
       struct ieee802154_disassoc_req_s disassocreq; /* MAC802154IOC_MLME_DISASSOC_REQUEST */
    -- 
    GitLab
    
    
    From b1c8f008d62c2c3f9a7502aefe8f98b7db6c2480 Mon Sep 17 00:00:00 2001
    From: Anthony Merlino 
    Date: Fri, 21 Apr 2017 14:57:15 -0400
    Subject: [PATCH 546/990] wireless/ieee802154: Simplifies TX completion
     interface.  Documents and cleans up some functions
    
    ---
     drivers/wireless/ieee802154/mrf24j40.c        |   4 +-
     .../wireless/ieee802154/ieee802154_radio.h    |   4 +-
     wireless/ieee802154/mac802154.c               | 350 +++++++++++++-----
     3 files changed, 269 insertions(+), 89 deletions(-)
    
    diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c
    index b6e155bd93..1e07d1126b 100644
    --- a/drivers/wireless/ieee802154/mrf24j40.c
    +++ b/drivers/wireless/ieee802154/mrf24j40.c
    @@ -1520,7 +1520,7 @@ static void mrf24j40_irqwork_txnorm(FAR struct mrf24j40_radio_s *dev)
     
       /* Inform the next layer of the transmission success/failure */
     
    -  dev->radiocb->txdone_csma(dev->radiocb, &dev->csma_desc.pub);
    +  dev->radiocb->txdone(dev->radiocb, &dev->csma_desc.pub);
     
       /* We are now done with the transaction */
     
    @@ -1566,7 +1566,7 @@ static void mrf24j40_irqwork_txgts(FAR struct mrf24j40_radio_s *dev,
     
       /* Inform the next layer of the transmission success/failure */
     
    -  dev->radiocb->txdone_gts(dev->radiocb, &dev->gts_desc[gts].pub);
    +  dev->radiocb->txdone(dev->radiocb, &dev->gts_desc[gts].pub);
     
       /* We are now done with the transaction */
     
    diff --git a/include/nuttx/wireless/ieee802154/ieee802154_radio.h b/include/nuttx/wireless/ieee802154/ieee802154_radio.h
    index 272d5fdf2c..58748b267a 100644
    --- a/include/nuttx/wireless/ieee802154/ieee802154_radio.h
    +++ b/include/nuttx/wireless/ieee802154/ieee802154_radio.h
    @@ -180,9 +180,7 @@ struct ieee802154_radiocb_s
                  FAR struct ieee802154_txdesc_s *tx_desc, FAR uint8_t *buf);
       CODE int (*poll_gts) (FAR struct ieee802154_radiocb_s *radiocb,
                  FAR struct ieee802154_txdesc_s *tx_desc, FAR uint8_t *buf);
    -  CODE int (*txdone_csma) (FAR struct ieee802154_radiocb_s *radiocb,
    -             FAR const struct ieee802154_txdesc_s *tx_desc);
    -  CODE int (*txdone_gts) (FAR struct ieee802154_radiocb_s *radiocb,
    +  CODE int (*txdone) (FAR struct ieee802154_radiocb_s *radiocb,
                  FAR const struct ieee802154_txdesc_s *tx_desc);
       CODE int (*rx_frame) (FAR struct ieee802154_radiocb_s *radiocb,
                  FAR const struct ieee8021254_rxdesc_s *rx_desc,
    diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c
    index 0977c72b92..51658893c0 100644
    --- a/wireless/ieee802154/mac802154.c
    +++ b/wireless/ieee802154/mac802154.c
    @@ -105,6 +105,9 @@ struct ieee802154_privmac_s
     
       sem_t exclsem; /* Support exclusive access */
     
    +  struct work_s tx_work;
    +  struct work_s rx_work;
    +
       /* Support a singly linked list of transactions that will be sent using the
        * CSMA algorithm.  On a non-beacon enabled PAN, these transactions will be
        * sent whenever. On a beacon-enabled PAN, these transactions will be sent
    @@ -125,6 +128,10 @@ struct ieee802154_privmac_s
       FAR struct mac802154_trans_s *indirect_head;
       FAR struct mac802154_trans_s *indirect_tail;
     
    +  FAR struct ieee802154_txdesc_s *txhead; /* Next TX descriptor to handle */
    +  FAR struct ieee802154_txdesc_s *txtail; /* Location to push TX descriptor */
    +  struct ieee802154_txdesc_s txtable[CONFIG_IEEE802154_NTXDESC];
    +
       /* MAC PIB attributes, grouped to save memory */
     
       /* Holds all address information (Extended, Short, and PAN ID) for the MAC. */
    @@ -262,6 +269,9 @@ static int mac802154_poll_gts(FAR struct ieee802154_radiocb_s *radiocb,
                                   FAR struct ieee802154_txdesc_s *tx_desc,
                                   FAR uint8_t *buf);
     
    +static int mac802154_txdone(FAR struct ieee802154_radiocb_s *radiocb,
    +                            FAR struct ieee802154_txdesc_s *tx_desc);
    +
     /****************************************************************************
      * Private Data
      ****************************************************************************/
    @@ -325,6 +335,258 @@ static int mac802154_applymib(FAR struct ieee802154_privmac_s *priv)
       return OK;
     }
     
    +/****************************************************************************
    + * Name: mac802154_poll_csma
    + *
    + * Description:
    + *   Called from the radio driver through the callback struct.  This function is
    + *   called when the radio has room for another CSMA transaction.  If the MAC
    + *   layer has a CSMA transaction, it copies it into the supplied buffer and
    + *   returns the length.  A descriptor is also populated with the transaction. 
    + *
    + ****************************************************************************/
    +
    +static int mac802154_poll_csma(FAR struct ieee802154_radiocb_s *radiocb,
    +                               FAR struct ieee802154_txdesc_s *tx_desc,
    +                               FAR uint8_t *buf)
    +{
    +  FAR struct mac802154_radiocb_s *cb =
    +    (FAR struct mac802154_radiocb_s *)radiocb;
    +  FAR struct ieee802154_privmac_s *priv;
    +  FAR struct mac802154_trans_s *trans;
    +
    +  DEBUGASSERT(cb != NULL && cb->priv != NULL);
    +  priv = cb->priv;
    +
    +  /* Get exclusive access to the driver structure.  We don't care about any
    +   * signals so if we see one, just go back to trying to get access again.
    +   */
    +
    +  while (mac802154_takesem(&priv->exclsem) != 0);
    +
    +  /* Check to see if there are any CSMA transactions waiting */
    +
    +  if (priv->csma_head)
    +    {
    +      /* Pop a CSMA transaction off the list */
    +
    +      trans = priv->csma_head;
    +      priv->csma_head = priv->csma_head->flink;
    +
    +      mac802154_givesem(&priv->exclsem);
    +
    +      /* Setup the transmit descriptor */
    +
    +      tx_desc->psdu_handle = trans->msdu_handle;
    +      tx_desc->psdu_length = trans->mhr_len + trans->d_len;
    +
    +      /* Copy the frame into the buffer */
    +
    +      memcpy(&buf[0], trans->mhr_buf, trans->mhr_len);
    +      memcpy(&buf[trans->mhr_len], trans->d_buf, trans->d_len);
    +
    +      /* Now that we've passed off the data, notify the waiting thread.
    +       * NOTE: The transaction was allocated on the waiting thread's stack so
    +       * it will be automatically deallocated when that thread awakens and
    +       * returns.
    +       */
    +
    +      sem_post(&trans->sem);
    +      return tx_desc->psdu_length;
    +    }
    +
    +  mac802154_givesem(&priv->exclsem);
    +  return 0;
    +}
    +
    +/****************************************************************************
    + * Name: mac802154_poll_gts
    + *
    + * Description:
    + *   Called from the radio driver through the callback struct.  This function is
    + *   called when the radio has room for another GTS transaction.  If the MAC
    + *   layer has a GTS transaction, it copies it into the supplied buffer and
    + *   returns the length.  A descriptor is also populated with the transaction. 
    + *
    + ****************************************************************************/
    +
    +static int mac802154_poll_gts(FAR struct ieee802154_radiocb_s *radiocb, 
    +                              FAR struct ieee802154_txdesc_s *tx_desc,
    +                              FAR uint8_t *buf)
    +{
    +  FAR struct mac802154_radiocb_s *cb =
    +    (FAR struct mac802154_radiocb_s *)radiocb;
    +  FAR struct ieee802154_privmac_s *priv;
    +  FAR struct mac802154_trans_s *trans;
    +  int ret = 0;
    +
    +  DEBUGASSERT(cb != NULL && cb->priv != NULL);
    +  priv = cb->priv;
    +
    +  /* Get exclusive access to the driver structure.  We don't care about any
    +   * signals so if we see one, just go back to trying to get access again.
    +   */
    +
    +  while (mac802154_takesem(&priv->exclsem) != 0);
    +
    +#warning Missing logic.
    +
    +  mac802154_givesem(&priv->exclsem);
    +
    +  return 0;
    +}
    +
    +/****************************************************************************
    + * Name: mac802154_txdone
    + *
    + * Description:
    + *   Called from the radio driver through the callback struct.  This function is
    + *   called when the radio has completed a transaction.  The txdesc passed gives
    + *   provides information about the completed transaction including the original
    + *   handle provided when the transaction was created and the status of the
    + *   transaction.  This function copies the descriptor and schedules work to
    + *   handle the transaction without blocking the radio.
    + *
    + ****************************************************************************/
    +
    +static int mac802154_txdone(FAR struct ieee802154_radiocb_s *radiocb,
    +                            FAR const struct ieee802154_txdesc_s *tx_desc)
    +{
    +  FAR struct mac802154_radiocb_s *cb =
    +    (FAR struct mac802154_radiocb_s *)radiocb;
    +  FAR struct ieee802154_privmac_s *priv;
    +  FAR struct ieee802154_txdesc_s *desc;
    +  int ret = 0;
    +
    +  DEBUGASSERT(cb != NULL && cb->priv != NULL);
    +  priv = cb->priv;
    +
    +  /* Get exclusive access to the driver structure.  We don't care about any
    +   * signals so if we see one, just go back to trying to get access again.
    +   */
    +
    +  while (mac802154_takesem(&priv->exclsem) != 0);
    +
    +  /* Allocate a tx_desc */
    +
    +  desc = kmm_zalloc(sizeof(struct ieee802154_txdesc_s));
    +  if (desc == NULL)
    +    {
    +      mac802154_givesem(&priv->exclsem);
    +
    +      return -ENOMEM; 
    +    }
    +  
    +  /* Copy the txdesc over and link it into our list */
    +
    +  memcpy(desc, tx_desc, sizeof(ieee802154_txdesc_s));
    +
    +  /* Link the descriptor */
    +
    +#warning Missing Logic!
    +
    +  mac802154_givesem(&priv->exclsem);
    +
    +  /* Schedule work with the work queue to process the completion further */
    +
    +  if (work_available(&priv->tx_work))
    +  {
    +    work_queue(MAC802154_WORK, &priv->tx_work, mac802154_txdone_worker,
    +               (FAR void *)dev, 0);
    +  }
    +}
    +
    +/****************************************************************************
    + * Name: mac802154_txdone_worker
    + *
    + * Description:
    + *   Worker function scheduled from mac802154_txdone.  This function pops any
    + *   TX descriptors off of the list and calls the next highest layers callback
    + *   to inform the layer of the completed transaction and the status of it.
    + *
    + ****************************************************************************/
    +
    +static void mac802154_txdone_worker(FAR void *arg)
    +{
    +  FAR struct ieee802154_privmanc_s *priv = 
    +    (FAR struct ieee802154_privmanc_s *)arg;
    +  
    +
    +}
    +
    +/****************************************************************************
    + * Name: mac802154_rxframe
    + *
    + * Description:
    + *   Called from the radio driver through the callback struct.  This function is
    + *   called when the radio has received a frame. The frame is passed in an iob,
    + *   so that we can free it when we are done processing.  A pointer to the RX
    + *   descriptor is passed along with the iob, but it must be copied here as it
    + *   is allocated directly on the caller's stack.  We simply link the frame,
    + *   copy the RX descriptor, and schedule a worker to process the frame later so
    + *   that we do not hold up the radio. 
    + *
    + ****************************************************************************/
    +
    +static void mac802154_rxframe(FAR struct ieee802154_radiocb_s *radiocb,
    +                              FAR struct ieee802154_rxdesc_s *rx_desc,
    +                              FAR struct iob_s *frame)
    +{
    +  FAR struct mac802154_radiocb_s *cb =
    +    (FAR struct mac802154_radiocb_s *)radiocb;
    +  FAR struct ieee802154_privmac_s *priv;
    +  FAR struct ieee802154_txdesc_s *desc;
    +  int ret = 0;
    +
    +  DEBUGASSERT(cb != NULL && cb->priv != NULL);
    +  priv = cb->priv;
    +
    +  /* Get exclusive access to the driver structure.  We don't care about any
    +   * signals so if we see one, just go back to trying to get access again.
    +   */
    +
    +  while (mac802154_takesem(&priv->exclsem) != 0);
    +
    +  /* TODO: Copy the frame descriptor to some type of list */
    +
    +  /* Push the iob onto the tail of the frame list for processing */
    +
    +  priv->rxframes_tail->io_flink = iob;
    +  priv->rxframes_tail = iob;
    +
    +  mac802154_givesem(&priv->exclsem);
    +
    +  /* Schedule work with the work queue to process the completion further */
    +
    +  if (work_available(&priv->rx_work))
    +    {
    +      work_queue(MAC802154_WORK, &priv->rx_work, mac802154_rxframe_worker,
    +                 (FAR void *)priv, 0);
    +    }
    +}
    +
    +/****************************************************************************
    + * Name: mac802154_rxframe_worker
    + *
    + * Description:
    + *   Worker function scheduled from mac802154_rxframe.  This function processes
    + *   any frames in the list.  Frames intended to be consumed by the MAC layer
    + *   will not produce any callbacks to the next highest layer.  Frames intended
    + *   for the application layer will be forwarded to them.
    + *
    + ****************************************************************************/
    +
    +static void mac802154_rxframe_worker(FAR void *arg)
    +{
    +  FAR struct ieee802154_privmac_s *priv =
    +    (FAR struct ieee802154_privmac_s *)arg;
    +  
    +  /* The radio layer is responsible for handling all ACKs and retries. If for
    +   * some reason an ACK gets here, just throw it out */
    +
    +}
    +
    +
     /****************************************************************************
      * Public Functions
      ****************************************************************************/
    @@ -379,9 +641,10 @@ MACHANDLE mac802154_create(FAR struct ieee802154_radio_s *radiodev)
     
       mac->radiocb.priv = mac;
     
    -  radiocb             = &mac->radiocb.cb;
    -  radiocb->poll_csma  = mac802154_poll_csma;
    -  radiocb->poll_gts   = mac802154_poll_gts;
    +  radiocb              = &mac->radiocb.cb;
    +  radiocb->poll_csma   = mac802154_poll_csma;
    +  radiocb->poll_gts    = mac802154_poll_gts;
    +  radiocb->txdone      = mac802154_txdone;
     
       /* Bind our callback structure */
     
    @@ -710,87 +973,6 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req)
       return OK;
     }
     
    -/* Called from interrupt level or worker thread with interrupts disabled */
    -
    -static int mac802154_poll_csma(FAR struct ieee802154_radiocb_s *radiocb,
    -                               FAR struct ieee802154_txdesc_s *tx_desc,
    -                               FAR uint8_t *buf)
    -{
    -  FAR struct mac802154_radiocb_s *cb =
    -    (FAR struct mac802154_radiocb_s *)radiocb;
    -  FAR struct ieee802154_privmac_s *priv;
    -  FAR struct mac802154_trans_s *trans;
    -  int ret = 0;
    -
    -  DEBUGASSERT(cb != NULL && cb->priv != NULL);
    -  priv = cb->priv;
    -
    -  /* Get exclusive access to the driver structure.  We don't care about any
    -   * signals so if we see one, just go back to trying to get access again.
    -   */
    -
    -  while (mac802154_takesem(&priv->exclsem) != 0);
    -
    -  /* Check to see if there are any CSMA transactions waiting */
    -
    -  if (priv->csma_head)
    -    {
    -      /* Pop a CSMA transaction off the list */
    -
    -      trans = priv->csma_head;
    -      priv->csma_head = priv->csma_head->flink;
    -
    -      /* Setup the transmit descriptor */
    -
    -      tx_desc->psdu_handle = trans->msdu_handle;
    -      tx_desc->psdu_length = trans->mhr_len + trans->d_len;
    -
    -      /* Copy the frame into the buffer */
    -
    -      memcpy(&buf[0], trans->mhr_buf, trans->mhr_len);
    -      memcpy(&buf[trans->mhr_len], trans->d_buf, trans->d_len);
    -
    -      /* Now that we've passed off the data, notify the waiting thread.
    -       * NOTE: The transaction was allocated on the waiting thread's stack so
    -       * it will be automatically deallocated when that thread awakens and
    -       * returns.
    -       */
    -
    -      sem_post(&trans->sem);
    -
    -      ret = tx_desc->psdu_length;
    -    }
    -
    -  mac802154_givesem(&priv->exclsem);
    -
    -  return ret;
    -}
    -
    -static int mac802154_poll_gts(FAR struct ieee802154_radiocb_s *radiocb, 
    -                              FAR struct ieee802154_txdesc_s *tx_desc,
    -                              FAR uint8_t *buf)
    -{
    -  FAR struct mac802154_radiocb_s *cb =
    -    (FAR struct mac802154_radiocb_s *)radiocb;
    -  FAR struct ieee802154_privmac_s *priv;
    -  FAR struct mac802154_trans_s *trans;
    -  int ret = 0;
    -
    -  DEBUGASSERT(cb != NULL && cb->priv != NULL);
    -  priv = cb->priv;
    -
    -  /* Get exclusive access to the driver structure.  We don't care about any
    -   * signals so if we see one, just go back to trying to get access again.
    -   */
    -
    -  while (mac802154_takesem(&priv->exclsem) != 0);
    -
    -#warning Missing logic.
    -
    -  mac802154_givesem(&priv->exclsem);
    -
    -  return 0;
    -}
     
     /****************************************************************************
      * Name: mac802154_req_purge
    -- 
    GitLab
    
    
    From b2292cd2cbef6af4693328e44f282b6ac027caf7 Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Fri, 21 Apr 2017 13:21:43 -0600
    Subject: [PATCH 547/990] Some trivial spacing changes from review of last PR;
     Remove some dangling whitespace at the end of lines.
    
    ---
     wireless/ieee802154/mac802154.c        | 35 ++++++++++++--------------
     wireless/ieee802154/mac802154_device.c |  2 +-
     wireless/ieee802154/mac802154_netdev.c | 32 +++++++++++------------
     3 files changed, 33 insertions(+), 36 deletions(-)
    
    diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c
    index 51658893c0..ca877d5442 100644
    --- a/wireless/ieee802154/mac802154.c
    +++ b/wireless/ieee802154/mac802154.c
    @@ -58,7 +58,7 @@
     /****************************************************************************
      * Private Types
      ****************************************************************************/
    - 
    +
     struct mac802154_trans_s
     {
       /* Supports a singly linked list */
    @@ -265,7 +265,7 @@ static int mac802154_poll_csma(FAR struct ieee802154_radiocb_s *radiocb,
                                    FAR struct ieee802154_txdesc_s *tx_desc,
                                    FAR uint8_t *buf);
     
    -static int mac802154_poll_gts(FAR struct ieee802154_radiocb_s *radiocb, 
    +static int mac802154_poll_gts(FAR struct ieee802154_radiocb_s *radiocb,
                                   FAR struct ieee802154_txdesc_s *tx_desc,
                                   FAR uint8_t *buf);
     
    @@ -342,7 +342,7 @@ static int mac802154_applymib(FAR struct ieee802154_privmac_s *priv)
      *   Called from the radio driver through the callback struct.  This function is
      *   called when the radio has room for another CSMA transaction.  If the MAC
      *   layer has a CSMA transaction, it copies it into the supplied buffer and
    - *   returns the length.  A descriptor is also populated with the transaction. 
    + *   returns the length.  A descriptor is also populated with the transaction.
      *
      ****************************************************************************/
     
    @@ -406,11 +406,11 @@ static int mac802154_poll_csma(FAR struct ieee802154_radiocb_s *radiocb,
      *   Called from the radio driver through the callback struct.  This function is
      *   called when the radio has room for another GTS transaction.  If the MAC
      *   layer has a GTS transaction, it copies it into the supplied buffer and
    - *   returns the length.  A descriptor is also populated with the transaction. 
    + *   returns the length.  A descriptor is also populated with the transaction.
      *
      ****************************************************************************/
     
    -static int mac802154_poll_gts(FAR struct ieee802154_radiocb_s *radiocb, 
    +static int mac802154_poll_gts(FAR struct ieee802154_radiocb_s *radiocb,
                                   FAR struct ieee802154_txdesc_s *tx_desc,
                                   FAR uint8_t *buf)
     {
    @@ -474,9 +474,9 @@ static int mac802154_txdone(FAR struct ieee802154_radiocb_s *radiocb,
         {
           mac802154_givesem(&priv->exclsem);
     
    -      return -ENOMEM; 
    +      return -ENOMEM;
         }
    -  
    +
       /* Copy the txdesc over and link it into our list */
     
       memcpy(desc, tx_desc, sizeof(ieee802154_txdesc_s));
    @@ -490,10 +490,10 @@ static int mac802154_txdone(FAR struct ieee802154_radiocb_s *radiocb,
       /* Schedule work with the work queue to process the completion further */
     
       if (work_available(&priv->tx_work))
    -  {
    -    work_queue(MAC802154_WORK, &priv->tx_work, mac802154_txdone_worker,
    -               (FAR void *)dev, 0);
    -  }
    +    {
    +      work_queue(MAC802154_WORK, &priv->tx_work, mac802154_txdone_worker,
    +                 (FAR void *)dev, 0);
    +    }
     }
     
     /****************************************************************************
    @@ -508,10 +508,8 @@ static int mac802154_txdone(FAR struct ieee802154_radiocb_s *radiocb,
     
     static void mac802154_txdone_worker(FAR void *arg)
     {
    -  FAR struct ieee802154_privmanc_s *priv = 
    +  FAR struct ieee802154_privmanc_s *priv =
         (FAR struct ieee802154_privmanc_s *)arg;
    -  
    -
     }
     
     /****************************************************************************
    @@ -524,7 +522,7 @@ static void mac802154_txdone_worker(FAR void *arg)
      *   descriptor is passed along with the iob, but it must be copied here as it
      *   is allocated directly on the caller's stack.  We simply link the frame,
      *   copy the RX descriptor, and schedule a worker to process the frame later so
    - *   that we do not hold up the radio. 
    + *   that we do not hold up the radio.
      *
      ****************************************************************************/
     
    @@ -580,13 +578,12 @@ static void mac802154_rxframe_worker(FAR void *arg)
     {
       FAR struct ieee802154_privmac_s *priv =
         (FAR struct ieee802154_privmac_s *)arg;
    -  
    -  /* The radio layer is responsible for handling all ACKs and retries. If for
    -   * some reason an ACK gets here, just throw it out */
     
    +  /* The radio layer is responsible for handling all ACKs and retries. If for
    +   * some reason an ACK gets here, just throw it out.
    +   */
     }
     
    -
     /****************************************************************************
      * Public Functions
      ****************************************************************************/
    diff --git a/wireless/ieee802154/mac802154_device.c b/wireless/ieee802154/mac802154_device.c
    index 3b7dc49309..6370ff4762 100644
    --- a/wireless/ieee802154/mac802154_device.c
    +++ b/wireless/ieee802154/mac802154_device.c
    @@ -461,7 +461,7 @@ static ssize_t mac802154dev_write(FAR struct file *filep,
     
           mac802154dev_givesem(&dev->md_exclsem);
       }
    - 
    +
       /* Pass the request to the MAC layer */
     
       ret = mac802154_req_data(dev->md_mac, req);
    diff --git a/wireless/ieee802154/mac802154_netdev.c b/wireless/ieee802154/mac802154_netdev.c
    index adc433aa65..18b2d6e1cd 100644
    --- a/wireless/ieee802154/mac802154_netdev.c
    +++ b/wireless/ieee802154/mac802154_netdev.c
    @@ -181,36 +181,36 @@ static void macnet_conf_get(FAR struct macnet_driver_s *priv,
     static void macnet_conf_gts(FAR struct macnet_driver_s *priv,
                  FAR struct ieee802154_gts_conf_s *conf);
     static void macnet_conf_reset(FAR struct macnet_driver_s *priv,
    -             FAR struct ieee802154_reset_conf_s *conf); 
    +             FAR struct ieee802154_reset_conf_s *conf);
     static void macnet_conf_rxenable(FAR struct macnet_driver_s *priv,
    -             FAR struct ieee802154_rxenable_conf_s *conf); 
    +             FAR struct ieee802154_rxenable_conf_s *conf);
     static void macnet_conf_scan(FAR struct macnet_driver_s *priv,
    -             FAR struct ieee802154_scan_conf_s *conf); 
    +             FAR struct ieee802154_scan_conf_s *conf);
     static void macnet_conf_set(FAR struct macnet_driver_s *priv,
    -             FAR struct ieee802154_set_conf_s *conf); 
    +             FAR struct ieee802154_set_conf_s *conf);
     static void macnet_conf_start(FAR struct macnet_driver_s *priv,
    -             FAR struct ieee802154_start_conf_s *conf); 
    +             FAR struct ieee802154_start_conf_s *conf);
     static void macnet_conf_poll(FAR struct macnet_driver_s *priv,
    -             FAR struct ieee802154_poll_conf_s *conf); 
    +             FAR struct ieee802154_poll_conf_s *conf);
     
       /* Asynchronous event indications, replied to synchronously with responses */
     
     static void macnet_ind_data(FAR struct macnet_driver_s *priv,
    -             FAR struct ieee802154_data_ind_s *conf); 
    +             FAR struct ieee802154_data_ind_s *conf);
     static void macnet_ind_associate(FAR struct macnet_driver_s *priv,
    -             FAR struct ieee802154_assoc_ind_s *conf); 
    +             FAR struct ieee802154_assoc_ind_s *conf);
     static void macnet_ind_disassociate(FAR struct macnet_driver_s *priv,
    -             FAR struct ieee802154_disassoc_ind_s *conf); 
    +             FAR struct ieee802154_disassoc_ind_s *conf);
     static void macnet_ind_beaconnotify(FAR struct macnet_driver_s *priv,
    -             FAR struct ieee802154_beaconnotify_ind_s *conf); 
    +             FAR struct ieee802154_beaconnotify_ind_s *conf);
     static void macnet_ind_gts(FAR struct macnet_driver_s *priv,
    -             FAR struct ieee802154_gts_ind_s *conf); 
    +             FAR struct ieee802154_gts_ind_s *conf);
     static void macnet_ind_orphan(FAR struct macnet_driver_s *priv,
    -             FAR struct ieee802154_orphan_ind_s *conf); 
    +             FAR struct ieee802154_orphan_ind_s *conf);
     static void macnet_ind_commstatus(FAR struct macnet_driver_s *priv,
    -             FAR struct ieee802154_commstatus_ind_s *conf); 
    +             FAR struct ieee802154_commstatus_ind_s *conf);
     static void macnet_ind_syncloss(FAR struct macnet_driver_s *priv,
    -             FAR struct ieee802154_syncloss_ind_s *conf); 
    +             FAR struct ieee802154_syncloss_ind_s *conf);
     
     /* Network interface support ************************************************/
     /* Common TX logic */
    @@ -1576,8 +1576,8 @@ int mac802154netdev_register(MACHANDLE mac)
       priv->md_cb.mc_priv = priv;
     
       maccb               = &priv->md_cb.mc_cb;
    -  maccb->mlme_notify  = macdev_mlme_notify;       
    -  maccb->mcps_notify  = macdev_mcps_notify;       
    +  maccb->mlme_notify  = macdev_mlme_notify;
    +  maccb->mcps_notify  = macdev_mcps_notify;
     
       /* Bind the callback structure */
     
    -- 
    GitLab
    
    
    From 2c4800f51188302bcc282a56b2507ff3df5670fe Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Fri, 21 Apr 2017 14:17:46 -0600
    Subject: [PATCH 548/990] Remove the 6loWPAN PANID IOCTLs they are redundant.
    
    ---
     include/nuttx/wireless/wireless.h | 23 +++++++++------------
     net/netdev/netdev_ioctl.c         | 34 ++++---------------------------
     2 files changed, 14 insertions(+), 43 deletions(-)
    
    diff --git a/include/nuttx/wireless/wireless.h b/include/nuttx/wireless/wireless.h
    index 0b67366e79..a9abf706b6 100644
    --- a/include/nuttx/wireless/wireless.h
    +++ b/include/nuttx/wireless/wireless.h
    @@ -164,14 +164,11 @@
      *  3. To the IEEE802.15.4 radio device layer, as documented in,
      *     include/nuttx/wireless/ieee802154/ioeee802154_radio.h.
      *
    - * SIOCSWPANID - Join the specified PAN ID
    + * This is a placeholder; no 6LoWPAN IOCTL commands have been defined.
      */
     
    -#define SIOCSWPANID         _WLIOC(0x0033)  /* Join PAN ID */
    -#define SIOCGWPANID         _WLIOC(0x0034)  /* Return PAN ID */
    -
    -#define WL_FIRSTCHAR        0x0035
    -#define WL_NNETCMDS         0x0034
    +#define WL_FIRSTCHAR        0x0033
    +#define WL_NNETCMDS         0x0032
     
     /* Character Driver IOCTL commands *************************************************/
     /* Non-compatible, NuttX only IOCTL definitions for use with low-level wireless
    @@ -179,23 +176,23 @@
      * requires a file descriptor created by the open() interface.
      */
     
    -#define WLIOC_SETRADIOFREQ  _WLIOC(0x0035)  /* arg: Pointer to uint32_t, frequency
    +#define WLIOC_SETRADIOFREQ  _WLIOC(0x0033)  /* arg: Pointer to uint32_t, frequency
                                                  * value (in Mhz) */
    -#define WLIOC_GETRADIOFREQ  _WLIOC(0x0036)  /* arg: Pointer to uint32_t, frequency
    +#define WLIOC_GETRADIOFREQ  _WLIOC(0x0034)  /* arg: Pointer to uint32_t, frequency
                                                  * value (in Mhz) */
    -#define WLIOC_SETADDR       _WLIOC(0x0037)  /* arg: Pointer to address value, format
    +#define WLIOC_SETADDR       _WLIOC(0x0035)  /* arg: Pointer to address value, format
                                                  * of the address is driver specific */
    -#define WLIOC_GETADDR       _WLIOC(0x0038)  /* arg: Pointer to address value, format
    +#define WLIOC_GETADDR       _WLIOC(0x0036)  /* arg: Pointer to address value, format
                                                  * of the address is driver specific */
    -#define WLIOC_SETTXPOWER    _WLIOC(0x0039)  /* arg: Pointer to int32_t, output power
    +#define WLIOC_SETTXPOWER    _WLIOC(0x0036)  /* arg: Pointer to int32_t, output power
                                                  * (in dBm) */
    -#define WLIOC_GETTXPOWER    _WLIOC(0x003a)  /* arg: Pointer to int32_t, output power
    +#define WLIOC_GETTXPOWER    _WLIOC(0x0038)  /* arg: Pointer to int32_t, output power
                                                  * (in dBm) */
     
     /* Device-specific IOCTL commands **************************************************/
     
     #define WL_FIRST            0x0001          /* First common command */
    -#define WL_NCMDS            0x003a          /* Number of common commands */
    +#define WL_NCMDS            0x0038          /* Number of common commands */
     
     /* User defined ioctl commands are also supported. These will be forwarded
      * by the upper-half QE driver to the lower-half QE driver via the ioctl()
    diff --git a/net/netdev/netdev_ioctl.c b/net/netdev/netdev_ioctl.c
    index 7f2efbf982..17ac9f51d3 100644
    --- a/net/netdev/netdev_ioctl.c
    +++ b/net/netdev/netdev_ioctl.c
    @@ -343,6 +343,7 @@ static void ioctl_set_ipv6addr(FAR net_ipv6addr_t outaddr,
     static int netdev_sixlowpan_ioctl(FAR struct socket *psock, int cmd,
                                       FAR struct sixlowpan_req_s *req)
     {
    +#if 0 /* None yet defined */
       FAR struct ieee802154_driver_s *ieee;
       int ret = -ENOTTY;
     
    @@ -353,42 +354,15 @@ static int netdev_sixlowpan_ioctl(FAR struct socket *psock, int cmd,
           switch (cmd)
             {
     
    -          case SIOCSWPANID:  /* Join PAN ID */
    -            {
    -              ieee = (FAR struct ieee802154_driver_s *)netdev_findbyname(req->ifr_name);
    -              if (ieee == NULL)
    -                {
    -                  ret = -ENODEV;
    -                }
    -              else
    -                {
    -                  ieee->i_panid = req->u.panid.panid;
    -                  ret = OK;
    -                }
    -            }
    -            break;
    -
    -          case SIOCGWPANID:   /* Return PAN ID */
    -            {
    -              ieee = (FAR struct ieee802154_driver_s *)netdev_findbyname(req->ifr_name);
    -              if (ieee == NULL)
    -                {
    -                  ret = -ENODEV;
    -                }
    -              else
    -                {
    -                  req->u.panid.panid = ieee->i_panid;
    -                  ret = OK;
    -                }
    -            }
    -            break;
    -
               default:
                 return -ENOTTY;
             }
         }
     
       return ret;
    +#else
    +  return -ENOTTY;
    +#endif
     }
     #endif
     
    -- 
    GitLab
    
    
    From 5d68eb60592518da7d7d1bee786edad669abc6cd Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Fri, 21 Apr 2017 16:23:40 -0600
    Subject: [PATCH 549/990] 6loWPAN: Remove the PAN ID from the 6loWPAN data
     structure.  This is owned by the radio driver.  Rather, use an IOCTL to
     obtain the PAN ID from the downstream radio driver.
    
    ---
     include/nuttx/net/sixlowpan.h            | 21 ++----
     net/netdev/netdev_ioctl.c                | 15 -----
     net/sixlowpan/sixlowpan.h                |  8 +--
     net/sixlowpan/sixlowpan_framelist.c      | 16 ++++-
     net/sixlowpan/sixlowpan_framer.c         | 26 +++++---
     net/sixlowpan/sixlowpan_input.c          |  2 +-
     net/sixlowpan/sixlowpan_internal.h       | 22 ++++++-
     net/sixlowpan/sixlowpan_send.c           |  4 +-
     net/sixlowpan/sixlowpan_tcpsend.c        |  4 +-
     net/sixlowpan/sixlowpan_udpsend.c        |  4 +-
     net/sixlowpan/sixlowpan_utils.c          | 37 +++++++++++
     wireless/ieee802154/mac802154_loopback.c | 81 +++++++++++++++++++++++-
     12 files changed, 180 insertions(+), 60 deletions(-)
    
    diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h
    index 855948b4e8..fd2301632d 100644
    --- a/include/nuttx/net/sixlowpan.h
    +++ b/include/nuttx/net/sixlowpan.h
    @@ -426,15 +426,12 @@ struct rimeaddr_s
      * this structure.  In general, all fields must be set to NULL.  In
      * addtion:
      *
    - * 1. i_panid must be set to identify the network.  It may be set to 0xfff
    - *    if the device is not associated.
    - *
    - * 2. i_dsn must be set to a random value.  After that, it will be managed
    + * 1. i_dsn must be set to a random value.  After that, it will be managed
      *    by the network.
      *
    - * 3. i_nodeaddr must be set after the MAC is assigned an address.
    + * 2. i_nodeaddr must be set after the MAC is assigned an address.
      *
    - * 4. On a TX poll, the IEEE802.15.4 MAC driver should provide its driver
    + * 3. On a TX poll, the IEEE802.15.4 MAC driver should provide its driver
      *    structure with i_framelist set to NULL.  At the conclusion of the
      *    poll, if there are frames to be sent, they will have been added to
      *    the i_framelist.  The non-empty frame list at the conclusion of the
    @@ -449,7 +446,7 @@ struct rimeaddr_s
      *    After sending each frame, the driver must return the IOB to the pool
      *    of free IOBs using the FROM_IOB_FREE() macro.
      *
    - * 5. When receiving data both buffers must be provided:
    + * 4. When receiving data both buffers must be provided:
      *
      *    The IEEE802.15.4 MAC driver should receive the frame data directly
      *    into the payload area of an IOB structure.  That IOB structure may be
    @@ -500,16 +497,6 @@ struct ieee802154_driver_s
       FAR struct iob_s *i_framelist;
     
       /* Driver Configuration ***************************************************/
    -  /* i_panid.  The PAN ID is 16-bit number that identifies the network. It
    -   * must be unique to differentiate a network. All the nodes in the same
    -   * network should have the same PAN ID.  This value must be provided to
    -   * the network from the IEEE802.15.4 MAC driver.
    -   *
    -   * If this value is 0xffff, the device is not associated.
    -   */
    -
    -  uint16_t i_panid;
    -
       /* i_node_addr.  The address assigned to this node. */
     
       struct rimeaddr_s i_nodeaddr;
    diff --git a/net/netdev/netdev_ioctl.c b/net/netdev/netdev_ioctl.c
    index 96eff51998..7f194d1c1a 100644
    --- a/net/netdev/netdev_ioctl.c
    +++ b/net/netdev/netdev_ioctl.c
    @@ -1301,21 +1301,6 @@ int psock_ioctl(FAR struct socket *psock, int cmd, unsigned long arg)
     {
       int ret;
     
    -  /* Check if this is a valid command.  In all cases, arg is a pointer that has
    -   * been cast to unsigned long.  Verify that the value of the to-be-pointer is
    -   * non-NULL.
    -   */
    -
    -#ifdef CONFIG_DRIVERS_WIRELESS
    -  if (!_SIOCVALID(cmd) && !_WLIOCVALID(cmd))
    -#else
    -  if (!_SIOCVALID(cmd))
    -#endif
    -    {
    -      ret = -ENOTTY;
    -      goto errout;
    -    }
    -
       /* Verify that the psock corresponds to valid, allocated socket */
     
       if (psock == NULL || psock->s_crefs <= 0)
    diff --git a/net/sixlowpan/sixlowpan.h b/net/sixlowpan/sixlowpan.h
    index 05ce9496c9..fe4451c093 100644
    --- a/net/sixlowpan/sixlowpan.h
    +++ b/net/sixlowpan/sixlowpan.h
    @@ -79,7 +79,7 @@ struct sockaddr;     /* Forward reference */
     void sixlowpan_initialize(void);
     
     /****************************************************************************
    - * Function: psock_6lowpan_tcp_send
    + * Name: psock_6lowpan_tcp_send
      *
      * Description:
      *   psock_6lowpan_tcp_send() call may be used only when the TCP socket is in a
    @@ -107,7 +107,7 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf,
     #endif
     
     /****************************************************************************
    - * Function: sixlowpan_tcp_send
    + * Name: sixlowpan_tcp_send
      *
      * Description:
      *   TCP output comes through three different mechansims.  Either from:
    @@ -139,7 +139,7 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf,
     void sixlowpan_tcp_send(FAR struct net_driver_s *dev);
     
     /****************************************************************************
    - * Function: psock_6lowpan_udp_send
    + * Name: psock_6lowpan_udp_send
      *
      * Description:
      *   psock_6lowpan_udp_send() call may be used with connectionlesss UDP
    @@ -167,7 +167,7 @@ ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf,
     #endif
     
     /****************************************************************************
    - * Function: psock_6lowpan_udp_sendto
    + * Name: psock_6lowpan_udp_sendto
      *
      * Description:
      *   If sendto() is used on a connection-mode (SOCK_STREAM, SOCK_SEQPACKET)
    diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c
    index ee9487a101..e392c02298 100644
    --- a/net/sixlowpan/sixlowpan_framelist.c
    +++ b/net/sixlowpan/sixlowpan_framelist.c
    @@ -217,6 +217,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee,
       struct rimeaddr_s bcastmac;
       uint16_t pktlen;
       uint16_t paysize;
    +  uint16_t dest_panid;
     #ifdef CONFIG_NET_6LOWPAN_FRAG
       uint16_t outlen = 0;
     #endif
    @@ -286,9 +287,18 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee,
       rimeaddr_copy(&g_pktaddrs[PACKETBUF_ADDR_SENDER], &ieee->i_nodeaddr);
       rimeaddr_copy(&g_pktaddrs[PACKETBUF_ADDR_RECEIVER], destmac);
     
    +  /* Get the destination PAN ID.
    +   *
    +   * REVISIT: For now I am assuming that the source and destination
    +   * PAN IDs are the same.
    +   */
    +
    +  dest_panid = 0xffff;
    +  (void)sixlowpan_src_panid(ieee, &dest_panid);
    +
       /* Pre-calculate frame header length. */
     
    -  framer_hdrlen = sixlowpan_send_hdrlen(ieee, ieee->i_panid);
    +  framer_hdrlen = sixlowpan_send_hdrlen(ieee, dest_panid);
       if (framer_hdrlen < 0)
         {
           /* Failed to determine the size of the header failed. */
    @@ -349,7 +359,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee,
           /* Create 1st Fragment */
           /* Add the frame header using the pre-allocated IOB. */
     
    -      verify = sixlowpan_framecreate(ieee, iob, ieee->i_panid);
    +      verify = sixlowpan_framecreate(ieee, iob, dest_panid);
           DEBUGASSERT(verify == framer_hdrlen);
           UNUSED(verify);
     
    @@ -513,7 +523,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee,
     
           /* Add the frame header to the preallocated IOB. */
     
    -      verify = sixlowpan_framecreate(ieee, iob, ieee->i_panid);
    +      verify = sixlowpan_framecreate(ieee, iob, dest_panid);
           DEBUGASSERT(verify == framer_hdrlen);
           UNUSED(verify);
     
    diff --git a/net/sixlowpan/sixlowpan_framer.c b/net/sixlowpan/sixlowpan_framer.c
    index 66f8a1c3fb..4ec877d2d5 100644
    --- a/net/sixlowpan/sixlowpan_framer.c
    +++ b/net/sixlowpan/sixlowpan_framer.c
    @@ -82,7 +82,7 @@ struct field_length_s
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: sixlowpan_addrlen
    + * Name: sixlowpan_addrlen
      *
      * Description:
      *   Return the address length associated with a 2-bit address mode
    @@ -109,7 +109,7 @@ static inline uint8_t sixlowpan_addrlen(uint8_t addrmode)
     }
     
     /****************************************************************************
    - * Function: sixlowpan_addrnull
    + * Name: sixlowpan_addrnull
      *
      * Description:
      *   If the output address is NULL in the Rime buf, then it is broadcast
    @@ -140,7 +140,7 @@ static bool sixlowpan_addrnull(FAR uint8_t *addr)
     
     
     /****************************************************************************
    - * Function: sixlowpan_fieldlengths
    + * Name: sixlowpan_fieldlengths
      *
      * Description:
      *   Return the lengths associated fields of the IEEE802.15.4 header.
    @@ -228,7 +228,7 @@ static void sixlowpan_fieldlengths(FAR struct frame802154_s *finfo,
     }
     
     /****************************************************************************
    - * Function: sixlowpan_fieldlengths
    + * Name: sixlowpan_fieldlengths
      *
      * Description:
      *   Return the lengths associated fields of the IEEE802.15.4 header.
    @@ -249,7 +249,7 @@ static int sixlowpan_flen_hdrlen(FAR const struct field_length_s *flen)
     }
     
     /****************************************************************************
    - * Function: sixlowpan_802154_hdrlen
    + * Name: sixlowpan_802154_hdrlen
      *
      * Description:
      *   Calculates the length of the frame header.  This function is meant to
    @@ -272,7 +272,7 @@ static int sixlowpan_802154_hdrlen(FAR struct frame802154_s *finfo)
     }
     
     /****************************************************************************
    - * Function: sixlowpan_setup_params
    + * Name: sixlowpan_setup_params
      *
      * Description:
      *   Configure frame parmeters structure.
    @@ -293,6 +293,7 @@ static void sixlowpan_setup_params(FAR struct ieee802154_driver_s *ieee,
                                        uint16_t dest_panid,
                                        FAR struct frame802154_s *params)
     {
    +  uint16_t src_panid;
       bool rcvrnull;
     
       /* Initialize all prameters to all zero */
    @@ -331,9 +332,14 @@ static void sixlowpan_setup_params(FAR struct ieee802154_driver_s *ieee,
         }
     
       /* Complete the addressing fields. */
    +  /* Get the source PAN ID from the IEEE802.15.4 radio driver */
    +
    +  src_panid = 0xffff;
    +  (void)sixlowpan_src_panid(ieee, &src_panid);
    +
       /* Set the source and destination PAN ID. */
     
    -  params->src_pid  = ieee->i_panid;
    +  params->src_pid  = src_panid;
       params->dest_pid = dest_panid;
     
       /* If the output address is NULL in the Rime buf, then it is broadcast
    @@ -382,7 +388,7 @@ static void sixlowpan_setup_params(FAR struct ieee802154_driver_s *ieee,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: sixlowpan_send_hdrlen
    + * Name: sixlowpan_send_hdrlen
      *
      * Description:
      *   This function is before the first frame has been sent in order to
    @@ -415,7 +421,7 @@ int sixlowpan_send_hdrlen(FAR struct ieee802154_driver_s *ieee,
     }
     
     /****************************************************************************
    - * Function: sixlowpan_802154_framecreate
    + * Name: sixlowpan_802154_framecreate
      *
      * Description:
      *   Creates a frame for transmission over the air.  This function is meant
    @@ -514,7 +520,7 @@ int sixlowpan_802154_framecreate(FAR struct frame802154_s *finfo,
     }
     
     /****************************************************************************
    - * Function: sixlowpan_framecreate
    + * Name: sixlowpan_framecreate
      *
      * Description:
      *   This function is called after eiether (1) the IEEE802.15.4 MAC driver
    diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c
    index bfa74da13a..bccd97677b 100644
    --- a/net/sixlowpan/sixlowpan_input.c
    +++ b/net/sixlowpan/sixlowpan_input.c
    @@ -680,7 +680,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee,
     }
     
     /****************************************************************************
    - * Function: sixlowpan_dispatch
    + * Name: sixlowpan_dispatch
      *
      * Description:
      *   Inject the packet in d_buf into the network for normal packet processing.
    diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h
    index 392bc376b7..08b2fc445c 100644
    --- a/net/sixlowpan/sixlowpan_internal.h
    +++ b/net/sixlowpan/sixlowpan_internal.h
    @@ -344,7 +344,7 @@ int sixlowpan_send(FAR struct net_driver_s *dev,
                        uint16_t timeout);
     
     /****************************************************************************
    - * Function: sixlowpan_send_hdrlen
    + * Name: sixlowpan_send_hdrlen
      *
      * Description:
      *   This function is before the first frame has been sent in order to
    @@ -366,7 +366,7 @@ int sixlowpan_send_hdrlen(FAR struct ieee802154_driver_s *ieee,
                          uint16_t dest_panid);
     
     /****************************************************************************
    - * Function: sixlowpan_framecreate
    + * Name: sixlowpan_framecreate
      *
      * Description:
      *   This function is called after the IEEE802.15.4 MAC driver polls for
    @@ -606,5 +606,23 @@ void sixlowpan_rimefromip(const net_ipv6addr_t ipaddr,
     bool sixlowpan_ismacbased(const net_ipv6addr_t ipaddr,
                               FAR const struct rimeaddr_s *rime);
     
    +/****************************************************************************
    + * Name: sixlowpan_src_panid
    + *
    + * Description:
    + *   Get the source PAN ID from the IEEE802.15.4 radio.
    + *
    + * Input parameters:
    + *   ieee  - A reference IEEE802.15.4 MAC network device structure.
    + *   panid - The location in which to return the PAN ID.  0xfff may be
    + *           returned if the device is not associated.
    + *
    + * Returned Value:
    + *   Zero (OK) on success; a negated errno value on failure.
    + *
    + ****************************************************************************/
    +
    +int sixlowpan_src_panid(FAR struct ieee802154_driver_s *ieee,
    +                        FAR uint16_t *panid);
     #endif /* CONFIG_NET_6LOWPAN */
     #endif /* _NET_SIXLOWPAN_SIXLOWPAN_INTERNAL_H */
    diff --git a/net/sixlowpan/sixlowpan_send.c b/net/sixlowpan/sixlowpan_send.c
    index 1dd8f86c66..3ad68554ae 100644
    --- a/net/sixlowpan/sixlowpan_send.c
    +++ b/net/sixlowpan/sixlowpan_send.c
    @@ -93,7 +93,7 @@ struct sixlowpan_send_s
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: send_timeout
    + * Name: send_timeout
      *
      * Description:
      *   Check for send timeout.
    @@ -134,7 +134,7 @@ static inline bool send_timeout(FAR struct sixlowpan_send_s *sinfo)
     }
     
     /****************************************************************************
    - * Function: send_interrupt
    + * Name: send_interrupt
      *
      * Description:
      *   This function is called from the interrupt level to perform the actual
    diff --git a/net/sixlowpan/sixlowpan_tcpsend.c b/net/sixlowpan/sixlowpan_tcpsend.c
    index 3ee39e72ed..2bb6c49130 100644
    --- a/net/sixlowpan/sixlowpan_tcpsend.c
    +++ b/net/sixlowpan/sixlowpan_tcpsend.c
    @@ -136,7 +136,7 @@ static uint16_t sixlowpan_tcp_chksum(FAR struct ipv6tcp_hdr_s *ipv6tcp,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: psock_6lowpan_tcp_send
    + * Name: psock_6lowpan_tcp_send
      *
      * Description:
      *   psock_6lowpan_tcp_send() call may be used only when the TCP socket is in a
    @@ -348,7 +348,7 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf,
     }
     
     /****************************************************************************
    - * Function: sixlowpan_tcp_send
    + * Name: sixlowpan_tcp_send
      *
      * Description:
      *   TCP output comes through three different mechansims.  Either from:
    diff --git a/net/sixlowpan/sixlowpan_udpsend.c b/net/sixlowpan/sixlowpan_udpsend.c
    index f8f62e528b..a29197eec7 100644
    --- a/net/sixlowpan/sixlowpan_udpsend.c
    +++ b/net/sixlowpan/sixlowpan_udpsend.c
    @@ -125,7 +125,7 @@ static uint16_t sixlowpan_udp_chksum(FAR struct ipv6udp_hdr_s *ipv6udp,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: psock_6lowpan_udp_sendto
    + * Name: psock_6lowpan_udp_sendto
      *
      * Description:
      *   If sendto() is used on a connection-mode (SOCK_STREAM, SOCK_SEQPACKET)
    @@ -323,7 +323,7 @@ ssize_t psock_6lowpan_udp_sendto(FAR struct socket *psock,
     }
     
     /****************************************************************************
    - * Function: psock_6lowpan_udp_send
    + * Name: psock_6lowpan_udp_send
      *
      * Description:
      *   psock_6lowpan_udp_send() call may be used with connectionlesss UDP
    diff --git a/net/sixlowpan/sixlowpan_utils.c b/net/sixlowpan/sixlowpan_utils.c
    index dcda6be652..7e1a6ac2ee 100644
    --- a/net/sixlowpan/sixlowpan_utils.c
    +++ b/net/sixlowpan/sixlowpan_utils.c
    @@ -54,8 +54,10 @@
     #include 
     #include 
     #include 
    +#include 
     
     #include 
    +#include 
     
     #include "sixlowpan/sixlowpan_internal.h"
     
    @@ -156,4 +158,39 @@ bool sixlowpan_ismacbased(const net_ipv6addr_t ipaddr,
     #endif
     }
     
    +/****************************************************************************
    + * Name: sixlowpan_src_panid
    + *
    + * Description:
    + *   Get the source PAN ID from the IEEE802.15.4 radio.
    + *
    + * Input parameters:
    + *   ieee  - A reference IEEE802.15.4 MAC network device structure.
    + *   panid - The location in which to return the PAN ID.  0xfff may be
    + *           returned if the device is not associated.
    + *
    + * Returned Value:
    + *   Zero (OK) on success; a negated errno value on failure.
    + *
    + ****************************************************************************/
    +
    +int sixlowpan_src_panid(FAR struct ieee802154_driver_s *ieee,
    +                        FAR uint16_t *panid)
    +{
    +  FAR struct net_driver_s *dev = &ieee->i_dev;
    +  struct ieee802154_netradio_s arg;
    +  int ret;
    +
    +  memcpy(arg.ifr_name, ieee->i_dev.d_ifname, IFNAMSIZ);
    +  ret = dev->d_ioctl(dev, PHY802154IOC_GET_PANID, (unsigned long)((uintptr_t)&arg));
    +  if (ret < 0)
    +    {
    +      wlerr("ERROR: PHY802154IOC_GET_PANID failed: %d\n", ret);
    +      return ret;
    +    }
    +
    +  *panid = arg.u.panid;
    +  return OK;
    +}
    +
     #endif /* CONFIG_NET_6LOWPAN */
    diff --git a/wireless/ieee802154/mac802154_loopback.c b/wireless/ieee802154/mac802154_loopback.c
    index b3c0c4cdf5..13243baed0 100644
    --- a/wireless/ieee802154/mac802154_loopback.c
    +++ b/wireless/ieee802154/mac802154_loopback.c
    @@ -54,6 +54,7 @@
     #include 
     #include 
     #include 
    +#include 
     #include 
     
     #include "mac802154.h"
    @@ -94,6 +95,7 @@ struct lo_driver_s
     {
       bool lo_bifup;               /* true:ifup false:ifdown */
       bool lo_txdone;              /* One RX packet was looped back */
    +  uint16_t lo_panid;           /* Fake PAN ID for testing */
       WDOG_ID lo_polldog;          /* TX poll timer */
       struct work_s lo_work;       /* For deferring poll work to the work queue */
     
    @@ -131,6 +133,10 @@ static int lo_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac);
     static int lo_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac);
     #endif
     #endif
    +#ifdef CONFIG_NETDEV_IOCTL
    +static int  lo_ioctl(FAR struct net_driver_s *dev, int cmd,
    +              unsigned long arg);
    +#endif
     
     /****************************************************************************
      * Private Functions
    @@ -371,11 +377,11 @@ static int lo_ifup(FAR struct net_driver_s *dev)
              priv->lo_ieee.i_nodeaddr.u8[2], priv->lo_ieee.i_nodeaddr.u8[3],
              priv->lo_ieee.i_nodeaddr.u8[4], priv->lo_ieee.i_nodeaddr.u8[5],
              priv->lo_ieee.i_nodeaddr.u8[6], priv->lo_ieee.i_nodeaddr.u8[7],
    -         priv->lo_ieee.i_panid);
    +         priv->lo_panid);
     #else
       ninfo("             Node: %02x:%02x PANID=%04x\n",
              priv->lo_ieee.i_nodeaddr.u8[0], priv->lo_ieee.i_nodeaddr.u8[1],
    -         priv->lo_ieee.i_panid);
    +         priv->lo_panid);
     #endif
     
       /* Set and activate a timer process */
    @@ -570,6 +576,74 @@ static int lo_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac)
     }
     #endif
     
    +/****************************************************************************
    + * Name: macnet_ioctl
    + *
    + * Description:
    + *   Handle network IOCTL commands directed to this device.
    + *
    + * Parameters:
    + *   dev - Reference to the NuttX driver state structure
    + *   cmd - The IOCTL command
    + *   arg - The argument for the IOCTL command
    + *
    + * Returned Value:
    + *   OK on success; Negated errno on failure.
    + *
    + * Assumptions:
    + *
    + ****************************************************************************/
    +
    +#ifdef CONFIG_NETDEV_IOCTL
    +static int lo_ioctl(FAR struct net_driver_s *dev, int cmd,
    +                    unsigned long arg)
    +{
    +  FAR struct lo_driver_s *priv = (FAR struct lo_driver_s *)dev->d_private;
    +  int ret = -ENOTTY;
    +
    +#if 0
    +  /* Check for IOCTLs aimed at the IEEE802.15.4 MAC layer */
    +
    +  if (_MAC802154IOCVALID(cmd))
    +    {
    +      FAR struct ieee802154_netmac_s *netmac =
    +        (FAR struct ieee802154_netmac_s *)arg;
    +    }
    +
    +  /* No, check for IOCTLs aimed at the IEEE802.15.4 radio layer */
    +
    +  else
    +#endif
    +  if (_PHY802154IOCVALID(cmd))
    +    {
    +      FAR struct ieee802154_netradio_s *netradio =
    +        (FAR struct ieee802154_netradio_s *)arg;
    +
    +      /* Pick out radio settings of interest.  There is, of course, no
    +       * radio in this loopback.
    +       */
    +
    +      switch (cmd)
    +        {
    +           case PHY802154IOC_SET_PANID:
    +             priv->lo_panid = netradio->u.panid;
    +             ret = OK;
    +             break;
    +
    +           case PHY802154IOC_GET_PANID:
    +             netradio->u.panid = priv->lo_panid;
    +             ret = OK;
    +             break;
    +
    +           default:
    +             break;
    +        }
    +    }
    +
    +  return ret;
    +}
    +#endif
    +
     /****************************************************************************
      * Public Functions
      ****************************************************************************/
    @@ -612,6 +686,9 @@ int ieee8021514_loopback(void)
     #ifdef CONFIG_NET_IGMP
       dev->d_addmac  = lo_addmac;     /* Add multicast MAC address */
       dev->d_rmmac   = lo_rmmac;      /* Remove multicast MAC address */
    +#endif
    +#ifdef CONFIG_NETDEV_IOCTL
    +  dev->d_ioctl   = lo_ioctl;      /* Handle network IOCTL commands */
     #endif
       dev->d_buf     = g_iobuffer;    /* Attach the IO buffer */
       dev->d_private = (FAR void *)priv; /* Used to recover private state from dev */
    -- 
    GitLab
    
    
    From d5207efb5a67ab69ad3e825d88f05615acaba406 Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Fri, 21 Apr 2017 16:33:14 -0600
    Subject: [PATCH 550/990] Be consistent... Use Name: consistent in function
     headers vs Function:
    
    ---
     crypto/random_pool.c                          | 14 +--
     drivers/input/ads7843e.c                      |  4 +-
     drivers/input/max11802.c                      |  4 +-
     drivers/iob/iob_dump.c                        |  2 +-
     drivers/lcd/nokia6100.c                       |  4 +-
     drivers/lcd/st7567.c                          |  4 +-
     drivers/lcd/ug-9664hswag01.c                  |  4 +-
     drivers/net/cs89x0.c                          | 30 +++----
     drivers/net/dm90x0.c                          | 54 ++++++------
     drivers/net/enc28j60.c                        | 78 ++++++++--------
     drivers/net/encx24j600.c                      | 88 +++++++++----------
     drivers/net/ftmac100.c                        | 44 +++++-----
     drivers/net/loopback.c                        | 20 ++---
     drivers/net/phy_notify.c                      |  4 +-
     drivers/net/slip.c                            | 28 +++---
     drivers/net/tun.c                             | 28 +++---
     drivers/video/ov2640.c                        | 12 +--
     drivers/wireless/cc3000/cc3000.c              | 12 +--
     drivers/wireless/nrf24l01.c                   |  4 +-
     fs/vfs/fs_poll.c                              |  4 +-
     graphics/vnc/server/vnc_fbdev.c               |  2 +-
     graphics/vnc/server/vnc_keymap.c              |  2 +-
     graphics/vnc/server/vnc_receiver.c            |  2 +-
     include/net/route.h                           |  4 +-
     include/nuttx/audio/vs1053.h                  |  2 +-
     include/nuttx/clock.h                         |  6 +-
     include/nuttx/drivers/iob.h                   |  2 +-
     include/nuttx/fs/fs.h                         |  4 +-
     include/nuttx/net/cs89x0.h                    |  2 +-
     include/nuttx/net/enc28j60.h                  |  2 +-
     include/nuttx/net/encx24j600.h                |  2 +-
     include/nuttx/net/ftmac100.h                  |  2 +-
     include/nuttx/net/loopback.h                  |  2 +-
     include/nuttx/net/net.h                       | 50 +++++------
     include/nuttx/net/netdev.h                    |  4 +-
     include/nuttx/net/phy.h                       |  4 +-
     include/nuttx/net/slip.h                      |  2 +-
     include/nuttx/net/tun.h                       |  2 +-
     include/nuttx/random.h                        |  8 +-
     include/nuttx/semaphore.h                     |  4 +-
     include/nuttx/time.h                          |  8 +-
     include/nuttx/video/ov2640.h                  |  2 +-
     include/nuttx/video/vnc.h                     |  6 +-
     include/nuttx/wireless/ieee80211/bcmf_board.h |  6 +-
     include/nuttx/wireless/ieee80211/bcmf_sdio.h  |  2 +-
     .../wireless/ieee802154/ieee802154_loopback.h |  2 +-
     include/nuttx/wireless/ieee802154/mrf24j40.h  |  2 +-
     include/sys/random.h                          |  2 +-
     libc/libgen/lib_basename.c                    |  2 +-
     libc/libgen/lib_dirname.c                     |  2 +-
     libc/net/lib_addroute.c                       |  2 +-
     libc/net/lib_delroute.c                       |  2 +-
     libc/pthread/pthread_attr_destroy.c           |  2 +-
     libc/pthread/pthread_attr_getaffinity.c       |  2 +-
     libc/pthread/pthread_attr_getinheritsched.c   |  2 +-
     libc/pthread/pthread_attr_getschedparam.c     |  2 +-
     libc/pthread/pthread_attr_getschedpolicy.c    |  2 +-
     libc/pthread/pthread_attr_getstacksize.c      |  2 +-
     libc/pthread/pthread_attr_init.c              |  2 +-
     libc/pthread/pthread_attr_setaffinity.c       |  2 +-
     libc/pthread/pthread_attr_setinheritsched.c   |  2 +-
     libc/pthread/pthread_attr_setschedparam.c     |  2 +-
     libc/pthread/pthread_attr_setschedpolicy.c    |  2 +-
     libc/pthread/pthread_attr_setstacksize.c      |  2 +-
     libc/pthread/pthread_barrierattr_destroy.c    |  2 +-
     libc/pthread/pthread_barrierattr_getpshared.c |  2 +-
     libc/pthread/pthread_barrierattr_init.c       |  2 +-
     libc/pthread/pthread_barrierattr_setpshared.c |  2 +-
     libc/pthread/pthread_condattr_destroy.c       |  2 +-
     libc/pthread/pthread_condattr_init.c          |  2 +-
     libc/pthread/pthread_mutexattr_destroy.c      |  2 +-
     libc/pthread/pthread_mutexattr_getprotocol.c  |  2 +-
     libc/pthread/pthread_mutexattr_getpshared.c   |  2 +-
     libc/pthread/pthread_mutexattr_getrobust.c    |  2 +-
     libc/pthread/pthread_mutexattr_gettype.c      |  2 +-
     libc/pthread/pthread_mutexattr_init.c         |  2 +-
     libc/pthread/pthread_mutexattr_setprotocol.c  |  2 +-
     libc/pthread/pthread_mutexattr_setpshared.c   |  2 +-
     libc/pthread/pthread_mutexattr_setrobust.c    |  2 +-
     libc/pthread/pthread_mutexattr_settype.c      |  2 +-
     libc/semaphore/sem_getprotocol.c              |  2 +-
     libc/semaphore/sem_getvalue.c                 |  2 +-
     libc/semaphore/sem_init.c                     |  2 +-
     libc/semaphore/sem_setprotocol.c              |  2 +-
     libc/signal/sig_addset.c                      |  2 +-
     libc/signal/sig_delset.c                      |  2 +-
     libc/signal/sig_emptyset.c                    |  2 +-
     libc/signal/sig_fillset.c                     |  2 +-
     libc/signal/sig_ismember.c                    |  2 +-
     libc/stdio/lib_sscanf.c                       | 10 +--
     libc/time/lib_asctime.c                       |  2 +-
     libc/time/lib_asctimer.c                      |  2 +-
     libc/time/lib_calendar2utc.c                  |  4 +-
     libc/time/lib_ctime.c                         |  2 +-
     libc/time/lib_ctimer.c                        |  2 +-
     libc/time/lib_dayofweek.c                     |  2 +-
     libc/time/lib_daysbeforemonth.c               |  2 +-
     libc/time/lib_difftime.c                      |  2 +-
     libc/time/lib_gmtime.c                        |  2 +-
     libc/time/lib_gmtimer.c                       |  4 +-
     libc/time/lib_isleapyear.c                    |  2 +-
     libc/time/lib_strftime.c                      |  2 +-
     libc/time/lib_time.c                          |  2 +-
     net/arp/arp.h                                 | 14 +--
     net/arp/arp_notify.c                          |  8 +-
     net/arp/arp_poll.c                            |  2 +-
     net/arp/arp_send.c                            |  6 +-
     net/arp/arp_timer.c                           |  4 +-
     net/devif/devif.h                             | 12 +--
     net/devif/devif_callback.c                    | 14 +--
     net/devif/devif_poll.c                        | 20 ++---
     net/devif/ipv4_input.c                        |  4 +-
     net/devif/ipv6_input.c                        |  2 +-
     net/devif/net_setipid.c                       |  2 +-
     net/icmp/icmp_ping.c                          |  4 +-
     net/icmpv6/icmpv6.h                           | 16 ++--
     net/icmpv6/icmpv6_notify.c                    |  8 +-
     net/icmpv6/icmpv6_ping.c                      |  4 +-
     net/icmpv6/icmpv6_rnotify.c                   | 10 +--
     net/local/local.h                             | 10 +--
     net/local/local_accept.c                      |  4 +-
     net/local/local_netpoll.c                     |  6 +-
     net/local/local_recvfrom.c                    |  6 +-
     net/local/local_sendto.c                      |  2 +-
     net/netdev/netdev.h                           | 24 ++---
     net/netdev/netdev_carrier.c                   |  4 +-
     net/netdev/netdev_count.c                     |  2 +-
     net/netdev/netdev_default.c                   |  2 +-
     net/netdev/netdev_findbyaddr.c                |  8 +-
     net/netdev/netdev_findbyindex.c               |  2 +-
     net/netdev/netdev_findbyname.c                |  2 +-
     net/netdev/netdev_foreach.c                   |  2 +-
     net/netdev/netdev_register.c                  |  4 +-
     net/netdev/netdev_rxnotify.c                  |  4 +-
     net/netdev/netdev_txnotify.c                  |  6 +-
     net/netdev/netdev_unregister.c                |  2 +-
     net/netdev/netdev_verify.c                    |  2 +-
     net/pkt/pkt.h                                 |  6 +-
     net/pkt/pkt_callback.c                        |  2 +-
     net/pkt/pkt_finddev.c                         |  2 +-
     net/pkt/pkt_send.c                            |  4 +-
     net/route/net_addroute.c                      |  2 +-
     net/route/net_allocroute.c                    |  6 +-
     net/route/net_delroute.c                      |  4 +-
     net/route/net_foreachroute.c                  |  2 +-
     net/route/net_router.c                        |  8 +-
     net/route/netdev_router.c                     |  8 +-
     net/route/route.h                             | 20 ++---
     net/sixlowpan/sixlowpan.h                     |  8 +-
     net/sixlowpan/sixlowpan_framer.c              | 18 ++--
     net/sixlowpan/sixlowpan_input.c               |  2 +-
     net/sixlowpan/sixlowpan_internal.h            |  4 +-
     net/sixlowpan/sixlowpan_send.c                |  4 +-
     net/sixlowpan/sixlowpan_tcpsend.c             |  4 +-
     net/sixlowpan/sixlowpan_udpsend.c             |  4 +-
     net/socket/accept.c                           |  4 +-
     net/socket/bind.c                             |  6 +-
     net/socket/getsockname.c                      |  6 +-
     net/socket/getsockopt.c                       |  4 +-
     net/socket/listen.c                           |  4 +-
     net/socket/net_clone.c                        |  2 +-
     net/socket/net_close.c                        | 14 +--
     net/socket/net_dupsd.c                        |  2 +-
     net/socket/net_dupsd2.c                       |  2 +-
     net/socket/net_poll.c                         |  8 +-
     net/socket/net_sendfile.c                     | 10 +--
     net/socket/net_timeo.c                        |  2 +-
     net/socket/recv.c                             |  2 +-
     net/socket/recvfrom.c                         | 46 +++++-----
     net/socket/send.c                             |  4 +-
     net/socket/sendto.c                           |  4 +-
     net/socket/setsockopt.c                       |  4 +-
     net/socket/socket.c                           |  4 +-
     net/socket/socket.h                           |  8 +-
     net/tcp/tcp.h                                 | 58 ++++++------
     net/tcp/tcp_accept.c                          |  6 +-
     net/tcp/tcp_backlog.c                         | 12 +--
     net/tcp/tcp_callback.c                        |  6 +-
     net/tcp/tcp_finddev.c                         | 12 +--
     net/tcp/tcp_ipselect.c                        |  4 +-
     net/tcp/tcp_listen.c                          | 12 +--
     net/tcp/tcp_netpoll.c                         |  6 +-
     net/tcp/tcp_send_buffered.c                   | 16 ++--
     net/tcp/tcp_send_unbuffered.c                 | 14 +--
     net/tcp/tcp_wrbuffer.c                        |  8 +-
     net/udp/udp.h                                 | 22 ++---
     net/udp/udp_callback.c                        |  6 +-
     net/udp/udp_finddev.c                         |  8 +-
     net/udp/udp_ipselect.c                        |  4 +-
     net/udp/udp_netpoll.c                         |  6 +-
     net/udp/udp_psock_send.c                      |  2 +-
     net/udp/udp_psock_sendto.c                    |  8 +-
     net/usrsock/usrsock_close.c                   |  2 +-
     net/usrsock/usrsock_event.c                   |  2 +-
     net/usrsock/usrsock_getsockname.c             |  2 +-
     net/usrsock/usrsock_getsockopt.c              |  2 +-
     net/usrsock/usrsock_poll.c                    |  6 +-
     net/usrsock/usrsock_recvfrom.c                |  2 +-
     net/usrsock/usrsock_sendto.c                  |  2 +-
     net/usrsock/usrsock_setsockopt.c              |  2 +-
     net/usrsock/usrsock_socket.c                  |  2 +-
     net/utils/net_dsec2tick.c                     |  2 +-
     net/utils/net_dsec2timeval.c                  |  2 +-
     net/utils/net_ipv6_maskcmp.c                  |  2 +-
     net/utils/net_ipv6_pref2mask.c                |  2 +-
     net/utils/net_lock.c                          | 12 +--
     net/utils/net_timeval2dsec.c                  |  2 +-
     net/utils/utils.h                             | 10 +--
     sched/mqueue/mq_getattr.c                     |  2 +-
     sched/mqueue/mq_setattr.c                     |  2 +-
     sched/sched/sched_cpuload.c                   |  2 +-
     sched/semaphore/sem_setprotocol.c             |  2 +-
     wireless/ieee802154/mac802154_loopback.c      | 20 ++---
     213 files changed, 730 insertions(+), 730 deletions(-)
    
    diff --git a/crypto/random_pool.c b/crypto/random_pool.c
    index 7fd761be00..f6a53d7119 100644
    --- a/crypto/random_pool.c
    +++ b/crypto/random_pool.c
    @@ -136,7 +136,7 @@ static const uint32_t pool_twist[8] =
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: addentropy
    + * Name: addentropy
      *
      * Description:
      *
    @@ -201,7 +201,7 @@ static void addentropy(FAR const uint32_t *buf, size_t n, bool inc_new)
     }
     
     /****************************************************************************
    - * Function: getentropy
    + * Name: getentropy
      *
      * Description:
      *   Hash entropy pool to BLAKE2s context. This is an internal interface for
    @@ -385,7 +385,7 @@ static void rng_init(void)
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: up_rngaddint
    + * Name: up_rngaddint
      *
      * Description:
      *   Add one integer to entropy pool, contributing a specific kind
    @@ -410,7 +410,7 @@ void up_rngaddint(enum rnd_source_t kindof, int val)
     }
     
     /****************************************************************************
    - * Function: up_rngaddentropy
    + * Name: up_rngaddentropy
      *
      * Description:
      *   Add buffer of integers to entropy pool.
    @@ -490,7 +490,7 @@ void up_rngaddentropy(enum rnd_source_t kindof, FAR const uint32_t *buf,
     }
     
     /****************************************************************************
    - * Function: up_rngreseed
    + * Name: up_rngreseed
      *
      * Description:
      *   Force reseeding random number generator from entropy pool
    @@ -513,7 +513,7 @@ void up_rngreseed(void)
     }
     
     /****************************************************************************
    - * Function: up_randompool_initialize
    + * Name: up_randompool_initialize
      *
      * Description:
      *   Initialize entropy pool and random number generator
    @@ -530,7 +530,7 @@ void up_randompool_initialize(void)
     }
     
     /****************************************************************************
    - * Function: getrandom
    + * Name: getrandom
      *
      * Description:
      *   Fill a buffer of arbitrary length with randomness. This is the
    diff --git a/drivers/input/ads7843e.c b/drivers/input/ads7843e.c
    index 6e4e9395ec..820cb873f2 100644
    --- a/drivers/input/ads7843e.c
    +++ b/drivers/input/ads7843e.c
    @@ -159,7 +159,7 @@ static struct ads7843e_dev_s *g_ads7843elist;
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: ads7843e_lock
    + * Name: ads7843e_lock
      *
      * Description:
      *   Lock the SPI bus and re-configure as necessary.  This function must be
    @@ -198,7 +198,7 @@ static void ads7843e_lock(FAR struct spi_dev_s *spi)
     }
     
     /****************************************************************************
    - * Function: ads7843e_unlock
    + * Name: ads7843e_unlock
      *
      * Description:
      *   Un-lock the SPI bus after each transfer,  possibly losing the current
    diff --git a/drivers/input/max11802.c b/drivers/input/max11802.c
    index 7fb2087f06..c3cd4c09f3 100644
    --- a/drivers/input/max11802.c
    +++ b/drivers/input/max11802.c
    @@ -159,7 +159,7 @@ static struct max11802_dev_s *g_max11802list;
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: max11802_lock
    + * Name: max11802_lock
      *
      * Description:
      *   Lock the SPI bus and re-configure as necessary.  This function must be
    @@ -196,7 +196,7 @@ static void max11802_lock(FAR struct spi_dev_s *spi)
     }
     
     /****************************************************************************
    - * Function: max11802_unlock
    + * Name: max11802_unlock
      *
      * Description:
      *   Un-lock the SPI bus after each transfer, possibly losing the current
    diff --git a/drivers/iob/iob_dump.c b/drivers/iob/iob_dump.c
    index 470ba740ac..e2f72edb8d 100644
    --- a/drivers/iob/iob_dump.c
    +++ b/drivers/iob/iob_dump.c
    @@ -61,7 +61,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: iob_dump
    + * Name: iob_dump
      *
      * Description:
      *   Dump the contents of a I/O buffer chain
    diff --git a/drivers/lcd/nokia6100.c b/drivers/lcd/nokia6100.c
    index 3b4a05383d..b67af2bada 100644
    --- a/drivers/lcd/nokia6100.c
    +++ b/drivers/lcd/nokia6100.c
    @@ -637,7 +637,7 @@ static const uint8_t g_setcon[] =
      **************************************************************************************/
     
     /**************************************************************************************
    - * Function: nokia_select
    + * Name: nokia_select
      *
      * Description:
      *   Select the SPI, locking and  re-configuring if necessary
    @@ -674,7 +674,7 @@ static void nokia_select(FAR struct spi_dev_s *spi)
     }
     
     /**************************************************************************************
    - * Function: nokia_deselect
    + * Name: nokia_deselect
      *
      * Description:
      *   De-select the SPI
    diff --git a/drivers/lcd/st7567.c b/drivers/lcd/st7567.c
    index a1f8b13661..c95ffaa8a3 100644
    --- a/drivers/lcd/st7567.c
    +++ b/drivers/lcd/st7567.c
    @@ -343,7 +343,7 @@ static struct st7567_dev_s g_st7567dev =
      **************************************************************************************/
     
     /**************************************************************************************
    - * Function: st7567_select
    + * Name: st7567_select
      *
      * Description:
      *   Select the SPI, locking and  re-configuring if necessary
    @@ -380,7 +380,7 @@ static void st7567_select(FAR struct spi_dev_s *spi)
     }
     
     /**************************************************************************************
    - * Function: st7567_deselect
    + * Name: st7567_deselect
      *
      * Description:
      *   De-select the SPI
    diff --git a/drivers/lcd/ug-9664hswag01.c b/drivers/lcd/ug-9664hswag01.c
    index 1dadf52620..f56c8f7cd1 100644
    --- a/drivers/lcd/ug-9664hswag01.c
    +++ b/drivers/lcd/ug-9664hswag01.c
    @@ -377,7 +377,7 @@ static inline FAR const char *ug_powerstring(uint8_t power)
     }
     
     /**************************************************************************************
    - * Function: ug_select
    + * Name: ug_select
      *
      * Description:
      *   Select the SPI, locking and  re-configuring if necessary
    @@ -414,7 +414,7 @@ static void ug_select(FAR struct spi_dev_s *spi)
     }
     
     /**************************************************************************************
    - * Function: ug_deselect
    + * Name: ug_deselect
      *
      * Description:
      *   De-select the SPI
    diff --git a/drivers/net/cs89x0.c b/drivers/net/cs89x0.c
    index ef2f7f46ae..e64c2404e0 100644
    --- a/drivers/net/cs89x0.c
    +++ b/drivers/net/cs89x0.c
    @@ -137,7 +137,7 @@ static int cs89x0_rmmac(struct net_driver_s *dev, FAR const uint8_t *mac);
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: cs89x0_getreg and cs89x0_putreg
    + * Name: cs89x0_getreg and cs89x0_putreg
      *
      * Description:
      *   Read from and write to a CS89x0 register
    @@ -172,7 +172,7 @@ static void cs89x0_putreg(struct cs89x0_driver_s *cs89x0, int offset, uint16_t v
     }
     
     /****************************************************************************
    - * Function: cs89x0_getppreg and cs89x0_putppreg
    + * Name: cs89x0_getppreg and cs89x0_putppreg
      *
      * Description:
      *   Read from and write to a CS89x0 page packet register
    @@ -257,7 +257,7 @@ static void cs89x0_putppreg(struct cs89x0_driver_s *cs89x0, int addr, uint16_t v
     }
     
     /****************************************************************************
    - * Function: cs89x0_transmit
    + * Name: cs89x0_transmit
      *
      * Description:
      *   Start hardware transmission.  Called either from the txdone interrupt
    @@ -298,7 +298,7 @@ static int cs89x0_transmit(struct cs89x0_driver_s *cs89x0)
     }
     
     /****************************************************************************
    - * Function: cs89x0_txpoll
    + * Name: cs89x0_txpoll
      *
      * Description:
      *   The transmitter is available, check if the network has any outgoing packets ready
    @@ -368,7 +368,7 @@ static int cs89x0_txpoll(struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: cs89x0_receive
    + * Name: cs89x0_receive
      *
      * Description:
      *   An interrupt was received indicating the availability of a new RX packet
    @@ -554,7 +554,7 @@ static void cs89x0_receive(FAR struct cs89x0_driver_s *cs89x0, uint16_t isq)
     }
     
     /****************************************************************************
    - * Function: cs89x0_txdone
    + * Name: cs89x0_txdone
      *
      * Description:
      *   An interrupt was received indicating that the last TX packet(s) is done
    @@ -611,7 +611,7 @@ static void cs89x0_txdone(struct cs89x0_driver_s *cs89x0, uint16_t isq)
     }
     
     /****************************************************************************
    - * Function: cs89x0_interrupt
    + * Name: cs89x0_interrupt
      *
      * Description:
      *   Hardware interrupt handler
    @@ -680,7 +680,7 @@ static int cs89x0_interrupt(int irq, FAR void *context, FAR void *arg)
     }
     
     /****************************************************************************
    - * Function: cs89x0_txtimeout
    + * Name: cs89x0_txtimeout
      *
      * Description:
      *   Our TX watchdog timed out.  Called from the timer interrupt handler.
    @@ -713,7 +713,7 @@ static void cs89x0_txtimeout(int argc, uint32_t arg, ...)
     }
     
     /****************************************************************************
    - * Function: cs89x0_polltimer
    + * Name: cs89x0_polltimer
      *
      * Description:
      *   Periodic timer handler.  Called from the timer interrupt handler.
    @@ -747,7 +747,7 @@ static void cs89x0_polltimer(int argc, uint32_t arg, ...)
     }
     
     /****************************************************************************
    - * Function: cs89x0_ifup
    + * Name: cs89x0_ifup
      *
      * Description:
      *   NuttX Callback: Bring up the Ethernet interface when an IP address is
    @@ -787,7 +787,7 @@ static int cs89x0_ifup(struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: cs89x0_ifdown
    + * Name: cs89x0_ifdown
      *
      * Description:
      *   NuttX Callback: Stop the interface.
    @@ -825,7 +825,7 @@ static int cs89x0_ifdown(struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: cs89x0_txavail
    + * Name: cs89x0_txavail
      *
      * Description:
      *   Driver callback invoked when new TX data is available.  This is a
    @@ -867,7 +867,7 @@ static int cs89x0_txavail(struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: cs89x0_addmac
    + * Name: cs89x0_addmac
      *
      * Description:
      *   NuttX Callback: Add the specified MAC address to the hardware multicast
    @@ -897,7 +897,7 @@ static int cs89x0_addmac(struct net_driver_s *dev, FAR const uint8_t *mac)
     #endif
     
     /****************************************************************************
    - * Function: cs89x0_rmmac
    + * Name: cs89x0_rmmac
      *
      * Description:
      *   NuttX Callback: Remove the specified MAC address from the hardware multicast
    @@ -931,7 +931,7 @@ static int cs89x0_rmmac(struct net_driver_s *dev, FAR const uint8_t *mac)
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: cs89x0_initialize
    + * Name: cs89x0_initialize
      *
      * Description:
      *   Initialize the Ethernet driver
    diff --git a/drivers/net/dm90x0.c b/drivers/net/dm90x0.c
    index 4707ff87f4..a812686e8a 100644
    --- a/drivers/net/dm90x0.c
    +++ b/drivers/net/dm90x0.c
    @@ -419,7 +419,7 @@ static void dm9x_reset(struct dm9x_driver_s *priv);
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: getreg and setreg
    + * Name: getreg and setreg
      *
      * Description:
      *   Access to memory-mapped DM90x0 8-bit registers
    @@ -448,7 +448,7 @@ static void putreg(int reg, uint8_t value)
     }
     
     /****************************************************************************
    - * Function: read8, read16, read32
    + * Name: read8, read16, read32
      *
      * Description:
      *   Read packet data from the DM90x0 SRAM based on its current I/O mode
    @@ -496,7 +496,7 @@ static void read32(FAR uint8_t *ptr, int len)
     }
     
     /****************************************************************************
    - * Function: discard8, discard16, discard32
    + * Name: discard8, discard16, discard32
      *
      * Description:
      *   Read and discard packet data in the DM90x0 SRAM based on its current
    @@ -540,7 +540,7 @@ static void discard32(int len)
     }
     
     /****************************************************************************
    - * Function: write8, write16, write32
    + * Name: write8, write16, write32
      *
      * Description:
      *   Write packet data into the DM90x0 SRAM based on its current I/O mode
    @@ -591,7 +591,7 @@ static void write32(FAR const uint8_t *ptr, int len)
     }
     
     /****************************************************************************
    - * Function: dm9x_readsrom
    + * Name: dm9x_readsrom
      *
      * Description:
      *   Read a word from SROM
    @@ -619,7 +619,7 @@ static uint16_t dm9x_readsrom(struct dm9x_driver_s *priv, int offset)
     #endif
     
     /****************************************************************************
    - * Function: dm9x_phyread and dm9x_phywrite
    + * Name: dm9x_phyread and dm9x_phywrite
      *
      * Description:
      *   Read/write data from/to the PHY
    @@ -672,7 +672,7 @@ static void dm9x_phywrite(struct dm9x_driver_s *priv, int reg, uint16_t value)
     }
     
     /****************************************************************************
    - * Function: dm9x_rxchecksumready
    + * Name: dm9x_rxchecksumready
      *
      * Description:
      *   Return true if the RX checksum is available
    @@ -700,7 +700,7 @@ static inline bool dm9x_rxchecksumready(uint8_t rxbyte)
     #endif
     
     /****************************************************************************
    - * Function: dm9x_transmit
    + * Name: dm9x_transmit
      *
      * Description:
      *   Start hardware transmission.  Called either from the txdone interrupt
    @@ -767,7 +767,7 @@ static int dm9x_transmit(struct dm9x_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: dm9x_txpoll
    + * Name: dm9x_txpoll
      *
      * Description:
      *   The transmitter is available, check if the network has any outgoing packets ready
    @@ -843,7 +843,7 @@ static int dm9x_txpoll(struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: dm9x_receive
    + * Name: dm9x_receive
      *
      * Description:
      *   An interrupt was received indicating the availability of a new RX packet
    @@ -1041,7 +1041,7 @@ static void dm9x_receive(FAR struct dm9x_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: dm9x_txdone
    + * Name: dm9x_txdone
      *
      * Description:
      *   An interrupt was received indicating that the last TX packet(s) is done
    @@ -1104,7 +1104,7 @@ static void dm9x_txdone(struct dm9x_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: dm9x_interrupt_work
    + * Name: dm9x_interrupt_work
      *
      * Description:
      *   Perform interrupt related work from the worker thread
    @@ -1223,7 +1223,7 @@ static void dm9x_interrupt_work(FAR void *arg)
     }
     
     /****************************************************************************
    - * Function: dm9x_interrupt
    + * Name: dm9x_interrupt
      *
      * Description:
      *   Hardware interrupt handler
    @@ -1275,7 +1275,7 @@ static int dm9x_interrupt(int irq, FAR void *context, FAR void *arg)
     }
     
     /****************************************************************************
    - * Function: dm9x_txtimeout_work
    + * Name: dm9x_txtimeout_work
      *
      * Description:
      *   Perform TX timeout related work from the worker thread
    @@ -1319,7 +1319,7 @@ static void dm9x_txtimeout_work(FAR void *arg)
     }
     
     /****************************************************************************
    - * Function: dm9x_txtimeout_expiry
    + * Name: dm9x_txtimeout_expiry
      *
      * Description:
      *   Our TX watchdog timed out.  Called from the timer interrupt handler.
    @@ -1354,7 +1354,7 @@ static void dm9x_txtimeout_expiry(int argc, wdparm_t arg, ...)
     }
     
     /****************************************************************************
    - * Function: dm9x_poll_work
    + * Name: dm9x_poll_work
      *
      * Description:
      *   Perform periodic polling from the worker thread
    @@ -1407,7 +1407,7 @@ static void dm9x_poll_work(FAR void *arg)
     }
     
     /****************************************************************************
    - * Function: dm9x_poll_expiry
    + * Name: dm9x_poll_expiry
      *
      * Description:
      *   Periodic timer handler.  Called from the timer interrupt handler.
    @@ -1434,7 +1434,7 @@ static void dm9x_poll_expiry(int argc, wdparm_t arg, ...)
     }
     
     /****************************************************************************
    - * Function: dm9x_phymode
    + * Name: dm9x_phymode
      *
      * Description:
      *   Configure the PHY operating mode
    @@ -1478,7 +1478,7 @@ static inline void dm9x_phymode(struct dm9x_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: dm9x_ifup
    + * Name: dm9x_ifup
      *
      * Description:
      *   NuttX Callback: Bring up the DM90x0 interface when an IP address is
    @@ -1545,7 +1545,7 @@ static int dm9x_ifup(struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: dm9x_ifdown
    + * Name: dm9x_ifdown
      *
      * Description:
      *   NuttX Callback: Stop the interface.
    @@ -1591,7 +1591,7 @@ static int dm9x_ifdown(struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: dm9x_txavail_work
    + * Name: dm9x_txavail_work
      *
      * Description:
      *   Perform an out-of-cycle poll on the worker thread.
    @@ -1635,7 +1635,7 @@ static void dm9x_txavail_work(FAR void *arg)
     }
     
     /****************************************************************************
    - * Function: dm9x_txavail
    + * Name: dm9x_txavail
      *
      * Description:
      *   Driver callback invoked when new TX data is available.  This is a
    @@ -1673,7 +1673,7 @@ static int dm9x_txavail(FAR struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: dm9x_addmac
    + * Name: dm9x_addmac
      *
      * Description:
      *   NuttX Callback: Add the specified MAC address to the hardware multicast
    @@ -1703,7 +1703,7 @@ static int dm9x_addmac(struct net_driver_s *dev, FAR const uint8_t *mac)
     #endif
     
     /****************************************************************************
    - * Function: dm9x_rmmac
    + * Name: dm9x_rmmac
      *
      * Description:
      *   NuttX Callback: Remove the specified MAC address from the hardware multicast
    @@ -1733,7 +1733,7 @@ static int dm9x_rmmac(struct net_driver_s *dev, FAR const uint8_t *mac)
     #endif
     
     /****************************************************************************
    - * Function: dm9x_bringup
    + * Name: dm9x_bringup
      *
      * Description:
      *   Initialize the dm90x0 chip
    @@ -1829,7 +1829,7 @@ static void dm9x_bringup(struct dm9x_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: dm9x_reset
    + * Name: dm9x_reset
      *
      * Description:
      *   Stop, reset, re-initialize, and restart the DM90x0 chip and driver.  At
    @@ -1886,7 +1886,7 @@ static void dm9x_reset(struct dm9x_driver_s *priv)
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: dm9x_initialize
    + * Name: dm9x_initialize
      *
      * Description:
      *   Initialize the DM90x0 driver
    diff --git a/drivers/net/enc28j60.c b/drivers/net/enc28j60.c
    index 4b6f93a712..d0034543a8 100644
    --- a/drivers/net/enc28j60.c
    +++ b/drivers/net/enc28j60.c
    @@ -358,7 +358,7 @@ static int  enc_reset(FAR struct enc_driver_s *priv);
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: enc_configspi
    + * Name: enc_configspi
      *
      * Description:
      *   Configure the SPI for use with the ENC28J60
    @@ -384,7 +384,7 @@ static inline void enc_configspi(FAR struct spi_dev_s *spi)
     }
     
     /****************************************************************************
    - * Function: enc_lock
    + * Name: enc_lock
      *
      * Description:
      *   Select the SPI, locking and  re-configuring if necessary
    @@ -418,7 +418,7 @@ static void enc_lock(FAR struct enc_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: enc_unlock
    + * Name: enc_unlock
      *
      * Description:
      *   De-select the SPI
    @@ -441,7 +441,7 @@ static inline void enc_unlock(FAR struct enc_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: enc_rdgreg2
    + * Name: enc_rdgreg2
      *
      * Description:
      *   Read a global register (EIE, EIR, ESTAT, ECON2, or ECON1).  The cmd
    @@ -484,7 +484,7 @@ static uint8_t enc_rdgreg2(FAR struct enc_driver_s *priv, uint8_t cmd)
     }
     
     /****************************************************************************
    - * Function: enc_wrgreg2
    + * Name: enc_wrgreg2
      *
      * Description:
      *   Write to a global register (EIE, EIR, ESTAT, ECON2, or ECON1).  The cmd
    @@ -525,7 +525,7 @@ static void enc_wrgreg2(FAR struct enc_driver_s *priv, uint8_t cmd,
     }
     
     /****************************************************************************
    - * Function: enc_src
    + * Name: enc_src
      *
      * Description:
      *   Send the single byte system reset command (SRC).
    @@ -579,7 +579,7 @@ static inline void enc_src(FAR struct enc_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: enc_setbank
    + * Name: enc_setbank
      *
      * Description:
      *   Set the bank for these next control register access.
    @@ -622,7 +622,7 @@ static void enc_setbank(FAR struct enc_driver_s *priv, uint8_t bank)
     }
     
     /****************************************************************************
    - * Function: enc_rdbreg
    + * Name: enc_rdbreg
      *
      * Description:
      *   Read from a banked control register using the RCR command.
    @@ -677,7 +677,7 @@ static uint8_t enc_rdbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg)
     }
     
     /****************************************************************************
    - * Function: enc_wrbreg
    + * Name: enc_wrbreg
      *
      * Description:
      *   Write to a banked control register using the WCR command.  Unlike
    @@ -723,7 +723,7 @@ static void enc_wrbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg,
     }
     
     /****************************************************************************
    - * Function: enc_waitbreg
    + * Name: enc_waitbreg
      *
      * Description:
      *   Wait until banked register bit(s) take a specific value (or a timeout
    @@ -764,7 +764,7 @@ static int enc_waitbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg,
     }
     
     /****************************************************************************
    - * Function: enc_txdump enc_rxdump
    + * Name: enc_txdump enc_rxdump
      *
      * Description:
      *   Dump registers associated with receiving or sending packets.
    @@ -836,7 +836,7 @@ static void enc_txdump(FAR struct enc_driver_s *priv)
     #endif
     
     /****************************************************************************
    - * Function: enc_rdbuffer
    + * Name: enc_rdbuffer
      *
      * Description:
      *   Read a buffer of data.
    @@ -878,7 +878,7 @@ static void enc_rdbuffer(FAR struct enc_driver_s *priv, FAR uint8_t *buffer,
     }
     
     /****************************************************************************
    - * Function: enc_wrbuffer
    + * Name: enc_wrbuffer
      *
      * Description:
      *   Write a buffer of data.
    @@ -961,7 +961,7 @@ static inline void enc_wrbuffer(FAR struct enc_driver_s *priv,
     }
     
     /****************************************************************************
    - * Function: enc_rdphy
    + * Name: enc_rdphy
      *
      * Description:
      *   Read 16-bits of PHY data.
    @@ -1022,7 +1022,7 @@ static uint16_t enc_rdphy(FAR struct enc_driver_s *priv, uint8_t phyaddr)
     }
     
     /****************************************************************************
    - * Function: enc_wrphy
    + * Name: enc_wrphy
      *
      * Description:
      *   write 16-bits of PHY data.
    @@ -1075,7 +1075,7 @@ static void enc_wrphy(FAR struct enc_driver_s *priv, uint8_t phyaddr,
     }
     
     /****************************************************************************
    - * Function: enc_transmit
    + * Name: enc_transmit
      *
      * Description:
      *   Start hardware transmission.  Called either from:
    @@ -1159,7 +1159,7 @@ static int enc_transmit(FAR struct enc_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: enc_txpoll
    + * Name: enc_txpoll
      *
      * Description:
      *   The transmitter is available, check if the network has any outgoing packets ready
    @@ -1230,7 +1230,7 @@ static int enc_txpoll(struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: enc_linkstatus
    + * Name: enc_linkstatus
      *
      * Description:
      *   The current link status can be obtained from the PHSTAT1.LLSTAT or
    @@ -1256,7 +1256,7 @@ static void enc_linkstatus(FAR struct enc_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: enc_txif
    + * Name: enc_txif
      *
      * Description:
      *   An TXIF interrupt was received indicating that the last TX packet(s) is
    @@ -1293,7 +1293,7 @@ static void enc_txif(FAR struct enc_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: enc_txerif
    + * Name: enc_txerif
      *
      * Description:
      *   An TXERIF interrupt was received indicating that a TX abort has occurred.
    @@ -1336,7 +1336,7 @@ static void enc_txerif(FAR struct enc_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: enc_rxerif
    + * Name: enc_rxerif
      *
      * Description:
      *   An RXERIF interrupt was received indicating that the last TX packet(s) is
    @@ -1358,7 +1358,7 @@ static void enc_rxerif(FAR struct enc_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: enc_rxdispatch
    + * Name: enc_rxdispatch
      *
      * Description:
      *   Give the newly received packet to the network.
    @@ -1489,7 +1489,7 @@ static void enc_rxdispatch(FAR struct enc_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: enc_pktif
    + * Name: enc_pktif
      *
      * Description:
      *   An interrupt was received indicating the availability of a new RX packet
    @@ -1595,7 +1595,7 @@ static void enc_pktif(FAR struct enc_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: enc_irqworker
    + * Name: enc_irqworker
      *
      * Description:
      *   Perform interrupt handling logic outside of the interrupt handler (on
    @@ -1815,7 +1815,7 @@ static void enc_irqworker(FAR void *arg)
     }
     
     /****************************************************************************
    - * Function: enc_interrupt
    + * Name: enc_interrupt
      *
      * Description:
      *   Hardware interrupt handler
    @@ -1854,7 +1854,7 @@ static int enc_interrupt(int irq, FAR void *context, FAR void *arg)
     }
     
     /****************************************************************************
    - * Function: enc_toworker
    + * Name: enc_toworker
      *
      * Description:
      *   Our TX watchdog timed out.  This is the worker thread continuation of
    @@ -1906,7 +1906,7 @@ static void enc_toworker(FAR void *arg)
     }
     
     /****************************************************************************
    - * Function: enc_txtimeout
    + * Name: enc_txtimeout
      *
      * Description:
      *   Our TX watchdog timed out.  Called from the timer interrupt handler.
    @@ -1947,7 +1947,7 @@ static void enc_txtimeout(int argc, uint32_t arg, ...)
     }
     
     /****************************************************************************
    - * Function: enc_pollworker
    + * Name: enc_pollworker
      *
      * Description:
      *   Periodic timer handler continuation.
    @@ -2002,7 +2002,7 @@ static void enc_pollworker(FAR void *arg)
     }
     
     /****************************************************************************
    - * Function: enc_polltimer
    + * Name: enc_polltimer
      *
      * Description:
      *   Periodic timer handler.  Called from the timer interrupt handler.
    @@ -2042,7 +2042,7 @@ static void enc_polltimer(int argc, uint32_t arg, ...)
     }
     
     /****************************************************************************
    - * Function: enc_ifup
    + * Name: enc_ifup
      *
      * Description:
      *   NuttX Callback: Bring up the Ethernet interface when an IP address is
    @@ -2114,7 +2114,7 @@ static int enc_ifup(struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: enc_ifdown
    + * Name: enc_ifdown
      *
      * Description:
      *   NuttX Callback: Stop the interface.
    @@ -2168,7 +2168,7 @@ static int enc_ifdown(struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: enc_txavail
    + * Name: enc_txavail
      *
      * Description:
      *   Driver callback invoked when new TX data is available.  This is a
    @@ -2222,7 +2222,7 @@ static int enc_txavail(struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: enc_addmac
    + * Name: enc_addmac
      *
      * Description:
      *   NuttX Callback: Add the specified MAC address to the hardware multicast
    @@ -2260,7 +2260,7 @@ static int enc_addmac(struct net_driver_s *dev, FAR const uint8_t *mac)
     #endif
     
     /****************************************************************************
    - * Function: enc_rmmac
    + * Name: enc_rmmac
      *
      * Description:
      *   NuttX Callback: Remove the specified MAC address from the hardware multicast
    @@ -2298,7 +2298,7 @@ static int enc_rmmac(struct net_driver_s *dev, FAR const uint8_t *mac)
     #endif
     
     /****************************************************************************
    - * Function: enc_pwrsave
    + * Name: enc_pwrsave
      *
      * Description:
      *   The ENC28J60 may be commanded to power-down via the SPI interface.
    @@ -2360,7 +2360,7 @@ static void enc_pwrsave(FAR struct enc_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: enc_pwrfull
    + * Name: enc_pwrfull
      *
      * Description:
      *   When normal operation is desired, the host controller must perform
    @@ -2412,7 +2412,7 @@ static void enc_pwrfull(FAR struct enc_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: enc_setmacaddr
    + * Name: enc_setmacaddr
      *
      * Description:
      *   Set the MAC address to the configured value.  This is done after ifup
    @@ -2449,7 +2449,7 @@ static void enc_setmacaddr(FAR struct enc_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: enc_reset
    + * Name: enc_reset
      *
      * Description:
      *   Stop, reset, re-initialize, and restart the ENC28J60.  This is done
    @@ -2588,7 +2588,7 @@ static int enc_reset(FAR struct enc_driver_s *priv)
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: enc_initialize
    + * Name: enc_initialize
      *
      * Description:
      *   Initialize the Ethernet driver.  The ENC28J60 device is assumed to be
    diff --git a/drivers/net/encx24j600.c b/drivers/net/encx24j600.c
    index 3394710f8a..e15cfe71dc 100644
    --- a/drivers/net/encx24j600.c
    +++ b/drivers/net/encx24j600.c
    @@ -378,7 +378,7 @@ static int  enc_reset(FAR struct enc_driver_s *priv);
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: enc_lock
    + * Name: enc_lock
      *
      * Description:
      *   Select the SPI, locking and  re-configuring if necessary
    @@ -412,7 +412,7 @@ static void enc_lock(FAR struct enc_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: enc_unlock
    + * Name: enc_unlock
      *
      * Description:
      *   De-select the SPI
    @@ -435,7 +435,7 @@ static inline void enc_unlock(FAR struct enc_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: enc_cmd
    + * Name: enc_cmd
      *
      * Description:
      *   Execute two byte command.
    @@ -471,7 +471,7 @@ static void enc_cmd(FAR struct enc_driver_s *priv, uint8_t cmd, uint16_t arg)
     }
     
     /****************************************************************************
    - * Function: enc_setethrst
    + * Name: enc_setethrst
      *
      * Description:
      *   Issues System Reset by setting ETHRST (ECON2<4>)
    @@ -507,7 +507,7 @@ static inline void enc_setethrst(FAR struct enc_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: enc_setbank
    + * Name: enc_setbank
      *
      * Description:
      *   Set the bank for the next control register access.
    @@ -547,7 +547,7 @@ static void enc_setbank(FAR struct enc_driver_s *priv, uint8_t bank)
     }
     
     /****************************************************************************
    - * Function: enc_rdreg
    + * Name: enc_rdreg
      *
      * Description:
      *   Read one word from a control register using the RCR command.
    @@ -587,7 +587,7 @@ static uint16_t enc_rdreg(FAR struct enc_driver_s *priv, uint16_t ctrlreg)
     }
     
     /****************************************************************************
    - * Function: enc_wrreg
    + * Name: enc_wrreg
      *
      * Description:
      *   Write one word to a control register using the WCR command.
    @@ -623,7 +623,7 @@ static void enc_wrreg(FAR struct enc_driver_s *priv, uint16_t ctrlreg,
     }
     
     /****************************************************************************
    - * Function: enc_waitbreg
    + * Name: enc_waitbreg
      *
      * Description:
      *   Wait until banked register bit(s) take a specific value (or a timeout
    @@ -664,7 +664,7 @@ static int enc_waitreg(FAR struct enc_driver_s *priv, uint16_t ctrlreg,
     }
     
     /****************************************************************************
    - * Function: enc_bfs
    + * Name: enc_bfs
      *
      * Description:
      *   Bit Field Set.
    @@ -709,7 +709,7 @@ static void enc_bfs(FAR struct enc_driver_s *priv, uint16_t ctrlreg,
     }
     
     /****************************************************************************
    - * Function: enc_bfc
    + * Name: enc_bfc
      *
      * Description:
      *   Bit Field Clear.
    @@ -754,7 +754,7 @@ static void enc_bfc(FAR struct enc_driver_s *priv, uint16_t ctrlreg,
     }
     
     /****************************************************************************
    - * Function: enc_txdump enc_rxdump
    + * Name: enc_txdump enc_rxdump
      *
      * Description:
      *   Dump registers associated with receiving or sending packets.
    @@ -826,7 +826,7 @@ static void enc_txdump(FAR struct enc_driver_s *priv)
     #endif
     
     /****************************************************************************
    - * Function: enc_rdbuffer
    + * Name: enc_rdbuffer
      *
      * Description:
      *   Read a buffer of data from RX Data Buffer.
    @@ -868,7 +868,7 @@ static void enc_rdbuffer(FAR struct enc_driver_s *priv, FAR uint8_t *buffer,
     }
     
     /****************************************************************************
    - * Function: enc_wrbuffer
    + * Name: enc_wrbuffer
      *
      * Description:
      *   Write a buffer of data.
    @@ -901,7 +901,7 @@ static inline void enc_wrbuffer(FAR struct enc_driver_s *priv,
     }
     
     /****************************************************************************
    - * Function: enc_rdphy
    + * Name: enc_rdphy
      *
      * Description:
      *   Read 16-bits of PHY data.
    @@ -961,7 +961,7 @@ static uint16_t enc_rdphy(FAR struct enc_driver_s *priv, uint8_t phyaddr)
     }
     
     /****************************************************************************
    - * Function: enc_wrphy
    + * Name: enc_wrphy
      *
      * Description:
      *   write 16-bits of PHY data.
    @@ -1009,7 +1009,7 @@ static void enc_wrphy(FAR struct enc_driver_s *priv, uint8_t phyaddr,
     }
     
     /****************************************************************************
    - * Function: enc_transmit
    + * Name: enc_transmit
      *
      * Description:
      *   Start hardware transmission.  Called either from:
    @@ -1075,7 +1075,7 @@ static int enc_transmit(FAR struct enc_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: enc_txenqueue
    + * Name: enc_txenqueue
      *
      * Description:
      *   Write packet from d_buf to the enc's SRAM if a free descriptor is available.
    @@ -1143,7 +1143,7 @@ static int enc_txenqueue(FAR struct enc_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: enc_txpoll
    + * Name: enc_txpoll
      *
      * Description:
      *   Enqueues network packets if available.
    @@ -1212,7 +1212,7 @@ static int enc_txpoll(struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: enc_linkstatus
    + * Name: enc_linkstatus
      *
      * Description:
      *   The current link status can be obtained from the PHSTAT1.LLSTAT or
    @@ -1268,7 +1268,7 @@ static void enc_linkstatus(FAR struct enc_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: enc_txif
    + * Name: enc_txif
      *
      * Description:
      *   An TXIF interrupt was received indicating that the last TX packet(s) is
    @@ -1308,7 +1308,7 @@ static void enc_txif(FAR struct enc_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: enc_rxldpkt
    + * Name: enc_rxldpkt
      *
      * Description:
      *   Load packet from the enc's RX buffer to the driver d_buf.
    @@ -1348,7 +1348,7 @@ static void enc_rxldpkt(FAR struct enc_driver_s *priv,
     }
     
     /****************************************************************************
    - * Function: enc_rxgetdescr
    + * Name: enc_rxgetdescr
      *
      * Description:
      *   Check for a free descriptor in the free list. If no free descriptor is
    @@ -1380,7 +1380,7 @@ static struct enc_descr_s *enc_rxgetdescr(FAR struct enc_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: enc_rxrmpkt
    + * Name: enc_rxrmpkt
      *
      * Description:
      *   Remove packet from the RX queue and free the block of memory in the enc's
    @@ -1439,7 +1439,7 @@ static void enc_rxrmpkt(FAR struct enc_driver_s *priv, FAR struct enc_descr_s *d
     }
     
     /****************************************************************************
    - * Function: enc_rxdispatch
    + * Name: enc_rxdispatch
      *
      * Description:
      *   Give the newly received packet to the network.
    @@ -1620,7 +1620,7 @@ static void enc_rxdispatch(FAR struct enc_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: enc_pktif
    + * Name: enc_pktif
      *
      * Description:
      *   An interrupt was received indicating the availability of a new RX packet
    @@ -1741,7 +1741,7 @@ static void enc_pktif(FAR struct enc_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: enc_rxabtif
    + * Name: enc_rxabtif
      *
      * Description:
      *   An interrupt was received indicating the abortion of an RX packet
    @@ -1807,7 +1807,7 @@ static void enc_rxabtif(FAR struct enc_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: enc_irqworker
    + * Name: enc_irqworker
      *
      * Description:
      *   Perform interrupt handling logic outside of the interrupt handler (on
    @@ -1980,7 +1980,7 @@ static void enc_irqworker(FAR void *arg)
     }
     
     /****************************************************************************
    - * Function: enc_interrupt
    + * Name: enc_interrupt
      *
      * Description:
      *   Hardware interrupt handler
    @@ -2019,7 +2019,7 @@ static int enc_interrupt(int irq, FAR void *context)
     }
     
     /****************************************************************************
    - * Function: enc_toworker
    + * Name: enc_toworker
      *
      * Description:
      *   Our TX watchdog timed out.  This is the worker thread continuation of
    @@ -2071,7 +2071,7 @@ static void enc_toworker(FAR void *arg)
     }
     
     /****************************************************************************
    - * Function: enc_txtimeout
    + * Name: enc_txtimeout
      *
      * Description:
      *   Our TX watchdog timed out.  Called from the timer interrupt handler.
    @@ -2112,7 +2112,7 @@ static void enc_txtimeout(int argc, uint32_t arg, ...)
     }
     
     /****************************************************************************
    - * Function: enc_pollworker
    + * Name: enc_pollworker
      *
      * Description:
      *   Periodic timer handler continuation.
    @@ -2166,7 +2166,7 @@ static void enc_pollworker(FAR void *arg)
     }
     
     /****************************************************************************
    - * Function: enc_polltimer
    + * Name: enc_polltimer
      *
      * Description:
      *   Periodic timer handler.  Called from the timer interrupt handler.
    @@ -2206,7 +2206,7 @@ static void enc_polltimer(int argc, uint32_t arg, ...)
     }
     
     /****************************************************************************
    - * Function: enc_ifup
    + * Name: enc_ifup
      *
      * Description:
      *   NuttX Callback: Bring up the Ethernet interface when an IP address is
    @@ -2282,7 +2282,7 @@ static int enc_ifup(struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: enc_ifdown
    + * Name: enc_ifdown
      *
      * Description:
      *   NuttX Callback: Stop the interface.
    @@ -2337,7 +2337,7 @@ static int enc_ifdown(struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: enc_txavail
    + * Name: enc_txavail
      *
      * Description:
      *   Driver callback invoked when new TX data is available.  This is a
    @@ -2392,7 +2392,7 @@ static int enc_txavail(struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: enc_rxavail
    + * Name: enc_rxavail
      *
      * Description:
      *   Driver callback invoked when new TX data is available.  This is a
    @@ -2424,7 +2424,7 @@ static int enc_rxavail(struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: enc_addmac
    + * Name: enc_addmac
      *
      * Description:
      *   NuttX Callback: Add the specified MAC address to the hardware multicast
    @@ -2462,7 +2462,7 @@ static int enc_addmac(struct net_driver_s *dev, FAR const uint8_t *mac)
     #endif
     
     /****************************************************************************
    - * Function: enc_rmmac
    + * Name: enc_rmmac
      *
      * Description:
      *   NuttX Callback: Remove the specified MAC address from the hardware multicast
    @@ -2500,7 +2500,7 @@ static int enc_rmmac(struct net_driver_s *dev, FAR const uint8_t *mac)
     #endif
     
     /****************************************************************************
    - * Function: enc_pwrsave
    + * Name: enc_pwrsave
      *
      * Description:
      *   The ENCX24J600 may be placed in Power-Down mode through the command
    @@ -2572,7 +2572,7 @@ static void enc_pwrsave(FAR struct enc_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: enc_ldmacaddr
    + * Name: enc_ldmacaddr
      *
      * Description:
      *   Load the MAC address from the ENCX24j600 and write it to the device
    @@ -2609,7 +2609,7 @@ static void enc_ldmacaddr(FAR struct enc_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: enc_setmacaddr
    + * Name: enc_setmacaddr
      *
      * Description:
      *   Set the MAC address to the configured value.  This is done after ifup
    @@ -2653,7 +2653,7 @@ static void enc_setmacaddr(FAR struct enc_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: enc_resetbuffers
    + * Name: enc_resetbuffers
      *
      * Description:
      *   Initializes the RX/TX queues and configures the enc's RX/TX buffers.
    @@ -2703,7 +2703,7 @@ static void enc_resetbuffers(FAR struct enc_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: enc_reset
    + * Name: enc_reset
      *
      * Description:
      *   Stop, reset, re-initialize, and restart the ENCX24J600.  This is done
    @@ -2822,7 +2822,7 @@ static int enc_reset(FAR struct enc_driver_s *priv)
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: enc_initialize
    + * Name: enc_initialize
      *
      * Description:
      *   Initialize the Ethernet driver.  The ENCX24J600 device is assumed to be
    diff --git a/drivers/net/ftmac100.c b/drivers/net/ftmac100.c
    index fbc5f909b1..7b02fa9e21 100644
    --- a/drivers/net/ftmac100.c
    +++ b/drivers/net/ftmac100.c
    @@ -244,7 +244,7 @@ static void ftmac100_ipv6multicast(FAR struct ftmac100_driver_s *priv);
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: ftmac100_transmit
    + * Name: ftmac100_transmit
      *
      * Description:
      *   Start hardware transmission.  Called either from the txdone interrupt
    @@ -331,7 +331,7 @@ static int ftmac100_transmit(FAR struct ftmac100_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: ftmac100_txpoll
    + * Name: ftmac100_txpoll
      *
      * Description:
      *   The transmitter is available, check if the network has any outgoing packets
    @@ -405,7 +405,7 @@ static int ftmac100_txpoll(struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: ftmac100_reset
    + * Name: ftmac100_reset
      *
      * Description:
      *   Do the HW reset
    @@ -434,7 +434,7 @@ static void ftmac100_reset(FAR struct ftmac100_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: ftmac100_init
    + * Name: ftmac100_init
      *
      * Description:
      *   Perform HW initialization
    @@ -542,7 +542,7 @@ static void ftmac100_init(FAR struct ftmac100_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: ftmac100_mdio_read
    + * Name: ftmac100_mdio_read
      *
      * Description:
      *   Read MII registers
    @@ -583,7 +583,7 @@ static uint32_t ftmac100_mdio_read(FAR struct ftmac100_register_s *iobase, int r
     }
     
     /****************************************************************************
    - * Function: ftmac100_set_mac
    + * Name: ftmac100_set_mac
      *
      * Description:
      *   Set the MAC address
    @@ -613,7 +613,7 @@ static void ftmac100_set_mac(FAR struct ftmac100_driver_s *priv,
     }
     
     /****************************************************************************
    - * Function: ftmac100_receive
    + * Name: ftmac100_receive
      *
      * Description:
      *   An interrupt was received indicating the availability of a new RX packet
    @@ -787,7 +787,7 @@ static void ftmac100_receive(FAR struct ftmac100_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: ftmac100_txdone
    + * Name: ftmac100_txdone
      *
      * Description:
      *   An interrupt was received indicating that the last TX packet(s) is done
    @@ -850,7 +850,7 @@ static void ftmac100_txdone(FAR struct ftmac100_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: ftmac100_interrupt_work
    + * Name: ftmac100_interrupt_work
      *
      * Description:
      *   Perform interrupt related work from the worker thread
    @@ -954,7 +954,7 @@ out:
     }
     
     /****************************************************************************
    - * Function: ftmac100_interrupt
    + * Name: ftmac100_interrupt
      *
      * Description:
      *   Hardware interrupt handler
    @@ -1009,7 +1009,7 @@ static int ftmac100_interrupt(int irq, FAR void *context, FAR void *arg)
     }
     
     /****************************************************************************
    - * Function: ftmac100_txtimeout_work
    + * Name: ftmac100_txtimeout_work
      *
      * Description:
      *   Perform TX timeout related work from the worker thread
    @@ -1042,7 +1042,7 @@ static void ftmac100_txtimeout_work(FAR void *arg)
     }
     
     /****************************************************************************
    - * Function: ftmac100_txtimeout_expiry
    + * Name: ftmac100_txtimeout_expiry
      *
      * Description:
      *   Our TX watchdog timed out.  Called from the timer interrupt handler.
    @@ -1077,7 +1077,7 @@ static void ftmac100_txtimeout_expiry(int argc, uint32_t arg, ...)
     }
     
     /****************************************************************************
    - * Function: ftmac100_poll_work
    + * Name: ftmac100_poll_work
      *
      * Description:
      *   Perform periodic polling from the worker thread
    @@ -1120,7 +1120,7 @@ static void ftmac100_poll_work(FAR void *arg)
     }
     
     /****************************************************************************
    - * Function: ftmac100_poll_expiry
    + * Name: ftmac100_poll_expiry
      *
      * Description:
      *   Periodic timer handler.  Called from the timer interrupt handler.
    @@ -1147,7 +1147,7 @@ static void ftmac100_poll_expiry(int argc, uint32_t arg, ...)
     }
     
     /****************************************************************************
    - * Function: ftmac100_ifup
    + * Name: ftmac100_ifup
      *
      * Description:
      *   NuttX Callback: Bring up the Ethernet interface when an IP address is
    @@ -1208,7 +1208,7 @@ static int ftmac100_ifup(struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: ftmac100_ifdown
    + * Name: ftmac100_ifdown
      *
      * Description:
      *   NuttX Callback: Stop the interface.
    @@ -1254,7 +1254,7 @@ static int ftmac100_ifdown(struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: ftmac100_txavail_work
    + * Name: ftmac100_txavail_work
      *
      * Description:
      *   Perform an out-of-cycle poll on the worker thread.
    @@ -1293,7 +1293,7 @@ static void ftmac100_txavail_work(FAR void *arg)
     }
     
     /****************************************************************************
    - * Function: ftmac100_txavail
    + * Name: ftmac100_txavail
      *
      * Description:
      *   Driver callback invoked when new TX data is available.  This is a
    @@ -1331,7 +1331,7 @@ static int ftmac100_txavail(struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: ftmac100_addmac
    + * Name: ftmac100_addmac
      *
      * Description:
      *   NuttX Callback: Add the specified MAC address to the hardware multicast
    @@ -1385,7 +1385,7 @@ static int ftmac100_addmac(struct net_driver_s *dev, FAR const uint8_t *mac)
     #endif
     
     /****************************************************************************
    - * Function: ftmac100_rmmac
    + * Name: ftmac100_rmmac
      *
      * Description:
      *   NuttX Callback: Remove the specified MAC address from the hardware multicast
    @@ -1430,7 +1430,7 @@ static int ftmac100_rmmac(struct net_driver_s *dev, FAR const uint8_t *mac)
     #endif
     
     /****************************************************************************
    - * Function: ftmac100_ipv6multicast
    + * Name: ftmac100_ipv6multicast
      *
      * Description:
      *   Configure the IPv6 multicast MAC address.
    @@ -1507,7 +1507,7 @@ static void ftmac100_ipv6multicast(FAR struct ftmac100_driver_s *priv)
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: ftmac100_initialize
    + * Name: ftmac100_initialize
      *
      * Description:
      *   Initialize the Ethernet controller and driver
    diff --git a/drivers/net/loopback.c b/drivers/net/loopback.c
    index 68f6c9abdc..08f7b8295a 100644
    --- a/drivers/net/loopback.c
    +++ b/drivers/net/loopback.c
    @@ -145,7 +145,7 @@ static int lo_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac);
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: lo_txpoll
    + * Name: lo_txpoll
      *
      * Description:
      *   Check if the network has any outgoing packets ready to send.  This is
    @@ -219,7 +219,7 @@ static int lo_txpoll(FAR struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: lo_poll_work
    + * Name: lo_poll_work
      *
      * Description:
      *   Perform periodic polling from the worker thread
    @@ -262,7 +262,7 @@ static void lo_poll_work(FAR void *arg)
     }
     
     /****************************************************************************
    - * Function: lo_poll_expiry
    + * Name: lo_poll_expiry
      *
      * Description:
      *   Periodic timer handler.  Called from the timer interrupt handler.
    @@ -289,7 +289,7 @@ static void lo_poll_expiry(int argc, wdparm_t arg, ...)
     }
     
     /****************************************************************************
    - * Function: lo_ifup
    + * Name: lo_ifup
      *
      * Description:
      *   NuttX Callback: Bring up the Ethernet interface when an IP address is
    @@ -331,7 +331,7 @@ static int lo_ifup(FAR struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: lo_ifdown
    + * Name: lo_ifdown
      *
      * Description:
      *   NuttX Callback: Stop the interface.
    @@ -361,7 +361,7 @@ static int lo_ifdown(FAR struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: lo_txavail_work
    + * Name: lo_txavail_work
      *
      * Description:
      *   Perform an out-of-cycle poll on the worker thread.
    @@ -400,7 +400,7 @@ static void lo_txavail_work(FAR void *arg)
     }
     
     /****************************************************************************
    - * Function: lo_txavail
    + * Name: lo_txavail
      *
      * Description:
      *   Driver callback invoked when new TX data is available.  This is a
    @@ -438,7 +438,7 @@ static int lo_txavail(FAR struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: lo_addmac
    + * Name: lo_addmac
      *
      * Description:
      *   NuttX Callback: Add the specified MAC address to the hardware multicast
    @@ -465,7 +465,7 @@ static int lo_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac)
     #endif
     
     /****************************************************************************
    - * Function: lo_rmmac
    + * Name: lo_rmmac
      *
      * Description:
      *   NuttX Callback: Remove the specified MAC address from the hardware multicast
    @@ -496,7 +496,7 @@ static int lo_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac)
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: localhost_initialize
    + * Name: localhost_initialize
      *
      * Description:
      *   Initialize the Ethernet controller and driver
    diff --git a/drivers/net/phy_notify.c b/drivers/net/phy_notify.c
    index f26dad2b74..6cc8e739df 100644
    --- a/drivers/net/phy_notify.c
    +++ b/drivers/net/phy_notify.c
    @@ -275,7 +275,7 @@ static int phy_handler(int irq, FAR void *context, FAR void *arg)
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: phy_notify_subscribe
    + * Name: phy_notify_subscribe
      *
      * Description:
      *   Setup up to deliver signals to the task identified by 'pid' when
    @@ -362,7 +362,7 @@ int phy_notify_subscribe(FAR const char *intf, pid_t pid, int signo,
     }
     
     /****************************************************************************
    - * Function: phy_notify_unsubscribe
    + * Name: phy_notify_unsubscribe
      *
      * Description:
      *   Stop the deliver of signals for events from the PHY associated with
    diff --git a/drivers/net/slip.c b/drivers/net/slip.c
    index afd3ca91ae..36eefbef95 100644
    --- a/drivers/net/slip.c
    +++ b/drivers/net/slip.c
    @@ -214,7 +214,7 @@ static void slip_semtake(FAR struct slip_driver_s *priv)
     #define slip_semgive(p) sem_post(&(p)->waitsem);
     
     /****************************************************************************
    - * Function: slip_write
    + * Name: slip_write
      *
      * Description:
      *   Just an inline wrapper around fwrite with error checking.
    @@ -238,7 +238,7 @@ static inline void slip_write(FAR struct slip_driver_s *priv,
     }
     
     /****************************************************************************
    - * Function: slip_putc
    + * Name: slip_putc
      *
      * Description:
      *   Just an inline wrapper around putc with error checking.
    @@ -256,7 +256,7 @@ static inline void slip_putc(FAR struct slip_driver_s *priv, int ch)
     }
     
     /****************************************************************************
    - * Function: slip_transmit
    + * Name: slip_transmit
      *
      * Description:
      *   Start hardware transmission.  Called either from the txdone interrupt
    @@ -368,7 +368,7 @@ static int slip_transmit(FAR struct slip_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: slip_txpoll
    + * Name: slip_txpoll
      *
      * Description:
      *   Check if the network has any outgoing packets ready to send.  This is a
    @@ -409,7 +409,7 @@ static int slip_txpoll(FAR struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: slip_txtask
    + * Name: slip_txtask
      *
      * Description:
      *   Polling and transmission is performed on tx thread.
    @@ -499,7 +499,7 @@ static void slip_txtask(int argc, FAR char *argv[])
     }
     
     /****************************************************************************
    - * Function: slip_getc
    + * Name: slip_getc
      *
      * Description:
      *   Get one byte from the serial input.
    @@ -525,7 +525,7 @@ static inline int slip_getc(FAR struct slip_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: slip_receive
    + * Name: slip_receive
      *
      * Description:
      *   Read a packet from the serial input
    @@ -630,7 +630,7 @@ static inline void slip_receive(FAR struct slip_driver_s *priv)
     }
     
     /****************************************************************************
    - * Function: slip_rxtask
    + * Name: slip_rxtask
      *
      * Description:
      *   Wait for incoming data.
    @@ -751,7 +751,7 @@ static int slip_rxtask(int argc, FAR char *argv[])
     }
     
     /****************************************************************************
    - * Function: slip_ifup
    + * Name: slip_ifup
      *
      * Description:
      *   NuttX Callback: Bring up the Ethernet interface when an IP address is
    @@ -782,7 +782,7 @@ static int slip_ifup(FAR struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: slip_ifdown
    + * Name: slip_ifdown
      *
      * Description:
      *   NuttX Callback: Stop the interface.
    @@ -808,7 +808,7 @@ static int slip_ifdown(FAR struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: slip_txavail
    + * Name: slip_txavail
      *
      * Description:
      *   Driver callback invoked when new TX data is available.  This is a
    @@ -841,7 +841,7 @@ static int slip_txavail(FAR struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: slip_addmac
    + * Name: slip_addmac
      *
      * Description:
      *   NuttX Callback: Add the specified MAC address to the hardware multicast
    @@ -870,7 +870,7 @@ static int slip_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac)
     #endif
     
     /****************************************************************************
    - * Function: slip_rmmac
    + * Name: slip_rmmac
      *
      * Description:
      *   NuttX Callback: Remove the specified MAC address from the hardware multicast
    @@ -903,7 +903,7 @@ static int slip_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac)
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: slip_initialize
    + * Name: slip_initialize
      *
      * Description:
      *   Instantiate a SLIP network interface.
    diff --git a/drivers/net/tun.c b/drivers/net/tun.c
    index 968a9e2122..a942bebe13 100644
    --- a/drivers/net/tun.c
    +++ b/drivers/net/tun.c
    @@ -304,7 +304,7 @@ static void tun_pollnotify(FAR struct tun_device_s *priv, pollevent_t eventset)
     #endif
     
     /****************************************************************************
    - * Function: tun_transmit
    + * Name: tun_transmit
      *
      * Description:
      *   Start hardware transmission.  Called either from the txdone interrupt
    @@ -343,7 +343,7 @@ static int tun_fd_transmit(FAR struct tun_device_s *priv)
     }
     
     /****************************************************************************
    - * Function: tun_txpoll
    + * Name: tun_txpoll
      *
      * Description:
      *   The transmitter is available, check if the network has any outgoing packets
    @@ -393,7 +393,7 @@ static int tun_txpoll(struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: tun_receive
    + * Name: tun_receive
      *
      * Description:
      *   An interrupt was received indicating the availability of a new RX packet
    @@ -495,7 +495,7 @@ static void tun_net_receive(FAR struct tun_device_s *priv)
     }
     
     /****************************************************************************
    - * Function: tun_txdone
    + * Name: tun_txdone
      *
      * Description:
      *   An interrupt was received indicating that the last TX packet(s) is done
    @@ -524,7 +524,7 @@ static void tun_txdone(FAR struct tun_device_s *priv)
     }
     
     /****************************************************************************
    - * Function: tun_poll_work
    + * Name: tun_poll_work
      *
      * Description:
      *   Perform periodic polling from the worker thread
    @@ -570,7 +570,7 @@ static void tun_poll_work(FAR void *arg)
     }
     
     /****************************************************************************
    - * Function: tun_poll_expiry
    + * Name: tun_poll_expiry
      *
      * Description:
      *   Periodic timer handler.  Called from the timer interrupt handler.
    @@ -597,7 +597,7 @@ static void tun_poll_expiry(int argc, wdparm_t arg, ...)
     }
     
     /****************************************************************************
    - * Function: tun_ifup
    + * Name: tun_ifup
      *
      * Description:
      *   NuttX Callback: Bring up the Ethernet interface when an IP address is
    @@ -649,7 +649,7 @@ static int tun_ifup(struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: tun_ifdown
    + * Name: tun_ifdown
      *
      * Description:
      *   NuttX Callback: Stop the interface.
    @@ -682,7 +682,7 @@ static int tun_ifdown(struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: tun_txavail
    + * Name: tun_txavail
      *
      * Description:
      *   Driver callback invoked when new TX data is available.  This is a
    @@ -731,7 +731,7 @@ static int tun_txavail(struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: tun_addmac
    + * Name: tun_addmac
      *
      * Description:
      *   NuttX Callback: Add the specified MAC address to the hardware multicast
    @@ -758,7 +758,7 @@ static int tun_addmac(struct net_driver_s *dev, FAR const uint8_t *mac)
     #endif
     
     /****************************************************************************
    - * Function: tun_rmmac
    + * Name: tun_rmmac
      *
      * Description:
      *   NuttX Callback: Remove the specified MAC address from the hardware multicast
    @@ -785,7 +785,7 @@ static int tun_rmmac(struct net_driver_s *dev, FAR const uint8_t *mac)
     #endif
     
     /****************************************************************************
    - * Function: tun_ipv6multicast
    + * Name: tun_ipv6multicast
      *
      * Description:
      *   Configure the IPv6 multicast MAC address.
    @@ -807,7 +807,7 @@ static void tun_ipv6multicast(FAR struct tun_device_s *priv)
     #endif /* CONFIG_NET_ICMPv6 */
     
     /****************************************************************************
    - * Function: tun_dev_init
    + * Name: tun_dev_init
      *
      * Description:
      *   Initialize the TUN device
    @@ -1228,7 +1228,7 @@ static int tun_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: tun_initialize
    + * Name: tun_initialize
      *
      * Description:
      *   Instantiate a SLIP network interface.
    diff --git a/drivers/video/ov2640.c b/drivers/video/ov2640.c
    index 06f88d1bf4..f0dc396289 100644
    --- a/drivers/video/ov2640.c
    +++ b/drivers/video/ov2640.c
    @@ -672,7 +672,7 @@ static const struct ovr2640_reg_s g_ov2640_jpeg_uxga_resolution[] =
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: ov2640_putreg
    + * Name: ov2640_putreg
      *
      * Description:
      *   Set one OV2640 register
    @@ -723,7 +723,7 @@ static int ov2640_putreg(FAR struct i2c_master_s *i2c, uint8_t regaddr,
     }
     
     /****************************************************************************
    - * Function: ov2640_getreg
    + * Name: ov2640_getreg
      *
      * Description:
      *   Set one OV2640 register
    @@ -779,7 +779,7 @@ static uint8_t ov2640_getreg(FAR struct i2c_master_s *i2c, uint8_t regaddr)
     }
     
     /****************************************************************************
    - * Function: ov2640_putreglist
    + * Name: ov2640_putreglist
      *
      * Description:
      *   Set a list of OV2640 register values.
    @@ -816,7 +816,7 @@ static int ov2640_putreglist(FAR struct i2c_master_s *i2c,
     }
     
     /****************************************************************************
    - * Function: ovr2640_chipid
    + * Name: ovr2640_chipid
      *
      * Description:
      *   Read and verify the CHIP ID
    @@ -869,7 +869,7 @@ static int ovr2640_chipid(FAR struct i2c_master_s *i2c)
     }
     
     /****************************************************************************
    - * Function: ov2640_reset
    + * Name: ov2640_reset
      *
      * Description:
      *   Reset the OV2640.
    @@ -904,7 +904,7 @@ static int ov2640_reset(FAR struct i2c_master_s *i2c)
      * Public Functions
      ****************************************************************************/
     /****************************************************************************
    - * Function: ov2640_initialize
    + * Name: ov2640_initialize
      *
      * Description:
      *   Initialize the OV2640 camera.
    diff --git a/drivers/wireless/cc3000/cc3000.c b/drivers/wireless/cc3000/cc3000.c
    index 1b13276ede..dfb312fb68 100644
    --- a/drivers/wireless/cc3000/cc3000.c
    +++ b/drivers/wireless/cc3000/cc3000.c
    @@ -231,7 +231,7 @@ static inline void cc3000_devgive(FAR struct cc3000_dev_s *priv)
     }
     
     /****************************************************************************
    - * Function: cc3000_configspi
    + * Name: cc3000_configspi
      *
      * Description:
      *   Configure the SPI for use with the CC3000.  This function should be
    @@ -260,7 +260,7 @@ static inline void cc3000_configspi(FAR struct spi_dev_s *spi)
     }
     
     /****************************************************************************
    - * Function: cc3000_lock
    + * Name: cc3000_lock
      *
      * Description:
      *   Lock the SPI bus and re-configure as necessary.  This function must be
    @@ -293,7 +293,7 @@ static void cc3000_lock_and_select(FAR struct spi_dev_s *spi)
     }
     
     /****************************************************************************
    - * Function: cc3000_unlock
    + * Name: cc3000_unlock
      *
      * Description:
      *   Un-lock the SPI bus after each transfer, possibly losing the current
    @@ -321,7 +321,7 @@ static void cc3000_deselect_and_unlock(FAR struct spi_dev_s *spi)
     }
     
     /****************************************************************************
    - * Function: cc3000_wait
    + * Name: cc3000_wait
      *
      * Description:
      *  Helper function to wait on the semaphore signaled by the
    @@ -363,7 +363,7 @@ static int cc3000_wait(FAR struct cc3000_dev_s *priv, sem_t *psem)
     }
     
     /****************************************************************************
    - * Function: cc3000_wait_irq
    + * Name: cc3000_wait_irq
      *
      * Description:
      *  Helper function to wait on the irqsem signaled by the interrupt
    @@ -385,7 +385,7 @@ static inline int cc3000_wait_irq(FAR struct cc3000_dev_s *priv)
     }
     
     /****************************************************************************
    - * Function: cc3000_wait_ready
    + * Name: cc3000_wait_ready
      *
      * Description:
      *  Helper function to wait on the readysem signaled by the interrupt
    diff --git a/drivers/wireless/nrf24l01.c b/drivers/wireless/nrf24l01.c
    index ae0d29b483..8bfc725c3b 100644
    --- a/drivers/wireless/nrf24l01.c
    +++ b/drivers/wireless/nrf24l01.c
    @@ -290,7 +290,7 @@ static void nrf24l01_lock(FAR struct spi_dev_s *spi)
     }
     
     /****************************************************************************
    - * Function: nrf24l01_unlock
    + * Name: nrf24l01_unlock
      *
      * Description:
      *   Un-lock the SPI bus after each transfer, possibly losing the current
    @@ -314,7 +314,7 @@ static void nrf24l01_unlock(FAR struct spi_dev_s *spi)
     }
     
     /****************************************************************************
    - * Function: nrf24l01_configspi
    + * Name: nrf24l01_configspi
      *
      * Description:
      *   Configure the SPI for use with the NRF24L01.
    diff --git a/fs/vfs/fs_poll.c b/fs/vfs/fs_poll.c
    index f0cc6ce2a9..168c393dd0 100644
    --- a/fs/vfs/fs_poll.c
    +++ b/fs/vfs/fs_poll.c
    @@ -245,7 +245,7 @@ static inline int poll_teardown(FAR struct pollfd *fds, nfds_t nfds, int *count,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: file_poll
    + * Name: file_poll
      *
      * Description:
      *   Low-level poll operation based on struc file.  This is used both to (1)
    @@ -288,7 +288,7 @@ int file_poll(FAR struct file *filep, FAR struct pollfd *fds, bool setup)
     #endif
     
     /****************************************************************************
    - * Function: fdesc_poll
    + * Name: fdesc_poll
      *
      * Description:
      *   The standard poll() operation redirects operations on file descriptors
    diff --git a/graphics/vnc/server/vnc_fbdev.c b/graphics/vnc/server/vnc_fbdev.c
    index 54abc1dc5c..5517a30e9f 100644
    --- a/graphics/vnc/server/vnc_fbdev.c
    +++ b/graphics/vnc/server/vnc_fbdev.c
    @@ -651,7 +651,7 @@ int up_fbinitialize(int display)
     }
     
     /****************************************************************************
    - * Function: vnc_fbinitialize
    + * Name: vnc_fbinitialize
      *
      * Description:
      *   Initialize the VNC frame buffer driver.  The VNC frame buffer driver
    diff --git a/graphics/vnc/server/vnc_keymap.c b/graphics/vnc/server/vnc_keymap.c
    index b23e3199a1..589f3c64f8 100644
    --- a/graphics/vnc/server/vnc_keymap.c
    +++ b/graphics/vnc/server/vnc_keymap.c
    @@ -630,7 +630,7 @@ void vnc_key_map(FAR struct vnc_session_s *session, uint16_t keysym,
     }
     
     /****************************************************************************
    - * Function: vnc_kbdout
    + * Name: vnc_kbdout
      *
      * Description:
      *   This is the default keyboard callout function.  This is simply wrappers around nx_kdbout(), respectively.  When configured using vnc_fbinitialize(), the 'arg' must be the correct NXHANDLE value.
    diff --git a/graphics/vnc/server/vnc_receiver.c b/graphics/vnc/server/vnc_receiver.c
    index 8f4e0988af..36d04428ab 100644
    --- a/graphics/vnc/server/vnc_receiver.c
    +++ b/graphics/vnc/server/vnc_receiver.c
    @@ -497,7 +497,7 @@ int vnc_client_encodings(FAR struct vnc_session_s *session,
     }
     
     /****************************************************************************
    - * Function: vnc_mouse
    + * Name: vnc_mouse
      *
      * Description:
      *   This is the default keyboard/mouse callout function.  This is simply a
    diff --git a/include/net/route.h b/include/net/route.h
    index c77d365676..24e456e848 100644
    --- a/include/net/route.h
    +++ b/include/net/route.h
    @@ -84,7 +84,7 @@ extern "C"
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: net_addroute
    + * Name: net_addroute
      *
      * Description:
      *   Add a new route to the routing table.  This is just a convenience
    @@ -107,7 +107,7 @@ int addroute(int sockfd, FAR struct sockaddr_storage *target,
                  FAR struct sockaddr_storage *router);
     
     /****************************************************************************
    - * Function: net_delroute
    + * Name: net_delroute
      *
      * Description:
      *   Add a new route to the routing table.  This is just a convenience
    diff --git a/include/nuttx/audio/vs1053.h b/include/nuttx/audio/vs1053.h
    index 75cc291674..896bb37e0b 100644
    --- a/include/nuttx/audio/vs1053.h
    +++ b/include/nuttx/audio/vs1053.h
    @@ -92,7 +92,7 @@ extern "C"
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: vs1053_initialize
    + * Name: vs1053_initialize
      *
      * Description:
      *   Initialize the VS1053 driver.  This will perform a chip reset of the
    diff --git a/include/nuttx/clock.h b/include/nuttx/clock.h
    index c6a1deafc5..2c679deb73 100644
    --- a/include/nuttx/clock.h
    +++ b/include/nuttx/clock.h
    @@ -239,7 +239,7 @@ EXTERN volatile systime_t g_system_timer;
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  clock_synchronize
    + * Name:  clock_synchronize
      *
      * Description:
      *   Synchronize the system timer to a hardware RTC.  This operation is
    @@ -302,7 +302,7 @@ void clock_resynchronize(FAR struct timespec *rtc_diff);
     #endif
     
     /****************************************************************************
    - * Function:  clock_systimer
    + * Name:  clock_systimer
      *
      * Description:
      *   Return the current value of the 32/64-bit system timer counter.
    @@ -347,7 +347,7 @@ systime_t clock_systimer(void);
     int clock_systimespec(FAR struct timespec *ts);
     
     /****************************************************************************
    - * Function:  clock_cpuload
    + * Name:  clock_cpuload
      *
      * Description:
      *   Return load measurement data for the select PID.
    diff --git a/include/nuttx/drivers/iob.h b/include/nuttx/drivers/iob.h
    index d6ce3c3025..486c56761b 100644
    --- a/include/nuttx/drivers/iob.h
    +++ b/include/nuttx/drivers/iob.h
    @@ -406,7 +406,7 @@ FAR struct iob_s *iob_pack(FAR struct iob_s *iob);
     int iob_contig(FAR struct iob_s *iob, unsigned int len);
     
     /****************************************************************************
    - * Function: iob_dump
    + * Name: iob_dump
      *
      * Description:
      *   Dump the contents of a I/O buffer chain
    diff --git a/include/nuttx/fs/fs.h b/include/nuttx/fs/fs.h
    index 809325389c..7b3e32970f 100644
    --- a/include/nuttx/fs/fs.h
    +++ b/include/nuttx/fs/fs.h
    @@ -975,7 +975,7 @@ int file_vfcntl(FAR struct file *filep, int cmd, va_list ap);
     #endif
     
     /****************************************************************************
    - * Function: file_poll
    + * Name: file_poll
      *
      * Description:
      *   Low-level poll operation based on struc file.  This is used both to (1)
    @@ -998,7 +998,7 @@ int file_poll(FAR struct file *filep, FAR struct pollfd *fds, bool setup);
     #endif
     
     /****************************************************************************
    - * Function: fdesc_poll
    + * Name: fdesc_poll
      *
      * Description:
      *   The standard poll() operation redirects operations on file descriptors
    diff --git a/include/nuttx/net/cs89x0.h b/include/nuttx/net/cs89x0.h
    index 5629a8f479..98ef9772b4 100644
    --- a/include/nuttx/net/cs89x0.h
    +++ b/include/nuttx/net/cs89x0.h
    @@ -108,7 +108,7 @@ extern "C"
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: cs89x0_initialize
    + * Name: cs89x0_initialize
      *
      * Description:
      *   Initialize the Ethernet driver
    diff --git a/include/nuttx/net/enc28j60.h b/include/nuttx/net/enc28j60.h
    index b5d31e4654..78b394ec9f 100644
    --- a/include/nuttx/net/enc28j60.h
    +++ b/include/nuttx/net/enc28j60.h
    @@ -108,7 +108,7 @@ extern "C"
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: enc_initialize
    + * Name: enc_initialize
      *
      * Description:
      *   Initialize the Ethernet driver.  The ENC28J60 device is assumed to be
    diff --git a/include/nuttx/net/encx24j600.h b/include/nuttx/net/encx24j600.h
    index 39ce6c8664..0a628dcf9b 100644
    --- a/include/nuttx/net/encx24j600.h
    +++ b/include/nuttx/net/encx24j600.h
    @@ -108,7 +108,7 @@ extern "C"
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: enc_initialize
    + * Name: enc_initialize
      *
      * Description:
      *   Initialize the Ethernet driver.  The ENCX24J600 device is assumed to be
    diff --git a/include/nuttx/net/ftmac100.h b/include/nuttx/net/ftmac100.h
    index f44bbd78ac..2cdbbc71ce 100644
    --- a/include/nuttx/net/ftmac100.h
    +++ b/include/nuttx/net/ftmac100.h
    @@ -217,7 +217,7 @@ struct ftmac100_rxdes_s
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: ftmac100_initialize
    + * Name: ftmac100_initialize
      *
      * Description:
      *   Initialize the Ethernet controller and driver
    diff --git a/include/nuttx/net/loopback.h b/include/nuttx/net/loopback.h
    index 76e8312c39..f2ebd7a6ba 100644
    --- a/include/nuttx/net/loopback.h
    +++ b/include/nuttx/net/loopback.h
    @@ -91,7 +91,7 @@ EXTERN const net_ipv6addr_t g_lo_ipv6addr;
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: localhost_initialize
    + * Name: localhost_initialize
      *
      * Description:
      *   Initialize the Ethernet controller and driver
    diff --git a/include/nuttx/net/net.h b/include/nuttx/net/net.h
    index d99c2f584a..4ccbdfde38 100644
    --- a/include/nuttx/net/net.h
    +++ b/include/nuttx/net/net.h
    @@ -215,7 +215,7 @@ void net_initialize(void);
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: net_lock
    + * Name: net_lock
      *
      * Description:
      *   Take the lock
    @@ -225,7 +225,7 @@ void net_initialize(void);
     void net_lock(void);
     
     /****************************************************************************
    - * Function: net_unlock
    + * Name: net_unlock
      *
      * Description:
      *   Release the lock.
    @@ -235,7 +235,7 @@ void net_lock(void);
     void net_unlock(void);
     
     /****************************************************************************
    - * Function: net_timedwait
    + * Name: net_timedwait
      *
      * Description:
      *   Atomically wait for sem (or a timeout( while temporarily releasing
    @@ -256,7 +256,7 @@ struct timespec;
     int net_timedwait(sem_t *sem, FAR const struct timespec *abstime);
     
     /****************************************************************************
    - * Function: net_lockedwait
    + * Name: net_lockedwait
      *
      * Description:
      *   Atomically wait for sem while temporarily releasing lock on the network.
    @@ -274,7 +274,7 @@ int net_timedwait(sem_t *sem, FAR const struct timespec *abstime);
     int net_lockedwait(sem_t *sem);
     
     /****************************************************************************
    - * Function: net_setipid
    + * Name: net_setipid
      *
      * Description:
      *   This function may be used at boot time to set the initial ip_id.
    @@ -349,7 +349,7 @@ void net_releaselist(FAR struct socketlist *list);
     FAR struct socket *sockfd_socket(int sockfd);
     
     /****************************************************************************
    - * Function: psock_socket
    + * Name: psock_socket
      *
      * Description:
      *   socket() creates an endpoint for communication and returns a socket
    @@ -389,7 +389,7 @@ FAR struct socket *sockfd_socket(int sockfd);
     int psock_socket(int domain, int type, int protocol, FAR struct socket *psock);
     
     /****************************************************************************
    - * Function: net_close
    + * Name: net_close
      *
      * Description:
      *   Performs the close operation on socket descriptors
    @@ -407,7 +407,7 @@ int psock_socket(int domain, int type, int protocol, FAR struct socket *psock);
     int net_close(int sockfd);
     
     /****************************************************************************
    - * Function: psock_close
    + * Name: psock_close
      *
      * Description:
      *   Performs the close operation on a socket instance
    @@ -425,7 +425,7 @@ int net_close(int sockfd);
     int psock_close(FAR struct socket *psock);
     
     /****************************************************************************
    - * Function: psock_bind
    + * Name: psock_bind
      *
      * Description:
      *   bind() gives the socket 'psock' the local address 'addr'. 'addr' is
    @@ -459,7 +459,7 @@ int psock_bind(FAR struct socket *psock, FAR const struct sockaddr *addr,
                    socklen_t addrlen);
     
     /****************************************************************************
    - * Function: psock_listen
    + * Name: psock_listen
      *
      * Description:
      *   To accept connections, a socket is first created with psock_socket(), a
    @@ -490,7 +490,7 @@ int psock_bind(FAR struct socket *psock, FAR const struct sockaddr *addr,
     int psock_listen(FAR struct socket *psock, int backlog);
     
     /****************************************************************************
    - * Function: psock_accept
    + * Name: psock_accept
      *
      * Description:
      *   The psock_accept function is used with connection-based socket types
    @@ -631,7 +631,7 @@ int psock_connect(FAR struct socket *psock, FAR const struct sockaddr *addr,
                       socklen_t addrlen);
     
     /****************************************************************************
    - * Function: psock_send
    + * Name: psock_send
      *
      * Description:
      *   The send() call may be used only when the socket is in a connected state
    @@ -698,7 +698,7 @@ ssize_t psock_send(FAR struct socket *psock, const void *buf, size_t len,
                        int flags);
     
     /****************************************************************************
    - * Function: psock_sendto
    + * Name: psock_sendto
      *
      * Description:
      *   If sendto() is used on a connection-mode (SOCK_STREAM, SOCK_SEQPACKET)
    @@ -767,7 +767,7 @@ ssize_t psock_sendto(FAR struct socket *psock, FAR const void *buf,
                          socklen_t tolen);
     
     /****************************************************************************
    - * Function: psock_recvfrom
    + * Name: psock_recvfrom
      *
      * Description:
      *   recvfrom() receives messages from a socket, and may be used to receive
    @@ -830,7 +830,7 @@ ssize_t psock_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
       psock_recvfrom(psock,buf,len,flags,NULL,0)
     
     /****************************************************************************
    - * Function: psock_getsockopt
    + * Name: psock_getsockopt
      *
      * Description:
      *   getsockopt() retrieve thse value for the option specified by the
    @@ -874,7 +874,7 @@ int psock_getsockopt(FAR struct socket *psock, int level, int option,
                          FAR void *value, FAR socklen_t *value_len);
     
     /****************************************************************************
    - * Function: psock_setsockopt
    + * Name: psock_setsockopt
      *
      * Description:
      *   psock_setsockopt() sets the option specified by the 'option' argument,
    @@ -989,7 +989,7 @@ int psock_ioctl(FAR struct socket *psock, int cmd, unsigned long arg);
     int netdev_ioctl(int sockfd, int cmd, unsigned long arg);
     
     /****************************************************************************
    - * Function: psock_poll
    + * Name: psock_poll
      *
      * Description:
      *   The standard poll() operation redirects operations on socket descriptors
    @@ -1012,7 +1012,7 @@ int psock_poll(FAR struct socket *psock, struct pollfd *fds, bool setup);
     #endif
     
     /****************************************************************************
    - * Function: net_poll
    + * Name: net_poll
      *
      * Description:
      *   The standard poll() operation redirects operations on socket descriptors
    @@ -1035,7 +1035,7 @@ int net_poll(int sockfd, struct pollfd *fds, bool setup);
     #endif
     
     /****************************************************************************
    - * Function: net_dupsd
    + * Name: net_dupsd
      *
      * Description:
      *   Clone a socket descriptor to an arbitray descriptor number.  If file
    @@ -1048,7 +1048,7 @@ int net_poll(int sockfd, struct pollfd *fds, bool setup);
     int net_dupsd(int sockfd, int minsd);
     
     /****************************************************************************
    - * Function: net_dupsd2
    + * Name: net_dupsd2
      *
      * Description:
      *   Clone a socket descriptor to an arbitray descriptor number.  If file
    @@ -1061,7 +1061,7 @@ int net_dupsd(int sockfd, int minsd);
     int net_dupsd2(int sockfd1, int sockfd2);
     
     /****************************************************************************
    - * Function: net_clone
    + * Name: net_clone
      *
      * Description:
      *   Performs the low level, common portion of net_dupsd() and net_dupsd2()
    @@ -1071,7 +1071,7 @@ int net_dupsd2(int sockfd1, int sockfd2);
     int net_clone(FAR struct socket *psock1, FAR struct socket *psock2);
     
     /****************************************************************************
    - * Function: net_sendfile
    + * Name: net_sendfile
      *
      * Description:
      *   The send() call may be used only when the socket is in a connected state
    @@ -1159,7 +1159,7 @@ ssize_t net_sendfile(int outfd, struct file *infile, off_t *offset, size_t count
     int net_vfcntl(int sockfd, int cmd, va_list ap);
     
     /****************************************************************************
    - * Function: netdev_register
    + * Name: netdev_register
      *
      * Description:
      *   Register a network device driver and assign a name to it so that it can
    @@ -1180,7 +1180,7 @@ int net_vfcntl(int sockfd, int cmd, va_list ap);
     int netdev_register(FAR struct net_driver_s *dev, enum net_lltype_e lltype);
     
     /****************************************************************************
    - * Function: netdev_unregister
    + * Name: netdev_unregister
      *
      * Description:
      *   Unregister a network device driver.
    @@ -1200,7 +1200,7 @@ int netdev_register(FAR struct net_driver_s *dev, enum net_lltype_e lltype);
     int netdev_unregister(FAR struct net_driver_s *dev);
     
     /****************************************************************************
    - * Function: netdev_foreach
    + * Name: netdev_foreach
      *
      * Description:
      *   Enumerate each registered network device.
    diff --git a/include/nuttx/net/netdev.h b/include/nuttx/net/netdev.h
    index 844117ee79..7caf247adc 100644
    --- a/include/nuttx/net/netdev.h
    +++ b/include/nuttx/net/netdev.h
    @@ -616,7 +616,7 @@ uint16_t ipv6_chksum(FAR struct net_driver_s *dev);
     #endif
     
     /****************************************************************************
    - * Function: netdev_ipv4_hdrlen
    + * Name: netdev_ipv4_hdrlen
      *
      * Description:
      *    Provide header length for interface based on device
    @@ -637,7 +637,7 @@ uint16_t ipv6_chksum(FAR struct net_driver_s *dev);
     #endif /* CONFIG_NET_IPv4 */
     
     /****************************************************************************
    - * Function: netdev_ipv6_hdrlen
    + * Name: netdev_ipv6_hdrlen
      *
      * Description:
      *    Provide header length for interface based on device
    diff --git a/include/nuttx/net/phy.h b/include/nuttx/net/phy.h
    index c2bf9e99fd..f492ccab28 100644
    --- a/include/nuttx/net/phy.h
    +++ b/include/nuttx/net/phy.h
    @@ -86,7 +86,7 @@ extern "C"
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: phy_notify_subscribe
    + * Name: phy_notify_subscribe
      *
      * Description:
      *   Setup up to deliver signals to the task identified by 'pid' when
    @@ -117,7 +117,7 @@ int phy_notify_subscribe(FAR const char *intf, pid_t pid, int signo,
     #endif
     
     /****************************************************************************
    - * Function: phy_notify_unsubscribe
    + * Name: phy_notify_unsubscribe
      *
      * Description:
      *   Stop the deliver of signals for events from the PHY associated with
    diff --git a/include/nuttx/net/slip.h b/include/nuttx/net/slip.h
    index 546781f85f..6cdc5c827f 100644
    --- a/include/nuttx/net/slip.h
    +++ b/include/nuttx/net/slip.h
    @@ -93,7 +93,7 @@ extern "C"
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: slip_initialize
    + * Name: slip_initialize
      *
      * Description:
      *   Instantiate a SLIP network interface.
    diff --git a/include/nuttx/net/tun.h b/include/nuttx/net/tun.h
    index c61c3c84f4..d8c4e68603 100644
    --- a/include/nuttx/net/tun.h
    +++ b/include/nuttx/net/tun.h
    @@ -82,7 +82,7 @@ extern "C"
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: tun_initialize
    + * Name: tun_initialize
      *
      * Description:
      *   Instantiate a SLIP network interface.
    diff --git a/include/nuttx/random.h b/include/nuttx/random.h
    index 4017837071..81276aa8ee 100644
    --- a/include/nuttx/random.h
    +++ b/include/nuttx/random.h
    @@ -110,7 +110,7 @@ extern struct entropy_pool_s board_entropy_pool;
     #ifdef CONFIG_CRYPTO_RANDOM_POOL
     
     /****************************************************************************
    - * Function: up_rngaddint
    + * Name: up_rngaddint
      *
      * Description:
      *   Add one integer to entropy pool, contributing a specific kind
    @@ -128,7 +128,7 @@ extern struct entropy_pool_s board_entropy_pool;
     void up_rngaddint(enum rnd_source_t kindof, int val);
     
     /****************************************************************************
    - * Function: up_rngaddentropy
    + * Name: up_rngaddentropy
      *
      * Description:
      *   Add buffer of integers to entropy pool.
    @@ -147,7 +147,7 @@ void up_rngaddentropy(enum rnd_source_t kindof, FAR const uint32_t *buf,
                           size_t n);
     
     /****************************************************************************
    - * Function: up_rngreseed
    + * Name: up_rngreseed
      *
      * Description:
      *   Force reseeding random number generator from entropy pool
    @@ -157,7 +157,7 @@ void up_rngaddentropy(enum rnd_source_t kindof, FAR const uint32_t *buf,
     void up_rngreseed(void);
     
     /****************************************************************************
    - * Function: up_randompool_initialize
    + * Name: up_randompool_initialize
      *
      * Description:
      *   Initialize entropy pool and random number generator
    diff --git a/include/nuttx/semaphore.h b/include/nuttx/semaphore.h
    index 579a0c4a10..fce15b1134 100644
    --- a/include/nuttx/semaphore.h
    +++ b/include/nuttx/semaphore.h
    @@ -143,7 +143,7 @@ int sem_tickwait(FAR sem_t *sem, systime_t start, uint32_t delay);
     int sem_reset(FAR sem_t *sem, int16_t count);
     
     /****************************************************************************
    - * Function: sem_getprotocol
    + * Name: sem_getprotocol
      *
      * Description:
      *    Return the value of the semaphore protocol attribute.
    @@ -163,7 +163,7 @@ int sem_reset(FAR sem_t *sem, int16_t count);
     int sem_getprotocol(FAR sem_t *sem, FAR int *protocol);
     
     /****************************************************************************
    - * Function: sem_setprotocol
    + * Name: sem_setprotocol
      *
      * Description:
      *    Set semaphore protocol attribute.
    diff --git a/include/nuttx/time.h b/include/nuttx/time.h
    index 9863664798..2a6c596978 100644
    --- a/include/nuttx/time.h
    +++ b/include/nuttx/time.h
    @@ -81,7 +81,7 @@ extern "C"
     #endif
     
     /****************************************************************************
    - * Function:  clock_isleapyear
    + * Name:  clock_isleapyear
      *
      * Description:
      *    Return true if the specified year is a leap year
    @@ -91,7 +91,7 @@ extern "C"
     int clock_isleapyear(int year);
     
     /****************************************************************************
    - * Function:  clock_daysbeforemonth
    + * Name:  clock_daysbeforemonth
      *
      * Description:
      *    Get the number of days that occurred before the beginning of the month.
    @@ -101,7 +101,7 @@ int clock_isleapyear(int year);
     int clock_daysbeforemonth(int month, bool leapyear);
     
     /****************************************************************************
    - * Function:  clock_dayoftheweek
    + * Name:  clock_dayoftheweek
      *
      * Description:
      *    Get the day of the week
    @@ -121,7 +121,7 @@ int clock_dayoftheweek(int mday, int month, int year);
     #endif
     
     /****************************************************************************
    - * Function:  clock_calendar2utc
    + * Name:  clock_calendar2utc
      *
      * Description:
      *    Calendar/UTC conversion based on algorithms from p. 604
    diff --git a/include/nuttx/video/ov2640.h b/include/nuttx/video/ov2640.h
    index b398994d97..8c40906cfa 100644
    --- a/include/nuttx/video/ov2640.h
    +++ b/include/nuttx/video/ov2640.h
    @@ -63,7 +63,7 @@ extern "C"
     #endif
     
     /****************************************************************************
    - * Function: ov2640_initialize
    + * Name: ov2640_initialize
      *
      * Description:
      *   Initialize the OV2640 camera.
    diff --git a/include/nuttx/video/vnc.h b/include/nuttx/video/vnc.h
    index fdb1dfd4a9..df39d5b7fd 100644
    --- a/include/nuttx/video/vnc.h
    +++ b/include/nuttx/video/vnc.h
    @@ -74,7 +74,7 @@ extern "C"
     #endif
     
     /****************************************************************************
    - * Function: vnc_fbinitialize
    + * Name: vnc_fbinitialize
      *
      * Description:
      *   Initialize the VNC frame buffer driver.  The VNC frame buffer driver
    @@ -132,7 +132,7 @@ int vnc_fbinitialize(int display, vnc_kbdout_t kbdout,
                          vnc_mouseout_t mouseout, FAR void *arg);
     
     /****************************************************************************
    - * Function: vnc_mouse and vnc_kbdout
    + * Name: vnc_mouse and vnc_kbdout
      *
      * Description:
      *   These are the default keyboard/mouse callout functions.  They are
    @@ -162,7 +162,7 @@ void vnc_mouseout(FAR void *arg, nxgl_coord_t x, nxgl_coord_t y,
     #endif
     
     /****************************************************************************
    - * Function: vnc_default_fbinitialize
    + * Name: vnc_default_fbinitialize
      *
      * Description:
      *   This is just a wrapper around vnc_fbinitialize() that will establish
    diff --git a/include/nuttx/wireless/ieee80211/bcmf_board.h b/include/nuttx/wireless/ieee80211/bcmf_board.h
    index 7ae0c21dc2..a404fd4160 100644
    --- a/include/nuttx/wireless/ieee80211/bcmf_board.h
    +++ b/include/nuttx/wireless/ieee80211/bcmf_board.h
    @@ -59,7 +59,7 @@ extern "C"
      ****************************************************************************/
     
     /************************************************************************************
    - * Function: bcmf_board_initialize
    + * Name: bcmf_board_initialize
      *
      * Description:
      *   Board specific function called from Broadcom FullMAC driver
    @@ -73,7 +73,7 @@ extern "C"
     void bcmf_board_initialize(int minor);
     
     /************************************************************************************
    - * Function: bcmf_board_power
    + * Name: bcmf_board_power
      *
      * Description:
      *   Board specific function called from Broadcom FullMAC driver
    @@ -88,7 +88,7 @@ void bcmf_board_initialize(int minor);
     void bcmf_board_power(int minor, bool power);
     
     /************************************************************************************
    - * Function: bcmf_board_reset
    + * Name: bcmf_board_reset
      *
      * Description:
      *   Board specific function called from Broadcom FullMAC driver
    diff --git a/include/nuttx/wireless/ieee80211/bcmf_sdio.h b/include/nuttx/wireless/ieee80211/bcmf_sdio.h
    index 09c5733f3a..9dd686858b 100644
    --- a/include/nuttx/wireless/ieee80211/bcmf_sdio.h
    +++ b/include/nuttx/wireless/ieee80211/bcmf_sdio.h
    @@ -59,7 +59,7 @@ extern "C"
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: bcmf_sdio_initialize
    + * Name: bcmf_sdio_initialize
      *
      * Description:
      *   Initialize Broadcom FullMAC driver.
    diff --git a/include/nuttx/wireless/ieee802154/ieee802154_loopback.h b/include/nuttx/wireless/ieee802154/ieee802154_loopback.h
    index d1952df24f..9a5f3e6b3e 100644
    --- a/include/nuttx/wireless/ieee802154/ieee802154_loopback.h
    +++ b/include/nuttx/wireless/ieee802154/ieee802154_loopback.h
    @@ -52,7 +52,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: ieee8021514_loopback
    + * Name: ieee8021514_loopback
      *
      * Description:
      *   Initialize and register the Ieee802.15.4 MAC loopback network driver.
    diff --git a/include/nuttx/wireless/ieee802154/mrf24j40.h b/include/nuttx/wireless/ieee802154/mrf24j40.h
    index 2c78faee01..878f7d9b45 100644
    --- a/include/nuttx/wireless/ieee802154/mrf24j40.h
    +++ b/include/nuttx/wireless/ieee802154/mrf24j40.h
    @@ -79,7 +79,7 @@ extern "C"
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: mrf24j40_init
    + * Name: mrf24j40_init
      *
      * Description:
      *   Initialize the IEEE802.15.4 driver.  The MRF24J40 device is assumed to be
    diff --git a/include/sys/random.h b/include/sys/random.h
    index 7856ca007e..10507ff203 100644
    --- a/include/sys/random.h
    +++ b/include/sys/random.h
    @@ -51,7 +51,7 @@
     #ifdef CONFIG_CRYPTO_RANDOM_POOL
     
     /****************************************************************************
    - * Function: getrandom
    + * Name: getrandom
      *
      * Description:
      *   Fill a buffer of arbitrary length with randomness. This is the
    diff --git a/libc/libgen/lib_basename.c b/libc/libgen/lib_basename.c
    index 94df071200..18b2168fad 100644
    --- a/libc/libgen/lib_basename.c
    +++ b/libc/libgen/lib_basename.c
    @@ -53,7 +53,7 @@ static char g_retchar[2];
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: basename
    + * Name: basename
      *
      * Description:
      *   basename() extracts the filename component from a null-terminated
    diff --git a/libc/libgen/lib_dirname.c b/libc/libgen/lib_dirname.c
    index b7760c3a1f..0acd03c71f 100644
    --- a/libc/libgen/lib_dirname.c
    +++ b/libc/libgen/lib_dirname.c
    @@ -53,7 +53,7 @@ static char g_retchar[2];
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: dirname
    + * Name: dirname
      *
      * Description:
      *   dirname() extracts the directory component from a null-terminated
    diff --git a/libc/net/lib_addroute.c b/libc/net/lib_addroute.c
    index 8c7012abe8..c8712ecde1 100644
    --- a/libc/net/lib_addroute.c
    +++ b/libc/net/lib_addroute.c
    @@ -49,7 +49,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: net_addroute
    + * Name: net_addroute
      *
      * Description:
      *   Add a new route to the routing table.  This is just a convenience
    diff --git a/libc/net/lib_delroute.c b/libc/net/lib_delroute.c
    index 5110659c48..7a6617dbdb 100644
    --- a/libc/net/lib_delroute.c
    +++ b/libc/net/lib_delroute.c
    @@ -50,7 +50,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: net_delroute
    + * Name: net_delroute
      *
      * Description:
      *   Add a new route to the routing table.  This is just a convenience
    diff --git a/libc/pthread/pthread_attr_destroy.c b/libc/pthread/pthread_attr_destroy.c
    index 7d39a19278..16dd2cc50e 100644
    --- a/libc/pthread/pthread_attr_destroy.c
    +++ b/libc/pthread/pthread_attr_destroy.c
    @@ -49,7 +49,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  pthread_attr_destroy
    + * Name:  pthread_attr_destroy
      *
      * Description:
      *    An attributes object can be deleted when it is no longer needed.
    diff --git a/libc/pthread/pthread_attr_getaffinity.c b/libc/pthread/pthread_attr_getaffinity.c
    index 706f059ec5..1371ceff37 100644
    --- a/libc/pthread/pthread_attr_getaffinity.c
    +++ b/libc/pthread/pthread_attr_getaffinity.c
    @@ -48,7 +48,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  pthread_attr_getaffinity
    + * Name:  pthread_attr_getaffinity
      *
      * Description:
      *
    diff --git a/libc/pthread/pthread_attr_getinheritsched.c b/libc/pthread/pthread_attr_getinheritsched.c
    index 0760c5e265..d8e6515fa8 100644
    --- a/libc/pthread/pthread_attr_getinheritsched.c
    +++ b/libc/pthread/pthread_attr_getinheritsched.c
    @@ -49,7 +49,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  pthread_attr_getinheritsched
    + * Name:  pthread_attr_getinheritsched
      *
      * Description:
      *   Report whether the scheduling info in the pthread
    diff --git a/libc/pthread/pthread_attr_getschedparam.c b/libc/pthread/pthread_attr_getschedparam.c
    index d3280ffde3..3de2a3b7a2 100644
    --- a/libc/pthread/pthread_attr_getschedparam.c
    +++ b/libc/pthread/pthread_attr_getschedparam.c
    @@ -50,7 +50,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  pthread_attr_getschedparam
    + * Name:  pthread_attr_getschedparam
      *
      * Description:
      *
    diff --git a/libc/pthread/pthread_attr_getschedpolicy.c b/libc/pthread/pthread_attr_getschedpolicy.c
    index f4f624f4f0..ca819b8ffa 100644
    --- a/libc/pthread/pthread_attr_getschedpolicy.c
    +++ b/libc/pthread/pthread_attr_getschedpolicy.c
    @@ -48,7 +48,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  pthread_attr_getschedpolicy
    + * Name:  pthread_attr_getschedpolicy
      *
      * Description:
      *   Obtain the scheduling algorithm attribute.
    diff --git a/libc/pthread/pthread_attr_getstacksize.c b/libc/pthread/pthread_attr_getstacksize.c
    index 15de1b38f9..858cf88c9d 100644
    --- a/libc/pthread/pthread_attr_getstacksize.c
    +++ b/libc/pthread/pthread_attr_getstacksize.c
    @@ -48,7 +48,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  pthread_attr_getstacksize
    + * Name:  pthread_attr_getstacksize
      *
      * Description:
      *
    diff --git a/libc/pthread/pthread_attr_init.c b/libc/pthread/pthread_attr_init.c
    index b6c7c39ed6..256be4b235 100644
    --- a/libc/pthread/pthread_attr_init.c
    +++ b/libc/pthread/pthread_attr_init.c
    @@ -66,7 +66,7 @@ const pthread_attr_t g_default_pthread_attr = PTHREAD_ATTR_INITIALIZER;
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  pthread_attr_init
    + * Name:  pthread_attr_init
      *
      * Description:
      *   Initializes a thread attributes object (attr) with
    diff --git a/libc/pthread/pthread_attr_setaffinity.c b/libc/pthread/pthread_attr_setaffinity.c
    index 6705e87aa0..83f8e337cf 100644
    --- a/libc/pthread/pthread_attr_setaffinity.c
    +++ b/libc/pthread/pthread_attr_setaffinity.c
    @@ -49,7 +49,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  pthread_attr_setaffinity
    + * Name:  pthread_attr_setaffinity
      *
      * Description:
      *
    diff --git a/libc/pthread/pthread_attr_setinheritsched.c b/libc/pthread/pthread_attr_setinheritsched.c
    index c61be6f4f6..36b1d1dba1 100644
    --- a/libc/pthread/pthread_attr_setinheritsched.c
    +++ b/libc/pthread/pthread_attr_setinheritsched.c
    @@ -50,7 +50,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  pthread_attr_setinheritsched
    + * Name:  pthread_attr_setinheritsched
      *
      * Description:
      *   Indicate whether the scheduling info in the pthread
    diff --git a/libc/pthread/pthread_attr_setschedparam.c b/libc/pthread/pthread_attr_setschedparam.c
    index b37d3aad27..812ebee859 100644
    --- a/libc/pthread/pthread_attr_setschedparam.c
    +++ b/libc/pthread/pthread_attr_setschedparam.c
    @@ -50,7 +50,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  pthread_attr_setschedparam
    + * Name:  pthread_attr_setschedparam
      *
      * Description:
      *
    diff --git a/libc/pthread/pthread_attr_setschedpolicy.c b/libc/pthread/pthread_attr_setschedpolicy.c
    index 75a58e105b..9d7ce10fff 100644
    --- a/libc/pthread/pthread_attr_setschedpolicy.c
    +++ b/libc/pthread/pthread_attr_setschedpolicy.c
    @@ -50,7 +50,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  pthread_attr_setschedpolicy
    + * Name:  pthread_attr_setschedpolicy
      *
      * Description:
      *   Set the scheduling algorithm attribute.
    diff --git a/libc/pthread/pthread_attr_setstacksize.c b/libc/pthread/pthread_attr_setstacksize.c
    index 0501f76aa6..f69fc7df9c 100644
    --- a/libc/pthread/pthread_attr_setstacksize.c
    +++ b/libc/pthread/pthread_attr_setstacksize.c
    @@ -49,7 +49,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  pthread_attr_setstacksize
    + * Name:  pthread_attr_setstacksize
      *
      * Description:
      *
    diff --git a/libc/pthread/pthread_barrierattr_destroy.c b/libc/pthread/pthread_barrierattr_destroy.c
    index 7ab23b7b84..663f449981 100644
    --- a/libc/pthread/pthread_barrierattr_destroy.c
    +++ b/libc/pthread/pthread_barrierattr_destroy.c
    @@ -48,7 +48,7 @@
      ********************************************************************************/
     
     /********************************************************************************
    - * Function: pthread_barrierattr_destroy
    + * Name: pthread_barrierattr_destroy
      *
      * Description:
      *   The pthread_barrierattr_destroy() function will destroy a barrier attributes
    diff --git a/libc/pthread/pthread_barrierattr_getpshared.c b/libc/pthread/pthread_barrierattr_getpshared.c
    index d74d54dcbf..3964a801ca 100644
    --- a/libc/pthread/pthread_barrierattr_getpshared.c
    +++ b/libc/pthread/pthread_barrierattr_getpshared.c
    @@ -48,7 +48,7 @@
      ********************************************************************************/
     
     /********************************************************************************
    - * Function: pthread_barrierattr_getpshared
    + * Name: pthread_barrierattr_getpshared
      *
      * Description:
      *   The pthread_barrierattr_getpshared() function will obtain the value of the
    diff --git a/libc/pthread/pthread_barrierattr_init.c b/libc/pthread/pthread_barrierattr_init.c
    index 9b3f577552..e8270f6b98 100644
    --- a/libc/pthread/pthread_barrierattr_init.c
    +++ b/libc/pthread/pthread_barrierattr_init.c
    @@ -48,7 +48,7 @@
      ********************************************************************************/
     
     /********************************************************************************
    - * Function: pthread_barrierattr_init
    + * Name: pthread_barrierattr_init
      *
      * Description:
      *   The pthread_barrierattr_init() function will initialize a barrier attribute
    diff --git a/libc/pthread/pthread_barrierattr_setpshared.c b/libc/pthread/pthread_barrierattr_setpshared.c
    index 1736a4e430..76109ac08c 100644
    --- a/libc/pthread/pthread_barrierattr_setpshared.c
    +++ b/libc/pthread/pthread_barrierattr_setpshared.c
    @@ -68,7 +68,7 @@
      ********************************************************************************/
     
     /********************************************************************************
    - * Function: pthread_barrierattr_setpshared
    + * Name: pthread_barrierattr_setpshared
      *
      * Description:
      *   The process-shared attribute is set to PTHREAD_PROCESS_SHARED to permit a
    diff --git a/libc/pthread/pthread_condattr_destroy.c b/libc/pthread/pthread_condattr_destroy.c
    index 5833de44cf..12bee245dc 100644
    --- a/libc/pthread/pthread_condattr_destroy.c
    +++ b/libc/pthread/pthread_condattr_destroy.c
    @@ -48,7 +48,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  pthread_condattr_destroy
    + * Name:  pthread_condattr_destroy
      *
      * Description:
      *   Operations on condition variable attributes
    diff --git a/libc/pthread/pthread_condattr_init.c b/libc/pthread/pthread_condattr_init.c
    index 8532bc9a61..8865868b81 100644
    --- a/libc/pthread/pthread_condattr_init.c
    +++ b/libc/pthread/pthread_condattr_init.c
    @@ -48,7 +48,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  pthread_condattr_init
    + * Name:  pthread_condattr_init
      *
      * Description:
      *   Operations on condition variable attributes
    diff --git a/libc/pthread/pthread_mutexattr_destroy.c b/libc/pthread/pthread_mutexattr_destroy.c
    index 62d5de4a92..01c8a6589a 100644
    --- a/libc/pthread/pthread_mutexattr_destroy.c
    +++ b/libc/pthread/pthread_mutexattr_destroy.c
    @@ -48,7 +48,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  pthread_mutexattr_destroy
    + * Name:  pthread_mutexattr_destroy
      *
      * Description:
      *    Destroy mutex attributes.
    diff --git a/libc/pthread/pthread_mutexattr_getprotocol.c b/libc/pthread/pthread_mutexattr_getprotocol.c
    index f803006bb2..7cc6065d36 100644
    --- a/libc/pthread/pthread_mutexattr_getprotocol.c
    +++ b/libc/pthread/pthread_mutexattr_getprotocol.c
    @@ -48,7 +48,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: pthread_mutexattr_getprotocol
    + * Name: pthread_mutexattr_getprotocol
      *
      * Description:
      *    Return the value of the mutex protocol attribute.
    diff --git a/libc/pthread/pthread_mutexattr_getpshared.c b/libc/pthread/pthread_mutexattr_getpshared.c
    index 51e515cbbb..6d219fb085 100644
    --- a/libc/pthread/pthread_mutexattr_getpshared.c
    +++ b/libc/pthread/pthread_mutexattr_getpshared.c
    @@ -48,7 +48,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  pthread_mutexattr_getpshared
    + * Name:  pthread_mutexattr_getpshared
      *
      * Description:
      *    Get pshared mutex attribute.
    diff --git a/libc/pthread/pthread_mutexattr_getrobust.c b/libc/pthread/pthread_mutexattr_getrobust.c
    index 8d5e4c1060..4db30f6b75 100644
    --- a/libc/pthread/pthread_mutexattr_getrobust.c
    +++ b/libc/pthread/pthread_mutexattr_getrobust.c
    @@ -46,7 +46,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: pthread_mutexattr_getrobust
    + * Name: pthread_mutexattr_getrobust
      *
      * Description:
      *   Return the mutex robustneess from the mutex attributes.
    diff --git a/libc/pthread/pthread_mutexattr_gettype.c b/libc/pthread/pthread_mutexattr_gettype.c
    index 784a347ce8..c45008f8d4 100644
    --- a/libc/pthread/pthread_mutexattr_gettype.c
    +++ b/libc/pthread/pthread_mutexattr_gettype.c
    @@ -46,7 +46,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: pthread_mutexattr_gettype
    + * Name: pthread_mutexattr_gettype
      *
      * Description:
      *   Return the mutex type from the mutex attributes.
    diff --git a/libc/pthread/pthread_mutexattr_init.c b/libc/pthread/pthread_mutexattr_init.c
    index 895346a6cd..6f24188152 100644
    --- a/libc/pthread/pthread_mutexattr_init.c
    +++ b/libc/pthread/pthread_mutexattr_init.c
    @@ -48,7 +48,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  pthread_mutexattr_init
    + * Name:  pthread_mutexattr_init
      *
      * Description:
      *    Create mutex attributes.
    diff --git a/libc/pthread/pthread_mutexattr_setprotocol.c b/libc/pthread/pthread_mutexattr_setprotocol.c
    index 44d8be7849..e2a8a45ac5 100644
    --- a/libc/pthread/pthread_mutexattr_setprotocol.c
    +++ b/libc/pthread/pthread_mutexattr_setprotocol.c
    @@ -49,7 +49,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: pthread_mutexattr_setprotocol
    + * Name: pthread_mutexattr_setprotocol
      *
      * Description:
      *    Set mutex protocol attribute.
    diff --git a/libc/pthread/pthread_mutexattr_setpshared.c b/libc/pthread/pthread_mutexattr_setpshared.c
    index 22b915c4f0..054c4db07e 100644
    --- a/libc/pthread/pthread_mutexattr_setpshared.c
    +++ b/libc/pthread/pthread_mutexattr_setpshared.c
    @@ -48,7 +48,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  pthread_mutexattr_setpshared
    + * Name:  pthread_mutexattr_setpshared
      *
      * Description:
      *    Set pshared  mutex attribute.
    diff --git a/libc/pthread/pthread_mutexattr_setrobust.c b/libc/pthread/pthread_mutexattr_setrobust.c
    index 42930fa0b7..aeb2714e93 100644
    --- a/libc/pthread/pthread_mutexattr_setrobust.c
    +++ b/libc/pthread/pthread_mutexattr_setrobust.c
    @@ -46,7 +46,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: pthread_mutexattr_setrobust
    + * Name: pthread_mutexattr_setrobust
      *
      * Description:
      *   Set the mutex robustness in the mutex attributes.
    diff --git a/libc/pthread/pthread_mutexattr_settype.c b/libc/pthread/pthread_mutexattr_settype.c
    index 6047f90ef2..02e1832cd6 100644
    --- a/libc/pthread/pthread_mutexattr_settype.c
    +++ b/libc/pthread/pthread_mutexattr_settype.c
    @@ -46,7 +46,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: pthread_mutexattr_settype
    + * Name: pthread_mutexattr_settype
      *
      * Description:
      *   Set the mutex type in the mutex attributes.
    diff --git a/libc/semaphore/sem_getprotocol.c b/libc/semaphore/sem_getprotocol.c
    index 614d5da72a..a9e8a837e1 100644
    --- a/libc/semaphore/sem_getprotocol.c
    +++ b/libc/semaphore/sem_getprotocol.c
    @@ -48,7 +48,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: sem_getprotocol
    + * Name: sem_getprotocol
      *
      * Description:
      *    Return the value of the semaphore protocol attribute.
    diff --git a/libc/semaphore/sem_getvalue.c b/libc/semaphore/sem_getvalue.c
    index 16fcc7be0a..f1c77aa6f0 100644
    --- a/libc/semaphore/sem_getvalue.c
    +++ b/libc/semaphore/sem_getvalue.c
    @@ -68,7 +68,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  sem_getvalue
    + * Name:  sem_getvalue
      *
      * Description:
      *   This function updates the location referenced by 'sval' argument to
    diff --git a/libc/semaphore/sem_init.c b/libc/semaphore/sem_init.c
    index ec7de2730a..e10e83f1fa 100644
    --- a/libc/semaphore/sem_init.c
    +++ b/libc/semaphore/sem_init.c
    @@ -49,7 +49,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: sem_init
    + * Name: sem_init
      *
      * Description:
      *   This function initializes the UNAMED semaphore sem. Following a
    diff --git a/libc/semaphore/sem_setprotocol.c b/libc/semaphore/sem_setprotocol.c
    index 38336a31a0..b687d72280 100644
    --- a/libc/semaphore/sem_setprotocol.c
    +++ b/libc/semaphore/sem_setprotocol.c
    @@ -51,7 +51,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: sem_setprotocol
    + * Name: sem_setprotocol
      *
      * Description:
      *    Set semaphore protocol attribute.
    diff --git a/libc/signal/sig_addset.c b/libc/signal/sig_addset.c
    index 1379d3ceb8..392be1ca69 100644
    --- a/libc/signal/sig_addset.c
    +++ b/libc/signal/sig_addset.c
    @@ -45,7 +45,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: sigaddset
    + * Name: sigaddset
      *
      * Description:
      *   This function adds the signal specified by signo to the signal set
    diff --git a/libc/signal/sig_delset.c b/libc/signal/sig_delset.c
    index 9c488e7011..9c6c608a2d 100644
    --- a/libc/signal/sig_delset.c
    +++ b/libc/signal/sig_delset.c
    @@ -45,7 +45,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: sigdelset
    + * Name: sigdelset
      *
      * Description:
      *   This function deletes the signal specified by signo from the signal
    diff --git a/libc/signal/sig_emptyset.c b/libc/signal/sig_emptyset.c
    index 1899302bf0..01b398ad08 100644
    --- a/libc/signal/sig_emptyset.c
    +++ b/libc/signal/sig_emptyset.c
    @@ -44,7 +44,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: sigemptyset
    + * Name: sigemptyset
      *
      * Description:
      *   This function initializes the signal set specified by set such that all
    diff --git a/libc/signal/sig_fillset.c b/libc/signal/sig_fillset.c
    index a064242c34..2586646e37 100644
    --- a/libc/signal/sig_fillset.c
    +++ b/libc/signal/sig_fillset.c
    @@ -44,7 +44,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: sigfillset
    + * Name: sigfillset
      *
      * Description:
      *   This function initializes the signal set specified by set such that all
    diff --git a/libc/signal/sig_ismember.c b/libc/signal/sig_ismember.c
    index 6240392011..2fbac5f6c8 100644
    --- a/libc/signal/sig_ismember.c
    +++ b/libc/signal/sig_ismember.c
    @@ -44,7 +44,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: sigismember
    + * Name: sigismember
      *
      * Description:
      *   This function tests whether the signal specified by signo is a member
    diff --git a/libc/stdio/lib_sscanf.c b/libc/stdio/lib_sscanf.c
    index b5fd60f4de..52e89b5e9a 100644
    --- a/libc/stdio/lib_sscanf.c
    +++ b/libc/stdio/lib_sscanf.c
    @@ -81,7 +81,7 @@ static const char spaces[] = " \t\n\r\f\v";
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  findwidth
    + * Name:  findwidth
      *
      * Description:
      *    Try to figure out the width of the input data.
    @@ -139,7 +139,7 @@ static int findwidth(FAR const char *buf, FAR const char *fmt)
     }
     
     /****************************************************************************
    - * Function:  findscanset
    + * Name:  findscanset
      *
      * Description:
      *    Fill in the given table from the scanset at the given format.
    @@ -265,7 +265,7 @@ doexit:
     #endif
     
     /****************************************************************************
    - * Function:  scansetwidth
    + * Name:  scansetwidth
      ****************************************************************************/
     
     #ifdef CONFIG_LIBC_SCANSET
    @@ -295,7 +295,7 @@ static int scansetwidth(FAR const char *buf,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  sscanf
    + * Name:  sscanf
      *
      * Description:
      *    ANSI standard sscanf implementation.
    @@ -314,7 +314,7 @@ int sscanf(FAR const char *buf, FAR const char *fmt, ...)
     }
     
     /****************************************************************************
    - * Function:  vsscanf
    + * Name:  vsscanf
      *
      * Description:
      *    ANSI standard vsscanf implementation.
    diff --git a/libc/time/lib_asctime.c b/libc/time/lib_asctime.c
    index cd15699559..af633ebd73 100644
    --- a/libc/time/lib_asctime.c
    +++ b/libc/time/lib_asctime.c
    @@ -48,7 +48,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  asctime
    + * Name:  asctime
      *
      * Description:
      *   asctime and asctime_r convert the time provided in a struct tm to a
    diff --git a/libc/time/lib_asctimer.c b/libc/time/lib_asctimer.c
    index 0235b89c15..11b25974fa 100644
    --- a/libc/time/lib_asctimer.c
    +++ b/libc/time/lib_asctimer.c
    @@ -67,7 +67,7 @@ static const char * const g_mon_name[12] =
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  asctime_r
    + * Name:  asctime_r
      *
      * Description:
      *   asctime and asctime_r convert the time provided in a struct tm to a
    diff --git a/libc/time/lib_calendar2utc.c b/libc/time/lib_calendar2utc.c
    index 51a8581af4..3cd519179a 100644
    --- a/libc/time/lib_calendar2utc.c
    +++ b/libc/time/lib_calendar2utc.c
    @@ -50,7 +50,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  clock_gregorian2utc, clock_julian2utc
    + * Name:  clock_gregorian2utc, clock_julian2utc
      *
      * Description:
      *    UTC conversion routines.  These conversions are based
    @@ -90,7 +90,7 @@ static time_t clock_julian2utc(int year, int month, int day)
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  clock_calendar2utc
    + * Name:  clock_calendar2utc
      *
      * Description:
      *    Calendar/UTC conversion based on algorithms from p. 604
    diff --git a/libc/time/lib_ctime.c b/libc/time/lib_ctime.c
    index 6d1bcb8efe..4072663fb8 100644
    --- a/libc/time/lib_ctime.c
    +++ b/libc/time/lib_ctime.c
    @@ -48,7 +48,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  ctime
    + * Name:  ctime
      *
      * Description:
      *   ctime and ctime_r convert the time provided in seconds since the
    diff --git a/libc/time/lib_ctimer.c b/libc/time/lib_ctimer.c
    index 935a72bbd6..ccc9c8f928 100644
    --- a/libc/time/lib_ctimer.c
    +++ b/libc/time/lib_ctimer.c
    @@ -52,7 +52,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  ctime_r
    + * Name:  ctime_r
      *
      * Description:
      *   ctime and ctime_r convert the time provided in seconds since the
    diff --git a/libc/time/lib_dayofweek.c b/libc/time/lib_dayofweek.c
    index bf1ed7280f..981e027025 100644
    --- a/libc/time/lib_dayofweek.c
    +++ b/libc/time/lib_dayofweek.c
    @@ -80,7 +80,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  clock_dayoftheweek
    + * Name:  clock_dayoftheweek
      *
      * Description:
      *    Get the day of the week
    diff --git a/libc/time/lib_daysbeforemonth.c b/libc/time/lib_daysbeforemonth.c
    index d17d05b57e..39f50197ee 100644
    --- a/libc/time/lib_daysbeforemonth.c
    +++ b/libc/time/lib_daysbeforemonth.c
    @@ -58,7 +58,7 @@ static const uint16_t g_daysbeforemonth[13] =
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  clock_daysbeforemonth
    + * Name:  clock_daysbeforemonth
      *
      * Description:
      *    Get the number of days that occurred before the beginning of the
    diff --git a/libc/time/lib_difftime.c b/libc/time/lib_difftime.c
    index ee9a62ebb2..42bd374307 100644
    --- a/libc/time/lib_difftime.c
    +++ b/libc/time/lib_difftime.c
    @@ -48,7 +48,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  difftime
    + * Name:  difftime
      *
      * Description:
      *   The difftime() function returns the number of seconds elapsed
    diff --git a/libc/time/lib_gmtime.c b/libc/time/lib_gmtime.c
    index 1eeade4675..bcf17cfbc1 100644
    --- a/libc/time/lib_gmtime.c
    +++ b/libc/time/lib_gmtime.c
    @@ -78,7 +78,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  gmtime
    + * Name:  gmtime
      *
      * Description:
      *  Similar to gmtime_r, but not thread-safe
    diff --git a/libc/time/lib_gmtimer.c b/libc/time/lib_gmtimer.c
    index 10173d8c97..ed82306156 100644
    --- a/libc/time/lib_gmtimer.c
    +++ b/libc/time/lib_gmtimer.c
    @@ -86,7 +86,7 @@ static void   clock_utc2julian(time_t jdn, int *year, int *month, int *day);
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  clock_utc2calendar, clock_utc2gregorian, and clock_utc2julian
    + * Name:  clock_utc2calendar, clock_utc2gregorian, and clock_utc2julian
      *
      * Description:
      *    Calendar to UTC conversion routines.  These conversions
    @@ -291,7 +291,7 @@ static void clock_utc2calendar(time_t days, FAR int *year, FAR int *month,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  gmtime_r
    + * Name:  gmtime_r
      *
      * Description:
      *  Time conversion (based on the POSIX API)
    diff --git a/libc/time/lib_isleapyear.c b/libc/time/lib_isleapyear.c
    index 3bad316477..185ba112f3 100644
    --- a/libc/time/lib_isleapyear.c
    +++ b/libc/time/lib_isleapyear.c
    @@ -74,7 +74,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  clock_isleapyear
    + * Name:  clock_isleapyear
      *
      * Description:
      *    Return true if the specified year is a leap year
    diff --git a/libc/time/lib_strftime.c b/libc/time/lib_strftime.c
    index 6af9220297..9397bb0c6e 100644
    --- a/libc/time/lib_strftime.c
    +++ b/libc/time/lib_strftime.c
    @@ -103,7 +103,7 @@ static const char * const g_monthname[12] =
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  strftime
    + * Name:  strftime
      *
      * Description:
      *   The  strftime()  function  formats the broken-down time tm according to
    diff --git a/libc/time/lib_time.c b/libc/time/lib_time.c
    index 21efb1428a..504f7795f9 100644
    --- a/libc/time/lib_time.c
    +++ b/libc/time/lib_time.c
    @@ -46,7 +46,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  time
    + * Name:  time
      *
      * Description:
      *   Get the current calendar time as a time_t object.  The function returns
    diff --git a/net/arp/arp.h b/net/arp/arp.h
    index 0b95c4abd3..46cd0039f8 100644
    --- a/net/arp/arp.h
    +++ b/net/arp/arp.h
    @@ -188,7 +188,7 @@ struct arp_notify_s
     void arp_reset(void);
     
     /****************************************************************************
    - * Function: arp_timer_initialize
    + * Name: arp_timer_initialize
      *
      * Description:
      *   Initialized the 10 second timer that is need by the ARP logic in order
    @@ -239,7 +239,7 @@ struct net_driver_s; /* Forward reference */
     void arp_format(FAR struct net_driver_s *dev, in_addr_t ipaddr);
     
     /****************************************************************************
    - * Function: arp_send
    + * Name: arp_send
      *
      * Description:
      *   The arp_send() call may be to send an ARP request to resolve an IPv4
    @@ -274,7 +274,7 @@ int arp_send(in_addr_t ipaddr);
     #endif
     
     /****************************************************************************
    - * Function: arp_poll
    + * Name: arp_poll
      *
      * Description:
      *   Poll all pending transfer for ARP requests to send.
    @@ -293,7 +293,7 @@ int arp_poll(FAR struct net_driver_s *dev, devif_poll_callback_t callback);
     #endif
     
     /****************************************************************************
    - * Function: arp_wait_setup
    + * Name: arp_wait_setup
      *
      * Description:
      *   Called BEFORE an ARP request is sent.  This function sets up the ARP
    @@ -313,7 +313,7 @@ void arp_wait_setup(in_addr_t ipaddr, FAR struct arp_notify_s *notify);
     #endif
     
     /****************************************************************************
    - * Function: arp_wait_cancel
    + * Name: arp_wait_cancel
      *
      * Description:
      *   Cancel any wait set after arp_wait_setup is called but before arm_wait()
    @@ -332,7 +332,7 @@ int arp_wait_cancel(FAR struct arp_notify_s *notify);
     #endif
     
     /****************************************************************************
    - * Function: arp_wait
    + * Name: arp_wait
      *
      * Description:
      *   Called each time that a ARP request is sent.  This function will sleep
    @@ -353,7 +353,7 @@ int arp_wait(FAR struct arp_notify_s *notify, FAR struct timespec *timeout);
     #endif
     
     /****************************************************************************
    - * Function: arp_notify
    + * Name: arp_notify
      *
      * Description:
      *   Called each time that a ARP response is received in order to wake-up
    diff --git a/net/arp/arp_notify.c b/net/arp/arp_notify.c
    index 7b92bfc25a..112cb6614a 100644
    --- a/net/arp/arp_notify.c
    +++ b/net/arp/arp_notify.c
    @@ -68,7 +68,7 @@ static FAR struct arp_notify_s *g_arp_waiters;
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: arp_wait_setup
    + * Name: arp_wait_setup
      *
      * Description:
      *   Called BEFORE an ARP request is sent.  This function sets up the ARP
    @@ -106,7 +106,7 @@ void arp_wait_setup(in_addr_t ipaddr, FAR struct arp_notify_s *notify)
     }
     
     /****************************************************************************
    - * Function: arp_wait_cancel
    + * Name: arp_wait_cancel
      *
      * Description:
      *   Cancel any wait set after arp_wait_setup is called but before arp_wait()
    @@ -155,7 +155,7 @@ int arp_wait_cancel(FAR struct arp_notify_s *notify)
     }
     
     /****************************************************************************
    - * Function: arp_wait
    + * Name: arp_wait
      *
      * Description:
      *   Called each time that a ARP request is sent.  This function will sleep
    @@ -220,7 +220,7 @@ int arp_wait(FAR struct arp_notify_s *notify, FAR struct timespec *timeout)
     }
     
     /****************************************************************************
    - * Function: arp_notify
    + * Name: arp_notify
      *
      * Description:
      *   Called each time that a ARP response is received in order to wake-up
    diff --git a/net/arp/arp_poll.c b/net/arp/arp_poll.c
    index 424d0fe2e7..9a023af347 100644
    --- a/net/arp/arp_poll.c
    +++ b/net/arp/arp_poll.c
    @@ -53,7 +53,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: arp_poll
    + * Name: arp_poll
      *
      * Description:
      *   Poll all pending transfer for ARP requests to send.
    diff --git a/net/arp/arp_send.c b/net/arp/arp_send.c
    index e5a1e48221..92de47e806 100644
    --- a/net/arp/arp_send.c
    +++ b/net/arp/arp_send.c
    @@ -75,7 +75,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: arp_send_terminate
    + * Name: arp_send_terminate
      ****************************************************************************/
     
     static void arp_send_terminate(FAR struct arp_send_s *state, int result)
    @@ -94,7 +94,7 @@ static void arp_send_terminate(FAR struct arp_send_s *state, int result)
     }
     
     /****************************************************************************
    - * Function: arp_send_interrupt
    + * Name: arp_send_interrupt
      ****************************************************************************/
     
     static uint16_t arp_send_interrupt(FAR struct net_driver_s *dev,
    @@ -158,7 +158,7 @@ static uint16_t arp_send_interrupt(FAR struct net_driver_s *dev,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: arp_send
    + * Name: arp_send
      *
      * Description:
      *   The arp_send() call may be to send an ARP request to resolve an IP
    diff --git a/net/arp/arp_timer.c b/net/arp/arp_timer.c
    index cec202ae41..1a893fc107 100644
    --- a/net/arp/arp_timer.c
    +++ b/net/arp/arp_timer.c
    @@ -72,7 +72,7 @@ static WDOG_ID g_arptimer;           /* ARP timer */
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: arptimer_poll
    + * Name: arptimer_poll
      *
      * Description:
      *   Periodic timer handler.  Called from the timer interrupt handler.
    @@ -104,7 +104,7 @@ static void arptimer_poll(int argc, wdparm_t arg, ...)
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: arp_timer_initialize
    + * Name: arp_timer_initialize
      *
      * Description:
      *   Initialized the 10 second timer that is need by the ARP logic in order
    diff --git a/net/devif/devif.h b/net/devif/devif.h
    index d7574786ec..baa1644c63 100644
    --- a/net/devif/devif.h
    +++ b/net/devif/devif.h
    @@ -297,7 +297,7 @@ extern "C"
     void devif_initialize(void);
     
     /****************************************************************************
    - * Function: devif_callback_init
    + * Name: devif_callback_init
      *
      * Description:
      *   Configure the pre-allocated callback structures into a free list.
    @@ -310,7 +310,7 @@ void devif_initialize(void);
     void devif_callback_init(void);
     
     /****************************************************************************
    - * Function: devif_callback_alloc
    + * Name: devif_callback_alloc
      *
      * Description:
      *   Allocate a callback container from the free list.
    @@ -330,7 +330,7 @@ FAR struct devif_callback_s *
                            FAR struct devif_callback_s **list);
     
     /****************************************************************************
    - * Function: devif_conn_callback_free
    + * Name: devif_conn_callback_free
      *
      * Description:
      *   Return a connection/port callback container to the free list.
    @@ -352,7 +352,7 @@ void devif_conn_callback_free(FAR struct net_driver_s *dev,
                                   FAR struct devif_callback_s **list);
     
     /****************************************************************************
    - * Function: devif_dev_callback_free
    + * Name: devif_dev_callback_free
      *
      * Description:
      *   Return a device callback container to the free list.
    @@ -375,7 +375,7 @@ void devif_dev_callback_free(FAR struct net_driver_s *dev,
                                  FAR struct devif_callback_s *cb);
     
     /****************************************************************************
    - * Function: devif_conn_event
    + * Name: devif_conn_event
      *
      * Description:
      *   Execute a list of callbacks.
    @@ -401,7 +401,7 @@ uint16_t devif_conn_event(FAR struct net_driver_s *dev, FAR void *pvconn,
                               uint16_t flags, FAR struct devif_callback_s *list);
     
     /****************************************************************************
    - * Function: devif_dev_event
    + * Name: devif_dev_event
      *
      * Description:
      *   Execute a list of callbacks using the device event chain.
    diff --git a/net/devif/devif_callback.c b/net/devif/devif_callback.c
    index 067b7663d9..bb8867b73f 100644
    --- a/net/devif/devif_callback.c
    +++ b/net/devif/devif_callback.c
    @@ -64,7 +64,7 @@ static FAR struct devif_callback_s *g_cbfreelist = NULL;
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: devif_callback_free
    + * Name: devif_callback_free
      *
      * Description:
      *   Return a callback container to the free list.
    @@ -167,7 +167,7 @@ static void devif_callback_free(FAR struct net_driver_s *dev,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: devif_callback_init
    + * Name: devif_callback_init
      *
      * Description:
      *   Configure the pre-allocated callback structures into a free list.
    @@ -189,7 +189,7 @@ void devif_callback_init(void)
     }
     
     /****************************************************************************
    - * Function: devif_callback_alloc
    + * Name: devif_callback_alloc
      *
      * Description:
      *   Allocate a callback container from the free list.
    @@ -267,7 +267,7 @@ FAR struct devif_callback_s *
     }
     
     /****************************************************************************
    - * Function: devif_conn_callback_free
    + * Name: devif_conn_callback_free
      *
      * Description:
      *   Return a connection/port callback container to the free list.
    @@ -306,7 +306,7 @@ void devif_conn_callback_free(FAR struct net_driver_s *dev,
     }
     
     /****************************************************************************
    - * Function: devif_dev_callback_free
    + * Name: devif_dev_callback_free
      *
      * Description:
      *   Return a device callback container to the free list.
    @@ -357,7 +357,7 @@ void devif_dev_callback_free(FAR struct net_driver_s *dev,
     }
     
     /****************************************************************************
    - * Function: devif_conn_event
    + * Name: devif_conn_event
      *
      * Description:
      *   Execute a list of callbacks using the packet event chain.
    @@ -421,7 +421,7 @@ uint16_t devif_conn_event(FAR struct net_driver_s *dev, void *pvconn,
     }
     
     /****************************************************************************
    - * Function: devif_dev_event
    + * Name: devif_dev_event
      *
      * Description:
      *   Execute a list of callbacks using the device event chain.
    diff --git a/net/devif/devif_poll.c b/net/devif/devif_poll.c
    index 235c58bcf2..107f68c6de 100644
    --- a/net/devif/devif_poll.c
    +++ b/net/devif/devif_poll.c
    @@ -85,7 +85,7 @@ systime_t g_polltime;
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: devif_packet_conversion
    + * Name: devif_packet_conversion
      *
      * Description:
      *   Generic output conversion hook.  Only needed for IEEE802.15.4 for now
    @@ -157,7 +157,7 @@ static void devif_packet_conversion(FAR struct net_driver_s *dev,
     #endif /* CONFIG_NET_6LOWPAN */
     
     /****************************************************************************
    - * Function: devif_poll_pkt_connections
    + * Name: devif_poll_pkt_connections
      *
      * Description:
      *   Poll all packet connections for available packets to send.
    @@ -197,7 +197,7 @@ static int devif_poll_pkt_connections(FAR struct net_driver_s *dev,
     #endif /* CONFIG_NET_PKT */
     
     /****************************************************************************
    - * Function: devif_poll_icmp
    + * Name: devif_poll_icmp
      *
      * Description:
      *   Poll all of the connections waiting to send an ICMP ECHO request
    @@ -223,7 +223,7 @@ static inline int devif_poll_icmp(FAR struct net_driver_s *dev,
     #endif /* CONFIG_NET_ICMP && CONFIG_NET_ICMP_PING */
     
     /****************************************************************************
    - * Function: devif_poll_icmpv6
    + * Name: devif_poll_icmpv6
      *
      * Description:
      *   Poll all of the connections waiting to send an ICMPv6 ECHO request
    @@ -249,7 +249,7 @@ static inline int devif_poll_icmpv6(FAR struct net_driver_s *dev,
     #endif /* CONFIG_NET_ICMPv6_PING || CONFIG_NET_ICMPv6_NEIGHBOR*/
     
     /****************************************************************************
    - * Function: devif_poll_igmp
    + * Name: devif_poll_igmp
      *
      * Description:
      *   Poll all IGMP connections for available packets to send.
    @@ -279,7 +279,7 @@ static inline int devif_poll_igmp(FAR struct net_driver_s *dev,
     #endif /* CONFIG_NET_IGMP */
     
     /****************************************************************************
    - * Function: devif_poll_udp_connections
    + * Name: devif_poll_udp_connections
      *
      * Description:
      *   Poll all UDP connections for available packets to send.
    @@ -319,7 +319,7 @@ static int devif_poll_udp_connections(FAR struct net_driver_s *dev,
     #endif /* NET_UDP_HAVE_STACK */
     
     /****************************************************************************
    - * Function: devif_poll_tcp_connections
    + * Name: devif_poll_tcp_connections
      *
      * Description:
      *   Poll all UDP connections for available packets to send.
    @@ -361,7 +361,7 @@ static inline int devif_poll_tcp_connections(FAR struct net_driver_s *dev,
     #endif
     
     /****************************************************************************
    - * Function: devif_poll_tcp_timer
    + * Name: devif_poll_tcp_timer
      *
      * Description:
      *   The TCP timer has expired.  Update TCP timing state in each active,
    @@ -409,7 +409,7 @@ static inline int devif_poll_tcp_timer(FAR struct net_driver_s *dev,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: devif_poll
    + * Name: devif_poll
      *
      * Description:
      *   This function will traverse each active network connection structure and
    @@ -513,7 +513,7 @@ int devif_poll(FAR struct net_driver_s *dev, devif_poll_callback_t callback)
     }
     
     /****************************************************************************
    - * Function: devif_timer
    + * Name: devif_timer
      *
      * Description:
      *   These function will traverse each active network connection structure and
    diff --git a/net/devif/ipv4_input.c b/net/devif/ipv4_input.c
    index faa23ad547..2920aeba3b 100644
    --- a/net/devif/ipv4_input.c
    +++ b/net/devif/ipv4_input.c
    @@ -140,7 +140,7 @@ static uint8_t g_reassembly_flags;
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: devif_reassembly
    + * Name: devif_reassembly
      *
      * Description:
      *   IP fragment reassembly: not well-tested.
    @@ -302,7 +302,7 @@ nullreturn:
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: ipv4_input
    + * Name: ipv4_input
      *
      * Description:
      *
    diff --git a/net/devif/ipv6_input.c b/net/devif/ipv6_input.c
    index 24be107a47..0e53240364 100644
    --- a/net/devif/ipv6_input.c
    +++ b/net/devif/ipv6_input.c
    @@ -114,7 +114,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: ipv6_input
    + * Name: ipv6_input
      *
      * Description:
      *
    diff --git a/net/devif/net_setipid.c b/net/devif/net_setipid.c
    index 79e9c25b35..b3cbf4ea8f 100644
    --- a/net/devif/net_setipid.c
    +++ b/net/devif/net_setipid.c
    @@ -58,7 +58,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: net_setipid
    + * Name: net_setipid
      *
      * Description:
      *   This function may be used at boot time to set the initial ip_id.
    diff --git a/net/icmp/icmp_ping.c b/net/icmp/icmp_ping.c
    index e6f8961b48..ca16f12663 100644
    --- a/net/icmp/icmp_ping.c
    +++ b/net/icmp/icmp_ping.c
    @@ -99,7 +99,7 @@ struct icmp_ping_s
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: ping_timeout
    + * Name: ping_timeout
      *
      * Description:
      *   Check for send timeout.
    @@ -127,7 +127,7 @@ static inline int ping_timeout(FAR struct icmp_ping_s *pstate)
     }
     
     /****************************************************************************
    - * Function: ping_interrupt
    + * Name: ping_interrupt
      *
      * Description:
      *   This function is called from the interrupt level to perform the actual
    diff --git a/net/icmpv6/icmpv6.h b/net/icmpv6/icmpv6.h
    index a5003cf9a8..a45197d1c6 100644
    --- a/net/icmpv6/icmpv6.h
    +++ b/net/icmpv6/icmpv6.h
    @@ -290,7 +290,7 @@ void icmpv6_radvertise(FAR struct net_driver_s *dev);
     #endif
     
     /****************************************************************************
    - * Function: icmpv6_wait_setup
    + * Name: icmpv6_wait_setup
      *
      * Description:
      *   Called BEFORE an Neighbor Solicitation is sent.  This function sets up
    @@ -311,7 +311,7 @@ void icmpv6_wait_setup(const net_ipv6addr_t ipaddr,
     #endif
     
     /****************************************************************************
    - * Function: icmpv6_wait_cancel
    + * Name: icmpv6_wait_cancel
      *
      * Description:
      *   Cancel any wait set after icmpv6_wait_setup is called but before
    @@ -331,7 +331,7 @@ int icmpv6_wait_cancel(FAR struct icmpv6_notify_s *notify);
     #endif
     
     /****************************************************************************
    - * Function: icmpv6_wait
    + * Name: icmpv6_wait
      *
      * Description:
      *   Called each time that a Neighbor Solicitation is sent.  This function
    @@ -353,7 +353,7 @@ int icmpv6_wait(FAR struct icmpv6_notify_s *notify,
     #endif
     
     /****************************************************************************
    - * Function: icmpv6_notify
    + * Name: icmpv6_notify
      *
      * Description:
      *   Called each time that a Neighbor Advertisement is received in order to
    @@ -393,7 +393,7 @@ int icmpv6_autoconfig(FAR struct net_driver_s *dev);
     #endif
     
     /****************************************************************************
    - * Function: icmpv6_rwait_setup
    + * Name: icmpv6_rwait_setup
      *
      * Description:
      *   Called BEFORE an Router Solicitation is sent.  This function sets up
    @@ -415,7 +415,7 @@ void icmpv6_rwait_setup(FAR struct net_driver_s *dev,
     #endif
     
     /****************************************************************************
    - * Function: icmpv6_rwait_cancel
    + * Name: icmpv6_rwait_cancel
      *
      * Description:
      *   Cancel any wait set after icmpv6_rwait_setup() is called but before
    @@ -435,7 +435,7 @@ int icmpv6_rwait_cancel(FAR struct icmpv6_rnotify_s *notify);
     #endif
     
     /****************************************************************************
    - * Function: icmpv6_rwait
    + * Name: icmpv6_rwait
      *
      * Description:
      *   Called each time that a Router Solicitation is sent.  This function
    @@ -457,7 +457,7 @@ int icmpv6_rwait(FAR struct icmpv6_rnotify_s *notify,
     #endif
     
     /****************************************************************************
    - * Function: icmpv6_rnotify
    + * Name: icmpv6_rnotify
      *
      * Description:
      *   Called each time that a Router Advertisement is received in order to
    diff --git a/net/icmpv6/icmpv6_notify.c b/net/icmpv6/icmpv6_notify.c
    index ad0ddbd8c1..2a0ce43690 100644
    --- a/net/icmpv6/icmpv6_notify.c
    +++ b/net/icmpv6/icmpv6_notify.c
    @@ -80,7 +80,7 @@ static struct icmpv6_notify_s *g_icmpv6_waiters;
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: icmpv6_wait_setup
    + * Name: icmpv6_wait_setup
      *
      * Description:
      *   Called BEFORE an Neighbor Solicitation is sent.  This function sets up
    @@ -119,7 +119,7 @@ void icmpv6_wait_setup(const net_ipv6addr_t ipaddr,
     }
     
     /****************************************************************************
    - * Function: icmpv6_wait_cancel
    + * Name: icmpv6_wait_cancel
      *
      * Description:
      *   Cancel any wait set after icmpv6_wait_setup is called but before
    @@ -169,7 +169,7 @@ int icmpv6_wait_cancel(FAR struct icmpv6_notify_s *notify)
     }
     
     /****************************************************************************
    - * Function: icmpv6_wait
    + * Name: icmpv6_wait
      *
      * Description:
      *   Called each time that a Neighbor Solicitation is sent.  This function
    @@ -224,7 +224,7 @@ int icmpv6_wait(FAR struct icmpv6_notify_s *notify,
     }
     
     /****************************************************************************
    - * Function: icmpv6_notify
    + * Name: icmpv6_notify
      *
      * Description:
      *   Called each time that a Neighbor Advertisement is received in order to
    diff --git a/net/icmpv6/icmpv6_ping.c b/net/icmpv6/icmpv6_ping.c
    index 2d37890464..ae9f4e7ced 100644
    --- a/net/icmpv6/icmpv6_ping.c
    +++ b/net/icmpv6/icmpv6_ping.c
    @@ -110,7 +110,7 @@ struct icmpv6_ping_s
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: ping_timeout
    + * Name: ping_timeout
      *
      * Description:
      *   Check for send timeout.
    @@ -228,7 +228,7 @@ static void icmpv6_echo_request(FAR struct net_driver_s *dev,
     }
     
     /****************************************************************************
    - * Function: ping_interrupt
    + * Name: ping_interrupt
      *
      * Description:
      *   This function is called from the interrupt level to perform the actual
    diff --git a/net/icmpv6/icmpv6_rnotify.c b/net/icmpv6/icmpv6_rnotify.c
    index b43d825702..49f0199e01 100644
    --- a/net/icmpv6/icmpv6_rnotify.c
    +++ b/net/icmpv6/icmpv6_rnotify.c
    @@ -79,7 +79,7 @@ static struct icmpv6_rnotify_s *g_icmpv6_rwaiters;
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: icmpv6_setaddresses
    + * Name: icmpv6_setaddresses
      *
      * Description:
      *   We successfully obtained the Router Advertisement.  See the new IPv6
    @@ -143,7 +143,7 @@ static void icmpv6_setaddresses(FAR struct net_driver_s *dev,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: icmpv6_rwait_setup
    + * Name: icmpv6_rwait_setup
      *
      * Description:
      *   Called BEFORE an Router Solicitation is sent.  This function sets up
    @@ -204,7 +204,7 @@ void icmpv6_rwait_setup(FAR struct net_driver_s *dev,
     }
     
     /****************************************************************************
    - * Function: icmpv6_rwait_cancel
    + * Name: icmpv6_rwait_cancel
      *
      * Description:
      *   Cancel any wait set after icmpv6_rwait_setup() is called but before
    @@ -269,7 +269,7 @@ int icmpv6_rwait_cancel(FAR struct icmpv6_rnotify_s *notify)
     }
     
     /****************************************************************************
    - * Function: icmpv6_rwait
    + * Name: icmpv6_rwait
      *
      * Description:
      *   Called each time that a Router Solicitation is sent.  This function
    @@ -326,7 +326,7 @@ int icmpv6_rwait(FAR struct icmpv6_rnotify_s *notify,
     }
     
     /****************************************************************************
    - * Function: icmpv6_rnotify
    + * Name: icmpv6_rnotify
      *
      * Description:
      *   Called each time that a Router Advertisement is received in order to
    diff --git a/net/local/local.h b/net/local/local.h
    index 999f804ea0..db4fffc0fa 100644
    --- a/net/local/local.h
    +++ b/net/local/local.h
    @@ -321,7 +321,7 @@ int local_release(FAR struct local_conn_s *conn);
     int local_listen(FAR struct local_conn_s *server, int backlog);
     
     /****************************************************************************
    - * Function: psock_local_accept
    + * Name: psock_local_accept
      *
      * Description:
      *   This function implements accept() for Unix domain sockets.  See the
    @@ -371,7 +371,7 @@ ssize_t psock_local_send(FAR struct socket *psock, FAR const void *buf,
     #endif
     
     /****************************************************************************
    - * Function: psock_local_sendto
    + * Name: psock_local_sendto
      *
      * Description:
      *   This function implements the Unix domain-specific logic of the
    @@ -421,7 +421,7 @@ ssize_t psock_local_sendto(FAR struct socket *psock, FAR const void *buf,
     int local_send_packet(int fd, FAR const uint8_t *buf, size_t len);
     
     /****************************************************************************
    - * Function: psock_recvfrom
    + * Name: psock_recvfrom
      *
      * Description:
      *   recvfrom() receives messages from a local socket, and may be used to
    @@ -646,7 +646,7 @@ void local_accept_pollnotify(FAR struct local_conn_s *conn,
     #endif
     
     /****************************************************************************
    - * Function: local_pollsetup
    + * Name: local_pollsetup
      *
      * Description:
      *   Setup to monitor events on one Unix domain socket
    @@ -666,7 +666,7 @@ int local_pollsetup(FAR struct socket *psock, FAR struct pollfd *fds);
     #endif
     
     /****************************************************************************
    - * Function: local_pollteardown
    + * Name: local_pollteardown
      *
      * Description:
      *   Teardown monitoring of events on a Unix domain socket
    diff --git a/net/local/local_accept.c b/net/local/local_accept.c
    index e148e3e60f..2ead57d103 100644
    --- a/net/local/local_accept.c
    +++ b/net/local/local_accept.c
    @@ -56,7 +56,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: local_waitlisten
    + * Name: local_waitlisten
      ****************************************************************************/
     
     static int local_waitlisten(FAR struct local_conn_s *server)
    @@ -88,7 +88,7 @@ static int local_waitlisten(FAR struct local_conn_s *server)
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: psock_local_accept
    + * Name: psock_local_accept
      *
      * Description:
      *   This function implements accept() for Unix domain sockets.  See the
    diff --git a/net/local/local_netpoll.c b/net/local/local_netpoll.c
    index f9e087b36d..cf741d9442 100644
    --- a/net/local/local_netpoll.c
    +++ b/net/local/local_netpoll.c
    @@ -54,7 +54,7 @@
     #ifdef HAVE_LOCAL_POLL
     
     /****************************************************************************
    - * Function: local_accept_pollsetup
    + * Name: local_accept_pollsetup
      ****************************************************************************/
     
     #ifdef CONFIG_NET_LOCAL_STREAM
    @@ -160,7 +160,7 @@ void local_accept_pollnotify(FAR struct local_conn_s *conn,
     }
     
     /****************************************************************************
    - * Function: local_pollsetup
    + * Name: local_pollsetup
      *
      * Description:
      *   Setup to monitor events on one Unix domain socket
    @@ -299,7 +299,7 @@ pollerr:
     }
     
     /****************************************************************************
    - * Function: local_pollteardown
    + * Name: local_pollteardown
      *
      * Description:
      *   Teardown monitoring of events on a Unix domain socket
    diff --git a/net/local/local_recvfrom.c b/net/local/local_recvfrom.c
    index 8585468f61..a19d5323b3 100644
    --- a/net/local/local_recvfrom.c
    +++ b/net/local/local_recvfrom.c
    @@ -120,7 +120,7 @@ static int psock_fifo_read(FAR struct socket *psock, FAR void *buf,
     }
     
     /****************************************************************************
    - * Function: psock_stream_recvfrom
    + * Name: psock_stream_recvfrom
      *
      * Description:
      *   psock_stream_recvfrom() receives messages from a local stream socket.
    @@ -216,7 +216,7 @@ psock_stream_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
     #endif /* CONFIG_NET_LOCAL_STREAM */
     
     /****************************************************************************
    - * Function: psock_dgram_recvfrom
    + * Name: psock_dgram_recvfrom
      *
      * Description:
      *   psock_dgram_recvfrom() receives messages from a local datagram socket.
    @@ -387,7 +387,7 @@ errout_with_halfduplex:
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: psock_local_recvfrom
    + * Name: psock_local_recvfrom
      *
      * Description:
      *   psock_local_recvfrom() receives messages from a local socket and may be
    diff --git a/net/local/local_sendto.c b/net/local/local_sendto.c
    index 1351c67a28..de59ee34f9 100644
    --- a/net/local/local_sendto.c
    +++ b/net/local/local_sendto.c
    @@ -57,7 +57,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: psock_local_sendto
    + * Name: psock_local_sendto
      *
      * Description:
      *   This function implements the Unix domain-specific logic of the
    diff --git a/net/netdev/netdev.h b/net/netdev/netdev.h
    index 19955d3951..06409909cf 100644
    --- a/net/netdev/netdev.h
    +++ b/net/netdev/netdev.h
    @@ -86,7 +86,7 @@ void netdev_ifup(FAR struct net_driver_s *dev);
     void netdev_ifdown(FAR struct net_driver_s *dev);
     
     /****************************************************************************
    - * Function: netdev_verify
    + * Name: netdev_verify
      *
      * Description:
      *   Verify that the specified device still exists
    @@ -99,7 +99,7 @@ void netdev_ifdown(FAR struct net_driver_s *dev);
     bool netdev_verify(FAR struct net_driver_s *dev);
     
     /****************************************************************************
    - * Function: netdev_findbyname
    + * Name: netdev_findbyname
      *
      * Description:
      *   Find a previously registered network device using its assigned
    @@ -121,7 +121,7 @@ FAR struct net_driver_s *netdev_findbyname(FAR const char *ifname);
     #endif
     
     /****************************************************************************
    - * Function: netdev_findby_ipv4addr
    + * Name: netdev_findby_ipv4addr
      *
      * Description:
      *   Find a previously registered network device by matching an arbitrary
    @@ -151,7 +151,7 @@ FAR struct net_driver_s *netdev_findby_ipv4addr(in_addr_t ripaddr);
     #endif
     
     /****************************************************************************
    - * Function: netdev_findby_ipv6addr
    + * Name: netdev_findby_ipv6addr
      *
      * Description:
      *   Find a previously registered network device by matching an arbitrary
    @@ -181,7 +181,7 @@ FAR struct net_driver_s *netdev_findby_ipv6addr(const net_ipv6addr_t ripaddr);
     #endif
     
     /****************************************************************************
    - * Function: netdev_findbyindex
    + * Name: netdev_findbyindex
      *
      * Description:
      *   Find a previously registered network device by its position in the
    @@ -205,7 +205,7 @@ FAR struct net_driver_s *netdev_findby_ipv6addr(const net_ipv6addr_t ripaddr);
     FAR struct net_driver_s *netdev_findbyindex(int index);
     
     /****************************************************************************
    - * Function: netdev_default
    + * Name: netdev_default
      *
      * Description:
      *   Return the default network device.  REVISIT:  At present this function
    @@ -233,7 +233,7 @@ FAR struct net_driver_s *netdev_default(void);
     #endif
     
     /****************************************************************************
    - * Function: netdev_ipv4_txnotify
    + * Name: netdev_ipv4_txnotify
      *
      * Description:
      *   Notify the device driver that forwards the IPv4 address that new TX
    @@ -261,7 +261,7 @@ void netdev_ipv4_txnotify(in_addr_t ripaddr);
     #endif /* CONFIG_NET_IPv4 */
     
     /****************************************************************************
    - * Function: netdev_ipv6_txnotify
    + * Name: netdev_ipv6_txnotify
      *
      * Description:
      *   Notify the device driver that forwards the IPv4 address that new TX
    @@ -290,7 +290,7 @@ void netdev_ipv6_txnotify(FAR const net_ipv6addr_t ripaddr);
     #endif /* CONFIG_NSOCKET_DESCRIPTORS > 0 */
     
     /****************************************************************************
    - * Function: netdev_txnotify_dev
    + * Name: netdev_txnotify_dev
      *
      * Description:
      *   Notify the device driver that new TX data is available.  This variant
    @@ -311,7 +311,7 @@ void netdev_ipv6_txnotify(FAR const net_ipv6addr_t ripaddr);
     void netdev_txnotify_dev(FAR struct net_driver_s *dev);
     
     /****************************************************************************
    - * Function: netdev_ipv4_rxnotify
    + * Name: netdev_ipv4_rxnotify
      *
      * Description:
      *   Notify the device driver that forwards the IPv4 address that the
    @@ -340,7 +340,7 @@ void netdev_ipv4_rxnotify(in_addr_t ripaddr);
     #endif /* CONFIG_NET_IPv4 */
     
     /****************************************************************************
    - * Function: netdev_ipv6_rxnotify
    + * Name: netdev_ipv6_rxnotify
      *
      * Description:
      *   Notify the device driver that forwards the IPv6 address that the
    @@ -386,7 +386,7 @@ void netdev_ipv6_rxnotify(FAR const net_ipv6addr_t ripaddr);
     #endif
     
     /****************************************************************************
    - * Function: netdev_count
    + * Name: netdev_count
      *
      * Description:
      *   Return the number of network devices
    diff --git a/net/netdev/netdev_carrier.c b/net/netdev/netdev_carrier.c
    index 8c42203328..35f9ff2892 100644
    --- a/net/netdev/netdev_carrier.c
    +++ b/net/netdev/netdev_carrier.c
    @@ -59,7 +59,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: netdev_carrier_on
    + * Name: netdev_carrier_on
      *
      * Description:
      *   Notifies the networking layer about an available carrier.
    @@ -85,7 +85,7 @@ int netdev_carrier_on(FAR struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: netdev_carrier_off
    + * Name: netdev_carrier_off
      *
      * Description:
      *   Notifies the networking layer about an disappeared carrier.
    diff --git a/net/netdev/netdev_count.c b/net/netdev/netdev_count.c
    index 171039caf6..71a1ecaab4 100644
    --- a/net/netdev/netdev_count.c
    +++ b/net/netdev/netdev_count.c
    @@ -53,7 +53,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: netdev_count
    + * Name: netdev_count
      *
      * Description:
      *   Return the number of network devices
    diff --git a/net/netdev/netdev_default.c b/net/netdev/netdev_default.c
    index 331f50343d..40a176f1a2 100644
    --- a/net/netdev/netdev_default.c
    +++ b/net/netdev/netdev_default.c
    @@ -50,7 +50,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: netdev_default
    + * Name: netdev_default
      *
      * Description:
      *   Return the default network device.  REVISIT:  At present this function
    diff --git a/net/netdev/netdev_findbyaddr.c b/net/netdev/netdev_findbyaddr.c
    index 6aea450393..bd41a262fb 100644
    --- a/net/netdev/netdev_findbyaddr.c
    +++ b/net/netdev/netdev_findbyaddr.c
    @@ -60,7 +60,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: netdev_finddevice_ipv4addr
    + * Name: netdev_finddevice_ipv4addr
      *
      * Description:
      *   Find a previously registered network device by matching a local address
    @@ -113,7 +113,7 @@ static FAR struct net_driver_s *netdev_finddevice_ipv4addr(in_addr_t ripaddr)
     #endif /* CONFIG_NET_IPv4 */
     
     /****************************************************************************
    - * Function: netdev_finddevice_ipv6addr
    + * Name: netdev_finddevice_ipv6addr
      *
      * Description:
      *   Find a previously registered network device by matching a local address
    @@ -171,7 +171,7 @@ netdev_finddevice_ipv6addr(const net_ipv6addr_t ripaddr)
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: netdev_findby_ipv4addr
    + * Name: netdev_findby_ipv4addr
      *
      * Description:
      *   Find a previously registered network device by matching an arbitrary
    @@ -293,7 +293,7 @@ FAR struct net_driver_s *netdev_findby_ipv4addr(in_addr_t ripaddr)
     #endif /* CONFIG_NET_IPv4 */
     
     /****************************************************************************
    - * Function: netdev_findby_ipv6addr
    + * Name: netdev_findby_ipv6addr
      *
      * Description:
      *   Find a previously registered network device by matching an arbitrary
    diff --git a/net/netdev/netdev_findbyindex.c b/net/netdev/netdev_findbyindex.c
    index f17bba0b7c..2496d2b902 100644
    --- a/net/netdev/netdev_findbyindex.c
    +++ b/net/netdev/netdev_findbyindex.c
    @@ -53,7 +53,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: netdev_findbyindex
    + * Name: netdev_findbyindex
      *
      * Description:
      *   Find a previously registered network device by its position in the
    diff --git a/net/netdev/netdev_findbyname.c b/net/netdev/netdev_findbyname.c
    index 944489a2d0..50b7ffbddd 100644
    --- a/net/netdev/netdev_findbyname.c
    +++ b/net/netdev/netdev_findbyname.c
    @@ -53,7 +53,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: netdev_findbyname
    + * Name: netdev_findbyname
      *
      * Description:
      *   Find a previously registered network device using its assigned
    diff --git a/net/netdev/netdev_foreach.c b/net/netdev/netdev_foreach.c
    index 11df953902..bb6a9c6c3e 100644
    --- a/net/netdev/netdev_foreach.c
    +++ b/net/netdev/netdev_foreach.c
    @@ -51,7 +51,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: netdev_foreach
    + * Name: netdev_foreach
      *
      * Description:
      *   Enumerate each registered network device.
    diff --git a/net/netdev/netdev_register.c b/net/netdev/netdev_register.c
    index 01a61b5b8e..1aef9c3ed1 100644
    --- a/net/netdev/netdev_register.c
    +++ b/net/netdev/netdev_register.c
    @@ -103,7 +103,7 @@ struct net_driver_s *g_netdevices = NULL;
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: find_devnum
    + * Name: find_devnum
      *
      * Description:
      *   Given a device name format string, find the next device number for the
    @@ -156,7 +156,7 @@ static int find_devnum(FAR const char *devfmt)
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: netdev_register
    + * Name: netdev_register
      *
      * Description:
      *   Register a network device driver and assign a name to it so that it can
    diff --git a/net/netdev/netdev_rxnotify.c b/net/netdev/netdev_rxnotify.c
    index be7aed64d0..1c18bb51d1 100644
    --- a/net/netdev/netdev_rxnotify.c
    +++ b/net/netdev/netdev_rxnotify.c
    @@ -55,7 +55,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: netdev_ipv4_rxnotify
    + * Name: netdev_ipv4_rxnotify
      *
      * Description:
      *   Notify the device driver that forwards the IPv4 address that the
    @@ -100,7 +100,7 @@ void netdev_ipv4_rxnotify(in_addr_t ripaddr)
     #endif /* CONFIG_NET_IPv4 */
     
     /****************************************************************************
    - * Function: netdev_ipv6_rxnotify
    + * Name: netdev_ipv6_rxnotify
      *
      * Description:
      *   Notify the device driver that forwards the IPv6 address that the
    diff --git a/net/netdev/netdev_txnotify.c b/net/netdev/netdev_txnotify.c
    index 3d0c85203c..72382e01df 100644
    --- a/net/netdev/netdev_txnotify.c
    +++ b/net/netdev/netdev_txnotify.c
    @@ -55,7 +55,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: netdev_ipv4_txnotify
    + * Name: netdev_ipv4_txnotify
      *
      * Description:
      *   Notify the device driver that forwards the IPv4 address that new TX
    @@ -101,7 +101,7 @@ void netdev_ipv4_txnotify(in_addr_t ripaddr)
     
     
     /****************************************************************************
    - * Function: netdev_ipv6_txnotify
    + * Name: netdev_ipv6_txnotify
      *
      * Description:
      *   Notify the device driver that forwards the IPv4 address that new TX
    @@ -147,7 +147,7 @@ void netdev_ipv6_txnotify(FAR const net_ipv6addr_t ripaddr)
     #endif /* CONFIG_NET_IPv6 */
     
     /****************************************************************************
    - * Function: netdev_txnotify_dev
    + * Name: netdev_txnotify_dev
      *
      * Description:
      *   Notify the device driver that new TX data is available.  This variant
    diff --git a/net/netdev/netdev_unregister.c b/net/netdev/netdev_unregister.c
    index 6d56ad70f4..57c6754a7c 100644
    --- a/net/netdev/netdev_unregister.c
    +++ b/net/netdev/netdev_unregister.c
    @@ -70,7 +70,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: netdev_unregister
    + * Name: netdev_unregister
      *
      * Description:
      *   Unregister a network device driver.
    diff --git a/net/netdev/netdev_verify.c b/net/netdev/netdev_verify.c
    index ee3031ea78..14e05b97a0 100644
    --- a/net/netdev/netdev_verify.c
    +++ b/net/netdev/netdev_verify.c
    @@ -51,7 +51,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: netdev_verify
    + * Name: netdev_verify
      *
      * Description:
      *   Verify that the specified device still exists
    diff --git a/net/pkt/pkt.h b/net/pkt/pkt.h
    index 295c40b07e..aa6237da81 100644
    --- a/net/pkt/pkt.h
    +++ b/net/pkt/pkt.h
    @@ -160,7 +160,7 @@ struct pkt_conn_s *pkt_nextconn(FAR struct pkt_conn_s *conn);
     
     /* Defined in pkt_callback.c ************************************************/
     /****************************************************************************
    - * Function: pkt_callback
    + * Name: pkt_callback
      *
      * Description:
      *   Inform the application holding the packet socket of a change in state.
    @@ -199,7 +199,7 @@ uint16_t pkt_callback(FAR struct net_driver_s *dev,
     /* pkt_input() is prototyped in include/nuttx/net/pkt.h */
     
     /****************************************************************************
    - * Function: pkt_find_device
    + * Name: pkt_find_device
      *
      * Description:
      *   Select the network driver to use with the PKT transaction.
    @@ -235,7 +235,7 @@ FAR struct net_driver_s *pkt_find_device(FAR struct pkt_conn_s *conn);
     void pkt_poll(FAR struct net_driver_s *dev, FAR struct pkt_conn_s *conn);
     
     /****************************************************************************
    - * Function: psock_pkt_send
    + * Name: psock_pkt_send
      *
      * Description:
      *   The psock_pkt_send() call may be used only when the packet socket is in a
    diff --git a/net/pkt/pkt_callback.c b/net/pkt/pkt_callback.c
    index 53df4c4afd..1343796256 100644
    --- a/net/pkt/pkt_callback.c
    +++ b/net/pkt/pkt_callback.c
    @@ -54,7 +54,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: pkt_callback
    + * Name: pkt_callback
      *
      * Description:
      *   Inform the application holding the packet socket of a change in state.
    diff --git a/net/pkt/pkt_finddev.c b/net/pkt/pkt_finddev.c
    index 639c894b3b..19e7fedd13 100644
    --- a/net/pkt/pkt_finddev.c
    +++ b/net/pkt/pkt_finddev.c
    @@ -50,7 +50,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: pkt_find_device
    + * Name: pkt_find_device
      *
      * Description:
      *   Select the network driver to use with the PKT transaction.
    diff --git a/net/pkt/pkt_send.c b/net/pkt/pkt_send.c
    index fa5bda318b..3902247fc8 100644
    --- a/net/pkt/pkt_send.c
    +++ b/net/pkt/pkt_send.c
    @@ -86,7 +86,7 @@ struct send_s
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: psock_send_interrupt
    + * Name: psock_send_interrupt
      ****************************************************************************/
     
     static uint16_t psock_send_interrupt(FAR struct net_driver_s *dev,
    @@ -152,7 +152,7 @@ static uint16_t psock_send_interrupt(FAR struct net_driver_s *dev,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: psock_pkt_send
    + * Name: psock_pkt_send
      *
      * Description:
      *   The psock_pkt_send() call may be used only when the packet socket is in a
    diff --git a/net/route/net_addroute.c b/net/route/net_addroute.c
    index 1f75944ec5..28496ebe19 100644
    --- a/net/route/net_addroute.c
    +++ b/net/route/net_addroute.c
    @@ -58,7 +58,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: net_addroute
    + * Name: net_addroute
      *
      * Description:
      *   Add a new route to the routing table
    diff --git a/net/route/net_allocroute.c b/net/route/net_allocroute.c
    index 8c0cfdd02f..edb08d24b5 100644
    --- a/net/route/net_allocroute.c
    +++ b/net/route/net_allocroute.c
    @@ -93,7 +93,7 @@ static struct net_route_ipv6_s g_preallocroutes_ipv6[CONFIG_NET_MAXROUTES];
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: net_initroute
    + * Name: net_initroute
      *
      * Description:
      *   Initialize to the routing table
    @@ -143,7 +143,7 @@ void net_initroute(void)
     }
     
     /****************************************************************************
    - * Function: net_allocroute
    + * Name: net_allocroute
      *
      * Description:
      *   Allocate one route by removing it from the free list
    @@ -196,7 +196,7 @@ FAR struct net_route_ipv6_s *net_allocroute_ipv6(void)
     #endif
     
     /****************************************************************************
    - * Function: net_freeroute
    + * Name: net_freeroute
      *
      * Description:
      *   Free one route by adding it from the free list
    diff --git a/net/route/net_delroute.c b/net/route/net_delroute.c
    index 1efbb0e18e..b40b6a7c21 100644
    --- a/net/route/net_delroute.c
    +++ b/net/route/net_delroute.c
    @@ -76,7 +76,7 @@ struct route_match_ipv6_s
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: net_match
    + * Name: net_match
      *
      * Description:
      *   Return 1 if the route is available
    @@ -175,7 +175,7 @@ static int net_match_ipv6(FAR struct net_route_ipv6_s *route, FAR void *arg)
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: net_delroute
    + * Name: net_delroute
      *
      * Description:
      *   Remove an existing route from the routing table
    diff --git a/net/route/net_foreachroute.c b/net/route/net_foreachroute.c
    index b9e52051af..f386088ce4 100644
    --- a/net/route/net_foreachroute.c
    +++ b/net/route/net_foreachroute.c
    @@ -55,7 +55,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: net_foreachroute
    + * Name: net_foreachroute
      *
      * Description:
      *   Traverse the route table
    diff --git a/net/route/net_router.c b/net/route/net_router.c
    index a72990e37d..add9761255 100644
    --- a/net/route/net_router.c
    +++ b/net/route/net_router.c
    @@ -77,7 +77,7 @@ struct route_ipv6_match_s
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: net_ipv4_match
    + * Name: net_ipv4_match
      *
      * Description:
      *   Return 1 if the IPv4 route is available
    @@ -114,7 +114,7 @@ static int net_ipv4_match(FAR struct net_route_s *route, FAR void *arg)
     #endif /* CONFIG_NET_IPv4 */
     
     /****************************************************************************
    - * Function: net_ipv6_match
    + * Name: net_ipv6_match
      *
      * Description:
      *   Return 1 if the IPv6 route is available
    @@ -155,7 +155,7 @@ static int net_ipv6_match(FAR struct net_route_ipv6_s *route, FAR void *arg)
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: net_ipv4_router
    + * Name: net_ipv4_router
      *
      * Description:
      *   Given an IPv4 address on a external network, return the address of the
    @@ -213,7 +213,7 @@ int net_ipv4_router(in_addr_t target, FAR in_addr_t *router)
     #endif /* CONFIG_NET_IPv4 */
     
     /****************************************************************************
    - * Function: net_ipv6_router
    + * Name: net_ipv6_router
      *
      * Description:
      *   Given an IPv6 address on a external network, return the address of the
    diff --git a/net/route/netdev_router.c b/net/route/netdev_router.c
    index d76a4e52b7..9ba9cb3a4c 100644
    --- a/net/route/netdev_router.c
    +++ b/net/route/netdev_router.c
    @@ -78,7 +78,7 @@ struct route_ipv6_devmatch_s
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: net_ipv4_devmatch
    + * Name: net_ipv4_devmatch
      *
      * Description:
      *   Return 1 if the IPv4 route is available on the device's network.
    @@ -119,7 +119,7 @@ static int net_ipv4_devmatch(FAR struct net_route_s *route, FAR void *arg)
     #endif /* CONFIG_NET_IPv4 */
     
     /****************************************************************************
    - * Function: net_ipv6_devmatch
    + * Name: net_ipv6_devmatch
      *
      * Description:
      *   Return 1 if the IPv6 route is available on the device's network.
    @@ -164,7 +164,7 @@ static int net_ipv6_devmatch(FAR struct net_route_ipv6_s *route, FAR void *arg)
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: netdev_ipv4_router
    + * Name: netdev_ipv4_router
      *
      * Description:
      *   Given an IPv4 address on a external network, return the address of the
    @@ -220,7 +220,7 @@ void netdev_ipv4_router(FAR struct net_driver_s *dev, in_addr_t target,
     #endif
     
     /****************************************************************************
    - * Function: netdev_ipv6_router
    + * Name: netdev_ipv6_router
      *
      * Description:
      *   Given an IPv6 address on a external network, return the address of the
    diff --git a/net/route/route.h b/net/route/route.h
    index 99e8e67676..460b9dfd0c 100644
    --- a/net/route/route.h
    +++ b/net/route/route.h
    @@ -118,7 +118,7 @@ EXTERN sq_queue_t g_routes_ipv6;
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: net_initroute
    + * Name: net_initroute
      *
      * Description:
      *   Initialize to the routing table
    @@ -134,7 +134,7 @@ EXTERN sq_queue_t g_routes_ipv6;
     void net_initroute(void);
     
     /****************************************************************************
    - * Function: net_allocroute
    + * Name: net_allocroute
      *
      * Description:
      *   Allocate one route by removing it from the free list
    @@ -157,7 +157,7 @@ FAR struct net_route_ipv6_s *net_allocroute_ipv6(void);
     #endif
     
     /****************************************************************************
    - * Function: net_allocroute
    + * Name: net_allocroute
      *
      * Description:
      *   Free one route by adding it from the free list
    @@ -179,7 +179,7 @@ void net_freeroute_ipv6(FAR struct net_route_ipv6_s *route);
     #endif
     
     /****************************************************************************
    - * Function: net_addroute
    + * Name: net_addroute
      *
      * Description:
      *   Add a new route to the routing table
    @@ -206,7 +206,7 @@ int net_addroute_ipv6(net_ipv6addr_t target, net_ipv6addr_t netmask,
     #endif
     
     /****************************************************************************
    - * Function: net_delroute
    + * Name: net_delroute
      *
      * Description:
      *   Remove an existing route from the routing table
    @@ -227,7 +227,7 @@ int net_delroute_ipv6(net_ipv6addr_t target, net_ipv6addr_t netmask);
     #endif
     
     /****************************************************************************
    - * Function: net_ipv4_router
    + * Name: net_ipv4_router
      *
      * Description:
      *   Given an IPv4 address on a external network, return the address of the
    @@ -248,7 +248,7 @@ int net_ipv4_router(in_addr_t target, FAR in_addr_t *router);
     #endif
     
     /****************************************************************************
    - * Function: net_ipv6_router
    + * Name: net_ipv6_router
      *
      * Description:
      *   Given an IPv6 address on a external network, return the address of the
    @@ -269,7 +269,7 @@ int net_ipv6_router(net_ipv6addr_t target, net_ipv6addr_t router);
     #endif
     
     /****************************************************************************
    - * Function: netdev_ipv4_router
    + * Name: netdev_ipv4_router
      *
      * Description:
      *   Given an IPv4 address on a external network, return the address of the
    @@ -296,7 +296,7 @@ void netdev_ipv4_router(FAR struct net_driver_s *dev, in_addr_t target,
     #endif
     
     /****************************************************************************
    - * Function: netdev_ipv6_router
    + * Name: netdev_ipv6_router
      *
      * Description:
      *   Given an IPv6 address on a external network, return the address of the
    @@ -324,7 +324,7 @@ void netdev_ipv6_router(FAR struct net_driver_s *dev,
     #endif
     
     /****************************************************************************
    - * Function: net_foreachroute
    + * Name: net_foreachroute
      *
      * Description:
      *   Traverse the route table
    diff --git a/net/sixlowpan/sixlowpan.h b/net/sixlowpan/sixlowpan.h
    index 05ce9496c9..fe4451c093 100644
    --- a/net/sixlowpan/sixlowpan.h
    +++ b/net/sixlowpan/sixlowpan.h
    @@ -79,7 +79,7 @@ struct sockaddr;     /* Forward reference */
     void sixlowpan_initialize(void);
     
     /****************************************************************************
    - * Function: psock_6lowpan_tcp_send
    + * Name: psock_6lowpan_tcp_send
      *
      * Description:
      *   psock_6lowpan_tcp_send() call may be used only when the TCP socket is in a
    @@ -107,7 +107,7 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf,
     #endif
     
     /****************************************************************************
    - * Function: sixlowpan_tcp_send
    + * Name: sixlowpan_tcp_send
      *
      * Description:
      *   TCP output comes through three different mechansims.  Either from:
    @@ -139,7 +139,7 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf,
     void sixlowpan_tcp_send(FAR struct net_driver_s *dev);
     
     /****************************************************************************
    - * Function: psock_6lowpan_udp_send
    + * Name: psock_6lowpan_udp_send
      *
      * Description:
      *   psock_6lowpan_udp_send() call may be used with connectionlesss UDP
    @@ -167,7 +167,7 @@ ssize_t psock_6lowpan_udp_send(FAR struct socket *psock, FAR const void *buf,
     #endif
     
     /****************************************************************************
    - * Function: psock_6lowpan_udp_sendto
    + * Name: psock_6lowpan_udp_sendto
      *
      * Description:
      *   If sendto() is used on a connection-mode (SOCK_STREAM, SOCK_SEQPACKET)
    diff --git a/net/sixlowpan/sixlowpan_framer.c b/net/sixlowpan/sixlowpan_framer.c
    index 66f8a1c3fb..d8771a060c 100644
    --- a/net/sixlowpan/sixlowpan_framer.c
    +++ b/net/sixlowpan/sixlowpan_framer.c
    @@ -82,7 +82,7 @@ struct field_length_s
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: sixlowpan_addrlen
    + * Name: sixlowpan_addrlen
      *
      * Description:
      *   Return the address length associated with a 2-bit address mode
    @@ -109,7 +109,7 @@ static inline uint8_t sixlowpan_addrlen(uint8_t addrmode)
     }
     
     /****************************************************************************
    - * Function: sixlowpan_addrnull
    + * Name: sixlowpan_addrnull
      *
      * Description:
      *   If the output address is NULL in the Rime buf, then it is broadcast
    @@ -140,7 +140,7 @@ static bool sixlowpan_addrnull(FAR uint8_t *addr)
     
     
     /****************************************************************************
    - * Function: sixlowpan_fieldlengths
    + * Name: sixlowpan_fieldlengths
      *
      * Description:
      *   Return the lengths associated fields of the IEEE802.15.4 header.
    @@ -228,7 +228,7 @@ static void sixlowpan_fieldlengths(FAR struct frame802154_s *finfo,
     }
     
     /****************************************************************************
    - * Function: sixlowpan_fieldlengths
    + * Name: sixlowpan_fieldlengths
      *
      * Description:
      *   Return the lengths associated fields of the IEEE802.15.4 header.
    @@ -249,7 +249,7 @@ static int sixlowpan_flen_hdrlen(FAR const struct field_length_s *flen)
     }
     
     /****************************************************************************
    - * Function: sixlowpan_802154_hdrlen
    + * Name: sixlowpan_802154_hdrlen
      *
      * Description:
      *   Calculates the length of the frame header.  This function is meant to
    @@ -272,7 +272,7 @@ static int sixlowpan_802154_hdrlen(FAR struct frame802154_s *finfo)
     }
     
     /****************************************************************************
    - * Function: sixlowpan_setup_params
    + * Name: sixlowpan_setup_params
      *
      * Description:
      *   Configure frame parmeters structure.
    @@ -382,7 +382,7 @@ static void sixlowpan_setup_params(FAR struct ieee802154_driver_s *ieee,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: sixlowpan_send_hdrlen
    + * Name: sixlowpan_send_hdrlen
      *
      * Description:
      *   This function is before the first frame has been sent in order to
    @@ -415,7 +415,7 @@ int sixlowpan_send_hdrlen(FAR struct ieee802154_driver_s *ieee,
     }
     
     /****************************************************************************
    - * Function: sixlowpan_802154_framecreate
    + * Name: sixlowpan_802154_framecreate
      *
      * Description:
      *   Creates a frame for transmission over the air.  This function is meant
    @@ -514,7 +514,7 @@ int sixlowpan_802154_framecreate(FAR struct frame802154_s *finfo,
     }
     
     /****************************************************************************
    - * Function: sixlowpan_framecreate
    + * Name: sixlowpan_framecreate
      *
      * Description:
      *   This function is called after eiether (1) the IEEE802.15.4 MAC driver
    diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c
    index bfa74da13a..bccd97677b 100644
    --- a/net/sixlowpan/sixlowpan_input.c
    +++ b/net/sixlowpan/sixlowpan_input.c
    @@ -680,7 +680,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee,
     }
     
     /****************************************************************************
    - * Function: sixlowpan_dispatch
    + * Name: sixlowpan_dispatch
      *
      * Description:
      *   Inject the packet in d_buf into the network for normal packet processing.
    diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h
    index 392bc376b7..a56678c27f 100644
    --- a/net/sixlowpan/sixlowpan_internal.h
    +++ b/net/sixlowpan/sixlowpan_internal.h
    @@ -344,7 +344,7 @@ int sixlowpan_send(FAR struct net_driver_s *dev,
                        uint16_t timeout);
     
     /****************************************************************************
    - * Function: sixlowpan_send_hdrlen
    + * Name: sixlowpan_send_hdrlen
      *
      * Description:
      *   This function is before the first frame has been sent in order to
    @@ -366,7 +366,7 @@ int sixlowpan_send_hdrlen(FAR struct ieee802154_driver_s *ieee,
                          uint16_t dest_panid);
     
     /****************************************************************************
    - * Function: sixlowpan_framecreate
    + * Name: sixlowpan_framecreate
      *
      * Description:
      *   This function is called after the IEEE802.15.4 MAC driver polls for
    diff --git a/net/sixlowpan/sixlowpan_send.c b/net/sixlowpan/sixlowpan_send.c
    index 1dd8f86c66..3ad68554ae 100644
    --- a/net/sixlowpan/sixlowpan_send.c
    +++ b/net/sixlowpan/sixlowpan_send.c
    @@ -93,7 +93,7 @@ struct sixlowpan_send_s
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: send_timeout
    + * Name: send_timeout
      *
      * Description:
      *   Check for send timeout.
    @@ -134,7 +134,7 @@ static inline bool send_timeout(FAR struct sixlowpan_send_s *sinfo)
     }
     
     /****************************************************************************
    - * Function: send_interrupt
    + * Name: send_interrupt
      *
      * Description:
      *   This function is called from the interrupt level to perform the actual
    diff --git a/net/sixlowpan/sixlowpan_tcpsend.c b/net/sixlowpan/sixlowpan_tcpsend.c
    index 3ee39e72ed..2bb6c49130 100644
    --- a/net/sixlowpan/sixlowpan_tcpsend.c
    +++ b/net/sixlowpan/sixlowpan_tcpsend.c
    @@ -136,7 +136,7 @@ static uint16_t sixlowpan_tcp_chksum(FAR struct ipv6tcp_hdr_s *ipv6tcp,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: psock_6lowpan_tcp_send
    + * Name: psock_6lowpan_tcp_send
      *
      * Description:
      *   psock_6lowpan_tcp_send() call may be used only when the TCP socket is in a
    @@ -348,7 +348,7 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf,
     }
     
     /****************************************************************************
    - * Function: sixlowpan_tcp_send
    + * Name: sixlowpan_tcp_send
      *
      * Description:
      *   TCP output comes through three different mechansims.  Either from:
    diff --git a/net/sixlowpan/sixlowpan_udpsend.c b/net/sixlowpan/sixlowpan_udpsend.c
    index f8f62e528b..a29197eec7 100644
    --- a/net/sixlowpan/sixlowpan_udpsend.c
    +++ b/net/sixlowpan/sixlowpan_udpsend.c
    @@ -125,7 +125,7 @@ static uint16_t sixlowpan_udp_chksum(FAR struct ipv6udp_hdr_s *ipv6udp,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: psock_6lowpan_udp_sendto
    + * Name: psock_6lowpan_udp_sendto
      *
      * Description:
      *   If sendto() is used on a connection-mode (SOCK_STREAM, SOCK_SEQPACKET)
    @@ -323,7 +323,7 @@ ssize_t psock_6lowpan_udp_sendto(FAR struct socket *psock,
     }
     
     /****************************************************************************
    - * Function: psock_6lowpan_udp_send
    + * Name: psock_6lowpan_udp_send
      *
      * Description:
      *   psock_6lowpan_udp_send() call may be used with connectionlesss UDP
    diff --git a/net/socket/accept.c b/net/socket/accept.c
    index b4db581dba..a93e490b9e 100644
    --- a/net/socket/accept.c
    +++ b/net/socket/accept.c
    @@ -61,7 +61,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: psock_accept
    + * Name: psock_accept
      *
      * Description:
      *   The psock_accept function is used with connection-based socket types
    @@ -305,7 +305,7 @@ errout:
     }
     
     /****************************************************************************
    - * Function: accept
    + * Name: accept
      *
      * Description:
      *   The accept function is used with connection-based socket types
    diff --git a/net/socket/bind.c b/net/socket/bind.c
    index 8ffc1274e8..544d1e0d53 100644
    --- a/net/socket/bind.c
    +++ b/net/socket/bind.c
    @@ -68,7 +68,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: pkt_bind
    + * Name: pkt_bind
      *
      * Description:
      *   Bind a raw socket to an network device.
    @@ -122,7 +122,7 @@ static int pkt_bind(FAR struct pkt_conn_s *conn,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: psock_bind
    + * Name: psock_bind
      *
      * Description:
      *   bind() gives the socket 'psock' the local address 'addr'. 'addr' is
    @@ -345,7 +345,7 @@ errout:
     }
     
     /****************************************************************************
    - * Function: bind
    + * Name: bind
      *
      * Description:
      *   bind() gives the socket 'sockfd' the local address 'addr'. 'addr' is
    diff --git a/net/socket/getsockname.c b/net/socket/getsockname.c
    index 703136e0d9..ba7cc76434 100644
    --- a/net/socket/getsockname.c
    +++ b/net/socket/getsockname.c
    @@ -64,7 +64,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: get_ipv4_sockname
    + * Name: get_ipv4_sockname
      *
      * Description:
      *   The getsockname() function retrieves the locally-bound name of the
    @@ -187,7 +187,7 @@ int ipv4_getsockname(FAR struct socket *psock, FAR struct sockaddr *addr,
     #endif
     
     /****************************************************************************
    - * Function: ipv6_getsockname
    + * Name: ipv6_getsockname
      *
      * Description:
      *   The getsockname() function retrieves the locally-bound name of the
    @@ -314,7 +314,7 @@ int ipv6_getsockname(FAR struct socket *psock, FAR struct sockaddr *addr,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: getsockname
    + * Name: getsockname
      *
      * Description:
      *   The getsockname() function retrieves the locally-bound name of the
    diff --git a/net/socket/getsockopt.c b/net/socket/getsockopt.c
    index ab15d511aa..00841fe511 100644
    --- a/net/socket/getsockopt.c
    +++ b/net/socket/getsockopt.c
    @@ -56,7 +56,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: psock_getsockopt
    + * Name: psock_getsockopt
      *
      * Description:
      *   getsockopt() retrieve thse value for the option specified by the
    @@ -277,7 +277,7 @@ errout:
     }
     
     /****************************************************************************
    - * Function: getsockopt
    + * Name: getsockopt
      *
      * Description:
      *   getsockopt() retrieve thse value for the option specified by the
    diff --git a/net/socket/listen.c b/net/socket/listen.c
    index 3b0189d019..b05d18aceb 100644
    --- a/net/socket/listen.c
    +++ b/net/socket/listen.c
    @@ -55,7 +55,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: psock_listen
    + * Name: psock_listen
      *
      * Description:
      *   To accept connections, a socket is first created with psock_socket(), a
    @@ -168,7 +168,7 @@ errout:
     }
     
     /****************************************************************************
    - * Function: listen
    + * Name: listen
      *
      * Description:
      *   To accept connections, a socket is first created with socket(), a
    diff --git a/net/socket/net_clone.c b/net/socket/net_clone.c
    index 83a7c5150c..a08c236329 100644
    --- a/net/socket/net_clone.c
    +++ b/net/socket/net_clone.c
    @@ -58,7 +58,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: net_clone
    + * Name: net_clone
      *
      * Description:
      *   Performs the low level, common portion of net_dupsd() and net_dupsd2()
    diff --git a/net/socket/net_close.c b/net/socket/net_close.c
    index 6bbc01b725..adb1812ad2 100644
    --- a/net/socket/net_close.c
    +++ b/net/socket/net_close.c
    @@ -91,7 +91,7 @@ struct tcp_close_s
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: close_timeout
    + * Name: close_timeout
      *
      * Description:
      *   Check for a timeout on a lingering close.
    @@ -136,7 +136,7 @@ static inline int close_timeout(FAR struct tcp_close_s *pstate)
     #endif /* NET_TCP_HAVE_STACK && CONFIG_NET_SOLINGER */
     
     /****************************************************************************
    - * Function: netclose_interrupt
    + * Name: netclose_interrupt
      *
      * Description:
      *   Handle network callback events.
    @@ -260,7 +260,7 @@ end_wait:
     #endif /* NET_TCP_HAVE_STACK */
     
     /****************************************************************************
    - * Function: netclose_txnotify
    + * Name: netclose_txnotify
      *
      * Description:
      *   Notify the appropriate device driver that we are have data ready to
    @@ -317,7 +317,7 @@ static inline void netclose_txnotify(FAR struct socket *psock,
     #endif /* NET_TCP_HAVE_STACK */
     
     /****************************************************************************
    - * Function: netclose_disconnect
    + * Name: netclose_disconnect
      *
      * Description:
      *   Break any current TCP connection
    @@ -455,7 +455,7 @@ static inline int netclose_disconnect(FAR struct socket *psock)
     #endif /* NET_TCP_HAVE_STACK */
     
     /****************************************************************************
    - * Function: local_close
    + * Name: local_close
      *
      * Description:
      *   Performs the close operation on a local socket instance
    @@ -498,7 +498,7 @@ static void local_close(FAR struct socket *psock)
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: psock_close
    + * Name: psock_close
      *
      * Description:
      *   Performs the close operation on a socket instance
    @@ -733,7 +733,7 @@ errout:
     }
     
     /****************************************************************************
    - * Function: net_close
    + * Name: net_close
      *
      * Description:
      *   Performs the close operation on socket descriptors
    diff --git a/net/socket/net_dupsd.c b/net/socket/net_dupsd.c
    index b5696871d2..3f92ac0252 100644
    --- a/net/socket/net_dupsd.c
    +++ b/net/socket/net_dupsd.c
    @@ -53,7 +53,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: net_dupsd
    + * Name: net_dupsd
      *
      * Description:
      *   Clone a socket descriptor to an arbitrary descriptor number.  If file
    diff --git a/net/socket/net_dupsd2.c b/net/socket/net_dupsd2.c
    index 7aa2634e21..4d6027667c 100644
    --- a/net/socket/net_dupsd2.c
    +++ b/net/socket/net_dupsd2.c
    @@ -53,7 +53,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: net_dupsd2
    + * Name: net_dupsd2
      *
      * Description:
      *   Clone a socket descriptor to an arbitray descriptor number.  If file
    diff --git a/net/socket/net_poll.c b/net/socket/net_poll.c
    index 0fe2b23db1..b8cbaf3e02 100644
    --- a/net/socket/net_poll.c
    +++ b/net/socket/net_poll.c
    @@ -70,7 +70,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: net_pollsetup
    + * Name: net_pollsetup
      *
      * Description:
      *   Setup to monitor events on one socket
    @@ -138,7 +138,7 @@ static inline int net_pollsetup(FAR struct socket *psock,
     }
     
     /****************************************************************************
    - * Function: net_pollteardown
    + * Name: net_pollteardown
      *
      * Description:
      *   Teardown monitoring of events on an socket
    @@ -211,7 +211,7 @@ static inline int net_pollteardown(FAR struct socket *psock,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: psock_poll
    + * Name: psock_poll
      *
      * Description:
      *   The standard poll() operation redirects operations on socket descriptors
    @@ -264,7 +264,7 @@ int psock_poll(FAR struct socket *psock, FAR struct pollfd *fds, bool setup)
     }
     
     /****************************************************************************
    - * Function: net_poll
    + * Name: net_poll
      *
      * Description:
      *   The standard poll() operation redirects operations on socket descriptors
    diff --git a/net/socket/net_sendfile.c b/net/socket/net_sendfile.c
    index 81f527abe7..8f17f8a5c2 100644
    --- a/net/socket/net_sendfile.c
    +++ b/net/socket/net_sendfile.c
    @@ -115,7 +115,7 @@ struct sendfile_s
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: sendfile_timeout
    + * Name: sendfile_timeout
      *
      * Description:
      *   Check for send timeout.
    @@ -238,7 +238,7 @@ static uint16_t ack_interrupt(FAR struct net_driver_s *dev, FAR void *pvconn,
     }
     
     /****************************************************************************
    - * Function: sendfile_addrcheck
    + * Name: sendfile_addrcheck
      *
      * Description:
      *   Check if the destination IP address is in the IPv4 ARP or IPv6 Neighbor
    @@ -301,7 +301,7 @@ static inline bool sendfile_addrcheck(FAR struct tcp_conn_s *conn)
     #endif /* CONFIG_NET_ETHERNET */
     
     /****************************************************************************
    - * Function: sendfile_interrupt
    + * Name: sendfile_interrupt
      *
      * Description:
      *   This function is called from the interrupt level to perform the actual
    @@ -478,7 +478,7 @@ wait:
     }
     
     /****************************************************************************
    - * Function: sendfile_txnotify
    + * Name: sendfile_txnotify
      *
      * Description:
      *   Notify the appropriate device driver that we are have data ready to
    @@ -537,7 +537,7 @@ static inline void sendfile_txnotify(FAR struct socket *psock,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: net_sendfile
    + * Name: net_sendfile
      *
      * Description:
      *   The send() call may be used only when the socket is in a connected state
    diff --git a/net/socket/net_timeo.c b/net/socket/net_timeo.c
    index 81b7123a31..fd3288c099 100644
    --- a/net/socket/net_timeo.c
    +++ b/net/socket/net_timeo.c
    @@ -52,7 +52,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: net_timeo
    + * Name: net_timeo
      *
      * Description:
      *   Check if a timeout has elapsed.  This can be called from a socket poll
    diff --git a/net/socket/recv.c b/net/socket/recv.c
    index 2e590c0b71..4cd62d2cf8 100644
    --- a/net/socket/recv.c
    +++ b/net/socket/recv.c
    @@ -51,7 +51,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: recv
    + * Name: recv
      *
      * Description:
      *   The recv() call is identical to recvfrom() with a NULL from parameter.
    diff --git a/net/socket/recvfrom.c b/net/socket/recvfrom.c
    index 1bc3e76c1b..4a3ad32234 100644
    --- a/net/socket/recvfrom.c
    +++ b/net/socket/recvfrom.c
    @@ -115,7 +115,7 @@ struct recvfrom_s
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: recvfrom_add_recvlen
    + * Name: recvfrom_add_recvlen
      *
      * Description:
      *   Update information about space available for new data and update size
    @@ -149,7 +149,7 @@ static inline void recvfrom_add_recvlen(FAR struct recvfrom_s *pstate,
     #endif /* NET_UDP_HAVE_STACK || NET_TCP_HAVE_STACK || CONFIG_NET_PKT */
     
     /****************************************************************************
    - * Function: recvfrom_newdata
    + * Name: recvfrom_newdata
      *
      * Description:
      *   Copy the read data from the packet
    @@ -197,7 +197,7 @@ static size_t recvfrom_newdata(FAR struct net_driver_s *dev,
     #endif /* NET_UDP_HAVE_STACK || NET_TCP_HAVE_STACK */
     
     /****************************************************************************
    - * Function: recvfrom_newpktdata
    + * Name: recvfrom_newpktdata
      *
      * Description:
      *   Copy the read data from the packet
    @@ -241,7 +241,7 @@ static void recvfrom_newpktdata(FAR struct net_driver_s *dev,
     #endif /* CONFIG_NET_PKT */
     
     /****************************************************************************
    - * Function: recvfrom_newtcpdata
    + * Name: recvfrom_newtcpdata
      *
      * Description:
      *   Copy the read data from the packet
    @@ -313,7 +313,7 @@ static inline void recvfrom_newtcpdata(FAR struct net_driver_s *dev,
     #endif /* NET_TCP_HAVE_STACK */
     
     /****************************************************************************
    - * Function: recvfrom_newudpdata
    + * Name: recvfrom_newudpdata
      *
      * Description:
      *   Copy the read data from the packet
    @@ -345,7 +345,7 @@ static inline void recvfrom_newudpdata(FAR struct net_driver_s *dev,
     #endif /* NET_UDP_HAVE_STACK */
     
     /****************************************************************************
    - * Function: recvfrom_tcpreadahead
    + * Name: recvfrom_tcpreadahead
      *
      * Description:
      *   Copy the read data from the packet
    @@ -513,7 +513,7 @@ out:
     #endif
     
     /****************************************************************************
    - * Function: recvfrom_timeout
    + * Name: recvfrom_timeout
      *
      * Description:
      *   Check for recvfrom timeout.
    @@ -587,7 +587,7 @@ static int recvfrom_timeout(struct recvfrom_s *pstate)
     #endif /* NET_UDP_HAVE_STACK || NET_TCP_HAVE_STACK */
     
     /****************************************************************************
    - * Function: recvfrom_pktsender
    + * Name: recvfrom_pktsender
      *
      * Description:
      *
    @@ -607,7 +607,7 @@ static inline void recvfrom_pktsender(FAR struct net_driver_s *dev,
     #endif /* CONFIG_NET_PKT */
     
     /****************************************************************************
    - * Function: recvfrom_pktinterrupt
    + * Name: recvfrom_pktinterrupt
      *
      * Description:
      *
    @@ -670,7 +670,7 @@ static uint16_t recvfrom_pktinterrupt(FAR struct net_driver_s *dev,
     #endif /* CONFIG_NET_PKT */
     
     /****************************************************************************
    - * Function: recvfrom_tcpsender
    + * Name: recvfrom_tcpsender
      *
      * Description:
      *   Getting the sender's address from the UDP packet
    @@ -741,7 +741,7 @@ static inline void recvfrom_tcpsender(FAR struct net_driver_s *dev,
     #endif /* NET_TCP_HAVE_STACK */
     
     /****************************************************************************
    - * Function: recvfrom_tcpinterrupt
    + * Name: recvfrom_tcpinterrupt
      *
      * Description:
      *   This function is called from the interrupt level to perform the actual
    @@ -964,7 +964,7 @@ static uint16_t recvfrom_tcpinterrupt(FAR struct net_driver_s *dev,
     #endif /* NET_TCP_HAVE_STACK */
     
     /****************************************************************************
    - * Function: recvfrom_udpsender
    + * Name: recvfrom_udpsender
      *
      * Description:
      *   Getting the sender's address from the UDP packet
    @@ -1065,7 +1065,7 @@ static inline void recvfrom_udpsender(struct net_driver_s *dev, struct recvfrom_
     #endif /* NET_UDP_HAVE_STACK */
     
     /****************************************************************************
    - * Function: recvfrom_udp_terminate
    + * Name: recvfrom_udp_terminate
      *
      * Description:
      *   Terminate the UDP transfer.
    @@ -1101,7 +1101,7 @@ static void recvfrom_udp_terminate(FAR struct recvfrom_s *pstate, int result)
     #endif /* NET_UDP_HAVE_STACK */
     
     /****************************************************************************
    - * Function: recvfrom_udp_interrupt
    + * Name: recvfrom_udp_interrupt
      *
      * Description:
      *   This function is called from the interrupt level to perform the actual
    @@ -1195,7 +1195,7 @@ static uint16_t recvfrom_udp_interrupt(FAR struct net_driver_s *dev,
     #endif /* NET_UDP_HAVE_STACK */
     
     /****************************************************************************
    - * Function: recvfrom_init
    + * Name: recvfrom_init
      *
      * Description:
      *   Initialize the state structure
    @@ -1253,7 +1253,7 @@ static void recvfrom_init(FAR struct socket *psock, FAR void *buf,
     #endif /* NET_UDP_HAVE_STACK || NET_TCP_HAVE_STACK */
     
     /****************************************************************************
    - * Function: recvfrom_result
    + * Name: recvfrom_result
      *
      * Description:
      *   Evaluate the result of the recv operations
    @@ -1302,7 +1302,7 @@ static ssize_t recvfrom_result(int result, struct recvfrom_s *pstate)
     #endif /* NET_UDP_HAVE_STACK || NET_TCP_HAVE_STACK */
     
     /****************************************************************************
    - * Function: recvfromo_pkt_rxnotify
    + * Name: recvfromo_pkt_rxnotify
      *
      * Description:
      *   Notify the appropriate device driver that we are ready to receive a
    @@ -1324,7 +1324,7 @@ static void recvfromo_pkt_rxnotify(FAR struct pkt_conn_s *conn)
     #endif
     
     /****************************************************************************
    - * Function: recvfrom_udp_rxnotify
    + * Name: recvfrom_udp_rxnotify
      *
      * Description:
      *   Notify the appropriate device driver that we are ready to receive a
    @@ -1381,7 +1381,7 @@ static inline void recvfrom_udp_rxnotify(FAR struct socket *psock,
     #endif /* NET_UDP_HAVE_STACK */
     
     /****************************************************************************
    - * Function: pkt_recvfrom
    + * Name: pkt_recvfrom
      *
      * Description:
      *   Perform the recvfrom operation for packet socket
    @@ -1475,7 +1475,7 @@ errout_with_state:
     #endif /* CONFIG_NET_PKT */
     
     /****************************************************************************
    - * Function: udp_recvfrom
    + * Name: udp_recvfrom
      *
      * Description:
      *   Perform the recvfrom operation for a UDP SOCK_DGRAM
    @@ -1615,7 +1615,7 @@ errout_with_state:
     #endif /* NET_UDP_HAVE_STACK */
     
     /****************************************************************************
    - * Function: tcp_recvfrom
    + * Name: tcp_recvfrom
      *
      * Description:
      *   Perform the recvfrom operation for a TCP/IP SOCK_STREAM
    @@ -1797,7 +1797,7 @@ static ssize_t tcp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: psock_recvfrom
    + * Name: psock_recvfrom
      *
      * Description:
      *   recvfrom() receives messages from a socket, and may be used to receive
    @@ -2057,7 +2057,7 @@ errout:
     }
     
     /****************************************************************************
    - * Function: recvfrom
    + * Name: recvfrom
      *
      * Description:
      *   recvfrom() receives messages from a socket, and may be used to receive
    diff --git a/net/socket/send.c b/net/socket/send.c
    index 340e4caa62..646fba8bf4 100644
    --- a/net/socket/send.c
    +++ b/net/socket/send.c
    @@ -58,7 +58,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: psock_send
    + * Name: psock_send
      *
      * Description:
      *   The send() call may be used only when the socket is in a connected state
    @@ -259,7 +259,7 @@ ssize_t psock_send(FAR struct socket *psock, FAR const void *buf, size_t len,
     }
     
     /****************************************************************************
    - * Function: send
    + * Name: send
      *
      * Description:
      *   The send() call may be used only when the socket is in a connected state
    diff --git a/net/socket/sendto.c b/net/socket/sendto.c
    index 4c2798cd6c..6b3490b10a 100644
    --- a/net/socket/sendto.c
    +++ b/net/socket/sendto.c
    @@ -59,7 +59,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: psock_sendto
    + * Name: psock_sendto
      *
      * Description:
      *   If sendto() is used on a connection-mode (SOCK_STREAM, SOCK_SEQPACKET)
    @@ -279,7 +279,7 @@ errout:
     }
     
     /****************************************************************************
    - * Function: sendto
    + * Name: sendto
      *
      * Description:
      *   If sendto() is used on a connection-mode (SOCK_STREAM, SOCK_SEQPACKET)
    diff --git a/net/socket/setsockopt.c b/net/socket/setsockopt.c
    index fd41045f3e..856f2ce700 100644
    --- a/net/socket/setsockopt.c
    +++ b/net/socket/setsockopt.c
    @@ -60,7 +60,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: psock_setsockopt
    + * Name: psock_setsockopt
      *
      * Description:
      *   psock_setsockopt() sets the option specified by the 'option' argument,
    @@ -315,7 +315,7 @@ errout:
     }
     
     /****************************************************************************
    - * Function: setsockopt
    + * Name: setsockopt
      *
      * Description:
      *   setsockopt() sets the option specified by the 'option' argument,
    diff --git a/net/socket/socket.c b/net/socket/socket.c
    index 04d595a831..38407462fc 100644
    --- a/net/socket/socket.c
    +++ b/net/socket/socket.c
    @@ -205,7 +205,7 @@ static int psock_local_alloc(FAR struct socket *psock)
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: psock_socket
    + * Name: psock_socket
      *
      * Description:
      *   socket() creates an endpoint for communication and returns a socket
    @@ -545,7 +545,7 @@ errout:
     }
     
     /****************************************************************************
    - * Function: socket
    + * Name: socket
      *
      * Description:
      *   socket() creates an endpoint for communication and returns a descriptor.
    diff --git a/net/socket/socket.h b/net/socket/socket.h
    index 4141cf7477..d4b0525809 100644
    --- a/net/socket/socket.h
    +++ b/net/socket/socket.h
    @@ -293,7 +293,7 @@ void net_lostconnection(FAR struct socket *psock, uint16_t flags);
     #endif
     
     /****************************************************************************
    - * Function: psock_close
    + * Name: psock_close
      *
      * Description:
      *   Performs the close operation on a socket instance
    @@ -311,7 +311,7 @@ void net_lostconnection(FAR struct socket *psock, uint16_t flags);
     int psock_close(FAR struct socket *psock);
     
     /****************************************************************************
    - * Function: net_close
    + * Name: net_close
      *
      * Description:
      *   Performs the close operation on socket descriptors
    @@ -329,7 +329,7 @@ int psock_close(FAR struct socket *psock);
     int net_close(int sockfd);
     
     /****************************************************************************
    - * Function: net_timeo
    + * Name: net_timeo
      *
      * Description:
      *   Check if a timeout has elapsed.  This can be called from a socket poll
    @@ -351,7 +351,7 @@ int net_timeo(systime_t start_time, socktimeo_t timeo);
     #endif
     
     /****************************************************************************
    - * Function: psock_send
    + * Name: psock_send
      *
      * Description:
      *   The send() call may be used only when the socket is in a connected state
    diff --git a/net/tcp/tcp.h b/net/tcp/tcp.h
    index e6c98a0847..54808a3075 100644
    --- a/net/tcp/tcp.h
    +++ b/net/tcp/tcp.h
    @@ -413,7 +413,7 @@ FAR struct tcp_conn_s *tcp_active(FAR struct net_driver_s *dev,
     FAR struct tcp_conn_s *tcp_nextconn(FAR struct tcp_conn_s *conn);
     
     /****************************************************************************
    - * Function: tcp_local_ipv4_device
    + * Name: tcp_local_ipv4_device
      *
      * Description:
      *   Select the network driver to use with the IPv4 TCP transaction based
    @@ -434,7 +434,7 @@ int tcp_local_ipv4_device(FAR struct tcp_conn_s *conn);
     #endif
     
     /****************************************************************************
    - * Function: tcp_remote_ipv4_device
    + * Name: tcp_remote_ipv4_device
      *
      * Description:
      *   Select the network driver to use with the IPv4 TCP transaction based
    @@ -455,7 +455,7 @@ int tcp_remote_ipv4_device(FAR struct tcp_conn_s *conn);
     #endif
     
     /****************************************************************************
    - * Function: tcp_local_ipv6_device
    + * Name: tcp_local_ipv6_device
      *
      * Description:
      *   Select the network driver to use with the IPv6 TCP transaction based
    @@ -476,7 +476,7 @@ int tcp_local_ipv6_device(FAR struct tcp_conn_s *conn);
     #endif
     
     /****************************************************************************
    - * Function: tcp_remote_ipv6_device
    + * Name: tcp_remote_ipv6_device
      *
      * Description:
      *   Select the network driver to use with the IPv6 TCP transaction based
    @@ -552,7 +552,7 @@ int tcp_bind(FAR struct tcp_conn_s *conn, FAR const struct sockaddr *addr);
     int tcp_connect(FAR struct tcp_conn_s *conn, FAR const struct sockaddr *addr);
     
     /****************************************************************************
    - * Function: tcp_ipv4_select
    + * Name: tcp_ipv4_select
      *
      * Description:
      *   Configure to send or receive an TCP IPv4 packet
    @@ -564,7 +564,7 @@ void tcp_ipv4_select(FAR struct net_driver_s *dev);
     #endif
     
     /****************************************************************************
    - * Function: tcp_ipv6_select
    + * Name: tcp_ipv6_select
      *
      * Description:
      *   Configure to send or receive an TCP IPv6 packet
    @@ -684,7 +684,7 @@ void tcp_timer(FAR struct net_driver_s *dev, FAR struct tcp_conn_s *conn,
                    int hsec);
     
     /****************************************************************************
    - * Function: tcp_listen_initialize
    + * Name: tcp_listen_initialize
      *
      * Description:
      *   Setup the listening data structures
    @@ -698,7 +698,7 @@ void tcp_timer(FAR struct net_driver_s *dev, FAR struct tcp_conn_s *conn,
     void tcp_listen_initialize(void);
     
     /****************************************************************************
    - * Function: tcp_unlisten
    + * Name: tcp_unlisten
      *
      * Description:
      *   Stop listening to the port bound to the specified TCP connection
    @@ -711,7 +711,7 @@ void tcp_listen_initialize(void);
     int tcp_unlisten(FAR struct tcp_conn_s *conn);
     
     /****************************************************************************
    - * Function: tcp_listen
    + * Name: tcp_listen
      *
      * Description:
      *   Start listening to the port bound to the specified TCP connection
    @@ -724,7 +724,7 @@ int tcp_unlisten(FAR struct tcp_conn_s *conn);
     int tcp_listen(FAR struct tcp_conn_s *conn);
     
     /****************************************************************************
    - * Function: tcp_islistener
    + * Name: tcp_islistener
      *
      * Description:
      *   Return true is there is a listener for the specified port
    @@ -737,7 +737,7 @@ int tcp_listen(FAR struct tcp_conn_s *conn);
     bool tcp_islistener(uint16_t portno);
     
     /****************************************************************************
    - * Function: tcp_accept_connection
    + * Name: tcp_accept_connection
      *
      * Description:
      *   Accept the new connection for the specified listening port.
    @@ -903,7 +903,7 @@ void tcp_ipv6_input(FAR struct net_driver_s *dev);
     #endif
     
     /****************************************************************************
    - * Function: tcp_callback
    + * Name: tcp_callback
      *
      * Description:
      *   Inform the application holding the TCP socket of a change in state.
    @@ -917,7 +917,7 @@ uint16_t tcp_callback(FAR struct net_driver_s *dev,
                           FAR struct tcp_conn_s *conn, uint16_t flags);
     
     /****************************************************************************
    - * Function: tcp_datahandler
    + * Name: tcp_datahandler
      *
      * Description:
      *   Handle data that is not accepted by the application.  This may be called
    @@ -948,7 +948,7 @@ uint16_t tcp_datahandler(FAR struct tcp_conn_s *conn, FAR uint8_t *buffer,
     #endif
     
     /****************************************************************************
    - * Function: tcp_backlogcreate
    + * Name: tcp_backlogcreate
      *
      * Description:
      *   Called from the listen() logic to setup the backlog as specified in the
    @@ -966,7 +966,7 @@ int tcp_backlogcreate(FAR struct tcp_conn_s *conn, int nblg);
     #endif
     
     /****************************************************************************
    - * Function: tcp_backlogdestroy
    + * Name: tcp_backlogdestroy
      *
      * Description:
      *   (1) Called from tcp_free() whenever a connection is freed.
    @@ -987,7 +987,7 @@ int tcp_backlogdestroy(FAR struct tcp_conn_s *conn);
     #endif
     
     /****************************************************************************
    - * Function: tcp_backlogadd
    + * Name: tcp_backlogadd
      *
      * Description:
      *  Called tcp_listen when a new connection is made with a listener socket
    @@ -1007,7 +1007,7 @@ int tcp_backlogadd(FAR struct tcp_conn_s *conn,
     #endif
     
     /****************************************************************************
    - * Function: tcp_backlogavailable
    + * Name: tcp_backlogavailable
      *
      * Description:
      *  Called from poll().  Before waiting for a new connection, poll will
    @@ -1025,7 +1025,7 @@ bool tcp_backlogavailable(FAR struct tcp_conn_s *conn);
     #endif
     
     /****************************************************************************
    - * Function: tcp_backlogremove
    + * Name: tcp_backlogremove
      *
      * Description:
      *  Called from accept().  Before waiting for a new connection, accept will
    @@ -1043,7 +1043,7 @@ FAR struct tcp_conn_s *tcp_backlogremove(FAR struct tcp_conn_s *conn);
     #endif
     
     /****************************************************************************
    - * Function: tcp_backlogdelete
    + * Name: tcp_backlogdelete
      *
      * Description:
      *  Called from tcp_free() when a connection is freed that this also
    @@ -1063,7 +1063,7 @@ int tcp_backlogdelete(FAR struct tcp_conn_s *conn,
     #endif
     
     /****************************************************************************
    - * Function: tcp_accept
    + * Name: tcp_accept
      *
      * Description:
      *   This function implements accept() for TCP/IP sockets.  See the
    @@ -1089,7 +1089,7 @@ int psock_tcp_accept(FAR struct socket *psock, FAR struct sockaddr *addr,
                          FAR socklen_t *addrlen, FAR void **newconn);
     
     /****************************************************************************
    - * Function: psock_tcp_send
    + * Name: psock_tcp_send
      *
      * Description:
      *   The psock_tcp_send() call may be used only when the TCP socket is in a
    @@ -1150,7 +1150,7 @@ ssize_t psock_tcp_send(FAR struct socket *psock, FAR const void *buf,
                            size_t len);
     
     /****************************************************************************
    - * Function: psock_tcp_cansend
    + * Name: psock_tcp_cansend
      *
      * Description:
      *   psock_tcp_cansend() returns a value indicating if a write to the socket
    @@ -1179,7 +1179,7 @@ ssize_t psock_tcp_send(FAR struct socket *psock, FAR const void *buf,
     int psock_tcp_cansend(FAR struct socket *psock);
     
     /****************************************************************************
    - * Function: tcp_wrbuffer_initialize
    + * Name: tcp_wrbuffer_initialize
      *
      * Description:
      *   Initialize the list of free write buffers
    @@ -1194,7 +1194,7 @@ void tcp_wrbuffer_initialize(void);
     #endif /* CONFIG_NET_TCP_WRITE_BUFFERS */
     
     /****************************************************************************
    - * Function: tcp_wrbuffer_alloc
    + * Name: tcp_wrbuffer_alloc
      *
      * Description:
      *   Allocate a TCP write buffer by taking a pre-allocated buffer from
    @@ -1216,7 +1216,7 @@ FAR struct tcp_wrbuffer_s *tcp_wrbuffer_alloc(void);
     #endif /* CONFIG_NET_TCP_WRITE_BUFFERS */
     
     /****************************************************************************
    - * Function: tcp_wrbuffer_release
    + * Name: tcp_wrbuffer_release
      *
      * Description:
      *   Release a TCP write buffer by returning the buffer to the free list.
    @@ -1233,7 +1233,7 @@ void tcp_wrbuffer_release(FAR struct tcp_wrbuffer_s *wrb);
     #endif /* CONFIG_NET_TCP_WRITE_BUFFERS */
     
     /****************************************************************************
    - * Function: tcp_wrbuffer_test
    + * Name: tcp_wrbuffer_test
      *
      * Description:
      *   Check if there is room in the write buffer.  Does not reserve any space.
    @@ -1248,7 +1248,7 @@ int tcp_wrbuffer_test(void);
     #endif /* CONFIG_NET_TCP_WRITE_BUFFERS */
     
     /****************************************************************************
    - * Function: tcp_wrbuffer_dump
    + * Name: tcp_wrbuffer_dump
      *
      * Description:
      *   Dump the contents of a write buffer.
    @@ -1265,7 +1265,7 @@ void tcp_wrbuffer_dump(FAR const char *msg, FAR struct tcp_wrbuffer_s *wrb,
     #endif /* CONFIG_NET_TCP_WRITE_BUFFERS */
     
     /****************************************************************************
    - * Function: tcp_pollsetup
    + * Name: tcp_pollsetup
      *
      * Description:
      *   Setup to monitor events on one TCP/IP socket
    @@ -1285,7 +1285,7 @@ int tcp_pollsetup(FAR struct socket *psock, FAR struct pollfd *fds);
     #endif
     
     /****************************************************************************
    - * Function: tcp_pollteardown
    + * Name: tcp_pollteardown
      *
      * Description:
      *   Teardown monitoring of events on an TCP/IP socket
    diff --git a/net/tcp/tcp_accept.c b/net/tcp/tcp_accept.c
    index 95d8bfbf40..ce186cd386 100644
    --- a/net/tcp/tcp_accept.c
    +++ b/net/tcp/tcp_accept.c
    @@ -74,7 +74,7 @@ struct accept_s
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: accept_tcpsender
    + * Name: accept_tcpsender
      *
      * Description:
      *   Get the sender's address from the UDP packet
    @@ -145,7 +145,7 @@ static inline void accept_tcpsender(FAR struct socket *psock,
     #endif /* CONFIG_NET_TCP */
     
     /****************************************************************************
    - * Function: accept_interrupt
    + * Name: accept_interrupt
      *
      * Description:
      *   Receive interrupt level callbacks when connections occur
    @@ -203,7 +203,7 @@ static int accept_interrupt(FAR struct tcp_conn_s *listener,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: tcp_accept
    + * Name: tcp_accept
      *
      * Description:
      *   This function implements accept() for TCP/IP sockets.  See the
    diff --git a/net/tcp/tcp_backlog.c b/net/tcp/tcp_backlog.c
    index 252f04a0f8..516596ee30 100644
    --- a/net/tcp/tcp_backlog.c
    +++ b/net/tcp/tcp_backlog.c
    @@ -57,7 +57,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: tcp_backlogcreate
    + * Name: tcp_backlogcreate
      *
      * Description:
      *   Called from the listen() logic to setup the backlog as specified in the
    @@ -139,7 +139,7 @@ int tcp_backlogcreate(FAR struct tcp_conn_s *conn, int nblg)
     }
     
     /****************************************************************************
    - * Function: tcp_backlogdestroy
    + * Name: tcp_backlogdestroy
      *
      * Description:
      *   (1) Called from tcp_free() whenever a connection is freed.
    @@ -203,7 +203,7 @@ int tcp_backlogdestroy(FAR struct tcp_conn_s *conn)
     }
     
     /****************************************************************************
    - * Function: tcp_backlogadd
    + * Name: tcp_backlogadd
      *
      * Description:
      *  Called tcp_listen when a new connection is made with a listener socket
    @@ -257,7 +257,7 @@ int tcp_backlogadd(FAR struct tcp_conn_s *conn, FAR struct tcp_conn_s *blconn)
     }
     
     /****************************************************************************
    - * Function: tcp_backlogremove
    + * Name: tcp_backlogremove
      *
      * Description:
      *  Called from poll().  Before waiting for a new connection, poll will
    @@ -276,7 +276,7 @@ bool tcp_backlogavailable(FAR struct tcp_conn_s *conn)
     #endif
     
     /****************************************************************************
    - * Function: tcp_backlogremove
    + * Name: tcp_backlogremove
      *
      * Description:
      *  Called from accept().  Before waiting for a new connection, accept will
    @@ -325,7 +325,7 @@ FAR struct tcp_conn_s *tcp_backlogremove(FAR struct tcp_conn_s *conn)
     }
     
     /****************************************************************************
    - * Function: tcp_backlogdelete
    + * Name: tcp_backlogdelete
      *
      * Description:
      *  Called from tcp_free() when a connection is freed that this also
    diff --git a/net/tcp/tcp_callback.c b/net/tcp/tcp_callback.c
    index 0feb41e68a..5c467bae29 100644
    --- a/net/tcp/tcp_callback.c
    +++ b/net/tcp/tcp_callback.c
    @@ -58,7 +58,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: tcp_data_event
    + * Name: tcp_data_event
      *
      * Description:
      *   Handle data that is not accepted by the application because there is no
    @@ -133,7 +133,7 @@ tcp_data_event(FAR struct net_driver_s *dev, FAR struct tcp_conn_s *conn,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: tcp_callback
    + * Name: tcp_callback
      *
      * Description:
      *   Inform the application holding the TCP socket of a change in state.
    @@ -205,7 +205,7 @@ uint16_t tcp_callback(FAR struct net_driver_s *dev,
     }
     
     /****************************************************************************
    - * Function: tcp_datahandler
    + * Name: tcp_datahandler
      *
      * Description:
      *   Handle data that is not accepted by the application.  This may be called
    diff --git a/net/tcp/tcp_finddev.c b/net/tcp/tcp_finddev.c
    index e3cf0b3288..54caf9600e 100644
    --- a/net/tcp/tcp_finddev.c
    +++ b/net/tcp/tcp_finddev.c
    @@ -54,7 +54,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: tcp_find_ipv4_device
    + * Name: tcp_find_ipv4_device
      *
      * Description:
      *   Select the network driver to use with the IPv4 TCP connection.
    @@ -112,7 +112,7 @@ static int tcp_find_ipv4_device(FAR struct tcp_conn_s *conn, in_addr_t addr)
     #endif /* CONFIG_NET_IPv4 */
     
     /****************************************************************************
    - * Function: tcp_find_ipv6_device
    + * Name: tcp_find_ipv6_device
      *
      * Description:
      *   Select the network driver to use with the IPv6 TCP transaction.
    @@ -175,7 +175,7 @@ static int tcp_find_ipv6_device(FAR struct tcp_conn_s *conn,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: tcp_local_ipv4_device
    + * Name: tcp_local_ipv4_device
      *
      * Description:
      *   Select the network driver to use with the IPv4 TCP transaction based
    @@ -203,7 +203,7 @@ int tcp_local_ipv4_device(FAR struct tcp_conn_s *conn)
     #endif /* CONFIG_NET_IPv4 */
     
     /****************************************************************************
    - * Function: tcp_remote_ipv4_device
    + * Name: tcp_remote_ipv4_device
      *
      * Description:
      *   Select the network driver to use with the IPv4 TCP transaction based
    @@ -227,7 +227,7 @@ int tcp_remote_ipv4_device(FAR struct tcp_conn_s *conn)
     #endif
     
     /****************************************************************************
    - * Function: tcp_local_ipv6_device
    + * Name: tcp_local_ipv6_device
      *
      * Description:
      *   Select the network driver to use with the IPv6 TCP transaction.
    @@ -254,7 +254,7 @@ int tcp_local_ipv6_device(FAR struct tcp_conn_s *conn)
     #endif /* CONFIG_NET_IPv6 */
     
     /****************************************************************************
    - * Function: tcp_remote_ipv6_device
    + * Name: tcp_remote_ipv6_device
      *
      * Description:
      *   Select the network driver to use with the IPv6 TCP transaction based
    diff --git a/net/tcp/tcp_ipselect.c b/net/tcp/tcp_ipselect.c
    index a2570c34b0..dc726c01cb 100644
    --- a/net/tcp/tcp_ipselect.c
    +++ b/net/tcp/tcp_ipselect.c
    @@ -54,7 +54,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: tcp_ipv4_select
    + * Name: tcp_ipv4_select
      *
      * Description:
      *   Configure to send or receive an TCP IPv4 packet
    @@ -75,7 +75,7 @@ void tcp_ipv4_select(FAR struct net_driver_s *dev)
     #endif /* CONFIG_NET_IPv4 */
     
     /****************************************************************************
    - * Function: tcp_ipv6_select
    + * Name: tcp_ipv6_select
      *
      * Description:
      *   Configure to send or receive an TCP IPv6 packet
    diff --git a/net/tcp/tcp_listen.c b/net/tcp/tcp_listen.c
    index 8a10fd9b57..f7d771d2b6 100644
    --- a/net/tcp/tcp_listen.c
    +++ b/net/tcp/tcp_listen.c
    @@ -67,7 +67,7 @@ static FAR struct tcp_conn_s *tcp_listenports[CONFIG_NET_MAX_LISTENPORTS];
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: tcp_findlistener
    + * Name: tcp_findlistener
      *
      * Description:
      *   Return the connection listener for connections on this port (if any)
    @@ -108,7 +108,7 @@ FAR struct tcp_conn_s *tcp_findlistener(uint16_t portno)
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: tcp_listen_initialize
    + * Name: tcp_listen_initialize
      *
      * Description:
      *   Setup the listening data structures
    @@ -129,7 +129,7 @@ void tcp_listen_initialize(void)
     }
     
     /****************************************************************************
    - * Function: tcp_unlisten
    + * Name: tcp_unlisten
      *
      * Description:
      *   Stop listening to the port bound to the specified TCP connection
    @@ -160,7 +160,7 @@ int tcp_unlisten(FAR struct tcp_conn_s *conn)
     }
     
     /****************************************************************************
    - * Function: tcp_listen
    + * Name: tcp_listen
      *
      * Description:
      *   Start listening to the port bound to the specified TCP connection
    @@ -219,7 +219,7 @@ int tcp_listen(FAR struct tcp_conn_s *conn)
     }
     
     /****************************************************************************
    - * Function: tcp_islistener
    + * Name: tcp_islistener
      *
      * Description:
      *   Return true is there is a listener for the specified port
    @@ -235,7 +235,7 @@ bool tcp_islistener(uint16_t portno)
     }
     
     /****************************************************************************
    - * Function: tcp_accept_connection
    + * Name: tcp_accept_connection
      *
      * Description:
      *   Accept the new connection for the specified listening port.
    diff --git a/net/tcp/tcp_netpoll.c b/net/tcp/tcp_netpoll.c
    index 733c8c89e8..f099a57c66 100644
    --- a/net/tcp/tcp_netpoll.c
    +++ b/net/tcp/tcp_netpoll.c
    @@ -69,7 +69,7 @@ struct tcp_poll_s
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: tcp_poll_interrupt
    + * Name: tcp_poll_interrupt
      *
      * Description:
      *   This function is called from the interrupt level to perform the actual
    @@ -144,7 +144,7 @@ static uint16_t tcp_poll_interrupt(FAR struct net_driver_s *dev, FAR void *conn,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: tcp_pollsetup
    + * Name: tcp_pollsetup
      *
      * Description:
      *   Setup to monitor events on one TCP/IP socket
    @@ -305,7 +305,7 @@ errout_with_lock:
     }
     
     /****************************************************************************
    - * Function: tcp_pollteardown
    + * Name: tcp_pollteardown
      *
      * Description:
      *   Teardown monitoring of events on an TCP/IP socket
    diff --git a/net/tcp/tcp_send_buffered.c b/net/tcp/tcp_send_buffered.c
    index 52a21d72e9..4000d694df 100644
    --- a/net/tcp/tcp_send_buffered.c
    +++ b/net/tcp/tcp_send_buffered.c
    @@ -106,7 +106,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: psock_insert_segment
    + * Name: psock_insert_segment
      *
      * Description:
      *   Insert a new segment in a write buffer queue, keep the segment queue in
    @@ -155,7 +155,7 @@ static void psock_insert_segment(FAR struct tcp_wrbuffer_s *wrb,
     }
     
     /****************************************************************************
    - * Function: psock_lost_connection
    + * Name: psock_lost_connection
      *
      * Description:
      *   The TCP connection has been lost.  Free all write buffers.
    @@ -206,7 +206,7 @@ static inline void psock_lost_connection(FAR struct socket *psock,
     }
     
     /****************************************************************************
    - * Function: send_ipselect
    + * Name: send_ipselect
      *
      * Description:
      *   If both IPv4 and IPv6 support are enabled, then we will need to select
    @@ -249,7 +249,7 @@ static inline void send_ipselect(FAR struct net_driver_s *dev,
     #endif
     
     /****************************************************************************
    - * Function: psock_send_addrchck
    + * Name: psock_send_addrchck
      *
      * Description:
      *   Check if the destination IP address is in the IPv4 ARP or IPv6 Neighbor
    @@ -312,7 +312,7 @@ static inline bool psock_send_addrchck(FAR struct tcp_conn_s *conn)
     #endif /* CONFIG_NET_ETHERNET */
     
     /****************************************************************************
    - * Function: psock_send_interrupt
    + * Name: psock_send_interrupt
      *
      * Description:
      *   This function is called from the interrupt level to perform the actual
    @@ -828,7 +828,7 @@ static uint16_t psock_send_interrupt(FAR struct net_driver_s *dev,
     }
     
     /****************************************************************************
    - * Function: send_txnotify
    + * Name: send_txnotify
      *
      * Description:
      *   Notify the appropriate device driver that we are have data ready to
    @@ -887,7 +887,7 @@ static inline void send_txnotify(FAR struct socket *psock,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: psock_tcp_send
    + * Name: psock_tcp_send
      *
      * Description:
      *   psock_tcp_send() call may be used only when the TCP socket is in a
    @@ -1119,7 +1119,7 @@ errout:
     }
     
     /****************************************************************************
    - * Function: psock_tcp_cansend
    + * Name: psock_tcp_cansend
      *
      * Description:
      *   psock_tcp_cansend() returns a value indicating if a write to the socket
    diff --git a/net/tcp/tcp_send_unbuffered.c b/net/tcp/tcp_send_unbuffered.c
    index 5a2ccc98c4..9571819952 100644
    --- a/net/tcp/tcp_send_unbuffered.c
    +++ b/net/tcp/tcp_send_unbuffered.c
    @@ -117,7 +117,7 @@ struct send_s
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: send_timeout
    + * Name: send_timeout
      *
      * Description:
      *   Check for send timeout.
    @@ -157,7 +157,7 @@ static inline int send_timeout(FAR struct send_s *pstate)
     #endif /* CONFIG_NET_SOCKOPTS */
     
     /****************************************************************************
    - * Function: tcpsend_ipselect
    + * Name: tcpsend_ipselect
      *
      * Description:
      *   If both IPv4 and IPv6 support are enabled, then we will need to select
    @@ -200,7 +200,7 @@ static inline void tcpsend_ipselect(FAR struct net_driver_s *dev,
     #endif
     
     /****************************************************************************
    - * Function: psock_send_addrchck
    + * Name: psock_send_addrchck
      *
      * Description:
      *   Check if the destination IP address is in the IPv4 ARP or IPv6 Neighbor
    @@ -263,7 +263,7 @@ static inline bool psock_send_addrchck(FAR struct tcp_conn_s *conn)
     #endif /* CONFIG_NET_ETHERNET */
     
     /****************************************************************************
    - * Function: tcpsend_interrupt
    + * Name: tcpsend_interrupt
      *
      * Description:
      *   This function is called from the interrupt level to perform the actual
    @@ -597,7 +597,7 @@ end_wait:
     }
     
     /****************************************************************************
    - * Function: send_txnotify
    + * Name: send_txnotify
      *
      * Description:
      *   Notify the appropriate device driver that we are have data ready to
    @@ -656,7 +656,7 @@ static inline void send_txnotify(FAR struct socket *psock,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: psock_tcp_send
    + * Name: psock_tcp_send
      *
      * Description:
      *   psock_tcp_send() call may be used only when the TCP socket is in a
    @@ -884,7 +884,7 @@ errout:
     }
     
     /****************************************************************************
    - * Function: psock_tcp_cansend
    + * Name: psock_tcp_cansend
      *
      * Description:
      *   psock_tcp_cansend() returns a value indicating if a write to the socket
    diff --git a/net/tcp/tcp_wrbuffer.c b/net/tcp/tcp_wrbuffer.c
    index 7662df8bbc..a74ee6f3a1 100644
    --- a/net/tcp/tcp_wrbuffer.c
    +++ b/net/tcp/tcp_wrbuffer.c
    @@ -93,7 +93,7 @@ static struct wrbuffer_s g_wrbuffer;
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: tcp_wrbuffer_initialize
    + * Name: tcp_wrbuffer_initialize
      *
      * Description:
      *   Initialize the list of free write buffers
    @@ -118,7 +118,7 @@ void tcp_wrbuffer_initialize(void)
     }
     
     /****************************************************************************
    - * Function: tcp_wrbuffer_alloc
    + * Name: tcp_wrbuffer_alloc
      *
      * Description:
      *   Allocate a TCP write buffer by taking a pre-allocated buffer from
    @@ -169,7 +169,7 @@ FAR struct tcp_wrbuffer_s *tcp_wrbuffer_alloc(void)
     }
     
     /****************************************************************************
    - * Function: tcp_wrbuffer_release
    + * Name: tcp_wrbuffer_release
      *
      * Description:
      *   Release a TCP write buffer by returning the buffer to the free list.
    @@ -198,7 +198,7 @@ void tcp_wrbuffer_release(FAR struct tcp_wrbuffer_s *wrb)
     }
     
     /****************************************************************************
    - * Function: tcp_wrbuffer_test
    + * Name: tcp_wrbuffer_test
      *
      * Description:
      *   Check if there is room in the write buffer.  Does not reserve any space.
    diff --git a/net/udp/udp.h b/net/udp/udp.h
    index c020853109..73ac15fbaf 100644
    --- a/net/udp/udp.h
    +++ b/net/udp/udp.h
    @@ -228,7 +228,7 @@ int udp_bind(FAR struct udp_conn_s *conn, FAR const struct sockaddr *addr);
     int udp_connect(FAR struct udp_conn_s *conn, FAR const struct sockaddr *addr);
     
     /****************************************************************************
    - * Function: udp_ipv4_select
    + * Name: udp_ipv4_select
      *
      * Description:
      *   Configure to send or receive an UDP IPv4 packet
    @@ -240,7 +240,7 @@ void udp_ipv4_select(FAR struct net_driver_s *dev);
     #endif
     
     /****************************************************************************
    - * Function: udp_ipv6_select
    + * Name: udp_ipv6_select
      *
      * Description:
      *   Configure to send or receive an UDP IPv6 packet
    @@ -338,7 +338,7 @@ int udp_ipv6_input(FAR struct net_driver_s *dev);
     #endif
     
     /****************************************************************************
    - * Function: udp_find_ipv4_device
    + * Name: udp_find_ipv4_device
      *
      * Description:
      *   Select the network driver to use with the IPv4 UDP transaction.
    @@ -358,7 +358,7 @@ FAR struct net_driver_s *udp_find_ipv4_device(FAR struct udp_conn_s *conn,
     #endif
     
     /****************************************************************************
    - * Function: udp_find_ipv6_device
    + * Name: udp_find_ipv6_device
      *
      * Description:
      *   Select the network driver to use with the IPv6 UDP transaction.
    @@ -378,7 +378,7 @@ FAR struct net_driver_s *udp_find_ipv6_device(FAR struct udp_conn_s *conn,
     #endif
     
     /****************************************************************************
    - * Function: udp_find_laddr_device
    + * Name: udp_find_laddr_device
      *
      * Description:
      *   Select the network driver to use with the UDP transaction using the
    @@ -395,7 +395,7 @@ FAR struct net_driver_s *udp_find_ipv6_device(FAR struct udp_conn_s *conn,
     FAR struct net_driver_s *udp_find_laddr_device(FAR struct udp_conn_s *conn);
     
     /****************************************************************************
    - * Function: udp_find_raddr_device
    + * Name: udp_find_raddr_device
      *
      * Description:
      *   Select the network driver to use with the UDP transaction using the
    @@ -412,7 +412,7 @@ FAR struct net_driver_s *udp_find_laddr_device(FAR struct udp_conn_s *conn);
     FAR struct net_driver_s *udp_find_raddr_device(FAR struct udp_conn_s *conn);
     
     /****************************************************************************
    - * Function: udp_callback
    + * Name: udp_callback
      *
      * Description:
      *   Inform the application holding the UDP socket of a change in state.
    @@ -429,7 +429,7 @@ uint16_t udp_callback(FAR struct net_driver_s *dev,
                           FAR struct udp_conn_s *conn, uint16_t flags);
     
     /****************************************************************************
    - * Function: psock_udp_send
    + * Name: psock_udp_send
      *
      * Description:
      *   Implements send() for connected UDP sockets
    @@ -440,7 +440,7 @@ ssize_t psock_udp_send(FAR struct socket *psock, FAR const void *buf,
                            size_t len);
     
     /****************************************************************************
    - * Function: psock_udp_sendto
    + * Name: psock_udp_sendto
      *
      * Description:
      *   This function implements the UDP-specific logic of the standard
    @@ -469,7 +469,7 @@ ssize_t psock_udp_sendto(FAR struct socket *psock, FAR const void *buf,
                              socklen_t tolen);
     
     /****************************************************************************
    - * Function: udp_pollsetup
    + * Name: udp_pollsetup
      *
      * Description:
      *   Setup to monitor events on one UDP/IP socket
    @@ -489,7 +489,7 @@ int udp_pollsetup(FAR struct socket *psock, FAR struct pollfd *fds);
     #endif
     
     /****************************************************************************
    - * Function: udp_pollteardown
    + * Name: udp_pollteardown
      *
      * Description:
      *   Teardown monitoring of events on an UDP/IP socket
    diff --git a/net/udp/udp_callback.c b/net/udp/udp_callback.c
    index 52caaea543..6a763f79bc 100644
    --- a/net/udp/udp_callback.c
    +++ b/net/udp/udp_callback.c
    @@ -67,7 +67,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: udp_datahandler
    + * Name: udp_datahandler
      *
      * Description:
      *   Handle the receipt of UDP data by adding the newly received packet to
    @@ -230,7 +230,7 @@ static uint16_t udp_datahandler(FAR struct net_driver_s *dev, FAR struct udp_con
     #endif /* CONFIG_NET_UDP_READAHEAD */
     
     /****************************************************************************
    - * Function: net_dataevent
    + * Name: net_dataevent
      *
      * Description:
      *   Handling the network UDP_NEWDATA event.
    @@ -287,7 +287,7 @@ net_dataevent(FAR struct net_driver_s *dev, FAR struct udp_conn_s *conn,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: udp_callback
    + * Name: udp_callback
      *
      * Description:
      *   Inform the application holding the UDP socket of a change in state.
    diff --git a/net/udp/udp_finddev.c b/net/udp/udp_finddev.c
    index c943ab3796..96262dfb6c 100644
    --- a/net/udp/udp_finddev.c
    +++ b/net/udp/udp_finddev.c
    @@ -53,7 +53,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: udp_find_ipv4_device
    + * Name: udp_find_ipv4_device
      *
      * Description:
      *   Select the network driver to use with the IPv4 UDP transaction.
    @@ -102,7 +102,7 @@ FAR struct net_driver_s *udp_find_ipv4_device(FAR struct udp_conn_s *conn,
     #endif /* CONFIG_NET_IPv4 */
     
     /****************************************************************************
    - * Function: udp_find_ipv6_device
    + * Name: udp_find_ipv6_device
      *
      * Description:
      *   Select the network driver to use with the IPv6 UDP transaction.
    @@ -151,7 +151,7 @@ FAR struct net_driver_s *udp_find_ipv6_device(FAR struct udp_conn_s *conn,
     #endif /* CONFIG_NET_IPv6 */
     
     /****************************************************************************
    - * Function: udp_find_laddr_device
    + * Name: udp_find_laddr_device
      *
      * Description:
      *   Select the network driver to use with the UDP transaction using the
    @@ -200,7 +200,7 @@ FAR struct net_driver_s *udp_find_laddr_device(FAR struct udp_conn_s *conn)
     }
     
     /****************************************************************************
    - * Function: udp_find_raddr_device
    + * Name: udp_find_raddr_device
      *
      * Description:
      *   Select the network driver to use with the UDP transaction using the
    diff --git a/net/udp/udp_ipselect.c b/net/udp/udp_ipselect.c
    index 286e796102..bb5a91bcb2 100644
    --- a/net/udp/udp_ipselect.c
    +++ b/net/udp/udp_ipselect.c
    @@ -55,7 +55,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: udp_ipv4_select
    + * Name: udp_ipv4_select
      *
      * Description:
      *   Configure to send or receive an UDP IPv4 packet
    @@ -76,7 +76,7 @@ void udp_ipv4_select(FAR struct net_driver_s *dev)
     #endif /* CONFIG_NET_IPv4 */
     
     /****************************************************************************
    - * Function: udp_ipv6_select
    + * Name: udp_ipv6_select
      *
      * Description:
      *   Configure to send or receive an UDP IPv6 packet
    diff --git a/net/udp/udp_netpoll.c b/net/udp/udp_netpoll.c
    index 6dd873aaec..7bc31ced64 100644
    --- a/net/udp/udp_netpoll.c
    +++ b/net/udp/udp_netpoll.c
    @@ -69,7 +69,7 @@ struct udp_poll_s
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: udp_poll_interrupt
    + * Name: udp_poll_interrupt
      *
      * Description:
      *   This function is called from the interrupt level to perform the actual
    @@ -141,7 +141,7 @@ static uint16_t udp_poll_interrupt(FAR struct net_driver_s *dev, FAR void *conn,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: udp_pollsetup
    + * Name: udp_pollsetup
      *
      * Description:
      *   Setup to monitor events on one UDP/IP socket
    @@ -271,7 +271,7 @@ errout_with_lock:
     }
     
     /****************************************************************************
    - * Function: udp_pollteardown
    + * Name: udp_pollteardown
      *
      * Description:
      *   Teardown monitoring of events on an UDP/IP socket
    diff --git a/net/udp/udp_psock_send.c b/net/udp/udp_psock_send.c
    index c701fe064d..4c5ee0cf85 100644
    --- a/net/udp/udp_psock_send.c
    +++ b/net/udp/udp_psock_send.c
    @@ -54,7 +54,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: psock_udp_send
    + * Name: psock_udp_send
      *
      * Description:
      *   Implements send() for connected UDP sockets
    diff --git a/net/udp/udp_psock_sendto.c b/net/udp/udp_psock_sendto.c
    index 84564f8a7e..a7b7a9d032 100644
    --- a/net/udp/udp_psock_sendto.c
    +++ b/net/udp/udp_psock_sendto.c
    @@ -114,7 +114,7 @@ struct sendto_s
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: send_timeout
    + * Name: send_timeout
      *
      * Description:
      *   Check for send timeout.
    @@ -154,7 +154,7 @@ static inline int send_timeout(FAR struct sendto_s *pstate)
     #endif /* CONFIG_NET_SENDTO_TIMEOUT */
     
     /****************************************************************************
    - * Function: sendto_ipselect
    + * Name: sendto_ipselect
      *
      * Description:
      *   If both IPv4 and IPv6 support are enabled, then we will need to select
    @@ -200,7 +200,7 @@ static inline void sendto_ipselect(FAR struct net_driver_s *dev,
     #endif
     
     /****************************************************************************
    - * Function: sendto_interrupt
    + * Name: sendto_interrupt
      *
      * Description:
      *   This function is called from the interrupt level to perform the actual
    @@ -309,7 +309,7 @@ static uint16_t sendto_interrupt(FAR struct net_driver_s *dev, FAR void *conn,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: psock_udp_sendto
    + * Name: psock_udp_sendto
      *
      * Description:
      *   This function implements the UDP-specific logic of the standard
    diff --git a/net/usrsock/usrsock_close.c b/net/usrsock/usrsock_close.c
    index bb6f052732..8933892811 100644
    --- a/net/usrsock/usrsock_close.c
    +++ b/net/usrsock/usrsock_close.c
    @@ -127,7 +127,7 @@ static int do_close_request(FAR struct usrsock_conn_s *conn)
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: usrsock_close
    + * Name: usrsock_close
      *
      * Description:
      *
    diff --git a/net/usrsock/usrsock_event.c b/net/usrsock/usrsock_event.c
    index d16fb04fc9..87ca8598c2 100644
    --- a/net/usrsock/usrsock_event.c
    +++ b/net/usrsock/usrsock_event.c
    @@ -61,7 +61,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: usrsock_event
    + * Name: usrsock_event
      *
      * Description:
      *   Handler for received connection events
    diff --git a/net/usrsock/usrsock_getsockname.c b/net/usrsock/usrsock_getsockname.c
    index 5049ab8d21..085f28ed65 100644
    --- a/net/usrsock/usrsock_getsockname.c
    +++ b/net/usrsock/usrsock_getsockname.c
    @@ -168,7 +168,7 @@ static void setup_conn_getsockname(FAR struct usrsock_conn_s *conn,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: usrsock_getsockname
    + * Name: usrsock_getsockname
      *
      * Description:
      *   The getsockname() function retrieves the locally-bound name of the
    diff --git a/net/usrsock/usrsock_getsockopt.c b/net/usrsock/usrsock_getsockopt.c
    index f4a8ccb0d4..a3ca0a1594 100644
    --- a/net/usrsock/usrsock_getsockopt.c
    +++ b/net/usrsock/usrsock_getsockopt.c
    @@ -177,7 +177,7 @@ static void setup_conn_getsockopt(FAR struct usrsock_conn_s *conn,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: usrsock_getsockopt
    + * Name: usrsock_getsockopt
      *
      * Description:
      *   getsockopt() retrieve thse value for the option specified by the
    diff --git a/net/usrsock/usrsock_poll.c b/net/usrsock/usrsock_poll.c
    index 41860f4d7f..4af267766b 100644
    --- a/net/usrsock/usrsock_poll.c
    +++ b/net/usrsock/usrsock_poll.c
    @@ -152,7 +152,7 @@ static uint16_t poll_event(FAR struct net_driver_s *dev, FAR void *pvconn,
     }
     
     /****************************************************************************
    - * Function: usrsock_poll
    + * Name: usrsock_poll
      *
      * Description:
      *   Setup to monitor events on an usrsock socket
    @@ -299,7 +299,7 @@ errout_unlock:
     }
     
     /****************************************************************************
    - * Function: usrsock_pollteardown
    + * Name: usrsock_pollteardown
      *
      * Description:
      *   Teardown monitoring of events on an usrsock socket
    @@ -357,7 +357,7 @@ static int usrsock_pollteardown(FAR struct socket *psock,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: usrsock_poll
    + * Name: usrsock_poll
      *
      * Description:
      *   The standard poll() operation redirects operations on socket descriptors
    diff --git a/net/usrsock/usrsock_recvfrom.c b/net/usrsock/usrsock_recvfrom.c
    index d97cba5c3a..271210d88a 100644
    --- a/net/usrsock/usrsock_recvfrom.c
    +++ b/net/usrsock/usrsock_recvfrom.c
    @@ -214,7 +214,7 @@ static void setup_conn_recvfrom(FAR struct usrsock_conn_s *conn,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: usrsock_recvfrom
    + * Name: usrsock_recvfrom
      *
      * Description:
      *   recvfrom() receives messages from a socket, and may be used to receive
    diff --git a/net/usrsock/usrsock_sendto.c b/net/usrsock/usrsock_sendto.c
    index dc747d451c..9e27eb6a8f 100644
    --- a/net/usrsock/usrsock_sendto.c
    +++ b/net/usrsock/usrsock_sendto.c
    @@ -189,7 +189,7 @@ static int do_sendto_request(FAR struct usrsock_conn_s *conn,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: usrsock_sendto
    + * Name: usrsock_sendto
      *
      * Description:
      *   If sendto() is used on a connection-mode (SOCK_STREAM, SOCK_SEQPACKET)
    diff --git a/net/usrsock/usrsock_setsockopt.c b/net/usrsock/usrsock_setsockopt.c
    index 5795fdee94..3dbd078ac2 100644
    --- a/net/usrsock/usrsock_setsockopt.c
    +++ b/net/usrsock/usrsock_setsockopt.c
    @@ -151,7 +151,7 @@ static int do_setsockopt_request(FAR struct usrsock_conn_s *conn,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: usrsock_setsockopt
    + * Name: usrsock_setsockopt
      *
      * Description:
      *   psock_setsockopt() sets the option specified by the 'option' argument,
    diff --git a/net/usrsock/usrsock_socket.c b/net/usrsock/usrsock_socket.c
    index 71764befea..63c4424f28 100644
    --- a/net/usrsock/usrsock_socket.c
    +++ b/net/usrsock/usrsock_socket.c
    @@ -153,7 +153,7 @@ static int do_socket_request(FAR struct usrsock_conn_s *conn, int domain,
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: usrsock_socket
    + * Name: usrsock_socket
      *
      * Description:
      *   socket() creates an endpoint for communication and returns a socket
    diff --git a/net/utils/net_dsec2tick.c b/net/utils/net_dsec2tick.c
    index 96a28db005..ed6a2d629e 100644
    --- a/net/utils/net_dsec2tick.c
    +++ b/net/utils/net_dsec2tick.c
    @@ -45,7 +45,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: net_dsec2tick
    + * Name: net_dsec2tick
      *
      * Description:
      *   Convert a decisecond value to a system clock ticks.  Used by IGMP logic.
    diff --git a/net/utils/net_dsec2timeval.c b/net/utils/net_dsec2timeval.c
    index b454844fa6..6700a08b3d 100644
    --- a/net/utils/net_dsec2timeval.c
    +++ b/net/utils/net_dsec2timeval.c
    @@ -53,7 +53,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: net_dsec2timeval
    + * Name: net_dsec2timeval
      *
      * Description:
      *   Convert a decisecond timeout value to a struct timeval.  Needed by
    diff --git a/net/utils/net_ipv6_maskcmp.c b/net/utils/net_ipv6_maskcmp.c
    index a5165e4817..61aee45de8 100644
    --- a/net/utils/net_ipv6_maskcmp.c
    +++ b/net/utils/net_ipv6_maskcmp.c
    @@ -50,7 +50,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: net_ipv6addr_maskcmp
    + * Name: net_ipv6addr_maskcmp
      *
      * Description:
      *   Compare two IPv6 addresses under a netmask.  The mask is used to mask
    diff --git a/net/utils/net_ipv6_pref2mask.c b/net/utils/net_ipv6_pref2mask.c
    index 40a1eb8dd6..6b04635413 100644
    --- a/net/utils/net_ipv6_pref2mask.c
    +++ b/net/utils/net_ipv6_pref2mask.c
    @@ -50,7 +50,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: net_ipv6_pref2mask
    + * Name: net_ipv6_pref2mask
      *
      * Description:
      *   Convert a IPv6 prefix length to a network mask.  The prefix length
    diff --git a/net/utils/net_lock.c b/net/utils/net_lock.c
    index fbd42342ae..8ad8c38cb1 100644
    --- a/net/utils/net_lock.c
    +++ b/net/utils/net_lock.c
    @@ -70,7 +70,7 @@ static unsigned int g_count   = 0;
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: _net_takesem
    + * Name: _net_takesem
      *
      * Description:
      *   Take the semaphore
    @@ -94,7 +94,7 @@ static void _net_takesem(void)
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: net_lockinitialize
    + * Name: net_lockinitialize
      *
      * Description:
      *   Initialize the locking facility
    @@ -107,7 +107,7 @@ void net_lockinitialize(void)
     }
     
     /****************************************************************************
    - * Function: net_lock
    + * Name: net_lock
      *
      * Description:
      *   Take the lock
    @@ -140,7 +140,7 @@ void net_lock(void)
     }
     
     /****************************************************************************
    - * Function: net_unlock
    + * Name: net_unlock
      *
      * Description:
      *   Release the lock.
    @@ -170,7 +170,7 @@ void net_unlock(void)
     }
     
     /****************************************************************************
    - * Function: net_timedwait
    + * Name: net_timedwait
      *
      * Description:
      *   Atomically wait for sem (or a timeout( while temporarily releasing
    @@ -237,7 +237,7 @@ int net_timedwait(sem_t *sem, FAR const struct timespec *abstime)
     }
     
     /****************************************************************************
    - * Function: net_lockedwait
    + * Name: net_lockedwait
      *
      * Description:
      *   Atomically wait for sem while temporarily releasing g_netlock.
    diff --git a/net/utils/net_timeval2dsec.c b/net/utils/net_timeval2dsec.c
    index a08a17e964..1cd39f78a8 100644
    --- a/net/utils/net_timeval2dsec.c
    +++ b/net/utils/net_timeval2dsec.c
    @@ -50,7 +50,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: net_timeval2dsec
    + * Name: net_timeval2dsec
      *
      * Description:
      *   Convert a struct timeval to deciseconds.  Needed by setsockopt() to
    diff --git a/net/utils/utils.h b/net/utils/utils.h
    index ffeca8c3f6..0b14be5585 100644
    --- a/net/utils/utils.h
    +++ b/net/utils/utils.h
    @@ -77,7 +77,7 @@ struct net_driver_s;      /* Forward reference */
     struct timeval;           /* Forward reference */
     
     /****************************************************************************
    - * Function: net_lockinitialize
    + * Name: net_lockinitialize
      *
      * Description:
      *   Initialize the locking facility
    @@ -87,7 +87,7 @@ struct timeval;           /* Forward reference */
     void net_lockinitialize(void);
     
     /****************************************************************************
    - * Function: net_dsec2timeval
    + * Name: net_dsec2timeval
      *
      * Description:
      *   Convert a decisecond value to a struct timeval.  Needed by getsockopt()
    @@ -107,7 +107,7 @@ void net_lockinitialize(void);
     void net_dsec2timeval(uint16_t dsec, FAR struct timeval *tv);
     
     /****************************************************************************
    - * Function: net_dsec2tick
    + * Name: net_dsec2tick
      *
      * Description:
      *   Convert a decisecond value to a system clock ticks.  Used by IGMP logic.
    @@ -123,7 +123,7 @@ void net_dsec2timeval(uint16_t dsec, FAR struct timeval *tv);
     unsigned int net_dsec2tick(int dsec);
     
     /****************************************************************************
    - * Function: net_timeval2dsec
    + * Name: net_timeval2dsec
      *
      * Description:
      *   Convert a struct timeval to deciseconds.  Needed by setsockopt() to
    @@ -172,7 +172,7 @@ uint8_t net_ipv6_mask2pref(FAR const uint16_t *mask);
     #endif
     
     /****************************************************************************
    - * Function: net_ipv6_pref2mask
    + * Name: net_ipv6_pref2mask
      *
      * Description:
      *   Convert a IPv6 prefix length to a network mask.  The prefix length
    diff --git a/sched/mqueue/mq_getattr.c b/sched/mqueue/mq_getattr.c
    index 3c0725320f..b1475b6846 100644
    --- a/sched/mqueue/mq_getattr.c
    +++ b/sched/mqueue/mq_getattr.c
    @@ -47,7 +47,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  mq_getattr
    + * Name:  mq_getattr
      *
      * Description:
      *   This functions gets status information and attributes
    diff --git a/sched/mqueue/mq_setattr.c b/sched/mqueue/mq_setattr.c
    index 71fe8df728..de238e4601 100644
    --- a/sched/mqueue/mq_setattr.c
    +++ b/sched/mqueue/mq_setattr.c
    @@ -49,7 +49,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function:  mq_setattr
    + * Name:  mq_setattr
      *
      * Description:
      *   This function sets the attributes associated with the
    diff --git a/sched/sched/sched_cpuload.c b/sched/sched/sched_cpuload.c
    index af8f90c72a..f236c2c50b 100644
    --- a/sched/sched/sched_cpuload.c
    +++ b/sched/sched/sched_cpuload.c
    @@ -219,7 +219,7 @@ void weak_function sched_process_cpuload(void)
     }
     
     /****************************************************************************
    - * Function:  clock_cpuload
    + * Name:  clock_cpuload
      *
      * Description:
      *   Return load measurement data for the select PID.
    diff --git a/sched/semaphore/sem_setprotocol.c b/sched/semaphore/sem_setprotocol.c
    index 1350206941..6f015bea4c 100644
    --- a/sched/semaphore/sem_setprotocol.c
    +++ b/sched/semaphore/sem_setprotocol.c
    @@ -53,7 +53,7 @@
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: sem_setprotocol
    + * Name: sem_setprotocol
      *
      * Description:
      *    Set semaphore protocol attribute.
    diff --git a/wireless/ieee802154/mac802154_loopback.c b/wireless/ieee802154/mac802154_loopback.c
    index 71255f0d60..31b72dca40 100644
    --- a/wireless/ieee802154/mac802154_loopback.c
    +++ b/wireless/ieee802154/mac802154_loopback.c
    @@ -135,7 +135,7 @@ static int lo_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac);
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: lo_txpoll
    + * Name: lo_txpoll
      *
      * Description:
      *   Check if the network has any outgoing packets ready to send.  This is
    @@ -263,7 +263,7 @@ static int lo_txpoll(FAR struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: lo_poll_work
    + * Name: lo_poll_work
      *
      * Description:
      *   Perform periodic polling from the worker thread
    @@ -306,7 +306,7 @@ static void lo_poll_work(FAR void *arg)
     }
     
     /****************************************************************************
    - * Function: lo_poll_expiry
    + * Name: lo_poll_expiry
      *
      * Description:
      *   Periodic timer handler.  Called from the timer interrupt handler.
    @@ -338,7 +338,7 @@ static void lo_poll_expiry(int argc, wdparm_t arg, ...)
     }
     
     /****************************************************************************
    - * Function: lo_ifup
    + * Name: lo_ifup
      *
      * Description:
      *   NuttX Callback: Bring up the Ethernet interface when an IP address is
    @@ -386,7 +386,7 @@ static int lo_ifup(FAR struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: lo_ifdown
    + * Name: lo_ifdown
      *
      * Description:
      *   NuttX Callback: Stop the interface.
    @@ -418,7 +418,7 @@ static int lo_ifdown(FAR struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: lo_txavail_work
    + * Name: lo_txavail_work
      *
      * Description:
      *   Perform an out-of-cycle poll on the worker thread.
    @@ -459,7 +459,7 @@ static void lo_txavail_work(FAR void *arg)
     }
     
     /****************************************************************************
    - * Function: lo_txavail
    + * Name: lo_txavail
      *
      * Description:
      *   Driver callback invoked when new TX data is available.  This is a
    @@ -499,7 +499,7 @@ static int lo_txavail(FAR struct net_driver_s *dev)
     }
     
     /****************************************************************************
    - * Function: lo_addmac
    + * Name: lo_addmac
      *
      * Description:
      *   NuttX Callback: Add the specified MAC address to the hardware multicast
    @@ -534,7 +534,7 @@ static int lo_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac)
     #endif
     
     /****************************************************************************
    - * Function: lo_rmmac
    + * Name: lo_rmmac
      *
      * Description:
      *   NuttX Callback: Remove the specified MAC address from the hardware multicast
    @@ -573,7 +573,7 @@ static int lo_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac)
      ****************************************************************************/
     
     /****************************************************************************
    - * Function: ieee8021514_loopback
    + * Name: ieee8021514_loopback
      *
      * Description:
      *   Initialize and register the Ieee802.15.4 MAC loopback network driver.
    -- 
    GitLab
    
    
    From a253e420f29a2f9a63e52e419dfd29b5042ef904 Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Fri, 21 Apr 2017 17:38:34 -0600
    Subject: [PATCH 551/990] MAC IOCTLs:  Eliminate a couple 'To be determined.'
    
    ---
     include/nuttx/wireless/ieee802154/ieee802154_mac.h | 4 ++--
     1 file changed, 2 insertions(+), 2 deletions(-)
    
    diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h
    index 2f78ec443f..95ccf10ecd 100644
    --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h
    +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h
    @@ -1327,8 +1327,8 @@ union ieee802154_mcps_notify_u
     
     union ieee802154_macarg_u
     {
    -  /* To be determined */                        /* MAC802154IOC_MCPS_REGISTER */
    -  /* To be determined */                        /* MAC802154IOC_MLME_REGISTER */
    +  union  ieee802154_mcps_notify_u  mcpsnotify;  /* MAC802154IOC_MCPS_REGISTER */
    +  union  ieee802154_mlme_notify_u  mlmenotify;  /* MAC802154IOC_MLME_REGISTER */
       struct ieee802154_assoc_req_s    assocreq;    /* MAC802154IOC_MLME_ASSOC_REQUEST */
       struct ieee802154_assoc_resp_s   assocresp;   /* MAC802154IOC_MLME_ASSOC_RESPONSE */
       struct ieee802154_disassoc_req_s disassocreq; /* MAC802154IOC_MLME_DISASSOC_REQUEST */
    -- 
    GitLab
    
    
    From 7c6f2c3c9a7171f85912052860d43d1b98d96ddc Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Fri, 21 Apr 2017 18:31:05 -0600
    Subject: [PATCH 552/990] Back out most of
     ebf05cb9f56278b03965f86ea8a1c33634cbfec5
    
    ---
     include/nuttx/wireless/wireless.h | 46 +-----------------
     net/netdev/netdev_ioctl.c         | 77 ++-----------------------------
     2 files changed, 4 insertions(+), 119 deletions(-)
    
    diff --git a/include/nuttx/wireless/wireless.h b/include/nuttx/wireless/wireless.h
    index a9abf706b6..a09c2bb148 100644
    --- a/include/nuttx/wireless/wireless.h
    +++ b/include/nuttx/wireless/wireless.h
    @@ -63,7 +63,6 @@
      * interface.
      */
     
    -/* IEEE802.11 */
     /* Wireless identification */
     
     #define SIOCSIWCOMMIT       _WLIOC(0x0001)  /* Commit pending changes to driver */
    @@ -154,19 +153,6 @@
     
     #define SIOCSIWPMKSA        _WLIOC(0x0032)  /* PMKSA cache operation */
     
    -/* IEEE802.15.4 6loWPAN
    - *
    - *  IEEE802.15.4 IOCTLs may be directed at one of three layers:
    - *
    - *  1. To the 6loWPAN network layer, as documented here,
    - *  2. To the IEEE802.15.4 MAC layer, as documented in,
    - *     include/nuttx/wireless/ieee802154/ioeee802154_mac.h, or to
    - *  3. To the IEEE802.15.4 radio device layer, as documented in,
    - *     include/nuttx/wireless/ieee802154/ioeee802154_radio.h.
    - *
    - * This is a placeholder; no 6LoWPAN IOCTL commands have been defined.
    - */
    -
     #define WL_FIRSTCHAR        0x0033
     #define WL_NNETCMDS         0x0032
     
    @@ -184,7 +170,7 @@
                                                  * of the address is driver specific */
     #define WLIOC_GETADDR       _WLIOC(0x0036)  /* arg: Pointer to address value, format
                                                  * of the address is driver specific */
    -#define WLIOC_SETTXPOWER    _WLIOC(0x0036)  /* arg: Pointer to int32_t, output power
    +#define WLIOC_SETTXPOWER    _WLIOC(0x0037)  /* arg: Pointer to int32_t, output power
                                                  * (in dBm) */
     #define WLIOC_GETTXPOWER    _WLIOC(0x0038)  /* arg: Pointer to int32_t, output power
                                                  * (in dBm) */
    @@ -369,35 +355,5 @@ struct iw_event
       union iwreq_data   u;     /* Fixed IOCTL payload */
     };
     
    -/* 6loWPAN */
    -/* This structure is used with the SIOCSWPANID IOCTL command to select the
    - * PAN ID to join.
    - */
    -
    -struct sixlowpan_panid_s
    -{
    -  uint16_t           panid; /* The PAN ID to join */
    -};
    -
    -/* This union defines the data payload of an 6loWPAN or SIOCGWPANID ioctl
    - * command and is used in struct sixlowpan_req_s below.
    - */
    -
    -union sixlowpan_data
    -{
    -  struct sixlowpan_panid_s panid;  /* PAN ID to join */
    -};
    -
    -/* This is the structure used to exchange data in wireless IOCTLs.  This
    - * structure is the same as 'struct ifreq', but defined for use with
    - * 6loWPAN IOCTLs.
    - */
    -
    -struct sixlowpan_req_s
    -{
    -  char ifr_name[IFNAMSIZ];  /* Interface name, e.g. "wpan0" */
    -  union sixlowpan_data u;   /* Data payload */
    -};
    -
     #endif /* CONFIG_DRIVERS_WIRELESS */
     #endif /* __INCLUDE_NUTTX_WIRELESS_WIRELESS_H */
    diff --git a/net/netdev/netdev_ioctl.c b/net/netdev/netdev_ioctl.c
    index 17ac9f51d3..f42acbeedb 100644
    --- a/net/netdev/netdev_ioctl.c
    +++ b/net/netdev/netdev_ioctl.c
    @@ -61,7 +61,6 @@
     
     #ifdef CONFIG_NET_6LOWPAN
     #  include 
    -#  include 
     #endif
     
     #ifdef CONFIG_NET_IGMP
    @@ -321,51 +320,6 @@ static void ioctl_set_ipv6addr(FAR net_ipv6addr_t outaddr,
     }
     #endif
     
    -/****************************************************************************
    - * Name: netdev_sixlowpan_ioctl
    - *
    - * Description:
    - *   Perform 6loWPAN network device specific operations.
    - *
    - * Parameters:
    - *   psock    Socket structure
    - *   dev      Ethernet driver device structure
    - *   cmd      The ioctl command
    - *   req      The argument of the ioctl cmd
    - *
    - * Return:
    - *   >=0 on success (positive non-zero values are cmd-specific)
    - *   Negated errno returned on failure.
    - *
    - ****************************************************************************/
    -
    -#if defined(CONFIG_NETDEV_IOCTL) && defined(CONFIG_NET_6LOWPAN)
    -static int netdev_sixlowpan_ioctl(FAR struct socket *psock, int cmd,
    -                                  FAR struct sixlowpan_req_s *req)
    -{
    -#if 0 /* None yet defined */
    -  FAR struct ieee802154_driver_s *ieee;
    -  int ret = -ENOTTY;
    -
    -  /* Verify that this is a valid wireless network IOCTL command */
    -
    -  if (_WLIOCVALID(cmd) && (unsigned)_IOC_NR(cmd) <= WL_NNETCMDS)
    -    {
    -      switch (cmd)
    -        {
    -
    -          default:
    -            return -ENOTTY;
    -        }
    -    }
    -
    -  return ret;
    -#else
    -  return -ENOTTY;
    -#endif
    -}
    -#endif
    -
     /****************************************************************************
      * Name: netdev_wifr_ioctl
      *
    @@ -721,7 +675,9 @@ static int netdev_ifr_ioctl(FAR struct socket *psock, int cmd,
             }
             break;
     
    -      /* MAC address operations only make sense if Ethernet is supported */
    +      /* MAC address operations only make sense if Ethernet or 6loWPAN are
    +       * supported.
    +       */
     
     #if defined(CONFIG_NET_ETHERNET) || defined(CONFIG_NET_6LOWPAN)
           case SIOCGIFHWADDR:  /* Get hardware address */
    @@ -1220,21 +1176,6 @@ int psock_ioctl(FAR struct socket *psock, int cmd, unsigned long arg)
     {
       int ret;
     
    -  /* Check if this is a valid command.  In all cases, arg is a pointer that has
    -   * been cast to unsigned long.  Verify that the value of the to-be-pointer is
    -   * non-NULL.
    -   */
    -
    -#ifdef CONFIG_DRIVERS_WIRELESS
    -  if (!_SIOCVALID(cmd) && !_WLIOCVALID(cmd))
    -#else
    -  if (!_SIOCVALID(cmd))
    -#endif
    -    {
    -      ret = -ENOTTY;
    -      goto errout;
    -    }
    -
       /* Verify that the psock corresponds to valid, allocated socket */
     
       if (psock == NULL || psock->s_crefs <= 0)
    @@ -1247,18 +1188,6 @@ int psock_ioctl(FAR struct socket *psock, int cmd, unsigned long arg)
     
       ret = netdev_ifr_ioctl(psock, cmd, (FAR struct ifreq *)((uintptr_t)arg));
     
    -#if defined(CONFIG_NETDEV_IOCTL) && defined(CONFIG_NET_6LOWPAN)
    -  /* Check for a 6loWPAN network command */
    -
    -  if (ret == -ENOTTY)
    -    {
    -      FAR struct sixlowpan_req_s *slpreq;
    -
    -      slpreq = (FAR struct sixlowpan_req_s *)((uintptr_t)arg);
    -      ret    = netdev_sixlowpan_ioctl(psock, cmd, slpreq);
    -    }
    -#endif
    -
     #if defined(CONFIG_NETDEV_IOCTL) && defined(CONFIG_NETDEV_WIRELESS_IOCTL)
       /* Check for a wireless network command */
     
    -- 
    GitLab
    
    
    From d884958a2ea9eb8f08ca9b0b7cb5d7ec7a215f8c Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Fri, 21 Apr 2017 18:37:07 -0600
    Subject: [PATCH 553/990] Back out most of
     ebf05cb9f56278b03965f86ea8a1c33634cbfec5
    
    ---
     include/nuttx/wireless/wireless.h | 44 ------------------------
     net/netdev/netdev_ioctl.c         | 57 -------------------------------
     2 files changed, 101 deletions(-)
    
    diff --git a/include/nuttx/wireless/wireless.h b/include/nuttx/wireless/wireless.h
    index a9abf706b6..cc5df1e309 100644
    --- a/include/nuttx/wireless/wireless.h
    +++ b/include/nuttx/wireless/wireless.h
    @@ -63,7 +63,6 @@
      * interface.
      */
     
    -/* IEEE802.11 */
     /* Wireless identification */
     
     #define SIOCSIWCOMMIT       _WLIOC(0x0001)  /* Commit pending changes to driver */
    @@ -154,19 +153,6 @@
     
     #define SIOCSIWPMKSA        _WLIOC(0x0032)  /* PMKSA cache operation */
     
    -/* IEEE802.15.4 6loWPAN
    - *
    - *  IEEE802.15.4 IOCTLs may be directed at one of three layers:
    - *
    - *  1. To the 6loWPAN network layer, as documented here,
    - *  2. To the IEEE802.15.4 MAC layer, as documented in,
    - *     include/nuttx/wireless/ieee802154/ioeee802154_mac.h, or to
    - *  3. To the IEEE802.15.4 radio device layer, as documented in,
    - *     include/nuttx/wireless/ieee802154/ioeee802154_radio.h.
    - *
    - * This is a placeholder; no 6LoWPAN IOCTL commands have been defined.
    - */
    -
     #define WL_FIRSTCHAR        0x0033
     #define WL_NNETCMDS         0x0032
     
    @@ -369,35 +355,5 @@ struct iw_event
       union iwreq_data   u;     /* Fixed IOCTL payload */
     };
     
    -/* 6loWPAN */
    -/* This structure is used with the SIOCSWPANID IOCTL command to select the
    - * PAN ID to join.
    - */
    -
    -struct sixlowpan_panid_s
    -{
    -  uint16_t           panid; /* The PAN ID to join */
    -};
    -
    -/* This union defines the data payload of an 6loWPAN or SIOCGWPANID ioctl
    - * command and is used in struct sixlowpan_req_s below.
    - */
    -
    -union sixlowpan_data
    -{
    -  struct sixlowpan_panid_s panid;  /* PAN ID to join */
    -};
    -
    -/* This is the structure used to exchange data in wireless IOCTLs.  This
    - * structure is the same as 'struct ifreq', but defined for use with
    - * 6loWPAN IOCTLs.
    - */
    -
    -struct sixlowpan_req_s
    -{
    -  char ifr_name[IFNAMSIZ];  /* Interface name, e.g. "wpan0" */
    -  union sixlowpan_data u;   /* Data payload */
    -};
    -
     #endif /* CONFIG_DRIVERS_WIRELESS */
     #endif /* __INCLUDE_NUTTX_WIRELESS_WIRELESS_H */
    diff --git a/net/netdev/netdev_ioctl.c b/net/netdev/netdev_ioctl.c
    index 7f194d1c1a..41014ce5ef 100644
    --- a/net/netdev/netdev_ioctl.c
    +++ b/net/netdev/netdev_ioctl.c
    @@ -326,51 +326,6 @@ static void ioctl_set_ipv6addr(FAR net_ipv6addr_t outaddr,
     }
     #endif
     
    -/****************************************************************************
    - * Name: netdev_sixlowpan_ioctl
    - *
    - * Description:
    - *   Perform 6loWPAN network device specific operations.
    - *
    - * Parameters:
    - *   psock    Socket structure
    - *   dev      Ethernet driver device structure
    - *   cmd      The ioctl command
    - *   req      The argument of the ioctl cmd
    - *
    - * Return:
    - *   >=0 on success (positive non-zero values are cmd-specific)
    - *   Negated errno returned on failure.
    - *
    - ****************************************************************************/
    -
    -#if defined(CONFIG_NETDEV_IOCTL) && defined(CONFIG_NET_6LOWPAN)
    -static int netdev_sixlowpan_ioctl(FAR struct socket *psock, int cmd,
    -                                  FAR struct sixlowpan_req_s *req)
    -{
    -#if 0 /* None yet defined */
    -  FAR struct ieee802154_driver_s *ieee;
    -  int ret = -ENOTTY;
    -
    -  /* Verify that this is a valid wireless network IOCTL command */
    -
    -  if (_WLIOCVALID(cmd) && (unsigned)_IOC_NR(cmd) <= WL_NNETCMDS)
    -    {
    -      switch (cmd)
    -        {
    -
    -          default:
    -            return -ENOTTY;
    -        }
    -    }
    -
    -  return ret;
    -#else
    -  return -ENOTTY;
    -#endif
    -}
    -#endif
    -
     /****************************************************************************
      * Name: netdev_iee802154_ioctl
      *
    @@ -1313,18 +1268,6 @@ int psock_ioctl(FAR struct socket *psock, int cmd, unsigned long arg)
     
       ret = netdev_ifr_ioctl(psock, cmd, (FAR struct ifreq *)((uintptr_t)arg));
     
    -#if defined(CONFIG_NETDEV_IOCTL) && defined(CONFIG_NET_6LOWPAN)
    -  /* Check for a 6loWPAN network command */
    -
    -  if (ret == -ENOTTY)
    -    {
    -      FAR struct sixlowpan_req_s *slpreq;
    -
    -      slpreq = (FAR struct sixlowpan_req_s *)((uintptr_t)arg);
    -      ret    = netdev_sixlowpan_ioctl(psock, cmd, slpreq);
    -    }
    -#endif
    -
     #if defined(CONFIG_NETDEV_IOCTL) && defined(CONFIG_NETDEV_WIRELESS_IOCTL)
       /* Check for a wireless network command */
     
    -- 
    GitLab
    
    
    From 0184bf6787e862d9639ea55d86c5c95e1d34bb4e Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Fri, 21 Apr 2017 18:42:13 -0600
    Subject: [PATCH 554/990] Correct type in a cast
    
    ---
     net/netdev/netdev_ioctl.c | 2 +-
     1 file changed, 1 insertion(+), 1 deletion(-)
    
    diff --git a/net/netdev/netdev_ioctl.c b/net/netdev/netdev_ioctl.c
    index f42acbeedb..b9581f46d3 100644
    --- a/net/netdev/netdev_ioctl.c
    +++ b/net/netdev/netdev_ioctl.c
    @@ -1195,7 +1195,7 @@ int psock_ioctl(FAR struct socket *psock, int cmd, unsigned long arg)
         {
           FAR struct iwreq *wifrreq;
     
    -      wifrreq = (FAR struct sixlowpan_req_s *)((uintptr_t)arg);
    +      wifrreq = (FAR struct iwreq *)((uintptr_t)arg);
           ret     = netdev_wifr_ioctl(psock, cmd, wifrreq);
         }
     #endif
    -- 
    GitLab
    
    
    From 22e5cec3763746e0eb6106de22f6b6b7dec84a6a Mon Sep 17 00:00:00 2001
    From: Simon Piriou 
    Date: Sat, 22 Apr 2017 15:57:51 +0200
    Subject: [PATCH 555/990] photon: add basic wlan scan function
    
    ---
     drivers/wireless/ieee80211/Make.defs     |   1 +
     drivers/wireless/ieee80211/bcmf_driver.c | 346 +++++++++++++++++++++++
     drivers/wireless/ieee80211/bcmf_driver.h |   3 +
     drivers/wireless/ieee80211/bcmf_sdio.c   |  35 +--
     drivers/wireless/ieee80211/bcmf_sdpcm.c  | 118 +++++---
     drivers/wireless/ieee80211/bcmf_sdpcm.h  |   6 +-
     6 files changed, 448 insertions(+), 61 deletions(-)
     create mode 100644 drivers/wireless/ieee80211/bcmf_driver.c
    
    diff --git a/drivers/wireless/ieee80211/Make.defs b/drivers/wireless/ieee80211/Make.defs
    index 1fa0d3b091..e7d41ee762 100644
    --- a/drivers/wireless/ieee80211/Make.defs
    +++ b/drivers/wireless/ieee80211/Make.defs
    @@ -41,6 +41,7 @@ ifeq ($(CONFIG_DRIVERS_IEEE80211),y)
     # Include IEEE 802.11 drivers into the build
     
     ifeq ($(CONFIG_IEEE80211_BROADCOM_FULLMAC_SDIO),y)
    +  CSRCS += bcmf_driver.c
       CSRCS += bcmf_sdio.c
       CSRCS += bcmf_core.c
       CSRCS += bcmf_sdpcm.c
    diff --git a/drivers/wireless/ieee80211/bcmf_driver.c b/drivers/wireless/ieee80211/bcmf_driver.c
    new file mode 100644
    index 0000000000..1ca1fd0010
    --- /dev/null
    +++ b/drivers/wireless/ieee80211/bcmf_driver.c
    @@ -0,0 +1,346 @@
    +/****************************************************************************
    + * drivers/wireless/ieee80211/bcmf_driver.c
    + *
    + *   Copyright (C) 2017 Gregory Nutt. All rights reserved.
    + *   Author: Simon Piriou 
    + *
    + * 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 "bcmf_driver.h"
    +#include "bcmf_sdpcm.h"
    +#include "bcmf_sdio_core.h"
    +#include "bcmf_ioctl.h"
    +
    +/****************************************************************************
    + * Pre-processor Definitions
    + ****************************************************************************/
    +
    +// TODO move elsewhere
    +#define DOT11_BSSTYPE_ANY     2
    +#define WL_SCAN_CHANNEL_TIME   40
    +#define WL_SCAN_UNASSOC_TIME   40
    +#define WL_SCAN_PASSIVE_TIME   120
    +
    +/****************************************************************************
    + * Private Types
    + ****************************************************************************/
    +
    +/****************************************************************************
    + * Private Function Prototypes
    + ****************************************************************************/
    +
    +static int bcmf_run_escan(FAR struct bcmf_dev_s *priv);
    +
    +/****************************************************************************
    + * Private Data
    + ****************************************************************************/
    +
    +/****************************************************************************
    + * Private Functions
    + ****************************************************************************/
    +
    +int bcmf_wl_set_mac_address(FAR struct bcmf_dev_s *priv, uint8_t *addr)
    +{
    +  int ret;
    +  uint32_t out_len = 6;
    +
    +  ret = bcmf_sdpcm_iovar_request(priv, CHIP_STA_INTERFACE, true,
    +                                 IOVAR_STR_CUR_ETHERADDR, addr,
    +                                 &out_len);
    +  if (ret != OK)
    +    {
    +      return ret;
    +    }
    +
    +  _info("MAC address updated %02X:%02X:%02X:%02X:%02X:%02X\n",
    +                            addr[0], addr[1], addr[2],
    +                            addr[3], addr[4], addr[5]);
    +  memcpy(priv->mac_addr, addr, 6);
    +    
    +  return OK;
    +}
    +
    +int bcmf_wl_enable(FAR struct bcmf_dev_s *priv, bool enable)
    +{
    +  int ret;
    +  uint32_t out_len;
    +
    +  /* TODO chek device state */
    +
    +  out_len = 0;
    +  ret = bcmf_sdpcm_ioctl(priv, CHIP_STA_INTERFACE, true,
    +                         enable ? WLC_UP : WLC_DOWN, NULL, &out_len);
    +  
    +  if (ret == OK)
    +    {
    +      /* TODO update device state */
    +    }
    +
    +  return ret;
    +}
    +
    +int bcmf_dongle_scantime(FAR struct bcmf_dev_s *priv, int32_t scan_assoc_time,
    +          int32_t scan_unassoc_time, int32_t scan_passive_time)
    +{
    +  int ret;
    +  uint32_t out_len, value;
    +
    +  out_len = 4;
    +  value = scan_assoc_time;
    +  ret = bcmf_sdpcm_ioctl(priv, CHIP_STA_INTERFACE, true,
    +                         WLC_SET_SCAN_CHANNEL_TIME, (uint8_t*)&value,
    +                         &out_len);
    +  if (ret != OK)
    +    {
    +      return -EIO;
    +    }
    +
    +  out_len = 4;
    +  value = scan_unassoc_time;
    +  ret = bcmf_sdpcm_ioctl(priv, CHIP_STA_INTERFACE, true,
    +                         WLC_SET_SCAN_UNASSOC_TIME, (uint8_t*)&value,
    +                         &out_len);
    +  if (ret != OK)
    +    {
    +      return -EIO;
    +    }
    +
    +  out_len = 4;
    +  value = scan_passive_time;
    +  ret = bcmf_sdpcm_ioctl(priv, CHIP_STA_INTERFACE, true,
    +                         WLC_SET_SCAN_PASSIVE_TIME, (uint8_t*)&value,
    +                         &out_len);
    +  if (ret != OK)
    +    {
    +      return -EIO;
    +    }
    +
    +  return OK;
    +}
    +
    +int bcmf_dongle_initialize(FAR struct bcmf_dev_s *priv)
    +{
    +  int ret;
    +  uint32_t out_len;
    +  uint32_t value;
    +
    +  ret = bcmf_wl_enable(priv, true);
    +  if (ret)
    +    {
    +      return ret;
    +    }
    +
    +  ret = bcmf_dongle_scantime(priv, WL_SCAN_CHANNEL_TIME,
    +            WL_SCAN_UNASSOC_TIME, WL_SCAN_PASSIVE_TIME);
    +  if (ret)
    +    {
    +      return ret;
    +    }
    +
    +  /* FIXME disable power save mode */
    +
    +  out_len = 4;
    +  value = 0;
    +  ret = bcmf_sdpcm_ioctl(priv, CHIP_STA_INTERFACE, true,
    +                         WLC_SET_PM, (uint8_t*)&value, &out_len);
    +  if (ret != OK)
    +    {
    +      return ret;
    +    }
    +
    +  /* Set the GMode */
    +
    +  out_len = 4;
    +  value = GMODE_AUTO;
    +  ret = bcmf_sdpcm_ioctl(priv, CHIP_STA_INTERFACE, true,
    +                         WLC_SET_GMODE, (uint8_t*)&value, &out_len);
    +  if (ret != OK)
    +    {
    +      return ret;
    +    }
    +
    +  /* TODO configure roaming if needed. Disable for now */
    +
    +  out_len = 4;
    +  value = 1;
    +  ret = bcmf_sdpcm_iovar_request(priv, CHIP_STA_INTERFACE, true,
    +                                 IOVAR_STR_ROAM_OFF, (uint8_t*)&value,
    +                                 &out_len);
    +
    +  // FIXME remove
    +
    +  /* Try scan */
    +
    +  value = 0;
    +  out_len = 4;
    +  ret = bcmf_sdpcm_ioctl(priv, CHIP_STA_INTERFACE, true,
    +                         WLC_SET_PASSIVE_SCAN, (uint8_t*)&value, &out_len);
    +  bcmf_run_escan(priv);
    +  return OK;
    +}
    +
    +int bcmf_run_escan(FAR struct bcmf_dev_s *priv)
    +{
    +  int ret;
    +  uint32_t out_len;
    +
    +  /* Default request structure */
    +
    +  struct wl_escan_params *params =
    +                  (struct wl_escan_params*)kmm_malloc(sizeof(*params));
    +  if (!params)
    +    {
    +      return -ENOMEM;
    +    }
    +
    +  memset(params, 0, sizeof(*params));
    +
    +  params->version = ESCAN_REQ_VERSION;
    +  params->action = WL_SCAN_ACTION_START;
    +  params->sync_id = 0x1234;
    +
    +  
    +  memset(¶ms->params.bssid, 0xFF, sizeof(params->params.bssid));
    +  params->params.bss_type = DOT11_BSSTYPE_ANY;
    +  params->params.scan_type = 0; /* Active scan */
    +  params->params.nprobes = -1;
    +  params->params.active_time = -1;
    +  params->params.passive_time = -1;
    +  params->params.home_time = -1;
    +
    +  params->params.channel_num = 0;
    +
    +  _info("start scan\n");
    +
    +  out_len = sizeof(*params);
    +  ret = bcmf_sdpcm_iovar_request(priv, CHIP_STA_INTERFACE, true,
    +                                 IOVAR_STR_ESCAN, (uint8_t*)params,
    +                                 &out_len);
    +
    +  free(params);
    +
    +  if (ret != OK)
    +    {
    +      return -EIO;
    +    }
    +
    +  return OK;
    +}
    +
    +/****************************************************************************
    + * Public Functions
    + ****************************************************************************/
    +
    +int bcmf_wl_initialize(FAR struct bcmf_dev_s *priv)
    +{
    +  int ret;
    +  uint32_t out_len;
    +  uint8_t tmp_buf[64];
    +
    +  /* Disable TX Gloming feature */
    +
    +  out_len = 4;
    +  *(uint32_t*)tmp_buf = 0;
    +  ret = bcmf_sdpcm_iovar_request(priv, CHIP_STA_INTERFACE, false,
    +                                 IOVAR_STR_TX_GLOM, tmp_buf,
    +                                 &out_len);
    +  if (ret != OK)
    +    {
    +      return -EIO;
    +    }
    +
    +  /* Query MAC address */
    +
    +  out_len = 6;
    +  ret = bcmf_sdpcm_iovar_request(priv, CHIP_STA_INTERFACE, false,
    +                                 IOVAR_STR_CUR_ETHERADDR, tmp_buf,
    +                                 &out_len);
    +  if (ret != OK)
    +    {
    +      return -EIO;
    +    }
    +
    +  memcpy(priv->mac_addr, tmp_buf, 6);
    +
    +  _info("MAC address is %02X:%02X:%02X:%02X:%02X:%02X\n",
    +                        tmp_buf[0], tmp_buf[1], tmp_buf[2],
    +                        tmp_buf[3], tmp_buf[4], tmp_buf[5]);
    +  
    +  /* Query firmware version string */
    +
    +  out_len = sizeof(tmp_buf);
    +  ret = bcmf_sdpcm_iovar_request(priv, CHIP_STA_INTERFACE, false,
    +                                 IOVAR_STR_VERSION, tmp_buf,
    +                                 &out_len);
    +  if (ret != OK)
    +    {
    +      return -EIO;
    +    }
    +
    +  /* Remove line feed */
    +  out_len = strlen((char*)tmp_buf);
    +  if (out_len > 0 && tmp_buf[out_len-1] == '\n')
    +    {
    +      tmp_buf[out_len-1] = 0;
    +    }
    +
    +  _info("fw version <%s>\n", tmp_buf);
    +
    +  /* FIXME Configure event mask to enable all asynchronous events */
    +
    +  uint8_t event_mask[16];
    +  memset(event_mask, 0xff, sizeof(event_mask));
    +
    +  out_len = sizeof(event_mask);
    +  ret = bcmf_sdpcm_iovar_request(priv, CHIP_STA_INTERFACE, true,
    +                                 IOVAR_STR_EVENT_MSGS, event_mask,
    +                                 &out_len);
    +  if (ret != OK)
    +    {
    +      return -EIO;
    +    }
    +  // TODO Create a wlan device name and register network driver
    +
    +  return bcmf_dongle_initialize(priv);
    +}
    \ No newline at end of file
    diff --git a/drivers/wireless/ieee80211/bcmf_driver.h b/drivers/wireless/ieee80211/bcmf_driver.h
    index 0d6e664d2c..483f719a3e 100644
    --- a/drivers/wireless/ieee80211/bcmf_driver.h
    +++ b/drivers/wireless/ieee80211/bcmf_driver.h
    @@ -73,10 +73,13 @@ struct bcmf_dev_s
       sem_t control_timeout;           /* Semaphore to wait for control frame rsp */
       uint16_t control_reqid;          /* Current control request id */
       uint8_t *control_rxframe;        /* Received control frame response */
    +  uint32_t control_status;         /* Last received frame status */
     
       // FIXME use mutex instead of semaphore
       sem_t tx_queue_mutex;            /* Lock for transmit queue */
       dq_queue_t tx_queue;             /* Queue of frames to tramsmit */
    +
    +  uint8_t mac_addr[6];             /* Current mac address */
     };
     
     #endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_DRIVER_H */
    diff --git a/drivers/wireless/ieee80211/bcmf_sdio.c b/drivers/wireless/ieee80211/bcmf_sdio.c
    index 9f7a125915..ee10b0fc9e 100644
    --- a/drivers/wireless/ieee80211/bcmf_sdio.c
    +++ b/drivers/wireless/ieee80211/bcmf_sdio.c
    @@ -673,31 +673,14 @@ int bcmf_sdio_initialize(int minor, FAR struct sdio_dev_s *dev)
           goto exit_uninit_hw;
         }
     
    -  /* Device is up and running
    -     TODO Create a wlan device name and register network driver here */
    +  /* sdio bus is ready, init driver */
     
    -  // TODO remove: basic iovar test
    -  up_mdelay(1000);
    -  char fw_version[64];
    -  uint32_t out_len = sizeof(fw_version);
    -  ret = bcmf_sdpcm_iovar_request(priv, CHIP_STA_INTERFACE, false,
    -                                 IOVAR_STR_VERSION, fw_version,
    -                                 &out_len);
    -  if (ret == OK)
    -    {
    -      _info("fw version %d <%s>\n", out_len, fw_version);
    -    }
    -
    -  up_mdelay(100);
    -  out_len = 6;
    -  ret = bcmf_sdpcm_iovar_request(priv, CHIP_STA_INTERFACE, false,
    -                                 IOVAR_STR_CUR_ETHERADDR, fw_version,
    -                                 &out_len);
    -  if (ret == OK)
    +  ret = bcmf_wl_initialize(priv);
    +  if (ret != OK)
         {
    -      _info("MAC address %d %02X:%02X:%02X:%02X:%02X:%02X\n", out_len,
    -                            fw_version[0], fw_version[1], fw_version[2],
    -                            fw_version[3], fw_version[4], fw_version[5]);
    +      _err("Cannot init wlan driver %d\n", ret);
    +      ret = -EIO;
    +      goto exit_uninit_hw;
         }
     
       return OK;
    @@ -793,14 +776,14 @@ int bcmf_sdio_thread(int argc, char **argv)
               bcmf_write_sbregw(priv,
                            CORE_BUS_REG(priv->get_core_base_address(SDIOD_CORE_ID),
                            intstatus), priv->intstatus);
    -          _info("intstatus %x\n", priv->intstatus);
    +          // _info("intstatus %x\n", priv->intstatus);
             }
     
           /* On frame indication, read available frames */
     
           if (priv->intstatus & I_HMB_FRAME_IND)
             {
    -          _info("Frames available\n");
    +          // _info("Frames available\n");
     
               do
                 {
    @@ -825,7 +808,7 @@ int bcmf_sdio_thread(int argc, char **argv)
           /* If we're done for now, turn off clock request. */
     
           // TODO add wakelock
    -      bcmf_sdio_bus_sleep(priv, true);
    +      // bcmf_sdio_bus_sleep(priv, true);
         }
         return 0;
     }
    \ No newline at end of file
    diff --git a/drivers/wireless/ieee80211/bcmf_sdpcm.c b/drivers/wireless/ieee80211/bcmf_sdpcm.c
    index 1336efef97..bc66f7bee4 100644
    --- a/drivers/wireless/ieee80211/bcmf_sdpcm.c
    +++ b/drivers/wireless/ieee80211/bcmf_sdpcm.c
    @@ -206,7 +206,8 @@ int bcmf_sdpcm_process_header(FAR struct bcmf_dev_s *priv,
      ****************************************************************************/
     
     // FIXME remove
    -uint8_t tmp_buffer[512];
    +uint8_t tmp_buffer[1024];
    +uint8_t tmp_buffer_ctl[1024];
     int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv)
     {
       int ret;
    @@ -241,7 +242,7 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv)
         }
     
       // FIXME define for size
    -  if (len > 512)
    +  if (len > sizeof(tmp_buffer))
         {
           _err("Frame is too large, cancel %d\n", len);
           ret = -ENOMEM;
    @@ -258,8 +259,8 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv)
           goto exit_free_abort;
         }
     
    -  _info("Receive frame\n");
    -  bcmf_hexdump((uint8_t*)header, len, (unsigned int)header);
    +  // _info("Receive frame\n");
    +  // bcmf_hexdump((uint8_t*)header, len, (unsigned int)header);
     
       /* Process and validate header */
     
    @@ -276,7 +277,7 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv)
       switch (header->channel & 0x0f)
         {
           case SDPCM_CONTROL_CHANNEL:
    -        _info("Control message\n");
    +        // _info("Control message\n");
     
             /* Check frame */
     
    @@ -295,7 +296,7 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv)
             if (header->size < sizeof(struct bcmf_sdpcm_header) + 
                                sizeof(struct bcmf_sdpcm_cdc_header) +
                                cdc_header->len ||
    -            cdc_header->len > 512 -
    +            cdc_header->len > sizeof(tmp_buffer) -
                                   sizeof(struct bcmf_sdpcm_header) -
                                   sizeof(struct bcmf_sdpcm_cdc_header))
               {
    @@ -310,7 +311,10 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv)
               {
                 /* Expected frame received, send it back to user */
     
    -            priv->control_rxframe = (uint8_t*)header;
    +            // TODO allocate real buffer
    +            memcpy(tmp_buffer_ctl, tmp_buffer, header->size);
    +            priv->control_rxframe = tmp_buffer_ctl;
    +            // priv->control_rxframe = (uint8_t*)header;
     
                 sem_post(&priv->control_timeout);
                 return OK;
    @@ -325,6 +329,7 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv)
     
           case SDPCM_EVENT_CHANNEL:
             _info("Event message\n");
    +        bcmf_hexdump((uint8_t*)header, header->size, (unsigned long)header);
             ret = OK;
             break;
     
    @@ -380,9 +385,9 @@ int bcmf_sdpcm_sendframe(FAR struct bcmf_dev_s *priv)
     
       frame->header.sequence = priv->tx_seq++;
     
    -  _info("Send frame\n");
    -  bcmf_hexdump((uint8_t*)&frame->header, frame->header.size,
    -               (unsigned int)&frame->header);
    +  // _info("Send frame\n");
    +  // bcmf_hexdump((uint8_t*)&frame->header, frame->header.size,
    +  //              (unsigned int)&frame->header);
     
       ret = bcmf_transfer_bytes(priv, true, 2, 0, (uint8_t*)&frame->header,
                                 frame->header.size);
    @@ -423,29 +428,39 @@ exit_post_sem:
     // FIXME remove
     uint8_t tmp_buffer2[512];
     uint8_t* bcmf_sdpcm_allocate_iovar(FAR struct bcmf_dev_s *priv, char *name,
    -                              char *data, uint32_t *len)
    +                              uint8_t *data, uint32_t *len)
     {
       uint32_t data_len;
    -  uint16_t name_len = strlen(name) + 1;
    +  uint16_t name_len;
     
    -  if (!data)
    +  if (name)
         {
    -      data_len = 0;
    +      name_len = strlen(name) + 1;
         }
       else
    -   {
    +    {
    +      name_len = 0;
    +    }
    +
    +  if (data)
    +    {
           data_len = *len;
    -   }
    +    }
    +  else
    +    {
    +      data_len = 0;
    +    }
    +
    +  *len = 0;
     
       // FIXME allocate buffer and use max_size instead of 512
       if (data_len > 512-sizeof(struct bcmf_sdpcm_cdc_frame) ||
           (data_len + name_len) > 512-sizeof(struct bcmf_sdpcm_cdc_frame))
         {
    -      *len = 0;
           return NULL;
         }
     
    -  // TODO allocate buffer
    +  // TODO allocate buffer len + sizeof(struct bcmf_sdpcm_cdc_frame)
     
       /* Copy name string and data */
     
    @@ -532,12 +547,13 @@ int bcmf_sdpcm_send_cdc_frame(FAR struct bcmf_dev_s *priv, uint32_t cmd,
       return bcmf_sdpcm_queue_frame(priv, SDPCM_CONTROL_CHANNEL, data, len);
     }
     
    -int bcmf_sdpcm_iovar_request(FAR struct bcmf_dev_s *priv,
    -                             uint32_t ifidx, bool set, char *name,
    -                             char *data, uint32_t *len)
    +int bcmf_sdpcm_control_request(FAR struct bcmf_dev_s *priv,
    +                               uint32_t ifidx, bool set, uint32_t cmd,
    +                               char *name, uint8_t *data, uint32_t *len)
     {
       int ret;
       uint8_t *iovar_buf;
    +  uint32_t out_len = *len;
       uint32_t iovar_buf_len = *len;
     
       *len = 0;
    @@ -559,13 +575,14 @@ int bcmf_sdpcm_iovar_request(FAR struct bcmf_dev_s *priv,
           goto exit_sem_post;
         }
     
    -  /* Send control frame. Frame buffer is freed when sent */
    +  /* Send control frame. iovar buffer is freed when sent */
     
    -  ret = bcmf_sdpcm_send_cdc_frame(priv, set ? WLC_SET_VAR : WLC_GET_VAR,
    +  ret = bcmf_sdpcm_send_cdc_frame(priv, cmd,
                                  ifidx, set, iovar_buf, iovar_buf_len);
       if (ret != OK)
         {
    -       goto exit_free_iovar;
    +      // TODO free allocated iovar buffer here
    +      goto exit_sem_post;
         }
     
       /* Wait for response */
    @@ -579,25 +596,58 @@ int bcmf_sdpcm_iovar_request(FAR struct bcmf_dev_s *priv,
           goto exit_sem_post;
         }
     
    -  if (!set)
    -    {
    -      /* Request sent, copy received data back */
    +  /* Check frame status */
     
    -      struct bcmf_sdpcm_cdc_dcmd *rxframe =
    +  struct bcmf_sdpcm_cdc_dcmd *rxframe =
                   (struct bcmf_sdpcm_cdc_dcmd*)priv->control_rxframe;
     
    -      memcpy(data, rxframe->data, rxframe->cdc_header.len);
    +  priv->control_status = rxframe->cdc_header.status;
     
    -      *len = rxframe->cdc_header.len;
    +  if (priv->control_status != 0)
    +    {
    +      _err("Invalid cdc status 0x%x\n", priv->control_status);
    +      ret = -EIO;
    +      goto exit_free_rx_frame;
         }
     
    -  // TODO free rxframe buffer */
    +  if (!set)
    +    {
    +      /* Request sent, copy received data back */
     
    -  goto exit_sem_post;
    +      if (rxframe->cdc_header.len > out_len)
    +        {
    +          _err("RX frame too big %d %d\n", rxframe->cdc_header.len, out_len);
    +          memcpy(data, rxframe->data, out_len);
    +          *len = out_len;
    +        }
    +      else
    +        {
    +          memcpy(data, rxframe->data, rxframe->cdc_header.len);
    +          *len = rxframe->cdc_header.len;
    +        }
    +    }
    +
    +exit_free_rx_frame:
    +  // TODO free rxframe buffer */
    +  priv->control_rxframe = NULL;
     
    -exit_free_iovar:
    -  // TODO free allocated buffer here
     exit_sem_post:
       sem_post(&priv->control_mutex);
       return ret;
    +}
    +
    +int bcmf_sdpcm_iovar_request(FAR struct bcmf_dev_s *priv,
    +                             uint32_t ifidx, bool set, char *name,
    +                             uint8_t *data, uint32_t *len)
    +{
    +  return bcmf_sdpcm_control_request(priv, ifidx, set,
    +                                  set ? WLC_SET_VAR : WLC_GET_VAR, name,
    +                                  data, len);
    +}
    +
    +int bcmf_sdpcm_ioctl(FAR struct bcmf_dev_s *priv,
    +                     uint32_t ifidx, bool set, uint32_t cmd,
    +                     uint8_t *data, uint32_t *len)
    +{
    +   return bcmf_sdpcm_control_request(priv, ifidx, set, cmd, NULL, data, len);
     }
    \ No newline at end of file
    diff --git a/drivers/wireless/ieee80211/bcmf_sdpcm.h b/drivers/wireless/ieee80211/bcmf_sdpcm.h
    index 324970f2aa..1735482d26 100644
    --- a/drivers/wireless/ieee80211/bcmf_sdpcm.h
    +++ b/drivers/wireless/ieee80211/bcmf_sdpcm.h
    @@ -9,6 +9,10 @@ int bcmf_sdpcm_sendframe(FAR struct bcmf_dev_s *priv);
     
     int bcmf_sdpcm_iovar_request(FAR struct bcmf_dev_s *priv,
                                  uint32_t ifidx, bool set, char *name,
    -                             char *data, uint32_t *len);
    +                             uint8_t *data, uint32_t *len);
    +
    +int bcmf_sdpcm_ioctl(FAR struct bcmf_dev_s *priv,
    +                     uint32_t ifidx, bool set, uint32_t cmd,
    +                     uint8_t *data, uint32_t *len);
     
     #endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_SDPCM_H */
    \ No newline at end of file
    -- 
    GitLab
    
    
    From 1d4aee87a03aaf1a268c97d046a459e1d926382b Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Sat, 22 Apr 2017 10:33:06 -0600
    Subject: [PATCH 556/990] 6loWPAN: Separate MAC-related definitions from
     sixlowpan.h.  Put in ieee802154.h
    
    ---
     include/nuttx/net/ieee802154.h | 138 +++++++++++++++++++++++++++++++++
     include/nuttx/net/sixlowpan.h  |  68 +---------------
     2 files changed, 139 insertions(+), 67 deletions(-)
     create mode 100644 include/nuttx/net/ieee802154.h
    
    diff --git a/include/nuttx/net/ieee802154.h b/include/nuttx/net/ieee802154.h
    new file mode 100644
    index 0000000000..6132d3d02b
    --- /dev/null
    +++ b/include/nuttx/net/ieee802154.h
    @@ -0,0 +1,138 @@
    +/****************************************************************************
    + * include/nuttx/net/ieee802154.h
    + *
    + *   Copyright (C) 2017, Gregory Nutt, all rights reserved
    + *   Author: Gregory Nutt 
    + *
    + * Derives from Contiki:
    + *
    + *   Copyright (c) 2008, Swedish Institute of Computer Science.
    + *   All rights reserved.
    + *   Authors: Adam Dunkels 
    + *            Nicolas Tsiftes 
    + *            Niclas Finne 
    + *            Mathilde Durvy 
    + *            Julien Abeille 
    + *
    + * Redistribution and use in source and binary forms, with or without
    + * modification, are permitted provided that the following conditions
    + * are met:
    + *
    + * 1. Redistributions of source code must retain the above copyright
    + *    notice, this list of conditions and the following disclaimer.
    + * 2. Redistributions in binary form must reproduce the above copyright
    + *    notice, this list of conditions and the following disclaimer in the
    + *    documentation and/or other materials provided with the distribution.
    + * 3. Neither the name of the Institute 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 INSTITUTE 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 INSTITUTE 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_NET_IEEE802154_H
    +#define __INCLUDE_NUTTX_NET_IEEE802154_H
    +
    +/****************************************************************************
    + * Included Files
    + ****************************************************************************/
    +
    +#include 
    +
    +#include 
    +
    +#ifdef CONFIG_NET_6LOWPAN
    +
    +/****************************************************************************
    + * Pre-processor Definitions
    + ****************************************************************************/
    +
    +/* By default, a 2-byte Rime address is used for the IEEE802.15.4 MAC
    + * device's link  layer address.  If CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED
    + * is selected, then an 8-byte Rime address will be used.
    + */
    +
    +#ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED
    +#  define NET_6LOWPAN_RIMEADDR_SIZE 8
    +#else
    +#  define NET_6LOWPAN_RIMEADDR_SIZE 2
    +#endif
    +
    +/* Frame format definitions *************************************************/
    +/* These are some definitions of element values used in the FCF.  See the
    + * IEEE802.15.4 spec for details.
    + */
    +
    +#define FRAME802154_FRAMETYPE_SHIFT      (0)  /* Bits 0-2: Frame type */
    +#define FRAME802154_FRAMETYPE_MASK       (7 << FRAME802154_FRAMETYPE_SHIFT)
    +#define FRAME802154_SECENABLED_SHIFT     (3)  /* Bit 3: Security enabled */
    +#define FRAME802154_FRAMEPENDING_SHIFT   (4)  /* Bit 4: Frame pending */
    +#define FRAME802154_ACKREQUEST_SHIFT     (5)  /* Bit 5: ACK request */
    +#define FRAME802154_PANIDCOMP_SHIFT      (6)  /* Bit 6: PANID compression */
    +                                              /* Bits 7-9: Reserved */
    +#define FRAME802154_DSTADDR_SHIFT        (2)  /* Bits 10-11: Dest address mode */
    +#define FRAME802154_DSTADDR_MASK         (3 << FRAME802154_DSTADDR_SHIFT)
    +#define FRAME802154_VERSION_SHIFT        (4)  /* Bit 12-13: Frame version */
    +#define FRAME802154_VERSION_MASK         (3 << FRAME802154_VERSION_SHIFT)
    +#define FRAME802154_SRCADDR_SHIFT        (6)  /* Bits 14-15: Source address mode */
    +#define FRAME802154_SRCADDR_MASK         (3 << FRAME802154_SRCADDR_SHIFT)
    +
    +/* Unshifted values for use in struct frame802154_fcf_s */
    +
    +#define FRAME802154_BEACONFRAME          (0)
    +#define FRAME802154_DATAFRAME            (1)
    +#define FRAME802154_ACKFRAME             (2)
    +#define FRAME802154_CMDFRAME             (3)
    +
    +#define FRAME802154_BEACONREQ            (7)
    +
    +#define FRAME802154_IEEERESERVED         (0)
    +#define FRAME802154_NOADDR               (0)  /* Only valid for ACK or Beacon frames */
    +#define FRAME802154_SHORTADDRMODE        (2)
    +#define FRAME802154_LONGADDRMODE         (3)
    +
    +#define FRAME802154_NOBEACONS            0x0f
    +
    +#define FRAME802154_BROADCASTADDR        0xffff
    +#define FRAME802154_BROADCASTPANDID      0xffff
    +
    +#define FRAME802154_IEEE802154_2003      (0)
    +#define FRAME802154_IEEE802154_2006      (1)
    +
    +#define FRAME802154_SECURITY_LEVEL_NONE  (0)
    +#define FRAME802154_SECURITY_LEVEL_128   (3)
    +
    +/* This maximum size of an IEEE802.15.4 frame.  Certain, non-standard
    + * devices may exceed this value, however.
    + */
    +
    +#define SIXLOWPAN_MAC_STDFRAME 127
    +
    +/****************************************************************************
    + * Public Types
    + ****************************************************************************/
    +
    +/* Rime address representation */
    +
    +struct rimeaddr_s
    +{
    +  uint8_t u8[NET_6LOWPAN_RIMEADDR_SIZE];
    +};
    +
    +/****************************************************************************
    + * Public Function Prototypes
    + ****************************************************************************/
    +
    +#endif /* CONFIG_NET_6LOWPAN */
    +#endif /* __INCLUDE_NUTTX_NET_IEEE802154_H */
    diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h
    index 855948b4e8..63fa39283a 100644
    --- a/include/nuttx/net/sixlowpan.h
    +++ b/include/nuttx/net/sixlowpan.h
    @@ -56,6 +56,7 @@
     #include 
     #include 
     #include 
    +#include 
     
     #ifdef CONFIG_NET_6LOWPAN
     
    @@ -63,17 +64,6 @@
      * Pre-processor Definitions
      ****************************************************************************/
     
    -/* By default, a 2-byte Rime address is used for the IEEE802.15.4 MAC
    - * device's link  layer address.  If CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED
    - * is selected, then an 8-byte Rime address will be used.
    - */
    -
    -#ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED
    -#  define NET_6LOWPAN_RIMEADDR_SIZE 8
    -#else
    -#  define NET_6LOWPAN_RIMEADDR_SIZE 2
    -#endif
    -
     /* Frame format definitions *************************************************/
     /* Fragment header.
      *
    @@ -108,49 +98,6 @@
     #define RIME_HC1_HC_UDP_PORTS            4  /* 8 bit */
     #define RIME_HC1_HC_UDP_CHKSUM           5  /* 16 bit */
     
    -/* These are some definitions of element values used in the FCF.  See the
    - * IEEE802.15.4 spec for details.
    - */
    -
    -#define FRAME802154_FRAMETYPE_SHIFT      (0)  /* Bits 0-2: Frame type */
    -#define FRAME802154_FRAMETYPE_MASK       (7 << FRAME802154_FRAMETYPE_SHIFT)
    -#define FRAME802154_SECENABLED_SHIFT     (3)  /* Bit 3: Security enabled */
    -#define FRAME802154_FRAMEPENDING_SHIFT   (4)  /* Bit 4: Frame pending */
    -#define FRAME802154_ACKREQUEST_SHIFT     (5)  /* Bit 5: ACK request */
    -#define FRAME802154_PANIDCOMP_SHIFT      (6)  /* Bit 6: PANID compression */
    -                                              /* Bits 7-9: Reserved */
    -#define FRAME802154_DSTADDR_SHIFT        (2)  /* Bits 10-11: Dest address mode */
    -#define FRAME802154_DSTADDR_MASK         (3 << FRAME802154_DSTADDR_SHIFT)
    -#define FRAME802154_VERSION_SHIFT        (4)  /* Bit 12-13: Frame version */
    -#define FRAME802154_VERSION_MASK         (3 << FRAME802154_VERSION_SHIFT)
    -#define FRAME802154_SRCADDR_SHIFT        (6)  /* Bits 14-15: Source address mode */
    -#define FRAME802154_SRCADDR_MASK         (3 << FRAME802154_SRCADDR_SHIFT)
    -
    -/* Unshifted values for use in struct frame802154_fcf_s */
    -
    -#define FRAME802154_BEACONFRAME          (0)
    -#define FRAME802154_DATAFRAME            (1)
    -#define FRAME802154_ACKFRAME             (2)
    -#define FRAME802154_CMDFRAME             (3)
    -
    -#define FRAME802154_BEACONREQ            (7)
    -
    -#define FRAME802154_IEEERESERVED         (0)
    -#define FRAME802154_NOADDR               (0)  /* Only valid for ACK or Beacon frames */
    -#define FRAME802154_SHORTADDRMODE        (2)
    -#define FRAME802154_LONGADDRMODE         (3)
    -
    -#define FRAME802154_NOBEACONS            0x0f
    -
    -#define FRAME802154_BROADCASTADDR        0xffff
    -#define FRAME802154_BROADCASTPANDID      0xffff
    -
    -#define FRAME802154_IEEE802154_2003      (0)
    -#define FRAME802154_IEEE802154_2006      (1)
    -
    -#define FRAME802154_SECURITY_LEVEL_NONE  (0)
    -#define FRAME802154_SECURITY_LEVEL_128   (3)
    -
     /* Min and Max compressible UDP ports - HC06 */
     
     #define SIXLOWPAN_UDP_4_BIT_PORT_MIN     0xf0b0
    @@ -261,12 +208,6 @@
     #define SIXLOWPAN_FRAG1_HDR_LEN          4
     #define SIXLOWPAN_FRAGN_HDR_LEN          5
     
    -/* This maximum size of an IEEE802.15.4 frame.  Certain, non-standard
    - * devices may exceed this value, however.
    - */
    -
    -#define SIXLOWPAN_MAC_STDFRAME 127
    -
     /* Address compressibility test macros **************************************/
     
     /* Check whether we can compress the IID in address 'a' to 16 bits.  This is
    @@ -389,13 +330,6 @@
      * Public Types
      ****************************************************************************/
     
    -/* Rime address representation */
    -
    -struct rimeaddr_s
    -{
    -  uint8_t u8[NET_6LOWPAN_RIMEADDR_SIZE];
    -};
    -
     /* The device structure for IEEE802.15.4 MAC network device differs from the
      * standard Ethernet MAC device structure.  The main reason for this
      * difference is that fragmentation must be supported.
    -- 
    GitLab
    
    
    From 79256573e1c84670ec015b8760601a5e75e04f7c Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Sat, 22 Apr 2017 11:10:30 -0600
    Subject: [PATCH 557/990] net: network drver now retains Ethernet MAC address
     in a union so that other link layer addresses may be used in a MULTILINK
     environment.
    
    ---
     arch/arm/src/c5471/c5471_ethernet.c      |  2 +-
     arch/arm/src/kinetis/kinetis_enet.c      |  4 ++--
     arch/arm/src/lpc17xx/lpc17_ethernet.c    | 12 +++++-----
     arch/arm/src/lpc43xx/lpc43_ethernet.c    | 18 +++++++-------
     arch/arm/src/sam34/sam_emac.c            | 18 +++++++-------
     arch/arm/src/sama5/sam_emaca.c           | 18 +++++++-------
     arch/arm/src/sama5/sam_emacb.c           | 18 +++++++-------
     arch/arm/src/sama5/sam_gmac.c            | 18 +++++++-------
     arch/arm/src/samv7/sam_emac.c            | 26 ++++++++++----------
     arch/arm/src/stm32/stm32_eth.c           | 18 +++++++-------
     arch/arm/src/stm32f7/stm32_ethernet.c    | 18 +++++++-------
     arch/arm/src/tiva/lm3s_ethernet.c        | 16 ++++++-------
     arch/arm/src/tiva/tm4c_ethernet.c        | 20 ++++++++--------
     arch/hc/src/m9s12/m9s12_ethernet.c       |  2 +-
     arch/mips/src/pic32mx/pic32mx-ethernet.c | 24 +++++++++----------
     arch/mips/src/pic32mz/pic32mz-ethernet.c | 30 ++++++++++++------------
     arch/misoc/src/common/misoc_net.c        |  4 ++--
     arch/sim/src/up_netdriver.c              |  4 ++--
     arch/z80/src/ez80/ez80_emac.c            | 20 ++++++++--------
     drivers/net/cs89x0.c                     |  2 +-
     drivers/net/dm90x0.c                     |  2 +-
     drivers/net/enc28j60.c                   | 12 +++++-----
     drivers/net/encx24j600.c                 |  6 ++---
     drivers/net/ftmac100.c                   |  8 +++----
     drivers/net/skeleton.c                   |  4 ++--
     drivers/net/tun.c                        |  2 +-
     include/nuttx/net/netdev.h               | 11 +++++++--
     net/arp/arp_arpin.c                      |  4 ++--
     net/arp/arp_format.c                     |  4 ++--
     net/arp/arp_out.c                        |  2 +-
     net/icmpv6/icmpv6_advertise.c            |  4 ++--
     net/icmpv6/icmpv6_autoconfig.c           |  2 +-
     net/icmpv6/icmpv6_radvertise.c           |  4 ++--
     net/icmpv6/icmpv6_rsolicit.c             |  4 ++--
     net/icmpv6/icmpv6_solicit.c              |  4 ++--
     net/neighbor/neighbor_ethernet_out.c     |  2 +-
     net/netdev/netdev_ioctl.c                |  4 ++--
     net/netdev/netdev_register.c             |  6 ++---
     net/procfs/netdev_statistics.c           |  4 ++--
     net/socket/bind.c                        |  2 +-
     40 files changed, 195 insertions(+), 188 deletions(-)
    
    diff --git a/arch/arm/src/c5471/c5471_ethernet.c b/arch/arm/src/c5471/c5471_ethernet.c
    index 03ddbe3383..b98fd6ecac 100644
    --- a/arch/arm/src/c5471/c5471_ethernet.c
    +++ b/arch/arm/src/c5471/c5471_ethernet.c
    @@ -2364,7 +2364,7 @@ static void c5471_reset(struct c5471_driver_s *priv)
     static void c5471_macassign(struct c5471_driver_s *priv)
     {
       struct net_driver_s *dev = &priv->c_dev;
    -  uint8_t *mptr = dev->d_mac.ether_addr_octet;
    +  uint8_t *mptr = dev->d_mac.ether.ether_addr_octet;
       register uint32_t tmp;
     
       ninfo("MAC: %0x:%0x:%0x:%0x:%0x:%0x\n",
    diff --git a/arch/arm/src/kinetis/kinetis_enet.c b/arch/arm/src/kinetis/kinetis_enet.c
    index 37910fc9b9..1a13ab856a 100644
    --- a/arch/arm/src/kinetis/kinetis_enet.c
    +++ b/arch/arm/src/kinetis/kinetis_enet.c
    @@ -1125,7 +1125,7 @@ static int kinetis_ifup(struct net_driver_s *dev)
     {
       FAR struct kinetis_driver_s *priv =
         (FAR struct kinetis_driver_s *)dev->d_private;
    -  uint8_t *mac = dev->d_mac.ether_addr_octet;
    +  uint8_t *mac = dev->d_mac.ether.ether_addr_octet;
       uint32_t regval;
       int ret;
     
    @@ -2144,7 +2144,7 @@ int kinetis_netinitialize(int intf)
     
       uidl   = getreg32(KINETIS_SIM_UIDL);
       uidml  = getreg32(KINETIS_SIM_UIDML);
    -  mac    = priv->dev.d_mac.ether_addr_octet;
    +  mac    = priv->dev.d_mac.ether.ether_addr_octet;
     
       uidml |= 0x00000200;
       uidml &= 0x0000FEFF;
    diff --git a/arch/arm/src/lpc17xx/lpc17_ethernet.c b/arch/arm/src/lpc17xx/lpc17_ethernet.c
    index 42e046aea1..dd1c05d0d1 100644
    --- a/arch/arm/src/lpc17xx/lpc17_ethernet.c
    +++ b/arch/arm/src/lpc17xx/lpc17_ethernet.c
    @@ -1591,16 +1591,16 @@ static int lpc17_ifup(struct net_driver_s *dev)
     
       /* Configure the MAC station address */
     
    -  regval = (uint32_t)priv->lp_dev.d_mac.ether_addr_octet[5] << 8 |
    -           (uint32_t)priv->lp_dev.d_mac.ether_addr_octet[4];
    +  regval = (uint32_t)priv->lp_dev.d_mac.ether.ether_addr_octet[5] << 8 |
    +           (uint32_t)priv->lp_dev.d_mac.ether.ether_addr_octet[4];
       lpc17_putreg(regval, LPC17_ETH_SA0);
     
    -  regval = (uint32_t)priv->lp_dev.d_mac.ether_addr_octet[3] << 8 |
    -           (uint32_t)priv->lp_dev.d_mac.ether_addr_octet[2];
    +  regval = (uint32_t)priv->lp_dev.d_mac.ether.ether_addr_octet[3] << 8 |
    +           (uint32_t)priv->lp_dev.d_mac.ether.ether_addr_octet[2];
       lpc17_putreg(regval, LPC17_ETH_SA1);
     
    -  regval = (uint32_t)priv->lp_dev.d_mac.ether_addr_octet[1] << 8 |
    -           (uint32_t)priv->lp_dev.d_mac.ether_addr_octet[0];
    +  regval = (uint32_t)priv->lp_dev.d_mac.ether.ether_addr_octet[1] << 8 |
    +           (uint32_t)priv->lp_dev.d_mac.ether.ether_addr_octet[0];
       lpc17_putreg(regval, LPC17_ETH_SA2);
     
     #ifdef CONFIG_NET_ICMPv6
    diff --git a/arch/arm/src/lpc43xx/lpc43_ethernet.c b/arch/arm/src/lpc43xx/lpc43_ethernet.c
    index 171f20ee74..2c564aa5ff 100644
    --- a/arch/arm/src/lpc43xx/lpc43_ethernet.c
    +++ b/arch/arm/src/lpc43xx/lpc43_ethernet.c
    @@ -3535,22 +3535,22 @@ static void lpc43_macaddress(FAR struct lpc43_ethmac_s *priv)
     
       ninfo("%s MAC: %02x:%02x:%02x:%02x:%02x:%02x\n",
             dev->d_ifname,
    -        dev->d_mac.ether_addr_octet[0], dev->d_mac.ether_addr_octet[1],
    -        dev->d_mac.ether_addr_octet[2], dev->d_mac.ether_addr_octet[3],
    -        dev->d_mac.ether_addr_octet[4], dev->d_mac.ether_addr_octet[5]);
    +        dev->d_mac.ether.ether_addr_octet[0], dev->d_mac.ether.ether_addr_octet[1],
    +        dev->d_mac.ether.ether_addr_octet[2], dev->d_mac.ether.ether_addr_octet[3],
    +        dev->d_mac.ether.ether_addr_octet[4], dev->d_mac.ether.ether_addr_octet[5]);
     
       /* Set the MAC address high register */
     
    -  regval = ((uint32_t)dev->d_mac.ether_addr_octet[5] << 8) |
    -            (uint32_t)dev->d_mac.ether_addr_octet[4];
    +  regval = ((uint32_t)dev->d_mac.ether.ether_addr_octet[5] << 8) |
    +            (uint32_t)dev->d_mac.ether.ether_addr_octet[4];
       lpc43_putreg(regval, LPC43_ETH_MACA0HI);
     
       /* Set the MAC address low register */
     
    -  regval = ((uint32_t)dev->d_mac.ether_addr_octet[3] << 24) |
    -           ((uint32_t)dev->d_mac.ether_addr_octet[2] << 16) |
    -           ((uint32_t)dev->d_mac.ether_addr_octet[1] <<  8) |
    -            (uint32_t)dev->d_mac.ether_addr_octet[0];
    +  regval = ((uint32_t)dev->d_mac.ether.ether_addr_octet[3] << 24) |
    +           ((uint32_t)dev->d_mac.ether.ether_addr_octet[2] << 16) |
    +           ((uint32_t)dev->d_mac.ether.ether_addr_octet[1] <<  8) |
    +            (uint32_t)dev->d_mac.ether.ether_addr_octet[0];
       lpc43_putreg(regval, LPC43_ETH_MACA0LO);
     }
     
    diff --git a/arch/arm/src/sam34/sam_emac.c b/arch/arm/src/sam34/sam_emac.c
    index f1db43f0ca..7e5839cc19 100644
    --- a/arch/arm/src/sam34/sam_emac.c
    +++ b/arch/arm/src/sam34/sam_emac.c
    @@ -3416,20 +3416,20 @@ static void sam_macaddress(struct sam_emac_s *priv)
     
       ninfo("%s MAC: %02x:%02x:%02x:%02x:%02x:%02x\n",
             dev->d_ifname,
    -        dev->d_mac.ether_addr_octet[0], dev->d_mac.ether_addr_octet[1],
    -        dev->d_mac.ether_addr_octet[2], dev->d_mac.ether_addr_octet[3],
    -        dev->d_mac.ether_addr_octet[4], dev->d_mac.ether_addr_octet[5]);
    +        dev->d_mac.ether.ether_addr_octet[0], dev->d_mac.ether.ether_addr_octet[1],
    +        dev->d_mac.ether.ether_addr_octet[2], dev->d_mac.ether.ether_addr_octet[3],
    +        dev->d_mac.ether.ether_addr_octet[4], dev->d_mac.ether.ether_addr_octet[5]);
     
       /* Set the MAC address */
     
    -  regval = (uint32_t)dev->d_mac.ether_addr_octet[0] |
    -           (uint32_t)dev->d_mac.ether_addr_octet[1] << 8 |
    -           (uint32_t)dev->d_mac.ether_addr_octet[2] << 16 |
    -           (uint32_t)dev->d_mac.ether_addr_octet[3] << 24;
    +  regval = (uint32_t)dev->d_mac.ether.ether_addr_octet[0] |
    +           (uint32_t)dev->d_mac.ether.ether_addr_octet[1] << 8 |
    +           (uint32_t)dev->d_mac.ether.ether_addr_octet[2] << 16 |
    +           (uint32_t)dev->d_mac.ether.ether_addr_octet[3] << 24;
       sam_putreg(priv, SAM_EMAC_SAB1, regval);
     
    -  regval = (uint32_t)dev->d_mac.ether_addr_octet[4] |
    -           (uint32_t)dev->d_mac.ether_addr_octet[5] << 8;
    +  regval = (uint32_t)dev->d_mac.ether.ether_addr_octet[4] |
    +           (uint32_t)dev->d_mac.ether.ether_addr_octet[5] << 8;
       sam_putreg(priv, SAM_EMAC_SAT1, regval);
     }
     
    diff --git a/arch/arm/src/sama5/sam_emaca.c b/arch/arm/src/sama5/sam_emaca.c
    index 09cba2280f..494fb7a6e5 100644
    --- a/arch/arm/src/sama5/sam_emaca.c
    +++ b/arch/arm/src/sama5/sam_emaca.c
    @@ -3458,20 +3458,20 @@ static void sam_macaddress(struct sam_emac_s *priv)
     
       ninfo("%s MAC: %02x:%02x:%02x:%02x:%02x:%02x\n",
             dev->d_ifname,
    -        dev->d_mac.ether_addr_octet[0], dev->d_mac.ether_addr_octet[1],
    -        dev->d_mac.ether_addr_octet[2], dev->d_mac.ether_addr_octet[3],
    -        dev->d_mac.ether_addr_octet[4], dev->d_mac.ether_addr_octet[5]);
    +        dev->d_mac.ether.ether_addr_octet[0], dev->d_mac.ether.ether_addr_octet[1],
    +        dev->d_mac.ether.ether_addr_octet[2], dev->d_mac.ether.ether_addr_octet[3],
    +        dev->d_mac.ether.ether_addr_octet[4], dev->d_mac.ether.ether_addr_octet[5]);
     
       /* Set the MAC address */
     
    -  regval = (uint32_t)dev->d_mac.ether_addr_octet[0] |
    -           (uint32_t)dev->d_mac.ether_addr_octet[1] << 8 |
    -           (uint32_t)dev->d_mac.ether_addr_octet[2] << 16 |
    -           (uint32_t)dev->d_mac.ether_addr_octet[3] << 24;
    +  regval = (uint32_t)dev->d_mac.ether.ether_addr_octet[0] |
    +           (uint32_t)dev->d_mac.ether.ether_addr_octet[1] << 8 |
    +           (uint32_t)dev->d_mac.ether.ether_addr_octet[2] << 16 |
    +           (uint32_t)dev->d_mac.ether.ether_addr_octet[3] << 24;
       sam_putreg(priv, SAM_EMAC_SA1B, regval);
     
    -  regval = (uint32_t)dev->d_mac.ether_addr_octet[4] |
    -           (uint32_t)dev->d_mac.ether_addr_octet[5] << 8;
    +  regval = (uint32_t)dev->d_mac.ether.ether_addr_octet[4] |
    +           (uint32_t)dev->d_mac.ether.ether_addr_octet[5] << 8;
       sam_putreg(priv, SAM_EMAC_SA1T, regval);
     }
     
    diff --git a/arch/arm/src/sama5/sam_emacb.c b/arch/arm/src/sama5/sam_emacb.c
    index 10c120cc47..2f4fcbf693 100644
    --- a/arch/arm/src/sama5/sam_emacb.c
    +++ b/arch/arm/src/sama5/sam_emacb.c
    @@ -4106,20 +4106,20 @@ static void sam_macaddress(struct sam_emac_s *priv)
     
       ninfo("%s MAC: %02x:%02x:%02x:%02x:%02x:%02x\n",
             dev->d_ifname,
    -        dev->d_mac.ether_addr_octet[0], dev->d_mac.ether_addr_octet[1],
    -        dev->d_mac.ether_addr_octet[2], dev->d_mac.ether_addr_octet[3],
    -        dev->d_mac.ether_addr_octet[4], dev->d_mac.ether_addr_octet[5]);
    +        dev->d_mac.ether.ether_addr_octet[0], dev->d_mac.ether.ether_addr_octet[1],
    +        dev->d_mac.ether.ether_addr_octet[2], dev->d_mac.ether.ether_addr_octet[3],
    +        dev->d_mac.ether.ether_addr_octet[4], dev->d_mac.ether.ether_addr_octet[5]);
     
       /* Set the MAC address */
     
    -  regval = (uint32_t)dev->d_mac.ether_addr_octet[0] |
    -           (uint32_t)dev->d_mac.ether_addr_octet[1] << 8 |
    -           (uint32_t)dev->d_mac.ether_addr_octet[2] << 16 |
    -           (uint32_t)dev->d_mac.ether_addr_octet[3] << 24;
    +  regval = (uint32_t)dev->d_mac.ether.ether_addr_octet[0] |
    +           (uint32_t)dev->d_mac.ether.ether_addr_octet[1] << 8 |
    +           (uint32_t)dev->d_mac.ether.ether_addr_octet[2] << 16 |
    +           (uint32_t)dev->d_mac.ether.ether_addr_octet[3] << 24;
       sam_putreg(priv, SAM_EMAC_SAB1_OFFSET, regval);
     
    -  regval = (uint32_t)dev->d_mac.ether_addr_octet[4] |
    -           (uint32_t)dev->d_mac.ether_addr_octet[5] << 8;
    +  regval = (uint32_t)dev->d_mac.ether.ether_addr_octet[4] |
    +           (uint32_t)dev->d_mac.ether.ether_addr_octet[5] << 8;
       sam_putreg(priv, SAM_EMAC_SAT1_OFFSET, regval);
     }
     
    diff --git a/arch/arm/src/sama5/sam_gmac.c b/arch/arm/src/sama5/sam_gmac.c
    index 0988f8aedb..29d42258de 100644
    --- a/arch/arm/src/sama5/sam_gmac.c
    +++ b/arch/arm/src/sama5/sam_gmac.c
    @@ -3506,20 +3506,20 @@ static void sam_macaddress(struct sam_gmac_s *priv)
     
       ninfo("%s MAC: %02x:%02x:%02x:%02x:%02x:%02x\n",
             dev->d_ifname,
    -        dev->d_mac.ether_addr_octet[0], dev->d_mac.ether_addr_octet[1],
    -        dev->d_mac.ether_addr_octet[2], dev->d_mac.ether_addr_octet[3],
    -        dev->d_mac.ether_addr_octet[4], dev->d_mac.ether_addr_octet[5]);
    +        dev->d_mac.ether.ether_addr_octet[0], dev->d_mac.ether.ether_addr_octet[1],
    +        dev->d_mac.ether.ether_addr_octet[2], dev->d_mac.ether.ether_addr_octet[3],
    +        dev->d_mac.ether.ether_addr_octet[4], dev->d_mac.ether.ether_addr_octet[5]);
     
       /* Set the MAC address */
     
    -  regval = (uint32_t)dev->d_mac.ether_addr_octet[0] |
    -           (uint32_t)dev->d_mac.ether_addr_octet[1] << 8 |
    -           (uint32_t)dev->d_mac.ether_addr_octet[2] << 16 |
    -           (uint32_t)dev->d_mac.ether_addr_octet[3] << 24;
    +  regval = (uint32_t)dev->d_mac.ether.ether_addr_octet[0] |
    +           (uint32_t)dev->d_mac.ether.ether_addr_octet[1] << 8 |
    +           (uint32_t)dev->d_mac.ether.ether_addr_octet[2] << 16 |
    +           (uint32_t)dev->d_mac.ether.ether_addr_octet[3] << 24;
       sam_putreg(priv, SAM_GMAC_SAB1, regval);
     
    -  regval = (uint32_t)dev->d_mac.ether_addr_octet[4] |
    -           (uint32_t)dev->d_mac.ether_addr_octet[5] << 8;
    +  regval = (uint32_t)dev->d_mac.ether.ether_addr_octet[4] |
    +           (uint32_t)dev->d_mac.ether.ether_addr_octet[5] << 8;
       sam_putreg(priv, SAM_GMAC_SAT1, regval);
     }
     
    diff --git a/arch/arm/src/samv7/sam_emac.c b/arch/arm/src/samv7/sam_emac.c
    index 4760577b8b..5bfb2f4a58 100644
    --- a/arch/arm/src/samv7/sam_emac.c
    +++ b/arch/arm/src/samv7/sam_emac.c
    @@ -4668,20 +4668,20 @@ static void sam_macaddress(struct sam_emac_s *priv)
     
       ninfo("%s MAC: %02x:%02x:%02x:%02x:%02x:%02x\n",
             dev->d_ifname,
    -        dev->d_mac.ether_addr_octet[0], dev->d_mac.ether_addr_octet[1],
    -        dev->d_mac.ether_addr_octet[2], dev->d_mac.ether_addr_octet[3],
    -        dev->d_mac.ether_addr_octet[4], dev->d_mac.ether_addr_octet[5]);
    +        dev->d_mac.ether.ether_addr_octet[0], dev->d_mac.ether.ether_addr_octet[1],
    +        dev->d_mac.ether.ether_addr_octet[2], dev->d_mac.ether.ether_addr_octet[3],
    +        dev->d_mac.ether.ether_addr_octet[4], dev->d_mac.ether.ether_addr_octet[5]);
     
       /* Set the MAC address */
     
    -  regval = (uint32_t)dev->d_mac.ether_addr_octet[0] |
    -           (uint32_t)dev->d_mac.ether_addr_octet[1] << 8 |
    -           (uint32_t)dev->d_mac.ether_addr_octet[2] << 16 |
    -           (uint32_t)dev->d_mac.ether_addr_octet[3] << 24;
    +  regval = (uint32_t)dev->d_mac.ether.ether_addr_octet[0] |
    +           (uint32_t)dev->d_mac.ether.ether_addr_octet[1] << 8 |
    +           (uint32_t)dev->d_mac.ether.ether_addr_octet[2] << 16 |
    +           (uint32_t)dev->d_mac.ether.ether_addr_octet[3] << 24;
       sam_putreg(priv, SAM_EMAC_SAB1_OFFSET, regval);
     
    -  regval = (uint32_t)dev->d_mac.ether_addr_octet[4] |
    -           (uint32_t)dev->d_mac.ether_addr_octet[5] << 8;
    +  regval = (uint32_t)dev->d_mac.ether.ether_addr_octet[4] |
    +           (uint32_t)dev->d_mac.ether.ether_addr_octet[5] << 8;
       sam_putreg(priv, SAM_EMAC_SAT1_OFFSET, regval);
     }
     
    @@ -5160,13 +5160,13 @@ int sam_emac_setmacaddr(int intf, uint8_t mac[6])
       /* Copy the MAC address into the device structure */
     
       dev = &priv->dev;
    -  memcpy(dev->d_mac.ether_addr_octet, mac, 6);
    +  memcpy(dev->d_mac.ether.ether_addr_octet, mac, 6);
     
       ninfo("%s MAC: %02x:%02x:%02x:%02x:%02x:%02x\n",
             dev->d_ifname,
    -        dev->d_mac.ether_addr_octet[0], dev->d_mac.ether_addr_octet[1],
    -        dev->d_mac.ether_addr_octet[2], dev->d_mac.ether_addr_octet[3],
    -        dev->d_mac.ether_addr_octet[4], dev->d_mac.ether_addr_octet[5]);
    +        dev->d_mac.ether.ether_addr_octet[0], dev->d_mac.ether.ether_addr_octet[1],
    +        dev->d_mac.ether.ether_addr_octet[2], dev->d_mac.ether.ether_addr_octet[3],
    +        dev->d_mac.ether.ether_addr_octet[4], dev->d_mac.ether.ether_addr_octet[5]);
     
       return OK;
     }
    diff --git a/arch/arm/src/stm32/stm32_eth.c b/arch/arm/src/stm32/stm32_eth.c
    index 0b1bbd247c..8b38985f15 100644
    --- a/arch/arm/src/stm32/stm32_eth.c
    +++ b/arch/arm/src/stm32/stm32_eth.c
    @@ -3674,22 +3674,22 @@ static void stm32_macaddress(FAR struct stm32_ethmac_s *priv)
     
       ninfo("%s MAC: %02x:%02x:%02x:%02x:%02x:%02x\n",
             dev->d_ifname,
    -        dev->d_mac.ether_addr_octet[0], dev->d_mac.ether_addr_octet[1],
    -        dev->d_mac.ether_addr_octet[2], dev->d_mac.ether_addr_octet[3],
    -        dev->d_mac.ether_addr_octet[4], dev->d_mac.ether_addr_octet[5]);
    +        dev->d_mac.ether.ether_addr_octet[0], dev->d_mac.ether.ether_addr_octet[1],
    +        dev->d_mac.ether.ether_addr_octet[2], dev->d_mac.ether.ether_addr_octet[3],
    +        dev->d_mac.ether.ether_addr_octet[4], dev->d_mac.ether.ether_addr_octet[5]);
     
       /* Set the MAC address high register */
     
    -  regval = ((uint32_t)dev->d_mac.ether_addr_octet[5] << 8) |
    -            (uint32_t)dev->d_mac.ether_addr_octet[4];
    +  regval = ((uint32_t)dev->d_mac.ether.ether_addr_octet[5] << 8) |
    +            (uint32_t)dev->d_mac.ether.ether_addr_octet[4];
       stm32_putreg(regval, STM32_ETH_MACA0HR);
     
       /* Set the MAC address low register */
     
    -  regval = ((uint32_t)dev->d_mac.ether_addr_octet[3] << 24) |
    -           ((uint32_t)dev->d_mac.ether_addr_octet[2] << 16) |
    -           ((uint32_t)dev->d_mac.ether_addr_octet[1] <<  8) |
    -            (uint32_t)dev->d_mac.ether_addr_octet[0];
    +  regval = ((uint32_t)dev->d_mac.ether.ether_addr_octet[3] << 24) |
    +           ((uint32_t)dev->d_mac.ether.ether_addr_octet[2] << 16) |
    +           ((uint32_t)dev->d_mac.ether.ether_addr_octet[1] <<  8) |
    +            (uint32_t)dev->d_mac.ether.ether_addr_octet[0];
       stm32_putreg(regval, STM32_ETH_MACA0LR);
     }
     
    diff --git a/arch/arm/src/stm32f7/stm32_ethernet.c b/arch/arm/src/stm32f7/stm32_ethernet.c
    index 0885c086cd..2ac01c649e 100644
    --- a/arch/arm/src/stm32f7/stm32_ethernet.c
    +++ b/arch/arm/src/stm32f7/stm32_ethernet.c
    @@ -3780,22 +3780,22 @@ static void stm32_macaddress(struct stm32_ethmac_s *priv)
     
       ninfo("%s MAC: %02x:%02x:%02x:%02x:%02x:%02x\n",
             dev->d_ifname,
    -        dev->d_mac.ether_addr_octet[0], dev->d_mac.ether_addr_octet[1],
    -        dev->d_mac.ether_addr_octet[2], dev->d_mac.ether_addr_octet[3],
    -        dev->d_mac.ether_addr_octet[4], dev->d_mac.ether_addr_octet[5]);
    +        dev->d_mac.ether.ether_addr_octet[0], dev->d_mac.ether.ether_addr_octet[1],
    +        dev->d_mac.ether.ether_addr_octet[2], dev->d_mac.ether.ether_addr_octet[3],
    +        dev->d_mac.ether.ether_addr_octet[4], dev->d_mac.ether.ether_addr_octet[5]);
     
       /* Set the MAC address high register */
     
    -  regval = ((uint32_t)dev->d_mac.ether_addr_octet[5] << 8) |
    -            (uint32_t)dev->d_mac.ether_addr_octet[4];
    +  regval = ((uint32_t)dev->d_mac.ether.ether_addr_octet[5] << 8) |
    +            (uint32_t)dev->d_mac.ether.ether_addr_octet[4];
       stm32_putreg(regval, STM32_ETH_MACA0HR);
     
       /* Set the MAC address low register */
     
    -  regval = ((uint32_t)dev->d_mac.ether_addr_octet[3] << 24) |
    -           ((uint32_t)dev->d_mac.ether_addr_octet[2] << 16) |
    -           ((uint32_t)dev->d_mac.ether_addr_octet[1] <<  8) |
    -            (uint32_t)dev->d_mac.ether_addr_octet[0];
    +  regval = ((uint32_t)dev->d_mac.ether.ether_addr_octet[3] << 24) |
    +           ((uint32_t)dev->d_mac.ether.ether_addr_octet[2] << 16) |
    +           ((uint32_t)dev->d_mac.ether.ether_addr_octet[1] <<  8) |
    +            (uint32_t)dev->d_mac.ether.ether_addr_octet[0];
       stm32_putreg(regval, STM32_ETH_MACA0LR);
     }
     
    diff --git a/arch/arm/src/tiva/lm3s_ethernet.c b/arch/arm/src/tiva/lm3s_ethernet.c
    index acfa6c7c2e..885f8cc4d6 100644
    --- a/arch/arm/src/tiva/lm3s_ethernet.c
    +++ b/arch/arm/src/tiva/lm3s_ethernet.c
    @@ -1389,14 +1389,14 @@ static int tiva_ifup(struct net_driver_s *dev)
     
       /* Program the hardware with it's MAC address (for filtering) */
     
    -  regval = (uint32_t)priv->ld_dev.d_mac.ether_addr_octet[3] << 24 |
    -           (uint32_t)priv->ld_dev.d_mac.ether_addr_octet[2] << 16 |
    -           (uint32_t)priv->ld_dev.d_mac.ether_addr_octet[1] << 8 |
    -           (uint32_t)priv->ld_dev.d_mac.ether_addr_octet[0];
    +  regval = (uint32_t)priv->ld_dev.d_mac.ether.ether_addr_octet[3] << 24 |
    +           (uint32_t)priv->ld_dev.d_mac.ether.ether_addr_octet[2] << 16 |
    +           (uint32_t)priv->ld_dev.d_mac.ether.ether_addr_octet[1] << 8 |
    +           (uint32_t)priv->ld_dev.d_mac.ether.ether_addr_octet[0];
       tiva_ethout(priv, TIVA_MAC_IA0_OFFSET, regval);
     
    -  regval = (uint32_t)priv->ld_dev.d_mac.ether_addr_octet[5] << 8 |
    -           (uint32_t)priv->ld_dev.d_mac.ether_addr_octet[4];
    +  regval = (uint32_t)priv->ld_dev.d_mac.ether.ether_addr_octet[5] << 8 |
    +           (uint32_t)priv->ld_dev.d_mac.ether.ether_addr_octet[4];
       tiva_ethout(priv, TIVA_MAC_IA1_OFFSET, regval);
     
       /* Set and activate a timer process */
    @@ -1696,13 +1696,13 @@ static inline int tiva_ethinitialize(int intf)
       priv->ld_txpoll        = wd_create(); /* Create periodic poll timer */
       priv->ld_txtimeout     = wd_create(); /* Create TX timeout timer */
     
    +#ifdef CONFIG_TIVA_BOARDMAC
       /* If the board can provide us with a MAC address, get the address
        * from the board now.  The MAC will not be applied until tiva_ifup()
        * is called (and the MAC can be overwritten with a netdev ioctl call).
        */
     
    -#ifdef CONFIG_TIVA_BOARDMAC
    -   tiva_ethernetmac(&priv->ld_dev.d_mac);
    +   tiva_ethernetmac(&priv->ld_dev.d_mac.ether);
     #endif
     
       /* Perform minimal, one-time initialization -- just reset the controller and
    diff --git a/arch/arm/src/tiva/tm4c_ethernet.c b/arch/arm/src/tiva/tm4c_ethernet.c
    index cf0661d36e..63cf22689c 100644
    --- a/arch/arm/src/tiva/tm4c_ethernet.c
    +++ b/arch/arm/src/tiva/tm4c_ethernet.c
    @@ -3755,22 +3755,22 @@ static void tiva_macaddress(FAR struct tiva_ethmac_s *priv)
     
       ninfo("%s MAC: %02x:%02x:%02x:%02x:%02x:%02x\n",
             dev->d_ifname,
    -        dev->d_mac.ether_addr_octet[0], dev->d_mac.ether_addr_octet[1],
    -        dev->d_mac.ether_addr_octet[2], dev->d_mac.ether_addr_octet[3],
    -        dev->d_mac.ether_addr_octet[4], dev->d_mac.ether_addr_octet[5]);
    +        dev->d_mac.ether.ether_addr_octet[0], dev->d_mac.ether.ether_addr_octet[1],
    +        dev->d_mac.ether.ether_addr_octet[2], dev->d_mac.ether.ether_addr_octet[3],
    +        dev->d_mac.ether.ether_addr_octet[4], dev->d_mac.ether.ether_addr_octet[5]);
     
       /* Set the MAC address high register */
     
    -  regval = ((uint32_t)dev->d_mac.ether_addr_octet[5] << 8) |
    -            (uint32_t)dev->d_mac.ether_addr_octet[4];
    +  regval = ((uint32_t)dev->d_mac.ether.ether_addr_octet[5] << 8) |
    +            (uint32_t)dev->d_mac.ether.ether_addr_octet[4];
       tiva_putreg(regval, TIVA_EMAC_ADDR0H);
     
       /* Set the MAC address low register */
     
    -  regval = ((uint32_t)dev->d_mac.ether_addr_octet[3] << 24) |
    -           ((uint32_t)dev->d_mac.ether_addr_octet[2] << 16) |
    -           ((uint32_t)dev->d_mac.ether_addr_octet[1] <<  8) |
    -            (uint32_t)dev->d_mac.ether_addr_octet[0];
    +  regval = ((uint32_t)dev->d_mac.ether.ether_addr_octet[3] << 24) |
    +           ((uint32_t)dev->d_mac.ether.ether_addr_octet[2] << 16) |
    +           ((uint32_t)dev->d_mac.ether.ether_addr_octet[1] <<  8) |
    +            (uint32_t)dev->d_mac.ether.ether_addr_octet[0];
       tiva_putreg(regval, TIVA_EMAC_ADDR0L);
     }
     
    @@ -4056,7 +4056,7 @@ int tiva_ethinitialize(int intf)
        * is called (and the MAC can be overwritten with a netdev ioctl call).
        */
     
    -  tiva_ethernetmac(&priv->dev.d_mac);
    +  tiva_ethernetmac(&priv->dev.d_mac.ether);
     #endif
     
       /* Enable power and clocking to the Ethernet MAC
    diff --git a/arch/hc/src/m9s12/m9s12_ethernet.c b/arch/hc/src/m9s12/m9s12_ethernet.c
    index 2a2673ed5f..3b3fcf0d74 100644
    --- a/arch/hc/src/m9s12/m9s12_ethernet.c
    +++ b/arch/hc/src/m9s12/m9s12_ethernet.c
    @@ -781,7 +781,7 @@ int emac_initialize(int intf)
        * the device and/or calling emac_ifdown().
        */
     
    -  /* Read the MAC address from the hardware into priv->d_dev.d_mac.ether_addr_octet */
    +  /* Read the MAC address from the hardware into priv->d_dev.d_mac.ether.ether_addr_octet */
     
       /* Register the device with the OS so that socket IOCTLs can be performed */
     
    diff --git a/arch/mips/src/pic32mx/pic32mx-ethernet.c b/arch/mips/src/pic32mx/pic32mx-ethernet.c
    index 5a4b7654d1..f436b298b6 100644
    --- a/arch/mips/src/pic32mx/pic32mx-ethernet.c
    +++ b/arch/mips/src/pic32mx/pic32mx-ethernet.c
    @@ -2216,29 +2216,29 @@ static int pic32mx_ifup(struct net_driver_s *dev)
        */
     
     #if 0
    -  regval = (uint32_t)priv->pd_dev.d_mac.ether_addr_octet[5] << 8 |
    -           (uint32_t)priv->pd_dev.d_mac.ether_addr_octet[4];
    +  regval = (uint32_t)priv->pd_dev.d_mac.ether.ether_addr_octet[5] << 8 |
    +           (uint32_t)priv->pd_dev.d_mac.ether.ether_addr_octet[4];
       pic32mx_putreg(regval, PIC32MX_EMAC1_SA0);
     
    -  regval = (uint32_t)priv->pd_dev.d_mac.ether_addr_octet[3] << 8 |
    -           (uint32_t)priv->pd_dev.d_mac.ether_addr_octet[2];
    +  regval = (uint32_t)priv->pd_dev.d_mac.ether.ether_addr_octet[3] << 8 |
    +           (uint32_t)priv->pd_dev.d_mac.ether.ether_addr_octet[2];
       pic32mx_putreg(regval, PIC32MX_EMAC1_SA1);
     
    -  regval = (uint32_t)priv->pd_dev.d_mac.ether_addr_octet[1] << 8 |
    -           (uint32_t)priv->pd_dev.d_mac.ether_addr_octet[0];
    +  regval = (uint32_t)priv->pd_dev.d_mac.ether.ether_addr_octet[1] << 8 |
    +           (uint32_t)priv->pd_dev.d_mac.ether.ether_addr_octet[0];
       pic32mx_putreg(regval, PIC32MX_EMAC1_SA2);
     #else
       regval = pic32mx_getreg(PIC32MX_EMAC1_SA0);
    -  priv->pd_dev.d_mac.ether_addr_octet[4] = (uint32_t)(regval & 0xff);
    -  priv->pd_dev.d_mac.ether_addr_octet[5] = (uint32_t)((regval >> 8) & 0xff);
    +  priv->pd_dev.d_mac.ether.ether_addr_octet[4] = (uint32_t)(regval & 0xff);
    +  priv->pd_dev.d_mac.ether.ether_addr_octet[5] = (uint32_t)((regval >> 8) & 0xff);
     
       regval = pic32mx_getreg(PIC32MX_EMAC1_SA1);
    -  priv->pd_dev.d_mac.ether_addr_octet[2] = (uint32_t)(regval & 0xff);
    -  priv->pd_dev.d_mac.ether_addr_octet[3] = (uint32_t)((regval >> 8) & 0xff);
    +  priv->pd_dev.d_mac.ether.ether_addr_octet[2] = (uint32_t)(regval & 0xff);
    +  priv->pd_dev.d_mac.ether.ether_addr_octet[3] = (uint32_t)((regval >> 8) & 0xff);
     
       regval = pic32mx_getreg(PIC32MX_EMAC1_SA2);
    -  priv->pd_dev.d_mac.ether_addr_octet[0] = (uint32_t)(regval & 0xff);
    -  priv->pd_dev.d_mac.ether_addr_octet[1] = (uint32_t)((regval >> 8) & 0xff);
    +  priv->pd_dev.d_mac.ether.ether_addr_octet[0] = (uint32_t)(regval & 0xff);
    +  priv->pd_dev.d_mac.ether.ether_addr_octet[1] = (uint32_t)((regval >> 8) & 0xff);
     #endif
     
       /* Continue Ethernet Controller Initialization ****************************/
    diff --git a/arch/mips/src/pic32mz/pic32mz-ethernet.c b/arch/mips/src/pic32mz/pic32mz-ethernet.c
    index f49da8530d..5e1b2f5e04 100644
    --- a/arch/mips/src/pic32mz/pic32mz-ethernet.c
    +++ b/arch/mips/src/pic32mz/pic32mz-ethernet.c
    @@ -2243,34 +2243,34 @@ static int pic32mz_ifup(struct net_driver_s *dev)
        */
     
     #if 0
    -  regval = (uint32_t)priv->pd_dev.d_mac.ether_addr_octet[5] << 8 |
    -           (uint32_t)priv->pd_dev.d_mac.ether_addr_octet[4];
    +  regval = (uint32_t)priv->pd_dev.d_mac.ether.ether_addr_octet[5] << 8 |
    +           (uint32_t)priv->pd_dev.d_mac.ether.ether_addr_octet[4];
       pic32mz_putreg(regval, PIC32MZ_EMAC1_SA0);
     
    -  regval = (uint32_t)priv->pd_dev.d_mac.ether_addr_octet[3] << 8 |
    -           (uint32_t)priv->pd_dev.d_mac.ether_addr_octet[2];
    +  regval = (uint32_t)priv->pd_dev.d_mac.ether.ether_addr_octet[3] << 8 |
    +           (uint32_t)priv->pd_dev.d_mac.ether.ether_addr_octet[2];
       pic32mz_putreg(regval, PIC32MZ_EMAC1_SA1);
     
    -  regval = (uint32_t)priv->pd_dev.d_mac.ether_addr_octet[1] << 8 |
    -           (uint32_t)priv->pd_dev.d_mac.ether_addr_octet[0];
    +  regval = (uint32_t)priv->pd_dev.d_mac.ether.ether_addr_octet[1] << 8 |
    +           (uint32_t)priv->pd_dev.d_mac.ether.ether_addr_octet[0];
       pic32mz_putreg(regval, PIC32MZ_EMAC1_SA2);
     #else
       regval = pic32mz_getreg(PIC32MZ_EMAC1_SA0);
    -  priv->pd_dev.d_mac.ether_addr_octet[4] = (uint32_t)(regval & 0xff);
    -  priv->pd_dev.d_mac.ether_addr_octet[5] = (uint32_t)((regval >> 8) & 0xff);
    +  priv->pd_dev.d_mac.ether.ether_addr_octet[4] = (uint32_t)(regval & 0xff);
    +  priv->pd_dev.d_mac.ether.ether_addr_octet[5] = (uint32_t)((regval >> 8) & 0xff);
     
       regval = pic32mz_getreg(PIC32MZ_EMAC1_SA1);
    -  priv->pd_dev.d_mac.ether_addr_octet[2] = (uint32_t)(regval & 0xff);
    -  priv->pd_dev.d_mac.ether_addr_octet[3] = (uint32_t)((regval >> 8) & 0xff);
    +  priv->pd_dev.d_mac.ether.ether_addr_octet[2] = (uint32_t)(regval & 0xff);
    +  priv->pd_dev.d_mac.ether.ether_addr_octet[3] = (uint32_t)((regval >> 8) & 0xff);
     
       regval = pic32mz_getreg(PIC32MZ_EMAC1_SA2);
    -  priv->pd_dev.d_mac.ether_addr_octet[0] = (uint32_t)(regval & 0xff);
    -  priv->pd_dev.d_mac.ether_addr_octet[1] = (uint32_t)((regval >> 8) & 0xff);
    +  priv->pd_dev.d_mac.ether.ether_addr_octet[0] = (uint32_t)(regval & 0xff);
    +  priv->pd_dev.d_mac.ether.ether_addr_octet[1] = (uint32_t)((regval >> 8) & 0xff);
     
       ninfo("MAC: %02x:%02x:%02x:%02x:%02x:%02x\n",
    -        dev->d_mac.ether_addr_octet[0], dev->d_mac.ether_addr_octet[1],
    -        dev->d_mac.ether_addr_octet[2], dev->d_mac.ether_addr_octet[3],
    -        dev->d_mac.ether_addr_octet[4], dev->d_mac.ether_addr_octet[5]);
    +        dev->d_mac.ether.ether_addr_octet[0], dev->d_mac.ether.ether_addr_octet[1],
    +        dev->d_mac.ether.ether_addr_octet[2], dev->d_mac.ether.ether_addr_octet[3],
    +        dev->d_mac.ether.ether_addr_octet[4], dev->d_mac.ether.ether_addr_octet[5]);
     #endif
     
       /* Continue Ethernet Controller Initialization ****************************/
    diff --git a/arch/misoc/src/common/misoc_net.c b/arch/misoc/src/common/misoc_net.c
    index 6d7b64b62c..a7df365435 100644
    --- a/arch/misoc/src/common/misoc_net.c
    +++ b/arch/misoc/src/common/misoc_net.c
    @@ -833,7 +833,7 @@ static int misoc_net_ifup(FAR struct net_driver_s *dev)
     
       /* Initialize PHYs, the Ethernet interface, and setup up Ethernet interrupts */
     
    -  /* Instantiate the MAC address from priv->misoc_net_dev.d_mac.ether_addr_octet */
    +  /* Instantiate the MAC address from priv->misoc_net_dev.d_mac.ether.ether_addr_octet */
     
     #ifdef CONFIG_NET_ICMPv6
       /* Set up IPv6 multicast address filtering */
    @@ -1182,7 +1182,7 @@ int misoc_net_initialize(int intf)
        */
     
       /* Read the MAC address from the hardware into
    -   * priv->misoc_net_dev.d_mac.ether_addr_octet
    +   * priv->misoc_net_dev.d_mac.ether.ether_addr_octet
        */
     
       /* Register the device with the OS so that socket IOCTLs can be performed */
    diff --git a/arch/sim/src/up_netdriver.c b/arch/sim/src/up_netdriver.c
    index bb37ec9fcc..99eaf73dbe 100644
    --- a/arch/sim/src/up_netdriver.c
    +++ b/arch/sim/src/up_netdriver.c
    @@ -198,7 +198,7 @@ void netdriver_loop(void)
                * up_comparemac will always return 0.
                */
     
    -         is_ours = (up_comparemac(eth->dest, &g_sim_dev.d_mac) == 0);
    +         is_ours = (up_comparemac(eth->dest, &g_sim_dev.d_mac.ether) == 0);
     
     #ifdef CONFIG_NET_PKT
               /* When packet sockets are enabled, feed the frame into the packet
    @@ -359,7 +359,7 @@ int netdriver_init(void)
     
     int netdriver_setmacaddr(unsigned char *macaddr)
     {
    -  (void)memcpy(g_sim_dev.d_mac.ether_addr_octet, macaddr, IFHWADDRLEN);
    +  (void)memcpy(g_sim_dev.d_mac.ether.ether_addr_octet, macaddr, IFHWADDRLEN);
       return 0;
     }
     
    diff --git a/arch/z80/src/ez80/ez80_emac.c b/arch/z80/src/ez80/ez80_emac.c
    index 5da9255416..55896c08ff 100644
    --- a/arch/z80/src/ez80/ez80_emac.c
    +++ b/arch/z80/src/ez80/ez80_emac.c
    @@ -1999,9 +1999,9 @@ static int ez80emac_ifup(FAR struct net_driver_s *dev)
       int ret;
     
       ninfo("Bringing up: MAC %02x:%02x:%02x:%02x:%02x:%02x\n",
    -        dev->d_mac.ether_addr_octet[0], dev->d_mac.ether_addr_octet[1],
    -        dev->d_mac.ether_addr_octet[2], dev->d_mac.ether_addr_octet[3],
    -        dev->d_mac.ether_addr_octet[4], dev->d_mac.ether_addr_octet[5]);
    +        dev->d_mac.ether.ether_addr_octet[0], dev->d_mac.ether.ether_addr_octet[1],
    +        dev->d_mac.ether.ether_addr_octet[2], dev->d_mac.ether.ether_addr_octet[3],
    +        dev->d_mac.ether.ether_addr_octet[4], dev->d_mac.ether.ether_addr_octet[5]);
       ninfo("             IP  %d.%d.%d.%d\n",
             dev->d_ipaddr >> 24,       (dev->d_ipaddr >> 16) & 0xff,
            (dev->d_ipaddr >> 8) & 0xff, dev->d_ipaddr & 0xff);
    @@ -2028,12 +2028,12 @@ static int ez80emac_ifup(FAR struct net_driver_s *dev)
     
           /* Set the MAC address */
     
    -      outp(EZ80_EMAC_STAD_0, priv->dev.d_mac.ether_addr_octet[0]);
    -      outp(EZ80_EMAC_STAD_1, priv->dev.d_mac.ether_addr_octet[1]);
    -      outp(EZ80_EMAC_STAD_2, priv->dev.d_mac.ether_addr_octet[2]);
    -      outp(EZ80_EMAC_STAD_3, priv->dev.d_mac.ether_addr_octet[3]);
    -      outp(EZ80_EMAC_STAD_4, priv->dev.d_mac.ether_addr_octet[4]);
    -      outp(EZ80_EMAC_STAD_5, priv->dev.d_mac.ether_addr_octet[5]);
    +      outp(EZ80_EMAC_STAD_0, priv->dev.d_mac.ether.ether_addr_octet[0]);
    +      outp(EZ80_EMAC_STAD_1, priv->dev.d_mac.ether.ether_addr_octet[1]);
    +      outp(EZ80_EMAC_STAD_2, priv->dev.d_mac.ether.ether_addr_octet[2]);
    +      outp(EZ80_EMAC_STAD_3, priv->dev.d_mac.ether.ether_addr_octet[3]);
    +      outp(EZ80_EMAC_STAD_4, priv->dev.d_mac.ether.ether_addr_octet[4]);
    +      outp(EZ80_EMAC_STAD_5, priv->dev.d_mac.ether.ether_addr_octet[5]);
     
           /* Enable/disable promiscuous mode */
     
    @@ -2542,7 +2542,7 @@ int up_netinitialize(void)
       priv->txpoll        = wd_create();        /* Create periodic poll timer */
       priv->txtimeout     = wd_create();        /* Create TX timeout timer */
     
    -  /* Read the MAC address from the hardware into priv->dev.d_mac.ether_addr_octet */
    +  /* Read the MAC address from the hardware into priv->dev.d_mac.ether.ether_addr_octet */
     
       /* Register the device with the OS so that socket IOCTLs can be performed */
     
    diff --git a/drivers/net/cs89x0.c b/drivers/net/cs89x0.c
    index e64c2404e0..3dd1e7e0dd 100644
    --- a/drivers/net/cs89x0.c
    +++ b/drivers/net/cs89x0.c
    @@ -1006,7 +1006,7 @@ int cs89x0_initialize(FAR const cs89x0_driver_s *cs89x0, int devno)
       cs89x0->cs_txpoll       = wd_create();         /* Create periodic poll timer */
       cs89x0->cs_txtimeout    = wd_create();         /* Create TX timeout timer */
     
    -  /* Read the MAC address from the hardware into cs89x0->cs_dev.d_mac.ether_addr_octet */
    +  /* Read the MAC address from the hardware into cs89x0->cs_dev.d_mac.ether.ether_addr_octet */
     
       /* Register the device with the OS so that socket IOCTLs can be performed */
     
    diff --git a/drivers/net/dm90x0.c b/drivers/net/dm90x0.c
    index a812686e8a..b6cfa6dfb7 100644
    --- a/drivers/net/dm90x0.c
    +++ b/drivers/net/dm90x0.c
    @@ -1955,7 +1955,7 @@ int dm9x_initialize(void)
     
       /* Read the MAC address */
     
    -  mptr = g_dm9x[0].dm_dev.d_mac.ether_addr_octet;
    +  mptr = g_dm9x[0].dm_dev.d_mac.ether.ether_addr_octet;
       for (i = 0, j = DM9X_PAB0; i < ETHER_ADDR_LEN; i++, j++)
         {
           mptr[i] = getreg(j);
    diff --git a/drivers/net/enc28j60.c b/drivers/net/enc28j60.c
    index d0034543a8..90aa996c0b 100644
    --- a/drivers/net/enc28j60.c
    +++ b/drivers/net/enc28j60.c
    @@ -2440,12 +2440,12 @@ static void enc_setmacaddr(FAR struct enc_driver_s *priv)
        *   MAADR6  MAC Address Byte 6 (MAADR<7:0>)
        */
     
    -  enc_wrbreg(priv, ENC_MAADR1, priv->dev.d_mac.ether_addr_octet[0]);
    -  enc_wrbreg(priv, ENC_MAADR2, priv->dev.d_mac.ether_addr_octet[1]);
    -  enc_wrbreg(priv, ENC_MAADR3, priv->dev.d_mac.ether_addr_octet[2]);
    -  enc_wrbreg(priv, ENC_MAADR4, priv->dev.d_mac.ether_addr_octet[3]);
    -  enc_wrbreg(priv, ENC_MAADR5, priv->dev.d_mac.ether_addr_octet[4]);
    -  enc_wrbreg(priv, ENC_MAADR6, priv->dev.d_mac.ether_addr_octet[5]);
    +  enc_wrbreg(priv, ENC_MAADR1, priv->dev.d_mac.ether.ether_addr_octet[0]);
    +  enc_wrbreg(priv, ENC_MAADR2, priv->dev.d_mac.ether.ether_addr_octet[1]);
    +  enc_wrbreg(priv, ENC_MAADR3, priv->dev.d_mac.ether.ether_addr_octet[2]);
    +  enc_wrbreg(priv, ENC_MAADR4, priv->dev.d_mac.ether.ether_addr_octet[3]);
    +  enc_wrbreg(priv, ENC_MAADR5, priv->dev.d_mac.ether.ether_addr_octet[4]);
    +  enc_wrbreg(priv, ENC_MAADR6, priv->dev.d_mac.ether.ether_addr_octet[5]);
     }
     
     /****************************************************************************
    diff --git a/drivers/net/encx24j600.c b/drivers/net/encx24j600.c
    index e15cfe71dc..be66e56da5 100644
    --- a/drivers/net/encx24j600.c
    +++ b/drivers/net/encx24j600.c
    @@ -2591,7 +2591,7 @@ static void enc_pwrsave(FAR struct enc_driver_s *priv)
     static void enc_ldmacaddr(FAR struct enc_driver_s *priv)
     {
       uint16_t regval;
    -  uint8_t *mac = priv->dev.d_mac.ether_addr_octet;
    +  uint8_t *mac = priv->dev.d_mac.ether.ether_addr_octet;
     
       ninfo("Using ENCX24J600's built in MAC address\n");
     
    @@ -2629,12 +2629,12 @@ static void enc_ldmacaddr(FAR struct enc_driver_s *priv)
     
     static void enc_setmacaddr(FAR struct enc_driver_s *priv)
     {
    -  uint8_t *mac = priv->dev.d_mac.ether_addr_octet;
    +  uint8_t *mac = priv->dev.d_mac.ether.ether_addr_octet;
       struct ether_addr zmac;
     
       memset(&zmac, 0, sizeof(zmac));
     
    -  if (memcmp(&priv->dev.d_mac, &zmac, sizeof(zmac)) == 0)
    +  if (memcmp(&priv->dev.d_mac.ether, &zmac, sizeof(zmac)) == 0)
         {
           /* No user defined MAC address. Read it from the device. */
     
    diff --git a/drivers/net/ftmac100.c b/drivers/net/ftmac100.c
    index 7b02fa9e21..9acc93d643 100644
    --- a/drivers/net/ftmac100.c
    +++ b/drivers/net/ftmac100.c
    @@ -1185,9 +1185,9 @@ static int ftmac100_ifup(struct net_driver_s *dev)
     
       ftmac100_init(priv);
     
    -  /* Instantiate the MAC address from priv->ft_dev.d_mac.ether_addr_octet */
    +  /* Instantiate the MAC address from priv->ft_dev.d_mac.ether.ether_addr_octet */
     
    -  ftmac100_set_mac(priv, priv->ft_dev.d_mac.ether_addr_octet);
    +  ftmac100_set_mac(priv, priv->ft_dev.d_mac.ether.ether_addr_octet);
     
     #ifdef CONFIG_NET_ICMPv6
       /* Set up IPv6 multicast address filtering */
    @@ -1566,9 +1566,9 @@ int ftmac100_initialize(int intf)
        */
       ftmac100_reset(priv);
     
    -  /* Read the MAC address from the hardware into priv->ft_dev.d_mac.ether_addr_octet */
    +  /* Read the MAC address from the hardware into priv->ft_dev.d_mac.ether.ether_addr_octet */
     
    -  memcpy(priv->ft_dev.d_mac.ether_addr_octet, (void *)(CONFIG_FTMAC100_MAC0_ENV_ADDR), 6);
    +  memcpy(priv->ft_dev.d_mac.ether.ether_addr_octet, (void *)(CONFIG_FTMAC100_MAC0_ENV_ADDR), 6);
     
       /* Register the device with the OS so that socket IOCTLs can be performed */
     
    diff --git a/drivers/net/skeleton.c b/drivers/net/skeleton.c
    index 77f1aea82d..5edeadc162 100644
    --- a/drivers/net/skeleton.c
    +++ b/drivers/net/skeleton.c
    @@ -803,7 +803,7 @@ static int skel_ifup(FAR struct net_driver_s *dev)
     
       /* Initialize PHYs, the Ethernet interface, and setup up Ethernet interrupts */
     
    -  /* Instantiate the MAC address from priv->sk_dev.d_mac.ether_addr_octet */
    +  /* Instantiate the MAC address from priv->sk_dev.d_mac.ether.ether_addr_octet */
     
     #ifdef CONFIG_NET_ICMPv6
       /* Set up IPv6 multicast address filtering */
    @@ -1187,7 +1187,7 @@ int skel_initialize(int intf)
        * the device and/or calling skel_ifdown().
        */
     
    -  /* Read the MAC address from the hardware into priv->sk_dev.d_mac.ether_addr_octet */
    +  /* Read the MAC address from the hardware into priv->sk_dev.d_mac.ether.ether_addr_octet */
     
       /* Register the device with the OS so that socket IOCTLs can be performed */
     
    diff --git a/drivers/net/tun.c b/drivers/net/tun.c
    index a942bebe13..4451d52b0a 100644
    --- a/drivers/net/tun.c
    +++ b/drivers/net/tun.c
    @@ -631,7 +631,7 @@ static int tun_ifup(struct net_driver_s *dev)
     
       /* Initialize PHYs, the Ethernet interface, and setup up Ethernet interrupts */
     
    -  /* Instantiate the MAC address from priv->dev.d_mac.ether_addr_octet */
    +  /* Instantiate the MAC address from priv->dev.d_mac.ether.ether_addr_octet */
     
     #ifdef CONFIG_NET_ICMPv6
       /* Set up IPv6 multicast address filtering */
    diff --git a/include/nuttx/net/netdev.h b/include/nuttx/net/netdev.h
    index 7caf247adc..85eed6a1e8 100644
    --- a/include/nuttx/net/netdev.h
    +++ b/include/nuttx/net/netdev.h
    @@ -207,10 +207,17 @@ struct net_driver_s
     #endif
     #endif
     
    +#if defined(CONFIG_NET_ETHERNET)
    +  /* Link layer address */
    +
    +  union
    +  {
     #ifdef CONFIG_NET_ETHERNET
    -  /* Ethernet device identity */
    +    /* Ethernet device identity */
     
    -  struct ether_addr d_mac;      /* Device MAC address */
    +    struct ether_addr ether;    /* Device Ethernet MAC address */
    +#endif
    +  } d_mac;
     #endif
     
       /* Network identity */
    diff --git a/net/arp/arp_arpin.c b/net/arp/arp_arpin.c
    index fe8d47a63e..b3350554f5 100644
    --- a/net/arp/arp_arpin.c
    +++ b/net/arp/arp_arpin.c
    @@ -124,8 +124,8 @@ void arp_arpin(FAR struct net_driver_s *dev)
     
                 arp->ah_opcode = HTONS(ARP_REPLY);
                 memcpy(arp->ah_dhwaddr, arp->ah_shwaddr, ETHER_ADDR_LEN);
    -            memcpy(arp->ah_shwaddr, dev->d_mac.ether_addr_octet, ETHER_ADDR_LEN);
    -            memcpy(eth->src, dev->d_mac.ether_addr_octet, ETHER_ADDR_LEN);
    +            memcpy(arp->ah_shwaddr, dev->d_mac.ether.ether_addr_octet, ETHER_ADDR_LEN);
    +            memcpy(eth->src, dev->d_mac.ether.ether_addr_octet, ETHER_ADDR_LEN);
                 memcpy(eth->dest, arp->ah_dhwaddr, ETHER_ADDR_LEN);
     
                 arp->ah_dipaddr[0] = arp->ah_sipaddr[0];
    diff --git a/net/arp/arp_format.c b/net/arp/arp_format.c
    index 4b0af255d5..c17b4fbdf1 100644
    --- a/net/arp/arp_format.c
    +++ b/net/arp/arp_format.c
    @@ -90,8 +90,8 @@ void arp_format(FAR struct net_driver_s *dev, in_addr_t ipaddr)
     
       memset(eth->dest, 0xff, ETHER_ADDR_LEN);
       memset(arp->ah_dhwaddr, 0x00, ETHER_ADDR_LEN);
    -  memcpy(eth->src, dev->d_mac.ether_addr_octet, ETHER_ADDR_LEN);
    -  memcpy(arp->ah_shwaddr, dev->d_mac.ether_addr_octet, ETHER_ADDR_LEN);
    +  memcpy(eth->src, dev->d_mac.ether.ether_addr_octet, ETHER_ADDR_LEN);
    +  memcpy(arp->ah_shwaddr, dev->d_mac.ether.ether_addr_octet, ETHER_ADDR_LEN);
     
       net_ipv4addr_hdrcopy(arp->ah_dipaddr, &ipaddr);
       net_ipv4addr_hdrcopy(arp->ah_sipaddr, &dev->d_ipaddr);
    diff --git a/net/arp/arp_out.c b/net/arp/arp_out.c
    index b816197671..53853af7a2 100644
    --- a/net/arp/arp_out.c
    +++ b/net/arp/arp_out.c
    @@ -249,7 +249,7 @@ void arp_out(FAR struct net_driver_s *dev)
     
       /* Finish populating the Ethernet header */
     
    -  memcpy(peth->src, dev->d_mac.ether_addr_octet, ETHER_ADDR_LEN);
    +  memcpy(peth->src, dev->d_mac.ether.ether_addr_octet, ETHER_ADDR_LEN);
       peth->type  = HTONS(ETHTYPE_IP);
       dev->d_len += ETH_HDRLEN;
     }
    diff --git a/net/icmpv6/icmpv6_advertise.c b/net/icmpv6/icmpv6_advertise.c
    index 68d417873a..621b8d6c14 100644
    --- a/net/icmpv6/icmpv6_advertise.c
    +++ b/net/icmpv6/icmpv6_advertise.c
    @@ -139,7 +139,7 @@ void icmpv6_advertise(FAR struct net_driver_s *dev,
        * REVISIT:  What if the link layer is not Ethernet?
        */
     
    -  memcpy(adv->tgtlladdr, &dev->d_mac, IFHWADDRLEN);
    +  memcpy(adv->tgtlladdr, &dev->d_mac.ether, IFHWADDRLEN);
     
       /* Calculate the checksum over both the ICMP header and payload */
     
    @@ -166,7 +166,7 @@ void icmpv6_advertise(FAR struct net_driver_s *dev,
           FAR struct eth_hdr_s *eth = ETHBUF;
     
           memcpy(eth->dest, eth->src, ETHER_ADDR_LEN);
    -      memcpy(eth->src, dev->d_mac.ether_addr_octet, ETHER_ADDR_LEN);
    +      memcpy(eth->src, dev->d_mac.ether.ether_addr_octet, ETHER_ADDR_LEN);
     
           /* Set the IPv6 Ethernet type */
     
    diff --git a/net/icmpv6/icmpv6_autoconfig.c b/net/icmpv6/icmpv6_autoconfig.c
    index 05a9c44926..08ec223def 100644
    --- a/net/icmpv6/icmpv6_autoconfig.c
    +++ b/net/icmpv6/icmpv6_autoconfig.c
    @@ -402,7 +402,7 @@ int icmpv6_autoconfig(FAR struct net_driver_s *dev)
     
       lladdr[0] = HTONS(0xfe80);                        /* 10-bit address + 6 zeroes */
       memset(&lladdr[1], 0, 4 * sizeof(uint16_t));      /* 64 more zeroes */
    -  memcpy(&lladdr[5], dev->d_mac.ether_addr_octet,
    +  memcpy(&lladdr[5], dev->d_mac.ether.ether_addr_octet,
             sizeof(struct ether_addr));                 /* 48-bit Ethernet address */
     
       ninfo("lladdr=%04x:%04x:%04x:%04x:%04x:%04x:%04x:%04x\n",
    diff --git a/net/icmpv6/icmpv6_radvertise.c b/net/icmpv6/icmpv6_radvertise.c
    index 040d1e39f7..cec05c51a8 100644
    --- a/net/icmpv6/icmpv6_radvertise.c
    +++ b/net/icmpv6/icmpv6_radvertise.c
    @@ -176,7 +176,7 @@ void icmpv6_radvertise(FAR struct net_driver_s *dev)
       srcaddr           = &adv->srcaddr;
       srcaddr->opttype  = ICMPv6_OPT_SRCLLADDR;
       srcaddr->optlen   = 1;
    -  memcpy(srcaddr->srclladdr, &dev->d_mac.ether_addr_octet, ETHER_ADDR_LEN);
    +  memcpy(srcaddr->srclladdr, &dev->d_mac.ether.ether_addr_octet, ETHER_ADDR_LEN);
     
       /* Set up the MTU option */
     
    @@ -228,7 +228,7 @@ void icmpv6_radvertise(FAR struct net_driver_s *dev)
           FAR struct eth_hdr_s *eth = ETHBUF;
     
           memcpy(eth->dest, g_ipv6_ethallnodes.ether_addr_octet, ETHER_ADDR_LEN);
    -      memcpy(eth->src, dev->d_mac.ether_addr_octet, ETHER_ADDR_LEN);
    +      memcpy(eth->src, dev->d_mac.ether.ether_addr_octet, ETHER_ADDR_LEN);
     
           /* Set the IPv6 Ethernet type */
     
    diff --git a/net/icmpv6/icmpv6_rsolicit.c b/net/icmpv6/icmpv6_rsolicit.c
    index db21f7f0a7..93a2631432 100644
    --- a/net/icmpv6/icmpv6_rsolicit.c
    +++ b/net/icmpv6/icmpv6_rsolicit.c
    @@ -137,7 +137,7 @@ void icmpv6_rsolicit(FAR struct net_driver_s *dev)
        * REVISIT:  What if the link layer is not Ethernet?
        */
     
    -  memcpy(sol->srclladdr, dev->d_mac.ether_addr_octet, sizeof(net_ipv6addr_t));
    +  memcpy(sol->srclladdr, dev->d_mac.ether.ether_addr_octet, sizeof(net_ipv6addr_t));
     
       /* Calculate the checksum over both the ICMP header and payload */
     
    @@ -162,7 +162,7 @@ void icmpv6_rsolicit(FAR struct net_driver_s *dev)
     
           /* Move our source Ethernet addresses into the Ethernet header */
     
    -      memcpy(eth->src, dev->d_mac.ether_addr_octet, ETHER_ADDR_LEN);
    +      memcpy(eth->src, dev->d_mac.ether.ether_addr_octet, ETHER_ADDR_LEN);
     
           /* Set the IPv6 Ethernet type */
     
    diff --git a/net/icmpv6/icmpv6_solicit.c b/net/icmpv6/icmpv6_solicit.c
    index 5a9c6e868a..5eae392c52 100644
    --- a/net/icmpv6/icmpv6_solicit.c
    +++ b/net/icmpv6/icmpv6_solicit.c
    @@ -152,7 +152,7 @@ void icmpv6_solicit(FAR struct net_driver_s *dev,
        * REVISIT:  What if the link layer is not Ethernet?
        */
     
    -  memcpy(sol->srclladdr, &dev->d_mac, IFHWADDRLEN);
    +  memcpy(sol->srclladdr, &dev->d_mac.ether, IFHWADDRLEN);
     
       /* Calculate the checksum over both the ICMP header and payload */
     
    @@ -190,7 +190,7 @@ void icmpv6_solicit(FAR struct net_driver_s *dev,
     
           /* Move our source Ethernet addresses into the Ethernet header */
     
    -      memcpy(eth->src, dev->d_mac.ether_addr_octet, ETHER_ADDR_LEN);
    +      memcpy(eth->src, dev->d_mac.ether.ether_addr_octet, ETHER_ADDR_LEN);
     
           /* Set the IPv6 Ethernet type */
     
    diff --git a/net/neighbor/neighbor_ethernet_out.c b/net/neighbor/neighbor_ethernet_out.c
    index ddd9a3a5ff..adfff98723 100644
    --- a/net/neighbor/neighbor_ethernet_out.c
    +++ b/net/neighbor/neighbor_ethernet_out.c
    @@ -245,7 +245,7 @@ void neighbor_out(FAR struct net_driver_s *dev)
     
       /* Finish populating the Ethernet header */
     
    -  memcpy(eth->src, dev->d_mac.ether_addr_octet, ETHER_ADDR_LEN);
    +  memcpy(eth->src, dev->d_mac.ether.ether_addr_octet, ETHER_ADDR_LEN);
       eth->type  = HTONS(ETHTYPE_IP6);
     
       /* Add the size of the layer layer header to the total size of the
    diff --git a/net/netdev/netdev_ioctl.c b/net/netdev/netdev_ioctl.c
    index b9581f46d3..a40d526ecf 100644
    --- a/net/netdev/netdev_ioctl.c
    +++ b/net/netdev/netdev_ioctl.c
    @@ -694,7 +694,7 @@ static int netdev_ifr_ioctl(FAR struct socket *psock, int cmd,
                     {
                       req->ifr_hwaddr.sa_family = AF_INETX;
                       memcpy(req->ifr_hwaddr.sa_data,
    -                         dev->d_mac.ether_addr_octet, IFHWADDRLEN);
    +                         dev->d_mac.ether.ether_addr_octet, IFHWADDRLEN);
                       ret = OK;
                     }
                   else
    @@ -736,7 +736,7 @@ static int netdev_ifr_ioctl(FAR struct socket *psock, int cmd,
                   if (true)
     #endif
                     {
    -                  memcpy(dev->d_mac.ether_addr_octet,
    +                  memcpy(dev->d_mac.ether.ether_addr_octet,
                              req->ifr_hwaddr.sa_data, IFHWADDRLEN);
                       ret = OK;
                     }
    diff --git a/net/netdev/netdev_register.c b/net/netdev/netdev_register.c
    index 1aef9c3ed1..8da52f9151 100644
    --- a/net/netdev/netdev_register.c
    +++ b/net/netdev/netdev_register.c
    @@ -334,9 +334,9 @@ int netdev_register(FAR struct net_driver_s *dev, enum net_lltype_e lltype)
     
     #ifdef CONFIG_NET_ETHERNET
           ninfo("Registered MAC: %02x:%02x:%02x:%02x:%02x:%02x as dev: %s\n",
    -            dev->d_mac.ether_addr_octet[0], dev->d_mac.ether_addr_octet[1],
    -            dev->d_mac.ether_addr_octet[2], dev->d_mac.ether_addr_octet[3],
    -            dev->d_mac.ether_addr_octet[4], dev->d_mac.ether_addr_octet[5],
    +            dev->d_mac.ether.ether_addr_octet[0], dev->d_mac.ether.ether_addr_octet[1],
    +            dev->d_mac.ether.ether_addr_octet[2], dev->d_mac.ether.ether_addr_octet[3],
    +            dev->d_mac.ether.ether_addr_octet[4], dev->d_mac.ether.ether_addr_octet[5],
                 dev->d_ifname);
     #else
           ninfo("Registered dev: %s\n", dev->d_ifname);
    diff --git a/net/procfs/netdev_statistics.c b/net/procfs/netdev_statistics.c
    index f4927eab2f..b4c29f3bdf 100644
    --- a/net/procfs/netdev_statistics.c
    +++ b/net/procfs/netdev_statistics.c
    @@ -147,7 +147,7 @@ static int netprocfs_linklayer(FAR struct netprocfs_file_s *netfile)
           case NET_LL_ETHERNET:
             len += snprintf(&netfile->line[len], NET_LINELEN - len,
                             "%s\tLink encap:Ethernet HWaddr %s",
    -                        dev->d_ifname, ether_ntoa(&dev->d_mac));
    +                        dev->d_ifname, ether_ntoa(&dev->d_mac.ether));
             break;
     #endif
     
    @@ -215,7 +215,7 @@ static int netprocfs_linklayer(FAR struct netprocfs_file_s *netfile)
     #elif defined(CONFIG_NET_ETHERNET)
       len += snprintf(&netfile->line[len], NET_LINELEN - len,
                       "%s\tLink encap:Ethernet HWaddr %s at %s\n",
    -                  dev->d_ifname, ether_ntoa(&dev->d_mac), status);
    +                  dev->d_ifname, ether_ntoa(&dev->d_mac.ether), status);
     
     #elif defined(CONFIG_NET_6LOWPAN)
       ieee = (FAR struct ieee802154_driver_s *)dev;
    diff --git a/net/socket/bind.c b/net/socket/bind.c
    index 544d1e0d53..a6671ec40d 100644
    --- a/net/socket/bind.c
    +++ b/net/socket/bind.c
    @@ -105,7 +105,7 @@ static int pkt_bind(FAR struct pkt_conn_s *conn,
     #if 0
       /* Get the MAC address of that interface */
     
    -  memcpy(hwaddr, g_netdevices->d_mac, 6);
    +  memcpy(hwaddr, g_netdevices->d_mac.ether, 6);
     #endif
     
       /* Put ifindex and mac address into connection */
    -- 
    GitLab
    
    
    From 7da031aea143415d260c7332e9e0107fed51af5a Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Sat, 22 Apr 2017 11:52:45 -0600
    Subject: [PATCH 558/990] 6loWPAN: Add IEEE802.15.4 Rime address to union of
     link layer addresses in the network driver.
    
    ---
     include/nuttx/net/netdev.h               | 15 ++++++++++---
     include/nuttx/net/sixlowpan.h            | 10 ++-------
     net/netdev/netdev_ioctl.c                | 18 +++++-----------
     net/procfs/netdev_statistics.c           | 27 +++++++++---------------
     net/sixlowpan/sixlowpan_framelist.c      |  3 ++-
     net/sixlowpan/sixlowpan_framer.c         |  3 ++-
     net/sixlowpan/sixlowpan_hc06.c           |  6 ++++--
     net/sixlowpan/sixlowpan_hc1.c            |  2 +-
     wireless/ieee802154/mac802154_loopback.c | 10 ++++-----
     9 files changed, 43 insertions(+), 51 deletions(-)
    
    diff --git a/include/nuttx/net/netdev.h b/include/nuttx/net/netdev.h
    index 85eed6a1e8..eb84a7774f 100644
    --- a/include/nuttx/net/netdev.h
    +++ b/include/nuttx/net/netdev.h
    @@ -56,12 +56,16 @@
     #include 
     #include 
     
    +#include 
    +#include 
    +
     #ifdef CONFIG_NET_IGMP
     #  include 
     #endif
     
    -#include 
    -#include 
    +#ifdef CONFIG_NET_6LOWPAN
    +#  include 
    +#endif
     
     /****************************************************************************
      * Pre-processor Definitions
    @@ -207,7 +211,7 @@ struct net_driver_s
     #endif
     #endif
     
    -#if defined(CONFIG_NET_ETHERNET)
    +#if defined(CONFIG_NET_ETHERNET) || defined(CONFIG_NET_6LOWPAN)
       /* Link layer address */
     
       union
    @@ -216,6 +220,11 @@ struct net_driver_s
         /* Ethernet device identity */
     
         struct ether_addr ether;    /* Device Ethernet MAC address */
    +#endif
    +#ifdef CONFIG_NET_6LOWPAN
    +  /* The address assigned to an IEEE 802.15.4 radio. */
    +
    +    struct rimeaddr_s ieee802154; /* IEEE 802.15.4 Radio address */
     #endif
       } d_mac;
     #endif
    diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h
    index 63fa39283a..328723b2f8 100644
    --- a/include/nuttx/net/sixlowpan.h
    +++ b/include/nuttx/net/sixlowpan.h
    @@ -366,9 +366,7 @@
      * 2. i_dsn must be set to a random value.  After that, it will be managed
      *    by the network.
      *
    - * 3. i_nodeaddr must be set after the MAC is assigned an address.
    - *
    - * 4. On a TX poll, the IEEE802.15.4 MAC driver should provide its driver
    + * 3. On a TX poll, the IEEE802.15.4 MAC driver should provide its driver
      *    structure with i_framelist set to NULL.  At the conclusion of the
      *    poll, if there are frames to be sent, they will have been added to
      *    the i_framelist.  The non-empty frame list at the conclusion of the
    @@ -383,7 +381,7 @@
      *    After sending each frame, the driver must return the IOB to the pool
      *    of free IOBs using the FROM_IOB_FREE() macro.
      *
    - * 5. When receiving data both buffers must be provided:
    + * 4. When receiving data both buffers must be provided:
      *
      *    The IEEE802.15.4 MAC driver should receive the frame data directly
      *    into the payload area of an IOB structure.  That IOB structure may be
    @@ -444,10 +442,6 @@ struct ieee802154_driver_s
     
       uint16_t i_panid;
     
    -  /* i_node_addr.  The address assigned to this node. */
    -
    -  struct rimeaddr_s i_nodeaddr;
    -
       /* i_dsn.  The sequence number in the range 0x00-0xff added to the
        * transmitted data or MAC command frame. The default is a random value
        * within that range.
    diff --git a/net/netdev/netdev_ioctl.c b/net/netdev/netdev_ioctl.c
    index a40d526ecf..87b21e355f 100644
    --- a/net/netdev/netdev_ioctl.c
    +++ b/net/netdev/netdev_ioctl.c
    @@ -707,13 +707,9 @@ static int netdev_ifr_ioctl(FAR struct socket *psock, int cmd,
                   if (true)
     #endif
                     {
    -                  FAR struct ieee802154_driver_s *ieee =
    -                    (FAR struct ieee802154_driver_s *)dev;
    -
                        req->ifr_hwaddr.sa_family = AF_INETX;
    -                   memcpy(req->ifr_hwaddr.sa_data, ieee->i_nodeaddr.u8,
    -                          NET_6LOWPAN_RIMEADDR_SIZE);
    -                   ret = OK;
    +                   memcpy(req->ifr_hwaddr.sa_data,
    +                         dev->d_mac.ieee802154.u8, NET_6LOWPAN_RIMEADDR_SIZE);                          
                     }
                    else
     #endif
    @@ -750,13 +746,9 @@ static int netdev_ifr_ioctl(FAR struct socket *psock, int cmd,
                   if (true)
     #endif
                     {
    -                  FAR struct ieee802154_driver_s *ieee =
    -                    (FAR struct ieee802154_driver_s *)dev;
    -
    -                   req->ifr_hwaddr.sa_family = AF_INETX;
    -                   memcpy(ieee->i_nodeaddr.u8, req->ifr_hwaddr.sa_data,
    -                          NET_6LOWPAN_RIMEADDR_SIZE);
    -                   ret = OK;
    +                  memcpy(dev->d_mac.ieee802154.u8,
    +                         req->ifr_hwaddr.sa_data, NET_6LOWPAN_RIMEADDR_SIZE);
    +                  ret = OK;
                     }
                   else
     #endif
    diff --git a/net/procfs/netdev_statistics.c b/net/procfs/netdev_statistics.c
    index b4c29f3bdf..5383adfc6a 100644
    --- a/net/procfs/netdev_statistics.c
    +++ b/net/procfs/netdev_statistics.c
    @@ -112,9 +112,6 @@ static const linegen_t g_linegen[] =
     static int netprocfs_linklayer(FAR struct netprocfs_file_s *netfile)
     {
       FAR struct net_driver_s *dev;
    -#ifdef CONFIG_NET_6LOWPAN
    -  FAR struct ieee802154_driver_s *ieee;
    -#endif
       FAR const char *status;
       int len = 0;
     
    @@ -154,22 +151,20 @@ static int netprocfs_linklayer(FAR struct netprocfs_file_s *netfile)
     #ifdef CONFIG_NET_6LOWPAN
           case NET_LL_IEEE802154:
             {
    -          ieee = (FAR struct ieee802154_driver_s *)dev;
    -
     #ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED
               len += snprintf(&netfile->line[len], NET_LINELEN - len,
                               "%s\tLink encap:6loWPAN HWaddr "
                               "%02x:%02x:%02x:%02x:%02x:%02x:%02x:%02x",
                               dev->d_ifname,
    -                          ieee->i_nodeaddr.u8[0], ieee->i_nodeaddr.u8[1],
    -                          ieee->i_nodeaddr.u8[2], ieee->i_nodeaddr.u8[3],
    -                          ieee->i_nodeaddr.u8[4], ieee->i_nodeaddr.u8[5],
    -                          ieee->i_nodeaddr.u8[6], ieee->i_nodeaddr.u8[7]);
    +                          dev->d_mac.ieee802154.u8[0], dev->d_mac.ieee802154.u8[1],
    +                          dev->d_mac.ieee802154.u8[2], dev->d_mac.ieee802154.u8[3],
    +                          dev->d_mac.ieee802154.u8[4], dev->d_mac.ieee802154.u8[5],
    +                          dev->d_mac.ieee802154.u8[6], dev->d_mac.ieee802154.u8[7]);
     #else
               len += snprintf(&netfile->line[len], NET_LINELEN - len,
                               "%s\tLink encap:6loWPAN HWaddr %02x:%02x",
                               dev->d_ifname,
    -                          ieee->i_nodeaddr.u8[0], ieee->i_nodeaddr.u8[1]);
    +                          dev->d_mac.ieee802154.u8[0], dev->d_mac.ieee802154.u8[1]);
     #endif
             }
             break;
    @@ -218,23 +213,21 @@ static int netprocfs_linklayer(FAR struct netprocfs_file_s *netfile)
                       dev->d_ifname, ether_ntoa(&dev->d_mac.ether), status);
     
     #elif defined(CONFIG_NET_6LOWPAN)
    -  ieee = (FAR struct ieee802154_driver_s *)dev;
    -
     #ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED
       len += snprintf(&netfile->line[len], NET_LINELEN - len,
                       "%s\tLink encap:6loWPAN HWaddr "
                       "%02x:%02x:%02x:%02x:%02x:%02x:%02x:%02x at %s\n",
                       dev->d_ifname,
    -                  ieee->i_nodeaddr.u8[0], ieee->i_nodeaddr.u8[1],
    -                  ieee->i_nodeaddr.u8[2], ieee->i_nodeaddr.u8[3],
    -                  ieee->i_nodeaddr.u8[4], ieee->i_nodeaddr.u8[5],
    -                  ieee->i_nodeaddr.u8[6], ieee->i_nodeaddr.u8[7],
    +                  dev->d_mac.ieee802154.u8[0], dev->d_mac.ieee802154.u8[1],
    +                  dev->d_mac.ieee802154.u8[2], dev->d_mac.ieee802154.u8[3],
    +                  dev->d_mac.ieee802154.u8[4], dev->d_mac.ieee802154.u8[5],
    +                  dev->d_mac.ieee802154.u8[6], dev->d_mac.ieee802154.u8[7],
                       status);
     #else
       len += snprintf(&netfile->line[len], NET_LINELEN - len,
                       "%s\tLink encap:6loWPAN HWaddr %02x:%02x at %s\n",
                       dev->d_ifname,
    -                  ieee->i_nodeaddr.u8[0], ieee->i_nodeaddr.u8[1],
    +                  dev->d_mac.ieee802154.u8[0], dev->d_mac.ieee802154.u8[1],
                       status);
     #endif
     #elif defined(CONFIG_NET_LOOPBACK)
    diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c
    index 79e653d10b..c9985872ba 100644
    --- a/net/sixlowpan/sixlowpan_framelist.c
    +++ b/net/sixlowpan/sixlowpan_framelist.c
    @@ -283,7 +283,8 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee,
     
       /* Set the source and destinatino address */
     
    -  rimeaddr_copy(&g_pktaddrs[PACKETBUF_ADDR_SENDER], &ieee->i_nodeaddr);
    +  rimeaddr_copy(&g_pktaddrs[PACKETBUF_ADDR_SENDER],
    +                &ieee->i_dev.d_mac.ieee802154);
       rimeaddr_copy(&g_pktaddrs[PACKETBUF_ADDR_RECEIVER], destmac);
     
       /* Pre-calculate frame header length. */
    diff --git a/net/sixlowpan/sixlowpan_framer.c b/net/sixlowpan/sixlowpan_framer.c
    index d8771a060c..13aa9fecd3 100644
    --- a/net/sixlowpan/sixlowpan_framer.c
    +++ b/net/sixlowpan/sixlowpan_framer.c
    @@ -366,7 +366,8 @@ static void sixlowpan_setup_params(FAR struct ieee802154_driver_s *ieee,
     
       /* Set the source address to the node address assigned to the device */
     
    -  rimeaddr_copy((struct rimeaddr_s *)¶ms->src_addr, &ieee->i_nodeaddr);
    +  rimeaddr_copy((struct rimeaddr_s *)¶ms->src_addr,
    +                &ieee->i_dev.d_mac.ieee802154);
     
       /* Use short soruce address mode if so configured */
     
    diff --git a/net/sixlowpan/sixlowpan_hc06.c b/net/sixlowpan/sixlowpan_hc06.c
    index 8a4999579e..a2ceb53cb6 100644
    --- a/net/sixlowpan/sixlowpan_hc06.c
    +++ b/net/sixlowpan/sixlowpan_hc06.c
    @@ -614,7 +614,8 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee,
     
           /* Compression compare with this nodes address (source) */
     
    -      iphc1   |= compress_addr_64(ipv6->srcipaddr, &ieee->i_nodeaddr,
    +      iphc1   |= compress_addr_64(ipv6->srcipaddr,
    +                                  &ieee->i_dev.d_mac.ieee802154,
                                       SIXLOWPAN_IPHC_SAM_BIT);
         }
     
    @@ -624,7 +625,8 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee,
                ipv6->destipaddr[1] == 0 &&  ipv6->destipaddr[2] == 0 &&
                ipv6->destipaddr[3] == 0)
         {
    -      iphc1 |= compress_addr_64(ipv6->srcipaddr, &ieee->i_nodeaddr,
    +      iphc1 |= compress_addr_64(ipv6->srcipaddr,
    +                                &ieee->i_dev.d_mac.ieee802154,
                                     SIXLOWPAN_IPHC_SAM_BIT);
         }
       else
    diff --git a/net/sixlowpan/sixlowpan_hc1.c b/net/sixlowpan/sixlowpan_hc1.c
    index 313fc388ab..3696c4a34f 100644
    --- a/net/sixlowpan/sixlowpan_hc1.c
    +++ b/net/sixlowpan/sixlowpan_hc1.c
    @@ -129,7 +129,7 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee,
     
       if (ipv6->vtc != 0x60 || ipv6->tcf != 0 || ipv6->flow != 0 ||
           !sixlowpan_islinklocal(ipv6->srcipaddr) ||
    -      !sixlowpan_ismacbased(ipv6->srcipaddr, &ieee->i_nodeaddr) ||
    +      !sixlowpan_ismacbased(ipv6->srcipaddr, &ieee->i_dev.d_mac.ieee802154) ||
           !sixlowpan_islinklocal(ipv6->destipaddr) ||
           !sixlowpan_ismacbased(ipv6->destipaddr, destmac) ||
           (ipv6->proto != IP_PROTO_ICMP6 && ipv6->proto != IP_PROTO_UDP &&
    diff --git a/wireless/ieee802154/mac802154_loopback.c b/wireless/ieee802154/mac802154_loopback.c
    index 31b72dca40..af1320fccf 100644
    --- a/wireless/ieee802154/mac802154_loopback.c
    +++ b/wireless/ieee802154/mac802154_loopback.c
    @@ -365,14 +365,14 @@ static int lo_ifup(FAR struct net_driver_s *dev)
     
     #ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED
       ninfo("             Node: %02x:%02x:%02x:%02x:%02x:%02x:%02x:%02x PANID=%04x\n",
    -         priv->lo_ieee.i_nodeaddr.u8[0], priv->lo_ieee.i_nodeaddr.u8[1],
    -         priv->lo_ieee.i_nodeaddr.u8[2], priv->lo_ieee.i_nodeaddr.u8[3],
    -         priv->lo_ieee.i_nodeaddr.u8[4], priv->lo_ieee.i_nodeaddr.u8[5],
    -         priv->lo_ieee.i_nodeaddr.u8[6], priv->lo_ieee.i_nodeaddr.u8[7],
    +         dev->d_mac.ieee802154.u8[0], dev->d_mac.ieee802154.u8[1],
    +         dev->d_mac.ieee802154.u8[2], dev->d_mac.ieee802154.u8[3],
    +         dev->d_mac.ieee802154.u8[4], dev->d_mac.ieee802154.u8[5],
    +         dev->d_mac.ieee802154.u8[6], dev->d_mac.ieee802154.u8[7],
              priv->lo_ieee.i_panid);
     #else
       ninfo("             Node: %02x:%02x PANID=%04x\n",
    -         priv->lo_ieee.i_nodeaddr.u8[0], priv->lo_ieee.i_nodeaddr.u8[1],
    +         dev->d_mac.ieee802154.u8[0], dev->d_mac.ieee802154.u8[1],
              priv->lo_ieee.i_panid);
     #endif
     
    -- 
    GitLab
    
    
    From a55e9376431280fd23d99e00ba49d54aa0abfe69 Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Sat, 22 Apr 2017 17:03:34 -0600
    Subject: [PATCH 559/990] Correct mispelling
    
    ---
     arch/arm/src/common/up_udelay.c        | 2 +-
     arch/arm/src/lpc11xx/Kconfig           | 2 +-
     arch/arm/src/lpc17xx/Kconfig           | 2 +-
     arch/avr/src/common/up_udelay.c        | 2 +-
     arch/hc/src/common/up_udelay.c         | 2 +-
     arch/mips/src/common/up_udelay.c       | 2 +-
     arch/misoc/src/common/misoc_udelay.c   | 2 +-
     arch/renesas/src/common/up_udelay.c    | 2 +-
     arch/x86/src/common/up_udelay.c        | 2 +-
     arch/xtensa/src/common/xtensa_udelay.c | 2 +-
     arch/z16/src/common/up_udelay.c        | 2 +-
     arch/z80/src/common/up_udelay.c        | 2 +-
     12 files changed, 12 insertions(+), 12 deletions(-)
    
    diff --git a/arch/arm/src/common/up_udelay.c b/arch/arm/src/common/up_udelay.c
    index e1a19445f0..9e3115b201 100644
    --- a/arch/arm/src/common/up_udelay.c
    +++ b/arch/arm/src/common/up_udelay.c
    @@ -59,7 +59,7 @@
      * Description:
      *   Delay inline for the requested number of microseconds.  NOTE:  Because
      *   of all of the setup, several microseconds will be lost before the actual
    - *   timing looop begins.  Thus, the delay will always be a few microseconds
    + *   timing loop begins.  Thus, the delay will always be a few microseconds
      *   longer than requested.
      *
      *   *** NOT multi-tasking friendly ***
    diff --git a/arch/arm/src/lpc11xx/Kconfig b/arch/arm/src/lpc11xx/Kconfig
    index 46b01ab6e9..088188c950 100644
    --- a/arch/arm/src/lpc11xx/Kconfig
    +++ b/arch/arm/src/lpc11xx/Kconfig
    @@ -222,7 +222,7 @@ config CAN_SAM
     		The bus is sampled 3 times (recommended for low to medium speed buses to spikes on the bus-line).
     
     config CAN_LOOPBACK
    -	bool "CAN looopback mode"
    +	bool "CAN loopback mode"
     	default n
     	---help---
     		Enable CAN loopback mode
    diff --git a/arch/arm/src/lpc17xx/Kconfig b/arch/arm/src/lpc17xx/Kconfig
    index f8f95f8c5d..bef6ef884c 100644
    --- a/arch/arm/src/lpc17xx/Kconfig
    +++ b/arch/arm/src/lpc17xx/Kconfig
    @@ -589,7 +589,7 @@ config CAN_SAM
     		The bus is sampled 3 times (recommended for low to medium speed buses to spikes on the bus-line).
     
     config CAN_LOOPBACK
    -	bool "CAN looopback mode"
    +	bool "CAN loopback mode"
     	default n
     	---help---
     		Enable CAN loopback mode
    diff --git a/arch/avr/src/common/up_udelay.c b/arch/avr/src/common/up_udelay.c
    index f71d5ee6b2..4105623c3c 100644
    --- a/arch/avr/src/common/up_udelay.c
    +++ b/arch/avr/src/common/up_udelay.c
    @@ -75,7 +75,7 @@
      * Description:
      *   Delay inline for the requested number of microseconds.  NOTE:  Because
      *   of all of the setup, several microseconds will be lost before the actual
    - *   timing looop begins.  Thus, the delay will always be a few microseconds
    + *   timing loop begins.  Thus, the delay will always be a few microseconds
      *   longer than requested.
      *
      *   *** NOT multi-tasking friendly ***
    diff --git a/arch/hc/src/common/up_udelay.c b/arch/hc/src/common/up_udelay.c
    index d4b2d3aad8..490804a457 100644
    --- a/arch/hc/src/common/up_udelay.c
    +++ b/arch/hc/src/common/up_udelay.c
    @@ -75,7 +75,7 @@
      * Description:
      *   Delay inline for the requested number of microseconds.  NOTE:  Because
      *   of all of the setup, several microseconds will be lost before the actual
    - *   timing looop begins.  Thus, the delay will always be a few microseconds
    + *   timing loop begins.  Thus, the delay will always be a few microseconds
      *   longer than requested.
      *
      *   *** NOT multi-tasking friendly ***
    diff --git a/arch/mips/src/common/up_udelay.c b/arch/mips/src/common/up_udelay.c
    index 496811cd79..19a7fa0d6a 100644
    --- a/arch/mips/src/common/up_udelay.c
    +++ b/arch/mips/src/common/up_udelay.c
    @@ -75,7 +75,7 @@
      * Description:
      *   Delay inline for the requested number of microseconds.  NOTE:  Because
      *   of all of the setup, several microseconds will be lost before the actual
    - *   timing looop begins.  Thus, the delay will always be a few microseconds
    + *   timing loop begins.  Thus, the delay will always be a few microseconds
      *   longer than requested.
      *
      *   *** NOT multi-tasking friendly ***
    diff --git a/arch/misoc/src/common/misoc_udelay.c b/arch/misoc/src/common/misoc_udelay.c
    index 42bbc1f95a..9874e0695c 100644
    --- a/arch/misoc/src/common/misoc_udelay.c
    +++ b/arch/misoc/src/common/misoc_udelay.c
    @@ -59,7 +59,7 @@
      * Description:
      *   Delay inline for the requested number of microseconds.  NOTE:  Because
      *   of all of the setup, several microseconds will be lost before the actual
    - *   timing looop begins.  Thus, the delay will always be a few microseconds
    + *   timing loop begins.  Thus, the delay will always be a few microseconds
      *   longer than requested.
      *
      *   *** NOT multi-tasking friendly ***
    diff --git a/arch/renesas/src/common/up_udelay.c b/arch/renesas/src/common/up_udelay.c
    index 9f9bda3033..3cd9b4c0a6 100644
    --- a/arch/renesas/src/common/up_udelay.c
    +++ b/arch/renesas/src/common/up_udelay.c
    @@ -75,7 +75,7 @@
      * Description:
      *   Delay inline for the requested number of microseconds.  NOTE:  Because
      *   of all of the setup, several microseconds will be lost before the actual
    - *   timing looop begins.  Thus, the delay will always be a few microseconds
    + *   timing loop begins.  Thus, the delay will always be a few microseconds
      *   longer than requested.
      *
      *   *** NOT multi-tasking friendly ***
    diff --git a/arch/x86/src/common/up_udelay.c b/arch/x86/src/common/up_udelay.c
    index 4869741860..ea7841d5e3 100644
    --- a/arch/x86/src/common/up_udelay.c
    +++ b/arch/x86/src/common/up_udelay.c
    @@ -75,7 +75,7 @@
      * Description:
      *   Delay inline for the requested number of microseconds.  NOTE:  Because
      *   of all of the setup, several microseconds will be lost before the actual
    - *   timing looop begins.  Thus, the delay will always be a few microseconds
    + *   timing loop begins.  Thus, the delay will always be a few microseconds
      *   longer than requested.
      *
      *   *** NOT multi-tasking friendly ***
    diff --git a/arch/xtensa/src/common/xtensa_udelay.c b/arch/xtensa/src/common/xtensa_udelay.c
    index 09d16d5d4d..8ec27f1541 100644
    --- a/arch/xtensa/src/common/xtensa_udelay.c
    +++ b/arch/xtensa/src/common/xtensa_udelay.c
    @@ -59,7 +59,7 @@
      * Description:
      *   Delay inline for the requested number of microseconds.  NOTE:  Because
      *   of all of the setup, several microseconds will be lost before the actual
    - *   timing looop begins.  Thus, the delay will always be a few microseconds
    + *   timing loop begins.  Thus, the delay will always be a few microseconds
      *   longer than requested.
      *
      *   *** NOT multi-tasking friendly ***
    diff --git a/arch/z16/src/common/up_udelay.c b/arch/z16/src/common/up_udelay.c
    index 4b36bc2d3c..94a29a4fd0 100644
    --- a/arch/z16/src/common/up_udelay.c
    +++ b/arch/z16/src/common/up_udelay.c
    @@ -77,7 +77,7 @@
      * Description:
      *   Delay inline for the requested number of microseconds.  NOTE:  Because
      *   of all of the setup, several microseconds will be lost before the actual
    - *   timing looop begins.  Thus, the delay will always be a few microseconds
    + *   timing loop begins.  Thus, the delay will always be a few microseconds
      *   longer than requested.
      *
      *   *** NOT multi-tasking friendly ***
    diff --git a/arch/z80/src/common/up_udelay.c b/arch/z80/src/common/up_udelay.c
    index 85a1494b2f..98aca45898 100644
    --- a/arch/z80/src/common/up_udelay.c
    +++ b/arch/z80/src/common/up_udelay.c
    @@ -77,7 +77,7 @@
      * Description:
      *   Delay inline for the requested number of microseconds.  NOTE:  Because
      *   of all of the setup, several microseconds will be lost before the actual
    - *   timing looop begins.  Thus, the delay will always be a few microseconds
    + *   timing loop begins.  Thus, the delay will always be a few microseconds
      *   longer than requested.
      *
      *   *** NOT multi-tasking friendly ***
    -- 
    GitLab
    
    
    From eb1d4ca77463575daf948988166d28f01dac7c70 Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Sun, 23 Apr 2017 07:17:55 -0600
    Subject: [PATCH 560/990] SAM3/4:  Fixed configurations for TWI master. 
     Obviously an incomplete port from SAMA5.
    
    ---
     arch/arm/src/sam34/Kconfig   | 36 +++++++++++++++++++++++++++++++++++-
     arch/arm/src/sam34/sam_twi.c | 28 +++++++++++++++-------------
     2 files changed, 50 insertions(+), 14 deletions(-)
    
    diff --git a/arch/arm/src/sam34/Kconfig b/arch/arm/src/sam34/Kconfig
    index e9d3a7aece..806713c9d7 100644
    --- a/arch/arm/src/sam34/Kconfig
    +++ b/arch/arm/src/sam34/Kconfig
    @@ -572,7 +572,6 @@ config SAM34_TWIS
     	bool
     	default n
     
    -
     config SAM34_TWIM0
     	bool "Two-wire Master Interface 0 (TWIM0)"
     	default n
    @@ -1142,6 +1141,41 @@ config SAM34_SPI_REGDEBUG
     endmenu # AT91SAM3/4 SPI device driver options
     endif # SAM34_SPI0 || SAM34_SPI1
     
    +if SAM34_TWIM
    +
    +menu "AT91SAM3/4 TWI master device driver options"
    +
    +config SAM34_TWIM0_FREQUENCY
    +	int "TWI0 Frequency"
    +	default 100000
    +	depends on SAM34_TWIM0
    +
    +config SAM34_TWIM1_FREQUENCY
    +	int "TWI1 Frequency"
    +	default 100000
    +	depends on SAM34_TWIM1
    +
    +config SAM34_TWI2_FREQUENCY
    +	int "TWI2 Frequency"
    +	default 100000
    +	depends on SAM34_TWIM2
    +
    +config SAM34_TWI3_FREQUENCY
    +	int "TWI3 Frequency"
    +	default 100000
    +	depends on SAM34_TWIM3
    +
    +config SAM34_TWI_REGDEBUG
    +	bool "TWI register level debug"
    +	depends on DEBUG_I2C_INFO
    +	default n
    +	---help---
    +		Output detailed register-level TWI device debug information.
    +		Very invasive! Requires also CONFIG_DEBUG_I2C_INFO.
    +
    +endmenu # TWI device driver options
    +endif # SAM34_TWIM
    +
     menu "AT91SAM3/4 EMAC device driver options"
     	depends on SAM34_EMAC
     
    diff --git a/arch/arm/src/sam34/sam_twi.c b/arch/arm/src/sam34/sam_twi.c
    index 7242f4744d..ed52fb815a 100644
    --- a/arch/arm/src/sam34/sam_twi.c
    +++ b/arch/arm/src/sam34/sam_twi.c
    @@ -71,19 +71,21 @@
     #include "sam_gpio.h"
     #include "sam_twi.h"
     
    -#if defined(CONFIG_SAM34_TWI0) || defined(CONFIG_SAM34_TWI1)
    +/* REVISIT: Missing support for TWI2 master */
    +
    +#if defined(CONFIG_SAM34_TWIM0) || defined(CONFIG_SAM34_TWIM1)
     
     /****************************************************************************
      * Pre-processor Definitions
      ****************************************************************************/
     /* Configuration ***************************************************************/
     
    -#ifndef CONFIG_SAM34_TWI0_FREQUENCY
    -#  define CONFIG_SAM34_TWI0_FREQUENCY 100000
    +#ifndef CONFIG_SAM34_TWIM0_FREQUENCY
    +#  define CONFIG_SAM34_TWIM0_FREQUENCY 100000
     #endif
     
    -#ifndef CONFIG_SAM34_TWI1_FREQUENCY
    -#  define CONFIG_SAM34_TWI1_FREQUENCY 100000
    +#ifndef CONFIG_SAM34_TWIM1_FREQUENCY
    +#  define CONFIG_SAM34_TWIM1_FREQUENCY 100000
     #endif
     
     #ifndef CONFIG_DEBUG_I2C_INFO
    @@ -187,11 +189,11 @@ static void twi_hw_initialize(struct twi_dev_s *priv, unsigned int pid,
      * Private Data
      ****************************************************************************/
     
    -#ifdef CONFIG_SAM34_TWI0
    +#ifdef CONFIG_SAM34_TWIM0
     static struct twi_dev_s g_twi0;
     #endif
     
    -#ifdef CONFIG_SAM34_TWI1
    +#ifdef CONFIG_SAM34_TWIM1
     static struct twi_dev_s g_twi1;
     #endif
     
    @@ -901,7 +903,7 @@ struct i2c_master_s *sam_i2cbus_initialize(int bus)
     
       flags = enter_critical_section();
     
    -#ifdef CONFIG_SAM34_TWI0
    +#ifdef CONFIG_SAM34_TWIM0
       if (bus == 0)
         {
           /* Set up TWI0 register base address and IRQ number */
    @@ -922,18 +924,18 @@ struct i2c_master_s *sam_i2cbus_initialize(int bus)
     
           /* Select the TWI frequency, and peripheral ID */
     
    -      frequency  = CONFIG_SAM34_TWI0_FREQUENCY;
    +      frequency  = CONFIG_SAM34_TWIM0_FREQUENCY;
           pid        = SAM_PID_TWI0;
         }
       else
     #endif
    -#ifdef CONFIG_SAM34_TWI1
    +#ifdef CONFIG_SAM34_TWIM1
       if (bus == 1)
         {
           /* Set up TWI1 register base address and IRQ number */
     
           priv       = &g_twi1;
    -      priv->base = SAM_TWI0_BASE;
    +      priv->base = SAM_TWI1_BASE;
           priv->irq  = SAM_IRQ_TWI1;
           priv->twi  = 1;
     
    @@ -948,7 +950,7 @@ struct i2c_master_s *sam_i2cbus_initialize(int bus)
     
           /* Select the TWI frequency, and peripheral ID */
     
    -      frequency  = CONFIG_SAMA5_TWI1_FREQUENCY;
    +      frequency  = CONFIG_SAM34_TWIM1_FREQUENCY;
           pid        = SAM_PID_TWI1;
         }
       else
    @@ -1029,4 +1031,4 @@ int sam_i2cbus_uninitialize(FAR struct i2c_master_s * dev)
       return OK;
     }
     
    -#endif /* CONFIG_SAM34_TWI0 || CONFIG_SAM34_TWI1 */
    +#endif /* CONFIG_SAM34_TWIM0 || CONFIG_SAM34_TWIM1 */
    -- 
    GitLab
    
    
    From db9143b2bd98686690a49a013f079fcc1b840990 Mon Sep 17 00:00:00 2001
    From: kc_dtm 
    Date: Sun, 23 Apr 2017 07:21:44 -0600
    Subject: [PATCH 561/990] SAM3/4: Remove inappropriate semicolon.
    
    ---
     arch/arm/src/sam34/sam_twi.c | 2 +-
     1 file changed, 1 insertion(+), 1 deletion(-)
    
    diff --git a/arch/arm/src/sam34/sam_twi.c b/arch/arm/src/sam34/sam_twi.c
    index ed52fb815a..1b85275e8b 100644
    --- a/arch/arm/src/sam34/sam_twi.c
    +++ b/arch/arm/src/sam34/sam_twi.c
    @@ -432,7 +432,7 @@ static void twi_wakeup(struct twi_dev_s *priv, int result)
      *
      ****************************************************************************/
     
    -static int twi_interrupt(int irq, FAR void *context, FAR void *arg);
    +static int twi_interrupt(int irq, FAR void *context, FAR void *arg)
     {
       struct twi_dev_s *priv = (struct twi_dev_s *)arg;
       struct i2c_msg_s *msg;
    -- 
    GitLab
    
    
    From ca7d88f6bb3d3b1ae611b35432bbc2012d6b467c Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Sun, 23 Apr 2017 08:14:49 -0600
    Subject: [PATCH 562/990] SAM3/4:  Fix a few more naming differences noted by
     Alan Carvalho de Assiss.
    
    ---
     arch/arm/src/sam34/Kconfig | 4 ++--
     1 file changed, 2 insertions(+), 2 deletions(-)
    
    diff --git a/arch/arm/src/sam34/Kconfig b/arch/arm/src/sam34/Kconfig
    index 806713c9d7..862b381418 100644
    --- a/arch/arm/src/sam34/Kconfig
    +++ b/arch/arm/src/sam34/Kconfig
    @@ -1155,12 +1155,12 @@ config SAM34_TWIM1_FREQUENCY
     	default 100000
     	depends on SAM34_TWIM1
     
    -config SAM34_TWI2_FREQUENCY
    +config SAM34_TWIM2_FREQUENCY
     	int "TWI2 Frequency"
     	default 100000
     	depends on SAM34_TWIM2
     
    -config SAM34_TWI3_FREQUENCY
    +config SAM34_TWIM3_FREQUENCY
     	int "TWI3 Frequency"
     	default 100000
     	depends on SAM34_TWIM3
    -- 
    GitLab
    
    
    From a76266106a45bc28acac7c23db29adf078e7f511 Mon Sep 17 00:00:00 2001
    From: Simon Piriou 
    Date: Sat, 22 Apr 2017 20:55:22 +0200
    Subject: [PATCH 563/990] photon: fix compilation errors and update wlan
     defconfig
    
    ---
     config_wlan                                   | 33 ++++++++++++++++---
     drivers/wireless/ieee80211/bcmf_driver.h      |  2 ++
     include/nuttx/wireless/ieee80211/bcmf_board.h |  1 +
     3 files changed, 32 insertions(+), 4 deletions(-)
    
    diff --git a/config_wlan b/config_wlan
    index 9eaf60fd64..864769bc1c 100644
    --- a/config_wlan
    +++ b/config_wlan
    @@ -61,6 +61,7 @@ CONFIG_DEBUG_INFO=y
     # CONFIG_DEBUG_GRAPHICS is not set
     # CONFIG_DEBUG_LIB is not set
     # CONFIG_DEBUG_MM is not set
    +# CONFIG_DEBUG_WIRELESS is not set
     # CONFIG_DEBUG_SCHED is not set
     
     #
    @@ -125,6 +126,7 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_LPC2378 is not set
     # CONFIG_ARCH_CHIP_LPC31XX is not set
     # CONFIG_ARCH_CHIP_LPC43XX is not set
    +# CONFIG_ARCH_CHIP_MOXART is not set
     # CONFIG_ARCH_CHIP_NUC1XX is not set
     # CONFIG_ARCH_CHIP_SAMA5 is not set
     # CONFIG_ARCH_CHIP_SAMD is not set
    @@ -132,11 +134,12 @@ CONFIG_ARCH="arm"
     # CONFIG_ARCH_CHIP_SAM34 is not set
     # CONFIG_ARCH_CHIP_SAMV7 is not set
     CONFIG_ARCH_CHIP_STM32=y
    +# CONFIG_ARCH_CHIP_STM32F0 is not set
     # CONFIG_ARCH_CHIP_STM32F7 is not set
     # CONFIG_ARCH_CHIP_STM32L4 is not set
     # CONFIG_ARCH_CHIP_STR71X is not set
     # CONFIG_ARCH_CHIP_TMS570 is not set
    -# CONFIG_ARCH_CHIP_MOXART is not set
    +# CONFIG_ARCH_CHIP_XMC4 is not set
     # CONFIG_ARCH_ARM7TDMI is not set
     # CONFIG_ARCH_ARM926EJS is not set
     # CONFIG_ARCH_ARM920T is not set
    @@ -208,6 +211,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y
     # CONFIG_ARCH_CHIP_STM32L152V6 is not set
     # CONFIG_ARCH_CHIP_STM32L152V8 is not set
     # CONFIG_ARCH_CHIP_STM32L152VB is not set
    +# CONFIG_ARCH_CHIP_STM32L152CC is not set
    +# CONFIG_ARCH_CHIP_STM32L152RC is not set
    +# CONFIG_ARCH_CHIP_STM32L152VC is not set
     # CONFIG_ARCH_CHIP_STM32L162ZD is not set
     # CONFIG_ARCH_CHIP_STM32L162VE is not set
     # CONFIG_ARCH_CHIP_STM32F100C8 is not set
    @@ -407,9 +413,13 @@ CONFIG_STM32_HAVE_ADC3=y
     # CONFIG_STM32_HAVE_SDADC3_DMA is not set
     CONFIG_STM32_HAVE_CAN1=y
     CONFIG_STM32_HAVE_CAN2=y
    +# CONFIG_STM32_HAVE_COMP1 is not set
     # CONFIG_STM32_HAVE_COMP2 is not set
    +# CONFIG_STM32_HAVE_COMP3 is not set
     # CONFIG_STM32_HAVE_COMP4 is not set
    +# CONFIG_STM32_HAVE_COMP5 is not set
     # CONFIG_STM32_HAVE_COMP6 is not set
    +# CONFIG_STM32_HAVE_COMP7 is not set
     CONFIG_STM32_HAVE_DAC1=y
     CONFIG_STM32_HAVE_DAC2=y
     CONFIG_STM32_HAVE_RNG=y
    @@ -423,7 +433,10 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_HAVE_SPI6 is not set
     # CONFIG_STM32_HAVE_SAIPLL is not set
     # CONFIG_STM32_HAVE_I2SPLL is not set
    -# CONFIG_STM32_HAVE_OPAMP is not set
    +# CONFIG_STM32_HAVE_OPAMP1 is not set
    +# CONFIG_STM32_HAVE_OPAMP2 is not set
    +# CONFIG_STM32_HAVE_OPAMP3 is not set
    +# CONFIG_STM32_HAVE_OPAMP4 is not set
     # CONFIG_STM32_ADC1 is not set
     # CONFIG_STM32_ADC2 is not set
     # CONFIG_STM32_ADC3 is not set
    @@ -437,6 +450,7 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_I2C1 is not set
     # CONFIG_STM32_I2C2 is not set
     # CONFIG_STM32_I2C3 is not set
    +# CONFIG_STM32_OPAMP is not set
     # CONFIG_STM32_OTGFS is not set
     # CONFIG_STM32_OTGHS is not set
     # CONFIG_STM32_PWR is not set
    @@ -472,6 +486,7 @@ CONFIG_STM32_IWDG=y
     #
     # Alternate Pin Mapping
     #
    +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set
     # CONFIG_STM32_JTAG_DISABLE is not set
     # CONFIG_STM32_JTAG_FULL_ENABLE is not set
     # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
    @@ -561,6 +576,7 @@ CONFIG_ARCH_HAVE_MPU=y
     # CONFIG_ARCH_HAVE_EXTCLK is not set
     # CONFIG_ARCH_HAVE_POWEROFF is not set
     CONFIG_ARCH_HAVE_RESET=y
    +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set
     # CONFIG_ARCH_USE_MPU is not set
     # CONFIG_ARCH_IRQPRIO is not set
     CONFIG_ARCH_STACKDUMP=y
    @@ -685,7 +701,10 @@ CONFIG_SCHED_WAITPID=y
     #
     # Pthread Options
     #
    -# CONFIG_MUTEX_TYPES is not set
    +# CONFIG_PTHREAD_MUTEX_TYPES is not set
    +CONFIG_PTHREAD_MUTEX_ROBUST=y
    +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set
    +# CONFIG_PTHREAD_MUTEX_BOTH is not set
     CONFIG_NPTHREAD_KEYS=4
     # CONFIG_PTHREAD_CLEANUP is not set
     # CONFIG_CANCELLATION_POINTS is not set
    @@ -764,6 +783,11 @@ CONFIG_DEV_NULL=y
     #
     # Buffering
     #
    +
    +#
    +# Common  I/O Buffer Support
    +#
    +# CONFIG_DRIVERS_IOB is not set
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -888,6 +912,7 @@ CONFIG_USART1_2STOP=0
     # CONFIG_PSEUDOTERM is not set
     # CONFIG_USBDEV is not set
     # CONFIG_USBHOST is not set
    +# CONFIG_USBMISC is not set
     # CONFIG_HAVE_USBTRACE is not set
     CONFIG_DRIVERS_WIRELESS=y
     # CONFIG_WL_CC1101 is not set
    @@ -1188,9 +1213,9 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_TIFF is not set
     # CONFIG_EXAMPLES_TOUCHSCREEN is not set
     # CONFIG_EXAMPLES_USBSERIAL is not set
    -# CONFIG_EXAMPLES_USBTERM is not set
     # CONFIG_EXAMPLES_WATCHDOG is not set
     # CONFIG_EXAMPLES_WEBSERVER is not set
    +# CONFIG_EXAMPLES_XBC_TEST is not set
     
     #
     # File System Utilities
    diff --git a/drivers/wireless/ieee80211/bcmf_driver.h b/drivers/wireless/ieee80211/bcmf_driver.h
    index 483f719a3e..1d32317e7d 100644
    --- a/drivers/wireless/ieee80211/bcmf_driver.h
    +++ b/drivers/wireless/ieee80211/bcmf_driver.h
    @@ -82,4 +82,6 @@ struct bcmf_dev_s
       uint8_t mac_addr[6];             /* Current mac address */
     };
     
    +int bcmf_wl_initialize(FAR struct bcmf_dev_s *priv);
    +
     #endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_DRIVER_H */
    diff --git a/include/nuttx/wireless/ieee80211/bcmf_board.h b/include/nuttx/wireless/ieee80211/bcmf_board.h
    index 33c618f22a..868712c6c3 100644
    --- a/include/nuttx/wireless/ieee80211/bcmf_board.h
    +++ b/include/nuttx/wireless/ieee80211/bcmf_board.h
    @@ -41,6 +41,7 @@
      ****************************************************************************/
     
     #include 
    +#include 
     
     #ifdef __cplusplus
     #define EXTERN extern "C"
    -- 
    GitLab
    
    
    From e1a4e88a55cf3f9f61cb4346a5eaaee0376661e6 Mon Sep 17 00:00:00 2001
    From: Simon Piriou 
    Date: Sun, 23 Apr 2017 12:26:52 +0200
    Subject: [PATCH 564/990] photon: add DOWNLOAD function to upload firmware
     through DFU
    
    ---
     Kconfig                      | 19 +++++++++++++++++++
     config_wlan                  |  4 ++++
     configs/photon/nsh/Make.defs | 20 ++++++++++++++++++++
     3 files changed, 43 insertions(+)
    
    diff --git a/Kconfig b/Kconfig
    index 1116ba6ccc..451b22206d 100644
    --- a/Kconfig
    +++ b/Kconfig
    @@ -313,6 +313,25 @@ config UIMAGE_ENTRY_POINT
     	hex "uImage entry point"
     	default 0x0
     
    +endif
    +
    +menuconfig DFU_BINARY
    +	bool "DFU binary format"
    +	select RAW_BINARY
    +	---help---
    +	Create the dfu binary used with dfu-utils.
    +
    +if DFU_BINARY
    +
    +config DFU_BASE
    +	hex "Address DFU image is loaded to"
    +
    +config DFU_VID
    +	hex "VID to use for DFU image"
    +
    +config DFU_PID
    +	hex "PID to use for DFU image"
    +
     endif
     endmenu # Binary Output Formats
     
    diff --git a/config_wlan b/config_wlan
    index 864769bc1c..0e606cb11f 100644
    --- a/config_wlan
    +++ b/config_wlan
    @@ -28,6 +28,10 @@ CONFIG_INTELHEX_BINARY=y
     # CONFIG_MOTOROLA_SREC is not set
     CONFIG_RAW_BINARY=y
     # CONFIG_UBOOT_UIMAGE is not set
    +CONFIG_DFU_BINARY=y
    +CONFIG_DFU_BASE=0x8020000
    +CONFIG_DFU_VID=0x2b04
    +CONFIG_DFU_PID=0xd006
     
     #
     # Customize Header Files
    diff --git a/configs/photon/nsh/Make.defs b/configs/photon/nsh/Make.defs
    index b6f58f2943..724f65af15 100644
    --- a/configs/photon/nsh/Make.defs
    +++ b/configs/photon/nsh/Make.defs
    @@ -68,6 +68,9 @@ NM = $(ARCROSSDEV)nm
     OBJCOPY = $(CROSSDEV)objcopy
     OBJDUMP = $(CROSSDEV)objdump
     
    +DFUSUFFIX = dfu-suffix
    +DFUUTIL = dfu-util
    +
     ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'}
     ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1}
     
    @@ -114,3 +117,20 @@ HOSTCC = gcc
     HOSTINCLUDES = -I.
     HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -Wundef -g -pipe
     HOSTLDFLAGS =
    +
    +ifeq ($(CONFIG_DFU_BINARY),y)
    +
    +define DOWNLOAD
    +  $(Q) echo "DFUSUFFIX: $(1).dfu"
    +  $(Q) $(OBJCOPY) $(OBJCOPYARGS) -O binary $(1) $(1).dfu
    +  $(Q) $(DFUSUFFIX) -v $(subst 0x,,$(CONFIG_DFU_VID)) -p $(subst 0x,,$(CONFIG_DFU_PID)) -a $(1).dfu
    +  $(Q) $(DFUUTIL) -d $(CONFIG_DFU_VID):$(CONFIG_DFU_PID) -a 0 -s $(CONFIG_DFU_BASE) -D $(1).dfu
    +endef
    +
    +else
    +
    +define DOWNLOAD
    +  $(Q) $(ECHO) "Photon firmware upload through JTAG is not supported"
    +endef
    +
    +endif
    \ No newline at end of file
    -- 
    GitLab
    
    
    From 6601912f12165ff5046fcb7e13f8d8aff1e58e33 Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Sun, 23 Apr 2017 10:56:33 -0600
    Subject: [PATCH 565/990] Add URL for dfu-util
    
    ---
     configs/photon/nsh/Make.defs | 5 ++++-
     1 file changed, 4 insertions(+), 1 deletion(-)
    
    diff --git a/configs/photon/nsh/Make.defs b/configs/photon/nsh/Make.defs
    index 724f65af15..a3d6f0de35 100644
    --- a/configs/photon/nsh/Make.defs
    +++ b/configs/photon/nsh/Make.defs
    @@ -68,6 +68,8 @@ NM = $(ARCROSSDEV)nm
     OBJCOPY = $(CROSSDEV)objcopy
     OBJDUMP = $(CROSSDEV)objdump
     
    +# See http://dfu-util.sourceforge.net/
    +
     DFUSUFFIX = dfu-suffix
     DFUUTIL = dfu-util
     
    @@ -133,4 +135,5 @@ define DOWNLOAD
       $(Q) $(ECHO) "Photon firmware upload through JTAG is not supported"
     endef
     
    -endif
    \ No newline at end of file
    +endif
    +
    -- 
    GitLab
    
    
    From c0862c862f2c9a220cc82b366472d6320fcf9514 Mon Sep 17 00:00:00 2001
    From: Simon Piriou 
    Date: Sun, 23 Apr 2017 22:17:43 +0200
    Subject: [PATCH 566/990] photon: cleanup and refactor bcmf driver
    
    ---
     configs/photon/src/stm32_wlan_firmware.c      |   8 +-
     drivers/wireless/ieee80211/Make.defs          |  11 +-
     .../wireless/ieee80211/bcm43362_constants.h   |  76 ----
     drivers/wireless/ieee80211/bcmf_cdc.c         | 333 ++++++++++++++
     drivers/wireless/ieee80211/bcmf_cdc.h         |  23 +
     drivers/wireless/ieee80211/bcmf_chip_43362.c  | 101 +++--
     drivers/wireless/ieee80211/bcmf_chip_43362.h  |   8 -
     drivers/wireless/ieee80211/bcmf_core.c        | 134 +++---
     drivers/wireless/ieee80211/bcmf_core.h        |  31 +-
     drivers/wireless/ieee80211/bcmf_driver.c      | 129 +++++-
     drivers/wireless/ieee80211/bcmf_driver.h      |  66 +--
     drivers/wireless/ieee80211/bcmf_sdio.c        | 320 +++++++------
     drivers/wireless/ieee80211/bcmf_sdio.h        |  61 ++-
     drivers/wireless/ieee80211/bcmf_sdio_core.h   |  13 +-
     drivers/wireless/ieee80211/bcmf_sdpcm.c       | 428 +++++-------------
     drivers/wireless/ieee80211/bcmf_sdpcm.h       |  10 +-
     .../{bcmf_hexdump.c => bcmf_utils.c}          |  34 +-
     drivers/wireless/ieee80211/bcmf_utils.h       |  11 +
     18 files changed, 1056 insertions(+), 741 deletions(-)
     delete mode 100644 drivers/wireless/ieee80211/bcm43362_constants.h
     create mode 100644 drivers/wireless/ieee80211/bcmf_cdc.c
     create mode 100644 drivers/wireless/ieee80211/bcmf_cdc.h
     delete mode 100644 drivers/wireless/ieee80211/bcmf_chip_43362.h
     rename drivers/wireless/ieee80211/{bcmf_hexdump.c => bcmf_utils.c} (50%)
     create mode 100644 drivers/wireless/ieee80211/bcmf_utils.h
    
    diff --git a/configs/photon/src/stm32_wlan_firmware.c b/configs/photon/src/stm32_wlan_firmware.c
    index d550643d97..a1290ad162 100644
    --- a/configs/photon/src/stm32_wlan_firmware.c
    +++ b/configs/photon/src/stm32_wlan_firmware.c
    @@ -45,7 +45,7 @@
      * Character array of NVRAM image
      */
     
    -const char __attribute__((section(".wlan_nvram_image"))) bcmf_nvram_image[] =
    +const char __attribute__((section(".wlan_nvram_image"))) bcm43362_nvram_image[] =
             "manfid=0x2d0"                                              "\x00"
             "prodid=0x492"                                              "\x00"
             "vendid=0x14e4"                                             "\x00"
    @@ -106,10 +106,10 @@ const char __attribute__((section(".wlan_nvram_image"))) bcmf_nvram_image[] =
             "edoffthd=-76"                                              "\x00"
             "\x00\x00";
     
    -const unsigned int bcmf_nvram_image_len = sizeof(bcmf_nvram_image);
    +const unsigned int bcm43362_nvram_image_len = sizeof(bcm43362_nvram_image);
     
     const uint8_t
    -__attribute__((section(".wlan_firmware_image"))) bcmf_firmware_image[] = {
    +__attribute__((section(".wlan_firmware_image"))) bcm43362_firmware_image[] = {
       0x00, 0x00, 0x00, 0x00, 0xcd, 0xc2, 0x00, 0x00, 0x91, 0xc1, 0x00, 0x00,
       0x91, 0xc1, 0x00, 0x00, 0x91, 0xc1, 0x00, 0x00, 0x91, 0xc1, 0x00, 0x00,
       0x91, 0xc1, 0x00, 0x00, 0x91, 0xc1, 0x00, 0x00, 0x91, 0xc1, 0x00, 0x00,
    @@ -17647,4 +17647,4 @@ __attribute__((section(".wlan_firmware_image"))) bcmf_firmware_image[] = {
       0xd2, 0x58, 0x82, 0x92
     };
     
    -const unsigned int bcmf_firmware_image_len = sizeof(bcmf_firmware_image);
    +const unsigned int bcm43362_firmware_image_len = sizeof(bcm43362_firmware_image);
    \ No newline at end of file
    diff --git a/drivers/wireless/ieee80211/Make.defs b/drivers/wireless/ieee80211/Make.defs
    index e7d41ee762..eebfb9f821 100644
    --- a/drivers/wireless/ieee80211/Make.defs
    +++ b/drivers/wireless/ieee80211/Make.defs
    @@ -40,19 +40,24 @@ ifeq ($(CONFIG_DRIVERS_IEEE80211),y)
     
     # Include IEEE 802.11 drivers into the build
     
    -ifeq ($(CONFIG_IEEE80211_BROADCOM_FULLMAC_SDIO),y)
    +ifeq ($(CONFIG_IEEE80211_BROADCOM_FULLMAC),y)
       CSRCS += bcmf_driver.c
    +  CSRCS += bcmf_cdc.c
    +  CSRCS += bcmf_utils.c
    +
    +ifeq ($(CONFIG_IEEE80211_BROADCOM_FULLMAC_SDIO),y)  
    +  CSRCS += mmc_sdio.c
       CSRCS += bcmf_sdio.c
       CSRCS += bcmf_core.c
       CSRCS += bcmf_sdpcm.c
    -  CSRCS += bcmf_hexdump.c
    -  CSRCS += mmc_sdio.c
     endif
     
     ifeq ($(CONFIG_IEEE80211_BROADCOM_BCM43362),y)
     CSRCS += bcmf_chip_43362.c
     endif
     
    +endif # CONFIG_IEEE80211_BROADCOM_FULLMAC
    +
     # Include IEEE 802.11 build support
     
     DEPPATH += --dep-path wireless$(DELIM)ieee80211
    diff --git a/drivers/wireless/ieee80211/bcm43362_constants.h b/drivers/wireless/ieee80211/bcm43362_constants.h
    deleted file mode 100644
    index 4144c049b6..0000000000
    --- a/drivers/wireless/ieee80211/bcm43362_constants.h
    +++ /dev/null
    @@ -1,76 +0,0 @@
    -/*
    - * Copyright (c) 2015 Broadcom
    - * 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 of Broadcom nor the names of other contributors to this
    - * software may be used to endorse or promote products derived from this software
    - * without specific prior written permission.
    - *
    - * 4. This software may not be used as a standalone product, and may only be used as
    - * incorporated in your product or device that incorporates Broadcom wireless connectivity
    - * products and solely for the purpose of enabling the functionalities of such Broadcom products.
    - *
    - *
    - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
    - * ANY WARRANTIES OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
    - * WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT, ARE
    - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER 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 BCM43362_CONSTANTS_H_
    -#define BCM43362_CONSTANTS_H_
    -
    -/******************************************************
    - *             Architecture Constants
    - ******************************************************/
    -
    -/* General chip stats */
    -#define CHIP_RAM_SIZE      0x3C000
    -
    -/* Backplane architecture */
    -#define CHIPCOMMON_BASE_ADDRESS  0x18000000    /* Chipcommon core register region   */
    -#define DOT11MAC_BASE_ADDRESS    0x18001000    /* dot11mac core register region     */
    -#define SDIO_BASE_ADDRESS        0x18002000    /* SDIOD Device core register region */
    -#define WLAN_ARMCM3_BASE_ADDRESS 0x18003000    /* ARMCM3 core register region       */
    -#define SOCSRAM_BASE_ADDRESS     0x18004000    /* SOCSRAM core register region      */
    -#define BACKPLANE_ADDRESS_MASK   0x7FFF
    -
    -/* Maximum value of bus data credit difference */
    -#define CHIP_MAX_BUS_DATA_CREDIT_DIFF    7
    -
    -/* Chipcommon registers */
    -#define CHIPCOMMON_GPIO_CONTROL ((uint32_t) (CHIPCOMMON_BASE_ADDRESS + 0x6C) )
    -
    -/******************************************************
    - *             Bit Masks
    - ******************************************************/
    -
    -#define WL_CHANSPEC_BAND_MASK             (0xf000)
    -#define WL_CHANSPEC_BAND_5G               (0x1000)
    -#define WL_CHANSPEC_BAND_2G               (0x2000)
    -#define WL_CHANSPEC_CTL_SB_MASK           (0x0300)
    -#define WL_CHANSPEC_CTL_SB_LOWER          (0x0100)
    -#define WL_CHANSPEC_CTL_SB_UPPER          (0x0200)
    -#define WL_CHANSPEC_CTL_SB_NONE           (0x0300)
    -#define WL_CHANSPEC_BW_MASK               (0x0C00)
    -#define WL_CHANSPEC_BW_10                 (0x0400)
    -#define WL_CHANSPEC_BW_20                 (0x0800)
    -#define WL_CHANSPEC_BW_40                 (0x0C00)
    -
    -#endif /* ifndef BCM43362_CONSTANTS_H_ */
    diff --git a/drivers/wireless/ieee80211/bcmf_cdc.c b/drivers/wireless/ieee80211/bcmf_cdc.c
    new file mode 100644
    index 0000000000..b3f772963f
    --- /dev/null
    +++ b/drivers/wireless/ieee80211/bcmf_cdc.c
    @@ -0,0 +1,333 @@
    +/****************************************************************************
    + * drivers/wireless/ieee80211/bcmf_cdc.c
    + *
    + *   Copyright (C) 2017 Gregory Nutt. All rights reserved.
    + *   Author: Simon Piriou 
    + *
    + * 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 "bcmf_driver.h"
    +#include "bcmf_ioctl.h"
    +#include "bcmf_utils.h"
    +
    +/****************************************************************************
    + * Pre-processor Definitions
    + ****************************************************************************/
    +
    +/* CDC flag definitions */
    +#define CDC_DCMD_ERROR    0x01       /* 1=cmd failed */
    +#define CDC_DCMD_SET      0x02       /* 0=get, 1=set cmd */
    +#define CDC_DCMD_IF_MASK  0xF000     /* I/F index */
    +#define CDC_DCMD_IF_SHIFT 12
    +#define CDC_DCMD_ID_MASK  0xFFFF0000 /* id an cmd pairing */
    +#define CDC_DCMD_ID_SHIFT 16         /* ID Mask shift bits */
    +#define CDC_DCMD_ID(flags)  \
    +  (((flags) & CDC_DCMD_ID_MASK) >> CDC_DCMD_ID_SHIFT)
    +
    +#define CDC_CONTROL_TIMEOUT_MS 1000
    +
    +/****************************************************************************
    + * Private Types
    + ****************************************************************************/
    +
    +struct bcmf_cdc_header {
    +    uint32_t cmd;    /* dongle command value */
    +    uint32_t len;    /* lower 16: output buflen;
    +                      * upper 16: input buflen (excludes header) */
    +    uint32_t flags;  /* flag defns given below */
    +    uint32_t status; /* status code returned from the device */
    +};
    +
    +/****************************************************************************
    + * Private Function Prototypes
    + ****************************************************************************/
    +
    +static struct bcmf_frame_s* bcmf_cdc_allocate_frame(
    +                                FAR struct bcmf_dev_s *priv, char *name,
    +                                uint8_t *data, uint32_t len);
    +
    +static int bcmf_cdc_sendframe(FAR struct bcmf_dev_s *priv, uint32_t cmd,
    +                         int ifidx, bool set, struct bcmf_frame_s *frame);
    +
    +static int bcmf_cdc_control_request(FAR struct bcmf_dev_s *priv,
    +                               uint32_t ifidx, bool set, uint32_t cmd,
    +                               char *name, uint8_t *data, uint32_t *len);
    +
    +/****************************************************************************
    + * Private Data
    + ****************************************************************************/
    +
    +/****************************************************************************
    + * Private Functions
    + ****************************************************************************/
    +
    +struct bcmf_frame_s* bcmf_cdc_allocate_frame(FAR struct bcmf_dev_s *priv,
    +                                char *name, uint8_t *data, uint32_t len)
    +{
    +  uint32_t data_len;
    +  uint16_t name_len;
    +  struct bcmf_frame_s *frame;
    +
    +  if (name)
    +    {
    +      name_len = strlen(name) + 1;
    +    }
    +  else
    +    {
    +      name_len = 0;
    +    }
    +
    +  if (data)
    +    {
    +      data_len = len;
    +    }
    +  else
    +    {
    +      data_len = 0;
    +    }
    +
    +  if (data_len + name_len + sizeof(struct bcmf_cdc_header) < data_len)
    +    {
    +      /* Integer overflow */
    +
    +      return NULL;
    +    }
    +
    +  /* Allocate control frame */
    +
    +  frame = priv->bus->allocate_frame(priv,
    +                sizeof(struct bcmf_cdc_header) + data_len + name_len,
    +                true, true);
    +  
    +  if (!frame)
    +    {
    +      return NULL;
    +    }
    +
    +  /* Copy name string and data */
    +
    +  memcpy(frame->data + sizeof(struct bcmf_cdc_header), name, name_len);
    +  memcpy(frame->data + sizeof(struct bcmf_cdc_header)
    +                     + name_len, data, data_len);
    +
    +  return frame;
    +}
    +
    +int bcmf_cdc_sendframe(FAR struct bcmf_dev_s *priv, uint32_t cmd,
    +                         int ifidx, bool set, struct bcmf_frame_s *frame)
    +{
    +  struct bcmf_cdc_header* header =
    +                  (struct bcmf_cdc_header*)frame->data;
    +
    +  /* Setup cdc_dcmd header */
    +
    +  uint32_t cdc_data_len = frame->len - (uint32_t)(frame->data-frame->base);
    +  header->cmd = cmd;
    +  header->len = cdc_data_len-sizeof(struct bcmf_cdc_header);
    +  header->status = 0;
    +  header->flags = ++priv->control_reqid << CDC_DCMD_ID_SHIFT;
    +  header->flags |= ifidx << CDC_DCMD_IF_SHIFT;
    +
    +  if (set)
    +  {
    +    header->flags |= CDC_DCMD_SET;
    +  }
    +
    +  /* Queue frame */
    +
    +  return priv->bus->txframe(priv, frame);
    +}
    +
    +int bcmf_cdc_control_request(FAR struct bcmf_dev_s *priv,
    +                               uint32_t ifidx, bool set, uint32_t cmd,
    +                               char *name, uint8_t *data, uint32_t *len)
    +{
    +  int ret;
    +  struct bcmf_frame_s *frame;
    +  uint32_t out_len = *len;
    +
    +  *len = 0;
    +
    +  /* Take device control mutex */
    +
    +  if ((ret = sem_wait(&priv->control_mutex)) != OK)
    +   {
    +      return ret;
    +   }
    +
    +  /* Prepare control frame */
    +
    +  frame = bcmf_cdc_allocate_frame(priv, name, data, out_len);
    +  if (!frame)
    +    {
    +      _err("Cannot allocate cdc frame\n");
    +      ret = -ENOMEM;
    +      goto exit_sem_post;
    +    }
    +
    +  /* Setup buffer to store response */
    +
    +  priv->control_rxdata = set ? NULL : data;
    +  priv->control_rxdata_len = out_len;
    +
    +  /* Send control frame. iovar buffer is freed when sent */
    +
    +  ret = bcmf_cdc_sendframe(priv, cmd, ifidx, set, frame);
    +  if (ret != OK)
    +    {
    +      // TODO free allocated iovar buffer here
    +      goto exit_sem_post;
    +    }
    +
    +  ret = bcmf_sem_wait(&priv->control_timeout, CDC_CONTROL_TIMEOUT_MS);
    +  if (ret != OK)
    +    {
    +      _err("Error while waiting for control response %d\n", ret);
    +      goto exit_sem_post;
    +    }
    +
    +  *len = priv->control_rxdata_len;
    +
    +  /* Check frame status */
    +
    +  if (priv->control_status != 0)
    +    {
    +      _err("Invalid cdc status 0x%x\n", priv->control_status);
    +      ret = -EINVAL;
    +    }
    +
    +exit_sem_post:
    +  sem_post(&priv->control_mutex);
    +  return ret;
    +}
    +
    +/****************************************************************************
    + * Public Functions
    + ****************************************************************************/
    +
    +int bcmf_cdc_iovar_request(FAR struct bcmf_dev_s *priv,
    +                             uint32_t ifidx, bool set, char *name,
    +                             uint8_t *data, uint32_t *len)
    +{
    +  return bcmf_cdc_control_request(priv, ifidx, set,
    +                                  set ? WLC_SET_VAR : WLC_GET_VAR, name,
    +                                  data, len);
    +}
    +
    +int bcmf_cdc_ioctl(FAR struct bcmf_dev_s *priv,
    +                     uint32_t ifidx, bool set, uint32_t cmd,
    +                     uint8_t *data, uint32_t *len)
    +{
    +  return bcmf_cdc_control_request(priv, ifidx, set, cmd, NULL, data, len);
    +}
    +
    +int bcmf_cdc_process_control_frame(FAR struct bcmf_dev_s *priv,
    +                   struct bcmf_frame_s *frame)
    +{
    +  unsigned int data_size;
    +  struct bcmf_cdc_header *cdc_header;
    +
    +  /* Check frame */
    +
    +  data_size = frame->len - (unsigned int)(frame->data - frame->base);
    +
    +  if (data_size < sizeof(struct bcmf_cdc_header))
    +    {
    +      _err("Control frame too small\n");
    +      return -EINVAL;
    +    }
    +
    +  cdc_header = (struct bcmf_cdc_header*)frame->data;
    +
    +  if (data_size < cdc_header->len ||
    +      data_size < sizeof(struct bcmf_cdc_header) + cdc_header->len)
    +    {
    +      _err("Invalid control frame size\n");
    +      return -EINVAL;
    +    }
    +
    +  // TODO check interface ?
    +
    +  if (cdc_header->flags >> CDC_DCMD_ID_SHIFT == priv->control_reqid)
    +    {
    +      /* Expected frame received, send it back to user */
    +
    +      priv->control_status = cdc_header->status;
    +
    +      if (priv->control_rxdata)
    +        {
    +          if (priv->control_rxdata_len > cdc_header->len)
    +            {
    +              _err("Not enough data %d %d\n",
    +                      priv->control_rxdata_len, cdc_header->len);
    +              priv->control_rxdata_len = cdc_header->len;
    +            }
    +          memcpy(priv->control_rxdata, (uint8_t*)&cdc_header[1],
    +                                       priv->control_rxdata_len);
    +        }
    +
    +      sem_post(&priv->control_timeout);
    +      return OK;
    +    }
    +
    +  _info("Got unexpected control frame\n");
    +  return -EINVAL;
    +}
    +
    +int bcmf_cdc_process_event_frame(FAR struct bcmf_dev_s *priv,
    +                   struct bcmf_frame_s *frame)
    +{
    +  _info("Event message\n");
    +  bcmf_hexdump(frame->base, frame->len, (unsigned long)frame->base);
    +  return OK;
    +}
    +
    +int bcmf_cdc_process_data_frame(FAR struct bcmf_dev_s *priv,
    +                   struct bcmf_frame_s *frame)
    +{
    +  _info("Data message\n");
    +  bcmf_hexdump(frame->base, frame->len, (unsigned long)frame->base);
    +  return OK;
    +}
    \ No newline at end of file
    diff --git a/drivers/wireless/ieee80211/bcmf_cdc.h b/drivers/wireless/ieee80211/bcmf_cdc.h
    new file mode 100644
    index 0000000000..d19661c06f
    --- /dev/null
    +++ b/drivers/wireless/ieee80211/bcmf_cdc.h
    @@ -0,0 +1,23 @@
    +#ifndef __DRIVERS_WIRELESS_IEEE80211_BCMF_CDC_H
    +#define __DRIVERS_WIRELESS_IEEE80211_BCMF_CDC_H
    +
    +#include "bcmf_driver.h"
    +#include 
    +#include 
    +
    +int bcmf_cdc_iovar_request(FAR struct bcmf_dev_s *priv, uint32_t ifidx,
    +                           bool set, char *name, uint8_t *data, uint32_t *len);
    +
    +int bcmf_cdc_ioctl(FAR struct bcmf_dev_s *priv, uint32_t ifidx, bool set,
    +                   uint32_t cmd, uint8_t *data, uint32_t *len);
    +
    +int bcmf_cdc_process_control_frame(FAR struct bcmf_dev_s *priv,
    +								   struct bcmf_frame_s *frame);
    +
    +int bcmf_cdc_process_data_frame(FAR struct bcmf_dev_s *priv,
    +								struct bcmf_frame_s *frame);
    +
    +int bcmf_cdc_process_event_frame(FAR struct bcmf_dev_s *priv,
    +								 struct bcmf_frame_s *frame);
    +
    +#endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_CDC_H */
    \ No newline at end of file
    diff --git a/drivers/wireless/ieee80211/bcmf_chip_43362.c b/drivers/wireless/ieee80211/bcmf_chip_43362.c
    index 0c940ffae5..f53fb06b8e 100644
    --- a/drivers/wireless/ieee80211/bcmf_chip_43362.c
    +++ b/drivers/wireless/ieee80211/bcmf_chip_43362.c
    @@ -1,28 +1,73 @@
    -#include "bcmf_chip_43362.h"
    -#include "bcm43362_constants.h"
    -
    -#include 
    -#include 
    -#include "bcmf_sdio_core.h"
    -
    -#define WRAPPER_REGISTER_OFFSET  (0x100000)
    -
    -uint32_t bcmf_43362_get_core_base_address(unsigned int core)
    -{
    -  switch (core)
    -    {
    -      case CHIPCOMMON_CORE_ID:
    -        return CHIPCOMMON_BASE_ADDRESS;
    -      case DOT11MAC_CORE_ID:
    -        return DOT11MAC_BASE_ADDRESS;
    -      case SDIOD_CORE_ID:
    -        return SDIO_BASE_ADDRESS;
    -      case WLAN_ARMCM3_CORE_ID:
    -        return WLAN_ARMCM3_BASE_ADDRESS + WRAPPER_REGISTER_OFFSET;
    -      case SOCSRAM_CORE_ID:
    -        return SOCSRAM_BASE_ADDRESS + WRAPPER_REGISTER_OFFSET;
    -      default:
    -        _err("Invalid core id %d\n", core);
    -    }
    -  return 0;
    -}
    +/****************************************************************************
    + * drivers/wireless/ieee80211/bcmf_chip_43362.c
    + *
    + *   Copyright (C) 2017 Gregory Nutt. All rights reserved.
    + *   Author: Simon Piriou 
    + *
    + * 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.
    + *
    + ****************************************************************************/
    +
    +#include "bcmf_sdio.h"
    +          
    +#define WRAPPER_REGISTER_OFFSET  0x100000
    +
    +extern const char bcm43362_nvram_image[];
    +extern const unsigned int bcm43362_nvram_image_len;
    +
    +extern const uint8_t bcm43362_firmware_image[];
    +extern const unsigned int bcm43362_firmware_image_len;
    +
    +const struct bcmf_sdio_chip bcmf_43362_config_sdio = {
    +
    +  /* General chip stats */
    +
    +  .ram_size = 0x3C000,
    +
    +  /* Backplane architecture */
    +
    +  .core_base = {
    +    [CHIPCOMMON_CORE_ID]  = 0x18000000,  /* Chipcommon core register base   */
    +    [DOT11MAC_CORE_ID]    = 0x18001000,  /* dot11mac core register base     */
    +    [SDIOD_CORE_ID]       = 0x18002000,  /* SDIOD Device core register base */
    +    [WLAN_ARMCM3_CORE_ID] = 0x18003000 + /* ARMCM3 core register base       */
    +                            WRAPPER_REGISTER_OFFSET,
    +    [SOCSRAM_CORE_ID]     = 0x18004000 + /* SOCSRAM core register base      */
    +                            WRAPPER_REGISTER_OFFSET
    +  },
    +
    +  /* Firmware images */
    +
    +  // TODO find something smarter than using image_len references
    +
    +  .firmware_image      = bcm43362_firmware_image,
    +  .firmware_image_size = (unsigned int*)&bcm43362_firmware_image_len,
    +
    +  .nvram_image         = bcm43362_nvram_image,
    +  .nvram_image_size    = (unsigned int*)&bcm43362_nvram_image_len
    +};
    \ No newline at end of file
    diff --git a/drivers/wireless/ieee80211/bcmf_chip_43362.h b/drivers/wireless/ieee80211/bcmf_chip_43362.h
    deleted file mode 100644
    index 08f6918f62..0000000000
    --- a/drivers/wireless/ieee80211/bcmf_chip_43362.h
    +++ /dev/null
    @@ -1,8 +0,0 @@
    -#ifndef __DRIVERS_WIRELESS_IEEE80211_BCM_CHIP_43362_H
    -#define __DRIVERS_WIRELESS_IEEE80211_BCM_CHIP_43362_H
    -
    -#include 
    -
    -uint32_t bcmf_43362_get_core_base_address(unsigned int core);
    -
    -#endif /* __DRIVERS_WIRELESS_IEEE80211_BCM_CHIP_43362_H */
    diff --git a/drivers/wireless/ieee80211/bcmf_core.c b/drivers/wireless/ieee80211/bcmf_core.c
    index 0da0e2131c..a0bf4ab262 100644
    --- a/drivers/wireless/ieee80211/bcmf_core.c
    +++ b/drivers/wireless/ieee80211/bcmf_core.c
    @@ -48,6 +48,8 @@
     #include "bcmf_core.h"
     #include "bcmf_sdio.h"
     
    +#include "bcmf_sdio_regs.h"
    +
     /****************************************************************************
      * Pre-processor Definitions
      ****************************************************************************/
    @@ -75,15 +77,6 @@
     /* Transfer size properties */
     #define BCMF_UPLOAD_TRANSFER_SIZE     (64 * 256)
     
    -// TODO move in chip configuration data
    -#define CHIP_RAM_SIZE                 0x3C000
    -
    -extern const char bcmf_nvram_image[];
    -extern const unsigned int bcmf_nvram_image_len;
    -
    -extern const uint8_t bcmf_firmware_image[];
    -extern const unsigned int bcmf_firmware_image_len;
    -
     /****************************************************************************
      * Private Types
      ****************************************************************************/
    @@ -92,14 +85,14 @@ extern const unsigned int bcmf_firmware_image_len;
      * Private Function Prototypes
      ****************************************************************************/
     
    -static int bcmf_core_set_backplane_window(FAR struct bcmf_dev_s *priv,
    +static int bcmf_core_set_backplane_window(FAR struct bcmf_sdio_dev_s *sbus,
                                               uint32_t address);
     
    -static int bcmf_upload_binary(FAR struct bcmf_dev_s *priv,
    +static int bcmf_upload_binary(FAR struct bcmf_sdio_dev_s *sbusv,
                                        uint32_t address, uint8_t *buf,
                                        unsigned int len);
     
    -static int bcmf_upload_nvram(FAR struct bcmf_dev_s *priv);
    +static int bcmf_upload_nvram(FAR struct bcmf_sdio_dev_s *sbus);
     
     /****************************************************************************
      * Private Data
    @@ -109,7 +102,8 @@ static int bcmf_upload_nvram(FAR struct bcmf_dev_s *priv);
      * Private Functions
      ****************************************************************************/
     
    -int bcmf_core_set_backplane_window(FAR struct bcmf_dev_s *priv, uint32_t address)
    +int bcmf_core_set_backplane_window(FAR struct bcmf_sdio_dev_s *sbus,
    +                                   uint32_t address)
     {
       int ret;
       int i;
    @@ -119,13 +113,13 @@ int bcmf_core_set_backplane_window(FAR struct bcmf_dev_s *priv, uint32_t address
       for (i = 1; i < 4; i++)
         {
           uint8_t addr_part = (address >> (8*i)) & 0xff;
    -      uint8_t cur_addr_part = (priv->backplane_current_addr >> (8*i)) & 0xff;
    +      uint8_t cur_addr_part = (sbus->backplane_current_addr >> (8*i)) & 0xff;
     
           if (addr_part != cur_addr_part)
             {
               /* Update current backplane base address */
     
    -          ret = bcmf_write_reg(priv, 1, SBSDIO_FUNC1_SBADDRLOW+i-1,
    +          ret = bcmf_write_reg(sbus, 1, SBSDIO_FUNC1_SBADDRLOW+i-1,
                       addr_part);
     
               if (ret != OK)
    @@ -133,15 +127,15 @@ int bcmf_core_set_backplane_window(FAR struct bcmf_dev_s *priv, uint32_t address
                   return ret;
                 }
     
    -          priv->backplane_current_addr &= ~(0xff << (8*i));
    -          priv->backplane_current_addr |= addr_part << (8*i);
    +          sbus->backplane_current_addr &= ~(0xff << (8*i));
    +          sbus->backplane_current_addr |= addr_part << (8*i);
             }
         }
     
       return OK;
     }
     
    -int bcmf_upload_binary(FAR struct bcmf_dev_s *priv, uint32_t address,
    +int bcmf_upload_binary(FAR struct bcmf_sdio_dev_s *sbus, uint32_t address,
                            uint8_t *buf, unsigned int len)
     {
       unsigned int size;
    @@ -150,7 +144,7 @@ int bcmf_upload_binary(FAR struct bcmf_dev_s *priv, uint32_t address,
         {
           /* Set the backplane window to include the start address */
     
    -      int ret = bcmf_core_set_backplane_window(priv, address);
    +      int ret = bcmf_core_set_backplane_window(sbus, address);
           if (ret != OK)
             {
               return ret;
    @@ -167,7 +161,7 @@ int bcmf_upload_binary(FAR struct bcmf_dev_s *priv, uint32_t address,
     
           /* Transfer firmware data */
     
    -      ret = bcmf_transfer_bytes(priv, true, 1,
    +      ret = bcmf_transfer_bytes(sbus, true, 1,
                                     address & SBSDIO_SB_OFT_ADDR_MASK, buf, size);
           if (ret != OK)
             {
    @@ -182,7 +176,7 @@ int bcmf_upload_binary(FAR struct bcmf_dev_s *priv, uint32_t address,
       return OK;
     }
     
    -int bcmf_upload_nvram(FAR struct bcmf_dev_s *priv)
    +int bcmf_upload_nvram(FAR struct bcmf_sdio_dev_s *sbus)
     {
       int ret;
       uint32_t nvram_sz;
    @@ -190,14 +184,16 @@ int bcmf_upload_nvram(FAR struct bcmf_dev_s *priv)
     
       /* Round up the size of the image */
     
    -  nvram_sz = (bcmf_nvram_image_len + 63) & (-64);
    +  nvram_sz = (*sbus->chip->nvram_image_size + 63) & (-64);
     
    -  _info("nvram size is %d %d bytes\n", nvram_sz, bcmf_nvram_image_len);
    +  _info("nvram size is %d %d bytes\n", nvram_sz,
    +                                       *sbus->chip->nvram_image_size);
     
       /* Write image */
     
    -  ret = bcmf_upload_binary(priv, CHIP_RAM_SIZE - 4 - nvram_sz,
    -                           (uint8_t*)bcmf_nvram_image, bcmf_nvram_image_len);
    +  ret = bcmf_upload_binary(sbus, sbus->chip->ram_size - 4 - nvram_sz,
    +                           sbus->chip->nvram_image,
    +                           *sbus->chip->nvram_image_size);
       if ( ret != OK)
       {
           return ret;
    @@ -210,7 +206,7 @@ int bcmf_upload_nvram(FAR struct bcmf_dev_s *priv)
     
       /* Write the length token to the last word */
     
    -  ret = bcmf_write_sbreg(priv, CHIP_RAM_SIZE - 4, (uint8_t*)&token, 4);
    +  ret = bcmf_write_sbreg(sbus, sbus->chip->ram_size - 4, (uint8_t*)&token, 4);
       if ( ret != OK)
       {
           return ret;
    @@ -227,16 +223,16 @@ int bcmf_upload_nvram(FAR struct bcmf_dev_s *priv)
      * Name: bcmf_read_sbreg
      ****************************************************************************/
     
    -int bcmf_read_sbreg(FAR struct bcmf_dev_s *priv, uint32_t address,
    +int bcmf_read_sbreg(FAR struct bcmf_sdio_dev_s *sbus, uint32_t address,
                               uint8_t *reg, unsigned int len)
     {
    -  int ret = bcmf_core_set_backplane_window(priv, address);
    +  int ret = bcmf_core_set_backplane_window(sbus, address);
       if (ret != OK)
         {
           return ret;
         }
     
    -  return bcmf_transfer_bytes(priv, false, 1,
    +  return bcmf_transfer_bytes(sbus, false, 1,
                                  address & SBSDIO_SB_OFT_ADDR_MASK, reg, len);
     }
     
    @@ -244,17 +240,17 @@ int bcmf_read_sbreg(FAR struct bcmf_dev_s *priv, uint32_t address,
      * Name: bcmf_write_sbreg
      ****************************************************************************/
     
    -int bcmf_write_sbreg(FAR struct bcmf_dev_s *priv, uint32_t address,
    +int bcmf_write_sbreg(FAR struct bcmf_sdio_dev_s *sbus, uint32_t address,
                               uint8_t *reg, unsigned int len)
     {
     
    -  int ret = bcmf_core_set_backplane_window(priv, address);
    +  int ret = bcmf_core_set_backplane_window(sbus, address);
       if (ret != OK)
         {
           return ret;
         }
     
    -  return bcmf_transfer_bytes(priv, true, 1, address & SBSDIO_SB_OFT_ADDR_MASK,
    +  return bcmf_transfer_bytes(sbus, true, 1, address & SBSDIO_SB_OFT_ADDR_MASK,
                                  reg, len);
     }
     
    @@ -262,7 +258,7 @@ int bcmf_write_sbreg(FAR struct bcmf_dev_s *priv, uint32_t address,
      * Name: bcmf_core_upload_firmware
      ****************************************************************************/
     
    -int bcmf_core_upload_firmware(FAR struct bcmf_dev_s *priv)
    +int bcmf_core_upload_firmware(FAR struct bcmf_sdio_dev_s *sbus)
     {
       int ret;
     
    @@ -271,16 +267,16 @@ int bcmf_core_upload_firmware(FAR struct bcmf_dev_s *priv)
       /* Disable ARMCM3 core and reset SOCRAM core
        * to set device in firmware upload mode */
     
    -  bcmf_core_disable(priv, WLAN_ARMCM3_CORE_ID);
    -  bcmf_core_reset(priv, SOCSRAM_CORE_ID);
    +  bcmf_core_disable(sbus, WLAN_ARMCM3_CORE_ID);
    +  bcmf_core_reset(sbus, SOCSRAM_CORE_ID);
     
       up_mdelay(50);
     
       /* Flash chip firmware */
     
    -  _info("firmware size is %d bytes\n", bcmf_firmware_image_len);
    -  ret = bcmf_upload_binary(priv, 0, (uint8_t*)bcmf_firmware_image,
    -                           bcmf_firmware_image_len);
    +  _info("firmware size is %d bytes\n", *sbus->chip->firmware_image_size);
    +  ret = bcmf_upload_binary(sbus, 0, sbus->chip->firmware_image,
    +                           *sbus->chip->firmware_image_size);
     
       if (ret != OK)
         {
    @@ -291,7 +287,7 @@ int bcmf_core_upload_firmware(FAR struct bcmf_dev_s *priv)
       /* Flash NVRAM configuration file */
     
       _info("upload nvram configuration\n");
    -  ret = bcmf_upload_nvram(priv);
    +  ret = bcmf_upload_nvram(sbus);
       if (ret != OK)
         {
             _err("Failed to upload nvram\n");
    @@ -301,12 +297,12 @@ int bcmf_core_upload_firmware(FAR struct bcmf_dev_s *priv)
       /* Firmware upload done, restart ARMCM3 core */
     
       up_mdelay(10);
    -  bcmf_core_reset(priv, WLAN_ARMCM3_CORE_ID);
    +  bcmf_core_reset(sbus, WLAN_ARMCM3_CORE_ID);
     
       /*  Check ARMCM3 core is running */
     
       up_mdelay(10);
    -  if (!bcmf_core_isup(priv, WLAN_ARMCM3_CORE_ID))
    +  if (!bcmf_core_isup(sbus, WLAN_ARMCM3_CORE_ID))
         {
           _err("Cannot start ARMCM3 core\n");
           return -ETIMEDOUT;
    @@ -315,31 +311,43 @@ int bcmf_core_upload_firmware(FAR struct bcmf_dev_s *priv)
       return OK;
     }
     
    -bool bcmf_core_isup(FAR struct bcmf_dev_s *priv, unsigned int core)
    +bool bcmf_core_isup(FAR struct bcmf_sdio_dev_s *sbus, unsigned int core)
     {
       uint32_t value = 0;
    -  uint32_t base = priv->get_core_base_address(core);
     
    -  bcmf_read_sbregw(priv, base + BCMA_IOCTL, &value);
    +  if (core >= MAX_CORE_ID)
    +    {
    +      _err("Invalid core id %d\n", core);
    +      return false;
    +    }
    +  uint32_t base = sbus->chip->core_base[core];
    +
    +  bcmf_read_sbregw(sbus, base + BCMA_IOCTL, &value);
     
       if ((value & (BCMA_IOCTL_FGC | BCMA_IOCTL_CLK)) != BCMA_IOCTL_CLK)
         {
           return false;
         }
     
    -  bcmf_read_sbregw(priv, base + BCMA_RESET_CTL, &value);
    +  bcmf_read_sbregw(sbus, base + BCMA_RESET_CTL, &value);
     
       return (value & BCMA_RESET_CTL_RESET) == 0;
     }
     
    -void bcmf_core_disable(FAR struct bcmf_dev_s *priv, unsigned int core)
    +void bcmf_core_disable(FAR struct bcmf_sdio_dev_s *sbus, unsigned int core)
     {
       uint8_t value;
    -  uint32_t base = priv->get_core_base_address(core);
    +
    +  if (core >= MAX_CORE_ID)
    +    {
    +      _err("Invalid core id %d\n", core);
    +      return;
    +    }
    +  uint32_t base = sbus->chip->core_base[core];
       
       /* Check if core is already in reset state */
     
    -  bcmf_read_sbregb(priv, base + BCMA_RESET_CTL, &value);
    +  bcmf_read_sbregb(sbus, base + BCMA_RESET_CTL, &value);
     
       if ((value & BCMA_RESET_CTL_RESET) != 0)
         {
    @@ -354,37 +362,43 @@ void bcmf_core_disable(FAR struct bcmf_dev_s *priv, unsigned int core)
     
       /* Set core in reset state */
     
    -  bcmf_write_sbregb(priv, base + BCMA_RESET_CTL, BCMA_RESET_CTL_RESET);
    +  bcmf_write_sbregb(sbus, base + BCMA_RESET_CTL, BCMA_RESET_CTL_RESET);
       up_udelay(1);
     
       /* Write 0 to the IO control and read it back */
     
    -  bcmf_write_sbregb(priv, base + BCMA_IOCTL, 0);
    -  bcmf_read_sbregb(priv, base + BCMA_IOCTL, &value);
    +  bcmf_write_sbregb(sbus, base + BCMA_IOCTL, 0);
    +  bcmf_read_sbregb(sbus, base + BCMA_IOCTL, &value);
       up_udelay(10);
     }
     
    -void bcmf_core_reset(FAR struct bcmf_dev_s *priv, unsigned int core)
    +void bcmf_core_reset(FAR struct bcmf_sdio_dev_s *sbus, unsigned int core)
     {
       uint32_t value;
    -  uint32_t base = priv->get_core_base_address(core);
    +
    +  if (core >= MAX_CORE_ID)
    +    {
    +      _err("Invalid core id %d\n", core);
    +      return;
    +    }
    +  uint32_t base = sbus->chip->core_base[core];
     
       /* Put core in reset state */
     
    -  bcmf_core_disable(priv, core);
    +  bcmf_core_disable(sbus, core);
     
       /* Run initialization sequence */
     
    -  bcmf_write_sbregb(priv, base + BCMA_IOCTL, BCMA_IOCTL_FGC | BCMA_IOCTL_CLK);
    -  bcmf_read_sbregw(priv, base + BCMA_IOCTL, &value);
    +  bcmf_write_sbregb(sbus, base + BCMA_IOCTL, BCMA_IOCTL_FGC | BCMA_IOCTL_CLK);
    +  bcmf_read_sbregw(sbus, base + BCMA_IOCTL, &value);
     
    -  bcmf_write_sbregb(priv, base + BCMA_RESET_CTL, 0);
    -  bcmf_read_sbregw(priv, base + BCMA_RESET_CTL, &value);
    +  bcmf_write_sbregb(sbus, base + BCMA_RESET_CTL, 0);
    +  bcmf_read_sbregw(sbus, base + BCMA_RESET_CTL, &value);
     
       up_udelay(1);
     
    -  bcmf_write_sbregb(priv, base + BCMA_IOCTL, BCMA_IOCTL_CLK);
    -  bcmf_read_sbregw(priv, base + BCMA_IOCTL, &value);
    +  bcmf_write_sbregb(sbus, base + BCMA_IOCTL, BCMA_IOCTL_CLK);
    +  bcmf_read_sbregw(sbus, base + BCMA_IOCTL, &value);
     
       up_udelay(1);
     }
    diff --git a/drivers/wireless/ieee80211/bcmf_core.h b/drivers/wireless/ieee80211/bcmf_core.h
    index 9200423979..074196cded 100644
    --- a/drivers/wireless/ieee80211/bcmf_core.h
    +++ b/drivers/wireless/ieee80211/bcmf_core.h
    @@ -39,45 +39,44 @@
     #include 
     #include 
     
    -#include "bcmf_driver.h"
    +#include "bcmf_sdio.h"
     
    -
    -int bcmf_read_sbreg(FAR struct bcmf_dev_s *priv, uint32_t address,
    +int bcmf_read_sbreg(FAR struct bcmf_sdio_dev_s *sbus, uint32_t address,
                               uint8_t *reg, unsigned int len);
     
    -int bcmf_write_sbreg(FAR struct bcmf_dev_s *priv, uint32_t address,
    +int bcmf_write_sbreg(FAR struct bcmf_sdio_dev_s *sbus, uint32_t address,
                               uint8_t *reg, unsigned int len);
     
    -bool bcmf_core_isup(FAR struct bcmf_dev_s *priv, unsigned int core);
    +bool bcmf_core_isup(FAR struct bcmf_sdio_dev_s *sbus, unsigned int core);
     
    -void bcmf_core_disable(FAR struct bcmf_dev_s *priv, unsigned int core);
    +void bcmf_core_disable(FAR struct bcmf_sdio_dev_s *sbus, unsigned int core);
     
    -void bcmf_core_reset(FAR struct bcmf_dev_s *priv, unsigned int core);
    +void bcmf_core_reset(FAR struct bcmf_sdio_dev_s *sbus, unsigned int core);
     
    -int bcmf_core_upload_firmware(FAR struct bcmf_dev_s *priv);
    +int bcmf_core_upload_firmware(FAR struct bcmf_sdio_dev_s *sbus);
     
    -static inline int bcmf_read_sbregb(FAR struct bcmf_dev_s *priv,
    +static inline int bcmf_read_sbregb(FAR struct bcmf_sdio_dev_s *sbus,
                                        uint32_t address, uint8_t *reg)
     {
    -    return bcmf_read_sbreg(priv, address, reg, 1);
    +    return bcmf_read_sbreg(sbus, address, reg, 1);
     }
     
    -static inline int bcmf_read_sbregw(FAR struct bcmf_dev_s *priv,
    +static inline int bcmf_read_sbregw(FAR struct bcmf_sdio_dev_s *sbus,
                                        uint32_t address, uint32_t *reg)
     {
    -    return bcmf_read_sbreg(priv, address, (uint8_t*)reg, 4);
    +    return bcmf_read_sbreg(sbus, address, (uint8_t*)reg, 4);
     }
     
    -static inline int bcmf_write_sbregb(FAR struct bcmf_dev_s *priv,
    +static inline int bcmf_write_sbregb(FAR struct bcmf_sdio_dev_s *sbus,
                                         uint32_t address, uint8_t reg)
     {
    -    return bcmf_write_sbreg(priv, address, ®, 1);
    +    return bcmf_write_sbreg(sbus, address, ®, 1);
     }
     
    -static inline int bcmf_write_sbregw(FAR struct bcmf_dev_s *priv,
    +static inline int bcmf_write_sbregw(FAR struct bcmf_sdio_dev_s *sbus,
                                         uint32_t address, uint32_t reg)
     {
    -    return bcmf_write_sbreg(priv, address, (uint8_t*)®, 4);
    +    return bcmf_write_sbreg(sbus, address, (uint8_t*)®, 4);
     }
     
     #endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_CORE_H */
    diff --git a/drivers/wireless/ieee80211/bcmf_driver.c b/drivers/wireless/ieee80211/bcmf_driver.c
    index 1ca1fd0010..a30659b226 100644
    --- a/drivers/wireless/ieee80211/bcmf_driver.c
    +++ b/drivers/wireless/ieee80211/bcmf_driver.c
    @@ -48,10 +48,12 @@
     #include 
     
     #include "bcmf_driver.h"
    -#include "bcmf_sdpcm.h"
    -#include "bcmf_sdio_core.h"
    +#include "bcmf_cdc.h"
     #include "bcmf_ioctl.h"
     
    +#include 
    +#include "bcmf_sdio.h"
    +
     /****************************************************************************
      * Pre-processor Definitions
      ****************************************************************************/
    @@ -62,6 +64,11 @@
     #define WL_SCAN_UNASSOC_TIME   40
     #define WL_SCAN_PASSIVE_TIME   120
     
    +/* Chip interfaces */
    +#define CHIP_STA_INTERFACE   0
    +#define CHIP_AP_INTERFACE    1
    +#define CHIP_P2P_INTERFACE   2
    +
     /****************************************************************************
      * Private Types
      ****************************************************************************/
    @@ -70,7 +77,12 @@
      * Private Function Prototypes
      ****************************************************************************/
     
    +static FAR struct bcmf_dev_s* bcmf_allocate_device(void);
    +static void bcmf_free_device(FAR struct bcmf_dev_s *priv);
    +
    +#if 0
     static int bcmf_run_escan(FAR struct bcmf_dev_s *priv);
    +#endif
     
     /****************************************************************************
      * Private Data
    @@ -80,12 +92,58 @@ static int bcmf_run_escan(FAR struct bcmf_dev_s *priv);
      * Private Functions
      ****************************************************************************/
     
    +FAR struct bcmf_dev_s* bcmf_allocate_device(void)
    +{
    +  int ret;
    +  FAR struct bcmf_dev_s *priv;
    +
    +  /* Allocate a bcmf device structure */
    +
    +  priv = (FAR struct bcmf_dev_s *)kmm_malloc(sizeof(*priv));
    +  if (!priv)
    +    {
    +      return NULL;
    +    }
    +
    +  /* Initialize bcmf device structure */
    +
    +  memset(priv, 0, sizeof(*priv));
    +
    +  /* Init control frames mutex and timeout signal */
    +
    +  if ((ret = sem_init(&priv->control_mutex, 0, 1)) != OK)
    +    {
    +      goto exit_free_priv;
    +    }
    +  if ((ret = sem_init(&priv->control_timeout, 0, 0)) != OK)
    +    {
    +      goto exit_free_priv;
    +    }
    +  if ((ret = sem_setprotocol(&priv->control_timeout, SEM_PRIO_NONE)) != OK)
    +    {
    +      goto exit_free_priv;
    +    }
    +
    +  return priv;
    +
    +exit_free_priv:
    +  kmm_free(priv);
    +  return NULL;
    +}
    +
    +void bcmf_free_device(FAR struct bcmf_dev_s *priv)
    +{
    +  /* TODO deinitialize device structures */
    +
    +  kmm_free(priv);
    +}
    +
     int bcmf_wl_set_mac_address(FAR struct bcmf_dev_s *priv, uint8_t *addr)
     {
       int ret;
       uint32_t out_len = 6;
     
    -  ret = bcmf_sdpcm_iovar_request(priv, CHIP_STA_INTERFACE, true,
    +  ret = bcmf_cdc_iovar_request(priv, CHIP_STA_INTERFACE, true,
                                      IOVAR_STR_CUR_ETHERADDR, addr,
                                      &out_len);
       if (ret != OK)
    @@ -109,7 +167,7 @@ int bcmf_wl_enable(FAR struct bcmf_dev_s *priv, bool enable)
       /* TODO chek device state */
     
       out_len = 0;
    -  ret = bcmf_sdpcm_ioctl(priv, CHIP_STA_INTERFACE, true,
    +  ret = bcmf_cdc_ioctl(priv, CHIP_STA_INTERFACE, true,
                              enable ? WLC_UP : WLC_DOWN, NULL, &out_len);
       
       if (ret == OK)
    @@ -128,7 +186,7 @@ int bcmf_dongle_scantime(FAR struct bcmf_dev_s *priv, int32_t scan_assoc_time,
     
       out_len = 4;
       value = scan_assoc_time;
    -  ret = bcmf_sdpcm_ioctl(priv, CHIP_STA_INTERFACE, true,
    +  ret = bcmf_cdc_ioctl(priv, CHIP_STA_INTERFACE, true,
                              WLC_SET_SCAN_CHANNEL_TIME, (uint8_t*)&value,
                              &out_len);
       if (ret != OK)
    @@ -138,7 +196,7 @@ int bcmf_dongle_scantime(FAR struct bcmf_dev_s *priv, int32_t scan_assoc_time,
     
       out_len = 4;
       value = scan_unassoc_time;
    -  ret = bcmf_sdpcm_ioctl(priv, CHIP_STA_INTERFACE, true,
    +  ret = bcmf_cdc_ioctl(priv, CHIP_STA_INTERFACE, true,
                              WLC_SET_SCAN_UNASSOC_TIME, (uint8_t*)&value,
                              &out_len);
       if (ret != OK)
    @@ -148,7 +206,7 @@ int bcmf_dongle_scantime(FAR struct bcmf_dev_s *priv, int32_t scan_assoc_time,
     
       out_len = 4;
       value = scan_passive_time;
    -  ret = bcmf_sdpcm_ioctl(priv, CHIP_STA_INTERFACE, true,
    +  ret = bcmf_cdc_ioctl(priv, CHIP_STA_INTERFACE, true,
                              WLC_SET_SCAN_PASSIVE_TIME, (uint8_t*)&value,
                              &out_len);
       if (ret != OK)
    @@ -182,7 +240,7 @@ int bcmf_dongle_initialize(FAR struct bcmf_dev_s *priv)
     
       out_len = 4;
       value = 0;
    -  ret = bcmf_sdpcm_ioctl(priv, CHIP_STA_INTERFACE, true,
    +  ret = bcmf_cdc_ioctl(priv, CHIP_STA_INTERFACE, true,
                              WLC_SET_PM, (uint8_t*)&value, &out_len);
       if (ret != OK)
         {
    @@ -193,7 +251,7 @@ int bcmf_dongle_initialize(FAR struct bcmf_dev_s *priv)
     
       out_len = 4;
       value = GMODE_AUTO;
    -  ret = bcmf_sdpcm_ioctl(priv, CHIP_STA_INTERFACE, true,
    +  ret = bcmf_cdc_ioctl(priv, CHIP_STA_INTERFACE, true,
                              WLC_SET_GMODE, (uint8_t*)&value, &out_len);
       if (ret != OK)
         {
    @@ -204,22 +262,25 @@ int bcmf_dongle_initialize(FAR struct bcmf_dev_s *priv)
     
       out_len = 4;
       value = 1;
    -  ret = bcmf_sdpcm_iovar_request(priv, CHIP_STA_INTERFACE, true,
    +  ret = bcmf_cdc_iovar_request(priv, CHIP_STA_INTERFACE, true,
                                      IOVAR_STR_ROAM_OFF, (uint8_t*)&value,
                                      &out_len);
     
       // FIXME remove
    -
    +#if 0
       /* Try scan */
     
       value = 0;
       out_len = 4;
    -  ret = bcmf_sdpcm_ioctl(priv, CHIP_STA_INTERFACE, true,
    +  ret = bcmf_cdc_ioctl(priv, CHIP_STA_INTERFACE, true,
                              WLC_SET_PASSIVE_SCAN, (uint8_t*)&value, &out_len);
       bcmf_run_escan(priv);
    -  return OK;
    +#endif
    +
    +  return ret;
     }
     
    +#if 0
     int bcmf_run_escan(FAR struct bcmf_dev_s *priv)
     {
       int ret;
    @@ -254,7 +315,7 @@ int bcmf_run_escan(FAR struct bcmf_dev_s *priv)
       _info("start scan\n");
     
       out_len = sizeof(*params);
    -  ret = bcmf_sdpcm_iovar_request(priv, CHIP_STA_INTERFACE, true,
    +  ret = bcmf_cdc_iovar_request(priv, CHIP_STA_INTERFACE, true,
                                      IOVAR_STR_ESCAN, (uint8_t*)params,
                                      &out_len);
     
    @@ -267,6 +328,7 @@ int bcmf_run_escan(FAR struct bcmf_dev_s *priv)
     
       return OK;
     }
    +#endif
     
     /****************************************************************************
      * Public Functions
    @@ -282,7 +344,7 @@ int bcmf_wl_initialize(FAR struct bcmf_dev_s *priv)
     
       out_len = 4;
       *(uint32_t*)tmp_buf = 0;
    -  ret = bcmf_sdpcm_iovar_request(priv, CHIP_STA_INTERFACE, false,
    +  ret = bcmf_cdc_iovar_request(priv, CHIP_STA_INTERFACE, false,
                                      IOVAR_STR_TX_GLOM, tmp_buf,
                                      &out_len);
       if (ret != OK)
    @@ -293,7 +355,7 @@ int bcmf_wl_initialize(FAR struct bcmf_dev_s *priv)
       /* Query MAC address */
     
       out_len = 6;
    -  ret = bcmf_sdpcm_iovar_request(priv, CHIP_STA_INTERFACE, false,
    +  ret = bcmf_cdc_iovar_request(priv, CHIP_STA_INTERFACE, false,
                                      IOVAR_STR_CUR_ETHERADDR, tmp_buf,
                                      &out_len);
       if (ret != OK)
    @@ -310,7 +372,7 @@ int bcmf_wl_initialize(FAR struct bcmf_dev_s *priv)
       /* Query firmware version string */
     
       out_len = sizeof(tmp_buf);
    -  ret = bcmf_sdpcm_iovar_request(priv, CHIP_STA_INTERFACE, false,
    +  ret = bcmf_cdc_iovar_request(priv, CHIP_STA_INTERFACE, false,
                                      IOVAR_STR_VERSION, tmp_buf,
                                      &out_len);
       if (ret != OK)
    @@ -333,7 +395,7 @@ int bcmf_wl_initialize(FAR struct bcmf_dev_s *priv)
       memset(event_mask, 0xff, sizeof(event_mask));
     
       out_len = sizeof(event_mask);
    -  ret = bcmf_sdpcm_iovar_request(priv, CHIP_STA_INTERFACE, true,
    +  ret = bcmf_cdc_iovar_request(priv, CHIP_STA_INTERFACE, true,
                                      IOVAR_STR_EVENT_MSGS, event_mask,
                                      &out_len);
       if (ret != OK)
    @@ -343,4 +405,35 @@ int bcmf_wl_initialize(FAR struct bcmf_dev_s *priv)
       // TODO Create a wlan device name and register network driver
     
       return bcmf_dongle_initialize(priv);
    +}
    +
    +int bcmf_sdio_initialize(int minor, FAR struct sdio_dev_s *dev)
    +{
    +  int ret;
    +  FAR struct bcmf_dev_s *priv;
    +
    +  _info("minor: %d\n", minor);
    +
    +  priv = bcmf_allocate_device();
    +  if (!priv)
    +    {
    +      return -ENOMEM;
    +    }
    +
    +  /* Init sdio bus */
    +
    +  ret = bcmf_bus_sdio_initialize(priv, minor, dev);
    +  if (ret != OK)
    +    {
    +      ret = -EIO;
    +      goto exit_free_device;
    +    }
    +
    +  /* Bus initialized, register network driver */
    +
    +  return bcmf_wl_initialize(priv);
    +
    +exit_free_device:
    +  bcmf_free_device(priv);
    +  return ret;
     }
    \ No newline at end of file
    diff --git a/drivers/wireless/ieee80211/bcmf_driver.h b/drivers/wireless/ieee80211/bcmf_driver.h
    index 1d32317e7d..d121fc2a95 100644
    --- a/drivers/wireless/ieee80211/bcmf_driver.h
    +++ b/drivers/wireless/ieee80211/bcmf_driver.h
    @@ -37,7 +37,8 @@
     #define __DRIVERS_WIRELESS_IEEE80211_BCMF_DRIVER_H
     
     #include 
    -#include 
    +#include 
    +#include 
     
     #define BCMF_STATUS_BUS_UP (1<<0) /* Chip is flashed and running */
     #define BCMF_STATUS_READY  (1<<1) /* Chip is ready to receive requests */
    @@ -45,43 +46,56 @@
     #define BCMF_STATUS_SLEEP  (1<<2) /* Chip is in low power mode */
     #define BCMF_STATUS_WAIT_CONTROL (1<<3) /* Waiting for control response */
     
    +struct bcmf_bus_dev_s;
    +struct bcmf_frame_s;
    +
     /* This structure contains the unique state of the Broadcom FullMAC driver */
     
     struct bcmf_dev_s
     {
    -  FAR struct sdio_dev_s *sdio_dev; /* The SDIO device bound to this instance */
    -  int minor;                       /* Device minor number */
    +  FAR struct bcmf_bus_dev_s *bus;  /* Bus interface structure */
     
    -  uint32_t backplane_current_addr; /* Current function 1 backplane base addr */
    +  // FIXME use mutex instead of semaphore
    +  sem_t control_mutex;         /* Cannot handle multiple control requests */
    +  sem_t control_timeout;       /* Semaphore to wait for control frame rsp */
    +  uint16_t control_reqid;      /* Current control request id */
    +  uint16_t control_rxdata_len; /* Received control frame out buffer length */
    +  uint8_t *control_rxdata;     /* Received control frame out buffer */
    +  uint32_t control_status;     /* Last received frame status */
     
    -  uint32_t (*get_core_base_address)(unsigned int core); /* Get chip specific
    -                                      base address for evey cores */
    +  uint8_t mac_addr[6];         /* Current mac address */
    +};
     
    -  sem_t thread_signal;             /* Semaphore for processing thread event */
    -  struct wdog_s *waitdog;          /* Processing thread waitdog */
    -  bool ready;                      /* Current device status */
    -  bool sleeping;                   /* Current sleep status */
    -  volatile bool irq_pending;       /* True if interrupt is pending */
    -  uint32_t intstatus;              /* Copy of device current interrupt status */
    +/* Default bus interface structure */
     
    -  uint8_t max_seq;                 /* Maximum transmit sequence allowed */
    -  uint8_t tx_seq;                  /* Transmit sequence number (next) */
    -  uint8_t rx_seq;                  /* Receive sequence number (expected) */
    +struct bcmf_bus_dev_s {
    +  void (*stop)(FAR struct bcmf_dev_s *priv);
    +  int (*txframe)(FAR struct bcmf_dev_s *priv, struct bcmf_frame_s *frame);
     
    -  // FIXME use mutex instead of semaphore
    -  sem_t control_mutex;             /* Cannot handle multiple control requests */
    -  sem_t control_timeout;           /* Semaphore to wait for control frame rsp */
    -  uint16_t control_reqid;          /* Current control request id */
    -  uint8_t *control_rxframe;        /* Received control frame response */
    -  uint32_t control_status;         /* Last received frame status */
    +  /* Frame buffer allocation primitive
    +   * len     - requested payload length
    +   * control - true if control frame else false
    +   * block   - true to block until free frame is available
    +   */
    +  struct bcmf_frame_s* (*allocate_frame)(FAR struct bcmf_dev_s *priv,
    +          unsigned int len, bool control, bool block);
    +};
     
    -  // FIXME use mutex instead of semaphore
    -  sem_t tx_queue_mutex;            /* Lock for transmit queue */
    -  dq_queue_t tx_queue;             /* Queue of frames to tramsmit */
    +/* bcmf frame definition */
     
    -  uint8_t mac_addr[6];             /* Current mac address */
    +struct bcmf_frame_s {
    +  uint8_t *base;    /* Frame base buffer used by low level layer (SDIO) */
    +  uint8_t *data;    /* Payload data (Control, data and event messages) */
    +  unsigned int len; /* Frame buffer size */
     };
     
    -int bcmf_wl_initialize(FAR struct bcmf_dev_s *priv);
    +/* Notify driver frame is available */
    +
    +void bcmf_notify_rxframe(FAR struct bcmf_dev_s *priv,
    +                         struct bcmf_frame_s *frame);
    +
    +/* Notify driver bus is ready */
    +
    +int brcmf_bus_start(FAR struct bcmf_dev_s *priv);
     
     #endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_DRIVER_H */
    diff --git a/drivers/wireless/ieee80211/bcmf_sdio.c b/drivers/wireless/ieee80211/bcmf_sdio.c
    index ee10b0fc9e..178e716187 100644
    --- a/drivers/wireless/ieee80211/bcmf_sdio.c
    +++ b/drivers/wireless/ieee80211/bcmf_sdio.c
    @@ -46,9 +46,9 @@
     #include 
     #include 
     #include 
    +#include 
     
     #include 
    -#include 
     #include 
     #include 
     
    @@ -60,9 +60,17 @@
     #include "bcmf_core.h"
     #include "bcmf_sdpcm.h"
     
    +#include "bcmf_sdio_core.h"
    +#include "bcmf_sdio_regs.h"
    +
     // TODO remove
     #include "bcmf_ioctl.h"
     
    +/* Supported chip configurations */
    +#ifdef CONFIG_IEEE80211_BROADCOM_BCM43362
    +  extern const struct bcmf_sdio_chip bcmf_43362_config_sdio;
    +#endif
    +
     /****************************************************************************
      * Pre-processor Definitions
      ****************************************************************************/
    @@ -84,66 +92,66 @@
      * Private Function Prototypes
      ****************************************************************************/
     
    -static int  bcmf_probe(FAR struct bcmf_dev_s *priv);
    -static int  bcmf_hwinitialize(FAR struct bcmf_dev_s *priv);
    -static void bcmf_hwuninitialize(FAR struct bcmf_dev_s *priv);
    -static int  bcmf_chipinitialize(FAR struct bcmf_dev_s *priv);
    +static int  bcmf_probe(FAR struct bcmf_sdio_dev_s *sbus);
    +static int  bcmf_hwinitialize(FAR struct bcmf_sdio_dev_s *sbus);
    +static void bcmf_hwuninitialize(FAR struct bcmf_sdio_dev_s *sbus);
    +static int  bcmf_chipinitialize(FAR struct bcmf_sdio_dev_s *sbus);
     
     static int  bcmf_oob_irq(int irq, FAR void *context, FAR void *arg);
     
    -static int  bcmf_sdio_bus_sleep(FAR struct bcmf_dev_s *priv, bool sleep);
    +static int  bcmf_sdio_bus_sleep(FAR struct bcmf_sdio_dev_s *sbus, bool sleep);
     
     static void bcmf_sdio_waitdog_timeout(int argc, wdparm_t arg1, ...);
     static int  bcmf_sdio_thread(int argc, char **argv);
     
     static int  bcmf_sdio_find_block_size(unsigned int size);
     
    -/* FIXME remove */
    -FAR struct bcmf_dev_s *g_sdio_priv;
    -
     /****************************************************************************
      * Private Data
      ****************************************************************************/
     
    +/* FIXME remove */
    +FAR struct bcmf_dev_s *g_sdio_priv;
    +
     /****************************************************************************
      * Private Functions
      ****************************************************************************/
     
     int bcmf_oob_irq(int irq, FAR void *context, FAR void *arg)
     {
    -  FAR struct bcmf_dev_s *priv = (struct bcmf_dev_s*)arg;
    +  FAR struct bcmf_sdio_dev_s *sbus = (struct bcmf_sdio_dev_s*)arg;
     
    -  if (priv->ready)
    +  if (sbus->ready)
         {
           /*  Signal bmcf thread */
    -      priv->irq_pending = true;
    +      sbus->irq_pending = true;
     
    -      sem_post(&priv->thread_signal);
    +      sem_post(&sbus->thread_signal);
         }
       return OK;
     }
     
    -int bcmf_sdio_bus_sleep(FAR struct bcmf_dev_s *priv, bool sleep)
    +int bcmf_sdio_bus_sleep(FAR struct bcmf_sdio_dev_s *sbus, bool sleep)
     {
       int ret;
       int loops;
       uint8_t value;
     
    -  if (priv->sleeping == sleep)
    +  if (sbus->sleeping == sleep)
         {
           return OK;
         }
     
       if (sleep)
         {
    -      priv->sleeping = true;
    -      return bcmf_write_reg(priv, 1, SBSDIO_FUNC1_CHIPCLKCSR, 0);
    +      sbus->sleeping = true;
    +      return bcmf_write_reg(sbus, 1, SBSDIO_FUNC1_CHIPCLKCSR, 0);
         }
       else
         {
           /* Request HT Avail */
       
    -      ret = bcmf_write_reg(priv, 1, SBSDIO_FUNC1_CHIPCLKCSR,
    +      ret = bcmf_write_reg(sbus, 1, SBSDIO_FUNC1_CHIPCLKCSR,
                                SBSDIO_HT_AVAIL_REQ | SBSDIO_FORCE_HT);
           if (ret != OK)
             {
    @@ -157,7 +165,7 @@ int bcmf_sdio_bus_sleep(FAR struct bcmf_dev_s *priv, bool sleep)
           while (--loops > 0)
             {
               up_mdelay(1);
    -          ret = bcmf_read_reg(priv, 1, SBSDIO_FUNC1_CHIPCLKCSR, &value);
    +          ret = bcmf_read_reg(sbus, 1, SBSDIO_FUNC1_CHIPCLKCSR, &value);
       
               if (ret != OK)
                 {
    @@ -177,7 +185,7 @@ int bcmf_sdio_bus_sleep(FAR struct bcmf_dev_s *priv, bool sleep)
               return -ETIMEDOUT;
             }
     
    -      priv->sleeping = false;
    +      sbus->sleeping = false;
         }
       
       return OK;
    @@ -187,13 +195,13 @@ int bcmf_sdio_bus_sleep(FAR struct bcmf_dev_s *priv, bool sleep)
      * Name: bcmf_probe
      ****************************************************************************/
     
    -int bcmf_probe(FAR struct bcmf_dev_s *priv)
    +int bcmf_probe(FAR struct bcmf_sdio_dev_s *sbus)
     {
       int ret;
     
       /* Probe sdio card compatible device */
     
    -  ret = sdio_probe(priv->sdio_dev);
    +  ret = sdio_probe(sbus->sdio_dev);
       if (ret != OK)
         {
           goto exit_error;
    @@ -201,19 +209,19 @@ int bcmf_probe(FAR struct bcmf_dev_s *priv)
     
       /* Set FN0 / FN1 / FN2 default block size */
     
    -  ret = sdio_set_blocksize(priv->sdio_dev, 0, 64);
    +  ret = sdio_set_blocksize(sbus->sdio_dev, 0, 64);
       if (ret != OK)
         {
           goto exit_error;
         }
     
    -  ret = sdio_set_blocksize(priv->sdio_dev, 1, 64);
    +  ret = sdio_set_blocksize(sbus->sdio_dev, 1, 64);
       if (ret != OK)
         {
           goto exit_error;
         }
     
    -  ret = sdio_set_blocksize(priv->sdio_dev, 2, 64);
    +  ret = sdio_set_blocksize(sbus->sdio_dev, 2, 64);
       if (ret != OK)
         {
           goto exit_error;
    @@ -221,7 +229,7 @@ int bcmf_probe(FAR struct bcmf_dev_s *priv)
     
       /* Enable device interrupts for FN0, FN1 and FN2 */
     
    -  ret = bcmf_write_reg(priv, 0, SDIO_CCCR_INTEN,
    +  ret = bcmf_write_reg(sbus, 0, SDIO_CCCR_INTEN,
                            (1 << 0) | (1 << 1) | (1 << 2));
       if (ret != OK)
         {
    @@ -231,12 +239,12 @@ int bcmf_probe(FAR struct bcmf_dev_s *priv)
       /* Default device clock speed is up to 25 Mhz
        * We could set EHS bit to operate at a clock rate up to 50 Mhz */
     
    -  SDIO_CLOCK(priv->sdio_dev, CLOCK_SD_TRANSFER_4BIT);
    +  SDIO_CLOCK(sbus->sdio_dev, CLOCK_SD_TRANSFER_4BIT);
       up_mdelay(BCMF_CLOCK_SETUP_DELAY_MS);
     
       /* Enable bus FN1 */
     
    -  ret = sdio_enable_function(priv->sdio_dev, 1);
    +  ret = sdio_enable_function(sbus->sdio_dev, 1);
       if (ret != OK)
         {
           goto exit_error;
    @@ -246,7 +254,7 @@ int bcmf_probe(FAR struct bcmf_dev_s *priv)
     
     exit_error:
     
    -  _err("ERROR: failed to probe device %d\n", priv->minor);
    +  _err("ERROR: failed to probe device %d\n", sbus->minor);
       return ret;
     }
     
    @@ -254,7 +262,7 @@ exit_error:
      * Name: bcmf_businitialize
      ****************************************************************************/
     
    -int bcmf_businitialize(FAR struct bcmf_dev_s *priv)
    +int bcmf_businitialize(FAR struct bcmf_sdio_dev_s *sbus)
     {
       int ret;
       int loops;
    @@ -262,7 +270,7 @@ int bcmf_businitialize(FAR struct bcmf_dev_s *priv)
     
       /* Send Active Low-Power clock request */
     
    -  ret = bcmf_write_reg(priv, 1, SBSDIO_FUNC1_CHIPCLKCSR,
    +  ret = bcmf_write_reg(sbus, 1, SBSDIO_FUNC1_CHIPCLKCSR,
                 SBSDIO_FORCE_HW_CLKREQ_OFF |
                 SBSDIO_ALP_AVAIL_REQ |
                 SBSDIO_FORCE_ALP);
    @@ -276,7 +284,7 @@ int bcmf_businitialize(FAR struct bcmf_dev_s *priv)
       while (--loops > 0)
         {
           up_mdelay(10);
    -      ret = bcmf_read_reg(priv, 1, SBSDIO_FUNC1_CHIPCLKCSR, &value);
    +      ret = bcmf_read_reg(sbus, 1, SBSDIO_FUNC1_CHIPCLKCSR, &value);
     
           if (ret != OK)
             {
    @@ -298,7 +306,7 @@ int bcmf_businitialize(FAR struct bcmf_dev_s *priv)
     
       /* Clear Active Low-Power clock request */
     
    -  ret = bcmf_write_reg(priv, 1, SBSDIO_FUNC1_CHIPCLKCSR, 0);
    +  ret = bcmf_write_reg(sbus, 1, SBSDIO_FUNC1_CHIPCLKCSR, 0);
       if (ret != OK)
         {
           return ret;
    @@ -306,7 +314,7 @@ int bcmf_businitialize(FAR struct bcmf_dev_s *priv)
     
       /* Disable pull-ups on SDIO cmd, d0-2 lines */
     
    -  ret = bcmf_write_reg(priv, 1, SBSDIO_FUNC1_SDIOPULLUP, 0);
    +  ret = bcmf_write_reg(sbus, 1, SBSDIO_FUNC1_SDIOPULLUP, 0);
       if (ret != OK)
         {
           return ret;
    @@ -314,7 +322,7 @@ int bcmf_businitialize(FAR struct bcmf_dev_s *priv)
     
       /* Do chip specific initialization */
     
    -  ret = bcmf_chipinitialize(priv);
    +  ret = bcmf_chipinitialize(sbus);
       if (ret != OK)
         {
           return ret;
    @@ -322,7 +330,7 @@ int bcmf_businitialize(FAR struct bcmf_dev_s *priv)
     
       /* Upload firmware */
     
    -  ret = bcmf_core_upload_firmware(priv);
    +  ret = bcmf_core_upload_firmware(sbus);
       if (ret != OK)
         {
           return ret;
    @@ -330,7 +338,7 @@ int bcmf_businitialize(FAR struct bcmf_dev_s *priv)
     
       /* Enable FN2 (frame transfers) */
     
    -  ret = sdio_enable_function(priv->sdio_dev, 2);
    +  ret = sdio_enable_function(sbus->sdio_dev, 2);
       if (ret != OK)
         {
           return ret;
    @@ -339,22 +347,22 @@ int bcmf_businitialize(FAR struct bcmf_dev_s *priv)
       return OK;
     }
     
    -int bcmf_bus_setup_interrupts(FAR struct bcmf_dev_s *priv)
    +int bcmf_bus_setup_interrupts(FAR struct bcmf_sdio_dev_s *sbus)
     {
       int ret;
     
       /* Configure gpio interrupt pin */
     
    -  bcmf_board_setup_oob_irq(priv->minor, bcmf_oob_irq, (void*)priv);
    +  bcmf_board_setup_oob_irq(sbus->minor, bcmf_oob_irq, (void*)sbus);
     
       /* Enable function 2 interrupt */
     
    -  ret = sdio_enable_interrupt(priv->sdio_dev, 0);
    +  ret = sdio_enable_interrupt(sbus->sdio_dev, 0);
       if (ret != OK)
         {
           return ret;
         }
    -  ret = sdio_enable_interrupt(priv->sdio_dev, 2);
    +  ret = sdio_enable_interrupt(sbus->sdio_dev, 2);
       if (ret != OK)
         {
           return ret;
    @@ -362,7 +370,7 @@ int bcmf_bus_setup_interrupts(FAR struct bcmf_dev_s *priv)
     
       /* Redirect, configure and enable io for out-of-band interrupt signal */
     
    -  ret = bcmf_write_reg(priv, 0, SDIO_CCCR_BRCM_SEPINT,
    +  ret = bcmf_write_reg(sbus, 0, SDIO_CCCR_BRCM_SEPINT,
                            SDIO_SEPINT_MASK | SDIO_SEPINT_OE | SDIO_SEPINT_ACT_HI);
       if (ret != OK)
         {
    @@ -371,7 +379,7 @@ int bcmf_bus_setup_interrupts(FAR struct bcmf_dev_s *priv)
     
       /* Wake up chip to be sure function 2 is running */
     
    -  ret = bcmf_sdio_bus_sleep(priv, false);
    +  ret = bcmf_sdio_bus_sleep(sbus, false);
       if (ret != OK)
         {
           return ret;
    @@ -379,15 +387,15 @@ int bcmf_bus_setup_interrupts(FAR struct bcmf_dev_s *priv)
     
       /* FN2 successfully enabled, set core and enable interrupts */
     
    -  bcmf_write_sbregw(priv,
    -                   CORE_BUS_REG(priv->get_core_base_address(SDIOD_CORE_ID),
    +  bcmf_write_sbregw(sbus,
    +                   CORE_BUS_REG(sbus->chip->core_base[SDIOD_CORE_ID],
                        hostintmask), I_HMB_SW_MASK);
     
    -  bcmf_write_sbregb(priv,
    -                   CORE_BUS_REG(priv->get_core_base_address(SDIOD_CORE_ID),
    +  bcmf_write_sbregb(sbus,
    +                   CORE_BUS_REG(sbus->chip->core_base[SDIOD_CORE_ID],
                        funcintmask), 2);
     
    -  bcmf_write_reg(priv, 1, SBSDIO_WATERMARK, 8);
    +  bcmf_write_reg(sbus, 1, SBSDIO_WATERMARK, 8);
     
       return OK;
     }
    @@ -396,26 +404,26 @@ int bcmf_bus_setup_interrupts(FAR struct bcmf_dev_s *priv)
      * Name: bcmf_hwinitialize
      ****************************************************************************/
     
    -int bcmf_hwinitialize(FAR struct bcmf_dev_s *priv)
    +int bcmf_hwinitialize(FAR struct bcmf_sdio_dev_s *sbus)
     {
       /* Attach and prepare SDIO interrupts */
     
    -  SDIO_ATTACH(priv->sdio_dev);
    +  SDIO_ATTACH(sbus->sdio_dev);
     
       /* Set ID mode clocking (<400KHz) */
     
    -  SDIO_CLOCK(priv->sdio_dev, CLOCK_IDMODE);
    +  SDIO_CLOCK(sbus->sdio_dev, CLOCK_IDMODE);
     
       /* Configure hardware */
     
    -  bcmf_board_initialize(priv->minor);
    +  bcmf_board_initialize(sbus->minor);
     
       /* Reset and power device */
     
    -  bcmf_board_reset(priv->minor, true);
    -  bcmf_board_power(priv->minor, true);
    +  bcmf_board_reset(sbus->minor, true);
    +  bcmf_board_power(sbus->minor, true);
       up_mdelay(BCMF_DEVICE_RESET_DELAY_MS);
    -  bcmf_board_reset(priv->minor, false);
    +  bcmf_board_reset(sbus->minor, false);
     
       /* Wait for device to start */
     
    @@ -428,12 +436,12 @@ int bcmf_hwinitialize(FAR struct bcmf_dev_s *priv)
      * Name: bcmf_hwuninitialize
      ****************************************************************************/
     
    -void bcmf_hwuninitialize(FAR struct bcmf_dev_s *priv)
    +void bcmf_hwuninitialize(FAR struct bcmf_sdio_dev_s *sbus)
     {
       /*  Shutdown device */
     
    -  bcmf_board_power(priv->minor, false);
    -  bcmf_board_reset(priv->minor, true);
    +  bcmf_board_power(sbus->minor, false);
    +  bcmf_board_reset(sbus->minor, true);
     }
     
     int bcmf_sdio_find_block_size(unsigned int size)
    @@ -460,7 +468,7 @@ int bcmf_sdio_find_block_size(unsigned int size)
      * Name: bcmf_transfer_bytes
      ****************************************************************************/
     
    -int bcmf_transfer_bytes(FAR struct bcmf_dev_s *priv, bool write,
    +int bcmf_transfer_bytes(FAR struct bcmf_sdio_dev_s *sbus, bool write,
                             uint8_t function, uint32_t address,
                             uint8_t *buf, unsigned int len)
     {
    @@ -478,10 +486,10 @@ int bcmf_transfer_bytes(FAR struct bcmf_dev_s *priv, bool write,
         {
           if (write)
             {
    -          return sdio_io_rw_direct(priv->sdio_dev, write,
    +          return sdio_io_rw_direct(sbus->sdio_dev, write,
                                        function, address, *buf, NULL);
             }
    -      return sdio_io_rw_direct(priv->sdio_dev, write,
    +      return sdio_io_rw_direct(sbus->sdio_dev, write,
                                    function, address, 0, buf);
         }
     
    @@ -502,7 +510,7 @@ int bcmf_transfer_bytes(FAR struct bcmf_dev_s *priv, bool write,
             nblocks = 0;
           }
     
    -    return sdio_io_rw_extended(priv->sdio_dev, write,
    +    return sdio_io_rw_extended(sbus->sdio_dev, write,
                                    function, address, true, buf, blocklen, nblocks);
     }
     
    @@ -510,114 +518,85 @@ int bcmf_transfer_bytes(FAR struct bcmf_dev_s *priv, bool write,
      * Name: bcmf_read_reg
      ****************************************************************************/
     
    -int bcmf_read_reg(FAR struct bcmf_dev_s *priv, uint8_t function,
    +int bcmf_read_reg(FAR struct bcmf_sdio_dev_s *sbus, uint8_t function,
                       uint32_t address, uint8_t *reg)
     {
       *reg = 0;
    -  return bcmf_transfer_bytes(priv, false, function, address, reg, 1);
    +  return bcmf_transfer_bytes(sbus, false, function, address, reg, 1);
     }
     
     /****************************************************************************
      * Name: bcmf_write_reg
      ****************************************************************************/
     
    -int bcmf_write_reg(FAR struct bcmf_dev_s *priv, uint8_t function,
    +int bcmf_write_reg(FAR struct bcmf_sdio_dev_s *sbus, uint8_t function,
                        uint32_t address, uint8_t reg)
     {
    -  return bcmf_transfer_bytes(priv, true, function, address, ®, 1);
    +  return bcmf_transfer_bytes(sbus, true, function, address, ®, 1);
     }
     
     /****************************************************************************
    - * Name: bcmf_sem_wait
    + * Name: bcmf_bus_sdio_initialize
      ****************************************************************************/
     
    -int bcmf_sem_wait(sem_t *sem, unsigned int timeout_ms)
    +int bcmf_bus_sdio_initialize(FAR struct bcmf_dev_s *priv,
    +          int minor, FAR struct sdio_dev_s *dev)
     {
    -  struct timespec abstime;
    -
    -  /* Get the current time */
    +  int ret;
    +  FAR struct bcmf_sdio_dev_s *sbus;
     
    -  (void)clock_gettime(CLOCK_REALTIME, &abstime);
    +  /* Allocate sdio bus structure */
     
    -  abstime.tv_nsec += 1000 * 1000* timeout_ms;
    +  sbus = (FAR struct bcmf_sdio_dev_s*)kmm_malloc(sizeof(*sbus));
     
    -  if (abstime.tv_nsec >= 1000 * 1000 * 1000)
    +  if (!sbus)
         {
    -      abstime.tv_sec++;
    -      abstime.tv_nsec -= 1000 * 1000 * 1000;
    +      return -ENOMEM;
         }
     
    -  return sem_timedwait(sem, &abstime);
    -}
    -
    -/****************************************************************************
    - * Name: bcmf_sdio_initialize
    - ****************************************************************************/
    -
    -int bcmf_sdio_initialize(int minor, FAR struct sdio_dev_s *dev)
    -{
    -  FAR struct bcmf_dev_s *priv;
    -  int ret;
    +  /* Initialize sdio bus device structure */
     
    -  _info("minor: %d\n", minor);
    +  memset(sbus, 0, sizeof(*sbus));
    +  sbus->sdio_dev = dev;
    +  sbus->minor = minor;
    +  sbus->ready = false;
    +  sbus->sleeping = true;
     
    -  /* Allocate a bcmf device structure */
    +  sbus->bus.txframe = bcmf_sdpcm_queue_frame;
    +  sbus->bus.allocate_frame = bcmf_sdpcm_allocate_frame;
    +  sbus->bus.stop = NULL; // TODO
     
    -  priv = (FAR struct bcmf_dev_s *)kmm_malloc(sizeof(*priv));
    +  /* Init transmit frames queue */
     
    -  if (!priv)
    +  if ((ret = sem_init(&sbus->tx_queue_mutex, 0, 1)) != OK)
         {
    -      return -ENOMEM;
    +      goto exit_free_bus;
         }
    -
    -  /* Initialize bcmf device structure */
    -
    -  memset(priv, 0, sizeof(*priv));
    -  priv->sdio_dev = dev;
    -  priv->minor = minor;
    -  priv->ready = false;
    -  priv->sleeping = true;
    +  sq_init(&sbus->tx_queue);
       
    -  if ((ret = sem_init(&priv->thread_signal, 0, 0)) != OK)
    -    {
    -      goto exit_free_priv;
    -    }
    -  if ((ret = sem_setprotocol(&priv->thread_signal, SEM_PRIO_NONE)) != OK)
    -    {
    -      goto exit_free_priv;
    -    }
    +  /* Init thread semaphore */
     
    -  priv->waitdog = wd_create();
    -  if (!priv->waitdog)
    +  if ((ret = sem_init(&sbus->thread_signal, 0, 0)) != OK)
         {
    -      ret = -ENOMEM;
    -      goto exit_free_priv;
    +      goto exit_free_bus;
         }
    -
    -  if ((ret = sem_init(&priv->control_mutex, 0, 1)) != OK)
    +  if ((ret = sem_setprotocol(&sbus->thread_signal, SEM_PRIO_NONE)) != OK)
         {
    -      goto exit_free_waitdog;
    +      goto exit_free_bus;
         }
     
    -  if ((ret = sem_init(&priv->control_timeout, 0, 0)) != OK)
    -    {
    -      goto exit_free_waitdog;
    -    }
    -  if ((ret = sem_setprotocol(&priv->control_timeout, SEM_PRIO_NONE)) != OK)
    -    {
    -      goto exit_free_waitdog;
    -    }
    -  /* Init transmit frames queue */
    +  /* Init thread waitdog */
     
    -  if ((ret = sem_init(&priv->tx_queue_mutex, 0, 1)) != OK)
    +  sbus->waitdog = wd_create();
    +  if (!sbus->waitdog)
         {
    -      goto exit_free_waitdog;
    +      ret = -ENOMEM;
    +      goto exit_free_bus;
         }
    -  sq_init(&priv->tx_queue);
     
       /* Initialize device hardware */
     
    -  ret = bcmf_hwinitialize(priv);
    +  ret = bcmf_hwinitialize(sbus);
     
       if (ret != OK)
         {
    @@ -626,7 +605,7 @@ int bcmf_sdio_initialize(int minor, FAR struct sdio_dev_s *dev)
     
       /* Probe device */
     
    -  ret = bcmf_probe(priv);
    +  ret = bcmf_probe(sbus);
     
       if (ret != OK)
         {
    @@ -635,7 +614,7 @@ int bcmf_sdio_initialize(int minor, FAR struct sdio_dev_s *dev)
     
       /* Initialize device bus */
     
    -  ret = bcmf_businitialize(priv);
    +  ret = bcmf_businitialize(sbus);
     
       if (ret != OK)
         {
    @@ -645,9 +624,9 @@ int bcmf_sdio_initialize(int minor, FAR struct sdio_dev_s *dev)
     
       up_mdelay(100);
     
    -  priv->ready = true;
    +  sbus->ready = true;
     
    -  ret = bcmf_bus_setup_interrupts(priv);
    +  ret = bcmf_bus_setup_interrupts(sbus);
       if (ret != OK)
         {
           goto exit_uninit_hw;
    @@ -656,9 +635,13 @@ int bcmf_sdio_initialize(int minor, FAR struct sdio_dev_s *dev)
       /* FIXME global variable for now */
       g_sdio_priv = priv;
     
    +  /* Register sdio bus */
    +
    +  priv->bus = &sbus->bus;
    +
       /* Start the waitdog timer */
     
    -  wd_start(priv->waitdog, BCMF_WAITDOG_TIMEOUT_TICK, bcmf_sdio_waitdog_timeout, 0);
    +  wd_start(sbus->waitdog, BCMF_WAITDOG_TIMEOUT_TICK, bcmf_sdio_waitdog_timeout, 0);
     
       /* Spawn bcmf daemon thread */
     
    @@ -673,34 +656,30 @@ int bcmf_sdio_initialize(int minor, FAR struct sdio_dev_s *dev)
           goto exit_uninit_hw;
         }
     
    -  /* sdio bus is ready, init driver */
    +  sbus->thread_id = ret;
    +
     
    -  ret = bcmf_wl_initialize(priv);
    -  if (ret != OK)
    -    {
    -      _err("Cannot init wlan driver %d\n", ret);
    -      ret = -EIO;
    -      goto exit_uninit_hw;
    -    }
    +
    +  /* sdio bus is up and running */
     
       return OK;
     
     exit_uninit_hw:
    -  bcmf_hwuninitialize(priv);
    +  bcmf_hwuninitialize(sbus);
     exit_free_waitdog:
    -  // TODO
    -exit_free_priv:
    -  kmm_free(priv);
    -  priv->ready = false;
    +  wd_delete(sbus->waitdog);
    +exit_free_bus:
    +  kmm_free(sbus);
    +  priv->bus = NULL;
       return ret;
     }
     
    -int bcmf_chipinitialize(FAR struct bcmf_dev_s *priv)
    +int bcmf_chipinitialize(FAR struct bcmf_sdio_dev_s *sbus)
     {
       int ret;
       uint32_t value = 0;
     
    -  ret = bcmf_read_sbregw(priv, SI_ENUM_BASE, &value);
    +  ret = bcmf_read_sbregw(sbus, SI_ENUM_BASE, &value);
       if (ret != OK)
         {
           return ret;
    @@ -710,10 +689,12 @@ int bcmf_chipinitialize(FAR struct bcmf_dev_s *priv)
       int chipid = value & 0xffff;
       switch (chipid)
         {
    +#ifdef CONFIG_IEEE80211_BROADCOM_BCM43362
           case SDIO_DEVICE_ID_BROADCOM_43362:
             _info("bcm43362 chip detected\n");
    -        priv->get_core_base_address = bcmf_43362_get_core_base_address;
    +        sbus->chip = (struct bcmf_sdio_chip*)&bcmf_43362_config_sdio;
             break;
    +#endif
           default:
             _err("chip 0x%x is not supported\n", chipid);
             return -ENODEV;
    @@ -724,16 +705,18 @@ int bcmf_chipinitialize(FAR struct bcmf_dev_s *priv)
     void bcmf_sdio_waitdog_timeout(int argc, wdparm_t arg1, ...)
     {
       FAR struct bcmf_dev_s *priv = g_sdio_priv;
    +  FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s*)priv->bus;
     
       /* Notify bcmf thread */
     
    -  sem_post(&priv->thread_signal);
    +  sem_post(&sbus->thread_signal);
     }
     
     int bcmf_sdio_thread(int argc, char **argv)
     {
       int ret;
       FAR struct bcmf_dev_s *priv = g_sdio_priv;
    +  FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s*)priv->bus;
       
       _info("Enter\n");
     
    @@ -741,11 +724,11 @@ int bcmf_sdio_thread(int argc, char **argv)
     
       up_mdelay(50);
       
    -  while (1)
    +  while (sbus->ready)
         {
           /* Wait for event (device interrupt, user request or waitdog timer) */
     
    -      ret = sem_wait(&priv->thread_signal);
    +      ret = sem_wait(&sbus->thread_signal);
           if (ret != OK)
             {
               _err("Error while waiting for semaphore\n");
    @@ -754,34 +737,34 @@ int bcmf_sdio_thread(int argc, char **argv)
     
           /* Restart the waitdog timer */
     
    -      wd_start(priv->waitdog, BCMF_WAITDOG_TIMEOUT_TICK,
    +      wd_start(sbus->waitdog, BCMF_WAITDOG_TIMEOUT_TICK,
                    bcmf_sdio_waitdog_timeout, 0);
     
           /* Wake up device */
     
    -      bcmf_sdio_bus_sleep(priv, false);
    +      bcmf_sdio_bus_sleep(sbus, false);
     
    -      if (priv->irq_pending)
    +      if (sbus->irq_pending)
             {
               /* Woken up by interrupt, read device status */
     
    -          priv->irq_pending = false;
    +          sbus->irq_pending = false;
     
    -          bcmf_read_sbregw(priv,
    -                       CORE_BUS_REG(priv->get_core_base_address(SDIOD_CORE_ID),
    -                       intstatus), &priv->intstatus);
    +          bcmf_read_sbregw(sbus,
    +                       CORE_BUS_REG(sbus->chip->core_base[SDIOD_CORE_ID],
    +                       intstatus), &sbus->intstatus);
     
               /* Clear interrupts */
     
    -          bcmf_write_sbregw(priv,
    -                       CORE_BUS_REG(priv->get_core_base_address(SDIOD_CORE_ID),
    -                       intstatus), priv->intstatus);
    -          // _info("intstatus %x\n", priv->intstatus);
    +          bcmf_write_sbregw(sbus,
    +                       CORE_BUS_REG(sbus->chip->core_base[SDIOD_CORE_ID],
    +                       intstatus), sbus->intstatus);
    +          // _info("intstatus %x\n", sbus->intstatus);
             }
     
           /* On frame indication, read available frames */
     
    -      if (priv->intstatus & I_HMB_FRAME_IND)
    +      if (sbus->intstatus & I_HMB_FRAME_IND)
             {
               // _info("Frames available\n");
     
    @@ -794,7 +777,7 @@ int bcmf_sdio_thread(int argc, char **argv)
                 {
                   /*  All frames processed */
     
    -              priv->intstatus &= ~I_HMB_FRAME_IND;
    +              sbus->intstatus &= ~I_HMB_FRAME_IND;
                 }
             }
     
    @@ -808,7 +791,10 @@ int bcmf_sdio_thread(int argc, char **argv)
           /* If we're done for now, turn off clock request. */
     
           // TODO add wakelock
    -      // bcmf_sdio_bus_sleep(priv, true);
    +      // bcmf_sdio_bus_sleep(sbus, true);
         }
    -    return 0;
    +
    +  _info("Exit\n");
    +
    +  return 0;
     }
    \ No newline at end of file
    diff --git a/drivers/wireless/ieee80211/bcmf_sdio.h b/drivers/wireless/ieee80211/bcmf_sdio.h
    index 0645d23c92..83843705d8 100644
    --- a/drivers/wireless/ieee80211/bcmf_sdio.h
    +++ b/drivers/wireless/ieee80211/bcmf_sdio.h
    @@ -1,12 +1,59 @@
     #ifndef __DRIVERS_WIRELESS_IEEE80211_BCMF_SDIO_H
     #define __DRIVERS_WIRELESS_IEEE80211_BCMF_SDIO_H
     
    -#include "bcmf_sdio_regs.h"
    -#include "bcmf_sdio_core.h"
    -
     #include "bcmf_driver.h"
     #include 
     #include 
    +#include 
    +#include 
    +#include 
    +
    +#include "bcmf_sdio_core.h"
    +
    +/* sdio chip configuration structure */
    +
    +struct bcmf_sdio_chip {
    +	uint32_t ram_size;
    +	uint32_t core_base[MAX_CORE_ID];
    +
    +	uint8_t      *firmware_image;
    +	unsigned int *firmware_image_size;
    +
    +	uint8_t      *nvram_image;
    +	unsigned int *nvram_image_size;
    +};
    +
    +/* sdio bus structure extension */
    +
    +struct bcmf_sdio_dev_s {
    +  struct bcmf_bus_dev_s bus;       /* Default bcmf bus structure */
    +  FAR struct sdio_dev_s *sdio_dev; /* The SDIO device bound to this instance */
    +  int minor;                       /* Device minor number */
    +
    +  struct bcmf_sdio_chip *chip;     /* Chip specific configuration */
    +
    +  volatile bool ready;             /* Current device status */
    +  bool sleeping;                   /* Current sleep status */
    +
    +  int thread_id;                   /* Processing thread id */
    +  sem_t thread_signal;             /* Semaphore for processing thread event */
    +  struct wdog_s *waitdog;          /* Processing thread waitdog */
    +
    +  uint32_t backplane_current_addr; /* Current function 1 backplane base addr */
    +
    +  volatile bool irq_pending;       /* True if interrupt is pending */
    +  uint32_t intstatus;              /* Copy of device current interrupt status */
    +
    +  uint8_t max_seq;                 /* Maximum transmit sequence allowed */
    +  uint8_t tx_seq;                  /* Transmit sequence number (next) */
    +  uint8_t rx_seq;                  /* Receive sequence number (expected) */
    +
    +  sem_t tx_queue_mutex;            /* Lock for transmit queue */
    +  dq_queue_t tx_queue;             /* Queue of frames to tramsmit */
    +};
    +
    +int bcmf_bus_sdio_initialize(FAR struct bcmf_dev_s *priv,
    +					int minor, FAR struct sdio_dev_s *dev);
     
     /* FIXME: Low level bus data transfer function
      * To avoid bus error, len will be aligned to:
    @@ -14,16 +61,14 @@
      * - upper 64 bytes block if len is greater than 64
      */
     
    -int bcmf_transfer_bytes(FAR struct bcmf_dev_s *priv, bool write,
    +int bcmf_transfer_bytes(FAR struct bcmf_sdio_dev_s *sbus, bool write,
                              uint8_t function, uint32_t address,
                              uint8_t *buf, unsigned int len);
     
    -int bcmf_read_reg(FAR struct bcmf_dev_s *priv, uint8_t function,
    +int bcmf_read_reg(FAR struct bcmf_sdio_dev_s *sbus, uint8_t function,
                       uint32_t address, uint8_t *reg);
     
    -int bcmf_write_reg(FAR struct bcmf_dev_s *priv, uint8_t function,
    +int bcmf_write_reg(FAR struct bcmf_sdio_dev_s *sbus, uint8_t function,
                        uint32_t address, uint8_t reg);
     
    -int bcmf_sem_wait(sem_t *sem, unsigned int timeout_ms);
    -
     #endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_SDIO_H */
    \ No newline at end of file
    diff --git a/drivers/wireless/ieee80211/bcmf_sdio_core.h b/drivers/wireless/ieee80211/bcmf_sdio_core.h
    index fa592adc9e..174dd86bce 100644
    --- a/drivers/wireless/ieee80211/bcmf_sdio_core.h
    +++ b/drivers/wireless/ieee80211/bcmf_sdio_core.h
    @@ -61,16 +61,13 @@
     #define I_HMB_SW_MASK                 ( (uint32_t) 0x000000F0 )
     #define I_HMB_FRAME_IND               ( 1<<6 )
     
    -#define CHIP_STA_INTERFACE   0
    -#define CHIP_AP_INTERFACE    1
    -#define CHIP_P2P_INTERFACE   2
    -
     enum {
    -    CHIPCOMMON_CORE_ID,
    +    CHIPCOMMON_CORE_ID = 0,
         DOT11MAC_CORE_ID,
         SDIOD_CORE_ID,
         WLAN_ARMCM3_CORE_ID,
    -    SOCSRAM_CORE_ID
    +    SOCSRAM_CORE_ID,
    +    MAX_CORE_ID
     };
     
     struct chip_core_info {
    @@ -212,8 +209,4 @@ struct sdpcmd_regs {
     	uint16_t PAD[0x80];
     };
     
    -#ifdef CONFIG_IEEE80211_BROADCOM_BCM43362
    -#include "bcmf_chip_43362.h"
    -#endif
    -
     #endif /* _BCMF_SDIO_CHIP_H_ */
    diff --git a/drivers/wireless/ieee80211/bcmf_sdpcm.c b/drivers/wireless/ieee80211/bcmf_sdpcm.c
    index bc66f7bee4..b363bba249 100644
    --- a/drivers/wireless/ieee80211/bcmf_sdpcm.c
    +++ b/drivers/wireless/ieee80211/bcmf_sdpcm.c
    @@ -52,7 +52,10 @@
     #include "bcmf_sdio.h"
     #include "bcmf_core.h"
     #include "bcmf_sdpcm.h"
    -#include "bcmf_ioctl.h"
    +#include "bcmf_cdc.h"
    +#include "bcmf_utils.h"
    +
    +#include "bcmf_sdio_regs.h"
     
     /****************************************************************************
      * Pre-processor Definitions
    @@ -70,26 +73,14 @@
     #define SMB_USE_OOB (1 << 2)  /* Use OOB Wakeup */
     #define SMB_DEV_INT (1 << 3)  /* Miscellaneous Interrupt */
     
    -/* CDC flag definitions */
    -#define CDC_DCMD_ERROR    0x01       /* 1=cmd failed */
    -#define CDC_DCMD_SET      0x02       /* 0=get, 1=set cmd */
    -#define CDC_DCMD_IF_MASK  0xF000     /* I/F index */
    -#define CDC_DCMD_IF_SHIFT 12
    -#define CDC_DCMD_ID_MASK  0xFFFF0000 /* id an cmd pairing */
    -#define CDC_DCMD_ID_SHIFT 16         /* ID Mask shift bits */
    -#define CDC_DCMD_ID(flags)  \
    -  (((flags) & CDC_DCMD_ID_MASK) >> CDC_DCMD_ID_SHIFT)
    -
     #define SDPCM_CONTROL_CHANNEL 0  /* Control */
     #define SDPCM_EVENT_CHANNEL   1  /* Asyc Event Indication */
     #define SDPCM_DATA_CHANNEL    2  /* Data Xmit/Recv */
     #define SDPCM_GLOM_CHANNEL    3  /* Coalesced packets */
     #define SDPCM_TEST_CHANNEL    15 /* Test/debug packets */
     
    -#define SDPCM_CONTROL_TIMEOUT_MS 1000
    -
    -// TODO remove
    -void bcmf_hexdump(uint8_t *data, unsigned int len, unsigned long offset);
    +#define container_of(ptr, type, member) \
    +        (type *)( (uint8_t *)(ptr) - offsetof(type,member) )
     
     /****************************************************************************
      * Private Types
    @@ -107,40 +98,18 @@ struct bcmf_sdpcm_header {
         uint16_t padding;
     };
     
    -struct bcmf_sdpcm_cdc_header {
    -    uint32_t cmd;    /* dongle command value */
    -    uint32_t len;    /* lower 16: output buflen;
    -                      * upper 16: input buflen (excludes header) */
    -    uint32_t flags;  /* flag defns given below */
    -    uint32_t status; /* status code returned from the device */
    -};
    -
    -struct bcmf_sdpcm_cdc_dcmd {
    -    struct bcmf_sdpcm_header     header;
    -    struct bcmf_sdpcm_cdc_header cdc_header;
    -    uint8_t                      data[0];
    -};
    -
     struct bcmf_sdpcm_frame {
    +    struct bcmf_frame_s          frame_header;
         dq_entry_t                   list_entry;
    -    struct bcmf_sdpcm_header     header;
    -    uint8_t                      data[0];
    -};
    -
    -struct bcmf_sdpcm_cdc_frame {
    -    dq_entry_t                   list_entry;
    -    struct bcmf_sdpcm_header     header;
    -    struct bcmf_sdpcm_cdc_header cdc_header;
    -    uint8_t                      data[0];
     };
     
     /****************************************************************************
      * Private Function Prototypes
      ****************************************************************************/
     
    -static int bcmf_sdpcm_rxfail(FAR struct bcmf_dev_s *priv, bool retry);
    +static int bcmf_sdpcm_rxfail(FAR struct bcmf_sdio_dev_s *sbus, bool retry);
     
    -static int bcmf_sdpcm_process_header(FAR struct bcmf_dev_s *priv,
    +static int bcmf_sdpcm_process_header(FAR struct bcmf_sdio_dev_s *sbus,
                                   struct bcmf_sdpcm_header *header);
     
     /****************************************************************************
    @@ -151,51 +120,51 @@ static int bcmf_sdpcm_process_header(FAR struct bcmf_dev_s *priv,
      * Private Functions
      ****************************************************************************/
     
    -int bcmf_sdpcm_rxfail(FAR struct bcmf_dev_s *priv, bool retry)
    +int bcmf_sdpcm_rxfail(FAR struct bcmf_sdio_dev_s *sbus, bool retry)
     {
       /* issue abort command for F2 through F0 */
     
    -  bcmf_write_reg(priv, 0, SDIO_CCCR_IOABORT, 2);
    +  bcmf_write_reg(sbus, 0, SDIO_CCCR_IOABORT, 2);
     
    -  bcmf_write_reg(priv, 1, SBSDIO_FUNC1_FRAMECTRL, SFC_RF_TERM);
    +  bcmf_write_reg(sbus, 1, SBSDIO_FUNC1_FRAMECTRL, SFC_RF_TERM);
     
       /* TODO Wait until the packet has been flushed (device/FIFO stable) */
     
       /* Send NAK to retry to read frame */
       if (retry)
         {
    -      bcmf_write_sbregb(priv,
    -                  CORE_BUS_REG(priv->get_core_base_address(SDIOD_CORE_ID),
    +      bcmf_write_sbregb(sbus,
    +                  CORE_BUS_REG(sbus->chip->core_base[SDIOD_CORE_ID],
                       tosbmailbox), SMB_NAK);
         }
     
       return 0;
     }
     
    -int bcmf_sdpcm_process_header(FAR struct bcmf_dev_s *priv,
    +int bcmf_sdpcm_process_header(FAR struct bcmf_sdio_dev_s *sbus,
                                   struct bcmf_sdpcm_header *header)
     {
       if (header->data_offset < sizeof(struct bcmf_sdpcm_header) ||
           header->data_offset > header->size)
         {
           _err("Invalid data offset\n");
    -      bcmf_sdpcm_rxfail(priv, false);
    +      bcmf_sdpcm_rxfail(sbus, false);
           return -ENXIO;
         }
     
       /* Update tx credits */
     
    -  _info("update credit %x %x %x\n", header->credit,
    -                                    priv->tx_seq, priv->max_seq);
    +  // _info("update credit %x %x %x\n", header->credit,
    +  //                                   sbus->tx_seq, sbus->max_seq);
     
    -  if (header->credit - priv->tx_seq > 0x40)
    +  if (header->credit - sbus->tx_seq > 0x40)
         {
    -      _err("seq %d: max tx seq number error\n", priv->tx_seq);
    -      priv->max_seq = priv->tx_seq + 2;
    +      _err("seq %d: max tx seq number error\n", sbus->tx_seq);
    +      sbus->max_seq = sbus->tx_seq + 2;
         }
       else
         {
    -      priv->max_seq = header->credit;
    +      sbus->max_seq = header->credit;
         }
     
       return OK;
    @@ -207,16 +176,22 @@ int bcmf_sdpcm_process_header(FAR struct bcmf_dev_s *priv,
     
     // FIXME remove
     uint8_t tmp_buffer[1024];
    -uint8_t tmp_buffer_ctl[1024];
     int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv)
     {
       int ret;
       uint16_t len, checksum;
    -  struct bcmf_sdpcm_header *header = (struct bcmf_sdpcm_header*)tmp_buffer;
    +  struct bcmf_sdpcm_header *header;
    +  struct bcmf_sdpcm_frame *sframe;
    +  FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s*)priv->bus;
    +
    +  /* TODO request free frame buffer */
    +
    +  sframe = (struct bcmf_sdpcm_frame*)tmp_buffer;
    +  header = (struct bcmf_sdpcm_header*)&sframe[1];
     
       /* Read header */
     
    -  ret = bcmf_transfer_bytes(priv, false, 2, 0, (uint8_t*)header, 4);
    +  ret = bcmf_transfer_bytes(sbus, false, 2, 0, (uint8_t*)header, 4);
       if (ret != OK)
         {
           _info("failread size\n");
    @@ -252,7 +227,7 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv)
       /* Read remaining frame data */
       // TODO allocate buffer
     
    -  ret = bcmf_transfer_bytes(priv, false, 2, 0, (uint8_t*)header+4, len - 4);
    +  ret = bcmf_transfer_bytes(sbus, false, 2, 0, (uint8_t*)header+4, len - 4);
       if (ret != OK)
         {
           ret = -EIO;
    @@ -260,11 +235,11 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv)
         }
     
       // _info("Receive frame\n");
    -  // bcmf_hexdump((uint8_t*)header, len, (unsigned int)header);
    +  // bcmf_hexdump((uint8_t*)header, header->size, (unsigned int)header);
     
       /* Process and validate header */
     
    -  ret = bcmf_sdpcm_process_header(priv, header);
    +  ret = bcmf_sdpcm_process_header(sbus, header);
       if (ret != OK)
         {
           _err("Error while processing header %d\n", ret);
    @@ -272,70 +247,26 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv)
           goto exit_free_frame;
         }
     
    +  /* Setup new frame structure */  
    +
    +  sframe->frame_header.len = header->size;
    +  sframe->frame_header.data = (uint8_t*)header + header->data_offset;
    +  sframe->frame_header.base = (uint8_t*)header;
    +
       /* Process received frame content */
     
       switch (header->channel & 0x0f)
         {
           case SDPCM_CONTROL_CHANNEL:
    -        // _info("Control message\n");
    -
    -        /* Check frame */
    -
    -        if (header->size < sizeof(struct bcmf_sdpcm_header) + 
    -                           sizeof(struct bcmf_sdpcm_cdc_header))
    -          {
    -            _err("Control frame too small\n");
    -            ret = -EINVAL;
    -            goto exit_free_frame;
    -
    -          }
    -
    -        struct bcmf_sdpcm_cdc_header *cdc_header =
    -                (struct bcmf_sdpcm_cdc_header*)&header[1];
    -
    -        if (header->size < sizeof(struct bcmf_sdpcm_header) + 
    -                           sizeof(struct bcmf_sdpcm_cdc_header) +
    -                           cdc_header->len ||
    -            cdc_header->len > sizeof(tmp_buffer) -
    -                              sizeof(struct bcmf_sdpcm_header) -
    -                              sizeof(struct bcmf_sdpcm_cdc_header))
    -          {
    -            _err("Invalid control frame size\n");
    -            ret = -EINVAL;
    -            goto exit_free_frame;
    -          }
    -
    -        // TODO check interface ?
    -
    -        if (cdc_header->flags >> CDC_DCMD_ID_SHIFT == priv->control_reqid)
    -          {
    -            /* Expected frame received, send it back to user */
    -
    -            // TODO allocate real buffer
    -            memcpy(tmp_buffer_ctl, tmp_buffer, header->size);
    -            priv->control_rxframe = tmp_buffer_ctl;
    -            // priv->control_rxframe = (uint8_t*)header;
    -
    -            sem_post(&priv->control_timeout);
    -            return OK;
    -          }
    -        else
    -          {
    -            _info("Got unexpected control frame\n");
    -            ret = -EINVAL;
    -            goto exit_free_frame;
    -          }
    +        ret = bcmf_cdc_process_control_frame(priv, &sframe->frame_header);
             break;
     
           case SDPCM_EVENT_CHANNEL:
    -        _info("Event message\n");
    -        bcmf_hexdump((uint8_t*)header, header->size, (unsigned long)header);
    -        ret = OK;
    +        ret = bcmf_cdc_process_event_frame(priv, &sframe->frame_header);
             break;
     
           case SDPCM_DATA_CHANNEL:
    -        _info("Data message\n");
    -        ret = OK;
    +        ret = bcmf_cdc_process_data_frame(priv, &sframe->frame_header);
             break;
     
           default:
    @@ -350,23 +281,25 @@ exit_free_frame:
     exit_free_abort:
       // TODO free frame buffer
     exit_abort:
    -  bcmf_sdpcm_rxfail(priv, false);
    +  bcmf_sdpcm_rxfail(sbus, false);
       return ret;
     }
     
     int bcmf_sdpcm_sendframe(FAR struct bcmf_dev_s *priv)
     {
       int ret;
    -  struct bcmf_sdpcm_frame *frame;
    +  struct bcmf_sdpcm_frame *sframe;
    +  struct bcmf_sdpcm_header *header;
    +  FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s*)priv->bus;
     
    -  if (priv->tx_queue.tail == NULL)
    +  if (sbus->tx_queue.tail == NULL)
         {
           /* No more frames to send */
     
           return -ENODATA;
         }
     
    -  if (priv->tx_seq == priv->max_seq)
    +  if (sbus->tx_seq == sbus->max_seq)
         {
           // TODO handle this case
           _err("No credit to send frame\n");
    @@ -374,23 +307,25 @@ int bcmf_sdpcm_sendframe(FAR struct bcmf_dev_s *priv)
         }
     
     
    -  if ((ret = sem_wait(&priv->tx_queue_mutex)) != OK)
    +  if ((ret = sem_wait(&sbus->tx_queue_mutex)) != OK)
         {
           return ret;
         }
     
    -  frame = (struct bcmf_sdpcm_frame*)priv->tx_queue.tail;
    +  sframe = container_of(sbus->tx_queue.tail,
    +                        struct bcmf_sdpcm_frame, list_entry);
    +  header = (struct bcmf_sdpcm_header*)sframe->frame_header.base;
     
       /* Set frame sequence id */
     
    -  frame->header.sequence = priv->tx_seq++;
    +  header->sequence = sbus->tx_seq++;
     
       // _info("Send frame\n");
    -  // bcmf_hexdump((uint8_t*)&frame->header, frame->header.size,
    -  //              (unsigned int)&frame->header);
    +  // bcmf_hexdump(sframe->frame_header.base, sframe->frame_header.len,
    +  //              (unsigned long)sframe->frame_header.base);
     
    -  ret = bcmf_transfer_bytes(priv, true, 2, 0, (uint8_t*)&frame->header,
    -                            frame->header.size);
    +  ret = bcmf_transfer_bytes(sbus, true, 2, 0, sframe->frame_header.base,
    +                            sframe->frame_header.len);
       if (ret != OK)
         {
           _info("fail send frame %d\n", ret);
    @@ -401,17 +336,17 @@ int bcmf_sdpcm_sendframe(FAR struct bcmf_dev_s *priv)
     
       /* Frame sent, remove it from queue */
     
    -  if (priv->tx_queue.head == &frame->list_entry)
    +  if (sbus->tx_queue.head == &sframe->list_entry)
         {
           /* List is empty */
     
    -      priv->tx_queue.head = NULL;
    -      priv->tx_queue.tail = NULL;
    +      sbus->tx_queue.head = NULL;
    +      sbus->tx_queue.tail = NULL;
         }
       else
         {
    -      priv->tx_queue.tail = frame->list_entry.blink;
    -      frame->list_entry.blink->flink = priv->tx_queue.head;
    +      sbus->tx_queue.tail = sframe->list_entry.blink;
    +      sframe->list_entry.blink->flink = sbus->tx_queue.head;
         }
     
       /* TODO free frame buffer */
    @@ -419,235 +354,110 @@ int bcmf_sdpcm_sendframe(FAR struct bcmf_dev_s *priv)
       goto exit_post_sem;
     
     exit_abort:
    -  // bcmf_sdpcm_txfail(priv, false);
    +  // bcmf_sdpcm_txfail(sbus, false);
     exit_post_sem:
    -  sem_post(&priv->tx_queue_mutex);
    +  sem_post(&sbus->tx_queue_mutex);
       return ret;
     }
     
     // FIXME remove
     uint8_t tmp_buffer2[512];
    -uint8_t* bcmf_sdpcm_allocate_iovar(FAR struct bcmf_dev_s *priv, char *name,
    -                              uint8_t *data, uint32_t *len)
    +struct bcmf_frame_s* bcmf_sdpcm_allocate_frame(FAR struct bcmf_dev_s *priv,
    +                                   unsigned int len, bool control, bool block)
     {
    -  uint32_t data_len;
    -  uint16_t name_len;
    +  unsigned int frame_len;
     
    -  if (name)
    -    {
    -      name_len = strlen(name) + 1;
    -    }
    -  else
    -    {
    -      name_len = 0;
    -    }
    +  /* Integer overflow check */
     
    -  if (data)
    +  if (len > 512)
         {
    -      data_len = *len;
    +      return NULL;
         }
    -  else
    +
    +  frame_len = len + sizeof(struct bcmf_sdpcm_frame)
    +                  + sizeof(struct bcmf_sdpcm_header);
    +  if (!control)
         {
    -      data_len = 0;
    -    }
    +      /* Data frames needs 2 bytes padding */
     
    -  *len = 0;
    +      frame_len += 2;
    +    }
     
    -  // FIXME allocate buffer and use max_size instead of 512
    -  if (data_len > 512-sizeof(struct bcmf_sdpcm_cdc_frame) ||
    -      (data_len + name_len) > 512-sizeof(struct bcmf_sdpcm_cdc_frame))
    +  if (frame_len > 512)
         {
           return NULL;
         }
     
    -  // TODO allocate buffer len + sizeof(struct bcmf_sdpcm_cdc_frame)
    -
    -  /* Copy name string and data */
    -
    -  memcpy(tmp_buffer2+sizeof(struct bcmf_sdpcm_cdc_frame), name, name_len);
    -  memcpy(tmp_buffer2+sizeof(struct bcmf_sdpcm_cdc_frame)+name_len,
    -         data, data_len);
    -
    -  *len = sizeof(struct bcmf_sdpcm_cdc_frame)+name_len+data_len;
    -  return tmp_buffer2;
    -}
    +  // FIXME allocate buffer and use max_size instead of 512
    +  // allocate buffer len + sizeof(struct bcmf_sdpcm_frame)
     
    -int bcmf_sdpcm_queue_frame(FAR struct bcmf_dev_s *priv, uint8_t channel,
    -                           uint8_t *data, uint32_t len)
    -{
    -  int ret;
    -  struct bcmf_sdpcm_frame *frame = (struct bcmf_sdpcm_frame*)data;
    -  uint16_t frame_size = len - sizeof(frame->list_entry);
    +  struct bcmf_sdpcm_frame *sframe = (struct bcmf_sdpcm_frame*)tmp_buffer2;
    +  struct bcmf_sdpcm_header *header = (struct bcmf_sdpcm_header*)&sframe[1];
     
       /* Prepare sw header */
     
    -  memset(&frame->header, 0, sizeof(struct bcmf_sdpcm_header));
    -  frame->header.size = frame_size;
    -  frame->header.checksum = ~frame_size;
    -  frame->header.channel = channel;
    -  frame->header.data_offset = sizeof(struct bcmf_sdpcm_header);
    +  memset(header, 0, sizeof(struct bcmf_sdpcm_header));
    +  header->size = frame_len - sizeof(struct bcmf_sdpcm_frame);
    +  header->checksum = ~header->size;
     
    -  /* Add frame in tx queue */
    -
    -  if ((ret = sem_wait(&priv->tx_queue_mutex)) != OK)
    +  if (control)
         {
    -      return ret;
    -    }
    -
    -  if (priv->tx_queue.head == NULL)
    -    {
    -      /* List is empty */
    -
    -      priv->tx_queue.head = &frame->list_entry;
    -      priv->tx_queue.tail = &frame->list_entry;
    -
    -      frame->list_entry.flink = &frame->list_entry;
    -      frame->list_entry.blink = &frame->list_entry;
    +      header->channel = SDPCM_CONTROL_CHANNEL;
    +      header->data_offset = sizeof(struct bcmf_sdpcm_header);
         }
       else
         {
    -      /* Insert entry at list head */
    -
    -      frame->list_entry.flink = priv->tx_queue.head;
    -      frame->list_entry.blink = priv->tx_queue.tail;
    -
    -      priv->tx_queue.head->blink = &frame->list_entry;
    -      priv->tx_queue.head = &frame->list_entry;
    +      header->channel = SDPCM_DATA_CHANNEL;
    +      header->data_offset = sizeof(struct bcmf_sdpcm_header)+2;
         }
     
    -  sem_post(&priv->tx_queue_mutex);
    -
    -  /* Notify bcmf thread tx frame is ready */
    -
    -  sem_post(&priv->thread_signal);
    -
    -  return OK;
    -}
    -
    -int bcmf_sdpcm_send_cdc_frame(FAR struct bcmf_dev_s *priv, uint32_t cmd,
    -                         int ifidx, bool set, uint8_t *data, uint32_t len)
    -{
    -  struct bcmf_sdpcm_cdc_frame *msg = (struct bcmf_sdpcm_cdc_frame*)data;
    -
    -  /* Setup cdc_dcmd header */
    -
    -  msg->cdc_header.cmd = cmd;
    -  msg->cdc_header.len = len-sizeof(struct bcmf_sdpcm_cdc_frame);
    -  msg->cdc_header.status = 0;
    -  msg->cdc_header.flags = ++priv->control_reqid << CDC_DCMD_ID_SHIFT;
    -  msg->cdc_header.flags |= ifidx << CDC_DCMD_IF_SHIFT;
    +  sframe->frame_header.len = header->size;
    +  sframe->frame_header.base = (uint8_t*)header;
    +  sframe->frame_header.data = (uint8_t*)header + header->data_offset;
     
    -  if (set)
    -  {
    -    msg->cdc_header.flags |= CDC_DCMD_SET;
    -  }
    -
    -  /* Queue frame */
    -
    -  return bcmf_sdpcm_queue_frame(priv, SDPCM_CONTROL_CHANNEL, data, len);
    +  return &sframe->frame_header;
     }
     
    -int bcmf_sdpcm_control_request(FAR struct bcmf_dev_s *priv,
    -                               uint32_t ifidx, bool set, uint32_t cmd,
    -                               char *name, uint8_t *data, uint32_t *len)
    +int bcmf_sdpcm_queue_frame(FAR struct bcmf_dev_s *priv,
    +                           struct bcmf_frame_s *frame)
     {
       int ret;
    -  uint8_t *iovar_buf;
    -  uint32_t out_len = *len;
    -  uint32_t iovar_buf_len = *len;
    -
    -  *len = 0;
    -
    -  /* Take device control mutex */
    -
    -  if ((ret = sem_wait(&priv->control_mutex)) !=OK)
    -   {
    -      return ret;
    -   }
    +  FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s*)priv->bus;
    +  struct bcmf_sdpcm_frame *sframe = (struct bcmf_sdpcm_frame*)frame;
     
    -  /* Prepare control frame */
    +  /* Add frame in tx queue */
     
    -  iovar_buf = bcmf_sdpcm_allocate_iovar(priv, name, data, &iovar_buf_len);
    -  if (!iovar_buf)
    +  if ((ret = sem_wait(&sbus->tx_queue_mutex)) != OK)
         {
    -      _err("Cannot allocate iovar buf\n");
    -      ret = -ENOMEM;
    -      goto exit_sem_post;
    +      return ret;
         }
     
    -  /* Send control frame. iovar buffer is freed when sent */
    -
    -  ret = bcmf_sdpcm_send_cdc_frame(priv, cmd,
    -                             ifidx, set, iovar_buf, iovar_buf_len);
    -  if (ret != OK)
    +  if (sbus->tx_queue.head == NULL)
         {
    -      // TODO free allocated iovar buffer here
    -      goto exit_sem_post;
    -    }
    -
    -  /* Wait for response */
    +      /* List is empty */
     
    -  priv->control_rxframe = NULL;
    +      sbus->tx_queue.head = &sframe->list_entry;
    +      sbus->tx_queue.tail = &sframe->list_entry;
     
    -  ret = bcmf_sem_wait(&priv->control_timeout, SDPCM_CONTROL_TIMEOUT_MS);
    -  if (ret != OK)
    -    {
    -      _err("Error while waiting for control response %d\n", ret);
    -      goto exit_sem_post;
    +      sframe->list_entry.flink = &sframe->list_entry;
    +      sframe->list_entry.blink = &sframe->list_entry;
         }
    -
    -  /* Check frame status */
    -
    -  struct bcmf_sdpcm_cdc_dcmd *rxframe =
    -              (struct bcmf_sdpcm_cdc_dcmd*)priv->control_rxframe;
    -
    -  priv->control_status = rxframe->cdc_header.status;
    -
    -  if (priv->control_status != 0)
    +  else
         {
    -      _err("Invalid cdc status 0x%x\n", priv->control_status);
    -      ret = -EIO;
    -      goto exit_free_rx_frame;
    -    }
    +      /* Insert entry at list head */
     
    -  if (!set)
    -    {
    -      /* Request sent, copy received data back */
    -
    -      if (rxframe->cdc_header.len > out_len)
    -        {
    -          _err("RX frame too big %d %d\n", rxframe->cdc_header.len, out_len);
    -          memcpy(data, rxframe->data, out_len);
    -          *len = out_len;
    -        }
    -      else
    -        {
    -          memcpy(data, rxframe->data, rxframe->cdc_header.len);
    -          *len = rxframe->cdc_header.len;
    -        }
    +      sframe->list_entry.flink = sbus->tx_queue.head;
    +      sframe->list_entry.blink = sbus->tx_queue.tail;
    +
    +      sbus->tx_queue.head->blink = &sframe->list_entry;
    +      sbus->tx_queue.head = &sframe->list_entry;
         }
     
    -exit_free_rx_frame:
    -  // TODO free rxframe buffer */
    -  priv->control_rxframe = NULL;
    +  sem_post(&sbus->tx_queue_mutex);
     
    -exit_sem_post:
    -  sem_post(&priv->control_mutex);
    -  return ret;
    -}
    +  /* Notify bcmf thread tx frame is ready */
     
    -int bcmf_sdpcm_iovar_request(FAR struct bcmf_dev_s *priv,
    -                             uint32_t ifidx, bool set, char *name,
    -                             uint8_t *data, uint32_t *len)
    -{
    -  return bcmf_sdpcm_control_request(priv, ifidx, set,
    -                                  set ? WLC_SET_VAR : WLC_GET_VAR, name,
    -                                  data, len);
    -}
    +  sem_post(&sbus->thread_signal);
     
    -int bcmf_sdpcm_ioctl(FAR struct bcmf_dev_s *priv,
    -                     uint32_t ifidx, bool set, uint32_t cmd,
    -                     uint8_t *data, uint32_t *len)
    -{
    -   return bcmf_sdpcm_control_request(priv, ifidx, set, cmd, NULL, data, len);
    +  return OK;
     }
    \ No newline at end of file
    diff --git a/drivers/wireless/ieee80211/bcmf_sdpcm.h b/drivers/wireless/ieee80211/bcmf_sdpcm.h
    index 1735482d26..1136a8bb57 100644
    --- a/drivers/wireless/ieee80211/bcmf_sdpcm.h
    +++ b/drivers/wireless/ieee80211/bcmf_sdpcm.h
    @@ -7,12 +7,10 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv);
     
     int bcmf_sdpcm_sendframe(FAR struct bcmf_dev_s *priv);
     
    -int bcmf_sdpcm_iovar_request(FAR struct bcmf_dev_s *priv,
    -                             uint32_t ifidx, bool set, char *name,
    -                             uint8_t *data, uint32_t *len);
    +int bcmf_sdpcm_queue_frame(FAR struct bcmf_dev_s *priv,
    +                           struct bcmf_frame_s *frame);
     
    -int bcmf_sdpcm_ioctl(FAR struct bcmf_dev_s *priv,
    -                     uint32_t ifidx, bool set, uint32_t cmd,
    -                     uint8_t *data, uint32_t *len);
    +struct bcmf_frame_s* bcmf_sdpcm_allocate_frame(FAR struct bcmf_dev_s *priv,
    +                                unsigned int len, bool control, bool block);
     
     #endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_SDPCM_H */
    \ No newline at end of file
    diff --git a/drivers/wireless/ieee80211/bcmf_hexdump.c b/drivers/wireless/ieee80211/bcmf_utils.c
    similarity index 50%
    rename from drivers/wireless/ieee80211/bcmf_hexdump.c
    rename to drivers/wireless/ieee80211/bcmf_utils.c
    index d1f29b02ff..3b0fbf4b41 100644
    --- a/drivers/wireless/ieee80211/bcmf_hexdump.c
    +++ b/drivers/wireless/ieee80211/bcmf_utils.c
    @@ -1,11 +1,18 @@
    -#include 
     #include 
     #include 
    -
    +#include 
    +#include 
     #include 
    +#include 
    +
    +#include "bcmf_utils.h"
     
     #define LINE_LEN 16
     
    +/****************************************************************************
    + * Name: bcmf_hexdump
    + ****************************************************************************/
    +
     void bcmf_hexdump(uint8_t *data, unsigned int len, unsigned long offset)
     {
     	unsigned int i;
    @@ -33,4 +40,27 @@ void bcmf_hexdump(uint8_t *data, unsigned int len, unsigned long offset)
     		hex_line[3*LINE_LEN] = 0;
     		_info("%08x: %s%s\n", offset+i-char_count, hex_line, char_line);
     	}
    +}
    +
    +/****************************************************************************
    + * Name: bcmf_sem_wait
    + ****************************************************************************/
    +
    +int bcmf_sem_wait(sem_t *sem, unsigned int timeout_ms)
    +{
    +  struct timespec abstime;
    +
    +  /* Get the current time */
    +
    +  (void)clock_gettime(CLOCK_REALTIME, &abstime);
    +
    +  abstime.tv_nsec += 1000 * 1000* timeout_ms;
    +
    +  if (abstime.tv_nsec >= 1000 * 1000 * 1000)
    +    {
    +      abstime.tv_sec++;
    +      abstime.tv_nsec -= 1000 * 1000 * 1000;
    +    }
    +
    +  return sem_timedwait(sem, &abstime);
     }
    \ No newline at end of file
    diff --git a/drivers/wireless/ieee80211/bcmf_utils.h b/drivers/wireless/ieee80211/bcmf_utils.h
    new file mode 100644
    index 0000000000..a4b93c690d
    --- /dev/null
    +++ b/drivers/wireless/ieee80211/bcmf_utils.h
    @@ -0,0 +1,11 @@
    +#ifndef __DRIVERS_WIRELESS_IEEE80211_BCMF_UTILS_H
    +#define __DRIVERS_WIRELESS_IEEE80211_BCMF_UTILS_H
    +
    +#include 
    +#include 
    +
    +void bcmf_hexdump(uint8_t *data, unsigned int len, unsigned long offset);
    +
    +int bcmf_sem_wait(sem_t *sem, unsigned int timeout_ms);
    +
    +#endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_UTILS_H */
    \ No newline at end of file
    -- 
    GitLab
    
    
    From 0ac6fbb3c729bcd32b0d9012d0cc775cfd015cd1 Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Sun, 23 Apr 2017 16:24:47 -0600
    Subject: [PATCH 567/990] drivers/ieee80211/: Change all occurrences of _info,
     _warn, and _err to wlinfo, wlwarn, and wlerr.
    
    ---
     drivers/wireless/ieee80211/bcmf_cdc.c    | 18 ++++----
     drivers/wireless/ieee80211/bcmf_core.c   | 22 +++++-----
     drivers/wireless/ieee80211/bcmf_driver.c | 10 ++---
     drivers/wireless/ieee80211/bcmf_sdio.c   | 26 ++++++------
     drivers/wireless/ieee80211/bcmf_sdpcm.c  | 24 +++++------
     drivers/wireless/ieee80211/bcmf_utils.c  | 54 +++++++++++++-----------
     drivers/wireless/ieee80211/mmc_sdio.c    | 26 ++++++------
     7 files changed, 92 insertions(+), 88 deletions(-)
    
    diff --git a/drivers/wireless/ieee80211/bcmf_cdc.c b/drivers/wireless/ieee80211/bcmf_cdc.c
    index b3f772963f..79a8f05030 100644
    --- a/drivers/wireless/ieee80211/bcmf_cdc.c
    +++ b/drivers/wireless/ieee80211/bcmf_cdc.c
    @@ -202,7 +202,7 @@ int bcmf_cdc_control_request(FAR struct bcmf_dev_s *priv,
       frame = bcmf_cdc_allocate_frame(priv, name, data, out_len);
       if (!frame)
         {
    -      _err("Cannot allocate cdc frame\n");
    +      wlerr("Cannot allocate cdc frame\n");
           ret = -ENOMEM;
           goto exit_sem_post;
         }
    @@ -224,7 +224,7 @@ int bcmf_cdc_control_request(FAR struct bcmf_dev_s *priv,
       ret = bcmf_sem_wait(&priv->control_timeout, CDC_CONTROL_TIMEOUT_MS);
       if (ret != OK)
         {
    -      _err("Error while waiting for control response %d\n", ret);
    +      wlerr("Error while waiting for control response %d\n", ret);
           goto exit_sem_post;
         }
     
    @@ -234,7 +234,7 @@ int bcmf_cdc_control_request(FAR struct bcmf_dev_s *priv,
     
       if (priv->control_status != 0)
         {
    -      _err("Invalid cdc status 0x%x\n", priv->control_status);
    +      wlerr("Invalid cdc status 0x%x\n", priv->control_status);
           ret = -EINVAL;
         }
     
    @@ -275,7 +275,7 @@ int bcmf_cdc_process_control_frame(FAR struct bcmf_dev_s *priv,
     
       if (data_size < sizeof(struct bcmf_cdc_header))
         {
    -      _err("Control frame too small\n");
    +      wlerr("Control frame too small\n");
           return -EINVAL;
         }
     
    @@ -284,7 +284,7 @@ int bcmf_cdc_process_control_frame(FAR struct bcmf_dev_s *priv,
       if (data_size < cdc_header->len ||
           data_size < sizeof(struct bcmf_cdc_header) + cdc_header->len)
         {
    -      _err("Invalid control frame size\n");
    +      wlerr("Invalid control frame size\n");
           return -EINVAL;
         }
     
    @@ -300,7 +300,7 @@ int bcmf_cdc_process_control_frame(FAR struct bcmf_dev_s *priv,
             {
               if (priv->control_rxdata_len > cdc_header->len)
                 {
    -              _err("Not enough data %d %d\n",
    +              wlerr("Not enough data %d %d\n",
                           priv->control_rxdata_len, cdc_header->len);
                   priv->control_rxdata_len = cdc_header->len;
                 }
    @@ -312,14 +312,14 @@ int bcmf_cdc_process_control_frame(FAR struct bcmf_dev_s *priv,
           return OK;
         }
     
    -  _info("Got unexpected control frame\n");
    +  wlinfo("Got unexpected control frame\n");
       return -EINVAL;
     }
     
     int bcmf_cdc_process_event_frame(FAR struct bcmf_dev_s *priv,
                        struct bcmf_frame_s *frame)
     {
    -  _info("Event message\n");
    +  wlinfo("Event message\n");
       bcmf_hexdump(frame->base, frame->len, (unsigned long)frame->base);
       return OK;
     }
    @@ -327,7 +327,7 @@ int bcmf_cdc_process_event_frame(FAR struct bcmf_dev_s *priv,
     int bcmf_cdc_process_data_frame(FAR struct bcmf_dev_s *priv,
                        struct bcmf_frame_s *frame)
     {
    -  _info("Data message\n");
    +  wlinfo("Data message\n");
       bcmf_hexdump(frame->base, frame->len, (unsigned long)frame->base);
       return OK;
     }
    \ No newline at end of file
    diff --git a/drivers/wireless/ieee80211/bcmf_core.c b/drivers/wireless/ieee80211/bcmf_core.c
    index a0bf4ab262..77cd59f314 100644
    --- a/drivers/wireless/ieee80211/bcmf_core.c
    +++ b/drivers/wireless/ieee80211/bcmf_core.c
    @@ -165,7 +165,7 @@ int bcmf_upload_binary(FAR struct bcmf_sdio_dev_s *sbus, uint32_t address,
                                     address & SBSDIO_SB_OFT_ADDR_MASK, buf, size);
           if (ret != OK)
             {
    -            _err("transfer failed %d %x %d\n", ret, address, size);
    +            wlerr("transfer failed %d %x %d\n", ret, address, size);
                 return ret;
             }
     
    @@ -186,7 +186,7 @@ int bcmf_upload_nvram(FAR struct bcmf_sdio_dev_s *sbus)
     
       nvram_sz = (*sbus->chip->nvram_image_size + 63) & (-64);
     
    -  _info("nvram size is %d %d bytes\n", nvram_sz,
    +  wlinfo("nvram size is %d %d bytes\n", nvram_sz,
                                            *sbus->chip->nvram_image_size);
     
       /* Write image */
    @@ -262,7 +262,7 @@ int bcmf_core_upload_firmware(FAR struct bcmf_sdio_dev_s *sbus)
     {
       int ret;
     
    -  _info("upload firmware\n");
    +  wlinfo("upload firmware\n");
     
       /* Disable ARMCM3 core and reset SOCRAM core
        * to set device in firmware upload mode */
    @@ -274,23 +274,23 @@ int bcmf_core_upload_firmware(FAR struct bcmf_sdio_dev_s *sbus)
     
       /* Flash chip firmware */
     
    -  _info("firmware size is %d bytes\n", *sbus->chip->firmware_image_size);
    +  wlinfo("firmware size is %d bytes\n", *sbus->chip->firmware_image_size);
       ret = bcmf_upload_binary(sbus, 0, sbus->chip->firmware_image,
                                *sbus->chip->firmware_image_size);
     
       if (ret != OK)
         {
    -        _err("Failed to upload firmware\n");
    +        wlerr("Failed to upload firmware\n");
             return ret;
         }
     
       /* Flash NVRAM configuration file */
     
    -  _info("upload nvram configuration\n");
    +  wlinfo("upload nvram configuration\n");
       ret = bcmf_upload_nvram(sbus);
       if (ret != OK)
         {
    -        _err("Failed to upload nvram\n");
    +        wlerr("Failed to upload nvram\n");
             return ret;
         }
     
    @@ -304,7 +304,7 @@ int bcmf_core_upload_firmware(FAR struct bcmf_sdio_dev_s *sbus)
       up_mdelay(10);
       if (!bcmf_core_isup(sbus, WLAN_ARMCM3_CORE_ID))
         {
    -      _err("Cannot start ARMCM3 core\n");
    +      wlerr("Cannot start ARMCM3 core\n");
           return -ETIMEDOUT;
         }
     
    @@ -317,7 +317,7 @@ bool bcmf_core_isup(FAR struct bcmf_sdio_dev_s *sbus, unsigned int core)
     
       if (core >= MAX_CORE_ID)
         {
    -      _err("Invalid core id %d\n", core);
    +      wlerr("Invalid core id %d\n", core);
           return false;
         }
       uint32_t base = sbus->chip->core_base[core];
    @@ -340,7 +340,7 @@ void bcmf_core_disable(FAR struct bcmf_sdio_dev_s *sbus, unsigned int core)
     
       if (core >= MAX_CORE_ID)
         {
    -      _err("Invalid core id %d\n", core);
    +      wlerr("Invalid core id %d\n", core);
           return;
         }
       uint32_t base = sbus->chip->core_base[core];
    @@ -378,7 +378,7 @@ void bcmf_core_reset(FAR struct bcmf_sdio_dev_s *sbus, unsigned int core)
     
       if (core >= MAX_CORE_ID)
         {
    -      _err("Invalid core id %d\n", core);
    +      wlerr("Invalid core id %d\n", core);
           return;
         }
       uint32_t base = sbus->chip->core_base[core];
    diff --git a/drivers/wireless/ieee80211/bcmf_driver.c b/drivers/wireless/ieee80211/bcmf_driver.c
    index a30659b226..828de645f0 100644
    --- a/drivers/wireless/ieee80211/bcmf_driver.c
    +++ b/drivers/wireless/ieee80211/bcmf_driver.c
    @@ -151,7 +151,7 @@ int bcmf_wl_set_mac_address(FAR struct bcmf_dev_s *priv, uint8_t *addr)
           return ret;
         }
     
    -  _info("MAC address updated %02X:%02X:%02X:%02X:%02X:%02X\n",
    +  wlinfo("MAC address updated %02X:%02X:%02X:%02X:%02X:%02X\n",
                                 addr[0], addr[1], addr[2],
                                 addr[3], addr[4], addr[5]);
       memcpy(priv->mac_addr, addr, 6);
    @@ -312,7 +312,7 @@ int bcmf_run_escan(FAR struct bcmf_dev_s *priv)
     
       params->params.channel_num = 0;
     
    -  _info("start scan\n");
    +  wlinfo("start scan\n");
     
       out_len = sizeof(*params);
       ret = bcmf_cdc_iovar_request(priv, CHIP_STA_INTERFACE, true,
    @@ -365,7 +365,7 @@ int bcmf_wl_initialize(FAR struct bcmf_dev_s *priv)
     
       memcpy(priv->mac_addr, tmp_buf, 6);
     
    -  _info("MAC address is %02X:%02X:%02X:%02X:%02X:%02X\n",
    +  wlinfo("MAC address is %02X:%02X:%02X:%02X:%02X:%02X\n",
                             tmp_buf[0], tmp_buf[1], tmp_buf[2],
                             tmp_buf[3], tmp_buf[4], tmp_buf[5]);
       
    @@ -387,7 +387,7 @@ int bcmf_wl_initialize(FAR struct bcmf_dev_s *priv)
           tmp_buf[out_len-1] = 0;
         }
     
    -  _info("fw version <%s>\n", tmp_buf);
    +  wlinfo("fw version <%s>\n", tmp_buf);
     
       /* FIXME Configure event mask to enable all asynchronous events */
     
    @@ -412,7 +412,7 @@ int bcmf_sdio_initialize(int minor, FAR struct sdio_dev_s *dev)
       int ret;
       FAR struct bcmf_dev_s *priv;
     
    -  _info("minor: %d\n", minor);
    +  wlinfo("minor: %d\n", minor);
     
       priv = bcmf_allocate_device();
       if (!priv)
    diff --git a/drivers/wireless/ieee80211/bcmf_sdio.c b/drivers/wireless/ieee80211/bcmf_sdio.c
    index 178e716187..6df441faaa 100644
    --- a/drivers/wireless/ieee80211/bcmf_sdio.c
    +++ b/drivers/wireless/ieee80211/bcmf_sdio.c
    @@ -155,7 +155,7 @@ int bcmf_sdio_bus_sleep(FAR struct bcmf_sdio_dev_s *sbus, bool sleep)
                                SBSDIO_HT_AVAIL_REQ | SBSDIO_FORCE_HT);
           if (ret != OK)
             {
    -          _err("HT Avail request failed %d\n", ret);
    +          wlerr("HT Avail request failed %d\n", ret);
               return ret;
             }
       
    @@ -181,7 +181,7 @@ int bcmf_sdio_bus_sleep(FAR struct bcmf_sdio_dev_s *sbus, bool sleep)
       
           if (loops <= 0)
             {
    -          _err("HT clock not ready\n");
    +          wlerr("HT clock not ready\n");
               return -ETIMEDOUT;
             }
     
    @@ -254,7 +254,7 @@ int bcmf_probe(FAR struct bcmf_sdio_dev_s *sbus)
     
     exit_error:
     
    -  _err("ERROR: failed to probe device %d\n", sbus->minor);
    +  wlerr("ERROR: failed to probe device %d\n", sbus->minor);
       return ret;
     }
     
    @@ -300,7 +300,7 @@ int bcmf_businitialize(FAR struct bcmf_sdio_dev_s *sbus)
     
       if (loops <= 0)
         {
    -      _err("failed to enable ALP\n");
    +      wlerr("failed to enable ALP\n");
           return -ETIMEDOUT;
         }
     
    @@ -651,7 +651,7 @@ int bcmf_bus_sdio_initialize(FAR struct bcmf_dev_s *priv,
     
       if (ret <= 0)
         {
    -      _err("Cannot spawn bcmf thread\n");
    +      wlerr("Cannot spawn bcmf thread\n");
           ret = -EBADE;
           goto exit_uninit_hw;
         }
    @@ -684,19 +684,19 @@ int bcmf_chipinitialize(FAR struct bcmf_sdio_dev_s *sbus)
         {
           return ret;
         }
    -  _info("chip id is 0x%x\n", value);
    +  wlinfo("chip id is 0x%x\n", value);
     
       int chipid = value & 0xffff;
       switch (chipid)
         {
     #ifdef CONFIG_IEEE80211_BROADCOM_BCM43362
           case SDIO_DEVICE_ID_BROADCOM_43362:
    -        _info("bcm43362 chip detected\n");
    +        wlinfo("bcm43362 chip detected\n");
             sbus->chip = (struct bcmf_sdio_chip*)&bcmf_43362_config_sdio;
             break;
     #endif
           default:
    -        _err("chip 0x%x is not supported\n", chipid);
    +        wlerr("chip 0x%x is not supported\n", chipid);
             return -ENODEV;
        }
       return OK;
    @@ -718,7 +718,7 @@ int bcmf_sdio_thread(int argc, char **argv)
       FAR struct bcmf_dev_s *priv = g_sdio_priv;
       FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s*)priv->bus;
       
    -  _info("Enter\n");
    +  wlinfo("Enter\n");
     
       /*  FIXME wait for the chip to be ready to receive commands */
     
    @@ -731,7 +731,7 @@ int bcmf_sdio_thread(int argc, char **argv)
           ret = sem_wait(&sbus->thread_signal);
           if (ret != OK)
             {
    -          _err("Error while waiting for semaphore\n");
    +          wlerr("Error while waiting for semaphore\n");
               break;
             }
     
    @@ -759,14 +759,14 @@ int bcmf_sdio_thread(int argc, char **argv)
               bcmf_write_sbregw(sbus,
                            CORE_BUS_REG(sbus->chip->core_base[SDIOD_CORE_ID],
                            intstatus), sbus->intstatus);
    -          // _info("intstatus %x\n", sbus->intstatus);
    +          // wlinfo("intstatus %x\n", sbus->intstatus);
             }
     
           /* On frame indication, read available frames */
     
           if (sbus->intstatus & I_HMB_FRAME_IND)
             {
    -          // _info("Frames available\n");
    +          // wlinfo("Frames available\n");
     
               do
                 {
    @@ -794,7 +794,7 @@ int bcmf_sdio_thread(int argc, char **argv)
           // bcmf_sdio_bus_sleep(sbus, true);
         }
     
    -  _info("Exit\n");
    +  wlinfo("Exit\n");
     
       return 0;
     }
    \ No newline at end of file
    diff --git a/drivers/wireless/ieee80211/bcmf_sdpcm.c b/drivers/wireless/ieee80211/bcmf_sdpcm.c
    index b363bba249..e6146b5af8 100644
    --- a/drivers/wireless/ieee80211/bcmf_sdpcm.c
    +++ b/drivers/wireless/ieee80211/bcmf_sdpcm.c
    @@ -147,19 +147,19 @@ int bcmf_sdpcm_process_header(FAR struct bcmf_sdio_dev_s *sbus,
       if (header->data_offset < sizeof(struct bcmf_sdpcm_header) ||
           header->data_offset > header->size)
         {
    -      _err("Invalid data offset\n");
    +      wlerr("Invalid data offset\n");
           bcmf_sdpcm_rxfail(sbus, false);
           return -ENXIO;
         }
     
       /* Update tx credits */
     
    -  // _info("update credit %x %x %x\n", header->credit,
    +  // wlinfo("update credit %x %x %x\n", header->credit,
       //                                   sbus->tx_seq, sbus->max_seq);
     
       if (header->credit - sbus->tx_seq > 0x40)
         {
    -      _err("seq %d: max tx seq number error\n", sbus->tx_seq);
    +      wlerr("seq %d: max tx seq number error\n", sbus->tx_seq);
           sbus->max_seq = sbus->tx_seq + 2;
         }
       else
    @@ -194,7 +194,7 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv)
       ret = bcmf_transfer_bytes(sbus, false, 2, 0, (uint8_t*)header, 4);
       if (ret != OK)
         {
    -      _info("failread size\n");
    +      wlinfo("failread size\n");
           ret = -EIO;
           goto exit_abort;
         }
    @@ -211,7 +211,7 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv)
     
       if (((~len & 0xffff) ^ checksum) || len < sizeof(struct bcmf_sdpcm_header))
         {
    -      _err("Invalid header checksum or len %x %x\n", len, checksum);
    +      wlerr("Invalid header checksum or len %x %x\n", len, checksum);
           ret = -EINVAL;
           goto exit_abort;
         }
    @@ -219,7 +219,7 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv)
       // FIXME define for size
       if (len > sizeof(tmp_buffer))
         {
    -      _err("Frame is too large, cancel %d\n", len);
    +      wlerr("Frame is too large, cancel %d\n", len);
           ret = -ENOMEM;
           goto exit_abort;
         }
    @@ -234,7 +234,7 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv)
           goto exit_free_abort;
         }
     
    -  // _info("Receive frame\n");
    +  // wlinfo("Receive frame\n");
       // bcmf_hexdump((uint8_t*)header, header->size, (unsigned int)header);
     
       /* Process and validate header */
    @@ -242,7 +242,7 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv)
       ret = bcmf_sdpcm_process_header(sbus, header);
       if (ret != OK)
         {
    -      _err("Error while processing header %d\n", ret);
    +      wlerr("Error while processing header %d\n", ret);
           ret = -EINVAL;
           goto exit_free_frame;
         }
    @@ -270,7 +270,7 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv)
             break;
     
           default:
    -        _err("Got unexpected message type %d\n", header->channel);
    +        wlerr("Got unexpected message type %d\n", header->channel);
             ret = OK;
         }
     
    @@ -302,7 +302,7 @@ int bcmf_sdpcm_sendframe(FAR struct bcmf_dev_s *priv)
       if (sbus->tx_seq == sbus->max_seq)
         {
           // TODO handle this case
    -      _err("No credit to send frame\n");
    +      wlerr("No credit to send frame\n");
           return -EAGAIN;
         }
     
    @@ -320,7 +320,7 @@ int bcmf_sdpcm_sendframe(FAR struct bcmf_dev_s *priv)
     
       header->sequence = sbus->tx_seq++;
     
    -  // _info("Send frame\n");
    +  // wlinfo("Send frame\n");
       // bcmf_hexdump(sframe->frame_header.base, sframe->frame_header.len,
       //              (unsigned long)sframe->frame_header.base);
     
    @@ -328,7 +328,7 @@ int bcmf_sdpcm_sendframe(FAR struct bcmf_dev_s *priv)
                                 sframe->frame_header.len);
       if (ret != OK)
         {
    -      _info("fail send frame %d\n", ret);
    +      wlinfo("fail send frame %d\n", ret);
           ret = -EIO;
           goto exit_abort;
           // TODO handle retry count and remove frame from queue + abort TX
    diff --git a/drivers/wireless/ieee80211/bcmf_utils.c b/drivers/wireless/ieee80211/bcmf_utils.c
    index 3b0fbf4b41..dbd53b0619 100644
    --- a/drivers/wireless/ieee80211/bcmf_utils.c
    +++ b/drivers/wireless/ieee80211/bcmf_utils.c
    @@ -15,31 +15,35 @@
     
     void bcmf_hexdump(uint8_t *data, unsigned int len, unsigned long offset)
     {
    -	unsigned int i;
    -	unsigned int char_count = 0;
    -	char char_line[20];
    -	char hex_line[64];
    -
    -	for(i = 0; i < len; i++)
    -	{
    -		if (char_count >= LINE_LEN) {
    -			/* Flush line */
    -			_info("%08x: %s%s\n", offset+i-char_count, hex_line, char_line);
    -			char_count = 0;
    -		}
    -
    -		sprintf(hex_line+3*char_count, "%02x ", data[i]);
    -		sprintf(char_line+char_count, "%c",
    -				data[i] < 0x20 || data[i] >= 0x7f? '.': data[i]);
    -		char_count ++;
    -	}
    -
    -	if (char_count > 0) {
    -		/* Flush last line */
    -		memset(hex_line+3*char_count, ' ', 3*(LINE_LEN-char_count));
    -		hex_line[3*LINE_LEN] = 0;
    -		_info("%08x: %s%s\n", offset+i-char_count, hex_line, char_line);
    -	}
    +  unsigned int i;
    +  unsigned int char_count = 0;
    +  char char_line[20];
    +  char hex_line[64];
    +
    +  for(i = 0; i < len; i++)
    +    {
    +      if (char_count >= LINE_LEN)
    +      {
    +        /* Flush line */
    +
    +        wlinfo("%08x: %s%s\n", offset+i-char_count, hex_line, char_line);
    +        char_count = 0;
    +      }
    +
    +      sprintf(hex_line+3*char_count, "%02x ", data[i]);
    +      sprintf(char_line+char_count, "%c",
    +              data[i] < 0x20 || data[i] >= 0x7f? '.': data[i]);
    +      char_count ++;
    +    }
    +
    +  if (char_count > 0)
    +    {
    +      /* Flush last line */
    +
    +      memset(hex_line+3*char_count, ' ', 3*(LINE_LEN-char_count));
    +      hex_line[3*LINE_LEN] = 0;
    +      wlinfo("%08x: %s%s\n", offset+i-char_count, hex_line, char_line);
    +    }
     }
     
     /****************************************************************************
    diff --git a/drivers/wireless/ieee80211/mmc_sdio.c b/drivers/wireless/ieee80211/mmc_sdio.c
    index 947c71a956..39c4139160 100644
    --- a/drivers/wireless/ieee80211/mmc_sdio.c
    +++ b/drivers/wireless/ieee80211/mmc_sdio.c
    @@ -60,7 +60,7 @@ int sdio_sendcmdpoll(FAR struct sdio_dev_s *dev, uint32_t cmd, uint32_t arg)
           ret = SDIO_WAITRESPONSE(dev, cmd);
           if (ret != OK)
             {
    -          _err("ERROR: Wait for response to cmd: %08x failed: %d\n",
    +          wlerr("ERROR: Wait for response to cmd: %08x failed: %d\n",
                    cmd, ret);
             }
         }
    @@ -98,7 +98,7 @@ int sdio_io_rw_direct(FAR struct sdio_dev_s *dev, bool write,
     
         if (ret != OK)
           {
    -        _err("ERROR: SDIO_RECVR5 failed %d\n", ret);
    +        wlerr("ERROR: SDIO_RECVR5 failed %d\n", ret);
             return ret;
           }
     
    @@ -144,7 +144,7 @@ int sdio_io_rw_extended(FAR struct sdio_dev_s *dev, bool write,
           {
             /* Use byte mode */
     
    -        // _info("byte mode\n");
    +        // wlinfo("byte mode\n");
             arg.cmd53.block_mode = 0;
             arg.cmd53.byte_block_count = blocklen;
             nblocks = 1;
    @@ -165,7 +165,7 @@ int sdio_io_rw_extended(FAR struct sdio_dev_s *dev, bool write,
     
         if (write)
           {
    -        // _info("prep write %d %d\n", blocklen, nblocks);
    +        // wlinfo("prep write %d %d\n", blocklen, nblocks);
             sdio_sendcmdpoll(dev, SDIO_ACMD53, (uint32_t)arg.value);
             ret = SDIO_RECVR5(dev, SDIO_ACMD53, (uint32_t*)&resp);
     
    @@ -174,7 +174,7 @@ int sdio_io_rw_extended(FAR struct sdio_dev_s *dev, bool write,
           }
         else
           {
    -        // _info("prep read %d\n", blocklen * nblocks);
    +        // wlinfo("prep read %d\n", blocklen * nblocks);
             SDIO_RECVSETUP(dev, buf, blocklen * nblocks);
             SDIO_SENDCMD(dev, SDIO_ACMD53, (uint32_t)arg.value);
     
    @@ -184,7 +184,7 @@ int sdio_io_rw_extended(FAR struct sdio_dev_s *dev, bool write,
     
         if (ret != OK)
           {
    -        _err("ERROR: SDIO_RECVR5 failed %d\n", ret);
    +        wlerr("ERROR: SDIO_RECVR5 failed %d\n", ret);
             return ret;
           }
     
    @@ -192,17 +192,17 @@ int sdio_io_rw_extended(FAR struct sdio_dev_s *dev, bool write,
     
         if (wkupevent & SDIOWAIT_TIMEOUT)
           {
    -        _err("timeout\n");
    +        wlerr("timeout\n");
             return -ETIMEDOUT;
           }
         if (resp.flags.error || (wkupevent & SDIOWAIT_ERROR))
           {
    -        _err("error 1\n");
    +        wlerr("error 1\n");
             return -EIO;
           }
         if (resp.flags.function_number || resp.flags.out_of_range)
           {
    -        _err("error 2\n");
    +        wlerr("error 2\n");
             return -EINVAL;
           }
     
    @@ -266,11 +266,11 @@ int sdio_probe(FAR struct sdio_dev_s *dev)
       ret = SDIO_RECVR6(dev, SD_CMD3, &data);
         if (ret != OK)
         {
    -        _err("ERROR: RCA request failed: %d\n", ret);
    +        wlerr("ERROR: RCA request failed: %d\n", ret);
             return ret;
         }
     
    -    _info("rca is %x\n", data >> 16);
    +    wlinfo("rca is %x\n", data >> 16);
     
       /* Send CMD7 with the argument == RCA in order to select the card
        * and put it in Transfer State */
    @@ -280,7 +280,7 @@ int sdio_probe(FAR struct sdio_dev_s *dev)
       ret = SDIO_RECVR1(dev, MMCSD_CMD7S, &data);
       if (ret != OK)
         {
    -      _err("ERROR: card selection failed: %d\n", ret);
    +      wlerr("ERROR: card selection failed: %d\n", ret);
           return ret;
         }
     
    @@ -358,7 +358,7 @@ int sdio_enable_function(FAR struct sdio_dev_s *dev, uint8_t function)
             {
               /* Function enabled */
     
    -          _info("Function %d enabled\n", function);
    +          wlinfo("Function %d enabled\n", function);
               return OK;
             }
         }
    -- 
    GitLab
    
    
    From 80e22691fa8f66f69df8d33a3b83824b212f24f1 Mon Sep 17 00:00:00 2001
    From: Masatoshi Tateishi 
    Date: Thu, 9 Jan 2014 13:49:20 +0900
    Subject: [PATCH 568/990] USBMSC: Fix a wrong lun number issue
    
    Jira: PDFW15IS-98
    Signed-off-by: Masayuki Ishikawa 
    ---
     drivers/usbdev/usbmsc_scsi.c | 40 +++++++++++++++++++++++++++---------
     1 file changed, 30 insertions(+), 10 deletions(-)
    
    diff --git a/drivers/usbdev/usbmsc_scsi.c b/drivers/usbdev/usbmsc_scsi.c
    index 30e06be071..31c4b68ac0 100644
    --- a/drivers/usbdev/usbmsc_scsi.c
    +++ b/drivers/usbdev/usbmsc_scsi.c
    @@ -508,7 +508,7 @@ static inline int usbmsc_cmdrequestsense(FAR struct usbmsc_dev_s *priv,
     static inline int usbmsc_cmdread6(FAR struct usbmsc_dev_s *priv)
     {
       FAR struct scsicmd_read6_s *read6 = (FAR struct scsicmd_read6_s *)priv->cdb;
    -  FAR struct usbmsc_lun_s *lun = priv->lun;
    +  FAR struct usbmsc_lun_s *lun;
       int ret;
     
       priv->u.xfrlen = (uint16_t)read6->xfrlen;
    @@ -521,6 +521,8 @@ static inline int usbmsc_cmdread6(FAR struct usbmsc_dev_s *priv)
                             USBMSC_FLAGS_DIRDEVICE2HOST | USBMSC_FLAGS_BLOCKXFR);
       if (ret == OK)
         {
    +      lun = priv->lun;
    +
           /* Get the Logical Block Address (LBA) from cdb[] as the starting sector */
     
           priv->sector = (uint32_t)(read6->mslba & SCSICMD_READ6_MSLBAMASK) << 16 |
    @@ -568,7 +570,7 @@ static inline int usbmsc_cmdread6(FAR struct usbmsc_dev_s *priv)
     static inline int usbmsc_cmdwrite6(FAR struct usbmsc_dev_s *priv)
     {
       FAR struct scsicmd_write6_s *write6 = (FAR struct scsicmd_write6_s *)priv->cdb;
    -  FAR struct usbmsc_lun_s *lun = priv->lun;
    +  FAR struct usbmsc_lun_s *lun;
       int ret;
     
       priv->u.xfrlen = (uint16_t)write6->xfrlen;
    @@ -581,6 +583,8 @@ static inline int usbmsc_cmdwrite6(FAR struct usbmsc_dev_s *priv)
                             USBMSC_FLAGS_DIRHOST2DEVICE | USBMSC_FLAGS_BLOCKXFR);
       if (ret == OK)
         {
    +      lun = priv->lun;
    +
           /* Get the Logical Block Address (LBA) from cdb[] as the starting sector */
     
           priv->sector = (uint32_t)(write6->mslba & SCSICMD_WRITE6_MSLBAMASK) << 16 | (uint32_t)usbmsc_getbe16(write6->lslba);
    @@ -880,7 +884,7 @@ static inline int usbmsc_cmdpreventmediumremoval(FAR struct usbmsc_dev_s *priv)
     #ifdef CONFIG_USBMSC_REMOVABLE
       FAR struct scsicmd_preventmediumremoval_s *pmr = (FAR struct scsicmd_preventmediumremoval_s *)priv->cdb;
     #endif
    -  FAR struct usbmsc_lun_s *lun = priv->lun;
    +  FAR struct usbmsc_lun_s *lun;
       int ret;
     
       priv->u.alloclen = 0;
    @@ -888,6 +892,8 @@ static inline int usbmsc_cmdpreventmediumremoval(FAR struct usbmsc_dev_s *priv)
                             USBMSC_FLAGS_DIRNONE);
       if (ret == OK)
         {
    +      lun = priv->lun;
    +
     #ifndef CONFIG_USBMSC_REMOVABLE
           lun->sd = SCSI_KCQIR_INVALIDCOMMAND;
           ret = -EINVAL;
    @@ -919,7 +925,7 @@ static inline int usbmsc_cmdreadformatcapacity(FAR struct usbmsc_dev_s *priv,
     {
       FAR struct scsicmd_readformatcapcacities_s *rfc = (FAR struct scsicmd_readformatcapcacities_s *)priv->cdb;
       FAR struct scsiresp_readformatcapacities_s *hdr;
    -  FAR struct usbmsc_lun_s *lun = priv->lun;
    +  FAR struct usbmsc_lun_s *lun;
       int ret;
     
       priv->u.alloclen = usbmsc_getbe16(rfc->alloclen);
    @@ -927,6 +933,8 @@ static inline int usbmsc_cmdreadformatcapacity(FAR struct usbmsc_dev_s *priv,
                             USBMSC_FLAGS_DIRDEVICE2HOST);
       if (ret == OK)
         {
    +      lun = priv->lun;
    +
           hdr = (FAR struct scsiresp_readformatcapacities_s *)buf;
           memset(hdr, 0, SCSIRESP_READFORMATCAPACITIES_SIZEOF);
           hdr->listlen = SCSIRESP_CURRCAPACITYDESC_SIZEOF;
    @@ -955,7 +963,7 @@ static int inline usbmsc_cmdreadcapacity10(FAR struct usbmsc_dev_s *priv,
     {
       FAR struct scsicmd_readcapacity10_s *rcc = (FAR struct scsicmd_readcapacity10_s *)priv->cdb;
       FAR struct scsiresp_readcapacity10_s *rcr = (FAR struct scsiresp_readcapacity10_s *)buf;
    -  FAR struct usbmsc_lun_s *lun = priv->lun;
    +  FAR struct usbmsc_lun_s *lun;
       uint32_t lba;
       int ret;
     
    @@ -964,6 +972,8 @@ static int inline usbmsc_cmdreadcapacity10(FAR struct usbmsc_dev_s *priv,
                             USBMSC_FLAGS_DIRDEVICE2HOST);
       if (ret == OK)
         {
    +      lun = priv->lun;
    +
           /* Check the PMI and LBA fields */
     
           lba = usbmsc_getbe32(rcc->lba);
    @@ -996,7 +1006,7 @@ static int inline usbmsc_cmdreadcapacity10(FAR struct usbmsc_dev_s *priv,
     static inline int usbmsc_cmdread10(FAR struct usbmsc_dev_s *priv)
     {
       struct scsicmd_read10_s *read10 = (struct scsicmd_read10_s *)priv->cdb;
    -  FAR struct usbmsc_lun_s *lun = priv->lun;
    +  FAR struct usbmsc_lun_s *lun;
       int ret;
     
       priv->u.xfrlen = usbmsc_getbe16(read10->xfrlen);
    @@ -1004,6 +1014,8 @@ static inline int usbmsc_cmdread10(FAR struct usbmsc_dev_s *priv)
                             USBMSC_FLAGS_DIRDEVICE2HOST | USBMSC_FLAGS_BLOCKXFR);
       if (ret == OK)
         {
    +      lun = priv->lun;
    +
           /* Get the Logical Block Address (LBA) from cdb[] as the starting sector */
     
           priv->sector = usbmsc_getbe32(read10->lba);
    @@ -1058,7 +1070,7 @@ static inline int usbmsc_cmdread10(FAR struct usbmsc_dev_s *priv)
     static inline int usbmsc_cmdwrite10(FAR struct usbmsc_dev_s *priv)
     {
       struct scsicmd_write10_s *write10 = (struct scsicmd_write10_s *)priv->cdb;
    -  FAR struct usbmsc_lun_s *lun = priv->lun;
    +  FAR struct usbmsc_lun_s *lun;
       int ret;
     
       priv->u.xfrlen = usbmsc_getbe16(write10->xfrlen);
    @@ -1066,6 +1078,8 @@ static inline int usbmsc_cmdwrite10(FAR struct usbmsc_dev_s *priv)
                             USBMSC_FLAGS_DIRHOST2DEVICE | USBMSC_FLAGS_BLOCKXFR);
       if (ret == OK)
         {
    +      lun = priv->lun;
    +
           /* Get the Logical Block Address (LBA) from cdb[] as the starting sector */
     
           priv->sector = usbmsc_getbe32(write10->lba);
    @@ -1129,7 +1143,7 @@ static inline int usbmsc_cmdwrite10(FAR struct usbmsc_dev_s *priv)
     static inline int usbmsc_cmdverify10(FAR struct usbmsc_dev_s *priv)
     {
       FAR struct scsicmd_verify10_s *verf = (FAR struct scsicmd_verify10_s *)priv->cdb;
    -  FAR struct usbmsc_lun_s *lun = priv->lun;
    +  FAR struct usbmsc_lun_s *lun;
       uint32_t  lba;
       uint16_t  blocks;
       size_t  sector;
    @@ -1141,6 +1155,8 @@ static inline int usbmsc_cmdverify10(FAR struct usbmsc_dev_s *priv)
       ret = usbmsc_setupcmd(priv, SCSICMD_VERIFY10_SIZEOF, USBMSC_FLAGS_DIRNONE);
       if (ret == OK)
         {
    +      lun = priv->lun;
    +
           /* Verify the starting and ending LBA */
     
           lba    = usbmsc_getbe32(verf->lba);
    @@ -1317,7 +1333,7 @@ static int inline usbmsc_cmdmodesense10(FAR struct usbmsc_dev_s *priv,
     static inline int usbmsc_cmdread12(FAR struct usbmsc_dev_s *priv)
     {
       struct scsicmd_read12_s *read12 = (struct scsicmd_read12_s *)priv->cdb;
    -  FAR struct usbmsc_lun_s *lun = priv->lun;
    +  FAR struct usbmsc_lun_s *lun;
       int ret;
     
       priv->u.xfrlen = usbmsc_getbe32(read12->xfrlen);
    @@ -1325,6 +1341,8 @@ static inline int usbmsc_cmdread12(FAR struct usbmsc_dev_s *priv)
                             USBMSC_FLAGS_DIRDEVICE2HOST | USBMSC_FLAGS_BLOCKXFR);
       if (ret == OK)
         {
    +      lun = priv->lun;
    +
           /* Get the Logical Block Address (LBA) from cdb[] as the starting sector */
     
           priv->sector = usbmsc_getbe32(read12->lba);
    @@ -1379,7 +1397,7 @@ static inline int usbmsc_cmdread12(FAR struct usbmsc_dev_s *priv)
     static inline int usbmsc_cmdwrite12(FAR struct usbmsc_dev_s *priv)
     {
       struct scsicmd_write12_s *write12 = (struct scsicmd_write12_s *)priv->cdb;
    -  FAR struct usbmsc_lun_s *lun = priv->lun;
    +  FAR struct usbmsc_lun_s *lun;
       int ret;
     
       priv->u.xfrlen = usbmsc_getbe32(write12->xfrlen);
    @@ -1387,6 +1405,8 @@ static inline int usbmsc_cmdwrite12(FAR struct usbmsc_dev_s *priv)
                             USBMSC_FLAGS_DIRHOST2DEVICE | USBMSC_FLAGS_BLOCKXFR);
       if (ret == OK)
         {
    +      lun = priv->lun;
    +
           /* Get the Logical Block Address (LBA) from cdb[] as the starting sector */
     
           priv->sector = usbmsc_getbe32(write12->lba);
    -- 
    GitLab
    
    
    From c6376006f635056d1699044cd753e002c98b5b38 Mon Sep 17 00:00:00 2001
    From: Nobutaka Toyoshima 
    Date: Tue, 25 Nov 2014 13:58:20 +0900
    Subject: [PATCH 569/990] sched: Fix CHILD_FLAG_EXITED in include/nuttx/sched.h
    
    Jira: PDFW15IS-196
    Jira: PDFW15IS-1109
    Signed-off-by: Masayuki Ishikawa 
    ---
     include/nuttx/sched.h | 2 +-
     1 file changed, 1 insertion(+), 1 deletion(-)
    
    diff --git a/include/nuttx/sched.h b/include/nuttx/sched.h
    index f8bc539e3d..a6031c3183 100644
    --- a/include/nuttx/sched.h
    +++ b/include/nuttx/sched.h
    @@ -168,7 +168,7 @@
     #  define CHILD_FLAG_TTYPE_TASK    (0 << CHILD_FLAG_TTYPE_SHIFT) /* Normal user task */
     #  define CHILD_FLAG_TTYPE_PTHREAD (1 << CHILD_FLAG_TTYPE_SHIFT) /* User pthread */
     #  define CHILD_FLAG_TTYPE_KERNEL  (2 << CHILD_FLAG_TTYPE_SHIFT) /* Kernel thread */
    -#define CHILD_FLAG_EXITED          (1 << 0) /* Bit 2: The child thread has exit'ed */
    +#define CHILD_FLAG_EXITED          (1 << 2) /* Bit 2: The child thread has exit'ed */
                                                 /* Bits 3-7: Available */
     
     /* Sporadic scheduler flags */
    -- 
    GitLab
    
    
    From 3c1d85af323213093cdca8737f0961b45b3302cc Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Mon, 24 Apr 2017 09:42:51 -0600
    Subject: [PATCH 570/990] Update a README
    
    ---
     net/sixlowpan/README.txt | 22 ++++++++++++----------
     1 file changed, 12 insertions(+), 10 deletions(-)
    
    diff --git a/net/sixlowpan/README.txt b/net/sixlowpan/README.txt
    index a311f5408d..ca8a513d6a 100644
    --- a/net/sixlowpan/README.txt
    +++ b/net/sixlowpan/README.txt
    @@ -10,12 +10,14 @@ Optimal 6loWPAN Configuration
     
        128  112  96   80    64   48   32   16
        ---- ---- ---- ----  ---- ---- ---- ----
    -   xxxx xxxx xxxx xxxx  xxxx 00ff fe00 MMMM 2-byte Rime address IEEE 48-bit MAC
    -   fe80 0000 0000 0000  NNNN NNNN NNNN NNNN 8-byte Rime address IEEE EUI-64
    +   AAAA xxxx xxxx xxxx  xxxx 00ff fe00 MMMM 2-byte Rime address IEEE 48-bit MAC
    +   AAAA 0000 0000 0000  NNNN NNNN NNNN NNNN 8-byte Rime address IEEE EUI-64
     
    -   Where MMM is the 2-byte rime address XOR 0x0200.  For example, the MAC
    +   Where MMM is the 2-byte rime address XORed 0x0200.  For example, the MAC
        address of 0xabcd would be 0xa9cd.  And NNNN NNNN NNNN NNNN is the 8-byte
    -   rime address address XOR 02000 0000 0000 0000
    +   rime address address XOR 02000 0000 0000 0000.
    +
    +   For link-local address, AAAA is 0xfe80
     
     3. MAC based link-local addresses
     
    @@ -33,9 +35,9 @@ Optimal 6loWPAN Configuration
     Fragmentation Headers
     ---------------------
     A fragment header is placed at the beginning of the outgoing packet just
    -after the MAC when the payload is too large to fit in a single IEEE 802.15.4
    -frame. The fragment header contains three fields: Datagram size, datagram tag
    -and datagram offset.
    +after the MAC header when the payload is too large to fit in a single IEEE
    +802.15.4 frame. The fragment header contains three fields: Datagram size,
    +datagram tag and datagram offset.
     
     1. Datagram size describes the total (un-fragmented) payload.
     2. Datagram tag identifies the set of fragments and is used to match
    @@ -65,7 +67,7 @@ this is a HC1 compressed first frame of a packet
     This is the second frame of the same transfer:
     
       41 88 01 cefa 3412 cdab                       ### 9-byte MAC header
    -  e50e 000b 0a                                  ### 5 byte FRAGN header
    +  e50e 000b 0d                                  ### 5 byte FRAGN header
       42                                            ### SIXLOWPAN_DISPATCH_HC1
         fb                                          ### RIME_HC1_HC_UDP_HC1_ENCODING
         e0                                          ### RIME_HC1_HC_UDP_UDP_ENCODING
    @@ -81,5 +83,5 @@ This is the second frame of the same transfer:
     
     The payload length is encoded in the LS 11-bits of the first 16-bit value:
     In this example the payload size is 0x050e or 1,294.  The tag is 0x000b.  In
    -the second frame, the fifth byte contains the offset 0x0a which is 10 << 3 =
    -80 bytes, the size of the payload on the first packet.
    +the second frame, the fifth byte contains the offset 0x0d which is 13 << 3 =
    +104 bytes, the size of the payload on the first packet.
    -- 
    GitLab
    
    
    From 50fb7b0ba082ee4269a38b8eff2cfaa28b48080b Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Mon, 24 Apr 2017 10:23:31 -0600
    Subject: [PATCH 571/990] wireless/ieee80211: Add skeleton for a broadcom
     network driver.
    
    ---
     drivers/wireless/ieee80211/Kconfig       |   26 +
     drivers/wireless/ieee80211/bcmf_netdev.c | 1187 ++++++++++++++++++++++
     2 files changed, 1213 insertions(+)
     create mode 100644 drivers/wireless/ieee80211/bcmf_netdev.c
    
    diff --git a/drivers/wireless/ieee80211/Kconfig b/drivers/wireless/ieee80211/Kconfig
    index a38f67daf8..43a02237c5 100644
    --- a/drivers/wireless/ieee80211/Kconfig
    +++ b/drivers/wireless/ieee80211/Kconfig
    @@ -22,4 +22,30 @@ config IEEE80211_BROADCOM_FULLMAC_SDIO
     		This selection enables support for broadcom
     		FullMAC-compliant devices using SDIO bus.
     
    +choice
    +	prompt "Broadcom 43362 driver work queue"
    +	default IEEE80211_BROADCOM_LPWORK if SCHED_LPWORK
    +	default IEEE80211_BROADCOM_HPWORK if !SCHED_LPWORK && SCHED_HPWORK
    +	depends on SCHED_WORKQUEUE
    +	---help---
    +		Work queue support is required to use the loopback driver.  If the
    +		low priority work queue is available, then it should be used by the
    +		loopback driver.
    +
    +config IEEE80211_BROADCOM_HPWORK
    +	bool "High priority"
    +	depends on SCHED_HPWORK
    +
    +config IEEE80211_BROADCOM_LPWORK
    +	bool "Low priority"
    +	depends on SCHED_LPWORK
    +
    +endchoice # Work queue
    +endif # NETDEV_IEEE80211_BROADCOM_
    +
    +config IEEE80211_BROADCOM_NINTERFACES
    +	int "Nubmer of Broadcom 43362 interfaces"
    +	default 1
    +	depends on EXPERIMENTAL
    +
     endif # DRIVERS_IEEE80211
    diff --git a/drivers/wireless/ieee80211/bcmf_netdev.c b/drivers/wireless/ieee80211/bcmf_netdev.c
    new file mode 100644
    index 0000000000..74ab9da801
    --- /dev/null
    +++ b/drivers/wireless/ieee80211/bcmf_netdev.c
    @@ -0,0 +1,1187 @@
    +/****************************************************************************
    + * drivers/wireless/bcmf_netdev.c
    + *
    + *   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.
    + *
    + ****************************************************************************/
    +
    +/****************************************************************************
    + * Included Files
    + ****************************************************************************/
    +
    +#include 
    +#if defined(CONFIG_NET) && defined(CONFIG_IEEE80211_BROADCOM_FULLMAC)
    +
    +#include 
    +#include 
    +#include 
    +#include 
    +#include 
    +#include 
    +#include 
    +
    +#include 
    +
    +#include 
    +#include 
    +#include 
    +#include 
    +#include 
    +#include 
    +
    +#ifdef CONFIG_NET_PKT
    +#  include 
    +#endif
    +
    +/****************************************************************************
    + * Pre-processor Definitions
    + ****************************************************************************/
    +
    +/* If processing is not done at the interrupt level, then work queue support
    + * is required.
    + */
    +
    +#if !defined(CONFIG_SCHED_WORKQUEUE)
    +#  error Work queue support is required in this configuration (CONFIG_SCHED_WORKQUEUE)
    +#else
    +
    +   /* Use the selected work queue */
    +
    +#  if defined(CONFIG_IEEE80211_BROADCOM_HPWORK)
    +#    define BCMFWORK HPWORK
    +#  elif defined(CONFIG_IEEE80211_BROADCOM_HLWORK)
    +#    define BCMFWORK LPWORK
    +#  else
    +#    error Neither CONFIG_IEEE80211_BROADCOM_HPWORK nor CONFIG_IEEE80211_BROADCOM_HLWORK defined
    +#  endif
    +#endif
    +
    +/* CONFIG_IEEE80211_BROADCOM_NINTERFACES determines the number of physical interfaces
    + * that will be supported.
    + */
    +
    +#ifndef CONFIG_IEEE80211_BROADCOM_NINTERFACES
    +# define CONFIG_IEEE80211_BROADCOM_NINTERFACES 1
    +#endif
    +
    +/* TX poll delay = 1 seconds. CLK_TCK is the number of clock ticks per second */
    +
    +#define BCMF_WDDELAY   (1*CLK_TCK)
    +
    +/* TX timeout = 1 minute */
    +
    +#define BCMF_TXTIMEOUT (60*CLK_TCK)
    +
    +/* This is a helper pointer for accessing the contents of the Ethernet header */
    +
    +#define BUF ((struct eth_hdr_s *)priv->bc_dev.d_buf)
    +
    +/****************************************************************************
    + * Private Types
    + ****************************************************************************/
    +
    +/* The bcmf_driver_s encapsulates all state information for a single hardware
    + * interface
    + */
    +
    +struct bcmf_driver_s
    +{
    +  bool bc_bifup;               /* true:ifup false:ifdown */
    +  WDOG_ID bc_txpoll;           /* TX poll timer */
    +  WDOG_ID bc_txtimeout;        /* TX timeout timer */
    +  struct work_s bc_irqwork;    /* For deferring interupt work to the work queue */
    +  struct work_s bc_pollwork;   /* For deferring poll work to the work queue */
    +
    +  /* This holds the information visible to the NuttX network */
    +
    +  struct net_driver_s bc_dev;  /* Interface understood by the network */
    +};
    +
    +/****************************************************************************
    + * Private Data
    + ****************************************************************************/
    +
    +/* These statically allocated structur would mean that only a single
    + * instance of the device could be supported.  In order to support multiple
    + * devices instances, this data would have to be allocated dynamically.
    + */
    +
    +/* A single packet buffer per device is used here.  There might be multiple
    + * packet buffers in a more complex, pipelined design.
    + *
    + * NOTE that if CONFIG_IEEE80211_BROADCOM_NINTERFACES were greater than 1, you would
    + * need a minimum on one packetbuffer per instance.  Much better to be
    + * allocated dynamically.
    + */
    +
    +static uint8_t g_pktbuf[MAX_NET_DEV_MTU + CONFIG_NET_GUARDSIZE];
    +
    +/* Driver state structure */
    +
    +static struct bcmf_driver_s g_bcmf_interface[CONFIG_IEEE80211_BROADCOM_NINTERFACES];
    +
    +/****************************************************************************
    + * Private Function Prototypes
    + ****************************************************************************/
    +
    +/* Common TX logic */
    +
    +static int  bcmf_transmit(FAR struct bcmf_driver_s *priv);
    +static int  bcmf_txpoll(FAR struct net_driver_s *dev);
    +
    +/* Interrupt handling */
    +
    +static void bcmf_receive(FAR struct bcmf_driver_s *priv);
    +static void bcmf_txdone(FAR struct bcmf_driver_s *priv);
    +
    +static void bcmf_interrupt_work(FAR void *arg);
    +static int  bcmf_interrupt(int irq, FAR void *context, FAR void *arg);
    +
    +/* Watchdog timer expirations */
    +
    +static void bcmf_txtimeout_work(FAR void *arg);
    +static void bcmf_txtimeout_expiry(int argc, wdparm_t arg, ...);
    +
    +static void bcmf_poll_work(FAR void *arg);
    +static void bcmf_poll_expiry(int argc, wdparm_t arg, ...);
    +
    +/* NuttX callback functions */
    +
    +static int  bcmf_ifup(FAR struct net_driver_s *dev);
    +static int  bcmf_ifdown(FAR struct net_driver_s *dev);
    +
    +static void bcmf_txavail_work(FAR void *arg);
    +static int  bcmf_txavail(FAR struct net_driver_s *dev);
    +
    +#if defined(CONFIG_NET_IGMP) || defined(CONFIG_NET_ICMPv6)
    +static int  bcmf_addmac(FAR struct net_driver_s *dev,
    +              FAR const uint8_t *mac);
    +#ifdef CONFIG_NET_IGMP
    +static int  bcmf_rmmac(FAR struct net_driver_s *dev,
    +              FAR const uint8_t *mac);
    +#endif
    +#ifdef CONFIG_NET_ICMPv6
    +static void bcmf_ipv6multicast(FAR struct bcmf_driver_s *priv);
    +#endif
    +#endif
    +#ifdef CONFIG_NETDEV_IOCTL
    +static int  bcmf_ioctl(FAR struct net_driver_s *dev, int cmd,
    +            unsigned long arg);
    +#endif
    +
    +/****************************************************************************
    + * Private Functions
    + ****************************************************************************/
    +
    +/****************************************************************************
    + * Name: bcmf_transmit
    + *
    + * Description:
    + *   Start hardware transmission.  Called either from the txdone interrupt
    + *   handling or from watchdog based polling.
    + *
    + * Parameters:
    + *   priv - Reference to the driver state structure
    + *
    + * Returned Value:
    + *   OK on success; a negated errno on failure
    + *
    + * Assumptions:
    + *   May or may not be called from an interrupt handler.  In either case,
    + *   the network is locked.
    + *
    + ****************************************************************************/
    +
    +static int bcmf_transmit(FAR struct bcmf_driver_s *priv)
    +{
    +  /* Verify that the hardware is ready to send another packet.  If we get
    +   * here, then we are committed to sending a packet; Higher level logic
    +   * must have assured that there is no transmission in progress.
    +   */
    +
    +  /* Increment statistics */
    +
    +  NETDEV_TXPACKETS(priv->bc_dev);
    +
    +  /* Send the packet: address=priv->bc_dev.d_buf, length=priv->bc_dev.d_len */
    +
    +  /* Enable Tx interrupts */
    +
    +  /* Setup the TX timeout watchdog (perhaps restarting the timer) */
    +
    +  (void)wd_start(priv->bc_txtimeout, BCMF_TXTIMEOUT,
    +                 bcmf_txtimeout_expiry, 1, (wdparm_t)priv);
    +  return OK;
    +}
    +
    +/****************************************************************************
    + * Name: bcmf_txpoll
    + *
    + * Description:
    + *   The transmitter is available, check if the network has any outgoing
    + *   packets ready to send.  This is a callback from devif_poll().
    + *   devif_poll() may be called:
    + *
    + *   1. When the preceding TX packet send is complete,
    + *   2. When the preceding TX packet send timesout and the interface is reset
    + *   3. During normal TX polling
    + *
    + * Parameters:
    + *   dev - Reference to the NuttX driver state structure
    + *
    + * Returned Value:
    + *   OK on success; a negated errno on failure
    + *
    + * Assumptions:
    + *   May or may not be called from an interrupt handler.  In either case,
    + *   the network is locked.
    + *
    + ****************************************************************************/
    +
    +static int bcmf_txpoll(FAR struct net_driver_s *dev)
    +{
    +  FAR struct bcmf_driver_s *priv = (FAR struct bcmf_driver_s *)dev->d_private;
    +
    +  /* If the polling resulted in data that should be sent out on the network,
    +   * the field d_len is set to a value > 0.
    +   */
    +
    +  if (priv->bc_dev.d_len > 0)
    +    {
    +      /* Look up the destination MAC address and add it to the Ethernet
    +       * header.
    +       */
    +
    +#ifdef CONFIG_NET_IPv4
    +#ifdef CONFIG_NET_IPv6
    +      if (IFF_IS_IPv4(priv->bc_dev.d_flags))
    +#endif
    +        {
    +          arp_out(&priv->bc_dev);
    +        }
    +#endif /* CONFIG_NET_IPv4 */
    +
    +#ifdef CONFIG_NET_IPv6
    +#ifdef CONFIG_NET_IPv4
    +      else
    +#endif
    +        {
    +          neighbor_out(&priv->bc_dev);
    +        }
    +#endif /* CONFIG_NET_IPv6 */
    +
    +      /* Send the packet */
    +
    +      bcmf_transmit(priv);
    +
    +      /* Check if there is room in the device to hold another packet. If not,
    +       * return a non-zero value to terminate the poll.
    +       */
    +    }
    +
    +  /* If zero is returned, the polling will continue until all connections have
    +   * been examined.
    +   */
    +
    +  return 0;
    +}
    +
    +/****************************************************************************
    + * Name: bcmf_receive
    + *
    + * Description:
    + *   An interrupt was received indicating the availability of a new RX packet
    + *
    + * Parameters:
    + *   priv - Reference to the driver state structure
    + *
    + * Returned Value:
    + *   None
    + *
    + * Assumptions:
    + *   The network is locked.
    + *
    + ****************************************************************************/
    +
    +static void bcmf_receive(FAR struct bcmf_driver_s *priv)
    +{
    +  do
    +    {
    +      /* Check for errors and update statistics */
    +
    +      /* Check if the packet is a valid size for the network buffer
    +       * configuration.
    +       */
    +
    +      /* Copy the data data from the hardware to priv->bc_dev.d_buf.  Set
    +       * amount of data in priv->bc_dev.d_len
    +       */
    +
    +#ifdef CONFIG_NET_PKT
    +      /* When packet sockets are enabled, feed the frame into the packet tap */
    +
    +       pkt_input(&priv->bc_dev);
    +#endif
    +
    +      /* We only accept IP packets of the configured type and ARP packets */
    +
    +#ifdef CONFIG_NET_IPv4
    +      if (BUF->type == HTONS(ETHTYPE_IP))
    +        {
    +          ninfo("IPv4 frame\n");
    +          NETDEV_RXIPV4(&priv->bc_dev);
    +
    +          /* Handle ARP on input then give the IPv4 packet to the network
    +           * layer
    +           */
    +
    +          arp_ipin(&priv->bc_dev);
    +          ipv4_input(&priv->bc_dev);
    +
    +          /* If the above function invocation resulted in data that should be
    +           * sent out on the network, the field  d_len will set to a value > 0.
    +           */
    +
    +          if (priv->bc_dev.d_len > 0)
    +            {
    +              /* Update the Ethernet header with the correct MAC address */
    +
    +#ifdef CONFIG_NET_IPv6
    +              if (IFF_IS_IPv4(priv->bc_dev.d_flags))
    +#endif
    +                {
    +                  arp_out(&priv->bc_dev);
    +                }
    +#ifdef CONFIG_NET_IPv6
    +              else
    +                {
    +                  neighbor_out(&kel->bc_dev);
    +                }
    +#endif
    +
    +              /* And send the packet */
    +
    +              bcmf_transmit(priv);
    +            }
    +        }
    +      else
    +#endif
    +#ifdef CONFIG_NET_IPv6
    +      if (BUF->type == HTONS(ETHTYPE_IP6))
    +        {
    +          ninfo("Iv6 frame\n");
    +          NETDEV_RXIPV6(&priv->bc_dev);
    +
    +          /* Give the IPv6 packet to the network layer */
    +
    +          ipv6_input(&priv->bc_dev);
    +
    +          /* If the above function invocation resulted in data that should be
    +           * sent out on the network, the field  d_len will set to a value > 0.
    +           */
    +
    +          if (priv->bc_dev.d_len > 0)
    +           {
    +              /* Update the Ethernet header with the correct MAC address */
    +
    +#ifdef CONFIG_NET_IPv4
    +              if (IFF_IS_IPv4(priv->bc_dev.d_flags))
    +                {
    +                  arp_out(&priv->bc_dev);
    +                }
    +              else
    +#endif
    +#ifdef CONFIG_NET_IPv6
    +                {
    +                  neighbor_out(&priv->bc_dev);
    +                }
    +#endif
    +
    +              /* And send the packet */
    +
    +              bcmf_transmit(priv);
    +            }
    +        }
    +      else
    +#endif
    +#ifdef CONFIG_NET_ARP
    +      if (BUF->type == htons(ETHTYPE_ARP))
    +        {
    +          arp_arpin(&priv->bc_dev);
    +          NETDEV_RXARP(&priv->bc_dev);
    +
    +          /* If the above function invocation resulted in data that should be
    +           * sent out on the network, the field  d_len will set to a value > 0.
    +           */
    +
    +          if (priv->bc_dev.d_len > 0)
    +            {
    +              bcmf_transmit(priv);
    +            }
    +        }
    +      else
    +#endif
    +        {
    +          NETDEV_RXDROPPED(&priv->bc_dev);
    +        }
    +    }
    +  while (); /* While there are more packets to be processed */
    +}
    +
    +/****************************************************************************
    + * Name: bcmf_txdone
    + *
    + * Description:
    + *   An interrupt was received indicating that the last TX packet(s) is done
    + *
    + * Parameters:
    + *   priv - Reference to the driver state structure
    + *
    + * Returned Value:
    + *   None
    + *
    + * Assumptions:
    + *   The network is locked.
    + *
    + ****************************************************************************/
    +
    +static void bcmf_txdone(FAR struct bcmf_driver_s *priv)
    +{
    +  int delay;
    +
    +  /* Check for errors and update statistics */
    +
    +  NETDEV_TXDONE(priv->bc_dev);
    +
    +  /* Check if there are pending transmissions */
    +
    +  /* If no further transmissions are pending, then cancel the TX timeout and
    +   * disable further Tx interrupts.
    +   */
    +
    +  wd_cancel(priv->bc_txtimeout);
    +
    +  /* And disable further TX interrupts. */
    +
    +  /* In any event, poll the network for new TX data */
    +
    +  (void)devif_poll(&priv->bc_dev, bcmf_txpoll);
    +}
    +
    +/****************************************************************************
    + * Name: bcmf_interrupt_work
    + *
    + * Description:
    + *   Perform interrupt related work from the worker thread
    + *
    + * Parameters:
    + *   arg - The argument passed when work_queue() was called.
    + *
    + * Returned Value:
    + *   OK on success
    + *
    + * Assumptions:
    + *   The network is locked.
    + *
    + ****************************************************************************/
    +
    +static void bcmf_interrupt_work(FAR void *arg)
    +{
    +  FAR struct bcmf_driver_s *priv = (FAR struct bcmf_driver_s *)arg;
    +
    +  /* Lock the network and serialize driver operations if necessary.
    +   * NOTE: Serialization is only required in the case where the driver work
    +   * is performed on an LP worker thread and where more than one LP worker
    +   * thread has been configured.
    +   */
    +
    +  net_lock();
    +
    +  /* Process pending Ethernet interrupts */
    +
    +  /* Get and clear interrupt status bits */
    +
    +  /* Handle interrupts according to status bit settings */
    +
    +  /* Check if we received an incoming packet, if so, call bcmf_receive() */
    +
    +  bcmf_receive(priv);
    +
    +  /* Check if a packet transmission just completed.  If so, call bcmf_txdone.
    +   * This may disable further Tx interrupts if there are no pending
    +   * transmissions.
    +   */
    +
    +  bcmf_txdone(priv);
    +  net_unlock();
    +
    +  /* Re-enable Ethernet interrupts */
    +#warning Missing logic
    +}
    +
    +/****************************************************************************
    + * Name: bcmf_interrupt
    + *
    + * Description:
    + *   Hardware interrupt handler
    + *
    + * Parameters:
    + *   irq     - Number of the IRQ that generated the interrupt
    + *   context - Interrupt register state save info (architecture-specific)
    + *
    + * Returned Value:
    + *   OK on success
    + *
    + * Assumptions:
    + *
    + ****************************************************************************/
    +
    +static int bcmf_interrupt(int irq, FAR void *context, FAR void *arg)
    +{
    +  FAR struct bcmf_driver_s *priv = (FAR struct bcmf_driver_s *)arg;
    +
    +  DEBUGASSERT(priv != NULL);
    +
    +  /* Disable further Ethernet interrupts.  Because Ethernet interrupts are
    +   * also disabled if the TX timeout event occurs, there can be no race
    +   * condition here.
    +   */
    +#warning Missing logic
    +
    +  /* TODO: Determine if a TX transfer just completed */
    +
    +    {
    +      /* If a TX transfer just completed, then cancel the TX timeout so
    +       * there will be no race condition between any subsequent timeout
    +       * expiration and the deferred interrupt processing.
    +       */
    +
    +       wd_cancel(priv->bc_txtimeout);
    +    }
    +
    +  /* Schedule to perform the interrupt processing on the worker thread. */
    +
    +  work_queue(BCMFWORK, &priv->bc_irqwork, bcmf_interrupt_work, priv, 0);
    +  return OK;
    +}
    +
    +/****************************************************************************
    + * Name: bcmf_txtimeout_work
    + *
    + * Description:
    + *   Perform TX timeout related work from the worker thread
    + *
    + * Parameters:
    + *   arg - The argument passed when work_queue() as called.
    + *
    + * Returned Value:
    + *   OK on success
    + *
    + * Assumptions:
    + *   The network is locked.
    + *
    + ****************************************************************************/
    +
    +static void bcmf_txtimeout_work(FAR void *arg)
    +{
    +  FAR struct bcmf_driver_s *priv = (FAR struct bcmf_driver_s *)arg;
    +
    +  /* Lock the network and serialize driver operations if necessary.
    +   * NOTE: Serialization is only required in the case where the driver work
    +   * is performed on an LP worker thread and where more than one LP worker
    +   * thread has been configured.
    +   */
    +
    +  net_lock();
    +
    +  /* Increment statistics and dump debug info */
    +
    +  NETDEV_TXTIMEOUTS(priv->bc_dev);
    +
    +  /* Then reset the hardware */
    +
    +  /* Then poll the network for new XMIT data */
    +
    +  (void)devif_poll(&priv->bc_dev, bcmf_txpoll);
    +  net_unlock();
    +}
    +
    +/****************************************************************************
    + * Name: bcmf_txtimeout_expiry
    + *
    + * Description:
    + *   Our TX watchdog timed out.  Called from the timer interrupt handler.
    + *   The last TX never completed.  Reset the hardware and start again.
    + *
    + * Parameters:
    + *   argc - The number of available arguments
    + *   arg  - The first argument
    + *
    + * Returned Value:
    + *   None
    + *
    + * Assumptions:
    + *   Global interrupts are disabled by the watchdog logic.
    + *
    + ****************************************************************************/
    +
    +static void bcmf_txtimeout_expiry(int argc, wdparm_t arg, ...)
    +{
    +  FAR struct bcmf_driver_s *priv = (FAR struct bcmf_driver_s *)arg;
    +
    +  /* Disable further Ethernet interrupts.  This will prevent some race
    +   * conditions with interrupt work.  There is still a potential race
    +   * condition with interrupt work that is already queued and in progress.
    +   */
    +#warning Missing logic
    +
    +  /* Schedule to perform the TX timeout processing on the worker thread. */
    +
    +  work_queue(BCMFWORK, &priv->bc_irqwork, bcmf_txtimeout_work, priv, 0);
    +}
    +
    +/****************************************************************************
    + * Name: bcmf_poll_process
    + *
    + * Description:
    + *   Perform the periodic poll.  This may be called either from watchdog
    + *   timer logic or from the worker thread, depending upon the configuration.
    + *
    + * Parameters:
    + *   priv - Reference to the driver state structure
    + *
    + * Returned Value:
    + *   None
    + *
    + * Assumptions:
    + *
    + ****************************************************************************/
    +
    +static inline void bcmf_poll_process(FAR struct bcmf_driver_s *priv)
    +{
    +}
    +
    +/****************************************************************************
    + * Name: bcmf_poll_work
    + *
    + * Description:
    + *   Perform periodic polling from the worker thread
    + *
    + * Parameters:
    + *   arg - The argument passed when work_queue() as called.
    + *
    + * Returned Value:
    + *   OK on success
    + *
    + * Assumptions:
    + *   The network is locked.
    + *
    + ****************************************************************************/
    +
    +static void bcmf_poll_work(FAR void *arg)
    +{
    +  FAR struct bcmf_driver_s *priv = (FAR struct bcmf_driver_s *)arg;
    +
    +  /* Lock the network and serialize driver operations if necessary.
    +   * NOTE: Serialization is only required in the case where the driver work
    +   * is performed on an LP worker thread and where more than one LP worker
    +   * thread has been configured.
    +   */
    +
    +  net_lock();
    +
    +  /* Perform the poll */
    +
    +  /* Check if there is room in the send another TX packet.  We cannot perform
    +   * the TX poll if he are unable to accept another packet for transmission.
    +   */
    +
    +  /* If so, update TCP timing states and poll the network for new XMIT data.
    +   * Hmmm.. might be bug here.  Does this mean if there is a transmit in
    +   * progress, we will missing TCP time state updates?
    +   */
    +
    +  (void)devif_timer(&priv->bc_dev, bcmf_txpoll);
    +
    +  /* Setup the watchdog poll timer again */
    +
    +  (void)wd_start(priv->bc_txpoll, BCMF_WDDELAY, bcmf_poll_expiry, 1,
    +                 (wdparm_t)priv);
    +  net_unlock();
    +}
    +
    +/****************************************************************************
    + * Name: bcmf_poll_expiry
    + *
    + * Description:
    + *   Periodic timer handler.  Called from the timer interrupt handler.
    + *
    + * Parameters:
    + *   argc - The number of available arguments
    + *   arg  - The first argument
    + *
    + * Returned Value:
    + *   None
    + *
    + * Assumptions:
    + *   Global interrupts are disabled by the watchdog logic.
    + *
    + ****************************************************************************/
    +
    +static void bcmf_poll_expiry(int argc, wdparm_t arg, ...)
    +{
    +  FAR struct bcmf_driver_s *priv = (FAR struct bcmf_driver_s *)arg;
    +
    +  /* Schedule to perform the interrupt processing on the worker thread. */
    +
    +  work_queue(BCMFWORK, &priv->bc_pollwork, bcmf_poll_work, priv, 0);
    +}
    +
    +/****************************************************************************
    + * Name: bcmf_ifup
    + *
    + * Description:
    + *   NuttX Callback: Bring up the Ethernet interface when an IP address is
    + *   provided
    + *
    + * Parameters:
    + *   dev - Reference to the NuttX driver state structure
    + *
    + * Returned Value:
    + *   None
    + *
    + * Assumptions:
    + *
    + ****************************************************************************/
    +
    +static int bcmf_ifup(FAR struct net_driver_s *dev)
    +{
    +  FAR struct bcmf_driver_s *priv = (FAR struct bcmf_driver_s *)dev->d_private;
    +
    +#ifdef CONFIG_NET_IPv4
    +  ninfo("Bringing up: %d.%d.%d.%d\n",
    +        dev->d_ipaddr & 0xff, (dev->d_ipaddr >> 8) & 0xff,
    +        (dev->d_ipaddr >> 16) & 0xff, dev->d_ipaddr >> 24);
    +#endif
    +#ifdef CONFIG_NET_IPv6
    +  ninfo("Bringing up: %04x:%04x:%04x:%04x:%04x:%04x:%04x:%04x\n",
    +        dev->d_ipv6addr[0], dev->d_ipv6addr[1], dev->d_ipv6addr[2],
    +        dev->d_ipv6addr[3], dev->d_ipv6addr[4], dev->d_ipv6addr[5],
    +        dev->d_ipv6addr[6], dev->d_ipv6addr[7]);
    +#endif
    +
    +  /* Initialize PHYs, the Ethernet interface, and setup up Ethernet interrupts */
    +
    +  /* Instantiate the MAC address from priv->bc_dev.d_mac.ether.ether_addr_octet */
    +
    +#ifdef CONFIG_NET_ICMPv6
    +  /* Set up IPv6 multicast address filtering */
    +
    +  bcmf_ipv6multicast(priv);
    +#endif
    +
    +  /* Set and activate a timer process */
    +
    +  (void)wd_start(priv->bc_txpoll, BCMF_WDDELAY, bcmf_poll_expiry, 1,
    +                 (wdparm_t)priv);
    +
    +  /* Enable the hardware interrupt */
    +
    +  priv->bc_bifup = true;
    +#warning Missing logic
    +  return OK;
    +}
    +
    +/****************************************************************************
    + * Name: bcmf_ifdown
    + *
    + * Description:
    + *   NuttX Callback: Stop the interface.
    + *
    + * Parameters:
    + *   dev - Reference to the NuttX driver state structure
    + *
    + * Returned Value:
    + *   None
    + *
    + * Assumptions:
    + *
    + ****************************************************************************/
    +
    +static int bcmf_ifdown(FAR struct net_driver_s *dev)
    +{
    +  FAR struct bcmf_driver_s *priv = (FAR struct bcmf_driver_s *)dev->d_private;
    +  irqstate_t flags;
    +
    +  /* Disable the hardware interrupt */
    +
    +  flags = enter_critical_section();
    +#warning Missing logic
    +
    +  /* Cancel the TX poll timer and TX timeout timers */
    +
    +  wd_cancel(priv->bc_txpoll);
    +  wd_cancel(priv->bc_txtimeout);
    +
    +  /* Put the EMAC in its reset, non-operational state.  This should be
    +   * a known configuration that will guarantee the bcmf_ifup() always
    +   * successfully brings the interface back up.
    +   */
    +
    +  /* Mark the device "down" */
    +
    +  priv->bc_bifup = false;
    +  leave_critical_section(flags);
    +  return OK;
    +}
    +
    +/****************************************************************************
    + * Name: bcmf_txavail_work
    + *
    + * Description:
    + *   Perform an out-of-cycle poll on the worker thread.
    + *
    + * Parameters:
    + *   arg - Reference to the NuttX driver state structure (cast to void*)
    + *
    + * Returned Value:
    + *   None
    + *
    + * Assumptions:
    + *   Called on the higher priority worker thread.
    + *
    + ****************************************************************************/
    +
    +static void bcmf_txavail_work(FAR void *arg)
    +{
    +  FAR struct bcmf_driver_s *priv = (FAR struct bcmf_driver_s *)arg;
    +
    +  /* Lock the network and serialize driver operations if necessary.
    +   * NOTE: Serialization is only required in the case where the driver work
    +   * is performed on an LP worker thread and where more than one LP worker
    +   * thread has been configured.
    +   */
    +
    +  net_lock();
    +
    +  /* Ignore the notification if the interface is not yet up */
    +
    +  if (priv->bc_bifup)
    +    {
    +      /* Check if there is room in the hardware to hold another outgoing packet. */
    +
    +      /* If so, then poll the network for new XMIT data */
    +
    +      (void)devif_poll(&priv->bc_dev, bcmf_txpoll);
    +    }
    +
    +  net_unlock();
    +}
    +
    +/****************************************************************************
    + * Name: bcmf_txavail
    + *
    + * Description:
    + *   Driver callback invoked when new TX data is available.  This is a
    + *   stimulus perform an out-of-cycle poll and, thereby, reduce the TX
    + *   latency.
    + *
    + * Parameters:
    + *   dev - Reference to the NuttX driver state structure
    + *
    + * Returned Value:
    + *   None
    + *
    + * Assumptions:
    + *   Called in normal user mode
    + *
    + ****************************************************************************/
    +
    +static int bcmf_txavail(FAR struct net_driver_s *dev)
    +{
    +  FAR struct bcmf_driver_s *priv = (FAR struct bcmf_driver_s *)dev->d_private;
    +
    +  /* Is our single work structure available?  It may not be if there are
    +   * pending interrupt actions and we will have to ignore the Tx
    +   * availability action.
    +   */
    +
    +  if (work_available(&priv->bc_pollwork))
    +    {
    +      /* Schedule to serialize the poll on the worker thread. */
    +
    +      work_queue(BCMFWORK, &priv->bc_pollwork, bcmf_txavail_work, priv, 0);
    +    }
    +
    +  return OK;
    +}
    +
    +/****************************************************************************
    + * Name: bcmf_addmac
    + *
    + * Description:
    + *   NuttX Callback: Add the specified MAC address to the hardware multicast
    + *   address filtering
    + *
    + * Parameters:
    + *   dev  - Reference to the NuttX driver state structure
    + *   mac  - The MAC address to be added
    + *
    + * Returned Value:
    + *   None
    + *
    + * Assumptions:
    + *
    + ****************************************************************************/
    +
    +#if defined(CONFIG_NET_IGMP) || defined(CONFIG_NET_ICMPv6)
    +static int bcmf_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac)
    +{
    +  FAR struct bcmf_driver_s *priv = (FAR struct bcmf_driver_s *)dev->d_private;
    +
    +  /* Add the MAC address to the hardware multicast routing table */
    +
    +  return OK;
    +}
    +#endif
    +
    +/****************************************************************************
    + * Name: bcmf_rmmac
    + *
    + * Description:
    + *   NuttX Callback: Remove the specified MAC address from the hardware multicast
    + *   address filtering
    + *
    + * Parameters:
    + *   dev  - Reference to the NuttX driver state structure
    + *   mac  - The MAC address to be removed
    + *
    + * Returned Value:
    + *   None
    + *
    + * Assumptions:
    + *
    + ****************************************************************************/
    +
    +#ifdef CONFIG_NET_IGMP
    +static int bcmf_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac)
    +{
    +  FAR struct bcmf_driver_s *priv = (FAR struct bcmf_driver_s *)dev->d_private;
    +
    +  /* Add the MAC address to the hardware multicast routing table */
    +
    +  return OK;
    +}
    +#endif
    +
    +/****************************************************************************
    + * Name: bcmf_ipv6multicast
    + *
    + * Description:
    + *   Configure the IPv6 multicast MAC address.
    + *
    + * Parameters:
    + *   priv - A reference to the private driver state structure
    + *
    + * Returned Value:
    + *   OK on success; Negated errno on failure.
    + *
    + * Assumptions:
    + *
    + ****************************************************************************/
    +
    +#ifdef CONFIG_NET_ICMPv6
    +static void bcmf_ipv6multicast(FAR struct bcmf_driver_s *priv)
    +{
    +  FAR struct net_driver_s *dev;
    +  uint16_t tmp16;
    +  uint8_t mac[6];
    +
    +  /* For ICMPv6, we need to add the IPv6 multicast address
    +   *
    +   * For IPv6 multicast addresses, the Ethernet MAC is derived by
    +   * the four low-order octets OR'ed with the MAC 33:33:00:00:00:00,
    +   * so for example the IPv6 address FF02:DEAD:BEEF::1:3 would map
    +   * to the Ethernet MAC address 33:33:00:01:00:03.
    +   *
    +   * NOTES:  This appears correct for the ICMPv6 Router Solicitation
    +   * Message, but the ICMPv6 Neighbor Solicitation message seems to
    +   * use 33:33:ff:01:00:03.
    +   */
    +
    +  mac[0] = 0x33;
    +  mac[1] = 0x33;
    +
    +  dev    = &priv->dev;
    +  tmp16  = dev->d_ipv6addr[6];
    +  mac[2] = 0xff;
    +  mac[3] = tmp16 >> 8;
    +
    +  tmp16  = dev->d_ipv6addr[7];
    +  mac[4] = tmp16 & 0xff;
    +  mac[5] = tmp16 >> 8;
    +
    +  ninfo("IPv6 Multicast: %02x:%02x:%02x:%02x:%02x:%02x\n",
    +        mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]);
    +
    +  (void)bcmf_addmac(dev, mac);
    +
    +#ifdef CONFIG_NET_ICMPv6_AUTOCONF
    +  /* Add the IPv6 all link-local nodes Ethernet address.  This is the
    +   * address that we expect to receive ICMPv6 Router Advertisement
    +   * packets.
    +   */
    +
    +  (void)bcmf_addmac(dev, g_ipv6_ethallnodes.ether_addr_octet);
    +
    +#endif /* CONFIG_NET_ICMPv6_AUTOCONF */
    +
    +#ifdef CONFIG_NET_ICMPv6_ROUTER
    +  /* Add the IPv6 all link-local routers Ethernet address.  This is the
    +   * address that we expect to receive ICMPv6 Router Solicitation
    +   * packets.
    +   */
    +
    +  (void)bcmf_addmac(dev, g_ipv6_ethallrouters.ether_addr_octet);
    +
    +#endif /* CONFIG_NET_ICMPv6_ROUTER */
    +}
    +#endif /* CONFIG_NET_ICMPv6 */
    +
    +/****************************************************************************
    + * Name: bcmf_ioctl
    + *
    + * Description:
    + *   Handle network IOCTL commands directed to this device.
    + *
    + * Parameters:
    + *   dev - Reference to the NuttX driver state structure
    + *   cmd - The IOCTL command
    + *   arg - The argument for the IOCTL command
    + *
    + * Returned Value:
    + *   OK on success; Negated errno on failure.
    + *
    + * Assumptions:
    + *
    + ****************************************************************************/
    +
    +#ifdef CONFIG_NETDEV_IOCTL
    +static int bcmf_ioctl(FAR struct net_driver_s *dev, int cmd,
    +                      unsigned long arg)
    +{
    +  FAR struct bcmf_driver_s *priv = (FAR struct bcmf_driver_s *)dev->d_private;
    +  int ret;
    +
    +  /* Decode and dispatch the driver-specific IOCTL command */
    +
    +  switch (cmd)
    +    {
    +      /* Add cases here to support the IOCTL commands */
    +
    +      default:
    +        nerr("ERROR: Unrecognized IOCTL command: %d\n", command);
    +        return -ENOTTY;  /* Special return value for this case */
    +    }
    +
    +  return OK;
    +}
    +#endif
    +
    +/****************************************************************************
    + * Public Functions
    + ****************************************************************************/
    +
    +/****************************************************************************
    + * Name: bcmf_initialize
    + *
    + * Description:
    + *   Initialize the Broadcom 43362 controller and driver
    + *
    + * Parameters:
    + *   intf - In the case where there are multiple EMACs, this value
    + *          identifies which EMAC is to be initialized.
    + *
    + * Returned Value:
    + *   OK on success; Negated errno on failure.
    + *
    + * Assumptions:
    + *
    + ****************************************************************************/
    +
    +int bcmf_initialize(int intf)
    +{
    +  FAR struct bcmf_driver_s *priv;
    +
    +  /* Get the interface structure associated with this interface number. */
    +
    +  DEBUGASSERT(intf < CONFIG_IEEE80211_BROADCOM_NINTERFACES);
    +  priv = &g_bcmf_interface[intf];
    +
    +  /* Attach the IRQ to the driver */
    +#warning Missing logic
    +
    +  /* Initialize the driver structure */
    +
    +  memset(priv, 0, sizeof(struct bcmf_driver_s));
    +  priv->bc_dev.d_buf     = g_pktbuf;      /* Single packet buffer */
    +  priv->bc_dev.d_ifup    = bcmf_ifup;     /* I/F up (new IP address) callback */
    +  priv->bc_dev.d_ifdown  = bcmf_ifdown;   /* I/F down callback */
    +  priv->bc_dev.d_txavail = bcmf_txavail;  /* New TX data callback */
    +#ifdef CONFIG_NET_IGMP
    +  priv->bc_dev.d_addmac  = bcmf_addmac;   /* Add multicast MAC address */
    +  priv->bc_dev.d_rmmac   = bcmf_rmmac;    /* Remove multicast MAC address */
    +#endif
    +#ifdef CONFIG_NETDEV_IOCTL
    +  priv->bc_dev.d_ioctl   = bcmf_ioctl;    /* Handle network IOCTL commands */
    +#endif
    +  priv->bc_dev.d_private = (FAR void *)g_bcmf_interface; /* Used to recover private state from dev */
    +
    +  /* Create a watchdog for timing polling for and timing of transmisstions */
    +
    +  priv->bc_txpoll        = wd_create();   /* Create periodic poll timer */
    +  priv->bc_txtimeout     = wd_create();   /* Create TX timeout timer */
    +
    +  DEBUGASSERT(priv->bc_txpoll != NULL && priv->bc_txtimeout != NULL);
    +
    +  /* Put the interface in the down state.  This usually amounts to resetting
    +   * the device and/or calling bcmf_ifdown().
    +   */
    +
    +  /* Read the MAC address from the hardware into priv->bc_dev.d_mac.ether.ether_addr_octet */
    +
    +  /* Register the device with the OS so that socket IOCTLs can be performed */
    +
    +  (void)netdev_register(&priv->bc_dev, NET_LL_ETHERNET);
    +  return OK;
    +}
    +
    +#endif /* CONFIG_NET && CONFIG_IEEE80211_BROADCOM_FULLMAC */
    -- 
    GitLab
    
    
    From e507a3f295cbfdb0c92bb3e1c6fd1163abf16889 Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Mon, 24 Apr 2017 10:28:06 -0600
    Subject: [PATCH 572/990] wiress/ieee80211: Broadcom network driver needs to
     register as an ieee802.11 driver, not an Ethernet driver.
    
    ---
     drivers/wireless/ieee80211/bcmf_netdev.c | 2 +-
     1 file changed, 1 insertion(+), 1 deletion(-)
    
    diff --git a/drivers/wireless/ieee80211/bcmf_netdev.c b/drivers/wireless/ieee80211/bcmf_netdev.c
    index 74ab9da801..2715c4f57b 100644
    --- a/drivers/wireless/ieee80211/bcmf_netdev.c
    +++ b/drivers/wireless/ieee80211/bcmf_netdev.c
    @@ -1180,7 +1180,7 @@ int bcmf_initialize(int intf)
     
       /* Register the device with the OS so that socket IOCTLs can be performed */
     
    -  (void)netdev_register(&priv->bc_dev, NET_LL_ETHERNET);
    +  (void)netdev_register(&priv->bc_dev, NET_LL_IEEE80211);
       return OK;
     }
     
    -- 
    GitLab
    
    
    From a57c79e8b38f1c5b596c229fd0e995e0d54dac03 Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Mon, 24 Apr 2017 10:43:57 -0600
    Subject: [PATCH 573/990] wireless/ieee80211: Add broadcom network device
     registration logic.
    
    ---
     configs/photon/src/stm32_wlan.c               | 11 +++
     drivers/wireless/ieee80211/bcmf_netdev.c      |  4 +-
     .../nuttx/wireless/ieee80211/bcmf_netdev.h    | 85 +++++++++++++++++++
     3 files changed, 98 insertions(+), 2 deletions(-)
     create mode 100644 include/nuttx/wireless/ieee80211/bcmf_netdev.h
    
    diff --git a/configs/photon/src/stm32_wlan.c b/configs/photon/src/stm32_wlan.c
    index 9e886807e0..2892e7af2a 100644
    --- a/configs/photon/src/stm32_wlan.c
    +++ b/configs/photon/src/stm32_wlan.c
    @@ -150,5 +150,16 @@ int photon_wlan_initialize()
           return ERROR;
         }
     
    +#if 0 /* Not yet */
    +  /* Register the nework device */
    +
    +  ret = bcmf_netdev_register(0);
    +  if (ret != OK)
    +    {
    +      syslog(LOG_ERR, "Failed to register bcmf network device: %d\n", ret);
    +      return ret;
    +    }
    +#endif
    +
       return OK;
     }
    diff --git a/drivers/wireless/ieee80211/bcmf_netdev.c b/drivers/wireless/ieee80211/bcmf_netdev.c
    index 2715c4f57b..96ffed609f 100644
    --- a/drivers/wireless/ieee80211/bcmf_netdev.c
    +++ b/drivers/wireless/ieee80211/bcmf_netdev.c
    @@ -1121,7 +1121,7 @@ static int bcmf_ioctl(FAR struct net_driver_s *dev, int cmd,
      ****************************************************************************/
     
     /****************************************************************************
    - * Name: bcmf_initialize
    + * Name: bcmf_netdev_register
      *
      * Description:
      *   Initialize the Broadcom 43362 controller and driver
    @@ -1137,7 +1137,7 @@ static int bcmf_ioctl(FAR struct net_driver_s *dev, int cmd,
      *
      ****************************************************************************/
     
    -int bcmf_initialize(int intf)
    +int bcmf_netdev_register(int intf)
     {
       FAR struct bcmf_driver_s *priv;
     
    diff --git a/include/nuttx/wireless/ieee80211/bcmf_netdev.h b/include/nuttx/wireless/ieee80211/bcmf_netdev.h
    new file mode 100644
    index 0000000000..10e8157f1f
    --- /dev/null
    +++ b/include/nuttx/wireless/ieee80211/bcmf_netdev.h
    @@ -0,0 +1,85 @@
    +/****************************************************************************
    + * include/nuttx/wireless/ieee80211/bcmf_netdev.h
    + *
    + *   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.
    + *
    + ****************************************************************************/
    +
    +#ifndef __INCLUDE_NUTTX_WIRELESS_IEEE80211_BCMF_NETDEV_H
    +#define __INCLUDE_NUTTX_WIRELESS_IEEE80211_BCMF_NETDEV_H
    +
    +/****************************************************************************
    + * Included Files
    + ****************************************************************************/
    +
    +#include 
    +
    +#ifdef __cplusplus
    +#define EXTERN extern "C"
    +extern "C"
    +{
    +#else
    +#define EXTERN extern
    +#endif
    +
    +/****************************************************************************
    + * Public Types
    + ****************************************************************************/
    +
    +/****************************************************************************
    + * Public Function Prototypes
    + ****************************************************************************/
    +
    +/****************************************************************************
    + * Name: bcmf_netdev_register
    + *
    + * Description:
    + *   Initialize the Broadcom 43362 controller and driver
    + *
    + * Parameters:
    + *   intf - In the case where there are multiple EMACs, this value
    + *          identifies which EMAC is to be initialized.
    + *
    + * Returned Value:
    + *   OK on success; Negated errno on failure.
    + *
    + * Assumptions:
    + *
    + ****************************************************************************/
    +
    +int bcmf_netdev_register(int intf);
    +
    +#undef EXTERN
    +#ifdef __cplusplus
    +}
    +#endif
    +
    +#endif /* __INCLUDE_NUTTX_WIRELESS_IEEE80211_BCMF_NETDEV_H */
    -- 
    GitLab
    
    
    From 3bf5044306713cf75e62df0c427c8c682d4b8aff Mon Sep 17 00:00:00 2001
    From: Simon Piriou 
    Date: Mon, 24 Apr 2017 20:01:41 +0200
    Subject: [PATCH 574/990] stm32: cleanup stm32_sdio.c
    
    ---
     arch/arm/src/stm32/stm32_sdio.c | 7 +------
     1 file changed, 1 insertion(+), 6 deletions(-)
    
    diff --git a/arch/arm/src/stm32/stm32_sdio.c b/arch/arm/src/stm32/stm32_sdio.c
    index 3f67c8b900..66a8d10773 100644
    --- a/arch/arm/src/stm32/stm32_sdio.c
    +++ b/arch/arm/src/stm32/stm32_sdio.c
    @@ -1027,9 +1027,6 @@ static void stm32_dataconfig(uint32_t timeout, uint32_t dlen, uint32_t dctrl)
       dctrl  &=  (SDIO_DCTRL_DTDIR | SDIO_DCTRL_DTMODE | SDIO_DCTRL_DBLOCKSIZE_MASK);
       regval |=  (dctrl | SDIO_DCTRL_DTEN | SDIO_DCTRL_SDIOEN);
       putreg32(regval, STM32_SDIO_DCTRL);
    -
    -  struct stm32_dev_s *priv = &g_sdiodev;
    -  // mcinfo("data cfg: %08x %08x %08x (bs=%d)\n", timeout, dlen, regval, 1<block_size);
     }
     
     /****************************************************************************
    @@ -1869,7 +1866,7 @@ static int stm32_sendcmd(FAR struct sdio_dev_s *dev, uint32_t cmd, uint32_t arg)
       cmdidx  = (cmd & MMCSD_CMDIDX_MASK) >> MMCSD_CMDIDX_SHIFT;
       regval |= cmdidx | SDIO_CMD_CPSMEN;
     
    -  // mcinfo("cmd: %08x arg: %08x regval: %08x\n", cmd, arg, regval);
    +  mcinfo("cmd: %08x arg: %08x regval: %08x\n", cmd, arg, regval);
     
       /* Write the SDIO CMD */
     
    @@ -2261,7 +2258,6 @@ static int stm32_recvshortcrc(FAR struct sdio_dev_s *dev, uint32_t cmd, uint32_t
     
       putreg32(SDIO_RESPDONE_ICR | SDIO_CMDDONE_ICR, STM32_SDIO_ICR);
       *rshort = getreg32(STM32_SDIO_RESP1);
    -  // mcinfo("data: %08x %08x\n", *rshort, respcmd);
       return ret;
     }
     
    @@ -2362,7 +2358,6 @@ static int stm32_recvshort(FAR struct sdio_dev_s *dev, uint32_t cmd, uint32_t *r
       if (rshort)
         {
           *rshort = getreg32(STM32_SDIO_RESP1);
    -      // mcinfo("data: %08x\n", *rshort);
         }
     
       return ret;
    -- 
    GitLab
    
    
    From d72f36948e2658f7b76f0e7c1bf717590ae65378 Mon Sep 17 00:00:00 2001
    From: Simon Piriou 
    Date: Mon, 24 Apr 2017 20:02:20 +0200
    Subject: [PATCH 575/990] bcmf: fix Kconfig file
    
    ---
     drivers/wireless/ieee80211/Kconfig | 9 ++++++---
     1 file changed, 6 insertions(+), 3 deletions(-)
    
    diff --git a/drivers/wireless/ieee80211/Kconfig b/drivers/wireless/ieee80211/Kconfig
    index 43a02237c5..853b870b9c 100644
    --- a/drivers/wireless/ieee80211/Kconfig
    +++ b/drivers/wireless/ieee80211/Kconfig
    @@ -22,8 +22,10 @@ config IEEE80211_BROADCOM_FULLMAC_SDIO
     		This selection enables support for broadcom
     		FullMAC-compliant devices using SDIO bus.
     
    +if IEEE80211_BROADCOM_FULLMAC
    +
     choice
    -	prompt "Broadcom 43362 driver work queue"
    +	prompt "Broadcom FullMAC driver work queue"
     	default IEEE80211_BROADCOM_LPWORK if SCHED_LPWORK
     	default IEEE80211_BROADCOM_HPWORK if !SCHED_LPWORK && SCHED_HPWORK
     	depends on SCHED_WORKQUEUE
    @@ -41,11 +43,12 @@ config IEEE80211_BROADCOM_LPWORK
     	depends on SCHED_LPWORK
     
     endchoice # Work queue
    -endif # NETDEV_IEEE80211_BROADCOM_
     
     config IEEE80211_BROADCOM_NINTERFACES
    -	int "Nubmer of Broadcom 43362 interfaces"
    +	int "Number of Broadcom FullMAC interfaces"
     	default 1
     	depends on EXPERIMENTAL
     
    +endif # IEEE80211_BROADCOM_FULLMAC
    +
     endif # DRIVERS_IEEE80211
    -- 
    GitLab
    
    
    From a23ac029591fb40ef5e78d895801a9bc91a04fc7 Mon Sep 17 00:00:00 2001
    From: Simon Piriou 
    Date: Mon, 24 Apr 2017 20:04:47 +0200
    Subject: [PATCH 576/990] bcmf: register network driver + update defconfig file
    
    ---
     config_wlan                                  | 160 +++++++++++++++++--
     drivers/wireless/ieee80211/Make.defs         |   1 +
     drivers/wireless/ieee80211/bcmf_chip_43362.c |   4 +-
     drivers/wireless/ieee80211/bcmf_driver.c     | 136 +++++++---------
     drivers/wireless/ieee80211/bcmf_driver.h     |  36 +++--
     drivers/wireless/ieee80211/bcmf_ioctl.h      |   2 +-
     drivers/wireless/ieee80211/bcmf_netdev.c     | 123 +++++++-------
     7 files changed, 297 insertions(+), 165 deletions(-)
    
    diff --git a/config_wlan b/config_wlan
    index 0e606cb11f..51e7d92989 100644
    --- a/config_wlan
    +++ b/config_wlan
    @@ -65,7 +65,11 @@ CONFIG_DEBUG_INFO=y
     # CONFIG_DEBUG_GRAPHICS is not set
     # CONFIG_DEBUG_LIB is not set
     # CONFIG_DEBUG_MM is not set
    -# CONFIG_DEBUG_WIRELESS is not set
    +# CONFIG_DEBUG_NET is not set
    +CONFIG_DEBUG_WIRELESS=y
    +CONFIG_DEBUG_WIRELESS_ERROR=y
    +CONFIG_DEBUG_WIRELESS_WARN=y
    +CONFIG_DEBUG_WIRELESS_INFO=y
     # CONFIG_DEBUG_SCHED is not set
     
     #
    @@ -78,10 +82,7 @@ CONFIG_DEBUG_INFO=y
     #
     # CONFIG_DEBUG_LEDS is not set
     # CONFIG_DEBUG_GPIO is not set
    -CONFIG_DEBUG_MEMCARD=y
    -CONFIG_DEBUG_MEMCARD_ERROR=y
    -CONFIG_DEBUG_MEMCARD_WARN=y
    -CONFIG_DEBUG_MEMCARD_INFO=y
    +# CONFIG_DEBUG_MEMCARD is not set
     # CONFIG_DEBUG_TIMER is not set
     # CONFIG_DEBUG_WATCHDOG is not set
     CONFIG_ARCH_HAVE_STACKCHECK=y
    @@ -859,6 +860,26 @@ CONFIG_SDIO_BLOCKSETUP=y
     # CONFIG_MODEM is not set
     # CONFIG_MTD is not set
     # CONFIG_EEPROM is not set
    +CONFIG_NETDEVICES=y
    +
    +#
    +# General Ethernet MAC Driver Options
    +#
    +# CONFIG_NETDEV_LOOPBACK is not set
    +# CONFIG_NETDEV_MULTINIC is not set
    +# CONFIG_ARCH_HAVE_NETDEV_STATISTICS is not set
    +CONFIG_NETDEV_LATEINIT=y
    +# CONFIG_NET_DUMPPACKET is not set
    +
    +#
    +# External Ethernet MAC Device Support
    +#
    +# CONFIG_NET_DM90x0 is not set
    +# CONFIG_NET_CS89x0 is not set
    +# CONFIG_ENC28J60 is not set
    +# CONFIG_ENCX24J600 is not set
    +# CONFIG_NET_SLIP is not set
    +# CONFIG_NET_FTMAC100 is not set
     # CONFIG_PIPES is not set
     # CONFIG_PM is not set
     # CONFIG_POWER is not set
    @@ -926,6 +947,8 @@ CONFIG_DRIVERS_IEEE80211=y
     CONFIG_IEEE80211_BROADCOM_FULLMAC=y
     CONFIG_IEEE80211_BROADCOM_BCM43362=y
     CONFIG_IEEE80211_BROADCOM_FULLMAC_SDIO=y
    +CONFIG_IEEE80211_BROADCOM_HPWORK=y
    +CONFIG_IEEE80211_BROADCOM_NINTERFACES=1
     # CONFIG_WL_NRF24L01 is not set
     # CONFIG_DRIVERS_CONTACTLESS is not set
     
    @@ -946,9 +969,100 @@ CONFIG_SYSLOG_CONSOLE=y
     #
     # Networking Support
     #
    -# CONFIG_ARCH_HAVE_NET is not set
    +CONFIG_ARCH_HAVE_NET=y
     # CONFIG_ARCH_HAVE_PHY is not set
    -# CONFIG_NET is not set
    +CONFIG_NET=y
    +# CONFIG_NET_PROMISCUOUS is not set
    +
    +#
    +# Driver buffer configuration
    +#
    +CONFIG_NET_ETH_MTU=590
    +CONFIG_NET_GUARDSIZE=2
    +
    +#
    +# Data link support
    +#
    +# CONFIG_NET_MULTILINK is not set
    +# CONFIG_NET_USER_DEVFMT is not set
    +CONFIG_NET_ETHERNET=y
    +# CONFIG_NET_LOOPBACK is not set
    +# CONFIG_NET_TUN is not set
    +# CONFIG_NET_USRSOCK is not set
    +
    +#
    +# Network Device Operations
    +#
    +# CONFIG_NETDEV_IOCTL is not set
    +# CONFIG_NETDEV_PHY_IOCTL is not set
    +# CONFIG_NETDEV_WIRELESS_IOCTL is not set
    +
    +#
    +# Internet Protocol Selection
    +#
    +CONFIG_NET_IPv4=y
    +# CONFIG_NET_IPv6 is not set
    +
    +#
    +# Socket Support
    +#
    +CONFIG_NSOCKET_DESCRIPTORS=8
    +CONFIG_NET_NACTIVESOCKETS=16
    +# CONFIG_NET_SOCKOPTS is not set
    +
    +#
    +# Raw Socket Support
    +#
    +# CONFIG_NET_PKT is not set
    +
    +#
    +# Unix Domain Socket Support
    +#
    +# CONFIG_NET_LOCAL is not set
    +
    +#
    +# TCP/IP Networking
    +#
    +# CONFIG_NET_TCP is not set
    +# CONFIG_NET_TCP_NO_STACK is not set
    +
    +#
    +# UDP Networking
    +#
    +# CONFIG_NET_UDP is not set
    +# CONFIG_NET_UDP_NO_STACK is not set
    +
    +#
    +# ICMP Networking Support
    +#
    +# CONFIG_NET_ICMP is not set
    +
    +#
    +# IGMPv2 Client Support
    +#
    +# CONFIG_NET_IGMP is not set
    +
    +#
    +# ARP Configuration
    +#
    +CONFIG_NET_ARP=y
    +CONFIG_NET_ARPTAB_SIZE=16
    +CONFIG_NET_ARP_MAXAGE=120
    +# CONFIG_NET_ARP_IPIN is not set
    +# CONFIG_NET_ARP_SEND is not set
    +
    +#
    +# User-space networking stack API
    +#
    +# CONFIG_NET_ARCH_INCR32 is not set
    +# CONFIG_NET_ARCH_CHKSUM is not set
    +# CONFIG_NET_STATISTICS is not set
    +
    +#
    +# Routing Table Configuration
    +#
    +# CONFIG_NET_ROUTE is not set
    +CONFIG_NET_HOSTNAME=""
     
     #
     # Crypto API
    @@ -986,6 +1100,7 @@ CONFIG_FS_PROCFS=y
     # CONFIG_FS_PROCFS_EXCLUDE_PROCESS is not set
     # CONFIG_FS_PROCFS_EXCLUDE_UPTIME is not set
     # CONFIG_FS_PROCFS_EXCLUDE_MOUNTS is not set
    +# CONFIG_FS_PROCFS_EXCLUDE_NET is not set
     # CONFIG_FS_UNIONFS is not set
     
     #
    @@ -1109,9 +1224,8 @@ CONFIG_ARCH_HAVE_TLS=y
     #
     # Network-Related Options
     #
    -# CONFIG_LIBC_IPv4_ADDRCONV is not set
     # CONFIG_LIBC_IPv6_ADDRCONV is not set
    -# CONFIG_LIBC_NETDB is not set
    +CONFIG_LIBC_NETDB=y
     
     #
     # NETDB Support
    @@ -1259,6 +1373,7 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_NETUTILS_ESP8266 is not set
     # CONFIG_NETUTILS_FTPC is not set
     # CONFIG_NETUTILS_JSON is not set
    +CONFIG_NETUTILS_NETLIB=y
     # CONFIG_NETUTILS_SMTP is not set
     
     #
    @@ -1285,6 +1400,7 @@ CONFIG_NSH_BUILTIN_APPS=y
     # Disable Individual commands
     #
     # CONFIG_NSH_DISABLE_ADDROUTE is not set
    +# CONFIG_NSH_DISABLE_ARP is not set
     # CONFIG_NSH_DISABLE_BASENAME is not set
     # CONFIG_NSH_DISABLE_CAT is not set
     # CONFIG_NSH_DISABLE_CD is not set
    @@ -1358,6 +1474,26 @@ CONFIG_NSH_FILEIOSIZE=512
     CONFIG_NSH_CONSOLE=y
     # CONFIG_NSH_ALTCONDEV is not set
     CONFIG_NSH_ARCHINIT=y
    +
    +#
    +# Networking Configuration
    +#
    +CONFIG_NSH_NETINIT=y
    +# CONFIG_NSH_NETINIT_THREAD is not set
    +# CONFIG_NSH_NETINIT_DEBUG is not set
    +
    +#
    +# IP Address Configuration
    +#
    +
    +#
    +# IPv4 Addresses
    +#
    +CONFIG_NSH_IPADDR=0x0a000002
    +CONFIG_NSH_DRIPADDR=0x0a000001
    +CONFIG_NSH_NETMASK=0xffffff00
    +# CONFIG_NSH_NOMAC is not set
    +CONFIG_NSH_MAX_ROUNDTRIP=20
     # CONFIG_NSH_LOGIN is not set
     # CONFIG_NSH_CONSOLE_LOGIN is not set
     
    @@ -1375,6 +1511,7 @@ CONFIG_NSH_ARCHINIT=y
     # CONFIG_SYSTEM_HEX2BIN is not set
     # CONFIG_SYSTEM_HEXED is not set
     # CONFIG_SYSTEM_INSTALL is not set
    +# CONFIG_SYSTEM_NETDB is not set
     # CONFIG_SYSTEM_RAMTEST is not set
     CONFIG_READLINE_HAVE_EXTMATCH=y
     CONFIG_SYSTEM_READLINE=y
    @@ -1387,3 +1524,8 @@ CONFIG_READLINE_ECHO=y
     # CONFIG_SYSTEM_UBLOXMODEM is not set
     # CONFIG_SYSTEM_VI is not set
     # CONFIG_SYSTEM_ZMODEM is not set
    +
    +#
    +# Wireless Libraries and NSH Add-Ons
    +#
    +# CONFIG_WIRELESS_WAPI is not set
    diff --git a/drivers/wireless/ieee80211/Make.defs b/drivers/wireless/ieee80211/Make.defs
    index eebfb9f821..0586e423da 100644
    --- a/drivers/wireless/ieee80211/Make.defs
    +++ b/drivers/wireless/ieee80211/Make.defs
    @@ -44,6 +44,7 @@ ifeq ($(CONFIG_IEEE80211_BROADCOM_FULLMAC),y)
       CSRCS += bcmf_driver.c
       CSRCS += bcmf_cdc.c
       CSRCS += bcmf_utils.c
    +  CSRCS += bcmf_netdev.c
     
     ifeq ($(CONFIG_IEEE80211_BROADCOM_FULLMAC_SDIO),y)  
       CSRCS += mmc_sdio.c
    diff --git a/drivers/wireless/ieee80211/bcmf_chip_43362.c b/drivers/wireless/ieee80211/bcmf_chip_43362.c
    index f53fb06b8e..5637173c95 100644
    --- a/drivers/wireless/ieee80211/bcmf_chip_43362.c
    +++ b/drivers/wireless/ieee80211/bcmf_chip_43362.c
    @@ -65,9 +65,9 @@ const struct bcmf_sdio_chip bcmf_43362_config_sdio = {
     
       // TODO find something smarter than using image_len references
     
    -  .firmware_image      = bcm43362_firmware_image,
    +  .firmware_image      = (uint8_t*)bcm43362_firmware_image,
       .firmware_image_size = (unsigned int*)&bcm43362_firmware_image_len,
     
    -  .nvram_image         = bcm43362_nvram_image,
    +  .nvram_image         = (uint8_t*)bcm43362_nvram_image,
       .nvram_image_size    = (unsigned int*)&bcm43362_nvram_image_len
     };
    \ No newline at end of file
    diff --git a/drivers/wireless/ieee80211/bcmf_driver.c b/drivers/wireless/ieee80211/bcmf_driver.c
    index 828de645f0..5294e5a781 100644
    --- a/drivers/wireless/ieee80211/bcmf_driver.c
    +++ b/drivers/wireless/ieee80211/bcmf_driver.c
    @@ -45,6 +45,8 @@
     #include 
     #include 
     
    +#include 
    +
     #include 
     
     #include "bcmf_driver.h"
    @@ -64,11 +66,6 @@
     #define WL_SCAN_UNASSOC_TIME   40
     #define WL_SCAN_PASSIVE_TIME   120
     
    -/* Chip interfaces */
    -#define CHIP_STA_INTERFACE   0
    -#define CHIP_AP_INTERFACE    1
    -#define CHIP_P2P_INTERFACE   2
    -
     /****************************************************************************
      * Private Types
      ****************************************************************************/
    @@ -80,6 +77,11 @@
     static FAR struct bcmf_dev_s* bcmf_allocate_device(void);
     static void bcmf_free_device(FAR struct bcmf_dev_s *priv);
     
    +static int bcmf_driver_initialize(FAR struct bcmf_dev_s *priv);
    +
    +// FIXME add bcmf_netdev.h file
    +int bcmf_netdev_register(FAR struct bcmf_dev_s *priv);
    +
     #if 0
     static int bcmf_run_escan(FAR struct bcmf_dev_s *priv);
     #endif
    @@ -154,30 +156,11 @@ int bcmf_wl_set_mac_address(FAR struct bcmf_dev_s *priv, uint8_t *addr)
       wlinfo("MAC address updated %02X:%02X:%02X:%02X:%02X:%02X\n",
                                 addr[0], addr[1], addr[2],
                                 addr[3], addr[4], addr[5]);
    -  memcpy(priv->mac_addr, addr, 6);
    +  memcpy(priv->bc_dev.d_mac.ether.ether_addr_octet, addr, ETHER_ADDR_LEN);
         
       return OK;
     }
     
    -int bcmf_wl_enable(FAR struct bcmf_dev_s *priv, bool enable)
    -{
    -  int ret;
    -  uint32_t out_len;
    -
    -  /* TODO chek device state */
    -
    -  out_len = 0;
    -  ret = bcmf_cdc_ioctl(priv, CHIP_STA_INTERFACE, true,
    -                         enable ? WLC_UP : WLC_DOWN, NULL, &out_len);
    -  
    -  if (ret == OK)
    -    {
    -      /* TODO update device state */
    -    }
    -
    -  return ret;
    -}
    -
     int bcmf_dongle_scantime(FAR struct bcmf_dev_s *priv, int32_t scan_assoc_time,
               int32_t scan_unassoc_time, int32_t scan_passive_time)
     {
    @@ -220,8 +203,6 @@ int bcmf_dongle_scantime(FAR struct bcmf_dev_s *priv, int32_t scan_assoc_time,
     int bcmf_dongle_initialize(FAR struct bcmf_dev_s *priv)
     {
       int ret;
    -  uint32_t out_len;
    -  uint32_t value;
     
       ret = bcmf_wl_enable(priv, true);
       if (ret)
    @@ -236,36 +217,6 @@ int bcmf_dongle_initialize(FAR struct bcmf_dev_s *priv)
           return ret;
         }
     
    -  /* FIXME disable power save mode */
    -
    -  out_len = 4;
    -  value = 0;
    -  ret = bcmf_cdc_ioctl(priv, CHIP_STA_INTERFACE, true,
    -                         WLC_SET_PM, (uint8_t*)&value, &out_len);
    -  if (ret != OK)
    -    {
    -      return ret;
    -    }
    -
    -  /* Set the GMode */
    -
    -  out_len = 4;
    -  value = GMODE_AUTO;
    -  ret = bcmf_cdc_ioctl(priv, CHIP_STA_INTERFACE, true,
    -                         WLC_SET_GMODE, (uint8_t*)&value, &out_len);
    -  if (ret != OK)
    -    {
    -      return ret;
    -    }
    -
    -  /* TODO configure roaming if needed. Disable for now */
    -
    -  out_len = 4;
    -  value = 1;
    -  ret = bcmf_cdc_iovar_request(priv, CHIP_STA_INTERFACE, true,
    -                                 IOVAR_STR_ROAM_OFF, (uint8_t*)&value,
    -                                 &out_len);
    -
       // FIXME remove
     #if 0
       /* Try scan */
    @@ -330,14 +281,10 @@ int bcmf_run_escan(FAR struct bcmf_dev_s *priv)
     }
     #endif
     
    -/****************************************************************************
    - * Public Functions
    - ****************************************************************************/
    -
    -int bcmf_wl_initialize(FAR struct bcmf_dev_s *priv)
    +int bcmf_driver_initialize(FAR struct bcmf_dev_s *priv)
     {
       int ret;
    -  uint32_t out_len;
    +  uint32_t out_len, value;
       uint8_t tmp_buf[64];
     
       /* Disable TX Gloming feature */
    @@ -352,22 +299,35 @@ int bcmf_wl_initialize(FAR struct bcmf_dev_s *priv)
           return -EIO;
         }
     
    -  /* Query MAC address */
    +  /* FIXME disable power save mode */
     
    -  out_len = 6;
    -  ret = bcmf_cdc_iovar_request(priv, CHIP_STA_INTERFACE, false,
    -                                 IOVAR_STR_CUR_ETHERADDR, tmp_buf,
    -                                 &out_len);
    +  out_len = 4;
    +  value = 0;
    +  ret = bcmf_cdc_ioctl(priv, CHIP_STA_INTERFACE, true,
    +                         WLC_SET_PM, (uint8_t*)&value, &out_len);
       if (ret != OK)
         {
    -      return -EIO;
    +      return ret;
         }
     
    -  memcpy(priv->mac_addr, tmp_buf, 6);
    +  /* Set the GMode to auto */
     
    -  wlinfo("MAC address is %02X:%02X:%02X:%02X:%02X:%02X\n",
    -                        tmp_buf[0], tmp_buf[1], tmp_buf[2],
    -                        tmp_buf[3], tmp_buf[4], tmp_buf[5]);
    +  out_len = 4;
    +  value = GMODE_AUTO;
    +  ret = bcmf_cdc_ioctl(priv, CHIP_STA_INTERFACE, true,
    +                         WLC_SET_GMODE, (uint8_t*)&value, &out_len);
    +  if (ret != OK)
    +    {
    +      return ret;
    +    }
    +
    +  /* TODO configure roaming if needed. Disable for now */
    +
    +  out_len = 4;
    +  value = 1;
    +  ret = bcmf_cdc_iovar_request(priv, CHIP_STA_INTERFACE, true,
    +                                 IOVAR_STR_ROAM_OFF, (uint8_t*)&value,
    +                                 &out_len);
       
       /* Query firmware version string */
     
    @@ -402,11 +362,16 @@ int bcmf_wl_initialize(FAR struct bcmf_dev_s *priv)
         {
           return -EIO;
         }
    -  // TODO Create a wlan device name and register network driver
     
    -  return bcmf_dongle_initialize(priv);
    +  /* Register network driver */
    +
    +  return bcmf_netdev_register(priv);
     }
     
    +/****************************************************************************
    + * Public Functions
    + ****************************************************************************/
    +
     int bcmf_sdio_initialize(int minor, FAR struct sdio_dev_s *dev)
     {
       int ret;
    @@ -431,9 +396,28 @@ int bcmf_sdio_initialize(int minor, FAR struct sdio_dev_s *dev)
     
       /* Bus initialized, register network driver */
     
    -  return bcmf_wl_initialize(priv);
    +  return bcmf_driver_initialize(priv);
     
     exit_free_device:
       bcmf_free_device(priv);
       return ret;
    +}
    +
    +int bcmf_wl_enable(FAR struct bcmf_dev_s *priv, bool enable)
    +{
    +  int ret;
    +  uint32_t out_len;
    +
    +  /* TODO chek device state */
    +
    +  out_len = 0;
    +  ret = bcmf_cdc_ioctl(priv, CHIP_STA_INTERFACE, true,
    +                         enable ? WLC_UP : WLC_DOWN, NULL, &out_len);
    +
    +  if (ret == OK)
    +    {
    +      /* TODO update device state */
    +    }
    +
    +  return ret;
     }
    \ No newline at end of file
    diff --git a/drivers/wireless/ieee80211/bcmf_driver.h b/drivers/wireless/ieee80211/bcmf_driver.h
    index d121fc2a95..346b2e15fd 100644
    --- a/drivers/wireless/ieee80211/bcmf_driver.h
    +++ b/drivers/wireless/ieee80211/bcmf_driver.h
    @@ -40,11 +40,15 @@
     #include 
     #include 
     
    -#define BCMF_STATUS_BUS_UP (1<<0) /* Chip is flashed and running */
    -#define BCMF_STATUS_READY  (1<<1) /* Chip is ready to receive requests */
    +#include 
    +#include 
    +#include 
     
    -#define BCMF_STATUS_SLEEP  (1<<2) /* Chip is in low power mode */
    -#define BCMF_STATUS_WAIT_CONTROL (1<<3) /* Waiting for control response */
    +/* Chip interfaces */
    +
    +#define CHIP_STA_INTERFACE   0
    +#define CHIP_AP_INTERFACE    1
    +#define CHIP_P2P_INTERFACE   2
     
     struct bcmf_bus_dev_s;
     struct bcmf_frame_s;
    @@ -53,7 +57,18 @@ struct bcmf_frame_s;
     
     struct bcmf_dev_s
     {
    -  FAR struct bcmf_bus_dev_s *bus;  /* Bus interface structure */
    +  FAR struct bcmf_bus_dev_s *bus; /* Bus interface structure */
    +
    +  bool bc_bifup;             /* true:ifup false:ifdown */
    +  WDOG_ID bc_txpoll;         /* TX poll timer */
    +  WDOG_ID bc_txtimeout;      /* TX timeout timer */
    +  struct work_s bc_irqwork;  /* For deferring interrupt work to the work queue */
    +  struct work_s bc_pollwork; /* For deferring poll work to the work queue */
    +
    +  /* This holds the information visible to the NuttX network */
    +
    +  struct net_driver_s bc_dev;  /* Network interface structure */
    +
     
       // FIXME use mutex instead of semaphore
       sem_t control_mutex;         /* Cannot handle multiple control requests */
    @@ -62,8 +77,6 @@ struct bcmf_dev_s
       uint16_t control_rxdata_len; /* Received control frame out buffer length */
       uint8_t *control_rxdata;     /* Received control frame out buffer */
       uint32_t control_status;     /* Last received frame status */
    -
    -  uint8_t mac_addr[6];         /* Current mac address */
     };
     
     /* Default bus interface structure */
    @@ -89,13 +102,6 @@ struct bcmf_frame_s {
       unsigned int len; /* Frame buffer size */
     };
     
    -/* Notify driver frame is available */
    -
    -void bcmf_notify_rxframe(FAR struct bcmf_dev_s *priv,
    -                         struct bcmf_frame_s *frame);
    -
    -/* Notify driver bus is ready */
    -
    -int brcmf_bus_start(FAR struct bcmf_dev_s *priv);
    +int bcmf_wl_enable(FAR struct bcmf_dev_s *priv, bool enable);
     
     #endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_DRIVER_H */
    diff --git a/drivers/wireless/ieee80211/bcmf_ioctl.h b/drivers/wireless/ieee80211/bcmf_ioctl.h
    index 6940a5d344..d1936bb7ff 100644
    --- a/drivers/wireless/ieee80211/bcmf_ioctl.h
    +++ b/drivers/wireless/ieee80211/bcmf_ioctl.h
    @@ -49,7 +49,7 @@ extern "C" {
     typedef uint16_t wl_chanspec_t;
     typedef uint16_t chanspec_t;
     #define    ETHER_ADDR_LEN        6
    -typedef struct ether_addr
    +typedef struct ether_addr_dup
     {
         uint8_t octet[ETHER_ADDR_LEN];
     } wl_ether_addr_t;
    diff --git a/drivers/wireless/ieee80211/bcmf_netdev.c b/drivers/wireless/ieee80211/bcmf_netdev.c
    index 96ffed609f..5d94d9e583 100644
    --- a/drivers/wireless/ieee80211/bcmf_netdev.c
    +++ b/drivers/wireless/ieee80211/bcmf_netdev.c
    @@ -61,6 +61,10 @@
     #  include 
     #endif
     
    +#include "bcmf_driver.h"
    +#include "bcmf_cdc.h"
    +#include "bcmf_ioctl.h"
    +
     /****************************************************************************
      * Pre-processor Definitions
      ****************************************************************************/
    @@ -108,23 +112,6 @@
      * Private Types
      ****************************************************************************/
     
    -/* The bcmf_driver_s encapsulates all state information for a single hardware
    - * interface
    - */
    -
    -struct bcmf_driver_s
    -{
    -  bool bc_bifup;               /* true:ifup false:ifdown */
    -  WDOG_ID bc_txpoll;           /* TX poll timer */
    -  WDOG_ID bc_txtimeout;        /* TX timeout timer */
    -  struct work_s bc_irqwork;    /* For deferring interupt work to the work queue */
    -  struct work_s bc_pollwork;   /* For deferring poll work to the work queue */
    -
    -  /* This holds the information visible to the NuttX network */
    -
    -  struct net_driver_s bc_dev;  /* Interface understood by the network */
    -};
    -
     /****************************************************************************
      * Private Data
      ****************************************************************************/
    @@ -144,23 +131,19 @@ struct bcmf_driver_s
     
     static uint8_t g_pktbuf[MAX_NET_DEV_MTU + CONFIG_NET_GUARDSIZE];
     
    -/* Driver state structure */
    -
    -static struct bcmf_driver_s g_bcmf_interface[CONFIG_IEEE80211_BROADCOM_NINTERFACES];
    -
     /****************************************************************************
      * Private Function Prototypes
      ****************************************************************************/
     
     /* Common TX logic */
     
    -static int  bcmf_transmit(FAR struct bcmf_driver_s *priv);
    +static int  bcmf_transmit(FAR struct bcmf_dev_s *priv);
     static int  bcmf_txpoll(FAR struct net_driver_s *dev);
     
     /* Interrupt handling */
     
    -static void bcmf_receive(FAR struct bcmf_driver_s *priv);
    -static void bcmf_txdone(FAR struct bcmf_driver_s *priv);
    +static void bcmf_receive(FAR struct bcmf_dev_s *priv);
    +static void bcmf_txdone(FAR struct bcmf_dev_s *priv);
     
     static void bcmf_interrupt_work(FAR void *arg);
     static int  bcmf_interrupt(int irq, FAR void *context, FAR void *arg);
    @@ -189,7 +172,7 @@ static int  bcmf_rmmac(FAR struct net_driver_s *dev,
                   FAR const uint8_t *mac);
     #endif
     #ifdef CONFIG_NET_ICMPv6
    -static void bcmf_ipv6multicast(FAR struct bcmf_driver_s *priv);
    +static void bcmf_ipv6multicast(FAR struct bcmf_dev_s *priv);
     #endif
     #endif
     #ifdef CONFIG_NETDEV_IOCTL
    @@ -220,7 +203,7 @@ static int  bcmf_ioctl(FAR struct net_driver_s *dev, int cmd,
      *
      ****************************************************************************/
     
    -static int bcmf_transmit(FAR struct bcmf_driver_s *priv)
    +static int bcmf_transmit(FAR struct bcmf_dev_s *priv)
     {
       /* Verify that the hardware is ready to send another packet.  If we get
        * here, then we are committed to sending a packet; Higher level logic
    @@ -268,7 +251,7 @@ static int bcmf_transmit(FAR struct bcmf_driver_s *priv)
     
     static int bcmf_txpoll(FAR struct net_driver_s *dev)
     {
    -  FAR struct bcmf_driver_s *priv = (FAR struct bcmf_driver_s *)dev->d_private;
    +  FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)dev->d_private;
     
       /* If the polling resulted in data that should be sent out on the network,
        * the field d_len is set to a value > 0.
    @@ -331,7 +314,7 @@ static int bcmf_txpoll(FAR struct net_driver_s *dev)
      *
      ****************************************************************************/
     
    -static void bcmf_receive(FAR struct bcmf_driver_s *priv)
    +static void bcmf_receive(FAR struct bcmf_dev_s *priv)
     {
       do
         {
    @@ -453,7 +436,7 @@ static void bcmf_receive(FAR struct bcmf_driver_s *priv)
               NETDEV_RXDROPPED(&priv->bc_dev);
             }
         }
    -  while (); /* While there are more packets to be processed */
    +  while (1); /* While there are more packets to be processed */
     }
     
     /****************************************************************************
    @@ -473,7 +456,7 @@ static void bcmf_receive(FAR struct bcmf_driver_s *priv)
      *
      ****************************************************************************/
     
    -static void bcmf_txdone(FAR struct bcmf_driver_s *priv)
    +static void bcmf_txdone(FAR struct bcmf_dev_s *priv)
     {
       int delay;
     
    @@ -515,7 +498,7 @@ static void bcmf_txdone(FAR struct bcmf_driver_s *priv)
     
     static void bcmf_interrupt_work(FAR void *arg)
     {
    -  FAR struct bcmf_driver_s *priv = (FAR struct bcmf_driver_s *)arg;
    +  FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)arg;
     
       /* Lock the network and serialize driver operations if necessary.
        * NOTE: Serialization is only required in the case where the driver work
    @@ -566,7 +549,7 @@ static void bcmf_interrupt_work(FAR void *arg)
     
     static int bcmf_interrupt(int irq, FAR void *context, FAR void *arg)
     {
    -  FAR struct bcmf_driver_s *priv = (FAR struct bcmf_driver_s *)arg;
    +  FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)arg;
     
       DEBUGASSERT(priv != NULL);
     
    @@ -612,7 +595,7 @@ static int bcmf_interrupt(int irq, FAR void *context, FAR void *arg)
     
     static void bcmf_txtimeout_work(FAR void *arg)
     {
    -  FAR struct bcmf_driver_s *priv = (FAR struct bcmf_driver_s *)arg;
    +  FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)arg;
     
       /* Lock the network and serialize driver operations if necessary.
        * NOTE: Serialization is only required in the case where the driver work
    @@ -655,7 +638,7 @@ static void bcmf_txtimeout_work(FAR void *arg)
     
     static void bcmf_txtimeout_expiry(int argc, wdparm_t arg, ...)
     {
    -  FAR struct bcmf_driver_s *priv = (FAR struct bcmf_driver_s *)arg;
    +  FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)arg;
     
       /* Disable further Ethernet interrupts.  This will prevent some race
        * conditions with interrupt work.  There is still a potential race
    @@ -685,7 +668,7 @@ static void bcmf_txtimeout_expiry(int argc, wdparm_t arg, ...)
      *
      ****************************************************************************/
     
    -static inline void bcmf_poll_process(FAR struct bcmf_driver_s *priv)
    +static inline void bcmf_poll_process(FAR struct bcmf_dev_s *priv)
     {
     }
     
    @@ -708,7 +691,7 @@ static inline void bcmf_poll_process(FAR struct bcmf_driver_s *priv)
     
     static void bcmf_poll_work(FAR void *arg)
     {
    -  FAR struct bcmf_driver_s *priv = (FAR struct bcmf_driver_s *)arg;
    +  FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)arg;
     
       /* Lock the network and serialize driver operations if necessary.
        * NOTE: Serialization is only required in the case where the driver work
    @@ -758,7 +741,7 @@ static void bcmf_poll_work(FAR void *arg)
     
     static void bcmf_poll_expiry(int argc, wdparm_t arg, ...)
     {
    -  FAR struct bcmf_driver_s *priv = (FAR struct bcmf_driver_s *)arg;
    +  FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)arg;
     
       /* Schedule to perform the interrupt processing on the worker thread. */
     
    @@ -784,7 +767,7 @@ static void bcmf_poll_expiry(int argc, wdparm_t arg, ...)
     
     static int bcmf_ifup(FAR struct net_driver_s *dev)
     {
    -  FAR struct bcmf_driver_s *priv = (FAR struct bcmf_driver_s *)dev->d_private;
    +  FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)dev->d_private;
     
     #ifdef CONFIG_NET_IPv4
       ninfo("Bringing up: %d.%d.%d.%d\n",
    @@ -838,7 +821,7 @@ static int bcmf_ifup(FAR struct net_driver_s *dev)
     
     static int bcmf_ifdown(FAR struct net_driver_s *dev)
     {
    -  FAR struct bcmf_driver_s *priv = (FAR struct bcmf_driver_s *)dev->d_private;
    +  FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)dev->d_private;
       irqstate_t flags;
     
       /* Disable the hardware interrupt */
    @@ -882,7 +865,7 @@ static int bcmf_ifdown(FAR struct net_driver_s *dev)
     
     static void bcmf_txavail_work(FAR void *arg)
     {
    -  FAR struct bcmf_driver_s *priv = (FAR struct bcmf_driver_s *)arg;
    +  FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)arg;
     
       /* Lock the network and serialize driver operations if necessary.
        * NOTE: Serialization is only required in the case where the driver work
    @@ -927,7 +910,7 @@ static void bcmf_txavail_work(FAR void *arg)
     
     static int bcmf_txavail(FAR struct net_driver_s *dev)
     {
    -  FAR struct bcmf_driver_s *priv = (FAR struct bcmf_driver_s *)dev->d_private;
    +  FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)dev->d_private;
     
       /* Is our single work structure available?  It may not be if there are
        * pending interrupt actions and we will have to ignore the Tx
    @@ -965,7 +948,7 @@ static int bcmf_txavail(FAR struct net_driver_s *dev)
     #if defined(CONFIG_NET_IGMP) || defined(CONFIG_NET_ICMPv6)
     static int bcmf_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac)
     {
    -  FAR struct bcmf_driver_s *priv = (FAR struct bcmf_driver_s *)dev->d_private;
    +  FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)dev->d_private;
     
       /* Add the MAC address to the hardware multicast routing table */
     
    @@ -994,7 +977,7 @@ static int bcmf_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac)
     #ifdef CONFIG_NET_IGMP
     static int bcmf_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac)
     {
    -  FAR struct bcmf_driver_s *priv = (FAR struct bcmf_driver_s *)dev->d_private;
    +  FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)dev->d_private;
     
       /* Add the MAC address to the hardware multicast routing table */
     
    @@ -1019,7 +1002,7 @@ static int bcmf_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac)
      ****************************************************************************/
     
     #ifdef CONFIG_NET_ICMPv6
    -static void bcmf_ipv6multicast(FAR struct bcmf_driver_s *priv)
    +static void bcmf_ipv6multicast(FAR struct bcmf_dev_s *priv)
     {
       FAR struct net_driver_s *dev;
       uint16_t tmp16;
    @@ -1098,7 +1081,7 @@ static void bcmf_ipv6multicast(FAR struct bcmf_driver_s *priv)
     static int bcmf_ioctl(FAR struct net_driver_s *dev, int cmd,
                           unsigned long arg)
     {
    -  FAR struct bcmf_driver_s *priv = (FAR struct bcmf_driver_s *)dev->d_private;
    +  FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)dev->d_private;
       int ret;
     
       /* Decode and dispatch the driver-specific IOCTL command */
    @@ -1124,11 +1107,10 @@ static int bcmf_ioctl(FAR struct net_driver_s *dev, int cmd,
      * Name: bcmf_netdev_register
      *
      * Description:
    - *   Initialize the Broadcom 43362 controller and driver
    + *   Register a network driver and set Broadcom chip in a proper state
      *
      * Parameters:
    - *   intf - In the case where there are multiple EMACs, this value
    - *          identifies which EMAC is to be initialized.
    + *   priv - Broadcom driver device
      *
      * Returned Value:
      *   OK on success; Negated errno on failure.
    @@ -1137,21 +1119,14 @@ static int bcmf_ioctl(FAR struct net_driver_s *dev, int cmd,
      *
      ****************************************************************************/
     
    -int bcmf_netdev_register(int intf)
    +int bcmf_netdev_register(FAR struct bcmf_dev_s *priv)
     {
    -  FAR struct bcmf_driver_s *priv;
    -
    -  /* Get the interface structure associated with this interface number. */
    -
    -  DEBUGASSERT(intf < CONFIG_IEEE80211_BROADCOM_NINTERFACES);
    -  priv = &g_bcmf_interface[intf];
    -
    -  /* Attach the IRQ to the driver */
    -#warning Missing logic
    +  int ret;
    +  uint32_t out_len;
     
    -  /* Initialize the driver structure */
    +  /* Initialize network driver structure */
     
    -  memset(priv, 0, sizeof(struct bcmf_driver_s));
    +  memset(&priv->bc_dev, 0, sizeof(priv->bc_dev));
       priv->bc_dev.d_buf     = g_pktbuf;      /* Single packet buffer */
       priv->bc_dev.d_ifup    = bcmf_ifup;     /* I/F up (new IP address) callback */
       priv->bc_dev.d_ifdown  = bcmf_ifdown;   /* I/F down callback */
    @@ -1163,7 +1138,7 @@ int bcmf_netdev_register(int intf)
     #ifdef CONFIG_NETDEV_IOCTL
       priv->bc_dev.d_ioctl   = bcmf_ioctl;    /* Handle network IOCTL commands */
     #endif
    -  priv->bc_dev.d_private = (FAR void *)g_bcmf_interface; /* Used to recover private state from dev */
    +  priv->bc_dev.d_private = (FAR void *)priv; /* Used to recover private state from dev */
     
       /* Create a watchdog for timing polling for and timing of transmisstions */
     
    @@ -1176,7 +1151,31 @@ int bcmf_netdev_register(int intf)
        * the device and/or calling bcmf_ifdown().
        */
     
    -  /* Read the MAC address from the hardware into priv->bc_dev.d_mac.ether.ether_addr_octet */
    +  ret = bcmf_wl_enable(priv, false);
    +  if (ret != OK)
    +    {
    +      return -EIO;
    +    }
    +
    +  /* Query MAC address */
    +
    +  out_len = ETHER_ADDR_LEN;
    +  ret = bcmf_cdc_iovar_request(priv, CHIP_STA_INTERFACE, false,
    +                                 IOVAR_STR_CUR_ETHERADDR,
    +                                 priv->bc_dev.d_mac.ether.ether_addr_octet,
    +                                 &out_len);
    +  if (ret != OK)
    +    {
    +      return -EIO;
    +    }
    +
    +  wlinfo("MAC address is %02X:%02X:%02X:%02X:%02X:%02X\n",
    +                        priv->bc_dev.d_mac.ether.ether_addr_octet[0],
    +                        priv->bc_dev.d_mac.ether.ether_addr_octet[1],
    +                        priv->bc_dev.d_mac.ether.ether_addr_octet[2],
    +                        priv->bc_dev.d_mac.ether.ether_addr_octet[3],
    +                        priv->bc_dev.d_mac.ether.ether_addr_octet[4],
    +                        priv->bc_dev.d_mac.ether.ether_addr_octet[5]);
     
       /* Register the device with the OS so that socket IOCTLs can be performed */
     
    -- 
    GitLab
    
    
    From 62fc578661c898bc938437217cd855e9da81043d Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Mon, 24 Apr 2017 15:11:22 -0600
    Subject: [PATCH 577/990] wireless/ieee80211:  Add BSD license information to
     all files (except the Broadcom files -- need to revisit those).
    
    ---
     drivers/wireless/ieee80211/bcmf_cdc.h   | 49 ++++++++++++++++--
     drivers/wireless/ieee80211/bcmf_sdio.h  | 67 +++++++++++++++++++++----
     drivers/wireless/ieee80211/bcmf_sdpcm.h | 48 +++++++++++++++++-
     drivers/wireless/ieee80211/bcmf_utils.c | 47 +++++++++++++++++
     drivers/wireless/ieee80211/bcmf_utils.h | 43 ++++++++++++++++
     5 files changed, 240 insertions(+), 14 deletions(-)
    
    diff --git a/drivers/wireless/ieee80211/bcmf_cdc.h b/drivers/wireless/ieee80211/bcmf_cdc.h
    index d19661c06f..2c9743e4f0 100644
    --- a/drivers/wireless/ieee80211/bcmf_cdc.h
    +++ b/drivers/wireless/ieee80211/bcmf_cdc.h
    @@ -1,3 +1,42 @@
    +/****************************************************************************
    + * drivers/wireless/ieee80211/bcmf_cdc.h
    + *
    + *   Copyright (C) 2017 Gregory Nutt. All rights reserved.
    + *   Author: Simon Piriou 
    + *
    + * 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
    + ****************************************************************************/
    +
     #ifndef __DRIVERS_WIRELESS_IEEE80211_BCMF_CDC_H
     #define __DRIVERS_WIRELESS_IEEE80211_BCMF_CDC_H
     
    @@ -5,6 +44,10 @@
     #include 
     #include 
     
    +/****************************************************************************
    + * Public Function Prototypes
    + ****************************************************************************/
    +
     int bcmf_cdc_iovar_request(FAR struct bcmf_dev_s *priv, uint32_t ifidx,
                                bool set, char *name, uint8_t *data, uint32_t *len);
     
    @@ -12,12 +55,12 @@ int bcmf_cdc_ioctl(FAR struct bcmf_dev_s *priv, uint32_t ifidx, bool set,
                        uint32_t cmd, uint8_t *data, uint32_t *len);
     
     int bcmf_cdc_process_control_frame(FAR struct bcmf_dev_s *priv,
    -								   struct bcmf_frame_s *frame);
    +                                   struct bcmf_frame_s *frame);
     
     int bcmf_cdc_process_data_frame(FAR struct bcmf_dev_s *priv,
    -								struct bcmf_frame_s *frame);
    +                                struct bcmf_frame_s *frame);
     
     int bcmf_cdc_process_event_frame(FAR struct bcmf_dev_s *priv,
    -								 struct bcmf_frame_s *frame);
    +                                 struct bcmf_frame_s *frame);
     
     #endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_CDC_H */
    \ No newline at end of file
    diff --git a/drivers/wireless/ieee80211/bcmf_sdio.h b/drivers/wireless/ieee80211/bcmf_sdio.h
    index 83843705d8..228fbb8d18 100644
    --- a/drivers/wireless/ieee80211/bcmf_sdio.h
    +++ b/drivers/wireless/ieee80211/bcmf_sdio.h
    @@ -1,3 +1,42 @@
    +/****************************************************************************
    + * drivers/wireless/ieee80211/bcmf_sdio.h
    + *
    + *   Copyright (C) 2017 Gregory Nutt. All rights reserved.
    + *   Author: Simon Piriou 
    + *
    + * 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
    + ****************************************************************************/
    +
     #ifndef __DRIVERS_WIRELESS_IEEE80211_BCMF_SDIO_H
     #define __DRIVERS_WIRELESS_IEEE80211_BCMF_SDIO_H
     
    @@ -10,22 +49,28 @@
     
     #include "bcmf_sdio_core.h"
     
    +/****************************************************************************
    + * Public Types
    + ****************************************************************************/
    +
     /* sdio chip configuration structure */
     
    -struct bcmf_sdio_chip {
    -	uint32_t ram_size;
    -	uint32_t core_base[MAX_CORE_ID];
    +struct bcmf_sdio_chip
    +{
    +  uint32_t ram_size;
    +  uint32_t core_base[MAX_CORE_ID];
     
    -	uint8_t      *firmware_image;
    -	unsigned int *firmware_image_size;
    +  uint8_t      *firmware_image;
    +  unsigned int *firmware_image_size;
     
    -	uint8_t      *nvram_image;
    -	unsigned int *nvram_image_size;
    +  uint8_t      *nvram_image;
    +  unsigned int *nvram_image_size;
     };
     
     /* sdio bus structure extension */
     
    -struct bcmf_sdio_dev_s {
    +struct bcmf_sdio_dev_s
    +{
       struct bcmf_bus_dev_s bus;       /* Default bcmf bus structure */
       FAR struct sdio_dev_s *sdio_dev; /* The SDIO device bound to this instance */
       int minor;                       /* Device minor number */
    @@ -52,8 +97,12 @@ struct bcmf_sdio_dev_s {
       dq_queue_t tx_queue;             /* Queue of frames to tramsmit */
     };
     
    +/****************************************************************************
    + * Public Function Prototypes
    + ****************************************************************************/
    +
     int bcmf_bus_sdio_initialize(FAR struct bcmf_dev_s *priv,
    -					int minor, FAR struct sdio_dev_s *dev);
    +          int minor, FAR struct sdio_dev_s *dev);
     
     /* FIXME: Low level bus data transfer function
      * To avoid bus error, len will be aligned to:
    diff --git a/drivers/wireless/ieee80211/bcmf_sdpcm.h b/drivers/wireless/ieee80211/bcmf_sdpcm.h
    index 1136a8bb57..eedcb60050 100644
    --- a/drivers/wireless/ieee80211/bcmf_sdpcm.h
    +++ b/drivers/wireless/ieee80211/bcmf_sdpcm.h
    @@ -1,8 +1,51 @@
    +/****************************************************************************
    + * drivers/wireless/ieee80211/bcmf_sdpcm.h
    + *
    + *   Copyright (C) 2017 Gregory Nutt. All rights reserved.
    + *   Author: Simon Piriou 
    + *
    + * 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 __DRIVERS_WIRELESS_IEEE80211_BCMF_SDPCM_H
     #define __DRIVERS_WIRELESS_IEEE80211_BCMF_SDPCM_H
     
    +/****************************************************************************
    + * Included Files
    + ****************************************************************************/
    +
     #include "bcmf_driver.h"
     
    +/****************************************************************************
    + * Public Function Prototypes
    + ****************************************************************************/
    +
     int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv);
     
     int bcmf_sdpcm_sendframe(FAR struct bcmf_dev_s *priv);
    @@ -10,7 +53,8 @@ int bcmf_sdpcm_sendframe(FAR struct bcmf_dev_s *priv);
     int bcmf_sdpcm_queue_frame(FAR struct bcmf_dev_s *priv,
                                struct bcmf_frame_s *frame);
     
    -struct bcmf_frame_s* bcmf_sdpcm_allocate_frame(FAR struct bcmf_dev_s *priv,
    -                                unsigned int len, bool control, bool block);
    +struct bcmf_frame_s *bcmf_sdpcm_allocate_frame(FAR struct bcmf_dev_s *priv,
    +                                               unsigned int len, bool control,
    +                                               bool block);
     
     #endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_SDPCM_H */
    \ No newline at end of file
    diff --git a/drivers/wireless/ieee80211/bcmf_utils.c b/drivers/wireless/ieee80211/bcmf_utils.c
    index dbd53b0619..7a9c780671 100644
    --- a/drivers/wireless/ieee80211/bcmf_utils.c
    +++ b/drivers/wireless/ieee80211/bcmf_utils.c
    @@ -1,3 +1,42 @@
    +/****************************************************************************
    + * drivers/wireless/ieee80211/bcmf_utils.c
    + *
    + *   Copyright (C) 2017 Gregory Nutt. All rights reserved.
    + *   Author: Simon Piriou 
    + *
    + * 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 
    @@ -7,8 +46,16 @@
     
     #include "bcmf_utils.h"
     
    +/****************************************************************************
    + * Pre-processor Definitions
    + ****************************************************************************/
    +
     #define LINE_LEN 16
     
    +/****************************************************************************
    + * Public Functions
    + ****************************************************************************/
    +
     /****************************************************************************
      * Name: bcmf_hexdump
      ****************************************************************************/
    diff --git a/drivers/wireless/ieee80211/bcmf_utils.h b/drivers/wireless/ieee80211/bcmf_utils.h
    index a4b93c690d..ef7b45bbfa 100644
    --- a/drivers/wireless/ieee80211/bcmf_utils.h
    +++ b/drivers/wireless/ieee80211/bcmf_utils.h
    @@ -1,9 +1,52 @@
    +/****************************************************************************
    + * drivers/wireless/ieee80211/bcmf_utils.h
    + *
    + *   Copyright (C) 2017 Gregory Nutt. All rights reserved.
    + *   Author: Simon Piriou 
    + *
    + * 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 __DRIVERS_WIRELESS_IEEE80211_BCMF_UTILS_H
     #define __DRIVERS_WIRELESS_IEEE80211_BCMF_UTILS_H
     
    +/****************************************************************************
    + * Included Files
    + ****************************************************************************/
    +
     #include 
     #include 
     
    +/****************************************************************************
    + * Public Function Prototypes
    + ****************************************************************************/
    +
     void bcmf_hexdump(uint8_t *data, unsigned int len, unsigned long offset);
     
     int bcmf_sem_wait(sem_t *sem, unsigned int timeout_ms);
    -- 
    GitLab
    
    
    From ae8d5821e03c0408aea43aaa0cd9df66e189fda8 Mon Sep 17 00:00:00 2001
    From: Masatoshi Tateishi 
    Date: Fri, 5 Jun 2015 12:51:07 +0900
    Subject: [PATCH 578/990] procfs: Fix incorrect uptime with
     CONFIG_SYSTEM_TIME64
    
    Jira: PDFW15IS-45
    Signed-off-by: Masayuki Ishikawa 
    ---
     fs/procfs/fs_procfsuptime.c | 4 ++++
     1 file changed, 4 insertions(+)
    
    diff --git a/fs/procfs/fs_procfsuptime.c b/fs/procfs/fs_procfsuptime.c
    index f9e76cb897..c39ade3407 100644
    --- a/fs/procfs/fs_procfsuptime.c
    +++ b/fs/procfs/fs_procfsuptime.c
    @@ -265,7 +265,11 @@ static ssize_t uptime_read(FAR struct file *filep, FAR char *buffer,
     
           /* Convert the seconds + hundredths of seconds to a string */
     
    +#ifdef CONFIG_SYSTEM_TIME64
    +      linesize = snprintf(attr->line, UPTIME_LINELEN, "%7llu.%02u\n", sec, csec);
    +#else
           linesize = snprintf(attr->line, UPTIME_LINELEN, "%7lu.%02u\n", sec, csec);
    +#endif
     
     #endif
           /* Save the linesize in case we are re-entered with f_pos > 0 */
    -- 
    GitLab
    
    
    From 559660a53024d4f311fcdb302418476517914b8d Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Tue, 25 Apr 2017 07:44:25 -0600
    Subject: [PATCH 579/990] Move bogus top-level config-wlan to
     configs/photon/wlan/defconfig.
    
    ---
     configs/photon/wlan/Make.defs                | 139 +++++++++++++++++++
     config_wlan => configs/photon/wlan/defconfig |   7 +-
     configs/photon/wlan/setenv.sh                |  84 +++++++++++
     3 files changed, 228 insertions(+), 2 deletions(-)
     create mode 100644 configs/photon/wlan/Make.defs
     rename config_wlan => configs/photon/wlan/defconfig (99%)
     create mode 100644 configs/photon/wlan/setenv.sh
    
    diff --git a/configs/photon/wlan/Make.defs b/configs/photon/wlan/Make.defs
    new file mode 100644
    index 0000000000..e72c160c3f
    --- /dev/null
    +++ b/configs/photon/wlan/Make.defs
    @@ -0,0 +1,139 @@
    +############################################################################
    +# configs/photon/wlan/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.
    +#
    +############################################################################
    +
    +include ${TOPDIR}/.config
    +include ${TOPDIR}/tools/Config.mk
    +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
    +
    +ifeq ($(CONFIG_PHOTON_DFU_BOOTLOADER),y)
    +LDSCRIPT = photon_dfu.ld
    +else
    +LDSCRIPT = ld.script
    +endif
    +
    +ifeq ($(WINTOOL),y)
    +  # Windows-native toolchains
    +  DIRLINK = $(TOPDIR)/tools/copydir.sh
    +  DIRUNLINK = $(TOPDIR)/tools/unlink.sh
    +  MKDEP = $(TOPDIR)/tools/mkwindeps.sh
    +  ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
    +  ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
    +  ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
    +else
    +  # Linux/Cygwin-native toolchain
    +  MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT)
    +  ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
    +  ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
    +  ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
    +endif
    +
    +CC = $(CROSSDEV)gcc
    +CXX = $(CROSSDEV)g++
    +CPP = $(CROSSDEV)gcc -E
    +LD = $(CROSSDEV)ld
    +AR = $(ARCROSSDEV)ar rcs
    +NM = $(ARCROSSDEV)nm
    +OBJCOPY = $(CROSSDEV)objcopy
    +OBJDUMP = $(CROSSDEV)objdump
    +
    +# See http://dfu-util.sourceforge.net/
    +
    +DFUSUFFIX = dfu-suffix
    +DFUUTIL = dfu-util
    +
    +ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'}
    +ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1}
    +
    +ifeq ($(CONFIG_DEBUG_SYMBOLS),y)
    +  ARCHOPTIMIZATION = -g
    +endif
    +
    +ifneq ($(CONFIG_DEBUG_NOOPT),y)
    +  ARCHOPTIMIZATION += $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer
    +endif
    +
    +ARCHCFLAGS = -fno-builtin
    +ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fcheck-new -fno-rtti
    +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow -Wundef
    +ARCHWARNINGSXX = -Wall -Wshadow -Wundef
    +ARCHDEFINES =
    +ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
    +
    +CFLAGS = $(ARCHCFLAGS) $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
    +CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS)
    +CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
    +CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS)
    +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES)
    +AFLAGS = $(CFLAGS) -D__ASSEMBLY__
    +
    +NXFLATLDFLAGS1 = -r -d -warn-common
    +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections
    +LDNXFLATFLAGS = -e main -s 2048
    +
    +ASMEXT = .S
    +OBJEXT = .o
    +LIBEXT = .a
    +EXEEXT =
    +
    +ifneq ($(CROSSDEV),arm-nuttx-elf-)
    +  LDFLAGS += -nostartfiles -nodefaultlibs
    +endif
    +ifeq ($(CONFIG_DEBUG_SYMBOLS),y)
    +  LDFLAGS += -g
    +endif
    +
    +
    +HOSTCC = gcc
    +HOSTINCLUDES = -I.
    +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -Wundef -g -pipe
    +HOSTLDFLAGS =
    +
    +ifeq ($(CONFIG_DFU_BINARY),y)
    +
    +define DOWNLOAD
    +  $(Q) echo "DFUSUFFIX: $(1).dfu"
    +  $(Q) $(OBJCOPY) $(OBJCOPYARGS) -O binary $(1) $(1).dfu
    +  $(Q) $(DFUSUFFIX) -v $(subst 0x,,$(CONFIG_DFU_VID)) -p $(subst 0x,,$(CONFIG_DFU_PID)) -a $(1).dfu
    +  $(Q) $(DFUUTIL) -d $(CONFIG_DFU_VID):$(CONFIG_DFU_PID) -a 0 -s $(CONFIG_DFU_BASE) -D $(1).dfu
    +endef
    +
    +else
    +
    +define DOWNLOAD
    +  $(Q) $(ECHO) "Photon firmware upload through JTAG is not supported"
    +endef
    +
    +endif
    +
    diff --git a/config_wlan b/configs/photon/wlan/defconfig
    similarity index 99%
    rename from config_wlan
    rename to configs/photon/wlan/defconfig
    index 51e7d92989..f65c19b8f8 100644
    --- a/config_wlan
    +++ b/configs/photon/wlan/defconfig
    @@ -16,7 +16,7 @@ CONFIG_HOST_LINUX=y
     #
     # Build Configuration
     #
    -CONFIG_APPS_DIR="../apps"
    +# CONFIG_APPS_DIR="../apps"
     CONFIG_BUILD_FLAT=y
     # CONFIG_BUILD_2PASS is not set
     
    @@ -1528,4 +1528,7 @@ CONFIG_READLINE_ECHO=y
     #
     # Wireless Libraries and NSH Add-Ons
     #
    -# CONFIG_WIRELESS_WAPI is not set
    +CONFIG_WIRELESS_WAPI=y
    +CONFIG_WIRELESS_WAPI_CMDTOOL=y
    +CONFIG_WIRELESS_WAPI_STACKSIZE=2048
    +CONFIG_WIRELESS_WAPI_PRIORITY=100
    diff --git a/configs/photon/wlan/setenv.sh b/configs/photon/wlan/setenv.sh
    new file mode 100644
    index 0000000000..0c2e88b407
    --- /dev/null
    +++ b/configs/photon/wlan/setenv.sh
    @@ -0,0 +1,84 @@
    +#!/bin/bash
    +# configs/photon/wlan/setenv.sh
    +#
    +#   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.
    +#
    +
    +if [ "$_" = "$0" ] ; then
    +  echo "You must source this script, not run it!" 1>&2
    +  exit 1
    +fi
    +
    +WD=`pwd`
    +if [ ! -x "setenv.sh" ]; then
    +  echo "This script must be executed from the top-level NuttX build directory"
    +  exit 1
    +fi
    +
    +if [ -z "${PATH_ORIG}" ]; then
    +  export PATH_ORIG="${PATH}"
    +fi
    +
    +# This is the Cygwin path to the location where I installed the RIDE
    +# toolchain under windows.  You will also have to edit this if you install
    +# the RIDE toolchain in any other location
    +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    +
    +# This is the Cygwin path to the location where I installed the CodeSourcery
    +# toolchain under windows.  You will also have to edit this if you install
    +# the CodeSourcery toolchain in any other location
    +# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    +#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    +
    +# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    +# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    +
    +# These are the Cygwin paths to the locations where I installed the Atollic
    +# toolchain under windows.  You will also have to edit this if you install
    +# the Atollic toolchain in any other location.  /usr/bin is added before
    +# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    +# at those locations as well.
    +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    +
    +# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    +# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    +export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    +
    +# This is the Cygwin path to the location where I build the buildroot
    +# toolchain.
    +#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    +
    +# Add the path to the toolchain to the PATH variable
    +export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    +
    +echo "PATH : ${PATH}"
    -- 
    GitLab
    
    
    From 16038d1685a677bc8871d26c5238445bca4e9675 Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Tue, 25 Apr 2017 08:23:53 -0600
    Subject: [PATCH 580/990] photon/wlan:  Minor config changes to get a clean
     build.
    
    ---
     configs/photon/wlan/defconfig | 35 ++++++++++++++++++++++++++++-------
     1 file changed, 28 insertions(+), 7 deletions(-)
    
    diff --git a/configs/photon/wlan/defconfig b/configs/photon/wlan/defconfig
    index f65c19b8f8..25480a5acb 100644
    --- a/configs/photon/wlan/defconfig
    +++ b/configs/photon/wlan/defconfig
    @@ -792,7 +792,11 @@ CONFIG_DEV_NULL=y
     #
     # Common  I/O Buffer Support
     #
    -# CONFIG_DRIVERS_IOB is not set
    +CONFIG_DRIVERS_IOB=y
    +CONFIG_IOB_NBUFFERS=24
    +CONFIG_IOB_BUFSIZE=196
    +CONFIG_IOB_NCHAINS=8
    +# CONFIG_IOB_DEBUG is not set
     # CONFIG_DRVR_WRITEBUFFER is not set
     # CONFIG_DRVR_READAHEAD is not set
     # CONFIG_RAMDISK is not set
    @@ -866,6 +870,7 @@ CONFIG_NETDEVICES=y
     # General Ethernet MAC Driver Options
     #
     # CONFIG_NETDEV_LOOPBACK is not set
    +# CONFIG_NETDEV_TELNET is not set
     # CONFIG_NETDEV_MULTINIC is not set
     # CONFIG_ARCH_HAVE_NETDEV_STATISTICS is not set
     CONFIG_NETDEV_LATEINIT=y
    @@ -978,6 +983,7 @@ CONFIG_NET=y
     # Driver buffer configuration
     #
     CONFIG_NET_ETH_MTU=590
    +CONFIG_NET_ETH_TCP_RECVWNDO=536
     CONFIG_NET_GUARDSIZE=2
     
     #
    @@ -1023,8 +1029,18 @@ CONFIG_NET_NACTIVESOCKETS=16
     #
     # TCP/IP Networking
     #
    -# CONFIG_NET_TCP is not set
    +CONFIG_NET_TCP=y
     # CONFIG_NET_TCP_NO_STACK is not set
    +# CONFIG_NET_TCPURGDATA is not set
    +# CONFIG_NET_TCP_REASSEMBLY is not set
    +CONFIG_NET_TCP_CONNS=8
    +CONFIG_NET_MAX_LISTENPORTS=20
    +CONFIG_NET_TCP_READAHEAD=y
    +# CONFIG_NET_TCP_WRITE_BUFFERS is not set
    +CONFIG_NET_TCP_RECVDELAY=0
    +# CONFIG_NET_TCPBACKLOG is not set
    +# CONFIG_NET_TCP_SPLIT is not set
    +# CONFIG_NET_SENDFILE is not set
     
     #
     # UDP Networking
    @@ -1161,7 +1177,7 @@ CONFIG_LIBC_LONG_LONG=y
     # CONFIG_EOL_IS_BOTH_CRLF is not set
     CONFIG_EOL_IS_EITHER_CRLF=y
     # CONFIG_MEMCPY_VIK is not set
    -# CONFIG_LIBM is not set
    +CONFIG_LIBM=y
     
     #
     # Architecture-Specific Support
    @@ -1264,10 +1280,6 @@ CONFIG_HAVE_CXXINITIALIZE=y
     # Application Configuration
     #
     
    -#
    -# NxWidgets/NxWM
    -#
    -
     #
     # Built-In Applications
     #
    @@ -1300,6 +1312,7 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
     # CONFIG_EXAMPLES_MM is not set
     # CONFIG_EXAMPLES_MODBUS is not set
     # CONFIG_EXAMPLES_MOUNT is not set
    +# CONFIG_EXAMPLES_NETTEST is not set
     # CONFIG_EXAMPLES_NRF24L01TERM is not set
     CONFIG_EXAMPLES_NSH=y
     # CONFIG_EXAMPLES_NSH_CXXINITIALIZE is not set
    @@ -1375,6 +1388,10 @@ CONFIG_EXAMPLES_NSH=y
     # CONFIG_NETUTILS_JSON is not set
     CONFIG_NETUTILS_NETLIB=y
     # CONFIG_NETUTILS_SMTP is not set
    +# CONFIG_NETUTILS_TELNETD is not set
    +# CONFIG_NETUTILS_WEBCLIENT is not set
    +# CONFIG_NETUTILS_WEBSERVER is not set
    +# CONFIG_NETUTILS_XMLRPC is not set
     
     #
     # NSH Library
    @@ -1497,6 +1514,10 @@ CONFIG_NSH_MAX_ROUNDTRIP=20
     # CONFIG_NSH_LOGIN is not set
     # CONFIG_NSH_CONSOLE_LOGIN is not set
     
    +#
    +# NxWidgets/NxWM
    +#
    +
     #
     # Platform-specific Support
     #
    -- 
    GitLab
    
    
    From 06e4c4aedd8b97e4e4eb4e84fe8b9849b26d13c2 Mon Sep 17 00:00:00 2001
    From: Juha Niskanen 
    Date: Tue, 25 Apr 2017 08:42:36 -0600
    Subject: [PATCH 581/990] STM32L4: add support for the STM32L496XX family
    
    ---
     arch/arm/include/stm32l4/chip.h               | 23 ++++-
     arch/arm/include/stm32l4/irq.h                |  3 +-
     arch/arm/src/stm32l4/Kconfig                  | 99 +++++++++++++++++--
     arch/arm/src/stm32l4/README.txt               |  5 +-
     arch/arm/src/stm32l4/chip.h                   |  4 +-
     arch/arm/src/stm32l4/chip/stm32l4_i2c.h       | 14 +++
     arch/arm/src/stm32l4/chip/stm32l4_memorymap.h | 46 +++++----
     arch/arm/src/stm32l4/chip/stm32l4_pinmap.h    |  3 +-
     arch/arm/src/stm32l4/chip/stm32l4_syscfg.h    |  3 +-
     arch/arm/src/stm32l4/chip/stm32l4x6xx_rcc.h   |  3 +-
     arch/arm/src/stm32l4/stm32l4_allocateheap.c   | 29 +++---
     arch/arm/src/stm32l4/stm32l4_dma.c            |  3 +-
     arch/arm/src/stm32l4/stm32l4_dma.h            |  3 +-
     arch/arm/src/stm32l4/stm32l4_firewall.h       |  3 +-
     arch/arm/src/stm32l4/stm32l4_gpio.c           |  4 +-
     arch/arm/src/stm32l4/stm32l4_gpio.h           |  3 +-
     arch/arm/src/stm32l4/stm32l4_rcc.c            |  3 +-
     arch/arm/src/stm32l4/stm32l4_rcc.h            |  3 +-
     arch/arm/src/stm32l4/stm32l4_start.c          |  7 +-
     arch/arm/src/stm32l4/stm32l4_uart.h           |  3 +-
     20 files changed, 204 insertions(+), 60 deletions(-)
    
    diff --git a/arch/arm/include/stm32l4/chip.h b/arch/arm/include/stm32l4/chip.h
    index 9d0712b276..f24bf5b7e2 100644
    --- a/arch/arm/include/stm32l4/chip.h
    +++ b/arch/arm/include/stm32l4/chip.h
    @@ -45,7 +45,12 @@
     /************************************************************************************
      * Pre-processor Definitions
      ************************************************************************************/
    -/* STM32F476, STM32F486.  Differences between family members: 486 has AES.
    +/* STM32L476, STM32L486, STM32L496, STM32L4A6
    + *
    + * Differences between family members:
    + *  - L486 has AES
    + *  - L496, L4A6 has 320 Kib SRAM, 2xCAN and CameraIF. Most (all?) of these have I2C4.
    + *  - L4A6 has AES and HASH
      * 
      *   ----------- ---------------- ----- ------ ------ ---- ---- -----
      *   PART        PACKAGE          GPIOs LCD    Tamper FSMC CapS AdcCh
    @@ -56,6 +61,7 @@
      *   STM32L4x6Rx LQFP64             51   8x28   2     No    12   16
      *   STM32L4x6Vx LQFP100            82   8x40   3     Yes   21   16
      *   STM32L4x6Zx LQFP144           114   8x40   3     Yes   24   24
    + *   STM32L4x6Ax UFBGA169          132   8x40   3     Yes   24   24
      *   ----------- ---------------- ----- ------ ------ ---- ---- -----
      *
      * Parts STM32L4x6xC have 256Kb of FLASH
    @@ -66,8 +72,13 @@
      * selection.
      */
     
    +#if defined(CONFIG_STM32L4_STM32L496XX)
    +#  define STM32L4_SRAM1_SIZE       (256*1024)  /* 256Kb SRAM1 on AHB bus Matrix */
    +#  define STM32L4_SRAM2_SIZE       (64*1024)   /* 64Kb  SRAM2 on AHB bus Matrix */
    +#else
     #  define STM32L4_SRAM1_SIZE       (96*1024)   /* 96Kb SRAM1 on AHB bus Matrix */
     #  define STM32L4_SRAM2_SIZE       (32*1024)   /* 32Kb SRAM2 on AHB bus Matrix */
    +#endif
     
     #  define STM32L4_NFSMC                    1   /* Have FSMC memory controller */
     #  define STM32L4_NATIM                    2   /* Two advanced timers TIM1 and 8 */
    @@ -81,14 +92,22 @@
     #  define STM32L4_NUSART                   3   /* USART 1-3 */
     #  define STM32L4_NLPUART                  1   /* LPUART 1 */
     #  define STM32L4_NSPI                     3   /* SPI1-3 */
    +#if defined(CONFIG_STM32L4_STM32L496XX)
    +#  define STM32L4_NI2C                     4   /* I2C1-4 */
    +#else
     #  define STM32L4_NI2C                     3   /* I2C1-3 */
    +#endif
     #  define STM32L4_NUSBOTGFS                1   /* USB OTG FS */
    +#if defined(CONFIG_STM32L4_STM32L496XX)
    +#  define STM32L4_NCAN                     2   /* CAN1-2 */
    +#else
     #  define STM32L4_NCAN                     1   /* CAN1 */
    +#endif
     #  define STM32L4_NSAI                     2   /* SAI1-2 */
     #  define STM32L4_NSDMMC                   1   /* SDMMC interface */
     #  define STM32L4_NDMA                     2   /* DMA1-2 */
     #  define STM32L4_NPORTS                   8   /* 8 GPIO ports, GPIOA-H */
    -#  define STM32L4_NADC                     3   /* 12-bit ADC1-3, 24 channels *except V series) */
    +#  define STM32L4_NADC                     3   /* 12-bit ADC1-3, 24 channels (except V series) */
     #  define STM32L4_NDAC                     2   /* 12-bit DAC1-2 */
     #  define STM32L4_NCRC                     1   /* CRC */
     #  define STM32L4_NCOMP                    2   /* Comparators */
    diff --git a/arch/arm/include/stm32l4/irq.h b/arch/arm/include/stm32l4/irq.h
    index 89e74c1760..abb543bc72 100644
    --- a/arch/arm/include/stm32l4/irq.h
    +++ b/arch/arm/include/stm32l4/irq.h
    @@ -76,7 +76,8 @@
     
     #define STM32L4_IRQ_FIRST         (16) /* Vector number of the first external interrupt */
     
    -#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX)
    +#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX) || \
    +    defined(CONFIG_STM32L4_STM32L496XX)
     #  include 
     #else
     #  error "Unsupported STM32 L4 chip"
    diff --git a/arch/arm/src/stm32l4/Kconfig b/arch/arm/src/stm32l4/Kconfig
    index 68d6ee6806..0a8dceb0fc 100644
    --- a/arch/arm/src/stm32l4/Kconfig
    +++ b/arch/arm/src/stm32l4/Kconfig
    @@ -24,7 +24,7 @@ config ARCH_CHIP_STM32L476RE
     	select STM32L4_STM32L476XX
     	select STM32L4_FLASH_512KB
     	---help---
    -		STM32 L4 Cortex M4, 512 FLASH, 96+32 Kb SRAM
    +		STM32 L4 Cortex M4, 512Kb FLASH, 96+32 Kb SRAM
     
     config ARCH_CHIP_STM32L486
     	bool "STM32L486xx"
    @@ -33,6 +33,29 @@ config ARCH_CHIP_STM32L486
     	---help---
     		STM32 L4 Cortex M4, AES, 1024Kb FLASH, 96+32 Kb SRAM
     
    +config ARCH_CHIP_STM32L496ZE
    +	bool "STM32L496ZE"
    +	select STM32L4_STM32L496XX
    +	select STM32L4_FLASH_512KB
    +	---help---
    +		STM32 L4 Cortex M4, 512Kb FLASH, 320 Kb SRAM
    +
    +config ARCH_CHIP_STM32L496ZG
    +	bool "STM32L496ZG"
    +	select STM32L4_STM32L496XX
    +	select STM32L4_FLASH_1024KB
    +	---help---
    +		STM32 L4 Cortex M4, 1024Kb FLASH, 320 Kb SRAM
    +
    +config ARCH_CHIP_STM32L4A6
    +	bool "STM32L4A6xx"
    +	select STM32L4_STM32L496XX   # Close enough to L496
    +	select STM32L4_FLASH_1024KB
    +	select STM32L4_HAVE_AES
    +	select STM32L4_HAVE_HASH
    +	---help---
    +		STM32 L4 Cortex M4, AES, HASH, 1024Kb FLASH, 320 Kb SRAM
    +
     endchoice # STM32 L4 Chip Selection
     
     # Chip families
    @@ -82,12 +105,25 @@ config STM32L4_STM32L486XX
     	select ARMV7M_HAVE_DTCM
     	select STM32L4_FLASH_1024KB
     
    +config STM32L4_STM32L496XX
    +	bool
    +	default n
    +	select STM32L4_STM32L4X6
    +	select ARCH_HAVE_FPU
    +	select ARCH_HAVE_DPFPU # REVISIT
    +	select ARMV7M_HAVE_ITCM
    +	select ARMV7M_HAVE_DTCM
    +	select STM32L4_HAVE_I2C4
    +	select STM32L4_HAVE_CAN2
    +	select STM32L4_HAVE_DCMI
    +
     choice
     	prompt "Embedded FLASH size"
     	default STM32L4_FLASH_1024KB
     
     config STM32L4_FLASH_256KB
     	bool "256 KB"
    +	depends on !STM32L4_STM32L496XX
     
     config STM32L4_FLASH_512KB
     	bool "512 KB"
    @@ -132,19 +168,39 @@ menu "STM32L4 Peripheral Support"
     # These "hidden" settings determine is a peripheral option is available for the
     # selection MCU
     
    -config STM32L4_HAVE_LTDC
    +config STM32L4_HAVE_AES
     	bool
     	default n
     
    -config STM32L4_HAVE_LPTIM1
    +config STM32L4_HAVE_CAN2
     	bool
     	default n
     
    -config STM32L4_HAVE_LPTIM2
    +config STM32L4_HAVE_COMP
     	bool
     	default n
     
    -config STM32L4_HAVE_COMP
    +config STM32L4_HAVE_DCMI
    +	bool
    +	default n
    +
    +config STM32L4_HAVE_HASH
    +	bool
    +	default n
    +
    +config STM32L4_HAVE_I2C4
    +	bool
    +	default n
    +
    +config STM32L4_HAVE_LTDC
    +	bool
    +	default n
    +
    +config STM32L4_HAVE_LPTIM1
    +	bool
    +	default n
    +
    +config STM32L4_HAVE_LPTIM2
     	bool
     	default n
     
    @@ -244,6 +300,17 @@ config STM32L4_ADC3
     config STM32L4_AES
     	bool "AES"
     	default n
    +	depends on STM32L4_HAVE_AES
    +
    +config STM32L4_DCMI
    +	bool "DCMI"
    +	default n
    +	depends on STM32L4_HAVE_DCMI
    +
    +config STM32L4_HASH
    +	bool "HASH"
    +	default n
    +	depends on STM32L4_HAVE_HASH
     
     config STM32L4_RNG
     	bool "RNG"
    @@ -534,12 +601,25 @@ config STM32L4_I2C3
     	default n
     	select STM32L4_I2C
     
    +config STM32L4_I2C4
    +	bool "I2C4"
    +	default n
    +	select STM32L4_I2C
    +	depends on STM32L4_HAVE_I2C4
    +
     config STM32L4_CAN1
     	bool "CAN1"
     	default n
     	select CAN
     	select STM32L4_CAN
     
    +config STM32L4_CAN2
    +	bool "CAN2"
    +	default n
    +	select CAN
    +	select STM32L4_CAN
    +	depends on STM32L4_HAVE_CAN2
    +
     config STM32L4_DAC1
     	bool "DAC1"
     	default n
    @@ -2865,7 +2945,7 @@ config STM32L4_I2C_DUTY16_9
     endmenu
     
     menu "CAN driver configuration"
    -	depends on STM32L4_CAN1
    +	depends on STM32L4_CAN1 || STM32L4_CAN2
     
     config CAN1_BAUD
     	int "CAN1 BAUD"
    @@ -2874,6 +2954,13 @@ config CAN1_BAUD
     	---help---
     		CAN1 BAUD rate.  Required if CONFIG_STM32L4_CAN1 is defined.
     
    +config CAN2_BAUD
    +	int "CAN2 BAUD"
    +	default 250000
    +	depends on STM32L4_CAN2
    +	---help---
    +		CAN2 BAUD rate.  Required if CONFIG_STM32L4_CAN2 is defined.
    +
     config CAN_TSEG1
     	int "TSEG1 quanta"
     	default 6
    diff --git a/arch/arm/src/stm32l4/README.txt b/arch/arm/src/stm32l4/README.txt
    index 4e1d31f6aa..6b570ededd 100644
    --- a/arch/arm/src/stm32l4/README.txt
    +++ b/arch/arm/src/stm32l4/README.txt
    @@ -27,7 +27,7 @@ DMA      : works; at least tested with QSPI
     SRAM2    : OK; can be included in MM region or left separate for special app purposes
     FIREWALL : Code written, to be tested, requires support from ldscript
     SPI      : Code written, to be tested, including DMA
    -I2C      : Registers defined
    +I2C      : Code written, to be tested (I2C4 missing)
     RTC      : works
     QSPI     : works in polling, interrupt, DMA, and also memory-mapped modes
     CAN      : TODO
    @@ -58,4 +58,5 @@ DFSDM    : TODO (Digital Filter and Sigma-Delta Modulator)
     LCD      : TODO (Segment LCD controller)
     SAIPLL   : works (PLL For Digital Audio interfaces, and other things)
     SAI      : TODO (Digital Audio interfaces, I2S, SPDIF, etc)
    -
    +HASH     : TODO (SHA-1, SHA-224, SHA-256, HMAC)
    +DCMI     : TODO (Digital Camera interfaces)
    diff --git a/arch/arm/src/stm32l4/chip.h b/arch/arm/src/stm32l4/chip.h
    index b4caa13eac..99677fcfc7 100644
    --- a/arch/arm/src/stm32l4/chip.h
    +++ b/arch/arm/src/stm32l4/chip.h
    @@ -53,13 +53,13 @@
     
     /* If the common ARMv7-M vector handling logic is used, then it expects the
      * following definition in this file that provides the number of supported external
    - * interrupts which, for this architecture, is provided in the arch/stm32f7/chip.h
    + * interrupts which, for this architecture, is provided in the arch/stm32l4/chip.h
      * header file.
      */
     
     #define ARMV7M_PERIPHERAL_INTERRUPTS NR_INTERRUPTS
     
    -/* Cache line sizes (in bytes)for the STM32L4 */
    +/* Cache line sizes (in bytes) for the STM32L4 */
     
     #define ARMV7M_DCACHE_LINESIZE 0  /* no cache */
     #define ARMV7M_ICACHE_LINESIZE 0  /* no cache */
    diff --git a/arch/arm/src/stm32l4/chip/stm32l4_i2c.h b/arch/arm/src/stm32l4/chip/stm32l4_i2c.h
    index 02927801fd..a28dad8728 100644
    --- a/arch/arm/src/stm32l4/chip/stm32l4_i2c.h
    +++ b/arch/arm/src/stm32l4/chip/stm32l4_i2c.h
    @@ -98,6 +98,20 @@
     #  define STM32L4_I2C3_TXDR         (STM32L4_I2C3_BASE+STM32L4_I2C_TXDR_OFFSET)
     #endif
     
    +#if STM32L4_NI2C > 3
    +#  define STM32L4_I2C4_CR1          (STM32L4_I2C4_BASE+STM32L4_I2C_CR1_OFFSET)
    +#  define STM32L4_I2C4_CR2          (STM32L4_I2C4_BASE+STM32L4_I2C_CR2_OFFSET)
    +#  define STM32L4_I2C4_OAR1         (STM32L4_I2C4_BASE+STM32L4_I2C_OAR1_OFFSET)
    +#  define STM32L4_I2C4_OAR2         (STM32L4_I2C4_BASE+STM32L4_I2C_OAR2_OFFSET)
    +#  define STM32L4_I2C4_TIMINGR      (STM32L4_I2C4_BASE+STM32L4_I2C_TIMINGR_OFFSET)
    +#  define STM32L4_I2C4_TIMEOUTR     (STM32L4_I2C4_BASE+STM32L4_I2C_TIMEOUTR_OFFSET)
    +#  define STM32L4_I2C4_ISR          (STM32L4_I2C4_BASE+STM32L4_I2C_ISR_OFFSET)
    +#  define STM32L4_I2C4_ICR          (STM32L4_I2C4_BASE+STM32L4_I2C_ICR_OFFSET)
    +#  define STM32L4_I2C4_PECR         (STM32L4_I2C4_BASE+STM32L4_I2C_PECR_OFFSET)
    +#  define STM32L4_I2C4_RXDR         (STM32L4_I2C4_BASE+STM32L4_I2C_RXDR_OFFSET)
    +#  define STM32L4_I2C4_TXDR         (STM32L4_I2C4_BASE+STM32L4_I2C_TXDR_OFFSET)
    +#endif
    +
     /* Register Bitfield Definitions ****************************************************/
     
     /* Control register 1 */
    diff --git a/arch/arm/src/stm32l4/chip/stm32l4_memorymap.h b/arch/arm/src/stm32l4/chip/stm32l4_memorymap.h
    index 99271a7a52..33a9b5bd56 100644
    --- a/arch/arm/src/stm32l4/chip/stm32l4_memorymap.h
    +++ b/arch/arm/src/stm32l4/chip/stm32l4_memorymap.h
    @@ -43,7 +43,7 @@
     /* STM32F40XXX Address Blocks *******************************************************/
     
     #define STM32L4_CODE_BASE      0x00000000     /* 0x00000000-0x1fffffff: 512Mb code block */
    -#define STM32L4_SRAM_BASE      0x20000000     /* 0x20000000-0x3fffffff: 512Mb sram block (96k) */
    +#define STM32L4_SRAM_BASE      0x20000000     /* 0x20000000-0x3fffffff: 512Mb sram block (96k or 256k) */
     #define STM32L4_PERIPH_BASE    0x40000000     /* 0x40000000-0x5fffffff: 512Mb peripheral block */
     #define STM32L4_FSMC_BASE12    0x60000000     /* 0x60000000-0x7fffffff: 512Mb FSMC bank1&2 block */
     #  define STM32L4_FSMC_BANK1   0x60000000     /* 0x60000000-0x6fffffff:   256Mb NOR/SRAM */
    @@ -53,7 +53,7 @@
     #  define STM32L4_QSPI_BANK    0x90000000     /* 0x90000000-0x9fffffff:   256Mb QUADSPI*/
     #define STM32L4_FSMC_BASE      0xa0000000     /* 0xa0000000-0xbfffffff:       FSMC register block */
     #define STM32L4_QSPI_BASE      0xa0001000     /* 0xa0000000-0xbfffffff:       QSPI register block */
    -                                            /* 0xc0000000-0xdfffffff: 512Mb (not used) */
    +                                              /* 0xc0000000-0xdfffffff: 512Mb (not used) */
     #define STM32L4_CORTEX_BASE    0xe0000000     /* 0xe0000000-0xffffffff: 512Mb Cortex-M4 block */
     
     #define STM32L4_REGION_MASK    0xf0000000
    @@ -63,31 +63,33 @@
     /* Code Base Addresses **************************************************************/
     
     #define STM32L4_BOOT_BASE      0x00000000     /* 0x00000000-0x000fffff: Aliased boot memory */
    -                                            /* 0x00100000-0x07ffffff: Reserved */
    +                                              /* 0x00100000-0x07ffffff: Reserved */
     #define STM32L4_FLASH_BASE     0x08000000     /* 0x08000000-0x080fffff: FLASH memory */
    -                                            /* 0x08100000-0x0fffffff: Reserved */
    -#define STM32L4_SRAM2_BASE     0x10000000     /* 0x10000000-0x1000ffff: 32Kb SRAM2 */
    -                                            /* 0x10010000-0x1ffeffff: Reserved */
    +                                              /* 0x08100000-0x0fffffff: Reserved */
    +#define STM32L4_SRAM2_BASE     0x10000000     /* 0x10000000-0x1000ffff: 32Kb or 64Kb SRAM2 */
    +                                              /* 0x10010000-0x1ffeffff: Reserved */
     #define STM32L4_SYSMEM_BASE    0x1fff0000     /* 0x1fff0000-0x1fff7a0f: System memory */
    -                                            /* 0x1fff7a10-0x1fff7fff: Reserved */
    +                                              /* 0x1fff7a10-0x1fff7fff: Reserved */
     #define STM32L4_OPTION_BASE    0x1fffc000     /* 0x1fffc000-0x1fffc007: Option bytes */
    -                                            /* 0x1fffc008-0x1fffffff: Reserved */
    +                                              /* 0x1fffc008-0x1fffffff: Reserved */
     
     /* System Memory Addresses **********************************************************/
     
     #define STM32L4_SYSMEM_UID     0x1fff7590     /* The 96-bit unique device identifier */
     #define STM32L4_SYSMEM_FSIZE   0x1fff75E0     /* This bitfield indicates the size of
    -                                             * the device Flash memory expressed in
    -                                             * Kbytes. Example: 0x0400 corresponds
    -                                             * to 1024 Kbytes.
    -                                             */
    +                                               * the device Flash memory expressed in
    +                                               * Kbytes. Example: 0x0400 corresponds
    +                                               * to 1024 Kbytes.
    +                                               */
     #define STM32L4_SYSMEM_PACKAGE 0x1fff7500     /* This bitfield indicates the package
    -                                             * type.
    -                                             * 0: LQFP64
    -                                             * 2: LQFP100
    -                                             * 3: BGA132
    -                                             * 4: LQFP144, WLCSP81 or WLCSP72
    -                                             */
    +                                               * type.
    +                                               * 0:  LQFP64
    +                                               * 2:  LQFP100
    +                                               * 3:  UFBGA132
    +                                               * 4:  LQFP144, WLCSP81 or WLCSP72
    +                                               * 16: UFBGA169
    +                                               * 17: WLCSP100
    +                                               */
     
     /* SRAM Base Addresses **************************************************************/
     
    @@ -116,11 +118,13 @@
     
     #define STM32L4_LPTIM2_BASE     0x40009400
     #define STM32L4_SWPMI1_BASE     0x40008800
    +#define STM32L4_I2C4_BASE       0x40008400
     #define STM32L4_LPUART1_BASE    0x40008000
     #define STM32L4_LPTIM1_BASE     0x40007c00
     #define STM32L4_OPAMP_BASE      0x40007800
     #define STM32L4_DAC_BASE        0x40007400
     #define STM32L4_PWR_BASE        0x40007000
    +#define STM32L4_CAN2_BASE       0x40006800
     #define STM32L4_CAN1_BASE       0x40006400
     #define STM32L4_I2C3_BASE       0x40005c00
     #define STM32L4_I2C2_BASE       0x40005800
    @@ -163,6 +167,7 @@
     
     /* AHB1 Base Addresses **************************************************************/
     
    +#define STM32L4_DMA2D_BASE      0x4002b000
     #define STM32L4_TSC_BASE        0x40024000
     #define STM32L4_CRC_BASE        0x40023000
     #define STM32L4_FLASHIF_BASE    0x40022000
    @@ -173,10 +178,13 @@
     /* AHB2 Base Addresses **************************************************************/
     
     #define STM32L4_RNG_BASE        0x50060800
    +#define STM32L4_HASH_BASE       0x50060400
     #define STM32L4_AES_BASE        0x50060000
    +#define STM32L4_DCMI_BASE       0x50050000
     #define STM32L4_ADC_BASE        0x50040000
     #define STM32L4_OTGFS_BASE      0x50000000
    -#define STM32L4_GPIOH_BASE      0x50001c00
    +#define STM32L4_GPIOI_BASE      0x48002000
    +#define STM32L4_GPIOH_BASE      0x48001c00
     #define STM32L4_GPIOG_BASE      0x48001800
     #define STM32L4_GPIOF_BASE      0x48001400
     #define STM32L4_GPIOE_BASE      0x48001000
    diff --git a/arch/arm/src/stm32l4/chip/stm32l4_pinmap.h b/arch/arm/src/stm32l4/chip/stm32l4_pinmap.h
    index 0b2b537f1e..28257e1738 100644
    --- a/arch/arm/src/stm32l4/chip/stm32l4_pinmap.h
    +++ b/arch/arm/src/stm32l4/chip/stm32l4_pinmap.h
    @@ -43,7 +43,8 @@
     #include 
     #include "chip.h"
     
    -#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX)
    +#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX) || \
    +    defined(CONFIG_STM32L4_STM32L496XX)
     #  include "chip/stm32l4x6xx_pinmap.h"
     #else
     #  error "Unsupported STM32 L4 pin map"
    diff --git a/arch/arm/src/stm32l4/chip/stm32l4_syscfg.h b/arch/arm/src/stm32l4/chip/stm32l4_syscfg.h
    index 2e34974769..c1ad478751 100644
    --- a/arch/arm/src/stm32l4/chip/stm32l4_syscfg.h
    +++ b/arch/arm/src/stm32l4/chip/stm32l4_syscfg.h
    @@ -43,7 +43,8 @@
     #include 
     #include "chip.h"
     
    -#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX)
    +#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX) || \
    +    defined(CONFIG_STM32L4_STM32L496XX)
     
     /****************************************************************************************************
      * Pre-processor Definitions
    diff --git a/arch/arm/src/stm32l4/chip/stm32l4x6xx_rcc.h b/arch/arm/src/stm32l4/chip/stm32l4x6xx_rcc.h
    index c45c199e9b..2aef6f17d5 100644
    --- a/arch/arm/src/stm32l4/chip/stm32l4x6xx_rcc.h
    +++ b/arch/arm/src/stm32l4/chip/stm32l4x6xx_rcc.h
    @@ -44,7 +44,8 @@
     
     #include 
     
    -#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX)
    +#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX) || \
    +    defined(CONFIG_STM32L4_STM32L496XX)
     
     /****************************************************************************************************
      * Pre-processor Definitions
    diff --git a/arch/arm/src/stm32l4/stm32l4_allocateheap.c b/arch/arm/src/stm32l4/stm32l4_allocateheap.c
    index dc39c59e51..d0134de97f 100644
    --- a/arch/arm/src/stm32l4/stm32l4_allocateheap.c
    +++ b/arch/arm/src/stm32l4/stm32l4_allocateheap.c
    @@ -64,16 +64,17 @@
      * following definitions must be provided to specify the size and
      * location of internal (system) SRAM1 and SRAM2:
      *
    - * SRAM1_END     0x20018000
    + * SRAM1_START   0x20000000
    + * SRAM1_END
      * SRAM2_START   0x10000000
    - * SRAM2_END     0x10008000
    + * SRAM2_END
      *
      * In addition to internal SRAM, memory may also be available through the FSMC.
      * In order to use FSMC SRAM, the following additional things need to be
      * present in the NuttX configuration file:
      *
    - * CONFIG_STM32L4_FSMC=y        : Enables the FSMC
    - * CONFIG_STM32L4_FSMC_SRAM=y   : Indicates that SRAM is available via the
    + * CONFIG_STM32L4_FSMC=y      : Enables the FSMC
    + * CONFIG_STM32L4_FSMC_SRAM=y : Indicates that SRAM is available via the
      *                              FSMC (as opposed to an LCD or FLASH).
      * CONFIG_HEAP2_BASE          : The base address of the SRAM in the FSMC
      *                              address space
    @@ -87,22 +88,28 @@
     #  undef CONFIG_STM32L4_FSMC_SRAM
     #endif
     
    -/* STM32L4x6xx have 128Kib in two banks, both accessible to DMA:
    +/* STM32L4[7,8]6xx have 128 Kib in two banks, both accessible to DMA:
      *
    - *   1) 96KiB of System SRAM beginning at address 0x2000:0000 - 0x2001:8000
    - *   2) 32KiB of System SRAM beginning at address 0x1000:0000 - 0x1000:8000
    + *   1) 96 KiB of System SRAM beginning at address 0x2000:0000 - 0x2001:8000
    + *   2) 32 KiB of System SRAM beginning at address 0x1000:0000 - 0x1000:8000
    + *
    + * STM32L496xx have 320 Kib in two banks, both accessible to DMA:
    + *
    + *   1) 256 KiB of System SRAM beginning at address 0x2000:0000 - 0x2004:0000
    + *   2) 64 KiB of System SRAM beginning at address 0x1000:0000 - 0x1001:0000
      *
      * In addition, external FSMC SRAM may be available.
      */
     
    -/* Set the end of system SRAM */
    +/* Set the range of system SRAM */
     
    -#define SRAM1_END 0x20018000
    +#define SRAM1_START  STM32L4_SRAM_BASE
    +#define SRAM1_END    (SRAM1_START + STM32L4_SRAM1_SIZE)
     
     /* Set the range of SRAM2 as well, requires a second memory region */
     
    -#define SRAM2_START 0x10000000
    -#define SRAM2_END   0x10008000
    +#define SRAM2_START  STM32L4_SRAM2_BASE
    +#define SRAM2_END    (SRAM2_START + STM32L4_SRAM2_SIZE)
     
     #if defined(CONFIG_STM32L4_SRAM2_HEAP) && defined(CONFIG_STM32L4_FSMC_SRAM_HEAP)
     #  if CONFIG_MM_REGIONS < 3
    diff --git a/arch/arm/src/stm32l4/stm32l4_dma.c b/arch/arm/src/stm32l4/stm32l4_dma.c
    index c1b25e64de..d2fd26546e 100644
    --- a/arch/arm/src/stm32l4/stm32l4_dma.c
    +++ b/arch/arm/src/stm32l4/stm32l4_dma.c
    @@ -67,7 +67,8 @@
      * chip.h that can associate an STM32 part number with an STM32 family.
      */
     
    -#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX)
    +#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX) || \
    +    defined(CONFIG_STM32L4_STM32L496XX)
     #include "stm32l4x6xx_dma.c"
     #else
     #  error "Unsupported STM32L4 chip"
    diff --git a/arch/arm/src/stm32l4/stm32l4_dma.h b/arch/arm/src/stm32l4/stm32l4_dma.h
    index c5ccf60b29..89196cb381 100644
    --- a/arch/arm/src/stm32l4/stm32l4_dma.h
    +++ b/arch/arm/src/stm32l4/stm32l4_dma.h
    @@ -49,7 +49,8 @@
     
     /* Include the correct DMA register definitions for this STM32 family */
     
    -#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX)
    +#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX) || \
    +    defined(CONFIG_STM32L4_STM32L496XX)
     #  include "chip/stm32l4x6xx_dma.h"
     #else
     #  error "Unsupported STM32L4 chip"
    diff --git a/arch/arm/src/stm32l4/stm32l4_firewall.h b/arch/arm/src/stm32l4/stm32l4_firewall.h
    index 989e7e3c30..ec667fe5a7 100644
    --- a/arch/arm/src/stm32l4/stm32l4_firewall.h
    +++ b/arch/arm/src/stm32l4/stm32l4_firewall.h
    @@ -47,7 +47,8 @@
     
     /* Include the correct firewall register definitions for this STM32L4 family */
     
    -#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX)
    +#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX) || \
    +    defined(CONFIG_STM32L4_STM32L496XX)
     #  include "chip/stm32l4x6xx_firewall.h"
     #else
     #  error "Unsupported STM32L4 chip"
    diff --git a/arch/arm/src/stm32l4/stm32l4_gpio.c b/arch/arm/src/stm32l4/stm32l4_gpio.c
    index 0c3432d6e4..007c3b8514 100644
    --- a/arch/arm/src/stm32l4/stm32l4_gpio.c
    +++ b/arch/arm/src/stm32l4/stm32l4_gpio.c
    @@ -55,9 +55,7 @@
     #include "chip.h"
     #include "stm32l4_gpio.h"
     
    -#if defined(CONFIG_STM32L4_STM32L478XX) || defined(CONFIG_STM32L4_STM32L486XX)
    -#  include "chip/stm32l4_syscfg.h"
    -#endif
    +#include "chip/stm32l4_syscfg.h"
     
     /****************************************************************************
      * Public Data
    diff --git a/arch/arm/src/stm32l4/stm32l4_gpio.h b/arch/arm/src/stm32l4/stm32l4_gpio.h
    index 5d4f74d58d..f4175d817e 100644
    --- a/arch/arm/src/stm32l4/stm32l4_gpio.h
    +++ b/arch/arm/src/stm32l4/stm32l4_gpio.h
    @@ -54,7 +54,8 @@
     
     #include "chip.h"
     
    -#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX)
    +#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX) || \
    +    defined(CONFIG_STM32L4_STM32L496XX)
     #  include "chip/stm32l4x6xx_gpio.h"
     #else
     #  error "Unsupported STM32L4 chip"
    diff --git a/arch/arm/src/stm32l4/stm32l4_rcc.c b/arch/arm/src/stm32l4/stm32l4_rcc.c
    index 73abae16c5..6d7a240d89 100644
    --- a/arch/arm/src/stm32l4/stm32l4_rcc.c
    +++ b/arch/arm/src/stm32l4/stm32l4_rcc.c
    @@ -78,7 +78,8 @@
     
     /* Include chip-specific clocking initialization logic */
     
    -#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX)
    +#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX) || \
    +    defined(CONFIG_STM32L4_STM32L496XX)
     #  include "stm32l4x6xx_rcc.c"
     #else
     #  error "Unsupported STM32L4 chip"
    diff --git a/arch/arm/src/stm32l4/stm32l4_rcc.h b/arch/arm/src/stm32l4/stm32l4_rcc.h
    index 3dae842de8..33549648c2 100644
    --- a/arch/arm/src/stm32l4/stm32l4_rcc.h
    +++ b/arch/arm/src/stm32l4/stm32l4_rcc.h
    @@ -45,7 +45,8 @@
     #include "up_arch.h"
     #include "chip.h"
     
    -#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX)
    +#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX) || \
    +    defined(CONFIG_STM32L4_STM32L496XX)
     #  include "chip/stm32l4x6xx_rcc.h"
     #else
     #  error "Unsupported STM32L4 chip"
    diff --git a/arch/arm/src/stm32l4/stm32l4_start.c b/arch/arm/src/stm32l4/stm32l4_start.c
    index 1c391851b4..916985cccf 100644
    --- a/arch/arm/src/stm32l4/stm32l4_start.c
    +++ b/arch/arm/src/stm32l4/stm32l4_start.c
    @@ -68,7 +68,6 @@
      *               Mapped as boot memory address 0x0000:0000 at reset.
      * 0x080f:ffff - End of flash region (assuming the max of 2MiB of FLASH).
      * 0x1000:0000 - Start of internal SRAM2
    - * 0x1000:7fff - End of internal SRAM2
      * 0x2000:0000 - Start of internal SRAM and start of .data (_sdata)
      *             - End of .data (_edata) and start of .bss (_sbss)
      *             - End of .bss (_ebss) and bottom of idle stack
    @@ -76,11 +75,11 @@
      *               start of heap. NOTE that the ARM uses a decrement before
      *               store stack so that the correct initial value is the end of
      *               the stack + 4;
    - * 0x2001:7fff - End of internal SRAM and end of heap
      */
     
    -#define SRAM2_START 0x10000000
    -#define SRAM2_END   0x10008000
    +#define SRAM2_START  STM32L4_SRAM2_BASE
    +#define SRAM2_END    (SRAM2_START + STM32L4_SRAM2_SIZE)
    +
     #define IDLE_STACK ((uintptr_t)&_ebss+CONFIG_IDLETHREAD_STACKSIZE-4)
     #define HEAP_BASE  ((uintptr_t)&_ebss+CONFIG_IDLETHREAD_STACKSIZE)
     
    diff --git a/arch/arm/src/stm32l4/stm32l4_uart.h b/arch/arm/src/stm32l4/stm32l4_uart.h
    index e66302d8e4..d6922269fb 100644
    --- a/arch/arm/src/stm32l4/stm32l4_uart.h
    +++ b/arch/arm/src/stm32l4/stm32l4_uart.h
    @@ -44,7 +44,8 @@
     
     #include "chip.h"
     
    -#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX)
    +#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX) || \
    +    defined(CONFIG_STM32L4_STM32L496XX)
     #  include "chip/stm32l4x6xx_uart.h"
     #else
     #  error "Unsupported STM32L4 chip"
    -- 
    GitLab
    
    
    From afea57d43a5a76d498502f0b91fd02abac3aca2f Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Tue, 25 Apr 2017 12:03:27 -0600
    Subject: [PATCH 582/990] Photon: Rename ld.script to photon_jtag.ld for
     symmetry.
    
    ---
     configs/photon/nsh/Make.defs                         | 2 +-
     configs/photon/scripts/photon_dfu.ld                 | 2 +-
     configs/photon/scripts/{ld.script => photon_jtag.ld} | 4 ++--
     configs/photon/usbnsh/Make.defs                      | 2 +-
     configs/photon/wlan/Make.defs                        | 2 +-
     5 files changed, 6 insertions(+), 6 deletions(-)
     rename configs/photon/scripts/{ld.script => photon_jtag.ld} (97%)
    
    diff --git a/configs/photon/nsh/Make.defs b/configs/photon/nsh/Make.defs
    index a3d6f0de35..71af0ab67b 100644
    --- a/configs/photon/nsh/Make.defs
    +++ b/configs/photon/nsh/Make.defs
    @@ -40,7 +40,7 @@ include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
     ifeq ($(CONFIG_PHOTON_DFU_BOOTLOADER),y)
     LDSCRIPT = photon_dfu.ld
     else
    -LDSCRIPT = ld.script
    +LDSCRIPT = photon_jtag.ld
     endif
     
     ifeq ($(WINTOOL),y)
    diff --git a/configs/photon/scripts/photon_dfu.ld b/configs/photon/scripts/photon_dfu.ld
    index 7571d7fe90..1c86142e06 100644
    --- a/configs/photon/scripts/photon_dfu.ld
    +++ b/configs/photon/scripts/photon_dfu.ld
    @@ -33,7 +33,7 @@
      ****************************************************************************/
     
     /* The STM32F205RG has 1024Kb of FLASH beginning at address 0x0800:0000 and
    - * 112Kb of SRAM.
    + * 112Kb of SRAM in main SRAM1 and 16 Kb in auxiliary SRAM2.
      *
      * Bootloader jumps at 0x0802:0000.
      */
    diff --git a/configs/photon/scripts/ld.script b/configs/photon/scripts/photon_jtag.ld
    similarity index 97%
    rename from configs/photon/scripts/ld.script
    rename to configs/photon/scripts/photon_jtag.ld
    index 01309314fe..da1c9fa754 100644
    --- a/configs/photon/scripts/ld.script
    +++ b/configs/photon/scripts/photon_jtag.ld
    @@ -1,5 +1,5 @@
     /****************************************************************************
    - * configs/photon/scripts/ld.script
    + * configs/photon/scripts/photon_jtag.ld
      *
      *   Copyright (C) 2017 Gregory Nutt. All rights reserved.
      *
    @@ -33,7 +33,7 @@
      ****************************************************************************/
     
     /* The STM32F205RG has 1024Kb of FLASH beginning at address 0x0800:0000 and
    - * 112Kb of SRAM.
    + * 112Kb of SRAM in main SRAM1 and 16 Kb in auxiliary SRAM2.
      *
      * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
      * where the code expects to begin execution by jumping to the entry point in
    diff --git a/configs/photon/usbnsh/Make.defs b/configs/photon/usbnsh/Make.defs
    index cb2820a9cb..ee6740097c 100644
    --- a/configs/photon/usbnsh/Make.defs
    +++ b/configs/photon/usbnsh/Make.defs
    @@ -40,7 +40,7 @@ include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
     ifeq ($(CONFIG_PHOTON_DFU_BOOTLOADER),y)
     LDSCRIPT = photon_dfu.ld
     else
    -LDSCRIPT = ld.script
    +LDSCRIPT = photon_jtag.ld
     endif
     
     ifeq ($(WINTOOL),y)
    diff --git a/configs/photon/wlan/Make.defs b/configs/photon/wlan/Make.defs
    index e72c160c3f..b6329421a9 100644
    --- a/configs/photon/wlan/Make.defs
    +++ b/configs/photon/wlan/Make.defs
    @@ -40,7 +40,7 @@ include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
     ifeq ($(CONFIG_PHOTON_DFU_BOOTLOADER),y)
     LDSCRIPT = photon_dfu.ld
     else
    -LDSCRIPT = ld.script
    +LDSCRIPT = photon_jtag.ld
     endif
     
     ifeq ($(WINTOOL),y)
    -- 
    GitLab
    
    
    From ace460ad0eee29ec9a774d7012b387ce8c6ee559 Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Tue, 25 Apr 2017 13:02:50 -0600
    Subject: [PATCH 583/990] configs/photon/src/stm32_wlan.c: Remove unused,
     inappropriate network driver registration.
    
    ---
     configs/photon/src/stm32_wlan.c          | 11 -----------
     drivers/wireless/ieee80211/bcmf_driver.c |  9 +++++++--
     2 files changed, 7 insertions(+), 13 deletions(-)
    
    diff --git a/configs/photon/src/stm32_wlan.c b/configs/photon/src/stm32_wlan.c
    index 2892e7af2a..9e886807e0 100644
    --- a/configs/photon/src/stm32_wlan.c
    +++ b/configs/photon/src/stm32_wlan.c
    @@ -150,16 +150,5 @@ int photon_wlan_initialize()
           return ERROR;
         }
     
    -#if 0 /* Not yet */
    -  /* Register the nework device */
    -
    -  ret = bcmf_netdev_register(0);
    -  if (ret != OK)
    -    {
    -      syslog(LOG_ERR, "Failed to register bcmf network device: %d\n", ret);
    -      return ret;
    -    }
    -#endif
    -
       return OK;
     }
    diff --git a/drivers/wireless/ieee80211/bcmf_driver.c b/drivers/wireless/ieee80211/bcmf_driver.c
    index 5294e5a781..4aafc2b823 100644
    --- a/drivers/wireless/ieee80211/bcmf_driver.c
    +++ b/drivers/wireless/ieee80211/bcmf_driver.c
    @@ -117,10 +117,12 @@ FAR struct bcmf_dev_s* bcmf_allocate_device(void)
         {
           goto exit_free_priv;
         }
    +
       if ((ret = sem_init(&priv->control_timeout, 0, 0)) != OK)
         {
           goto exit_free_priv;
         }
    +
       if ((ret = sem_setprotocol(&priv->control_timeout, SEM_PRIO_NONE)) != OK)
         {
           goto exit_free_priv;
    @@ -165,7 +167,8 @@ int bcmf_dongle_scantime(FAR struct bcmf_dev_s *priv, int32_t scan_assoc_time,
               int32_t scan_unassoc_time, int32_t scan_passive_time)
     {
       int ret;
    -  uint32_t out_len, value;
    +  uint32_t out_len;
    +  uint32_t value;
     
       out_len = 4;
       value = scan_assoc_time;
    @@ -284,7 +287,8 @@ int bcmf_run_escan(FAR struct bcmf_dev_s *priv)
     int bcmf_driver_initialize(FAR struct bcmf_dev_s *priv)
     {
       int ret;
    -  uint32_t out_len, value;
    +  uint32_t out_len;
    +  uint32_t value;
       uint8_t tmp_buf[64];
     
       /* Disable TX Gloming feature */
    @@ -341,6 +345,7 @@ int bcmf_driver_initialize(FAR struct bcmf_dev_s *priv)
         }
     
       /* Remove line feed */
    +
       out_len = strlen((char*)tmp_buf);
       if (out_len > 0 && tmp_buf[out_len-1] == '\n')
         {
    -- 
    GitLab
    
    
    From 1c970254849b317e4b71bb598803a4b4a7c7bfa5 Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Tue, 25 Apr 2017 15:51:30 -0600
    Subject: [PATCH 584/990] netdev_register:  If there is only one ieee80211 and
     both CONFIG_ETHERNET and CONFIG_DRIVERS_IEEE8011, then use the wlan0 naming,
     not the eth0 naming.
    
    ---
     net/netdev/netdev_register.c | 6 +++---
     1 file changed, 3 insertions(+), 3 deletions(-)
    
    diff --git a/net/netdev/netdev_register.c b/net/netdev/netdev_register.c
    index 8da52f9151..745da4f50a 100644
    --- a/net/netdev/netdev_register.c
    +++ b/net/netdev/netdev_register.c
    @@ -70,10 +70,10 @@
     
     #if defined(CONFIG_NET_SLIP)
     #  define NETDEV_DEFAULT_FORMAT NETDEV_SLIP_FORMAT
    +#elif defined(CONFIG_DRIVERS_IEEE80211) /* Usually also has CONFIG_NET_ETHERNET */
    +#  define NETDEV_DEFAULT_FORMAT NETDEV_WLAN_FORMAT
     #elif defined(CONFIG_NET_ETHERNET)
     #  define NETDEV_DEFAULT_FORMAT NETDEV_ETH_FORMAT
    -#elif defined(CONFIG_DRIVERS_IEEE80211)
    -#  define NETDEV_DEFAULT_FORMAT NETDEV_WLAN_FORMAT
     #elif defined(CONFIG_NET_6LOWPAN)
     #  define NETDEV_DEFAULT_FORMAT NETDEV_WPAN_FORMAT
     #else /* if defined(CONFIG_NET_LOOPBACK) */
    @@ -332,7 +332,7 @@ int netdev_register(FAR struct net_driver_s *dev, enum net_lltype_e lltype)
     #endif
           net_unlock();
     
    -#ifdef CONFIG_NET_ETHERNET
    +#if defined(CONFIG_NET_ETHERNET) || defined(CONFIG_DRIVERS_IEEE80211)
           ninfo("Registered MAC: %02x:%02x:%02x:%02x:%02x:%02x as dev: %s\n",
                 dev->d_mac.ether.ether_addr_octet[0], dev->d_mac.ether.ether_addr_octet[1],
                 dev->d_mac.ether.ether_addr_octet[2], dev->d_mac.ether.ether_addr_octet[3],
    -- 
    GitLab
    
    
    From dd2efb909a34ba879e22f005d67941e7aa1e5286 Mon Sep 17 00:00:00 2001
    From: Yasuhiro Osaki 
    Date: Tue, 24 Feb 2015 15:58:12 +0900
    Subject: [PATCH 585/990] binfmt: Fix offset value when calling elf_read() in
     elf_symname()
    
    Jira: PDFW15IS-1650
    Signed-off-by: Masayuki Ishikawa 
    ---
     binfmt/libelf/libelf_symbols.c | 2 +-
     1 file changed, 1 insertion(+), 1 deletion(-)
    
    diff --git a/binfmt/libelf/libelf_symbols.c b/binfmt/libelf/libelf_symbols.c
    index ba67034e54..b93bdfdb3a 100644
    --- a/binfmt/libelf/libelf_symbols.c
    +++ b/binfmt/libelf/libelf_symbols.c
    @@ -126,7 +126,7 @@ static int elf_symname(FAR struct elf_loadinfo_s *loadinfo,
           /* Read that number of bytes into the array */
     
           buffer = &loadinfo->iobuffer[bytesread];
    -      ret = elf_read(loadinfo, buffer, readlen, offset);
    +      ret = elf_read(loadinfo, buffer, readlen, offset + bytesread);
           if (ret < 0)
             {
               berr("elf_read failed: %d\n", ret);
    -- 
    GitLab
    
    
    From 232fbf7f008b0695fee7a2389fae51579b3d467f Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Wed, 26 Apr 2017 07:45:40 -0600
    Subject: [PATCH 586/990] CONFIG_DEBUG_HARDFAULT should be available for
     Cortex-M0 too.  configs/nucle-f072rb/nsh: Correct amount of available SRAM in
     defconfig.
    
    ---
     arch/arm/Kconfig                    | 2 +-
     configs/nucleo-f072rb/nsh/defconfig | 2 +-
     2 files changed, 2 insertions(+), 2 deletions(-)
    
    diff --git a/arch/arm/Kconfig b/arch/arm/Kconfig
    index b7ccb129b3..c71fc98773 100644
    --- a/arch/arm/Kconfig
    +++ b/arch/arm/Kconfig
    @@ -618,7 +618,7 @@ config ARCH_ROMPGTABLE
     config DEBUG_HARDFAULT
     	bool "Verbose Hard-Fault Debug"
     	default n
    -	depends on DEBUG_FEATURES && (ARCH_CORTEXM3 || ARCH_CORTEXM4 || ARCH_CORTEXM7)
    +	depends on DEBUG_FEATURES && (ARCH_CORTEXM0 || ARCH_CORTEXM3 || ARCH_CORTEXM4 || ARCH_CORTEXM7)
     	---help---
     		Enables verbose debug output when a hard fault is occurs.  This verbose
     		output is sometimes helpful when debugging difficult hard fault problems,
    diff --git a/configs/nucleo-f072rb/nsh/defconfig b/configs/nucleo-f072rb/nsh/defconfig
    index 946a2edad2..ebce1f4dc3 100644
    --- a/configs/nucleo-f072rb/nsh/defconfig
    +++ b/configs/nucleo-f072rb/nsh/defconfig
    @@ -391,7 +391,7 @@ CONFIG_BOOT_RUNFROMFLASH=y
     # Boot Memory Configuration
     #
     CONFIG_RAM_START=0x20000000
    -CONFIG_RAM_SIZE=8192
    +CONFIG_RAM_SIZE=16384
     # CONFIG_ARCH_HAVE_SDRAM is not set
     
     #
    -- 
    GitLab
    
    
    From 1620ff05f4e5d5e7cc285a7b6ae1d1c84d4f9b38 Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Wed, 26 Apr 2017 07:49:37 -0600
    Subject: [PATCH 587/990] Remove all setenv.sh files.
    
    ---
     configs/amber/hello/setenv.sh                 |  63 -----------
     configs/arduino-due/nsh/setenv.sh             |  78 --------------
     configs/arduino-mega2560/hello/setenv.sh      |  64 -----------
     configs/arduino-mega2560/nsh/setenv.sh        |  64 -----------
     configs/avr32dev1/nsh/setenv.sh               |  57 ----------
     configs/avr32dev1/ostest/setenv.sh            |  57 ----------
     configs/bambino-200e/netnsh/setenv.sh         |  96 -----------------
     configs/bambino-200e/nsh/setenv.sh            |  96 -----------------
     configs/bambino-200e/usbnsh/setenv.sh         |  96 -----------------
     configs/c5471evm/httpd/setenv.sh              |  73 -------------
     configs/c5471evm/nettest/setenv.sh            |  73 -------------
     configs/c5471evm/nsh/setenv.sh                |  73 -------------
     configs/cc3200-launchpad/nsh/setenv.sh        |  75 -------------
     configs/clicker2-stm32/nsh/setenv.sh          |  80 --------------
     configs/clicker2-stm32/usbnsh/setenv.sh       |  80 --------------
     configs/cloudctrl/nsh/setenv.sh               |  78 --------------
     configs/demo9s12ne64/ostest/setenv.sh         |  46 --------
     configs/dk-tm4c129x/ipv6/setenv.sh            |  75 -------------
     configs/dk-tm4c129x/nsh/setenv.sh             |  75 -------------
     configs/ea3131/nsh/setenv.sh                  |  66 ------------
     configs/ea3131/pgnsh/setenv.sh                |  66 ------------
     configs/ea3131/usbserial/setenv.sh            |  66 ------------
     configs/ea3152/ostest/setenv.sh               |  66 ------------
     configs/eagle100/httpd/setenv.sh              |  76 -------------
     configs/eagle100/nettest/setenv.sh            |  63 -----------
     configs/eagle100/nsh/setenv.sh                |  62 -----------
     configs/eagle100/nxflat/setenv.sh             |  76 -------------
     configs/eagle100/thttpd/setenv.sh             |  76 -------------
     configs/efm32-g8xx-stk/nsh/setenv.sh          |  63 -----------
     configs/efm32gg-stk3700/nsh/setenv.sh         |  63 -----------
     configs/ekk-lm3s9b96/nsh/setenv.sh            |  64 -----------
     configs/esp32-core/nsh/setenv.sh              |  57 ----------
     configs/esp32-core/ostest/setenv.sh           |  57 ----------
     configs/esp32-core/smp/setenv.sh              |  57 ----------
     configs/ez80f910200kitg/ostest/setenv.sh      |  64 -----------
     configs/ez80f910200zco/dhcpd/setenv.sh        |  64 -----------
     configs/ez80f910200zco/httpd/setenv.sh        |  64 -----------
     configs/ez80f910200zco/nettest/setenv.sh      |  64 -----------
     configs/ez80f910200zco/nsh/setenv.sh          |  64 -----------
     configs/ez80f910200zco/poll/setenv.sh         |  64 -----------
     configs/fire-stm32v2/nsh/setenv.sh            |  78 --------------
     configs/freedom-k64f/netnsh/setenv.sh         |  77 --------------
     configs/freedom-k64f/nsh/setenv.sh            |  77 --------------
     configs/freedom-k66f/netnsh/setenv.sh         |  77 --------------
     configs/freedom-k66f/nsh/setenv.sh            |  77 --------------
     configs/freedom-kl25z/nsh/setenv.sh           |  75 -------------
     configs/freedom-kl26z/nsh/setenv.sh           |  71 -------------
     configs/hymini-stm32v/nsh/setenv.sh           |  47 --------
     configs/hymini-stm32v/nsh2/setenv.sh          |  67 ------------
     configs/hymini-stm32v/usbmsc/setenv.sh        |  47 --------
     configs/hymini-stm32v/usbnsh/setenv.sh        |  47 --------
     configs/hymini-stm32v/usbserial/setenv.sh     |  47 --------
     configs/kwikstik-k40/ostest/setenv.sh         |  61 -----------
     configs/launchxl-tms57004/nsh/setenv.sh       |  77 --------------
     configs/lincoln60/netnsh/setenv.sh            |  73 -------------
     configs/lincoln60/nsh/setenv.sh               |  73 -------------
     configs/lincoln60/thttpd-binfs/setenv.sh      |  73 -------------
     configs/lm3s6432-s2e/nsh/setenv.sh            |  46 --------
     configs/lm3s6965-ek/discover/setenv.sh        |  71 -------------
     configs/lm3s6965-ek/nsh/setenv.sh             |  70 ------------
     configs/lm3s6965-ek/nx/setenv.sh              |  70 ------------
     configs/lm3s6965-ek/tcpecho/setenv.sh         |  70 ------------
     configs/lm3s8962-ek/nsh/setenv.sh             |  63 -----------
     configs/lm3s8962-ek/nx/setenv.sh              |  62 -----------
     configs/lm4f120-launchpad/nsh/setenv.sh       |  74 -------------
     configs/lpc4330-xplorer/nsh/setenv.sh         |  91 ----------------
     configs/lpc4337-ws/nsh/setenv.sh              |  92 ----------------
     configs/lpc4357-evb/nsh/setenv.sh             |  92 ----------------
     configs/lpc4370-link2/nsh/setenv.sh           |  92 ----------------
     configs/lpcxpresso-lpc1115/nsh/setenv.sh      |  72 -------------
     configs/lpcxpresso-lpc1768/dhcpd/setenv.sh    |  59 -----------
     configs/lpcxpresso-lpc1768/nsh/setenv.sh      |  59 -----------
     configs/lpcxpresso-lpc1768/nx/setenv.sh       |  59 -----------
     configs/lpcxpresso-lpc1768/thttpd/setenv.sh   |  61 -----------
     configs/lpcxpresso-lpc1768/usbmsc/setenv.sh   |  59 -----------
     configs/maple/nsh/setenv.sh                   |  63 -----------
     configs/maple/nx/setenv.sh                    |  63 -----------
     configs/maple/usbnsh/setenv.sh                |  63 -----------
     configs/mbed/nsh/setenv.sh                    |  47 --------
     configs/mcu123-lpc214x/composite/setenv.sh    |  66 ------------
     configs/mcu123-lpc214x/nsh/setenv.sh          |  73 -------------
     configs/mcu123-lpc214x/usbmsc/setenv.sh       |  73 -------------
     configs/mcu123-lpc214x/usbserial/setenv.sh    |  73 -------------
     configs/micropendous3/hello/setenv.sh         |  63 -----------
     configs/mikroe-stm32f4/fulldemo/setenv.sh     |  76 -------------
     configs/mikroe-stm32f4/kostest/setenv.sh      |  76 -------------
     configs/mikroe-stm32f4/nsh/setenv.sh          |  75 -------------
     configs/mikroe-stm32f4/nx/setenv.sh           |  76 -------------
     configs/mikroe-stm32f4/nxlines/setenv.sh      |  76 -------------
     configs/mikroe-stm32f4/nxtext/setenv.sh       |  76 -------------
     configs/mikroe-stm32f4/usbnsh/setenv.sh       |  76 -------------
     configs/mirtoo/nsh/setenv.sh                  |  80 --------------
     configs/mirtoo/nxffs/setenv.sh                |  80 --------------
     configs/misoc/hello/setenv.sh                 |  58 ----------
     configs/misoc/nsh/setenv.sh                   |  58 ----------
     configs/moteino-mega/hello/setenv.sh          |  63 -----------
     configs/moteino-mega/nsh/setenv.sh            |  63 -----------
     configs/moxa/nsh/setenv.sh                    |  83 ---------------
     configs/mx1ads/ostest/setenv.sh               |  46 --------
     configs/ne64badge/ostest/setenv.sh            |  46 --------
     configs/nr5m100-nexys4/nsh/setenv.sh          |  45 --------
     configs/ntosd-dm320/nettest/setenv.sh         |  63 -----------
     configs/ntosd-dm320/nsh/setenv.sh             |  63 -----------
     configs/ntosd-dm320/poll/setenv.sh            |  63 -----------
     configs/ntosd-dm320/thttpd/setenv.sh          |  63 -----------
     configs/ntosd-dm320/udp/setenv.sh             |  63 -----------
     configs/ntosd-dm320/webserver/setenv.sh       |  63 -----------
     configs/nucleo-144/f746-evalos/setenv.sh      |  78 --------------
     configs/nucleo-144/f746-nsh/setenv.sh         |  77 --------------
     configs/nucleo-144/f767-evalos/setenv.sh      |  78 --------------
     configs/nucleo-144/f767-nsh/setenv.sh         |  77 --------------
     configs/nucleo-f072rb/nsh/setenv.sh           |  81 --------------
     configs/nucleo-f334r8/adc/setenv.sh           |  77 --------------
     configs/nucleo-f334r8/nsh/setenv.sh           |  77 --------------
     configs/nucleo-f4x1re/f401-nsh/setenv.sh      |  64 -----------
     configs/nucleo-f4x1re/f411-nsh/setenv.sh      |  64 -----------
     configs/nucleo-l476rg/nsh/setenv.sh           |  64 -----------
     configs/nutiny-nuc120/nsh/setenv.sh           |  75 -------------
     .../olimex-efm32g880f128-stk/nsh/setenv.sh    |  63 -----------
     configs/olimex-lpc-h3131/nsh/setenv.sh        |  67 ------------
     configs/olimex-lpc1766stk/ftpc/setenv.sh      |  75 -------------
     configs/olimex-lpc1766stk/hidmouse/setenv.sh  |  67 ------------
     configs/olimex-lpc1766stk/nettest/setenv.sh   |  76 -------------
     configs/olimex-lpc1766stk/nsh/setenv.sh       |  75 -------------
     configs/olimex-lpc1766stk/nx/setenv.sh        |  75 -------------
     .../olimex-lpc1766stk/slip-httpd/setenv.sh    |  75 -------------
     .../olimex-lpc1766stk/thttpd-binfs/setenv.sh  |  83 ---------------
     .../olimex-lpc1766stk/thttpd-nxflat/setenv.sh |  83 ---------------
     configs/olimex-lpc1766stk/usbmsc/setenv.sh    |  75 -------------
     configs/olimex-lpc1766stk/usbserial/setenv.sh |  75 -------------
     configs/olimex-lpc1766stk/zmodem/setenv.sh    |  75 -------------
     configs/olimex-lpc2378/nsh/setenv.sh          |  68 ------------
     configs/olimex-stm32-e407/discover/setenv.sh  |  80 --------------
     configs/olimex-stm32-e407/netnsh/setenv.sh    |  80 --------------
     configs/olimex-stm32-e407/nsh/setenv.sh       |  80 --------------
     configs/olimex-stm32-e407/telnetd/setenv.sh   |  80 --------------
     configs/olimex-stm32-e407/usbnsh/setenv.sh    |  80 --------------
     configs/olimex-stm32-e407/webserver/setenv.sh |  80 --------------
     configs/olimex-stm32-h405/usbnsh/setenv.sh    |  75 -------------
     configs/olimex-stm32-h407/nsh/setenv.sh       |  80 --------------
     configs/olimex-stm32-p107/nsh/setenv.sh       |  76 -------------
     configs/olimex-stm32-p207/nsh/setenv.sh       |  75 -------------
     configs/olimex-stm32-p407/knsh/setenv.sh      |  80 --------------
     configs/olimex-stm32-p407/nsh/setenv.sh       |  80 --------------
     configs/olimex-strp711/nettest/setenv.sh      |  72 -------------
     configs/olimex-strp711/nsh/setenv.sh          |  47 --------
     configs/olimexino-stm32/can/setenv.sh         |  80 --------------
     configs/olimexino-stm32/composite/setenv.sh   |  80 --------------
     configs/olimexino-stm32/nsh/setenv.sh         |  80 --------------
     configs/olimexino-stm32/smallnsh/setenv.sh    |  80 --------------
     configs/olimexino-stm32/tiny/setenv.sh        |  80 --------------
     configs/open1788/knsh/setenv.sh               |  73 -------------
     configs/open1788/nsh/setenv.sh                |  73 -------------
     configs/open1788/nxlines/setenv.sh            |  73 -------------
     configs/p112/scripts/setenv.sh                |  66 ------------
     configs/pcblogic-pic32mx/nsh/setenv.sh        |  61 -----------
     configs/pcduino-a10/nsh/setenv.sh             |  77 --------------
     configs/photon/nsh/setenv.sh                  |  84 ---------------
     configs/photon/usbnsh/setenv.sh               |  84 ---------------
     configs/pic32mx-starterkit/nsh/setenv.sh      |  66 ------------
     configs/pic32mx-starterkit/nsh2/setenv.sh     |  66 ------------
     configs/pic32mx7mmb/nsh/setenv.sh             |  61 -----------
     configs/pic32mz-starterkit/nsh/setenv.sh      |  68 ------------
     configs/qemu-i486/nsh/setenv.sh               |  48 ---------
     configs/qemu-i486/ostest/setenv.sh            |  48 ---------
     configs/sabre-6quad/nsh/setenv.sh             |  77 --------------
     configs/sabre-6quad/smp/setenv.sh             |  77 --------------
     configs/sam3u-ek/knsh/setenv.sh               |  75 -------------
     configs/sam3u-ek/nsh/setenv.sh                |  74 -------------
     configs/sam3u-ek/nx/setenv.sh                 |  74 -------------
     configs/sam3u-ek/nxwm/setenv.sh               |  74 -------------
     configs/sam4cmp-db/nsh/setenv.sh              |  73 -------------
     configs/sam4e-ek/nsh/setenv.sh                |  69 ------------
     configs/sam4e-ek/nxwm/setenv.sh               |  69 ------------
     configs/sam4e-ek/usbnsh/setenv.sh             |  69 ------------
     configs/sam4l-xplained/nsh/setenv.sh          |  74 -------------
     configs/sam4s-xplained-pro/nsh/setenv.sh      |  73 -------------
     configs/sam4s-xplained/nsh/setenv.sh          |  73 -------------
     configs/sama5d2-xult/nsh/setenv.sh            |  81 --------------
     configs/sama5d3-xplained/bridge/setenv.sh     |  77 --------------
     configs/sama5d3-xplained/nsh/setenv.sh        |  77 --------------
     configs/sama5d3x-ek/demo/setenv.sh            |  77 --------------
     configs/sama5d3x-ek/hello/setenv.sh           |  77 --------------
     configs/sama5d3x-ek/norboot/setenv.sh         |  77 --------------
     configs/sama5d3x-ek/nsh/setenv.sh             |  77 --------------
     configs/sama5d3x-ek/nx/setenv.sh              |  77 --------------
     configs/sama5d3x-ek/nxplayer/setenv.sh        |  77 --------------
     configs/sama5d3x-ek/nxwm/setenv.sh            |  77 --------------
     configs/sama5d3x-ek/ov2640/setenv.sh          |  77 --------------
     configs/sama5d4-ek/at25boot/setenv.sh         |  77 --------------
     configs/sama5d4-ek/bridge/setenv.sh           |  77 --------------
     configs/sama5d4-ek/dramboot/setenv.sh         |  77 --------------
     configs/sama5d4-ek/elf/setenv.sh              |  77 --------------
     configs/sama5d4-ek/ipv6/setenv.sh             |  77 --------------
     configs/sama5d4-ek/knsh/setenv.sh             |  77 --------------
     configs/sama5d4-ek/nsh/setenv.sh              |  77 --------------
     configs/sama5d4-ek/nxwm/setenv.sh             |  77 --------------
     configs/sama5d4-ek/ramtest/setenv.sh          |  77 --------------
     configs/samd20-xplained/nsh/setenv.sh         |  76 -------------
     configs/samd21-xplained/nsh/setenv.sh         |  84 ---------------
     configs/same70-xplained/netnsh/setenv.sh      |  77 --------------
     configs/same70-xplained/nsh/setenv.sh         |  80 --------------
     configs/saml21-xplained/nsh/setenv.sh         |  77 --------------
     configs/samv71-xult/knsh/setenv.sh            |  77 --------------
     configs/samv71-xult/module/setenv.sh          |  77 --------------
     configs/samv71-xult/mxtxplnd/setenv.sh        |  77 --------------
     configs/samv71-xult/netnsh/setenv.sh          |  77 --------------
     configs/samv71-xult/nsh/setenv.sh             |  77 --------------
     configs/samv71-xult/nxwm/setenv.sh            |  77 --------------
     configs/samv71-xult/vnc/setenv.sh             |  77 --------------
     configs/samv71-xult/vnxwm/setenv.sh           |  77 --------------
     configs/shenzhou/nsh/setenv.sh                |  78 --------------
     configs/shenzhou/nxwm/setenv.sh               |  78 --------------
     configs/shenzhou/thttpd/setenv.sh             |  78 --------------
     configs/sim/bas/setenv.sh                     |  45 --------
     configs/sim/configdata/setenv.sh              |  55 ----------
     configs/sim/cxxtest/setenv.sh                 |  45 --------
     configs/sim/minibasic/setenv.sh               |  45 --------
     configs/sim/mount/setenv.sh                   |  45 --------
     configs/sim/mtdpart/setenv.sh                 |  45 --------
     configs/sim/mtdrwb/setenv.sh                  |  45 --------
     configs/sim/nettest/setenv.sh                 |  45 --------
     configs/sim/nsh/setenv.sh                     |  45 --------
     configs/sim/nsh2/setenv.sh                    |  45 --------
     configs/sim/nx/setenv.sh                      |  45 --------
     configs/sim/nx11/setenv.sh                    |  45 --------
     configs/sim/nxffs/setenv.sh                   |  45 --------
     configs/sim/nxlines/setenv.sh                 |  53 ----------
     configs/sim/nxwm/setenv.sh                    |  45 --------
     configs/sim/ostest/setenv.sh                  |  45 --------
     configs/sim/pashello/setenv.sh                |  45 --------
     configs/sim/sixlowpan/setenv.sh               |  45 --------
     configs/sim/touchscreen/setenv.sh             |  45 --------
     configs/sim/traveler/setenv.sh                |  45 --------
     configs/sim/udgram/setenv.sh                  |  45 --------
     configs/sim/unionfs/setenv.sh                 |  45 --------
     configs/sim/ustream/setenv.sh                 |  45 --------
     configs/skp16c26/ostest/setenv.sh             |  46 --------
     configs/spark/composite/setenv.sh             |  67 ------------
     configs/spark/nsh/setenv.sh                   |  63 -----------
     configs/spark/usbmsc/setenv.sh                |  63 -----------
     configs/spark/usbnsh/setenv.sh                |  63 -----------
     configs/spark/usbserial/setenv.sh             |  67 ------------
     configs/stm3210e-eval/composite/setenv.sh     |  67 ------------
     configs/stm3210e-eval/nsh/setenv.sh           |  76 -------------
     configs/stm3210e-eval/nsh2/setenv.sh          |  67 ------------
     configs/stm3210e-eval/nx/setenv.sh            |  62 -----------
     configs/stm3210e-eval/nxterm/setenv.sh        |  62 -----------
     configs/stm3210e-eval/pm/setenv.sh            |  67 ------------
     configs/stm3210e-eval/usbmsc/setenv.sh        |  47 --------
     configs/stm3210e-eval/usbserial/setenv.sh     |  47 --------
     configs/stm3220g-eval/dhcpd/setenv.sh         |  75 -------------
     configs/stm3220g-eval/nettest/setenv.sh       |  75 -------------
     configs/stm3220g-eval/nsh/setenv.sh           |  75 -------------
     configs/stm3220g-eval/nsh2/setenv.sh          |  74 -------------
     configs/stm3220g-eval/nxwm/setenv.sh          |  75 -------------
     configs/stm3220g-eval/telnetd/setenv.sh       |  75 -------------
     configs/stm3240g-eval/dhcpd/setenv.sh         |  76 -------------
     configs/stm3240g-eval/discover/setenv.sh      |  76 -------------
     configs/stm3240g-eval/knxwm/setenv.sh         |  72 -------------
     configs/stm3240g-eval/nettest/setenv.sh       |  76 -------------
     configs/stm3240g-eval/nsh/setenv.sh           |  76 -------------
     configs/stm3240g-eval/nsh2/setenv.sh          |  76 -------------
     configs/stm3240g-eval/nxterm/setenv.sh        |  76 -------------
     configs/stm3240g-eval/nxwm/setenv.sh          |  72 -------------
     configs/stm3240g-eval/telnetd/setenv.sh       |  76 -------------
     configs/stm3240g-eval/webserver/setenv.sh     |  76 -------------
     configs/stm3240g-eval/xmlrpc/setenv.sh        |  76 -------------
     configs/stm32_tiny/nsh/setenv.sh              |  47 --------
     configs/stm32_tiny/usbnsh/setenv.sh           |  47 --------
     configs/stm32butterfly2/nsh/setenv.sh         |  78 --------------
     configs/stm32butterfly2/nshnet/setenv.sh      |  78 --------------
     configs/stm32butterfly2/nshusbdev/setenv.sh   |  78 --------------
     configs/stm32butterfly2/nshusbhost/setenv.sh  |  78 --------------
     configs/stm32f0discovery/nsh/setenv.sh        |  81 --------------
     .../stm32f103-minimum/audio_tone/setenv.sh    | 100 ------------------
     configs/stm32f103-minimum/buttons/setenv.sh   | 100 ------------------
     configs/stm32f103-minimum/jlx12864g/setenv.sh | 100 ------------------
     configs/stm32f103-minimum/nrf24/setenv.sh     | 100 ------------------
     configs/stm32f103-minimum/nsh/setenv.sh       | 100 ------------------
     configs/stm32f103-minimum/pwm/setenv.sh       | 100 ------------------
     .../stm32f103-minimum/rfid-rc522/setenv.sh    | 100 ------------------
     configs/stm32f103-minimum/rgbled/setenv.sh    | 100 ------------------
     configs/stm32f103-minimum/usbnsh/setenv.sh    |  72 -------------
     configs/stm32f103-minimum/userled/setenv.sh   | 100 ------------------
     configs/stm32f103-minimum/veml6070/setenv.sh  | 100 ------------------
     configs/stm32f3discovery/nsh/setenv.sh        |  75 -------------
     configs/stm32f3discovery/usbnsh/setenv.sh     |  75 -------------
     configs/stm32f411e-disco/nsh/setenv.sh        |  68 ------------
     configs/stm32f429i-disco/extflash/setenv.sh   |  77 --------------
     configs/stm32f429i-disco/lcd/setenv.sh        |  77 --------------
     configs/stm32f429i-disco/ltdc/setenv.sh       |  77 --------------
     configs/stm32f429i-disco/nsh/setenv.sh        |  77 --------------
     configs/stm32f429i-disco/nxwm/setenv.sh       |  80 --------------
     configs/stm32f429i-disco/usbmsc/setenv.sh     |  77 --------------
     configs/stm32f429i-disco/usbnsh/setenv.sh     |  77 --------------
     configs/stm32f4discovery/canard/setenv.sh     |  80 --------------
     configs/stm32f4discovery/cxxtest/setenv.sh    |  81 --------------
     configs/stm32f4discovery/elf/setenv.sh        |  84 ---------------
     configs/stm32f4discovery/ipv6/setenv.sh       |  81 --------------
     configs/stm32f4discovery/kostest/setenv.sh    |  80 --------------
     configs/stm32f4discovery/netnsh/setenv.sh     |  81 --------------
     configs/stm32f4discovery/nsh/setenv.sh        |  80 --------------
     configs/stm32f4discovery/nxlines/setenv.sh    |  80 --------------
     configs/stm32f4discovery/pm/setenv.sh         |  80 --------------
     .../stm32f4discovery/posix_spawn/setenv.sh    |  84 ---------------
     configs/stm32f4discovery/pseudoterm/setenv.sh |  80 --------------
     configs/stm32f4discovery/rgbled/setenv.sh     |  80 --------------
     configs/stm32f4discovery/usbnsh/setenv.sh     |  80 --------------
     configs/stm32f4discovery/xen1210/setenv.sh    |  80 --------------
     configs/stm32f746-ws/nsh/setenv.sh            |  77 --------------
     configs/stm32f746g-disco/nsh/setenv.sh        |  77 --------------
     configs/stm32l476-mdk/nsh/setenv.sh           |  64 -----------
     configs/stm32l476vg-disco/nsh/setenv.sh       |  64 -----------
     configs/stm32ldiscovery/nsh/setenv.sh         |  75 -------------
     configs/stm32vldiscovery/nsh/setenv.sh        |  76 -------------
     configs/sure-pic32mx/nsh/setenv.sh            |  61 -----------
     configs/sure-pic32mx/usbnsh/setenv.sh         |  61 -----------
     configs/teensy-2.0/hello/setenv.sh            |  68 ------------
     configs/teensy-2.0/nsh/setenv.sh              |  68 ------------
     configs/teensy-2.0/usbmsc/setenv.sh           |  68 ------------
     configs/teensy-3.x/nsh/setenv.sh              |  80 --------------
     configs/teensy-3.x/usbnsh/setenv.sh           |  76 -------------
     configs/teensy-lc/nsh/setenv.sh               |  75 -------------
     configs/tm4c123g-launchpad/nsh/setenv.sh      |  75 -------------
     configs/tm4c1294-launchpad/ipv6/setenv.sh     |  75 -------------
     configs/tm4c1294-launchpad/nsh/setenv.sh      |  75 -------------
     configs/twr-k60n512/nsh/setenv.sh             |  61 -----------
     configs/twr-k64f120m/netnsh/setenv.sh         |  61 -----------
     configs/twr-k64f120m/nsh/setenv.sh            |  61 -----------
     configs/u-blox-c027/nsh/setenv.sh             |  59 -----------
     configs/ubw32/nsh/setenv.sh                   |  61 -----------
     configs/us7032evb1/nsh/setenv.sh              |  47 --------
     configs/us7032evb1/ostest/setenv.sh           |  47 --------
     configs/viewtool-stm32f107/highpri/setenv.sh  |  77 --------------
     configs/viewtool-stm32f107/netnsh/setenv.sh   |  77 --------------
     configs/viewtool-stm32f107/nsh/setenv.sh      |  78 --------------
     configs/xmc4500-relax/nsh/setenv.sh           |  77 --------------
     configs/xtrs/scripts/setenv.sh                |  72 -------------
     configs/z16f2800100zcog/nsh/setenv.sh         |  70 ------------
     configs/z16f2800100zcog/ostest/setenv.sh      |  69 ------------
     configs/z16f2800100zcog/pashello/setenv.sh    |  69 ------------
     configs/z80sim/scripts/setenv.sh              |  66 ------------
     configs/z8encore000zco/ostest/setenv.sh       |  64 -----------
     configs/z8f64200100kit/ostest/setenv.sh       |  64 -----------
     configs/zkit-arm-1769/hello/setenv.sh         |  72 -------------
     configs/zkit-arm-1769/nsh/setenv.sh           |  72 -------------
     configs/zkit-arm-1769/nxhello/setenv.sh       |  72 -------------
     configs/zkit-arm-1769/thttpd/setenv.sh        |  72 -------------
     configs/zp214xpa/nsh/setenv.sh                |  65 ------------
     configs/zp214xpa/nxlines/setenv.sh            |  65 ------------
     351 files changed, 24735 deletions(-)
     delete mode 100755 configs/amber/hello/setenv.sh
     delete mode 100755 configs/arduino-due/nsh/setenv.sh
     delete mode 100755 configs/arduino-mega2560/hello/setenv.sh
     delete mode 100755 configs/arduino-mega2560/nsh/setenv.sh
     delete mode 100755 configs/avr32dev1/nsh/setenv.sh
     delete mode 100755 configs/avr32dev1/ostest/setenv.sh
     delete mode 100644 configs/bambino-200e/netnsh/setenv.sh
     delete mode 100644 configs/bambino-200e/nsh/setenv.sh
     delete mode 100644 configs/bambino-200e/usbnsh/setenv.sh
     delete mode 100755 configs/c5471evm/httpd/setenv.sh
     delete mode 100755 configs/c5471evm/nettest/setenv.sh
     delete mode 100755 configs/c5471evm/nsh/setenv.sh
     delete mode 100755 configs/cc3200-launchpad/nsh/setenv.sh
     delete mode 100644 configs/clicker2-stm32/nsh/setenv.sh
     delete mode 100644 configs/clicker2-stm32/usbnsh/setenv.sh
     delete mode 100755 configs/cloudctrl/nsh/setenv.sh
     delete mode 100755 configs/demo9s12ne64/ostest/setenv.sh
     delete mode 100755 configs/dk-tm4c129x/ipv6/setenv.sh
     delete mode 100755 configs/dk-tm4c129x/nsh/setenv.sh
     delete mode 100755 configs/ea3131/nsh/setenv.sh
     delete mode 100755 configs/ea3131/pgnsh/setenv.sh
     delete mode 100755 configs/ea3131/usbserial/setenv.sh
     delete mode 100755 configs/ea3152/ostest/setenv.sh
     delete mode 100755 configs/eagle100/httpd/setenv.sh
     delete mode 100755 configs/eagle100/nettest/setenv.sh
     delete mode 100755 configs/eagle100/nsh/setenv.sh
     delete mode 100755 configs/eagle100/nxflat/setenv.sh
     delete mode 100755 configs/eagle100/thttpd/setenv.sh
     delete mode 100755 configs/efm32-g8xx-stk/nsh/setenv.sh
     delete mode 100755 configs/efm32gg-stk3700/nsh/setenv.sh
     delete mode 100755 configs/ekk-lm3s9b96/nsh/setenv.sh
     delete mode 100644 configs/esp32-core/nsh/setenv.sh
     delete mode 100644 configs/esp32-core/ostest/setenv.sh
     delete mode 100755 configs/esp32-core/smp/setenv.sh
     delete mode 100755 configs/ez80f910200kitg/ostest/setenv.sh
     delete mode 100755 configs/ez80f910200zco/dhcpd/setenv.sh
     delete mode 100755 configs/ez80f910200zco/httpd/setenv.sh
     delete mode 100755 configs/ez80f910200zco/nettest/setenv.sh
     delete mode 100755 configs/ez80f910200zco/nsh/setenv.sh
     delete mode 100755 configs/ez80f910200zco/poll/setenv.sh
     delete mode 100755 configs/fire-stm32v2/nsh/setenv.sh
     delete mode 100644 configs/freedom-k64f/netnsh/setenv.sh
     delete mode 100644 configs/freedom-k64f/nsh/setenv.sh
     delete mode 100644 configs/freedom-k66f/netnsh/setenv.sh
     delete mode 100644 configs/freedom-k66f/nsh/setenv.sh
     delete mode 100755 configs/freedom-kl25z/nsh/setenv.sh
     delete mode 100755 configs/freedom-kl26z/nsh/setenv.sh
     delete mode 100755 configs/hymini-stm32v/nsh/setenv.sh
     delete mode 100755 configs/hymini-stm32v/nsh2/setenv.sh
     delete mode 100755 configs/hymini-stm32v/usbmsc/setenv.sh
     delete mode 100755 configs/hymini-stm32v/usbnsh/setenv.sh
     delete mode 100755 configs/hymini-stm32v/usbserial/setenv.sh
     delete mode 100755 configs/kwikstik-k40/ostest/setenv.sh
     delete mode 100755 configs/launchxl-tms57004/nsh/setenv.sh
     delete mode 100755 configs/lincoln60/netnsh/setenv.sh
     delete mode 100755 configs/lincoln60/nsh/setenv.sh
     delete mode 100755 configs/lincoln60/thttpd-binfs/setenv.sh
     delete mode 100755 configs/lm3s6432-s2e/nsh/setenv.sh
     delete mode 100755 configs/lm3s6965-ek/discover/setenv.sh
     delete mode 100755 configs/lm3s6965-ek/nsh/setenv.sh
     delete mode 100755 configs/lm3s6965-ek/nx/setenv.sh
     delete mode 100755 configs/lm3s6965-ek/tcpecho/setenv.sh
     delete mode 100755 configs/lm3s8962-ek/nsh/setenv.sh
     delete mode 100755 configs/lm3s8962-ek/nx/setenv.sh
     delete mode 100755 configs/lm4f120-launchpad/nsh/setenv.sh
     delete mode 100755 configs/lpc4330-xplorer/nsh/setenv.sh
     delete mode 100755 configs/lpc4337-ws/nsh/setenv.sh
     delete mode 100755 configs/lpc4357-evb/nsh/setenv.sh
     delete mode 100755 configs/lpc4370-link2/nsh/setenv.sh
     delete mode 100755 configs/lpcxpresso-lpc1115/nsh/setenv.sh
     delete mode 100755 configs/lpcxpresso-lpc1768/dhcpd/setenv.sh
     delete mode 100755 configs/lpcxpresso-lpc1768/nsh/setenv.sh
     delete mode 100755 configs/lpcxpresso-lpc1768/nx/setenv.sh
     delete mode 100755 configs/lpcxpresso-lpc1768/thttpd/setenv.sh
     delete mode 100755 configs/lpcxpresso-lpc1768/usbmsc/setenv.sh
     delete mode 100755 configs/maple/nsh/setenv.sh
     delete mode 100755 configs/maple/nx/setenv.sh
     delete mode 100755 configs/maple/usbnsh/setenv.sh
     delete mode 100755 configs/mbed/nsh/setenv.sh
     delete mode 100755 configs/mcu123-lpc214x/composite/setenv.sh
     delete mode 100755 configs/mcu123-lpc214x/nsh/setenv.sh
     delete mode 100755 configs/mcu123-lpc214x/usbmsc/setenv.sh
     delete mode 100755 configs/mcu123-lpc214x/usbserial/setenv.sh
     delete mode 100755 configs/micropendous3/hello/setenv.sh
     delete mode 100755 configs/mikroe-stm32f4/fulldemo/setenv.sh
     delete mode 100755 configs/mikroe-stm32f4/kostest/setenv.sh
     delete mode 100755 configs/mikroe-stm32f4/nsh/setenv.sh
     delete mode 100755 configs/mikroe-stm32f4/nx/setenv.sh
     delete mode 100755 configs/mikroe-stm32f4/nxlines/setenv.sh
     delete mode 100755 configs/mikroe-stm32f4/nxtext/setenv.sh
     delete mode 100755 configs/mikroe-stm32f4/usbnsh/setenv.sh
     delete mode 100755 configs/mirtoo/nsh/setenv.sh
     delete mode 100755 configs/mirtoo/nxffs/setenv.sh
     delete mode 100644 configs/misoc/hello/setenv.sh
     delete mode 100644 configs/misoc/nsh/setenv.sh
     delete mode 100755 configs/moteino-mega/hello/setenv.sh
     delete mode 100755 configs/moteino-mega/nsh/setenv.sh
     delete mode 100755 configs/moxa/nsh/setenv.sh
     delete mode 100755 configs/mx1ads/ostest/setenv.sh
     delete mode 100755 configs/ne64badge/ostest/setenv.sh
     delete mode 100644 configs/nr5m100-nexys4/nsh/setenv.sh
     delete mode 100755 configs/ntosd-dm320/nettest/setenv.sh
     delete mode 100755 configs/ntosd-dm320/nsh/setenv.sh
     delete mode 100755 configs/ntosd-dm320/poll/setenv.sh
     delete mode 100755 configs/ntosd-dm320/thttpd/setenv.sh
     delete mode 100755 configs/ntosd-dm320/udp/setenv.sh
     delete mode 100755 configs/ntosd-dm320/webserver/setenv.sh
     delete mode 100644 configs/nucleo-144/f746-evalos/setenv.sh
     delete mode 100644 configs/nucleo-144/f746-nsh/setenv.sh
     delete mode 100644 configs/nucleo-144/f767-evalos/setenv.sh
     delete mode 100644 configs/nucleo-144/f767-nsh/setenv.sh
     delete mode 100644 configs/nucleo-f072rb/nsh/setenv.sh
     delete mode 100644 configs/nucleo-f334r8/adc/setenv.sh
     delete mode 100644 configs/nucleo-f334r8/nsh/setenv.sh
     delete mode 100755 configs/nucleo-f4x1re/f401-nsh/setenv.sh
     delete mode 100755 configs/nucleo-f4x1re/f411-nsh/setenv.sh
     delete mode 100755 configs/nucleo-l476rg/nsh/setenv.sh
     delete mode 100755 configs/nutiny-nuc120/nsh/setenv.sh
     delete mode 100755 configs/olimex-efm32g880f128-stk/nsh/setenv.sh
     delete mode 100755 configs/olimex-lpc-h3131/nsh/setenv.sh
     delete mode 100755 configs/olimex-lpc1766stk/ftpc/setenv.sh
     delete mode 100755 configs/olimex-lpc1766stk/hidmouse/setenv.sh
     delete mode 100755 configs/olimex-lpc1766stk/nettest/setenv.sh
     delete mode 100755 configs/olimex-lpc1766stk/nsh/setenv.sh
     delete mode 100755 configs/olimex-lpc1766stk/nx/setenv.sh
     delete mode 100755 configs/olimex-lpc1766stk/slip-httpd/setenv.sh
     delete mode 100755 configs/olimex-lpc1766stk/thttpd-binfs/setenv.sh
     delete mode 100755 configs/olimex-lpc1766stk/thttpd-nxflat/setenv.sh
     delete mode 100755 configs/olimex-lpc1766stk/usbmsc/setenv.sh
     delete mode 100755 configs/olimex-lpc1766stk/usbserial/setenv.sh
     delete mode 100755 configs/olimex-lpc1766stk/zmodem/setenv.sh
     delete mode 100755 configs/olimex-lpc2378/nsh/setenv.sh
     delete mode 100755 configs/olimex-stm32-e407/discover/setenv.sh
     delete mode 100755 configs/olimex-stm32-e407/netnsh/setenv.sh
     delete mode 100755 configs/olimex-stm32-e407/nsh/setenv.sh
     delete mode 100755 configs/olimex-stm32-e407/telnetd/setenv.sh
     delete mode 100755 configs/olimex-stm32-e407/usbnsh/setenv.sh
     delete mode 100755 configs/olimex-stm32-e407/webserver/setenv.sh
     delete mode 100755 configs/olimex-stm32-h405/usbnsh/setenv.sh
     delete mode 100755 configs/olimex-stm32-h407/nsh/setenv.sh
     delete mode 100755 configs/olimex-stm32-p107/nsh/setenv.sh
     delete mode 100755 configs/olimex-stm32-p207/nsh/setenv.sh
     delete mode 100644 configs/olimex-stm32-p407/knsh/setenv.sh
     delete mode 100644 configs/olimex-stm32-p407/nsh/setenv.sh
     delete mode 100755 configs/olimex-strp711/nettest/setenv.sh
     delete mode 100755 configs/olimex-strp711/nsh/setenv.sh
     delete mode 100755 configs/olimexino-stm32/can/setenv.sh
     delete mode 100755 configs/olimexino-stm32/composite/setenv.sh
     delete mode 100755 configs/olimexino-stm32/nsh/setenv.sh
     delete mode 100755 configs/olimexino-stm32/smallnsh/setenv.sh
     delete mode 100755 configs/olimexino-stm32/tiny/setenv.sh
     delete mode 100755 configs/open1788/knsh/setenv.sh
     delete mode 100755 configs/open1788/nsh/setenv.sh
     delete mode 100755 configs/open1788/nxlines/setenv.sh
     delete mode 100755 configs/p112/scripts/setenv.sh
     delete mode 100755 configs/pcblogic-pic32mx/nsh/setenv.sh
     delete mode 100755 configs/pcduino-a10/nsh/setenv.sh
     delete mode 100755 configs/photon/nsh/setenv.sh
     delete mode 100755 configs/photon/usbnsh/setenv.sh
     delete mode 100755 configs/pic32mx-starterkit/nsh/setenv.sh
     delete mode 100755 configs/pic32mx-starterkit/nsh2/setenv.sh
     delete mode 100755 configs/pic32mx7mmb/nsh/setenv.sh
     delete mode 100755 configs/pic32mz-starterkit/nsh/setenv.sh
     delete mode 100755 configs/qemu-i486/nsh/setenv.sh
     delete mode 100755 configs/qemu-i486/ostest/setenv.sh
     delete mode 100755 configs/sabre-6quad/nsh/setenv.sh
     delete mode 100644 configs/sabre-6quad/smp/setenv.sh
     delete mode 100755 configs/sam3u-ek/knsh/setenv.sh
     delete mode 100755 configs/sam3u-ek/nsh/setenv.sh
     delete mode 100755 configs/sam3u-ek/nx/setenv.sh
     delete mode 100755 configs/sam3u-ek/nxwm/setenv.sh
     delete mode 100644 configs/sam4cmp-db/nsh/setenv.sh
     delete mode 100755 configs/sam4e-ek/nsh/setenv.sh
     delete mode 100755 configs/sam4e-ek/nxwm/setenv.sh
     delete mode 100755 configs/sam4e-ek/usbnsh/setenv.sh
     delete mode 100755 configs/sam4l-xplained/nsh/setenv.sh
     delete mode 100755 configs/sam4s-xplained-pro/nsh/setenv.sh
     delete mode 100755 configs/sam4s-xplained/nsh/setenv.sh
     delete mode 100755 configs/sama5d2-xult/nsh/setenv.sh
     delete mode 100755 configs/sama5d3-xplained/bridge/setenv.sh
     delete mode 100755 configs/sama5d3-xplained/nsh/setenv.sh
     delete mode 100755 configs/sama5d3x-ek/demo/setenv.sh
     delete mode 100755 configs/sama5d3x-ek/hello/setenv.sh
     delete mode 100755 configs/sama5d3x-ek/norboot/setenv.sh
     delete mode 100755 configs/sama5d3x-ek/nsh/setenv.sh
     delete mode 100755 configs/sama5d3x-ek/nx/setenv.sh
     delete mode 100755 configs/sama5d3x-ek/nxplayer/setenv.sh
     delete mode 100755 configs/sama5d3x-ek/nxwm/setenv.sh
     delete mode 100755 configs/sama5d3x-ek/ov2640/setenv.sh
     delete mode 100755 configs/sama5d4-ek/at25boot/setenv.sh
     delete mode 100755 configs/sama5d4-ek/bridge/setenv.sh
     delete mode 100755 configs/sama5d4-ek/dramboot/setenv.sh
     delete mode 100755 configs/sama5d4-ek/elf/setenv.sh
     delete mode 100755 configs/sama5d4-ek/ipv6/setenv.sh
     delete mode 100755 configs/sama5d4-ek/knsh/setenv.sh
     delete mode 100755 configs/sama5d4-ek/nsh/setenv.sh
     delete mode 100755 configs/sama5d4-ek/nxwm/setenv.sh
     delete mode 100755 configs/sama5d4-ek/ramtest/setenv.sh
     delete mode 100755 configs/samd20-xplained/nsh/setenv.sh
     delete mode 100755 configs/samd21-xplained/nsh/setenv.sh
     delete mode 100755 configs/same70-xplained/netnsh/setenv.sh
     delete mode 100755 configs/same70-xplained/nsh/setenv.sh
     delete mode 100755 configs/saml21-xplained/nsh/setenv.sh
     delete mode 100755 configs/samv71-xult/knsh/setenv.sh
     delete mode 100755 configs/samv71-xult/module/setenv.sh
     delete mode 100755 configs/samv71-xult/mxtxplnd/setenv.sh
     delete mode 100755 configs/samv71-xult/netnsh/setenv.sh
     delete mode 100755 configs/samv71-xult/nsh/setenv.sh
     delete mode 100755 configs/samv71-xult/nxwm/setenv.sh
     delete mode 100644 configs/samv71-xult/vnc/setenv.sh
     delete mode 100644 configs/samv71-xult/vnxwm/setenv.sh
     delete mode 100755 configs/shenzhou/nsh/setenv.sh
     delete mode 100755 configs/shenzhou/nxwm/setenv.sh
     delete mode 100755 configs/shenzhou/thttpd/setenv.sh
     delete mode 100755 configs/sim/bas/setenv.sh
     delete mode 100755 configs/sim/configdata/setenv.sh
     delete mode 100755 configs/sim/cxxtest/setenv.sh
     delete mode 100644 configs/sim/minibasic/setenv.sh
     delete mode 100755 configs/sim/mount/setenv.sh
     delete mode 100755 configs/sim/mtdpart/setenv.sh
     delete mode 100755 configs/sim/mtdrwb/setenv.sh
     delete mode 100755 configs/sim/nettest/setenv.sh
     delete mode 100755 configs/sim/nsh/setenv.sh
     delete mode 100755 configs/sim/nsh2/setenv.sh
     delete mode 100755 configs/sim/nx/setenv.sh
     delete mode 100755 configs/sim/nx11/setenv.sh
     delete mode 100755 configs/sim/nxffs/setenv.sh
     delete mode 100755 configs/sim/nxlines/setenv.sh
     delete mode 100755 configs/sim/nxwm/setenv.sh
     delete mode 100755 configs/sim/ostest/setenv.sh
     delete mode 100755 configs/sim/pashello/setenv.sh
     delete mode 100644 configs/sim/sixlowpan/setenv.sh
     delete mode 100755 configs/sim/touchscreen/setenv.sh
     delete mode 100755 configs/sim/traveler/setenv.sh
     delete mode 100755 configs/sim/udgram/setenv.sh
     delete mode 100755 configs/sim/unionfs/setenv.sh
     delete mode 100755 configs/sim/ustream/setenv.sh
     delete mode 100755 configs/skp16c26/ostest/setenv.sh
     delete mode 100755 configs/spark/composite/setenv.sh
     delete mode 100755 configs/spark/nsh/setenv.sh
     delete mode 100755 configs/spark/usbmsc/setenv.sh
     delete mode 100755 configs/spark/usbnsh/setenv.sh
     delete mode 100755 configs/spark/usbserial/setenv.sh
     delete mode 100755 configs/stm3210e-eval/composite/setenv.sh
     delete mode 100755 configs/stm3210e-eval/nsh/setenv.sh
     delete mode 100755 configs/stm3210e-eval/nsh2/setenv.sh
     delete mode 100755 configs/stm3210e-eval/nx/setenv.sh
     delete mode 100755 configs/stm3210e-eval/nxterm/setenv.sh
     delete mode 100755 configs/stm3210e-eval/pm/setenv.sh
     delete mode 100755 configs/stm3210e-eval/usbmsc/setenv.sh
     delete mode 100755 configs/stm3210e-eval/usbserial/setenv.sh
     delete mode 100755 configs/stm3220g-eval/dhcpd/setenv.sh
     delete mode 100755 configs/stm3220g-eval/nettest/setenv.sh
     delete mode 100755 configs/stm3220g-eval/nsh/setenv.sh
     delete mode 100755 configs/stm3220g-eval/nsh2/setenv.sh
     delete mode 100755 configs/stm3220g-eval/nxwm/setenv.sh
     delete mode 100755 configs/stm3220g-eval/telnetd/setenv.sh
     delete mode 100755 configs/stm3240g-eval/dhcpd/setenv.sh
     delete mode 100755 configs/stm3240g-eval/discover/setenv.sh
     delete mode 100755 configs/stm3240g-eval/knxwm/setenv.sh
     delete mode 100755 configs/stm3240g-eval/nettest/setenv.sh
     delete mode 100755 configs/stm3240g-eval/nsh/setenv.sh
     delete mode 100755 configs/stm3240g-eval/nsh2/setenv.sh
     delete mode 100755 configs/stm3240g-eval/nxterm/setenv.sh
     delete mode 100755 configs/stm3240g-eval/nxwm/setenv.sh
     delete mode 100755 configs/stm3240g-eval/telnetd/setenv.sh
     delete mode 100755 configs/stm3240g-eval/webserver/setenv.sh
     delete mode 100755 configs/stm3240g-eval/xmlrpc/setenv.sh
     delete mode 100755 configs/stm32_tiny/nsh/setenv.sh
     delete mode 100755 configs/stm32_tiny/usbnsh/setenv.sh
     delete mode 100755 configs/stm32butterfly2/nsh/setenv.sh
     delete mode 100755 configs/stm32butterfly2/nshnet/setenv.sh
     delete mode 100755 configs/stm32butterfly2/nshusbdev/setenv.sh
     delete mode 100755 configs/stm32butterfly2/nshusbhost/setenv.sh
     delete mode 100644 configs/stm32f0discovery/nsh/setenv.sh
     delete mode 100644 configs/stm32f103-minimum/audio_tone/setenv.sh
     delete mode 100644 configs/stm32f103-minimum/buttons/setenv.sh
     delete mode 100644 configs/stm32f103-minimum/jlx12864g/setenv.sh
     delete mode 100644 configs/stm32f103-minimum/nrf24/setenv.sh
     delete mode 100644 configs/stm32f103-minimum/nsh/setenv.sh
     delete mode 100644 configs/stm32f103-minimum/pwm/setenv.sh
     delete mode 100644 configs/stm32f103-minimum/rfid-rc522/setenv.sh
     delete mode 100644 configs/stm32f103-minimum/rgbled/setenv.sh
     delete mode 100644 configs/stm32f103-minimum/usbnsh/setenv.sh
     delete mode 100644 configs/stm32f103-minimum/userled/setenv.sh
     delete mode 100644 configs/stm32f103-minimum/veml6070/setenv.sh
     delete mode 100755 configs/stm32f3discovery/nsh/setenv.sh
     delete mode 100755 configs/stm32f3discovery/usbnsh/setenv.sh
     delete mode 100755 configs/stm32f411e-disco/nsh/setenv.sh
     delete mode 100755 configs/stm32f429i-disco/extflash/setenv.sh
     delete mode 100755 configs/stm32f429i-disco/lcd/setenv.sh
     delete mode 100755 configs/stm32f429i-disco/ltdc/setenv.sh
     delete mode 100755 configs/stm32f429i-disco/nsh/setenv.sh
     delete mode 100644 configs/stm32f429i-disco/nxwm/setenv.sh
     delete mode 100755 configs/stm32f429i-disco/usbmsc/setenv.sh
     delete mode 100755 configs/stm32f429i-disco/usbnsh/setenv.sh
     delete mode 100755 configs/stm32f4discovery/canard/setenv.sh
     delete mode 100755 configs/stm32f4discovery/cxxtest/setenv.sh
     delete mode 100755 configs/stm32f4discovery/elf/setenv.sh
     delete mode 100755 configs/stm32f4discovery/ipv6/setenv.sh
     delete mode 100755 configs/stm32f4discovery/kostest/setenv.sh
     delete mode 100755 configs/stm32f4discovery/netnsh/setenv.sh
     delete mode 100755 configs/stm32f4discovery/nsh/setenv.sh
     delete mode 100755 configs/stm32f4discovery/nxlines/setenv.sh
     delete mode 100755 configs/stm32f4discovery/pm/setenv.sh
     delete mode 100755 configs/stm32f4discovery/posix_spawn/setenv.sh
     delete mode 100644 configs/stm32f4discovery/pseudoterm/setenv.sh
     delete mode 100755 configs/stm32f4discovery/rgbled/setenv.sh
     delete mode 100755 configs/stm32f4discovery/usbnsh/setenv.sh
     delete mode 100644 configs/stm32f4discovery/xen1210/setenv.sh
     delete mode 100644 configs/stm32f746-ws/nsh/setenv.sh
     delete mode 100755 configs/stm32f746g-disco/nsh/setenv.sh
     delete mode 100755 configs/stm32l476-mdk/nsh/setenv.sh
     delete mode 100755 configs/stm32l476vg-disco/nsh/setenv.sh
     delete mode 100755 configs/stm32ldiscovery/nsh/setenv.sh
     delete mode 100755 configs/stm32vldiscovery/nsh/setenv.sh
     delete mode 100755 configs/sure-pic32mx/nsh/setenv.sh
     delete mode 100755 configs/sure-pic32mx/usbnsh/setenv.sh
     delete mode 100755 configs/teensy-2.0/hello/setenv.sh
     delete mode 100755 configs/teensy-2.0/nsh/setenv.sh
     delete mode 100755 configs/teensy-2.0/usbmsc/setenv.sh
     delete mode 100755 configs/teensy-3.x/nsh/setenv.sh
     delete mode 100755 configs/teensy-3.x/usbnsh/setenv.sh
     delete mode 100755 configs/teensy-lc/nsh/setenv.sh
     delete mode 100755 configs/tm4c123g-launchpad/nsh/setenv.sh
     delete mode 100755 configs/tm4c1294-launchpad/ipv6/setenv.sh
     delete mode 100755 configs/tm4c1294-launchpad/nsh/setenv.sh
     delete mode 100755 configs/twr-k60n512/nsh/setenv.sh
     delete mode 100755 configs/twr-k64f120m/netnsh/setenv.sh
     delete mode 100755 configs/twr-k64f120m/nsh/setenv.sh
     delete mode 100755 configs/u-blox-c027/nsh/setenv.sh
     delete mode 100755 configs/ubw32/nsh/setenv.sh
     delete mode 100755 configs/us7032evb1/nsh/setenv.sh
     delete mode 100755 configs/us7032evb1/ostest/setenv.sh
     delete mode 100755 configs/viewtool-stm32f107/highpri/setenv.sh
     delete mode 100755 configs/viewtool-stm32f107/netnsh/setenv.sh
     delete mode 100755 configs/viewtool-stm32f107/nsh/setenv.sh
     delete mode 100644 configs/xmc4500-relax/nsh/setenv.sh
     delete mode 100755 configs/xtrs/scripts/setenv.sh
     delete mode 100755 configs/z16f2800100zcog/nsh/setenv.sh
     delete mode 100755 configs/z16f2800100zcog/ostest/setenv.sh
     delete mode 100755 configs/z16f2800100zcog/pashello/setenv.sh
     delete mode 100755 configs/z80sim/scripts/setenv.sh
     delete mode 100755 configs/z8encore000zco/ostest/setenv.sh
     delete mode 100755 configs/z8f64200100kit/ostest/setenv.sh
     delete mode 100755 configs/zkit-arm-1769/hello/setenv.sh
     delete mode 100755 configs/zkit-arm-1769/nsh/setenv.sh
     delete mode 100755 configs/zkit-arm-1769/nxhello/setenv.sh
     delete mode 100755 configs/zkit-arm-1769/thttpd/setenv.sh
     delete mode 100755 configs/zp214xpa/nsh/setenv.sh
     delete mode 100755 configs/zp214xpa/nxlines/setenv.sh
    
    diff --git a/configs/amber/hello/setenv.sh b/configs/amber/hello/setenv.sh
    deleted file mode 100755
    index dc97e70b62..0000000000
    --- a/configs/amber/hello/setenv.sh
    +++ /dev/null
    @@ -1,63 +0,0 @@
    -#!/bin/bash
    -# configs/amber/hello/setenv.sh
    -#
    -#   Copyright (C) 2011 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the WinAVR
    -# toolchain under windows.  This is *not* the default install
    -# location so you will probably have to edit this.  You will also have
    -# to edit this if you install the Linux AVR toolchain as well
    -#export TOOLCHAIN_BIN="/cygdrive/c/WinAVR/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_avr/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/arduino-due/nsh/setenv.sh b/configs/arduino-due/nsh/setenv.sh
    deleted file mode 100755
    index d35b22620e..0000000000
    --- a/configs/arduino-due/nsh/setenv.sh
    +++ /dev/null
    @@ -1,78 +0,0 @@
    -#!/bin/bash
    -# configs/arduino-due/nsh/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the Cygwin path to the location where I have the Arduino BOSSA program
    -export BOSSA_BIN="/cygdrive/c/Program Files (x86)/Arduino/arduino-1.5.2/hardware/tools"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${BOSSA_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/arduino-mega2560/hello/setenv.sh b/configs/arduino-mega2560/hello/setenv.sh
    deleted file mode 100755
    index 3f4dd93a5a..0000000000
    --- a/configs/arduino-mega2560/hello/setenv.sh
    +++ /dev/null
    @@ -1,64 +0,0 @@
    -#!/bin/bash
    -# configs/arduino-mega2560/hello/setenv.sh
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the WinAVR
    -# toolchain under windows.  This is *not* the default install
    -# location so you will probably have to edit this.  You will also have
    -# to edit this if you install the Linux AVR toolchain as well
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Studio/7.0/toolchain/avr8/avr8-gnu-toolchain/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/as-7/7.0/toolchain/avr8/avr8-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_avr/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="/sbin:/usr/sbin:${PATH_ORIG}:${TOOLCHAIN_BIN}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/arduino-mega2560/nsh/setenv.sh b/configs/arduino-mega2560/nsh/setenv.sh
    deleted file mode 100755
    index 3bab94237f..0000000000
    --- a/configs/arduino-mega2560/nsh/setenv.sh
    +++ /dev/null
    @@ -1,64 +0,0 @@
    -#!/bin/bash
    -# configs/arduino-mega2560/nsh/setenv.sh
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the WinAVR
    -# toolchain under windows.  This is *not* the default install
    -# location so you will probably have to edit this.  You will also have
    -# to edit this if you install the Linux AVR toolchain as well
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Studio/7.0/toolchain/avr8/avr8-gnu-toolchain/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/as-7/7.0/toolchain/avr8/avr8-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_avr/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="/sbin:/usr/sbin:${PATH_ORIG}:${TOOLCHAIN_BIN}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/avr32dev1/nsh/setenv.sh b/configs/avr32dev1/nsh/setenv.sh
    deleted file mode 100755
    index b3ab164ad4..0000000000
    --- a/configs/avr32dev1/nsh/setenv.sh
    +++ /dev/null
    @@ -1,57 +0,0 @@
    -#!/bin/bash
    -# configs/avr32dev1/nsh/setenv.sh
    -#
    -#   Copyright (C) 2010 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -#
    -# This PATH setup assumes that you are using versin 2.1.4 of the Atmel
    -# AVR GNU tools installed at the default location on Windows.  NOTE
    -# that the path is in appended to the end of the PATH variable; this is
    -# because there are also many GNUWin32 binaries there that conflict with
    -# Cygwin versions.
    -#
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -
    -export AVR32_BIN="/cygdrive/c/Program Files/Atmel/AVR Tools/AVR32 Toolchain/bin/"
    -export FLIP_BIN="/cygdrive/c/Program Files/Atmel/Flip 3.4.2/bin"
    -export AVR32DEV1_BIN="${WD}/configs/avr32dev1/tools"
    -export PATH="${FLIP_BIN}:${AVR32DEV1_BIN}:/sbin:/usr/sbin:${PATH_ORIG}:${AVR32_BIN}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/avr32dev1/ostest/setenv.sh b/configs/avr32dev1/ostest/setenv.sh
    deleted file mode 100755
    index 3c3bfcc408..0000000000
    --- a/configs/avr32dev1/ostest/setenv.sh
    +++ /dev/null
    @@ -1,57 +0,0 @@
    -#!/bin/bash
    -# configs/avr32dev1/ostest/setenv.sh
    -#
    -#   Copyright (C) 2010 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -#
    -# This PATH setup assumes that you are using versin 2.1.4 of the Atmel
    -# AVR GNU tools installed at the default location on Windows.  NOTE
    -# that the path is in appended to the end of the PATH variable; this is
    -# because there are also many GNUWin32 binaries there that conflict with
    -# Cygwin versions.
    -#
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -
    -export AVR32_BIN="/cygdrive/c/Program Files/Atmel/AVR Tools/AVR32 Toolchain/bin/"
    -export FLIP_BIN="/cygdrive/c/Program Files/Atmel/Flip 3.4.2/bin"
    -export AVR32DEV1_BIN="${WD}/configs/avr32dev1/tools"
    -export PATH="${FLIP_BIN}:${AVR32DEV1_BIN}:/sbin:/usr/sbin:${PATH_ORIG}:${AVR32_BIN}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/bambino-200e/netnsh/setenv.sh b/configs/bambino-200e/netnsh/setenv.sh
    deleted file mode 100644
    index f2115b5991..0000000000
    --- a/configs/bambino-200e/netnsh/setenv.sh
    +++ /dev/null
    @@ -1,96 +0,0 @@
    -#!/bin/bash
    -# configs/bambino-200e/nsh/setenv.sh
    -#
    -#   Copyright (C) 2017 Gregory Nutt. All rights reserved.
    -#   Author: Gregory Nutt 
    -#           Alan Carvalho de Assis acassis@gmail.com [nuttx] 
    -#
    -# 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Code Red
    -# toolchain under windows.  You will have to edit this if you install the
    -# Code Red toolchain in any other location or if you install a different
    -# version
    -#export TOOLCHAIN_BIN="/cygdrive/c/code_red/RedSuite_4.2.3_379/redsuite/Tools/bin"
    -#export SCRIPT_BIN="/cygdrive/c/code_red/RedSuite_4.2.3_379/redsuite/bin"
    -#export SCRIPT_BIN="/cygdrive/c/nxp/LPCXpresso_4.2.3_292/lpcxpresso/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export SCRIPT_BIN=
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -#export SCRIPT_BIN=
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -#export SCRIPT_BIN=
    -
    -# And add the selected toolchain path[s] to the PATH variable
    -
    -export PATH="/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -if [ ! -z ${SCRIPT_BIN} ]; then
    -  export PATH="${SCRIPT_BIN}:${PATH}"
    -fi
    -
    -export PATH="${TOOLCHAIN_BIN}:${PATH}"
    -echo "PATH : ${PATH}"
    -
    -# Set an alias that can be used to put the LPC43xx in boot mode
    -
    -alias lpc43xx='${SCRIPT_BIN}/Scripts/bootLPCXpresso.cmd winusb'
    diff --git a/configs/bambino-200e/nsh/setenv.sh b/configs/bambino-200e/nsh/setenv.sh
    deleted file mode 100644
    index bb4edf3cc9..0000000000
    --- a/configs/bambino-200e/nsh/setenv.sh
    +++ /dev/null
    @@ -1,96 +0,0 @@
    -#!/bin/bash
    -# configs/bambino-200e/nsh/setenv.sh
    -#
    -#   Copyright (C) 2016 Gregory Nutt. All rights reserved.
    -#   Author: Gregory Nutt 
    -#           Alan Carvalho de Assis acassis@gmail.com [nuttx] 
    -#
    -# 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Code Red
    -# toolchain under windows.  You will have to edit this if you install the
    -# Code Red toolchain in any other location or if you install a different
    -# version
    -#export TOOLCHAIN_BIN="/cygdrive/c/code_red/RedSuite_4.2.3_379/redsuite/Tools/bin"
    -#export SCRIPT_BIN="/cygdrive/c/code_red/RedSuite_4.2.3_379/redsuite/bin"
    -#export SCRIPT_BIN="/cygdrive/c/nxp/LPCXpresso_4.2.3_292/lpcxpresso/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export SCRIPT_BIN=
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -#export SCRIPT_BIN=
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -#export SCRIPT_BIN=
    -
    -# And add the selected toolchain path[s] to the PATH variable
    -
    -export PATH="/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -if [ ! -z ${SCRIPT_BIN} ]; then
    -  export PATH="${SCRIPT_BIN}:${PATH}"
    -fi
    -
    -export PATH="${TOOLCHAIN_BIN}:${PATH}"
    -echo "PATH : ${PATH}"
    -
    -# Set an alias that can be used to put the LPC43xx in boot mode
    -
    -alias lpc43xx='${SCRIPT_BIN}/Scripts/bootLPCXpresso.cmd winusb'
    diff --git a/configs/bambino-200e/usbnsh/setenv.sh b/configs/bambino-200e/usbnsh/setenv.sh
    deleted file mode 100644
    index 74cf761d89..0000000000
    --- a/configs/bambino-200e/usbnsh/setenv.sh
    +++ /dev/null
    @@ -1,96 +0,0 @@
    -#!/bin/bash
    -# configs/bambino-200e/usbnsh/setenv.sh
    -#
    -#   Copyright (C) 2017 Gregory Nutt. All rights reserved.
    -#   Author: Gregory Nutt 
    -#           Alan Carvalho de Assis acassis@gmail.com [nuttx] 
    -#
    -# 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Code Red
    -# toolchain under windows.  You will have to edit this if you install the
    -# Code Red toolchain in any other location or if you install a different
    -# version
    -#export TOOLCHAIN_BIN="/cygdrive/c/code_red/RedSuite_4.2.3_379/redsuite/Tools/bin"
    -#export SCRIPT_BIN="/cygdrive/c/code_red/RedSuite_4.2.3_379/redsuite/bin"
    -#export SCRIPT_BIN="/cygdrive/c/nxp/LPCXpresso_4.2.3_292/lpcxpresso/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export SCRIPT_BIN=
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -#export SCRIPT_BIN=
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -#export SCRIPT_BIN=
    -
    -# And add the selected toolchain path[s] to the PATH variable
    -
    -export PATH="/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -if [ ! -z ${SCRIPT_BIN} ]; then
    -  export PATH="${SCRIPT_BIN}:${PATH}"
    -fi
    -
    -export PATH="${TOOLCHAIN_BIN}:${PATH}"
    -echo "PATH : ${PATH}"
    -
    -# Set an alias that can be used to put the LPC43xx in boot mode
    -
    -alias lpc43xx='${SCRIPT_BIN}/Scripts/bootLPCXpresso.cmd winusb'
    diff --git a/configs/c5471evm/httpd/setenv.sh b/configs/c5471evm/httpd/setenv.sh
    deleted file mode 100755
    index aef64269b7..0000000000
    --- a/configs/c5471evm/httpd/setenv.sh
    +++ /dev/null
    @@ -1,73 +0,0 @@
    -#!/bin/bash
    -##############################################################################
    -# c5471evm/httpd/setenv.sh
    -#
    -#   Copyright (C) 2007, 2008 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.
    -#
    -##############################################################################
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/c5471evm/nettest/setenv.sh b/configs/c5471evm/nettest/setenv.sh
    deleted file mode 100755
    index ed696a72e8..0000000000
    --- a/configs/c5471evm/nettest/setenv.sh
    +++ /dev/null
    @@ -1,73 +0,0 @@
    -#!/bin/bash
    -##############################################################################
    -# c5471evm/nettest/setenv.sh
    -#
    -#   Copyright (C) 2007, 2008, 2011 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.
    -#
    -##############################################################################
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/c5471evm/nsh/setenv.sh b/configs/c5471evm/nsh/setenv.sh
    deleted file mode 100755
    index ccf5d8fa33..0000000000
    --- a/configs/c5471evm/nsh/setenv.sh
    +++ /dev/null
    @@ -1,73 +0,0 @@
    -#!/bin/bash
    -##############################################################################
    -# c5471evm/nsh/setenv.sh
    -#
    -#   Copyright (C) 2007, 2008, 2011 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.
    -#
    -##############################################################################
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/cc3200-launchpad/nsh/setenv.sh b/configs/cc3200-launchpad/nsh/setenv.sh
    deleted file mode 100755
    index 3a1e376dcc..0000000000
    --- a/configs/cc3200-launchpad/nsh/setenv.sh
    +++ /dev/null
    @@ -1,75 +0,0 @@
    -#!/bin/bash
    -# configs/cc3200-launchpad/nsh/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# The cc3200-launchpad/tools directory
    -export TOOL_DIR="${WD}/configs/cc3200-launchpad/tools"
    -
    -# Add the path to the toolchain and tools directory to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${TOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/clicker2-stm32/nsh/setenv.sh b/configs/clicker2-stm32/nsh/setenv.sh
    deleted file mode 100644
    index 66b14fc7cf..0000000000
    --- a/configs/clicker2-stm32/nsh/setenv.sh
    +++ /dev/null
    @@ -1,80 +0,0 @@
    -#!/bin/bash
    -# configs/clicker2-stm32/nsh/setenv.sh
    -#
    -#   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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/clicker2-stm32/usbnsh/setenv.sh b/configs/clicker2-stm32/usbnsh/setenv.sh
    deleted file mode 100644
    index 17b9fd2a3d..0000000000
    --- a/configs/clicker2-stm32/usbnsh/setenv.sh
    +++ /dev/null
    @@ -1,80 +0,0 @@
    -#!/bin/bash
    -# configs/clicker2-stm32/usbnsh/setenv.sh
    -#
    -#   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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/cloudctrl/nsh/setenv.sh b/configs/cloudctrl/nsh/setenv.sh
    deleted file mode 100755
    index 143201e3bd..0000000000
    --- a/configs/cloudctrl/nsh/setenv.sh
    +++ /dev/null
    @@ -1,78 +0,0 @@
    -#!/bin/bash
    -# configs/cloudctrl/nsh/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the path to the tools/ subdirectory
    -export TOOLS_DIR="${WD}/configs/shenzhou/tools"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:${TOOLS_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/demo9s12ne64/ostest/setenv.sh b/configs/demo9s12ne64/ostest/setenv.sh
    deleted file mode 100755
    index 8f47650ca5..0000000000
    --- a/configs/demo9s12ne64/ostest/setenv.sh
    +++ /dev/null
    @@ -1,46 +0,0 @@
    -#!/bin/bash
    -# configs/demo9s12ne64/ostest/setenv.sh
    -#
    -#   Copyright (C) 2009 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -export BUILDROOT_BIN="${WD}/../buildroot/build_m9s12x/staging_dir/bin"
    -export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/dk-tm4c129x/ipv6/setenv.sh b/configs/dk-tm4c129x/ipv6/setenv.sh
    deleted file mode 100755
    index 602357a5ad..0000000000
    --- a/configs/dk-tm4c129x/ipv6/setenv.sh
    +++ /dev/null
    @@ -1,75 +0,0 @@
    -#!/bin/bash
    -# configs/dk-tm4c129x/ipv6/setenv.sh
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# The dk-tm4c129x/tools directory
    -export TOOL_DIR="${WD}/configs/dk-tm4c129x/tools"
    -
    -# Add the path to the toolchain and tools directory to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${TOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/dk-tm4c129x/nsh/setenv.sh b/configs/dk-tm4c129x/nsh/setenv.sh
    deleted file mode 100755
    index 0d2841b39c..0000000000
    --- a/configs/dk-tm4c129x/nsh/setenv.sh
    +++ /dev/null
    @@ -1,75 +0,0 @@
    -#!/bin/bash
    -# configs/dk-tm4c129x/nsh/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# The dk-tm4c129x/tools directory
    -export TOOL_DIR="${WD}/configs/dk-tm4c129x/tools"
    -
    -# Add the path to the toolchain and tools directory to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${TOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/ea3131/nsh/setenv.sh b/configs/ea3131/nsh/setenv.sh
    deleted file mode 100755
    index d40da9a3c9..0000000000
    --- a/configs/ea3131/nsh/setenv.sh
    +++ /dev/null
    @@ -1,66 +0,0 @@
    -#!/bin/bash
    -# configs/ea3131/nsh/setenv.sh
    -#
    -#   Copyright (C) 2010, 2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the path to the tools subdirectory
    -
    -export LPCTOOL_DIR="${WD}/configs/ea3131/tools"
    -
    -# Add the path to the toolchain to the PATH varialble
    -
    -export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -echo "PATH : ${PATH}"
    diff --git a/configs/ea3131/pgnsh/setenv.sh b/configs/ea3131/pgnsh/setenv.sh
    deleted file mode 100755
    index 5d23d67189..0000000000
    --- a/configs/ea3131/pgnsh/setenv.sh
    +++ /dev/null
    @@ -1,66 +0,0 @@
    -#!/bin/bash
    -# configs/ea3131/pgnsh/setenv.sh
    -#
    -#   Copyright (C) 2010 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the path to the tools subdirectory
    -
    -export LPCTOOL_DIR="${WD}/configs/ea3131/tools"
    -
    -# Add the path to the toolchain to the PATH varialble
    -
    -export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -echo "PATH : ${PATH}"
    diff --git a/configs/ea3131/usbserial/setenv.sh b/configs/ea3131/usbserial/setenv.sh
    deleted file mode 100755
    index 23d9bb74ad..0000000000
    --- a/configs/ea3131/usbserial/setenv.sh
    +++ /dev/null
    @@ -1,66 +0,0 @@
    -#!/bin/bash
    -# configs/ea3131/usbserial/setenv.sh
    -#
    -#   Copyright (C) 2010 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the path to the tools subdirectory
    -
    -export LPCTOOL_DIR="${WD}/configs/ea3131/tools"
    -
    -# Add the path to the toolchain to the PATH varialble
    -
    -export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -echo "PATH : ${PATH}"
    diff --git a/configs/ea3152/ostest/setenv.sh b/configs/ea3152/ostest/setenv.sh
    deleted file mode 100755
    index 1e4c5b3abf..0000000000
    --- a/configs/ea3152/ostest/setenv.sh
    +++ /dev/null
    @@ -1,66 +0,0 @@
    -#!/bin/bash
    -# configs/ea3152/ostest/setenv.sh
    -#
    -#   Copyright (C) 2011 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the path to the tools subdirectory
    -
    -export LPCTOOL_DIR="${WD}/configs/ea3152/tools"
    -
    -# Add the path to the toolchain to the PATH varialble
    -
    -export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -echo "PATH : ${PATH}"
    diff --git a/configs/eagle100/httpd/setenv.sh b/configs/eagle100/httpd/setenv.sh
    deleted file mode 100755
    index a22e3372ec..0000000000
    --- a/configs/eagle100/httpd/setenv.sh
    +++ /dev/null
    @@ -1,76 +0,0 @@
    -#!/bin/bash
    -# configs/eagle100/httpd/setenv.sh
    -#
    -#   Copyright (C) 2009 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/eagle100/nettest/setenv.sh b/configs/eagle100/nettest/setenv.sh
    deleted file mode 100755
    index 71c2c259ad..0000000000
    --- a/configs/eagle100/nettest/setenv.sh
    +++ /dev/null
    @@ -1,63 +0,0 @@
    -#!/bin/bash
    -# configs/eagle100/nettest/setenv.sh
    -#
    -#   Copyright (C) 2009 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/eagle100/nsh/setenv.sh b/configs/eagle100/nsh/setenv.sh
    deleted file mode 100755
    index decabe3812..0000000000
    --- a/configs/eagle100/nsh/setenv.sh
    +++ /dev/null
    @@ -1,62 +0,0 @@
    -#!/bin/bash
    -# configs/eagle100/nsh/setenv.sh
    -#
    -#   Copyright (C) 2009 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/eagle100/nxflat/setenv.sh b/configs/eagle100/nxflat/setenv.sh
    deleted file mode 100755
    index 5ccd842093..0000000000
    --- a/configs/eagle100/nxflat/setenv.sh
    +++ /dev/null
    @@ -1,76 +0,0 @@
    -#!/bin/bash
    -# configs/eagle100/nxflat/setenv.sh
    -#
    -#   Copyright (C) 2009 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/eagle100/thttpd/setenv.sh b/configs/eagle100/thttpd/setenv.sh
    deleted file mode 100755
    index cd25820658..0000000000
    --- a/configs/eagle100/thttpd/setenv.sh
    +++ /dev/null
    @@ -1,76 +0,0 @@
    -#!/bin/bash
    -# configs/eagle100/thttpd/setenv.sh
    -#
    -#   Copyright (C) 2009 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/efm32-g8xx-stk/nsh/setenv.sh b/configs/efm32-g8xx-stk/nsh/setenv.sh
    deleted file mode 100755
    index 22032bba65..0000000000
    --- a/configs/efm32-g8xx-stk/nsh/setenv.sh
    +++ /dev/null
    @@ -1,63 +0,0 @@
    -#!/bin/bash
    -# configs/efm32-g8xx-stk/nsh/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/efm32gg-stk3700/nsh/setenv.sh b/configs/efm32gg-stk3700/nsh/setenv.sh
    deleted file mode 100755
    index 22032bba65..0000000000
    --- a/configs/efm32gg-stk3700/nsh/setenv.sh
    +++ /dev/null
    @@ -1,63 +0,0 @@
    -#!/bin/bash
    -# configs/efm32-g8xx-stk/nsh/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/ekk-lm3s9b96/nsh/setenv.sh b/configs/ekk-lm3s9b96/nsh/setenv.sh
    deleted file mode 100755
    index 281a71aa38..0000000000
    --- a/configs/ekk-lm3s9b96/nsh/setenv.sh
    +++ /dev/null
    @@ -1,64 +0,0 @@
    -#!/bin/bash
    -# configs/ekk-lm3s9b96/nsh/setenv.sh
    -#
    -#   Copyright (C) 2012 Gregory Nutt. All rights reserved.
    -#   Authors: Gregory Nutt 
    -#            Jose Pablo Rojas V. 
    -#
    -# 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/esp32-core/nsh/setenv.sh b/configs/esp32-core/nsh/setenv.sh
    deleted file mode 100644
    index 3c57c18b55..0000000000
    --- a/configs/esp32-core/nsh/setenv.sh
    +++ /dev/null
    @@ -1,57 +0,0 @@
    -#!/bin/bash
    -# configs/esp32-core/nsh/setenv.sh
    -#
    -#   Copyright (C) 2011-2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the path to the location where I installed the Expressif crosstools-NG
    -# toolchaing
    -export TOOLCHAIN_BIN="/home/patacongo/projects/nuttx/crosstool-NG/builds/xtensa-esp32-elf/bin"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/esp32-core/ostest/setenv.sh b/configs/esp32-core/ostest/setenv.sh
    deleted file mode 100644
    index 5c52d03081..0000000000
    --- a/configs/esp32-core/ostest/setenv.sh
    +++ /dev/null
    @@ -1,57 +0,0 @@
    -#!/bin/bash
    -# configs/esp32-core/ostest/setenv.sh
    -#
    -#   Copyright (C) 2011-2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the path to the location where I installed the Expressif crosstools-NG
    -# toolchaing
    -export TOOLCHAIN_BIN="/home/patacongo/projects/nuttx/crosstool-NG/builds/xtensa-esp32-elf/bin"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/esp32-core/smp/setenv.sh b/configs/esp32-core/smp/setenv.sh
    deleted file mode 100755
    index 3c57c18b55..0000000000
    --- a/configs/esp32-core/smp/setenv.sh
    +++ /dev/null
    @@ -1,57 +0,0 @@
    -#!/bin/bash
    -# configs/esp32-core/nsh/setenv.sh
    -#
    -#   Copyright (C) 2011-2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the path to the location where I installed the Expressif crosstools-NG
    -# toolchaing
    -export TOOLCHAIN_BIN="/home/patacongo/projects/nuttx/crosstool-NG/builds/xtensa-esp32-elf/bin"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/ez80f910200kitg/ostest/setenv.sh b/configs/ez80f910200kitg/ostest/setenv.sh
    deleted file mode 100755
    index dbee7060cf..0000000000
    --- a/configs/ez80f910200kitg/ostest/setenv.sh
    +++ /dev/null
    @@ -1,64 +0,0 @@
    -#!/bin/bash
    -# configs/ez80f910200kitg/ostest/setenv.sh
    -#
    -#   Copyright (C) 2008, 2009 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.
    -#
    -# Check how we were executed
    -#
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -#
    -# This is the Cygwin path to location where the XDS-II tools were installed
    -#
    -#TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/ZiLOG/ZDSII_eZ80Acclaim!_5.1.1\bin"
    -TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/ZiLOG/ZDSII_eZ80Acclaim!_5.2.1/bin"
    -
    -#
    -# Add the path to the toolchain to the PATH varialble.  NOTE that /bin and /usr/bin
    -# preceded the toolchain bin directory.  This is because the ZDSII bin directory
    -# includes binaries like make.exe that will interfere with the normal build process
    -# if we do not give priority to the versions at /bin and /usr/bin.
    -#
    -export PATH="/bin:/usr/bin:${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -echo "PATH : ${PATH}"
    diff --git a/configs/ez80f910200zco/dhcpd/setenv.sh b/configs/ez80f910200zco/dhcpd/setenv.sh
    deleted file mode 100755
    index db5ea60ff8..0000000000
    --- a/configs/ez80f910200zco/dhcpd/setenv.sh
    +++ /dev/null
    @@ -1,64 +0,0 @@
    -#!/bin/bash
    -# configs/ez80f910200zco/dhcpd/setenv.sh
    -#
    -#   Copyright (C) 2009, 2012 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.
    -#
    -# Check how we were executed
    -#
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -#
    -# This is the Cygwin path to location where the XDS-II tools were installed
    -#
    -#TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/ZiLOG/ZDSII_eZ80Acclaim!_5.1.1\bin"
    -TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/ZiLOG/ZDSII_eZ80Acclaim!_5.2.1/bin"
    -
    -#
    -# Add the path to the toolchain to the PATH varialble.  NOTE that /bin and /usr/bin
    -# preceded the toolchain bin directory.  This is because the ZDSII bin directory
    -# includes binaries like make.exe that will interfere with the normal build process
    -# if we do not give priority to the versions at /bin and /usr/bin.
    -#
    -export PATH="/bin:/usr/bin:${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -echo "PATH : ${PATH}"
    diff --git a/configs/ez80f910200zco/httpd/setenv.sh b/configs/ez80f910200zco/httpd/setenv.sh
    deleted file mode 100755
    index 2d7aee1ce7..0000000000
    --- a/configs/ez80f910200zco/httpd/setenv.sh
    +++ /dev/null
    @@ -1,64 +0,0 @@
    -#!/bin/bash
    -# configs/ez80f910200zco/htppd/setenv.sh
    -#
    -#   Copyright (C) 2009, 2012 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.
    -#
    -# Check how we were executed
    -#
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -#
    -# This is the Cygwin path to location where the XDS-II tools were installed
    -#
    -#TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/ZiLOG/ZDSII_eZ80Acclaim!_5.1.1\bin"
    -TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/ZiLOG/ZDSII_eZ80Acclaim!_5.2.1/bin"
    -
    -#
    -# Add the path to the toolchain to the PATH varialble.  NOTE that /bin and /usr/bin
    -# preceded the toolchain bin directory.  This is because the ZDSII bin directory
    -# includes binaries like make.exe that will interfere with the normal build process
    -# if we do not give priority to the versions at /bin and /usr/bin.
    -#
    -export PATH="/bin:/usr/bin:${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -echo "PATH : ${PATH}"
    diff --git a/configs/ez80f910200zco/nettest/setenv.sh b/configs/ez80f910200zco/nettest/setenv.sh
    deleted file mode 100755
    index f3c50aa582..0000000000
    --- a/configs/ez80f910200zco/nettest/setenv.sh
    +++ /dev/null
    @@ -1,64 +0,0 @@
    -#!/bin/bash
    -# configs/ez80f910200zco/nettest/setenv.sh
    -#
    -#   Copyright (C) 2008, 2009, 2012 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.
    -#
    -# Check how we were executed
    -#
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -#
    -# This is the Cygwin path to location where the XDS-II tools were installed
    -#
    -#TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/ZiLOG/ZDSII_eZ80Acclaim!_5.1.1\bin"
    -TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/ZiLOG/ZDSII_eZ80Acclaim!_5.2.1/bin"
    -
    -#
    -# Add the path to the toolchain to the PATH varialble.  NOTE that /bin and /usr/bin
    -# preceded the toolchain bin directory.  This is because the ZDSII bin directory
    -# includes binaries like make.exe that will interfere with the normal build process
    -# if we do not give priority to the versions at /bin and /usr/bin.
    -#
    -export PATH="/bin:/usr/bin:${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -echo "PATH : ${PATH}"
    diff --git a/configs/ez80f910200zco/nsh/setenv.sh b/configs/ez80f910200zco/nsh/setenv.sh
    deleted file mode 100755
    index 8431e3b363..0000000000
    --- a/configs/ez80f910200zco/nsh/setenv.sh
    +++ /dev/null
    @@ -1,64 +0,0 @@
    -#!/bin/bash
    -# configs/ez80f910200zco/nsh/setenv.sh
    -#
    -#   Copyright (C) 2009, 2012 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.
    -#
    -# Check how we were executed
    -#
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -#
    -# This is the Cygwin path to location where the XDS-II tools were installed
    -#
    -#TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/ZiLOG/ZDSII_eZ80Acclaim!_5.1.1\bin"
    -TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/ZiLOG/ZDSII_eZ80Acclaim!_5.2.1/bin"
    -
    -#
    -# Add the path to the toolchain to the PATH varialble.  NOTE that /bin and /usr/bin
    -# preceded the toolchain bin directory.  This is because the ZDSII bin directory
    -# includes binaries like make.exe that will interfere with the normal build process
    -# if we do not give priority to the versions at /bin and /usr/bin.
    -#
    -export PATH="/bin:/usr/bin:${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -echo "PATH : ${PATH}"
    diff --git a/configs/ez80f910200zco/poll/setenv.sh b/configs/ez80f910200zco/poll/setenv.sh
    deleted file mode 100755
    index 115fed1f28..0000000000
    --- a/configs/ez80f910200zco/poll/setenv.sh
    +++ /dev/null
    @@ -1,64 +0,0 @@
    -#!/bin/bash
    -# configs/ez80f910200zco/poll/setenv.sh
    -#
    -#   Copyright (C) 2009, 2012 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.
    -#
    -# Check how we were executed
    -#
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -#
    -# This is the Cygwin path to location where the XDS-II tools were installed
    -#
    -#TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/ZiLOG/ZDSII_eZ80Acclaim!_5.1.1\bin"
    -TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/ZiLOG/ZDSII_eZ80Acclaim!_5.2.1/bin"
    -
    -#
    -# Add the path to the toolchain to the PATH varialble.  NOTE that /bin and /usr/bin
    -# preceded the toolchain bin directory.  This is because the ZDSII bin directory
    -# includes binaries like make.exe that will interfere with the normal build process
    -# if we do not give priority to the versions at /bin and /usr/bin.
    -#
    -export PATH="/bin:/usr/bin:${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -echo "PATH : ${PATH}"
    diff --git a/configs/fire-stm32v2/nsh/setenv.sh b/configs/fire-stm32v2/nsh/setenv.sh
    deleted file mode 100755
    index 072fae772c..0000000000
    --- a/configs/fire-stm32v2/nsh/setenv.sh
    +++ /dev/null
    @@ -1,78 +0,0 @@
    -#!/bin/bash
    -# configs/fire-stm32v2/nsh/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the path to the tools/ subdirectory
    -export TOOLS_DIR="${WD}/configs/fire-stm32v2/tools"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:${TOOLS_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/freedom-k64f/netnsh/setenv.sh b/configs/freedom-k64f/netnsh/setenv.sh
    deleted file mode 100644
    index c07c4f1607..0000000000
    --- a/configs/freedom-k64f/netnsh/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/freedom-k64f/netnsh/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/freedom-k64f/nsh/setenv.sh b/configs/freedom-k64f/nsh/setenv.sh
    deleted file mode 100644
    index abb64617f4..0000000000
    --- a/configs/freedom-k64f/nsh/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/freedom-k64f/nsh/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/freedom-k66f/netnsh/setenv.sh b/configs/freedom-k66f/netnsh/setenv.sh
    deleted file mode 100644
    index 0bd099e16c..0000000000
    --- a/configs/freedom-k66f/netnsh/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/freedom-k66f/netnsh/setenv.sh
    -#
    -#   Copyright (C) 2016-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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/freedom-k66f/nsh/setenv.sh b/configs/freedom-k66f/nsh/setenv.sh
    deleted file mode 100644
    index be3f2856cd..0000000000
    --- a/configs/freedom-k66f/nsh/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/freedom-k66f/nsh/setenv.sh
    -#
    -#   Copyright (C) 2016-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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/freedom-kl25z/nsh/setenv.sh b/configs/freedom-kl25z/nsh/setenv.sh
    deleted file mode 100755
    index 346e6c2a52..0000000000
    --- a/configs/freedom-kl25z/nsh/setenv.sh
    +++ /dev/null
    @@ -1,75 +0,0 @@
    -#!/bin/bash
    -# configs/freedom-kl25z/nsh/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/freedom-kl26z/nsh/setenv.sh b/configs/freedom-kl26z/nsh/setenv.sh
    deleted file mode 100755
    index 1b867bb765..0000000000
    --- a/configs/freedom-kl26z/nsh/setenv.sh
    +++ /dev/null
    @@ -1,71 +0,0 @@
    -#!/bin/bash
    -# configs/freedom-kl26z/nsh/setenv.sh
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/hymini-stm32v/nsh/setenv.sh b/configs/hymini-stm32v/nsh/setenv.sh
    deleted file mode 100755
    index a0371cdce4..0000000000
    --- a/configs/hymini-stm32v/nsh/setenv.sh
    +++ /dev/null
    @@ -1,47 +0,0 @@
    -#!/bin/bash
    -# configs/hymini-stm32v/dfu/setenv.sh
    -#
    -#   Copyright (C) 2011 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin"
    -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/hymini-stm32v/nsh2/setenv.sh b/configs/hymini-stm32v/nsh2/setenv.sh
    deleted file mode 100755
    index 0f98a6e5e1..0000000000
    --- a/configs/hymini-stm32v/nsh2/setenv.sh
    +++ /dev/null
    @@ -1,67 +0,0 @@
    -#!/bin/bash
    -# configs/hymini-stm32v/nsh2/setenv.sh
    -#
    -#   Copyright (C) 2011 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/hymini-stm32v/usbmsc/setenv.sh b/configs/hymini-stm32v/usbmsc/setenv.sh
    deleted file mode 100755
    index a0371cdce4..0000000000
    --- a/configs/hymini-stm32v/usbmsc/setenv.sh
    +++ /dev/null
    @@ -1,47 +0,0 @@
    -#!/bin/bash
    -# configs/hymini-stm32v/dfu/setenv.sh
    -#
    -#   Copyright (C) 2011 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin"
    -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/hymini-stm32v/usbnsh/setenv.sh b/configs/hymini-stm32v/usbnsh/setenv.sh
    deleted file mode 100755
    index e80939b3ca..0000000000
    --- a/configs/hymini-stm32v/usbnsh/setenv.sh
    +++ /dev/null
    @@ -1,47 +0,0 @@
    -#!/bin/bash
    -# configs/hymini-stm32v/usbndh/setenv.sh
    -#
    -#   Copyright (C) 2011 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin"
    -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/hymini-stm32v/usbserial/setenv.sh b/configs/hymini-stm32v/usbserial/setenv.sh
    deleted file mode 100755
    index 6b324148d2..0000000000
    --- a/configs/hymini-stm32v/usbserial/setenv.sh
    +++ /dev/null
    @@ -1,47 +0,0 @@
    -#!/bin/bash
    -# configs/hymini-stm32v/ostest/setenv.sh
    -#
    -#   Copyright (C) 2011 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin"
    -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/kwikstik-k40/ostest/setenv.sh b/configs/kwikstik-k40/ostest/setenv.sh
    deleted file mode 100755
    index 790030b1fd..0000000000
    --- a/configs/kwikstik-k40/ostest/setenv.sh
    +++ /dev/null
    @@ -1,61 +0,0 @@
    -#!/bin/bash
    -# configs/kwikstik-k40/ostest/setenv.sh
    -#
    -#   Copyright (C) 2011 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -echo "PATH : ${PATH}"
    diff --git a/configs/launchxl-tms57004/nsh/setenv.sh b/configs/launchxl-tms57004/nsh/setenv.sh
    deleted file mode 100755
    index 2f7b6d3ed8..0000000000
    --- a/configs/launchxl-tms57004/nsh/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/launchxl_tms570/nsh/Make.defs
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_armeb/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/lincoln60/netnsh/setenv.sh b/configs/lincoln60/netnsh/setenv.sh
    deleted file mode 100755
    index 3dd5a5b581..0000000000
    --- a/configs/lincoln60/netnsh/setenv.sh
    +++ /dev/null
    @@ -1,73 +0,0 @@
    -#!/bin/bash
    -# configs/lincoln60/netnsh/setenv.sh
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/lincoln60/nsh/setenv.sh b/configs/lincoln60/nsh/setenv.sh
    deleted file mode 100755
    index dc3c011dbc..0000000000
    --- a/configs/lincoln60/nsh/setenv.sh
    +++ /dev/null
    @@ -1,73 +0,0 @@
    -#!/bin/bash
    -# configs/lincoln60/nsh/setenv.sh
    -#
    -#   Copyright (C) 2012, 2015 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.
    -#
    -
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/lincoln60/thttpd-binfs/setenv.sh b/configs/lincoln60/thttpd-binfs/setenv.sh
    deleted file mode 100755
    index 127d7f3402..0000000000
    --- a/configs/lincoln60/thttpd-binfs/setenv.sh
    +++ /dev/null
    @@ -1,73 +0,0 @@
    -#!/bin/bash
    -# configs/lincoln60/thttpd-binfs/setenv.sh
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/lm3s6432-s2e/nsh/setenv.sh b/configs/lm3s6432-s2e/nsh/setenv.sh
    deleted file mode 100755
    index 3cd011f121..0000000000
    --- a/configs/lm3s6432-s2e/nsh/setenv.sh
    +++ /dev/null
    @@ -1,46 +0,0 @@
    -#!/bin/bash
    -# configs/lm3s6432-s2e/nsh/setenv.sh
    -#
    -#   Copyright (C) 2010 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/lm3s6965-ek/discover/setenv.sh b/configs/lm3s6965-ek/discover/setenv.sh
    deleted file mode 100755
    index 9153b0edf2..0000000000
    --- a/configs/lm3s6965-ek/discover/setenv.sh
    +++ /dev/null
    @@ -1,71 +0,0 @@
    -#!/bin/bash
    -# configs/lm3s6965-ek/discover/setenv.sh
    -#
    -#   Copyright (C) 2013, 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the path to the LM3S6995-EK tools directory
    -
    -export TOOL_BIN="${WD}/configs/lm3s6965-ek/tools"
    -
    -# Update the PATH variable
    -
    -export PATH="${TOOLCHAIN_BIN}:${TOOL_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    -
    diff --git a/configs/lm3s6965-ek/nsh/setenv.sh b/configs/lm3s6965-ek/nsh/setenv.sh
    deleted file mode 100755
    index 02af3f7685..0000000000
    --- a/configs/lm3s6965-ek/nsh/setenv.sh
    +++ /dev/null
    @@ -1,70 +0,0 @@
    -#!/bin/bash
    -# configs/lm3s6965-ek/nsh/setenv.sh
    -#
    -#   Copyright (C) 2010, 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the path to the LM3S6995-EK tools directory
    -
    -export TOOL_BIN="${WD}/configs/lm3s6965-ek/tools"
    -
    -# Update the PATH variable
    -
    -export PATH="${TOOLCHAIN_BIN}:${TOOL_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/lm3s6965-ek/nx/setenv.sh b/configs/lm3s6965-ek/nx/setenv.sh
    deleted file mode 100755
    index 07ccdeecd1..0000000000
    --- a/configs/lm3s6965-ek/nx/setenv.sh
    +++ /dev/null
    @@ -1,70 +0,0 @@
    -#!/bin/bash
    -# configs/lm3s6965-ek/nx/setenv.sh
    -#
    -#   Copyright (C) 2010, 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the path to the LM3S6995-EK tools directory
    -
    -export TOOL_BIN="${WD}/configs/lm3s6965-ek/tools"
    -
    -# Update the PATH variable
    -
    -export PATH="${TOOLCHAIN_BIN}:${TOOL_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/lm3s6965-ek/tcpecho/setenv.sh b/configs/lm3s6965-ek/tcpecho/setenv.sh
    deleted file mode 100755
    index dd1d739b5a..0000000000
    --- a/configs/lm3s6965-ek/tcpecho/setenv.sh
    +++ /dev/null
    @@ -1,70 +0,0 @@
    -#!/bin/bash
    -# configs/lm3s6965-ek/tcpecho/setenv.sh
    -#
    -#   Copyright (C) 2013-2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the path to the LM3S6995-EK tools directory
    -
    -export TOOL_BIN="${WD}/configs/lm3s6965-ek/tools"
    -
    -# Update the PATH variable
    -
    -export PATH="${TOOLCHAIN_BIN}:${TOOL_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/lm3s8962-ek/nsh/setenv.sh b/configs/lm3s8962-ek/nsh/setenv.sh
    deleted file mode 100755
    index 2452b3302f..0000000000
    --- a/configs/lm3s8962-ek/nsh/setenv.sh
    +++ /dev/null
    @@ -1,63 +0,0 @@
    -#!/bin/bash
    -# configs/lm3s8962-ek/nsh/setenv.sh
    -#
    -#   Copyright (C) 2010 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/lm3s8962-ek/nx/setenv.sh b/configs/lm3s8962-ek/nx/setenv.sh
    deleted file mode 100755
    index 9909d8963a..0000000000
    --- a/configs/lm3s8962-ek/nx/setenv.sh
    +++ /dev/null
    @@ -1,62 +0,0 @@
    -#!/bin/bash
    -# configs/lm3s8962-ek/nx/setenv.sh
    -#
    -#   Copyright (C) 2010 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/lm4f120-launchpad/nsh/setenv.sh b/configs/lm4f120-launchpad/nsh/setenv.sh
    deleted file mode 100755
    index c66b7edffb..0000000000
    --- a/configs/lm4f120-launchpad/nsh/setenv.sh
    +++ /dev/null
    @@ -1,74 +0,0 @@
    -#!/bin/bash
    -# configs/lm4f120-launchpad/nsh/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# The lm4f120-launchpad/tools directory
    -export TOOL_DIR="${WD}/configs/lm4f120-launchpad/tools"
    -
    -# Add the path to the toolchain and tools directory to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${TOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/lpc4330-xplorer/nsh/setenv.sh b/configs/lpc4330-xplorer/nsh/setenv.sh
    deleted file mode 100755
    index fd946191dd..0000000000
    --- a/configs/lpc4330-xplorer/nsh/setenv.sh
    +++ /dev/null
    @@ -1,91 +0,0 @@
    -#!/bin/bash
    -# configs/lpc4330-xplorer/nsh/setenv.sh
    -#
    -#   Copyright (C) 2010 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Code Red
    -# toolchain under windows.  You will have to edit this if you install the
    -# Code Red toolchain in any other location or if you install a different
    -# version
    -export TOOLCHAIN_BIN="/cygdrive/c/code_red/RedSuite_4.2.3_379/redsuite/Tools/bin"
    -#export SCRIPT_BIN="/cygdrive/c/code_red/RedSuite_4.2.3_379/redsuite/bin"
    -export SCRIPT_BIN="/cygdrive/c/nxp/LPCXpresso_4.2.3_292/lpcxpresso/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export SCRIPT_BIN=
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -#export SCRIPT_BIN=
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -#export SCRIPT_BIN=
    -
    -# And add the selected toolchain path[s] to the PATH variable
    -
    -export PATH="/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -if [ ! -z ${SCRIPT_BIN} ]; then
    -  export PATH="${SCRIPT_BIN}:${PATH}"
    -fi
    -
    -export PATH="${TOOLCHAIN_BIN}:${PATH}"
    -echo "PATH : ${PATH}"
    -
    -# Set an alias that can be used to put the LPC43xx in boot mode
    -
    -alias lpc43xx='${SCRIPT_BIN}/Scripts/bootLPCXpresso.cmd winusb'
    diff --git a/configs/lpc4337-ws/nsh/setenv.sh b/configs/lpc4337-ws/nsh/setenv.sh
    deleted file mode 100755
    index 60612b8c35..0000000000
    --- a/configs/lpc4337-ws/nsh/setenv.sh
    +++ /dev/null
    @@ -1,92 +0,0 @@
    -#!/bin/bash
    -# configs/lpc4337-ws/nsh/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Code Red
    -# toolchain under windows.  You will have to edit this if you install the
    -# Code Red toolchain in any other location or if you install a different
    -# version
    -export TOOLCHAIN_BIN="/cygdrive/c/Users/Public/tools/bin"
    -#export SCRIPT_BIN="/cygdrive/c/code_red/RedSuite_4.2.3_379/redsuite/bin"
    -export SCRIPT_BIN="/cygdrive/c/nxp/LPCXpresso_4.2.3_292/lpcxpresso/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export SCRIPT_BIN=
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -#export SCRIPT_BIN=
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -#export SCRIPT_BIN=
    -
    -# And add the selected toolchain path[s] to the PATH variable
    -
    -export PATH="/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -if [ ! -z ${SCRIPT_BIN} ]; then
    -  export PATH="${SCRIPT_BIN}:${PATH}"
    -fi
    -
    -export PATH="${TOOLCHAIN_BIN}:${PATH}"
    -echo "PATH : ${PATH}"
    -
    -# Set an alias that can be used to put the LPC43xx in boot mode
    -
    -alias lpc43xx='${SCRIPT_BIN}/Scripts/bootLPCXpresso.cmd winusb'
    diff --git a/configs/lpc4357-evb/nsh/setenv.sh b/configs/lpc4357-evb/nsh/setenv.sh
    deleted file mode 100755
    index c40d55a27b..0000000000
    --- a/configs/lpc4357-evb/nsh/setenv.sh
    +++ /dev/null
    @@ -1,92 +0,0 @@
    -#!/bin/bash
    -# configs/lpc4357-evb/nsh/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Code Red
    -# toolchain under windows.  You will have to edit this if you install the
    -# Code Red toolchain in any other location or if you install a different
    -# version
    -export TOOLCHAIN_BIN="/cygdrive/c/code_red/RedSuite_4.2.3_379/redsuite/Tools/bin"
    -#export SCRIPT_BIN="/cygdrive/c/code_red/RedSuite_4.2.3_379/redsuite/bin"
    -export SCRIPT_BIN="/cygdrive/c/nxp/LPCXpresso_4.2.3_292/lpcxpresso/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export SCRIPT_BIN=
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -#export SCRIPT_BIN=
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -#export SCRIPT_BIN=
    -
    -# And add the selected toolchain path[s] to the PATH variable
    -
    -export PATH="/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -if [ ! -z ${SCRIPT_BIN} ]; then
    -  export PATH="${SCRIPT_BIN}:${PATH}"
    -fi
    -
    -export PATH="${TOOLCHAIN_BIN}:${PATH}"
    -echo "PATH : ${PATH}"
    -
    -# Set an alias that can be used to put the LPC43xx in boot mode
    -
    -alias lpc43xx='${SCRIPT_BIN}/Scripts/bootLPCXpresso.cmd winusb'
    diff --git a/configs/lpc4370-link2/nsh/setenv.sh b/configs/lpc4370-link2/nsh/setenv.sh
    deleted file mode 100755
    index e9d6bc9372..0000000000
    --- a/configs/lpc4370-link2/nsh/setenv.sh
    +++ /dev/null
    @@ -1,92 +0,0 @@
    -#!/bin/bash
    -# configs/lpc4370-link2/nsh/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Code Red
    -# toolchain under windows.  You will have to edit this if you install the
    -# Code Red toolchain in any other location or if you install a different
    -# version
    -export TOOLCHAIN_BIN="/cygdrive/c/Users/Public/tools/bin"
    -#export SCRIPT_BIN="/cygdrive/c/code_red/RedSuite_4.2.3_379/redsuite/bin"
    -export SCRIPT_BIN="/cygdrive/c/nxp/LPCXpresso_4.2.3_292/lpcxpresso/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export SCRIPT_BIN=
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -#export SCRIPT_BIN=
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -#export SCRIPT_BIN=
    -
    -# And add the selected toolchain path[s] to the PATH variable
    -
    -export PATH="/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -if [ ! -z ${SCRIPT_BIN} ]; then
    -  export PATH="${SCRIPT_BIN}:${PATH}"
    -fi
    -
    -export PATH="${TOOLCHAIN_BIN}:${PATH}"
    -echo "PATH : ${PATH}"
    -
    -# Set an alias that can be used to put the LPC43xx in boot mode
    -
    -alias lpc43xx='${SCRIPT_BIN}/Scripts/bootLPCXpresso.cmd winusb'
    diff --git a/configs/lpcxpresso-lpc1115/nsh/setenv.sh b/configs/lpcxpresso-lpc1115/nsh/setenv.sh
    deleted file mode 100755
    index ad47eeaaf9..0000000000
    --- a/configs/lpcxpresso-lpc1115/nsh/setenv.sh
    +++ /dev/null
    @@ -1,72 +0,0 @@
    -#!/bin/bash
    -# configs/lpcxpresso-lpc1115/nsh/setenv.sh
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the default install location for Code Red on Linux
    -# export TOOLCHAIN_BIN="/usr/local/LPCXpresso/tools/bin"
    -
    -# This is the Cygwin path to the LPCXpresso 3.6 install location under Windows
    -#export TOOLCHAIN_BIN="/cygdrive/c/nxp/lpcxpresso_3.6/Tools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/lpcxpresso-lpc1768/dhcpd/setenv.sh b/configs/lpcxpresso-lpc1768/dhcpd/setenv.sh
    deleted file mode 100755
    index 03641fd612..0000000000
    --- a/configs/lpcxpresso-lpc1768/dhcpd/setenv.sh
    +++ /dev/null
    @@ -1,59 +0,0 @@
    -#!/bin/bash
    -# configs/lpcxpresso-lpc1768/dhcpd/setenv.sh
    -#
    -#   Copyright (C) 2011 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -
    -# This is where the buildroot might reside on a Linux or Cygwin system
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the default install location for Code Red on Linux
    -export TOOLCHAIN_BIN="/usr/local/LPCXpresso/tools/bin"
    -
    -# This is the Cygwin path to the LPCXpresso 3.6 install location under Windows
    -#export TOOLCHAIN_BIN="/cygdrive/c/nxp/lpcxpresso_3.6/Tools/bin"
    -
    -# This is the path to the LPCXpression tool subdirectory
    -export LPCTOOL_DIR="${WD}/configs/lpcxpresso-lpc1768/tools"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/lpcxpresso-lpc1768/nsh/setenv.sh b/configs/lpcxpresso-lpc1768/nsh/setenv.sh
    deleted file mode 100755
    index 46d5b3261f..0000000000
    --- a/configs/lpcxpresso-lpc1768/nsh/setenv.sh
    +++ /dev/null
    @@ -1,59 +0,0 @@
    -#!/bin/bash
    -# configs/lpcxpresso-lpc1768/nsh/setenv.sh
    -#
    -#   Copyright (C) 2011 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -
    -# This is where the buildroot might reside on a Linux or Cygwin system
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the default install location for Code Red on Linux
    -export TOOLCHAIN_BIN="/usr/local/LPCXpresso/tools/bin"
    -
    -# This is the Cygwin path to the LPCXpresso 3.6 install location under Windows
    -#export TOOLCHAIN_BIN="/cygdrive/c/nxp/lpcxpresso_3.6/Tools/bin"
    -
    -# This is the path to the LPCXpression tool subdirectory
    -export LPCTOOL_DIR="${WD}/configs/lpcxpresso-lpc1768/tools"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/lpcxpresso-lpc1768/nx/setenv.sh b/configs/lpcxpresso-lpc1768/nx/setenv.sh
    deleted file mode 100755
    index 2f04a8ac6d..0000000000
    --- a/configs/lpcxpresso-lpc1768/nx/setenv.sh
    +++ /dev/null
    @@ -1,59 +0,0 @@
    -#!/bin/bash
    -# configs/lpcxpresso-lpc1768/nx/setenv.sh
    -#
    -#   Copyright (C) 2011 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -
    -# This is where the buildroot might reside on a Linux or Cygwin system
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the default install location for Code Red on Linux
    -export TOOLCHAIN_BIN="/usr/local/LPCXpresso/tools/bin"
    -
    -# This is the Cygwin path to the LPCXpresso 3.6 install location under Windows
    -#export TOOLCHAIN_BIN="/cygdrive/c/nxp/lpcxpresso_3.6/Tools/bin"
    -
    -# This is the path to the LPCXpression tool subdirectory
    -export LPCTOOL_DIR="${WD}/configs/lpcxpresso-lpc1768/tools"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/lpcxpresso-lpc1768/thttpd/setenv.sh b/configs/lpcxpresso-lpc1768/thttpd/setenv.sh
    deleted file mode 100755
    index 7156a371dd..0000000000
    --- a/configs/lpcxpresso-lpc1768/thttpd/setenv.sh
    +++ /dev/null
    @@ -1,61 +0,0 @@
    -#!/bin/bash
    -# configs/lpcxpresso-lpc1768/thttpd/setenv.sh
    -#
    -#   Copyright (C) 2011 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -
    -# This is where the buildroot might reside on a Linux or Cygwin system
    -# A minimal buildroot version with the NXFLAT tools is always required
    -# for this configuration in order to buildthe THTTPD CGI programs
    -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the default install location for Code Red on Linux
    -export TOOLCHAIN_BIN="/usr/local/LPCXpresso/tools/bin"
    -
    -# This is the Cygwin path to the LPCXpresso 3.6 install location under Windows
    -#export TOOLCHAIN_BIN="/cygdrive/c/nxp/lpcxpresso_3.6/Tools/bin"
    -
    -# This is the path to the LPCXpression tool subdirectory
    -export LPCTOOL_DIR="${WD}/configs/lpcxpresso-lpc1768/tools"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/lpcxpresso-lpc1768/usbmsc/setenv.sh b/configs/lpcxpresso-lpc1768/usbmsc/setenv.sh
    deleted file mode 100755
    index 15c27bf48f..0000000000
    --- a/configs/lpcxpresso-lpc1768/usbmsc/setenv.sh
    +++ /dev/null
    @@ -1,59 +0,0 @@
    -#!/bin/bash
    -# configs/lpcxpresso-lpc1768/usbmsc/setenv.sh
    -#
    -#   Copyright (C) 2011 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -
    -# This is where the buildroot might reside on a Linux or Cygwin system
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the default install location for Code Red on Linux
    -export TOOLCHAIN_BIN="/usr/local/LPCXpresso/tools/bin"
    -
    -# This is the Cygwin path to the LPCXpresso 3.6 install location under Windows
    -#export TOOLCHAIN_BIN="/cygdrive/c/nxp/lpcxpresso_3.6/Tools/bin"
    -
    -# This is the path to the LPCXpression tool subdirectory
    -export LPCTOOL_DIR="${WD}/configs/lpcxpresso-lpc1768/tools"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/maple/nsh/setenv.sh b/configs/maple/nsh/setenv.sh
    deleted file mode 100755
    index 6ede0014ee..0000000000
    --- a/configs/maple/nsh/setenv.sh
    +++ /dev/null
    @@ -1,63 +0,0 @@
    -#!/bin/bash
    -# configs/maple/nsh/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -
    -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the path to the Spark tools directory
    -
    -export TOOL_BIN="${WD}/configs/maple/tools"
    -
    -# Update the PATH variable
    -
    -export PATH="${BUILDROOT_BIN}:${TOOL_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/maple/nx/setenv.sh b/configs/maple/nx/setenv.sh
    deleted file mode 100755
    index ca144ce26c..0000000000
    --- a/configs/maple/nx/setenv.sh
    +++ /dev/null
    @@ -1,63 +0,0 @@
    -#!/bin/bash
    -# configs/maple/nx/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -
    -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the path to the Spark tools directory
    -
    -export TOOL_BIN="${WD}/configs/maple/tools"
    -
    -# Update the PATH variable
    -
    -export PATH="${BUILDROOT_BIN}:${TOOL_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/maple/usbnsh/setenv.sh b/configs/maple/usbnsh/setenv.sh
    deleted file mode 100755
    index c24c1b78d5..0000000000
    --- a/configs/maple/usbnsh/setenv.sh
    +++ /dev/null
    @@ -1,63 +0,0 @@
    -#!/bin/bash
    -# configs/maple/usbnsh/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -
    -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the path to the Spark tools directory
    -
    -export TOOL_BIN="${WD}/configs/maple/tools"
    -
    -# Update the PATH variable
    -
    -export PATH="${BUILDROOT_BIN}:${TOOL_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/mbed/nsh/setenv.sh b/configs/mbed/nsh/setenv.sh
    deleted file mode 100755
    index f29d975892..0000000000
    --- a/configs/mbed/nsh/setenv.sh
    +++ /dev/null
    @@ -1,47 +0,0 @@
    -#!/bin/bash
    -# configs/mbed/nsh/setenv.sh
    -#
    -#   Copyright (C) 2010 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -export LPCTOOL_DIR="${WD}/configs/mbed/tools"
    -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/mcu123-lpc214x/composite/setenv.sh b/configs/mcu123-lpc214x/composite/setenv.sh
    deleted file mode 100755
    index 841f9c05a1..0000000000
    --- a/configs/mcu123-lpc214x/composite/setenv.sh
    +++ /dev/null
    @@ -1,66 +0,0 @@
    -#!/bin/bash
    -# configs/mcu123-lpc2148/composite/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the Cygwin path to the configuration scripts directory
    -
    -export LPC214XSCRIPTS="$WD/configs/mcu123-lpc214x/scripts"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${LPC214XSCRIPTS}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/mcu123-lpc214x/nsh/setenv.sh b/configs/mcu123-lpc214x/nsh/setenv.sh
    deleted file mode 100755
    index bfd6a39cf2..0000000000
    --- a/configs/mcu123-lpc214x/nsh/setenv.sh
    +++ /dev/null
    @@ -1,73 +0,0 @@
    -#!/bin/bash
    -##############################################################################
    -# configs/mcu123-lpc2148/nsh/setenv.sh
    -#
    -#   Copyright (C) 2008-2009 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.
    -#
    -##############################################################################
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/mcu123-lpc214x/usbmsc/setenv.sh b/configs/mcu123-lpc214x/usbmsc/setenv.sh
    deleted file mode 100755
    index 13be2d1feb..0000000000
    --- a/configs/mcu123-lpc214x/usbmsc/setenv.sh
    +++ /dev/null
    @@ -1,73 +0,0 @@
    -#!/bin/bash
    -##############################################################################
    -# configs/mcu123-lpc214x/usbmsc/setenv.sh
    -#
    -#   Copyright (C) 2008-2009 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.
    -#
    -##############################################################################
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/mcu123-lpc214x/usbserial/setenv.sh b/configs/mcu123-lpc214x/usbserial/setenv.sh
    deleted file mode 100755
    index ebcf4db510..0000000000
    --- a/configs/mcu123-lpc214x/usbserial/setenv.sh
    +++ /dev/null
    @@ -1,73 +0,0 @@
    -#!/bin/bash
    -##############################################################################
    -# configs/mcu123-lpc214x/usbserial/setenv.sh
    -#
    -#   Copyright (C) 2008-2009, 2014 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.
    -#
    -##############################################################################
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/micropendous3/hello/setenv.sh b/configs/micropendous3/hello/setenv.sh
    deleted file mode 100755
    index 1a5f762a3e..0000000000
    --- a/configs/micropendous3/hello/setenv.sh
    +++ /dev/null
    @@ -1,63 +0,0 @@
    -#!/bin/bash
    -# configs/micropendous3/hello/setenv.sh
    -#
    -#   Copyright (C) 2011 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the WinAVR
    -# toolchain under windows.  This is *not* the default install
    -# location so you will probably have to edit this.  You will also have
    -# to edit this if you install the Linux AVR toolchain as well
    -#export TOOLCHAIN_BIN="/cygdrive/c/WinAVR/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_avr/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/mikroe-stm32f4/fulldemo/setenv.sh b/configs/mikroe-stm32f4/fulldemo/setenv.sh
    deleted file mode 100755
    index 93dbf8d8cd..0000000000
    --- a/configs/mikroe-stm32f4/fulldemo/setenv.sh
    +++ /dev/null
    @@ -1,76 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f4discovery/usbnsh/setenv.sh
    -#
    -#   Copyright (C) 2013-2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/mikroe-stm32f4/kostest/setenv.sh b/configs/mikroe-stm32f4/kostest/setenv.sh
    deleted file mode 100755
    index 47142dcd6d..0000000000
    --- a/configs/mikroe-stm32f4/kostest/setenv.sh
    +++ /dev/null
    @@ -1,76 +0,0 @@
    -#!/bin/bash
    -# configs/mikroe-stm32f4/usbnsh/setenv.sh
    -#
    -#   Copyright (C) 2013-2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/mikroe-stm32f4/nsh/setenv.sh b/configs/mikroe-stm32f4/nsh/setenv.sh
    deleted file mode 100755
    index 331b1bef38..0000000000
    --- a/configs/mikroe-stm32f4/nsh/setenv.sh
    +++ /dev/null
    @@ -1,75 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f4discovery/nsh/setenv.sh
    -#
    -#   Copyright (C) 2011-2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/mikroe-stm32f4/nx/setenv.sh b/configs/mikroe-stm32f4/nx/setenv.sh
    deleted file mode 100755
    index 93dbf8d8cd..0000000000
    --- a/configs/mikroe-stm32f4/nx/setenv.sh
    +++ /dev/null
    @@ -1,76 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f4discovery/usbnsh/setenv.sh
    -#
    -#   Copyright (C) 2013-2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/mikroe-stm32f4/nxlines/setenv.sh b/configs/mikroe-stm32f4/nxlines/setenv.sh
    deleted file mode 100755
    index 93dbf8d8cd..0000000000
    --- a/configs/mikroe-stm32f4/nxlines/setenv.sh
    +++ /dev/null
    @@ -1,76 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f4discovery/usbnsh/setenv.sh
    -#
    -#   Copyright (C) 2013-2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/mikroe-stm32f4/nxtext/setenv.sh b/configs/mikroe-stm32f4/nxtext/setenv.sh
    deleted file mode 100755
    index 93dbf8d8cd..0000000000
    --- a/configs/mikroe-stm32f4/nxtext/setenv.sh
    +++ /dev/null
    @@ -1,76 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f4discovery/usbnsh/setenv.sh
    -#
    -#   Copyright (C) 2013-2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/mikroe-stm32f4/usbnsh/setenv.sh b/configs/mikroe-stm32f4/usbnsh/setenv.sh
    deleted file mode 100755
    index 93dbf8d8cd..0000000000
    --- a/configs/mikroe-stm32f4/usbnsh/setenv.sh
    +++ /dev/null
    @@ -1,76 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f4discovery/usbnsh/setenv.sh
    -#
    -#   Copyright (C) 2013-2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/mirtoo/nsh/setenv.sh b/configs/mirtoo/nsh/setenv.sh
    deleted file mode 100755
    index e19bcb407f..0000000000
    --- a/configs/mirtoo/nsh/setenv.sh
    +++ /dev/null
    @@ -1,80 +0,0 @@
    -#!/bin/bash
    -# configs/mirtoo/nsh/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -# This is the Cygwin path to the location where I installed the MicroChip
    -# PIC32MX C32 toolchain under windows.  This is *not* the default install
    -# location so you will probably have to edit this.  You will also have
    -# to edit this if you install a different version of if you install the
    -# toolchain at a different location
    -export TOOLCHAIN_BIN="/cygdrive/c/MicroChip/mplabc32/v1.12/bin"
    -
    -# This the Linux path to the location where I installed the MicroChip
    -# PIC32MX XC32 toolchain under Linux.  This is the default install
    -# location.  You will also have to edit this if you install a different
    -# version of if you install the toolchain at a different location
    -#export TOOLCHAIN_BIN="/opt/microchip/xc32/v1.00/bin"
    -
    -# This is the Cygwin path to the location where I installed the Pinguino
    -# toolchain under Windows.  You will have to edit this if you install the
    -# tool chain in a different location or use a different version.  /bin
    -# needs to precede the tool path or otherwise you will get
    -# /cygdrive/c/PinguinoX.3/win32/p32/bin/make which does not like POSIX
    -# style paths.
    -#export TOOLCHAIN_BIN="/bin:/cygdrive/c/PinguinoX.3/win32/p32/bin"
    -
    -# This the Linux path to the location where I installed the microchipOpen
    -# toolchain under Linux.  You will have to edit this if you use the
    -# microchipOpen toolchain.
    -#export TOOLCHAIN_BIN="~/projects/microchipopen/v105_freeze/pic32-v105-freeze-20120622/install-image/bin"
    -
    -# This is the path to the toosl subdirectory
    -export PIC32TOOL_DIR="${WD}/tools/pic32mx"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${PIC32TOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/mirtoo/nxffs/setenv.sh b/configs/mirtoo/nxffs/setenv.sh
    deleted file mode 100755
    index 1a6279ef13..0000000000
    --- a/configs/mirtoo/nxffs/setenv.sh
    +++ /dev/null
    @@ -1,80 +0,0 @@
    -#!/bin/bash
    -# configs/mirtoo/nxffs/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -# This is the Cygwin path to the location where I installed the MicroChip
    -# PIC32MX C32 toolchain under windows.  This is *not* the default install
    -# location so you will probably have to edit this.  You will also have
    -# to edit this if you install a different version of if you install the
    -# toolchain at a different location
    -export TOOLCHAIN_BIN="/cygdrive/c/MicroChip/mplabc32/v1.12/bin"
    -
    -# This the Linux path to the location where I installed the MicroChip
    -# PIC32MX XC32 toolchain under Linux.  This is the default install
    -# location.  You will also have to edit this if you install a different
    -# version of if you install the toolchain at a different location
    -#export TOOLCHAIN_BIN="/opt/microchip/xc32/v1.00/bin"
    -
    -# This is the Cygwin path to the location where I installed the Pinguino
    -# toolchain under Windows.  You will have to edit this if you install the
    -# tool chain in a different location or use a different version.  /bin
    -# needs to precede the tool path or otherwise you will get
    -# /cygdrive/c/PinguinoX.3/win32/p32/bin/make which does not like POSIX
    -# style paths.
    -#export TOOLCHAIN_BIN="/bin:/cygdrive/c/PinguinoX.3/win32/p32/bin"
    -
    -# This the Linux path to the location where I installed the microchipOpen
    -# toolchain under Linux.  You will have to edit this if you use the
    -# microchipOpen toolchain.
    -#export TOOLCHAIN_BIN="~/projects/microchipopen/v105_freeze/pic32-v105-freeze-20120622/install-image/bin"
    -
    -# This is the path to the toosl subdirectory
    -export PIC32TOOL_DIR="${WD}/tools/pic32mx"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${PIC32TOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/misoc/hello/setenv.sh b/configs/misoc/hello/setenv.sh
    deleted file mode 100644
    index 9b84648e5c..0000000000
    --- a/configs/misoc/hello/setenv.sh
    +++ /dev/null
    @@ -1,58 +0,0 @@
    -#!/bin/bash
    -# configs/misoc/hello/setenv.sh
    -#
    -#   Copyright (C) 2016 Gregory Nutt. All rights reserved.
    -#   Author: Gregory Nutt 
    -#           Ramtin Amin 
    -#
    -# 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_lm32/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/misoc/nsh/setenv.sh b/configs/misoc/nsh/setenv.sh
    deleted file mode 100644
    index 851cd9727d..0000000000
    --- a/configs/misoc/nsh/setenv.sh
    +++ /dev/null
    @@ -1,58 +0,0 @@
    -#!/bin/bash
    -# configs/misoc/nsh/setenv.sh
    -#
    -#   Copyright (C) 2016 Gregory Nutt. All rights reserved.
    -#   Author: Gregory Nutt 
    -#           Ramtin Amin 
    -#
    -# 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_lm32/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/moteino-mega/hello/setenv.sh b/configs/moteino-mega/hello/setenv.sh
    deleted file mode 100755
    index c61b40113a..0000000000
    --- a/configs/moteino-mega/hello/setenv.sh
    +++ /dev/null
    @@ -1,63 +0,0 @@
    -#!/bin/bash
    -# configs/moteino-mega/hello/setenv.sh
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the WinAVR
    -# toolchain under windows.  This is *not* the default install
    -# location so you will probably have to edit this.  You will also have
    -# to edit this if you install the Linux AVR toolchain as well
    -#export TOOLCHAIN_BIN="/cygdrive/c/WinAVR/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_avr/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/moteino-mega/nsh/setenv.sh b/configs/moteino-mega/nsh/setenv.sh
    deleted file mode 100755
    index b4da5bd2ca..0000000000
    --- a/configs/moteino-mega/nsh/setenv.sh
    +++ /dev/null
    @@ -1,63 +0,0 @@
    -#!/bin/bash
    -# configs/moteino-mega/nsh/setenv.sh
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the WinAVR
    -# toolchain under windows.  This is *not* the default install
    -# location so you will probably have to edit this.  You will also have
    -# to edit this if you install the Linux AVR toolchain as well
    -#export TOOLCHAIN_BIN="/cygdrive/c/WinAVR/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_avr/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/moxa/nsh/setenv.sh b/configs/moxa/nsh/setenv.sh
    deleted file mode 100755
    index 74b89f7f09..0000000000
    --- a/configs/moxa/nsh/setenv.sh
    +++ /dev/null
    @@ -1,83 +0,0 @@
    -#!/bin/bash
    -# configs/moxa/nsh/setenv.sh
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the Cygwin path to the location where I have the Arduino BOSSA program
    -export BOSSA_BIN="/cygdrive/c/Program Files (x86)/Arduino/arduino-1.5.2/hardware/tools"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${BOSSA_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/mx1ads/ostest/setenv.sh b/configs/mx1ads/ostest/setenv.sh
    deleted file mode 100755
    index e73858fc76..0000000000
    --- a/configs/mx1ads/ostest/setenv.sh
    +++ /dev/null
    @@ -1,46 +0,0 @@
    -#!/bin/bash
    -# configs/mx1ads/ostest/setenv.sh
    -#
    -#   Copyright (C) 2009 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
    -
    -WD=`pwd`
    -export BUILDROOT_BIN=${WD}/../buildroot/build_arm_nofpu/staging_dir/bin
    -export PATH=${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/ne64badge/ostest/setenv.sh b/configs/ne64badge/ostest/setenv.sh
    deleted file mode 100755
    index c5aa591b49..0000000000
    --- a/configs/ne64badge/ostest/setenv.sh
    +++ /dev/null
    @@ -1,46 +0,0 @@
    -#!/bin/bash
    -# configs/ne64badge/ostest/setenv.sh
    -#
    -#   Copyright (C) 2011 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -export BUILDROOT_BIN="${WD}/../buildroot/build_m9s12x/staging_dir/bin"
    -export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/nr5m100-nexys4/nsh/setenv.sh b/configs/nr5m100-nexys4/nsh/setenv.sh
    deleted file mode 100644
    index 8322085596..0000000000
    --- a/configs/nr5m100-nexys4/nsh/setenv.sh
    +++ /dev/null
    @@ -1,45 +0,0 @@
    -#!/bin/bash
    -# configs/nr5m100-nexys4/nsh/setenv.sh
    -#
    -#   Copyright (C) 2008 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
    -
    -#export NUTTX_BIN=
    -#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/ntosd-dm320/nettest/setenv.sh b/configs/ntosd-dm320/nettest/setenv.sh
    deleted file mode 100755
    index 0f5dd758ba..0000000000
    --- a/configs/ntosd-dm320/nettest/setenv.sh
    +++ /dev/null
    @@ -1,63 +0,0 @@
    -#!/bin/bash
    -# configs/ntosd-dm320/nettest/setenv.sh
    -#
    -#   Copyright (C) 2007, 2008 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/ntosd-dm320/nsh/setenv.sh b/configs/ntosd-dm320/nsh/setenv.sh
    deleted file mode 100755
    index 5bc5f24ff6..0000000000
    --- a/configs/ntosd-dm320/nsh/setenv.sh
    +++ /dev/null
    @@ -1,63 +0,0 @@
    -#!/bin/bash
    -# configs/ntosd-dm320/nsh/setenv.sh
    -#
    -#   Copyright (C) 2007, 2008 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/ntosd-dm320/poll/setenv.sh b/configs/ntosd-dm320/poll/setenv.sh
    deleted file mode 100755
    index 844983c75f..0000000000
    --- a/configs/ntosd-dm320/poll/setenv.sh
    +++ /dev/null
    @@ -1,63 +0,0 @@
    -#!/bin/bash
    -# configs/ntosd-dm320/poll/setenv.sh
    -#
    -#   Copyright (C) 2008 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/ntosd-dm320/thttpd/setenv.sh b/configs/ntosd-dm320/thttpd/setenv.sh
    deleted file mode 100755
    index a93654aeab..0000000000
    --- a/configs/ntosd-dm320/thttpd/setenv.sh
    +++ /dev/null
    @@ -1,63 +0,0 @@
    -#!/bin/bash
    -# configs/ntosd-dm320/thttpd/setenv.sh
    -#
    -#   Copyright (C) 2009 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/ntosd-dm320/udp/setenv.sh b/configs/ntosd-dm320/udp/setenv.sh
    deleted file mode 100755
    index 53c94895d1..0000000000
    --- a/configs/ntosd-dm320/udp/setenv.sh
    +++ /dev/null
    @@ -1,63 +0,0 @@
    -#!/bin/bash
    -# configs/ntosd-dm320/udp/setenv.sh
    -#
    -#   Copyright (C) 2007, 2008 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/ntosd-dm320/webserver/setenv.sh b/configs/ntosd-dm320/webserver/setenv.sh
    deleted file mode 100755
    index 07374f60b6..0000000000
    --- a/configs/ntosd-dm320/webserver/setenv.sh
    +++ /dev/null
    @@ -1,63 +0,0 @@
    -#!/bin/bash
    -# configs/ntosd-dm320/webserver/setenv.sh
    -#
    -#   Copyright (C) 2007, 2008 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/nucleo-144/f746-evalos/setenv.sh b/configs/nucleo-144/f746-evalos/setenv.sh
    deleted file mode 100644
    index 84db5f90ee..0000000000
    --- a/configs/nucleo-144/f746-evalos/setenv.sh
    +++ /dev/null
    @@ -1,78 +0,0 @@
    -#!/bin/bash
    -# configs/nucleo-144/f746-evalos/setenv.sh
    -#
    -#   Copyright (C) 2016 Gregory Nutt. All rights reserved.
    -#   Author: Gregory Nutt 
    -#   Author: Mark Olsson 
    -#
    -# 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/nucleo-144/f746-nsh/setenv.sh b/configs/nucleo-144/f746-nsh/setenv.sh
    deleted file mode 100644
    index 6a5fa6c801..0000000000
    --- a/configs/nucleo-144/f746-nsh/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/nucleo-144/f746-nsh/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/nucleo-144/f767-evalos/setenv.sh b/configs/nucleo-144/f767-evalos/setenv.sh
    deleted file mode 100644
    index cf10804e84..0000000000
    --- a/configs/nucleo-144/f767-evalos/setenv.sh
    +++ /dev/null
    @@ -1,78 +0,0 @@
    -#!/bin/bash
    -# configs/nucleo-144/f767-evalos/setenv.sh
    -#
    -#   Copyright (C) 2016 Gregory Nutt. All rights reserved.
    -#   Author: Gregory Nutt 
    -#   Author: Mark Olsson 
    -#
    -# 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/nucleo-144/f767-nsh/setenv.sh b/configs/nucleo-144/f767-nsh/setenv.sh
    deleted file mode 100644
    index e6eabd1f70..0000000000
    --- a/configs/nucleo-144/f767-nsh/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/nucleo-144/f767-nsh/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/nucleo-f072rb/nsh/setenv.sh b/configs/nucleo-f072rb/nsh/setenv.sh
    deleted file mode 100644
    index 9a1e879f87..0000000000
    --- a/configs/nucleo-f072rb/nsh/setenv.sh
    +++ /dev/null
    @@ -1,81 +0,0 @@
    -#!/bin/bash
    -# configs/nucleo-f072rb/nsh/setenv.sh
    -#
    -#   Copyright (C) 2017 Gregory Nutt. All rights reserved.
    -#   Author: Gregory Nutt 
    -#           Alan Carvalho de Assis 
    -#
    -# 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/nucleo-f334r8/adc/setenv.sh b/configs/nucleo-f334r8/adc/setenv.sh
    deleted file mode 100644
    index a9a8fc14a4..0000000000
    --- a/configs/nucleo-f334r8/adc/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/nucleo-f224r8/adc/setenv.sh
    -#
    -#   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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/nucleo-f334r8/nsh/setenv.sh b/configs/nucleo-f334r8/nsh/setenv.sh
    deleted file mode 100644
    index 1baaeb889e..0000000000
    --- a/configs/nucleo-f334r8/nsh/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/nucleo-f224r8/nsh/setenv.sh
    -#
    -#   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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/nucleo-f4x1re/f401-nsh/setenv.sh b/configs/nucleo-f4x1re/f401-nsh/setenv.sh
    deleted file mode 100755
    index 67f257ad6c..0000000000
    --- a/configs/nucleo-f4x1re/f401-nsh/setenv.sh
    +++ /dev/null
    @@ -1,64 +0,0 @@
    -#!/bin/bash
    -# configs/nucleo-f4x1re/f401nsh/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/nucleo-f4x1re/f411-nsh/setenv.sh b/configs/nucleo-f4x1re/f411-nsh/setenv.sh
    deleted file mode 100755
    index f4ab9bca9b..0000000000
    --- a/configs/nucleo-f4x1re/f411-nsh/setenv.sh
    +++ /dev/null
    @@ -1,64 +0,0 @@
    -#!/bin/bash
    -# configs/nucleo-f4x1re/f411-nsh/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/nucleo-l476rg/nsh/setenv.sh b/configs/nucleo-l476rg/nsh/setenv.sh
    deleted file mode 100755
    index c66a21a3ef..0000000000
    --- a/configs/nucleo-l476rg/nsh/setenv.sh
    +++ /dev/null
    @@ -1,64 +0,0 @@
    -#!/bin/bash
    -# configs/nucleo-l476rg/nsh/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/nutiny-nuc120/nsh/setenv.sh b/configs/nutiny-nuc120/nsh/setenv.sh
    deleted file mode 100755
    index f026535006..0000000000
    --- a/configs/nutiny-nuc120/nsh/setenv.sh
    +++ /dev/null
    @@ -1,75 +0,0 @@
    -#!/bin/bash
    -# configs/nutiny-nuc120/nsh/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimex-efm32g880f128-stk/nsh/setenv.sh b/configs/olimex-efm32g880f128-stk/nsh/setenv.sh
    deleted file mode 100755
    index 2a2238f783..0000000000
    --- a/configs/olimex-efm32g880f128-stk/nsh/setenv.sh
    +++ /dev/null
    @@ -1,63 +0,0 @@
    -#!/bin/bash
    -# configs/olimex-efm32g880f128-stk/nsh/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimex-lpc-h3131/nsh/setenv.sh b/configs/olimex-lpc-h3131/nsh/setenv.sh
    deleted file mode 100755
    index 2bfe99b74a..0000000000
    --- a/configs/olimex-lpc-h3131/nsh/setenv.sh
    +++ /dev/null
    @@ -1,67 +0,0 @@
    -#!/bin/bash
    -# configs/olimex-lpc-h3131/nsh/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the path to the tools subdirectory
    -
    -export LPCTOOL_DIR="${WD}/configs/olimex-lpc-h3131/tools"
    -
    -# Add the path to the toolchain to the PATH varialble
    -
    -export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimex-lpc1766stk/ftpc/setenv.sh b/configs/olimex-lpc1766stk/ftpc/setenv.sh
    deleted file mode 100755
    index 5e21d73dc0..0000000000
    --- a/configs/olimex-lpc1766stk/ftpc/setenv.sh
    +++ /dev/null
    @@ -1,75 +0,0 @@
    -#!/bin/bash
    -# configs/olimex-lpc1766stk/ftpc/setenv.sh
    -#
    -#   Copyright (C) 2011, 2014-2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# The Olimex-lpc1766stk/tools directory
    -export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools"
    -
    -# Add the path to the toolchain and tools directory to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimex-lpc1766stk/hidmouse/setenv.sh b/configs/olimex-lpc1766stk/hidmouse/setenv.sh
    deleted file mode 100755
    index bb617ff32d..0000000000
    --- a/configs/olimex-lpc1766stk/hidmouse/setenv.sh
    +++ /dev/null
    @@ -1,67 +0,0 @@
    -#!/bin/bash
    -# configs/olimex-lpc1766stk/hidmouse/setenv.sh
    -#
    -#   Copyright (C) 2014-2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# The Olimex-lpc1766stk/tools directory
    -export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools"
    -
    -# Add the path to the toolchain and tools directory to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimex-lpc1766stk/nettest/setenv.sh b/configs/olimex-lpc1766stk/nettest/setenv.sh
    deleted file mode 100755
    index 06d4574f16..0000000000
    --- a/configs/olimex-lpc1766stk/nettest/setenv.sh
    +++ /dev/null
    @@ -1,76 +0,0 @@
    -#!/bin/bash
    -# configs/olimex-lpc1766stk/nettest/setenv.sh
    -#
    -#   Copyright (C) 2010, 2014-2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# The Olimex-lpc1766stk/tools directory
    -export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools"
    -
    -# Add the path to the toolchain and tools directory to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimex-lpc1766stk/nsh/setenv.sh b/configs/olimex-lpc1766stk/nsh/setenv.sh
    deleted file mode 100755
    index 4d5efee2ba..0000000000
    --- a/configs/olimex-lpc1766stk/nsh/setenv.sh
    +++ /dev/null
    @@ -1,75 +0,0 @@
    -#!/bin/bash
    -# configs/olimex-lpc1766stk/nsh/setenv.sh
    -#
    -#   Copyright (C) 2010, 2014-2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# The Olimex-lpc1766stk/tools directory
    -export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools"
    -
    -# Add the path to the toolchain and tools directory to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimex-lpc1766stk/nx/setenv.sh b/configs/olimex-lpc1766stk/nx/setenv.sh
    deleted file mode 100755
    index d811266370..0000000000
    --- a/configs/olimex-lpc1766stk/nx/setenv.sh
    +++ /dev/null
    @@ -1,75 +0,0 @@
    -#!/bin/bash
    -# configs/olimex-lpc1766stk/nx/setenv.sh
    -#
    -#   Copyright (C) 2010, 2014-2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# The Olimex-lpc1766stk/tools directory
    -export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools"
    -
    -# Add the path to the toolchain and tools directory to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimex-lpc1766stk/slip-httpd/setenv.sh b/configs/olimex-lpc1766stk/slip-httpd/setenv.sh
    deleted file mode 100755
    index bb91fb0337..0000000000
    --- a/configs/olimex-lpc1766stk/slip-httpd/setenv.sh
    +++ /dev/null
    @@ -1,75 +0,0 @@
    -#!/bin/bash
    -# configs/olimex-lpc1766stk/slip-httpd/setenv.sh
    -#
    -#   Copyright (C) 2011, 2014-2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# The Olimex-lpc1766stk/tools directory
    -export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools"
    -
    -# Add the path to the toolchain and tools directory to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimex-lpc1766stk/thttpd-binfs/setenv.sh b/configs/olimex-lpc1766stk/thttpd-binfs/setenv.sh
    deleted file mode 100755
    index 7cbbdfbffc..0000000000
    --- a/configs/olimex-lpc1766stk/thttpd-binfs/setenv.sh
    +++ /dev/null
    @@ -1,83 +0,0 @@
    -#!/bin/bash
    -# configs/olimex-lpc1766stk/thttpd-binfs/setenv.sh
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# The Olimex-lpc1766stk/tools directory
    -export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools"
    -
    -# Add the path to the toolchain and tools directory to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimex-lpc1766stk/thttpd-nxflat/setenv.sh b/configs/olimex-lpc1766stk/thttpd-nxflat/setenv.sh
    deleted file mode 100755
    index b7dc87b826..0000000000
    --- a/configs/olimex-lpc1766stk/thttpd-nxflat/setenv.sh
    +++ /dev/null
    @@ -1,83 +0,0 @@
    -#!/bin/bash
    -# configs/olimex-lpc1766stk/thttpd/setenv.sh
    -#
    -#   Copyright (C) 2010, 2014-2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# The Olimex-lpc1766stk/tools directory
    -export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools"
    -
    -# Add the path to the toolchain and tools directory to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimex-lpc1766stk/usbmsc/setenv.sh b/configs/olimex-lpc1766stk/usbmsc/setenv.sh
    deleted file mode 100755
    index 2f2bc2d8d8..0000000000
    --- a/configs/olimex-lpc1766stk/usbmsc/setenv.sh
    +++ /dev/null
    @@ -1,75 +0,0 @@
    -#!/bin/bash
    -# configs/olimex-lpc1766stk/usbmsc/setenv.sh
    -#
    -#   Copyright (C) 2010, 2014-2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# The Olimex-lpc1766stk/tools directory
    -export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools"
    -
    -# Add the path to the toolchain and tools directory to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimex-lpc1766stk/usbserial/setenv.sh b/configs/olimex-lpc1766stk/usbserial/setenv.sh
    deleted file mode 100755
    index 90049ced75..0000000000
    --- a/configs/olimex-lpc1766stk/usbserial/setenv.sh
    +++ /dev/null
    @@ -1,75 +0,0 @@
    -#!/bin/bash
    -# configs/olimex-lpc1766stk/usbserial/setenv.sh
    -#
    -#   Copyright (C) 2010, 2014-2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# The Olimex-lpc1766stk/tools directory
    -export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools"
    -
    -# Add the path to the toolchain and tools directory to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimex-lpc1766stk/zmodem/setenv.sh b/configs/olimex-lpc1766stk/zmodem/setenv.sh
    deleted file mode 100755
    index 341ef38d6f..0000000000
    --- a/configs/olimex-lpc1766stk/zmodem/setenv.sh
    +++ /dev/null
    @@ -1,75 +0,0 @@
    -#!/bin/bash
    -# configs/olimex-lpc1766stk/zmodem/setenv.sh
    -#
    -#   Copyright (C) 2013-2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# The Olimex-lpc1766stk/tools directory
    -export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools"
    -
    -# Add the path to the toolchain and tools directory to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimex-lpc2378/nsh/setenv.sh b/configs/olimex-lpc2378/nsh/setenv.sh
    deleted file mode 100755
    index 6e87533e70..0000000000
    --- a/configs/olimex-lpc2378/nsh/setenv.sh
    +++ /dev/null
    @@ -1,68 +0,0 @@
    -#!/bin/bash
    -# configs/olimex-lpc2378/ostest/setenv.sh
    -#
    -#   Copyright (C) 2010 Rommel Marcelo. All rights reserved.
    -#   Author: Rommel Marcelo
    -#
    -# This is part of the NuttX RTOS and based on the LPC2148 port:
    -#
    -#   Copyright (C) 2010 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimex-stm32-e407/discover/setenv.sh b/configs/olimex-stm32-e407/discover/setenv.sh
    deleted file mode 100755
    index 528a4978e8..0000000000
    --- a/configs/olimex-stm32-e407/discover/setenv.sh
    +++ /dev/null
    @@ -1,80 +0,0 @@
    -#!/bin/bash
    -# configs/olimex-stm32-e407/discover/setenv.sh
    -#
    -#   Copyright (C) 2011-2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimex-stm32-e407/netnsh/setenv.sh b/configs/olimex-stm32-e407/netnsh/setenv.sh
    deleted file mode 100755
    index d6f071c221..0000000000
    --- a/configs/olimex-stm32-e407/netnsh/setenv.sh
    +++ /dev/null
    @@ -1,80 +0,0 @@
    -#!/bin/bash
    -# configs/olimex-stm32-e407/netnsh/setenv.sh
    -#
    -#   Copyright (C) 2011-2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimex-stm32-e407/nsh/setenv.sh b/configs/olimex-stm32-e407/nsh/setenv.sh
    deleted file mode 100755
    index ded7c15537..0000000000
    --- a/configs/olimex-stm32-e407/nsh/setenv.sh
    +++ /dev/null
    @@ -1,80 +0,0 @@
    -#!/bin/bash
    -# configs/olimex-stm32-e407/nsh/setenv.sh
    -#
    -#   Copyright (C) 2011-2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimex-stm32-e407/telnetd/setenv.sh b/configs/olimex-stm32-e407/telnetd/setenv.sh
    deleted file mode 100755
    index 62aa001c6e..0000000000
    --- a/configs/olimex-stm32-e407/telnetd/setenv.sh
    +++ /dev/null
    @@ -1,80 +0,0 @@
    -#!/bin/bash
    -# configs/olimex-stm32-e407/telnetd/setenv.sh
    -#
    -#   Copyright (C) 2011-2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimex-stm32-e407/usbnsh/setenv.sh b/configs/olimex-stm32-e407/usbnsh/setenv.sh
    deleted file mode 100755
    index e5b5af7104..0000000000
    --- a/configs/olimex-stm32-e407/usbnsh/setenv.sh
    +++ /dev/null
    @@ -1,80 +0,0 @@
    -#!/bin/bash
    -# configs/olimex-stm32-e407/usbnsh/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimex-stm32-e407/webserver/setenv.sh b/configs/olimex-stm32-e407/webserver/setenv.sh
    deleted file mode 100755
    index 3cffa68d40..0000000000
    --- a/configs/olimex-stm32-e407/webserver/setenv.sh
    +++ /dev/null
    @@ -1,80 +0,0 @@
    -#!/bin/bash
    -# configs/olimex-stm32-e407/webserver/setenv.sh
    -#
    -#   Copyright (C) 2011-2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimex-stm32-h405/usbnsh/setenv.sh b/configs/olimex-stm32-h405/usbnsh/setenv.sh
    deleted file mode 100755
    index d2dc21a00c..0000000000
    --- a/configs/olimex-stm32-h405/usbnsh/setenv.sh
    +++ /dev/null
    @@ -1,75 +0,0 @@
    -#!/bin/bash
    -# configs/olimex-stm32-h405/usbnsh/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimex-stm32-h407/nsh/setenv.sh b/configs/olimex-stm32-h407/nsh/setenv.sh
    deleted file mode 100755
    index 38135e980e..0000000000
    --- a/configs/olimex-stm32-h407/nsh/setenv.sh
    +++ /dev/null
    @@ -1,80 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f4discovery/nsh/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimex-stm32-p107/nsh/setenv.sh b/configs/olimex-stm32-p107/nsh/setenv.sh
    deleted file mode 100755
    index 8916f538cc..0000000000
    --- a/configs/olimex-stm32-p107/nsh/setenv.sh
    +++ /dev/null
    @@ -1,76 +0,0 @@
    -#!/bin/bash
    -# configs/olimex-stm32-p107/nsh/setenv.sh
    -#
    -#   Copyright (C) 2009 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimex-stm32-p207/nsh/setenv.sh b/configs/olimex-stm32-p207/nsh/setenv.sh
    deleted file mode 100755
    index ad8fd4e1e9..0000000000
    --- a/configs/olimex-stm32-p207/nsh/setenv.sh
    +++ /dev/null
    @@ -1,75 +0,0 @@
    -#!/bin/bash
    -# configs/olimex-stm32-p207/nsh/setenv.sh
    -#
    -#   Copyright (C) 2009 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimex-stm32-p407/knsh/setenv.sh b/configs/olimex-stm32-p407/knsh/setenv.sh
    deleted file mode 100644
    index dec893b820..0000000000
    --- a/configs/olimex-stm32-p407/knsh/setenv.sh
    +++ /dev/null
    @@ -1,80 +0,0 @@
    -#!/bin/bash
    -# configs/olimex-stm32-p407/knsh/setenv.sh
    -#
    -#   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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimex-stm32-p407/nsh/setenv.sh b/configs/olimex-stm32-p407/nsh/setenv.sh
    deleted file mode 100644
    index 6d260da852..0000000000
    --- a/configs/olimex-stm32-p407/nsh/setenv.sh
    +++ /dev/null
    @@ -1,80 +0,0 @@
    -#!/bin/bash
    -# configs/olimex-stm32-p407/nsh/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimex-strp711/nettest/setenv.sh b/configs/olimex-strp711/nettest/setenv.sh
    deleted file mode 100755
    index e30820e826..0000000000
    --- a/configs/olimex-strp711/nettest/setenv.sh
    +++ /dev/null
    @@ -1,72 +0,0 @@
    -#!/bin/bash
    -# configs/olimex-strp711/nettest/setenv.sh
    -#
    -#   Copyright (C) 2010 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.
    -#
    -##############################################################################
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimex-strp711/nsh/setenv.sh b/configs/olimex-strp711/nsh/setenv.sh
    deleted file mode 100755
    index 6724741f69..0000000000
    --- a/configs/olimex-strp711/nsh/setenv.sh
    +++ /dev/null
    @@ -1,47 +0,0 @@
    -#!/bin/bash
    -# configs/olimex-strp711/nsh/setenv.sh
    -#
    -#   Copyright (C) 2008-2009 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -export STR41XSCRIPTS="$WD/configs/olimex-strp711/scripts"
    -export PATH="${BUILDROOT_BIN}:${STR41XSCRIPTS}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimexino-stm32/can/setenv.sh b/configs/olimexino-stm32/can/setenv.sh
    deleted file mode 100755
    index 1a4701269d..0000000000
    --- a/configs/olimexino-stm32/can/setenv.sh
    +++ /dev/null
    @@ -1,80 +0,0 @@
    -#!/bin/bash
    -# configs/olimexino-stm32/can/setenv.sh
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimexino-stm32/composite/setenv.sh b/configs/olimexino-stm32/composite/setenv.sh
    deleted file mode 100755
    index dd18f383b7..0000000000
    --- a/configs/olimexino-stm32/composite/setenv.sh
    +++ /dev/null
    @@ -1,80 +0,0 @@
    -#!/bin/bash
    -# configs/olimexino-stm32/composite/setenv.sh
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimexino-stm32/nsh/setenv.sh b/configs/olimexino-stm32/nsh/setenv.sh
    deleted file mode 100755
    index 025b27b553..0000000000
    --- a/configs/olimexino-stm32/nsh/setenv.sh
    +++ /dev/null
    @@ -1,80 +0,0 @@
    -#!/bin/bash
    -# configs/olimexino-stm32/nsh/setenv.sh
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimexino-stm32/smallnsh/setenv.sh b/configs/olimexino-stm32/smallnsh/setenv.sh
    deleted file mode 100755
    index 4ad764c09e..0000000000
    --- a/configs/olimexino-stm32/smallnsh/setenv.sh
    +++ /dev/null
    @@ -1,80 +0,0 @@
    -#!/bin/bash
    -# configs/olimexino-stm32/smallnsh/setenv.sh
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/olimexino-stm32/tiny/setenv.sh b/configs/olimexino-stm32/tiny/setenv.sh
    deleted file mode 100755
    index 99645f9e45..0000000000
    --- a/configs/olimexino-stm32/tiny/setenv.sh
    +++ /dev/null
    @@ -1,80 +0,0 @@
    -#!/bin/bash
    -# configs/olimexino-stm32/tiny/setenv.sh
    -#
    -#   Copyright (C) 2025 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/open1788/knsh/setenv.sh b/configs/open1788/knsh/setenv.sh
    deleted file mode 100755
    index 4418984233..0000000000
    --- a/configs/open1788/knsh/setenv.sh
    +++ /dev/null
    @@ -1,73 +0,0 @@
    -#!/bin/bash
    -# configs/open1788/knsh/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# The Olimex-lpc1766stk/tools directory
    -export LPCTOOL_DIR="${WD}/configs/open1788/tools"
    -
    -# Add the path to the toolchain and tools directory to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/open1788/nsh/setenv.sh b/configs/open1788/nsh/setenv.sh
    deleted file mode 100755
    index 84c8100e1b..0000000000
    --- a/configs/open1788/nsh/setenv.sh
    +++ /dev/null
    @@ -1,73 +0,0 @@
    -#!/bin/bash
    -# configs/open1788/nsh/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# The open1788/tools directory
    -export LPCTOOL_DIR="${WD}/configs/open1788/tools"
    -
    -# Add the path to the toolchain and tools directory to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/open1788/nxlines/setenv.sh b/configs/open1788/nxlines/setenv.sh
    deleted file mode 100755
    index c454f6ee30..0000000000
    --- a/configs/open1788/nxlines/setenv.sh
    +++ /dev/null
    @@ -1,73 +0,0 @@
    -#!/bin/bash
    -# configs/open1788/nxlines/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# The open1788/tools directory
    -export LPCTOOL_DIR="${WD}/configs/open1788/tools"
    -
    -# Add the path to the toolchain and tools directory to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/p112/scripts/setenv.sh b/configs/p112/scripts/setenv.sh
    deleted file mode 100755
    index c55027d622..0000000000
    --- a/configs/p112/scripts/setenv.sh
    +++ /dev/null
    @@ -1,66 +0,0 @@
    -#!/bin/bash
    -# configs/p112/ostest/setenv.sh
    -#
    -#   Copyright (C) 2007, 2008, 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -#
    -# This is the normal installation directory for SDCC under Linux, OSX
    -# or Linux:
    -#
    -export TOOLCHAIN_BIN=/usr/local/bin
    -
    -#
    -# This is the normal installation directory for SDCC under Windows
    -#
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/SDCC/bin"
    -
    -#
    -# Add the path to the toolchain to the PATH varialble
    -#
    -export PATH="${TOOLCHAIN_BIN}":/sbin:/usr/sbin:${PATH_ORIG}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/pcblogic-pic32mx/nsh/setenv.sh b/configs/pcblogic-pic32mx/nsh/setenv.sh
    deleted file mode 100755
    index 91f0b8f2cb..0000000000
    --- a/configs/pcblogic-pic32mx/nsh/setenv.sh
    +++ /dev/null
    @@ -1,61 +0,0 @@
    -#!/bin/bash
    -# configs/pcblogic-pic32mx/nsh/setenv.sh
    -#
    -#   Copyright (C) 2011-2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -# This is the Cygwin path to the location where I installed the MicroChip
    -# PIC32MX toolchain under windows.  This is *not* the default install
    -# location so you will probably have to edit this.  You will also have
    -# to edit this if you install a different version of if you install
    -# the Linux PIC32MX toolchain as well
    -export TOOLCHAIN_BIN="/cygdrive/c/MicroChip/mplabc32/v1.12/bin"
    -
    -# This is the path to the toosl subdirectory
    -export PIC32TOOL_DIR="${WD}/tools/pic32mx"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${PIC32TOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/pcduino-a10/nsh/setenv.sh b/configs/pcduino-a10/nsh/setenv.sh
    deleted file mode 100755
    index 4877f86e81..0000000000
    --- a/configs/pcduino-a10/nsh/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/pcduino-a10/nsh/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/photon/nsh/setenv.sh b/configs/photon/nsh/setenv.sh
    deleted file mode 100755
    index dae53bd478..0000000000
    --- a/configs/photon/nsh/setenv.sh
    +++ /dev/null
    @@ -1,84 +0,0 @@
    -#!/bin/bash
    -# configs/photon/nsh/setenv.sh
    -#
    -#   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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/photon/usbnsh/setenv.sh b/configs/photon/usbnsh/setenv.sh
    deleted file mode 100755
    index 40ce369964..0000000000
    --- a/configs/photon/usbnsh/setenv.sh
    +++ /dev/null
    @@ -1,84 +0,0 @@
    -#!/bin/bash
    -# configs/photon/usbnsh/setenv.sh
    -#
    -#   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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/pic32mx-starterkit/nsh/setenv.sh b/configs/pic32mx-starterkit/nsh/setenv.sh
    deleted file mode 100755
    index 7bfde6dd62..0000000000
    --- a/configs/pic32mx-starterkit/nsh/setenv.sh
    +++ /dev/null
    @@ -1,66 +0,0 @@
    -#!/bin/bash
    -# configs/pic32mx-starterkit/nsh/setenv.sh
    -#
    -#   Copyright (C) 2012, 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -# This is the Cygwin path to the location where I installed the MicroChip
    -# PIC32MX toolchain under windows.  This is *not* the default install
    -# location so you will probably have to edit this.  You will also have
    -# to edit this if you install a different version of if you install
    -# the Linux PIC32MX toolchain as well
    -export TOOLCHAIN_PREBIN="/cygdrive/c/MicroChip/mplabc32/v1.12/bin":
    -
    -# This is where I have the Pinquino toolchain installed
    -# Careful with the ordering in the PATH variable... there is an incompatible
    -# version of make in this directory too!
    -#export TOOLCHAIN_POSTBIN=:"/cygdrive/c/pinguino-11/compilers/p32/bin"
    -
    -# This is the path to the tools subdirectory
    -export PIC32TOOL_DIR="${WD}/tools/pic32mx"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_PREBIN}${PIC32TOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}${TOOLCHAIN_POSTBIN}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/pic32mx-starterkit/nsh2/setenv.sh b/configs/pic32mx-starterkit/nsh2/setenv.sh
    deleted file mode 100755
    index 3b2145ed3c..0000000000
    --- a/configs/pic32mx-starterkit/nsh2/setenv.sh
    +++ /dev/null
    @@ -1,66 +0,0 @@
    -#!/bin/bash
    -# configs/pic32mx-starterkit/nsh2/setenv.sh
    -#
    -#   Copyright (C) 2012, 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -# This is the Cygwin path to the location where I installed the MicroChip
    -# PIC32MX toolchain under windows.  This is *not* the default install
    -# location so you will probably have to edit this.  You will also have
    -# to edit this if you install a different version of if you install
    -# the Linux PIC32MX toolchain as well
    -export TOOLCHAIN_PREBIN="/cygdrive/c/MicroChip/mplabc32/v1.12/bin":
    -
    -# This is where I have the Pinquino toolchain installed
    -# Careful with the ordering in the PATH variable... there is an incompatible
    -# version of make in this directory too!
    -#export TOOLCHAIN_POSTBIN=:"/cygdrive/c/pinguino-11/compilers/p32/bin"
    -
    -# This is the path to the tools subdirectory
    -export PIC32TOOL_DIR="${WD}/tools/pic32mx"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_PREBIN}${PIC32TOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}${TOOLCHAIN_POSTBIN}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/pic32mx7mmb/nsh/setenv.sh b/configs/pic32mx7mmb/nsh/setenv.sh
    deleted file mode 100755
    index 82518d7404..0000000000
    --- a/configs/pic32mx7mmb/nsh/setenv.sh
    +++ /dev/null
    @@ -1,61 +0,0 @@
    -#!/bin/bash
    -# configs/pic32mx7mmb/nsh/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -# This is the Cygwin path to the location where I installed the MicroChip
    -# PIC32MX toolchain under windows.  This is *not* the default install
    -# location so you will probably have to edit this.  You will also have
    -# to edit this if you install a different version of if you install
    -# the Linux PIC32MX toolchain as well
    -export TOOLCHAIN_BIN="/cygdrive/c/MicroChip/mplabc32/v1.12/bin"
    -
    -# This is the path to the tools subdirectory
    -export PIC32TOOL_DIR="${WD}/tools/pic32mx"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:${PIC32TOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/pic32mz-starterkit/nsh/setenv.sh b/configs/pic32mz-starterkit/nsh/setenv.sh
    deleted file mode 100755
    index 255d73293f..0000000000
    --- a/configs/pic32mz-starterkit/nsh/setenv.sh
    +++ /dev/null
    @@ -1,68 +0,0 @@
    -#!/bin/bash
    -# configs/pic32mz-starterkit/nsh/setenv.sh
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -# This is the Cygwin path to the location where I installed the MicroChip
    -# PIC32MZ toolchain under windows.  This is *not* the default install
    -# location so you will probably have to edit this.  You will also have
    -# to edit this if you install a different version of if you install
    -# the Linux PIC32MZ toolchain as well
    -#export TOOLCHAIN_PREBIN="/cygdrive/c/Program Files (x86)/Microchip/xc32/v1.34/bin":
    -#export TOOLCHAIN_POSTBIN=
    -
    -# This is where I have the Pinquino toolchain installed
    -# Careful with the ordering in the PATH variable... there is an incompatible
    -# version of make in this directory too!
    -export TOOLCHAIN_PREBIN=
    -export TOOLCHAIN_POSTBIN=:"/cygdrive/c/pinguino-11/compilers/p32/bin"
    -
    -# This is the path to the tools subdirectory
    -export PIC32TOOL_DIR="${WD}/tools/pic32mx"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_PREBIN}${PIC32TOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}${TOOLCHAIN_POSTBIN}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/qemu-i486/nsh/setenv.sh b/configs/qemu-i486/nsh/setenv.sh
    deleted file mode 100755
    index 25ae59d71b..0000000000
    --- a/configs/qemu-i486/nsh/setenv.sh
    +++ /dev/null
    @@ -1,48 +0,0 @@
    -#!/bin/bash
    -# configs/qemu-i486/nsh/setenv.sh
    -#
    -#   Copyright (C) 2011 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
    -
    -# Uncomment and modify the following if you are using anything other
    -# than the system GCC
    -# WD=`pwd`
    -# export BUILDROOT_BIN="${WD}/../../../buildroot/build_i486/staging_dir/bin"
    -# export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/qemu-i486/ostest/setenv.sh b/configs/qemu-i486/ostest/setenv.sh
    deleted file mode 100755
    index f9c3bdec8d..0000000000
    --- a/configs/qemu-i486/ostest/setenv.sh
    +++ /dev/null
    @@ -1,48 +0,0 @@
    -#!/bin/bash
    -# configs/qemu-i486/ostest/setenv.sh
    -#
    -#   Copyright (C) 2011 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
    -
    -# Uncomment and modify the following if you are using anything other
    -# than the system GCC
    -# WD=`pwd`
    -# export BUILDROOT_BIN="${WD}/../../../buildroot/build_i486/staging_dir/bin"
    -# export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sabre-6quad/nsh/setenv.sh b/configs/sabre-6quad/nsh/setenv.sh
    deleted file mode 100755
    index e6eae01797..0000000000
    --- a/configs/sabre-6quad/nsh/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/sabre-6quad/nsh/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sabre-6quad/smp/setenv.sh b/configs/sabre-6quad/smp/setenv.sh
    deleted file mode 100644
    index 1d0eacadd5..0000000000
    --- a/configs/sabre-6quad/smp/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/sabre-6quad/smp/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sam3u-ek/knsh/setenv.sh b/configs/sam3u-ek/knsh/setenv.sh
    deleted file mode 100755
    index 844c14ebf4..0000000000
    --- a/configs/sam3u-ek/knsh/setenv.sh
    +++ /dev/null
    @@ -1,75 +0,0 @@
    -#!/bin/bash
    -# configs/sam3u-ek/knsh/setenv.sh
    -#
    -#   Copyright (C) 2011 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sam3u-ek/nsh/setenv.sh b/configs/sam3u-ek/nsh/setenv.sh
    deleted file mode 100755
    index 0bbec9cdf0..0000000000
    --- a/configs/sam3u-ek/nsh/setenv.sh
    +++ /dev/null
    @@ -1,74 +0,0 @@
    -#!/bin/bash
    -# configs/sam3u-ek/nsh/setenv.sh
    -#
    -#   Copyright (C) 2010 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sam3u-ek/nx/setenv.sh b/configs/sam3u-ek/nx/setenv.sh
    deleted file mode 100755
    index 60df5e7f15..0000000000
    --- a/configs/sam3u-ek/nx/setenv.sh
    +++ /dev/null
    @@ -1,74 +0,0 @@
    -#!/bin/bash
    -# configs/sam3u-ek/nx/setenv.sh
    -#
    -#   Copyright (C) 2010 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.
    -#
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sam3u-ek/nxwm/setenv.sh b/configs/sam3u-ek/nxwm/setenv.sh
    deleted file mode 100755
    index 75bbc22895..0000000000
    --- a/configs/sam3u-ek/nxwm/setenv.sh
    +++ /dev/null
    @@ -1,74 +0,0 @@
    -#!/bin/bash
    -# configs/sam3u-ek/nxwm/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sam4cmp-db/nsh/setenv.sh b/configs/sam4cmp-db/nsh/setenv.sh
    deleted file mode 100644
    index 651b20b308..0000000000
    --- a/configs/sam4cmp-db/nsh/setenv.sh
    +++ /dev/null
    @@ -1,73 +0,0 @@
    -#!/bin/bash
    -# configs/sam4cmp-db/nsh/setenv.sh
    -#
    -#   Copyright (C) 2016 Masayuki Ishikawa. All rights reserved.
    -#   Author: Masayuki Ishikawa 
    -#
    -# 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.
    -#
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sam4e-ek/nsh/setenv.sh b/configs/sam4e-ek/nsh/setenv.sh
    deleted file mode 100755
    index eb0b7a2e66..0000000000
    --- a/configs/sam4e-ek/nsh/setenv.sh
    +++ /dev/null
    @@ -1,69 +0,0 @@
    -#!/bin/bash
    -# configs/sam4e-ek/nsh/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sam4e-ek/nxwm/setenv.sh b/configs/sam4e-ek/nxwm/setenv.sh
    deleted file mode 100755
    index b227abda1a..0000000000
    --- a/configs/sam4e-ek/nxwm/setenv.sh
    +++ /dev/null
    @@ -1,69 +0,0 @@
    -#!/bin/bash
    -# configs/sam4e-ek/nxwm/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sam4e-ek/usbnsh/setenv.sh b/configs/sam4e-ek/usbnsh/setenv.sh
    deleted file mode 100755
    index 19f255a6c5..0000000000
    --- a/configs/sam4e-ek/usbnsh/setenv.sh
    +++ /dev/null
    @@ -1,69 +0,0 @@
    -#!/bin/bash
    -# configs/sam4e-ek/usbnsh/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sam4l-xplained/nsh/setenv.sh b/configs/sam4l-xplained/nsh/setenv.sh
    deleted file mode 100755
    index 46f9aec12e..0000000000
    --- a/configs/sam4l-xplained/nsh/setenv.sh
    +++ /dev/null
    @@ -1,74 +0,0 @@
    -#!/bin/bash
    -# configs/sam4l-xplained/nsh/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sam4s-xplained-pro/nsh/setenv.sh b/configs/sam4s-xplained-pro/nsh/setenv.sh
    deleted file mode 100755
    index b5c9eba437..0000000000
    --- a/configs/sam4s-xplained-pro/nsh/setenv.sh
    +++ /dev/null
    @@ -1,73 +0,0 @@
    -#!/bin/bash
    -# configs/sam4s-xplained-pro/nsh/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sam4s-xplained/nsh/setenv.sh b/configs/sam4s-xplained/nsh/setenv.sh
    deleted file mode 100755
    index 00fd3c9171..0000000000
    --- a/configs/sam4s-xplained/nsh/setenv.sh
    +++ /dev/null
    @@ -1,73 +0,0 @@
    -#!/bin/bash
    -# configs/sam4s-xplained/nsh/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sama5d2-xult/nsh/setenv.sh b/configs/sama5d2-xult/nsh/setenv.sh
    deleted file mode 100755
    index 4fac002303..0000000000
    --- a/configs/sama5d2-xult/nsh/setenv.sh
    +++ /dev/null
    @@ -1,81 +0,0 @@
    -#!/bin/bash
    -# configs/sama5d2-xult/nsh/setenv.sh
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sama5d3-xplained/bridge/setenv.sh b/configs/sama5d3-xplained/bridge/setenv.sh
    deleted file mode 100755
    index fb6fe50e33..0000000000
    --- a/configs/sama5d3-xplained/bridge/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/sama5d3-xplained/bridge/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sama5d3-xplained/nsh/setenv.sh b/configs/sama5d3-xplained/nsh/setenv.sh
    deleted file mode 100755
    index 99d755d8e5..0000000000
    --- a/configs/sama5d3-xplained/nsh/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/sama5d3-xplained/nsh/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sama5d3x-ek/demo/setenv.sh b/configs/sama5d3x-ek/demo/setenv.sh
    deleted file mode 100755
    index 6a0cb44297..0000000000
    --- a/configs/sama5d3x-ek/demo/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/sama5d3x-ek/demo/setenv.sh
    -#
    -#   Copyright (C) 2013-2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sama5d3x-ek/hello/setenv.sh b/configs/sama5d3x-ek/hello/setenv.sh
    deleted file mode 100755
    index 28f2a0dc6e..0000000000
    --- a/configs/sama5d3x-ek/hello/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/sama5d3x-ek/hello/setenv.sh
    -#
    -#   Copyright (C) 2013-2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sama5d3x-ek/norboot/setenv.sh b/configs/sama5d3x-ek/norboot/setenv.sh
    deleted file mode 100755
    index 77b6f71064..0000000000
    --- a/configs/sama5d3x-ek/norboot/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/sama5d3x-ek/norboot/setenv.sh
    -#
    -#   Copyright (C) 2013-2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sama5d3x-ek/nsh/setenv.sh b/configs/sama5d3x-ek/nsh/setenv.sh
    deleted file mode 100755
    index 0e95851bd2..0000000000
    --- a/configs/sama5d3x-ek/nsh/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/sama5d3x-ek/nsh/setenv.sh
    -#
    -#   Copyright (C) 2013-2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sama5d3x-ek/nx/setenv.sh b/configs/sama5d3x-ek/nx/setenv.sh
    deleted file mode 100755
    index c0685defc4..0000000000
    --- a/configs/sama5d3x-ek/nx/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/sama5d3x-ek/nx/setenv.sh
    -#
    -#   Copyright (C) 2013-2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sama5d3x-ek/nxplayer/setenv.sh b/configs/sama5d3x-ek/nxplayer/setenv.sh
    deleted file mode 100755
    index 722fb349da..0000000000
    --- a/configs/sama5d3x-ek/nxplayer/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/sama5d3x-ek/nxplayer/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sama5d3x-ek/nxwm/setenv.sh b/configs/sama5d3x-ek/nxwm/setenv.sh
    deleted file mode 100755
    index b1b4082aae..0000000000
    --- a/configs/sama5d3x-ek/nxwm/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/sama5d3x-ek/nxwm/setenv.sh
    -#
    -#   Copyright (C) 2013-2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sama5d3x-ek/ov2640/setenv.sh b/configs/sama5d3x-ek/ov2640/setenv.sh
    deleted file mode 100755
    index edbf185a00..0000000000
    --- a/configs/sama5d3x-ek/ov2640/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/sama5d3x-ek/ov2640/setenv.sh
    -#
    -#   Copyright (C) 2013-2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sama5d4-ek/at25boot/setenv.sh b/configs/sama5d4-ek/at25boot/setenv.sh
    deleted file mode 100755
    index 46b09fdf03..0000000000
    --- a/configs/sama5d4-ek/at25boot/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/sama5d4-ek/at25boot/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sama5d4-ek/bridge/setenv.sh b/configs/sama5d4-ek/bridge/setenv.sh
    deleted file mode 100755
    index 6e79738d83..0000000000
    --- a/configs/sama5d4-ek/bridge/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/sama5d4-ek/bridge/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sama5d4-ek/dramboot/setenv.sh b/configs/sama5d4-ek/dramboot/setenv.sh
    deleted file mode 100755
    index 5134c0db47..0000000000
    --- a/configs/sama5d4-ek/dramboot/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/sama5d4-ek/dramboot/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sama5d4-ek/elf/setenv.sh b/configs/sama5d4-ek/elf/setenv.sh
    deleted file mode 100755
    index 8fb6aed56c..0000000000
    --- a/configs/sama5d4-ek/elf/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/sama5d4-ek/elf/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sama5d4-ek/ipv6/setenv.sh b/configs/sama5d4-ek/ipv6/setenv.sh
    deleted file mode 100755
    index c8799c3199..0000000000
    --- a/configs/sama5d4-ek/ipv6/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/sama5d4-ek/ipv6/setenv.sh
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sama5d4-ek/knsh/setenv.sh b/configs/sama5d4-ek/knsh/setenv.sh
    deleted file mode 100755
    index cc959079d2..0000000000
    --- a/configs/sama5d4-ek/knsh/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/sama5d4-ek/knsh/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sama5d4-ek/nsh/setenv.sh b/configs/sama5d4-ek/nsh/setenv.sh
    deleted file mode 100755
    index 20d23074da..0000000000
    --- a/configs/sama5d4-ek/nsh/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/sama5d4-ek/nsh/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sama5d4-ek/nxwm/setenv.sh b/configs/sama5d4-ek/nxwm/setenv.sh
    deleted file mode 100755
    index 24da498910..0000000000
    --- a/configs/sama5d4-ek/nxwm/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/sama5d4-ek/nxwm/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sama5d4-ek/ramtest/setenv.sh b/configs/sama5d4-ek/ramtest/setenv.sh
    deleted file mode 100755
    index 9cab6f5a10..0000000000
    --- a/configs/sama5d4-ek/ramtest/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/sama5d4-ek/ramtest/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/samd20-xplained/nsh/setenv.sh b/configs/samd20-xplained/nsh/setenv.sh
    deleted file mode 100755
    index ef8ac510c8..0000000000
    --- a/configs/samd20-xplained/nsh/setenv.sh
    +++ /dev/null
    @@ -1,76 +0,0 @@
    -#!/bin/bash
    -# configs/samd20-xplained/nsh/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/samd21-xplained/nsh/setenv.sh b/configs/samd21-xplained/nsh/setenv.sh
    deleted file mode 100755
    index d7dacda8e0..0000000000
    --- a/configs/samd21-xplained/nsh/setenv.sh
    +++ /dev/null
    @@ -1,84 +0,0 @@
    -#!/bin/bash
    -# configs/samd21-xplained/nsh/setenv.sh
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/same70-xplained/netnsh/setenv.sh b/configs/same70-xplained/netnsh/setenv.sh
    deleted file mode 100755
    index 3bb7d494df..0000000000
    --- a/configs/same70-xplained/netnsh/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/samv7-xult/netnsh/Make.defs
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/same70-xplained/nsh/setenv.sh b/configs/same70-xplained/nsh/setenv.sh
    deleted file mode 100755
    index 45dc13b84f..0000000000
    --- a/configs/same70-xplained/nsh/setenv.sh
    +++ /dev/null
    @@ -1,80 +0,0 @@
    -#!/bin/bash
    -# configs/samv7-xult/nsh/Make.defs
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# The same70-xplained/tools directory
    -export TOOL_DIR="${WD}/configs/same70-xplained/tools"
    -
    -# Add the path to the toolchain and tools directory to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${TOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/saml21-xplained/nsh/setenv.sh b/configs/saml21-xplained/nsh/setenv.sh
    deleted file mode 100755
    index becbb993d7..0000000000
    --- a/configs/saml21-xplained/nsh/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/saml21-xplained/nsh/setenv.sh
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/samv71-xult/knsh/setenv.sh b/configs/samv71-xult/knsh/setenv.sh
    deleted file mode 100755
    index aab3d9b64c..0000000000
    --- a/configs/samv71-xult/knsh/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/samv7-xult/knsh/Make.defs
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/samv71-xult/module/setenv.sh b/configs/samv71-xult/module/setenv.sh
    deleted file mode 100755
    index 8fda2eca92..0000000000
    --- a/configs/samv71-xult/module/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/samv7-xult/nsh/Make.defs
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/samv71-xult/mxtxplnd/setenv.sh b/configs/samv71-xult/mxtxplnd/setenv.sh
    deleted file mode 100755
    index c215192fa2..0000000000
    --- a/configs/samv71-xult/mxtxplnd/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/samv7-xult/mxtxplnd/Make.defs
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/samv71-xult/netnsh/setenv.sh b/configs/samv71-xult/netnsh/setenv.sh
    deleted file mode 100755
    index 3bb7d494df..0000000000
    --- a/configs/samv71-xult/netnsh/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/samv7-xult/netnsh/Make.defs
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/samv71-xult/nsh/setenv.sh b/configs/samv71-xult/nsh/setenv.sh
    deleted file mode 100755
    index 8fda2eca92..0000000000
    --- a/configs/samv71-xult/nsh/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/samv7-xult/nsh/Make.defs
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/samv71-xult/nxwm/setenv.sh b/configs/samv71-xult/nxwm/setenv.sh
    deleted file mode 100755
    index f260a338ba..0000000000
    --- a/configs/samv71-xult/nxwm/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/samv7-xult/nxwm/Make.defs
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/samv71-xult/vnc/setenv.sh b/configs/samv71-xult/vnc/setenv.sh
    deleted file mode 100644
    index 873796c9b0..0000000000
    --- a/configs/samv71-xult/vnc/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/samv7-xult/vnc/Make.defs
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/samv71-xult/vnxwm/setenv.sh b/configs/samv71-xult/vnxwm/setenv.sh
    deleted file mode 100644
    index c3756d2330..0000000000
    --- a/configs/samv71-xult/vnxwm/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/samv7-xult/vnxwm/Make.defs
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/shenzhou/nsh/setenv.sh b/configs/shenzhou/nsh/setenv.sh
    deleted file mode 100755
    index 79f9579706..0000000000
    --- a/configs/shenzhou/nsh/setenv.sh
    +++ /dev/null
    @@ -1,78 +0,0 @@
    -#!/bin/bash
    -# configs/shenzhou/nsh/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the path to the tools/ subdirectory
    -export TOOLS_DIR="${WD}/configs/shenzhou/tools"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:${TOOLS_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/shenzhou/nxwm/setenv.sh b/configs/shenzhou/nxwm/setenv.sh
    deleted file mode 100755
    index 01edb1d57e..0000000000
    --- a/configs/shenzhou/nxwm/setenv.sh
    +++ /dev/null
    @@ -1,78 +0,0 @@
    -#!/bin/bash
    -# configs/shenzhou/nxwm/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the path to the tools/ subdirectory
    -export TOOLS_DIR="${WD}/configs/shenzhou/tools"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:${TOOLS_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/shenzhou/thttpd/setenv.sh b/configs/shenzhou/thttpd/setenv.sh
    deleted file mode 100755
    index 8cc31a4e01..0000000000
    --- a/configs/shenzhou/thttpd/setenv.sh
    +++ /dev/null
    @@ -1,78 +0,0 @@
    -#!/bin/bash
    -# configs/shenzhou/thttpd/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the path to the tools/ subdirectory
    -export TOOLS_DIR="${WD}/configs/shenzhou/tools"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:${TOOLS_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sim/bas/setenv.sh b/configs/sim/bas/setenv.sh
    deleted file mode 100755
    index fea05ff5c3..0000000000
    --- a/configs/sim/bas/setenv.sh
    +++ /dev/null
    @@ -1,45 +0,0 @@
    -#!/bin/bash
    -# configs/sim/bas/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
    -
    -#export NUTTX_BIN=
    -#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sim/configdata/setenv.sh b/configs/sim/configdata/setenv.sh
    deleted file mode 100755
    index 7d099b071a..0000000000
    --- a/configs/sim/configdata/setenv.sh
    +++ /dev/null
    @@ -1,55 +0,0 @@
    -#!/bin/bash
    -# confisgs/sim/configdata/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# Add the path to the toolchain to the PATH variable
    -
    -#export NUTTX_BIN=
    -#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sim/cxxtest/setenv.sh b/configs/sim/cxxtest/setenv.sh
    deleted file mode 100755
    index c35ba6501f..0000000000
    --- a/configs/sim/cxxtest/setenv.sh
    +++ /dev/null
    @@ -1,45 +0,0 @@
    -#!/bin/bash
    -# configs/sim/cxxtext/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
    -
    -#export NUTTX_BIN=
    -#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sim/minibasic/setenv.sh b/configs/sim/minibasic/setenv.sh
    deleted file mode 100644
    index bc88903e63..0000000000
    --- a/configs/sim/minibasic/setenv.sh
    +++ /dev/null
    @@ -1,45 +0,0 @@
    -#!/bin/bash
    -# sim/minibasic/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
    -
    -#export NUTTX_BIN=
    -#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sim/mount/setenv.sh b/configs/sim/mount/setenv.sh
    deleted file mode 100755
    index 318e1628e5..0000000000
    --- a/configs/sim/mount/setenv.sh
    +++ /dev/null
    @@ -1,45 +0,0 @@
    -#!/bin/bash
    -# sim/setenv.sh
    -#
    -#   Copyright (C) 2008 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
    -
    -#export NUTTX_BIN=
    -#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sim/mtdpart/setenv.sh b/configs/sim/mtdpart/setenv.sh
    deleted file mode 100755
    index 2f5c6f40b0..0000000000
    --- a/configs/sim/mtdpart/setenv.sh
    +++ /dev/null
    @@ -1,45 +0,0 @@
    -#!/bin/bash
    -# confisgs/sim/mtdpart/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
    -
    -#export NUTTX_BIN=
    -#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sim/mtdrwb/setenv.sh b/configs/sim/mtdrwb/setenv.sh
    deleted file mode 100755
    index 7b00da1bc7..0000000000
    --- a/configs/sim/mtdrwb/setenv.sh
    +++ /dev/null
    @@ -1,45 +0,0 @@
    -#!/bin/bash
    -# confisgs/sim/mtdrwb/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
    -
    -#export NUTTX_BIN=
    -#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sim/nettest/setenv.sh b/configs/sim/nettest/setenv.sh
    deleted file mode 100755
    index 273e418ee1..0000000000
    --- a/configs/sim/nettest/setenv.sh
    +++ /dev/null
    @@ -1,45 +0,0 @@
    -#!/bin/bash
    -# sim/setenv.sh
    -#
    -#   Copyright (C) 2007, 2008 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
    -
    -#export NUTTX_BIN=
    -#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sim/nsh/setenv.sh b/configs/sim/nsh/setenv.sh
    deleted file mode 100755
    index c629c5a1ec..0000000000
    --- a/configs/sim/nsh/setenv.sh
    +++ /dev/null
    @@ -1,45 +0,0 @@
    -#!/bin/bash
    -# sim/nsh/setenv.sh
    -#
    -#   Copyright (C) 2008 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
    -
    -#export NUTTX_BIN=
    -#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sim/nsh2/setenv.sh b/configs/sim/nsh2/setenv.sh
    deleted file mode 100755
    index 78204f6ebd..0000000000
    --- a/configs/sim/nsh2/setenv.sh
    +++ /dev/null
    @@ -1,45 +0,0 @@
    -#!/bin/bash
    -# sim/nsh2/setenv.sh
    -#
    -#   Copyright (C) 2011 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
    -
    -#export NUTTX_BIN=
    -#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sim/nx/setenv.sh b/configs/sim/nx/setenv.sh
    deleted file mode 100755
    index 764d2a8be7..0000000000
    --- a/configs/sim/nx/setenv.sh
    +++ /dev/null
    @@ -1,45 +0,0 @@
    -#!/bin/bash
    -# sim/nx/setenv.sh
    -#
    -#   Copyright (C) 2008 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
    -
    -#export NUTTX_BIN=
    -#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sim/nx11/setenv.sh b/configs/sim/nx11/setenv.sh
    deleted file mode 100755
    index a9371a9d23..0000000000
    --- a/configs/sim/nx11/setenv.sh
    +++ /dev/null
    @@ -1,45 +0,0 @@
    -#!/bin/bash
    -# sim/nx11/setenv.sh
    -#
    -#   Copyright (C) 2008, 2011 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
    -
    -#export NUTTX_BIN=
    -#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sim/nxffs/setenv.sh b/configs/sim/nxffs/setenv.sh
    deleted file mode 100755
    index 3aa03bc988..0000000000
    --- a/configs/sim/nxffs/setenv.sh
    +++ /dev/null
    @@ -1,45 +0,0 @@
    -#!/bin/bash
    -# confisgs/sim/nxffs/setenv.sh
    -#
    -#   Copyright (C) 2007, 2008 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
    -
    -#export NUTTX_BIN=
    -#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sim/nxlines/setenv.sh b/configs/sim/nxlines/setenv.sh
    deleted file mode 100755
    index 0722cbc2ee..0000000000
    --- a/configs/sim/nxlines/setenv.sh
    +++ /dev/null
    @@ -1,53 +0,0 @@
    -#!/bin/bash
    -# sim/nxlines/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -#export NUTTX_BIN=
    -#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sim/nxwm/setenv.sh b/configs/sim/nxwm/setenv.sh
    deleted file mode 100755
    index a3e949cda9..0000000000
    --- a/configs/sim/nxwm/setenv.sh
    +++ /dev/null
    @@ -1,45 +0,0 @@
    -#!/bin/bash
    -# sim/nxwm/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
    -
    -#export NUTTX_BIN=
    -#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sim/ostest/setenv.sh b/configs/sim/ostest/setenv.sh
    deleted file mode 100755
    index f13d73ee42..0000000000
    --- a/configs/sim/ostest/setenv.sh
    +++ /dev/null
    @@ -1,45 +0,0 @@
    -#!/bin/bash
    -# configs/sim/ostest/setenv.sh
    -#
    -#   Copyright (C) 2007, 2008 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
    -
    -#export NUTTX_BIN=
    -#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sim/pashello/setenv.sh b/configs/sim/pashello/setenv.sh
    deleted file mode 100755
    index 273e418ee1..0000000000
    --- a/configs/sim/pashello/setenv.sh
    +++ /dev/null
    @@ -1,45 +0,0 @@
    -#!/bin/bash
    -# sim/setenv.sh
    -#
    -#   Copyright (C) 2007, 2008 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
    -
    -#export NUTTX_BIN=
    -#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sim/sixlowpan/setenv.sh b/configs/sim/sixlowpan/setenv.sh
    deleted file mode 100644
    index 65065ccc9b..0000000000
    --- a/configs/sim/sixlowpan/setenv.sh
    +++ /dev/null
    @@ -1,45 +0,0 @@
    -#!/bin/bash
    -# sim/sixlowpan/setenv.sh
    -#
    -#   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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
    -
    -#export NUTTX_BIN=
    -#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sim/touchscreen/setenv.sh b/configs/sim/touchscreen/setenv.sh
    deleted file mode 100755
    index 4cc3bba576..0000000000
    --- a/configs/sim/touchscreen/setenv.sh
    +++ /dev/null
    @@ -1,45 +0,0 @@
    -#!/bin/bash
    -# sim/touchscreen/setenv.sh
    -#
    -#   Copyright (C) 2011 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
    -
    -#export NUTTX_BIN=
    -#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sim/traveler/setenv.sh b/configs/sim/traveler/setenv.sh
    deleted file mode 100755
    index aaa54bd58c..0000000000
    --- a/configs/sim/traveler/setenv.sh
    +++ /dev/null
    @@ -1,45 +0,0 @@
    -#!/bin/bash
    -# sim/traveler/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
    -
    -#export NUTTX_BIN=
    -#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sim/udgram/setenv.sh b/configs/sim/udgram/setenv.sh
    deleted file mode 100755
    index ac82379203..0000000000
    --- a/configs/sim/udgram/setenv.sh
    +++ /dev/null
    @@ -1,45 +0,0 @@
    -#!/bin/bash
    -# sim/udgram/setenv.sh
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
    -
    -#export NUTTX_BIN=
    -#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sim/unionfs/setenv.sh b/configs/sim/unionfs/setenv.sh
    deleted file mode 100755
    index 8ef7388a6b..0000000000
    --- a/configs/sim/unionfs/setenv.sh
    +++ /dev/null
    @@ -1,45 +0,0 @@
    -#!/bin/bash
    -# sim/unionfs/setenv.sh
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
    -
    -#export NUTTX_BIN=
    -#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sim/ustream/setenv.sh b/configs/sim/ustream/setenv.sh
    deleted file mode 100755
    index acede5c7ff..0000000000
    --- a/configs/sim/ustream/setenv.sh
    +++ /dev/null
    @@ -1,45 +0,0 @@
    -#!/bin/bash
    -# sim/ustream/setenv.sh
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
    -
    -#export NUTTX_BIN=
    -#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/skp16c26/ostest/setenv.sh b/configs/skp16c26/ostest/setenv.sh
    deleted file mode 100755
    index a74258fb84..0000000000
    --- a/configs/skp16c26/ostest/setenv.sh
    +++ /dev/null
    @@ -1,46 +0,0 @@
    -#!/bin/bash
    -# configs/skp16c26/ostest/setenv.sh
    -#
    -#   Copyright (C) 2009 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
    -
    -WD=`pwd`
    -export BUILDROOT_BIN=${WD}/../buildroot/build_m32c/staging_dir/bin
    -export PATH=${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/spark/composite/setenv.sh b/configs/spark/composite/setenv.sh
    deleted file mode 100755
    index cda83fd1a9..0000000000
    --- a/configs/spark/composite/setenv.sh
    +++ /dev/null
    @@ -1,67 +0,0 @@
    -#!/bin/bash
    -# configs/spark/composite/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/spark/nsh/setenv.sh b/configs/spark/nsh/setenv.sh
    deleted file mode 100755
    index 66aa9427f5..0000000000
    --- a/configs/spark/nsh/setenv.sh
    +++ /dev/null
    @@ -1,63 +0,0 @@
    -#!/bin/bash
    -# configs/spark/nsh/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -
    -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the path to the Spark tools directory
    -
    -export TOOL_BIN="${WD}/configs/spark/tools"
    -
    -# Update the PATH variable
    -
    -export PATH="${BUILDROOT_BIN}:${TOOL_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/spark/usbmsc/setenv.sh b/configs/spark/usbmsc/setenv.sh
    deleted file mode 100755
    index ce036735e4..0000000000
    --- a/configs/spark/usbmsc/setenv.sh
    +++ /dev/null
    @@ -1,63 +0,0 @@
    -#!/bin/bash
    -# configs/spark/usbmsc/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -
    -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the path to the Spark tools directory
    -
    -export TOOL_BIN="${WD}/configs/spark/tools"
    -
    -# Update the PATH variable
    -
    -export PATH="${BUILDROOT_BIN}:${TOOL_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/spark/usbnsh/setenv.sh b/configs/spark/usbnsh/setenv.sh
    deleted file mode 100755
    index 993cd659c4..0000000000
    --- a/configs/spark/usbnsh/setenv.sh
    +++ /dev/null
    @@ -1,63 +0,0 @@
    -#!/bin/bash
    -# configs/spark/usbnsh/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -
    -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the path to the Spark tools directory
    -
    -export TOOL_BIN="${WD}/configs/spark/tools"
    -
    -# Update the PATH variable
    -
    -export PATH="${BUILDROOT_BIN}:${TOOL_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/spark/usbserial/setenv.sh b/configs/spark/usbserial/setenv.sh
    deleted file mode 100755
    index ba280ce1ff..0000000000
    --- a/configs/spark/usbserial/setenv.sh
    +++ /dev/null
    @@ -1,67 +0,0 @@
    -#!/bin/bash
    -# configs/spark/usbserial/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm3210e-eval/composite/setenv.sh b/configs/stm3210e-eval/composite/setenv.sh
    deleted file mode 100755
    index 742f508dde..0000000000
    --- a/configs/stm3210e-eval/composite/setenv.sh
    +++ /dev/null
    @@ -1,67 +0,0 @@
    -#!/bin/bash
    -# configs/stm3210e-eval/composite/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm3210e-eval/nsh/setenv.sh b/configs/stm3210e-eval/nsh/setenv.sh
    deleted file mode 100755
    index 6fa000ee1f..0000000000
    --- a/configs/stm3210e-eval/nsh/setenv.sh
    +++ /dev/null
    @@ -1,76 +0,0 @@
    -#!/bin/bash
    -# configs/stm3210e-eval/dfu/setenv.sh
    -#
    -#   Copyright (C) 2009 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm3210e-eval/nsh2/setenv.sh b/configs/stm3210e-eval/nsh2/setenv.sh
    deleted file mode 100755
    index e90b81c767..0000000000
    --- a/configs/stm3210e-eval/nsh2/setenv.sh
    +++ /dev/null
    @@ -1,67 +0,0 @@
    -#!/bin/bash
    -# configs/stm3210e-eval/nsh2/setenv.sh
    -#
    -#   Copyright (C) 2011 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm3210e-eval/nx/setenv.sh b/configs/stm3210e-eval/nx/setenv.sh
    deleted file mode 100755
    index bc83a0b334..0000000000
    --- a/configs/stm3210e-eval/nx/setenv.sh
    +++ /dev/null
    @@ -1,62 +0,0 @@
    -#!/bin/bash
    -# configs/stm3210e-eval/nx/setenv.sh
    -#
    -#   Copyright (C) 2011 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm3210e-eval/nxterm/setenv.sh b/configs/stm3210e-eval/nxterm/setenv.sh
    deleted file mode 100755
    index a5e76a5113..0000000000
    --- a/configs/stm3210e-eval/nxterm/setenv.sh
    +++ /dev/null
    @@ -1,62 +0,0 @@
    -#!/bin/bash
    -# configs/stm3210e-eval/nxterm/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm3210e-eval/pm/setenv.sh b/configs/stm3210e-eval/pm/setenv.sh
    deleted file mode 100755
    index dacfc95863..0000000000
    --- a/configs/stm3210e-eval/pm/setenv.sh
    +++ /dev/null
    @@ -1,67 +0,0 @@
    -#!/bin/bash
    -# configs/stm3210e-eval/pm/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm3210e-eval/usbmsc/setenv.sh b/configs/stm3210e-eval/usbmsc/setenv.sh
    deleted file mode 100755
    index ee33a8d21d..0000000000
    --- a/configs/stm3210e-eval/usbmsc/setenv.sh
    +++ /dev/null
    @@ -1,47 +0,0 @@
    -#!/bin/bash
    -# configs/stm3210e-eval/dfu/setenv.sh
    -#
    -#   Copyright (C) 2009 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin"
    -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm3210e-eval/usbserial/setenv.sh b/configs/stm3210e-eval/usbserial/setenv.sh
    deleted file mode 100755
    index 046a7f5acf..0000000000
    --- a/configs/stm3210e-eval/usbserial/setenv.sh
    +++ /dev/null
    @@ -1,47 +0,0 @@
    -#!/bin/bash
    -# configs/stm3210e-eval/ostest/setenv.sh
    -#
    -#   Copyright (C) 2009 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin"
    -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm3220g-eval/dhcpd/setenv.sh b/configs/stm3220g-eval/dhcpd/setenv.sh
    deleted file mode 100755
    index 931d4d1cad..0000000000
    --- a/configs/stm3220g-eval/dhcpd/setenv.sh
    +++ /dev/null
    @@ -1,75 +0,0 @@
    -#!/bin/bash
    -# configs/stm3220g-eval/dhcpd/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm3220g-eval/nettest/setenv.sh b/configs/stm3220g-eval/nettest/setenv.sh
    deleted file mode 100755
    index a870dec990..0000000000
    --- a/configs/stm3220g-eval/nettest/setenv.sh
    +++ /dev/null
    @@ -1,75 +0,0 @@
    -#!/bin/bash
    -# configs/stm3220g-eval/nettest/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm3220g-eval/nsh/setenv.sh b/configs/stm3220g-eval/nsh/setenv.sh
    deleted file mode 100755
    index 489322177a..0000000000
    --- a/configs/stm3220g-eval/nsh/setenv.sh
    +++ /dev/null
    @@ -1,75 +0,0 @@
    -#!/bin/bash
    -# configs/stm3220g-eval/nsh/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm3220g-eval/nsh2/setenv.sh b/configs/stm3220g-eval/nsh2/setenv.sh
    deleted file mode 100755
    index 1e2f87b403..0000000000
    --- a/configs/stm3220g-eval/nsh2/setenv.sh
    +++ /dev/null
    @@ -1,74 +0,0 @@
    -#!/bin/bash
    -# configs/stm3220g-eval/nsh2/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm3220g-eval/nxwm/setenv.sh b/configs/stm3220g-eval/nxwm/setenv.sh
    deleted file mode 100755
    index 913968e2a5..0000000000
    --- a/configs/stm3220g-eval/nxwm/setenv.sh
    +++ /dev/null
    @@ -1,75 +0,0 @@
    -#!/bin/bash
    -# configs/stm3220g-eval/nxwm/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm3220g-eval/telnetd/setenv.sh b/configs/stm3220g-eval/telnetd/setenv.sh
    deleted file mode 100755
    index d96f6fa63f..0000000000
    --- a/configs/stm3220g-eval/telnetd/setenv.sh
    +++ /dev/null
    @@ -1,75 +0,0 @@
    -#!/bin/bash
    -# configs/stm3220g-eval/telnetd/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm3240g-eval/dhcpd/setenv.sh b/configs/stm3240g-eval/dhcpd/setenv.sh
    deleted file mode 100755
    index ebf0963f1f..0000000000
    --- a/configs/stm3240g-eval/dhcpd/setenv.sh
    +++ /dev/null
    @@ -1,76 +0,0 @@
    -#!/bin/bash
    -# configs/stm3240g-eval/dhcpd/setenv.sh
    -#
    -#   Copyright (C) 2011-2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm3240g-eval/discover/setenv.sh b/configs/stm3240g-eval/discover/setenv.sh
    deleted file mode 100755
    index 71bb2e32c1..0000000000
    --- a/configs/stm3240g-eval/discover/setenv.sh
    +++ /dev/null
    @@ -1,76 +0,0 @@
    -#!/bin/bash
    -# configs/stm3240g-eval/discover/setenv.sh
    -#
    -#   Copyright (C) 2011-2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm3240g-eval/knxwm/setenv.sh b/configs/stm3240g-eval/knxwm/setenv.sh
    deleted file mode 100755
    index ce7c852735..0000000000
    --- a/configs/stm3240g-eval/knxwm/setenv.sh
    +++ /dev/null
    @@ -1,72 +0,0 @@
    -#!/bin/bash
    -# configs/stm3240g-eval/knxwm/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm3240g-eval/nettest/setenv.sh b/configs/stm3240g-eval/nettest/setenv.sh
    deleted file mode 100755
    index 3d0270f282..0000000000
    --- a/configs/stm3240g-eval/nettest/setenv.sh
    +++ /dev/null
    @@ -1,76 +0,0 @@
    -#!/bin/bash
    -# configs/stm3240g-eval/nettest/setenv.sh
    -#
    -#   Copyright (C) 2011-2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm3240g-eval/nsh/setenv.sh b/configs/stm3240g-eval/nsh/setenv.sh
    deleted file mode 100755
    index c6233ddd8f..0000000000
    --- a/configs/stm3240g-eval/nsh/setenv.sh
    +++ /dev/null
    @@ -1,76 +0,0 @@
    -#!/bin/bash
    -# configs/stm3240g-eval/nsh/setenv.sh
    -#
    -#   Copyright (C) 2011-2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm3240g-eval/nsh2/setenv.sh b/configs/stm3240g-eval/nsh2/setenv.sh
    deleted file mode 100755
    index 2fe27a60d2..0000000000
    --- a/configs/stm3240g-eval/nsh2/setenv.sh
    +++ /dev/null
    @@ -1,76 +0,0 @@
    -#!/bin/bash
    -# configs/stm3240g-eval/nsh/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm3240g-eval/nxterm/setenv.sh b/configs/stm3240g-eval/nxterm/setenv.sh
    deleted file mode 100755
    index 1b9eb92208..0000000000
    --- a/configs/stm3240g-eval/nxterm/setenv.sh
    +++ /dev/null
    @@ -1,76 +0,0 @@
    -#!/bin/bash
    -# configs/stm3240g-eval/nxterm/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm3240g-eval/nxwm/setenv.sh b/configs/stm3240g-eval/nxwm/setenv.sh
    deleted file mode 100755
    index db6e1e5d98..0000000000
    --- a/configs/stm3240g-eval/nxwm/setenv.sh
    +++ /dev/null
    @@ -1,72 +0,0 @@
    -#!/bin/bash
    -# configs/stm3240g-eval/nxwm/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm3240g-eval/telnetd/setenv.sh b/configs/stm3240g-eval/telnetd/setenv.sh
    deleted file mode 100755
    index 7da487bd53..0000000000
    --- a/configs/stm3240g-eval/telnetd/setenv.sh
    +++ /dev/null
    @@ -1,76 +0,0 @@
    -#!/bin/bash
    -# configs/stm3240g-eval/telnetd/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm3240g-eval/webserver/setenv.sh b/configs/stm3240g-eval/webserver/setenv.sh
    deleted file mode 100755
    index 779605964e..0000000000
    --- a/configs/stm3240g-eval/webserver/setenv.sh
    +++ /dev/null
    @@ -1,76 +0,0 @@
    -#!/bin/bash
    -# configs/stm3240g-eval/webserver/setenv.sh
    -#
    -#   Copyright (C) 2011-2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm3240g-eval/xmlrpc/setenv.sh b/configs/stm3240g-eval/xmlrpc/setenv.sh
    deleted file mode 100755
    index b73264106b..0000000000
    --- a/configs/stm3240g-eval/xmlrpc/setenv.sh
    +++ /dev/null
    @@ -1,76 +0,0 @@
    -#!/bin/bash
    -# configs/stm3240g-eval/xmlrpc/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32_tiny/nsh/setenv.sh b/configs/stm32_tiny/nsh/setenv.sh
    deleted file mode 100755
    index 2edc70b732..0000000000
    --- a/configs/stm32_tiny/nsh/setenv.sh
    +++ /dev/null
    @@ -1,47 +0,0 @@
    -#!/bin/bash
    -# configs/stm32_tiny/nsh/setenv.sh
    -#
    -#   Copyright (C) 2011, 2013 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin"
    -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32_tiny/usbnsh/setenv.sh b/configs/stm32_tiny/usbnsh/setenv.sh
    deleted file mode 100755
    index 1fdbb9687e..0000000000
    --- a/configs/stm32_tiny/usbnsh/setenv.sh
    +++ /dev/null
    @@ -1,47 +0,0 @@
    -#!/bin/bash
    -# configs/stm32_tiny/usbnsh/setenv.sh
    -#
    -#   Copyright (C) 2011, 2013 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin"
    -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32butterfly2/nsh/setenv.sh b/configs/stm32butterfly2/nsh/setenv.sh
    deleted file mode 100755
    index da893d41e6..0000000000
    --- a/configs/stm32butterfly2/nsh/setenv.sh
    +++ /dev/null
    @@ -1,78 +0,0 @@
    -#!/bin/bash
    -# configs/stm32butterfly2/nsh/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32butterfly2/nshnet/setenv.sh b/configs/stm32butterfly2/nshnet/setenv.sh
    deleted file mode 100755
    index da893d41e6..0000000000
    --- a/configs/stm32butterfly2/nshnet/setenv.sh
    +++ /dev/null
    @@ -1,78 +0,0 @@
    -#!/bin/bash
    -# configs/stm32butterfly2/nsh/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32butterfly2/nshusbdev/setenv.sh b/configs/stm32butterfly2/nshusbdev/setenv.sh
    deleted file mode 100755
    index da893d41e6..0000000000
    --- a/configs/stm32butterfly2/nshusbdev/setenv.sh
    +++ /dev/null
    @@ -1,78 +0,0 @@
    -#!/bin/bash
    -# configs/stm32butterfly2/nsh/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32butterfly2/nshusbhost/setenv.sh b/configs/stm32butterfly2/nshusbhost/setenv.sh
    deleted file mode 100755
    index da893d41e6..0000000000
    --- a/configs/stm32butterfly2/nshusbhost/setenv.sh
    +++ /dev/null
    @@ -1,78 +0,0 @@
    -#!/bin/bash
    -# configs/stm32butterfly2/nsh/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f0discovery/nsh/setenv.sh b/configs/stm32f0discovery/nsh/setenv.sh
    deleted file mode 100644
    index b8584be9c3..0000000000
    --- a/configs/stm32f0discovery/nsh/setenv.sh
    +++ /dev/null
    @@ -1,81 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f0discovery/nsh/setenv.sh
    -#
    -#   Copyright (C) 2017 Gregory Nutt. All rights reserved.
    -#   Author: Gregory Nutt 
    -#           Alan Carvalho de Assis 
    -#
    -# 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f103-minimum/audio_tone/setenv.sh b/configs/stm32f103-minimum/audio_tone/setenv.sh
    deleted file mode 100644
    index 665d744a6e..0000000000
    --- a/configs/stm32f103-minimum/audio_tone/setenv.sh
    +++ /dev/null
    @@ -1,100 +0,0 @@
    -#!/bin/bash
    -# configs//stm32f103-minimum/audio_tone/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -# 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f103-minimum/buttons/setenv.sh b/configs/stm32f103-minimum/buttons/setenv.sh
    deleted file mode 100644
    index 73dfab5a4d..0000000000
    --- a/configs/stm32f103-minimum/buttons/setenv.sh
    +++ /dev/null
    @@ -1,100 +0,0 @@
    -#!/bin/bash
    -# configs//stm32f103-minimum/nsh/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -# 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f103-minimum/jlx12864g/setenv.sh b/configs/stm32f103-minimum/jlx12864g/setenv.sh
    deleted file mode 100644
    index 4a9a11eff2..0000000000
    --- a/configs/stm32f103-minimum/jlx12864g/setenv.sh
    +++ /dev/null
    @@ -1,100 +0,0 @@
    -#!/bin/bash
    -# configs//stm32f103-minimum/jlx12864g/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -# 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f103-minimum/nrf24/setenv.sh b/configs/stm32f103-minimum/nrf24/setenv.sh
    deleted file mode 100644
    index 1cba74e39d..0000000000
    --- a/configs/stm32f103-minimum/nrf24/setenv.sh
    +++ /dev/null
    @@ -1,100 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f103-minimum/nrf24/setenv.sh
    -#
    -#   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.
    -#
    -
    -# 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f103-minimum/nsh/setenv.sh b/configs/stm32f103-minimum/nsh/setenv.sh
    deleted file mode 100644
    index 73dfab5a4d..0000000000
    --- a/configs/stm32f103-minimum/nsh/setenv.sh
    +++ /dev/null
    @@ -1,100 +0,0 @@
    -#!/bin/bash
    -# configs//stm32f103-minimum/nsh/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -# 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f103-minimum/pwm/setenv.sh b/configs/stm32f103-minimum/pwm/setenv.sh
    deleted file mode 100644
    index 73dfab5a4d..0000000000
    --- a/configs/stm32f103-minimum/pwm/setenv.sh
    +++ /dev/null
    @@ -1,100 +0,0 @@
    -#!/bin/bash
    -# configs//stm32f103-minimum/nsh/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -# 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f103-minimum/rfid-rc522/setenv.sh b/configs/stm32f103-minimum/rfid-rc522/setenv.sh
    deleted file mode 100644
    index a6e5649389..0000000000
    --- a/configs/stm32f103-minimum/rfid-rc522/setenv.sh
    +++ /dev/null
    @@ -1,100 +0,0 @@
    -#!/bin/bash
    -# configs//stm32f103-minimum/rfid-rc522/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -# 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f103-minimum/rgbled/setenv.sh b/configs/stm32f103-minimum/rgbled/setenv.sh
    deleted file mode 100644
    index 73dfab5a4d..0000000000
    --- a/configs/stm32f103-minimum/rgbled/setenv.sh
    +++ /dev/null
    @@ -1,100 +0,0 @@
    -#!/bin/bash
    -# configs//stm32f103-minimum/nsh/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -# 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f103-minimum/usbnsh/setenv.sh b/configs/stm32f103-minimum/usbnsh/setenv.sh
    deleted file mode 100644
    index aaf02b991b..0000000000
    --- a/configs/stm32f103-minimum/usbnsh/setenv.sh
    +++ /dev/null
    @@ -1,72 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f103-minimum/usbnsh/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f103-minimum/userled/setenv.sh b/configs/stm32f103-minimum/userled/setenv.sh
    deleted file mode 100644
    index 73dfab5a4d..0000000000
    --- a/configs/stm32f103-minimum/userled/setenv.sh
    +++ /dev/null
    @@ -1,100 +0,0 @@
    -#!/bin/bash
    -# configs//stm32f103-minimum/nsh/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -# 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f103-minimum/veml6070/setenv.sh b/configs/stm32f103-minimum/veml6070/setenv.sh
    deleted file mode 100644
    index efcbfee142..0000000000
    --- a/configs/stm32f103-minimum/veml6070/setenv.sh
    +++ /dev/null
    @@ -1,100 +0,0 @@
    -#!/bin/bash
    -# configs//stm32f103-minimum/veml6070/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -# 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f3discovery/nsh/setenv.sh b/configs/stm32f3discovery/nsh/setenv.sh
    deleted file mode 100755
    index 3612c96e85..0000000000
    --- a/configs/stm32f3discovery/nsh/setenv.sh
    +++ /dev/null
    @@ -1,75 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f3discovery/nsh/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f3discovery/usbnsh/setenv.sh b/configs/stm32f3discovery/usbnsh/setenv.sh
    deleted file mode 100755
    index d1e4ab41af..0000000000
    --- a/configs/stm32f3discovery/usbnsh/setenv.sh
    +++ /dev/null
    @@ -1,75 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f3discovery/usbnsh/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f411e-disco/nsh/setenv.sh b/configs/stm32f411e-disco/nsh/setenv.sh
    deleted file mode 100755
    index add9de147f..0000000000
    --- a/configs/stm32f411e-disco/nsh/setenv.sh
    +++ /dev/null
    @@ -1,68 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f411e-disco/nsh/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f429i-disco/extflash/setenv.sh b/configs/stm32f429i-disco/extflash/setenv.sh
    deleted file mode 100755
    index 7d116b560c..0000000000
    --- a/configs/stm32f429i-disco/extflash/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f429i-disco/usbnsh/setenv.sh
    -#
    -#   Copyright (C) 2013-2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f429i-disco/lcd/setenv.sh b/configs/stm32f429i-disco/lcd/setenv.sh
    deleted file mode 100755
    index 8ead5e80ac..0000000000
    --- a/configs/stm32f429i-disco/lcd/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f429i-disco/lcd/setenv.sh
    -#
    -#   Copyright (C) 2013-2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f429i-disco/ltdc/setenv.sh b/configs/stm32f429i-disco/ltdc/setenv.sh
    deleted file mode 100755
    index 6e88fbb729..0000000000
    --- a/configs/stm32f429i-disco/ltdc/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f429i-disco/ltdc/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f429i-disco/nsh/setenv.sh b/configs/stm32f429i-disco/nsh/setenv.sh
    deleted file mode 100755
    index 7d116b560c..0000000000
    --- a/configs/stm32f429i-disco/nsh/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f429i-disco/usbnsh/setenv.sh
    -#
    -#   Copyright (C) 2013-2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f429i-disco/nxwm/setenv.sh b/configs/stm32f429i-disco/nxwm/setenv.sh
    deleted file mode 100644
    index 9e49945922..0000000000
    --- a/configs/stm32f429i-disco/nxwm/setenv.sh
    +++ /dev/null
    @@ -1,80 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f429i-disco/nxwm/setenv.sh
    -#
    -#   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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f429i-disco/usbmsc/setenv.sh b/configs/stm32f429i-disco/usbmsc/setenv.sh
    deleted file mode 100755
    index 7d116b560c..0000000000
    --- a/configs/stm32f429i-disco/usbmsc/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f429i-disco/usbnsh/setenv.sh
    -#
    -#   Copyright (C) 2013-2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f429i-disco/usbnsh/setenv.sh b/configs/stm32f429i-disco/usbnsh/setenv.sh
    deleted file mode 100755
    index 7d116b560c..0000000000
    --- a/configs/stm32f429i-disco/usbnsh/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f429i-disco/usbnsh/setenv.sh
    -#
    -#   Copyright (C) 2013-2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f4discovery/canard/setenv.sh b/configs/stm32f4discovery/canard/setenv.sh
    deleted file mode 100755
    index ed2adcd4ff..0000000000
    --- a/configs/stm32f4discovery/canard/setenv.sh
    +++ /dev/null
    @@ -1,80 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f4discovery/canard/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f4discovery/cxxtest/setenv.sh b/configs/stm32f4discovery/cxxtest/setenv.sh
    deleted file mode 100755
    index 3428bcf4e6..0000000000
    --- a/configs/stm32f4discovery/cxxtest/setenv.sh
    +++ /dev/null
    @@ -1,81 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f4discovery/cxxtest/setenv.sh
    -#
    -#   Copyright (C) 2012, 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f4discovery/elf/setenv.sh b/configs/stm32f4discovery/elf/setenv.sh
    deleted file mode 100755
    index 40e5d91455..0000000000
    --- a/configs/stm32f4discovery/elf/setenv.sh
    +++ /dev/null
    @@ -1,84 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f4discovery/elf/setenv.sh
    -#
    -#   Copyright (C) 2011-2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This the Cygwin path to the location where I built genromfs.  If you use
    -# the buildroot toolchain, then genromfs can probably be found in TOOLCHAIN_DIR
    -export GENROMFS_PATH="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${GENROMFS_PATH}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f4discovery/ipv6/setenv.sh b/configs/stm32f4discovery/ipv6/setenv.sh
    deleted file mode 100755
    index 28b9db6ca3..0000000000
    --- a/configs/stm32f4discovery/ipv6/setenv.sh
    +++ /dev/null
    @@ -1,81 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f4discovery/ipv6/setenv.sh
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f4discovery/kostest/setenv.sh b/configs/stm32f4discovery/kostest/setenv.sh
    deleted file mode 100755
    index 6571513b65..0000000000
    --- a/configs/stm32f4discovery/kostest/setenv.sh
    +++ /dev/null
    @@ -1,80 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f4discovery/kostest/setenv.sh
    -#
    -#   Copyright (C) 2011-2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f4discovery/netnsh/setenv.sh b/configs/stm32f4discovery/netnsh/setenv.sh
    deleted file mode 100755
    index 51a6d2a961..0000000000
    --- a/configs/stm32f4discovery/netnsh/setenv.sh
    +++ /dev/null
    @@ -1,81 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f4discovery/netnsh/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f4discovery/nsh/setenv.sh b/configs/stm32f4discovery/nsh/setenv.sh
    deleted file mode 100755
    index d67e6fdc7d..0000000000
    --- a/configs/stm32f4discovery/nsh/setenv.sh
    +++ /dev/null
    @@ -1,80 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f4discovery/nsh/setenv.sh
    -#
    -#   Copyright (C) 2011-2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f4discovery/nxlines/setenv.sh b/configs/stm32f4discovery/nxlines/setenv.sh
    deleted file mode 100755
    index 5c15732e96..0000000000
    --- a/configs/stm32f4discovery/nxlines/setenv.sh
    +++ /dev/null
    @@ -1,80 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f4discovery/nxlines/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f4discovery/pm/setenv.sh b/configs/stm32f4discovery/pm/setenv.sh
    deleted file mode 100755
    index 815d58bf7d..0000000000
    --- a/configs/stm32f4discovery/pm/setenv.sh
    +++ /dev/null
    @@ -1,80 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f4discovery/pm/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f4discovery/posix_spawn/setenv.sh b/configs/stm32f4discovery/posix_spawn/setenv.sh
    deleted file mode 100755
    index 5253e55823..0000000000
    --- a/configs/stm32f4discovery/posix_spawn/setenv.sh
    +++ /dev/null
    @@ -1,84 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f4discovery/posix_spawn/setenv.sh
    -#
    -#   Copyright (C) 2011-2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This the Cygwin path to the location where I built genromfs.  If you use
    -# the buildroot toolchain, then genromfs can probably be found in TOOLCHAIN_DIR
    -export GENROMFS_PATH="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${GENROMFS_PATH}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f4discovery/pseudoterm/setenv.sh b/configs/stm32f4discovery/pseudoterm/setenv.sh
    deleted file mode 100644
    index d67e6fdc7d..0000000000
    --- a/configs/stm32f4discovery/pseudoterm/setenv.sh
    +++ /dev/null
    @@ -1,80 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f4discovery/nsh/setenv.sh
    -#
    -#   Copyright (C) 2011-2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f4discovery/rgbled/setenv.sh b/configs/stm32f4discovery/rgbled/setenv.sh
    deleted file mode 100755
    index d67e6fdc7d..0000000000
    --- a/configs/stm32f4discovery/rgbled/setenv.sh
    +++ /dev/null
    @@ -1,80 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f4discovery/nsh/setenv.sh
    -#
    -#   Copyright (C) 2011-2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f4discovery/usbnsh/setenv.sh b/configs/stm32f4discovery/usbnsh/setenv.sh
    deleted file mode 100755
    index 602a6adaae..0000000000
    --- a/configs/stm32f4discovery/usbnsh/setenv.sh
    +++ /dev/null
    @@ -1,80 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f4discovery/usbnsh/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f4discovery/xen1210/setenv.sh b/configs/stm32f4discovery/xen1210/setenv.sh
    deleted file mode 100644
    index 1f3a4940ed..0000000000
    --- a/configs/stm32f4discovery/xen1210/setenv.sh
    +++ /dev/null
    @@ -1,80 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f4discovery/xen1210/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f746-ws/nsh/setenv.sh b/configs/stm32f746-ws/nsh/setenv.sh
    deleted file mode 100644
    index 2d66398c3b..0000000000
    --- a/configs/stm32f746-ws/nsh/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f746-ws/nsh/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Users/Public/tools/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32f746g-disco/nsh/setenv.sh b/configs/stm32f746g-disco/nsh/setenv.sh
    deleted file mode 100755
    index e0e03726ac..0000000000
    --- a/configs/stm32f746g-disco/nsh/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/stm32f746g-disco/nsh/setenv.sh
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32l476-mdk/nsh/setenv.sh b/configs/stm32l476-mdk/nsh/setenv.sh
    deleted file mode 100755
    index 196fbd3993..0000000000
    --- a/configs/stm32l476-mdk/nsh/setenv.sh
    +++ /dev/null
    @@ -1,64 +0,0 @@
    -#!/bin/bash
    -# configs/stm32l476-mdk/nsh/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32l476vg-disco/nsh/setenv.sh b/configs/stm32l476vg-disco/nsh/setenv.sh
    deleted file mode 100755
    index d94f2f9066..0000000000
    --- a/configs/stm32l476vg-disco/nsh/setenv.sh
    +++ /dev/null
    @@ -1,64 +0,0 @@
    -#!/bin/bash
    -# configs/stm32l476vg-disco/nsh/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32ldiscovery/nsh/setenv.sh b/configs/stm32ldiscovery/nsh/setenv.sh
    deleted file mode 100755
    index 523dbd4455..0000000000
    --- a/configs/stm32ldiscovery/nsh/setenv.sh
    +++ /dev/null
    @@ -1,75 +0,0 @@
    -#!/bin/bash
    -# configs/stm32l1discovery/nsh/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/stm32vldiscovery/nsh/setenv.sh b/configs/stm32vldiscovery/nsh/setenv.sh
    deleted file mode 100755
    index 4b3abe66f6..0000000000
    --- a/configs/stm32vldiscovery/nsh/setenv.sh
    +++ /dev/null
    @@ -1,76 +0,0 @@
    -#!/bin/bash
    -# configs/stm32vldiscovery/nsh/setenv.sh
    -#
    -#   Copyright (C) 2012 Gregory Nutt. All rights reserved.
    -#   Author: Gregory Nutt 
    -#           Freddie Chopin 
    -#
    -# 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sure-pic32mx/nsh/setenv.sh b/configs/sure-pic32mx/nsh/setenv.sh
    deleted file mode 100755
    index bba6836094..0000000000
    --- a/configs/sure-pic32mx/nsh/setenv.sh
    +++ /dev/null
    @@ -1,61 +0,0 @@
    -#!/bin/bash
    -# configs/sure-pic32mx/nsh/setenv.sh
    -#
    -#   Copyright (C) 2011-2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -# This is the Cygwin path to the location where I installed the MicroChip
    -# PIC32MX toolchain under windows.  This is *not* the default install
    -# location so you will probably have to edit this.  You will also have
    -# to edit this if you install a different version of if you install
    -# the Linux PIC32MX toolchain as well
    -export TOOLCHAIN_BIN="/cygdrive/c/MicroChip/mplabc32/v1.12/bin"
    -
    -# This is the path to the toosl subdirectory
    -export PIC32TOOL_DIR="${WD}/tools/pic32mx"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${PIC32TOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/sure-pic32mx/usbnsh/setenv.sh b/configs/sure-pic32mx/usbnsh/setenv.sh
    deleted file mode 100755
    index 62074cdb35..0000000000
    --- a/configs/sure-pic32mx/usbnsh/setenv.sh
    +++ /dev/null
    @@ -1,61 +0,0 @@
    -#!/bin/bash
    -# configs/sure-pic32mx/usbnsh/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -# This is the Cygwin path to the location where I installed the MicroChip
    -# PIC32MX toolchain under windows.  This is *not* the default install
    -# location so you will probably have to edit this.  You will also have
    -# to edit this if you install a different version of if you install
    -# the Linux PIC32MX toolchain as well
    -export TOOLCHAIN_BIN="/cygdrive/c/MicroChip/mplabc32/v1.12/bin"
    -
    -# This is the path to the toosl subdirectory
    -export PIC32TOOL_DIR="${WD}/tools/pic32mx"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${PIC32TOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/teensy-2.0/hello/setenv.sh b/configs/teensy-2.0/hello/setenv.sh
    deleted file mode 100755
    index 6719b21010..0000000000
    --- a/configs/teensy-2.0/hello/setenv.sh
    +++ /dev/null
    @@ -1,68 +0,0 @@
    -#!/bin/bash
    -# configs/teensy-2.0/hello/setenv.sh
    -#
    -#   Copyright (C) 2011 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel
    -# Studio AVR toolchain.
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Studio/7.0/toolchain/avr8/avr8-gnu-toolchain/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/as-7/7.0/toolchain/avr8/avr8-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the WinAVR
    -# toolchain under windows.  This is *not* the default install
    -# location so you will probably have to edit this.  You will also have
    -# to edit this if you install the Linux AVR toolchain as well
    -#export TOOLCHAIN_BIN="/cygdrive/c/WinAVR/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_avr/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/teensy-2.0/nsh/setenv.sh b/configs/teensy-2.0/nsh/setenv.sh
    deleted file mode 100755
    index b14f17bbd1..0000000000
    --- a/configs/teensy-2.0/nsh/setenv.sh
    +++ /dev/null
    @@ -1,68 +0,0 @@
    -#!/bin/bash
    -# configs/teensy-2.0/nsh/setenv.sh
    -#
    -#   Copyright (C) 2011 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel
    -# Studio AVR toolchain.
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Studio/7.0/toolchain/avr8/avr8-gnu-toolchain/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/as-7/7.0/toolchain/avr8/avr8-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the WinAVR
    -# toolchain under windows.  This is *not* the default install
    -# location so you will probably have to edit this.  You will also have
    -# to edit this if you install the Linux AVR toolchain as well
    -#export TOOLCHAIN_BIN="/cygdrive/c/WinAVR/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_avr/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/teensy-2.0/usbmsc/setenv.sh b/configs/teensy-2.0/usbmsc/setenv.sh
    deleted file mode 100755
    index a19eb9c1ee..0000000000
    --- a/configs/teensy-2.0/usbmsc/setenv.sh
    +++ /dev/null
    @@ -1,68 +0,0 @@
    -#!/bin/bash
    -# configs/teensy-2.0/usbmsc/setenv.sh
    -#
    -#   Copyright (C) 2011 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel
    -# Studio AVR toolchain.
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Studio/7.0/toolchain/avr8/avr8-gnu-toolchain/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/as-7/7.0/toolchain/avr8/avr8-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the WinAVR
    -# toolchain under windows.  This is *not* the default install
    -# location so you will probably have to edit this.  You will also have
    -# to edit this if you install the Linux AVR toolchain as well
    -#export TOOLCHAIN_BIN="/cygdrive/c/WinAVR/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_avr/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/teensy-3.x/nsh/setenv.sh b/configs/teensy-3.x/nsh/setenv.sh
    deleted file mode 100755
    index e96a2ff345..0000000000
    --- a/configs/teensy-3.x/nsh/setenv.sh
    +++ /dev/null
    @@ -1,80 +0,0 @@
    -#!/bin/bash
    -# configs/teensy-3.1/nsh/setenv.sh
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/teensy-3.x/usbnsh/setenv.sh b/configs/teensy-3.x/usbnsh/setenv.sh
    deleted file mode 100755
    index dedab5191e..0000000000
    --- a/configs/teensy-3.x/usbnsh/setenv.sh
    +++ /dev/null
    @@ -1,76 +0,0 @@
    -#!/bin/bash
    -# configs/teensy-3.1/nsh/setenv.sh
    -#
    -#   Copyright (C) 2015-2016 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH variable
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/teensy-lc/nsh/setenv.sh b/configs/teensy-lc/nsh/setenv.sh
    deleted file mode 100755
    index 3bba390239..0000000000
    --- a/configs/teensy-lc/nsh/setenv.sh
    +++ /dev/null
    @@ -1,75 +0,0 @@
    -#!/bin/bash
    -# configs/teensy-lc/nsh/setenv.sh
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/tm4c123g-launchpad/nsh/setenv.sh b/configs/tm4c123g-launchpad/nsh/setenv.sh
    deleted file mode 100755
    index 9c63cd8cc0..0000000000
    --- a/configs/tm4c123g-launchpad/nsh/setenv.sh
    +++ /dev/null
    @@ -1,75 +0,0 @@
    -#!/bin/bash
    -# configs/tm4c123g-launchpad/nsh/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# The tm4c123g-launchpad/tools directory
    -export TOOL_DIR="${WD}/configs/tm4c123g-launchpad/tools"
    -
    -# Add the path to the toolchain and tools directory to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${TOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/tm4c1294-launchpad/ipv6/setenv.sh b/configs/tm4c1294-launchpad/ipv6/setenv.sh
    deleted file mode 100755
    index 286ff59eaa..0000000000
    --- a/configs/tm4c1294-launchpad/ipv6/setenv.sh
    +++ /dev/null
    @@ -1,75 +0,0 @@
    -#!/bin/bash
    -# configs/tm4c1294-launchpad/ipv6/setenv.sh
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# The tm4c1294-launchpad/tools directory
    -export TOOL_DIR="${WD}/configs/tm4c1294-launchpad/tools"
    -
    -# Add the path to the toolchain and tools directory to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${TOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/tm4c1294-launchpad/nsh/setenv.sh b/configs/tm4c1294-launchpad/nsh/setenv.sh
    deleted file mode 100755
    index 91a85fca7d..0000000000
    --- a/configs/tm4c1294-launchpad/nsh/setenv.sh
    +++ /dev/null
    @@ -1,75 +0,0 @@
    -#!/bin/bash
    -# configs/tm4c1294-launchpad/nsh/setenv.sh
    -#
    -#   Copyright (C) 2015 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# The tm4c1294-launchpad/tools directory
    -export TOOL_DIR="${WD}/configs/tm4c1294-launchpad/tools"
    -
    -# Add the path to the toolchain and tools directory to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${TOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/twr-k60n512/nsh/setenv.sh b/configs/twr-k60n512/nsh/setenv.sh
    deleted file mode 100755
    index b2dde26fc2..0000000000
    --- a/configs/twr-k60n512/nsh/setenv.sh
    +++ /dev/null
    @@ -1,61 +0,0 @@
    -#!/bin/bash
    -# configs/twr-k60n512/nsh/setenv.sh
    -#
    -#   Copyright (C) 2011 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -echo "PATH : ${PATH}"
    diff --git a/configs/twr-k64f120m/netnsh/setenv.sh b/configs/twr-k64f120m/netnsh/setenv.sh
    deleted file mode 100755
    index 009064720b..0000000000
    --- a/configs/twr-k64f120m/netnsh/setenv.sh
    +++ /dev/null
    @@ -1,61 +0,0 @@
    -#!/bin/bash
    -# configs/twr-k64f120m/netnsh/setenv.sh
    -#
    -#   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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -echo "PATH : ${PATH}"
    diff --git a/configs/twr-k64f120m/nsh/setenv.sh b/configs/twr-k64f120m/nsh/setenv.sh
    deleted file mode 100755
    index 7761313c01..0000000000
    --- a/configs/twr-k64f120m/nsh/setenv.sh
    +++ /dev/null
    @@ -1,61 +0,0 @@
    -#!/bin/bash
    -# configs/twr-k64f120m/nsh/setenv.sh
    -#
    -#   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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -echo "PATH : ${PATH}"
    diff --git a/configs/u-blox-c027/nsh/setenv.sh b/configs/u-blox-c027/nsh/setenv.sh
    deleted file mode 100755
    index 137954e6da..0000000000
    --- a/configs/u-blox-c027/nsh/setenv.sh
    +++ /dev/null
    @@ -1,59 +0,0 @@
    -#!/bin/bash
    -# configs/u-blox-c027/nsh/setenv.sh
    -#
    -#   Copyright (C) 2016 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -
    -# This is where the buildroot might reside on a Linux or Cygwin system
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the default install location for Code Red on Linux
    -export TOOLCHAIN_BIN="/usr/local/LPCXpresso/tools/bin"
    -
    -# This is the Cygwin path to the LPCXpresso 3.6 install location under Windows
    -#export TOOLCHAIN_BIN="/cygdrive/c/nxp/lpcxpresso_3.6/Tools/bin"
    -
    -# This is the path to the LPCXpression tool subdirectory
    -export LPCTOOL_DIR="${WD}/configs/u-blox-c027/tools"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/ubw32/nsh/setenv.sh b/configs/ubw32/nsh/setenv.sh
    deleted file mode 100755
    index ca5a097a3f..0000000000
    --- a/configs/ubw32/nsh/setenv.sh
    +++ /dev/null
    @@ -1,61 +0,0 @@
    -#!/bin/bash
    -# configs/ubw32/nsh/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -# This is the Cygwin path to the location where I installed the MicroChip
    -# PIC32MX toolchain under windows.  This is *not* the default install
    -# location so you will probably have to edit this.  You will also have
    -# to edit this if you install a different version of if you install
    -# the Linux PIC32MX toolchain as well
    -export TOOLCHAIN_BIN="/cygdrive/c/MicroChip/mplabc32/v1.12/bin"
    -
    -# This is the path to the toosl subdirectory
    -export PIC32TOOL_DIR="${WD}/tools/pic32mx"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${PIC32TOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/us7032evb1/nsh/setenv.sh b/configs/us7032evb1/nsh/setenv.sh
    deleted file mode 100755
    index d231336128..0000000000
    --- a/configs/us7032evb1/nsh/setenv.sh
    +++ /dev/null
    @@ -1,47 +0,0 @@
    -#!/bin/bash
    -# configs/us7032evb1/nsh/setenv.sh
    -#
    -#   Copyright (C) 2008 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
    -
    -WD=`pwd`
    -export BUILDROOT_BIN=${WD}/../buildroot/build_sh/staging_dir/bin
    -export SH1BINARIES=$WD/configs/us7032evb1/bin
    -export PATH=${BUILDROOT_BIN}:${SH1BINARIES}:/sbin:/usr/sbin:${PATH_ORIG}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/us7032evb1/ostest/setenv.sh b/configs/us7032evb1/ostest/setenv.sh
    deleted file mode 100755
    index ac37e9150f..0000000000
    --- a/configs/us7032evb1/ostest/setenv.sh
    +++ /dev/null
    @@ -1,47 +0,0 @@
    -#!/bin/bash
    -# configs/us7032evb1/ostest/setenv.sh
    -#
    -#   Copyright (C) 2008 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.
    -#
    -
    -if [ "$(basename $0)" = "setenv.sh" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
    -
    -WD=`pwd`
    -export BUILDROOT_BIN=${WD}/../buildroot/build_sh/staging_dir/bin
    -export SH1BINARIES=$WD/configs/us7032evb1/bin
    -export PATH=${BUILDROOT_BIN}:${SH1BINARIES}:/sbin:/usr/sbin:${PATH_ORIG}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/viewtool-stm32f107/highpri/setenv.sh b/configs/viewtool-stm32f107/highpri/setenv.sh
    deleted file mode 100755
    index a593715add..0000000000
    --- a/configs/viewtool-stm32f107/highpri/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/viewtool-stm32f107/highpri/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/viewtool-stm32f107/netnsh/setenv.sh b/configs/viewtool-stm32f107/netnsh/setenv.sh
    deleted file mode 100755
    index c799e1203b..0000000000
    --- a/configs/viewtool-stm32f107/netnsh/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/viewtool-stm32f107/netnsh/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/viewtool-stm32f107/nsh/setenv.sh b/configs/viewtool-stm32f107/nsh/setenv.sh
    deleted file mode 100755
    index 8b5188cf96..0000000000
    --- a/configs/viewtool-stm32f107/nsh/setenv.sh
    +++ /dev/null
    @@ -1,78 +0,0 @@
    -#!/bin/bash
    -# configs/viewtool-stm32f107/nsh/setenv.sh
    -#
    -#   Copyright (C) 2013 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the RIDE
    -# toolchain under windows.  You will also have to edit this if you install
    -# the RIDE toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# These are the Cygwin paths to the locations where I installed the Atollic
    -# toolchain under windows.  You will also have to edit this if you install
    -# the Atollic toolchain in any other location.  /usr/bin is added before
    -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
    -# at those locations as well.
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
    -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/xmc4500-relax/nsh/setenv.sh b/configs/xmc4500-relax/nsh/setenv.sh
    deleted file mode 100644
    index 2116ba35be..0000000000
    --- a/configs/xmc4500-relax/nsh/setenv.sh
    +++ /dev/null
    @@ -1,77 +0,0 @@
    -#!/bin/bash
    -# configs/xmc4500-relax/nsh/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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the Atmel GCC
    -# toolchain under Windows.  You will also have to edit this if you install
    -# this toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
    -
    -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
    -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
    -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
    -
    -# This is the path to the location where I installed the devkitARM toolchain
    -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/xtrs/scripts/setenv.sh b/configs/xtrs/scripts/setenv.sh
    deleted file mode 100755
    index 8dc863ba59..0000000000
    --- a/configs/xtrs/scripts/setenv.sh
    +++ /dev/null
    @@ -1,72 +0,0 @@
    -#!/bin/bash
    -# configs/xtrs/ostest/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -#
    -# This is the normal installation directory for SDCC under Linux, OSX
    -# or Linux:
    -#
    -export TOOLCHAIN_BIN=/usr/local/bin
    -
    -#
    -# This is the normal installation directory for SDCC under Windows
    -#
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/SDCC/bin"
    -
    -#
    -# Add the path to the toolchain to the PATH varialble
    -#
    -export PATH="${TOOLCHAIN_BIN}":/sbin:/usr/sbin:${PATH_ORIG}
    -
    -#
    -# This is the location where the XTRS hex2cmd program is available
    -#
    -# export HEX2CMD_BIN=????
    -# export PATH="${HEX2CMD_BIN}":${PATH}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/z16f2800100zcog/nsh/setenv.sh b/configs/z16f2800100zcog/nsh/setenv.sh
    deleted file mode 100755
    index 22408b498a..0000000000
    --- a/configs/z16f2800100zcog/nsh/setenv.sh
    +++ /dev/null
    @@ -1,70 +0,0 @@
    -#!/bin/bash
    -# configs/z16f2800100zcog/nsh/setenv.sh
    -#
    -#   Copyright (C) 2014 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.
    -#
    -# Check how we were executed
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -#
    -# This is the Cygwin path to location where the ZDS-II tools were installed
    -#
    -TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/ZiLOG/ZDSII_ZNEO_5.0.1/bin"
    -
    -#
    -# This is the path to the z16f2800100zcog tool directory
    -#
    -TOOL_DIR="${WD}/configs/z16f2800100zcog/tools"
    -
    -#
    -# Add the path to the toolchain and tool directory to the PATH variable.  NOTE
    -# that /bin and /usr/bin preceded the toolchain bin directory.  This is because
    -# the ZDSII bin directory includes binaries like make.exe that will interfere
    -# with the normal build process if we do not give priority to the versions at
    -# /bin and /usr/bin.
    -#
    -export PATH="/bin:/usr/bin:${TOOLCHAIN_BIN}:${TOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -echo "PATH : ${PATH}"
    diff --git a/configs/z16f2800100zcog/ostest/setenv.sh b/configs/z16f2800100zcog/ostest/setenv.sh
    deleted file mode 100755
    index edc62a07e3..0000000000
    --- a/configs/z16f2800100zcog/ostest/setenv.sh
    +++ /dev/null
    @@ -1,69 +0,0 @@
    -#!/bin/bash
    -# configs/z16f2800100zcog/ostest/setenv.sh
    -#
    -#   Copyright (C) 2008, 2009, 2012, 2014 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.
    -#
    -# Check how we were executed
    -#
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -#
    -# This is the Cygwin path to location where the ZDS-II tools were installed
    -#
    -TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/ZiLOG/ZDSII_ZNEO_5.0.1/bin"
    -
    -#
    -# This is the path to the z16f2800100zcog tool directory
    -#
    -TOOL_DIR="${WD}/configs/z16f2800100zcog/tools"
    -
    -#
    -# Add the path to the toolchain and tool directory to the PATH variable.  NOTE
    -# that /bin and /usr/bin preceded the toolchain bin directory.  This is because
    -# the ZDSII bin directory includes binaries like make.exe that will interfere
    -# with the normal build process if we do not give priority to the versions at
    -# /bin and /usr/bin.
    -#
    -export PATH="/bin:/usr/bin:${TOOLCHAIN_BIN}:${TOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -echo "PATH : ${PATH}"
    diff --git a/configs/z16f2800100zcog/pashello/setenv.sh b/configs/z16f2800100zcog/pashello/setenv.sh
    deleted file mode 100755
    index 4ade86cff9..0000000000
    --- a/configs/z16f2800100zcog/pashello/setenv.sh
    +++ /dev/null
    @@ -1,69 +0,0 @@
    -#!/bin/bash
    -# configs/z16f2800100zcog/pashello/setenv.sh
    -#
    -#   Copyright (C) 2008, 2009, 2012, 2014 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.
    -#
    -# Check how we were executed
    -#
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -#
    -# This is the Cygwin path to location where the ZDS-II tools were installed
    -#
    -TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/ZiLOG/ZDSII_ZNEO_5.0.1/bin"
    -
    -#
    -# This is the path to the z16f2800100zcog tool directory
    -#
    -TOOL_DIR="${WD}/configs/z16f2800100zcog/tools"
    -
    -#
    -# Add the path to the toolchain and tool directory to the PATH variable.  NOTE
    -# that /bin and /usr/bin preceded the toolchain bin directory.  This is because
    -# the ZDSII bin directory includes binaries like make.exe that will interfere
    -# with the normal build process if we do not give priority to the versions at
    -# /bin and /usr/bin.
    -#
    -export PATH="/bin:/usr/bin:${TOOLCHAIN_BIN}:${TOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -echo "PATH : ${PATH}"
    diff --git a/configs/z80sim/scripts/setenv.sh b/configs/z80sim/scripts/setenv.sh
    deleted file mode 100755
    index ead1e1f5f7..0000000000
    --- a/configs/z80sim/scripts/setenv.sh
    +++ /dev/null
    @@ -1,66 +0,0 @@
    -#!/bin/bash
    -# configs/z80sim/ostest/setenv.sh
    -#
    -#   Copyright (C) 2007, 2008, 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -#
    -# This is the normal installation directory for SDCC under Linux, OSX
    -# or Linux:
    -#
    -export TOOLCHAIN_BIN=/usr/local/bin
    -
    -#
    -# This is the normal installation directory for SDCC under Windows
    -#
    -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/SDCC/bin"
    -
    -#
    -# Add the path to the toolchain to the PATH varialble
    -#
    -export PATH="${TOOLCHAIN_BIN}":/sbin:/usr/sbin:${PATH_ORIG}
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/z8encore000zco/ostest/setenv.sh b/configs/z8encore000zco/ostest/setenv.sh
    deleted file mode 100755
    index 565f6f1fea..0000000000
    --- a/configs/z8encore000zco/ostest/setenv.sh
    +++ /dev/null
    @@ -1,64 +0,0 @@
    -#!/bin/bash
    -# configs/z8encore000zco/ostest/setenv.sh
    -#
    -#   Copyright (C) 2008, 2009, 2012, 2016 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.
    -#
    -# Check how we were executed
    -#
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -#
    -# This is the Cygwin path to location where the XDS-II tools were installed
    -#
    -# TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/ZiLOG/ZDSII_Z8Encore!_5.0.0/bin"
    -TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/ZiLOG/ZDSII_Z8Encore!_5.2.2/bin"
    -
    -#
    -# Add the path to the toolchain to the PATH varialble.  NOTE that /bin and /usr/bin
    -# preceded the toolchain bin directory.  This is because the ZDSII bin directory
    -# includes binaries like make.exe that will interfere with the normal build process
    -# if we do not give priority to the versions at /bin and /usr/bin.
    -#
    -export PATH="/bin:/usr/bin:${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -echo "PATH : ${PATH}"
    diff --git a/configs/z8f64200100kit/ostest/setenv.sh b/configs/z8f64200100kit/ostest/setenv.sh
    deleted file mode 100755
    index 825bd50dae..0000000000
    --- a/configs/z8f64200100kit/ostest/setenv.sh
    +++ /dev/null
    @@ -1,64 +0,0 @@
    -#!/bin/bash
    -# configs/z8f64200100kit/ostest/setenv.sh
    -#
    -#   Copyright (C) 2008, 2009, 2012, 2016 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.
    -#
    -# Check how we were executed
    -#
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -#
    -# This is the Cygwin path to location where the XDS-II tools were installed
    -#
    -# TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/ZiLOG/ZDSII_Z8Encore!_5.0.0/bin"
    -TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/ZiLOG/ZDSII_Z8Encore!_5.2.2/bin"
    -
    -#
    -# Add the path to the toolchain to the PATH varialble.  NOTE that /bin and /usr/bin
    -# preceded the toolchain bin directory.  This is because the ZDSII bin directory
    -# includes binaries like make.exe that will interfere with the normal build process
    -# if we do not give priority to the versions at /bin and /usr/bin.
    -#
    -export PATH="/bin:/usr/bin:${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -echo "PATH : ${PATH}"
    diff --git a/configs/zkit-arm-1769/hello/setenv.sh b/configs/zkit-arm-1769/hello/setenv.sh
    deleted file mode 100755
    index c8a2994393..0000000000
    --- a/configs/zkit-arm-1769/hello/setenv.sh
    +++ /dev/null
    @@ -1,72 +0,0 @@
    -#!/bin/bash
    -# configs/zkit-arm-1769/hello/setenv.sh
    -#
    -#   Copyright (C) 2013 Zilogic Systems. All rights reserved.
    -#   Author: BabuSubashChandar 
    -#
    -# Based on configs/lpcxpresso-lpc1768/thttpd/setenv.sh
    -#
    -#   Copyright (C) 2011 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is where the buildroot might reside on a Linux or Cygwin system
    -# A minimal buildroot version with the NXFLAT tools is always required
    -# for this configuration in order to buildthe THTTPD CGI programs
    -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the default install location for Code Red on Linux
    -#export TOOLCHAIN_BIN="/usr/local/LPCXpresso/tools/bin"
    -
    -# This the Cygwin path to the LPCXpresso 3.6 install location under Windows
    -#export TOOLCHAIN_BIN="/cygdrive/c/nxp/lpcxpresso_3.6/Tools/bin"
    -
    -# This is the path to the LPCXpresso tool subdirectory
    -export LPCTOOL_DIR="${WD}/configs/zkit-arm-1769/tools"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${LPCTOOL_DIR}:${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/zkit-arm-1769/nsh/setenv.sh b/configs/zkit-arm-1769/nsh/setenv.sh
    deleted file mode 100755
    index d9797a48ba..0000000000
    --- a/configs/zkit-arm-1769/nsh/setenv.sh
    +++ /dev/null
    @@ -1,72 +0,0 @@
    -#!/bin/bash
    -# configs/zkit-arm-1769/nsh/setenv.sh
    -#
    -#   Copyright (C) 2013 Zilogic Systems. All rights reserved.
    -#   Author: BabuSubashChandar 
    -#
    -# Based on configs/lpcxpresso-lpc1768/thttpd/setenv.sh
    -#
    -#   Copyright (C) 2011 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is where the buildroot might reside on a Linux or Cygwin system
    -# A minimal buildroot version with the NXFLAT tools is always required
    -# for this configuration in order to buildthe THTTPD CGI programs
    -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the default install location for Code Red on Linux
    -#export TOOLCHAIN_BIN="/usr/local/LPCXpresso/tools/bin"
    -
    -# This the Cygwin path to the LPCXpresso 3.6 install location under Windows
    -#export TOOLCHAIN_BIN="/cygdrive/c/nxp/lpcxpresso_3.6/Tools/bin"
    -
    -# This is the path to the LPCXpression tool subdirectory
    -export LPCTOOL_DIR="${WD}/configs/zkit-arm-1769/tools"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${LPCTOOL_DIR}:${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/zkit-arm-1769/nxhello/setenv.sh b/configs/zkit-arm-1769/nxhello/setenv.sh
    deleted file mode 100755
    index 1f8edd0d1d..0000000000
    --- a/configs/zkit-arm-1769/nxhello/setenv.sh
    +++ /dev/null
    @@ -1,72 +0,0 @@
    -#!/bin/bash
    -# configs/zkit-arm-1769/nxhello/setenv.sh
    -#
    -#   Copyright (C) 2013 Zilogic Systems. All rights reserved.
    -#   Author: Manikandan 
    -#
    -# Based on configs/lpcxpresso-lpc1768/thttpd/setenv.sh
    -#
    -#   Copyright (C) 2011 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is where the buildroot might reside on a Linux or Cygwin system
    -# A minimal buildroot version with the NXFLAT tools is always required
    -# for this configuration in order to buildthe THTTPD CGI programs
    -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the default install location for Code Red on Linux
    -#export TOOLCHAIN_BIN="/usr/local/LPCXpresso/tools/bin"
    -
    -# This the Cygwin path to the LPCXpresso 3.6 install location under Windows
    -#export TOOLCHAIN_BIN="/cygdrive/c/nxp/lpcxpresso_3.6/Tools/bin"
    -
    -# This is the path to the LPCXpression tool subdirectory
    -export LPCTOOL_DIR="${WD}/configs/zkit-arm-1769/tools"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${LPCTOOL_DIR}:${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/zkit-arm-1769/thttpd/setenv.sh b/configs/zkit-arm-1769/thttpd/setenv.sh
    deleted file mode 100755
    index 6d93498a7b..0000000000
    --- a/configs/zkit-arm-1769/thttpd/setenv.sh
    +++ /dev/null
    @@ -1,72 +0,0 @@
    -#!/bin/bash
    -# configs/zkit-arm-1769/thttpd/setenv.sh
    -#
    -#   Copyright (C) 2013 Zilogic Systems. All rights reserved.
    -#   Author: BabuSubashChandar 
    -#
    -# Based on configs/lpcxpresso-lpc1768/thttpd/setenv.sh
    -#
    -#   Copyright (C) 2011 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is where the buildroot might reside on a Linux or Cygwin system
    -# A minimal buildroot version with the NXFLAT tools is always required
    -# for this configuration in order to buildthe THTTPD CGI programs
    -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# This is the default install location for Code Red on Linux
    -#export TOOLCHAIN_BIN="/usr/local/LPCXpresso/tools/bin"
    -
    -# This the Cygwin path to the LPCXpresso 3.6 install location under Windows
    -#export TOOLCHAIN_BIN="/cygdrive/c/nxp/lpcxpresso_3.6/Tools/bin"
    -
    -# This is the path to the LPCXpression tool subdirectory
    -export LPCTOOL_DIR="${WD}/configs/zkit-arm-1769/tools"
    -
    -# Add the path to the toolchain to the PATH varialble
    -export PATH="${LPCTOOL_DIR}:${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/zp214xpa/nsh/setenv.sh b/configs/zp214xpa/nsh/setenv.sh
    deleted file mode 100755
    index a35d34aa56..0000000000
    --- a/configs/zp214xpa/nsh/setenv.sh
    +++ /dev/null
    @@ -1,65 +0,0 @@
    -#!/bin/bash
    -# configs/zp214xpa/nsh/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# The zp214xpa/tools directory
    -export LPCTOOL_DIR="${WD}/configs/zp214xpa/tools"
    -
    -# Add the path to the toolchain and tools directory to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    diff --git a/configs/zp214xpa/nxlines/setenv.sh b/configs/zp214xpa/nxlines/setenv.sh
    deleted file mode 100755
    index b2872cdc52..0000000000
    --- a/configs/zp214xpa/nxlines/setenv.sh
    +++ /dev/null
    @@ -1,65 +0,0 @@
    -#!/bin/bash
    -# configs/zp214xpa/nxlines/setenv.sh
    -#
    -#   Copyright (C) 2012 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.
    -#
    -
    -if [ "$_" = "$0" ] ; then
    -  echo "You must source this script, not run it!" 1>&2
    -  exit 1
    -fi
    -
    -WD=`pwd`
    -if [ ! -x "setenv.sh" ]; then
    -  echo "This script must be executed from the top-level NuttX build directory"
    -  exit 1
    -fi
    -
    -if [ -z "${PATH_ORIG}" ]; then
    -  export PATH_ORIG="${PATH}"
    -fi
    -
    -# This is the Cygwin path to the location where I installed the CodeSourcery
    -# toolchain under windows.  You will also have to edit this if you install
    -# the CodeSourcery toolchain in any other location
    -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -# This is the Cygwin path to the location where I build the buildroot
    -# toolchain.
    -export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -
    -# The zp214xpa/tools directory
    -export LPCTOOL_DIR="${WD}/configs/zp214xpa/tools"
    -
    -# Add the path to the toolchain and tools directory to the PATH varialble
    -export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
    -
    -echo "PATH : ${PATH}"
    -- 
    GitLab
    
    
    From 6bb2db8c15b5d16148d50bc08cd9f857062d2dcc Mon Sep 17 00:00:00 2001
    From: Simon Piriou 
    Date: Wed, 26 Apr 2017 17:23:53 +0200
    Subject: [PATCH 588/990] bcmf: enable DMA for SDIO transfers
    
    ---
     arch/arm/src/stm32/stm32_sdio.c       | 24 ++++++++++++++++++++++--
     configs/photon/include/board.h        | 11 +++++++++++
     configs/photon/wlan/defconfig         | 20 ++++++++++++--------
     drivers/wireless/ieee80211/mmc_sdio.c |  7 +++++--
     4 files changed, 50 insertions(+), 12 deletions(-)
    
    diff --git a/arch/arm/src/stm32/stm32_sdio.c b/arch/arm/src/stm32/stm32_sdio.c
    index 66a8d10773..db95c008e9 100644
    --- a/arch/arm/src/stm32/stm32_sdio.c
    +++ b/arch/arm/src/stm32/stm32_sdio.c
    @@ -2721,7 +2721,17 @@ static int stm32_dmarecvsetup(FAR struct sdio_dev_s *dev, FAR uint8_t *buffer,
     
       /* Then set up the SDIO data path */
     
    -  dblocksize = stm32_log2(buflen) << SDIO_DCTRL_DBLOCKSIZE_SHIFT;
    +#ifdef CONFIG_SDIO_BLOCKSETUP
    +  if (priv->block_size != STM32_SDIO_USE_DEFAULT_BLOCKSIZE)
    +    {
    +      dblocksize = priv->block_size << SDIO_DCTRL_DBLOCKSIZE_SHIFT;
    +    }
    +  else
    +#endif
    +    {
    +      dblocksize = stm32_log2(buflen) << SDIO_DCTRL_DBLOCKSIZE_SHIFT;
    +    }
    +
       stm32_dataconfig(SDIO_DTIMER_DATATIMEOUT, buflen, dblocksize | SDIO_DCTRL_DTDIR);
     
       /* Configure the RX DMA */
    @@ -2790,7 +2800,17 @@ static int stm32_dmasendsetup(FAR struct sdio_dev_s *dev,
     
       /* Then set up the SDIO data path */
     
    -  dblocksize = stm32_log2(buflen) << SDIO_DCTRL_DBLOCKSIZE_SHIFT;
    +#ifdef CONFIG_SDIO_BLOCKSETUP
    +  if (priv->block_size != STM32_SDIO_USE_DEFAULT_BLOCKSIZE)
    +    {
    +      dblocksize = priv->block_size << SDIO_DCTRL_DBLOCKSIZE_SHIFT;
    +    }
    +  else
    +#endif
    +    {
    +      dblocksize = stm32_log2(buflen) << SDIO_DCTRL_DBLOCKSIZE_SHIFT;
    +    }
    +
       stm32_dataconfig(SDIO_DTIMER_DATATIMEOUT, buflen, dblocksize);
     
       /* Configure the TX DMA */
    diff --git a/configs/photon/include/board.h b/configs/photon/include/board.h
    index 96115ca57f..119c90a322 100644
    --- a/configs/photon/include/board.h
    +++ b/configs/photon/include/board.h
    @@ -237,6 +237,17 @@
     #  define SDIO_SDXFR_CLKDIV     (2 << SDIO_CLKCR_CLKDIV_SHIFT)
     #endif
     
    +/* DMA Channl/Stream Selections *****************************************************/
    +/* Stream selections are arbitrary for now but might become important in the future
    + * if we set aside more DMA channels/streams.
    + *
    + * SDIO DMA
    + *   DMAMAP_SDIO_1 = Channel 4, Stream 3
    + *   DMAMAP_SDIO_2 = Channel 4, Stream 6
    + */
    +
    +#define DMAMAP_SDIO DMAMAP_SDIO_1
    +
     /************************************************************************************
      * Public Data
      ************************************************************************************/
    diff --git a/configs/photon/wlan/defconfig b/configs/photon/wlan/defconfig
    index 25480a5acb..d1cae5539d 100644
    --- a/configs/photon/wlan/defconfig
    +++ b/configs/photon/wlan/defconfig
    @@ -16,7 +16,7 @@ CONFIG_HOST_LINUX=y
     #
     # Build Configuration
     #
    -# CONFIG_APPS_DIR="../apps"
    +CONFIG_APPS_DIR="../apps"
     CONFIG_BUILD_FLAT=y
     # CONFIG_BUILD_2PASS is not set
     
    @@ -75,6 +75,7 @@ CONFIG_DEBUG_WIRELESS_INFO=y
     #
     # OS Function Debug Options
     #
    +# CONFIG_DEBUG_DMA is not set
     # CONFIG_DEBUG_IRQ is not set
     
     #
    @@ -449,7 +450,7 @@ CONFIG_STM32_HAVE_SPI3=y
     # CONFIG_STM32_CAN2 is not set
     # CONFIG_STM32_CRC is not set
     # CONFIG_STM32_DMA1 is not set
    -# CONFIG_STM32_DMA2 is not set
    +CONFIG_STM32_DMA2=y
     # CONFIG_STM32_DAC1 is not set
     # CONFIG_STM32_DAC2 is not set
     # CONFIG_STM32_I2C1 is not set
    @@ -499,6 +500,7 @@ CONFIG_STM32_JTAG_SW_ENABLE=y
     # CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG is not set
     # CONFIG_STM32_FORCEPOWER is not set
     # CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set
    +# CONFIG_STM32_DMACAPABLE is not set
     
     #
     # Timer Configuration
    @@ -529,6 +531,7 @@ CONFIG_STM32_SERIALDRIVER=y
     CONFIG_STM32_USART1_SERIALDRIVER=y
     # CONFIG_STM32_USART1_1WIREDRIVER is not set
     # CONFIG_USART1_RS485 is not set
    +# CONFIG_USART1_RXDMA is not set
     
     #
     # Serial Driver Configuration
    @@ -541,6 +544,7 @@ CONFIG_STM32_USART1_SERIALDRIVER=y
     #
     # SDIO Configuration
     #
    +CONFIG_STM32_SDIO_DMA=y
     CONFIG_STM32_SDIO_DMAPRIO=0x00010000
     # CONFIG_STM32_SDIO_WIDTH_D1_ONLY is not set
     # CONFIG_STM32_HAVE_RTC_COUNTER is not set
    @@ -567,7 +571,7 @@ CONFIG_STM32_SDIO_DMAPRIO=0x00010000
     #
     # CONFIG_ARCH_NOINTC is not set
     # CONFIG_ARCH_VECNOTIRQ is not set
    -# CONFIG_ARCH_DMA is not set
    +CONFIG_ARCH_DMA=y
     CONFIG_ARCH_HAVE_IRQPRIO=y
     # CONFIG_ARCH_L2CACHE is not set
     # CONFIG_ARCH_HAVE_COHERENT_DCACHE is not set
    @@ -853,7 +857,7 @@ CONFIG_MMCSD_NSLOTS=1
     # CONFIG_MMCSD_MMCSUPPORT is not set
     # CONFIG_MMCSD_HAVECARDDETECT is not set
     CONFIG_ARCH_HAVE_SDIO=y
    -# CONFIG_SDIO_DMA is not set
    +CONFIG_SDIO_DMA=y
     CONFIG_ARCH_HAVE_SDIOWAIT_WRCOMPLETE=y
     CONFIG_MMCSD_SDIO=y
     CONFIG_SDIO_PREFLIGHT=y
    @@ -1280,6 +1284,10 @@ CONFIG_HAVE_CXXINITIALIZE=y
     # Application Configuration
     #
     
    +#
    +# NxWidgets/NxWM
    +#
    +
     #
     # Built-In Applications
     #
    @@ -1514,10 +1522,6 @@ CONFIG_NSH_MAX_ROUNDTRIP=20
     # CONFIG_NSH_LOGIN is not set
     # CONFIG_NSH_CONSOLE_LOGIN is not set
     
    -#
    -# NxWidgets/NxWM
    -#
    -
     #
     # Platform-specific Support
     #
    diff --git a/drivers/wireless/ieee80211/mmc_sdio.c b/drivers/wireless/ieee80211/mmc_sdio.c
    index 39c4139160..1848c3f72f 100644
    --- a/drivers/wireless/ieee80211/mmc_sdio.c
    +++ b/drivers/wireless/ieee80211/mmc_sdio.c
    @@ -78,6 +78,8 @@ int sdio_io_rw_direct(FAR struct sdio_dev_s *dev, bool write,
     
         /* Setup CMD52 argument */
     
    +    arg.value = 0;
    +
         if (write)
           {
             arg.cmd52.write_data       = inb;
    @@ -135,6 +137,7 @@ int sdio_io_rw_extended(FAR struct sdio_dev_s *dev, bool write,
     
         /* Setup CMD53 argument */
     
    +    arg.value = 0;
         arg.cmd53.register_address = address & 0x1ffff;
         arg.cmd53.op_code          = inc_addr;
         arg.cmd53.function_number  = function & 7;
    @@ -169,13 +172,13 @@ int sdio_io_rw_extended(FAR struct sdio_dev_s *dev, bool write,
             sdio_sendcmdpoll(dev, SDIO_ACMD53, (uint32_t)arg.value);
             ret = SDIO_RECVR5(dev, SDIO_ACMD53, (uint32_t*)&resp);
     
    -        SDIO_SENDSETUP(dev, buf, blocklen * nblocks);
    +        SDIO_DMASENDSETUP(dev, buf, blocklen * nblocks);
             wkupevent = SDIO_EVENTWAIT(dev, SDIO_CMD53_TIMEOUT_MS);
           }
         else
           {
             // wlinfo("prep read %d\n", blocklen * nblocks);
    -        SDIO_RECVSETUP(dev, buf, blocklen * nblocks);
    +        SDIO_DMARECVSETUP(dev, buf, blocklen * nblocks);
             SDIO_SENDCMD(dev, SDIO_ACMD53, (uint32_t)arg.value);
     
             wkupevent = SDIO_EVENTWAIT(dev, SDIO_CMD53_TIMEOUT_MS);
    -- 
    GitLab
    
    
    From 9e760dcf6aed3ab2d1053e22d1116fcac8951e41 Mon Sep 17 00:00:00 2001
    From: Anthony Merlino 
    Date: Wed, 26 Apr 2017 11:30:54 -0400
    Subject: [PATCH 589/990] wireless/ieee802154: Lots of little fixes and changes
     to get everything to build
    
    ---
     configs/clicker2-stm32/src/stm32_mrf24j40.c   |    4 -
     drivers/wireless/ieee802154/mrf24j40.c        |   60 +-
     .../wireless/ieee802154/ieee802154_mac.h      |   51 +-
     .../wireless/ieee802154/ieee802154_radio.h    |   37 +-
     wireless/ieee802154/Kconfig                   |   35 +-
     wireless/ieee802154/mac802154.c               | 2548 +++++++++--------
     wireless/ieee802154/mac802154.h               |   34 +-
     wireless/ieee802154/mac802154_device.c        |   24 +-
     wireless/ieee802154/radio802154_device.c      |    6 +-
     9 files changed, 1418 insertions(+), 1381 deletions(-)
    
    diff --git a/configs/clicker2-stm32/src/stm32_mrf24j40.c b/configs/clicker2-stm32/src/stm32_mrf24j40.c
    index e1b664f28b..18751e27dc 100644
    --- a/configs/clicker2-stm32/src/stm32_mrf24j40.c
    +++ b/configs/clicker2-stm32/src/stm32_mrf24j40.c
    @@ -67,10 +67,6 @@
     #  error Wireless support requires CONFIG_DRIVERS_WIRELESS
     #endif
     
    -#ifndef CONFIG_IEEE802154_DEV
    -#  error IEEE802.15.4 radio character device required (CONFIG_IEEE802154_DEV)
    -#endif
    -
     #if !defined(CONFIG_CLICKER2_STM32_MB1_BEE) && \
         !defined(CONFIG_CLICKER2_STM32_MB2_BEE)
     #  error Only the Mikroe BEE board is supported
    diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c
    index 1e07d1126b..b819ed7d99 100644
    --- a/drivers/wireless/ieee802154/mrf24j40.c
    +++ b/drivers/wireless/ieee802154/mrf24j40.c
    @@ -56,6 +56,8 @@
     #include 
     #include 
     
    +#include 
    +
     #include 
     #include 
     #include 
    @@ -221,8 +223,7 @@ static int  mrf24j40_bind(FAR struct ieee802154_radio_s *radio,
                   FAR struct ieee802154_radiocb_s *radiocb);
     static int  mrf24j40_ioctl(FAR struct ieee802154_radio_s *radio, int cmd,
                   unsigned long arg);
    -static int  mrf24j40_rxenable(FAR struct ieee802154_radio_s *radio,
    -              bool state, FAR struct ieee802154_packet_s *packet);
    +static int  mrf24j40_rxenable(FAR struct ieee802154_radio_s *radio);
     static int  mrf24j40_transmit(FAR struct ieee802154_radio_s *radio,
                   FAR uint8_t *buf, uint16_t buf_len);
     static int mrf24j40_txnotify_csma(FAR struct ieee802154_radio_s *radio);
    @@ -324,7 +325,7 @@ static int mrf24j40_txnotify_csma(FAR struct ieee802154_radio_s *radio)
     static void mrf24j40_dopoll_csma(FAR void *arg)
     {
       FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)arg;
    -  int ret = 0;
    +  int len = 0;
     
       /* Need to get exlusive access to the device so that we can use the copy
        * buffer.
    @@ -338,9 +339,9 @@ static void mrf24j40_dopoll_csma(FAR void *arg)
         {
           /* need to somehow allow for a handle to be passed */
     
    -      ret = dev->radiocb->poll_csma(dev->radiocb, &dev->csma_desc.pub,
    +      len = dev->radiocb->poll_csma(dev->radiocb, &dev->csma_desc.pub,
                                         &dev->tx_buf[0]);
    -      if (ret > 0)
    +      if (len > 0)
             {
               /* Now the txdesc is in use */
     
    @@ -348,8 +349,7 @@ static void mrf24j40_dopoll_csma(FAR void *arg)
     
               /* Setup the transaction on the device in the CSMA FIFO */
     
    -          mrf24j40_csma_setup(dev, &dev->tx_buf[0],
    -                              dev->csma_desc.pub.psdu_length);
    +          mrf24j40_csma_setup(dev, &dev->tx_buf[0], len);
             }
         }
     
    @@ -419,7 +419,7 @@ static void mrf24j40_dopoll_gts(FAR void *arg)
     {
       FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)arg;
       int gts = 0;
    -  int ret = 0;
    +  int len = 0;
     
       /* Need to get exclusive access to the device so that we can use the copy
        * buffer.
    @@ -431,9 +431,9 @@ static void mrf24j40_dopoll_gts(FAR void *arg)
         {
           if (!dev->gts_desc[gts].busy)
             {
    -          ret = dev->radiocb->poll_gts(dev->radiocb, &dev->gts_desc[gts].pub,
    +          len = dev->radiocb->poll_gts(dev->radiocb, &dev->gts_desc[gts].pub,
                                            &dev->tx_buf[0]);
    -          if (ret > 0)
    +          if (len > 0)
                 {
                   /* Now the txdesc is in use */
     
    @@ -441,8 +441,7 @@ static void mrf24j40_dopoll_gts(FAR void *arg)
     
                   /* Setup the transaction on the device in the open GTS FIFO */
     
    -              mrf24j40_gts_setup(dev, gts, &dev->tx_buf[0],
    -                                 dev->gts_desc[gts].pub.psdu_length);
    +              mrf24j40_gts_setup(dev, gts, &dev->tx_buf[0], len);
                 }
             }
         }
    @@ -1583,27 +1582,18 @@ static void mrf24j40_irqwork_txgts(FAR struct mrf24j40_radio_s *dev,
      *
      ****************************************************************************/
     
    -static int mrf24j40_rxenable(FAR struct ieee802154_radio_s *radio, bool state,
    -                             FAR struct ieee802154_packet_s *packet)
    +static int mrf24j40_rxenable(FAR struct ieee802154_radio_s *radio)
     {
       FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)radio;
       uint8_t reg;
     
    -  if (state)
    -    {
    -      mrf24j40_pacontrol(dev, MRF24J40_PA_AUTO);
    -      radio->rxbuf = packet;
    +  mrf24j40_pacontrol(dev, MRF24J40_PA_AUTO);
     
    -      /* Enable rx int */
    +  /* Enable rx int */
     
    -      reg = mrf24j40_getreg(dev->spi, MRF24J40_INTCON);
    -      reg &= ~MRF24J40_INTCON_RXIE;
    -      mrf24j40_setreg(dev->spi, MRF24J40_INTCON, reg);
    -    }
    -  else
    -    {
    -      radio->rxbuf = NULL;
    -    }
    +  reg = mrf24j40_getreg(dev->spi, MRF24J40_INTCON);
    +  reg &= ~MRF24J40_INTCON_RXIE;
    +  mrf24j40_setreg(dev->spi, MRF24J40_INTCON, reg);
     
       return OK;
     }
    @@ -1619,7 +1609,7 @@ static int mrf24j40_rxenable(FAR struct ieee802154_radio_s *radio, bool state,
     static void mrf24j40_irqwork_rx(FAR struct mrf24j40_radio_s *dev)
     {
       FAR struct iob_s *iob;
    -  struct ieee802154_txdesc_s rxdesc;
    +  struct ieee802154_rxdesc_s rxdesc;
       uint32_t addr;
       uint32_t index;
       uint8_t  reg;
    @@ -1636,7 +1626,6 @@ static void mrf24j40_irqwork_rx(FAR struct mrf24j40_radio_s *dev)
     
       mrf24j40_setreg(dev->spi, MRF24J40_BBREG1, MRF24J40_BBREG1_RXDECINV);
     
    -
       /* Allocate an IOB to put the packet in */
     
       iob = iob_alloc(true);
    @@ -1675,7 +1664,8 @@ static void mrf24j40_irqwork_rx(FAR struct mrf24j40_radio_s *dev)
     
       /* Callback the receiver in the next highest layer */
     
    -  dev->radiocb->rx_frame(dev->radiocb, &rxdesc, iob);
    +  dev->radiocb->rxframe(dev->radiocb,
    +                        (FAR const struct ieee802154_rxdesc_s *)&rxdesc, iob);
     
       /* Enable reception of next packet by flushing the fifo.
        * This is an MRF24J40 errata (no. 1).
    @@ -1831,16 +1821,6 @@ FAR struct ieee802154_radio_s *mrf24j40_init(FAR struct spi_dev_s *spi,
     
       dev->radio.ops = &mrf24j40_devops;
     
    -  /* Initialize semaphores */
    -
    -  sem_init(&dev->radio.rxsem, 0, 0);
    -
    -  /* These semaphores are all used for signaling and, hence, should
    -   * not have priority inheritance enabled.
    -   */
    -
    -  sem_setprotocol(&dev->radio.rxsem, SEM_PRIO_NONE);
    -
       dev->lower    = lower;
       dev->spi      = spi;
     
    diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h
    index 95ccf10ecd..e1aca5de75 100644
    --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h
    +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h
    @@ -55,6 +55,8 @@
     #  include 
     #endif
     
    +#include 
    +
     #include 
     
     /****************************************************************************
    @@ -553,45 +555,7 @@ struct ieee802154_data_req_s
     
     struct ieee802154_data_conf_s
     {
    -  uint8_t msdu_handle;              /* Handle assoc. with MSDU */
    -
    -  /* The time, in symbols, at which the data were transmitted */
    -
    -  uint32_t timestamp;
    -
    -  enum ieee802154_status_e status;  /* The status of the MSDU transmission */
    -
    -#ifdef CONFIG_IEEE802154_RANGING
    -  bool rng_rcvd;                    /* Ranging indicated by MSDU */
    -
    -  /* A count of the time units corresponding to an RMARKER at the antenna at
    -   * the beginning of the ranging exchange
    -   */
    -
    -  uint32_t rng_counter_start; 
    -
    -  /* A count of the time units corresponding to an RMARKER at the antenna at
    -   * end of the ranging exchange
    -   */
    -
    -  uint32_t rng_counter_stop; 
    -
    -  /* A count of the time units in a message exchange over which the tracking
    -   * offset was measured
    -   */
    -
    -  uint34_t rng_tracking_interval;
    -
    -  /* A count of the time units slipped or advanced by the radio tracking
    -   * system over the course of the entire tracking interval
    -   */
    -
    -  uint32_t rng_offset;
    -
    -  /* The Figure of Merit (FoM) characterizing the ranging measurement */ 
    -
    -  uint8_t rng_fom; 
    -#endif
    +  IEEE802154_TXDESC_FIELDS
     };
     
     /*****************************************************************************
    @@ -1111,7 +1075,6 @@ struct ieee802154_rxenable_conf_s
     
     struct ieee802154_scan_req_s
     {
    -
       enum ieee802154_scantype_e type;
       uint8_t duration;
       uint8_t ch_page;
    @@ -1406,13 +1369,13 @@ enum ieee802154_macnotify_e
     
     struct ieee802154_maccb_s
     {
    -  CODE void (*mlme_notify) (FAR struct ieee802154_maccb_s *maccb,
    +  CODE void (*mlme_notify) (FAR const struct ieee802154_maccb_s *maccb,
                                 enum ieee802154_macnotify_e notif,
    -                            FAR union ieee802154_mlme_notify_u *arg);
    +                            FAR const union ieee802154_mlme_notify_u *arg);
     
    -  CODE void (*mcps_notify) (FAR struct ieee802154_maccb_s *maccb,
    +  CODE void (*mcps_notify) (FAR const struct ieee802154_maccb_s *maccb,
                                 enum ieee802154_macnotify_e notif,
    -                            FAR union ieee802154_mcps_notify_u *arg);
    +                            FAR const union ieee802154_mcps_notify_u *arg);
     };
     
     #ifdef __cplusplus
    diff --git a/include/nuttx/wireless/ieee802154/ieee802154_radio.h b/include/nuttx/wireless/ieee802154/ieee802154_radio.h
    index 58748b267a..54e08969d9 100644
    --- a/include/nuttx/wireless/ieee802154/ieee802154_radio.h
    +++ b/include/nuttx/wireless/ieee802154/ieee802154_radio.h
    @@ -158,12 +158,30 @@ struct ieee802154_netradio_s
     
     /* IEEE802.15.4 Radio Interface Operations **********************************/
     
    +/* This is a work-around to allow the MAC upper layer have a struct with
    + * identical members but with a different name. */
    +
    +#ifdef CONFIG_IEEE802154_RANGING
    +#define IEEE802154_TXDESC_FIELDS \ 
    +  uint8_t handle; \
    +  uint32_t timestamp; \
    +  uint8_t status;
    +#else
    +#define IEEE802154_TXDESC_FIELDS \ 
    +  uint8_t handle; \
    +  uint32_t timestamp; \
    +  uint8_t status;
    +  bool rng_rcvd; \
    +  uint32_t rng_counter_start; \ 
    +  uint32_t rng_counter_stop; \ 
    +  uint32_t rng_tracking_interval; \
    +  uint32_t rng_offset;\
    +  uint8_t rng_fom;
    +#endif
    +
     struct ieee802154_txdesc_s
     {
    -  uint8_t psdu_handle;  /* The psdu handle identifying the transaction */
    -  uint16_t psdu_length; /* The length of the PSDU */
    -  uint8_t status;       /* The status of the transaction.  This is set by the
    -                         * radio layer prior to calling txdone_csma */
    +  IEEE802154_TXDESC_FIELDS
     
       /* TODO: Add slotting information for GTS transactions */
     };
    @@ -176,13 +194,13 @@ struct ieee802154_rxdesc_s
     
     struct ieee802154_radiocb_s
     {
    -  CODE int (*poll_csma) (FAR struct ieee802154_radiocb_s *radiocb,
    +  CODE int (*poll_csma) (FAR const struct ieee802154_radiocb_s *radiocb,
                  FAR struct ieee802154_txdesc_s *tx_desc, FAR uint8_t *buf);
    -  CODE int (*poll_gts) (FAR struct ieee802154_radiocb_s *radiocb,
    +  CODE int (*poll_gts) (FAR const struct ieee802154_radiocb_s *radiocb,
                  FAR struct ieee802154_txdesc_s *tx_desc, FAR uint8_t *buf);
    -  CODE int (*txdone) (FAR struct ieee802154_radiocb_s *radiocb,
    +  CODE void (*txdone) (FAR const struct ieee802154_radiocb_s *radiocb,
                  FAR const struct ieee802154_txdesc_s *tx_desc);
    -  CODE int (*rx_frame) (FAR struct ieee802154_radiocb_s *radiocb,
    +  CODE void (*rxframe) (FAR const struct ieee802154_radiocb_s *radiocb,
                  FAR const struct ieee8021254_rxdesc_s *rx_desc,
                  FAR struct iob_s *frame);
     };
    @@ -195,8 +213,7 @@ struct ieee802154_radioops_s
                  FAR struct ieee802154_radiocb_s *radiocb);
       CODE int (*ioctl)(FAR struct ieee802154_radio_s *radio, int cmd,
                  unsigned long arg);
    -  CODE int (*rxenable)(FAR struct ieee802154_radio_s *radio, bool state,
    -             FAR struct ieee802154_packet_s *packet);
    +  CODE int (*rxenable)(FAR struct ieee802154_radio_s *radio);
       CODE int (*txnotify_csma)(FAR struct ieee802154_radio_s *radio);
       CODE int (*txnotify_gts)(FAR struct ieee802154_radio_s *radio);
     };
    diff --git a/wireless/ieee802154/Kconfig b/wireless/ieee802154/Kconfig
    index 64b9e66e91..c1f7f828fa 100644
    --- a/wireless/ieee802154/Kconfig
    +++ b/wireless/ieee802154/Kconfig
    @@ -6,13 +6,14 @@
     config WIRELESS_IEEE802154
     	bool "IEEE 802.15.4 Wireless Support"
     	default n
    +	select DRIVERS_IOB
     	---help---
     		Enables support for the IEEE 802.14.5 Wireless library.
     
     if WIRELESS_IEEE802154
     
    -config IEEE802154_MAC
    -	bool "Generic Media Access Control layer for 802.15.4 radios"
    +menuconfig IEEE802154_MAC
    +	bool "Generic Media Access Control (MAC) layer for 802.15.4 radios"
     	default n
     	depends on WIRELESS_IEEE802154
     	---help---
    @@ -21,6 +22,8 @@ config IEEE802154_MAC
     		such as 6lowpan. It is not required to use 802.15.4 radios,
     		but is strongly suggested to ensure exchange of valid frames.
     
    +if IEEE802154_MAC
    +
     config IEEE802154_MAC_DEV
     	bool "Character driver for IEEE 802.15.4 MAC layer"
     	default n
    @@ -29,6 +32,34 @@ config IEEE802154_MAC_DEV
     		Enable the device driver to expose the IEEE 802.15.4 MAC layer
     		access to user space as IOCTLs
     
    +choice
    +	prompt "IEEE 802.15.4 work queue"
    +	default MAC802154_LPWORK if SCHED_LPWORK
    +	default MAC802154_HPWORK if !SCHED_LPWORK && SCHED_HPWORK
    +	depends on SCHED_WORKQUEUE
    +	---help---
    +		Work queue support is required to use the IEEE 802.15.4 MAC layer.
    +		If the low priority work queue is available, then it should be used by
    +		the driver.
    +
    +config MAC802154_HPWORK
    +	bool "High priority"
    +	depends on SCHED_HPWORK
    +
    +config MAC802154_LPWORK
    +	bool "Low priority"
    +	depends on SCHED_LPWORK
    +
    +endchoice # Work queue
    +
    +config IEEE802154_NTXDESC
    +	int "Number or TX descriptors"
    +	default 3
    +	---help---
    +		Configured number of Tx descriptors. Default: 3
    +		
    +endif # IEEE802154_MAC
    +
     config IEEE802154_DEV
     	bool "Debug character driver for ieee802.15.4 radio interfaces"
     	default n
    diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c
    index ca877d5442..54e5782b41 100644
    --- a/wireless/ieee802154/mac802154.c
    +++ b/wireless/ieee802154/mac802154.c
    @@ -1,1252 +1,1296 @@
    -/****************************************************************************
    - * wireless/ieee802154/mac802154.c
    - *
    - *   Copyright (C) 2016 Sebastien Lorquet. All rights reserved.
    - *   Author: Sebastien Lorquet 
    - *
    - * 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 "mac802154.h"
    -
    -/****************************************************************************
    - * Pre-processor Definitions
    - ****************************************************************************/
    -
    -/****************************************************************************
    - * Private Types
    - ****************************************************************************/
    -
    -struct mac802154_trans_s
    -{
    -  /* Supports a singly linked list */
    -
    -  FAR struct mac802154_trans_s *flink;
    -
    -  uint8_t msdu_handle;
    -
    -  FAR uint8_t *mhr_buf;
    -  uint8_t mhr_len;
    -
    -  FAR uint8_t *d_buf;
    -  uint8_t d_len;
    -
    -  sem_t sem;
    -};
    -
    -struct mac802154_unsec_mhr_s
    -{
    -  uint8_t length;
    -  union
    -  {
    -    uint16_t frame_control;
    -    uint8_t data[IEEE802154_MAX_UNSEC_MHR_OVERHEAD];
    -  } u;
    -};
    -
    -struct mac802154_radiocb_s
    -{
    -  struct ieee802154_radiocb_s cb;
    -  FAR struct ieee802154_privmac_s *priv;
    -};
    -
    -/* The privmac structure holds the internal state of the MAC and is the
    - * underlying represention of the opaque MACHANDLE.  It contains storage for
    - * the IEEE802.15.4 MIB attributes.
    - */
    -
    -struct ieee802154_privmac_s
    -{
    -  FAR struct ieee802154_radio_s *radio;     /* Contained IEEE802.15.4 radio dev */
    -  FAR const struct ieee802154_maccb_s *cb;  /* Contained MAC callbacks */
    -  FAR struct mac802154_radiocb_s radiocb;   /* Interface to bind to radio */
    -
    -  sem_t exclsem; /* Support exclusive access */
    -
    -  struct work_s tx_work;
    -  struct work_s rx_work;
    -
    -  /* Support a singly linked list of transactions that will be sent using the
    -   * CSMA algorithm.  On a non-beacon enabled PAN, these transactions will be
    -   * sent whenever. On a beacon-enabled PAN, these transactions will be sent
    -   * during the CAP of the Coordinator's superframe.
    -   */
    -
    -  FAR struct mac802154_trans_s *csma_head;
    -  FAR struct mac802154_trans_s *csma_tail;
    -
    -  /* Support a singly linked list of transactions that will be sent indirectly.
    -   * This list should only be used by a MAC acting as a coordinator.  These
    -   * transactions will stay here until the data is extracted by the destination
    -   * device sending a Data Request MAC command or if too much time passes. This
    -   * list should also be used to populate the address list of the outgoing
    -   * beacon frame.
    -   */
    -
    -  FAR struct mac802154_trans_s *indirect_head;
    -  FAR struct mac802154_trans_s *indirect_tail;
    -
    -  FAR struct ieee802154_txdesc_s *txhead; /* Next TX descriptor to handle */
    -  FAR struct ieee802154_txdesc_s *txtail; /* Location to push TX descriptor */
    -  struct ieee802154_txdesc_s txtable[CONFIG_IEEE802154_NTXDESC];
    -
    -  /* MAC PIB attributes, grouped to save memory */
    -
    -  /* Holds all address information (Extended, Short, and PAN ID) for the MAC. */
    -
    -  struct ieee802154_addr_s addr;
    -
    -  /* Holds all address information (Extended, Short) for Coordinator */
    -
    -  struct ieee802154_addr_s coord_addr;
    -
    -  /* The maximum number of symbols to wait for an acknowledgement frame to
    -   * arrive following a transmitted data frame. [1] pg. 126
    -   *
    -   * NOTE: This may be able to be a 16-bit or even an 8-bit number.  I wasn't
    -   * sure at the time what the range of reasonable values was.
    -   */
    -
    -  uint32_t ack_wait_dur;
    -
    -  /* The maximum time to wait either for a frame intended as a response to a
    -   * data request frame or for a broadcast frame following a beacon with the
    -   * Frame Pending field set to one. [1] pg. 127
    -   *
    -   * NOTE: This may be able to be a 16-bit or even an 8-bit number.  I wasn't
    -   * sure at the time what the range of reasonable values was.
    -   */
    -
    -  uint32_t max_frame_wait_time;
    -
    -  /* The maximum time (in unit periods) that a transaction is stored by a
    -   * coordinator and indicated in its beacon.
    -   */
    -
    -  uint16_t trans_persist_time;
    -
    -  /* Contents of beacon payload */
    -
    -  uint8_t beacon_payload[IEEE802154_MAX_BEACON_PAYLOAD_LENGTH];
    -  uint8_t beacon_payload_len;       /* Length of beacon payload */
    -
    -  uint8_t batt_life_ext_periods;    /* # of backoff periods during which rx is
    -                                     * enabled after the IFS following beacon */
    -
    -  uint8_t bsn;                      /* Seq. num added to tx beacon frame */
    -  uint8_t dsn;                      /* Seq. num added to tx data or MAC frame */
    -  uint8_t max_retries;              /* Max # of retries alloed after tx failure */
    -
    -  /* The maximum time, in multiples of aBaseSuperframeDuration, a device shall
    -   * wait for a response command frame to be available following a request
    -   * command frame. [1] 128.
    -   */
    -
    -  uint8_t resp_wait_time;
    -
    -  /* The total transmit duration (including PHY header and FCS) specified in
    -   * symbols. [1] pg. 129.
    -   */
    -
    -  uint32_t tx_total_dur;
    -
    -  /* Start of 32-bit bitfield */
    -
    -  uint32_t is_assoc           : 1;  /* Are we associated to the PAN */
    -  uint32_t assoc_permit       : 1;  /* Are we allowing assoc. as a coord. */
    -  uint32_t auto_req           : 1;  /* Automatically send data req. if addr
    -                                     * addr is in the beacon frame */
    -
    -  uint32_t batt_life_ext      : 1;  /* Is BLE enabled */
    -  uint32_t gts_permit         : 1;  /* Is PAN Coord. accepting GTS reqs. */
    -  uint32_t promiscuous_mode   : 1;  /* Is promiscuous mode on? */
    -  uint32_t ranging_supported  : 1;  /* Does MAC sublayer support ranging */
    -  uint32_t rx_when_idle       : 1;  /* Recvr. on during idle periods */
    -  uint32_t sec_enabled        : 1;  /* Does MAC sublayer have security en. */
    -
    -  uint32_t max_csma_backoffs  : 3;  /* Max num backoffs for CSMA algorithm
    -                                     * before declaring ch access failure */
    -
    -  uint32_t beacon_order       : 4;  /* Freq. that beacon is transmitted */
    -
    -  uint32_t superframe_order   : 4;  /* Length of active portion of outgoing
    -                                     * superframe, including the beacon */
    -
    -  /* The offset, measured is symbols, between the symbol boundary at which the
    -   * MLME captures the timestamp of each transmitted and received frame, and
    -   * the onset of the first symbol past the SFD, namely the first symbol of
    -   * the frames [1] pg. 129.
    -   */
    -
    -  uint32_t sync_symb_offset   : 12;
    -
    -  /* End of 32-bit bitfield */
    -
    -  /* Start of 32-bit bitfield */
    -
    -  uint32_t beacon_tx_time     : 24; /* Time of last beacon transmit */
    -  uint32_t min_be             : 4;  /* Min value of backoff exponent (BE) */
    -  uint32_t max_be             : 4;  /* Max value of backoff exponent (BE) */
    -
    -  /* End of 32-bit bitfield */
    -
    -  /* Start of 32-bit bitfield */
    -
    -  uint32_t tx_ctrl_active_dur : 17; /* Duration for which tx is permitted to
    -                                     * be active */
    -  uint32_t tx_ctrl_pause_dur  : 1;  /* Duration after tx before another tx is
    -                                     * permitted. 0=2000, 1= 10000 */
    -  uint32_t timestamp_support  : 1;  /* Does MAC layer supports timestamping */
    -  uint32_t is_coord           : 1;  /* Is this device acting as coordinator */
    -                                    /* 12-bits remaining */
    -
    -  /* End of 32-bit bitfield. */
    -
    -  /* TODO: Add Security-related MAC PIB attributes */
    -};
    -
    -/****************************************************************************
    - * Private Function Prototypes
    - ****************************************************************************/
    -
    -static inline int mac802154_takesem(sem_t *sem);
    -#define mac802154_givesem(s) sem_post(s);
    -
    -/* Internal Functions */
    -
    -static int mac802154_defaultmib(FAR struct ieee802154_privmac_s *priv);
    -static int mac802154_applymib(FAR struct ieee802154_privmac_s *priv);
    -
    -/* IEEE 802.15.4 PHY Interface OPs */
    -
    -static int mac802154_poll_csma(FAR struct ieee802154_radiocb_s *radiocb,
    -                               FAR struct ieee802154_txdesc_s *tx_desc,
    -                               FAR uint8_t *buf);
    -
    -static int mac802154_poll_gts(FAR struct ieee802154_radiocb_s *radiocb,
    -                              FAR struct ieee802154_txdesc_s *tx_desc,
    -                              FAR uint8_t *buf);
    -
    -static int mac802154_txdone(FAR struct ieee802154_radiocb_s *radiocb,
    -                            FAR struct ieee802154_txdesc_s *tx_desc);
    -
    -/****************************************************************************
    - * Private Data
    - ****************************************************************************/
    -
    -
    -/****************************************************************************
    - * Private Functions
    - ****************************************************************************/
    -
    -/****************************************************************************
    - * Name: mac802154_semtake
    - *
    - * Description:
    - *   Acquire the semaphore used for access serialization.
    - *
    - ****************************************************************************/
    -
    -static inline int mac802154_takesem(sem_t *sem)
    -{
    -  /* Take a count from the semaphore, possibly waiting */
    -
    -  if (sem_wait(sem) < 0)
    -    {
    -      /* EINTR is the only error that we expect */
    -
    -      int errcode = get_errno();
    -      DEBUGASSERT(errcode == EINTR);
    -      return -errcode;
    -    }
    -
    -  return OK;
    -}
    -
    -/****************************************************************************
    - * Name: mac802154_defaultmib
    - *
    - * Description:
    - *   Set the MIB to its default values.
    - *
    - ****************************************************************************/
    -
    -static int mac802154_defaultmib(FAR struct ieee802154_privmac_s *priv)
    -{
    -  /* TODO: Set all MAC fields to default values */
    -
    -  return OK;
    -}
    -
    -/****************************************************************************
    - * Name: mac802154_applymib
    - *
    - * Description:
    - *   Some parts of the MIB must be sent to the radio device. This routine
    - *   calls the radio device routines to store the related parameters in the
    - *   radio driver. It must be called each time a MIB parameter is changed.
    - *
    - ****************************************************************************/
    -
    -static int mac802154_applymib(FAR struct ieee802154_privmac_s *priv)
    -{
    -  return OK;
    -}
    -
    -/****************************************************************************
    - * Name: mac802154_poll_csma
    - *
    - * Description:
    - *   Called from the radio driver through the callback struct.  This function is
    - *   called when the radio has room for another CSMA transaction.  If the MAC
    - *   layer has a CSMA transaction, it copies it into the supplied buffer and
    - *   returns the length.  A descriptor is also populated with the transaction.
    - *
    - ****************************************************************************/
    -
    -static int mac802154_poll_csma(FAR struct ieee802154_radiocb_s *radiocb,
    -                               FAR struct ieee802154_txdesc_s *tx_desc,
    -                               FAR uint8_t *buf)
    -{
    -  FAR struct mac802154_radiocb_s *cb =
    -    (FAR struct mac802154_radiocb_s *)radiocb;
    -  FAR struct ieee802154_privmac_s *priv;
    -  FAR struct mac802154_trans_s *trans;
    -
    -  DEBUGASSERT(cb != NULL && cb->priv != NULL);
    -  priv = cb->priv;
    -
    -  /* Get exclusive access to the driver structure.  We don't care about any
    -   * signals so if we see one, just go back to trying to get access again.
    -   */
    -
    -  while (mac802154_takesem(&priv->exclsem) != 0);
    -
    -  /* Check to see if there are any CSMA transactions waiting */
    -
    -  if (priv->csma_head)
    -    {
    -      /* Pop a CSMA transaction off the list */
    -
    -      trans = priv->csma_head;
    -      priv->csma_head = priv->csma_head->flink;
    -
    -      mac802154_givesem(&priv->exclsem);
    -
    -      /* Setup the transmit descriptor */
    -
    -      tx_desc->psdu_handle = trans->msdu_handle;
    -      tx_desc->psdu_length = trans->mhr_len + trans->d_len;
    -
    -      /* Copy the frame into the buffer */
    -
    -      memcpy(&buf[0], trans->mhr_buf, trans->mhr_len);
    -      memcpy(&buf[trans->mhr_len], trans->d_buf, trans->d_len);
    -
    -      /* Now that we've passed off the data, notify the waiting thread.
    -       * NOTE: The transaction was allocated on the waiting thread's stack so
    -       * it will be automatically deallocated when that thread awakens and
    -       * returns.
    -       */
    -
    -      sem_post(&trans->sem);
    -      return tx_desc->psdu_length;
    -    }
    -
    -  mac802154_givesem(&priv->exclsem);
    -  return 0;
    -}
    -
    -/****************************************************************************
    - * Name: mac802154_poll_gts
    - *
    - * Description:
    - *   Called from the radio driver through the callback struct.  This function is
    - *   called when the radio has room for another GTS transaction.  If the MAC
    - *   layer has a GTS transaction, it copies it into the supplied buffer and
    - *   returns the length.  A descriptor is also populated with the transaction.
    - *
    - ****************************************************************************/
    -
    -static int mac802154_poll_gts(FAR struct ieee802154_radiocb_s *radiocb,
    -                              FAR struct ieee802154_txdesc_s *tx_desc,
    -                              FAR uint8_t *buf)
    -{
    -  FAR struct mac802154_radiocb_s *cb =
    -    (FAR struct mac802154_radiocb_s *)radiocb;
    -  FAR struct ieee802154_privmac_s *priv;
    -  FAR struct mac802154_trans_s *trans;
    -  int ret = 0;
    -
    -  DEBUGASSERT(cb != NULL && cb->priv != NULL);
    -  priv = cb->priv;
    -
    -  /* Get exclusive access to the driver structure.  We don't care about any
    -   * signals so if we see one, just go back to trying to get access again.
    -   */
    -
    -  while (mac802154_takesem(&priv->exclsem) != 0);
    -
    -#warning Missing logic.
    -
    -  mac802154_givesem(&priv->exclsem);
    -
    -  return 0;
    -}
    -
    -/****************************************************************************
    - * Name: mac802154_txdone
    - *
    - * Description:
    - *   Called from the radio driver through the callback struct.  This function is
    - *   called when the radio has completed a transaction.  The txdesc passed gives
    - *   provides information about the completed transaction including the original
    - *   handle provided when the transaction was created and the status of the
    - *   transaction.  This function copies the descriptor and schedules work to
    - *   handle the transaction without blocking the radio.
    - *
    - ****************************************************************************/
    -
    -static int mac802154_txdone(FAR struct ieee802154_radiocb_s *radiocb,
    -                            FAR const struct ieee802154_txdesc_s *tx_desc)
    -{
    -  FAR struct mac802154_radiocb_s *cb =
    -    (FAR struct mac802154_radiocb_s *)radiocb;
    -  FAR struct ieee802154_privmac_s *priv;
    -  FAR struct ieee802154_txdesc_s *desc;
    -  int ret = 0;
    -
    -  DEBUGASSERT(cb != NULL && cb->priv != NULL);
    -  priv = cb->priv;
    -
    -  /* Get exclusive access to the driver structure.  We don't care about any
    -   * signals so if we see one, just go back to trying to get access again.
    -   */
    -
    -  while (mac802154_takesem(&priv->exclsem) != 0);
    -
    -  /* Allocate a tx_desc */
    -
    -  desc = kmm_zalloc(sizeof(struct ieee802154_txdesc_s));
    -  if (desc == NULL)
    -    {
    -      mac802154_givesem(&priv->exclsem);
    -
    -      return -ENOMEM;
    -    }
    -
    -  /* Copy the txdesc over and link it into our list */
    -
    -  memcpy(desc, tx_desc, sizeof(ieee802154_txdesc_s));
    -
    -  /* Link the descriptor */
    -
    -#warning Missing Logic!
    -
    -  mac802154_givesem(&priv->exclsem);
    -
    -  /* Schedule work with the work queue to process the completion further */
    -
    -  if (work_available(&priv->tx_work))
    -    {
    -      work_queue(MAC802154_WORK, &priv->tx_work, mac802154_txdone_worker,
    -                 (FAR void *)dev, 0);
    -    }
    -}
    -
    -/****************************************************************************
    - * Name: mac802154_txdone_worker
    - *
    - * Description:
    - *   Worker function scheduled from mac802154_txdone.  This function pops any
    - *   TX descriptors off of the list and calls the next highest layers callback
    - *   to inform the layer of the completed transaction and the status of it.
    - *
    - ****************************************************************************/
    -
    -static void mac802154_txdone_worker(FAR void *arg)
    -{
    -  FAR struct ieee802154_privmanc_s *priv =
    -    (FAR struct ieee802154_privmanc_s *)arg;
    -}
    -
    -/****************************************************************************
    - * Name: mac802154_rxframe
    - *
    - * Description:
    - *   Called from the radio driver through the callback struct.  This function is
    - *   called when the radio has received a frame. The frame is passed in an iob,
    - *   so that we can free it when we are done processing.  A pointer to the RX
    - *   descriptor is passed along with the iob, but it must be copied here as it
    - *   is allocated directly on the caller's stack.  We simply link the frame,
    - *   copy the RX descriptor, and schedule a worker to process the frame later so
    - *   that we do not hold up the radio.
    - *
    - ****************************************************************************/
    -
    -static void mac802154_rxframe(FAR struct ieee802154_radiocb_s *radiocb,
    -                              FAR struct ieee802154_rxdesc_s *rx_desc,
    -                              FAR struct iob_s *frame)
    -{
    -  FAR struct mac802154_radiocb_s *cb =
    -    (FAR struct mac802154_radiocb_s *)radiocb;
    -  FAR struct ieee802154_privmac_s *priv;
    -  FAR struct ieee802154_txdesc_s *desc;
    -  int ret = 0;
    -
    -  DEBUGASSERT(cb != NULL && cb->priv != NULL);
    -  priv = cb->priv;
    -
    -  /* Get exclusive access to the driver structure.  We don't care about any
    -   * signals so if we see one, just go back to trying to get access again.
    -   */
    -
    -  while (mac802154_takesem(&priv->exclsem) != 0);
    -
    -  /* TODO: Copy the frame descriptor to some type of list */
    -
    -  /* Push the iob onto the tail of the frame list for processing */
    -
    -  priv->rxframes_tail->io_flink = iob;
    -  priv->rxframes_tail = iob;
    -
    -  mac802154_givesem(&priv->exclsem);
    -
    -  /* Schedule work with the work queue to process the completion further */
    -
    -  if (work_available(&priv->rx_work))
    -    {
    -      work_queue(MAC802154_WORK, &priv->rx_work, mac802154_rxframe_worker,
    -                 (FAR void *)priv, 0);
    -    }
    -}
    -
    -/****************************************************************************
    - * Name: mac802154_rxframe_worker
    - *
    - * Description:
    - *   Worker function scheduled from mac802154_rxframe.  This function processes
    - *   any frames in the list.  Frames intended to be consumed by the MAC layer
    - *   will not produce any callbacks to the next highest layer.  Frames intended
    - *   for the application layer will be forwarded to them.
    - *
    - ****************************************************************************/
    -
    -static void mac802154_rxframe_worker(FAR void *arg)
    -{
    -  FAR struct ieee802154_privmac_s *priv =
    -    (FAR struct ieee802154_privmac_s *)arg;
    -
    -  /* The radio layer is responsible for handling all ACKs and retries. If for
    -   * some reason an ACK gets here, just throw it out.
    -   */
    -}
    -
    -/****************************************************************************
    - * Public Functions
    - ****************************************************************************/
    -
    -/****************************************************************************
    - * Name: mac802154_create
    - *
    - * Description:
    - *   Create a 802.15.4 MAC device from a 802.15.4 compatible radio device.
    - *
    - *   The returned MAC structure should be passed to either the next highest
    - *   layer in the network stack, or registered with a mac802154dev character
    - *   or network drivers.  In any of these scenarios, the next highest layer
    - *   should  register a set of callbacks with the MAC layer by setting the
    - *   mac->cbs member.
    - *
    - *   NOTE: This API does not create any device accessible to userspace. If
    - *   you want to call these APIs from userspace, you have to wrap your mac
    - *   in a character device via mac802154_device.c.
    - *
    - * Input Parameters:
    - *   radiodev - an instance of an IEEE 802.15.4 radio
    - *
    - * Returned Value:
    - *   An opaque reference to the MAC state data.
    - *
    - ****************************************************************************/
    -
    -MACHANDLE mac802154_create(FAR struct ieee802154_radio_s *radiodev)
    -{
    -  FAR struct ieee802154_privmac_s *mac;
    -  FAR struct ieee802154_radiocb_s *radiocb;
    -
    -  /* Allocate object */
    -
    -  mac = (FAR struct ieee802154_privmac_s *)
    -    kmm_zalloc(sizeof(struct ieee802154_privmac_s));
    -
    -  if (mac == NULL)
    -    {
    -      return NULL;
    -    }
    -
    -  /* Initialize fields */
    -
    -  mac->radio = radiodev;
    -
    -  mac802154_defaultmib(mac);
    -  mac802154_applymib(mac);
    -
    -  /* Initialize the Radio callbacks */
    -
    -  mac->radiocb.priv = mac;
    -
    -  radiocb              = &mac->radiocb.cb;
    -  radiocb->poll_csma   = mac802154_poll_csma;
    -  radiocb->poll_gts    = mac802154_poll_gts;
    -  radiocb->txdone      = mac802154_txdone;
    -
    -  /* Bind our callback structure */
    -
    -  radiodev->ops->bind(radiodev, &mac->radiocb.cb);
    -
    -  return (MACHANDLE)mac;
    -}
    -
    -/****************************************************************************
    - * Name: mac802154_bind
    - *
    - * Description:
    - *   Bind the MAC callback table to the MAC state.
    - *
    - * Parameters:
    - *   mac - Reference to the MAC driver state structure
    - *   cb  - MAC callback operations
    - *
    - * Returned Value:
    - *   OK on success; Negated errno on failure.
    - *
    - ****************************************************************************/
    -
    -int mac802154_bind(MACHANDLE mac, FAR const struct ieee802154_maccb_s *cb)
    -{
    -  FAR struct ieee802154_privmac_s *priv =
    -    (FAR struct ieee802154_privmac_s *)mac;
    -
    -  priv->cb = cb;
    -  return OK;
    -}
    -
    -/****************************************************************************
    - * Name: mac802154_ioctl
    - *
    - * Description:
    - *   Handle MAC and radio IOCTL commands directed to the MAC.
    - *
    - * Parameters:
    - *   mac - Reference to the MAC driver state structure
    - *   cmd - The IOCTL command
    - *   arg - The argument for the IOCTL command
    - *
    - * Returned Value:
    - *   OK on success; Negated errno on failure.
    - *
    - ****************************************************************************/
    -
    -int mac802154_ioctl(MACHANDLE mac, int cmd, unsigned long arg)
    -{
    -  FAR struct ieee802154_privmac_s *priv =
    -    (FAR struct ieee802154_privmac_s *)mac;
    -  int ret = -EINVAL;
    -
    -  DEBUGASSERT(priv != NULL);
    -
    -  /* Check for IOCTLs aimed at the IEEE802.15.4 MAC layer */
    -
    -  if (_MAC802154IOCVALID(cmd))
    -    {
    -      /* Handle the MAC IOCTL command */
    -#warning Missing logic
    -    }
    -
    -  /* No, other IOCTLs must be aimed at the IEEE802.15.4 radio layer */
    -
    -  else
    -   {
    -     DEBUGASSERT(priv->radio != NULL &&
    -                 priv->radio->ops != NULL &&
    -                 priv->radio->ops->ioctl != NULL);
    -
    -     ret = priv->radio->ops->ioctl(priv->radio, cmd, arg);
    -   }
    -
    - return ret;
    -}
    -
    -/****************************************************************************
    - * MAC Interface Operations
    - ****************************************************************************/
    -
    -/****************************************************************************
    - * Name: mac802154_req_data
    - *
    - * Description:
    - *   The MCPS-DATA.request primitive requests the transfer of a data SPDU
    - *   (i.e., MSDU) from a local SSCS entity to a single peer SSCS entity.
    - *   Confirmation is returned via the
    - *   struct ieee802154_maccb_s->conf_data callback.
    - *
    - ****************************************************************************/
    -
    -int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req)
    -{
    -  FAR struct ieee802154_privmac_s *priv =
    -    (FAR struct ieee802154_privmac_s *)mac;
    -  FAR struct mac802154_trans_s trans;
    -  struct mac802154_unsec_mhr_s mhr;
    -  int ret;
    -
    -  /* Start off assuming there is only the frame_control field in the MHR */
    -
    -  mhr.length = 2;
    -
    -  /* Do a preliminary check to make sure the MSDU isn't too long for even
    -   * the best case.
    -   */
    -
    -  if (req->msdu_length > IEEE802154_MAX_MAC_PAYLOAD_SIZE)
    -    {
    -      return -EINVAL;
    -    }
    -
    -  /* Ensure we start with a clear frame control field */
    -
    -  mhr.u.frame_control = 0;
    -
    -  /* Set the frame type to Data */
    -
    -  mhr.u.frame_control |= IEEE802154_FRAME_DATA <<
    -                         IEEE802154_FRAMECTRL_SHIFT_FTYPE;
    -
    -  /* If the msduLength is greater than aMaxMACSafePayloadSize, the MAC
    -   * sublayer will set the Frame Version to one. [1] pg. 118.
    -   */
    -
    -  if (req->msdu_length > IEEE802154_MAX_SAFE_MAC_PAYLOAD_SIZE)
    -    {
    -      mhr.u.frame_control |= IEEE802154_FRAMECTRL_VERSION;
    -    }
    -
    -  /* If the TXOptions parameter specifies that an acknowledged transmission
    -   * is required, the AR field will be set appropriately, as described in
    -   * 5.1.6.4 [1] pg. 118.
    -   */
    -
    -  mhr.u.frame_control |= (req->msdu_flags.ack_tx <<
    -                          IEEE802154_FRAMECTRL_SHIFT_ACKREQ);
    -
    -  /* If the destination address is present, copy the PAN ID and one of the
    -   * addresses, depending on mode, into the MHR .
    -   */
    -
    -  if (req->dest_addr.mode != IEEE802154_ADDRMODE_NONE)
    -    {
    -      memcpy(&mhr.u.data[mhr.length], &req->dest_addr.panid, 2);
    -      mhr.length += 2;
    -
    -      if (req->dest_addr.mode == IEEE802154_ADDRMODE_SHORT)
    -        {
    -          memcpy(&mhr.u.data[mhr.length], &req->dest_addr.saddr, 2);
    -          mhr.length += 2;
    -        }
    -      else if (req->dest_addr.mode == IEEE802154_ADDRMODE_EXTENDED)
    -        {
    -          memcpy(&mhr.u.data[mhr.length], &req->dest_addr.eaddr, 8);
    -          mhr.length += 8;
    -        }
    -    }
    -
    -  /* Set the destination addr mode inside the frame contorl field */
    -
    -  mhr.u.frame_control |= (req->dest_addr.mode <<
    -                          IEEE802154_FRAMECTRL_SHIFT_DADDR);
    -
    -  /* From this point on, we need exclusive access to the privmac struct */
    -
    -  ret = mac802154_takesem(&priv->exclsem);
    -  if (ret < 0)
    -    {
    -      wlerr("ERROR: mac802154_takesem failed: %d\n", ret);
    -      return ret;
    -    }
    -
    -  /* If both destination and source addressing information is present, the MAC
    -   * sublayer shall compare the destination and source PAN identifiers.
    -   * [1] pg. 41.
    -   */
    -
    -  if (req->src_addr_mode  != IEEE802154_ADDRMODE_NONE &&
    -      req->dest_addr.mode != IEEE802154_ADDRMODE_NONE)
    -    {
    -      /* If the PAN identifiers are identical, the PAN ID Compression field
    -       * shall be set to one, and the source PAN identifier shall be omitted
    -       * from the transmitted frame. [1] pg. 41.
    -       */
    -
    -      if (req->dest_addr.panid == priv->addr.panid)
    -        {
    -          mhr.u.frame_control |= IEEE802154_FRAMECTRL_PANIDCOMP;
    -        }
    -    }
    -
    -  if (req->src_addr_mode != IEEE802154_ADDRMODE_NONE)
    -    {
    -      /* If the destination address is not included, or if PAN ID Compression
    -       * is off, we need to include the Source PAN ID.
    -       */
    -
    -      if ((req->dest_addr.mode == IEEE802154_ADDRMODE_NONE) ||
    -          (mhr.u.frame_control & IEEE802154_FRAMECTRL_PANIDCOMP))
    -        {
    -          memcpy(&mhr.u.data[mhr.length], &priv->addr.panid, 2);
    -          mhr.length += 2;
    -        }
    -
    -      if (req->src_addr_mode == IEEE802154_ADDRMODE_SHORT)
    -        {
    -          memcpy(&mhr.u.data[mhr.length], &priv->addr.saddr, 2);
    -          mhr.length += 2;
    -        }
    -      else if (req->src_addr_mode == IEEE802154_ADDRMODE_EXTENDED)
    -        {
    -          memcpy(&mhr.u.data[mhr.length], &priv->addr.eaddr, 8);
    -          mhr.length += 8;
    -        }
    -    }
    -
    -  /* Set the source addr mode inside the frame control field */
    -
    -  mhr.u.frame_control |= (req->src_addr_mode <<
    -                          IEEE802154_FRAMECTRL_SHIFT_SADDR);
    -
    -  /* Each time a data or a MAC command frame is generated, the MAC sublayer
    -   * shall copy the value of macDSN into the Sequence Number field of the MHR
    -   * of the outgoing frame and then increment it by one. [1] pg. 40.
    -   */
    -
    -  mhr.u.data[mhr.length++] = priv->dsn++;
    -
    -  /* Now that we know which fields are included in the header, we can make
    -   * sure we actually have enough room in the PSDU.
    -   */
    -
    -  if (mhr.length + req->msdu_length + IEEE802154_MFR_LENGTH >
    -      IEEE802154_MAX_PHY_PACKET_SIZE)
    -  {
    -    return -E2BIG;
    -  }
    -
    -  trans.mhr_buf = &mhr.u.data[0];
    -  trans.mhr_len = mhr.length;
    -
    -  trans.d_buf = &req->msdu[0];
    -  trans.d_len = req->msdu_length;
    -
    -  trans.msdu_handle = req->msdu_handle;
    -
    -  /* If the TxOptions parameter specifies that a GTS transmission is required,
    -   * the MAC sublayer will determine whether it has a valid GTS as described
    -   * 5.1.7.3. If a valid GTS could not be found, the MAC sublayer will discard
    -   * the MSDU. If a valid GTS was found, the MAC sublayer will defer, if
    -   * necessary, until the GTS. If the TxOptions parameter specifies that a GTS
    -   * transmission is not required, the MAC sublayer will transmit the MSDU using
    -   * either slotted CSMA-CA in the CAP for a beacon-enabled PAN or unslotted
    -   * CSMA-CA for a nonbeacon-enabled PAN. Specifying a GTS transmission in the
    -   * TxOptions parameter overrides an indirect transmission request.
    -   * [1] pg. 118.
    -   */
    -
    -  if (req->msdu_flags.gts_tx)
    -    {
    -      /* TODO: Support GTS transmission. This should just change where we link
    -       * the transaction.  Instead of going in the CSMA transaction list, it
    -       * should be linked to the GTS' transaction list. We'll need to check if
    -       * the GTS is valid, and then find the GTS, before linking. Note, we also
    -       * don't have to try and kick-off any transmission here.
    -       */
    -
    -      return -ENOTSUP;
    -    }
    -  else
    -    {
    -      /* If the TxOptions parameter specifies that an indirect transmission is
    -       * required and this primitive is received by the MAC sublayer of a
    -       * coordinator, the data frame is sent using indirect transmission, as
    -       * described in 5.1.5 and 5.1.6.3. [1]
    -       */
    -
    -      if (req->msdu_flags.indirect_tx)
    -        {
    -          /* If the TxOptions parameter specifies that an indirect transmission
    -           * is required and if the device receiving this primitive is not a
    -           * coordinator, the destination address is not present, or the
    -           * TxOptions parameter also specifies a GTS transmission, the indirect
    -           * transmission option will be ignored. [1]
    -           */
    -
    -          if (priv->is_coord && req->dest_addr.mode != IEEE802154_ADDRMODE_NONE)
    -            {
    -              /* Link the transaction into the indirect_trans list */
    -
    -              priv->indirect_tail->flink = &trans;
    -              priv->indirect_tail = &trans;
    -            }
    -          else
    -            {
    -              /* Override the setting since it wasn't valid */
    -
    -              req->msdu_flags.indirect_tx = 0;
    -            }
    -        }
    -
    -      /* If this is a direct transmission not during a GTS */
    -
    -      if (!req->msdu_flags.indirect_tx)
    -        {
    -          /* Link the transaction into the CSMA transaction list */
    -
    -          priv->csma_tail->flink = &trans;
    -          priv->csma_tail = &trans;
    -
    -          /* We no longer need to have the MAC layer locked. */
    -
    -          mac802154_givesem(&priv->exclsem);
    -
    -          /* Notify the radio driver that there is data available */
    -
    -          priv->radio->ops->txnotify_csma(priv->radio);
    -
    -          sem_wait(&trans.sem);
    -        }
    -    }
    -
    -  return OK;
    -}
    -
    -
    -/****************************************************************************
    - * Name: mac802154_req_purge
    - *
    - * Description:
    - *   The MCPS-PURGE.request primitive allows the next higher layer to purge
    - *   an MSDU from the transaction queue. Confirmation is returned via
    - *   the struct ieee802154_maccb_s->conf_purge callback.
    - *
    - ****************************************************************************/
    -
    -int mac802154_req_purge(MACHANDLE mac, uint8_t handle)
    -{
    -  FAR struct ieee802154_privmac_s *priv =
    -    (FAR struct ieee802154_privmac_s *)mac;
    -  return -ENOTTY;
    -}
    -
    -/****************************************************************************
    - * Name: mac802154_req_associate
    - *
    - * Description:
    - *   The MLME-ASSOCIATE.request primitive allows a device to request an
    - *   association with a coordinator. Confirmation is returned via the
    - *   struct ieee802154_maccb_s->conf_associate callback.
    - *
    - ****************************************************************************/
    -
    -int mac802154_req_associate(MACHANDLE mac,
    -                            FAR struct ieee802154_assoc_req_s *req)
    -{
    -  FAR struct ieee802154_privmac_s *priv =
    -    (FAR struct ieee802154_privmac_s *)mac;
    -
    -  /* Set the channel of the PHY layer */
    -
    -  /* Set the channel page of the PHY layer */
    -
    -  /* Set the macPANId */
    -
    -  /* Set either the macCoordExtendedAddress and macCoordShortAddress
    -   * depending on the CoordAddrMode in the primitive.
    -   */
    -
    -  if (req->coord_addr.mode == IEEE802154_ADDRMODE_EXTENDED)
    -    {
    -
    -    }
    -  else if (req->coord_addr.mode == IEEE802154_ADDRMODE_EXTENDED)
    -    {
    -
    -    }
    -  else
    -    {
    -      return -EINVAL;
    -    }
    -
    -  return -ENOTTY;
    -}
    -
    -/****************************************************************************
    - * Name: mac802154_req_disassociate
    - *
    - * Description:
    - *   The MLME-DISASSOCIATE.request primitive is used by an associated device to
    - *   notify the coordinator of its intent to leave the PAN. It is also used by
    - *   the coordinator to instruct an associated device to leave the PAN.
    - *   Confirmation is returned via the
    - *   struct ieee802154_maccb_s->conf_disassociate callback.
    - *
    - ****************************************************************************/
    -
    -int mac802154_req_disassociate(MACHANDLE mac,
    -                               FAR struct ieee802154_disassoc_req_s *req)
    -{
    -  FAR struct ieee802154_privmac_s *priv =
    -    (FAR struct ieee802154_privmac_s *)mac;
    -  return -ENOTTY;
    -}
    -
    -/****************************************************************************
    - * Name: mac802154_req_get
    - *
    - * Description:
    - *   The MLME-GET.request primitive requests information about a given PIB
    - *   attribute. Actual data is returned via the
    - *   struct ieee802154_maccb_s->conf_get callback.
    - *
    - ****************************************************************************/
    -
    -int mac802154_req_get(MACHANDLE mac, enum ieee802154_pib_attr_e attr)
    -{
    -  FAR struct ieee802154_privmac_s *priv =
    -    (FAR struct ieee802154_privmac_s *)mac;
    -  return -ENOTTY;
    -}
    -
    -/****************************************************************************
    - * Name: mac802154_req_gts
    - *
    - * Description:
    - *   The MLME-GTS.request primitive allows a device to send a request to the PAN
    - *   coordinator to allocate a new GTS or to deallocate an existing GTS.
    - *   Confirmation is returned via the
    - *   struct ieee802154_maccb_s->conf_gts callback.
    - *
    - ****************************************************************************/
    -
    -int mac802154_req_gts(MACHANDLE mac, FAR uint8_t *characteristics)
    -{
    -  FAR struct ieee802154_privmac_s *priv =
    -    (FAR struct ieee802154_privmac_s *)mac;
    -  return -ENOTTY;
    -}
    -
    -/****************************************************************************
    - * Name: mac802154_req_reset
    - *
    - * Description:
    - *   The MLME-RESET.request primitive allows the next higher layer to request
    - *   that the MLME performs a reset operation. Confirmation is returned via
    - *   the struct ieee802154_maccb_s->conf_reset callback.
    - *
    - ****************************************************************************/
    -
    -int mac802154_req_reset(MACHANDLE mac, bool setdefaults)
    -{
    -  FAR struct ieee802154_privmac_s * priv =
    -    (FAR struct ieee802154_privmac_s *) mac;
    -  return -ENOTTY;
    -}
    -
    -/****************************************************************************
    - * Name: mac802154_req_rxenable
    - *
    - * Description:
    - *   The MLME-RX-ENABLE.request primitive allows the next higher layer to
    - *   request that the receiver is enable for a finite period of time.
    - *   Confirmation is returned via the
    - *   struct ieee802154_maccb_s->conf_rxenable callback.
    - *
    - ****************************************************************************/
    -
    -int mac802154_req_rxenable(MACHANDLE mac, bool deferrable, int ontime,
    -                           int duration)
    -{
    -  FAR struct ieee802154_privmac_s * priv =
    -    (FAR struct ieee802154_privmac_s *)mac;
    -  return -ENOTTY;
    -}
    -
    -/****************************************************************************
    - * Name: mac802154_req_scan
    - *
    - * Description:
    - *   The MLME-SCAN.request primitive is used to initiate a channel scan over a
    - *   given list of channels. A device can use a channel scan to measure the
    - *   energy on the channel, search for the coordinator with which it associated,
    - *   or search for all coordinators transmitting beacon frames within the POS of
    - *   the scanning device. Scan results are returned
    - *   via MULTIPLE calls to the struct ieee802154_maccb_s->conf_scan callback.
    - *   This is a difference with the official 802.15.4 specification, implemented
    - *   here to save memory.
    - *
    - ****************************************************************************/
    -
    -int mac802154_req_scan(MACHANDLE mac, uint8_t type, uint32_t channels,
    -                       int duration)
    -{
    -  FAR struct ieee802154_privmac_s *priv =
    -    (FAR struct ieee802154_privmac_s *)mac;
    -  return -ENOTTY;
    -}
    -
    -/****************************************************************************
    - * Name: mac802154_req_set
    - *
    - * Description:
    - *   The MLME-SET.request primitive attempts to write the given value to the
    - *   indicated MAC PIB attribute. Confirmation is returned via the
    - *   struct ieee802154_maccb_s->conf_set callback.
    - *
    - ****************************************************************************/
    -
    -int mac802154_req_set(MACHANDLE mac, int attribute, FAR uint8_t *value,
    -                      int valuelen)
    -{
    -  FAR struct ieee802154_privmac_s *priv =
    -    (FAR struct ieee802154_privmac_s *)mac;
    -  return -ENOTTY;
    -}
    -
    -/****************************************************************************
    - * Name: mac802154_req_start
    - *
    - * Description:
    - *   The MLME-START.request primitive makes a request for the device to start
    - *   using a new superframe configuration. Confirmation is returned
    - *   via the struct ieee802154_maccb_s->conf_start callback.
    - *
    - ****************************************************************************/
    -
    -int mac802154_req_start(MACHANDLE mac, uint16_t panid, int channel,
    -                        uint8_t bo, uint8_t fo, bool coord, bool batext,
    -                        bool realign)
    -{
    -  FAR struct ieee802154_privmac_s *priv =
    -    (FAR struct ieee802154_privmac_s *)mac;
    -  return -ENOTTY;
    -}
    -
    -/****************************************************************************
    - * Name: mac802154_req_sync
    - *
    - * Description:
    - *   The MLME-SYNC.request primitive requests to synchronize with the
    - *   coordinator by acquiring and, if specified, tracking its beacons.
    - *   Confirmation is returned via the
    - *   struct ieee802154_maccb_s->int_commstatus callback. TOCHECK.
    - *
    - ****************************************************************************/
    -
    -int mac802154_req_sync(MACHANDLE mac, int channel, bool track)
    -{
    -  FAR struct ieee802154_privmac_s *priv =
    -    (FAR struct ieee802154_privmac_s *)mac;
    -  return -ENOTTY;
    -}
    -
    -/****************************************************************************
    - * Name: mac802154_req_poll
    - *
    - * Description:
    - *   The MLME-POLL.request primitive prompts the device to request data from
    - *   the coordinator. Confirmation is returned via the
    - *   struct ieee802154_maccb_s->conf_poll callback, followed by a
    - *   struct ieee802154_maccb_s->ind_data callback.
    - *
    - ****************************************************************************/
    -
    -int mac802154_req_poll(MACHANDLE mac, FAR uint8_t *coordaddr)
    -{
    -  FAR struct ieee802154_privmac_s *priv =
    -    (FAR struct ieee802154_privmac_s *)mac;
    -  return -ENOTTY;
    -}
    -
    -/****************************************************************************
    - * Name: mac802154_rsp_associate
    - *
    - * Description:
    - *   The MLME-ASSOCIATE.response primitive is used to initiate a response to
    - *   an MLME-ASSOCIATE.indication primitive.
    - *
    - ****************************************************************************/
    -
    -int mac802154_rsp_associate(MACHANDLE mac, uint8_t eadr, uint16_t saddr,
    -                            int status)
    -{
    -  FAR struct ieee802154_privmac_s *priv =
    -    (FAR struct ieee802154_privmac_s *)mac;
    -  return -ENOTTY;
    -}
    -
    -/****************************************************************************
    - * Name: mac802154_rsp_orphan
    - *
    - * Description:
    - *   The MLME-ORPHAN.response primitive allows the next higher layer of a
    - *   coordinator to respond to the MLME-ORPHAN.indication primitive.
    - *
    - ****************************************************************************/
    -
    -int mac802154_rsp_orphan(MACHANDLE mac, FAR uint8_t *orphanaddr,
    -                         uint16_t saddr, bool associated)
    -{
    -  FAR struct ieee802154_privmac_s *priv =
    -    (FAR struct ieee802154_privmac_s *)mac;
    -  return -ENOTTY;
    -}
    +/****************************************************************************
    + * wireless/ieee802154/mac802154.c
    + *
    + *   Copyright (C) 2016 Sebastien Lorquet. All rights reserved.
    + *   Author: Sebastien Lorquet 
    + *
    + * 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 "mac802154.h"
    +
    +/****************************************************************************
    + * Pre-processor Definitions
    + ****************************************************************************/
    +/* Configuration ************************************************************/
    +/* If processing is not done at the interrupt level, then work queue support
    + * is required.
    + */
    +
    +#if !defined(CONFIG_SCHED_WORKQUEUE)
    +#  error Work queue support is required in this configuration (CONFIG_SCHED_WORKQUEUE)
    +#else
    +
    +  /* Use the low priority work queue if possible */
    +
    +#  if defined(CONFIG_MAC802154_HPWORK)
    +#    define MAC802154_WORK HPWORK
    +#  elif defined(CONFIG_MAC802154_LPWORK)
    +#    define MAC802154_WORK LPWORK
    +#  else
    +#    error Neither CONFIG_MAC802154_HPWORK nor CONFIG_MAC802154_LPWORK defined
    +#  endif
    +#endif
    +
    +/****************************************************************************
    + * Private Types
    + ****************************************************************************/
    +
    +struct mac802154_trans_s
    +{
    +  /* Supports a singly linked list */
    +
    +  FAR struct mac802154_trans_s *flink;
    +
    +  uint8_t msdu_handle;
    +
    +  FAR uint8_t *mhr_buf;
    +  uint8_t mhr_len;
    +
    +  FAR uint8_t *d_buf;
    +  uint8_t d_len;
    +
    +  sem_t sem;
    +};
    +
    +struct mac802154_unsec_mhr_s
    +{
    +  uint8_t length;
    +  union
    +  {
    +    uint16_t frame_control;
    +    uint8_t data[IEEE802154_MAX_UNSEC_MHR_OVERHEAD];
    +  } u;
    +};
    +
    +struct mac802154_radiocb_s
    +{
    +  struct ieee802154_radiocb_s cb;
    +  FAR struct ieee802154_privmac_s *priv;
    +};
    +
    +/* The privmac structure holds the internal state of the MAC and is the
    + * underlying represention of the opaque MACHANDLE.  It contains storage for
    + * the IEEE802.15.4 MIB attributes.
    + */
    +
    +struct ieee802154_privmac_s
    +{
    +  FAR struct ieee802154_radio_s *radio;     /* Contained IEEE802.15.4 radio dev */
    +  FAR const struct ieee802154_maccb_s *cb;  /* Contained MAC callbacks */
    +  FAR struct mac802154_radiocb_s radiocb;   /* Interface to bind to radio */
    +
    +  sem_t exclsem; /* Support exclusive access */
    +
    +  struct work_s tx_work;
    +  struct work_s rx_work;
    +
    +  /* Support a singly linked list of transactions that will be sent using the
    +   * CSMA algorithm.  On a non-beacon enabled PAN, these transactions will be
    +   * sent whenever. On a beacon-enabled PAN, these transactions will be sent
    +   * during the CAP of the Coordinator's superframe.
    +   */
    +
    +  FAR struct mac802154_trans_s *csma_head;
    +  FAR struct mac802154_trans_s *csma_tail;
    +
    +  /* Support a singly linked list of transactions that will be sent indirectly.
    +   * This list should only be used by a MAC acting as a coordinator.  These
    +   * transactions will stay here until the data is extracted by the destination
    +   * device sending a Data Request MAC command or if too much time passes. This
    +   * list should also be used to populate the address list of the outgoing
    +   * beacon frame.
    +   */
    +
    +  FAR struct mac802154_trans_s *indirect_head;
    +  FAR struct mac802154_trans_s *indirect_tail;
    +
    +  uint8_t txdesc_count;
    +  struct ieee802154_txdesc_s txdesc[CONFIG_IEEE802154_NTXDESC];
    +
    +  /* Support a singly linked list of frames received */
    +  FAR struct iob_s *rxframes_head;
    +  FAR struct iob_s *rxframes_tail;
    +
    +  /* MAC PIB attributes, grouped to save memory */
    +
    +  /* Holds all address information (Extended, Short, and PAN ID) for the MAC. */
    +
    +  struct ieee802154_addr_s addr;
    +
    +  /* Holds all address information (Extended, Short) for Coordinator */
    +
    +  struct ieee802154_addr_s coord_addr;
    +
    +  /* The maximum number of symbols to wait for an acknowledgement frame to
    +   * arrive following a transmitted data frame. [1] pg. 126
    +   *
    +   * NOTE: This may be able to be a 16-bit or even an 8-bit number.  I wasn't
    +   * sure at the time what the range of reasonable values was.
    +   */
    +
    +  uint32_t ack_wait_dur;
    +
    +  /* The maximum time to wait either for a frame intended as a response to a
    +   * data request frame or for a broadcast frame following a beacon with the
    +   * Frame Pending field set to one. [1] pg. 127
    +   *
    +   * NOTE: This may be able to be a 16-bit or even an 8-bit number.  I wasn't
    +   * sure at the time what the range of reasonable values was.
    +   */
    +
    +  uint32_t max_frame_wait_time;
    +
    +  /* The maximum time (in unit periods) that a transaction is stored by a
    +   * coordinator and indicated in its beacon.
    +   */
    +
    +  uint16_t trans_persist_time;
    +
    +  /* Contents of beacon payload */
    +
    +  uint8_t beacon_payload[IEEE802154_MAX_BEACON_PAYLOAD_LENGTH];
    +  uint8_t beacon_payload_len;       /* Length of beacon payload */
    +
    +  uint8_t batt_life_ext_periods;    /* # of backoff periods during which rx is
    +                                     * enabled after the IFS following beacon */
    +
    +  uint8_t bsn;                      /* Seq. num added to tx beacon frame */
    +  uint8_t dsn;                      /* Seq. num added to tx data or MAC frame */
    +  uint8_t max_retries;              /* Max # of retries alloed after tx failure */
    +
    +  /* The maximum time, in multiples of aBaseSuperframeDuration, a device shall
    +   * wait for a response command frame to be available following a request
    +   * command frame. [1] 128.
    +   */
    +
    +  uint8_t resp_wait_time;
    +
    +  /* The total transmit duration (including PHY header and FCS) specified in
    +   * symbols. [1] pg. 129.
    +   */
    +
    +  uint32_t tx_total_dur;
    +
    +  /* Start of 32-bit bitfield */
    +
    +  uint32_t is_assoc           : 1;  /* Are we associated to the PAN */
    +  uint32_t assoc_permit       : 1;  /* Are we allowing assoc. as a coord. */
    +  uint32_t auto_req           : 1;  /* Automatically send data req. if addr
    +                                     * addr is in the beacon frame */
    +
    +  uint32_t batt_life_ext      : 1;  /* Is BLE enabled */
    +  uint32_t gts_permit         : 1;  /* Is PAN Coord. accepting GTS reqs. */
    +  uint32_t promiscuous_mode   : 1;  /* Is promiscuous mode on? */
    +  uint32_t ranging_supported  : 1;  /* Does MAC sublayer support ranging */
    +  uint32_t rx_when_idle       : 1;  /* Recvr. on during idle periods */
    +  uint32_t sec_enabled        : 1;  /* Does MAC sublayer have security en. */
    +
    +  uint32_t max_csma_backoffs  : 3;  /* Max num backoffs for CSMA algorithm
    +                                     * before declaring ch access failure */
    +
    +  uint32_t beacon_order       : 4;  /* Freq. that beacon is transmitted */
    +
    +  uint32_t superframe_order   : 4;  /* Length of active portion of outgoing
    +                                     * superframe, including the beacon */
    +
    +  /* The offset, measured is symbols, between the symbol boundary at which the
    +   * MLME captures the timestamp of each transmitted and received frame, and
    +   * the onset of the first symbol past the SFD, namely the first symbol of
    +   * the frames [1] pg. 129.
    +   */
    +
    +  uint32_t sync_symb_offset   : 12;
    +
    +  /* End of 32-bit bitfield */
    +
    +  /* Start of 32-bit bitfield */
    +
    +  uint32_t beacon_tx_time     : 24; /* Time of last beacon transmit */
    +  uint32_t min_be             : 4;  /* Min value of backoff exponent (BE) */
    +  uint32_t max_be             : 4;  /* Max value of backoff exponent (BE) */
    +
    +  /* End of 32-bit bitfield */
    +
    +  /* Start of 32-bit bitfield */
    +
    +  uint32_t tx_ctrl_active_dur : 17; /* Duration for which tx is permitted to
    +                                     * be active */
    +  uint32_t tx_ctrl_pause_dur  : 1;  /* Duration after tx before another tx is
    +                                     * permitted. 0=2000, 1= 10000 */
    +  uint32_t timestamp_support  : 1;  /* Does MAC layer supports timestamping */
    +  uint32_t is_coord           : 1;  /* Is this device acting as coordinator */
    +                                    /* 12-bits remaining */
    +
    +  /* End of 32-bit bitfield. */
    +
    +  /* TODO: Add Security-related MAC PIB attributes */
    +};
    +
    +/****************************************************************************
    + * Private Function Prototypes
    + ****************************************************************************/
    +
    +static inline int mac802154_takesem(sem_t *sem);
    +#define mac802154_givesem(s) sem_post(s);
    +
    +static void mac802154_txdone_worker(FAR void *arg);
    +static void mac802154_rxframe_worker(FAR void *arg);
    +
    +/* Internal Functions */
    +
    +static int mac802154_defaultmib(FAR struct ieee802154_privmac_s *priv);
    +static int mac802154_applymib(FAR struct ieee802154_privmac_s *priv);
    +
    +/* IEEE 802.15.4 PHY Interface OPs */
    +
    +static int mac802154_poll_csma(FAR const struct ieee802154_radiocb_s *radiocb,
    +                               FAR struct ieee802154_txdesc_s *tx_desc,
    +                               FAR uint8_t *buf);
    +
    +static int mac802154_poll_gts(FAR const struct ieee802154_radiocb_s *radiocb,
    +                              FAR struct ieee802154_txdesc_s *tx_desc,
    +                              FAR uint8_t *buf);
    +
    +static void mac802154_txdone(FAR const struct ieee802154_radiocb_s *radiocb,
    +                             FAR const struct ieee802154_txdesc_s *tx_desc);
    +
    +static void mac802154_rxframe(FAR const struct ieee802154_radiocb_s *radiocb,
    +                              FAR struct ieee802154_rxdesc_s *rx_desc,
    +                              FAR struct iob_s *frame);
    +
    +/****************************************************************************
    + * Private Data
    + ****************************************************************************/
    +
    +
    +/****************************************************************************
    + * Private Functions
    + ****************************************************************************/
    +
    +/****************************************************************************
    + * Name: mac802154_semtake
    + *
    + * Description:
    + *   Acquire the semaphore used for access serialization.
    + *
    + ****************************************************************************/
    +
    +static inline int mac802154_takesem(sem_t *sem)
    +{
    +  /* Take a count from the semaphore, possibly waiting */
    +
    +  if (sem_wait(sem) < 0)
    +    {
    +      /* EINTR is the only error that we expect */
    +
    +      int errcode = get_errno();
    +      DEBUGASSERT(errcode == EINTR);
    +      return -errcode;
    +    }
    +
    +  return OK;
    +}
    +
    +/****************************************************************************
    + * Name: mac802154_defaultmib
    + *
    + * Description:
    + *   Set the MIB to its default values.
    + *
    + ****************************************************************************/
    +
    +static int mac802154_defaultmib(FAR struct ieee802154_privmac_s *priv)
    +{
    +  /* TODO: Set all MAC fields to default values */
    +
    +  return OK;
    +}
    +
    +/****************************************************************************
    + * Name: mac802154_applymib
    + *
    + * Description:
    + *   Some parts of the MIB must be sent to the radio device. This routine
    + *   calls the radio device routines to store the related parameters in the
    + *   radio driver. It must be called each time a MIB parameter is changed.
    + *
    + ****************************************************************************/
    +
    +static int mac802154_applymib(FAR struct ieee802154_privmac_s *priv)
    +{
    +  return OK;
    +}
    +
    +/****************************************************************************
    + * Name: mac802154_poll_csma
    + *
    + * Description:
    + *   Called from the radio driver through the callback struct.  This function is
    + *   called when the radio has room for another CSMA transaction.  If the MAC
    + *   layer has a CSMA transaction, it copies it into the supplied buffer and
    + *   returns the length.  A descriptor is also populated with the transaction.
    + *
    + ****************************************************************************/
    +
    +static int mac802154_poll_csma(FAR const struct ieee802154_radiocb_s *radiocb,
    +                               FAR struct ieee802154_txdesc_s *tx_desc,
    +                               FAR uint8_t *buf)
    +{
    +  FAR struct mac802154_radiocb_s *cb =
    +    (FAR struct mac802154_radiocb_s *)radiocb;
    +  FAR struct ieee802154_privmac_s *priv;
    +  FAR struct mac802154_trans_s *trans;
    +
    +  DEBUGASSERT(cb != NULL && cb->priv != NULL);
    +  priv = cb->priv;
    +
    +  /* Get exclusive access to the driver structure.  We don't care about any
    +   * signals so if we see one, just go back to trying to get access again.
    +   */
    +
    +  while (mac802154_takesem(&priv->exclsem) != 0);
    +
    +  /* Check to see if there are any CSMA transactions waiting */
    +
    +  if (priv->csma_head)
    +    {
    +      /* Pop a CSMA transaction off the list */
    +
    +      trans = priv->csma_head;
    +      priv->csma_head = priv->csma_head->flink;
    +
    +      mac802154_givesem(&priv->exclsem);
    +
    +      /* Setup the transmit descriptor */
    +
    +      tx_desc->handle = trans->msdu_handle;
    +
    +      /* Copy the frame into the buffer */
    +
    +      memcpy(&buf[0], trans->mhr_buf, trans->mhr_len);
    +      memcpy(&buf[trans->mhr_len], trans->d_buf, trans->d_len);
    +
    +      /* Now that we've passed off the data, notify the waiting thread.
    +       * NOTE: The transaction was allocated on the waiting thread's stack so
    +       * it will be automatically deallocated when that thread awakens and
    +       * returns.
    +       */
    +
    +      sem_post(&trans->sem);
    +      return (trans->mhr_len + trans->d_len);
    +    }
    +
    +  mac802154_givesem(&priv->exclsem);
    +  return 0;
    +}
    +
    +/****************************************************************************
    + * Name: mac802154_poll_gts
    + *
    + * Description:
    + *   Called from the radio driver through the callback struct.  This function is
    + *   called when the radio has room for another GTS transaction.  If the MAC
    + *   layer has a GTS transaction, it copies it into the supplied buffer and
    + *   returns the length.  A descriptor is also populated with the transaction.
    + *
    + ****************************************************************************/
    +
    +static int mac802154_poll_gts(FAR const struct ieee802154_radiocb_s *radiocb,
    +                              FAR struct ieee802154_txdesc_s *tx_desc,
    +                              FAR uint8_t *buf)
    +{
    +  FAR struct mac802154_radiocb_s *cb =
    +    (FAR struct mac802154_radiocb_s *)radiocb;
    +  FAR struct ieee802154_privmac_s *priv;
    +  FAR struct mac802154_trans_s *trans;
    +  int ret = 0;
    +
    +  DEBUGASSERT(cb != NULL && cb->priv != NULL);
    +  priv = cb->priv;
    +
    +  /* Get exclusive access to the driver structure.  We don't care about any
    +   * signals so if we see one, just go back to trying to get access again.
    +   */
    +
    +  while (mac802154_takesem(&priv->exclsem) != 0);
    +
    +#warning Missing logic.
    +
    +  mac802154_givesem(&priv->exclsem);
    +
    +  return 0;
    +}
    +
    +/****************************************************************************
    + * Name: mac802154_txdone
    + *
    + * Description:
    + *   Called from the radio driver through the callback struct.  This function is
    + *   called when the radio has completed a transaction.  The txdesc passed gives
    + *   provides information about the completed transaction including the original
    + *   handle provided when the transaction was created and the status of the
    + *   transaction.  This function copies the descriptor and schedules work to
    + *   handle the transaction without blocking the radio.
    + *
    + ****************************************************************************/
    +
    +static void mac802154_txdone(FAR const struct ieee802154_radiocb_s *radiocb,
    +                            FAR const struct ieee802154_txdesc_s *tx_desc)
    +{
    +  FAR struct mac802154_radiocb_s *cb =
    +    (FAR struct mac802154_radiocb_s *)radiocb;
    +  FAR struct ieee802154_privmac_s *priv;
    +
    +  DEBUGASSERT(cb != NULL && cb->priv != NULL);
    +  priv = cb->priv;
    +
    +  /* Get exclusive access to the driver structure.  We don't care about any
    +   * signals so if we see one, just go back to trying to get access again.
    +   */
    +
    +  while (mac802154_takesem(&priv->exclsem) != 0);
    +
    +  /* Check to see if there is an available tx descriptor slot.  If there is
    +   * not we simply drop the notification */
    +
    +  if (priv->txdesc_count < CONFIG_IEEE802154_NTXDESC)
    +    {
    +      /* Copy the txdesc over and link it into our list */
    +
    +      memcpy(&priv->txdesc[priv->txdesc_count++], tx_desc,
    +             sizeof(struct ieee802154_txdesc_s));
    +    }
    +  else
    +    {
    +      wlinfo("MAC802154: No room for TX Desc.\n");
    +    }
    +
    +  mac802154_givesem(&priv->exclsem);
    +
    +  /* Schedule work with the work queue to process the completion further */
    +
    +  if (work_available(&priv->tx_work))
    +    {
    +      work_queue(MAC802154_WORK, &priv->tx_work, mac802154_txdone_worker,
    +                 (FAR void *)priv, 0);
    +    }
    +}
    +
    +/****************************************************************************
    + * Name: mac802154_txdone_worker
    + *
    + * Description:
    + *   Worker function scheduled from mac802154_txdone.  This function pops any
    + *   TX descriptors off of the list and calls the next highest layers callback
    + *   to inform the layer of the completed transaction and the status of it.
    + *
    + ****************************************************************************/
    +
    +static void mac802154_txdone_worker(FAR void *arg)
    +{
    +  FAR struct ieee802154_privmac_s *priv = 
    +    (FAR struct ieee802154_privmac_s *)arg;
    +  int i = 0;
    +  
    +  /* Get exclusive access to the driver structure.  We don't care about any
    +   * signals so if we see one, just go back to trying to get access again.
    +   */
    +
    +  while (mac802154_takesem(&priv->exclsem) != 0);
    +
    +  /* For each pending TX descriptor, send an application callback */
    +
    +  for (i = 0; i < priv->txdesc_count; i++)
    +    {
    +      priv->cb->mcps_notify(priv->cb, IEEE802154_NOTIFY_CONF_DATA,
    +                  (FAR const union ieee802154_mcps_notify_u *) &priv->txdesc[i]);
    +    }
    +
    +  /* We've handled all the descriptors and no further desc could have been added
    +   * since we have the struct locked */
    +
    +  priv->txdesc_count = 0;
    +
    +  mac802154_givesem(&priv->exclsem);
    +}
    +
    +/****************************************************************************
    + * Name: mac802154_rxframe
    + *
    + * Description:
    + *   Called from the radio driver through the callback struct.  This function is
    + *   called when the radio has received a frame. The frame is passed in an iob,
    + *   so that we can free it when we are done processing.  A pointer to the RX
    + *   descriptor is passed along with the iob, but it must be copied here as it
    + *   is allocated directly on the caller's stack.  We simply link the frame,
    + *   copy the RX descriptor, and schedule a worker to process the frame later so
    + *   that we do not hold up the radio.
    + *
    + ****************************************************************************/
    +
    +static void mac802154_rxframe(FAR const struct ieee802154_radiocb_s *radiocb,
    +                              FAR struct ieee802154_rxdesc_s *rx_desc,
    +                              FAR struct iob_s *frame)
    +{
    +  FAR struct mac802154_radiocb_s *cb =
    +    (FAR struct mac802154_radiocb_s *)radiocb;
    +  FAR struct ieee802154_privmac_s *priv;
    +  FAR struct ieee802154_rxdesc_s *desc;
    +
    +  DEBUGASSERT(cb != NULL && cb->priv != NULL);
    +  priv = cb->priv;
    +
    +  /* Get exclusive access to the driver structure.  We don't care about any
    +   * signals so if we see one, just go back to trying to get access again.
    +   */
    +
    +  while (mac802154_takesem(&priv->exclsem) != 0);
    +
    +  /* TODO: Copy the frame descriptor to some type of list */
    +
    +  /* Push the iob onto the tail of the frame list for processing */
    +
    +  priv->rxframes_tail->io_flink = frame;
    +  priv->rxframes_tail = frame;
    +
    +  mac802154_givesem(&priv->exclsem);
    +
    +  /* Schedule work with the work queue to process the completion further */
    +
    +  if (work_available(&priv->rx_work))
    +    {
    +      work_queue(MAC802154_WORK, &priv->rx_work, mac802154_rxframe_worker,
    +                 (FAR void *)priv, 0);
    +    }
    +}
    +
    +/****************************************************************************
    + * Name: mac802154_rxframe_worker
    + *
    + * Description:
    + *   Worker function scheduled from mac802154_rxframe.  This function processes
    + *   any frames in the list.  Frames intended to be consumed by the MAC layer
    + *   will not produce any callbacks to the next highest layer.  Frames intended
    + *   for the application layer will be forwarded to them.
    + *
    + ****************************************************************************/
    +
    +static void mac802154_rxframe_worker(FAR void *arg)
    +{
    +  FAR struct ieee802154_privmac_s *priv =
    +    (FAR struct ieee802154_privmac_s *)arg;
    +
    +  /* The radio layer is responsible for handling all ACKs and retries. If for
    +   * some reason an ACK gets here, just throw it out.
    +   */
    +}
    +
    +/****************************************************************************
    + * Public Functions
    + ****************************************************************************/
    +
    +/****************************************************************************
    + * Name: mac802154_create
    + *
    + * Description:
    + *   Create a 802.15.4 MAC device from a 802.15.4 compatible radio device.
    + *
    + *   The returned MAC structure should be passed to either the next highest
    + *   layer in the network stack, or registered with a mac802154dev character
    + *   or network drivers.  In any of these scenarios, the next highest layer
    + *   should  register a set of callbacks with the MAC layer by setting the
    + *   mac->cbs member.
    + *
    + *   NOTE: This API does not create any device accessible to userspace. If
    + *   you want to call these APIs from userspace, you have to wrap your mac
    + *   in a character device via mac802154_device.c.
    + *
    + * Input Parameters:
    + *   radiodev - an instance of an IEEE 802.15.4 radio
    + *
    + * Returned Value:
    + *   An opaque reference to the MAC state data.
    + *
    + ****************************************************************************/
    +
    +MACHANDLE mac802154_create(FAR struct ieee802154_radio_s *radiodev)
    +{
    +  FAR struct ieee802154_privmac_s *mac;
    +  FAR struct ieee802154_radiocb_s *radiocb;
    +
    +  /* Allocate object */
    +
    +  mac = (FAR struct ieee802154_privmac_s *)
    +    kmm_zalloc(sizeof(struct ieee802154_privmac_s));
    +
    +  if (mac == NULL)
    +    {
    +      return NULL;
    +    }
    +
    +  /* Initialize fields */
    +
    +  mac->radio = radiodev;
    +
    +  mac802154_defaultmib(mac);
    +  mac802154_applymib(mac);
    +
    +  /* Initialize the Radio callbacks */
    +
    +  mac->radiocb.priv = mac;
    +
    +  radiocb              = &mac->radiocb.cb;
    +  radiocb->poll_csma   = mac802154_poll_csma;
    +  radiocb->poll_gts    = mac802154_poll_gts;
    +  radiocb->txdone      = mac802154_txdone;
    +  radiocb->rxframe     = mac802154_rxframe;
    +
    +  /* Bind our callback structure */
    +
    +  radiodev->ops->bind(radiodev, &mac->radiocb.cb);
    +
    +  return (MACHANDLE)mac;
    +}
    +
    +/****************************************************************************
    + * Name: mac802154_bind
    + *
    + * Description:
    + *   Bind the MAC callback table to the MAC state.
    + *
    + * Parameters:
    + *   mac - Reference to the MAC driver state structure
    + *   cb  - MAC callback operations
    + *
    + * Returned Value:
    + *   OK on success; Negated errno on failure.
    + *
    + ****************************************************************************/
    +
    +int mac802154_bind(MACHANDLE mac, FAR const struct ieee802154_maccb_s *cb)
    +{
    +  FAR struct ieee802154_privmac_s *priv =
    +    (FAR struct ieee802154_privmac_s *)mac;
    +
    +  priv->cb = cb;
    +  return OK;
    +}
    +
    +/****************************************************************************
    + * Name: mac802154_ioctl
    + *
    + * Description:
    + *   Handle MAC and radio IOCTL commands directed to the MAC.
    + *
    + * Parameters:
    + *   mac - Reference to the MAC driver state structure
    + *   cmd - The IOCTL command
    + *   arg - The argument for the IOCTL command
    + *
    + * Returned Value:
    + *   OK on success; Negated errno on failure.
    + *
    + ****************************************************************************/
    +
    +int mac802154_ioctl(MACHANDLE mac, int cmd, unsigned long arg)
    +{
    +  FAR struct ieee802154_privmac_s *priv =
    +    (FAR struct ieee802154_privmac_s *)mac;
    +  int ret = -EINVAL;
    +
    +  DEBUGASSERT(priv != NULL);
    +
    +  /* Check for IOCTLs aimed at the IEEE802.15.4 MAC layer */
    +
    +  if (_MAC802154IOCVALID(cmd))
    +    {
    +      /* Handle the MAC IOCTL command */
    +#warning Missing logic
    +    }
    +
    +  /* No, other IOCTLs must be aimed at the IEEE802.15.4 radio layer */
    +
    +  else
    +   {
    +     DEBUGASSERT(priv->radio != NULL &&
    +                 priv->radio->ops != NULL &&
    +                 priv->radio->ops->ioctl != NULL);
    +
    +     ret = priv->radio->ops->ioctl(priv->radio, cmd, arg);
    +   }
    +
    + return ret;
    +}
    +
    +/****************************************************************************
    + * MAC Interface Operations
    + ****************************************************************************/
    +
    +/****************************************************************************
    + * Name: mac802154_req_data
    + *
    + * Description:
    + *   The MCPS-DATA.request primitive requests the transfer of a data SPDU
    + *   (i.e., MSDU) from a local SSCS entity to a single peer SSCS entity.
    + *   Confirmation is returned via the
    + *   struct ieee802154_maccb_s->conf_data callback.
    + *
    + ****************************************************************************/
    +
    +int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req)
    +{
    +  FAR struct ieee802154_privmac_s *priv =
    +    (FAR struct ieee802154_privmac_s *)mac;
    +  FAR struct mac802154_trans_s trans;
    +  struct mac802154_unsec_mhr_s mhr;
    +  int ret;
    +
    +  /* Start off assuming there is only the frame_control field in the MHR */
    +
    +  mhr.length = 2;
    +
    +  /* Do a preliminary check to make sure the MSDU isn't too long for even
    +   * the best case.
    +   */
    +
    +  if (req->msdu_length > IEEE802154_MAX_MAC_PAYLOAD_SIZE)
    +    {
    +      return -EINVAL;
    +    }
    +
    +  /* Ensure we start with a clear frame control field */
    +
    +  mhr.u.frame_control = 0;
    +
    +  /* Set the frame type to Data */
    +
    +  mhr.u.frame_control |= IEEE802154_FRAME_DATA <<
    +                         IEEE802154_FRAMECTRL_SHIFT_FTYPE;
    +
    +  /* If the msduLength is greater than aMaxMACSafePayloadSize, the MAC
    +   * sublayer will set the Frame Version to one. [1] pg. 118.
    +   */
    +
    +  if (req->msdu_length > IEEE802154_MAX_SAFE_MAC_PAYLOAD_SIZE)
    +    {
    +      mhr.u.frame_control |= IEEE802154_FRAMECTRL_VERSION;
    +    }
    +
    +  /* If the TXOptions parameter specifies that an acknowledged transmission
    +   * is required, the AR field will be set appropriately, as described in
    +   * 5.1.6.4 [1] pg. 118.
    +   */
    +
    +  mhr.u.frame_control |= (req->msdu_flags.ack_tx <<
    +                          IEEE802154_FRAMECTRL_SHIFT_ACKREQ);
    +
    +  /* If the destination address is present, copy the PAN ID and one of the
    +   * addresses, depending on mode, into the MHR .
    +   */
    +
    +  if (req->dest_addr.mode != IEEE802154_ADDRMODE_NONE)
    +    {
    +      memcpy(&mhr.u.data[mhr.length], &req->dest_addr.panid, 2);
    +      mhr.length += 2;
    +
    +      if (req->dest_addr.mode == IEEE802154_ADDRMODE_SHORT)
    +        {
    +          memcpy(&mhr.u.data[mhr.length], &req->dest_addr.saddr, 2);
    +          mhr.length += 2;
    +        }
    +      else if (req->dest_addr.mode == IEEE802154_ADDRMODE_EXTENDED)
    +        {
    +          memcpy(&mhr.u.data[mhr.length], &req->dest_addr.eaddr, 8);
    +          mhr.length += 8;
    +        }
    +    }
    +
    +  /* Set the destination addr mode inside the frame contorl field */
    +
    +  mhr.u.frame_control |= (req->dest_addr.mode <<
    +                          IEEE802154_FRAMECTRL_SHIFT_DADDR);
    +
    +  /* From this point on, we need exclusive access to the privmac struct */
    +
    +  ret = mac802154_takesem(&priv->exclsem);
    +  if (ret < 0)
    +    {
    +      wlerr("ERROR: mac802154_takesem failed: %d\n", ret);
    +      return ret;
    +    }
    +
    +  /* If both destination and source addressing information is present, the MAC
    +   * sublayer shall compare the destination and source PAN identifiers.
    +   * [1] pg. 41.
    +   */
    +
    +  if (req->src_addr_mode  != IEEE802154_ADDRMODE_NONE &&
    +      req->dest_addr.mode != IEEE802154_ADDRMODE_NONE)
    +    {
    +      /* If the PAN identifiers are identical, the PAN ID Compression field
    +       * shall be set to one, and the source PAN identifier shall be omitted
    +       * from the transmitted frame. [1] pg. 41.
    +       */
    +
    +      if (req->dest_addr.panid == priv->addr.panid)
    +        {
    +          mhr.u.frame_control |= IEEE802154_FRAMECTRL_PANIDCOMP;
    +        }
    +    }
    +
    +  if (req->src_addr_mode != IEEE802154_ADDRMODE_NONE)
    +    {
    +      /* If the destination address is not included, or if PAN ID Compression
    +       * is off, we need to include the Source PAN ID.
    +       */
    +
    +      if ((req->dest_addr.mode == IEEE802154_ADDRMODE_NONE) ||
    +          (mhr.u.frame_control & IEEE802154_FRAMECTRL_PANIDCOMP))
    +        {
    +          memcpy(&mhr.u.data[mhr.length], &priv->addr.panid, 2);
    +          mhr.length += 2;
    +        }
    +
    +      if (req->src_addr_mode == IEEE802154_ADDRMODE_SHORT)
    +        {
    +          memcpy(&mhr.u.data[mhr.length], &priv->addr.saddr, 2);
    +          mhr.length += 2;
    +        }
    +      else if (req->src_addr_mode == IEEE802154_ADDRMODE_EXTENDED)
    +        {
    +          memcpy(&mhr.u.data[mhr.length], &priv->addr.eaddr, 8);
    +          mhr.length += 8;
    +        }
    +    }
    +
    +  /* Set the source addr mode inside the frame control field */
    +
    +  mhr.u.frame_control |= (req->src_addr_mode <<
    +                          IEEE802154_FRAMECTRL_SHIFT_SADDR);
    +
    +  /* Each time a data or a MAC command frame is generated, the MAC sublayer
    +   * shall copy the value of macDSN into the Sequence Number field of the MHR
    +   * of the outgoing frame and then increment it by one. [1] pg. 40.
    +   */
    +
    +  mhr.u.data[mhr.length++] = priv->dsn++;
    +
    +  /* Now that we know which fields are included in the header, we can make
    +   * sure we actually have enough room in the PSDU.
    +   */
    +
    +  if (mhr.length + req->msdu_length + IEEE802154_MFR_LENGTH >
    +      IEEE802154_MAX_PHY_PACKET_SIZE)
    +  {
    +    return -E2BIG;
    +  }
    +
    +  trans.mhr_buf = &mhr.u.data[0];
    +  trans.mhr_len = mhr.length;
    +
    +  trans.d_buf = &req->msdu[0];
    +  trans.d_len = req->msdu_length;
    +
    +  trans.msdu_handle = req->msdu_handle;
    +
    +  /* If the TxOptions parameter specifies that a GTS transmission is required,
    +   * the MAC sublayer will determine whether it has a valid GTS as described
    +   * 5.1.7.3. If a valid GTS could not be found, the MAC sublayer will discard
    +   * the MSDU. If a valid GTS was found, the MAC sublayer will defer, if
    +   * necessary, until the GTS. If the TxOptions parameter specifies that a GTS
    +   * transmission is not required, the MAC sublayer will transmit the MSDU using
    +   * either slotted CSMA-CA in the CAP for a beacon-enabled PAN or unslotted
    +   * CSMA-CA for a nonbeacon-enabled PAN. Specifying a GTS transmission in the
    +   * TxOptions parameter overrides an indirect transmission request.
    +   * [1] pg. 118.
    +   */
    +
    +  if (req->msdu_flags.gts_tx)
    +    {
    +      /* TODO: Support GTS transmission. This should just change where we link
    +       * the transaction.  Instead of going in the CSMA transaction list, it
    +       * should be linked to the GTS' transaction list. We'll need to check if
    +       * the GTS is valid, and then find the GTS, before linking. Note, we also
    +       * don't have to try and kick-off any transmission here.
    +       */
    +
    +      return -ENOTSUP;
    +    }
    +  else
    +    {
    +      /* If the TxOptions parameter specifies that an indirect transmission is
    +       * required and this primitive is received by the MAC sublayer of a
    +       * coordinator, the data frame is sent using indirect transmission, as
    +       * described in 5.1.5 and 5.1.6.3. [1]
    +       */
    +
    +      if (req->msdu_flags.indirect_tx)
    +        {
    +          /* If the TxOptions parameter specifies that an indirect transmission
    +           * is required and if the device receiving this primitive is not a
    +           * coordinator, the destination address is not present, or the
    +           * TxOptions parameter also specifies a GTS transmission, the indirect
    +           * transmission option will be ignored. [1]
    +           */
    +
    +          if (priv->is_coord && req->dest_addr.mode != IEEE802154_ADDRMODE_NONE)
    +            {
    +              /* Link the transaction into the indirect_trans list */
    +
    +              priv->indirect_tail->flink = &trans;
    +              priv->indirect_tail = &trans;
    +            }
    +          else
    +            {
    +              /* Override the setting since it wasn't valid */
    +
    +              req->msdu_flags.indirect_tx = 0;
    +            }
    +        }
    +
    +      /* If this is a direct transmission not during a GTS */
    +
    +      if (!req->msdu_flags.indirect_tx)
    +        {
    +          /* Link the transaction into the CSMA transaction list */
    +
    +          priv->csma_tail->flink = &trans;
    +          priv->csma_tail = &trans;
    +
    +          /* We no longer need to have the MAC layer locked. */
    +
    +          mac802154_givesem(&priv->exclsem);
    +
    +          /* Notify the radio driver that there is data available */
    +
    +          priv->radio->ops->txnotify_csma(priv->radio);
    +
    +          sem_wait(&trans.sem);
    +        }
    +    }
    +
    +  return OK;
    +}
    +
    +
    +/****************************************************************************
    + * Name: mac802154_req_purge
    + *
    + * Description:
    + *   The MCPS-PURGE.request primitive allows the next higher layer to purge
    + *   an MSDU from the transaction queue. Confirmation is returned via
    + *   the struct ieee802154_maccb_s->conf_purge callback.
    + *
    + ****************************************************************************/
    +
    +int mac802154_req_purge(MACHANDLE mac, FAR struct ieee802154_purge_req_s *req)
    +{
    +  FAR struct ieee802154_privmac_s *priv =
    +    (FAR struct ieee802154_privmac_s *)mac;
    +  return -ENOTTY;
    +}
    +
    +/****************************************************************************
    + * Name: mac802154_req_associate
    + *
    + * Description:
    + *   The MLME-ASSOCIATE.request primitive allows a device to request an
    + *   association with a coordinator. Confirmation is returned via the
    + *   struct ieee802154_maccb_s->conf_associate callback.
    + *
    + ****************************************************************************/
    +
    +int mac802154_req_associate(MACHANDLE mac,
    +                            FAR struct ieee802154_assoc_req_s *req)
    +{
    +  FAR struct ieee802154_privmac_s *priv =
    +    (FAR struct ieee802154_privmac_s *)mac;
    +
    +  /* Set the channel of the PHY layer */
    +
    +  /* Set the channel page of the PHY layer */
    +
    +  /* Set the macPANId */
    +
    +  /* Set either the macCoordExtendedAddress and macCoordShortAddress
    +   * depending on the CoordAddrMode in the primitive.
    +   */
    +
    +  if (req->coord_addr.mode == IEEE802154_ADDRMODE_EXTENDED)
    +    {
    +
    +    }
    +  else if (req->coord_addr.mode == IEEE802154_ADDRMODE_EXTENDED)
    +    {
    +
    +    }
    +  else
    +    {
    +      return -EINVAL;
    +    }
    +
    +  return -ENOTTY;
    +}
    +
    +/****************************************************************************
    + * Name: mac802154_req_disassociate
    + *
    + * Description:
    + *   The MLME-DISASSOCIATE.request primitive is used by an associated device to
    + *   notify the coordinator of its intent to leave the PAN. It is also used by
    + *   the coordinator to instruct an associated device to leave the PAN.
    + *   Confirmation is returned via the
    + *   struct ieee802154_maccb_s->conf_disassociate callback.
    + *
    + ****************************************************************************/
    +
    +int mac802154_req_disassociate(MACHANDLE mac,
    +                               FAR struct ieee802154_disassoc_req_s *req)
    +{
    +  FAR struct ieee802154_privmac_s *priv =
    +    (FAR struct ieee802154_privmac_s *)mac;
    +  return -ENOTTY;
    +}
    +
    +/****************************************************************************
    + * Name: mac802154_req_get
    + *
    + * Description:
    + *   The MLME-GET.request primitive requests information about a given PIB
    + *   attribute. Actual data is returned via the
    + *   struct ieee802154_maccb_s->conf_get callback.
    + *
    + ****************************************************************************/
    +
    +int mac802154_req_get(MACHANDLE mac, FAR struct ieee802154_get_req_s *req)
    +{
    +  FAR struct ieee802154_privmac_s *priv =
    +    (FAR struct ieee802154_privmac_s *)mac;
    +  return -ENOTTY;
    +}
    +
    +/****************************************************************************
    + * Name: mac802154_req_gts
    + *
    + * Description:
    + *   The MLME-GTS.request primitive allows a device to send a request to the PAN
    + *   coordinator to allocate a new GTS or to deallocate an existing GTS.
    + *   Confirmation is returned via the
    + *   struct ieee802154_maccb_s->conf_gts callback.
    + *
    + ****************************************************************************/
    +
    +int mac802154_req_gts(MACHANDLE mac, FAR struct ieee802154_gts_req_s *req)
    +{
    +  FAR struct ieee802154_privmac_s *priv =
    +    (FAR struct ieee802154_privmac_s *)mac;
    +  return -ENOTTY;
    +}
    +
    +/****************************************************************************
    + * Name: mac802154_req_reset
    + *
    + * Description:
    + *   The MLME-RESET.request primitive allows the next higher layer to request
    + *   that the MLME performs a reset operation. Confirmation is returned via
    + *   the struct ieee802154_maccb_s->conf_reset callback.
    + *
    + ****************************************************************************/
    +
    +int mac802154_req_reset(MACHANDLE mac, FAR struct ieee802154_reset_req_s *req)
    +{
    +  FAR struct ieee802154_privmac_s * priv =
    +    (FAR struct ieee802154_privmac_s *) mac;
    +  return -ENOTTY;
    +}
    +
    +/****************************************************************************
    + * Name: mac802154_req_rxenable
    + *
    + * Description:
    + *   The MLME-RX-ENABLE.request primitive allows the next higher layer to
    + *   request that the receiver is enable for a finite period of time.
    + *   Confirmation is returned via the
    + *   struct ieee802154_maccb_s->conf_rxenable callback.
    + *
    + ****************************************************************************/
    +
    +int mac802154_req_rxenable(MACHANDLE mac,
    +                           FAR struct ieee802154_rxenable_req_s *req)
    +{
    +  FAR struct ieee802154_privmac_s * priv =
    +    (FAR struct ieee802154_privmac_s *)mac;
    +  return -ENOTTY;
    +}
    +
    +/****************************************************************************
    + * Name: mac802154_req_scan
    + *
    + * Description:
    + *   The MLME-SCAN.request primitive is used to initiate a channel scan over a
    + *   given list of channels. A device can use a channel scan to measure the
    + *   energy on the channel, search for the coordinator with which it associated,
    + *   or search for all coordinators transmitting beacon frames within the POS of
    + *   the scanning device. Scan results are returned
    + *   via MULTIPLE calls to the struct ieee802154_maccb_s->conf_scan callback.
    + *   This is a difference with the official 802.15.4 specification, implemented
    + *   here to save memory.
    + *
    + ****************************************************************************/
    +
    +int mac802154_req_scan(MACHANDLE mac, FAR struct ieee802154_scan_req_s *req)
    +{
    +  FAR struct ieee802154_privmac_s *priv =
    +    (FAR struct ieee802154_privmac_s *)mac;
    +  return -ENOTTY;
    +}
    +
    +/****************************************************************************
    + * Name: mac802154_req_set
    + *
    + * Description:
    + *   The MLME-SET.request primitive attempts to write the given value to the
    + *   indicated MAC PIB attribute. Confirmation is returned via the
    + *   struct ieee802154_maccb_s->conf_set callback.
    + *
    + ****************************************************************************/
    +
    +int mac802154_req_set(MACHANDLE mac, FAR struct ieee802154_set_req_s *req)
    +{
    +  FAR struct ieee802154_privmac_s *priv =
    +    (FAR struct ieee802154_privmac_s *)mac;
    +  return -ENOTTY;
    +}
    +
    +/****************************************************************************
    + * Name: mac802154_req_start
    + *
    + * Description:
    + *   The MLME-START.request primitive makes a request for the device to start
    + *   using a new superframe configuration. Confirmation is returned
    + *   via the struct ieee802154_maccb_s->conf_start callback.
    + *
    + ****************************************************************************/
    +
    +int mac802154_req_start(MACHANDLE mac, FAR struct ieee802154_start_req_s *req)
    +{
    +  FAR struct ieee802154_privmac_s *priv =
    +    (FAR struct ieee802154_privmac_s *)mac;
    +  return -ENOTTY;
    +}
    +
    +/****************************************************************************
    + * Name: mac802154_req_sync
    + *
    + * Description:
    + *   The MLME-SYNC.request primitive requests to synchronize with the
    + *   coordinator by acquiring and, if specified, tracking its beacons.
    + *   Confirmation is returned via the
    + *   struct ieee802154_maccb_s->int_commstatus callback. TOCHECK.
    + *
    + ****************************************************************************/
    +
    +int mac802154_req_sync(MACHANDLE mac, FAR struct ieee802154_sync_req_s *req)
    +{
    +  FAR struct ieee802154_privmac_s *priv =
    +    (FAR struct ieee802154_privmac_s *)mac;
    +  return -ENOTTY;
    +}
    +
    +/****************************************************************************
    + * Name: mac802154_req_poll
    + *
    + * Description:
    + *   The MLME-POLL.request primitive prompts the device to request data from
    + *   the coordinator. Confirmation is returned via the
    + *   struct ieee802154_maccb_s->conf_poll callback, followed by a
    + *   struct ieee802154_maccb_s->ind_data callback.
    + *
    + ****************************************************************************/
    +
    +int mac802154_req_poll(MACHANDLE mac, FAR struct ieee802154_poll_req_s *req)
    +{
    +  FAR struct ieee802154_privmac_s *priv =
    +    (FAR struct ieee802154_privmac_s *)mac;
    +  return -ENOTTY;
    +}
    +
    +/****************************************************************************
    + * Name: mac802154_rsp_associate
    + *
    + * Description:
    + *   The MLME-ASSOCIATE.response primitive is used to initiate a response to
    + *   an MLME-ASSOCIATE.indication primitive.
    + *
    + ****************************************************************************/
    +
    +int mac802154_rsp_associate(MACHANDLE mac,
    +                            FAR struct ieee802154_assoc_resp_s *resp)
    +{
    +  FAR struct ieee802154_privmac_s *priv =
    +    (FAR struct ieee802154_privmac_s *)mac;
    +  return -ENOTTY;
    +}
    +
    +/****************************************************************************
    + * Name: mac802154_rsp_orphan
    + *
    + * Description:
    + *   The MLME-ORPHAN.response primitive allows the next higher layer of a
    + *   coordinator to respond to the MLME-ORPHAN.indication primitive.
    + *
    + ****************************************************************************/
    +
    +int mac802154_rsp_orphan(MACHANDLE mac,
    +                         FAR struct ieee802154_orphan_resp_s *resp)
    +{
    +  FAR struct ieee802154_privmac_s *priv =
    +    (FAR struct ieee802154_privmac_s *)mac;
    +  return -ENOTTY;
    +}
    diff --git a/wireless/ieee802154/mac802154.h b/wireless/ieee802154/mac802154.h
    index 3b2cd1de5a..00235d025b 100644
    --- a/wireless/ieee802154/mac802154.h
    +++ b/wireless/ieee802154/mac802154.h
    @@ -120,7 +120,7 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req);
      *
      ****************************************************************************/
     
    -int mac802154_req_purge(MACHANDLE mac, uint8_t handle);
    +int mac802154_req_purge(MACHANDLE mac, FAR struct ieee802154_purge_req_s *req);
     
     /****************************************************************************
      * Name: mac802154_req_associate
    @@ -162,7 +162,7 @@ int mac802154_req_disassociate(MACHANDLE mac,
      *
      ****************************************************************************/
     
    -int mac802154_req_get(MACHANDLE mac, enum ieee802154_pib_attr_e attr);
    +int mac802154_req_get(MACHANDLE mac, FAR struct ieee802154_get_req_s *req);
     
     /****************************************************************************
      * Name: mac802154_req_gts
    @@ -175,7 +175,7 @@ int mac802154_req_get(MACHANDLE mac, enum ieee802154_pib_attr_e attr);
      *
      ****************************************************************************/
     
    -int mac802154_req_gts(MACHANDLE mac, FAR uint8_t *characteristics);
    +int mac802154_req_gts(MACHANDLE mac, FAR struct ieee802154_gts_req_s *req);
     
     /****************************************************************************
      * Name: mac802154_req_reset
    @@ -187,7 +187,7 @@ int mac802154_req_gts(MACHANDLE mac, FAR uint8_t *characteristics);
      *
      ****************************************************************************/
     
    -int mac802154_req_reset(MACHANDLE mac, bool setdefaults);
    +int mac802154_req_reset(MACHANDLE mac, FAR struct ieee802154_reset_req_s *req);
     
     /****************************************************************************
      * Name: mac802154_req_rxenable
    @@ -200,8 +200,8 @@ int mac802154_req_reset(MACHANDLE mac, bool setdefaults);
      *
      ****************************************************************************/
     
    -int mac802154_req_rxenable(MACHANDLE mac, bool deferrable, int ontime,
    -                           int duration);
    +int mac802154_req_rxenable(MACHANDLE mac,
    +                           FAR struct ieee802154_rxenable_req_s *req);
     
     /****************************************************************************
      * Name: mac802154_req_scan
    @@ -218,8 +218,7 @@ int mac802154_req_rxenable(MACHANDLE mac, bool deferrable, int ontime,
      *
      ****************************************************************************/
     
    -int mac802154_req_scan(MACHANDLE mac, uint8_t type, uint32_t channels,
    -                       int duration);
    +int mac802154_req_scan(MACHANDLE mac, FAR struct ieee802154_scan_req_s *req);
     
     /****************************************************************************
      * Name: mac802154_req_set
    @@ -231,8 +230,7 @@ int mac802154_req_scan(MACHANDLE mac, uint8_t type, uint32_t channels,
      *
      ****************************************************************************/
     
    -int mac802154_req_set(MACHANDLE mac, int attribute, FAR uint8_t *value,
    -                      int valuelen);
    +int mac802154_req_set(MACHANDLE mac, FAR struct ieee802154_set_req_s *req);
     
     /****************************************************************************
      * Name: mac802154_req_start
    @@ -244,9 +242,7 @@ int mac802154_req_set(MACHANDLE mac, int attribute, FAR uint8_t *value,
      *
      ****************************************************************************/
     
    -int mac802154_req_start(MACHANDLE mac, uint16_t panid, int channel,
    -                        uint8_t bo, uint8_t fo, bool coord, bool batext,
    -                        bool realign);
    +int mac802154_req_start(MACHANDLE mac, FAR struct ieee802154_start_req_s *req);
     
     /****************************************************************************
      * Name: mac802154_req_sync
    @@ -259,7 +255,7 @@ int mac802154_req_start(MACHANDLE mac, uint16_t panid, int channel,
      *
      ****************************************************************************/
     
    -int mac802154_req_sync(MACHANDLE mac, int channel, bool track);
    +int mac802154_req_sync(MACHANDLE mac, FAR struct ieee802154_sync_req_s *req);
     
     /****************************************************************************
      * Name: mac802154_req_poll
    @@ -272,7 +268,7 @@ int mac802154_req_sync(MACHANDLE mac, int channel, bool track);
      *
      ****************************************************************************/
     
    -int mac802154_req_poll(MACHANDLE mac, FAR uint8_t *coordaddr);
    +int mac802154_req_poll(MACHANDLE mac, FAR struct ieee802154_poll_req_s *req);
     
     /****************************************************************************
      * Name: mac802154_rsp_associate
    @@ -283,8 +279,8 @@ int mac802154_req_poll(MACHANDLE mac, FAR uint8_t *coordaddr);
      *
      ****************************************************************************/
     
    -int mac802154_rsp_associate(MACHANDLE mac, uint8_t eadr, uint16_t saddr,
    -                            int status);
    +int mac802154_rsp_associate(MACHANDLE mac,
    +                            FAR struct ieee802154_assoc_resp_s *resp);
     
     /****************************************************************************
      * Name: mac802154_rsp_orphan
    @@ -295,8 +291,8 @@ int mac802154_rsp_associate(MACHANDLE mac, uint8_t eadr, uint16_t saddr,
      *
      ****************************************************************************/
     
    -int mac802154_rsp_orphan(MACHANDLE mac, FAR uint8_t *orphanaddr,
    -                         uint16_t saddr, bool associated);
    +int mac802154_rsp_orphan(MACHANDLE mac,
    +                         FAR struct ieee802154_orphan_resp_s *resp);
     
     #undef EXTERN
     #ifdef __cplusplus
    diff --git a/wireless/ieee802154/mac802154_device.c b/wireless/ieee802154/mac802154_device.c
    index 6370ff4762..19d3a5bc41 100644
    --- a/wireless/ieee802154/mac802154_device.c
    +++ b/wireless/ieee802154/mac802154_device.c
    @@ -139,6 +139,14 @@ struct mac802154_chardevice_s
     static inline int mac802154dev_takesem(sem_t *sem);
     #define mac802154dev_givesem(s) sem_post(s);
     
    +static void mac802154dev_mlme_notify(FAR const struct ieee802154_maccb_s *maccb,
    +                                     enum ieee802154_macnotify_e notif,
    +                                     FAR const union ieee802154_mlme_notify_u *arg);
    +
    +static void mac802154dev_mcps_notify(FAR const struct ieee802154_maccb_s *maccb,
    +                                     enum ieee802154_macnotify_e notif,
    +                                     FAR const union ieee802154_mcps_notify_u *arg);
    +
     static int  mac802154dev_open(FAR struct file *filep);
     static int  mac802154dev_close(FAR struct file *filep);
     static ssize_t mac802154dev_read(FAR struct file *filep, FAR char *buffer,
    @@ -151,7 +159,7 @@ static int  mac802154dev_ioctl(FAR struct file *filep, int cmd,
     /* MAC callback helpers */
     
     static void mac802154dev_conf_data(FAR struct mac802154_chardevice_s *dev,
    -                                   FAR struct ieee802154_data_conf_s *conf);
    +                                   FAR const struct ieee802154_data_conf_s *conf);
     
     /****************************************************************************
      * Private Data
    @@ -591,9 +599,9 @@ static int mac802154dev_ioctl(FAR struct file *filep, int cmd,
       return ret;
     }
     
    -static void mac802154dev_mlme_notify(FAR struct ieee802154_maccb_s *maccb,
    +static void mac802154dev_mlme_notify(FAR const struct ieee802154_maccb_s *maccb,
                                          enum ieee802154_macnotify_e notif,
    -                                     FAR union ieee802154_mlme_notify_u *arg)
    +                                     FAR const union ieee802154_mlme_notify_u *arg)
     {
       FAR struct mac802154dev_callback_s *cb =
         (FAR struct mac802154dev_callback_s *)maccb;
    @@ -610,9 +618,9 @@ static void mac802154dev_mlme_notify(FAR struct ieee802154_maccb_s *maccb,
         }
     }
     
    -static void mac802154dev_mcps_notify(FAR struct ieee802154_maccb_s *maccb,
    +static void mac802154dev_mcps_notify(FAR const struct ieee802154_maccb_s *maccb,
                                          enum ieee802154_macnotify_e notif,
    -                                     FAR union ieee802154_mcps_notify_u *arg)
    +                                     FAR const union ieee802154_mcps_notify_u *arg)
     {
       FAR struct mac802154dev_callback_s *cb =
         (FAR struct mac802154dev_callback_s *)maccb;
    @@ -634,7 +642,7 @@ static void mac802154dev_mcps_notify(FAR struct ieee802154_maccb_s *maccb,
     }
     
     static void mac802154dev_conf_data(FAR struct mac802154_chardevice_s *dev,
    -                                   FAR struct ieee802154_data_conf_s *conf)
    +                                   FAR const struct ieee802154_data_conf_s *conf)
     {
       FAR struct mac802154dev_dwait_s *curr;
       FAR struct mac802154dev_dwait_s *prev;
    @@ -647,7 +655,7 @@ static void mac802154dev_conf_data(FAR struct mac802154_chardevice_s *dev,
       /* Search to see if there is a dwait pending for this transaction */
     
       for (prev = NULL, curr = dev->md_dwait;
    -       curr && curr->mw_handle != conf->msdu_handle;
    +       curr && curr->mw_handle != conf->handle;
            prev = curr, curr = curr->mw_flink);
     
       /* If a dwait is found */
    @@ -669,7 +677,7 @@ static void mac802154dev_conf_data(FAR struct mac802154_chardevice_s *dev,
     
           /* Copy the transmission status into the dwait struct */
     
    -      curr->mw_status = conf->msdu_handle;
    +      curr->mw_status = conf->status;
     
           /* Wake the thread waiting for the data transmission */
     
    diff --git a/wireless/ieee802154/radio802154_device.c b/wireless/ieee802154/radio802154_device.c
    index a1fe8dc515..2c48e107d0 100644
    --- a/wireless/ieee802154/radio802154_device.c
    +++ b/wireless/ieee802154/radio802154_device.c
    @@ -254,13 +254,13 @@ static ssize_t radio802154dev_read(FAR struct file *filep, FAR char *buffer, siz
           goto done;
         }
     
    -  ret = dev->child->ops->rxenable(dev->child, 1, buf);
    +#warning Receive needs to be redone!
     #if 0
    +  ret = dev->child->ops->rxenable(dev->child, 1, buf);
       if (ret < 0)
         {
           goto done;
         }
    -#endif
     
       /* if no packet is received, this will produce -EAGAIN
        * The user is responsible for sleeping until sth arrives
    @@ -282,6 +282,8 @@ static ssize_t radio802154dev_read(FAR struct file *filep, FAR char *buffer, siz
       dev->child->ops->rxenable(dev->child, 0, NULL);
       ret = buf->len;
     
    +#endif
    +
     done:
       return ret;
     }
    -- 
    GitLab
    
    
    From 9aac1dd44d297a9be9af57a9cfd15ffa8a62a5e1 Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Wed, 26 Apr 2017 10:12:13 -0600
    Subject: [PATCH 590/990] configs: Remove all setenv.bat files.  Remove all
     references to setenv.sh and setenv.bat from all config README files.
    
    ---
     configs/README.txt                           |  21 +---
     configs/amber/README.txt                     |  14 +--
     configs/arduino-due/README.txt               |  25 ++--
     configs/arduino-mega2560/README.txt          |   1 -
     configs/avr32dev1/README.txt                 |   7 +-
     configs/bambino-200e/README.txt              |   1 -
     configs/c5471evm/README.txt                  |   7 +-
     configs/clicker2-stm32/README.txt            |   6 +-
     configs/cloudctrl/README.txt                 |  22 ++--
     configs/demo9s12ne64/README.txt              |   7 +-
     configs/dk-tm4c129x/README.txt               |   6 +-
     configs/ea3131/README.txt                    |  18 ++-
     configs/ea3152/README.txt                    |  18 ++-
     configs/eagle100/README.txt                  |  15 ++-
     configs/efm32-g8xx-stk/README.txt            |   1 -
     configs/efm32gg-stk3700/README.txt           |   2 +-
     configs/ekk-lm3s9b96/README.txt              |  15 ++-
     configs/esp32-core/README.txt                |   6 +-
     configs/ez80f910200kitg/README.txt           |  15 ++-
     configs/ez80f910200kitg/scripts/setenv.bat   |  50 --------
     configs/ez80f910200zco/README.txt            |  11 +-
     configs/ez80f910200zco/scripts/setenv.bat    |  50 --------
     configs/fire-stm32v2/README.txt              |  15 ++-
     configs/freedom-k64f/README.txt              |   6 +-
     configs/freedom-k66f/README.txt              |   6 +-
     configs/freedom-kl25z/README.txt             |   7 +-
     configs/freedom-kl26z/README.txt             |   7 +-
     configs/hymini-stm32v/README.txt             |  20 ++--
     configs/kwikstik-k40/README.txt              |  15 ++-
     configs/launchxl-tms57004/README.txt         |   6 +-
     configs/lincoln60/README.txt                 |  15 ++-
     configs/lm3s6432-s2e/README.txt              |  15 ++-
     configs/lm3s6965-ek/README.txt               |  15 ++-
     configs/lm3s8962-ek/README.txt               |  15 ++-
     configs/lm4f120-launchpad/README.txt         |  20 ++--
     configs/lpc4330-xplorer/README.txt           |  23 ++--
     configs/lpc4337-ws/README.txt                |  23 ++--
     configs/lpc4357-evb/README.txt               |  23 ++--
     configs/lpc4370-link2/README.txt             |  23 ++--
     configs/lpcxpresso-lpc1115/README.txt        |  13 +-
     configs/lpcxpresso-lpc1768/README.txt        |  13 +-
     configs/maple/README.txt                     |   6 +-
     configs/mbed/README.txt                      |  14 +--
     configs/mcu123-lpc214x/README.txt            |   7 +-
     configs/micropendous3/README.txt             |  14 +--
     configs/mikroe-stm32f4/README.txt            |  14 +--
     configs/mirtoo/README.txt                    |  15 ++-
     configs/misoc/README.txt                     |   8 +-
     configs/moteino-mega/README.txt              |   1 -
     configs/mx1ads/README.txt                    |   7 +-
     configs/ne64badge/README.txt                 |   7 +-
     configs/nr5m100-nexys4/README.txt            |   6 -
     configs/ntosd-dm320/README.txt               | 118 +++++++++----------
     configs/ntosd-dm320/doc/README.txt           |   4 +-
     configs/nucleo-144/README.txt                |   2 +-
     configs/nucleo-f072rb/README.txt             |   6 +-
     configs/nucleo-f4x1re/README.txt             |   2 +-
     configs/nucleo-l476rg/README.txt             |   2 +-
     configs/nutiny-nuc120/README.txt             |  12 +-
     configs/olimex-efm32g880f128-stk/README.txt  |   6 -
     configs/olimex-lpc-h3131/README.txt          |  27 ++---
     configs/olimex-lpc1766stk/README.txt         |  19 ++-
     configs/olimex-stm32-p407/README.txt         |   6 +-
     configs/olimex-strp711/README.txt            |  12 +-
     configs/olimex-strp711/scripts/oocd.sh       |   1 -
     configs/open1788/README.txt                  |   9 +-
     configs/p112/ostest/setenv.bat               |  51 --------
     configs/p112/scripts/setenv.bat              |  50 --------
     configs/pcblogic-pic32mx/README.txt          |   4 +-
     configs/pcduino-a10/README.txt               |  11 +-
     configs/pic32mx-starterkit/README.txt        |   4 +-
     configs/pic32mx7mmb/README.txt               |   4 +-
     configs/pic32mz-starterkit/README.txt        |   4 +-
     configs/qemu-i486/README.txt                 |  10 +-
     configs/sabre-6quad/README.txt               |   6 +-
     configs/sam3u-ek/README.txt                  |  30 ++---
     configs/sam4e-ek/README.txt                  |  30 ++---
     configs/sam4l-xplained/README.txt            |  23 ++--
     configs/sam4s-xplained-pro/README.txt        |  24 ++--
     configs/sam4s-xplained/README.txt            |  24 ++--
     configs/sama5d2-xult/README.txt              |  22 +---
     configs/sama5d3-xplained/README.txt          |  20 ++--
     configs/sama5d3x-ek/README.txt               |  33 ++----
     configs/sama5d4-ek/README.txt                |  47 +++-----
     configs/samd20-xplained/README.txt           |  19 +--
     configs/samd21-xplained/README.txt           |  10 +-
     configs/same70-xplained/README.txt           |  11 +-
     configs/saml21-xplained/README.txt           |  19 +--
     configs/samv71-xult/README.txt               |  25 +---
     configs/shenzhou/README.txt                  |  20 +---
     configs/sim/README.txt                       |   6 -
     configs/spark/README.txt                     |  13 +-
     configs/stm3210e-eval/README.txt             |  20 ++--
     configs/stm3220g-eval/README.txt             |  15 +--
     configs/stm3240g-eval/README.txt             |  15 +--
     configs/stm32_tiny/README.txt                |  19 +--
     configs/stm32f103-minimum/README.txt         |   6 -
     configs/stm32f3discovery/README.txt          |  19 +--
     configs/stm32f429i-disco/README.txt          |   7 --
     configs/stm32f4discovery/README.txt          |  19 +--
     configs/stm32f4discovery/winbuild/setenv.bat |  50 --------
     configs/stm32f746g-disco/README.txt          |  15 +--
     configs/stm32ldiscovery/README.txt           |  19 +--
     configs/stm32vldiscovery/README.txt          |  14 +--
     configs/sure-pic32mx/README.txt              |   4 +-
     configs/teensy-2.0/README.txt                |  14 +--
     configs/teensy-3.x/README.txt                |   6 +-
     configs/tm4c123g-launchpad/README.txt        |  19 ++-
     configs/tm4c1294-launchpad/README.txt        |   1 -
     configs/twr-k60n512/README.txt               |  14 +--
     configs/twr-k64f120m/README.txt              |  17 +--
     configs/ubw32/README.txt                     |   4 +-
     configs/us7032evb1/README.txt                |   7 +-
     configs/viewtool-stm32f107/README.txt        |  10 +-
     configs/xmc4500-relax/README.txt             |   6 +-
     configs/xtrs/README.txt                      |  29 ++---
     configs/xtrs/nsh/setenv.bat                  |  54 ---------
     configs/xtrs/ostest/setenv.bat               |  54 ---------
     configs/xtrs/pashello/setenv.bat             |  54 ---------
     configs/z16f2800100zcog/README.txt           |  15 +--
     configs/z16f2800100zcog/scripts/setenv.bat   |  50 --------
     configs/z80sim/README.txt                    |  19 ++-
     configs/z80sim/nsh/setenv.bat                |  50 --------
     configs/z80sim/ostest/setenv.bat             |  50 --------
     configs/z80sim/pashello/setenv.bat           |  50 --------
     configs/z80sim/scripts/setenv.bat            |  50 --------
     configs/z8encore000zco/README.txt            |  12 +-
     configs/z8encore000zco/scripts/setenv.bat    |  50 --------
     configs/z8f64200100kit/README.txt            |  12 +-
     configs/z8f64200100kit/scripts/setenv.bat    |  50 --------
     configs/zkit-arm-1769/README.txt             |  18 ++-
     configs/zp214xpa/README.txt                  |   6 +-
     132 files changed, 581 insertions(+), 1805 deletions(-)
     delete mode 100644 configs/ez80f910200kitg/scripts/setenv.bat
     delete mode 100644 configs/ez80f910200zco/scripts/setenv.bat
     delete mode 100644 configs/p112/ostest/setenv.bat
     delete mode 100644 configs/p112/scripts/setenv.bat
     delete mode 100644 configs/stm32f4discovery/winbuild/setenv.bat
     delete mode 100644 configs/xtrs/nsh/setenv.bat
     delete mode 100644 configs/xtrs/ostest/setenv.bat
     delete mode 100644 configs/xtrs/pashello/setenv.bat
     delete mode 100644 configs/z16f2800100zcog/scripts/setenv.bat
     delete mode 100644 configs/z80sim/nsh/setenv.bat
     delete mode 100644 configs/z80sim/ostest/setenv.bat
     delete mode 100644 configs/z80sim/pashello/setenv.bat
     delete mode 100644 configs/z80sim/scripts/setenv.bat
     delete mode 100644 configs/z8encore000zco/scripts/setenv.bat
     delete mode 100644 configs/z8f64200100kit/scripts/setenv.bat
    
    diff --git a/configs/README.txt b/configs/README.txt
    index cbdb3d0072..cfc90fa0f7 100644
    --- a/configs/README.txt
    +++ b/configs/README.txt
    @@ -72,12 +72,10 @@ following characteristics:
       |   `-- (board-specific source files)
       |-- 
       |   |-- Make.defs
    -  |   |-- defconfig
    -  |   `-- setenv.sh
    +  |   `-- defconfig
       |-- 
       |   |-- Make.defs
    -  |   |-- defconfig
    -  |   `-- setenv.sh
    +  |   `-- defconfig
       ...
     
     Summary of Files
    @@ -101,10 +99,10 @@ src/Makefile -- This makefile will be invoked to build the board specific
       and distclean.
     
     A board may have various different configurations using these common source
    -files.  Each board configuration is described by three files:  Make.defs,
    -defconfig, and setenv.sh.  Typically, each set of configuration files is
    -retained in a separate configuration sub-directory (,
    -, .. in the above diagram).
    +files.  Each board configuration is described by two files:  Make.defs and
    +defconfig.  Typically, each set of configuration files is retained in a
    +separate configuration sub-directory (, , .. in
    +the above diagram).
     
     Make.defs -- This makefile fragment provides architecture and
       tool-specific build options.  It will be included by all other
    @@ -141,12 +139,6 @@ defconfig -- This is a configuration file similar to the Linux
         (2) to generate include/nuttx/config.h which is included by
             most C files in the system.
     
    -setenv.sh -- This is a script that you can include that will be installed at
    -  the toplevel of the directory structure and can be sourced to set any
    -  necessary environment variables.  You will most likely have to customize the
    -  default setenv.sh script in order for it to work correctly in your
    -  environment.
    -
     Configuration Variables
     ^^^^^^^^^^^^^^^^^^^^^^^
     
    @@ -816,7 +808,6 @@ Configuring NuttX
     Configuring NuttX requires only copying
     
       configs///Make.def to ${TOPDIR}/Make.defs
    -  configs///setenv.sh to ${TOPDIR}/setenv.sh
       configs///defconfig to ${TOPDIR}/.config
     
     tools/configure.sh
    diff --git a/configs/amber/README.txt b/configs/amber/README.txt
    index 752d4a840a..d48090f237 100644
    --- a/configs/amber/README.txt
    +++ b/configs/amber/README.txt
    @@ -199,9 +199,8 @@ Buildroot:
       http://bitbucket.org/nuttx/buildroot/downloads/.  See the
       following section for details on building this toolchain.
     
    -  It is assumed in some places that buildroot toolchain is available
    -  at ../buildroot/build_avr.  Edit the setenv.sh file if
    -  this is not the case.
    +  You may also have to modify the PATH environment variable if your make cannot
    +  find the tools.
     
       After configuring NuttX, make sure that CONFIG_AVR_BUILDROOT_TOOLCHAIN=y is set in your
       .config file.
    @@ -211,8 +210,8 @@ WinAVR:
       For Cygwin development environment on Windows machines, you can use
       WinAVR: http://sourceforge.net/projects/winavr/files/
     
    -  It is assumed in some places that WinAVR is installed at C:/WinAVR.  Edit the
    -  setenv.sh file if this is not the case.
    +  You may also have to modify the PATH environment variable if your make cannot
    +  find the tools.
     
       After configuring NuttX, make sure that CONFIG_AVR_WINAVR_TOOLCHAIN=y is set in your
       .config file.
    @@ -297,8 +296,8 @@ NuttX buildroot Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       detailed PLUS some special instructions that you will need to follow if you
    @@ -493,7 +492,6 @@ Common Configuration Notes
            cd tools
            ./configure.sh amber/
            cd -
    -       . ./setenv.sh
     
          Where  is one of the configuration sub-directories described in
          the following paragraph.
    diff --git a/configs/arduino-due/README.txt b/configs/arduino-due/README.txt
    index e886b55889..a5065b6805 100644
    --- a/configs/arduino-due/README.txt
    +++ b/configs/arduino-due/README.txt
    @@ -275,9 +275,8 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL=y      : Generic GCC ARM EABI toolchain for Linux
         CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIW=y      : Generic GCC ARM EABI toolchain for Windows
     
    -  If you are not using CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT, then you may also
    -  have to modify the PATH in the setenv.h file if your make cannot find the
    -  tools.
    +  You may also have to modify the PATH environment variable if your make cannot
    +  find the tools.
     
       NOTE about Windows native toolchains
       ------------------------------------
    @@ -348,7 +347,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -375,8 +374,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you are
    @@ -437,8 +436,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     Buttons and LEDs
     ^^^^^^^^^^^^^^^^
    @@ -849,11 +848,9 @@ Configurations
         cd tools
         ./configure.sh arduino-due/
         cd -
    -    . ./setenv.sh
     
    -  Before sourcing the setenv.sh file above, you should examine it and perform
    -  edits as necessary so that BUILDROOT_BIN is the correct path to the directory
    -  than holds your toolchain binaries.
    +  Before building, make sure the PATH environment variable includes the
    +  correct path to the directory than holds your toolchain binaries.
     
       And then build NuttX by simply typing the following.  At the conclusion of
       the make, the nuttx binary will reside in an ELF file called, simply, nuttx.
    @@ -930,9 +927,7 @@ Configurations
     
          Also, make sure that your PATH variable has the new path to your
          Atmel tools.  Try 'which arm-none-eabi-gcc' to make sure that you
    -     are selecting the right tool.  setenv.sh is available for you to
    -     use to set or PATH variable.  The path in the that file may not,
    -     however, be correct for your installation.
    +     are selecting the right tool.
     
          See also the "NOTE about Windows native toolchains" in the section call
          "GNU Toolchain Options" above.
    diff --git a/configs/arduino-mega2560/README.txt b/configs/arduino-mega2560/README.txt
    index 7194f4e5a1..7663fdadbd 100644
    --- a/configs/arduino-mega2560/README.txt
    +++ b/configs/arduino-mega2560/README.txt
    @@ -51,7 +51,6 @@ Configurations
            cd tools
            ./configure.sh arduino-mega2560/
            cd -
    -       . ./setenv.sh
     
          Where  is one of the configuration sub-directories described in
          the following paragraph.
    diff --git a/configs/avr32dev1/README.txt b/configs/avr32dev1/README.txt
    index 54ac900270..8e6b639dec 100644
    --- a/configs/avr32dev1/README.txt
    +++ b/configs/avr32dev1/README.txt
    @@ -228,10 +228,8 @@ AVR32 Bootloader
       driver in the FLIP usb directory.  Then in the bin directory where
       you installed FLIP, you will also find batchisp.exe.
     
    -  NOTE: The AVR32DEV1 setenv.sh files will add the path to the BatchISP
    -  bin directory to the Cygwin PATH variable.  If you use a different
    -  version of FLIP or if you install FLIP in a different location, you
    -  will need to modify the setenv.sh files.
    +  NOTE: You will need to set the PATH environment variable to include the
    +  path to the BatchISP bin directory.
     
       Notes from "AVR32 UC3 USB DFU Bootloader" (doc7745.pdf)
     
    @@ -436,7 +434,6 @@ Common Configuration Notes
            cd tools
            ./configure.sh avr32dev1/
            cd -
    -       . ./setenv.sh
     
          Where  is one of the configuration sub-directories described in
          the following paragraph.
    diff --git a/configs/bambino-200e/README.txt b/configs/bambino-200e/README.txt
    index b6adcf8096..d4105f0895 100644
    --- a/configs/bambino-200e/README.txt
    +++ b/configs/bambino-200e/README.txt
    @@ -380,7 +380,6 @@ as follow:
         cd tools
         ./configure.sh bambino-200e/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    diff --git a/configs/c5471evm/README.txt b/configs/c5471evm/README.txt
    index 618b2ae1ce..36e6d7ce43 100644
    --- a/configs/c5471evm/README.txt
    +++ b/configs/c5471evm/README.txt
    @@ -4,7 +4,7 @@ README
     Toolchain
     ^^^^^^^^^
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the SH toolchain (if
       different from the default).
     
    @@ -28,8 +28,8 @@ Toolchain
     
       7. make
     
    -  8. Edit setenv.h so that the PATH variable includes the path to the
    -     newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
     Issues
     ^^^^^^
    @@ -133,7 +133,6 @@ Common Configuration Notes
            cd tools
            ./configure.sh c5471evm/
            cd -
    -       . ./setenv.sh
     
          Where  is one of the configuration sub-directories described in
          the following paragraph.
    diff --git a/configs/clicker2-stm32/README.txt b/configs/clicker2-stm32/README.txt
    index e265d475c0..810072c99c 100644
    --- a/configs/clicker2-stm32/README.txt
    +++ b/configs/clicker2-stm32/README.txt
    @@ -163,11 +163,9 @@ Configurations
         cd tools
         ./configure.sh clicker2-stm32/
         cd -
    -    . ./setenv.sh
     
    -  Before sourcing the setenv.sh file above, you should examine it and
    -  perform edits as necessary so that TOOLCHAIN_BIN is the correct path
    -  to the directory than holds your toolchain binaries.
    +  Before building, make sure the PATH environment variable includes the
    +  correct path to the directory than holds your toolchain binaries.
     
       And then build NuttX by simply typing the following.  At the conclusion of
       the make, the nuttx binary will reside in an ELF file called, simply, nuttx.
    diff --git a/configs/cloudctrl/README.txt b/configs/cloudctrl/README.txt
    index adce2658ba..ba2d8972ee 100644
    --- a/configs/cloudctrl/README.txt
    +++ b/configs/cloudctrl/README.txt
    @@ -202,8 +202,8 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_RAISONANCE=y     : Raisonance RIDE7 under Windows
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y      : NuttX buildroot under Linux or Cygwin (default)
     
    -  If you change the default toolchain, then you may also have to modify the PATH in
    -  the setenv.h file if your make cannot find the tools.
    +  You may also have to modify the PATH environment variable if your make cannot
    +  find the tools.
     
       NOTE: the CodeSourcery (for Windows), Atollic, devkitARM, and Raisonance toolchains are
       Windows native toolchains.  The CodeSourcery (for Linux) and NuttX buildroot
    @@ -304,7 +304,7 @@ IDEs
     NuttX EABI buildroot Toolchain
     ==============================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -340,14 +340,8 @@ NuttX EABI buildroot Toolchain
          -CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYW=y
          +CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y
     
    -  9. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    -
    -     -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -     +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -     -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -     +export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    +  9. Set the the PATH variable so tht it includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       detailed PLUS some special instructions that you will need to follow if you are
    @@ -408,8 +402,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     LEDs
     ====
    @@ -721,7 +715,6 @@ can be selected as follow:
         cd tools
         ./configure.sh shenzhou/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    @@ -802,7 +795,6 @@ Where  is one of the following:
         2. Make the build context (only)
     
            $ cd ..
    -       $ . ./setenv.sh
            $ make context
            ...
     
    diff --git a/configs/demo9s12ne64/README.txt b/configs/demo9s12ne64/README.txt
    index 48080bed70..b1b97145ef 100644
    --- a/configs/demo9s12ne64/README.txt
    +++ b/configs/demo9s12ne64/README.txt
    @@ -110,7 +110,7 @@ Development Environment
     NuttX Buildroot Toolchain
     ^^^^^^^^^^^^^^^^^^^^^^^^^
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the HC12 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -143,8 +143,8 @@ NuttX Buildroot Toolchain
          directory manually.  For example, binutils-2.18 can be found here:
          http://ftp.gnu.org/gnu/binutils/
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       detailed PLUS some special instructions that you will need to follow if you are
    @@ -367,7 +367,6 @@ Common Configuration Notes
            cd tools
            ./configure.sh demo9s12nec64/
            cd -
    -       . ./setenv.sh
     
          Where  is one of the configuration sub-directories described in
          the following paragraph.
    diff --git a/configs/dk-tm4c129x/README.txt b/configs/dk-tm4c129x/README.txt
    index bf81eb4f73..291323da4a 100644
    --- a/configs/dk-tm4c129x/README.txt
    +++ b/configs/dk-tm4c129x/README.txt
    @@ -83,9 +83,8 @@ Using OpenOCD and GDB with ICDI
     
           oocd.sh $PWD
     
    -    The relative path to the oocd.sh script is configs/dk-tm4c129x/tools,
    -    but that should have been added to your PATH variable when you sourced
    -    the setenv.sh script.
    +    Assuming that you have included the path to the oocd.sh script,
    +    configs/dk-tm4c129x/tools, in PATH variable.
     
         Note that OpenOCD needs to be run with administrator privileges in
         some environments (sudo).
    @@ -660,7 +659,6 @@ sub-directory and can be selected as follow:
         cd tools
         ./configure.sh dk-tm4c129x/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    diff --git a/configs/ea3131/README.txt b/configs/ea3131/README.txt
    index f69cb1fc51..0d966dafbc 100644
    --- a/configs/ea3131/README.txt
    +++ b/configs/ea3131/README.txt
    @@ -50,8 +50,8 @@ GNU Toolchain Options
         CONFIG_ARM_TOOLCHAIN_BUILDROOT=y      : NuttX buildroot under Linux or Cygwin (default)
         CONFIG_ARM_TOOLCHAIN_GNU_EABIL : Generic arm-none-eabi toolchain
     
    -  If you are not using CONFIG_ARM_TOOLCHAIN_BUILDROOT, then you may also have to modify
    -  the PATH in the setenv.h file if your make cannot find the tools.
    +  You may also have to modify the PATH environment variable if your make cannot
    +  find the tools.
     
       The toolchain may also be set using the kconfig-mconf utility (make menuconfig) or by
       passing CONFIG_ARM_TOOLCHAIN= to make, where  is one
    @@ -140,7 +140,7 @@ IDEs
     NuttX buildroot Toolchain
     ^^^^^^^^^^^^^^^^^^^^^^^^^
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -167,8 +167,8 @@ NuttX buildroot Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       detailed PLUS some special instructions that you will need to follow if you are
    @@ -209,16 +209,13 @@ Image Format
       - cd tools/                     # Configure Nuttx
       - ./configure.sh ea3131/nsh     # (using the nsh configuration for this example)
       - cd ..                         # Set up environment
    -  - . ./setenv.sh                 # (see notes below)
       - make                          # Make NuttX.  This will produce nuttx.bin
       - mklpc.sh                      # Make the bootloader binary (nuttx.lpc)
     
       NOTES:
     
    -    1. setenv.sh just sets up pathes to the toolchain and also to
    -       configs/ea3131/tools where mklpc.sh resides. Use of setenv.sh is optional.
    -       If you don't use setenv.sh, then just set your PATH variable appropriately or
    -       use the full path to mklpc.sh in the final step.
    +    1. You will need to set your PATH variable appropriately or use the full path
    +       to mklpc.sh in the final step.
         2. You can instruct Symantec to ignore the errors and it will stop quarantining
            the NXP program.
         3. The CRC32 logic in configs/ea3131/tools doesn't seem to work.  As a result,
    @@ -603,7 +600,6 @@ Common Configuration Notes
            cd tools
            ./configure.sh ea3131/
            cd -
    -       . ./setenv.sh
     
          Where  is one of the configuration sub-directories described in
          the following paragraph.
    diff --git a/configs/ea3152/README.txt b/configs/ea3152/README.txt
    index b9ada143ad..1063a4292a 100644
    --- a/configs/ea3152/README.txt
    +++ b/configs/ea3152/README.txt
    @@ -49,8 +49,8 @@ GNU Toolchain Options
         CONFIG_ARM_TOOLCHAIN_BUILDROOT=y      : NuttX buildroot under Linux or Cygwin (default)
         CONFIG_ARM_TOOLCHAIN_GNU_EABIL : Generic arm-none-eabi toolchain
     
    -  If you are not using CONFIG_ARM_TOOLCHAIN_BUILDROOT, then you may also have to modify
    -  the PATH in the setenv.h file if your make cannot find the tools.
    +  You may also have to modify the PATH environment variable if your make cannot
    +  find the tools.
     
       The toolchain may also be set using the kconfig-mconf utility (make menuconfig)
       or by passing CONFIG_ARM_TOOLCHAIN= to make, where  is one
    @@ -139,7 +139,7 @@ IDEs
     NuttX buildroot Toolchain
     ^^^^^^^^^^^^^^^^^^^^^^^^^
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -166,8 +166,8 @@ NuttX buildroot Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       detailed PLUS some special instructions that you will need to follow if you are
    @@ -208,16 +208,13 @@ Image Format
       - cd tools/                     # Configure Nuttx
       - ./configure.sh ea3152/ostest  # (using the ostest configuration for this example)
       - cd ..                         # Set up environment
    -  - . ./setenv.sh                 # (see notes below)
       - make                          # Make NuttX.  This will produce nuttx.bin
       - mklpc.sh                      # Make the bootloader binary (nuttx.lpc)
     
       NOTES:
     
    -    1. setenv.sh just sets up pathes to the toolchain and also to
    -       configs/ea3152/tools where mklpc.sh resides. Use of setenv.sh is optional.
    -       If you don't use setenv.sh, then just set your PATH variable appropriately or
    -       use the full path to mklpc.sh in the final step.
    +    1. You will need to set your PATH variable appropriately or use the full path
    +       to mklpc.sh in the final step.
         2. You can instruct Symantec to ignore the errors and it will stop quarantining
            the NXP program.
         3. The CRC32 logic in configs/ea3152/tools doesn't seem to work.  As a result,
    @@ -406,7 +403,6 @@ selected as follow:
         cd tools
         ./configure.sh ea3152/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    diff --git a/configs/eagle100/README.txt b/configs/eagle100/README.txt
    index 0b970355d7..f58ba90bb1 100644
    --- a/configs/eagle100/README.txt
    +++ b/configs/eagle100/README.txt
    @@ -38,8 +38,8 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_DEVKITARM=y     : devkitARM under Windows
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y     : NuttX buildroot under Linux or Cygwin (default)
     
    -  If you are not using CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT, then you may also have to modify
    -  the PATH in the setenv.h file if your make cannot find the tools.
    +  You may also have to modify the PATH environment variable if your make cannot
    +  find the tools.
     
       NOTE: the CodeSourcery (for Windows) and devkitARM are Windows native toolchains.
       The CodeSourcey (for Linux) and NuttX buildroot toolchains are Cygwin and/or Linux
    @@ -74,7 +74,7 @@ GNU Toolchain Options
     NuttX EABI "buildroot" Toolchain
     ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -101,8 +101,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you are
    @@ -155,8 +155,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     Ethernet-Bootloader
     ^^^^^^^^^^^^^^^^^^^
    @@ -345,7 +345,6 @@ Common Configuration Notes
            cd tools
            ./configure.sh eagle100/
            cd -
    -       . ./setenv.sh
     
          Where  is one of the configuration sub-directories described in
          the following paragraph.
    diff --git a/configs/efm32-g8xx-stk/README.txt b/configs/efm32-g8xx-stk/README.txt
    index 3f569bcd81..bd90ad9350 100644
    --- a/configs/efm32-g8xx-stk/README.txt
    +++ b/configs/efm32-g8xx-stk/README.txt
    @@ -234,7 +234,6 @@ CONFIGURATIONS
         cd tools
         ./configure.sh efm32-g8xx-stk/
         cd -
    -    . ./setenv.sh
     
       If this is a Windows native build, then configure.bat should be used
       instead of configure.sh:
    diff --git a/configs/efm32gg-stk3700/README.txt b/configs/efm32gg-stk3700/README.txt
    index c554259255..ec19a65f53 100644
    --- a/configs/efm32gg-stk3700/README.txt
    +++ b/configs/efm32gg-stk3700/README.txt
    @@ -179,13 +179,13 @@ USING THE J-LINK GDB SERVER
     
     Configurations
     ==============
    +
       Each EFM32 Giant Gecko Starter Kit configuration is maintained in a sub-
       directory and can be selected as follow:
     
         cd tools
         ./configure.sh efm32gg-stk3700/
         cd -
    -    . ./setenv.sh
     
       If this is a Windows native build, then configure.bat should be used
       instead of configure.sh:
    diff --git a/configs/ekk-lm3s9b96/README.txt b/configs/ekk-lm3s9b96/README.txt
    index 977d3df907..26ee59d69e 100644
    --- a/configs/ekk-lm3s9b96/README.txt
    +++ b/configs/ekk-lm3s9b96/README.txt
    @@ -107,8 +107,8 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_DEVKITARM=y       : devkitARM under Windows
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y       : NuttX buildroot under Linux or Cygwin (default)
     
    -  If you are not using CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT, then you may also have to modify
    -  the PATH in the setenv.h file if your make cannot find the tools.
    +  You may also have to modify the PATH environment variable if your make cannot
    +  find the tools.
     
       NOTE: the CodeSourcery (for Windows) and devkitARM are Windows native toolchains.
       The CodeSourcey (for Linux) and NuttX buildroot toolchains are Cygwin and/or Linux
    @@ -178,7 +178,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -205,8 +205,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you
    @@ -267,8 +267,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     Stellaris EKK-LM3S9B96 Evaluation Kit Configuration Options
     ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
    @@ -397,7 +397,6 @@ sub-directory and can be selected as follow:
         cd tools
         ./configure.sh ekk-lm3s9b96/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    diff --git a/configs/esp32-core/README.txt b/configs/esp32-core/README.txt
    index 674fab8995..cde3295ff0 100644
    --- a/configs/esp32-core/README.txt
    +++ b/configs/esp32-core/README.txt
    @@ -585,11 +585,9 @@ Configurations
         ./configure.sh esp32-core/
         cd -
         make oldconfig
    -    . ./setenv.sh
     
    -  Before sourcing the setenv.sh file above, you should examine it and
    -  perform edits as necessary so that TOOLCHAIN_BIN is the correct path to
    -  the directory than holds your toolchain binaries.
    +  Before building, make sure the PATH environment variable includes the
    +  correct path to the directory than holds your toolchain binaries.
     
       If this is a Windows native build, then configure.bat should be used
       instead of configure.sh:
    diff --git a/configs/ez80f910200kitg/README.txt b/configs/ez80f910200kitg/README.txt
    index f72c8e8fd2..635992b5d3 100644
    --- a/configs/ez80f910200kitg/README.txt
    +++ b/configs/ez80f910200kitg/README.txt
    @@ -49,9 +49,9 @@ Version 5.1.1
     
       Paths were also updated that are specific to a 32-bit toolchain running on
       a 64 bit windows platform.  Change to a different toolchain, you will need
    -  to modify the versioning in Make.defs and setenv.sh; if you want to build
    -  on a different platform, you will need to change the path in the ZDS binaries
    -  in those same files.
    +  to modify the versioning in Make.defs; if you want to build on a different
    +  platform, you will need to change the path in the ZDS binaries in that files
    +  and also in your PATH environment variable.
     
     Version 5.2.1
     
    @@ -63,8 +63,9 @@ Version 5.2.1
     Other Versions
       If you use any version of ZDS-II other than 5.1.1 or 5.2.1 or if you install
       ZDS-II at any location other than the default location, you will have to
    -  modify one or more of three files:  (1) configs/ez80f910200kitg/*/setenv.sh,
    -  (2) configs/ez80f910200kitg/*/Make.defs, and arch/z80/src/ez80/Toolchain.defs.
    +  modify one or two files:  (1) configs/ez80f910200kitg/*/Make.defs and
    +  (2) arch/z80/src/ez80/Toolchain.defs.  You probably have to modify the
    +  path to your toolchain in the PATH environment variable.
     
     Configuration Subdirectories
     ^^^^^^^^^^^^^^^^^^^^^^^^^^^^
    @@ -120,9 +121,7 @@ available:
              will need to use the short 8.3 filenames to avoid spaces.  On my
              PC, C:\PROGRA~1\ is is C:\Program Files\ and C:\PROGRA~2\ is
              C:\Program Files (x86)\
    -      b. You can't use setenv.sh in the native Windows environment.  Try
    -         scripts/setenv.bat instead.
    -      c. At present, the native Windows build fails at the final link stages.
    +      b. At present, the native Windows build fails at the final link stages.
              The failure is due to problems in arch/z80/src/nuttx.linkcmd that
              is autogenerated by arch/z80/src/Makefile.zdsii.  The basic problem
              is the spurious spaces and and carrirage returns are generated at
    diff --git a/configs/ez80f910200kitg/scripts/setenv.bat b/configs/ez80f910200kitg/scripts/setenv.bat
    deleted file mode 100644
    index 3a1b987b4d..0000000000
    --- a/configs/ez80f910200kitg/scripts/setenv.bat
    +++ /dev/null
    @@ -1,50 +0,0 @@
    -@echo off
    -
    -rem configs/ez80f810200kitg/scripts/setenv.bat
    -rem
    -rem   Copyright (C) 2012 Gregory Nutt. All rights reserved.
    -rem   Author: Gregory Nutt 
    -rem
    -rem Redistribution and use in source and binary forms, with or without
    -rem modification, are permitted provided that the following conditions
    -rem are met:
    -rem
    -rem 1. Redistributions of source code must retain the above copyright
    -rem    notice, this list of conditions and the following disclaimer.
    -rem 2. Redistributions in binary form must reproduce the above copyright
    -rem    notice, this list of conditions and the following disclaimer in
    -rem    the documentation and/or other materials provided with the
    -rem    distribution.
    -rem 3. Neither the name NuttX nor the names of its contributors may be
    -rem    used to endorse or promote products derived from this software
    -rem    without specific prior written permission.
    -rem
    -rem THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
    -rem "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
    -rem LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
    -rem FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
    -rem COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
    -rem INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
    -rem BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
    -rem OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
    -rem AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
    -rem LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
    -rem ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
    -rem POSSIBILITY OF SUCH DAMAGE.
    -
    -rem This is the location where I installed in the MinGW compiler. With
    -rem this configuration, it is recommended that you do NOT install the
    -rem MSYS tools; they conflict with the GNUWin32 tools.  See
    -rem http://www.mingw.org/ for further info.
    -
    -set PATH=C:\MinGW\bin;%PATH%
    -
    -rem This is the location where I installed the ZDS-II toolchain.
    -
    -set PATH=C:\Program Files (x86)\ZiLOG\ZDSII_eZ80Acclaim!_5.1.1\bin;%PATH%
    -
    -rem This is the location where I installed the GNUWin32 tools.  See
    -rem http://gnuwin32.sourceforge.net/.
    -
    -set PATH=C:\gnuwin32\bin;%PATH%
    -echo %PATH%
    diff --git a/configs/ez80f910200zco/README.txt b/configs/ez80f910200zco/README.txt
    index cf53682bcf..d88114e851 100644
    --- a/configs/ez80f910200zco/README.txt
    +++ b/configs/ez80f910200zco/README.txt
    @@ -49,9 +49,9 @@ Version 5.1.1
     
       Paths were also updated that are specific to a 32-bit toolchain running on
       a 64 bit windows platform.  Change to a different toolchain, you will need
    -  to modify the versioning in Make.defs and setenv.sh; if you want to build
    -  on a different platform, you will need to change the path in the ZDS binaries
    -  in those same files.
    +  to modify the versioning in Make.defs; if you want to build on a different
    +  platform, you will need to change the path the the ZDS binaries in that
    +  files as well as in your PATH environment variable.
     
     Version 5.2.1
     
    @@ -63,8 +63,9 @@ Version 5.2.1
     Other Versions
       If you use any version of ZDS-II other than 5.1.1 or 5.2.1 or if you install
       ZDS-II at any location other than the default location, you will have to
    -  modify one or more of three files:  (1) configs/ez80f910200zco/*/setenv.sh,
    -  (2) configs/ez80f910200zco/*/Make.defs, and arch/z80/src/ez80/Toolchain.defs.
    +  modify one or two files:  (2) configs/ez80f910200zco/*/Make.defs and (2)
    +  arch/z80/src/ez80/Toolchain.defs.  You may also have to modify you PATH
    +  environment variable.
     
     Configurations
     ^^^^^^^^^^^^^^
    diff --git a/configs/ez80f910200zco/scripts/setenv.bat b/configs/ez80f910200zco/scripts/setenv.bat
    deleted file mode 100644
    index 88fc6cbf31..0000000000
    --- a/configs/ez80f910200zco/scripts/setenv.bat
    +++ /dev/null
    @@ -1,50 +0,0 @@
    -@echo off
    -
    -rem configs/ez80f910200zco/scripts/setenv.bat
    -rem
    -rem   Copyright (C) 2012 Gregory Nutt. All rights reserved.
    -rem   Author: Gregory Nutt 
    -rem
    -rem Redistribution and use in source and binary forms, with or without
    -rem modification, are permitted provided that the following conditions
    -rem are met:
    -rem
    -rem 1. Redistributions of source code must retain the above copyright
    -rem    notice, this list of conditions and the following disclaimer.
    -rem 2. Redistributions in binary form must reproduce the above copyright
    -rem    notice, this list of conditions and the following disclaimer in
    -rem    the documentation and/or other materials provided with the
    -rem    distribution.
    -rem 3. Neither the name NuttX nor the names of its contributors may be
    -rem    used to endorse or promote products derived from this software
    -rem    without specific prior written permission.
    -rem
    -rem THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
    -rem "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
    -rem LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
    -rem FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
    -rem COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
    -rem INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
    -rem BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
    -rem OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
    -rem AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
    -rem LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
    -rem ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
    -rem POSSIBILITY OF SUCH DAMAGE.
    -
    -rem This is the location where I installed in the MinGW compiler. With
    -rem this configuration, it is recommended that you do NOT install the
    -rem MSYS tools; they conflict with the GNUWin32 tools.  See
    -rem http://www.mingw.org/ for further info.
    -
    -set PATH=C:\MinGW\bin;%PATH%
    -
    -rem This is the location where I installed the ZDS-II toolchain.
    -
    -set PATH=C:\Program Files (x86)\ZiLOG\ZDSII_eZ80Acclaim!_5.1.1\bin;%PATH%
    -
    -rem This is the location where I installed the GNUWin32 tools.  See
    -rem http://gnuwin32.sourceforge.net/.
    -
    -set PATH=C:\gnuwin32\bin;%PATH%
    -echo %PATH%
    diff --git a/configs/fire-stm32v2/README.txt b/configs/fire-stm32v2/README.txt
    index 3afb8126d3..a422d00cf4 100644
    --- a/configs/fire-stm32v2/README.txt
    +++ b/configs/fire-stm32v2/README.txt
    @@ -194,8 +194,8 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_RAISONANCE=y     : Raisonance RIDE7 under Windows
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y      : NuttX buildroot under Linux or Cygwin (default)
     
    -  If you change the default toolchain, then you may also have to modify the PATH in
    -  the setenv.h file if your make cannot find the tools.
    +  You may also have to modify the PATH environment variable if your make cannot
    +  find the tools.
     
       NOTE: the CodeSourcery (for Windows), Atollic, devkitARM, and Raisonance toolchains are
       Windows native toolchains.  The CodeSourcery (for Linux) and NuttX buildroot
    @@ -296,7 +296,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ================================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -323,8 +323,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you are
    @@ -385,8 +385,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     DFU and JTAG
     ============
    @@ -801,7 +801,6 @@ can be selected as follow:
         cd tools
         ./configure.sh fire-stm32v2/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    diff --git a/configs/freedom-k64f/README.txt b/configs/freedom-k64f/README.txt
    index 20d41d5713..cb04f040d4 100644
    --- a/configs/freedom-k64f/README.txt
    +++ b/configs/freedom-k64f/README.txt
    @@ -626,9 +626,8 @@ GNU Toolchain Options
     
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y
     
    -     If you are not using CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT, then you may
    -     also have to modify the PATH in the setenv.h file if your make cannot
    -     find the tools.
    +  You may also have to modify the PATH environment variable if your make cannot
    +  find the tools.
     
       NOTE:  Using native Windows toolchains under Cygwin has some limitations.
       This incuudes the CodeSourcery (for Windows) and devkitARM toolchains are
    @@ -822,7 +821,6 @@ can be selected as follow:
         cd tools
         ./configure.sh freedom-k64f/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    diff --git a/configs/freedom-k66f/README.txt b/configs/freedom-k66f/README.txt
    index 1dde7d71a6..9d1d1b0ecb 100644
    --- a/configs/freedom-k66f/README.txt
    +++ b/configs/freedom-k66f/README.txt
    @@ -629,9 +629,8 @@ GNU Toolchain Options
     
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y
     
    -     If you are not using CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT, then you may
    -     also have to modify the PATH in the setenv.h file if your make cannot
    -     find the tools.
    +  You may also have to modify the PATH environment variable if your make cannot
    +  find the tools.
     
       NOTE:  Using native Windows toolchains under Cygwin has some limitations.
       This incuudes the CodeSourcery (for Windows) and devkitARM toolchains are
    @@ -829,7 +828,6 @@ can be selected as follow:
         cd tools
         ./configure.sh freedom-K66F/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    diff --git a/configs/freedom-kl25z/README.txt b/configs/freedom-kl25z/README.txt
    index b5114b4d43..d8b5da82a5 100644
    --- a/configs/freedom-kl25z/README.txt
    +++ b/configs/freedom-kl25z/README.txt
    @@ -34,7 +34,7 @@ GNU Toolchain Options
     NuttX Buildroot Toolchain
     =========================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M0 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -61,8 +61,8 @@ NuttX Buildroot Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you are
    @@ -285,7 +285,6 @@ can be selected as follow:
         cd tools
         ./configure.sh freedom-kl25z/
         cd -
    -    . ./setenv.sh
     
     If this is a Windows native build, then configure.bat should be used
     instead of configure.sh:
    diff --git a/configs/freedom-kl26z/README.txt b/configs/freedom-kl26z/README.txt
    index 6237f71ad9..e23c202ac6 100644
    --- a/configs/freedom-kl26z/README.txt
    +++ b/configs/freedom-kl26z/README.txt
    @@ -34,7 +34,7 @@ GNU Toolchain Options
     NuttX Buildroot Toolchain
     =========================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M0 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -61,8 +61,8 @@ NuttX Buildroot Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you are
    @@ -263,7 +263,6 @@ can be selected as follow:
         cd tools
         ./configure.sh freedom-kl26z/
         cd -
    -    . ./setenv.sh
     
     If this is a Windows native build, then configure.bat should be used
     instead of configure.sh:
    diff --git a/configs/hymini-stm32v/README.txt b/configs/hymini-stm32v/README.txt
    index d477d6d8ee..0ec1913112 100644
    --- a/configs/hymini-stm32v/README.txt
    +++ b/configs/hymini-stm32v/README.txt
    @@ -50,8 +50,8 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_RAISONANCE=y     : Raisonance RIDE7 under Windows
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y      : NuttX buildroot under Linux or Cygwin (default)
     
    -  If you are not using CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT, then you may also have to modify
    -  the PATH in the setenv.h file if your make cannot find the tools.
    +  You may also have to modify the PATH environment variable if your make cannot
    +  find the tools.
     
       NOTE: the CodeSourcery (for Windows), devkitARM, and Raisonance toolchains are
       Windows native toolchains.  The CodeSourcey (for Linux) and NuttX buildroot
    @@ -118,7 +118,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ================================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -145,8 +145,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you are
    @@ -207,8 +207,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     ST Bootloader
     =============
    @@ -557,7 +557,6 @@ can be selected as follow:
         cd tools
         ./configure.sh hymini-stm32v/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    @@ -594,9 +593,8 @@ Where  is one of the following:
                                             apps/examples/nximage
         =========== ======================= ================================
     
    -    (1) You will probably need to modify nsh/setenv.sh or nsh2/setenv.sh
    -        to set up the correct PATH variable for whichever toolchain you
    -        may use.
    +    (1) You will probably need to the PATH environment variable to set
    +        up the correct PATH variable for whichever toolchain you may use.
         (2) When any other device other than /dev/console is used for a user
             interface, (1) linefeeds (\n) will not be expanded to carriage return
             / linefeeds \r\n). You will need to configure your terminal program
    diff --git a/configs/kwikstik-k40/README.txt b/configs/kwikstik-k40/README.txt
    index 9586a43c90..17c0d93526 100644
    --- a/configs/kwikstik-k40/README.txt
    +++ b/configs/kwikstik-k40/README.txt
    @@ -175,8 +175,8 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_DEVKITARM=y      : devkitARM under Windows
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y      : NuttX buildroot under Linux or Cygwin (default)
     
    -  If you are not using CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT, then you may also have to modify
    -  the PATH in the setenv.h file if your make cannot find the tools.
    +  You may also have to modify the PATH environment variable if your make cannot
    +  find the tools.
     
       NOTE: the CodeSourcery (for Windows) and devkitARM toolchains are
       Windows native toolchains.  The CodeSourcey (for Linux) and NuttX buildroot
    @@ -241,7 +241,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ================================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M4 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -270,8 +270,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you are
    @@ -332,8 +332,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     KwikStik-K40-specific Configuration Options
     ============================================
    @@ -507,7 +507,6 @@ can be selected as follow:
         cd tools
         ./configure.sh kwikstik-k40/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    diff --git a/configs/launchxl-tms57004/README.txt b/configs/launchxl-tms57004/README.txt
    index a229479fa8..6c9568f913 100644
    --- a/configs/launchxl-tms57004/README.txt
    +++ b/configs/launchxl-tms57004/README.txt
    @@ -175,11 +175,9 @@ Configurations
         cd tools
         ./configure.sh launchxl-tms57004/
         cd -
    -    . ./setenv.sh
     
    -  Before sourcing the setenv.sh file above, you should examine it and perform
    -  edits as necessary so that TOOLCHAIN_BIN is the correct path to the directory
    -  than holds your toolchain binaries.
    +  Before building, make sure the PATH environment variable includes the
    +  correct path to the directory than holds your toolchain binaries.
     
       And then build NuttX by simply typing the following.  At the conclusion of
       the make, the nuttx binary will reside in an ELF file called, simply, nuttx.
    diff --git a/configs/lincoln60/README.txt b/configs/lincoln60/README.txt
    index b5320549c0..4455198f7b 100644
    --- a/configs/lincoln60/README.txt
    +++ b/configs/lincoln60/README.txt
    @@ -82,8 +82,8 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_DEVKITARM=y       : devkitARM under Windows
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y       : NuttX buildroot under Linux or Cygwin (default)
     
    -  If you are not using CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT, then you may also have to modify
    -  the PATH in the setenv.h file if your make cannot find the tools.
    +  You may also have to modify the PATH environment variable if your make cannot
    +  find the tools.
     
       NOTE: the CodeSourcery (for Windows)and devkitARM are Windows native toolchains.
       The CodeSourcey (for Linux) and NuttX buildroot toolchains are Cygwin and/or
    @@ -148,7 +148,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -175,8 +175,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you
    @@ -237,8 +237,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     Lincoln 60 Configuration Options
     ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
    @@ -473,7 +473,6 @@ as follow:
         cd tools
         ./configure.sh lincoln60/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    diff --git a/configs/lm3s6432-s2e/README.txt b/configs/lm3s6432-s2e/README.txt
    index 5981dc790b..51faa22049 100644
    --- a/configs/lm3s6432-s2e/README.txt
    +++ b/configs/lm3s6432-s2e/README.txt
    @@ -102,8 +102,8 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_DEVKITARM=y       : devkitARM under Windows
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y       : NuttX buildroot under Linux or Cygwin (default)
     
    -  If you are not using CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT, then you may also have to modify
    -  the PATH in the setenv.h file if your make cannot find the tools.
    +  You may also have to modify the PATH environment variable if your make cannot
    +  find the tools.
     
       NOTE: the CodeSourcery (for Windows) and devkitARM are Windows native toolchains.
       The CodeSourcey (for Linux) and NuttX buildroot toolchains are Cygwin and/or Linux
    @@ -168,7 +168,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -199,8 +199,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you
    @@ -261,8 +261,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     Stellaris MDL-S2E Reference Design Configuration Options
     ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
    @@ -400,7 +400,6 @@ sub-directory and can be selected as follow:
         cd tools
         ./configure.sh lm3s6432-s2e/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    diff --git a/configs/lm3s6965-ek/README.txt b/configs/lm3s6965-ek/README.txt
    index 3bec4c6075..02113d495b 100644
    --- a/configs/lm3s6965-ek/README.txt
    +++ b/configs/lm3s6965-ek/README.txt
    @@ -211,8 +211,8 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_DEVKITARM=y       : devkitARM under Windows
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y       : NuttX buildroot under Linux or Cygwin (default)
     
    -  If you are not using CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT, then you may also have to modify
    -  the PATH in the setenv.h file if your make cannot find the tools.
    +  You may also have to modify the PATH environment variable if your make cannot
    +  find the tools.
     
       NOTE: the CodeSourcery (for Windows) and devkitARM are Windows native toolchains.
       The CodeSourcey (for Linux) and NuttX buildroot toolchains are Cygwin and/or Linux
    @@ -282,7 +282,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -309,8 +309,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you
    @@ -371,8 +371,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     USB Device Controller Functions
     ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
    @@ -540,7 +540,6 @@ sub-directory and can be selected as follow:
         cd tools
         ./configure.sh lm3s6965-ek/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    diff --git a/configs/lm3s8962-ek/README.txt b/configs/lm3s8962-ek/README.txt
    index 8c46c1db4a..37d7c8b744 100644
    --- a/configs/lm3s8962-ek/README.txt
    +++ b/configs/lm3s8962-ek/README.txt
    @@ -131,8 +131,8 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_DEVKITARM=y     : devkitARM under Windows
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y     : NuttX buildroot under Linux or Cygwin (default)
     
    -  If you are not using CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT, then you may also have to modify
    -  the PATH in the setenv.h file if your make cannot find the tools.
    +  You may also have to modify the PATH environment variable if your make cannot
    +  find the tools.
     
       NOTE: the CodeSourcery (for Windows) and devkitARM are Windows native toolchains.
       The CodeSourcey (for Linux) and NuttX buildroot toolchains are Cygwin and/or Linux
    @@ -186,7 +186,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -213,8 +213,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you
    @@ -275,8 +275,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     USB Device Controller Functions
     ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
    @@ -444,7 +444,6 @@ sub-directory and can be selected as follow:
         cd tools
         ./configure.sh lm3s8962-ek/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    diff --git a/configs/lm4f120-launchpad/README.txt b/configs/lm4f120-launchpad/README.txt
    index e90f68b16d..432b8503a7 100644
    --- a/configs/lm4f120-launchpad/README.txt
    +++ b/configs/lm4f120-launchpad/README.txt
    @@ -192,9 +192,8 @@ Using OpenOCD and GDB with an FT2232 JTAG emulator
     
           oocd.sh $PWD
     
    -    The relative path to the oocd.sh script is configs/lm4f120-launchpad/tools,
    -    but that should have been added to your PATH variable when you sourced
    -    the setenv.sh script.
    +    provided that you have the path to the oocd.sh script, configs/lm4f120-launchpad/tools,
    +    added to your PATH variable.
     
         Note that OpenOCD needs to be run with administrator privileges in
         some environments (sudo).
    @@ -269,8 +268,8 @@ GNU Toolchain Options
     
         CONFIG_ARMV7M_OABI_TOOLCHAIN=y           : If you use an older, OABI buildroot toolchain
     
    -  If you change the default toolchain, then you may also have to modify the PATH in
    -  the setenv.h file if your make cannot find the tools.
    +  You may also have to modify the PATH environment variable if your make cannot
    +  find the tools.
     
       NOTE: the CodeSourcery (for Windows), Atollic, devkitARM, and Code Red (for Windows)
       toolchains are Windows native toolchains.  The CodeSourcey (for Linux) and NuttX
    @@ -336,7 +335,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -363,8 +362,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you
    @@ -425,8 +424,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     LEDs
     ^^^^
    @@ -671,7 +670,6 @@ sub-directory and can be selected as follow:
         cd tools
         ./configure.sh lm4f120-launchpad/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    diff --git a/configs/lpc4330-xplorer/README.txt b/configs/lpc4330-xplorer/README.txt
    index 3afbe967ff..c0be108439 100644
    --- a/configs/lpc4330-xplorer/README.txt
    +++ b/configs/lpc4330-xplorer/README.txt
    @@ -155,8 +155,8 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_DEVKITARM=y      : devkitARM under Windows
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y      : NuttX buildroot under Linux or Cygwin (default)
     
    -  If you are not using CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT, then you may also have to modify
    -  the PATH in the setenv.h file if your make cannot find the tools.
    +  You may also have to modify the PATH environment variable if your make cannot
    +  find the tools.
     
       NOTE: the Code Red, CodeSourcery (for Windows), Atollic and devkitARM toolchains
       are Windows native toolchains.  The CodeSourcery (for Linux) and NuttX buildroot
    @@ -282,13 +282,13 @@ Code Red IDE/Tools
       (The "free" RedSuite version has a download limit of 8K; the "free" LPCXpresso
       version has a download limit of 128K).
     
    -  NOTE that the following alias is defined in the setenv.sh file and
    -  can be used to enter the boot mode with a simpler command:
    +  NOTE that the following alias may be defined to enter the boot mode with a
    +  simpler command:
     
         alias lpc43xx='${SCRIPT_BIN}/Scripts/bootLPCXpresso.cmd winusb'
     
    -  Be default, the setenv.sh scripts uses the LPCXpresso path shown above.
    -  Once setenv.sh has been sources, then entering boot mode becomes simply:
    +  You may also have to modify the PATH environment variable if your make cannot
    +  find the tools.
     
         $ lpc43xx
         Booting LPC-Link with LPCXpressoWIN.enc
    @@ -453,7 +453,7 @@ Code Red IDE/Tools
     NuttX EABI "buildroot" Toolchain
     ================================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -480,8 +480,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you
    @@ -542,8 +542,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     Serial Console
     ==============
    @@ -867,7 +867,6 @@ as follow:
         cd tools
         ./configure.sh lpc4330-xplorer/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    diff --git a/configs/lpc4337-ws/README.txt b/configs/lpc4337-ws/README.txt
    index a62558a8a0..d8ca540a69 100644
    --- a/configs/lpc4337-ws/README.txt
    +++ b/configs/lpc4337-ws/README.txt
    @@ -151,8 +151,8 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_DEVKITARM=y      : devkitARM under Windows
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y      : NuttX buildroot under Linux or Cygwin (default)
     
    -  If you are not using CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT, then you may also have to modify
    -  the PATH in the setenv.h file if your make cannot find the tools.
    +  You may also have to modify the PATH environment variable if your make cannot
    +  find the tools.
     
       NOTE: the Code Red, CodeSourcery (for Windows), Atollic and devkitARM toolchains
       are Windows native toolchains.  The CodeSourcery (for Linux) and NuttX buildroot
    @@ -278,13 +278,13 @@ Code Red IDE/Tools
       (The "free" RedSuite version has a download limit of 8K; the "free" LPCXpresso
       version has a download limit of 128K).
     
    -  NOTE that the following alias is defined in the setenv.sh file and
    -  can be used to enter the boot mode with a simpler command:
    +  NOTE that the following alias may be  defined to enter the boot mode with a
    +  simpler command:
     
         alias lpc43xx='${SCRIPT_BIN}/Scripts/bootLPCXpresso.cmd winusb'
     
    -  Be default, the setenv.sh scripts uses the LPCXpresso path shown above.
    -  Once setenv.sh has been sources, then entering boot mode becomes simply:
    +  You may also have to modify the PATH environment variable if your make cannot
    +  find the tools.
     
         $ lpc43xx
         Booting LPC-Link with LPCXpressoWIN.enc
    @@ -449,7 +449,7 @@ Code Red IDE/Tools
     NuttX EABI "buildroot" Toolchain
     ================================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -476,8 +476,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you
    @@ -538,8 +538,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     LED and Pushbuttons
     ===================
    @@ -906,7 +906,6 @@ as follow:
         cd tools
         ./configure.sh LPC4337-ws/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    diff --git a/configs/lpc4357-evb/README.txt b/configs/lpc4357-evb/README.txt
    index c3febbec03..95955308cc 100644
    --- a/configs/lpc4357-evb/README.txt
    +++ b/configs/lpc4357-evb/README.txt
    @@ -148,8 +148,8 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_DEVKITARM=y      : devkitARM under Windows
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y      : NuttX buildroot under Linux or Cygwin (default)
     
    -  If you are not using CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT, then you may also have to modify
    -  the PATH in the setenv.h file if your make cannot find the tools.
    +  You may also have to modify the PATH environment variable if your make cannot
    +  find the tools.
     
       NOTE: the Code Red, CodeSourcery (for Windows), Atollic and devkitARM toolchains
       are Windows native toolchains.  The CodeSourcery (for Linux) and NuttX buildroot
    @@ -275,13 +275,13 @@ Code Red IDE/Tools
       (The "free" RedSuite version has a download limit of 8K; the "free" LPCXpresso
       version has a download limit of 128K).
     
    -  NOTE that the following alias is defined in the setenv.sh file and
    -  can be used to enter the boot mode with a simpler command:
    +  NOTE that the following alias may be  defined to enter the boot mode with a
    +  simpler command:
     
         alias lpc43xx='${SCRIPT_BIN}/Scripts/bootLPCXpresso.cmd winusb'
     
    -  Be default, the setenv.sh scripts uses the LPCXpresso path shown above.
    -  Once setenv.sh has been sources, then entering boot mode becomes simply:
    +  You may also have to modify the PATH environment variable if your make cannot
    +  find the tools.
     
         $ lpc43xx
         Booting LPC-Link with LPCXpressoWIN.enc
    @@ -446,7 +446,7 @@ Code Red IDE/Tools
     NuttX EABI "buildroot" Toolchain
     ================================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -473,8 +473,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you
    @@ -535,8 +535,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     LED and Pushbuttons
     ===================
    @@ -903,7 +903,6 @@ as follow:
         cd tools
         ./configure.sh lpc4357-evb/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    diff --git a/configs/lpc4370-link2/README.txt b/configs/lpc4370-link2/README.txt
    index 9280b3258b..d39515d7f0 100644
    --- a/configs/lpc4370-link2/README.txt
    +++ b/configs/lpc4370-link2/README.txt
    @@ -151,8 +151,8 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_DEVKITARM=y      : devkitARM under Windows
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y      : NuttX buildroot under Linux or Cygwin (default)
     
    -  If you are not using CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT, then you may also have to modify
    -  the PATH in the setenv.h file if your make cannot find the tools.
    +  You may also have to modify the PATH environment variable if your make cannot
    +  find the tools.
     
       NOTE: the Code Red, CodeSourcery (for Windows), Atollic and devkitARM toolchains
       are Windows native toolchains.  The CodeSourcery (for Linux) and NuttX buildroot
    @@ -278,13 +278,13 @@ Code Red IDE/Tools
       (The "free" RedSuite version has a download limit of 8K; the "free" LPCXpresso
       version has a download limit of 128K).
     
    -  NOTE that the following alias is defined in the setenv.sh file and
    -  can be used to enter the boot mode with a simpler command:
    +  NOTE that the following alias may be defined to enter the boot mode with a
    +  simpler command:
     
         alias lpc43xx='${SCRIPT_BIN}/Scripts/bootLPCXpresso.cmd winusb'
     
    -  Be default, the setenv.sh scripts uses the LPCXpresso path shown above.
    -  Once setenv.sh has been sources, then entering boot mode becomes simply:
    +  You may also have to modify the PATH environment variable if your make cannot
    +  find the tools.
     
         $ lpc43xx
         Booting LPC-Link with LPCXpressoWIN.enc
    @@ -449,7 +449,7 @@ Code Red IDE/Tools
     NuttX EABI "buildroot" Toolchain
     ================================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -476,8 +476,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you
    @@ -538,8 +538,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     LED and Pushbuttons
     ===================
    @@ -906,7 +906,6 @@ as follow:
         cd tools
         ./configure.sh LPC4370-Link2/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    diff --git a/configs/lpcxpresso-lpc1115/README.txt b/configs/lpcxpresso-lpc1115/README.txt
    index 168bed5198..5b91b43a1f 100644
    --- a/configs/lpcxpresso-lpc1115/README.txt
    +++ b/configs/lpcxpresso-lpc1115/README.txt
    @@ -91,7 +91,7 @@ GNU Toolchain Options
         CONFIG_ARMV6M_TOOLCHAIN_CODEREDW=n        : Code Red toolchain under Windows
         CONFIG_ARMV6M_TOOLCHAIN_CODEREDL=y        : Code Red toolchain under Linux
     
    -  You may also have to modify the PATH in the setenv.h file if your make cannot
    +  You may also have to modify the PATH environment variable if your make cannot
       find the tools.
     
       NOTE: the CodeSourcery (for Windows), devkitARM, and Code Red (for Windoes)
    @@ -234,7 +234,7 @@ Code Red IDE
     NuttX EABI "buildroot" Toolchain
     ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -261,8 +261,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you
    @@ -323,8 +323,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     Using OpenOCD
     ^^^^^^^^^^^^^
    @@ -676,7 +676,6 @@ selected as follow:
         cd tools
         ./configure.sh lpcxpresso-lpc1115/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    diff --git a/configs/lpcxpresso-lpc1768/README.txt b/configs/lpcxpresso-lpc1768/README.txt
    index 36d5eead96..534108b309 100644
    --- a/configs/lpcxpresso-lpc1768/README.txt
    +++ b/configs/lpcxpresso-lpc1768/README.txt
    @@ -258,7 +258,7 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_CODEREDW=n        : Code Red toolchain under Windows
         CONFIG_ARMV7M_TOOLCHAIN_CODEREDL=y        : Code Red toolchain under Linux
     
    -  You may also have to modify the PATH in the setenv.h file if your make cannot
    +  You may also have to modify the PATH environment variable if your make cannot
       find the tools.
     
       NOTE: the CodeSourcery (for Windows), devkitARM, and Code Red (for Windoes)
    @@ -398,7 +398,7 @@ Code Red IDE
     NuttX EABI "buildroot" Toolchain
     ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -425,8 +425,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you
    @@ -487,8 +487,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     LEDs
     ^^^^
    @@ -728,7 +728,6 @@ selected as follow:
         cd tools
         ./configure.sh lpcxpresso-lpc1768/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    diff --git a/configs/maple/README.txt b/configs/maple/README.txt
    index b8d8a1fee9..076f7acb82 100644
    --- a/configs/maple/README.txt
    +++ b/configs/maple/README.txt
    @@ -111,11 +111,9 @@ Configurations
         cd tools
         ./configure.sh maple/
         cd -
    -    . ./setenv.sh
     
    -  Before sourcing the setenv.sh file above, you should examine it and perform
    -  edits as necessary so that TOOLCHAIN_BIN is the correct path to the directory
    -  than holds your toolchain binaries.
    +  Before building, make sure the PATH environment variable includes the
    +  correct path to the directory than holds your toolchain binaries.
     
       And then build NuttX by simply typing the following.  At the conclusion of
       the make, the nuttx binary will reside in an ELF file called, simply, nuttx.
    diff --git a/configs/mbed/README.txt b/configs/mbed/README.txt
    index 40d99a661e..c74cf4852f 100644
    --- a/configs/mbed/README.txt
    +++ b/configs/mbed/README.txt
    @@ -45,9 +45,6 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_DEVKITARM=y       : devkitARM under Windows
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y       : NuttX buildroot under Linux or Cygwin (default)
     
    -  If you are not using CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT, then you may also
    -  have to modify the PATH in the setenv.h file if your make cannot find the tools.
    -
       NOTE: the CodeSourcery (for Windows)and devkitARM are Windows native toolchains.
       The CodeSourcey (for Linux) and NuttX buildroot toolchains are Cygwin and/or
       Linux native toolchains. There are several limitations to using a Windows based
    @@ -111,7 +108,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -138,8 +135,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you
    @@ -200,8 +197,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     mbed Configuration Options
     ^^^^^^^^^^^^^^^^^^^^^^^^^^
    @@ -446,7 +443,6 @@ Configurations
         cd tools
         ./configure.sh mbed/
         cd -
    -    . ./setenv.sh
     
       Where  is one of the mbed subdirectories described in the
       following paragraph.
    diff --git a/configs/mcu123-lpc214x/README.txt b/configs/mcu123-lpc214x/README.txt
    index cae9bf9957..de1780d8dc 100644
    --- a/configs/mcu123-lpc214x/README.txt
    +++ b/configs/mcu123-lpc214x/README.txt
    @@ -79,7 +79,7 @@ GNU Toolchain Options
     NuttX buildroot Toolchain
     ^^^^^^^^^^^^^^^^^^^^^^^^^
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -106,8 +106,8 @@ NuttX buildroot Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       detailed PLUS some special instructions that you will need to follow if you are
    @@ -320,7 +320,6 @@ Configurations
            cd tools
            ./configure.sh mcu123-lpc214x/
            cd -
    -       . ./setenv.sh
     
          Where  is one of the configuration sub-directories described in
          the following paragraph.
    diff --git a/configs/micropendous3/README.txt b/configs/micropendous3/README.txt
    index f270116f31..b252ef207d 100644
    --- a/configs/micropendous3/README.txt
    +++ b/configs/micropendous3/README.txt
    @@ -212,9 +212,8 @@ Buildroot:
       http://bitbucket.org/nuttx/buildroot/downloads/.  See the
       following section for details on building this toolchain.
     
    -  It is assumed in some places that buildroot toolchain is available
    -  at ../buildroot/build_avr.  Edit the setenv.sh file if
    -  this is not the case.
    +  Before building, make sure that the path to the new toolchain is included
    +  in your PATH environment variable.
     
       After configuring NuttX, make sure that CONFIG_AVR_BUILDROOT_TOOLCHAIN=y is set in your
       .config file.
    @@ -224,8 +223,8 @@ WinAVR:
       For Cygwin development environment on Windows machines, you can use
       WinAVR: http://sourceforge.net/projects/winavr/files/
     
    -  It is assumed in some places that WinAVR is installed at C:/WinAVR.  Edit the
    -  setenv.sh file if this is not the case.
    +  Before building, make sure that the path to the new toolchain is included
    +  in your PATH environment variable.
     
       After configuring NuttX, make sure that CONFIG_AVR_WINAVR_TOOLCHAIN=y is set in your
       .config file.
    @@ -310,8 +309,8 @@ NuttX buildroot Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       detailed PLUS some special instructions that you will need to follow if you
    @@ -513,7 +512,6 @@ Common Configuration Notes
            cd tools
            ./configure.sh micropendous3/
            cd -
    -       . ./setenv.sh
     
          Where  is one of the configuration sub-directories described in
          the following paragraph.
    diff --git a/configs/mikroe-stm32f4/README.txt b/configs/mikroe-stm32f4/README.txt
    index 0348f0e18b..54c4fd9ef5 100644
    --- a/configs/mikroe-stm32f4/README.txt
    +++ b/configs/mikroe-stm32f4/README.txt
    @@ -69,9 +69,6 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_RAISONANCE=y     : Raisonance RIDE7 under Windows
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y      : NuttX buildroot under Linux or Cygwin (default)
     
    -  If you change the default toolchain, then you may also have to modify the PATH in
    -  the setenv.h file if your make cannot find the tools.
    -
       NOTE: the CodeSourcery (for Windows), Atollic, devkitARM, and Raisonance toolchains are
       Windows native toolchains.  The CodeSourcey (for Linux) and NuttX buildroot
       toolchains are Cygwin and/or Linux native toolchains. There are several limitations
    @@ -176,7 +173,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ================================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -203,8 +200,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you are
    @@ -265,8 +262,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     LEDs
     ====
    @@ -716,7 +713,6 @@ can be selected as follow:
         cd tools
         ./configure.sh mikroe-stm32f4/
         cd -
    -    . ./setenv.sh
     
     If this is a Windows native build, then configure.bat should be used
     instead of configure.sh:
    diff --git a/configs/mirtoo/README.txt b/configs/mirtoo/README.txt
    index d97e6d198c..29510b353a 100644
    --- a/configs/mirtoo/README.txt
    +++ b/configs/mirtoo/README.txt
    @@ -360,7 +360,7 @@ Toolchains
     
         CONFIG_MIPS32_TOOLCHAIN_MICROCHIPOPENL - microchipOpen toolchain for Linux
     
    -  And set the path appropriately in the setenv.sh file.
    +  And set the path appropriately in the PATH environment variable.
     
       Building MicrochipOpen (on Linux)
       ---------------------------------
    @@ -399,8 +399,9 @@ Toolchains
         CONFIG_MIPS32_TOOLCHAIN_PINGUINOW - Pinguino mips-elf toolchain for Windows
         CONFIG_MIPS32_TOOLCHAIN_GNU_ELF   - mips-elf toolchain for Linux or OS X
     
    -  And set the path appropriately in the setenv.sh file.  These tool configurations
    -  are untested -- expect some additional integration issues.  Good luck!
    +  And set the path appropriately in the PATH environment variable.  These tool
    +  configurations are untested -- expect some additional integration issues.
    +  Good luck!
     
       This configuration will also work with any generic mips-elf GCC past version
       4.6 or so.
    @@ -488,8 +489,7 @@ Loading NuttX with ICD3
     
         To use this file, you need to do the following things:
     
    -      . ./setenv.sh    # Source setenv.sh.  Among other this, this script
    -                       # will add the NuttX tools/pic32mx directory to your
    +      export PATH=???  # Add the NuttX tools/pic32mx directory to your
                            # PATH variable
           make             # Build nuttx and nuttx.hex
           mkpichex $PWD    # Convert addresses in nuttx.hex.  $PWD is the path
    @@ -844,7 +844,6 @@ selected as follow:
         cd tools
         ./configure.sh mirtoo/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    @@ -882,8 +881,8 @@ Where  is one of the following:
     
            To switch to the Linux C32 toolchain you will have to change (1) the
            toolchain selection in .config (after configuration) and (2) the
    -       path to the toolchain in setenv.sh.  See notes above with regard to
    -       the XC32 toolchain.
    +       path to the toolchain in the PATH environment variable.  See notes above
    +       with regard to the XC32 toolchain.
     
         4. PGA117 Support
     
    diff --git a/configs/misoc/README.txt b/configs/misoc/README.txt
    index a241aba6b6..b485dd1906 100644
    --- a/configs/misoc/README.txt
    +++ b/configs/misoc/README.txt
    @@ -10,7 +10,7 @@ Misoc README
     Buildroot Toolchain
     ===================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the LM32 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -48,10 +48,8 @@ Buildroot Toolchain
     
            ../buildroot/build_lm32/staging_dir/bin
     
    -     The setenv.sh files in these sub-directories are already set to use
    -     the relative path.  It you choose to install the buildroot package
    -     in some other location, you may need to edit the setenv.h file so
    -     that the PATH variable includes the path to the newly built binaries.
    +     Make sure that he PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       detailed PLUS some special instructions that you will need to follow if you
    diff --git a/configs/moteino-mega/README.txt b/configs/moteino-mega/README.txt
    index 9c3c03b1de..71600becaa 100644
    --- a/configs/moteino-mega/README.txt
    +++ b/configs/moteino-mega/README.txt
    @@ -251,7 +251,6 @@ Common Configuration Notes
            cd tools
            ./configure.sh moteino-mega/
            cd -
    -       . ./setenv.sh
     
          Where  is one of the configuration sub-directories described in
          the following paragraph.
    diff --git a/configs/mx1ads/README.txt b/configs/mx1ads/README.txt
    index f9133a8a6b..283127e580 100644
    --- a/configs/mx1ads/README.txt
    +++ b/configs/mx1ads/README.txt
    @@ -4,7 +4,7 @@ README
     Toolchain
     ^^^^^^^^^
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the ARM920T GCC toolchain (if
       different from the default).
     
    @@ -28,8 +28,8 @@ Toolchain
     
       7. make
     
    -  8. Edit setenv.h so that the PATH variable includes the path to the
    -     newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
     Issues
     ^^^^^^
    @@ -146,7 +146,6 @@ Common Configuration Notes
            cd tools
            ./configure.sh imxads/
            cd -
    -       . ./setenv.sh
     
          Where  is one of the configuration sub-directories described in
          the following paragraph.
    diff --git a/configs/ne64badge/README.txt b/configs/ne64badge/README.txt
    index 5eb2bc7d82..3f532cb7e3 100644
    --- a/configs/ne64badge/README.txt
    +++ b/configs/ne64badge/README.txt
    @@ -217,7 +217,7 @@ Development Environment
     NuttX Buildroot Toolchain
     ^^^^^^^^^^^^^^^^^^^^^^^^^
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the HC12 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -250,8 +250,8 @@ NuttX Buildroot Toolchain
          directory manually.  For example, binutils-2.18 can be found here:
          http://ftp.gnu.org/gnu/binutils/
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       detailed PLUS some special instructions that you will need to follow if you are
    @@ -474,7 +474,6 @@ Common Configuration Notes
            cd tools
            ./configure.sh ne64badge/
            cd -
    -       . ./setenv.sh
     
          Where  is one of the configuration sub-directories described in
          the following paragraph.
    diff --git a/configs/nr5m100-nexys4/README.txt b/configs/nr5m100-nexys4/README.txt
    index fc939aa4c6..88c488de68 100644
    --- a/configs/nr5m100-nexys4/README.txt
    +++ b/configs/nr5m100-nexys4/README.txt
    @@ -235,12 +235,6 @@ can be selected as follow:
         cd tools
         ./configure.sh nr5m100-nexys4/
         cd -
    -    . ./setenv.sh
    -
    -If this is a Windows native build, then configure.bat should be used
    -instead of configure.sh:
    -
    -    configure.bat nr5m100-nexys4\
     
     Where  is one of the following:
     
    diff --git a/configs/ntosd-dm320/README.txt b/configs/ntosd-dm320/README.txt
    index 3377ffdb78..1d0a66305f 100644
    --- a/configs/ntosd-dm320/README.txt
    +++ b/configs/ntosd-dm320/README.txt
    @@ -67,12 +67,9 @@ GNU Toolchain Options
         CONFIG_ARM_TOOLCHAIN_CODESOURCERYW=y  : CodeSourcery under Windows
         CONFIG_ARM_TOOLCHAIN_CODESOURCERYL=y  : CodeSourcery under Linux
         CONFIG_ARM_TOOLCHAIN_DEVKITARM=y      : devkitARM under Windows
    -    CONFIG_ARM_TOOLCHAIN_BUILDROOT=y	    : NuttX buildroot under Linux or Cygwin (default)
    +    CONFIG_ARM_TOOLCHAIN_BUILDROOT=y      : NuttX buildroot under Linux or Cygwin (default)
         CONFIG_ARM_TOOLCHAIN_GNU_EABIL : Generic arm-none-eabi toolchain
     
    -  If you are not using CONFIG_ARM_TOOLCHAIN_BUILDROOT, then you may also have to modify
    -  the PATH in the setenv.h file if your make cannot find the tools.
    -
       The toolchain may also be set using the kconfig-mconf utility (make menuconfig)
       or by passing CONFIG_ARM_TOOLCHAIN= to make, where  is one
       of CODESOURCERYW, CODESOURCERYL, DEVKITARM, BUILDROOT or GNU_EABI as described
    @@ -160,7 +157,7 @@ IDEs
     NuttX buildroot Toolchain
     ^^^^^^^^^^^^^^^^^^^^^^^^^
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the ARM926 GCC toolchain (if
       different from the default).
     
    @@ -185,93 +182,93 @@ NuttX buildroot Toolchain
     
       7. make
     
    -  8. Edit setenv.h so that the PATH variable includes the path to the
    -     newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
     ARM/DM320-specific Configuration Options
     ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
     
    -	CONFIG_ARCH - Identifies the arch/ subdirectory.  This should
    -	   be set to:
    +    CONFIG_ARCH - Identifies the arch/ subdirectory.  This should
    +       be set to:
     
    -	   CONFIG_ARCH=arm
    +       CONFIG_ARCH=arm
     
    -	CONFIG_ARCH_family - For use in C code:
    +    CONFIG_ARCH_family - For use in C code:
     
    -	   CONFIG_ARCH_ARM=y
    +       CONFIG_ARCH_ARM=y
     
    -	CONFIG_ARCH_architecture - For use in C code:
    +    CONFIG_ARCH_architecture - For use in C code:
     
    -	   CONFIG_ARCH_ARM926EJS=y
    +       CONFIG_ARCH_ARM926EJS=y
     
    -	CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory
    +    CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory
     
    -	   CONFIG_ARCH_CHIP=dm320
    +       CONFIG_ARCH_CHIP=dm320
     
    -	CONFIG_ARCH_CHIP_name - For use in C code
    +    CONFIG_ARCH_CHIP_name - For use in C code
     
    -	   CONFIG_ARCH_CHIP_DM320
    +       CONFIG_ARCH_CHIP_DM320
     
    -	CONFIG_ARCH_BOARD - Identifies the configs subdirectory and
    -	   hence, the board that supports the particular chip or SoC.
    +    CONFIG_ARCH_BOARD - Identifies the configs subdirectory and
    +       hence, the board that supports the particular chip or SoC.
     
    -	   CONFIG_ARCH_BOARD=ntosd-dm320
    +       CONFIG_ARCH_BOARD=ntosd-dm320
     
    -	CONFIG_ARCH_BOARD_name - For use in C code
    +    CONFIG_ARCH_BOARD_name - For use in C code
     
    -	   CONFIG_ARCH_BOARD_NTOSD_DM320 (for the Spectrum Digital C5471 EVM)
    +       CONFIG_ARCH_BOARD_NTOSD_DM320 (for the Spectrum Digital C5471 EVM)
     
    -	CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation
    -	   of delay loops
    +    CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation
    +       of delay loops
     
    -	CONFIG_ENDIAN_BIG - define if big endian (default is little
    -	   endian)
    +    CONFIG_ENDIAN_BIG - define if big endian (default is little
    +       endian)
     
    -	CONFIG_RAM_SIZE - Describes the installed DRAM.
    +    CONFIG_RAM_SIZE - Describes the installed DRAM.
     
    -	CONFIG_RAM_START - The start address of installed DRAM
    +    CONFIG_RAM_START - The start address of installed DRAM
     
    -	CONFIG_RAM_VSTART - The startaddress of DRAM (virtual)
    +    CONFIG_RAM_VSTART - The startaddress of DRAM (virtual)
     
    -	CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that
    -	   have LEDs
    +    CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that
    +       have LEDs
     
    -	CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt
    -	   stack. If defined, this symbol is the size of the interrupt
    -	   stack in bytes.  If not defined, the user task stacks will be
    -	  used during interrupt handling.
    +    CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt
    +       stack. If defined, this symbol is the size of the interrupt
    +       stack in bytes.  If not defined, the user task stacks will be
    +      used during interrupt handling.
     
    -	CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions
    +    CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions
     
    -	CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that
    -	   cause a 100 second delay during boot-up.  This 100 second delay
    -	   serves no purpose other than it allows you to calibratre
    -	   CONFIG_ARCH_LOOPSPERMSEC.  You simply use a stop watch to measure
    -	   the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until
    -	   the delay actually is 100 seconds.
    +    CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that
    +       cause a 100 second delay during boot-up.  This 100 second delay
    +       serves no purpose other than it allows you to calibratre
    +       CONFIG_ARCH_LOOPSPERMSEC.  You simply use a stop watch to measure
    +       the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until
    +       the delay actually is 100 seconds.
     
       DM320 specific device driver settings
     
    -	CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the
    -	   console and ttys0 (default is the UART0).
    -	CONFIG_UARTn_RXBUFSIZE - Characters are buffered as received.
    -	   This specific the size of the receive buffer
    -	CONFIG_UARTn_TXBUFSIZE - Characters are buffered before
    -	   being sent.  This specific the size of the transmit buffer
    -	CONFIG_UARTn_BAUD - The configure BAUD of the UART.  Must be
    -	CONFIG_UARTn_BITS - The number of bits.  Must be either 7 or 8.
    -	CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity
    -	CONFIG_UARTn_2STOP - Two stop bits
    +    CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the
    +       console and ttys0 (default is the UART0).
    +    CONFIG_UARTn_RXBUFSIZE - Characters are buffered as received.
    +       This specific the size of the receive buffer
    +    CONFIG_UARTn_TXBUFSIZE - Characters are buffered before
    +       being sent.  This specific the size of the transmit buffer
    +    CONFIG_UARTn_BAUD - The configure BAUD of the UART.  Must be
    +    CONFIG_UARTn_BITS - The number of bits.  Must be either 7 or 8.
    +    CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity
    +    CONFIG_UARTn_2STOP - Two stop bits
     
       DM320 USB Configuration
     
    -	CONFIG_DM320_GIO_USBATTACH
    -	   GIO that detects USB attach/detach events
    -	CONFIG_DM320_GIO_USBDPPULLUP
    -	   GIO
    -	CONFIG_DMA320_USBDEV_DMA
    -	   Enable DM320-specific DMA support
    -	CONFIG_DM320_GIO_USBATTACH=6
    +    CONFIG_DM320_GIO_USBATTACH
    +       GIO that detects USB attach/detach events
    +    CONFIG_DM320_GIO_USBDPPULLUP
    +       GIO
    +    CONFIG_DMA320_USBDEV_DMA
    +       Enable DM320-specific DMA support
    +    CONFIG_DM320_GIO_USBATTACH=6
     
     Configurations
     ^^^^^^^^^^^^^^
    @@ -285,7 +282,6 @@ Common Configuration Notes
            cd tools
            ./configure.sh ntosd-dm320/
            cd -
    -       . ./setenv.sh
     
          Where  is one of the configuration sub-directories described in
          the following paragraph.
    diff --git a/configs/ntosd-dm320/doc/README.txt b/configs/ntosd-dm320/doc/README.txt
    index 758870b9ca..e3c24ea4a6 100644
    --- a/configs/ntosd-dm320/doc/README.txt
    +++ b/configs/ntosd-dm320/doc/README.txt
    @@ -50,10 +50,12 @@ General instructions.
     6. Build Nuttx:
     
       cd nuttx
    -  . ./setenv.sh
       make
       mv nuttx /tftpboot/nuttx.dm320
     
    +  You may also have to modify the PATH environment variable if your make cannot
    +  find the tools.
    +
     7. Configure the OSD u-boot:
     
        Neuros Devboard > set ipaddr yy.yy.yy.yy
    diff --git a/configs/nucleo-144/README.txt b/configs/nucleo-144/README.txt
    index 6226299546..cb6d65692f 100644
    --- a/configs/nucleo-144/README.txt
    +++ b/configs/nucleo-144/README.txt
    @@ -193,7 +193,7 @@ IDEs
     Basic configuration & build steps
     ==================================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M7 GCC toolchain (if
       different from the default in your PATH variable).
     
    diff --git a/configs/nucleo-f072rb/README.txt b/configs/nucleo-f072rb/README.txt
    index 118d24d9af..3f4eecaabf 100644
    --- a/configs/nucleo-f072rb/README.txt
    +++ b/configs/nucleo-f072rb/README.txt
    @@ -198,11 +198,9 @@ Configurations
         cd tools
         ./configure.sh nucleo-f072rb/
         cd -
    -    . ./setenv.sh
     
    -  Before sourcing the setenv.sh file above, you should examine it and
    -  perform edits as necessary so that TOOLCHAIN_BIN is the correct path
    -  to the directory than holds your toolchain binaries.
    +  Before building, make sure the PATH environment variable includes the
    +  correct path to the directory than holds your toolchain binaries.
     
       And then build NuttX by simply typing the following.  At the conclusion of
       the make, the nuttx binary will reside in an ELF file called, simply, nuttx.
    diff --git a/configs/nucleo-f4x1re/README.txt b/configs/nucleo-f4x1re/README.txt
    index 9ea6be28ab..f22b3c6e19 100644
    --- a/configs/nucleo-f4x1re/README.txt
    +++ b/configs/nucleo-f4x1re/README.txt
    @@ -250,7 +250,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ================================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    diff --git a/configs/nucleo-l476rg/README.txt b/configs/nucleo-l476rg/README.txt
    index 72ab182d87..497035e4a8 100644
    --- a/configs/nucleo-l476rg/README.txt
    +++ b/configs/nucleo-l476rg/README.txt
    @@ -232,7 +232,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ================================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    diff --git a/configs/nutiny-nuc120/README.txt b/configs/nutiny-nuc120/README.txt
    index c6f747d167..90fabba39c 100644
    --- a/configs/nutiny-nuc120/README.txt
    +++ b/configs/nutiny-nuc120/README.txt
    @@ -35,7 +35,7 @@ GNU Toolchain Options
     NuttX Buildroot Toolchain
     =========================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M0 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -62,8 +62,8 @@ NuttX Buildroot Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you are
    @@ -271,12 +271,6 @@ can be selected as follow:
         cd tools
         ./configure.sh nutiny-nuc120/
         cd -
    -    . ./setenv.sh
    -
    -If this is a Windows native build, then configure.bat should be used
    -instead of configure.sh:
    -
    -    configure.bat nutiny-nuc120\
     
     Where  is one of the following:
     
    diff --git a/configs/olimex-efm32g880f128-stk/README.txt b/configs/olimex-efm32g880f128-stk/README.txt
    index 9309a03976..6256fb8299 100644
    --- a/configs/olimex-efm32g880f128-stk/README.txt
    +++ b/configs/olimex-efm32g880f128-stk/README.txt
    @@ -137,12 +137,6 @@ Configurations
         cd tools
         ./configure.sh olimex-efm32g880f128-stk/
         cd -
    -    . ./setenv.sh
    -
    -  If this is a Windows native build, then configure.bat should be used
    -  instead of configure.sh:
    -
    -    configure.bat olimex-efm32g880f128-stk\
     
       Where  is one of the following:
     
    diff --git a/configs/olimex-lpc-h3131/README.txt b/configs/olimex-lpc-h3131/README.txt
    index f262ff93c7..e9f54bf84f 100644
    --- a/configs/olimex-lpc-h3131/README.txt
    +++ b/configs/olimex-lpc-h3131/README.txt
    @@ -55,9 +55,6 @@ GNU Toolchain Options
         CONFIG_ARM_TOOLCHAIN_GNU_EABIL        : Generic arm-none-eabi toolchain for Linux
         CONFIG_ARM_TOOLCHAIN_GNU_EABIW        : Generic arm-none-eabi toolchain for Windows
     
    -  If you are not using CONFIG_ARM_TOOLCHAIN_BUILDROOT, then you may also have to modify
    -  the PATH in the setenv.h file if your make cannot find the tools.
    -
       The toolchain may also be set using the kconfig-mconf utility (make menuconfig) or by
       passing CONFIG_ARM_TOOLCHAIN= to make, where  is one
       of CODESOURCERYW, CODESOURCERYL, DEVKITARM, BUILDROOT or GNU_EABI as described
    @@ -145,7 +142,7 @@ IDEs
     NuttX buildroot Toolchain
     =========================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -172,8 +169,8 @@ NuttX buildroot Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       detailed PLUS some special instructions that you will need to follow if you are
    @@ -260,17 +257,13 @@ Image Format
       - cd tools/                     # Configure Nuttx
       - ./configure.sh olimex-lpc-h3131/ostest  # (using the ostest configuration for this example)
       - cd ..                         # Set up environment
    -  - . ./setenv.sh                 # (see notes below)
       - make                          # Make NuttX.  This will produce nuttx.bin
       - mklpc.sh                      # Make the bootloader binary (nuttx.lpc)
     
       NOTES:
     
    -    1. setenv.sh just sets up pathes to the toolchain and also to
    -       configs/olimex-lpc-h3131/tools where mklpc.sh resides. Use of
    -       setenv.sh is optional.  If you don't use setenv.sh, then just set
    -       your PATH variable appropriately or use the full path to mklpc.sh
    -       in the final step.
    +    1. Make sure to set your PATH variable appropriately or use the full path
    +       to mklpc.sh in the final step.
         2. You can instruct Symantec to ignore the errors and it will stop
            quarantining the NXP program.
         3. The CRC32 logic in configs/olimex-lpc-h3131/tools doesn't seem to
    @@ -504,11 +497,9 @@ Configurations
         cd tools
         ./configure.sh olimex-lpc-h3131/
         cd -
    -    . ./setenv.sh
     
    -  Before sourcing the setenv.sh file above, you should examine it and perform
    -  edits as necessary so that TOOLCHAIN_BIN is the correct path to the directory
    -  than holds your toolchain binaries.
    +  Before building, make sure the PATH environment variable includes the
    +  correct path to the directory than holds your toolchain binaries.
     
       And then build NuttX by simply typing the following.  At the conclusion of
       the make, the nuttx binary will reside in an ELF file called, simply, nuttx.
    @@ -548,10 +539,6 @@ Configurations
          System Type -> Toolchain:
            CONFIG_ARM_TOOLCHAIN_GNU_EABIW=y : GNU EABI toolchain for windows
     
    -     The setenv.sh file is available for you to use to set the PATH
    -     variable.  The path in the that file may not, however, be correct
    -     for your installation.
    -
       Configuration sub-directories
       -----------------------------
     
    diff --git a/configs/olimex-lpc1766stk/README.txt b/configs/olimex-lpc1766stk/README.txt
    index 1a96d8582a..bf1d32b4f2 100644
    --- a/configs/olimex-lpc1766stk/README.txt
    +++ b/configs/olimex-lpc1766stk/README.txt
    @@ -191,9 +191,6 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_DEVKITARM=y       : devkitARM under Windows
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y       : NuttX buildroot under Linux or Cygwin (default)
     
    -  If you are not using CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT, then you may also have to modify
    -  the PATH in the setenv.h file if your make cannot find the tools.
    -
       NOTE: the CodeSourcery (for Windows)and devkitARM are Windows native toolchains.
       The CodeSourcey (for Linux) and NuttX buildroot toolchains are Cygwin and/or
       Linux native toolchains. There are several limitations to using a Windows based
    @@ -257,7 +254,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -284,8 +281,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you
    @@ -346,8 +343,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     LEDs
     ^^^^
    @@ -578,9 +575,8 @@ Using OpenOCD and GDB with an FT2232 JTAG emulator
     
           configs/olimex-lpc1766stk/tools/oocd.sh $PWD
     
    -    If you use the setenv.sh file, that the path to oocd.sh will be added
    -    to your PATH environment variabl.  So, in that case, the command simplifies
    -    to just:
    +    If you add the path to oocd.sh to your PATH environment variable,
    +    the command simplifies to just:
     
           oocd.sh $PWD
     
    @@ -869,7 +865,6 @@ Common Configuration Notes
            cd tools
            ./configure.sh olimex-lpc1766stk/
            cd -
    -       . ./setenv.sh
     
          Where  is one of the sub-directories identified in the following
          paragraphs.
    diff --git a/configs/olimex-stm32-p407/README.txt b/configs/olimex-stm32-p407/README.txt
    index 0302020f0b..0692ffc502 100644
    --- a/configs/olimex-stm32-p407/README.txt
    +++ b/configs/olimex-stm32-p407/README.txt
    @@ -241,14 +241,12 @@ selected as follow:
         cd tools
         ./configure.sh olimex-stm32-p407/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the configuration sub-directories listed in the
     following section.
     
    -Before sourcing the setenv.sh file above, you should examine it and perform
    -edits as necessary so that TOOLCHAIN_BIN is the correct path to the directory
    -than holds your toolchain binaries.
    +Before building, make sure the PATH environment variable includes the
    +correct path to the directory than holds your toolchain binaries.
     
     And then build NuttX by simply typing the following.  At the conclusion of
     the make, the nuttx binary will reside in an ELF file called, simply, nuttx.
    diff --git a/configs/olimex-strp711/README.txt b/configs/olimex-strp711/README.txt
    index f603457193..572c2c6d04 100644
    --- a/configs/olimex-strp711/README.txt
    +++ b/configs/olimex-strp711/README.txt
    @@ -164,7 +164,7 @@ GNU Toolchain Options
     NuttX buildroot Toolchain
     ^^^^^^^^^^^^^^^^^^^^^^^^^
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the ARM toolchain (if
       different from the default).
     
    @@ -190,8 +190,8 @@ NuttX buildroot Toolchain
     
       7. make
     
    -  8. Edit setenv.h so that the PATH variable includes the path to the
    -     newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
     Linux OpenOCD with Wiggler JTAG
     ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
    @@ -275,9 +275,8 @@ Windows OpenOCD will Olimex JTAG
         - If you are working under Linux you will need to change any
           occurances of `cygpath -w blablabla` to just blablabla
     
    -  The setenv.sh file includes some environment varialble settings
    -  that are needed by oocd.sh.  If you have $PATH and other environment
    -  variables set up, then you should be able to start the OpenOCD daemon like:
    +  If you have $PATH and other environment variables set up, then you should
    +  be able to start the OpenOCD daemon like:
     
         oocd.sh
     
    @@ -375,7 +374,6 @@ Common Configuration Notes:
            cd tools
            ./configure.sh olimex-strp711/
            cd -
    -       . ./setenv.sh
     
          Where  is one of the configuration sub-directories described in
          the following paragraph.
    diff --git a/configs/olimex-strp711/scripts/oocd.sh b/configs/olimex-strp711/scripts/oocd.sh
    index 33924c93d1..845f9da370 100755
    --- a/configs/olimex-strp711/scripts/oocd.sh
    +++ b/configs/olimex-strp711/scripts/oocd.sh
    @@ -19,7 +19,6 @@ fi
     if [ -z $STR41XSCRIPTS ]; then
     	echo "Environment variable $STR41XSCRIPTS is not defined"
     	echo "Has NuttX been configured?"
    -	echo "If so, try sourcing the setenv.sh script in the top-level directory"
     	exit 1
     fi
     
    diff --git a/configs/open1788/README.txt b/configs/open1788/README.txt
    index b8604d6346..5dfd0d98f0 100644
    --- a/configs/open1788/README.txt
    +++ b/configs/open1788/README.txt
    @@ -164,14 +164,13 @@ Using OpenOCD with the Olimex ARM-USB-OCD
       Starting OpenOCD
     
         Then you should be able to start the OpenOCD daemon as follows.  This
    -    assumes that you have already CD'ed to the NuttX build directory:
    +    assumes that you have already CD'ed to the NuttX build directory and
    +    that you have set the full path to the onfigs/open1788/tools in your
    +    PATH environment variable:
     
    -      . ./setenv.sh
           oocd.sh $PWD
     
    -    The setenv.sh script is a convenience script that you may choose to
    -    use or not.  It simply sets up the PATH variable so that you can
    -    automatically find oocd.sh.  You could also do:
    +    or, if the PATH variable is not so configured:
     
           configs/open1788/tools/oocd.sh $PWD
     
    diff --git a/configs/p112/ostest/setenv.bat b/configs/p112/ostest/setenv.bat
    deleted file mode 100644
    index 01eb774dd5..0000000000
    --- a/configs/p112/ostest/setenv.bat
    +++ /dev/null
    @@ -1,51 +0,0 @@
    -@echo off
    -
    -rem configs/p112/ostest/setenv.bat
    -rem
    -rem   Copyright (C) 2012, 2014 Gregory Nutt. All rights reserved.
    -rem   Author: Gregory Nutt 
    -rem
    -rem Redistribution and use in source and binary forms, with or without
    -rem modification, are permitted provided that the following conditions
    -rem are met:
    -rem
    -rem 1. Redistributions of source code must retain the above copyright
    -rem    notice, this list of conditions and the following disclaimer.
    -rem 2. Redistributions in binary form must reproduce the above copyright
    -rem    notice, this list of conditions and the following disclaimer in
    -rem    the documentation and/or other materials provided with the
    -rem    distribution.
    -rem 3. Neither the name NuttX nor the names of its contributors may be
    -rem    used to endorse or promote products derived from this software
    -rem    without specific prior written permission.
    -rem
    -rem THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
    -rem "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
    -rem LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
    -rem FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
    -rem COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
    -rem INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
    -rem BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
    -rem OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
    -rem AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
    -rem LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
    -rem ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
    -rem POSSIBILITY OF SUCH DAMAGE.
    -
    -rem This is the location where I installed in the MinGW compiler. With
    -rem this configuration, it is recommended that you do NOT install the
    -rem MSYS tools; they conflict with the GNUWin32 tools.  See
    -rem http://www.mingw.org/ for further info.
    -
    -set PATH=C:\MinGW\bin;%PATH%
    -
    -rem This is the location where I installed the SDCC toolchain for windows.
    -
    -rem set PATH=C:\Program Files (x86)\SDCC/bin;%PATH%
    -set PATH=C:\Program Files\SDCC/bin;%PATH%
    -
    -rem This is the location where I installed the GNUWin32 tools.  See
    -rem http://gnuwin32.sourceforge.net/.
    -
    -set PATH=C:\gnuwin32\bin;%PATH%
    -echo %PATH%
    diff --git a/configs/p112/scripts/setenv.bat b/configs/p112/scripts/setenv.bat
    deleted file mode 100644
    index dc214445f1..0000000000
    --- a/configs/p112/scripts/setenv.bat
    +++ /dev/null
    @@ -1,50 +0,0 @@
    -@echo off
    -
    -rem configs/p112/scripts/setenv.bat
    -rem
    -rem   Copyright (C) 2012 Gregory Nutt. All rights reserved.
    -rem   Author: Gregory Nutt 
    -rem
    -rem Redistribution and use in source and binary forms, with or without
    -rem modification, are permitted provided that the following conditions
    -rem are met:
    -rem
    -rem 1. Redistributions of source code must retain the above copyright
    -rem    notice, this list of conditions and the following disclaimer.
    -rem 2. Redistributions in binary form must reproduce the above copyright
    -rem    notice, this list of conditions and the following disclaimer in
    -rem    the documentation and/or other materials provided with the
    -rem    distribution.
    -rem 3. Neither the name NuttX nor the names of its contributors may be
    -rem    used to endorse or promote products derived from this software
    -rem    without specific prior written permission.
    -rem
    -rem THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
    -rem "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
    -rem LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
    -rem FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
    -rem COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
    -rem INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
    -rem BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
    -rem OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
    -rem AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
    -rem LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
    -rem ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
    -rem POSSIBILITY OF SUCH DAMAGE.
    -
    -rem This is the location where I installed in the MinGW compiler. With
    -rem this configuration, it is recommended that you do NOT install the
    -rem MSYS tools; they conflict with the GNUWin32 tools.  See
    -rem http://www.mingw.org/ for further info.
    -
    -set PATH=C:\MinGW\bin;%PATH%
    -
    -rem This is the location where I installed the SDCC toolchain for windows.
    -
    -set PATH=C:\Program Files (x86)\SDCC/bin;%PATH%
    -
    -rem This is the location where I installed the GNUWin32 tools.  See
    -rem http://gnuwin32.sourceforge.net/.
    -
    -set PATH=C:\gnuwin32\bin;%PATH%
    -echo %PATH%
    diff --git a/configs/pcblogic-pic32mx/README.txt b/configs/pcblogic-pic32mx/README.txt
    index c98882584b..777b5b9eaa 100644
    --- a/configs/pcblogic-pic32mx/README.txt
    +++ b/configs/pcblogic-pic32mx/README.txt
    @@ -316,8 +316,7 @@ Loading NuttX with PICkit2
     
         To use this file, you need to do the following things:
     
    -      . ./setenv.sh    # Source setenv.sh.  Among other this, this script
    -                       # will add the NuttX tools/pic32mx directory to your
    +      export PATH=???  # Add the NuttX tools/pic32mx directory to your
                            # PATH variable
           make             # Build nuttx and nuttx.hex
           mkpichex $PWD    # Convert addresses in nuttx.hex.  $PWD is the path
    @@ -554,7 +553,6 @@ Configurations
         cd tools
         ./configure.sh pcblogic-pic32mx/
         cd -
    -    . ./setenv.sh
     
       Where  is one of the following sub-directories.
     
    diff --git a/configs/pcduino-a10/README.txt b/configs/pcduino-a10/README.txt
    index b3c26c6267..6a68047dfd 100644
    --- a/configs/pcduino-a10/README.txt
    +++ b/configs/pcduino-a10/README.txt
    @@ -329,11 +329,9 @@ Configurations
         cd tools
         ./configure.sh pcduino-a10/
         cd -
    -    . ./setenv.sh
     
    -  Before sourcing the setenv.sh file above, you should examine it and perform
    -  edits as necessary so that TOOLCHAIN_BIN is the correct path to the directory
    -  than holds your toolchain binaries.
    +  Before building, make sure the PATH environment variable includes the
    +  correct path to the directory than holds your toolchain binaries.
     
       And then build NuttX by simply typing the following.  At the conclusion of
       the make, the nuttx binary will reside in an ELF file called, simply, nuttx.
    @@ -369,11 +367,6 @@ Configurations
          System Type -> Toolchain:
            CONFIG_ARMV7A_TOOLCHAIN_CODESOURCERYW=y : CodeSourcery for Windows
     
    -     The setenv.sh file is available for you to use to set the PATH
    -     variable.  The path in the that file may not, however, be correct
    -     for your installation.  Try 'which arm-none-eabi-gcc' to make sure that
    -     you are selecting the right tool.
    -
       Configuration Sub-directories
       -----------------------------
     
    diff --git a/configs/pic32mx-starterkit/README.txt b/configs/pic32mx-starterkit/README.txt
    index 6a9d766607..8f5bd3cdfa 100644
    --- a/configs/pic32mx-starterkit/README.txt
    +++ b/configs/pic32mx-starterkit/README.txt
    @@ -566,8 +566,7 @@ Creating Compatible NuttX HEX files
     
         To use this file, you need to do the following things:
     
    -      . ./setenv.sh    # Source setenv.sh.  Among other this, this script
    -                       # will add the NuttX tools/pic32mx directory to your
    +      export PATH=???  # Add the NuttX tools/pic32mx directory to your
                            # PATH variable
           make             # Build nuttx and nuttx.hex
           mkpichex $PWD    #  Convert addresses in nuttx.hex.  $PWD is the path
    @@ -1019,7 +1018,6 @@ selected as follow:
         cd tools
         ./configure.sh pic32mx-starterkit/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    diff --git a/configs/pic32mx7mmb/README.txt b/configs/pic32mx7mmb/README.txt
    index 9167670fdb..b3b5d7400d 100644
    --- a/configs/pic32mx7mmb/README.txt
    +++ b/configs/pic32mx7mmb/README.txt
    @@ -301,8 +301,7 @@ Creating Compatible NuttX HEX files
     
         To use this file, you need to do the following things:
     
    -      . ./setenv.sh    # Source setenv.sh.  Among other this, this script
    -                       # will add the NuttX tools/pic32mx directory to your
    +      export PATH=???  # Add the NuttX tools/pic32mx directory to your
                            # PATH variable
           make             # Build nuttx and nuttx.hex
           mkpichex $PWD    #  Convert addresses in nuttx.hex.  $PWD is the path
    @@ -597,7 +596,6 @@ selected as follow:
         cd tools
         ./configure.sh pic32mx7mmb/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    diff --git a/configs/pic32mz-starterkit/README.txt b/configs/pic32mz-starterkit/README.txt
    index 4166a4728f..567bcde739 100644
    --- a/configs/pic32mz-starterkit/README.txt
    +++ b/configs/pic32mz-starterkit/README.txt
    @@ -121,8 +121,7 @@ Creating Compatible NuttX HEX files
     
         To use this file, you need to do the following things:
     
    -      . ./setenv.sh    # Source setenv.sh.  Among other this, this script
    -                       # will add the NuttX tools/pic32mx directory to your
    +      export PATH=???  # Add the NuttX tools/pic32mx directory to your
                            # PATH variable
           make             # Build nuttx and nuttx.hex
           mkpichex $PWD    #  Convert addresses in nuttx.hex.  $PWD is the path
    @@ -364,7 +363,6 @@ selected as follow:
         cd tools
         ./configure.sh pic32mz-starterkit/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    diff --git a/configs/qemu-i486/README.txt b/configs/qemu-i486/README.txt
    index c91270f568..bcc0da5ef4 100644
    --- a/configs/qemu-i486/README.txt
    +++ b/configs/qemu-i486/README.txt
    @@ -99,9 +99,8 @@ Toolchains
         suspect that this was not necessary, but it was a simple work-around
         that allowed that person to build a work-able system.
     
    -  In any event, the file */setenv.sh should be modified to point to the correct
    -  path to the GCC toolchain (if different from the default in your PATH
    -  variable).
    +  In any event, the PATH environment variable should be modified to point to
    +  the correct path to the GCC toolchain.
     
     Cygwin Buildroot Toolchain
     --------------------------
    @@ -136,8 +135,8 @@ Buildroot Instructions
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       detailed PLUS some special instructions that you will need to follow if you
    @@ -165,7 +164,6 @@ Common Configuration Notes
            cd tools
            ./configure.sh qemu-i486/
            cd -
    -       . ./setenv.sh
     
          Where  is one of the configuration sub-directories described in
          the following paragraph.
    diff --git a/configs/sabre-6quad/README.txt b/configs/sabre-6quad/README.txt
    index a9703e5a28..bff618371e 100644
    --- a/configs/sabre-6quad/README.txt
    +++ b/configs/sabre-6quad/README.txt
    @@ -582,11 +582,9 @@ can be selected as follow:
       cd tools
       ./configure.sh sabre-6quad/
       cd -
    -  . ./setenv.sh
     
    -Before sourcing the setenv.sh file above, you should examine it and perform
    -edits as necessary so that TOOLCHAIN_BIN is the correct path to the directory
    -than holds your toolchain binaries.
    +Before building, make sure the PATH environment variable includes the
    +correct path to the directory than holds your toolchain binaries.
     
     And then build NuttX by simply typing the following.  At the conclusion of
     the make, the nuttx binary will reside in an ELF file called, simply, nuttx.
    diff --git a/configs/sam3u-ek/README.txt b/configs/sam3u-ek/README.txt
    index 4c7f513757..f210f1a7cc 100644
    --- a/configs/sam3u-ek/README.txt
    +++ b/configs/sam3u-ek/README.txt
    @@ -43,9 +43,6 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL=y      : Generic GCC ARM EABI toolchain for Linux
         CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIW=y      : Generic GCC ARM EABI toolchain for Windows
     
    -  You may also have to modify the PATH in the setenv.h file if your make cannot
    -  find the tools.
    -
       NOTE about Windows native toolchains
       ------------------------------------
     
    @@ -115,7 +112,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -142,8 +139,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you are
    @@ -204,8 +201,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     AtmelStudio6.1
     ^^^^^^^^^^^^^^
    @@ -408,11 +405,9 @@ Configurations
         cd tools
         ./configure.sh sam3u-ek/
         cd -
    -    . ./setenv.sh
     
    -  Before sourcing the setenv.sh file above, you should examine it and perform
    -  edits as necessary so that BUILDROOT_BIN is the correct path to the directory
    -  than holds your toolchain binaries.
    +  Before building, make sure the PATH environment variable includes the
    +  correct path to the directory than holds your toolchain binaries.
     
       And then build NuttX by simply typing the following.  At the conclusion of
       the make, the nuttx binary will reside in an ELF file called, simply, nuttx.
    @@ -476,9 +471,7 @@ Configurations
     
          Also, make sure that your PATH variable has the new path to your
          Atmel tools.  Try 'which arm-none-eabi-gcc' to make sure that you
    -     are selecting the right tool.  setenv.sh is available for you to
    -     use to set or PATH variable.  The path in the that file may not,
    -     however, be correct for your installation.
    +     are selecting the right tool.
     
          See also the "NOTE about Windows native toolchains" in the section call
          "GNU Toolchain Options" above.
    @@ -699,16 +692,9 @@ Configurations
         2. Make the build context (only)
     
            $ cd ..
    -       $ . ./setenv.sh
            $ make context
            ...
     
    -       NOTE: the use of the setenv.sh file is optional.  All that it will
    -       do is to adjust your PATH variable so that the build system can find
    -       your tools.  If you use it, you will most likely need to modify the
    -       script so that it has the correct path to your tool binaries
    -       directory.
    -
         3. Install the nxwm unit test
     
            $ cd ~/nuttx-git/NxWidgets
    diff --git a/configs/sam4e-ek/README.txt b/configs/sam4e-ek/README.txt
    index 5f04cb5db4..aaf19d51c4 100644
    --- a/configs/sam4e-ek/README.txt
    +++ b/configs/sam4e-ek/README.txt
    @@ -53,9 +53,6 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL=y      : Generic GCC ARM EABI toolchain for Linux
         CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIW=y      : Generic GCC ARM EABI toolchain for Windows
     
    -  You may also have to modify the PATH in the setenv.h file if your
    -  make cannot find the tools.
    -
       NOTE about Windows native toolchains
       ------------------------------------
     
    @@ -121,7 +118,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ================================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -148,8 +145,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you are
    @@ -210,8 +207,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     Atmel Studio 6.1
     ================
    @@ -1230,11 +1227,9 @@ Configurations
         cd tools
         ./configure.sh sam4e-ek/
         cd -
    -    . ./setenv.sh
     
    -  Before sourcing the setenv.sh file above, you should examine it and perform
    -  edits as necessary so that TOOLCHAIN_BIN is the correct path to the directory
    -  than holds your toolchain binaries.
    +  Before building, make sure the PATH environment variable includes the
    +  correct path to the directory than holds your toolchain binaries.
     
       And then build NuttX by simply typing the following.  At the conclusion of
       the make, the nuttx binary will reside in an ELF file called, simply, nuttx.
    @@ -1292,9 +1287,7 @@ Configurations
     
          Also, make sure that your PATH variable has the new path to your
          Atmel tools.  Try 'which arm-none-eabi-gcc' to make sure that you
    -     are selecting the right tool.  setenv.sh is available for you to
    -     use to set or PATH variable.  The path in the that file may not,
    -     however, be correct for your installation.
    +     are selecting the right tool.
     
          See also the "NOTE about Windows native toolchains" in the section call
          "GNU Toolchain Options" above.
    @@ -1625,16 +1618,9 @@ Configurations
         2. Make the build context (only)
     
            $ cd ..
    -       $ . ./setenv.sh
            $ make context
            ...
     
    -       NOTE: the use of the setenv.sh file is optional.  All that it will
    -       do is to adjust your PATH variable so that the build system can find
    -       your tools.  If you use it, you will most likely need to modify the
    -       script so that it has the correct path to your tool binaries
    -       directory.
    -
         3. Install the nxwm unit test
     
            $ cd ~/nuttx-git/NxWidgets
    diff --git a/configs/sam4l-xplained/README.txt b/configs/sam4l-xplained/README.txt
    index a52b8ae8c4..088db6a64e 100644
    --- a/configs/sam4l-xplained/README.txt
    +++ b/configs/sam4l-xplained/README.txt
    @@ -211,9 +211,6 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL=y      : Generic GCC ARM EABI toolchain for Linux
         CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIW=y      : Generic GCC ARM EABI toolchain for Windows
     
    -  If you are not using CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT, then you may also
    -  have to modify the PATH in the setenv.h file if your make cannot find the tools.
    -
       NOTE about Windows native toolchains
       ------------------------------------
     
    @@ -283,7 +280,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -310,8 +307,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you are
    @@ -372,8 +369,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     LEDs
     ^^^^
    @@ -593,11 +590,9 @@ Configurations
         cd tools
         ./configure.sh sam4l-xplained/
         cd -
    -    . ./setenv.sh
     
    -  Before sourcing the setenv.sh file above, you should examine it and perform
    -  edits as necessary so that BUILDROOT_BIN is the correct path to the directory
    -  than holds your toolchain binaries.
    +  Before building, make sure the PATH environment variable includes the
    +  correct path to the directory than holds your toolchain binaries.
     
       And then build NuttX by simply typing the following.  At the conclusion of
       the make, the nuttx binary will reside in an ELF file called, simply, nuttx.
    @@ -680,9 +675,7 @@ Configurations
     
          Also, make sure that your PATH variable has the new path to your
          Atmel tools.  Try 'which arm-none-eabi-gcc' to make sure that you
    -     are selecting the right tool.  setenv.sh is available for you to
    -     use to set or PATH variable.  The path in the that file may not,
    -     however, be correct for your installation.
    +     are selecting the right tool.
     
          See also the "NOTE about Windows native toolchains" in the section call
          "GNU Toolchain Options" above.
    diff --git a/configs/sam4s-xplained-pro/README.txt b/configs/sam4s-xplained-pro/README.txt
    index 83f19be929..6747d99f29 100644
    --- a/configs/sam4s-xplained-pro/README.txt
    +++ b/configs/sam4s-xplained-pro/README.txt
    @@ -104,7 +104,7 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIW=y      : Generic GCC ARM EABI toolchain for Windows
     
       If you are not using CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT, then you may also
    -  have to modify the PATH in the setenv.h file if your make cannot find the
    +  have to modify the PATH environment variable  if your make cannot find the
       tools.
     
       NOTE about Windows native toolchains
    @@ -177,7 +177,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -204,8 +204,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you are
    @@ -266,15 +266,14 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     Buttons and LEDs
     ^^^^^^^^^^^^^^^^
     
       Buttons
       -------
    -
       The SAM4S Xplained has two mechanical buttons. One button is the RESET button
       connected to the SAM4S reset line and the other is a generic user configurable
       button labeled BP2 and connected to GPIO PA5. When a button is pressed it
    @@ -282,7 +281,6 @@ Buttons and LEDs
     
       LEDs
       ----
    -=======================
       There is one LED on board the SAM4S Xplained board Pro that can be
       controlled by software in the SAM4S:
     
    @@ -491,11 +489,9 @@ Configurations
         cd tools
         ./configure.shsam4s-xplained-pro/
         cd -
    -    . ./setenv.sh
     
    -  Before sourcing the setenv.sh file above, you should examine it and perform
    -  edits as necessary so that BUILDROOT_BIN is the correct path to the directory
    -  than holds your toolchain binaries.
    +  Before building, make sure the PATH environment variable includes the
    +  correct path to the directory than holds your toolchain binaries.
     
       And then build NuttX by simply typing the following.  At the conclusion of
       the make, the nuttx binary will reside in an ELF file called, simply, nuttx.
    @@ -569,9 +565,7 @@ Configurations
     
          Also, make sure that your PATH variable has the new path to your
          Atmel tools.  Try 'which arm-none-eabi-gcc' to make sure that you
    -     are selecting the right tool.  setenv.sh is available for you to
    -     use to set or PATH variable.  The path in the that file may not,
    -     however, be correct for your installation.
    +     are selecting the right tool.
     
          See also the "NOTE about Windows native toolchains" in the section call
          "GNU Toolchain Options" above.
    diff --git a/configs/sam4s-xplained/README.txt b/configs/sam4s-xplained/README.txt
    index d5af219e24..6aab73ec5b 100644
    --- a/configs/sam4s-xplained/README.txt
    +++ b/configs/sam4s-xplained/README.txt
    @@ -103,10 +103,6 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL=y      : Generic GCC ARM EABI toolchain for Linux
         CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIW=y      : Generic GCC ARM EABI toolchain for Windows
     
    -  If you are not using CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT, then you may also
    -  have to modify the PATH in the setenv.h file if your make cannot find the
    -  tools.
    -
       NOTE about Windows native toolchains
       ------------------------------------
     
    @@ -176,7 +172,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -203,8 +199,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you are
    @@ -265,8 +261,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     Buttons and LEDs
     ^^^^^^^^^^^^^^^^
    @@ -483,11 +479,9 @@ Configurations
         cd tools
         ./configure.shsam4s-xplained/
         cd -
    -    . ./setenv.sh
     
    -  Before sourcing the setenv.sh file above, you should examine it and perform
    -  edits as necessary so that BUILDROOT_BIN is the correct path to the directory
    -  than holds your toolchain binaries.
    +  Before building, make sure the PATH environment variable includes the
    +  correct path to the directory than holds your toolchain binaries.
     
       And then build NuttX by simply typing the following.  At the conclusion of
       the make, the nuttx binary will reside in an ELF file called, simply, nuttx.
    @@ -561,9 +555,7 @@ Configurations
     
          Also, make sure that your PATH variable has the new path to your
          Atmel tools.  Try 'which arm-none-eabi-gcc' to make sure that you
    -     are selecting the right tool.  setenv.sh is available for you to
    -     use to set or PATH variable.  The path in the that file may not,
    -     however, be correct for your installation.
    +     are selecting the right tool.
     
          See also the "NOTE about Windows native toolchains" in the section call
          "GNU Toolchain Options" above.
    diff --git a/configs/sama5d2-xult/README.txt b/configs/sama5d2-xult/README.txt
    index 8f11cc1db5..cb48cc0a29 100644
    --- a/configs/sama5d2-xult/README.txt
    +++ b/configs/sama5d2-xult/README.txt
    @@ -77,11 +77,9 @@ REVISIT: Unverified, cloned text from the SAMA5D4-EK README.txt
            cd tools
            ./configure.sh sama5d2-xult/dramboot
            cd -
    -       . ./setenv.sh
     
    -     Before sourcing the setenv.sh file above, you should examine it and
    -     perform edits as necessary so that TOOLCHAIN_BIN is the correct path
    -     to the directory than holds your toolchain binaries.
    +     Before building, make sure the PATH environment variable includes the
    +     correct path to the directory than holds your toolchain binaries.
     
          NOTE:  Be aware that the default dramboot also disables the watchdog.
          Since you will not be able to re-enable the watchdog later, you may
    @@ -185,11 +183,9 @@ REVISIT: Unverified, cloned text from the SAMA5D4-EK README.txt
            cd tools
            ./configure.sh sama5d2-xult/at25boot
            cd -
    -       . ./setenv.sh
     
    -     Before sourcing the setenv.sh file above, you should examine it and
    -     perform edits as necessary so that TOOLCHAIN_BIN is the correct path
    -     to the directory than holds your toolchain binaries.
    +     Before building, make sure the PATH environment variable includes the
    +     correct path to the directory than holds your toolchain binaries.
     
          Then make AT25BOOT:
     
    @@ -916,11 +912,9 @@ Configurations
         cd tools
         ./configure.sh sama5d2-xult/
         cd -
    -    . ./setenv.sh
     
    -  Before sourcing the setenv.sh file above, you should examine it and perform
    -  edits as necessary so that TOOLCHAIN_BIN is the correct path to the directory
    -  than holds your toolchain binaries.
    +  Before building, make sure the PATH environment variable includes the
    +  correct path to the directory than holds your toolchain binaries.
     
       And then build NuttX by simply typing the following.  At the conclusion of
       the make, the nuttx binary will reside in an ELF file called, simply, nuttx.
    @@ -962,10 +956,6 @@ Configurations
          tools.  Try 'which arm-none-eabi-gcc' to make sure that you are
          selecting the right tool.
     
    -     The setenv.sh file is available for you to use to set the PATH
    -     variable.  The path in the that file may not, however, be correct
    -     for your installation.
    -
          See also the "NOTE about Windows native toolchains" in the section call
          "GNU Toolchain Options" above.
     
    diff --git a/configs/sama5d3-xplained/README.txt b/configs/sama5d3-xplained/README.txt
    index 89610babed..a124cd728f 100644
    --- a/configs/sama5d3-xplained/README.txt
    +++ b/configs/sama5d3-xplained/README.txt
    @@ -179,7 +179,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ================================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -220,8 +220,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you are
    @@ -257,8 +257,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built NXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
       NOTE:  There are some known incompatibilities with 4.6.3 EABI toolchain
       and the NXFLAT tools.  See the top-level TODO file (under "Binary
    @@ -2981,11 +2981,9 @@ Configurations
         cd tools
         ./configure.sh sama5d3-xplained/
         cd -
    -    . ./setenv.sh
     
    -  Before sourcing the setenv.sh file above, you should examine it and perform
    -  edits as necessary so that TOOLCHAIN_BIN is the correct path to the directory
    -  than holds your toolchain binaries.
    +  Before building, make sure that the PATH environment variable include the
    +  correct path to the directory than holds your toolchain binaries.
     
       And then build NuttX by simply typing the following.  At the conclusion of
       the make, the nuttx binary will reside in an ELF file called, simply, nuttx.
    @@ -3027,10 +3025,6 @@ Configurations
          tools.  Try 'which arm-none-eabi-gcc' to make sure that you are
          selecting the right tool.
     
    -     The setenv.sh file is available for you to use to set the PATH
    -     variable.  The path in the that file may not, however, be correct
    -     for your installation.
    -
          See also the "NOTE about Windows native toolchains" in the section call
          "GNU Toolchain Options" above.
     
    diff --git a/configs/sama5d3x-ek/README.txt b/configs/sama5d3x-ek/README.txt
    index 73d3ef0b94..1fa017aaf7 100644
    --- a/configs/sama5d3x-ek/README.txt
    +++ b/configs/sama5d3x-ek/README.txt
    @@ -201,7 +201,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ================================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -242,8 +242,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you are
    @@ -279,8 +279,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built NXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
       NOTE:  There are some known incompatibilities with 4.6.3 EABI toolchain
       and the NXFLAT tools.  See the top-level TODO file (under "Binary
    @@ -372,11 +372,9 @@ Creating and Using NORBOOT
            cd tools
            ./configure.sh sama5d3x-ek/
            cd -
    -       . ./setenv.sh
     
    -     Before sourcing the setenv.sh file above, you should examine it and
    -     perform edits as necessary so that TOOLCHAIN_BIN is the correct path
    -     to the directory than holds your toolchain binaries.
    +     Before building, make sure the PATH environment variable includes the
    +     correct path to the directory than holds your toolchain binaries.
     
          NOTE:  Be aware that the default norboot also disables the watchdog.
          Since you will not be able to re-enable the watchdog later, you may
    @@ -3306,11 +3304,9 @@ Configurations
         cd tools
         ./configure.sh sama5d3x-ek/
         cd -
    -    . ./setenv.sh
     
    -  Before sourcing the setenv.sh file above, you should examine it and perform
    -  edits as necessary so that TOOLCHAIN_BIN is the correct path to the directory
    -  than holds your toolchain binaries.
    +  Before building, make sure the PATH environment variable includes the
    +  correct path to the directory than holds your toolchain binaries.
     
       And then build NuttX by simply typing the following.  At the conclusion of
       the make, the nuttx binary will reside in an ELF file called, simply, nuttx.
    @@ -3352,10 +3348,6 @@ Configurations
          tools.  Try 'which arm-none-eabi-gcc' to make sure that you are
          selecting the right tool.
     
    -     The setenv.sh file is available for you to use to set the PATH
    -     variable.  The path in the that file may not, however, be correct
    -     for your installation.
    -
          See also the "NOTE about Windows native toolchains" in the section call
          "GNU Toolchain Options" above.
     
    @@ -3805,16 +3797,9 @@ Configurations
         2. Make the build context (only)
     
            $ cd ..
    -       $ . ./setenv.sh
            $ make context
            ...
     
    -       NOTE: the use of the setenv.sh file is optional.  All that it will
    -       do is to adjust your PATH variable so that the build system can find
    -       your tools.  If you use it, you will most likely need to modify the
    -       script so that it has the correct path to your tool binaries
    -       directory.
    -
         3. Install the nxwm unit test
     
            $ cd ~/nuttx-git/NxWidgets
    diff --git a/configs/sama5d4-ek/README.txt b/configs/sama5d4-ek/README.txt
    index eec9b59510..bff91b7a06 100644
    --- a/configs/sama5d4-ek/README.txt
    +++ b/configs/sama5d4-ek/README.txt
    @@ -195,7 +195,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ================================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -236,8 +236,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you are
    @@ -273,8 +273,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built NXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
       NOTE:  There are some known incompatibilities with 4.6.3 EABI toolchain
       and the NXFLAT tools.  See the top-level TODO file (under "Binary
    @@ -359,11 +359,9 @@ Creating and Using DRAMBOOT
            cd tools
            ./configure.sh sama5d4-ek/dramboot
            cd -
    -       . ./setenv.sh
    -
    -     Before sourcing the setenv.sh file above, you should examine it and
    -     perform edits as necessary so that TOOLCHAIN_BIN is the correct path
    -     to the directory than holds your toolchain binaries.
    + 
    +     Before building, make sure that the PATH environment variable includes
    +     the correct path  to the directory than holds your toolchain binaries.
     
          NOTE:  Be aware that the default dramboot also disables the watchdog.
          Since you will not be able to re-enable the watchdog later, you may
    @@ -466,11 +464,9 @@ Creating and Using AT25BOOT
            cd tools
            ./configure.sh sama5d4-ek/at25boot
            cd -
    -       . ./setenv.sh
     
    -     Before sourcing the setenv.sh file above, you should examine it and
    -     perform edits as necessary so that TOOLCHAIN_BIN is the correct path
    -     to the directory than holds your toolchain binaries.
    +     Before building, make sure that the PATH environment variable includes
    +     the correct path  to the directory than holds your toolchain binaries.
     
          Then make AT25BOOT:
     
    @@ -3592,11 +3588,9 @@ Configurations
         cd tools
         ./configure.sh sama5d4-ek/
         cd -
    -    . ./setenv.sh
     
    -  Before sourcing the setenv.sh file above, you should examine it and perform
    -  edits as necessary so that TOOLCHAIN_BIN is the correct path to the directory
    -  than holds your toolchain binaries.
    +  Before building, make sure that the PATH environment variable includes
    +  the correct path  to the directory than holds your toolchain binaries.
     
       And then build NuttX by simply typing the following.  At the conclusion of
       the make, the nuttx binary will reside in an ELF file called, simply, nuttx.
    @@ -3638,10 +3632,6 @@ Configurations
          tools.  Try 'which arm-none-eabi-gcc' to make sure that you are
          selecting the right tool.
     
    -     The setenv.sh file is available for you to use to set the PATH
    -     variable.  The path in the that file may not, however, be correct
    -     for your installation.
    -
          See also the "NOTE about Windows native toolchains" in the section call
          "GNU Toolchain Options" above.
     
    @@ -4165,8 +4155,7 @@ Configurations
             $ cd nuttx/tools                    : Go to the tools sub-directory
             $ ./configure.sh sama5d4-ek/kernel  : Establish this configuration
             $ cd ..                             : Back to the NuttX build directory
    -                                            : Edit setenv.sh to use the correct path
    -        $ . ./setenv.sh                     : Set up the PATH variable
    +        $ export PATH=???:$PATH             : Set up the PATH variable
             $ make                              : Build the kerne with a dummy ROMFS image
                                                 : This should create the nuttx ELF
             $ make export                       : Create the kernel export package
    @@ -4184,8 +4173,7 @@ Configurations
             $ cd nuttx/tools                    : Go to the tools sub-directory
             $ ./configure.sh sama5d4-ek/kernel  : Establish this configuration
             $ cd ..                             : Back to the NuttX build directory
    -                                            : Edit setenv.sh to use the correct path
    -        $ . ./setenv.sh                     : Set up the PATH variable
    +        $ export PATH=???:$PATH             : Set up the PATH variable
             $ touch configs/sama5d4-ek/include/boot_romfsimg.h
             $ make                              : Build the kernel with a dummy ROMFS image
                                                 : This should create the nuttx ELF
    @@ -4770,16 +4758,9 @@ Configurations
             b. Make the build context (only)
     
                $ cd ..
    -           $ . ./setenv.sh
                $ make context
                ...
     
    -           NOTE: the use of the setenv.sh file is optional.  All that it
    -           will do is to adjust your PATH variable so that the build system
    -           can find your tools.  If you use it, you will most likely need to
    -           modify the script so that it has the correct path to your tool
    -           binary directory.
    -
             c. Install the nxwm unit test
     
                $ cd ~/nuttx-git/NxWidgets
    diff --git a/configs/samd20-xplained/README.txt b/configs/samd20-xplained/README.txt
    index f489d6b618..d79a298b69 100644
    --- a/configs/samd20-xplained/README.txt
    +++ b/configs/samd20-xplained/README.txt
    @@ -291,9 +291,6 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL=y      : Generic GCC ARM EABI toolchain for Linux
         CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIW=y      : Generic GCC ARM EABI toolchain for Windows
     
    -  You may also have to modify the PATH in the setenv.h file if your
    -  make cannot find the tools.
    -
       NOTE about Windows native toolchains
       ------------------------------------
     
    @@ -359,7 +356,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ================================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M0 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -386,8 +383,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you are
    @@ -604,11 +601,9 @@ Configurations
         cd tools
         ./configure.sh samd20-xplained/
         cd -
    -    . ./setenv.sh
     
    -  Before sourcing the setenv.sh file above, you should examine it and perform
    -  edits as necessary so that BUILDROOT_BIN is the correct path to the directory
    -  than holds your toolchain binaries.
    +  Before building, make sure that the PATH environment variable include the
    +  correct path to the directory than holds your toolchain binaries.
     
       And then build NuttX by simply typing the following.  At the conclusion of
       the make, the nuttx binary will reside in an ELF file called, simply, nuttx.
    @@ -695,9 +690,7 @@ Configurations
     
          Also, make sure that your PATH variable has the new path to your
          Atmel tools.  Try 'which arm-none-eabi-gcc' to make sure that you
    -     are selecting the right tool.  setenv.sh is available for you to
    -     use to set or PATH variable.  The path in the that file may not,
    -     however, be correct for your installation.
    +     are selecting the right tool.
     
          See also the "NOTE about Windows native toolchains" in the section
          called "GNU Toolchain Options" above.
    diff --git a/configs/samd21-xplained/README.txt b/configs/samd21-xplained/README.txt
    index c000821cb3..6ac8fafe39 100644
    --- a/configs/samd21-xplained/README.txt
    +++ b/configs/samd21-xplained/README.txt
    @@ -466,11 +466,9 @@ Configurations
         cd tools
         ./configure.sh samd21-xplained/
         cd -
    -    . ./setenv.sh
     
    -  Before sourcing the setenv.sh file above, you should examine it and perform
    -  edits as necessary so that BUILDROOT_BIN is the correct path to the directory
    -  than holds your toolchain binaries.
    +  Before building, make sure the the PATH environment varaible include the
    +  correct path to the directory than holds your toolchain binaries.
     
       And then build NuttX by simply typing the following.  At the conclusion of
       the make, the nuttx binary will reside in an ELF file called, simply, nuttx.
    @@ -557,9 +555,7 @@ Configurations
     
          Also, make sure that your PATH variable has the new path to your
          Atmel tools.  Try 'which arm-none-eabi-gcc' to make sure that you
    -     are selecting the right tool.  setenv.sh is available for you to
    -     use to set or PATH variable.  The path in the that file may not,
    -     however, be correct for your installation.
    +     are selecting the right tool.
     
          See also the "NOTE about Windows native toolchains" in the section
          called "GNU Toolchain Options" above.
    diff --git a/configs/same70-xplained/README.txt b/configs/same70-xplained/README.txt
    index c95eef6e1b..1b10b484b0 100644
    --- a/configs/same70-xplained/README.txt
    +++ b/configs/same70-xplained/README.txt
    @@ -1099,11 +1099,9 @@ can be selected as follow:
       cd tools
       ./configure.sh same70-xplained/
       cd -
    -  . ./setenv.sh
     
    -Before sourcing the setenv.sh file above, you should examine it and perform
    -edits as necessary so that TOOLCHAIN_BIN is the correct path to the directory
    -than holds your toolchain binaries.
    +Before building, make sure that the PATH environment variable include the
    +correct path to the directory than holds your toolchain binaries.
     
     And then build NuttX by simply typing the following.  At the conclusion of
     the make, the nuttx binary will reside in an ELF file called, simply, nuttx.
    @@ -1166,11 +1164,6 @@ NOTES:
          for the Cortex-M7, but is supported by at least this realeasse of
          the ARM GNU tools:
     
    -       https://launchpadlibrarian.net/192228215/release.txt
    -
    -     Current (2105-07-31) setenv.sh file are configured to use this
    -     release:
    -
            https://launchpadlibrarian.net/209776344/release.txt
     
          That toolchain selection can easily be reconfigured using
    diff --git a/configs/saml21-xplained/README.txt b/configs/saml21-xplained/README.txt
    index 673b9e43b2..c55ff4fab8 100644
    --- a/configs/saml21-xplained/README.txt
    +++ b/configs/saml21-xplained/README.txt
    @@ -272,9 +272,6 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL=y      : Generic GCC ARM EABI toolchain for Linux
         CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIW=y      : Generic GCC ARM EABI toolchain for Windows
     
    -  You may also have to modify the PATH in the setenv.h file if your
    -  make cannot find the tools.
    -
       NOTE about Windows native toolchains
       ------------------------------------
     
    @@ -340,7 +337,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ================================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M0 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -367,8 +364,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you are
    @@ -642,11 +639,9 @@ Configurations
         cd tools
         ./configure.sh saml21-xplained/
         cd -
    -    . ./setenv.sh
     
    -  Before sourcing the setenv.sh file above, you should examine it and perform
    -  edits as necessary so that BUILDROOT_BIN is the correct path to the directory
    -  than holds your toolchain binaries.
    +  Before building, make sure that the PATH environmental variable includes the
    +  correct path to the directory than holds your toolchain binaries.
     
       And then build NuttX by simply typing the following.  At the conclusion of
       the make, the nuttx binary will reside in an ELF file called, simply, nuttx.
    @@ -724,9 +719,7 @@ Configurations
     
          Also, make sure that your PATH variable has the new path to your
          Atmel tools.  Try 'which arm-none-eabi-gcc' to make sure that you
    -     are selecting the right tool.  setenv.sh is available for you to
    -     use to set or PATH variable.  The path in the that file may not,
    -     however, be correct for your installation.
    +     are selecting the right tool.
     
          See also the "NOTE about Windows native toolchains" in the section
          called "GNU Toolchain Options" above.
    diff --git a/configs/samv71-xult/README.txt b/configs/samv71-xult/README.txt
    index c963851259..182b0cc99a 100644
    --- a/configs/samv71-xult/README.txt
    +++ b/configs/samv71-xult/README.txt
    @@ -1597,11 +1597,9 @@ can be selected as follow:
       cd tools
       ./configure.sh samv71-xult/
       cd -
    -  . ./setenv.sh
     
    -Before sourcing the setenv.sh file above, you should examine it and perform
    -edits as necessary so that TOOLCHAIN_BIN is the correct path to the directory
    -than holds your toolchain binaries.
    +Before building, make sure the the PATH environment variable include the
    +correct path to the directory than holds your toolchain binaries.
     
     And then build NuttX by simply typing the following.  At the conclusion of
     the make, the nuttx binary will reside in an ELF file called, simply, nuttx.
    @@ -1636,11 +1634,6 @@ NOTES:
          for the Cortex-M7, but is supported by at least this realeasse of
          the ARM GNU tools:
     
    -       https://launchpadlibrarian.net/192228215/release.txt
    -
    -     Current (2105-07-31) setenv.sh file are configured to use this
    -     release:
    -
            https://launchpadlibrarian.net/209776344/release.txt
     
          That toolchain selection can easily be reconfigured using
    @@ -2237,16 +2230,9 @@ Configuration sub-directories
            b. Make the build context (only)
     
               $ cd ..
    -          $ . ./setenv.sh
               $ make context
               ...
     
    -          NOTE: the use of the setenv.sh file is optional.  All that it will
    -          do is to adjust your PATH variable so that the build system can find
    -          your tools.  If you use it, you will most likely need to modify the
    -          script so that it has the correct path to your tool binaries
    -          directory.
    -
            c. Install the nxwm unit test
     
               $ cd HOME/NxWidgets
    @@ -2427,16 +2413,9 @@ Configuration sub-directories
            b. Make the build context (only)
     
               $ cd ..
    -          $ . ./setenv.sh
               $ make context
               ...
     
    -          NOTE: the use of the setenv.sh file is optional.  All that it will
    -          do is to adjust your PATH variable so that the build system can find
    -          your tools.  If you use it, you will most likely need to modify the
    -          script so that it has the correct path to your tool binaries
    -          directory.
    -
            c. Install the nxwm unit test
     
               $ cd HOME/NxWidgets
    diff --git a/configs/shenzhou/README.txt b/configs/shenzhou/README.txt
    index 1eeedcd252..2fb9dd6eec 100644
    --- a/configs/shenzhou/README.txt
    +++ b/configs/shenzhou/README.txt
    @@ -219,9 +219,6 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_RAISONANCE=y     : Raisonance RIDE7 under Windows
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y      : NuttX buildroot under Linux or Cygwin (default)
     
    -  If you change the default toolchain, then you may also have to modify the PATH in
    -  the setenv.h file if your make cannot find the tools.
    -
       NOTE: the CodeSourcery (for Windows), Atollic, devkitARM, and Raisonance toolchains are
       Windows native toolchains.  The CodeSourcery (for Linux) and NuttX buildroot
       toolchains are Cygwin and/or Linux native toolchains. There are several limitations
    @@ -321,7 +318,7 @@ IDEs
     NuttX EABI buildroot Toolchain
     ==============================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -357,14 +354,7 @@ NuttX EABI buildroot Toolchain
          -CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYW=y
          +CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y
     
    -  9. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    -
    -     -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -     +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
    -
    -     -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    -     +export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
    +  9. Make sure that the PATH variable includes the path to the newly built binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       detailed PLUS some special instructions that you will need to follow if you are
    @@ -425,8 +415,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     LEDs
     ====
    @@ -738,7 +728,6 @@ can be selected as follow:
         cd tools
         ./configure.sh shenzhou/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    @@ -819,7 +808,6 @@ Where  is one of the following:
         2. Make the build context (only)
     
            $ cd ..
    -       $ . ./setenv.sh
            $ make context
            ...
     
    diff --git a/configs/sim/README.txt b/configs/sim/README.txt
    index 816ed00743..15ec2078a8 100644
    --- a/configs/sim/README.txt
    +++ b/configs/sim/README.txt
    @@ -382,12 +382,6 @@ Common Configuration Information
            cd /tools
            ./configure.sh sim/
            cd -
    -       . ./setenv.sh
    -
    -     If this is a Windows native build, then configure.bat should be used
    -     instead of configure.sh:
    -
    -        configure.bat sim\
     
          Where  is one of the following sub-directories.
     
    diff --git a/configs/spark/README.txt b/configs/spark/README.txt
    index c870066b9a..3b8b0ebf6f 100644
    --- a/configs/spark/README.txt
    +++ b/configs/spark/README.txt
    @@ -73,9 +73,6 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_RAISONANCE=y     : Raisonance RIDE7 under Windows
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=n      : NuttX buildroot under Linux or Cygwin (default)
     
    -  If you change the default toolchain, then you may also have to modify the PATH in
    -  the setenv.h file if your make cannot find the tools.
    -
       NOTE: the CodeSourcery (for Windows), Atollic, devkitARM, and Raisonance toolchains are
       Windows native toolchains.  The CodeSourcey (for Linux) and NuttX buildroot
       toolchains are Cygwin and/or Linux native toolchains. There are several limitations
    @@ -191,7 +188,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ================================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -218,8 +215,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you are
    @@ -280,8 +277,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     DFU and JTAG
     ============
    diff --git a/configs/stm3210e-eval/README.txt b/configs/stm3210e-eval/README.txt
    index 9ca365c92c..b622630f98 100644
    --- a/configs/stm3210e-eval/README.txt
    +++ b/configs/stm3210e-eval/README.txt
    @@ -53,9 +53,6 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_RAISONANCE=y     : Raisonance RIDE7 under Windows
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y      : NuttX buildroot under Linux or Cygwin (default)
     
    -  If you are not using CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT, then you may also have to modify
    -  the PATH in the setenv.h file if your make cannot find the tools.
    -
       NOTE: the CodeSourcery (for Windows), devkitARM, and Raisonance toolchains are
       Windows native toolchains.  The CodeSourcey (for Linux) and NuttX buildroot
       toolchains are Cygwin and/or Linux native toolchains. There are several limitations
    @@ -121,7 +118,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ================================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -148,8 +145,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you are
    @@ -210,8 +207,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     DFU and JTAG
     ============
    @@ -701,7 +698,6 @@ can be selected as follow:
         cd tools
         ./configure.sh stm3210e-eval/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    @@ -748,9 +744,9 @@ Where  is one of the following:
                                             apps/system/i2c
         =========== ======================= ================================
     
    -    (1) You will probably need to modify nsh/setenv.sh or nsh2/setenv.sh
    -        to set up the correct PATH variable for whichever toolchain you
    -        may use.
    +    (1) You will probably need to modify PATH environment variable to
    +        to include the correct path to the binaries for whichever
    +        toolchain you may use.
         (2) Since DfuSe is assumed, this configuration may only work under
             Cygwin without modification.
         (3) When any other device other than /dev/console is used for a user
    diff --git a/configs/stm3220g-eval/README.txt b/configs/stm3220g-eval/README.txt
    index aa4b365791..69cded915f 100644
    --- a/configs/stm3220g-eval/README.txt
    +++ b/configs/stm3220g-eval/README.txt
    @@ -61,9 +61,6 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y      : NuttX buildroot under Linux or Cygwin (default)
         CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL : Generic arm-none-eabi toolchain
     
    -  If you change the default toolchain, then you may also have to modify the PATH in
    -  the setenv.h file if your make cannot find the tools.
    -
       The toolchain may also be set using the kconfig-mconf utility (make menuconfig)
       or by passing CONFIG_ARMV7M_TOOLCHAIN= to make, where  is one
       of CODESOURCERYW, CODESOURCERYL, ATOLLOC, DEVKITARM, RAISONANCE, BUILDROOT or
    @@ -272,7 +269,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ================================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -299,8 +296,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you are
    @@ -361,8 +358,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     Ethernet
     ========
    @@ -855,7 +852,6 @@ can be selected as follow:
         cd tools
         ./configure.sh stm3220g-eval/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    @@ -1172,7 +1168,6 @@ Where  is one of the following:
         2. Make the build context (only)
     
            $ cd ..
    -       $ . ./setenv.sh
            $ make context
            ...
     
    diff --git a/configs/stm3240g-eval/README.txt b/configs/stm3240g-eval/README.txt
    index 4b9a1f3ce8..fc01bae908 100644
    --- a/configs/stm3240g-eval/README.txt
    +++ b/configs/stm3240g-eval/README.txt
    @@ -61,9 +61,6 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_RAISONANCE=y     : Raisonance RIDE7 under Windows
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y      : NuttX buildroot under Linux or Cygwin (default)
     
    -  If you change the default toolchain, then you may also have to modify the PATH in
    -  the setenv.h file if your make cannot find the tools.
    -
       NOTE: the CodeSourcery (for Windows), Atollic, devkitARM, and Raisonance toolchains are
       Windows native toolchains.  The CodeSourcery (for Linux) and NuttX buildroot
       toolchains are Cygwin and/or Linux native toolchains. There are several limitations
    @@ -168,7 +165,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ================================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -195,8 +192,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you are
    @@ -257,8 +254,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     Ethernet
     ========
    @@ -890,7 +887,6 @@ can be selected as follow:
         cd tools
         ./configure.sh stm3240g-eval/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    @@ -1467,7 +1463,6 @@ Where  is one of the following:
         2. Make the build context (only)
     
            $ cd ..
    -       $ . ./setenv.sh
            $ make context
            ...
     
    diff --git a/configs/stm32_tiny/README.txt b/configs/stm32_tiny/README.txt
    index 7abbc4ccb0..71fdfd472e 100644
    --- a/configs/stm32_tiny/README.txt
    +++ b/configs/stm32_tiny/README.txt
    @@ -57,9 +57,6 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_RAISONANCE=y     : Raisonance RIDE7 under Windows
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y      : NuttX buildroot under Linux or Cygwin (default)
     
    -  If you change the default toolchain, then you may also have to modify the PATH in
    -  the setenv.h file if your make cannot find the tools.
    -
       NOTE: the CodeSourcery (for Windows), Atollic, devkitARM, and Raisonance toolchains are
       Windows native toolchains.  The CodeSourcey (for Linux) and NuttX buildroot
       toolchains are Cygwin and/or Linux native toolchains. There are several limitations
    @@ -164,7 +161,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ================================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -191,8 +188,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you are
    @@ -253,8 +250,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     LEDs
     ====
    @@ -513,12 +510,6 @@ can be selected as follow:
         cd tools
         ./configure.sh STM32Tiny/
         cd -
    -    . ./setenv.sh
    -
    -If this is a Windows native build, then configure.bat should be used
    -instead of configure.sh:
    -
    -    configure.bat STM32Tiny\
     
     Where  is one of the following:
     
    diff --git a/configs/stm32f103-minimum/README.txt b/configs/stm32f103-minimum/README.txt
    index 82f9f33ce8..91e08731f2 100644
    --- a/configs/stm32f103-minimum/README.txt
    +++ b/configs/stm32f103-minimum/README.txt
    @@ -528,12 +528,6 @@ Configurations
         cd tools
         ./configure.sh STM32F103 Minimum/
         cd -
    -    . ./setenv.sh
    -
    -  If this is a Windows native build, then configure.bat should be used
    -  instead of configure.sh:
    -
    -    configure.bat STM32F103-Minimum\
     
       Where  is one of the following:
     
    diff --git a/configs/stm32f3discovery/README.txt b/configs/stm32f3discovery/README.txt
    index 8cb94aa2f7..c3783d1606 100644
    --- a/configs/stm32f3discovery/README.txt
    +++ b/configs/stm32f3discovery/README.txt
    @@ -53,9 +53,6 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_RAISONANCE=y     : Raisonance RIDE7 under Windows
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y      : NuttX buildroot under Linux or Cygwin (default)
     
    -  If you change the default toolchain, then you may also have to modify the PATH in
    -  the setenv.h file if your make cannot find the tools.
    -
       NOTE: the CodeSourcery (for Windows), Atollic, devkitARM, and Raisonance toolchains are
       Windows native toolchains.  The CodeSourcey (for Linux) and NuttX buildroot
       toolchains are Cygwin and/or Linux native toolchains. There are several limitations
    @@ -160,7 +157,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ================================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -187,8 +184,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you are
    @@ -249,8 +246,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     LEDs
     ====
    @@ -657,12 +654,6 @@ can be selected as follow:
         cd tools
         ./configure.sh STM32F3Discovery/
         cd -
    -    . ./setenv.sh
    -
    -If this is a Windows native build, then configure.bat should be used
    -instead of configure.sh:
    -
    -    configure.bat STM32F3Discovery\
     
     Where  is one of the following:
     
    diff --git a/configs/stm32f429i-disco/README.txt b/configs/stm32f429i-disco/README.txt
    index 2b406e035c..fc2719ad00 100644
    --- a/configs/stm32f429i-disco/README.txt
    +++ b/configs/stm32f429i-disco/README.txt
    @@ -650,12 +650,6 @@ can be selected as follow:
         cd tools
         ./configure.sh STM32F429I-DISCO/
         cd -
    -    . ./setenv.sh
    -
    -If this is a Windows native build, then configure.bat should be used
    -instead of configure.sh:
    -
    -    configure.bat STM32F429I-DISCO\
     
     Where  is one of the following:
     
    @@ -957,7 +951,6 @@ Where  is one of the following:
            2. Make the build context (only)
     
               $ cd ..
    -          $ . ./setenv.sh
               $ make context
               ...
     
    diff --git a/configs/stm32f4discovery/README.txt b/configs/stm32f4discovery/README.txt
    index 472621c1fe..b748027d83 100644
    --- a/configs/stm32f4discovery/README.txt
    +++ b/configs/stm32f4discovery/README.txt
    @@ -74,9 +74,6 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_RAISONANCE=y     : Raisonance RIDE7 under Windows
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y      : NuttX buildroot under Linux or Cygwin (default)
     
    -  If you change the default toolchain, then you may also have to modify the PATH in
    -  the setenv.h file if your make cannot find the tools.
    -
       NOTE: the CodeSourcery (for Windows), Atollic, devkitARM, and Raisonance toolchains are
       Windows native toolchains.  The CodeSourcey (for Linux) and NuttX buildroot
       toolchains are Cygwin and/or Linux native toolchains. There are several limitations
    @@ -181,7 +178,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ================================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -208,8 +205,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you are
    @@ -270,8 +267,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     LEDs
     ====
    @@ -1217,12 +1214,6 @@ can be selected as follow:
         cd tools
         ./configure.sh STM32F4Discovery/
         cd -
    -    . ./setenv.sh
    -
    -If this is a Windows native build, then configure.bat should be used
    -instead of configure.sh:
    -
    -    configure.bat STM32F4Discovery\
     
     Where  is one of the following:
     
    diff --git a/configs/stm32f4discovery/winbuild/setenv.bat b/configs/stm32f4discovery/winbuild/setenv.bat
    deleted file mode 100644
    index 22fa1e599b..0000000000
    --- a/configs/stm32f4discovery/winbuild/setenv.bat
    +++ /dev/null
    @@ -1,50 +0,0 @@
    -@echo off
    -
    -rem configs/stm32f4discovery/winbuild/setenv.bat
    -rem
    -rem   Copyright (C) 2012 Gregory Nutt. All rights reserved.
    -rem   Author: Gregory Nutt 
    -rem
    -rem Redistribution and use in source and binary forms, with or without
    -rem modification, are permitted provided that the following conditions
    -rem are met:
    -rem
    -rem 1. Redistributions of source code must retain the above copyright
    -rem    notice, this list of conditions and the following disclaimer.
    -rem 2. Redistributions in binary form must reproduce the above copyright
    -rem    notice, this list of conditions and the following disclaimer in
    -rem    the documentation and/or other materials provided with the
    -rem    distribution.
    -rem 3. Neither the name NuttX nor the names of its contributors may be
    -rem    used to endorse or promote products derived from this software
    -rem    without specific prior written permission.
    -rem
    -rem THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
    -rem "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
    -rem LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
    -rem FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
    -rem COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
    -rem INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
    -rem BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
    -rem OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
    -rem AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
    -rem LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
    -rem ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
    -rem POSSIBILITY OF SUCH DAMAGE.
    -
    -rem This is the location where I installed in the MinGW compiler. With
    -rem this configuration, it is recommended that you do NOT install the
    -rem MSYS tools; they conflict with the GNUWin32 tools.  See
    -rem http://www.mingw.org/ for further info.
    -
    -set PATH=C:\MinGW\bin;%PATH%
    -
    -rem This is the location where I installed the CodeSourcey toolchain.  See
    -rem http://www.mentor.com/embedded-software/codesourcery
    -
    -set PATH=C:\Program Files (x86)\CodeSourcery\Sourcery G++ Lite\bin;%PATH%
    -
    -rem This is the location where I installed the GNUWin32 tools.  See
    -rem http://gnuwin32.sourceforge.net/.
    -
    -set PATH=C:\gnuwin32\bin;%PATH%
    diff --git a/configs/stm32f746g-disco/README.txt b/configs/stm32f746g-disco/README.txt
    index 47dc3a6468..a3477a5997 100644
    --- a/configs/stm32f746g-disco/README.txt
    +++ b/configs/stm32f746g-disco/README.txt
    @@ -465,12 +465,6 @@ Configurations
         cd tools
         ./configure.sh stm32f746g-disco/
         cd -
    -    . ./setenv.sh
    -
    -  If this is a Windows native build, then configure.bat should be used
    -  instead of configure.sh:
    -
    -    configure.bat STM32F746G-DISCO\
     
       Where  is one of the sub-directories listed below.
     
    @@ -497,15 +491,10 @@ Configurations
              https://launchpad.net/gcc-arm-embedded
     
            As of this writing (2015-03-11), full support is difficult to find
    -       for the Cortex-M7, but is supported by at least this realeasse of
    +       for the Cortex-M7, but is supported by at least this realease of
            the ARM GNU tools:
     
    -         https://launchpadlibrarian.net/192228215/release.txt
    -
    -       Current (2105-07-31) setenv.sh file are configured to use this
    -       release:
    -
    -       https://launchpadlibrarian.net/209776344/release.txt
    +         https://launchpadlibrarian.net/209776344/release.txt
     
            That toolchain selection can easily be reconfigured using
            'make menuconfig'.  Here are the relevant current settings:
    diff --git a/configs/stm32ldiscovery/README.txt b/configs/stm32ldiscovery/README.txt
    index 4158273b5a..92fdb43111 100644
    --- a/configs/stm32ldiscovery/README.txt
    +++ b/configs/stm32ldiscovery/README.txt
    @@ -218,9 +218,6 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_RAISONANCE=y     : Raisonance RIDE7 under Windows
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y      : NuttX buildroot under Linux or Cygwin (default)
     
    -  If you change the default toolchain, then you may also have to modify the PATH in
    -  the setenv.h file if your make cannot find the tools.
    -
       NOTE: the CodeSourcery (for Windows), Atollic, devkitARM, and Raisonance toolchains are
       Windows native toolchains.  The CodeSourcey (for Linux) and NuttX buildroot
       toolchains are Cygwin and/or Linux native toolchains. There are several limitations
    @@ -325,7 +322,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ================================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -352,8 +349,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you are
    @@ -414,8 +411,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     LEDs
     ====
    @@ -727,12 +724,6 @@ Configurations
         cd tools
         ./configure.sh STM32L-Discovery/
         cd -
    -    . ./setenv.sh
    -
    -  If this is a Windows native build, then configure.bat should be used
    -  instead of configure.sh:
    -
    -    configure.bat STM32L-Discovery\
     
       Where  is one of the following sub-directories.
     
    diff --git a/configs/stm32vldiscovery/README.txt b/configs/stm32vldiscovery/README.txt
    index 963a85ff7c..8d4923be71 100644
    --- a/configs/stm32vldiscovery/README.txt
    +++ b/configs/stm32vldiscovery/README.txt
    @@ -51,9 +51,6 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_RAISONANCE=y     : Raisonance RIDE7 under Windows
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y      : NuttX buildroot under Linux or Cygwin (default)
     
    -  If you change the default toolchain, then you may also have to modify the PATH in
    -  the setenv.sh file if your make cannot find the tools.
    -
       NOTE: the CodeSourcery (for Windows), Atollic, devkitARM, and Raisonance toolchains are
       Windows native toolchains.  The CodeSourcey (for Linux) and NuttX buildroot
       toolchains are Cygwin and/or Linux native toolchains. There are several limitations
    @@ -153,7 +150,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ================================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -180,8 +177,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you are
    @@ -242,8 +239,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     LEDs
     ====
    @@ -447,7 +444,6 @@ and can be selected as follow:
         cd tools
         ./configure.sh stm32vldiscovery/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    diff --git a/configs/sure-pic32mx/README.txt b/configs/sure-pic32mx/README.txt
    index 754005c541..b8ca0cc722 100644
    --- a/configs/sure-pic32mx/README.txt
    +++ b/configs/sure-pic32mx/README.txt
    @@ -387,8 +387,7 @@ Loading NuttX with PICkit2
     
         To use this file, you need to do the following things:
     
    -      . ./setenv.sh    # Source setenv.sh.  Among other this, this script
    -                       # will add the NuttX tools/pic32mx directory to your
    +                       # Add the NuttX tools/pic32mx directory to your
                            # PATH variable
           make             # Build nuttx and nuttx.hex
           mkpichex $PWD    # Convert addresses in nuttx.hex.  $PWD is the path
    @@ -635,7 +634,6 @@ Configurations
         cd tools
         ./configure.sh sure-pic32mx/
         cd -
    -    . ./setenv.sh
     
       Where  is one of the following sub-directories.
     
    diff --git a/configs/teensy-2.0/README.txt b/configs/teensy-2.0/README.txt
    index b409268a65..105b289157 100644
    --- a/configs/teensy-2.0/README.txt
    +++ b/configs/teensy-2.0/README.txt
    @@ -215,9 +215,8 @@ Buildroot:
       http://bitbucket.org/nuttx/buildroot/downloads/.  See the
       following section for details on building this toolchain.
     
    -  It is assumed in some places that buildroot toolchain is available
    -  at ../buildroot/build_avr.  Edit the setenv.sh file if
    -  this is not the case.
    +  Make sure that your PATH evirnoment variable includes the path the newly
    +  built binaries.
     
       After configuring NuttX, make sure that CONFIG_AVR_BUILDROOT_TOOLCHAIN=y is set in your
       .config file.
    @@ -227,8 +226,8 @@ WinAVR:
       For Cygwin development environment on Windows machines, you can use
       WinAVR: http://sourceforge.net/projects/winavr/files/
     
    -  It is assumed in some places that WinAVR is installed at C:/WinAVR.  Edit the
    -  setenv.sh file if this is not the case.
    +  Make sure that your PATH evirnoment variable includes the path the WinAvR
    +  binaries.
     
       After configuring NuttX, make sure that CONFIG_AVR_WINAVR_TOOLCHAIN=y is set in your
       .config file.
    @@ -319,8 +318,8 @@ NuttX buildroot Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       detailed PLUS some special instructions that you will need to follow if you
    @@ -522,7 +521,6 @@ Common Configuration Notes
            cd tools
            ./configure.sh teensy-2.0/
            cd -
    -       . ./setenv.sh
     
          Where  is one of the configuration sub-directories described in
          the following paragraph.
    diff --git a/configs/teensy-3.x/README.txt b/configs/teensy-3.x/README.txt
    index a43a0c0833..cdcfee7e62 100644
    --- a/configs/teensy-3.x/README.txt
    +++ b/configs/teensy-3.x/README.txt
    @@ -228,11 +228,9 @@ Configurations
         ./configure.sh teensy-3.x/
         cd -
         make oldconfig
    -    . ./setenv.sh
     
    -  Before sourcing the setenv.sh file above, you should examine it and
    -  perform edits as necessary so that TOOLCHAIN_BIN is the correct path to
    -  the directory than holds your toolchain binaries.
    +  Before building, make sure that your PATH environment variable includes
    +  the correct path to the directory than holds your toolchain binaries.
     
       If this is a Windows native build, then configure.bat should be used
       instead of configure.sh:
    diff --git a/configs/tm4c123g-launchpad/README.txt b/configs/tm4c123g-launchpad/README.txt
    index e4554002cf..cdb2d2ca89 100644
    --- a/configs/tm4c123g-launchpad/README.txt
    +++ b/configs/tm4c123g-launchpad/README.txt
    @@ -291,9 +291,8 @@ Using OpenOCD and GDB with an FT2232 JTAG emulator
     
           oocd.sh $PWD
     
    -    The relative path to the oocd.sh script is configs/tm4c123g-launchpad/tools,
    -    but that should have been added to your PATH variable when you sourced
    -    the setenv.sh script.
    +    The relative path to the oocd.sh script is configs/tm4c123g-launchpad/tools.
    +    You may want to add that path to you PATH variable.
     
         Note that OpenOCD needs to be run with administrator privileges in
         some environments (sudo).
    @@ -368,9 +367,6 @@ GNU Toolchain Options
     
         CONFIG_ARMV7M_OABI_TOOLCHAIN=y           : If you use an older, OABI buildroot toolchain
     
    -  If you change the default toolchain, then you may also have to modify the PATH in
    -  the setenv.h file if your make cannot find the tools.
    -
       NOTE: the CodeSourcery (for Windows), Atollic, devkitARM, and Code Red (for Windows)
       toolchains are Windows native toolchains.  The CodeSourcey (for Linux) and NuttX
       buildroot toolchains are Cygwin and/or Linux native toolchains. There are several
    @@ -435,7 +431,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ================================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -462,8 +458,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you
    @@ -524,8 +520,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     LEDs
     ====
    @@ -763,7 +759,6 @@ sub-directory and can be selected as follow:
         cd tools
         ./configure.sh tm4c123g-launchpad/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    diff --git a/configs/tm4c1294-launchpad/README.txt b/configs/tm4c1294-launchpad/README.txt
    index b670121ade..1ed896c3e9 100644
    --- a/configs/tm4c1294-launchpad/README.txt
    +++ b/configs/tm4c1294-launchpad/README.txt
    @@ -28,7 +28,6 @@ sub-directory and can be selected as follow:
         cd tools
         ./configure.sh tm4c1294-launchpad/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    diff --git a/configs/twr-k60n512/README.txt b/configs/twr-k60n512/README.txt
    index 9c64cae46d..bf7ff26db3 100644
    --- a/configs/twr-k60n512/README.txt
    +++ b/configs/twr-k60n512/README.txt
    @@ -312,9 +312,6 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_DEVKITARM=y      : devkitARM under Windows
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y      : NuttX buildroot under Linux or Cygwin (default)
     
    -  If you are not using CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT, then you may also have to modify
    -  the PATH in the setenv.h file if your make cannot find the tools.
    -
       NOTE: the CodeSourcery (for Windows) and devkitARM toolchains are
       Windows native toolchains.  The CodeSourcey (for Linux) and NuttX buildroot
       toolchains are Cygwin and/or Linux native toolchains. There are several limitations
    @@ -378,7 +375,7 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ================================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the Cortex-M4 GCC toolchain (if
       different from the default in your PATH variable).
     
    @@ -407,8 +404,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you are
    @@ -469,8 +466,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     TWR-K60N512-specific Configuration Options
     ==========================================
    @@ -643,7 +640,6 @@ can be selected as follow:
         cd tools
         ./configure.sh twr-k60n512/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    diff --git a/configs/twr-k64f120m/README.txt b/configs/twr-k64f120m/README.txt
    index cbb5a88b8d..6c69686a84 100644
    --- a/configs/twr-k64f120m/README.txt
    +++ b/configs/twr-k64f120m/README.txt
    @@ -442,9 +442,6 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y      : NuttX buildroot under Linux or Cygwin
         CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL=y      : GCC (default)
     
    -  If you are not using CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT, then you may also have to modify
    -  the PATH in the setenv.h file if your make cannot find the tools.
    -
       NOTE: the CodeSourcery (for Windows) and devkitARM toolchains are
       Windows native toolchains.  The CodeSourcey (for Linux) and NuttX buildroot
       toolchains are Cygwin and/or Linux native toolchains. There are several limitations
    @@ -508,9 +505,8 @@ IDEs
     NuttX EABI "buildroot" Toolchain
     ================================
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    -  be modified to point to the correct path to the Cortex-M4 GCC toolchain (if
    -  different from the default in your PATH variable).
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
    +  be modified to point to the correct path to the Cortex-M4 GCC toolchain.
     
       If you have no Cortex-M4 toolchain, one can be downloaded from the NuttX
       Bitbucket download site (https://bitbucket.org/nuttx/buildroot/downloads/).
    @@ -537,8 +533,8 @@ NuttX EABI "buildroot" Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       details PLUS some special instructions that you will need to follow if you are
    @@ -599,8 +595,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     TWR-K64F120M-specific Configuration Options
     ==========================================
    @@ -770,7 +766,6 @@ can be selected as follow:
         cd tools
         ./configure.sh twr-k64f120m/
         cd ..
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    diff --git a/configs/ubw32/README.txt b/configs/ubw32/README.txt
    index cbd4cad6e6..a1a77294ef 100644
    --- a/configs/ubw32/README.txt
    +++ b/configs/ubw32/README.txt
    @@ -326,8 +326,7 @@ Loading NuttX with PICkit2
     
         To use this file, you need to do the following things:
     
    -      . ./setenv.sh    # Source setenv.sh.  Among other this, this script
    -                       # will add the NuttX tools/pic32mx directory to your
    +                       # Add the NuttX tools/pic32mx directory to your
                            # PATH variable
           make             # Build nuttx and nuttx.hex
           mkpichex $PWD    # Convert addresses in nuttx.hex.  $PWD is the path
    @@ -569,7 +568,6 @@ selected as follow:
         cd tools
         ./configure.sh ubw32/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    diff --git a/configs/us7032evb1/README.txt b/configs/us7032evb1/README.txt
    index 15efbddfe0..eabbba1403 100644
    --- a/configs/us7032evb1/README.txt
    +++ b/configs/us7032evb1/README.txt
    @@ -14,7 +14,7 @@ time being.
     Toolchain
     ^^^^^^^^^
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    +  A GNU GCC-based toolchain is assumed.  The PATH environment variable should
       be modified to point to the correct path to the SH toolchain (if
       different from the default).
     
    @@ -38,8 +38,8 @@ Toolchain
     
       7. make
     
    -  8. Edit setenv.h so that the PATH variable includes the path to the
    -     newly built binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     binaries.
     
     shterm
     ^^^^^^
    @@ -64,7 +64,6 @@ Common Configuration Notes
            cd tools
            ./configure.sh us7032evb1/
            cd -
    -       . ./setenv.sh
     
          Where  is one of the configuration sub-directories described in
          the following paragraph.
    diff --git a/configs/viewtool-stm32f107/README.txt b/configs/viewtool-stm32f107/README.txt
    index 04ff1afbb2..31d5fc734e 100644
    --- a/configs/viewtool-stm32f107/README.txt
    +++ b/configs/viewtool-stm32f107/README.txt
    @@ -536,11 +536,9 @@ Configurations
         cd tools
         ./configure.sh viewtool-stm32f107/
         cd -
    -    . ./setenv.sh
     
    -  Before sourcing the setenv.sh file above, you should examine it and perform
    -  edits as necessary so that TOOLCHAIN_BIN is the correct path to the directory
    -  than holds your toolchain binaries.
    +  Before starting the build, make sure that your PATH environment variable
    +  includes the correct path to your toolchain.
     
       And then build NuttX by simply typing the following.  At the conclusion of
       the make, the nuttx binary will reside in an ELF file called, simply, nuttx.
    @@ -579,10 +577,6 @@ Configurations
          System Type -> Toolchain:
            CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYW=y : GNU EABI toolchain for windows
     
    -     The setenv.sh file is available for you to use to set the PATH
    -     variable.  The path in the that file may not, however, be correct
    -     for your installation.
    -
          See also the "NOTE about Windows native toolchains" in the section call
          "GNU Toolchain Options" above.
     
    diff --git a/configs/xmc4500-relax/README.txt b/configs/xmc4500-relax/README.txt
    index 9fb7e29c2e..7c3e3d6ef6 100644
    --- a/configs/xmc4500-relax/README.txt
    +++ b/configs/xmc4500-relax/README.txt
    @@ -84,11 +84,9 @@ Configurations
         cd tools
         ./configure.sh xmc5400-relax/
         cd -
    -    . ./setenv.sh
     
    -  Before sourcing the setenv.sh file above, you should examine it and
    -  perform edits as necessary so that TOOLCHAIN_BIN is the correct path
    -  to the directory than holds your toolchain binaries.
    +  Before starting the build, make sure that your PATH environment variable
    +  includes the correct path to your toolchain.
     
       And then build NuttX by simply typing the following.  At the conclusion of
       the make, the nuttx binary will reside in an ELF file called, simply, nuttx.
    diff --git a/configs/xtrs/README.txt b/configs/xtrs/README.txt
    index a1dc4e6b03..d778f087f7 100644
    --- a/configs/xtrs/README.txt
    +++ b/configs/xtrs/README.txt
    @@ -55,8 +55,9 @@ Configuring NuttX
         1) From a POSIX window:
            cd tools
            ./configure.sh xtrs/ostest
    -    2) From a CMD.exe window
    -       setenv.bat
    +    2) Modify your PATH environment variable to include the path to the
    +       SDCC toolchain.
    +    3) From a CMD.exe window
            make
     
         If this is a Windows native build, then configure.bat should be used
    @@ -64,9 +65,6 @@ Configuring NuttX
     
           configure.bat xtrs\ostest
     
    -    The setenv.bat will need to be updated to include the PATH to the XTRS
    -    hex2cmd program.
    -
         NOTES:
     
         1. This configuration uses the mconf-based configuration tool.  See the
    @@ -91,8 +89,9 @@ Configuring NuttX
         1) From a POSIX window:
            cd tools
            ./configure.sh xtrs/nsh
    -    2) From a CMD.exe window
    -       setenv.bat
    +    2) Modify your PATH environment variable to include the path to the
    +       SDCC toolchain.
    +    3) From a CMD.exe window
            make
     
         If this is a Windows native build, then configure.bat should be used
    @@ -100,9 +99,6 @@ Configuring NuttX
     
           configure.bat xtrs\nsh
     
    -    The setenv.bat will need to be updated to include the PATH to the XTRS
    -    hex2cmd program.
    -
         NOTES:
     
         1. This configuration uses the mconf-based configuration tool.  See the
    @@ -134,8 +130,9 @@ Configuring NuttX
         1) From a POSIX window:
            cd tools
            ./configure.sh xtrs/pashello
    -    2) From a CMD.exe window
    -       setenv.bat
    +    2) Modify your PATH environment variable to include the path to the
    +       SDCC toolchain.
    +    3) From a CMD.exe window
            make
     
         If this is a Windows native build, then configure.bat should be used
    @@ -143,9 +140,6 @@ Configuring NuttX
     
           configure.bat xtrs\pashello
     
    -    The setenv.bat will need to be updated to include the PATH to the XTRS
    -    hex2cmd program.
    -
         NOTES:
     
         1. This configuration uses the mconf-based configuration tool.  See the
    @@ -195,11 +189,6 @@ in the .config file because the backslash may upset some Unix-based tools.
     This configuration will require a recent version of SDCC (ca. 3.2.1) for Linux
     or custom built for Cygwin (see below).
     
    -You cannot use the default setenv.bat in these Unix-like enviroments because
    -that is a Windows batch file.  Use configs/z80sim/script/setenv.sh instead.
    -setenv.sh must include the path to the installation location of SDCC (probably
    -/usr/local/bin).
    -
     SDCC
     ^^^^
     
    diff --git a/configs/xtrs/nsh/setenv.bat b/configs/xtrs/nsh/setenv.bat
    deleted file mode 100644
    index 0df2ba4b66..0000000000
    --- a/configs/xtrs/nsh/setenv.bat
    +++ /dev/null
    @@ -1,54 +0,0 @@
    -@echo off
    -
    -rem configs/xtrs/nsh/setenv.bat
    -rem
    -rem   Copyright (C) 2012 Gregory Nutt. All rights reserved.
    -rem   Author: Gregory Nutt 
    -rem
    -rem Redistribution and use in source and binary forms, with or without
    -rem modification, are permitted provided that the following conditions
    -rem are met:
    -rem
    -rem 1. Redistributions of source code must retain the above copyright
    -rem    notice, this list of conditions and the following disclaimer.
    -rem 2. Redistributions in binary form must reproduce the above copyright
    -rem    notice, this list of conditions and the following disclaimer in
    -rem    the documentation and/or other materials provided with the
    -rem    distribution.
    -rem 3. Neither the name NuttX nor the names of its contributors may be
    -rem    used to endorse or promote products derived from this software
    -rem    without specific prior written permission.
    -rem
    -rem THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
    -rem "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
    -rem LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
    -rem FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
    -rem COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
    -rem INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
    -rem BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
    -rem OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
    -rem AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
    -rem LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
    -rem ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
    -rem POSSIBILITY OF SUCH DAMAGE.
    -
    -rem This is the location where I installed in the MinGW compiler. With
    -rem this configuration, it is recommended that you do NOT install the
    -rem MSYS tools; they conflict with the GNUWin32 tools.  See
    -rem http://www.mingw.org/ for further info.
    -
    -set PATH=C:\MinGW\bin;%PATH%
    -
    -rem This is the location where I installed the SDCC toolchain for windows.
    -
    -set PATH=C:\Program Files (x86)\SDCC/bin;%PATH%
    -
    -rem This is the location where I installed the GNUWin32 tools.  See
    -rem http://gnuwin32.sourceforge.net/.
    -
    -set PATH=C:\gnuwin32\bin;%PATH%
    -
    -rem This is the location where the XTRS hex2cmd program is available
    -rem set PATH=????:%PATH%
    -
    -echo %PATH%
    diff --git a/configs/xtrs/ostest/setenv.bat b/configs/xtrs/ostest/setenv.bat
    deleted file mode 100644
    index 38822dcc2d..0000000000
    --- a/configs/xtrs/ostest/setenv.bat
    +++ /dev/null
    @@ -1,54 +0,0 @@
    -@echo off
    -
    -rem configs/xtrs/ostest/setenv.bat
    -rem
    -rem   Copyright (C) 2012 Gregory Nutt. All rights reserved.
    -rem   Author: Gregory Nutt 
    -rem
    -rem Redistribution and use in source and binary forms, with or without
    -rem modification, are permitted provided that the following conditions
    -rem are met:
    -rem
    -rem 1. Redistributions of source code must retain the above copyright
    -rem    notice, this list of conditions and the following disclaimer.
    -rem 2. Redistributions in binary form must reproduce the above copyright
    -rem    notice, this list of conditions and the following disclaimer in
    -rem    the documentation and/or other materials provided with the
    -rem    distribution.
    -rem 3. Neither the name NuttX nor the names of its contributors may be
    -rem    used to endorse or promote products derived from this software
    -rem    without specific prior written permission.
    -rem
    -rem THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
    -rem "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
    -rem LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
    -rem FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
    -rem COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
    -rem INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
    -rem BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
    -rem OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
    -rem AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
    -rem LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
    -rem ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
    -rem POSSIBILITY OF SUCH DAMAGE.
    -
    -rem This is the location where I installed in the MinGW compiler. With
    -rem this configuration, it is recommended that you do NOT install the
    -rem MSYS tools; they conflict with the GNUWin32 tools.  See
    -rem http://www.mingw.org/ for further info.
    -
    -set PATH=C:\MinGW\bin;%PATH%
    -
    -rem This is the location where I installed the SDCC toolchain for windows.
    -
    -set PATH=C:\Program Files (x86)\SDCC/bin;%PATH%
    -
    -rem This is the location where I installed the GNUWin32 tools.  See
    -rem http://gnuwin32.sourceforge.net/.
    -
    -set PATH=C:\gnuwin32\bin;%PATH%
    -
    -rem This is the location where the XTRS hex2cmd program is available
    -rem set PATH=????:%PATH%
    -
    -echo %PATH%
    diff --git a/configs/xtrs/pashello/setenv.bat b/configs/xtrs/pashello/setenv.bat
    deleted file mode 100644
    index fbedd244a8..0000000000
    --- a/configs/xtrs/pashello/setenv.bat
    +++ /dev/null
    @@ -1,54 +0,0 @@
    -@echo off
    -
    -rem configs/xtrs/pashello/setenv.bat
    -rem
    -rem   Copyright (C) 2012 Gregory Nutt. All rights reserved.
    -rem   Author: Gregory Nutt 
    -rem
    -rem Redistribution and use in source and binary forms, with or without
    -rem modification, are permitted provided that the following conditions
    -rem are met:
    -rem
    -rem 1. Redistributions of source code must retain the above copyright
    -rem    notice, this list of conditions and the following disclaimer.
    -rem 2. Redistributions in binary form must reproduce the above copyright
    -rem    notice, this list of conditions and the following disclaimer in
    -rem    the documentation and/or other materials provided with the
    -rem    distribution.
    -rem 3. Neither the name NuttX nor the names of its contributors may be
    -rem    used to endorse or promote products derived from this software
    -rem    without specific prior written permission.
    -rem
    -rem THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
    -rem "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
    -rem LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
    -rem FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
    -rem COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
    -rem INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
    -rem BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
    -rem OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
    -rem AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
    -rem LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
    -rem ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
    -rem POSSIBILITY OF SUCH DAMAGE.
    -
    -rem This is the location where I installed in the MinGW compiler. With
    -rem this configuration, it is recommended that you do NOT install the
    -rem MSYS tools; they conflict with the GNUWin32 tools.  See
    -rem http://www.mingw.org/ for further info.
    -
    -set PATH=C:\MinGW\bin;%PATH%
    -
    -rem This is the location where I installed the SDCC toolchain for windows.
    -
    -set PATH=C:\Program Files (x86)\SDCC/bin;%PATH%
    -
    -rem This is the location where I installed the GNUWin32 tools.  See
    -rem http://gnuwin32.sourceforge.net/.
    -
    -set PATH=C:\gnuwin32\bin;%PATH%
    -
    -rem This is the location where the XTRS hex2cmd program is available
    -rem set PATH=????:%PATH%
    -
    -echo %PATH%
    diff --git a/configs/z16f2800100zcog/README.txt b/configs/z16f2800100zcog/README.txt
    index 02f7f84bfd..5875a15e0d 100644
    --- a/configs/z16f2800100zcog/README.txt
    +++ b/configs/z16f2800100zcog/README.txt
    @@ -64,17 +64,17 @@ Version 5.0.1
     
       Paths were also updated that are specific to a 32-bit toolchain running on
       a 64 bit windows platform.  Change to a different toolchain, you will need
    -  to modify the versioning in Make.defs and setenv.sh; if you want to build
    +  to modify the versioning in the Make.defs file; if you want to build
       on a different platform, you will need to change the path in the ZDS binaries
    -  in those same files.
    +  in those that file and your PATH environment variable.
     
     Other Versions
     
       If you use any version of ZDS-II other than 5.0.1 or if you install ZDS-II
       at any location other than the default location, you will have to modify
    -  two files:  (1) configs/z16f2800100zcog/*/setenv.sh and (2)
    -  configs/z16f2800100zcog/*/Make.defs.  Simply edit these two files, changing
    -  5.0.1 to whatever.
    +  configs/z16f2800100zcog/*/Make.defs.  Simply edit that file, changing
    +  5.0.1 to whatever.  Also make sure that your PATH environment variable
    +  includes th correct path to the toolchain.
     
     Patches
     =======
    @@ -104,7 +104,6 @@ The patch would be applied when NuttX is configured as follows:
       cd tools
       ./configure.sh z16f2800100zcog/nsh
       cd ..
    -  . ./setenv.sh
       dopatch.sh
       make
     
    @@ -240,9 +239,7 @@ ostest
              will need to use the short 8.3 filenames to avoid spaces.  On my
              PC, C:\PROGRA~1\ is is C:\Program Files\ and C:\PROGRA~2\ is
              C:\Program Files (x86)\
    -      b. You can't use setenv.sh in the native Windows environment.  Try
    -         scripts/setenv.bat instead.
    -      c. At present, the native Windows build fails at the final link stages.
    +      b. At present, the native Windows build fails at the final link stages.
              The failure is due to problems in arch/z16/src/nuttx.linkcmd that
              is autogenerated by arch/z16/src/Makefile.  The basic problem
              is the spurious spaces and and carriage returns are generated at
    diff --git a/configs/z16f2800100zcog/scripts/setenv.bat b/configs/z16f2800100zcog/scripts/setenv.bat
    deleted file mode 100644
    index 4ee67c97eb..0000000000
    --- a/configs/z16f2800100zcog/scripts/setenv.bat
    +++ /dev/null
    @@ -1,50 +0,0 @@
    -@echo off
    -
    -rem configs/z16f2800100zcog/scripts/setenv.bat
    -rem
    -rem   Copyright (C) 2012 Gregory Nutt. All rights reserved.
    -rem   Author: Gregory Nutt 
    -rem
    -rem Redistribution and use in source and binary forms, with or without
    -rem modification, are permitted provided that the following conditions
    -rem are met:
    -rem
    -rem 1. Redistributions of source code must retain the above copyright
    -rem    notice, this list of conditions and the following disclaimer.
    -rem 2. Redistributions in binary form must reproduce the above copyright
    -rem    notice, this list of conditions and the following disclaimer in
    -rem    the documentation and/or other materials provided with the
    -rem    distribution.
    -rem 3. Neither the name NuttX nor the names of its contributors may be
    -rem    used to endorse or promote products derived from this software
    -rem    without specific prior written permission.
    -rem
    -rem THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
    -rem "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
    -rem LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
    -rem FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
    -rem COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
    -rem INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
    -rem BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
    -rem OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
    -rem AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
    -rem LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
    -rem ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
    -rem POSSIBILITY OF SUCH DAMAGE.
    -
    -rem This is the location where I installed in the MinGW compiler. With
    -rem this configuration, it is recommended that you do NOT install the
    -rem MSYS tools; they conflict with the GNUWin32 tools.  See
    -rem http://www.mingw.org/ for further info.
    -
    -set PATH=C:\MinGW\bin;%PATH%
    -
    -rem This is the location where I installed the ZDS-II toolchain.
    -
    -set PATH=C:\Program Files (x86)\ZiLOG\ZDSII_ZNEO_5.0.1\bin;%PATH%
    -
    -rem This is the location where I installed the GNUWin32 tools.  See
    -rem http://gnuwin32.sourceforge.net/.
    -
    -set PATH=C:\gnuwin32\bin;%PATH%
    -echo %PATH%
    diff --git a/configs/z80sim/README.txt b/configs/z80sim/README.txt
    index b45c762cb6..45eb1d3109 100644
    --- a/configs/z80sim/README.txt
    +++ b/configs/z80sim/README.txt
    @@ -22,13 +22,13 @@ Configuring NuttX
       ostest
     
         This configuration performs a simple, minimal OS test using
    -    examples/ostest.  This can be configurated as follows:
    +    examples/ostest.  This can be configured as follows:
     
         1) From a POSIX window:
            cd tools
            ./configure.sh z80sim/ostest
    -    2) From a CMD.exe window
    -       setenv.bat
    +    2) Make sure that your PATH environment variable includes the path
    +       to the SDCC toolchain.
     
         NOTES:
     
    @@ -56,8 +56,8 @@ Configuring NuttX
         1) From a POSIX window:
            cd tools
            ./configure.sh z80sim/nsh
    -    2) From a CMD.exe window
    -       setenv.bat
    +    2) Set the PATH environment variable to include the path to the SDCC
    +       toolchain.
     
         NOTES:
     
    @@ -87,8 +87,8 @@ Configuring NuttX
         1) From a POSIX window:
            cd tools
            ./configure.sh z80sim/pashello
    -    2) From a CMD.exe window
    -       setenv.bat
    +    2) Set the PATH environment variable to include the path to the SDCC
    +       toolchain.
     
         NOTES:
     
    @@ -141,11 +141,6 @@ in the .config file because the backslash may upset some Unix-based tools.
     This configuration will require a recent version of SDCC (ca. 3.2.1) for Linux
     or custom built for Cygwin (see below).
     
    -You cannot use the default setenv.bat in these Unix-like enviroments because
    -that is a Windows batch file.  Use configs/z80sim/script/setenv.sh instead.
    -setenv.sh must include the path to the installation location of SDCC (probably
    -/usr/local/bin).
    -
     SDCC
     ^^^^
     
    diff --git a/configs/z80sim/nsh/setenv.bat b/configs/z80sim/nsh/setenv.bat
    deleted file mode 100644
    index 9ce941938b..0000000000
    --- a/configs/z80sim/nsh/setenv.bat
    +++ /dev/null
    @@ -1,50 +0,0 @@
    -@echo off
    -
    -rem configs/z80sim/nsh/setenv.bat
    -rem
    -rem   Copyright (C) 2012 Gregory Nutt. All rights reserved.
    -rem   Author: Gregory Nutt 
    -rem
    -rem Redistribution and use in source and binary forms, with or without
    -rem modification, are permitted provided that the following conditions
    -rem are met:
    -rem
    -rem 1. Redistributions of source code must retain the above copyright
    -rem    notice, this list of conditions and the following disclaimer.
    -rem 2. Redistributions in binary form must reproduce the above copyright
    -rem    notice, this list of conditions and the following disclaimer in
    -rem    the documentation and/or other materials provided with the
    -rem    distribution.
    -rem 3. Neither the name NuttX nor the names of its contributors may be
    -rem    used to endorse or promote products derived from this software
    -rem    without specific prior written permission.
    -rem
    -rem THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
    -rem "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
    -rem LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
    -rem FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
    -rem COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
    -rem INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
    -rem BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
    -rem OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
    -rem AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
    -rem LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
    -rem ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
    -rem POSSIBILITY OF SUCH DAMAGE.
    -
    -rem This is the location where I installed in the MinGW compiler. With
    -rem this configuration, it is recommended that you do NOT install the
    -rem MSYS tools; they conflict with the GNUWin32 tools.  See
    -rem http://www.mingw.org/ for further info.
    -
    -set PATH=C:\MinGW\bin;%PATH%
    -
    -rem This is the location where I installed the SDCC toolchain for windows.
    -
    -set PATH=C:\Program Files (x86)\SDCC/bin;%PATH%
    -
    -rem This is the location where I installed the GNUWin32 tools.  See
    -rem http://gnuwin32.sourceforge.net/.
    -
    -set PATH=C:\gnuwin32\bin;%PATH%
    -echo %PATH%
    diff --git a/configs/z80sim/ostest/setenv.bat b/configs/z80sim/ostest/setenv.bat
    deleted file mode 100644
    index e5c7ff5bf1..0000000000
    --- a/configs/z80sim/ostest/setenv.bat
    +++ /dev/null
    @@ -1,50 +0,0 @@
    -@echo off
    -
    -rem configs/z80sim/ostest/setenv.bat
    -rem
    -rem   Copyright (C) 2012 Gregory Nutt. All rights reserved.
    -rem   Author: Gregory Nutt 
    -rem
    -rem Redistribution and use in source and binary forms, with or without
    -rem modification, are permitted provided that the following conditions
    -rem are met:
    -rem
    -rem 1. Redistributions of source code must retain the above copyright
    -rem    notice, this list of conditions and the following disclaimer.
    -rem 2. Redistributions in binary form must reproduce the above copyright
    -rem    notice, this list of conditions and the following disclaimer in
    -rem    the documentation and/or other materials provided with the
    -rem    distribution.
    -rem 3. Neither the name NuttX nor the names of its contributors may be
    -rem    used to endorse or promote products derived from this software
    -rem    without specific prior written permission.
    -rem
    -rem THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
    -rem "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
    -rem LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
    -rem FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
    -rem COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
    -rem INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
    -rem BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
    -rem OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
    -rem AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
    -rem LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
    -rem ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
    -rem POSSIBILITY OF SUCH DAMAGE.
    -
    -rem This is the location where I installed in the MinGW compiler. With
    -rem this configuration, it is recommended that you do NOT install the
    -rem MSYS tools; they conflict with the GNUWin32 tools.  See
    -rem http://www.mingw.org/ for further info.
    -
    -set PATH=C:\MinGW\bin;%PATH%
    -
    -rem This is the location where I installed the SDCC toolchain for windows.
    -
    -set PATH=C:\Program Files (x86)\SDCC/bin;%PATH%
    -
    -rem This is the location where I installed the GNUWin32 tools.  See
    -rem http://gnuwin32.sourceforge.net/.
    -
    -set PATH=C:\gnuwin32\bin;%PATH%
    -echo %PATH%
    diff --git a/configs/z80sim/pashello/setenv.bat b/configs/z80sim/pashello/setenv.bat
    deleted file mode 100644
    index 59c372ddd9..0000000000
    --- a/configs/z80sim/pashello/setenv.bat
    +++ /dev/null
    @@ -1,50 +0,0 @@
    -@echo off
    -
    -rem configs/z80sim/pashello/setenv.bat
    -rem
    -rem   Copyright (C) 2012 Gregory Nutt. All rights reserved.
    -rem   Author: Gregory Nutt 
    -rem
    -rem Redistribution and use in source and binary forms, with or without
    -rem modification, are permitted provided that the following conditions
    -rem are met:
    -rem
    -rem 1. Redistributions of source code must retain the above copyright
    -rem    notice, this list of conditions and the following disclaimer.
    -rem 2. Redistributions in binary form must reproduce the above copyright
    -rem    notice, this list of conditions and the following disclaimer in
    -rem    the documentation and/or other materials provided with the
    -rem    distribution.
    -rem 3. Neither the name NuttX nor the names of its contributors may be
    -rem    used to endorse or promote products derived from this software
    -rem    without specific prior written permission.
    -rem
    -rem THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
    -rem "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
    -rem LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
    -rem FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
    -rem COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
    -rem INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
    -rem BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
    -rem OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
    -rem AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
    -rem LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
    -rem ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
    -rem POSSIBILITY OF SUCH DAMAGE.
    -
    -rem This is the location where I installed in the MinGW compiler. With
    -rem this configuration, it is recommended that you do NOT install the
    -rem MSYS tools; they conflict with the GNUWin32 tools.  See
    -rem http://www.mingw.org/ for further info.
    -
    -set PATH=C:\MinGW\bin;%PATH%
    -
    -rem This is the location where I installed the SDCC toolchain for windows.
    -
    -set PATH=C:\Program Files (x86)\SDCC/bin;%PATH%
    -
    -rem This is the location where I installed the GNUWin32 tools.  See
    -rem http://gnuwin32.sourceforge.net/.
    -
    -set PATH=C:\gnuwin32\bin;%PATH%
    -echo %PATH%
    diff --git a/configs/z80sim/scripts/setenv.bat b/configs/z80sim/scripts/setenv.bat
    deleted file mode 100644
    index c266d1e818..0000000000
    --- a/configs/z80sim/scripts/setenv.bat
    +++ /dev/null
    @@ -1,50 +0,0 @@
    -@echo off
    -
    -rem configs/z80sim/scripts/setenv.bat
    -rem
    -rem   Copyright (C) 2012 Gregory Nutt. All rights reserved.
    -rem   Author: Gregory Nutt 
    -rem
    -rem Redistribution and use in source and binary forms, with or without
    -rem modification, are permitted provided that the following conditions
    -rem are met:
    -rem
    -rem 1. Redistributions of source code must retain the above copyright
    -rem    notice, this list of conditions and the following disclaimer.
    -rem 2. Redistributions in binary form must reproduce the above copyright
    -rem    notice, this list of conditions and the following disclaimer in
    -rem    the documentation and/or other materials provided with the
    -rem    distribution.
    -rem 3. Neither the name NuttX nor the names of its contributors may be
    -rem    used to endorse or promote products derived from this software
    -rem    without specific prior written permission.
    -rem
    -rem THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
    -rem "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
    -rem LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
    -rem FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
    -rem COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
    -rem INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
    -rem BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
    -rem OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
    -rem AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
    -rem LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
    -rem ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
    -rem POSSIBILITY OF SUCH DAMAGE.
    -
    -rem This is the location where I installed in the MinGW compiler. With
    -rem this configuration, it is recommended that you do NOT install the
    -rem MSYS tools; they conflict with the GNUWin32 tools.  See
    -rem http://www.mingw.org/ for further info.
    -
    -set PATH=C:\MinGW\bin;%PATH%
    -
    -rem This is the location where I installed the SDCC toolchain for windows.
    -
    -set PATH=C:\Program Files (x86)\SDCC/bin;%PATH%
    -
    -rem This is the location where I installed the GNUWin32 tools.  See
    -rem http://gnuwin32.sourceforge.net/.
    -
    -set PATH=C:\gnuwin32\bin;%PATH%
    -echo %PATH%
    diff --git a/configs/z8encore000zco/README.txt b/configs/z8encore000zco/README.txt
    index 85cb56f52c..35e2484f2e 100644
    --- a/configs/z8encore000zco/README.txt
    +++ b/configs/z8encore000zco/README.txt
    @@ -34,15 +34,15 @@ Version 5.0.0
     
       Paths were also updated that are specific to a 32-bit toolchain running on
       a 64 bit windows platform.  Change to a different toolchain, you will need
    -  to modify the versioning in Make.defs and setenv.sh; if you want to build
    +  to modify the versioning in the Make.defs file; if you want to build
       on a different platform, you will need to change the path in the ZDS binaries
    -  in those same files.
    +  in those that file and also in your patch variable.
     
     Other Versions
       If you use any version of ZDS-II other than 5.0.0 or if you install ZDS-II
       at any location other than the default location, you will have to modify
    -  two files:  (1) configs/z8encore000zco/*/setenv.sh and (2)
    -  configs/z8encore000zco/*/Make.defs.
    +  the configs/z8encore000zco/*/Make.defs file and your PATH environment
    +  variable.
     
     Configuration Subdirectories
     ^^^^^^^^^^^^^^^^^^^^^^^^^^^^
    @@ -98,9 +98,7 @@ available:
              will need to use the short 8.3 filenames to avoid spaces.  On my
              PC, C:\PROGRA~1\ is is C:\Program Files\ and C:\PROGRA~2\ is
              C:\Program Files (x86)\
    -      b. You can't use setenv.sh in the native Windows environment.  Try
    -         scripts/setenv.bat instead.
    -      c. At present, the native Windows build fails at the final link stages.
    +      b. At present, the native Windows build fails at the final link stages.
              The failure is due to problems in arch/z80/src/nuttx.linkcmd that
              is autogenerated by arch/z80/src/Makefile.zdsii.  The basic problem
              is the spurious spaces and and carrirage returns are generated at
    diff --git a/configs/z8encore000zco/scripts/setenv.bat b/configs/z8encore000zco/scripts/setenv.bat
    deleted file mode 100644
    index 407cca97fe..0000000000
    --- a/configs/z8encore000zco/scripts/setenv.bat
    +++ /dev/null
    @@ -1,50 +0,0 @@
    -@echo off
    -
    -rem configs/z8encore000zco/scripts/setenv.bat
    -rem
    -rem   Copyright (C) 2012 Gregory Nutt. All rights reserved.
    -rem   Author: Gregory Nutt 
    -rem
    -rem Redistribution and use in source and binary forms, with or without
    -rem modification, are permitted provided that the following conditions
    -rem are met:
    -rem
    -rem 1. Redistributions of source code must retain the above copyright
    -rem    notice, this list of conditions and the following disclaimer.
    -rem 2. Redistributions in binary form must reproduce the above copyright
    -rem    notice, this list of conditions and the following disclaimer in
    -rem    the documentation and/or other materials provided with the
    -rem    distribution.
    -rem 3. Neither the name NuttX nor the names of its contributors may be
    -rem    used to endorse or promote products derived from this software
    -rem    without specific prior written permission.
    -rem
    -rem THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
    -rem "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
    -rem LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
    -rem FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
    -rem COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
    -rem INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
    -rem BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
    -rem OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
    -rem AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
    -rem LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
    -rem ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
    -rem POSSIBILITY OF SUCH DAMAGE.
    -
    -rem This is the location where I installed in the MinGW compiler. With
    -rem this configuration, it is recommended that you do NOT install the
    -rem MSYS tools; they conflict with the GNUWin32 tools.  See
    -rem http://www.mingw.org/ for further info.
    -
    -set PATH=C:\MinGW\bin;%PATH%
    -
    -rem This is the location where I installed the ZDS-II toolchain.
    -
    -set PATH=C:\Program Files (x86)\ZiLOG\ZDSII_Z8Encore!_5.0.0\bin;%PATH%
    -
    -rem This is the location where I installed the GNUWin32 tools.  See
    -rem http://gnuwin32.sourceforge.net/.
    -
    -set PATH=C:\gnuwin32\bin;%PATH%
    -echo %PATH%
    diff --git a/configs/z8f64200100kit/README.txt b/configs/z8f64200100kit/README.txt
    index 142ea785e1..69c69acdf9 100644
    --- a/configs/z8f64200100kit/README.txt
    +++ b/configs/z8f64200100kit/README.txt
    @@ -34,15 +34,15 @@ Version 5.0.0
     
       Paths were also updated that are specific to a 32-bit toolchain running on
       a 64 bit windows platform.  Change to a different toolchain, you will need
    -  to modify the versioning in Make.defs and setenv.sh; if you want to build
    +  to modify the versioning in the Make.defs file; if you want to build
       on a different platform, you will need to change the path in the ZDS binaries
    -  in those same files.
    +  in those that file and also in your PATH variable.
     
     Other Versions
       If you use any version of ZDS-II other than 5.0.0 or if you install ZDS-II
       at any location other than the default location, you will have to modify
    -  two files:  (1) configs/z8f64200100kit/*/setenv.sh and (2)
    -  configs/z8f64200100kit/*/Make.defs.
    +  the configs/z8f64200100kit/*/Make.defs file and also your PATH environment
    +  variable.
     
     Configuration Subdirectories
     ^^^^^^^^^^^^^^^^^^^^^^^^^^^^
    @@ -98,9 +98,7 @@ available:
              will need to use the short 8.3 filenames to avoid spaces.  On my
              PC, C:\PROGRA~1\ is is C:\Program Files\ and C:\PROGRA~2\ is
              C:\Program Files (x86)\
    -      b. You can't use setenv.sh in the native Windows environment.  Try
    -         scripts/setenv.bat instead.
    -      c. At present, the native Windows build fails at the final link stages.
    +      b. At present, the native Windows build fails at the final link stages.
              The failure is due to problems in arch/z80/src/nuttx.linkcmd that
              is autogenerated by arch/z80/src/Makefile.zdsii.  The basic problem
              is the spurious spaces and and carrirage returns are generated at
    diff --git a/configs/z8f64200100kit/scripts/setenv.bat b/configs/z8f64200100kit/scripts/setenv.bat
    deleted file mode 100644
    index e0526d988a..0000000000
    --- a/configs/z8f64200100kit/scripts/setenv.bat
    +++ /dev/null
    @@ -1,50 +0,0 @@
    -@echo off
    -
    -rem configs/z8f64200100kit/scripts/setenv.bat
    -rem
    -rem   Copyright (C) 2012 Gregory Nutt. All rights reserved.
    -rem   Author: Gregory Nutt 
    -rem
    -rem Redistribution and use in source and binary forms, with or without
    -rem modification, are permitted provided that the following conditions
    -rem are met:
    -rem
    -rem 1. Redistributions of source code must retain the above copyright
    -rem    notice, this list of conditions and the following disclaimer.
    -rem 2. Redistributions in binary form must reproduce the above copyright
    -rem    notice, this list of conditions and the following disclaimer in
    -rem    the documentation and/or other materials provided with the
    -rem    distribution.
    -rem 3. Neither the name NuttX nor the names of its contributors may be
    -rem    used to endorse or promote products derived from this software
    -rem    without specific prior written permission.
    -rem
    -rem THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
    -rem "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
    -rem LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
    -rem FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
    -rem COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
    -rem INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
    -rem BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
    -rem OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
    -rem AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
    -rem LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
    -rem ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
    -rem POSSIBILITY OF SUCH DAMAGE.
    -
    -rem This is the location where I installed in the MinGW compiler. With
    -rem this configuration, it is recommended that you do NOT install the
    -rem MSYS tools; they conflict with the GNUWin32 tools.  See
    -rem http://www.mingw.org/ for further info.
    -
    -set PATH=C:\MinGW\bin;%PATH%
    -
    -rem This is the location where I installed the ZDS-II toolchain.
    -
    -set PATH=C:\Program Files (x86)\ZiLOG\ZDSII_Z8Encore!_5.0.0\bin;%PATH%
    -
    -rem This is the location where I installed the GNUWin32 tools.  See
    -rem http://gnuwin32.sourceforge.net/.
    -
    -set PATH=C:\gnuwin32\bin;%PATH%
    -echo %PATH%
    diff --git a/configs/zkit-arm-1769/README.txt b/configs/zkit-arm-1769/README.txt
    index b645c7f6b2..3a26764bba 100644
    --- a/configs/zkit-arm-1769/README.txt
    +++ b/configs/zkit-arm-1769/README.txt
    @@ -171,9 +171,6 @@ GNU Toolchain Options
         CONFIG_ARMV7M_TOOLCHAIN_CODEREDL=y      : Code Red toolchain under Linux
         CONFIG_ARMV7M_TOOLCHAIN_ATOLLIC=y       : The Atollic toolchain
     
    -  You may also have to modify the PATH in the setenv.h file if your make cannot
    -  find the tools.
    -
       NOTE: the CodeSourcery (for Windows), devkitARM, and Code Red (for Windoes)
       are Windows native toolchains.  The CodeSourcey (for Linux), Code Red (for Linux)
       and NuttX buildroot toolchains are Cygwin and/or Linux native toolchains. There
    @@ -208,9 +205,9 @@ GNU Toolchain Options
     NuttX buildroot Toolchain
     ^^^^^^^^^^^^^^^^^^^^^^^^^
     
    -  A GNU GCC-based toolchain is assumed.  The files */setenv.sh should
    -  be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
    -  different from the default in your PATH variable).
    +  A GNU GCC-based toolchain is assumed.  The PATH variable should be modified to
    +  point to the correct path to the Cortex-M3 GCC toolchain (if different from the
    +  default in your PATH variable).
     
       If you have no Cortex-M3 toolchain, one can be downloaded from the NuttX
       Bitbucket download site (https://bitbucket.org/nuttx/nuttx/downloads/).
    @@ -235,8 +232,8 @@ NuttX buildroot Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly built binaries.
    +  8. Make sure that your PATH variable includes the path to the newly built
    +     binaries.
     
       See the file configs/README.txt in the buildroot source tree.  That has more
       detailed PLUS some special instructions that you will need to follow if you
    @@ -280,8 +277,8 @@ NXFLAT Toolchain
     
       7. make
     
    -  8. Edit setenv.h, if necessary, so that the PATH variable includes
    -     the path to the newly builtNXFLAT binaries.
    +  8. Make sure that the PATH variable includes the path to the newly built
    +     NXFLAT binaries.
     
     LEDs
     ^^^^
    @@ -521,7 +518,6 @@ selected as follow:
         cd tools
         ./configure.sh zkit-arm-1769/
         cd -
    -    . ./setenv.sh
     
     Where  is one of the following:
     
    diff --git a/configs/zp214xpa/README.txt b/configs/zp214xpa/README.txt
    index 471d648e04..ca4f79038e 100644
    --- a/configs/zp214xpa/README.txt
    +++ b/configs/zp214xpa/README.txt
    @@ -236,9 +236,8 @@ Using OpenOCD and GDB with an FT2232 JTAG emulator
     
           configs/zp214xpa/tools/oocd.sh $PWD
     
    -    If you use the setenv.sh file, that the path to oocd.sh will be added
    -    to your PATH environment variabl.  So, in that case, the command simplifies
    -    to just:
    +    If you add that path to your PATH environment variable, ithe commandi
    +    simplifies to just:
     
           oocd.sh $PWD
     
    @@ -288,7 +287,6 @@ Configurations:
         cd tools
         ./configure.sh zp214xpa/
         cd -
    -    . ./setenv.sh
     
       Where  is one of the following:
     
    -- 
    GitLab
    
    
    From 2f9028b54762e628ffc8ed847bef46d1cbf70047 Mon Sep 17 00:00:00 2001
    From: Gregory Nutt 
    Date: Wed, 26 Apr 2017 10:28:37 -0600
    Subject: [PATCH 591/990] Remove all remaining references to setenv.h and
     setenv.bat.
    
    ---
     .gitignore                           |  2 --
     Documentation/NuttxPortingGuide.html | 28 ++++--------------
     Makefile.unix                        |  2 --
     Makefile.win                         |  2 --
     README.txt                           | 24 ++++------------
     arch/avr/src/avr/Kconfig             | 11 -------
     configs/nucleo-144/README.txt        |  4 +--
     configs/nucleo-f4x1re/README.txt     | 12 ++++----
     configs/nucleo-l476rg/README.txt     | 12 ++++----
     tools/configure.c                    | 43 ----------------------------
     tools/configure.sh                   | 24 +---------------
     11 files changed, 26 insertions(+), 138 deletions(-)
    
    diff --git a/.gitignore b/.gitignore
    index 42240bd35d..fd06298905 100644
    --- a/.gitignore
    +++ b/.gitignore
    @@ -14,8 +14,6 @@ core
     /.config.old
     /.version
     /Make.defs
    -/setenv.sh
    -/setenv.bat
     /nuttx
     /nuttx.*
     /nuttx-*
    diff --git a/Documentation/NuttxPortingGuide.html b/Documentation/NuttxPortingGuide.html
    index 2e20d72ac9..0923a1786b 100644
    --- a/Documentation/NuttxPortingGuide.html
    +++ b/Documentation/NuttxPortingGuide.html
    @@ -742,12 +742,10 @@
     |   `-- (board-specific source files)
     |-- <config1-dir>
     |   |-- Make.defs
    -|   |-- defconfig
    -|   `-- setenv.sh
    +|   `-- defconfig
     |-- <config2-dir>
     |   |-- Make.defs
    -|   |-- defconfig
    -|   `-- setenv.sh
    +|   `-- defconfig
     |   ...
     `-- (other board-specific configuration sub-directories)/
     
    @@ -780,7 +778,7 @@ The configs/<board-name>/ sub-directory holds all of the files that are necessary to configure NuttX for the particular board. A board may have various different configurations using the common source files. - Each board configuration is described by three files: Make.defs, defconfig, and setenv.sh. + Each board configuration is described by two files: Make.defs and defconfig. Typically, each set of configuration files is retained in a separate configuration sub-directory (<config1-dir>, <config2-dir>, .. in the above diagram). @@ -836,15 +834,6 @@ most C files in the system.
  • -
  • -

    - setenv.sh: This is a script that can be included that will be installed at - the top level of the directory structure and can be sourced to set any - necessary environment variables. - You will most likely have to customize the default setenv.sh script in order - for it to work correctly in your environment. -

    -
  • 2.5.3 Supported Boards

    @@ -1364,7 +1353,6 @@ tools/

    • Copy configs/<board-name>/[<config-dir>/]Make.defs to ${TOPDIR}/Make.defs,
    • -
    • Copy configs/<board-name>/[<config-dir>/]setenv.sh to ${TOPDIR}/setenv.sh, and
    • Copy configs/<board-name>/[<config-dir>/]defconfig to ${TOPDIR}/.config
    @@ -1464,7 +1452,6 @@ tools/version.h -v 6.1 .version

       cd ${TOPDIR}
      -source ./setenv.sh
       make
       

    @@ -1477,15 +1464,12 @@ make That directory also holds:

      -
    • The makefile fragment .config that describes the current configuration.
    • -
    • The makefile fragment Make.defs that provides customized build targets, and
    • -
    • The shell script setenv.sh that sets up the configuration environment for the build.
    • +
    • The makefile fragment .config that describes the current configuration, and
    • +
    • The makefile fragment Make.defs that provides customized build targets.

    -The setenv.sh contains Linux/Cygwin environmental settings that are needed for the build. +Environment Variables. The specific environmental definitions are unique for each board but should include, as a minimum, updates to the PATH variable to include the full path to the architecture-specific toolchain identified in Make.defs. -The setenv.sh only needs to be source'ed at the beginning of a session. -The system can be re-made subsequently by just typing make.

    First Time Make. diff --git a/Makefile.unix b/Makefile.unix index d816947a38..b7bf86b805 100644 --- a/Makefile.unix +++ b/Makefile.unix @@ -558,8 +558,6 @@ ifeq ($(CONFIG_BUILD_2PASS),y) $(Q) $(MAKE) -C $(CONFIG_PASS1_BUILDIR) TOPDIR="$(TOPDIR)" distclean endif $(call DELFILE, Make.defs) - $(call DELFILE, setenv.sh) - $(call DELFILE, setenv.bat) $(call DELFILE, .config) $(call DELFILE, .config.old) diff --git a/Makefile.win b/Makefile.win index feb94d5eb3..e1d9bc1278 100644 --- a/Makefile.win +++ b/Makefile.win @@ -536,8 +536,6 @@ ifeq ($(CONFIG_BUILD_2PASS),y) $(Q) $(MAKE) -C $(CONFIG_PASS1_BUILDIR) TOPDIR="$(TOPDIR)" distclean endif $(call DELFILE, Make.defs) - $(call DELFILE, setenv.sh) - $(call DELFILE, setenv.bat) $(call DELFILE, .config) $(call DELFILE, .config.old) diff --git a/README.txt b/README.txt index de771d53c7..f06800339f 100644 --- a/README.txt +++ b/README.txt @@ -550,13 +550,6 @@ Instantiating "Canned" Configurations and link code. You may need to modify this file to match the specific needs of your toolchain. - Copy configs///setenv.sh to ${TOPDIR}/setenv.sh - - setenv.sh is an optional convenience file that I use to set - the PATH variable to the toolchain binaries. You may chose to - use setenv.sh or not. If you use it, then it may need to be - modified to include the path to your toolchain binaries. - Copy configs///defconfig to ${TOPDIR}/.config The defconfig file holds the actual build configuration. This @@ -928,10 +921,8 @@ Cross-Development Toolchains That README file contains suggestions and information about appropriate tools and development environments for use with your board. - In any case, the script, setenv.sh that was deposited in the top- - level directory when NuttX was configured should be edited to set - the path to where you installed the toolchain. The use of setenv.sh - is optional but can save a lot of confusion in the future. + In any case, the PATH environment variable will need to be updated to + include the loction where the build can find the toolchain binaries. NuttX Buildroot Toolchain ------------------------- @@ -1009,12 +1000,11 @@ Building NuttX builds in-place in the source tree. You do not need to create any special build directories. Assuming that your Make.defs is setup - properly for your tool chain and that setenv.sh contains the path to where - your cross-development tools are installed, the following steps are all that - are required to build NuttX: + properly for your tool chain and that PATH environment variable contains + the path to where your cross-development tools are installed, the + following steps are all that are required to build NuttX: cd ${TOPDIR} - . ./setenv.sh make At least one configuration (eagle100) requires additional command line @@ -1186,10 +1176,6 @@ Native Windows Build (2) it still lacks some of the creature-comforts of the more mature environments. - There is an alternative to the setenv.sh script available for the Windows - native environment: tools/configure.bat. See tools/README.txt for additional - information. - Installing GNUWin32 ------------------- diff --git a/arch/avr/src/avr/Kconfig b/arch/avr/src/avr/Kconfig index 2ddfa4e194..ef55b1d620 100644 --- a/arch/avr/src/avr/Kconfig +++ b/arch/avr/src/avr/Kconfig @@ -19,9 +19,6 @@ config AVR_WINAVR_TOOLCHAIN For Cygwin development environment on Windows machines, you can use WinAVR: http://sourceforge.net/projects/winavr/files/ - It is assumed in some places that WinAVR is installed at - C:/WinAVR. Edit the setenv.sh file if this is not the case. - WARNING: There is an incompatible version of cygwin.dll in the WinAVR/bin directory! Make sure that the path to the correct cygwin.dll file precedes the path to the WinAVR @@ -49,10 +46,6 @@ config AVR_CROSSPACK_TOOLCHAIN For OS X, the AVR CrossPack toolchain is supported: http://www.obdev.at/products/crosspack/index.html - It is assumed that /usr/local/CrossPack-AVR/bin is on the - user's path. Edit the setenv.sh file if this is not the - case. - config AVR_BUILDROOT_TOOLCHAIN bool "Buildroot" ---help--- @@ -60,10 +53,6 @@ config AVR_BUILDROOT_TOOLCHAIN http://sourceforge.net/projects/nuttx/files/buildroot/. See the following section for details on building this toolchain. - It is assumed in some places that buildroot toolchain is - available at ../buildroot/build_avr. Edit the setenv.sh - file if this is not the case. - endchoice # Toolchain menu "Atmel AVR Toolchain options" diff --git a/configs/nucleo-144/README.txt b/configs/nucleo-144/README.txt index cb6d65692f..db816dd5c6 100644 --- a/configs/nucleo-144/README.txt +++ b/configs/nucleo-144/README.txt @@ -173,8 +173,8 @@ Development Environment All testing has been conducted using the GNU toolchain from ARM for Linux. found here https://launchpad.net/gcc-arm-embedded/4.9/4.9-2015-q3-update/+download/gcc-arm-none-eabi-4_9-2015q3-20150921-linux.tar.bz2 - If you change the default toolchain, then you may also have to modify the PATH in - the setenv.h file if your make cannot find the tools. + If you change the default toolchain, then you may also have to modify the + PATH environment variable to include the path to the toolchain binaries. IDEs ==== diff --git a/configs/nucleo-f4x1re/README.txt b/configs/nucleo-f4x1re/README.txt index f22b3c6e19..e74a2ecb7d 100644 --- a/configs/nucleo-f4x1re/README.txt +++ b/configs/nucleo-f4x1re/README.txt @@ -140,8 +140,8 @@ GNU Toolchain Options CONFIG_ARMV7M_TOOLCHAIN_RAISONANCE=y : Raisonance RIDE7 under Windows CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=n : NuttX buildroot under Linux or Cygwin (default) - If you change the default toolchain, then you may also have to modify the PATH in - the setenv.h file if your make cannot find the tools. + If you change the default toolchain, then you may also have to modify the + PATH environment variable to include the path to the toolchain binaries. NOTE: There are several limitations to using a Windows based toolchain in a Cygwin environment. The three biggest are: @@ -280,8 +280,8 @@ NuttX EABI "buildroot" Toolchain 7. make - 8. Edit setenv.h, if necessary, so that the PATH variable includes - the path to the newly built binaries. + 8. Make sure that the PATH variable includes the path to the newly built + binaries. See the file configs/README.txt in the buildroot source tree. That has more details PLUS some special instructions that you will need to follow if you are @@ -322,8 +322,8 @@ NXFLAT Toolchain 7. make - 8. Edit setenv.h, if necessary, so that the PATH variable includes - the path to the newly builtNXFLAT binaries. + 8. Make sure that the PATH variable includes the path to the newly built + NXFLAT binaries. mbed ==== diff --git a/configs/nucleo-l476rg/README.txt b/configs/nucleo-l476rg/README.txt index 497035e4a8..f216b93cf7 100644 --- a/configs/nucleo-l476rg/README.txt +++ b/configs/nucleo-l476rg/README.txt @@ -116,8 +116,8 @@ GNU Toolchain Options CONFIG_ARMV7M_TOOLCHAIN_RAISONANCE=y : Raisonance RIDE7 under Windows CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=n : NuttX buildroot under Linux or Cygwin (default) - If you change the default toolchain, then you may also have to modify the PATH in - the setenv.h file if your make cannot find the tools. + If you change the default toolchain, then you may also have to modify the + PATH environment variable to include the path to the toolchain binaries. NOTE: There are several limitations to using a Windows based toolchain in a Cygwin environment. The three biggest are: @@ -262,8 +262,8 @@ NuttX EABI "buildroot" Toolchain 7. make - 8. Edit setenv.h, if necessary, so that the PATH variable includes - the path to the newly built binaries. + 8. Make sure that the PATH variable includes the path to the newly built + binaries. See the file configs/README.txt in the buildroot source tree. That has more details PLUS some special instructions that you will need to follow if you are @@ -304,8 +304,8 @@ NXFLAT Toolchain 7. make - 8. Edit setenv.h, if necessary, so that the PATH variable includes - the path to the newly builtNXFLAT binaries. + 8. Make sure that the PATH variable includes the path to the newly built + NXFLAT binaries. mbed ==== diff --git a/tools/configure.c b/tools/configure.c index fcf0407e48..8a40981d2b 100644 --- a/tools/configure.c +++ b/tools/configure.c @@ -87,8 +87,6 @@ static char *g_verstring = "0.0"; /* Version String */ static char *g_srcdefconfig = NULL; /* Source defconfig file */ static char *g_srcmakedefs = NULL; /* Source Make.defs file */ -static char *g_srcsetenvsh = NULL; /* Source setenv.sh file (optional) */ -static char *g_srcsetenvbat = NULL; /* Source setenv.bat file (optional) */ static bool g_winnative = false; /* True: Windows native configuration */ static bool g_needapppath = true; /* Need to add app path to the .config file */ @@ -634,29 +632,6 @@ static void check_configuration(void) } g_srcmakedefs = strdup(g_buffer); - - /* Windows native configurations may provide setenv.bat; POSIX - * configurations may provide a setenv.sh. - */ - - if (g_winnative) - { - snprintf(g_buffer, BUFFER_SIZE, "%s%csetenv.bat", g_configpath, g_delim); - debug("check_configuration: Checking %s\n", g_buffer); - if (verify_file(g_buffer)) - { - g_srcsetenvbat = strdup(g_buffer); - } - } - else - { - snprintf(g_buffer, BUFFER_SIZE, "%s%csetenv.sh", g_configpath, g_delim); - debug("check_configuration: Checking %s\n", g_buffer); - if (verify_file(g_buffer)) - { - g_srcsetenvsh = strdup(g_buffer); - } - } } static void copy_file(const char *srcpath, const char *destpath, mode_t mode) @@ -756,24 +731,6 @@ static void configure(void) debug("configure: Copying from %s to %s\n", g_srcmakedefs, g_buffer); copy_file(g_srcmakedefs, g_buffer, 0644); - /* Copy the setenv.sh file if have one and need one */ - - if (g_srcsetenvsh) - { - snprintf(g_buffer, BUFFER_SIZE, "%s%csetenv.sh", g_topdir, g_delim); - debug("configure: Copying from %s to %s\n", g_srcsetenvsh, g_buffer); - copy_file(g_srcsetenvsh, g_buffer, 0755); - } - - /* Copy the setenv.bat file if have one and need one */ - - if (g_srcsetenvbat) - { - snprintf(g_buffer, BUFFER_SIZE, "%s%csetenv.bat", g_topdir, g_delim); - debug("configure: Copying from %s to %s\n", g_srcsetenvbat, g_buffer); - copy_file(g_srcsetenvbat, g_buffer, 0644); - } - /* If we did not use the CONFIG_APPS_DIR that was in the defconfig config file, * then append the correct application information to the tail of the .config * file diff --git a/tools/configure.sh b/tools/configure.sh index 3ee734d6e9..41e9223771 100755 --- a/tools/configure.sh +++ b/tools/configure.sh @@ -108,22 +108,6 @@ if [ ! -r "${src_makedefs}" ]; then exit 4 fi -src_setenv="${configpath}/setenv.sh" -unset have_setenv - -if [ -r "${src_setenv}" ]; then - dest_setenv=${TOPDIR}/setenv.sh - have_setenv=y -else - src_setenv="${configpath}/setenv.bat" - if [ -r "${src_setenv}" ]; then - dest_setenv=${TOPDIR}/setenv.bat - have_setenv=y - else - unset src_setenv - fi -fi - src_config="${configpath}/defconfig" dest_config="${TOPDIR}/.config" @@ -134,8 +118,7 @@ fi # Extract values needed from the defconfig file. We need: # (1) The CONFIG_WINDOWS_NATIVE setting to know it this is target for a -# native Windows (meaning that we want setenv.bat vs setenv.sh and we need -# to use backslashes in the CONFIG_APPS_DIR setting). +# native Windows # (2) The CONFIG_APPS_DIR setting to see if there is a configured location for the # application directory. This can be overridden from the command line. @@ -191,11 +174,6 @@ fi install -m 644 "${src_makedefs}" "${dest_makedefs}" || \ { echo "Failed to copy \"${src_makedefs}\"" ; exit 7 ; } -if [ "X${have_setenv}" = "Xy" ]; then - install "${src_setenv}" "${dest_setenv}" || \ - { echo "Failed to copy ${src_setenv}" ; exit 8 ; } - chmod 755 "${dest_setenv}" -fi install -m 644 "${src_config}" "${dest_config}" || \ { echo "Failed to copy \"${src_config}\"" ; exit 9 ; } -- GitLab From e8358031666c5d6036c702da0dcf3c82ad94d946 Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Wed, 26 Apr 2017 10:38:15 -0600 Subject: [PATCH 592/990] yslog: use monotonic clock for timestamp when available --- drivers/syslog/vsyslog.c | 20 +++++++++++++++++--- sched/clock/clock_initialize.c | 3 ++- 2 files changed, 19 insertions(+), 4 deletions(-) diff --git a/drivers/syslog/vsyslog.c b/drivers/syslog/vsyslog.c index 27fab399ec..ba0d3726f8 100644 --- a/drivers/syslog/vsyslog.c +++ b/drivers/syslog/vsyslog.c @@ -1,7 +1,7 @@ /**************************************************************************** * drivers/syslog/vsyslog.c * - * Copyright (C) 2007-2009, 2011-2014, 2016 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009, 2011-2014, 2016-2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -70,15 +70,29 @@ int _vsyslog(int priority, FAR const IPTR char *fmt, FAR va_list *ap) struct lib_outstream_s stream; #ifdef CONFIG_SYSLOG_TIMESTAMP struct timespec ts; + int ret = -1; /* Get the current time. Since debug output may be generated very early * in the start-up sequence, hardware timer support may not yet be * available. */ - if (!OSINIT_HW_READY() || clock_systimespec(&ts) < 0) + if (OSINIT_HW_READY()) { - /* Timer hardware is not available, or clock_systimespec failed */ + /* Prefer monotonic when enabled, as it can be synchronized to + * RTC with clock_resynchronize. + */ + +#ifdef CONFIG_CLOCK_MONOTONIC + ret = clock_gettime(CLOCK_MONOTONIC, &ts); +#else + ret = clock_systimespec(&ts); +#endif + } + + if (ret < 0) + { + /* Timer hardware is not available, or clock function failed */ ts.tv_sec = 0; ts.tv_nsec = 0; diff --git a/sched/clock/clock_initialize.c b/sched/clock/clock_initialize.c index d8a7b13497..ca565c9c8a 100644 --- a/sched/clock/clock_initialize.c +++ b/sched/clock/clock_initialize.c @@ -68,7 +68,8 @@ #define SEC_PER_HOUR ((time_t)60 * SEC_PER_MIN) #define SEC_PER_DAY ((time_t)24 * SEC_PER_HOUR) -#if defined(CONFIG_DEBUG_FEATURES) && defined(CONFIG_SYSTEM_TIME64) +#if defined(CONFIG_DEBUG_FEATURES) && defined(CONFIG_SYSTEM_TIME64) && \ + defined(CONFIG_CLOCK_MONOTONIC) /* Initial system timer ticks value close to maximum 32-bit value, to test * 64-bit system-timer after going over 32-bit value. This is to make errors * of casting 64-bit system-timer to 32-bit variables more visible. -- GitLab From 804395e2c69bf711167ba2f42c52aa329ebaa024 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 26 Apr 2017 10:40:39 -0600 Subject: [PATCH 593/990] Remove /configs/clicker2-stm32/mrf24j40-radio/setenv.sh --- .../clicker2-stm32/mrf24j40-radio/setenv.sh | 80 ------------------- 1 file changed, 80 deletions(-) delete mode 100644 configs/clicker2-stm32/mrf24j40-radio/setenv.sh diff --git a/configs/clicker2-stm32/mrf24j40-radio/setenv.sh b/configs/clicker2-stm32/mrf24j40-radio/setenv.sh deleted file mode 100644 index a235db68fb..0000000000 --- a/configs/clicker2-stm32/mrf24j40-radio/setenv.sh +++ /dev/null @@ -1,80 +0,0 @@ -#!/bin/bash -# configs/clicker2-stm32/mrf24j40-radio/setenv.sh -# -# 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. -# - -if [ "$_" = "$0" ] ; then - echo "You must source this script, not run it!" 1>&2 - exit 1 -fi - -WD=`pwd` -if [ ! -x "setenv.sh" ]; then - echo "This script must be executed from the top-level NuttX build directory" - exit 1 -fi - -if [ -z "${PATH_ORIG}" ]; then - export PATH_ORIG="${PATH}" -fi - -# This is the Cygwin path to the location where I installed the CodeSourcery -# toolchain under windows. You will also have to edit this if you install -# the CodeSourcery toolchain in any other location -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin" -# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin" - -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors" -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin" - -# This is the path to the location where I installed the devkitARM toolchain -# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/ -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin" - -# These are the Cygwin paths to the locations where I installed the Atollic -# toolchain under windows. You will also have to edit this if you install -# the Atollic toolchain in any other location. /usr/bin is added before -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe -# at those locations as well. -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" - -# This is the Cygwin path to the location where I build the buildroot -# toolchain. -# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" - -# Add the path to the toolchain to the PATH varialble -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" - -echo "PATH : ${PATH}" -- GitLab From 1ae795a348b753adc6a82a344e93835ab85481da Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 26 Apr 2017 10:42:50 -0600 Subject: [PATCH 594/990] Remove ./configs/photon/wlan/setenv.sh --- configs/photon/wlan/setenv.sh | 84 ----------------------------------- 1 file changed, 84 deletions(-) delete mode 100644 configs/photon/wlan/setenv.sh diff --git a/configs/photon/wlan/setenv.sh b/configs/photon/wlan/setenv.sh deleted file mode 100644 index 0c2e88b407..0000000000 --- a/configs/photon/wlan/setenv.sh +++ /dev/null @@ -1,84 +0,0 @@ -#!/bin/bash -# configs/photon/wlan/setenv.sh -# -# 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. -# - -if [ "$_" = "$0" ] ; then - echo "You must source this script, not run it!" 1>&2 - exit 1 -fi - -WD=`pwd` -if [ ! -x "setenv.sh" ]; then - echo "This script must be executed from the top-level NuttX build directory" - exit 1 -fi - -if [ -z "${PATH_ORIG}" ]; then - export PATH_ORIG="${PATH}" -fi - -# This is the Cygwin path to the location where I installed the RIDE -# toolchain under windows. You will also have to edit this if you install -# the RIDE toolchain in any other location -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" - -# This is the Cygwin path to the location where I installed the CodeSourcery -# toolchain under windows. You will also have to edit this if you install -# the CodeSourcery toolchain in any other location -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" -#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin" - -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors" -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin" - -# These are the Cygwin paths to the locations where I installed the Atollic -# toolchain under windows. You will also have to edit this if you install -# the Atollic toolchain in any other location. /usr/bin is added before -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe -# at those locations as well. -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" - -# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors" -# You can this free toolchain here https://launchpad.net/gcc-arm-embedded -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin" - -# This is the Cygwin path to the location where I build the buildroot -# toolchain. -#export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" - -# Add the path to the toolchain to the PATH variable -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" - -echo "PATH : ${PATH}" -- GitLab From a1341780347cc3a350a01489c10b6767a3caafd2 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 26 Apr 2017 12:30:18 -0600 Subject: [PATCH 595/990] Enabled wireless IOCTL commands in photon/wlan configuration --- configs/photon/wlan/defconfig | 4 +- drivers/wireless/ieee80211/bcmf_netdev.c | 66 ++++++++++++++++++++++-- 2 files changed, 65 insertions(+), 5 deletions(-) diff --git a/configs/photon/wlan/defconfig b/configs/photon/wlan/defconfig index d1cae5539d..ca7cd23619 100644 --- a/configs/photon/wlan/defconfig +++ b/configs/photon/wlan/defconfig @@ -16,7 +16,7 @@ CONFIG_HOST_LINUX=y # # Build Configuration # -CONFIG_APPS_DIR="../apps" +# CONFIG_APPS_DIR="../apps" CONFIG_BUILD_FLAT=y # CONFIG_BUILD_2PASS is not set @@ -1005,7 +1005,7 @@ CONFIG_NET_ETHERNET=y # # CONFIG_NETDEV_IOCTL is not set # CONFIG_NETDEV_PHY_IOCTL is not set -# CONFIG_NETDEV_WIRELESS_IOCTL is not set +CONFIG_NETDEV_WIRELESS_IOCTL=y # # Internet Protocol Selection diff --git a/drivers/wireless/ieee80211/bcmf_netdev.c b/drivers/wireless/ieee80211/bcmf_netdev.c index 5d94d9e583..b81ced26dd 100644 --- a/drivers/wireless/ieee80211/bcmf_netdev.c +++ b/drivers/wireless/ieee80211/bcmf_netdev.c @@ -56,6 +56,7 @@ #include #include #include +#include #ifdef CONFIG_NET_PKT # include @@ -1088,14 +1089,73 @@ static int bcmf_ioctl(FAR struct net_driver_s *dev, int cmd, switch (cmd) { - /* Add cases here to support the IOCTL commands */ + case SIOCSIWFREQ: /* Set channel/frequency (Hz) */ + wlwarn("WARNING: SIOCSIWFREQ not implemented\n"); + ret = -ENOSYS; + break; + + case SIOCGIWFREQ: /* Get channel/frequency (Hz) */ + wlwarn("WARNING: SIOCGIWFREQ not implemented\n"); + ret = -ENOSYS; + break; + + case SIOCSIWMODE: /* Set operation mode */ + wlwarn("WARNING: SIOCSIWMODE not implemented\n"); + ret = -ENOSYS; + break; + + case SIOCGIWMODE: /* Get operation mode */ + wlwarn("WARNING: SIOCGIWMODE not implemented\n"); + ret = -ENOSYS; + break; + + case SIOCSIWAP: /* Set access point MAC addresses */ + wlwarn("WARNING: SIOCSIWAP not implemented\n"); + ret = -ENOSYS; + break; + + case SIOCGIWAP: /* Get access point MAC addresses */ + wlwarn("WARNING: SIOCGIWAP not implemented\n"); + ret = -ENOSYS; + break; + + case SIOCSIWESSID: /* Set ESSID (network name) */ + wlwarn("WARNING: SIOCSIWESSID not implemented\n"); + ret = -ENOSYS; + break; + + case SIOCGIWESSID: /* Get ESSID */ + wlwarn("WARNING: SIOCGIWESSID not implemented\n"); + ret = -ENOSYS; + break; + + case SIOCSIWRATE: /* Set default bit rate (bps) */ + wlwarn("WARNING: SIOCSIWRATE not implemented\n"); + ret = -ENOSYS; + break; + + case SIOCGIWRATE: /* Get default bit rate (bps) */ + wlwarn("WARNING: SIOCGIWRATE not implemented\n"); + ret = -ENOSYS; + break; + + case SIOCSIWTXPOW: /* Set transmit power (dBm) */ + wlwarn("WARNING: SIOCSIWTXPOW not implemented\n"); + ret = -ENOSYS; + break; + + case SIOCGIWTXPOW: /* Get transmit power (dBm) */ + wlwarn("WARNING: SIOCGIWTXPOW not implemented\n"); + ret = -ENOSYS; + break; default: nerr("ERROR: Unrecognized IOCTL command: %d\n", command); - return -ENOTTY; /* Special return value for this case */ + ret = -ENOTTY; /* Special return value for this case */ + break; } - return OK; + return ret; } #endif -- GitLab From 1cdc90914ee7543fb2c626e1f094d5114c7a32c6 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 26 Apr 2017 12:31:13 -0600 Subject: [PATCH 596/990] network IOCTLs: Correct a compilation error when wireless IOCTLs are enabled. --- net/netdev/netdev_ioctl.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/net/netdev/netdev_ioctl.c b/net/netdev/netdev_ioctl.c index 87b21e355f..23f81c5276 100644 --- a/net/netdev/netdev_ioctl.c +++ b/net/netdev/netdev_ioctl.c @@ -351,7 +351,7 @@ static int netdev_wifr_ioctl(FAR struct socket *psock, int cmd, { /* Get the wireless device associated with the IOCTL command */ - dev = netdev_findbyname(req->ifrn_name); + dev = netdev_findbyname(req->ifr_name); if (dev != NULL) { /* Just forward the IOCTL to the wireless driver */ -- GitLab From 707d1e67fcc4b34d9c9abead36dbec3abc640eb7 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Thu, 27 Apr 2017 07:18:36 -0600 Subject: [PATCH 597/990] STM32, STM32F7, STM32L4: Remove incorrect comment about STM32L1 LSE/RTC/LCD --- arch/arm/src/stm32/stm32_rcc.h | 12 ++++-------- arch/arm/src/stm32/stm32_waste.h | 2 +- arch/arm/src/stm32f7/stm32_rcc.h | 12 ++++-------- arch/arm/src/stm32l4/stm32l4_rcc.h | 10 +++------- 4 files changed, 12 insertions(+), 24 deletions(-) diff --git a/arch/arm/src/stm32/stm32_rcc.h b/arch/arm/src/stm32/stm32_rcc.h index d331ab90b6..79949cd60c 100644 --- a/arch/arm/src/stm32/stm32_rcc.h +++ b/arch/arm/src/stm32/stm32_rcc.h @@ -33,8 +33,8 @@ * ************************************************************************************/ -#ifndef __ARCH_ARM_SRC_STM32_STM32_RRC_H -#define __ARCH_ARM_SRC_STM32_STM32_RRC_H +#ifndef __ARCH_ARM_SRC_STM32_STM32_RCC_H +#define __ARCH_ARM_SRC_STM32_STM32_RCC_H /************************************************************************************ * Included Files @@ -299,11 +299,7 @@ void stm32_clockenable(void); * Name: stm32_rcc_enablelse * * Description: - * Enable the External Low-Speed (LSE) Oscillator and, if the RTC is - * configured, setup the LSE as the RTC clock source, and enable the RTC. - * - * For the STM32L15X family, this will also select the LSE as the clock source of - * the LCD. + * Enable the External Low-Speed (LSE) Oscillator. * * Input Parameters: * None @@ -340,4 +336,4 @@ void stm32_rcc_disablelsi(void); } #endif #endif /* __ASSEMBLY__ */ -#endif /* __ARCH_ARM_SRC_STM32_STM32_RRC_H */ +#endif /* __ARCH_ARM_SRC_STM32_STM32_RCC_H */ diff --git a/arch/arm/src/stm32/stm32_waste.h b/arch/arm/src/stm32/stm32_waste.h index 4d13700ea2..6c800c756f 100644 --- a/arch/arm/src/stm32/stm32_waste.h +++ b/arch/arm/src/stm32/stm32_waste.h @@ -76,4 +76,4 @@ void up_waste(void); #endif #endif /* __ASSEMBLY__ */ -#endif /* __ARCH_ARM_SRC_STM32_STM32_RRC_H */ +#endif /* __ARCH_ARM_SRC_STM32_STM32_WASTE_H */ diff --git a/arch/arm/src/stm32f7/stm32_rcc.h b/arch/arm/src/stm32f7/stm32_rcc.h index 40f3155cca..9320c34aa6 100644 --- a/arch/arm/src/stm32f7/stm32_rcc.h +++ b/arch/arm/src/stm32f7/stm32_rcc.h @@ -33,8 +33,8 @@ * ************************************************************************************/ -#ifndef __ARCH_ARM_SRC_STM32F7_STM32_RRC_H -#define __ARCH_ARM_SRC_STM32F7_STM32_RRC_H +#ifndef __ARCH_ARM_SRC_STM32F7_STM32_RCC_H +#define __ARCH_ARM_SRC_STM32F7_STM32_RCC_H /************************************************************************************ * Included Files @@ -211,11 +211,7 @@ void stm32_clockenable(void); * Name: stm32_rcc_enablelse * * Description: - * Enable the External Low-Speed (LSE) Oscillator and, if the RTC is - * configured, setup the LSE as the RTC clock source, and enable the RTC. - * - * For the STM32L15X family, this will also select the LSE as the clock source of - * the LCD. + * Enable the External Low-Speed (LSE) Oscillator. * * Input Parameters: * None @@ -252,4 +248,4 @@ void stm32_rcc_disablelsi(void); } #endif #endif /* __ASSEMBLY__ */ -#endif /* __ARCH_ARM_SRC_STM32F7_STM32_RRC_H */ +#endif /* __ARCH_ARM_SRC_STM32F7_STM32_RCC_H */ diff --git a/arch/arm/src/stm32l4/stm32l4_rcc.h b/arch/arm/src/stm32l4/stm32l4_rcc.h index 33549648c2..6c77771ec6 100644 --- a/arch/arm/src/stm32l4/stm32l4_rcc.h +++ b/arch/arm/src/stm32l4/stm32l4_rcc.h @@ -33,8 +33,8 @@ * ************************************************************************************/ -#ifndef __ARCH_ARM_SRC_STM32L4_STM32L4_RRC_H -#define __ARCH_ARM_SRC_STM32L4_STM32L4_RRC_H +#ifndef __ARCH_ARM_SRC_STM32L4_STM32L4_RCC_H +#define __ARCH_ARM_SRC_STM32L4_STM32L4_RCC_H /************************************************************************************ * Included Files @@ -187,11 +187,7 @@ void stm32l4_clockenable(void); * Name: stm32l4_rcc_enablelse * * Description: - * Enable the External Low-Speed (LSE) Oscillator and, if the RTC is - * configured, setup the LSE as the RTC clock source, and enable the RTC. - * - * For the STM32L15X family, this will also select the LSE as the clock source of - * the LCD. + * Enable the External Low-Speed (LSE) Oscillator. * * Input Parameters: * None -- GitLab From 8a6662c95751b9a109c6cef5225db635ba814cd4 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Thu, 27 Apr 2017 07:25:20 -0600 Subject: [PATCH 598/990] TM32L4: Add some defines for the new peripherals in STM32L496 parts --- arch/arm/include/stm32l4/chip.h | 4 +- .../arm/include/stm32l4\200stm32l4x6xx_irq.h" | 202 ++++++++++++++++++ arch/arm/src/stm32l4/Kconfig | 10 + arch/arm/src/stm32l4/README.txt | 25 ++- arch/arm/src/stm32l4/chip/stm32l4_exti.h | 5 +- arch/arm/src/stm32l4/chip/stm32l4_syscfg.h | 49 +++-- arch/arm/src/stm32l4/chip/stm32l4x6xx_dma.h | 12 ++ .../arm/src/stm32l4/chip/stm32l4x6xx_pinmap.h | 31 +++ arch/arm/src/stm32l4/chip/stm32l4x6xx_rcc.h | 126 +++++++---- arch/arm/src/stm32l4/stm32l4x6xx_rcc.c | 32 ++- 10 files changed, 421 insertions(+), 75 deletions(-) create mode 100644 "arch/arm/include/stm32l4\200stm32l4x6xx_irq.h" diff --git a/arch/arm/include/stm32l4/chip.h b/arch/arm/include/stm32l4/chip.h index f24bf5b7e2..52c5ccae69 100644 --- a/arch/arm/include/stm32l4/chip.h +++ b/arch/arm/include/stm32l4/chip.h @@ -75,9 +75,11 @@ #if defined(CONFIG_STM32L4_STM32L496XX) # define STM32L4_SRAM1_SIZE (256*1024) /* 256Kb SRAM1 on AHB bus Matrix */ # define STM32L4_SRAM2_SIZE (64*1024) /* 64Kb SRAM2 on AHB bus Matrix */ -#else +#elif defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX) # define STM32L4_SRAM1_SIZE (96*1024) /* 96Kb SRAM1 on AHB bus Matrix */ # define STM32L4_SRAM2_SIZE (32*1024) /* 32Kb SRAM2 on AHB bus Matrix */ +#else +# error "Unsupported STM32L4 chip" #endif # define STM32L4_NFSMC 1 /* Have FSMC memory controller */ diff --git "a/arch/arm/include/stm32l4\200stm32l4x6xx_irq.h" "b/arch/arm/include/stm32l4\200stm32l4x6xx_irq.h" new file mode 100644 index 0000000000..23d5ec4247 --- /dev/null +++ "b/arch/arm/include/stm32l4\200stm32l4x6xx_irq.h" @@ -0,0 +1,202 @@ +/**************************************************************************************************** + * arch/arm/include/stm32l4/stm32l4x6xx_irq.h + * + * Copyright (C) 2015 Sebastien Lorquet. All rights reserved. + * Author: Sebastien Lorquet + * + * 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. + * + ****************************************************************************************************/ + +/* This file should never be included directed but, rather, only indirectly through arch/irq.h */ + +#ifndef __ARCH_ARM_INCLUDE_STM32L4_STM32L4X6XX_IRQ_H +#define __ARCH_ARM_INCLUDE_STM32L4_STM32L4X6XX_IRQ_H + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include + +/**************************************************************************************************** + * Pre-processor Definitions + ****************************************************************************************************/ + +/* IRQ numbers. The IRQ number corresponds vector number and hence map directly to bits in the + * NVIC. This does, however, waste several words of memory in the IRQ to handle mapping tables. + * + * Processor Exceptions (vectors 0-15). These common definitions can be found in the file + * nuttx/arch/arm/include/stm32f7/irq.h which includes this file + * + * External interrupts (vectors >= 16) + */ + +#define STM32L4_IRQ_WWDG (STM32L4_IRQ_FIRST+0) /* 0: Window Watchdog interrupt */ +#define STM32L4_IRQ_PVD (STM32L4_IRQ_FIRST+1) /* 1: PVD through EXTI Line detection interrupt */ +#define STM32L4_IRQ_TAMPER (STM32L4_IRQ_FIRST+2) /* 2: Tamper and time stamp interrupts */ +#define STM32L4_IRQ_TIMESTAMP (STM32L4_IRQ_FIRST+2) /* 2: Tamper and time stamp interrupts */ +#define STM32L4_IRQ_RTC_WKUP (STM32L4_IRQ_FIRST+3) /* 3: RTC global interrupt */ +#define STM32L4_IRQ_FLASH (STM32L4_IRQ_FIRST+4) /* 4: Flash global interrupt */ +#define STM32L4_IRQ_RCC (STM32L4_IRQ_FIRST+5) /* 5: RCC global interrupt */ +#define STM32L4_IRQ_EXTI0 (STM32L4_IRQ_FIRST+6) /* 6: EXTI Line 0 interrupt */ +#define STM32L4_IRQ_EXTI1 (STM32L4_IRQ_FIRST+7) /* 7: EXTI Line 1 interrupt */ +#define STM32L4_IRQ_EXTI2 (STM32L4_IRQ_FIRST+8) /* 8: EXTI Line 2 interrupt */ +#define STM32L4_IRQ_EXTI3 (STM32L4_IRQ_FIRST+9) /* 9: EXTI Line 3 interrupt */ +#define STM32L4_IRQ_EXTI4 (STM32L4_IRQ_FIRST+10) /* 10: EXTI Line 4 interrupt */ +#define STM32L4_IRQ_DMA1CH1 (STM32L4_IRQ_FIRST+11) /* 12: DMA1 Channel 1 global interrupt */ +#define STM32L4_IRQ_DMA1CH2 (STM32L4_IRQ_FIRST+12) /* 13: DMA1 Channel 2 global interrupt */ +#define STM32L4_IRQ_DMA1CH3 (STM32L4_IRQ_FIRST+13) /* 14: DMA1 Channel 3 global interrupt */ +#define STM32L4_IRQ_DMA1CH4 (STM32L4_IRQ_FIRST+14) /* 15: DMA1 Channel 4 global interrupt */ +#define STM32L4_IRQ_DMA1CH5 (STM32L4_IRQ_FIRST+15) /* 16: DMA1 Channel 5 global interrupt */ +#define STM32L4_IRQ_DMA1CH6 (STM32L4_IRQ_FIRST+16) /* 17: DMA1 Channel 6 global interrupt */ +#define STM32L4_IRQ_DMA1CH7 (STM32L4_IRQ_FIRST+17) /* 17: DMA1 Channel 7 global interrupt */ +#define STM32L4_IRQ_ADC12 (STM32L4_IRQ_FIRST+18) /* 18: ADC1 and ADC2 global interrupt */ +#define STM32L4_IRQ_CAN1TX (STM32L4_IRQ_FIRST+19) /* 19: CAN1 TX interrupts */ +#define STM32L4_IRQ_CAN1RX0 (STM32L4_IRQ_FIRST+20) /* 20: CAN1 RX0 interrupts */ +#define STM32L4_IRQ_CAN1RX1 (STM32L4_IRQ_FIRST+21) /* 21: CAN1 RX1 interrupt */ +#define STM32L4_IRQ_CAN1SCE (STM32L4_IRQ_FIRST+22) /* 22: CAN1 SCE interrupt */ +#define STM32L4_IRQ_EXTI95 (STM32L4_IRQ_FIRST+23) /* 23: EXTI Line[9:5] interrupts */ +#define STM32L4_IRQ_TIM1BRK (STM32L4_IRQ_FIRST+24) /* 24: TIM1 Break interrupt */ +#define STM32L4_IRQ_TIM15 (STM32L4_IRQ_FIRST+24) /* 24: TIM15 global interrupt */ +#define STM32L4_IRQ_TIM1UP (STM32L4_IRQ_FIRST+25) /* 25: TIM1 Update interrupt */ +#define STM32L4_IRQ_TIM16 (STM32L4_IRQ_FIRST+25) /* 25: TIM16 global interrupt */ +#define STM32L4_IRQ_TIM1TRGCOM (STM32L4_IRQ_FIRST+26) /* 26: TIM1 Trigger and Commutation interrupts */ +#define STM32L4_IRQ_TIM17 (STM32L4_IRQ_FIRST+26) /* 26: TIM17 global interrupt */ +#define STM32L4_IRQ_TIM1CC (STM32L4_IRQ_FIRST+27) /* 27: TIM1 Capture Compare interrupt */ +#define STM32L4_IRQ_TIM2 (STM32L4_IRQ_FIRST+28) /* 28: TIM2 global interrupt */ +#define STM32L4_IRQ_TIM3 (STM32L4_IRQ_FIRST+29) /* 29: TIM3 global interrupt */ +#define STM32L4_IRQ_TIM4 (STM32L4_IRQ_FIRST+30) /* 30: TIM4 global interrupt */ +#define STM32L4_IRQ_I2C1EV (STM32L4_IRQ_FIRST+31) /* 31: I2C1 event interrupt */ +#define STM32L4_IRQ_I2C1ER (STM32L4_IRQ_FIRST+32) /* 32: I2C1 error interrupt */ +#define STM32L4_IRQ_I2C2EV (STM32L4_IRQ_FIRST+33) /* 33: I2C2 event interrupt */ +#define STM32L4_IRQ_I2C2ER (STM32L4_IRQ_FIRST+34) /* 34: I2C2 error interrupt */ +#define STM32L4_IRQ_SPI1 (STM32L4_IRQ_FIRST+35) /* 35: SPI1 global interrupt */ +#define STM32L4_IRQ_SPI2 (STM32L4_IRQ_FIRST+36) /* 36: SPI2 global interrupt */ +#define STM32L4_IRQ_USART1 (STM32L4_IRQ_FIRST+37) /* 37: USART1 global interrupt */ +#define STM32L4_IRQ_USART2 (STM32L4_IRQ_FIRST+38) /* 38: USART2 global interrupt */ +#define STM32L4_IRQ_USART3 (STM32L4_IRQ_FIRST+39) /* 39: USART3 global interrupt */ +#define STM32L4_IRQ_EXTI1510 (STM32L4_IRQ_FIRST+40) /* 40: EXTI Line[15:10] interrupts */ +#define STM32L4_IRQ_RTCALRM (STM32L4_IRQ_FIRST+41) /* 41: RTC alarm through EXTI line interrupt */ +#define STM32L4_IRQ_DFSDM3 (STM32L4_IRQ_FIRST+42) /* 42: Digital Filter / Sigma Delta Modulator interrupt */ +#define STM32L4_IRQ_TIM8BRK (STM32L4_IRQ_FIRST+43) /* 43: TIM8 Break interrupt */ +#define STM32L4_IRQ_TIM8UP (STM32L4_IRQ_FIRST+44) /* 44: TIM8 Update interrupt */ +#define STM32L4_IRQ_TIM8TRGCOM (STM32L4_IRQ_FIRST+45) /* 45: TIM8 Trigger and Commutation interrupts */ +#define STM32L4_IRQ_TIM8CC (STM32L4_IRQ_FIRST+46) /* 46: TIM8 Capture Compare interrupt */ +#define STM32L4_IRQ_ADC3 (STM32L4_IRQ_FIRST+47) /* 47: ADC3 global interrupt */ +#define STM32L4_IRQ_FSMC (STM32L4_IRQ_FIRST+48) /* 48: FSMC global interrupt */ +#define STM32L4_IRQ_SDMMC1 (STM32L4_IRQ_FIRST+49) /* 49: SDMMC1 global interrupt */ +#define STM32L4_IRQ_TIM5 (STM32L4_IRQ_FIRST+50) /* 50: TIM5 global interrupt */ +#define STM32L4_IRQ_SPI3 (STM32L4_IRQ_FIRST+51) /* 51: SPI3 global interrupt */ +#define STM32L4_IRQ_UART4 (STM32L4_IRQ_FIRST+52) /* 52: UART4 global interrupt */ +#define STM32L4_IRQ_UART5 (STM32L4_IRQ_FIRST+53) /* 53: UART5 global interrupt */ +#define STM32L4_IRQ_TIM6 (STM32L4_IRQ_FIRST+54) /* 54: TIM6 global interrupt */ +#define STM32L4_IRQ_DAC (STM32L4_IRQ_FIRST+54) /* 54: DAC1 and DAC2 underrun error interrupts */ +#define STM32L4_IRQ_TIM7 (STM32L4_IRQ_FIRST+55) /* 55: TIM7 global interrupt */ +#define STM32L4_IRQ_DMA2CH1 (STM32L4_IRQ_FIRST+56) /* 56: DMA2 Channel 1 global interrupt */ +#define STM32L4_IRQ_DMA2CH2 (STM32L4_IRQ_FIRST+57) /* 57: DMA2 Channel 2 global interrupt */ +#define STM32L4_IRQ_DMA2CH3 (STM32L4_IRQ_FIRST+58) /* 58: DMA2 Channel 3 global interrupt */ +#define STM32L4_IRQ_DMA2CH4 (STM32L4_IRQ_FIRST+59) /* 59: DMA2 Channel 4 global interrupt */ +#define STM32L4_IRQ_DMA2CH5 (STM32L4_IRQ_FIRST+60) /* 60: DMA2 Channel 5 global interrupt */ +#define STM32L4_IRQ_DFSDM0 (STM32L4_IRQ_FIRST+61) /* 61: DFSDM0 global interrupt */ +#define STM32L4_IRQ_DFSDM1 (STM32L4_IRQ_FIRST+62) /* 62: DFSDM1 global interrupt*/ +#define STM32L4_IRQ_DFSDM2 (STM32L4_IRQ_FIRST+63) /* 63: DFSDM2 global interrupt */ +#define STM32L4_IRQ_COMP (STM32L4_IRQ_FIRST+64) /* 64: COMP1/COMP2 interrupts */ +#define STM32L4_IRQ_LPTIM1 (STM32L4_IRQ_FIRST+65) /* 65: LPTIM1 global interrupt */ +#define STM32L4_IRQ_LPTIM2 (STM32L4_IRQ_FIRST+66) /* 66: LPTIM2 global interrupt */ +#define STM32L4_IRQ_OTGFS (STM32L4_IRQ_FIRST+67) /* 67: USB On The Go FS global interrupt */ +#define STM32L4_IRQ_DMA2CH6 (STM32L4_IRQ_FIRST+68) /* 68: DMA2 Channel 6 global interrupt */ +#define STM32L4_IRQ_DMA2CH7 (STM32L4_IRQ_FIRST+69) /* 69: DMA2 Channel 7 global interrupt */ +#define STM32L4_IRQ_LPUART1 (STM32L4_IRQ_FIRST+70) /* 70: Low power UART 1 global interrupt */ +#define STM32L4_IRQ_QUADSPI (STM32L4_IRQ_FIRST+71) /* 71: QUADSPI global interrupt */ +#define STM32L4_IRQ_I2C3EV (STM32L4_IRQ_FIRST+72) /* 72: I2C3 event interrupt */ +#define STM32L4_IRQ_I2C3ER (STM32L4_IRQ_FIRST+73) /* 73: I2C3 error interrupt */ +#define STM32L4_IRQ_SAI1 (STM32L4_IRQ_FIRST+74) /* 74: SAI1 global interrupt */ +#define STM32L4_IRQ_SAI2 (STM32L4_IRQ_FIRST+75) /* 75: SAI2 global interrupt */ +#define STM32L4_IRQ_SWPMI1 (STM32L4_IRQ_FIRST+76) /* 76: SWPMI1 global interrupt */ +#define STM32L4_IRQ_TSC (STM32L4_IRQ_FIRST+77) /* 77: TSC global interrupt */ +#define STM32L4_IRQ_LCD (STM32L4_IRQ_FIRST+78) /* 78: LCD global interrupt */ +#define STM32L4_IRQ_AES (STM32L4_IRQ_FIRST+79) /* 79: AES crypto global interrupt */ +#define STM32L4_IRQ_RNG (STM32L4_IRQ_FIRST+80) /* 80: RNG global interrupt */ +#define STM32L4_IRQ_FPU (STM32L4_IRQ_FIRST+81) /* 81: FPU global interrupt */ + +/* STM32L496xx/4A6xx only: */ + +#define STM32L4_IRQ_HASH_CRS (STM32L4_IRQ_FIRST+82) /* 82: HASH and CRS global interrupt */ +#define STM32L4_IRQ_I2C4_EV (STM32L4_IRQ_FIRST+83) /* 83: I2C4 event interrupt */ +#define STM32L4_IRQ_I2C4_ER (STM32L4_IRQ_FIRST+84) /* 84: I2C4 error interrupt */ +#define STM32L4_IRQ_DCMI (STM32L4_IRQ_FIRST+85) /* 85: DCMI global interrupt */ +#define STM32L4_IRQ_CAN2TX (STM32L4_IRQ_FIRST+86) /* 86: CAN2 TX interrupts */ +#define STM32L4_IRQ_CAN2RX0 (STM32L4_IRQ_FIRST+87) /* 87: CAN2 RX0 interrupts */ +#define STM32L4_IRQ_CAN2RX1 (STM32L4_IRQ_FIRST+88) /* 88: CAN2 RX1 interrupt */ +#define STM32L4_IRQ_CAN2SCE (STM32L4_IRQ_FIRST+89) /* 89: CAN2 SCE interrupt */ +#define STM32L4_IRQ_DMA2D (STM32L4_IRQ_FIRST+90) /* 90: DMA2D global interrupt */ + +#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX) +# define NR_INTERRUPTS 82 +#elif defined(CONFIG_STM32L4_STM32L496XX) +# define NR_INTERRUPTS 91 +#else +# error "Unsupported STM32L4 chip" +#endif + +#define NR_VECTORS (STM32L4_IRQ_FIRST+NR_INTERRUPTS) + +/* EXTI interrupts (Do not use IRQ numbers) */ + +#define NR_IRQS NR_VECTORS + +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + +/**************************************************************************************************** + * Public Data + ****************************************************************************************************/ + +#ifndef __ASSEMBLY__ +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/**************************************************************************************************** + * Public Functions + ****************************************************************************************************/ + +#undef EXTERN +#ifdef __cplusplus +} +#endif +#endif + +#endif /* __ARCH_ARM_INCLUDE_STM32L4_STM32L4X6XX_IRQ_H */ diff --git a/arch/arm/src/stm32l4/Kconfig b/arch/arm/src/stm32l4/Kconfig index 0a8dceb0fc..5af9603644 100644 --- a/arch/arm/src/stm32l4/Kconfig +++ b/arch/arm/src/stm32l4/Kconfig @@ -116,6 +116,7 @@ config STM32L4_STM32L496XX select STM32L4_HAVE_I2C4 select STM32L4_HAVE_CAN2 select STM32L4_HAVE_DCMI + select STM32L4_HAVE_DMA2D choice prompt "Embedded FLASH size" @@ -184,6 +185,10 @@ config STM32L4_HAVE_DCMI bool default n +config STM32L4_HAVE_DMA2D + bool + default n + config STM32L4_HAVE_HASH bool default n @@ -307,6 +312,11 @@ config STM32L4_DCMI default n depends on STM32L4_HAVE_DCMI +config STM32L4_DMA2D + bool "DMA2D" + default n + depends on STM32L4_HAVE_DMA2D + config STM32L4_HASH bool "HASH" default n diff --git a/arch/arm/src/stm32l4/README.txt b/arch/arm/src/stm32l4/README.txt index 6b570ededd..67d9be527e 100644 --- a/arch/arm/src/stm32l4/README.txt +++ b/arch/arm/src/stm32l4/README.txt @@ -1,9 +1,7 @@ This is a port of NuttX to the STM32L4 Family -Used development board is the Nucleo L476RG, STM32L4VGDiscovery -The status is HIGHLY EXPERIMENTAL. - -OSTEST application works, but drivers are not complete. +Used development boards are the Nucleo L476RG, Nucleo L496ZG and +STM32L4VGDiscovery Most code is copied and adapted from the STM32 Port. @@ -24,16 +22,20 @@ RCC : All registers defined, peripherals enabled, basic clock working SYSCTL : All registers defined USART : Working in normal mode (no DMA, to be tested, code is written) DMA : works; at least tested with QSPI -SRAM2 : OK; can be included in MM region or left separate for special app purposes +SRAM2 : OK; can be included in MM region or left separate for special app + : purposes FIREWALL : Code written, to be tested, requires support from ldscript SPI : Code written, to be tested, including DMA I2C : Code written, to be tested (I2C4 missing) RTC : works QSPI : works in polling, interrupt, DMA, and also memory-mapped modes CAN : TODO -OTGFS : dev implemented, tested, outstanding issue with CDCACM (ACM_SET_LINE_CODING, but otherwise works); - : host implemented, only build smoke-tested (i.e. builds, but no functional testing yet) -Timers : Implemented, with PWM oneshot and freerun, tickless OS support. Limited testing (focused on tickless OS so far) +OTGFS : dev implemented, tested, outstanding issue with CDCACM + : (ACM_SET_LINE_CODING, but otherwise works); host implemented, + : only build smoke-tested (i.e. builds, but no functional testing + : yet) +Timers : Implemented, with PWM oneshot and freerun, tickless OS support. + : Limited testing (focused on tickless OS so far) PM : TODO, PWR registers defined FSMC : TODO AES : TODO @@ -46,10 +48,12 @@ ADC : TODO DAC : TODO New peripherals with implementation to be written from scratch -These are Low Priority TODO items, unless someone requests or contributes it. +These are Low Priority TODO items, unless someone requests or contributes +it. TSC : TODO (Touch Screen Controller) -SWP : TODO (Single wire protocol master, to connect with NFC enabled SIM cards) +SWP : TODO (Single wire protocol master, to connect with NFC enabled + : SIM cards) LPUART : TODO (Low power UART working with LSE at low baud rates) LPTIMER : TODO (Low power TIMER) OPAMP : TODO (Analog operational amplifier) @@ -60,3 +64,4 @@ SAIPLL : works (PLL For Digital Audio interfaces, and other things) SAI : TODO (Digital Audio interfaces, I2S, SPDIF, etc) HASH : TODO (SHA-1, SHA-224, SHA-256, HMAC) DCMI : TODO (Digital Camera interfaces) +DMA2D : TODO (Chrom-Art Accelerator for image manipulation) diff --git a/arch/arm/src/stm32l4/chip/stm32l4_exti.h b/arch/arm/src/stm32l4/chip/stm32l4_exti.h index f9f087a051..4af53eb347 100644 --- a/arch/arm/src/stm32l4/chip/stm32l4_exti.h +++ b/arch/arm/src/stm32l4/chip/stm32l4_exti.h @@ -49,8 +49,8 @@ #define STM32L4_NEXTI1 31 #define STM32L4_EXTI1_MASK 0xffffffff -#define STM32L4_NEXTI2 8 -#define STM32L4_EXTI2_MASK 0x000000ff +#define STM32L4_NEXTI2 9 +#define STM32L4_EXTI2_MASK 0x000001ff #define STM32L4_EXTI1_BIT(n) (1 << (n)) #define STM32L4_EXTI2_BIT(n) (1 << (n)) @@ -114,6 +114,7 @@ #define EXTI2_PVM3 (1 << 5) /* EXTI line 37 is connected to the PVM3 wakeup */ #define EXTI2_PVM4 (1 << 6) /* EXTI line 38 is connected to the PVM4 wakeup */ #define EXTI2_LCD (1 << 7) /* EXTI line 39 is connected to the LCD wakeup */ +#define EXTI2_I2C4 (1 << 8) /* EXTI line 40 is connected to the I2C4 wakeup */ /* Interrupt mask register */ diff --git a/arch/arm/src/stm32l4/chip/stm32l4_syscfg.h b/arch/arm/src/stm32l4/chip/stm32l4_syscfg.h index c1ad478751..2cbffbc7f1 100644 --- a/arch/arm/src/stm32l4/chip/stm32l4_syscfg.h +++ b/arch/arm/src/stm32l4/chip/stm32l4_syscfg.h @@ -63,6 +63,7 @@ #define STM32L4_SYSCFG_CFGR2_OFFSET 0x001c /* SYSCFG configuration register 2 */ #define STM32L4_SYSCFG_SWPR_OFFSET 0x0020 /* SYSCFG SRAM2 write protection register */ #define STM32L4_SYSCFG_SKR_OFFSET 0x0024 /* SYSCFG SRAM2 key register */ +#define STM32L4_SYSCFG_SWPR2_OFFSET 0x0028 /* SYSCFG SRAM2 write protection register 2 */ /* Register Addresses *******************************************************************************/ @@ -100,8 +101,9 @@ #define SYSCFG_CFGR1_I2C_PB8_FMP (1 << 18) /* Bit 18: Fast-mode Plus (Fm+) driving capability activation on PB8 */ #define SYSCFG_CFGR1_I2C_PB9_FMP (1 << 19) /* Bit 19: Fast-mode Plus (Fm+) driving capability activation on PB9 */ #define SYSCFG_CFGR1_I2C1_FMP (1 << 20) /* Bit 20: I2C1 Fast-mode Plus (Fm+) driving capability activation */ -#define SYSCFG_CFGR1_I2C2_FMP (1 << 21) /* Bit 21: I2C1 Fast-mode Plus (Fm+) driving capability activation */ -#define SYSCFG_CFGR1_I2C3_FMP (1 << 22) /* Bit 22: I2C1 Fast-mode Plus (Fm+) driving capability activation */ +#define SYSCFG_CFGR1_I2C2_FMP (1 << 21) /* Bit 21: I2C2 Fast-mode Plus (Fm+) driving capability activation */ +#define SYSCFG_CFGR1_I2C3_FMP (1 << 22) /* Bit 22: I2C3 Fast-mode Plus (Fm+) driving capability activation */ +#define SYSCFG_CFGR1_I2C4_FMP (1 << 23) /* Bit 23: I2C4 Fast-mode Plus (Fm+) driving capability activation */ #define SYSCFG_CFGR1_FPU_IE0 (1 << 26) /* Bit 26: FPU Invalid operation interrupt enable */ #define SYSCFG_CFGR1_FPU_IE1 (1 << 27) /* Bit 27: FPU Divide-by-zero interrupt enable */ #define SYSCFG_CFGR1_FPU_IE2 (1 << 28) /* Bit 28: FPU Underflow interrupt enable */ @@ -118,45 +120,47 @@ #define SYSCFG_EXTICR_PORTE (4) /* 0100: PE[x] pin */ #define SYSCFG_EXTICR_PORTF (5) /* 0101: PF[C] pin */ #define SYSCFG_EXTICR_PORTG (6) /* 0110: PG[x] pin */ +#define SYSCFG_EXTICR_PORTH (7) /* 0111: PH[x] pin (only on STM32L496xx/4A6xx) */ +#define SYSCFG_EXTICR_PORTI (8) /* 1000: PI[x] pin (only on STM32L496xx/4A6xx) */ -#define SYSCFG_EXTICR_PORT_MASK (7) +#define SYSCFG_EXTICR_PORT_MASK (15) #define SYSCFG_EXTICR_EXTI_SHIFT(g) (((g) & 3) << 2) #define SYSCFG_EXTICR_EXTI_MASK(g) (SYSCFG_EXTICR_PORT_MASK << (SYSCFG_EXTICR_EXTI_SHIFT(g))) -#define SYSCFG_EXTICR1_EXTI0_SHIFT (0) /* Bits 0-2: EXTI 0 coinfiguration */ +#define SYSCFG_EXTICR1_EXTI0_SHIFT (0) /* Bits 0-2: EXTI 0 configuration */ #define SYSCFG_EXTICR1_EXTI0_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI0_SHIFT) -#define SYSCFG_EXTICR1_EXTI1_SHIFT (4) /* Bits 4-6: EXTI 1 coinfiguration */ +#define SYSCFG_EXTICR1_EXTI1_SHIFT (4) /* Bits 4-6: EXTI 1 configuration */ #define SYSCFG_EXTICR1_EXTI1_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI1_SHIFT) -#define SYSCFG_EXTICR1_EXTI2_SHIFT (8) /* Bits 8-10: EXTI 2 coinfiguration */ +#define SYSCFG_EXTICR1_EXTI2_SHIFT (8) /* Bits 8-10: EXTI 2 configuration */ #define SYSCFG_EXTICR1_EXTI2_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI2_SHIFT) -#define SYSCFG_EXTICR1_EXTI3_SHIFT (12) /* Bits 12-14: EXTI 3 coinfiguration */ +#define SYSCFG_EXTICR1_EXTI3_SHIFT (12) /* Bits 12-14: EXTI 3 configuration */ #define SYSCFG_EXTICR1_EXTI3_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI3_SHIFT) -#define SYSCFG_EXTICR2_EXTI4_SHIFT (0) /* Bits 0-2: EXTI 4 coinfiguration */ +#define SYSCFG_EXTICR2_EXTI4_SHIFT (0) /* Bits 0-2: EXTI 4 configuration */ #define SYSCFG_EXTICR2_EXTI4_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI4_SHIFT) -#define SYSCFG_EXTICR2_EXTI5_SHIFT (4) /* Bits 4-6: EXTI 5 coinfiguration */ +#define SYSCFG_EXTICR2_EXTI5_SHIFT (4) /* Bits 4-6: EXTI 5 configuration */ #define SYSCFG_EXTICR2_EXTI5_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI5_SHIFT) -#define SYSCFG_EXTICR2_EXTI6_SHIFT (8) /* Bits 8-10: EXTI 6 coinfiguration */ +#define SYSCFG_EXTICR2_EXTI6_SHIFT (8) /* Bits 8-10: EXTI 6 configuration */ #define SYSCFG_EXTICR2_EXTI6_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI6_SHIFT) -#define SYSCFG_EXTICR2_EXTI7_SHIFT (12) /* Bits 12-14: EXTI 7 coinfiguration */ +#define SYSCFG_EXTICR2_EXTI7_SHIFT (12) /* Bits 12-14: EXTI 7 configuration */ #define SYSCFG_EXTICR2_EXTI7_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI7_SHIFT) -#define SYSCFG_EXTICR3_EXTI8_SHIFT (0) /* Bits 0-2: EXTI 8 coinfiguration */ +#define SYSCFG_EXTICR3_EXTI8_SHIFT (0) /* Bits 0-2: EXTI 8 configuration */ #define SYSCFG_EXTICR3_EXTI8_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI8_SHIFT) -#define SYSCFG_EXTICR3_EXTI9_SHIFT (4) /* Bits 4-6: EXTI 9 coinfiguration */ +#define SYSCFG_EXTICR3_EXTI9_SHIFT (4) /* Bits 4-6: EXTI 9 configuration */ #define SYSCFG_EXTICR3_EXTI9_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI9_SHIFT) -#define SYSCFG_EXTICR3_EXTI10_SHIFT (8) /* Bits 8-10: EXTI 10 coinfiguration */ +#define SYSCFG_EXTICR3_EXTI10_SHIFT (8) /* Bits 8-10: EXTI 10 configuration */ #define SYSCFG_EXTICR3_EXTI10_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI10_SHIFT) -#define SYSCFG_EXTICR3_EXTI11_SHIFT (12) /* Bits 12-14: EXTI 11 coinfiguration */ +#define SYSCFG_EXTICR3_EXTI11_SHIFT (12) /* Bits 12-14: EXTI 11 configuration */ #define SYSCFG_EXTICR3_EXTI11_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI11_SHIFT) -#define SYSCFG_EXTICR4_EXTI12_SHIFT (0) /* Bits 0-2: EXTI 12 coinfiguration */ +#define SYSCFG_EXTICR4_EXTI12_SHIFT (0) /* Bits 0-2: EXTI 12 configuration */ #define SYSCFG_EXTICR4_EXTI12_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI12_SHIFT) -#define SYSCFG_EXTICR4_EXTI13_SHIFT (4) /* Bits 4-6: EXTI 13 coinfiguration */ +#define SYSCFG_EXTICR4_EXTI13_SHIFT (4) /* Bits 4-6: EXTI 13 configuration */ #define SYSCFG_EXTICR4_EXTI13_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI13_SHIFT) -#define SYSCFG_EXTICR4_EXTI14_SHIFT (8) /* Bits 8-10: EXTI 14 coinfiguration */ +#define SYSCFG_EXTICR4_EXTI14_SHIFT (8) /* Bits 8-10: EXTI 14 configuration */ #define SYSCFG_EXTICR4_EXTI14_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI14_SHIFT) -#define SYSCFG_EXTICR4_EXTI15_SHIFT (12) /* Bits 12-14: EXTI 15 coinfiguration */ +#define SYSCFG_EXTICR4_EXTI15_SHIFT (12) /* Bits 12-14: EXTI 15 configuration */ #define SYSCFG_EXTICR4_EXTI15_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI15_SHIFT) /* SYSCFG SRAM2 control and status register */ @@ -173,13 +177,16 @@ #define SYSCFG_CFGR2_SPF (1 << 8) /* Bit 8: SRAM2 parity error flag */ /* SYSCFG SRAM2 write protection register */ -/* There is one bit per SRAM2 page */ +/* There is one bit per SRAM2 page (0 to 31) */ /* SYSCFG SRAM2 key register */ #define SYSCFG_SKR_SHIFT 0 #define SYSCFG_SKR_MASK (0xFF << SYSCFG_SKR_SHIFT) -#endif /* CONFIG_STM32L4_STM32L476XX || CONFIG_STM32L4_STM32L486XX */ +/* SYSCFG SRAM2 write protection register 2 (only on STM32L496xx/4A6xx) */ +/* There is one bit per SRAM2 page (32 to 63) */ + +#endif /* CONFIG_STM32L4_STM32L476XX || CONFIG_STM32L4_STM32L486XX || CONFIG_STM32L4_STM32L496XX */ #endif /* __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4_SYSCFG_H */ diff --git a/arch/arm/src/stm32l4/chip/stm32l4x6xx_dma.h b/arch/arm/src/stm32l4/chip/stm32l4x6xx_dma.h index 6e7afac9af..173e0adbe7 100644 --- a/arch/arm/src/stm32l4/chip/stm32l4x6xx_dma.h +++ b/arch/arm/src/stm32l4/chip/stm32l4x6xx_dma.h @@ -343,6 +343,11 @@ #define DMACHAN_DAC2 DMACHAN_SETTING(STM32L4_DMA2_CHAN5, 3) +/* DCMI */ + +#define DMACHAN_DCMI_1 DMACHAN_SETTING(STM32L4_DMA2_CHAN5, 4) +#define DMACHAN_DCMI_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN6, 0) + /* DFSDM */ #define DMACHAN_DFSDM0 DMACHAN_SETTING(STM32L4_DMA1_CHAN4, 0) @@ -350,6 +355,10 @@ #define DMACHAN_DFSDM2 DMACHAN_SETTING(STM32L4_DMA1_CHAN6, 0) #define DMACHAN_DFSDM3 DMACHAN_SETTING(STM32L4_DMA1_CHAN7, 0) +/* HASH */ + +#define DMACHAN_HASH_IN DMACHAN_SETTING(STM32L4_DMA2_CHAN7, 6) + /* I2C */ #define DMACHAN_I2C1_RX_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN7, 3) @@ -363,6 +372,9 @@ #define DMACHAN_I2C3_RX DMACHAN_SETTING(STM32L4_DMA1_CHAN3, 2) #define DMACHAN_I2C3_TX DMACHAN_SETTING(STM32L4_DMA1_CHAN2, 3) +#define DMACHAN_I2C4_RX DMACHAN_SETTING(STM32L4_DMA2_CHAN1, 0) +#define DMACHAN_I2C4_TX DMACHAN_SETTING(STM32L4_DMA2_CHAN2, 0) + /* QUADSPI */ #define DMACHAN_QUADSPI_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN5, 5) diff --git a/arch/arm/src/stm32l4/chip/stm32l4x6xx_pinmap.h b/arch/arm/src/stm32l4/chip/stm32l4x6xx_pinmap.h index 8be6eca5a5..19f90a0148 100644 --- a/arch/arm/src/stm32l4/chip/stm32l4x6xx_pinmap.h +++ b/arch/arm/src/stm32l4/chip/stm32l4x6xx_pinmap.h @@ -126,6 +126,11 @@ #define GPIO_CAN1_TX_2 (GPIO_ALT|GPIO_AF9 |GPIO_PORTB|GPIO_PIN9) #define GPIO_CAN1_TX_3 (GPIO_ALT|GPIO_AF9 |GPIO_PORTD|GPIO_PIN1) +#define GPIO_CAN2_RX_1 (GPIO_ALT|GPIO_AF3 |GPIO_PORTB|GPIO_PIN5) +#define GPIO_CAN2_TX_1 (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN6) +#define GPIO_CAN2_RX_2 (GPIO_ALT|GPIO_AF10 |GPIO_PORTB|GPIO_PIN12) +#define GPIO_CAN2_TX_2 (GPIO_ALT|GPIO_AF10 |GPIO_PORTB|GPIO_PIN13) + /* Clocks outputs */ #define GPIO_MCO (GPIO_ALT|GPIO_AF0 |GPIO_PORTA|GPIO_PIN8) @@ -151,6 +156,15 @@ #define GPIO_DAC1_OUT (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN4) #define GPIO_DAC2_OUT (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN5) +/* Digital Camera Interface (DCMI) */ + +#define GPIO_DCMI_PIXCK_1 (GPIO_ALT|GPIO_AF4|GPIO_PORTA|GPIO_PIN6) +#define GPIO_DCMI_PIXCK_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTD|GPIO_PIN9) +#define GPIO_DCMI_HSYNC_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTA|GPIO_PIN4) +#define GPIO_DCMI_HSYNC_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTD|GPIO_PIN8) +#define GPIO_DCMI_VSYNC_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN7) +/* TODO: DCMI data pins missing */ + /* Digital Filter for Sigma-Delta Modulators (DFSDM) */ #define GPIO_DFSDM_DATIN0_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTB|GPIO_PIN1) @@ -253,6 +267,10 @@ /* I2C */ +/* Note: STM32L496xx/4A6xx devices have few additional mappings for + * I2C1-3 that are not defined here. + */ + #define GPIO_I2C1_SDA_1 (GPIO_ALT|GPIO_AF4 |GPIO_PORTB|GPIO_PIN7) #define GPIO_I2C1_SDA_2 (GPIO_ALT|GPIO_AF4 |GPIO_PORTB|GPIO_PIN9) #define GPIO_I2C1_SDA_3 (GPIO_ALT|GPIO_AF4 |GPIO_PORTG|GPIO_PIN13) @@ -278,6 +296,19 @@ #define GPIO_I2C3_SMBA_1 (GPIO_ALT|GPIO_AF4 |GPIO_PORTB|GPIO_PIN2) #define GPIO_I2C3_SMBA_2 (GPIO_ALT|GPIO_AF4 |GPIO_PORTG|GPIO_PIN6) +#define GPIO_I2C4_SDA_1 (GPIO_ALT|GPIO_AF5 |GPIO_PORTB|GPIO_PIN7) +#define GPIO_I2C4_SDA_2 (GPIO_ALT|GPIO_AF3 |GPIO_PORTB|GPIO_PIN11) +#define GPIO_I2C4_SDA_3 (GPIO_ALT|GPIO_AF2 |GPIO_PORTC|GPIO_PIN1) +#define GPIO_I2C4_SDA_4 (GPIO_ALT|GPIO_AF4 |GPIO_PORTD|GPIO_PIN13) +#define GPIO_I2C4_SCL_1 (GPIO_ALT|GPIO_AF5 |GPIO_PORTB|GPIO_PIN6) +#define GPIO_I2C4_SCL_2 (GPIO_ALT|GPIO_AF3 |GPIO_PORTB|GPIO_PIN10) +#define GPIO_I2C4_SCL_3 (GPIO_ALT|GPIO_AF2 |GPIO_PORTC|GPIO_PIN0) +#define GPIO_I2C4_SCL_4 (GPIO_ALT|GPIO_AF4 |GPIO_PORTD|GPIO_PIN12) +#define GPIO_I2C4_SMBA_1 (GPIO_ALT|GPIO_AF5 |GPIO_PORTA|GPIO_PIN14) +#define GPIO_I2C4_SMBA_2 (GPIO_ALT|GPIO_AF4 |GPIO_PORTD|GPIO_PIN11) +#define GPIO_I2C4_SMBA_3 (GPIO_ALT|GPIO_AF4 |GPIO_PORTD|GPIO_PIN11) +#define GPIO_I2C4_SMBA_4 (GPIO_ALT|GPIO_AF4 |GPIO_PORTF|GPIO_PIN13) + /* JTAG */ #define GPIO_JTCK_SWCLK (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN14) diff --git a/arch/arm/src/stm32l4/chip/stm32l4x6xx_rcc.h b/arch/arm/src/stm32l4/chip/stm32l4x6xx_rcc.h index 2aef6f17d5..d180033ad2 100644 --- a/arch/arm/src/stm32l4/chip/stm32l4x6xx_rcc.h +++ b/arch/arm/src/stm32l4/chip/stm32l4x6xx_rcc.h @@ -35,8 +35,8 @@ * ****************************************************************************************************/ -#ifndef __ARCH_ARM_SRC_STM32L4_CHIP_STM32F42XXX_RCC_H -#define __ARCH_ARM_SRC_STM32L4_CHIP_STM32F42XXX_RCC_H +#ifndef __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X6XX_RCC_H +#define __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X6XX_RCC_H /**************************************************************************************************** * Included Files @@ -80,9 +80,11 @@ #define STM32L4_RCC_APB1SMENR1_OFFSET 0x0078 /* RCC APB1 low power mode peripheral clock enable register 1 */ #define STM32L4_RCC_APB1SMENR2_OFFSET 0x007c /* RCC APB1 low power mode peripheral clock enable register 2 */ #define STM32L4_RCC_APB2SMENR_OFFSET 0x0080 /* RCC APB2 low power mode peripheral clock enable register */ -#define STM32L4_RCC_CCIPR_OFFSET 0x0088 /* Peripherals independ clock configuration register */ +#define STM32L4_RCC_CCIPR_OFFSET 0x0088 /* Peripherals independent clock configuration register 1 */ #define STM32L4_RCC_BDCR_OFFSET 0x0090 /* Backup domain control register */ #define STM32L4_RCC_CSR_OFFSET 0x0094 /* Control/status register */ +#define STM32L4_RCC_CRRCR_OFFSET 0x0098 /* Clock recovery RC register */ +#define STM32L4_RCC_CCIPR2_OFFSET 0x009c /* Peripherals independent clock configuration register 2 */ /* Register Addresses *******************************************************************************/ @@ -116,6 +118,8 @@ #define STM32L4_RCC_CCIPR (STM32L4_RCC_BASE+STM32L4_RCC_CCIPR_OFFSET) #define STM32L4_RCC_BDCR (STM32L4_RCC_BASE+STM32L4_RCC_BDCR_OFFSET) #define STM32L4_RCC_CSR (STM32L4_RCC_BASE+STM32L4_RCC_CSR_OFFSET) +#define STM32L4_RCC_CRRCR (STM32L4_RCC_BASE+STM32L4_RCC_CRRCR_OFFSET) +#define STM32L4_RCC_CCIPR2 (STM32L4_RCC_BASE+STM32L4_RCC_CCIPR2_OFFSET) /* Register Bitfield Definitions ********************************************************************/ @@ -336,41 +340,44 @@ /* Clock interrupt enable register */ -#define RCC_CIR_LSIRDYIE (1 << 0) /* Bit 0: LSI Ready Interrupt Enable */ -#define RCC_CIR_LSERDYIE (1 << 1) /* Bit 1: LSE Ready Interrupt Enable */ -#define RCC_CIR_MSIRDYIE (1 << 2) /* Bit 2: MSI Ready Interrupt Enable */ -#define RCC_CIR_HSIRDYIE (1 << 3) /* Bit 3: HSI Ready Interrupt Enable */ -#define RCC_CIR_HSERDYIE (1 << 4) /* Bit 4: HSE Ready Interrupt Enable */ -#define RCC_CIR_PLLRDYIE (1 << 5) /* Bit 5: PLL Ready Interrupt Enable */ -#define RCC_CIR_PLLSAI1RDYIE (1 << 6) /* Bit 6: PLLSAI1 Ready Interrupt enable */ -#define RCC_CIR_PLLSAI2RDYIE (1 << 7) /* Bit 7: PLLSAI2 Ready Interrupt enable */ -#define RCC_CIR_LSECSSIE (1 << 9) /* Bit 9: LSE Clock Security System Interrupt Enable */ +#define RCC_CIR_LSIRDYIE (1 << 0) /* Bit 0: LSI Ready Interrupt Enable */ +#define RCC_CIR_LSERDYIE (1 << 1) /* Bit 1: LSE Ready Interrupt Enable */ +#define RCC_CIR_MSIRDYIE (1 << 2) /* Bit 2: MSI Ready Interrupt Enable */ +#define RCC_CIR_HSIRDYIE (1 << 3) /* Bit 3: HSI Ready Interrupt Enable */ +#define RCC_CIR_HSERDYIE (1 << 4) /* Bit 4: HSE Ready Interrupt Enable */ +#define RCC_CIR_PLLRDYIE (1 << 5) /* Bit 5: PLL Ready Interrupt Enable */ +#define RCC_CIR_PLLSAI1RDYIE (1 << 6) /* Bit 6: PLLSAI1 Ready Interrupt enable */ +#define RCC_CIR_PLLSAI2RDYIE (1 << 7) /* Bit 7: PLLSAI2 Ready Interrupt enable */ +#define RCC_CIR_LSECSSIE (1 << 9) /* Bit 9: LSE Clock Security System Interrupt Enable */ +#define RCC_CIR_HSI48RDYIE (1 << 10) /* Bit 10: HSI48 Ready Interrupt Enable */ /* Clock interrupt flag register */ -#define RCC_CIR_LSIRDYIF (1 << 0) /* Bit 0: LSI Ready Interrupt Flag */ -#define RCC_CIR_LSERDYIF (1 << 1) /* Bit 1: LSE Ready Interrupt Flag */ -#define RCC_CIR_MSIRDYIF (1 << 2) /* Bit 2: MSI Ready Interrupt Flag */ -#define RCC_CIR_HSIRDYIF (1 << 3) /* Bit 3: HSI Ready Interrupt Flag */ -#define RCC_CIR_HSERDYIF (1 << 4) /* Bit 4: HSE Ready Interrupt Flag */ -#define RCC_CIR_PLLRDYIF (1 << 5) /* Bit 5: PLL Ready Interrupt Flag */ -#define RCC_CIR_PLLSAI1RDYIF (1 << 6) /* Bit 6: PLLSAI1 Ready Interrupt Flag */ -#define RCC_CIR_PLLSAI2RDYIF (1 << 7) /* Bit 7: PLLSAI2 Ready Interrupt Flag */ -#define RCC_CIR_CSSF (1 << 8) /* Bit 8: Clock Security System Interrupt Flag */ -#define RCC_CIR_LSECSSIF (1 << 9) /* Bit 9: LSE Clock Security System Interrupt Flag */ +#define RCC_CIR_LSIRDYIF (1 << 0) /* Bit 0: LSI Ready Interrupt Flag */ +#define RCC_CIR_LSERDYIF (1 << 1) /* Bit 1: LSE Ready Interrupt Flag */ +#define RCC_CIR_MSIRDYIF (1 << 2) /* Bit 2: MSI Ready Interrupt Flag */ +#define RCC_CIR_HSIRDYIF (1 << 3) /* Bit 3: HSI Ready Interrupt Flag */ +#define RCC_CIR_HSERDYIF (1 << 4) /* Bit 4: HSE Ready Interrupt Flag */ +#define RCC_CIR_PLLRDYIF (1 << 5) /* Bit 5: PLL Ready Interrupt Flag */ +#define RCC_CIR_PLLSAI1RDYIF (1 << 6) /* Bit 6: PLLSAI1 Ready Interrupt Flag */ +#define RCC_CIR_PLLSAI2RDYIF (1 << 7) /* Bit 7: PLLSAI2 Ready Interrupt Flag */ +#define RCC_CIR_CSSF (1 << 8) /* Bit 8: Clock Security System Interrupt Flag */ +#define RCC_CIR_LSECSSIF (1 << 9) /* Bit 9: LSE Clock Security System Interrupt Flag */ +#define RCC_CIR_HSI48RDYIF (1 << 10) /* Bit 10: HSI48 Ready Interrupt Flag */ /* Clock interrupt clear register */ -#define RCC_CIR_LSIRDYIC (1 << 0) /* Bit 0: LSI Ready Interrupt Clear */ -#define RCC_CIR_LSERDYIC (1 << 1) /* Bit 1: LSE Ready Interrupt Clear */ -#define RCC_CIR_MSIRDYIC (1 << 2) /* Bit 2: MSI Ready Interrupt Clear */ -#define RCC_CIR_HSIRDYIC (1 << 3) /* Bit 3: HSI Ready Interrupt Clear */ -#define RCC_CIR_HSERDYIC (1 << 4) /* Bit 4: HSE Ready Interrupt Clear */ -#define RCC_CIR_PLLRDYIC (1 << 5) /* Bit 5: PLL Ready Interrupt Clear */ -#define RCC_CIR_PLLSAI1RDYIC (1 << 6) /* Bit 6: PLLSAI1 Ready Interrupt Clear */ -#define RCC_CIR_PLLSAI2RDYIC (1 << 7) /* Bit 7: PLLSAI2 Ready Interrupt Clear */ -#define RCC_CIR_CSSC (1 << 8) /* Bit 8: Clock Security System Interrupt Clear */ -#define RCC_CIR_LSECSSIC (1 << 9) /* Bit 9: LSE Clock Security System Interrupt Clear */ +#define RCC_CIR_LSIRDYIC (1 << 0) /* Bit 0: LSI Ready Interrupt Clear */ +#define RCC_CIR_LSERDYIC (1 << 1) /* Bit 1: LSE Ready Interrupt Clear */ +#define RCC_CIR_MSIRDYIC (1 << 2) /* Bit 2: MSI Ready Interrupt Clear */ +#define RCC_CIR_HSIRDYIC (1 << 3) /* Bit 3: HSI Ready Interrupt Clear */ +#define RCC_CIR_HSERDYIC (1 << 4) /* Bit 4: HSE Ready Interrupt Clear */ +#define RCC_CIR_PLLRDYIC (1 << 5) /* Bit 5: PLL Ready Interrupt Clear */ +#define RCC_CIR_PLLSAI1RDYIC (1 << 6) /* Bit 6: PLLSAI1 Ready Interrupt Clear */ +#define RCC_CIR_PLLSAI2RDYIC (1 << 7) /* Bit 7: PLLSAI2 Ready Interrupt Clear */ +#define RCC_CIR_CSSC (1 << 8) /* Bit 8: Clock Security System Interrupt Clear */ +#define RCC_CIR_LSECSSIC (1 << 9) /* Bit 9: LSE Clock Security System Interrupt Clear */ +#define RCC_CIR_HSI48RDYIC (1 << 10) /* Bit 10: HSI48 Oscillator Ready Interrupt Clear */ /* AHB1 peripheral reset register */ @@ -379,10 +386,11 @@ #define RCC_AHB1RSTR_FLASHRST (1 << 8) /* Bit 8: Flash memory interface reset */ #define RCC_AHB1RSTR_CRCRST (1 << 12) /* Bit 12: CRC reset */ #define RCC_AHB1RSTR_TSCRST (1 << 16) /* Bit 16: Touch Sensing Controller reset */ +#define RCC_AHB1RSTR_DMA2DRST (1 << 17) /* Bit 17: DMA2D reset */ /* AHB2 peripheral reset register */ -#define RCC_AHB1ENR_GPIOEN(port) (1 << port) +#define RCC_AHB1ENR_GPIOEN(port) (1 << (port)) #define RCC_AHB2RSTR_GPIOARST (1 << 0) /* Bit 0: IO port A reset */ #define RCC_AHB2RSTR_GPIOBRST (1 << 1) /* Bit 1: IO port B reset */ #define RCC_AHB2RSTR_GPIOCRST (1 << 2) /* Bit 2: IO port C reset */ @@ -391,10 +399,13 @@ #define RCC_AHB2RSTR_GPIOFRST (1 << 5) /* Bit 5: IO port F reset */ #define RCC_AHB2RSTR_GPIOGRST (1 << 6) /* Bit 6: IO port G reset */ #define RCC_AHB2RSTR_GPIOHRST (1 << 7) /* Bit 7: IO port H reset */ +#define RCC_AHB2RSTR_GPIOIRST (1 << 8) /* Bit 8: IO port I reset */ #define RCC_AHB2RSTR_OTGFSRST (1 << 12) /* Bit 12: USB OTG FS module reset */ #define RCC_AHB2RSTR_ADCRST (1 << 13) /* Bit 13: ADC interface reset (common to all ADCs) */ +#define RCC_AHB2RSTR_DCMIRST (1 << 14) /* Bit 14: DCMI interface reset */ #define RCC_AHB2RSTR_AESRST (1 << 16) /* Bit 16: AES Cryptographic module reset */ -#define RCC_AHB2RSTR_RNGRST (1 << 18) /* Bit 6: Random number generator module reset */ +#define RCC_AHB2RSTR_HASHRST (1 << 17) /* Bit 17: HASH module reset */ +#define RCC_AHB2RSTR_RNGRST (1 << 18) /* Bit 18: Random number generator module reset */ /* AHB3 peripheral reset register */ @@ -419,7 +430,9 @@ #define RCC_APB1RSTR1_I2C1RST (1 << 21) /* Bit 21: I2C1 reset */ #define RCC_APB1RSTR1_I2C2RST (1 << 22) /* Bit 22: I2C2 reset */ #define RCC_APB1RSTR1_I2C3RST (1 << 23) /* Bit 23: I2C3 reset */ +#define RCC_APB1RSTR1_CRSRST (1 << 24) /* Bit 24: CRS reset */ #define RCC_APB1RSTR1_CAN1RST (1 << 25) /* Bit 25: CAN1 reset */ +#define RCC_APB1RSTR1_CAN2RST (1 << 26) /* Bit 26: CAN2 reset */ #define RCC_APB1RSTR1_PWRRST (1 << 28) /* Bit 28: Power interface reset */ #define RCC_APB1RSTR1_DAC1RST (1 << 29) /* Bit 29: DAC1 reset */ #define RCC_APB1RSTR1_OPAMPRST (1 << 30) /* Bit 30: OPAMP reset */ @@ -428,6 +441,7 @@ /* APB1 Peripheral reset register 2 */ #define RCC_APB1RSTR2_LPUART1RST (1 << 0) /* Bit 0: Low-power UART 1 reset */ +#define RCC_APB1RSTR2_I2C4RST (1 << 1) /* Bit 1: I2C4 reset */ #define RCC_APB1RSTR2_SWPMI1RST (1 << 2) /* Bit 2: Single Wire Protocol reset */ #define RCC_APB1RSTR2_LPTIM2RST (1 << 5) /* Bit 5: Low-power Timer 2 reset */ @@ -453,6 +467,7 @@ #define RCC_AHB1ENR_FLASHEN (1 << 8) /* Bit 8: Flash memory interface enable */ #define RCC_AHB1ENR_CRCEN (1 << 12) /* Bit 12: CRC enable */ #define RCC_AHB1ENR_TSCEN (1 << 16) /* Bit 16: Touch Sensing Controller enable */ +#define RCC_AHB1ENR_DMA2DEN (1 << 17) /* Bit 17: DMA2D enable */ /* AHB2 Peripheral Clock enable register */ @@ -464,9 +479,12 @@ #define RCC_AHB2ENR_GPIOFEN (1 << 5) /* Bit 5: IO port F enable */ #define RCC_AHB2ENR_GPIOGEN (1 << 6) /* Bit 6: IO port G enable */ #define RCC_AHB2ENR_GPIOHEN (1 << 7) /* Bit 7: IO port H enable */ +#define RCC_AHB2ENR_GPIOIEN (1 << 8) /* Bit 8: IO port I enable */ #define RCC_AHB2ENR_OTGFSEN (1 << 12) /* Bit 12: USB OTG FS module enable */ #define RCC_AHB2ENR_ADCEN (1 << 13) /* Bit 13: ADC interface enable (common to all ADCs) */ +#define RCC_AHB2ENR_DCMIEN (1 << 14) /* Bit 14: DCMI interface enable */ #define RCC_AHB2ENR_AESEN (1 << 16) /* Bit 16: AES Cryptographic module enable */ +#define RCC_AHB2ENR_HASHEN (1 << 17) /* Bit 17: HASH module enable */ #define RCC_AHB2ENR_RNGEN (1 << 18) /* Bit 18: Random number generator module enable */ /* AHB3 Peripheral Clock enable register */ @@ -474,7 +492,7 @@ #define RCC_AHB3ENR_FSMCEN (1 << 0) /* Bit 0: Flexible static memory controller module enable */ #define RCC_AHB3ENR_QSPIEN (1 << 8) /* Bit 8: Quad SPI module enable */ -/* APB1 Peripheral Clock enable register 1*/ +/* APB1 Peripheral Clock enable register 1 */ #define RCC_APB1ENR1_TIM2EN (1 << 0) /* Bit 0: TIM2 enable */ #define RCC_APB1ENR1_TIM3EN (1 << 1) /* Bit 1: TIM3 enable */ @@ -483,6 +501,7 @@ #define RCC_APB1ENR1_TIM6EN (1 << 4) /* Bit 4: TIM6 enable */ #define RCC_APB1ENR1_TIM7EN (1 << 5) /* Bit 5: TIM7 enable */ #define RCC_APB1ENR1_LCDEN (1 << 9) /* Bit 9: LCD controller enable */ +#define RCC_APB1ENR1_RTCAPBEN (1 << 10) /* Bit 10: RTC APB clock enable */ #define RCC_APB1ENR1_WWDGEN (1 << 11) /* Bit 11: Windowed Watchdog enable */ #define RCC_APB1ENR1_SPI2EN (1 << 14) /* Bit 14: SPI2 enable */ #define RCC_APB1ENR1_SPI3EN (1 << 15) /* Bit 15: SPI3 enable */ @@ -493,15 +512,18 @@ #define RCC_APB1ENR1_I2C1EN (1 << 21) /* Bit 21: I2C1 enable */ #define RCC_APB1ENR1_I2C2EN (1 << 22) /* Bit 22: I2C2 enable */ #define RCC_APB1ENR1_I2C3EN (1 << 23) /* Bit 23: I2C3 enable */ +#define RCC_APB1ENR1_CRSEN (1 << 24) /* Bit 24: CRSEN enable */ #define RCC_APB1ENR1_CAN1EN (1 << 25) /* Bit 25: CAN1 enable */ +#define RCC_APB1ENR1_CAN2EN (1 << 26) /* Bit 26: CAN2 enable */ #define RCC_APB1ENR1_PWREN (1 << 28) /* Bit 28: Power interface enable */ #define RCC_APB1ENR1_DAC1EN (1 << 29) /* Bit 29: DAC1 enable */ #define RCC_APB1ENR1_OPAMPEN (1 << 30) /* Bit 30: OPAMP enable */ #define RCC_APB1ENR1_LPTIM1EN (1 << 31) /* Bit 31: Low-power Timer 1 enable */ -/* APB1 Peripheral Clock enable register 2*/ +/* APB1 Peripheral Clock enable register 2 */ #define RCC_APB1ENR2_LPUART1EN (1 << 0) /* Bit 0: Low-power UART 1 enable */ +#define RCC_APB1ENR2_I2C4EN (1 << 1) /* Bit 1: I2C4 enable */ #define RCC_APB1ENR2_SWPMI1EN (1 << 2) /* Bit 2: Single Wire Protocol enable */ #define RCC_APB1ENR2_LPTIM2EN (1 << 5) /* Bit 5: Low-power Timer 2 enable */ @@ -529,6 +551,7 @@ #define RCC_AHB1SMENR_SRAM1SMEN (1 << 9) /* Bit 9: SRAM1 enable during Sleep mode */ #define RCC_AHB1SMENR_CRCLPSMEN (1 << 12) /* Bit 12: CRC enable during Sleep mode */ #define RCC_AHB1SMENR_TSCLPSMEN (1 << 16) /* Bit 16: Touch Sensing Controller enable during Sleep mode */ +#define RCC_AHB1SMENR_DMA2DSMEN (1 << 17) /* Bit 17: DMA2D enable during Sleep mode */ /* RCC AHB2 low power mode peripheral clock enable register */ @@ -540,18 +563,21 @@ #define RCC_AHB2SMENR_GPIOFSMEN (1 << 5) /* Bit 5: IO port F enable during Sleep mode */ #define RCC_AHB2SMENR_GPIOGSMEN (1 << 6) /* Bit 6: IO port G enable during Sleep mode */ #define RCC_AHB2SMENR_GPIOHSMEN (1 << 7) /* Bit 7: IO port H enable during Sleep mode */ +#define RCC_AHB2SMENR_GPIOISMEN (1 << 8) /* Bit 8: IO port I enable during Sleep mode */ #define RCC_AHB2SMENR_SRAM2SMEN (1 << 9) /* Bit 9: SRAM2 enable during Sleep mode */ #define RCC_AHB2SMENR_OTGFSSMEN (1 << 12) /* Bit 12: USB OTG FS module enable during Sleep mode */ #define RCC_AHB2SMENR_ADCSMEN (1 << 13) /* Bit 13: ADC interface enable during Sleep mode (common to all ADCs) */ +#define RCC_AHB2SMENR_DCMISMEN (1 << 14) /* Bit 14: DCMI interface enable during Sleep mode */ #define RCC_AHB2SMENR_AESSMEN (1 << 16) /* Bit 16: AES Cryptographic module enable during Sleep mode */ -#define RCC_AHB2SMENR_RNGSMEN (1 << 18) /* Bit 6: Random number generator module enable during Sleep mode */ +#define RCC_AHB2SMENR_HASHSMEN (1 << 17) /* Bit 17: HASH module enable during Sleep mode */ +#define RCC_AHB2SMENR_RNGSMEN (1 << 18) /* Bit 18: Random number generator module enable during Sleep mode */ /* RCC AHB3 low power mode peripheral clock enable register */ #define RCC_AHB3SMENR_FSMCSMEN (1 << 0) /* Bit 0: Flexible static memory controller module enable during Sleep mode */ #define RCC_AHB3SMENR_QSPISMEN (1 << 8) /* Bit 8: Quad SPI module enable during Sleep mode */ -/* RCC APB1 low power modeperipheral clock enable register 1 */ +/* RCC APB1 low power mode peripheral clock enable register 1 */ #define RCC_APB1SMENR1_TIM2SMEN (1 << 0) /* Bit 0: TIM2 enable during Sleep mode */ #define RCC_APB1SMENR1_TIM3SMEN (1 << 1) /* Bit 1: TIM3 enable during Sleep mode */ @@ -560,6 +586,7 @@ #define RCC_APB1SMENR1_TIM6SMEN (1 << 4) /* Bit 4: TIM6 enable during Sleep mode */ #define RCC_APB1SMENR1_TIM7SMEN (1 << 5) /* Bit 5: TIM7 enable during Sleep mode */ #define RCC_APB1SMENR1_LCDSMEN (1 << 9) /* Bit 9: LCD controller enable during Sleep mode */ +#define RCC_APB1SMENR1_RTCAPBSMEN (1 << 10) /* Bit 10: RTC APB clock enable during Sleep mode */ #define RCC_APB1SMENR1_WWDGSMEN (1 << 11) /* Bit 11: Windowed Watchdog enable during Sleep mode */ #define RCC_APB1SMENR1_SPI2SMEN (1 << 14) /* Bit 14: SPI2 enable during Sleep mode */ #define RCC_APB1SMENR1_SPI3SMEN (1 << 15) /* Bit 15: SPI3 enable during Sleep mode */ @@ -570,7 +597,9 @@ #define RCC_APB1SMENR1_I2C1SMEN (1 << 21) /* Bit 21: I2C1 enable during Sleep mode */ #define RCC_APB1SMENR1_I2C2SMEN (1 << 22) /* Bit 22: I2C2 enable during Sleep mode */ #define RCC_APB1SMENR1_I2C3SMEN (1 << 23) /* Bit 23: I2C3 enable during Sleep mode */ +#define RCC_APB1SMENR1_CRSSMEN (1 << 24) /* Bit 24: CRS enable during Sleep mode */ #define RCC_APB1SMENR1_CAN1SMEN (1 << 25) /* Bit 25: CAN1 enable during Sleep mode */ +#define RCC_APB1SMENR1_CAN2SMEN (1 << 26) /* Bit 26: CAN2 enable during Sleep mode */ #define RCC_APB1SMENR1_PWRSMEN (1 << 28) /* Bit 28: Power interface enable during Sleep mode */ #define RCC_APB1SMENR1_DAC1SMEN (1 << 29) /* Bit 29: DAC1 enable during Sleep mode */ #define RCC_APB1SMENR1_OPAMPSMEN (1 << 30) /* Bit 30: OPAMP enable during Sleep mode */ @@ -579,6 +608,7 @@ /* RCC APB1 low power modeperipheral clock enable register 2 */ #define RCC_APB1SMENR2_LPUART1SMEN (1 << 0) /* Bit 0: Low-power UART 1 enable during Sleep mode */ +#define RCC_APB1SMENR2_I2C4SMEN (1 << 1) /* Bit 1: I2C4 enable during Sleep mode */ #define RCC_APB1SMENR2_SWPMI1SMEN (1 << 2) /* Bit 2: Single Wire Protocol enable during Sleep mode */ #define RCC_APB1SMENR2_LPTIM2SMEN (1 << 5) /* Bit 5: Low-power Timer 2 enable during Sleep mode */ @@ -761,5 +791,21 @@ #define RCC_CSR_WWDGRSTF (1 << 30) /* Bit 30: Window watchdog reset flag */ #define RCC_CSR_LPWRRSTF (1 << 31) /* Bit 31: Low-Power reset flag */ -#endif /* CONFIG_STM32L4_STM32L476XX || CONFIG_STM32L4_STM32L486XX */ -#endif /* __ARCH_ARM_SRC_STM32L4_CHIP_STM32F42XXX_RCC_H */ +/* Clock recovery RC register (only on STM32L496xx/4A6xx) */ + +#define RCC_CRRCR_HSI48CAL_SHIFT 7 +# define RCC_CRRCR_HSI48CAL_MASK (0x01ff << RCC_CRRCR_HSI48CAL_SHIFT) /* HSI48 clock calibration */ + +#define RCC_CRRCR_HSI48ON (1 << 0) /* Bit 0: HSI48 clock enable */ +#define RCC_CRRCR_HSI48RDY (1 << 1) /* Bit 1: HSI48 clock ready flag */ + +/* Peripheral Independent Clock Configuration 2 register (only on STM32L496xx/4A6xx) */ + +#define RCC_CCIPR2_I2C4SEL_SHIFT (0) +#define RCC_CCIPR2_I2C4SEL_MASK (3 << RCC_CCIPR2_I2C4SEL_SHIFT) +# define RCC_CCIPR2_I2C4SEL_PCLK (0 << RCC_CCIPR2_I2C4SEL_SHIFT) +# define RCC_CCIPR2_I2C4SEL_SYSCLK (1 << RCC_CCIPR2_I2C4SEL_SHIFT) +# define RCC_CCIPR2_I2C4SEL_HSI (2 << RCC_CCIPR2_I2C4SEL_SHIFT) + +#endif /* CONFIG_STM32L4_STM32L476XX || CONFIG_STM32L4_STM32L486XX || CONFIG_STM32L4_STM32L496XX */ +#endif /* __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X6XX_RCC_H */ diff --git a/arch/arm/src/stm32l4/stm32l4x6xx_rcc.c b/arch/arm/src/stm32l4/stm32l4x6xx_rcc.c index 8f6aa209b0..c043c100fa 100644 --- a/arch/arm/src/stm32l4/stm32l4x6xx_rcc.c +++ b/arch/arm/src/stm32l4/stm32l4x6xx_rcc.c @@ -159,6 +159,12 @@ static inline void rcc_enableahb1(void) regval |= RCC_AHB1ENR_TSCEN; #endif +#ifdef CONFIG_STM32L4_DMA2D + /* DMA2D clock enable */ + + regval |= RCC_AHB1ENR_DMA2DEN; +#endif + putreg32(regval, STM32L4_RCC_AHB1ENR); /* Enable peripherals */ } @@ -220,12 +226,24 @@ static inline void rcc_enableahb2(void) regval |= RCC_AHB2ENR_ADCEN; #endif +#ifdef CONFIG_STM32L4_DCMI + /* Digital Camera interfaces clock enable */ + + regval |= RCC_AHB2ENR_DCMIEN; +#endif + #ifdef CONFIG_STM32L4_AES /* Cryptographic modules clock enable */ regval |= RCC_AHB2ENR_AESEN; #endif +#ifdef CONFIG_STM32L4_HASH + /* HASH module clock enable */ + + regval |= RCC_AHB2ENR_HASHEN; +#endif + #ifdef CONFIG_STM32L4_RNG /* Random number generator clock enable */ @@ -389,6 +407,12 @@ static inline void rcc_enableapb1(void) regval |= RCC_APB1ENR1_CAN1EN; #endif +#ifdef CONFIG_STM32L4_CAN2 + /* CAN 2 clock enable */ + + regval |= RCC_APB1ENR1_CAN2EN; +#endif + /* Power interface clock enable. The PWR block is always enabled so that * we can set the internal voltage regulator as required. */ @@ -425,6 +449,12 @@ static inline void rcc_enableapb1(void) regval |= RCC_APB1ENR2_LPUART1EN; #endif +#ifdef CONFIG_STM32L4_I2C4 + /* I2C4 clock enable */ + + regval |= RCC_APB1ENR2_I2C4EN; +#endif + #ifdef CONFIG_STM32L4_SWPMI /* Single-wire protocol master clock enable */ @@ -889,7 +919,7 @@ static void stm32l4_stdclockconfig(void) #endif /**************************************************************************** - * Name: rcc_enableperiphals + * Name: rcc_enableperipherals ****************************************************************************/ static inline void rcc_enableperipherals(void) -- GitLab From f1b71e3ae7b8c0fba8707f6d4ffc46fd038c7d12 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Thu, 27 Apr 2017 07:26:32 -0600 Subject: [PATCH 599/990] TM32L4: Add some defines for the new peripherals in STM32L496 parts --- arch/arm/include/stm32l4/stm32l4x6xx_irq.h | 27 ++- .../arm/include/stm32l4\200stm32l4x6xx_irq.h" | 202 ------------------ 2 files changed, 23 insertions(+), 206 deletions(-) delete mode 100644 "arch/arm/include/stm32l4\200stm32l4x6xx_irq.h" diff --git a/arch/arm/include/stm32l4/stm32l4x6xx_irq.h b/arch/arm/include/stm32l4/stm32l4x6xx_irq.h index c992ed942f..23d5ec4247 100644 --- a/arch/arm/include/stm32l4/stm32l4x6xx_irq.h +++ b/arch/arm/include/stm32l4/stm32l4x6xx_irq.h @@ -143,15 +143,34 @@ #define STM32L4_IRQ_TSC (STM32L4_IRQ_FIRST+77) /* 77: TSC global interrupt */ #define STM32L4_IRQ_LCD (STM32L4_IRQ_FIRST+78) /* 78: LCD global interrupt */ #define STM32L4_IRQ_AES (STM32L4_IRQ_FIRST+79) /* 79: AES crypto global interrupt */ -#define STM32L4_IRQ_RNG (STM32L4_IRQ_FIRST+80) /* 80: Rng global interrupt */ +#define STM32L4_IRQ_RNG (STM32L4_IRQ_FIRST+80) /* 80: RNG global interrupt */ #define STM32L4_IRQ_FPU (STM32L4_IRQ_FIRST+81) /* 81: FPU global interrupt */ -#define NR_INTERRUPTS 82 -#define NR_VECTORS (STM32L4_IRQ_FIRST+NR_INTERRUPTS) +/* STM32L496xx/4A6xx only: */ + +#define STM32L4_IRQ_HASH_CRS (STM32L4_IRQ_FIRST+82) /* 82: HASH and CRS global interrupt */ +#define STM32L4_IRQ_I2C4_EV (STM32L4_IRQ_FIRST+83) /* 83: I2C4 event interrupt */ +#define STM32L4_IRQ_I2C4_ER (STM32L4_IRQ_FIRST+84) /* 84: I2C4 error interrupt */ +#define STM32L4_IRQ_DCMI (STM32L4_IRQ_FIRST+85) /* 85: DCMI global interrupt */ +#define STM32L4_IRQ_CAN2TX (STM32L4_IRQ_FIRST+86) /* 86: CAN2 TX interrupts */ +#define STM32L4_IRQ_CAN2RX0 (STM32L4_IRQ_FIRST+87) /* 87: CAN2 RX0 interrupts */ +#define STM32L4_IRQ_CAN2RX1 (STM32L4_IRQ_FIRST+88) /* 88: CAN2 RX1 interrupt */ +#define STM32L4_IRQ_CAN2SCE (STM32L4_IRQ_FIRST+89) /* 89: CAN2 SCE interrupt */ +#define STM32L4_IRQ_DMA2D (STM32L4_IRQ_FIRST+90) /* 90: DMA2D global interrupt */ + +#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX) +# define NR_INTERRUPTS 82 +#elif defined(CONFIG_STM32L4_STM32L496XX) +# define NR_INTERRUPTS 91 +#else +# error "Unsupported STM32L4 chip" +#endif + +#define NR_VECTORS (STM32L4_IRQ_FIRST+NR_INTERRUPTS) /* EXTI interrupts (Do not use IRQ numbers) */ -#define NR_IRQS NR_VECTORS +#define NR_IRQS NR_VECTORS /**************************************************************************************************** * Public Types diff --git "a/arch/arm/include/stm32l4\200stm32l4x6xx_irq.h" "b/arch/arm/include/stm32l4\200stm32l4x6xx_irq.h" deleted file mode 100644 index 23d5ec4247..0000000000 --- "a/arch/arm/include/stm32l4\200stm32l4x6xx_irq.h" +++ /dev/null @@ -1,202 +0,0 @@ -/**************************************************************************************************** - * arch/arm/include/stm32l4/stm32l4x6xx_irq.h - * - * Copyright (C) 2015 Sebastien Lorquet. All rights reserved. - * Author: Sebastien Lorquet - * - * 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. - * - ****************************************************************************************************/ - -/* This file should never be included directed but, rather, only indirectly through arch/irq.h */ - -#ifndef __ARCH_ARM_INCLUDE_STM32L4_STM32L4X6XX_IRQ_H -#define __ARCH_ARM_INCLUDE_STM32L4_STM32L4X6XX_IRQ_H - -/**************************************************************************************************** - * Included Files - ****************************************************************************************************/ - -#include - -/**************************************************************************************************** - * Pre-processor Definitions - ****************************************************************************************************/ - -/* IRQ numbers. The IRQ number corresponds vector number and hence map directly to bits in the - * NVIC. This does, however, waste several words of memory in the IRQ to handle mapping tables. - * - * Processor Exceptions (vectors 0-15). These common definitions can be found in the file - * nuttx/arch/arm/include/stm32f7/irq.h which includes this file - * - * External interrupts (vectors >= 16) - */ - -#define STM32L4_IRQ_WWDG (STM32L4_IRQ_FIRST+0) /* 0: Window Watchdog interrupt */ -#define STM32L4_IRQ_PVD (STM32L4_IRQ_FIRST+1) /* 1: PVD through EXTI Line detection interrupt */ -#define STM32L4_IRQ_TAMPER (STM32L4_IRQ_FIRST+2) /* 2: Tamper and time stamp interrupts */ -#define STM32L4_IRQ_TIMESTAMP (STM32L4_IRQ_FIRST+2) /* 2: Tamper and time stamp interrupts */ -#define STM32L4_IRQ_RTC_WKUP (STM32L4_IRQ_FIRST+3) /* 3: RTC global interrupt */ -#define STM32L4_IRQ_FLASH (STM32L4_IRQ_FIRST+4) /* 4: Flash global interrupt */ -#define STM32L4_IRQ_RCC (STM32L4_IRQ_FIRST+5) /* 5: RCC global interrupt */ -#define STM32L4_IRQ_EXTI0 (STM32L4_IRQ_FIRST+6) /* 6: EXTI Line 0 interrupt */ -#define STM32L4_IRQ_EXTI1 (STM32L4_IRQ_FIRST+7) /* 7: EXTI Line 1 interrupt */ -#define STM32L4_IRQ_EXTI2 (STM32L4_IRQ_FIRST+8) /* 8: EXTI Line 2 interrupt */ -#define STM32L4_IRQ_EXTI3 (STM32L4_IRQ_FIRST+9) /* 9: EXTI Line 3 interrupt */ -#define STM32L4_IRQ_EXTI4 (STM32L4_IRQ_FIRST+10) /* 10: EXTI Line 4 interrupt */ -#define STM32L4_IRQ_DMA1CH1 (STM32L4_IRQ_FIRST+11) /* 12: DMA1 Channel 1 global interrupt */ -#define STM32L4_IRQ_DMA1CH2 (STM32L4_IRQ_FIRST+12) /* 13: DMA1 Channel 2 global interrupt */ -#define STM32L4_IRQ_DMA1CH3 (STM32L4_IRQ_FIRST+13) /* 14: DMA1 Channel 3 global interrupt */ -#define STM32L4_IRQ_DMA1CH4 (STM32L4_IRQ_FIRST+14) /* 15: DMA1 Channel 4 global interrupt */ -#define STM32L4_IRQ_DMA1CH5 (STM32L4_IRQ_FIRST+15) /* 16: DMA1 Channel 5 global interrupt */ -#define STM32L4_IRQ_DMA1CH6 (STM32L4_IRQ_FIRST+16) /* 17: DMA1 Channel 6 global interrupt */ -#define STM32L4_IRQ_DMA1CH7 (STM32L4_IRQ_FIRST+17) /* 17: DMA1 Channel 7 global interrupt */ -#define STM32L4_IRQ_ADC12 (STM32L4_IRQ_FIRST+18) /* 18: ADC1 and ADC2 global interrupt */ -#define STM32L4_IRQ_CAN1TX (STM32L4_IRQ_FIRST+19) /* 19: CAN1 TX interrupts */ -#define STM32L4_IRQ_CAN1RX0 (STM32L4_IRQ_FIRST+20) /* 20: CAN1 RX0 interrupts */ -#define STM32L4_IRQ_CAN1RX1 (STM32L4_IRQ_FIRST+21) /* 21: CAN1 RX1 interrupt */ -#define STM32L4_IRQ_CAN1SCE (STM32L4_IRQ_FIRST+22) /* 22: CAN1 SCE interrupt */ -#define STM32L4_IRQ_EXTI95 (STM32L4_IRQ_FIRST+23) /* 23: EXTI Line[9:5] interrupts */ -#define STM32L4_IRQ_TIM1BRK (STM32L4_IRQ_FIRST+24) /* 24: TIM1 Break interrupt */ -#define STM32L4_IRQ_TIM15 (STM32L4_IRQ_FIRST+24) /* 24: TIM15 global interrupt */ -#define STM32L4_IRQ_TIM1UP (STM32L4_IRQ_FIRST+25) /* 25: TIM1 Update interrupt */ -#define STM32L4_IRQ_TIM16 (STM32L4_IRQ_FIRST+25) /* 25: TIM16 global interrupt */ -#define STM32L4_IRQ_TIM1TRGCOM (STM32L4_IRQ_FIRST+26) /* 26: TIM1 Trigger and Commutation interrupts */ -#define STM32L4_IRQ_TIM17 (STM32L4_IRQ_FIRST+26) /* 26: TIM17 global interrupt */ -#define STM32L4_IRQ_TIM1CC (STM32L4_IRQ_FIRST+27) /* 27: TIM1 Capture Compare interrupt */ -#define STM32L4_IRQ_TIM2 (STM32L4_IRQ_FIRST+28) /* 28: TIM2 global interrupt */ -#define STM32L4_IRQ_TIM3 (STM32L4_IRQ_FIRST+29) /* 29: TIM3 global interrupt */ -#define STM32L4_IRQ_TIM4 (STM32L4_IRQ_FIRST+30) /* 30: TIM4 global interrupt */ -#define STM32L4_IRQ_I2C1EV (STM32L4_IRQ_FIRST+31) /* 31: I2C1 event interrupt */ -#define STM32L4_IRQ_I2C1ER (STM32L4_IRQ_FIRST+32) /* 32: I2C1 error interrupt */ -#define STM32L4_IRQ_I2C2EV (STM32L4_IRQ_FIRST+33) /* 33: I2C2 event interrupt */ -#define STM32L4_IRQ_I2C2ER (STM32L4_IRQ_FIRST+34) /* 34: I2C2 error interrupt */ -#define STM32L4_IRQ_SPI1 (STM32L4_IRQ_FIRST+35) /* 35: SPI1 global interrupt */ -#define STM32L4_IRQ_SPI2 (STM32L4_IRQ_FIRST+36) /* 36: SPI2 global interrupt */ -#define STM32L4_IRQ_USART1 (STM32L4_IRQ_FIRST+37) /* 37: USART1 global interrupt */ -#define STM32L4_IRQ_USART2 (STM32L4_IRQ_FIRST+38) /* 38: USART2 global interrupt */ -#define STM32L4_IRQ_USART3 (STM32L4_IRQ_FIRST+39) /* 39: USART3 global interrupt */ -#define STM32L4_IRQ_EXTI1510 (STM32L4_IRQ_FIRST+40) /* 40: EXTI Line[15:10] interrupts */ -#define STM32L4_IRQ_RTCALRM (STM32L4_IRQ_FIRST+41) /* 41: RTC alarm through EXTI line interrupt */ -#define STM32L4_IRQ_DFSDM3 (STM32L4_IRQ_FIRST+42) /* 42: Digital Filter / Sigma Delta Modulator interrupt */ -#define STM32L4_IRQ_TIM8BRK (STM32L4_IRQ_FIRST+43) /* 43: TIM8 Break interrupt */ -#define STM32L4_IRQ_TIM8UP (STM32L4_IRQ_FIRST+44) /* 44: TIM8 Update interrupt */ -#define STM32L4_IRQ_TIM8TRGCOM (STM32L4_IRQ_FIRST+45) /* 45: TIM8 Trigger and Commutation interrupts */ -#define STM32L4_IRQ_TIM8CC (STM32L4_IRQ_FIRST+46) /* 46: TIM8 Capture Compare interrupt */ -#define STM32L4_IRQ_ADC3 (STM32L4_IRQ_FIRST+47) /* 47: ADC3 global interrupt */ -#define STM32L4_IRQ_FSMC (STM32L4_IRQ_FIRST+48) /* 48: FSMC global interrupt */ -#define STM32L4_IRQ_SDMMC1 (STM32L4_IRQ_FIRST+49) /* 49: SDMMC1 global interrupt */ -#define STM32L4_IRQ_TIM5 (STM32L4_IRQ_FIRST+50) /* 50: TIM5 global interrupt */ -#define STM32L4_IRQ_SPI3 (STM32L4_IRQ_FIRST+51) /* 51: SPI3 global interrupt */ -#define STM32L4_IRQ_UART4 (STM32L4_IRQ_FIRST+52) /* 52: UART4 global interrupt */ -#define STM32L4_IRQ_UART5 (STM32L4_IRQ_FIRST+53) /* 53: UART5 global interrupt */ -#define STM32L4_IRQ_TIM6 (STM32L4_IRQ_FIRST+54) /* 54: TIM6 global interrupt */ -#define STM32L4_IRQ_DAC (STM32L4_IRQ_FIRST+54) /* 54: DAC1 and DAC2 underrun error interrupts */ -#define STM32L4_IRQ_TIM7 (STM32L4_IRQ_FIRST+55) /* 55: TIM7 global interrupt */ -#define STM32L4_IRQ_DMA2CH1 (STM32L4_IRQ_FIRST+56) /* 56: DMA2 Channel 1 global interrupt */ -#define STM32L4_IRQ_DMA2CH2 (STM32L4_IRQ_FIRST+57) /* 57: DMA2 Channel 2 global interrupt */ -#define STM32L4_IRQ_DMA2CH3 (STM32L4_IRQ_FIRST+58) /* 58: DMA2 Channel 3 global interrupt */ -#define STM32L4_IRQ_DMA2CH4 (STM32L4_IRQ_FIRST+59) /* 59: DMA2 Channel 4 global interrupt */ -#define STM32L4_IRQ_DMA2CH5 (STM32L4_IRQ_FIRST+60) /* 60: DMA2 Channel 5 global interrupt */ -#define STM32L4_IRQ_DFSDM0 (STM32L4_IRQ_FIRST+61) /* 61: DFSDM0 global interrupt */ -#define STM32L4_IRQ_DFSDM1 (STM32L4_IRQ_FIRST+62) /* 62: DFSDM1 global interrupt*/ -#define STM32L4_IRQ_DFSDM2 (STM32L4_IRQ_FIRST+63) /* 63: DFSDM2 global interrupt */ -#define STM32L4_IRQ_COMP (STM32L4_IRQ_FIRST+64) /* 64: COMP1/COMP2 interrupts */ -#define STM32L4_IRQ_LPTIM1 (STM32L4_IRQ_FIRST+65) /* 65: LPTIM1 global interrupt */ -#define STM32L4_IRQ_LPTIM2 (STM32L4_IRQ_FIRST+66) /* 66: LPTIM2 global interrupt */ -#define STM32L4_IRQ_OTGFS (STM32L4_IRQ_FIRST+67) /* 67: USB On The Go FS global interrupt */ -#define STM32L4_IRQ_DMA2CH6 (STM32L4_IRQ_FIRST+68) /* 68: DMA2 Channel 6 global interrupt */ -#define STM32L4_IRQ_DMA2CH7 (STM32L4_IRQ_FIRST+69) /* 69: DMA2 Channel 7 global interrupt */ -#define STM32L4_IRQ_LPUART1 (STM32L4_IRQ_FIRST+70) /* 70: Low power UART 1 global interrupt */ -#define STM32L4_IRQ_QUADSPI (STM32L4_IRQ_FIRST+71) /* 71: QUADSPI global interrupt */ -#define STM32L4_IRQ_I2C3EV (STM32L4_IRQ_FIRST+72) /* 72: I2C3 event interrupt */ -#define STM32L4_IRQ_I2C3ER (STM32L4_IRQ_FIRST+73) /* 73: I2C3 error interrupt */ -#define STM32L4_IRQ_SAI1 (STM32L4_IRQ_FIRST+74) /* 74: SAI1 global interrupt */ -#define STM32L4_IRQ_SAI2 (STM32L4_IRQ_FIRST+75) /* 75: SAI2 global interrupt */ -#define STM32L4_IRQ_SWPMI1 (STM32L4_IRQ_FIRST+76) /* 76: SWPMI1 global interrupt */ -#define STM32L4_IRQ_TSC (STM32L4_IRQ_FIRST+77) /* 77: TSC global interrupt */ -#define STM32L4_IRQ_LCD (STM32L4_IRQ_FIRST+78) /* 78: LCD global interrupt */ -#define STM32L4_IRQ_AES (STM32L4_IRQ_FIRST+79) /* 79: AES crypto global interrupt */ -#define STM32L4_IRQ_RNG (STM32L4_IRQ_FIRST+80) /* 80: RNG global interrupt */ -#define STM32L4_IRQ_FPU (STM32L4_IRQ_FIRST+81) /* 81: FPU global interrupt */ - -/* STM32L496xx/4A6xx only: */ - -#define STM32L4_IRQ_HASH_CRS (STM32L4_IRQ_FIRST+82) /* 82: HASH and CRS global interrupt */ -#define STM32L4_IRQ_I2C4_EV (STM32L4_IRQ_FIRST+83) /* 83: I2C4 event interrupt */ -#define STM32L4_IRQ_I2C4_ER (STM32L4_IRQ_FIRST+84) /* 84: I2C4 error interrupt */ -#define STM32L4_IRQ_DCMI (STM32L4_IRQ_FIRST+85) /* 85: DCMI global interrupt */ -#define STM32L4_IRQ_CAN2TX (STM32L4_IRQ_FIRST+86) /* 86: CAN2 TX interrupts */ -#define STM32L4_IRQ_CAN2RX0 (STM32L4_IRQ_FIRST+87) /* 87: CAN2 RX0 interrupts */ -#define STM32L4_IRQ_CAN2RX1 (STM32L4_IRQ_FIRST+88) /* 88: CAN2 RX1 interrupt */ -#define STM32L4_IRQ_CAN2SCE (STM32L4_IRQ_FIRST+89) /* 89: CAN2 SCE interrupt */ -#define STM32L4_IRQ_DMA2D (STM32L4_IRQ_FIRST+90) /* 90: DMA2D global interrupt */ - -#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX) -# define NR_INTERRUPTS 82 -#elif defined(CONFIG_STM32L4_STM32L496XX) -# define NR_INTERRUPTS 91 -#else -# error "Unsupported STM32L4 chip" -#endif - -#define NR_VECTORS (STM32L4_IRQ_FIRST+NR_INTERRUPTS) - -/* EXTI interrupts (Do not use IRQ numbers) */ - -#define NR_IRQS NR_VECTORS - -/**************************************************************************************************** - * Public Types - ****************************************************************************************************/ - -/**************************************************************************************************** - * Public Data - ****************************************************************************************************/ - -#ifndef __ASSEMBLY__ -#ifdef __cplusplus -#define EXTERN extern "C" -extern "C" -{ -#else -#define EXTERN extern -#endif - -/**************************************************************************************************** - * Public Functions - ****************************************************************************************************/ - -#undef EXTERN -#ifdef __cplusplus -} -#endif -#endif - -#endif /* __ARCH_ARM_INCLUDE_STM32L4_STM32L4X6XX_IRQ_H */ -- GitLab From c3119f06a276961502f92d0eb06d29211adaccb4 Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Thu, 27 Apr 2017 08:37:14 -0600 Subject: [PATCH 600/990] Update STM32L4 README.txt file. --- arch/arm/src/stm32l4/README.txt | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/arch/arm/src/stm32l4/README.txt b/arch/arm/src/stm32l4/README.txt index 67d9be527e..944be02c29 100644 --- a/arch/arm/src/stm32l4/README.txt +++ b/arch/arm/src/stm32l4/README.txt @@ -25,17 +25,17 @@ DMA : works; at least tested with QSPI SRAM2 : OK; can be included in MM region or left separate for special app : purposes FIREWALL : Code written, to be tested, requires support from ldscript -SPI : Code written, to be tested, including DMA +SPI : OK, tested (Including DMA) I2C : Code written, to be tested (I2C4 missing) RTC : works QSPI : works in polling, interrupt, DMA, and also memory-mapped modes -CAN : TODO +CAN : OK, tested OTGFS : dev implemented, tested, outstanding issue with CDCACM : (ACM_SET_LINE_CODING, but otherwise works); host implemented, : only build smoke-tested (i.e. builds, but no functional testing : yet) Timers : Implemented, with PWM oneshot and freerun, tickless OS support. - : Limited testing (focused on tickless OS so far) + : Limited testing (focused on tickless OS so far), PWM and QE tested OK. PM : TODO, PWR registers defined FSMC : TODO AES : TODO -- GitLab From 92d761dfe3efb8e6263cfeeaa9295e86a77b3cac Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 27 Apr 2017 09:15:18 -0600 Subject: [PATCH 601/990] STM32F0 Serial: Costmetic changes to spacing. --- arch/arm/src/stm32f0/stm32f0_serial.c | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/arch/arm/src/stm32f0/stm32f0_serial.c b/arch/arm/src/stm32f0/stm32f0_serial.c index 632ccab4d6..fb5fe2230c 100644 --- a/arch/arm/src/stm32f0/stm32f0_serial.c +++ b/arch/arm/src/stm32f0/stm32f0_serial.c @@ -1029,32 +1029,32 @@ static void stm32f0serial_setapbclock(FAR struct uart_dev_s *dev, bool on) return; #ifdef CONFIG_STM32F0_USART1 case STM32F0_USART1_BASE: - rcc_en = RCC_APB2ENR_USART1EN; + rcc_en = RCC_APB2ENR_USART1EN; regaddr = STM32F0_RCC_APB2ENR; break; #endif #ifdef CONFIG_STM32F0_USART2 case STM32F0_USART2_BASE: - rcc_en = RCC_APB1ENR_USART2EN; - regaddr =STM32F0_RCC_APB1ENR; + rcc_en = RCC_APB1ENR_USART2EN; + regaddr = STM32F0_RCC_APB1ENR; break; #endif #ifdef CONFIG_STM32F0_USART3 case STM32F0_USART3_BASE: - rcc_en = RCC_APB1ENR_USART3EN; - regaddr =STM32F0_RCC_APB1ENR; + rcc_en = RCC_APB1ENR_USART3EN; + regaddr = STM32F0_RCC_APB1ENR; break; #endif #ifdef CONFIG_STM32F0_USART4 case STM32F0_USART4_BASE: - rcc_en = RCC_APB1ENR_USART4EN; - regaddr =STM32F0_RCC_APB1ENR; + rcc_en = RCC_APB1ENR_USART4EN; + regaddr = STM32F0_RCC_APB1ENR; break; #endif #ifdef CONFIG_STM32F0_USART5 case STM32F0_USART5_BASE: - rcc_en = RCC_APB1ENR_USART5EN; - regaddr =STM32F0_RCC_APB1ENR; + rcc_en = RCC_APB1ENR_USART5EN; + regaddr = STM32F0_RCC_APB1ENR; break; #endif } -- GitLab From a7dc83b70dcae37535b51f581c47f6d126ed4de8 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 27 Apr 2017 09:26:12 -0600 Subject: [PATCH 602/990] Update a README file. --- configs/nucleo-f072rb/README.txt | 30 ++++++++++++++++++++++++++++++ 1 file changed, 30 insertions(+) diff --git a/configs/nucleo-f072rb/README.txt b/configs/nucleo-f072rb/README.txt index 3f4eecaabf..de1713e5ab 100644 --- a/configs/nucleo-f072rb/README.txt +++ b/configs/nucleo-f072rb/README.txt @@ -8,12 +8,42 @@ Nucleo-F072RB README Contents ======== + - Status - Nucleo-64 Boards - LEDs - Buttons - Serial Console - Configurations +Status +====== + 2017-04-27: There are many problems. On start up, I have to reset + several times before I get NSH prompt (or parts of it). Apparently the + STM32 is either hanging (perhaps in clockconfig()) or perhaps it has + taken a hard fault before it is able to generate debug output? + + There are many hardfaults during initial serial output. This change + seems to eliminate those hardfaults: + + @@ -2163,7 +2163,7 @@ static void stm32f0serial_txint(FAR struct uart_dev_s *dev, bool enable) + * interrupts disabled (note this may recurse). + */ + + - uart_xmitchars(dev); + +// uart_xmitchars(dev); + #endif + } + else + + Which implies that the hardfaults are due to runaway recursion in the + serial driver? This suggest some error in either determining when there + is TX data available or in disabling TX interrupts. + + But this not a solution. Even without the hard faults, it may hang + attempting to output the NSH greeting and prompt or hang unable to + receive input. These symptoms suggest some issue with TX and RX + interrupt handling. + Nucleo-64 Boards ================ -- GitLab From b608afc484e20e3528a4a5a7c5f99b0058b422fe Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 27 Apr 2017 15:44:05 -0600 Subject: [PATCH 603/990] STM32F0: Fix some missing settings in the clock configuration logic --- arch/arm/src/stm32f0/chip/stm32f0_flash.h | 115 +++++++++++++++++++++ arch/arm/src/stm32f0/chip/stm32f0_rcc.h | 8 +- arch/arm/src/stm32f0/stm32f0_clockconfig.c | 31 +++++- arch/arm/src/stm32f0/stm32f0_serial.c | 6 +- 4 files changed, 151 insertions(+), 9 deletions(-) create mode 100644 arch/arm/src/stm32f0/chip/stm32f0_flash.h diff --git a/arch/arm/src/stm32f0/chip/stm32f0_flash.h b/arch/arm/src/stm32f0/chip/stm32f0_flash.h new file mode 100644 index 0000000000..9a6e668346 --- /dev/null +++ b/arch/arm/src/stm32f0/chip/stm32f0_flash.h @@ -0,0 +1,115 @@ +/************************************************************************************ + * arch/arm/src/stm32/chip/stm32fo_flash.h + * + * Copyright (C) 20017 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_FLASH_H +#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_FLASH_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include "chip.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Register Offsets *****************************************************************/ + +#define STM32_FLASH_ACR_OFFSET 0x0000 +#define STM32_FLASH_KEYR_OFFSET 0x0004 +#define STM32_FLASH_OPTKEYR_OFFSET 0x0008 +#define STM32_FLASH_SR_OFFSET 0x000c +#define STM32_FLASH_CR_OFFSET 0x0010 +#define STM32_FLASH_AR_OFFSET 0x0014 +#define STM32_FLASH_OBR_OFFSET 0x001c +#define STM32_FLASH_WRPR_OFFSET 0x0020 + +/* Register Addresses ***************************************************************/ + +#define STM32_FLASH_ACR (STM32F0_FLASHIF_BASE+STM32_FLASH_ACR_OFFSET) +#define STM32_FLASH_KEYR (STM32F0_FLASHIF_BASE+STM32_FLASH_KEYR_OFFSET) +#define STM32_FLASH_OPTKEYR (STM32F0_FLASHIF_BASE+STM32_FLASH_OPTKEYR_OFFSET) +#define STM32_FLASH_SR (STM32F0_FLASHIF_BASE+STM32_FLASH_SR_OFFSET) +#define STM32_FLASH_CR (STM32F0_FLASHIF_BASE+STM32_FLASH_CR_OFFSET) +#define STM32_FLASH_AR (STM32F0_FLASHIF_BASE+STM32_FLASH_AR_OFFSET) +#define STM32_FLASH_OBR (STM32F0_FLASHIF_BASE+STM32_FLASH_OBR_OFFSET) +#define STM32_FLASH_WRPR (STM32F0_FLASHIF_BASE+STM32_FLASH_WRPR_OFFSET) + +/* Register Bitfield Definitions ****************************************************/ +/* Flash Access Control Register (ACR) */ + +#define FLASH_ACR_LATENCY_SHIFT (0) +#define FLASH_ACR_LATENCY_MASK (7 << FLASH_ACR_LATENCY_SHIFT) +# define FLASH_ACR_LATENCY(n) ((n) << FLASH_ACR_LATENCY_SHIFT) /* n wait states */ +# define FLASH_ACR_LATENCY_0 (0 << FLASH_ACR_LATENCY_SHIFT) /* 000: Zero wait states */ +# define FLASH_ACR_LATENCY_1 (1 << FLASH_ACR_LATENCY_SHIFT) /* 001: One wait state */ +#define FLASH_ACR_PRTFBE (1 << 4) /* Bit 4: FLASH prefetch enable */ +#define FLASH_ACR_PRFTBS (1 << 5) /* Bit 5: FLASH Prefetch buffer status */ + +/* Flash Status Register (SR) */ + +#define FLASH_SR_BSY (1 << 0) /* Bit 0: Busy */ +#define FLASH_SR_PGERR (1 << 2) /* Bit 2: Programming Error */ +#define FLASH_SR_WRPRT_ERR (1 << 4) /* Bit 3: Write Protection Error */ +#define FLASH_SR_EOP (1 << 5) /* Bit 4: End of Operation */ + +/* Flash Control Register (CR) */ + +#define FLASH_CR_PG (1 << 0) /* Bit 0: Program Page */ +#define FLASH_CR_PER (1 << 1) /* Bit 1: Page Erase */ +#define FLASH_CR_MER (1 << 2) /* Bit 2: Mass Erase */ +#define FLASH_CR_OPTPG (1 << 4) /* Bit 4: Option Byte Programming */ +#define FLASH_CR_OPTER (1 << 5) /* Bit 5: Option Byte Erase */ +#define FLASH_CR_STRT (1 << 6) /* Bit 6: Start Erase */ +#define FLASH_CR_LOCK (1 << 7) /* Bit 7: Page Locked or Lock Page */ +#define FLASH_CR_OPTWRE (1 << 9) /* Bit 8: Option Bytes Write Enable */ +#define FLASH_CR_ERRIE (1 << 10) /* Bit 10: Error Interrupt Enable */ +#define FLASH_CR_EOPIE (1 << 12) /* Bit 12: End of Program Interrupt Enable */ +#define FLASH_CR_OBLLAUNCH (1 << 13) /* Bit 13: Force option byte loading */ + +/* Flash Option byte register */ +#define FLASH_OBR_ /* To be provided */ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +void stm32_flash_lock(void); +void stm32_flash_unlock(void); + +#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_FLASH_H */ diff --git a/arch/arm/src/stm32f0/chip/stm32f0_rcc.h b/arch/arm/src/stm32f0/chip/stm32f0_rcc.h index 89464aa682..f499071d05 100644 --- a/arch/arm/src/stm32f0/chip/stm32f0_rcc.h +++ b/arch/arm/src/stm32f0/chip/stm32f0_rcc.h @@ -124,15 +124,17 @@ # define RCC_CFGR_PPRE1_HCLKd4 (5 << RCC_CFGR_PPRE1_SHIFT) /* 101: HCLK divided by 4 */ # define RCC_CFGR_PPRE1_HCLKd8 (6 << RCC_CFGR_PPRE1_SHIFT) /* 110: HCLK divided by 8 */ # define RCC_CFGR_PPRE1_HCLKd16 (7 << RCC_CFGR_PPRE1_SHIFT) /* 111: HCLK divided by 16 */ - /* Bits 13-11: Reserve. Keep the reset value */ + /* Bits 13-11: Reserve. Keep the reset value */ #define RCC_CFGR_ADCPRE (1 << 14) /* Bit 14: ADC prescaler, Obsolete use ADC_CFGR2 */ -#define RCC_CFGR_PLLSRC_SHIFT (15) /* Bit 15: PLL input clock source */ +#define RCC_CFGR_PLLSRC_SHIFT (15) /* Bit 15: PLL input clock source */ #define RCC_CFGR_PLLSRC_MASK (3 << RCC_CFGR_PLLSRC_SHIFT) # define RCC_CFGR_PLLSRC_HSId2 (0 << RCC_CFGR_PLLSRC_SHIFT) /* 00: HSI/2 as PLL input clock */ # define RCC_CFGR_PLLSRC_HS1_PREDIV (1 << RCC_CFGR_PLLSRC_SHIFT) /* 01: HSE/PREDIV as PLL input clock */ # define RCC_CFGR_PLLSRC_HSE_PREDIV (2 << RCC_CFGR_PLLSRC_SHIFT) /* 10: HSE/PREDIV as PLL input clock */ # define RCC_CFGR_PLLSRC_HSI48_PREDIV (3 << RCC_CFGR_PLLSRC_SHIFT) /* 11: HSI48/PREDIV as PLL input clock */ -#define RCC_CFGR_PLLXTPRE (1 << 17) /* Bit 17: HSE divider for PLL entry */ +#define RCC_CFGR_PLLXTPRE_MASK (1 << 17) /* Bit 17: HSE divider for PLL entry */ +# define RCC_CFGR_PLLXTPRE_DIV1 (0 << 17) /* 0=No divistion */ +# define RCC_CFGR_PLLXTPRE_DIV2 (1 << 17) /* 1=Divide by two */ #define RCC_CFGR_PLLMUL_SHIFT (18) /* Bits 21-18: PLL Multiplication Factor */ #define RCC_CFGR_PLLMUL_MASK (0x0f << RCC_CFGR_PLLMUL_SHIFT) # define RCC_CFGR_PLLMUL_CLKx2 (0 << RCC_CFGR_PLLMUL_SHIFT) /* 0000: PLL input clock x 2 */ diff --git a/arch/arm/src/stm32f0/stm32f0_clockconfig.c b/arch/arm/src/stm32f0/stm32f0_clockconfig.c index ca8736bb23..7d57c98b9f 100644 --- a/arch/arm/src/stm32f0/stm32f0_clockconfig.c +++ b/arch/arm/src/stm32f0/stm32f0_clockconfig.c @@ -51,6 +51,7 @@ #include "stm32f0_rcc.h" #include "stm32f0_clockconfig.h" #include "chip/stm32f0_syscfg.h" +#include "chip/stm32f0_flash.h" #include "chip/stm32f0_gpio.h" /**************************************************************************** @@ -91,11 +92,35 @@ void stm32f0_clockconfig(void) putreg32(regval, STM32F0_RCC_CR); while ((getreg32(STM32F0_RCC_CR) & RCC_CR_PLLRDY) != 0); - /* Configure the PLL. Multiply the HSI to get System Clock */ + /* Enable FLASH prefetch buffer and set flash latency */ + + regval = getreg32(STM32_FLASH_ACR); + regval &= ~FLASH_ACR_LATENCY_MASK; + regval |= (FLASH_ACR_LATENCY_1 | FLASH_ACR_PRTFBE); + putreg32(regval, STM32_FLASH_ACR); + + /* Set HCLK = SYSCLK */ regval = getreg32(STM32F0_RCC_CFGR); - regval &= ~RCC_CFGR_PLLMUL_MASK; - regval |= STM32F0_CFGR_PLLMUL; + regval &= ~RCC_CFGR_HPRE_MASK; + regval |= RCC_CFGR_HPRE_SYSCLK; + putreg32(regval, STM32F0_RCC_CFGR); + + /* Set PCLK = HCLK */ + + regval &= ~RCC_CFGR_PPRE1_MASK; + regval |= RCC_CFGR_PPRE1_HCLK; + putreg32(regval, STM32F0_RCC_CFGR); + + /* Configure the PLL to generate the system clock + * + * 1. Use source = HSI/2 + * 2. Use PREDIV = 1 + * 3. Use multiplier from board.h + */ + + regval &= ~(RCC_CFGR_PLLSRC_MASK | RCC_CFGR_PLLXTPRE_MASK | RCC_CFGR_PLLMUL_MASK); + regval |= (RCC_CFGR_PLLSRC_HSId2 | RCC_CFGR_PLLXTPRE_DIV1 | STM32F0_CFGR_PLLMUL); putreg32(regval, STM32F0_RCC_CFGR); /* Enable the PLL */ diff --git a/arch/arm/src/stm32f0/stm32f0_serial.c b/arch/arm/src/stm32f0/stm32f0_serial.c index fb5fe2230c..f0975fad2c 100644 --- a/arch/arm/src/stm32f0/stm32f0_serial.c +++ b/arch/arm/src/stm32f0/stm32f0_serial.c @@ -552,7 +552,7 @@ static struct stm32f0_serial_s g_usart3priv = .priv = &g_usart3priv, }, - .irq = STM32F0_IRQ_USART3, + .irq = STM32F0_IRQ_USART345678, .parity = CONFIG_USART3_PARITY, .bits = CONFIG_USART3_BITS, .stopbits2 = CONFIG_USART3_2STOP, @@ -613,7 +613,7 @@ static struct stm32f0_serial_s g_usart4priv = .priv = &g_usart4priv, }, - .irq = STM32F0_IRQ_USART4, + .irq = STM32F0_IRQ_USART345678, .parity = CONFIG_USART4_PARITY, .bits = CONFIG_USART4_BITS, .stopbits2 = CONFIG_USART4_2STOP, @@ -678,7 +678,7 @@ static struct stm32f0_serial_s g_usart5priv = .priv = &g_usart5priv, }, - .irq = STM32F0_IRQ_USART5, + .irq = STM32F0_IRQ_USART345678, .parity = CONFIG_USART5_PARITY, .bits = CONFIG_USART5_BITS, .stopbits2 = CONFIG_USART5_2STOP, -- GitLab From 2e6908b384a475898f2ba10b740eeb7872cc9b24 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 27 Apr 2017 16:58:30 -0600 Subject: [PATCH 604/990] IOCTLS. Separate wireless character driver IOCTL commands from wireless network driver IOCTL commands. Move from wireless.h to ioctl.h. --- arch/arm/src/stm32f0/chip/stm32f0_flash.h | 2 +- configs/nucleo-f4x1re/src/stm32_wireless.c | 1 - configs/nucleo-l476rg/src/stm32_cc3000.c | 1 - configs/spark/src/stm32_cc3000.c | 1 - drivers/wireless/cc3000/cc3000.c | 2 +- drivers/wireless/cc3000/cc3000.h | 3 +- drivers/wireless/nrf24l01.h | 1 - include/nuttx/fs/ioctl.h | 47 ++++---- include/nuttx/wireless/cc3000.h | 2 +- .../wireless/cc3000/include/cc3000_upif.h | 1 - include/nuttx/wireless/ioctl.h | 108 ++++++++++++++++++ include/nuttx/wireless/nrf24l01.h | 2 +- include/nuttx/wireless/wireless.h | 49 +------- 13 files changed, 147 insertions(+), 73 deletions(-) create mode 100644 include/nuttx/wireless/ioctl.h diff --git a/arch/arm/src/stm32f0/chip/stm32f0_flash.h b/arch/arm/src/stm32f0/chip/stm32f0_flash.h index 9a6e668346..82a9442156 100644 --- a/arch/arm/src/stm32f0/chip/stm32f0_flash.h +++ b/arch/arm/src/stm32f0/chip/stm32f0_flash.h @@ -1,5 +1,5 @@ /************************************************************************************ - * arch/arm/src/stm32/chip/stm32fo_flash.h + * arch/arm/src/stm32/chip/stm32f0_flash.h * * Copyright (C) 20017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt diff --git a/configs/nucleo-f4x1re/src/stm32_wireless.c b/configs/nucleo-f4x1re/src/stm32_wireless.c index c5012f0438..b868cad46c 100644 --- a/configs/nucleo-f4x1re/src/stm32_wireless.c +++ b/configs/nucleo-f4x1re/src/stm32_wireless.c @@ -47,7 +47,6 @@ #include #include -#include #include #include diff --git a/configs/nucleo-l476rg/src/stm32_cc3000.c b/configs/nucleo-l476rg/src/stm32_cc3000.c index d1c94b338e..ac935e929f 100644 --- a/configs/nucleo-l476rg/src/stm32_cc3000.c +++ b/configs/nucleo-l476rg/src/stm32_cc3000.c @@ -47,7 +47,6 @@ #include #include -#include #include #include diff --git a/configs/spark/src/stm32_cc3000.c b/configs/spark/src/stm32_cc3000.c index 7f384213e4..92d255d6d9 100644 --- a/configs/spark/src/stm32_cc3000.c +++ b/configs/spark/src/stm32_cc3000.c @@ -47,7 +47,6 @@ #include #include -#include #include #include diff --git a/drivers/wireless/cc3000/cc3000.c b/drivers/wireless/cc3000/cc3000.c index dfb312fb68..6f335c99fd 100644 --- a/drivers/wireless/cc3000/cc3000.c +++ b/drivers/wireless/cc3000/cc3000.c @@ -73,7 +73,7 @@ #include #include -#include +#include #include #include #include diff --git a/drivers/wireless/cc3000/cc3000.h b/drivers/wireless/cc3000/cc3000.h index ddcd4f5163..d969a1e5f6 100644 --- a/drivers/wireless/cc3000/cc3000.h +++ b/drivers/wireless/cc3000/cc3000.h @@ -53,9 +53,10 @@ #include #include #include + #include #include -#include +#include #include #include diff --git a/drivers/wireless/nrf24l01.h b/drivers/wireless/nrf24l01.h index caaf67f566..108591feea 100644 --- a/drivers/wireless/nrf24l01.h +++ b/drivers/wireless/nrf24l01.h @@ -43,7 +43,6 @@ #include #include #include -#include #include #include diff --git a/include/nuttx/fs/ioctl.h b/include/nuttx/fs/ioctl.h index ce31d599ce..674eafc1d7 100644 --- a/include/nuttx/fs/ioctl.h +++ b/include/nuttx/fs/ioctl.h @@ -68,25 +68,26 @@ #define _QEIOCBASE (0x0f00) /* Quadrature encoder ioctl commands */ #define _AUDIOIOCBASE (0x1000) /* Audio ioctl commands */ #define _SLCDIOCBASE (0x1100) /* Segment LCD ioctl commands */ -#define _WLIOCBASE (0x1200) /* Wireless modules ioctl commands */ -#define _CFGDIOCBASE (0x1300) /* Config Data device (app config) ioctl commands */ -#define _TCIOCBASE (0x1400) /* Timer ioctl commands */ -#define _DJOYBASE (0x1500) /* Discrete joystick ioctl commands */ -#define _AJOYBASE (0x1600) /* Analog joystick ioctl commands */ -#define _PIPEBASE (0x1700) /* FIFO/pipe ioctl commands */ -#define _RTCBASE (0x1800) /* RTC ioctl commands */ -#define _RELAYBASE (0x1900) /* Relay devices ioctl commands */ -#define _CANBASE (0x1a00) /* CAN ioctl commands */ -#define _BTNBASE (0x1b00) /* Button ioctl commands */ -#define _ULEDBASE (0x1c00) /* User LED ioctl commands */ -#define _ZCBASE (0x1d00) /* Zero Cross ioctl commands */ -#define _LOOPBASE (0x1e00) /* Loop device commands */ -#define _MODEMBASE (0x1f00) /* Modem ioctl commands */ -#define _I2CBASE (0x2000) /* I2C driver commands */ -#define _SPIBASE (0x2100) /* SPI driver commands */ -#define _GPIOBASE (0x2200) /* GPIO driver commands */ -#define _CLIOCBASE (0x2300) /* Contactless modules ioctl commands */ -#define _USBCBASE (0x2400) /* USB-C controller ioctl commands */ +#define _WLIOCBASE (0x1200) /* Wireless modules ioctl network commands */ +#define _WLCIOCBASE (0x1300) /* Wireless modules ioctl character driver commands */ +#define _CFGDIOCBASE (0x1400) /* Config Data device (app config) ioctl commands */ +#define _TCIOCBASE (0x1500) /* Timer ioctl commands */ +#define _DJOYBASE (0x1600) /* Discrete joystick ioctl commands */ +#define _AJOYBASE (0x1700) /* Analog joystick ioctl commands */ +#define _PIPEBASE (0x1800) /* FIFO/pipe ioctl commands */ +#define _RTCBASE (0x1900) /* RTC ioctl commands */ +#define _RELAYBASE (0x1a00) /* Relay devices ioctl commands */ +#define _CANBASE (0x1b00) /* CAN ioctl commands */ +#define _BTNBASE (0x1c00) /* Button ioctl commands */ +#define _ULEDBASE (0x1d00) /* User LED ioctl commands */ +#define _ZCBASE (0x1e00) /* Zero Cross ioctl commands */ +#define _LOOPBASE (0x1f00) /* Loop device commands */ +#define _MODEMBASE (0x2000) /* Modem ioctl commands */ +#define _I2CBASE (0x2100) /* I2C driver commands */ +#define _SPIBASE (0x2200) /* SPI driver commands */ +#define _GPIOBASE (0x2300) /* GPIO driver commands */ +#define _CLIOCBASE (0x2400) /* Contactless modules ioctl commands */ +#define _USBCBASE (0x2500) /* USB-C controller ioctl commands */ /* boardctl() commands share the same number space */ @@ -294,12 +295,18 @@ #define _SLCDIOCVALID(c) (_IOC_TYPE(c)==_SLCDIOCBASE) #define _SLCDIOC(nr) _IOC(_SLCDIOCBASE,nr) -/* Wireless driver ioctl definitions ****************************************/ +/* Wireless driver networki ioctl definitions *******************************/ /* (see nuttx/include/wireless/wireless.h */ #define _WLIOCVALID(c) (_IOC_TYPE(c)==_WLIOCBASE) #define _WLIOC(nr) _IOC(_WLIOCBASE,nr) +/* Wireless driver character driver ioctl definitions ***********************/ +/* (see nuttx/include/wireless/ioctl.h */ + +#define _WLCIOCVALID(c) (_IOC_TYPE(c)==_WLCIOCBASE) +#define _WLCIOC(nr) _IOC(_WLCIOCBASE,nr) + /* Application Config Data driver ioctl definitions *************************/ /* (see nuttx/include/configdata.h */ diff --git a/include/nuttx/wireless/cc3000.h b/include/nuttx/wireless/cc3000.h index 6aa234ed56..47348d2653 100644 --- a/include/nuttx/wireless/cc3000.h +++ b/include/nuttx/wireless/cc3000.h @@ -50,7 +50,7 @@ #include #include -#include +#include /**************************************************************************** * Pre-processor Definitions diff --git a/include/nuttx/wireless/cc3000/include/cc3000_upif.h b/include/nuttx/wireless/cc3000/include/cc3000_upif.h index e24d572b00..e44a2cf45c 100644 --- a/include/nuttx/wireless/cc3000/include/cc3000_upif.h +++ b/include/nuttx/wireless/cc3000/include/cc3000_upif.h @@ -54,7 +54,6 @@ #include #include #include -#include #if defined(CONFIG_DRIVERS_WIRELESS) && defined(CONFIG_WL_CC3000) diff --git a/include/nuttx/wireless/ioctl.h b/include/nuttx/wireless/ioctl.h new file mode 100644 index 0000000000..f21d589f36 --- /dev/null +++ b/include/nuttx/wireless/ioctl.h @@ -0,0 +1,108 @@ +/************************************************************************************ + * include/nuttx/wireless/ioctl.h + * Wireless character driver IOCTL commands + * + * Copyright (C) 2011-2013, 2017 Gregory Nutt. All rights reserved. + * Author: Laurent Latil + * + * 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. + * + ************************************************************************************/ + +/* This file includes common definitions to be used in all wireless character drivers + * (when applicable). + */ + +#ifndef __INCLUDE_NUTTX_WIRELESS_IOCTL_H +#define __INCLUDE_NUTTX_WIRELESS_IOCTL_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include + +#ifdef CONFIG_DRIVERS_WIRELESS + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Character Driver IOCTL commands *************************************************/ +/* Non-compatible, NuttX only IOCTL definitions for use with low-level wireless + * drivers that are accessed via a character device. Use of these IOCTL commands + * requires a file descriptor created by the open() interface. + */ + +#define WLIOC_SETRADIOFREQ _WLCIOC(0x0001) /* arg: Pointer to uint32_t, frequency + * value (in Mhz) */ +#define WLIOC_GETRADIOFREQ _WLCIOC(0x0002) /* arg: Pointer to uint32_t, frequency + * value (in Mhz) */ +#define WLIOC_SETADDR _WLCIOC(0x0003) /* arg: Pointer to address value, format + * of the address is driver specific */ +#define WLIOC_GETADDR _WLCIOC(0x0004) /* arg: Pointer to address value, format + * of the address is driver specific */ +#define WLIOC_SETTXPOWER _WLCIOC(0x0005) /* arg: Pointer to int32_t, output power + * (in dBm) */ +#define WLIOC_GETTXPOWER _WLCIOC(0x0006) /* arg: Pointer to int32_t, output power + * (in dBm) */ + +/* Device-specific IOCTL commands **************************************************/ + +#define WL_FIRST 0x0001 /* First common command */ +#define WL_NCMDS 0x0006 /* Number of common commands */ + +/* User defined ioctl commands are also supported. These will be forwarded + * by the upper-half QE driver to the lower-half QE driver via the ioctl() + * method fo the QE lower-half interface. However, the lower-half driver + * must reserve a block of commands as follows in order prevent IOCTL + * command numbers from overlapping. + */ + +/* See include/nuttx/wireless/cc3000.h */ + +#define CC3000_FIRST (WL_FIRST + WL_NCMDS) +#define CC3000_NCMDS 7 + +/* See include/nuttx/wireless/nrf24l01.h */ + +#define NRF24L01_FIRST (CC3000_FIRST + CC3000_NCMDS) +#define NRF24L01_NCMDS 14 + +/* See include/nuttx/wireless/ieee802154/ieee802154_ioctl.h */ + +#define IEEE802154_FIRST (NRF24L01_FIRST + NRF24L01_NCMDS) +#define IEEE802154_NCMDS 2 + +/************************************************************************************ + * Public Types + ************************************************************************************/ + + #endif /* CONFIG_DRIVERS_WIRELESS */ +#endif /* __INCLUDE_NUTTX_WIRELESS_IOCTL_H */ diff --git a/include/nuttx/wireless/nrf24l01.h b/include/nuttx/wireless/nrf24l01.h index 610b3c3682..d8b37aeeab 100644 --- a/include/nuttx/wireless/nrf24l01.h +++ b/include/nuttx/wireless/nrf24l01.h @@ -43,7 +43,7 @@ #include #include #include -#include +#include #include #include diff --git a/include/nuttx/wireless/wireless.h b/include/nuttx/wireless/wireless.h index a09c2bb148..b21135f2fe 100644 --- a/include/nuttx/wireless/wireless.h +++ b/include/nuttx/wireless/wireless.h @@ -1,5 +1,6 @@ /************************************************************************************ * include/nuttx/wireless/wireless.h + * Wireless network IOCTL commands * * Copyright (C) 2011-2013, 2017 Gregory Nutt. All rights reserved. * Author: Laurent Latil @@ -33,7 +34,7 @@ * ************************************************************************************/ -/* This file includes common definitions to be used in all wireless drivers +/* This file includes common definitions to be used in all wireless network drivers * (when applicable). */ @@ -153,49 +154,11 @@ #define SIOCSIWPMKSA _WLIOC(0x0032) /* PMKSA cache operation */ -#define WL_FIRSTCHAR 0x0033 -#define WL_NNETCMDS 0x0032 +/* Device-specific network IOCTL commands ******************************************/ -/* Character Driver IOCTL commands *************************************************/ -/* Non-compatible, NuttX only IOCTL definitions for use with low-level wireless - * drivers that are accessed via a character device. Use of these IOCTL commands - * requires a file descriptor created by the open() interface. - */ - -#define WLIOC_SETRADIOFREQ _WLIOC(0x0033) /* arg: Pointer to uint32_t, frequency - * value (in Mhz) */ -#define WLIOC_GETRADIOFREQ _WLIOC(0x0034) /* arg: Pointer to uint32_t, frequency - * value (in Mhz) */ -#define WLIOC_SETADDR _WLIOC(0x0035) /* arg: Pointer to address value, format - * of the address is driver specific */ -#define WLIOC_GETADDR _WLIOC(0x0036) /* arg: Pointer to address value, format - * of the address is driver specific */ -#define WLIOC_SETTXPOWER _WLIOC(0x0037) /* arg: Pointer to int32_t, output power - * (in dBm) */ -#define WLIOC_GETTXPOWER _WLIOC(0x0038) /* arg: Pointer to int32_t, output power - * (in dBm) */ - -/* Device-specific IOCTL commands **************************************************/ - -#define WL_FIRST 0x0001 /* First common command */ -#define WL_NCMDS 0x0038 /* Number of common commands */ - -/* User defined ioctl commands are also supported. These will be forwarded - * by the upper-half QE driver to the lower-half QE driver via the ioctl() - * method fo the QE lower-half interface. However, the lower-half driver - * must reserve a block of commands as follows in order prevent IOCTL - * command numbers from overlapping. - */ - -/* See include/nuttx/wireless/cc3000.h */ - -#define CC3000_FIRST (WL_FIRST + WL_NCMDS) -#define CC3000_NCMDS 7 - -/* See include/nuttx/wireless/nrf24l01.h */ - -#define NRF24L01_FIRST (CC3000_FIRST + CC3000_NCMDS) -#define NRF24L01_NCMDS 14 +#define WL_NETFIRST 0x0001 /* First network command */ +#define WL_NNETCMDS 0x0032 /* Number of network commands */ +#define WL_USERFIRST (WL_NETFIRST + WL_NNETCMDS) /* Other Common Wireless Definitions ***********************************************/ -- GitLab From 414516be20936d766d135f767bec42925d70c40c Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 27 Apr 2017 17:11:07 -0600 Subject: [PATCH 605/990] IEEE 802.15.4: Move MAC character driver IOCTL commands from ieee802154_mac.h to ieee802154_ioctl.h --- .../wireless/ieee802154/ieee802154_ioctl.h | 73 +++++++++++++++++++ 1 file changed, 73 insertions(+) create mode 100644 include/nuttx/wireless/ieee802154/ieee802154_ioctl.h diff --git a/include/nuttx/wireless/ieee802154/ieee802154_ioctl.h b/include/nuttx/wireless/ieee802154/ieee802154_ioctl.h new file mode 100644 index 0000000000..24ac37369f --- /dev/null +++ b/include/nuttx/wireless/ieee802154/ieee802154_ioctl.h @@ -0,0 +1,73 @@ +/************************************************************************************ + * include/nuttx/wireless/ieee802154/ieee802154_ioctl.h + * IEEE802.15.4 character driver IOCTL commands + * + * 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. + * + ************************************************************************************/ + +/* This file includes common definitions to be used in all wireless character drivers + * (when applicable). + */ + +#ifndef __INCLUDE_NUTTX_WIRELESS_IEEE802154_IEEE802154_IOCTL_H +#define __INCLUDE_NUTTX_WIRELESS_IEEE802154_IEEE802154_IOCTL_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include + +#ifdef CONFIG_WIRELESS_IEEE802154 + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* IEEE 802.15.4 Radio Character Driver IOCTL commands ******************************/ +/* None defined */ + +/* IEEE 802.15.4 MAC Character Driver IOCTL commands ********************************/ + + +#define MAC802154IOC_MCPS_REGISTER _WLCIOC(IEEE802154_FIRST) +#define MAC802154IOC_MLME_REGISTER _WLCIOC(IEEE802154_FIRST+1) + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/* To be provided */ + +#endif /* CONFIG_WIRELESS_IEEE802154 */ +#endif /* __INCLUDE_NUTTX_WIRELESS_IEEE802154_IEEE802154_IOCTL_H */ -- GitLab From 84a79502a2cdea1fac16a43e15f6b2af519e77f6 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 27 Apr 2017 17:11:36 -0600 Subject: [PATCH 606/990] IEEE 802.15.4: Move MAC character driver IOCTL commands from ieee802154_mac.h to ieee802154_ioctl.h --- include/nuttx/wireless/ieee802154/ieee802154_mac.h | 5 ----- 1 file changed, 5 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index e1aca5de75..fc2b57c8f7 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -85,9 +85,6 @@ * Request and Response primitives. */ -#define MAC802154IOC_MCPS_REGISTER _MAC802154IOC(0x0001) - -#define MAC802154IOC_MLME_REGISTER _MAC802154IOC(0x0002) #define MAC802154IOC_MLME_ASSOC_REQUEST _MAC802154IOC(0x0003) #define MAC802154IOC_MLME_ASSOC_RESPONSE _MAC802154IOC(0x0004) #define MAC802154IOC_MLME_DISASSOC_REQUEST _MAC802154IOC(0x0005) @@ -1290,8 +1287,6 @@ union ieee802154_mcps_notify_u union ieee802154_macarg_u { - union ieee802154_mcps_notify_u mcpsnotify; /* MAC802154IOC_MCPS_REGISTER */ - union ieee802154_mlme_notify_u mlmenotify; /* MAC802154IOC_MLME_REGISTER */ struct ieee802154_assoc_req_s assocreq; /* MAC802154IOC_MLME_ASSOC_REQUEST */ struct ieee802154_assoc_resp_s assocresp; /* MAC802154IOC_MLME_ASSOC_RESPONSE */ struct ieee802154_disassoc_req_s disassocreq; /* MAC802154IOC_MLME_DISASSOC_REQUEST */ -- GitLab From 4910e073cb97f072f261cf1e63d0aca525b37a3d Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 27 Apr 2017 17:16:02 -0600 Subject: [PATCH 607/990] Correct use of _WLIOC where _WLCIOC is required. --- include/nuttx/wireless/cc3000.h | 14 +++++++------- include/nuttx/wireless/ioctl.h | 3 ++- include/nuttx/wireless/nrf24l01.h | 28 ++++++++++++++-------------- include/nuttx/wireless/wireless.h | 2 +- 4 files changed, 24 insertions(+), 23 deletions(-) diff --git a/include/nuttx/wireless/cc3000.h b/include/nuttx/wireless/cc3000.h index 47348d2653..0350578b39 100644 --- a/include/nuttx/wireless/cc3000.h +++ b/include/nuttx/wireless/cc3000.h @@ -67,13 +67,13 @@ /* IOCTL commands */ -#define CC3000IOC_GETQUESEMID _WLIOC(CC3000_FIRST+0) /* arg: Address of int for number*/ -#define CC3000IOC_ADDSOCKET _WLIOC(CC3000_FIRST+1) /* arg: Address of int for result*/ -#define CC3000IOC_REMOVESOCKET _WLIOC(CC3000_FIRST+2) /* arg: Address of int for result*/ -#define CC3000IOC_SELECTDATA _WLIOC(CC3000_FIRST+3) /* arg: Address of int for result*/ -#define CC3000IOC_SELECTACCEPT _WLIOC(CC3000_FIRST+4) /* arg: Address of struct cc3000_acceptcfg_s */ -#define CC3000IOC_SETRX_SIZE _WLIOC(CC3000_FIRST+5) /* arg: Address of int for new size */ -#define CC3000IOC_REMOTECLOSEDSOCKET _WLIOC(CC3000_FIRST+6) /* arg: Address of int for result*/ +#define CC3000IOC_GETQUESEMID _WLCIOC(CC3000_FIRST+0) /* arg: Address of int for number*/ +#define CC3000IOC_ADDSOCKET _WLCIOC(CC3000_FIRST+1) /* arg: Address of int for result*/ +#define CC3000IOC_REMOVESOCKET _WLCIOC(CC3000_FIRST+2) /* arg: Address of int for result*/ +#define CC3000IOC_SELECTDATA _WLCIOC(CC3000_FIRST+3) /* arg: Address of int for result*/ +#define CC3000IOC_SELECTACCEPT _WLCIOC(CC3000_FIRST+4) /* arg: Address of struct cc3000_acceptcfg_s */ +#define CC3000IOC_SETRX_SIZE _WLCIOC(CC3000_FIRST+5) /* arg: Address of int for new size */ +#define CC3000IOC_REMOTECLOSEDSOCKET _WLCIOC(CC3000_FIRST+6) /* arg: Address of int for result*/ /**************************************************************************** * Public Types diff --git a/include/nuttx/wireless/ioctl.h b/include/nuttx/wireless/ioctl.h index f21d589f36..1d9c38dd8d 100644 --- a/include/nuttx/wireless/ioctl.h +++ b/include/nuttx/wireless/ioctl.h @@ -4,6 +4,7 @@ * * Copyright (C) 2011-2013, 2017 Gregory Nutt. All rights reserved. * Author: Laurent Latil + * Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -104,5 +105,5 @@ * Public Types ************************************************************************************/ - #endif /* CONFIG_DRIVERS_WIRELESS */ +#endif /* CONFIG_DRIVERS_WIRELESS */ #endif /* __INCLUDE_NUTTX_WIRELESS_IOCTL_H */ diff --git a/include/nuttx/wireless/nrf24l01.h b/include/nuttx/wireless/nrf24l01.h index d8b37aeeab..123eb93503 100644 --- a/include/nuttx/wireless/nrf24l01.h +++ b/include/nuttx/wireless/nrf24l01.h @@ -66,20 +66,20 @@ /* IOCTL commands */ -#define NRF24L01IOC_SETRETRCFG _WLIOC(NRF24L01_FIRST+0) /* arg: Pointer to nrf24l01_retrcfg_t structure */ -#define NRF24L01IOC_GETRETRCFG _WLIOC(NRF24L01_FIRST+1) /* arg: Pointer to nrf24l01_retrcfg_t structure */ -#define NRF24L01IOC_SETPIPESCFG _WLIOC(NRF24L01_FIRST+2) /* arg: Pointer to an array of nrf24l01_pipecfg_t pointers */ -#define NRF24L01IOC_GETPIPESCFG _WLIOC(NRF24L01_FIRST+3) /* arg: Pointer to an array of nrf24l01_pipecfg_t pointers */ -#define NRF24L01IOC_SETPIPESENABLED _WLIOC(NRF24L01_FIRST+4) /* arg: Pointer to a uint8_t value, bit field of enabled / disabled pipes */ -#define NRF24L01IOC_GETPIPESENABLED _WLIOC(NRF24L01_FIRST+5) /* arg: Pointer to a uint8_t value, bit field of enabled / disabled pipes */ -#define NRF24L01IOC_SETDATARATE _WLIOC(NRF24L01_FIRST+6) /* arg: Pointer to a nrf24l01_datarate_t value */ -#define NRF24L01IOC_GETDATARATE _WLIOC(NRF24L01_FIRST+7) /* arg: Pointer to a nrf24l01_datarate_t value */ -#define NRF24L01IOC_SETADDRWIDTH _WLIOC(NRF24L01_FIRST+8) /* arg: Pointer to an uint32_t value, width of the address */ -#define NRF24L01IOC_GETADDRWIDTH _WLIOC(NRF24L01_FIRST+9) /* arg: Pointer to an uint32_t value, width of the address */ -#define NRF24L01IOC_SETSTATE _WLIOC(NRF24L01_FIRST+10) /* arg: Pointer to a nrf24l01_state_t value */ -#define NRF24L01IOC_GETSTATE _WLIOC(NRF24L01_FIRST+11) /* arg: Pointer to a nrf24l01_state_t value */ -#define NRF24L01IOC_GETLASTXMITCOUNT _WLIOC(NRF24L01_FIRST+12) /* arg: Pointer to an uint32_t value, retransmission count of the last send operation (NRF24L01_XMIT_MAXRT if no ACK received)*/ -#define NRF24L01IOC_GETLASTPIPENO _WLIOC(NRF24L01_FIRST+13) /* arg: Pointer to an uint32_t value, pipe # of the last received packet */ +#define NRF24L01IOC_SETRETRCFG _WLCIOC(NRF24L01_FIRST+0) /* arg: Pointer to nrf24l01_retrcfg_t structure */ +#define NRF24L01IOC_GETRETRCFG _WLCIOC(NRF24L01_FIRST+1) /* arg: Pointer to nrf24l01_retrcfg_t structure */ +#define NRF24L01IOC_SETPIPESCFG _WLCIOC(NRF24L01_FIRST+2) /* arg: Pointer to an array of nrf24l01_pipecfg_t pointers */ +#define NRF24L01IOC_GETPIPESCFG _WLCIOC(NRF24L01_FIRST+3) /* arg: Pointer to an array of nrf24l01_pipecfg_t pointers */ +#define NRF24L01IOC_SETPIPESENABLED _WLCIOC(NRF24L01_FIRST+4) /* arg: Pointer to a uint8_t value, bit field of enabled / disabled pipes */ +#define NRF24L01IOC_GETPIPESENABLED _WLCIOC(NRF24L01_FIRST+5) /* arg: Pointer to a uint8_t value, bit field of enabled / disabled pipes */ +#define NRF24L01IOC_SETDATARATE _WLCIOC(NRF24L01_FIRST+6) /* arg: Pointer to a nrf24l01_datarate_t value */ +#define NRF24L01IOC_GETDATARATE _WLCIOC(NRF24L01_FIRST+7) /* arg: Pointer to a nrf24l01_datarate_t value */ +#define NRF24L01IOC_SETADDRWIDTH _WLCIOC(NRF24L01_FIRST+8) /* arg: Pointer to an uint32_t value, width of the address */ +#define NRF24L01IOC_GETADDRWIDTH _WLCIOC(NRF24L01_FIRST+9) /* arg: Pointer to an uint32_t value, width of the address */ +#define NRF24L01IOC_SETSTATE _WLCIOC(NRF24L01_FIRST+10) /* arg: Pointer to a nrf24l01_state_t value */ +#define NRF24L01IOC_GETSTATE _WLCIOC(NRF24L01_FIRST+11) /* arg: Pointer to a nrf24l01_state_t value */ +#define NRF24L01IOC_GETLASTXMITCOUNT _WLCIOC(NRF24L01_FIRST+12) /* arg: Pointer to an uint32_t value, retransmission count of the last send operation (NRF24L01_XMIT_MAXRT if no ACK received)*/ +#define NRF24L01IOC_GETLASTPIPENO _WLCIOC(NRF24L01_FIRST+13) /* arg: Pointer to an uint32_t value, pipe # of the last received packet */ /* Aliased name for these commands */ diff --git a/include/nuttx/wireless/wireless.h b/include/nuttx/wireless/wireless.h index b21135f2fe..a07a4cbf70 100644 --- a/include/nuttx/wireless/wireless.h +++ b/include/nuttx/wireless/wireless.h @@ -3,7 +3,7 @@ * Wireless network IOCTL commands * * Copyright (C) 2011-2013, 2017 Gregory Nutt. All rights reserved. - * Author: Laurent Latil + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions -- GitLab From 1b3ab950a4f4e463b2e6f8d041da301537caebf1 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 27 Apr 2017 17:44:07 -0600 Subject: [PATCH 608/990] STM32F103-Mininum: Rename an incorrectly named file. --- configs/stm32f103-minimum/src/Makefile | 2 +- .../src/{stm32_cc3000.c => stm32_nrf24l01.c} | 10 +++++----- 2 files changed, 6 insertions(+), 6 deletions(-) rename configs/stm32f103-minimum/src/{stm32_cc3000.c => stm32_nrf24l01.c} (95%) diff --git a/configs/stm32f103-minimum/src/Makefile b/configs/stm32f103-minimum/src/Makefile index 75b6cb2953..8402e553ea 100644 --- a/configs/stm32f103-minimum/src/Makefile +++ b/configs/stm32f103-minimum/src/Makefile @@ -86,7 +86,7 @@ CSRCS += stm32_veml6070.c endif ifeq ($(CONFIG_WL_NRF24L01),y) -CSRCS += stm32_cc3000.c +CSRCS += stm32_nrf24l01.c endif ifeq ($(CONFIG_USBDEV),y) diff --git a/configs/stm32f103-minimum/src/stm32_cc3000.c b/configs/stm32f103-minimum/src/stm32_nrf24l01.c similarity index 95% rename from configs/stm32f103-minimum/src/stm32_cc3000.c rename to configs/stm32f103-minimum/src/stm32_nrf24l01.c index 23b1144ef5..6edecba0e0 100644 --- a/configs/stm32f103-minimum/src/stm32_cc3000.c +++ b/configs/stm32f103-minimum/src/stm32_nrf24l01.c @@ -1,5 +1,5 @@ /************************************************************************************ - * configs/stm32f103-minimum//src/stm32_cc3000.c + * configs/stm32f103-minimum//src/stm32_nrf24l01.c * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Laurent Latil @@ -82,7 +82,7 @@ static FAR void *g_arg; static int stm32tiny_wl_irq_attach(xcpt_t isr, FAR void *arg) { - winfo("Attach IRQ\n"); + wlinfo("Attach IRQ\n"); g_isr = isr; g_arg = arg; (void)stm32_gpiosetevent(GPIO_NRF24L01_IRQ, false, true, false, g_isr, g_arg); @@ -91,7 +91,7 @@ static int stm32tiny_wl_irq_attach(xcpt_t isr, FAR void *arg) static void stm32tiny_wl_chip_enable(bool enable) { - winfo("CE:%d\n", enable); + wlinfo("CE:%d\n", enable); stm32_gpiowrite(GPIO_NRF24L01_CE, enable); } @@ -132,14 +132,14 @@ void stm32_wlinitialize(void) spidev = stm32_spibus_initialize(1); if (!spidev) { - werr("ERROR: Failed to initialize SPI bus\n"); + wlerr("ERROR: Failed to initialize SPI bus\n"); return; } result = nrf24l01_register(spidev, &nrf_cfg); if (result != OK) { - werr("ERROR: Failed to register initialize SPI bus\n"); + wlerr("ERROR: Failed to register initialize SPI bus\n"); return; } } -- GitLab From d1fc0040d7fcc1ed4e64fecfb48df6d0bceaa263 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 27 Apr 2017 17:44:07 -0600 Subject: [PATCH 609/990] STM32F103-Mininum: Rename an incorrectly named file. --- configs/stm32f103-minimum/src/Makefile | 2 +- .../src/{stm32_cc3000.c => stm32_nrf24l01.c} | 10 +++++----- 2 files changed, 6 insertions(+), 6 deletions(-) rename configs/stm32f103-minimum/src/{stm32_cc3000.c => stm32_nrf24l01.c} (95%) diff --git a/configs/stm32f103-minimum/src/Makefile b/configs/stm32f103-minimum/src/Makefile index 75b6cb2953..8402e553ea 100644 --- a/configs/stm32f103-minimum/src/Makefile +++ b/configs/stm32f103-minimum/src/Makefile @@ -86,7 +86,7 @@ CSRCS += stm32_veml6070.c endif ifeq ($(CONFIG_WL_NRF24L01),y) -CSRCS += stm32_cc3000.c +CSRCS += stm32_nrf24l01.c endif ifeq ($(CONFIG_USBDEV),y) diff --git a/configs/stm32f103-minimum/src/stm32_cc3000.c b/configs/stm32f103-minimum/src/stm32_nrf24l01.c similarity index 95% rename from configs/stm32f103-minimum/src/stm32_cc3000.c rename to configs/stm32f103-minimum/src/stm32_nrf24l01.c index 23b1144ef5..6edecba0e0 100644 --- a/configs/stm32f103-minimum/src/stm32_cc3000.c +++ b/configs/stm32f103-minimum/src/stm32_nrf24l01.c @@ -1,5 +1,5 @@ /************************************************************************************ - * configs/stm32f103-minimum//src/stm32_cc3000.c + * configs/stm32f103-minimum//src/stm32_nrf24l01.c * * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Laurent Latil @@ -82,7 +82,7 @@ static FAR void *g_arg; static int stm32tiny_wl_irq_attach(xcpt_t isr, FAR void *arg) { - winfo("Attach IRQ\n"); + wlinfo("Attach IRQ\n"); g_isr = isr; g_arg = arg; (void)stm32_gpiosetevent(GPIO_NRF24L01_IRQ, false, true, false, g_isr, g_arg); @@ -91,7 +91,7 @@ static int stm32tiny_wl_irq_attach(xcpt_t isr, FAR void *arg) static void stm32tiny_wl_chip_enable(bool enable) { - winfo("CE:%d\n", enable); + wlinfo("CE:%d\n", enable); stm32_gpiowrite(GPIO_NRF24L01_CE, enable); } @@ -132,14 +132,14 @@ void stm32_wlinitialize(void) spidev = stm32_spibus_initialize(1); if (!spidev) { - werr("ERROR: Failed to initialize SPI bus\n"); + wlerr("ERROR: Failed to initialize SPI bus\n"); return; } result = nrf24l01_register(spidev, &nrf_cfg); if (result != OK) { - werr("ERROR: Failed to register initialize SPI bus\n"); + wlerr("ERROR: Failed to register initialize SPI bus\n"); return; } } -- GitLab From c109e92962dabf9dbd9468346d0fc4354e562bae Mon Sep 17 00:00:00 2001 From: Yasuhiro Osaki Date: Fri, 8 May 2015 14:00:59 +0900 Subject: [PATCH 610/990] binfmt: Fix offset value when calling elf_read() in elf_sectname() Jira: PDFW15IS-3030 Signed-off-by: Masayuki Ishikawa --- binfmt/libelf/libelf_sections.c | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/binfmt/libelf/libelf_sections.c b/binfmt/libelf/libelf_sections.c index 8f4369d367..6f58b4a318 100644 --- a/binfmt/libelf/libelf_sections.c +++ b/binfmt/libelf/libelf_sections.c @@ -114,7 +114,6 @@ static inline int elf_sectname(FAR struct elf_loadinfo_s *loadinfo, /* Loop until we get the entire section name into memory */ - buffer = loadinfo->iobuffer; bytesread = 0; for (; ; ) @@ -136,7 +135,7 @@ static inline int elf_sectname(FAR struct elf_loadinfo_s *loadinfo, /* Read that number of bytes into the array */ buffer = &loadinfo->iobuffer[bytesread]; - ret = elf_read(loadinfo, buffer, readlen, offset); + ret = elf_read(loadinfo, buffer, readlen, offset + bytesread); if (ret < 0) { berr("Failed to read section name\n"); -- GitLab From d928b4271dda8268292763f33f3c45bbe39878fa Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Fri, 28 Apr 2017 08:00:36 -0600 Subject: [PATCH 611/990] net/socket: fix cloning of local and raw sockets --- net/socket/net_clone.c | 20 ++++++++++++++++++++ 1 file changed, 20 insertions(+) diff --git a/net/socket/net_clone.c b/net/socket/net_clone.c index a08c236329..d720eb8731 100644 --- a/net/socket/net_clone.c +++ b/net/socket/net_clone.c @@ -50,6 +50,8 @@ #include "tcp/tcp.h" #include "udp/udp.h" +#include "pkt/pkt.h" +#include "local/local.h" #include "socket/socket.h" #include "usrsock/usrsock.h" @@ -97,6 +99,24 @@ int net_clone(FAR struct socket *psock1, FAR struct socket *psock2) DEBUGASSERT(psock2->s_conn); psock2->s_crefs = 1; /* One reference on the new socket itself */ +#ifdef CONFIG_NET_LOCAL + if (psock2->s_domain == PF_LOCAL) + { + FAR struct local_conn_s *conn = psock2->s_conn; + DEBUGASSERT(conn->lc_crefs > 0 && conn->lc_crefs < 255); + conn->lc_crefs++; + } + else +#endif +#ifdef CONFIG_NET_PKT + if (psock2->s_type == SOCK_RAW) + { + FAR struct pkt_conn_s *conn = psock2->s_conn; + DEBUGASSERT(conn->crefs > 0 && conn->crefs < 255); + conn->crefs++; + } + else +#endif #ifdef NET_TCP_HAVE_STACK if (psock2->s_type == SOCK_STREAM) { -- GitLab From b4d2651ca9e5866da10c3d0aa8be92c9692af5fd Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Fri, 28 Apr 2017 08:09:16 -0600 Subject: [PATCH 612/990] STM32L4: stm32l4_i2c: add I2C4 code --- arch/arm/include/stm32l4/stm32l4x6xx_irq.h | 4 +- arch/arm/src/stm32l4/README.txt | 4 +- arch/arm/src/stm32l4/stm32l4_i2c.c | 60 ++++++++++++++++++++-- 3 files changed, 61 insertions(+), 7 deletions(-) diff --git a/arch/arm/include/stm32l4/stm32l4x6xx_irq.h b/arch/arm/include/stm32l4/stm32l4x6xx_irq.h index 23d5ec4247..b675e786bb 100644 --- a/arch/arm/include/stm32l4/stm32l4x6xx_irq.h +++ b/arch/arm/include/stm32l4/stm32l4x6xx_irq.h @@ -149,8 +149,8 @@ /* STM32L496xx/4A6xx only: */ #define STM32L4_IRQ_HASH_CRS (STM32L4_IRQ_FIRST+82) /* 82: HASH and CRS global interrupt */ -#define STM32L4_IRQ_I2C4_EV (STM32L4_IRQ_FIRST+83) /* 83: I2C4 event interrupt */ -#define STM32L4_IRQ_I2C4_ER (STM32L4_IRQ_FIRST+84) /* 84: I2C4 error interrupt */ +#define STM32L4_IRQ_I2C4EV (STM32L4_IRQ_FIRST+83) /* 83: I2C4 event interrupt */ +#define STM32L4_IRQ_I2C4ER (STM32L4_IRQ_FIRST+84) /* 84: I2C4 error interrupt */ #define STM32L4_IRQ_DCMI (STM32L4_IRQ_FIRST+85) /* 85: DCMI global interrupt */ #define STM32L4_IRQ_CAN2TX (STM32L4_IRQ_FIRST+86) /* 86: CAN2 TX interrupts */ #define STM32L4_IRQ_CAN2RX0 (STM32L4_IRQ_FIRST+87) /* 87: CAN2 RX0 interrupts */ diff --git a/arch/arm/src/stm32l4/README.txt b/arch/arm/src/stm32l4/README.txt index 944be02c29..9124d966a7 100644 --- a/arch/arm/src/stm32l4/README.txt +++ b/arch/arm/src/stm32l4/README.txt @@ -26,7 +26,7 @@ SRAM2 : OK; can be included in MM region or left separate for special app : purposes FIREWALL : Code written, to be tested, requires support from ldscript SPI : OK, tested (Including DMA) -I2C : Code written, to be tested (I2C4 missing) +I2C : Code written, to be tested RTC : works QSPI : works in polling, interrupt, DMA, and also memory-mapped modes CAN : OK, tested @@ -57,7 +57,7 @@ SWP : TODO (Single wire protocol master, to connect with NFC enabled LPUART : TODO (Low power UART working with LSE at low baud rates) LPTIMER : TODO (Low power TIMER) OPAMP : TODO (Analog operational amplifier) -COMP : TODO (Analog comparators) +COMP : There is some code (Analog comparators) DFSDM : TODO (Digital Filter and Sigma-Delta Modulator) LCD : TODO (Segment LCD controller) SAIPLL : works (PLL For Digital Audio interfaces, and other things) diff --git a/arch/arm/src/stm32l4/stm32l4_i2c.c b/arch/arm/src/stm32l4/stm32l4_i2c.c index 3468af22be..6df49e444f 100644 --- a/arch/arm/src/stm32l4/stm32l4_i2c.c +++ b/arch/arm/src/stm32l4/stm32l4_i2c.c @@ -96,7 +96,8 @@ /* At least one I2C peripheral must be enabled */ -#if defined(CONFIG_STM32L4_I2C1) || defined(CONFIG_STM32L4_I2C2) || defined(CONFIG_STM32L4_I2C3) +#if defined(CONFIG_STM32L4_I2C1) || defined(CONFIG_STM32L4_I2C2) || \ + defined(CONFIG_STM32L4_I2C3) || defined(CONFIG_STM32L4_I2C4) /************************************************************************************ * Pre-processor Definitions @@ -300,6 +301,9 @@ static int stm32l4_i2c2_isr(int irq, void *context, FAR void *arg); #ifdef CONFIG_STM32L4_I2C3 static int stm32l4_i2c3_isr(int irq, void *context, FAR void *arg); #endif +#ifdef CONFIG_STM32L4_I2C4 +static int stm32l4_i2c4_isr(int irq, void *context, FAR void *arg); +#endif #endif static int stm32l4_i2c_init(FAR struct stm32l4_i2c_priv_s *priv); static int stm32l4_i2c_deinit(FAR struct stm32l4_i2c_priv_s *priv); @@ -413,6 +417,36 @@ struct stm32l4_i2c_priv_s stm32l4_i2c3_priv = }; #endif +#ifdef CONFIG_STM32L4_I2C4 +static const struct stm32l4_i2c_config_s stm32l4_i2c4_config = +{ + .base = STM32L4_I2C4_BASE, + .clk_bit = RCC_APB1ENR2_I2C4EN, + .reset_bit = RCC_APB1RSTR2_I2C4RST, + .scl_pin = GPIO_I2C4_SCL, + .sda_pin = GPIO_I2C4_SDA, +#ifndef CONFIG_I2C_POLLED + .isr = stm32l4_i2c4_isr, + .ev_irq = STM32L4_IRQ_I2C4EV, + .er_irq = STM32L4_IRQ_I2C4ER +#endif +}; + +struct stm32l4_i2c_priv_s stm32l4_i2c4_priv = +{ + .ops = &stm32l4_i2c_ops, + .config = &stm32l4_i2c4_config, + .refs = 0, + .intstate = INTSTATE_IDLE, + .msgc = 0, + .msgv = NULL, + .ptr = NULL, + .dcnt = 0, + .flags = 0, + .status = 0 +}; +#endif + /************************************************************************************ * Private Functions ************************************************************************************/ @@ -1541,7 +1575,7 @@ static int stm32l4_i2c2_isr(int irq, void *context, FAR void *arg) * Name: stm32l4_i2c3_isr * * Description: - * I2C2 interrupt service routine + * I2C3 interrupt service routine * ************************************************************************************/ @@ -1551,7 +1585,22 @@ static int stm32l4_i2c3_isr(int irq, void *context, FAR void *arg) return stm32l4_i2c_isr(&stm32l4_i2c3_priv); } #endif + +/************************************************************************************ + * Name: stm32l4_i2c4_isr + * + * Description: + * I2C4 interrupt service routine + * + ************************************************************************************/ + +#ifdef CONFIG_STM32L4_I2C4 +static int stm32l4_i2c4_isr(int irq, void *context, FAR void *arg) +{ + return stm32l4_i2c_isr(&stm32l4_i2c4_priv); +} #endif +#endif /* !CONFIG_I2C_POLLED */ /************************************************************************************ * Private Initialization and Deinitialization @@ -2009,6 +2058,11 @@ FAR struct i2c_master_s *stm32l4_i2cbus_initialize(int port) case 3: priv = (struct stm32l4_i2c_priv_s *)&stm32l4_i2c3_priv; break; +#endif +#ifdef CONFIG_STM32L4_I2C4 + case 4: + priv = (struct stm32l4_i2c_priv_s *)&stm32l4_i2c4_priv; + break; #endif default: return NULL; @@ -2072,5 +2126,5 @@ int stm32l4_i2cbus_uninitialize(FAR struct i2c_master_s * dev) return OK; } -#endif /* CONFIG_STM32L4_I2C1 || CONFIG_STM32L4_I2C2 || CONFIG_STM32L4_I2C3 */ +#endif /* CONFIG_STM32L4_I2C1 || CONFIG_STM32L4_I2C2 || CONFIG_STM32L4_I2C3 || CONFIG_STM32L4_I2C4 */ -- GitLab From 9431fb1d912713e4ae156635752b422476ca5350 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 28 Apr 2017 08:21:02 -0600 Subject: [PATCH 613/990] STM32L4: I2C was not using current interrupt handling parameter passing logic. --- arch/arm/src/stm32l4/stm32l4_i2c.c | 94 +++++------------------------- 1 file changed, 15 insertions(+), 79 deletions(-) diff --git a/arch/arm/src/stm32l4/stm32l4_i2c.c b/arch/arm/src/stm32l4/stm32l4_i2c.c index 6df49e444f..9be4419de4 100644 --- a/arch/arm/src/stm32l4/stm32l4_i2c.c +++ b/arch/arm/src/stm32l4/stm32l4_i2c.c @@ -215,7 +215,6 @@ struct stm32l4_i2c_config_s uint32_t scl_pin; /* GPIO configuration for SCL as SCL */ uint32_t sda_pin; /* GPIO configuration for SDA as SDA */ #ifndef CONFIG_I2C_POLLED - int (*isr)(int, void *, void *); /* Interrupt handler */ uint32_t ev_irq; /* Event IRQ */ uint32_t er_irq; /* Error IRQ */ #endif @@ -290,20 +289,9 @@ static inline void stm32l4_i2c_sendstart(FAR struct stm32l4_i2c_priv_s *priv); static inline void stm32l4_i2c_clrstart(FAR struct stm32l4_i2c_priv_s *priv); static inline void stm32l4_i2c_sendstop(FAR struct stm32l4_i2c_priv_s *priv); static inline uint32_t stm32l4_i2c_getstatus(FAR struct stm32l4_i2c_priv_s *priv); -static int stm32l4_i2c_isr(struct stm32l4_i2c_priv_s * priv); +static int stm32l4_i2c_isr_process(struct stm32l4_i2c_priv_s *priv); #ifndef CONFIG_I2C_POLLED -#ifdef CONFIG_STM32L4_I2C1 -static int stm32l4_i2c1_isr(int irq, void *context, FAR void *arg); -#endif -#ifdef CONFIG_STM32L4_I2C2 -static int stm32l4_i2c2_isr(int irq, void *context, FAR void *arg); -#endif -#ifdef CONFIG_STM32L4_I2C3 -static int stm32l4_i2c3_isr(int irq, void *context, FAR void *arg); -#endif -#ifdef CONFIG_STM32L4_I2C4 -static int stm32l4_i2c4_isr(int irq, void *context, FAR void *arg); -#endif +static int stm32l4_i2c_isr(int irq, void *context, FAR void *arg); #endif static int stm32l4_i2c_init(FAR struct stm32l4_i2c_priv_s *priv); static int stm32l4_i2c_deinit(FAR struct stm32l4_i2c_priv_s *priv); @@ -336,7 +324,6 @@ static const struct stm32l4_i2c_config_s stm32l4_i2c1_config = .scl_pin = GPIO_I2C1_SCL, .sda_pin = GPIO_I2C1_SDA, #ifndef CONFIG_I2C_POLLED - .isr = stm32l4_i2c1_isr, .ev_irq = STM32L4_IRQ_I2C1EV, .er_irq = STM32L4_IRQ_I2C1ER #endif @@ -366,7 +353,6 @@ static const struct stm32l4_i2c_config_s stm32l4_i2c2_config = .scl_pin = GPIO_I2C2_SCL, .sda_pin = GPIO_I2C2_SDA, #ifndef CONFIG_I2C_POLLED - .isr = stm32l4_i2c2_isr, .ev_irq = STM32L4_IRQ_I2C2EV, .er_irq = STM32L4_IRQ_I2C2ER #endif @@ -396,7 +382,6 @@ static const struct stm32l4_i2c_config_s stm32l4_i2c3_config = .scl_pin = GPIO_I2C3_SCL, .sda_pin = GPIO_I2C3_SDA, #ifndef CONFIG_I2C_POLLED - .isr = stm32l4_i2c3_isr, .ev_irq = STM32L4_IRQ_I2C3EV, .er_irq = STM32L4_IRQ_I2C3ER #endif @@ -426,7 +411,6 @@ static const struct stm32l4_i2c_config_s stm32l4_i2c4_config = .scl_pin = GPIO_I2C4_SCL, .sda_pin = GPIO_I2C4_SDA, #ifndef CONFIG_I2C_POLLED - .isr = stm32l4_i2c4_isr, .ev_irq = STM32L4_IRQ_I2C4EV, .er_irq = STM32L4_IRQ_I2C4ER #endif @@ -690,7 +674,7 @@ static inline int stm32l4_i2c_sem_waitdone(FAR struct stm32l4_i2c_priv_s *priv) * reports that it is done. */ - stm32l4_i2c_isr(priv); + stm32l4_i2c_isr_process(priv); } /* Loop until the transfer is complete. */ @@ -1299,7 +1283,7 @@ static inline uint32_t stm32l4_i2c_getstatus(FAR struct stm32l4_i2c_priv_s *priv } /************************************************************************************ - * Name: stm32l4_i2c_isr + * Name: stm32l4_i2c_isr_startmessage * * Description: * Common logic when a message is started. Just adds the even to the trace buffer @@ -1332,14 +1316,14 @@ static inline void stm32l4_i2c_clearinterrupts(struct stm32l4_i2c_priv_s *priv) } /************************************************************************************ - * Name: stm32l4_i2c_isr + * Name: stm32l4_i2c_isr_process * * Description: - * Common Interrupt Service Routine + * I2C processing logic common to polled and non-polled operation. * ************************************************************************************/ -static int stm32l4_i2c_isr(struct stm32l4_i2c_priv_s *priv) +static int stm32l4_i2c_isr_process(struct stm32l4_i2c_priv_s *priv) { uint32_t status = stm32l4_i2c_getstatus(priv); @@ -1541,71 +1525,23 @@ static int stm32l4_i2c_isr(struct stm32l4_i2c_priv_s *priv) } /************************************************************************************ - * Name: stm32l4_i2c1_isr - * - * Description: - * I2C1 interrupt service routine - * - ************************************************************************************/ - -#ifndef CONFIG_I2C_POLLED -#ifdef CONFIG_STM32L4_I2C1 -static int stm32l4_i2c1_isr(int irq, void *context, FAR void *arg) -{ - return stm32l4_i2c_isr(&stm32l4_i2c1_priv); -} -#endif - -/************************************************************************************ - * Name: stm32l4_i2c2_isr + * Name: stm32l4_i2c_isr * * Description: - * I2C2 interrupt service routine + * I2C interrupt service routine * ************************************************************************************/ #ifdef CONFIG_STM32L4_I2C2 -static int stm32l4_i2c2_isr(int irq, void *context, FAR void *arg) +static int stm32l4_i2c_isr(int irq, void *context, FAR void *arg) { - return stm32l4_i2c_isr(&stm32l4_i2c2_priv); -} -#endif - -/************************************************************************************ - * Name: stm32l4_i2c3_isr - * - * Description: - * I2C3 interrupt service routine - * - ************************************************************************************/ + struct stm32l4_i2c_priv_s *priv = (struct stm32l4_i2c_priv_s *priv)arg; -#ifdef CONFIG_STM32L4_I2C3 -static int stm32l4_i2c3_isr(int irq, void *context, FAR void *arg) -{ - return stm32l4_i2c_isr(&stm32l4_i2c3_priv); + DEBUGASSERT(priv != NULL); + return stm32l4_i2c_isr_process(priv); } #endif -/************************************************************************************ - * Name: stm32l4_i2c4_isr - * - * Description: - * I2C4 interrupt service routine - * - ************************************************************************************/ - -#ifdef CONFIG_STM32L4_I2C4 -static int stm32l4_i2c4_isr(int irq, void *context, FAR void *arg) -{ - return stm32l4_i2c_isr(&stm32l4_i2c4_priv); -} -#endif -#endif /* !CONFIG_I2C_POLLED */ - -/************************************************************************************ - * Private Initialization and Deinitialization - ************************************************************************************/ - /************************************************************************************ * Name: stm32l4_i2c_init * @@ -1640,8 +1576,8 @@ static int stm32l4_i2c_init(FAR struct stm32l4_i2c_priv_s *priv) /* Attach ISRs */ #ifndef CONFIG_I2C_POLLED - irq_attach(priv->config->ev_irq, priv->config->isr, NULL); - irq_attach(priv->config->er_irq, priv->config->isr, NULL); + irq_attach(priv->config->ev_irq, stm32l4_i2c_isr, priv); + irq_attach(priv->config->er_irq, stm32l4_i2c_isr, priv); up_enable_irq(priv->config->ev_irq); up_enable_irq(priv->config->er_irq); #endif -- GitLab From 37ca797d1cd2d72519fd1511823ca6dd9c65860c Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Fri, 28 Apr 2017 08:42:37 -0600 Subject: [PATCH 614/990] vfs/poll: round timeout up to next full tick. Calling poll() with timeout less than half tick (thus MSEC2TICK(timeout) => 0) caused returning error with EAGAIN. Instead of rounding timeout down, value should be rounded up. Open Group spec for poll says: "Implementations may place limitations on the granularity of timeout intervals. If the requested timeout interval requires a finer granularity than the implementation supports, the actual timeout interval will be rounded up to the next supported value." --- fs/vfs/fs_poll.c | 21 ++++++++++++++++++++- 1 file changed, 20 insertions(+), 1 deletion(-) diff --git a/fs/vfs/fs_poll.c b/fs/vfs/fs_poll.c index 168c393dd0..c828890210 100644 --- a/fs/vfs/fs_poll.c +++ b/fs/vfs/fs_poll.c @@ -388,6 +388,25 @@ int poll(FAR struct pollfd *fds, nfds_t nfds, int timeout) } else if (timeout > 0) { + systime_t ticks; + + /* "Implementations may place limitations on the granularity of + * timeout intervals. If the requested timeout interval requires + * a finer granularity than the implementation supports, the + * actual timeout interval will be rounded up to the next + * supported value." -- opengroup.org + * + * Round timeout up to next full tick. + */ + +#if (MSEC_PER_TICK * USEC_PER_MSEC) != USEC_PER_TICK && \ + defined(CONFIG_HAVE_LONG_LONG) + ticks = ((long long)timeout * USEC_PER_MSEC) + (USEC_PER_TICK - 1) / + USEC_PER_TICK; +#else + ticks = (timeout + (MSEC_PER_TICK - 1)) / MSEC_PER_TICK; +#endif + /* Either wait for either a poll event(s), for a signal to occur, * or for the specified timeout to elapse with no event. * @@ -396,7 +415,7 @@ int poll(FAR struct pollfd *fds, nfds_t nfds, int timeout) * immediately. */ - ret = sem_tickwait(&sem, clock_systimer(), MSEC2TICK(timeout)); + ret = sem_tickwait(&sem, clock_systimer(), ticks); if (ret < 0) { if (ret == -ETIMEDOUT) -- GitLab From 401caf6826a2b4257168b363af424a42e30e58d5 Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Fri, 28 Apr 2017 18:15:29 +0200 Subject: [PATCH 615/990] add main includes --- include/nuttx/spi/spi.h | 85 ++++++++++++++++++++++---------- include/nuttx/spi/spi_transfer.h | 2 +- 2 files changed, 61 insertions(+), 26 deletions(-) diff --git a/include/nuttx/spi/spi.h b/include/nuttx/spi/spi.h index 2a48bc92e3..92d2ecb4b8 100644 --- a/include/nuttx/spi/spi.h +++ b/include/nuttx/spi/spi.h @@ -428,33 +428,68 @@ typedef void (*spi_mediachange_t)(FAR void *arg); -/* If the board supports multiple SPI devices, this enumeration identifies - * which is selected or de-selected. +/* If the board supports multiple SPI devices types, this enumeration + * identifies which is selected or de-selected. + * There may be more than one instance of each type on a bus, see below. */ -enum spi_dev_e +enum spi_devtype_e { - SPIDEV_NONE = 0, /* Not a valid value */ - SPIDEV_MMCSD, /* Select SPI MMC/SD device */ - SPIDEV_FLASH, /* Select SPI FLASH device */ - SPIDEV_ETHERNET, /* Select SPI Ethernet device */ - SPIDEV_DISPLAY, /* Select SPI LCD/OLED display device */ - SPIDEV_CAMERA, /* Select SPI imaging device */ - SPIDEV_WIRELESS, /* Select SPI Wireless device */ - SPIDEV_TOUCHSCREEN, /* Select SPI touchscreen device */ - SPIDEV_EXPANDER, /* Select SPI I/O expander device */ - SPIDEV_MUX, /* Select SPI multiplexer device */ - SPIDEV_AUDIO_DATA, /* Select SPI audio codec device data port */ - SPIDEV_AUDIO_CTRL, /* Select SPI audio codec device control port */ - SPIDEV_EEPROM, /* Select SPI EEPROM device */ - SPIDEV_ACCELEROMETER, /* Select SPI Accelerometer device */ - SPIDEV_BAROMETER, /* Select SPI Pressure/Barometer device */ - SPIDEV_TEMPERATURE, /* Select SPI Temperature sensor device */ - SPIDEV_IEEE802154, /* Select SPI IEEE 802.15.4 wireless device */ - SPIDEV_CONTACTLESS, /* Select SPI Contactless device */ - SPIDEV_USER /* Board-specific values start here */ + SPIDEVTYPE_NONE = 0, /* Not a valid value */ + SPIDEVTYPE_MMCSD, /* Select SPI MMC/SD device */ + SPIDEVTYPE_FLASH, /* Select SPI FLASH device */ + SPIDEVTYPE_ETHERNET, /* Select SPI Ethernet device */ + SPIDEVTYPE_DISPLAY, /* Select SPI LCD/OLED display device */ + SPIDEVTYPE_CAMERA, /* Select SPI imaging device */ + SPIDEVTYPE_WIRELESS, /* Select SPI Wireless device */ + SPIDEVTYPE_TOUCHSCREEN, /* Select SPI touchscreen device */ + SPIDEVTYPE_EXPANDER, /* Select SPI I/O expander device */ + SPIDEVTYPE_MUX, /* Select SPI multiplexer device */ + SPIDEVTYPE_AUDIO_DATA, /* Select SPI audio codec device data port */ + SPIDEVTYPE_AUDIO_CTRL, /* Select SPI audio codec device control port */ + SPIDEVTYPE_EEPROM, /* Select SPI EEPROM device */ + SPIDEVTYPE_ACCELEROMETER, /* Select SPI Accelerometer device */ + SPIDEVTYPE_BAROMETER, /* Select SPI Pressure/Barometer device */ + SPIDEVTYPE_TEMPERATURE, /* Select SPI Temperature sensor device */ + SPIDEVTYPE_IEEE802154, /* Select SPI IEEE 802.15.4 wireless device */ + SPIDEVTYPE_CONTACTLESS, /* Select SPI Contactless device */ + SPIDEVTYPE_USER /* Board-specific values start here */ }; +/* This builds a SPI devid from its type and index */ + +#define SPIDEV_ID(type,index) (((type)&0xFFFF)<<16 | (index)&0xFFFF) + +/* This retrieves the fields from a SPI devid */ + +#define SPIDEVID_TYPE (devid) (((devid)>>16)&0xFFFF) +#define SPIDEVID_INDEX(devid) ( (devid) &0xFFFF) + +/* These are replacement definitions for the currently used SPI device indexes. + * They are meant as a compatibility measure. it is expected that new drivers + * will use SPIDEV_ID directly. + */ + +#define SPIDEV_NONE SPIDEV_ID(SPIDEVTYPE_NONE , 0) +#define SPIDEV_MMCSD SPIDEV_ID(SPIDEVTYPE_MMCSD , 0) +#define SPIDEV_FLASH SPIDEV_ID(SPIDEVTYPE_FLASH , 0) +#define SPIDEV_ETHERNET SPIDEV_ID(SPIDEVTYPE_ETHERNET , 0) +#define SPIDEV_DISPLAY SPIDEV_ID(SPIDEVTYPE_DISPLAY , 0) +#define SPIDEV_CAMERA SPIDEV_ID(SPIDEVTYPE_CAMERA , 0) +#define SPIDEV_WIRELESS SPIDEV_ID(SPIDEVTYPE_WIRELESS , 0) +#define SPIDEV_TOUCHSCREEN SPIDEV_ID(SPIDEVTYPE_TOUCHSCREEN , 0) +#define SPIDEV_EXPANDER SPIDEV_ID(SPIDEVTYPE_EXPANDER , 0) +#define SPIDEV_MUX SPIDEV_ID(SPIDEVTYPE_MUX , 0) +#define SPIDEV_AUDIO_DATA SPIDEV_ID(SPIDEVTYPE_AUDIO_DATA , 0) +#define SPIDEV_AUDIO_CTRL SPIDEV_ID(SPIDEVTYPE_AUDIO_CTRL , 0) +#define SPIDEV_EEPROM SPIDEV_ID(SPIDEVTYPE_EEPROM , 0) +#define SPIDEV_ACCELEROMETER SPIDEV_ID(SPIDEVTYPE_ACCELEROMETER, 0) +#define SPIDEV_BAROMETER SPIDEV_ID(SPIDEVTYPE_BAROMETER , 0) +#define SPIDEV_TEMPERATURE SPIDEV_ID(SPIDEVTYPE_TEMPERATURE , 0) +#define SPIDEV_IEEE802154 SPIDEV_ID(SPIDEVTYPE_IEEE802154 , 0) +#define SPIDEV_CONTACTLESS SPIDEV_ID(SPIDEVTYPE_CONTACTLESS , 0) +#define SPIDEV_USER SPIDEV_ID(SPIDEVTYPE_USER , 0) + /* Certain SPI devices may required different clocking modes */ enum spi_mode_e @@ -477,7 +512,7 @@ struct spi_dev_s; struct spi_ops_s { CODE int (*lock)(FAR struct spi_dev_s *dev, bool lock); - CODE void (*select)(FAR struct spi_dev_s *dev, enum spi_dev_e devid, + CODE void (*select)(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); CODE uint32_t (*setfrequency)(FAR struct spi_dev_s *dev, uint32_t frequency); #ifdef CONFIG_SPI_CS_DELAY_CONTROL @@ -490,9 +525,9 @@ struct spi_ops_s CODE int (*hwfeatures)(FAR struct spi_dev_s *dev, spi_hwfeatures_t features); #endif - CODE uint8_t (*status)(FAR struct spi_dev_s *dev, enum spi_dev_e devid); + CODE uint8_t (*status)(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA - CODE int (*cmddata)(FAR struct spi_dev_s *dev, enum spi_dev_e devid, + CODE int (*cmddata)(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif CODE uint16_t (*send)(FAR struct spi_dev_s *dev, uint16_t wd); diff --git a/include/nuttx/spi/spi_transfer.h b/include/nuttx/spi/spi_transfer.h index ef31e84265..071f5c1134 100644 --- a/include/nuttx/spi/spi_transfer.h +++ b/include/nuttx/spi/spi_transfer.h @@ -109,7 +109,7 @@ struct spi_sequence_s { /* Properties that are fixed throughout the transfer */ - uint8_t dev; /* See enum spi_dev_e */ + uint32_t dev; /* See enum spi_devtype_e */ uint8_t mode; /* See enum spi_mode_e */ uint8_t nbits; /* Number of bits */ uint8_t ntrans; /* Number of transactions */ -- GitLab From 0138a79028dabbc2b4a794eb61bc38197767bf51 Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Fri, 28 Apr 2017 18:15:42 +0200 Subject: [PATCH 616/990] bitbang --- drivers/spi/spi_bitbang.c | 12 ++++++------ include/nuttx/spi/spi_bitbang.c | 6 +++--- include/nuttx/spi/spi_bitbang.h | 6 +++--- 3 files changed, 12 insertions(+), 12 deletions(-) diff --git a/drivers/spi/spi_bitbang.c b/drivers/spi/spi_bitbang.c index e20a28b212..0e502f6c37 100644 --- a/drivers/spi/spi_bitbang.c +++ b/drivers/spi/spi_bitbang.c @@ -86,7 +86,7 @@ /* SPI methods */ static int spi_lock(FAR struct spi_dev_s *dev, bool lock); -static void spi_select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +static void spi_select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency); @@ -103,9 +103,9 @@ static void spi_sndblock(FAR struct spi_dev_s *dev, static void spi_recvblock(FAR struct spi_dev_s *dev, FAR void *buffer, size_t nwords); #endif -static uint8_t spi_status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +static uint8_t spi_status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -static int spi_cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +static int spi_cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif @@ -206,7 +206,7 @@ static int spi_lock(FAR struct spi_dev_s *dev, bool lock) * ****************************************************************************/ -static void spi_select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +static void spi_select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { FAR struct spi_bitbang_s *priv = (FAR struct spi_bitbang_s *)dev; @@ -481,7 +481,7 @@ static void spi_recvblock(FAR struct spi_dev_s *dev, FAR void *buffer, size_t nw * ****************************************************************************/ -static uint8_t spi_status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +static uint8_t spi_status(FAR struct spi_dev_s *dev, uint32_t devid) { FAR struct spi_bitbang_s *priv = (FAR struct spi_bitbang_s *)dev; DEBUGASSERT(priv && priv->low && priv->low->status); @@ -506,7 +506,7 @@ static uint8_t spi_status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) ****************************************************************************/ #ifdef CONFIG_SPI_CMDDATA -static int spi_cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +static int spi_cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { FAR struct spi_bitbang_s *priv = (FAR struct spi_bitbang_s *)dev; diff --git a/include/nuttx/spi/spi_bitbang.c b/include/nuttx/spi/spi_bitbang.c index 86b340bcdc..ad490b4b67 100644 --- a/include/nuttx/spi/spi_bitbang.c +++ b/include/nuttx/spi/spi_bitbang.c @@ -70,7 +70,7 @@ static void spi_delay(uint32_t holdtime); static void spi_select(FAR struct spi_bitbang_s *priv, - enum spi_dev_e devid, bool selected); + uint32_t devid, bool selected); static uint32_t spi_setfrequency(FAR struct spi_bitbang_s *priv, uint32_t frequency); static void spi_setmode(FAR struct spi_bitbang_s *priv, @@ -90,10 +90,10 @@ static uint16_t spi_bitexchange3(uint16_t dataout, uint32_t holdtime); static uint16_t spi_exchange(FAR struct spi_bitbang_s *priv, uint16_t dataout); static uint8_t spi_status(FAR struct spi_bitbang_s *priv, - enum spi_dev_e devid); + uint32_t devid); #ifdef CONFIG_SPI_CMDDATA static int spi_cmddata(FAR struct spi_bitbang_s *priv, - enum spi_dev_e devid, bool cmd); + uint32_t devid, bool cmd); #endif /**************************************************************************** diff --git a/include/nuttx/spi/spi_bitbang.h b/include/nuttx/spi/spi_bitbang.h index f5058be9d3..9f3a010671 100644 --- a/include/nuttx/spi/spi_bitbang.h +++ b/include/nuttx/spi/spi_bitbang.h @@ -63,7 +63,7 @@ struct spi_bitbang_ops_s { /* Platform specific chip select logic */ - void (*select)(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid, + void (*select)(FAR struct spi_bitbang_s *priv, uint32_t devid, bool selected); /* Platform-specific, SPI frequency function */ @@ -81,12 +81,12 @@ struct spi_bitbang_ops_s /* Platform-specific word exchange function */ - uint8_t (*status)(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid); + uint8_t (*status)(FAR struct spi_bitbang_s *priv, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA /* Platform-specific CMD/DATA function */ - int (*cmddata)(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid, + int (*cmddata)(FAR struct spi_bitbang_s *priv, uint32_t devid, bool cmd); #endif }; -- GitLab From e1df34912d84c86522b6970fd81d84b1c872e955 Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Fri, 28 Apr 2017 18:15:56 +0200 Subject: [PATCH 617/990] Documentation --- Documentation/NuttxPortingGuide.html | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Documentation/NuttxPortingGuide.html b/Documentation/NuttxPortingGuide.html index 0923a1786b..1c3ff2d886 100644 --- a/Documentation/NuttxPortingGuide.html +++ b/Documentation/NuttxPortingGuide.html @@ -5014,11 +5014,11 @@ int kbd_decode(FAR struct lib_instream_s *stream, FAR struct kbd_getstate_s *sta That structure defines a call table with the following methods:

      void lock(FAR struct spi_dev_s *dev);

      -

      void select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected);
      +

      void select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected);
      uint32_t setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency);
      void setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode);
      void setbits(FAR struct spi_dev_s *dev, int nbits);
      - uint8_t status(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
      + uint8_t status(FAR struct spi_dev_s *dev, uint32_t devid);
      uint16_t send(FAR struct spi_dev_s *dev, uint16_t wd);
      void exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer, FAR void *rxbuffer, size_t nwords);

      int registercallback(FAR struct spi_dev_s *dev, mediachange_t callback, void *arg);

      -- GitLab From c56c6f7ccc08cc33153081ea0ff8da761ea968d9 Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Fri, 28 Apr 2017 18:23:29 +0200 Subject: [PATCH 618/990] ARM arch changes --- arch/arm/src/efm32/efm32_spi.c | 18 +++++++------- arch/arm/src/efm32/efm32_spi.h | 20 ++++++++-------- arch/arm/src/imx1/imx_cspi.h | 8 +++---- arch/arm/src/imx6/imx_ecspi.c | 18 +++++++------- arch/arm/src/imx6/imx_ecspi.h | 32 ++++++++++++------------- arch/arm/src/kinetis/kinetis_spi.h | 18 +++++++------- arch/arm/src/kl/kl_spi.h | 14 +++++------ arch/arm/src/lpc11xx/lpc11_spi.h | 6 ++--- arch/arm/src/lpc11xx/lpc11_ssp.h | 12 +++++----- arch/arm/src/lpc17xx/lpc17_spi.h | 8 +++---- arch/arm/src/lpc17xx/lpc17_ssp.h | 12 +++++----- arch/arm/src/lpc2378/lpc23xx_spi.h | 6 ++--- arch/arm/src/lpc31xx/lpc31.h | 8 +++---- arch/arm/src/lpc31xx/lpc31_spi.c | 8 +++---- arch/arm/src/lpc43xx/lpc43_spi.c | 2 +- arch/arm/src/lpc43xx/lpc43_spi.h | 6 ++--- arch/arm/src/lpc43xx/lpc43_ssp.h | 12 +++++----- arch/arm/src/sam34/sam_spi.c | 6 ++--- arch/arm/src/sam34/sam_spi.h | 14 +++++------ arch/arm/src/sama5/sam_spi.c | 6 ++--- arch/arm/src/sama5/sam_spi.h | 14 +++++------ arch/arm/src/samdl/sam_spi.h | 38 +++++++++++++++--------------- arch/arm/src/samv7/sam_spi.c | 6 ++--- arch/arm/src/samv7/sam_spi.h | 14 +++++------ arch/arm/src/stm32/stm32_spi.h | 36 ++++++++++++++-------------- arch/arm/src/stm32f7/stm32_spi.h | 36 ++++++++++++++-------------- arch/arm/src/stm32l4/stm32l4_spi.h | 18 +++++++------- arch/arm/src/tiva/tiva_ssi.h | 8 +++---- arch/arm/src/xmc4/xmc4_spi.h | 18 +++++++------- 29 files changed, 211 insertions(+), 211 deletions(-) diff --git a/arch/arm/src/efm32/efm32_spi.c b/arch/arm/src/efm32/efm32_spi.c index d0ae6d378a..01491669fd 100644 --- a/arch/arm/src/efm32/efm32_spi.c +++ b/arch/arm/src/efm32/efm32_spi.c @@ -109,11 +109,11 @@ struct efm32_spiconfig_s /* SPI-specific methods */ - void (*select)(struct spi_dev_s *dev, enum spi_dev_e devid, + void (*select)(struct spi_dev_s *dev, uint32_t devid, bool selected); - uint8_t (*status)(struct spi_dev_s *dev, enum spi_dev_e devid); + uint8_t (*status)(struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA - int (*cmddata)(struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); + int (*cmddata)(struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif }; @@ -180,7 +180,7 @@ static inline void spi_dmatxstart(FAR struct efm32_spidev_s *priv); /* SPI methods */ static int spi_lock(struct spi_dev_s *dev, bool lock); -static void spi_select(struct spi_dev_s *dev, enum spi_dev_e devid, +static void spi_select(struct spi_dev_s *dev, uint32_t devid, bool selected); static uint32_t spi_setfrequency(struct spi_dev_s *dev, uint32_t frequency); @@ -190,9 +190,9 @@ static void spi_setbits(struct spi_dev_s *dev, int nbits); static int spi_hwfeatures(FAR struct spi_dev_s *dev, spi_hwfeatures_t features); #endif -static uint8_t spi_status(struct spi_dev_s *dev, enum spi_dev_e devid); +static uint8_t spi_status(struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -static int spi_cmddata(struct spi_dev_s *dev, enum spi_dev_e devid, +static int spi_cmddata(struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif static uint16_t spi_send(struct spi_dev_s *dev, uint16_t wd); @@ -781,7 +781,7 @@ static int spi_lock(struct spi_dev_s *dev, bool lock) * ****************************************************************************/ -static void spi_select(struct spi_dev_s *dev, enum spi_dev_e devid, +static void spi_select(struct spi_dev_s *dev, uint32_t devid, bool selected) { struct efm32_spidev_s *priv = (struct efm32_spidev_s *)dev; @@ -1147,7 +1147,7 @@ static int spi_hwfeatures(FAR struct spi_dev_s *dev, spi_hwfeatures_t features) * ****************************************************************************/ -static uint8_t spi_status(struct spi_dev_s *dev, enum spi_dev_e devid) +static uint8_t spi_status(struct spi_dev_s *dev, uint32_t devid) { struct efm32_spidev_s *priv = (struct efm32_spidev_s *)dev; const struct efm32_spiconfig_s *config; @@ -1185,7 +1185,7 @@ static uint8_t spi_status(struct spi_dev_s *dev, enum spi_dev_e devid) ****************************************************************************/ #ifdef CONFIG_SPI_CMDDATA -static int spi_cmddata(struct spi_dev_s *dev, enum spi_dev_e devid, +static int spi_cmddata(struct spi_dev_s *dev, uint32_t devid, bool cmd); { struct efm32_spidev_s *priv = (struct efm32_spidev_s *)dev; diff --git a/arch/arm/src/efm32/efm32_spi.h b/arch/arm/src/efm32/efm32_spi.h index 315eb0615d..1108eec2ac 100644 --- a/arch/arm/src/efm32/efm32_spi.h +++ b/arch/arm/src/efm32/efm32_spi.h @@ -52,7 +52,7 @@ ****************************************************************************/ struct spi_dev_s; /* Forward reference */ -enum spi_dev_e; /* Forward reference */ +uint32_t; /* Forward reference */ /**************************************************************************** * Name: efm32_spibus_initialize @@ -101,26 +101,26 @@ struct spi_dev_s *efm32_spibus_initialize(int port); ****************************************************************************/ #ifdef CONFIG_EFM32_USART0_ISSPI -void efm32_spi0_select(struct spi_dev_s *dev, enum spi_dev_e devid, +void efm32_spi0_select(struct spi_dev_s *dev, uint32_t devid, bool selected); -uint8_t efm32_spi0_status(struct spi_dev_s *dev, enum spi_dev_e devid); -int efm32_spi0_cmddata(struct spi_dev_s *dev, enum spi_dev_e devid, +uint8_t efm32_spi0_status(struct spi_dev_s *dev, uint32_t devid); +int efm32_spi0_cmddata(struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #ifdef CONFIG_EFM32_USART1_ISSPI -void efm32_spi1_select(struct spi_dev_s *dev, enum spi_dev_e devid, +void efm32_spi1_select(struct spi_dev_s *dev, uint32_t devid, bool selected); -uint8_t efm32_spi1_status(struct spi_dev_s *dev, enum spi_dev_e devid); -int efm32_spi1_cmddata(struct spi_dev_s *dev, enum spi_dev_e devid, +uint8_t efm32_spi1_status(struct spi_dev_s *dev, uint32_t devid); +int efm32_spi1_cmddata(struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #ifdef CONFIG_EFM32_USART2_ISSPI -void efm32_spi2_select(struct spi_dev_s *dev, enum spi_dev_e devid, +void efm32_spi2_select(struct spi_dev_s *dev, uint32_t devid, bool selected); -uint8_t efm32_spi2_status(struct spi_dev_s *dev, enum spi_dev_e devid); -int efm32_spi2_cmddata(struct spi_dev_s *dev, enum spi_dev_e devid, +uint8_t efm32_spi2_status(struct spi_dev_s *dev, uint32_t devid); +int efm32_spi2_cmddata(struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif diff --git a/arch/arm/src/imx1/imx_cspi.h b/arch/arm/src/imx1/imx_cspi.h index 842a4ca111..af36d194ba 100644 --- a/arch/arm/src/imx1/imx_cspi.h +++ b/arch/arm/src/imx1/imx_cspi.h @@ -178,7 +178,7 @@ extern "C" ************************************************************************************/ struct spi_dev_s; /* Forward reference */ -enum spi_dev_e; /* Forward reference */ +uint32_t; /* Forward reference */ /**************************************************************************** * Name: imx_spibus_initialize @@ -225,10 +225,10 @@ FAR struct spi_dev_s *imx_spibus_initialize(int port); * ****************************************************************************/ -void imx_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t imx_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +void imx_spiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t imx_spistatus(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int imx_spicmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int imx_spicmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #undef EXTERN diff --git a/arch/arm/src/imx6/imx_ecspi.c b/arch/arm/src/imx6/imx_ecspi.c index 0199419681..2018c410bb 100644 --- a/arch/arm/src/imx6/imx_ecspi.c +++ b/arch/arm/src/imx6/imx_ecspi.c @@ -138,12 +138,12 @@ /* Per SPI callouts to board-specific logic */ typedef CODE void (*imx_select_t)(FAR struct spi_dev_s *dev, - enum spi_dev_e devid, bool selected); + uint32_t devid, bool selected); typedef CODE uint8_t (*imx_status_t)(FAR struct spi_dev_s *dev, - enum spi_dev_e devid); + uint32_t devid); #ifdef CONFIG_SPI_CMDDATA typedef CODE int (*imx_cmddata_t)(FAR struct spi_dev_s *dev, - enum spi_dev_e devid, bool cmd); + uint32_t devid, bool cmd); #endif struct imx_spidev_s @@ -228,16 +228,16 @@ static int spi_interrupt(int irq, void *context, FAR void *arg); /* SPI methods */ static int spi_lock(FAR struct spi_dev_s *dev, bool lock); -static void spi_select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +static void spi_select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency); static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode); static void spi_setbits(FAR struct spi_dev_s *dev, int nbits); static uint16_t spi_send(FAR struct spi_dev_s *dev, uint16_t wd); -static uint8_t spi_status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +static uint8_t spi_status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -static int spi_cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +static int spi_cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #ifdef CONFIG_SPI_EXCHANGE @@ -835,7 +835,7 @@ static int spi_lock(FAR struct spi_dev_s *dev, bool lock) * ****************************************************************************/ -static void spi_select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +static void spi_select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { struct imx_spidev_s *priv = (struct imx_spidev_s *)dev; @@ -1051,7 +1051,7 @@ static uint16_t spi_send(FAR struct spi_dev_s *dev, uint16_t wd) * ****************************************************************************/ -static uint8_t spi_status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +static uint8_t spi_status(FAR struct spi_dev_s *dev, uint32_t devid) { struct imx_spidev_s *priv = (struct imx_spidev_s *)dev; uint8_t ret = 0; @@ -1091,7 +1091,7 @@ static uint8_t spi_status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) ****************************************************************************/ #ifdef CONFIG_SPI_CMDDATA -static int spi_cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +static int spi_cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { struct imx_spidev_s *priv = (struct imx_spidev_s *)dev; diff --git a/arch/arm/src/imx6/imx_ecspi.h b/arch/arm/src/imx6/imx_ecspi.h index 40ca57c465..8807c23145 100644 --- a/arch/arm/src/imx6/imx_ecspi.h +++ b/arch/arm/src/imx6/imx_ecspi.h @@ -70,7 +70,7 @@ extern "C" ************************************************************************************/ struct spi_dev_s; /* Forward reference */ -enum spi_dev_e; /* Forward reference */ +uint32_t; /* Forward reference */ /************************************************************************************ * Name: imx_spibus_initialize @@ -118,42 +118,42 @@ FAR struct spi_dev_s *imx_spibus_initialize(int port); ************************************************************************************/ #ifdef CONFIG_IMX6_ECSPI1 -void imx_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t imx_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +void imx_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t imx_spi1status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int imx_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int imx_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif #ifdef CONFIG_IMX6_ECSPI2 -void imx_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t imx_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +void imx_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t imx_spi2status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int imx_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int imx_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif #ifdef CONFIG_IMX6_ECSPI3 -void imx_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t imx_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +void imx_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t imx_spi3status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int imx_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int imx_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif #ifdef CONFIG_IMX6_ECSPI4 -void imx_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t imx_spi4status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +void imx_spi4select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t imx_spi4status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int imx_spi4cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int imx_spi4cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif #ifdef CONFIG_IMX6_ECSPI5 -void imx_spi5select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t imx_spi5status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +void imx_spi5select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t imx_spi5status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int imx_spi5cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int imx_spi5cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif diff --git a/arch/arm/src/kinetis/kinetis_spi.h b/arch/arm/src/kinetis/kinetis_spi.h index 19ce126d10..bbc097199f 100644 --- a/arch/arm/src/kinetis/kinetis_spi.h +++ b/arch/arm/src/kinetis/kinetis_spi.h @@ -115,24 +115,24 @@ FAR struct spi_dev_s *kinetis_spibus_initialize(int bus); ************************************************************************************/ #ifdef CONFIG_KINETIS_SPI0 -void kinetis_spi0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t kinetis_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +void kinetis_spi0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t kinetis_spi0status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int kinetis_spi0cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int kinetis_spi0cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif #ifdef CONFIG_KINETIS_SPI1 -void kinetis_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t kinetis_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +void kinetis_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t kinetis_spi1status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int kinetis_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int kinetis_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif #ifdef CONFIG_KINETIS_SPI2 -void kinetis_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t kinetis_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +void kinetis_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t kinetis_spi2status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int kinetis_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int kinetis_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif diff --git a/arch/arm/src/kl/kl_spi.h b/arch/arm/src/kl/kl_spi.h index 227ab9e6c5..d2f4824b73 100644 --- a/arch/arm/src/kl/kl_spi.h +++ b/arch/arm/src/kl/kl_spi.h @@ -64,7 +64,7 @@ extern "C" ************************************************************************************/ struct spi_dev_s; /* Forward reference */ -enum spi_dev_e; /* Forward reference */ +uint32_t; /* Forward reference */ /**************************************************************************** * Name: kl_spibus_initialize @@ -111,18 +111,18 @@ FAR struct spi_dev_s *kl_spibus_initialize(int port); ************************************************************************************/ #ifdef CONFIG_KL_SPI0 -void kl_spi0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t kl_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +void kl_spi0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t kl_spi0status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int kl_spi0cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int kl_spi0cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif #ifdef CONFIG_KL_SPI1 -void kl_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t kl_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +void kl_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t kl_spi1status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int kl_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int kl_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif diff --git a/arch/arm/src/lpc11xx/lpc11_spi.h b/arch/arm/src/lpc11xx/lpc11_spi.h index dc8edfa904..1a6786d218 100644 --- a/arch/arm/src/lpc11xx/lpc11_spi.h +++ b/arch/arm/src/lpc11xx/lpc11_spi.h @@ -112,10 +112,10 @@ FAR struct spi_dev_s *lpc11_spibus_initialize(int port); * ************************************************************************************/ -void lpc11_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t lpc11_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +void lpc11_spiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t lpc11_spistatus(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int lpc11_spicmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int lpc11_spicmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif /************************************************************************************ diff --git a/arch/arm/src/lpc11xx/lpc11_ssp.h b/arch/arm/src/lpc11xx/lpc11_ssp.h index 9910650a30..f117b1cf03 100644 --- a/arch/arm/src/lpc11xx/lpc11_ssp.h +++ b/arch/arm/src/lpc11xx/lpc11_ssp.h @@ -113,18 +113,18 @@ FAR struct spi_dev_s *lpc11_sspbus_initialize(int port); ************************************************************************************/ #ifdef CONFIG_LPC11_SSP0 -void lpc11_ssp0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t lpc11_ssp0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +void lpc11_ssp0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t lpc11_ssp0status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int lpc11_ssp0cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int lpc11_ssp0cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif #ifdef CONFIG_LPC11_SSP1 -void lpc11_ssp1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t lpc11_ssp1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +void lpc11_ssp1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t lpc11_ssp1status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int lpc11_ssp1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int lpc11_ssp1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif diff --git a/arch/arm/src/lpc17xx/lpc17_spi.h b/arch/arm/src/lpc17xx/lpc17_spi.h index c2eeea58f9..1934eb582f 100644 --- a/arch/arm/src/lpc17xx/lpc17_spi.h +++ b/arch/arm/src/lpc17xx/lpc17_spi.h @@ -71,7 +71,7 @@ extern "C" ************************************************************************************/ struct spi_dev_s; /* Forward reference */ -enum spi_dev_e; /* Forward reference */ +uint32_t; /* Forward reference */ /************************************************************************************ * Name: lpc17_spibus_initialize @@ -115,10 +115,10 @@ FAR struct spi_dev_s *lpc17_spibus_initialize(int port); * ************************************************************************************/ -void lpc17_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t lpc17_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +void lpc17_spiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t lpc17_spistatus(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int lpc17_spicmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int lpc17_spicmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif /**************************************************************************** diff --git a/arch/arm/src/lpc17xx/lpc17_ssp.h b/arch/arm/src/lpc17xx/lpc17_ssp.h index 6ea6375b13..c679206ca1 100644 --- a/arch/arm/src/lpc17xx/lpc17_ssp.h +++ b/arch/arm/src/lpc17xx/lpc17_ssp.h @@ -113,18 +113,18 @@ FAR struct spi_dev_s *lpc17_sspbus_initialize(int port); ************************************************************************************/ #ifdef CONFIG_LPC17_SSP0 -void lpc17_ssp0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t lpc17_ssp0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +void lpc17_ssp0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t lpc17_ssp0status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int lpc17_ssp0cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int lpc17_ssp0cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif #ifdef CONFIG_LPC17_SSP1 -void lpc17_ssp1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t lpc17_ssp1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +void lpc17_ssp1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t lpc17_ssp1status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int lpc17_ssp1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int lpc17_ssp1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif diff --git a/arch/arm/src/lpc2378/lpc23xx_spi.h b/arch/arm/src/lpc2378/lpc23xx_spi.h index f701c9e1f9..08ffcfbbbf 100644 --- a/arch/arm/src/lpc2378/lpc23xx_spi.h +++ b/arch/arm/src/lpc2378/lpc23xx_spi.h @@ -154,7 +154,7 @@ ************************************************************************************/ struct spi_dev_s; /* Forward reference */ -enum spi_dev_e; /* Forward reference */ +uint32_t; /* Forward reference */ /**************************************************************************** * Name: lpc23_spibus_initialize @@ -178,7 +178,7 @@ FAR struct spi_dev_s *lpc23_spibus_initialize(int port); * ****************************************************************************/ -void lpc23xx_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t lpc23xx_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +void lpc23xx_spiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t lpc23xx_spistatus(FAR struct spi_dev_s *dev, uint32_t devid); #endif /* __ARCH_ARM_SRC_LPC2378_LPC23XX_SPI_H */ diff --git a/arch/arm/src/lpc31xx/lpc31.h b/arch/arm/src/lpc31xx/lpc31.h index 4a342a9a83..de9294928a 100644 --- a/arch/arm/src/lpc31xx/lpc31.h +++ b/arch/arm/src/lpc31xx/lpc31.h @@ -185,7 +185,7 @@ void lpc31_clockconfig(void); ************************************************************************************/ struct spi_dev_s; /* Forward reference */ -enum spi_dev_e; /* Forward reference */ +uint32_t; /* Forward reference */ FAR struct spi_dev_s *lpc31_spibus_initialize(int port); @@ -218,10 +218,10 @@ FAR struct spi_dev_s *lpc31_spibus_initialize(int port); * ************************************************************************************/ -void lpc31_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t lpc31_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +void lpc31_spiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t lpc31_spistatus(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int lpc31_spicmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int lpc31_spicmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif /************************************************************************************ diff --git a/arch/arm/src/lpc31xx/lpc31_spi.c b/arch/arm/src/lpc31xx/lpc31_spi.c index ca2544bc26..9f64e5d772 100644 --- a/arch/arm/src/lpc31xx/lpc31_spi.c +++ b/arch/arm/src/lpc31xx/lpc31_spi.c @@ -115,11 +115,11 @@ static inline uint16_t spi_readword(FAR struct lpc31_spidev_s *priv); static inline void spi_writeword(FAR struct lpc31_spidev_s *priv, uint16_t word); static int spi_lock(FAR struct spi_dev_s *dev, bool lock); -static void spi_select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); +static void spi_select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency); static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode); static void spi_setbits(FAR struct spi_dev_s *dev, int nbits); -static uint8_t spi_status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +static uint8_t spi_status(FAR struct spi_dev_s *dev, uint32_t devid); static uint16_t spi_send(FAR struct spi_dev_s *dev, uint16_t word); static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer, FAR void *rxbuffer, size_t nwords); @@ -482,7 +482,7 @@ static int spi_lock(FAR struct spi_dev_s *dev, bool lock) * ****************************************************************************/ -static void spi_select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +static void spi_select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { struct lpc31_spidev_s *priv = (struct lpc31_spidev_s *) dev; uint8_t slave = 0; @@ -689,7 +689,7 @@ static void spi_setbits(FAR struct spi_dev_s *dev, int nbits) * ****************************************************************************/ -static uint8_t spi_status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +static uint8_t spi_status(FAR struct spi_dev_s *dev, uint32_t devid) { /* FIXME: is there anyway to determine this * it should probably be board dependant anyway */ diff --git a/arch/arm/src/lpc43xx/lpc43_spi.c b/arch/arm/src/lpc43xx/lpc43_spi.c index e30b39bf25..43e7e08052 100644 --- a/arch/arm/src/lpc43xx/lpc43_spi.c +++ b/arch/arm/src/lpc43xx/lpc43_spi.c @@ -103,7 +103,7 @@ struct lpc43_spidev_s /* SPI methods */ static int spi_lock(FAR struct spi_dev_s *dev, bool lock); -static void spi_select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); +static void spi_select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency); static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode); static void spi_setbits(FAR struct spi_dev_s *dev, int nbits); diff --git a/arch/arm/src/lpc43xx/lpc43_spi.h b/arch/arm/src/lpc43xx/lpc43_spi.h index 42ade41b1a..d0414f9af6 100644 --- a/arch/arm/src/lpc43xx/lpc43_spi.h +++ b/arch/arm/src/lpc43xx/lpc43_spi.h @@ -122,11 +122,11 @@ FAR struct spi_dev_s *lpc43_spibus_initialize(int port); * ************************************************************************************/ -void lpc43_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t lpc43_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +void lpc43_spiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t lpc43_spistatus(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int lpc43_spicmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int lpc43_spicmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif /************************************************************************************ diff --git a/arch/arm/src/lpc43xx/lpc43_ssp.h b/arch/arm/src/lpc43xx/lpc43_ssp.h index 1c98618cbf..5bf708859e 100644 --- a/arch/arm/src/lpc43xx/lpc43_ssp.h +++ b/arch/arm/src/lpc43xx/lpc43_ssp.h @@ -121,18 +121,18 @@ FAR struct spi_dev_s *lpc43_sspbus_initialize(int port); ************************************************************************************/ #ifdef CONFIG_LPC43_SSP0 -void lpc43_ssp0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t lpc43_ssp0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +void lpc43_ssp0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t lpc43_ssp0status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int lpc43_ssp0cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int lpc43_ssp0cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif #ifdef CONFIG_LPC43_SSP1 -void lpc43_ssp1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t lpc43_ssp1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +void lpc43_ssp1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t lpc43_ssp1status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int lpc43_ssp1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int lpc43_ssp1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif diff --git a/arch/arm/src/sam34/sam_spi.c b/arch/arm/src/sam34/sam_spi.c index 2cbe3614b6..899eb9bc2e 100644 --- a/arch/arm/src/sam34/sam_spi.c +++ b/arch/arm/src/sam34/sam_spi.c @@ -190,7 +190,7 @@ struct sam_spics_s /* Type of board-specific SPI status function */ -typedef void (*select_t)(enum spi_dev_e devid, bool selected); +typedef void (*select_t)(uint32_t devid, bool selected); /* Chip select register offsetrs */ @@ -272,7 +272,7 @@ static inline uintptr_t spi_regaddr(struct sam_spics_s *spics, /* SPI methods */ static int spi_lock(struct spi_dev_s *dev, bool lock); -static void spi_select(struct spi_dev_s *dev, enum spi_dev_e devid, +static void spi_select(struct spi_dev_s *dev, uint32_t devid, bool selected); static uint32_t spi_setfrequency(struct spi_dev_s *dev, uint32_t frequency); static void spi_setmode(struct spi_dev_s *dev, enum spi_mode_e mode); @@ -916,7 +916,7 @@ static int spi_lock(struct spi_dev_s *dev, bool lock) * ****************************************************************************/ -static void spi_select(struct spi_dev_s *dev, enum spi_dev_e devid, +static void spi_select(struct spi_dev_s *dev, uint32_t devid, bool selected) { struct sam_spics_s *spics = (struct sam_spics_s *)dev; diff --git a/arch/arm/src/sam34/sam_spi.h b/arch/arm/src/sam34/sam_spi.h index 1d37d340d4..f3bebd11f1 100644 --- a/arch/arm/src/sam34/sam_spi.h +++ b/arch/arm/src/sam34/sam_spi.h @@ -110,7 +110,7 @@ extern "C" ****************************************************************************/ struct spi_dev_s; /* Forward reference */ -enum spi_dev_e; /* Forward reference */ +uint32_t; /* Forward reference */ /**************************************************************************** * Name: sam_spibus_initialize @@ -189,10 +189,10 @@ struct spi_dev_s *sam_spibus_initialize(int port); ****************************************************************************/ #ifdef CONFIG_SAM34_SPI0 -void sam_spi0select(enum spi_dev_e devid, bool selected); +void sam_spi0select(uint32_t devid, bool selected); #endif #ifdef CONFIG_SAM34_SPI1 -void sam_spi1select(enum spi_dev_e devid, bool selected); +void sam_spi1select(uint32_t devid, bool selected); #endif /**************************************************************************** @@ -211,10 +211,10 @@ void sam_spi1select(enum spi_dev_e devid, bool selected); ****************************************************************************/ #ifdef CONFIG_SAM34_SPI0 -uint8_t sam_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +uint8_t sam_spi0status(FAR struct spi_dev_s *dev, uint32_t devid); #endif #ifdef CONFIG_SAM34_SPI1 -uint8_t sam_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +uint8_t sam_spi1status(FAR struct spi_dev_s *dev, uint32_t devid); #endif /**************************************************************************** @@ -243,10 +243,10 @@ uint8_t sam_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); #ifdef CONFIG_SPI_CMDDATA #ifdef CONFIG_SAM34_SPI0 -int sam_spi0cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int sam_spi0cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #ifdef CONFIG_SAM34_SPI1 -int sam_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int sam_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif diff --git a/arch/arm/src/sama5/sam_spi.c b/arch/arm/src/sama5/sam_spi.c index 459e949cad..cda2a36f97 100644 --- a/arch/arm/src/sama5/sam_spi.c +++ b/arch/arm/src/sama5/sam_spi.c @@ -182,7 +182,7 @@ struct sam_spics_s /* Type of board-specific SPI status fuction */ -typedef void (*select_t)(enum spi_dev_e devid, bool selected); +typedef void (*select_t)(uint32_t devid, bool selected); /* Chip select register offsetrs */ @@ -263,7 +263,7 @@ static inline uintptr_t spi_physregaddr(struct sam_spics_s *spics, /* SPI methods */ static int spi_lock(struct spi_dev_s *dev, bool lock); -static void spi_select(struct spi_dev_s *dev, enum spi_dev_e devid, +static void spi_select(struct spi_dev_s *dev, uint32_t devid, bool selected); static uint32_t spi_setfrequency(struct spi_dev_s *dev, uint32_t frequency); static void spi_setmode(struct spi_dev_s *dev, enum spi_mode_e mode); @@ -905,7 +905,7 @@ static int spi_lock(struct spi_dev_s *dev, bool lock) * ****************************************************************************/ -static void spi_select(struct spi_dev_s *dev, enum spi_dev_e devid, +static void spi_select(struct spi_dev_s *dev, uint32_t devid, bool selected) { struct sam_spics_s *spics = (struct sam_spics_s *)dev; diff --git a/arch/arm/src/sama5/sam_spi.h b/arch/arm/src/sama5/sam_spi.h index cf98863937..ad73fdf78b 100644 --- a/arch/arm/src/sama5/sam_spi.h +++ b/arch/arm/src/sama5/sam_spi.h @@ -104,7 +104,7 @@ extern "C" ****************************************************************************/ struct spi_dev_s; /* Forward reference */ -enum spi_dev_e; /* Forward reference */ +uint32_t; /* Forward reference */ /**************************************************************************** * Name: sam_spibus_initialize @@ -182,10 +182,10 @@ struct spi_dev_s *sam_spibus_initialize(int port); ****************************************************************************/ #ifdef CONFIG_SAMA5_SPI0 -void sam_spi0select(enum spi_dev_e devid, bool selected); +void sam_spi0select(uint32_t devid, bool selected); #endif #ifdef CONFIG_SAMA5_SPI1 -void sam_spi1select(enum spi_dev_e devid, bool selected); +void sam_spi1select(uint32_t devid, bool selected); #endif /**************************************************************************** @@ -204,10 +204,10 @@ void sam_spi1select(enum spi_dev_e devid, bool selected); ****************************************************************************/ #ifdef CONFIG_SAMA5_SPI0 -uint8_t sam_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +uint8_t sam_spi0status(FAR struct spi_dev_s *dev, uint32_t devid); #endif #ifdef CONFIG_SAMA5_SPI1 -uint8_t sam_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +uint8_t sam_spi1status(FAR struct spi_dev_s *dev, uint32_t devid); #endif /**************************************************************************** @@ -236,10 +236,10 @@ uint8_t sam_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); #ifdef CONFIG_SPI_CMDDATA #ifdef CONFIG_SAMA5_SPI0 -int sam_spi0cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int sam_spi0cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #ifdef CONFIG_SAMA5_SPI1 -int sam_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int sam_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif diff --git a/arch/arm/src/samdl/sam_spi.h b/arch/arm/src/samdl/sam_spi.h index 6185a5b3f0..4bfff626a2 100644 --- a/arch/arm/src/samdl/sam_spi.h +++ b/arch/arm/src/samdl/sam_spi.h @@ -87,7 +87,7 @@ extern "C" ****************************************************************************/ struct spi_dev_s; /* Forward reference */ -enum spi_dev_e; /* Forward reference */ +uint32_t; /* Forward reference */ /**************************************************************************** * Name: sam_spibus_initialize @@ -168,32 +168,32 @@ struct spi_dev_s *sam_spibus_initialize(int port); ****************************************************************************/ #ifdef SAMDL_HAVE_SPI0 -void sam_spi0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void sam_spi0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); #endif #ifdef SAMDL_HAVE_SPI1 -void sam_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void sam_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); #endif #ifdef SAMDL_HAVE_SPI2 -void sam_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void sam_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); #endif #ifdef SAMDL_HAVE_SPI3 -void sam_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void sam_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); #endif #ifdef SAMDL_HAVE_SPI4 -void sam_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void sam_spi4select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); #endif #ifdef SAMDL_HAVE_SPI5 -void sam_spi5select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void sam_spi5select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); #endif @@ -213,27 +213,27 @@ void sam_spi5select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, ****************************************************************************/ #ifdef SAMDL_HAVE_SPI0 -uint8_t sam_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +uint8_t sam_spi0status(FAR struct spi_dev_s *dev, uint32_t devid); #endif #ifdef SAMDL_HAVE_SPI1 -uint8_t sam_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +uint8_t sam_spi1status(FAR struct spi_dev_s *dev, uint32_t devid); #endif #ifdef SAMDL_HAVE_SPI2 -uint8_t sam_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +uint8_t sam_spi2status(FAR struct spi_dev_s *dev, uint32_t devid); #endif #ifdef SAMDL_HAVE_SPI3 -uint8_t sam_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +uint8_t sam_spi3status(FAR struct spi_dev_s *dev, uint32_t devid); #endif #ifdef SAMDL_HAVE_SPI4 -uint8_t sam_spi4status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +uint8_t sam_spi4status(FAR struct spi_dev_s *dev, uint32_t devid); #endif #ifdef SAMDL_HAVE_SPI5 -uint8_t sam_spi5status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +uint8_t sam_spi5status(FAR struct spi_dev_s *dev, uint32_t devid); #endif /**************************************************************************** @@ -262,27 +262,27 @@ uint8_t sam_spi5status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); #ifdef CONFIG_SPI_CMDDATA #ifdef SAMDL_HAVE_SPI0 -int sam_spi0cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int sam_spi0cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #ifdef SAMDL_HAVE_SPI1 -int sam_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int sam_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #ifdef SAMDL_HAVE_SPI2 -int sam_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int sam_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #ifdef SAMDL_HAVE_SPI3 -int sam_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int sam_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #ifdef SAMDL_HAVE_SPI4 -int sam_spi4cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int sam_spi4cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #ifdef SAMDL_HAVE_SPI5 -int sam_spi5cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int sam_spi5cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif diff --git a/arch/arm/src/samv7/sam_spi.c b/arch/arm/src/samv7/sam_spi.c index de1dec1615..a1df892188 100644 --- a/arch/arm/src/samv7/sam_spi.c +++ b/arch/arm/src/samv7/sam_spi.c @@ -181,7 +181,7 @@ struct sam_spics_s /* Type of board-specific SPI status function */ -typedef void (*select_t)(enum spi_dev_e devid, bool selected); +typedef void (*select_t)(uint32_t devid, bool selected); /* Chip select register offsets */ @@ -263,7 +263,7 @@ static inline uintptr_t spi_regaddr(struct sam_spics_s *spics, /* SPI master methods */ static int spi_lock(struct spi_dev_s *dev, bool lock); -static void spi_select(struct spi_dev_s *dev, enum spi_dev_e devid, +static void spi_select(struct spi_dev_s *dev, uint32_t devid, bool selected); static uint32_t spi_setfrequency(struct spi_dev_s *dev, uint32_t frequency); #ifdef CONFIG_SPI_CS_DELAY_CONTROL @@ -943,7 +943,7 @@ static int spi_lock(struct spi_dev_s *dev, bool lock) * ****************************************************************************/ -static void spi_select(struct spi_dev_s *dev, enum spi_dev_e devid, +static void spi_select(struct spi_dev_s *dev, uint32_t devid, bool selected) { struct sam_spics_s *spics = (struct sam_spics_s *)dev; diff --git a/arch/arm/src/samv7/sam_spi.h b/arch/arm/src/samv7/sam_spi.h index dded642534..fc24b289f1 100644 --- a/arch/arm/src/samv7/sam_spi.h +++ b/arch/arm/src/samv7/sam_spi.h @@ -158,7 +158,7 @@ extern "C" ****************************************************************************/ struct spi_dev_s; /* Forward reference */ -enum spi_dev_e; /* Forward reference */ +uint32_t; /* Forward reference */ struct spi_sctrlr_s; /* Forward reference */ /**************************************************************************** @@ -255,10 +255,10 @@ FAR struct spi_sctrlr_s *sam_spi_slave_initialize(int port); ****************************************************************************/ #ifdef CONFIG_SAMV7_SPI0_MASTER -void sam_spi0select(enum spi_dev_e devid, bool selected); +void sam_spi0select(uint32_t devid, bool selected); #endif #ifdef CONFIG_SAMV7_SPI1_MASTER -void sam_spi1select(enum spi_dev_e devid, bool selected); +void sam_spi1select(uint32_t devid, bool selected); #endif /**************************************************************************** @@ -277,10 +277,10 @@ void sam_spi1select(enum spi_dev_e devid, bool selected); ****************************************************************************/ #ifdef CONFIG_SAMV7_SPI0 -uint8_t sam_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +uint8_t sam_spi0status(FAR struct spi_dev_s *dev, uint32_t devid); #endif #ifdef CONFIG_SAMV7_SPI1 -uint8_t sam_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +uint8_t sam_spi1status(FAR struct spi_dev_s *dev, uint32_t devid); #endif /**************************************************************************** @@ -309,10 +309,10 @@ uint8_t sam_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); #ifdef CONFIG_SPI_CMDDATA #ifdef CONFIG_SAMV7_SPI0_MASTER -int sam_spi0cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int sam_spi0cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #ifdef CONFIG_SAMV7_SPI1_MASTER -int sam_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int sam_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif /* CONFIG_SPI_CMDDATA */ diff --git a/arch/arm/src/stm32/stm32_spi.h b/arch/arm/src/stm32/stm32_spi.h index a9d336cb86..e874441809 100644 --- a/arch/arm/src/stm32/stm32_spi.h +++ b/arch/arm/src/stm32/stm32_spi.h @@ -117,39 +117,39 @@ FAR struct spi_dev_s *stm32_spibus_initialize(int bus); ************************************************************************************/ #ifdef CONFIG_STM32_SPI1 -void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); -int stm32_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid); +int stm32_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #ifdef CONFIG_STM32_SPI2 -void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); -int stm32_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid); +int stm32_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #ifdef CONFIG_STM32_SPI3 -void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); -int stm32_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid); +int stm32_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #ifdef CONFIG_STM32_SPI4 -void stm32_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); -int stm32_spi4cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +void stm32_spi4select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, uint32_t devid); +int stm32_spi4cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #ifdef CONFIG_STM32_SPI5 -void stm32_spi5select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t stm32_spi5status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); -int stm32_spi5cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +void stm32_spi5select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t stm32_spi5status(FAR struct spi_dev_s *dev, uint32_t devid); +int stm32_spi5cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #ifdef CONFIG_STM32_SPI6 -void stm32_spi6select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t stm32_spi6status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); -int stm32_spi6cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +void stm32_spi6select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t stm32_spi6status(FAR struct spi_dev_s *dev, uint32_t devid); +int stm32_spi6cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif /************************************************************************************ diff --git a/arch/arm/src/stm32f7/stm32_spi.h b/arch/arm/src/stm32f7/stm32_spi.h index 2a2aa91881..475459a9a1 100644 --- a/arch/arm/src/stm32f7/stm32_spi.h +++ b/arch/arm/src/stm32f7/stm32_spi.h @@ -112,39 +112,39 @@ FAR struct spi_dev_s *stm32_spibus_initialize(int bus); ************************************************************************************/ #ifdef CONFIG_STM32F7_SPI1 -void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); -int stm32_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid); +int stm32_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #ifdef CONFIG_STM32F7_SPI2 -void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); -int stm32_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid); +int stm32_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #ifdef CONFIG_STM32F7_SPI3 -void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); -int stm32_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid); +int stm32_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #ifdef CONFIG_STM32F7_SPI4 -void stm32_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); -int stm32_spi4cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +void stm32_spi4select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, uint32_t devid); +int stm32_spi4cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #ifdef CONFIG_STM32F7_SPI5 -void stm32_spi5select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t stm32_spi5status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); -int stm32_spi5cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +void stm32_spi5select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t stm32_spi5status(FAR struct spi_dev_s *dev, uint32_t devid); +int stm32_spi5cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #ifdef CONFIG_STM32F7_SPI6 -void stm32_spi6select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t stm32_spi6status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); -int stm32_spi6cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +void stm32_spi6select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t stm32_spi6status(FAR struct spi_dev_s *dev, uint32_t devid); +int stm32_spi6cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif /************************************************************************************ diff --git a/arch/arm/src/stm32l4/stm32l4_spi.h b/arch/arm/src/stm32l4/stm32l4_spi.h index 242a81f184..77ba1a3f1b 100644 --- a/arch/arm/src/stm32l4/stm32l4_spi.h +++ b/arch/arm/src/stm32l4/stm32l4_spi.h @@ -117,21 +117,21 @@ FAR struct spi_dev_s *stm32l4_spibus_initialize(int bus); ************************************************************************************/ #ifdef CONFIG_STM32L4_SPI1 -void stm32l4_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t stm32l4_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); -int stm32l4_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +void stm32l4_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t stm32l4_spi1status(FAR struct spi_dev_s *dev, uint32_t devid); +int stm32l4_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #ifdef CONFIG_STM32L4_SPI2 -void stm32l4_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t stm32l4_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); -int stm32l4_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +void stm32l4_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t stm32l4_spi2status(FAR struct spi_dev_s *dev, uint32_t devid); +int stm32l4_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #ifdef CONFIG_STM32L4_SPI3 -void stm32l4_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t stm32l4_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); -int stm32l4_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +void stm32l4_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t stm32l4_spi3status(FAR struct spi_dev_s *dev, uint32_t devid); +int stm32l4_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif /************************************************************************************ diff --git a/arch/arm/src/tiva/tiva_ssi.h b/arch/arm/src/tiva/tiva_ssi.h index 6ef306cefc..54d2004702 100644 --- a/arch/arm/src/tiva/tiva_ssi.h +++ b/arch/arm/src/tiva/tiva_ssi.h @@ -108,11 +108,11 @@ FAR struct spi_dev_s *tiva_ssibus_initialize(int port); ****************************************************************************/ struct spi_dev_s; -enum spi_dev_e; -void tiva_ssiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t tiva_ssistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +uint32_t; +void tiva_ssiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t tiva_ssistatus(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int tiva_ssicmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int tiva_ssicmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #if defined(__cplusplus) diff --git a/arch/arm/src/xmc4/xmc4_spi.h b/arch/arm/src/xmc4/xmc4_spi.h index 0ac514c5ce..f95257a320 100644 --- a/arch/arm/src/xmc4/xmc4_spi.h +++ b/arch/arm/src/xmc4/xmc4_spi.h @@ -115,24 +115,24 @@ FAR struct spi_dev_s *xmc4_spibus_initialize(int bus); ************************************************************************************/ #ifdef CONFIG_XMC4_SPI0 -void xmc4_spi0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t xmc4_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +void xmc4_spi0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t xmc4_spi0status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int xmc4_spi0cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int xmc4_spi0cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif #ifdef CONFIG_XMC4_SPI1 -void xmc4_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t xmc4_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +void xmc4_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t xmc4_spi1status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int xmc4_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int xmc4_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif #ifdef CONFIG_XMC4_SPI2 -void xmc4_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t xmc4_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +void xmc4_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t xmc4_spi2status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int xmc4_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int xmc4_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif -- GitLab From c70d7972293c74aa4f8b816765a2a1f8b6dfe1eb Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Fri, 28 Apr 2017 18:24:06 +0200 Subject: [PATCH 619/990] misc archs --- arch/avr/src/avr/avr.h | 8 +++--- arch/hc/src/m9s12/m9s12.h | 6 ++--- arch/mips/src/pic32mx/pic32mx.h | 26 ++++++++++---------- arch/mips/src/pic32mz/pic32mz-spi.h | 38 ++++++++++++++--------------- arch/sim/src/up_spiflash.c | 12 ++++----- arch/x86/src/qemu/qemu.h | 10 ++++---- arch/z16/src/z16f/chip.h | 8 +++--- arch/z80/src/ez80/ez80f91_spi.h | 6 ++--- 8 files changed, 57 insertions(+), 57 deletions(-) diff --git a/arch/avr/src/avr/avr.h b/arch/avr/src/avr/avr.h index b1b37befe6..a06de4c024 100644 --- a/arch/avr/src/avr/avr.h +++ b/arch/avr/src/avr/avr.h @@ -151,7 +151,7 @@ uint8_t *up_doirq(uint8_t irq, uint8_t *regs); ****************************************************************************/ struct spi_dev_s; /* Forward references */ -enum spi_dev_e; /* Forward references */ +uint32_t; /* Forward references */ FAR struct spi_dev_s *avr_spibus_initialize(int port); @@ -183,10 +183,10 @@ FAR struct spi_dev_s *avr_spibus_initialize(int port); ************************************************************************************/ #ifdef CONFIG_AVR_SPI -void avr_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t avr_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +void avr_spiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t avr_spistatus(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int avr_spicmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int avr_spicmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif diff --git a/arch/hc/src/m9s12/m9s12.h b/arch/hc/src/m9s12/m9s12.h index 50e3a14abe..921c4efa96 100644 --- a/arch/hc/src/m9s12/m9s12.h +++ b/arch/hc/src/m9s12/m9s12.h @@ -338,7 +338,7 @@ int hcs12_ethinitialize(int intf); ****************************************************************************/ struct spi_dev_s; /* Forward reference */ -enum spi_dev_e; /* Forward reference */ +uint32_t; /* Forward reference */ FAR struct spi_dev_s *hcs12_spibus_initialize(int port); @@ -367,8 +367,8 @@ FAR struct spi_dev_s *hcs12_spibus_initialize(int port); * ************************************************************************************/ -void hcs12_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t hcs12_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +void hcs12_spiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t hcs12_spistatus(FAR struct spi_dev_s *dev, uint32_t devid); #undef EXTERN #if defined(__cplusplus) diff --git a/arch/mips/src/pic32mx/pic32mx.h b/arch/mips/src/pic32mx/pic32mx.h index a2de82ed5a..cd2272597a 100644 --- a/arch/mips/src/pic32mx/pic32mx.h +++ b/arch/mips/src/pic32mx/pic32mx.h @@ -400,7 +400,7 @@ void pic32mx_dumpgpio(uint32_t pinset, const char *msg); ****************************************************************************/ struct spi_dev_s; /* Forward reference */ -enum spi_dev_e; /* Forward reference */ +uint32_t; /* Forward reference */ FAR struct spi_dev_s *pic32mx_spibus_initialize(int port); @@ -433,38 +433,38 @@ FAR struct spi_dev_s *pic32mx_spibus_initialize(int port); ************************************************************************************/ #ifdef CONFIG_PIC32MX_SPI1 -void pic32mx_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void pic32mx_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); -uint8_t pic32mx_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +uint8_t pic32mx_spi1status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int pic32mx_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int pic32mx_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif #ifdef CONFIG_PIC32MX_SPI2 -void pic32mx_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void pic32mx_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); -uint8_t pic32mx_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +uint8_t pic32mx_spi2status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int pic32mx_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int pic32mx_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif #ifdef CONFIG_PIC32MX_SPI3 -void pic32mx_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void pic32mx_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); -uint8_t pic32mx_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +uint8_t pic32mx_spi3status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int pic32mx_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int pic32mx_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif #ifdef CONFIG_PIC32MX_SPI3 -void pic32mx_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void pic32mx_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); -uint8_t pic32mx_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +uint8_t pic32mx_spi3status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int pic32mx_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int pic32mx_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif diff --git a/arch/mips/src/pic32mz/pic32mz-spi.h b/arch/mips/src/pic32mz/pic32mz-spi.h index f908f63b7c..1cbc8e4be3 100644 --- a/arch/mips/src/pic32mz/pic32mz-spi.h +++ b/arch/mips/src/pic32mz/pic32mz-spi.h @@ -71,7 +71,7 @@ extern "C" ************************************************************************************/ struct spi_dev_s; /* Forward reference */ -enum spi_dev_e; /* Forward reference */ +uint32_t; /* Forward reference */ /**************************************************************************** * Name: pic32mz_spibus_initialize @@ -118,56 +118,56 @@ FAR struct spi_dev_s *pic32mz_spibus_initialize(int port); ************************************************************************************/ #ifdef CONFIG_PIC32MZ_SPI1 -void pic32mz_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void pic32mz_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); -uint8_t pic32mz_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +uint8_t pic32mz_spi1status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int pic32mz_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int pic32mz_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif #ifdef CONFIG_PIC32MZ_SPI2 -void pic32mz_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void pic32mz_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); -uint8_t pic32mz_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +uint8_t pic32mz_spi2status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int pic32mz_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int pic32mz_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif #ifdef CONFIG_PIC32MZ_SPI3 -void pic32mz_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void pic32mz_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); -uint8_t pic32mz_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +uint8_t pic32mz_spi3status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int pic32mz_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int pic32mz_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif #ifdef CONFIG_PIC32MZ_SPI4 -void pic32mz_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void pic32mz_spi4select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); -uint8_t pic32mz_spi4status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +uint8_t pic32mz_spi4status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int pic32mz_spi4cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int pic32mz_spi4cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif #ifdef CONFIG_PIC32MZ_SPI5 -void pic32mz_spi5select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void pic32mz_spi5select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); -uint8_t pic32mz_spi5status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +uint8_t pic32mz_spi5status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int pic32mz_spi5cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int pic32mz_spi5cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif #ifdef CONFIG_PIC32MZ_SPI6 -void pic32mz_spi6select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void pic32mz_spi6select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); -uint8_t pic32mz_spi6status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +uint8_t pic32mz_spi6status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int pic32mz_spi6cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int pic32mz_spi6cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif diff --git a/arch/sim/src/up_spiflash.c b/arch/sim/src/up_spiflash.c index ad36789069..46b96e2201 100644 --- a/arch/sim/src/up_spiflash.c +++ b/arch/sim/src/up_spiflash.c @@ -200,11 +200,11 @@ static void spiflash_setbits(FAR struct spi_dev_s *dev, int nbits); static uint16_t spiflash_send(FAR struct spi_dev_s *dev, uint16_t wd); static void spiflash_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer, FAR void *rxbuffer, size_t nwords); -static void spiflash_select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +static void spiflash_select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); -static uint8_t spiflash_status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +static uint8_t spiflash_status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -static int spiflash_cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +static int spiflash_cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #ifndef CONFIG_SPI_EXCHANGE static void spiflash_sndblock(FAR struct spi_dev_s *dev, FAR const void *txbuffer, @@ -357,7 +357,7 @@ static int spiflash_lock(FAR struct spi_dev_s *dev, bool lock) * ************************************************************************************/ -static void spiflash_select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +static void spiflash_select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { FAR struct sim_spiflashdev_s *priv = (FAR struct sim_spiflashdev_s *)dev; @@ -392,7 +392,7 @@ static void spiflash_select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, ************************************************************************************/ #ifdef CONFIG_SPI_CMDDATA -static int spiflash_cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +static int spiflash_cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return 0; } @@ -467,7 +467,7 @@ static void spiflash_setbits(FAR struct spi_dev_s *dev, int nbits) * ************************************************************************************/ -static uint8_t spiflash_status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +static uint8_t spiflash_status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } diff --git a/arch/x86/src/qemu/qemu.h b/arch/x86/src/qemu/qemu.h index a42fd0a328..6eada26a05 100644 --- a/arch/x86/src/qemu/qemu.h +++ b/arch/x86/src/qemu/qemu.h @@ -208,7 +208,7 @@ int i486_dumpgpio(uint16_t pinset, const char *msg); ****************************************************************************/ struct spi_dev_s; /* Forward reference */ -enum spi_dev_e; /* Forward reference */ +uint32_t; /* Forward reference */ FAR struct spi_dev_s *i486_spibus_initialize(int port); @@ -242,13 +242,13 @@ FAR struct spi_dev_s *i486_spibus_initialize(int port); ************************************************************************************/ struct spi_dev_s; -enum spi_dev_e; +uint32_t; #ifdef CONFIG_I486_SPI -void i486_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t i486_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +void i486_spiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t i486_spistatus(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -int i486_spicmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int i486_spicmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif diff --git a/arch/z16/src/z16f/chip.h b/arch/z16/src/z16f/chip.h index 9d4942f7b9..f54a188a22 100644 --- a/arch/z16/src/z16f/chip.h +++ b/arch/z16/src/z16f/chip.h @@ -677,7 +677,7 @@ void z16f_reset(void); #ifdef CONFIG_Z16F_ESPI struct spi_dev_s; /* Forward reference */ -enum spi_dev_e; /* Forward reference */ +uint32_t; /* Forward reference */ /* Initialize the selected SPI port */ @@ -685,16 +685,16 @@ FAR struct spi_dev_s *z16_spibus_initialize(int port); /* Select an SPI device (see include/nuttx/spi/spi.h) */ -void z16f_espi_select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); +void z16f_espi_select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); /* Provide SPI device status (see include/nuttx/spi/spi.h) */ -uint8_t z16f_espi_status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +uint8_t z16f_espi_status(FAR struct spi_dev_s *dev, uint32_t devid); /* Select CMD/DATA options (often used with LCD devices) */ #ifdef CONFIG_SPI_CMDDATA -int z16f_espi_cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +int z16f_espi_cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif #endif diff --git a/arch/z80/src/ez80/ez80f91_spi.h b/arch/z80/src/ez80/ez80f91_spi.h index 36c0016f48..fe7c34bb7e 100644 --- a/arch/z80/src/ez80/ez80f91_spi.h +++ b/arch/z80/src/ez80/ez80f91_spi.h @@ -145,9 +145,9 @@ FAR struct spi_dev_s *ez80_spibus_initialize(int port); * ************************************************************************************/ -void ez80_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -uint8_t ez80_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid); -int ez80_spicmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +void ez80_spiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); +uint8_t ez80_spistatus(FAR struct spi_dev_s *dev, uint32_t devid); +int ez80_spicmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #undef EXTERN #ifdef __cplusplus -- GitLab From aca2e36d67cab5619b68747a82380fdbb37c4d5e Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Fri, 28 Apr 2017 18:26:05 +0200 Subject: [PATCH 620/990] stm32 devboards --- configs/nucleo-144/src/stm32_spi.c | 37 ++++++++++++----------- configs/nucleo-f303re/src/stm32_spi.c | 18 +++++------ configs/nucleo-f4x1re/src/stm32_spi.c | 18 +++++------ configs/nucleo-l476rg/src/stm32_spi.c | 18 +++++------ configs/stm3210e-eval/src/stm32_spi.c | 12 ++++---- configs/stm3220g-eval/src/stm32_spi.c | 12 ++++---- configs/stm3240g-eval/src/stm32_spi.c | 12 ++++---- configs/stm32_tiny/src/stm32_spi.c | 8 ++--- configs/stm32butterfly2/src/stm32_spi.c | 4 +-- configs/stm32f103-minimum/src/stm32_spi.c | 10 +++--- configs/stm32f3discovery/src/stm32_spi.c | 18 +++++------ configs/stm32f429i-disco/src/stm32_spi.c | 30 +++++++++--------- configs/stm32f4discovery/src/stm32_spi.c | 18 +++++------ configs/stm32f746-ws/src/stm32_spi.c | 36 +++++++++++----------- configs/stm32f746g-disco/src/stm32_spi.c | 30 +++++++++--------- configs/stm32l476-mdk/src/stm32_spi.c | 18 +++++------ configs/stm32l476vg-disco/src/stm32_spi.c | 18 +++++------ configs/stm32ldiscovery/src/stm32_spi.c | 18 +++++------ 18 files changed, 168 insertions(+), 167 deletions(-) diff --git a/configs/nucleo-144/src/stm32_spi.c b/configs/nucleo-144/src/stm32_spi.c index 61dab7a51e..5e24455c26 100644 --- a/configs/nucleo-144/src/stm32_spi.c +++ b/configs/nucleo-144/src/stm32_spi.c @@ -213,39 +213,39 @@ void weak_function stm32_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_STM32F7_SPI1 -void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); stm32_gpiowrite(g_spigpio[devid], !selected); } -uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32F7_SPI2 -void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); stm32_gpiowrite(g_spigpio[devid], !selected); } -uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32F7_SPI3 -void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); stm32_gpiowrite(g_spigpio[devid], !selected); } -uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } @@ -256,13 +256,13 @@ uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) # error "NUCLEO_SPI_BUS4_CSn Are not defined" # endif -void stm32_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi4select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); stm32_gpiowrite(g_spigpio[devid], !selected); } -uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } @@ -273,13 +273,13 @@ uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) # error "NUCLEO_SPI_BUS4_CSn Are not defined" # endif -void stm32_spi5select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi5select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); stm32_gpiowrite(g_spigpio[devid], !selected); } -uint8_t stm32_spi5status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi5status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } @@ -289,13 +289,13 @@ uint8_t stm32_spi5status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) # ifndef NUCLEO_SPI_BUS6_CS # error "NUCLEO_SPI_BUS4_CSn Are not defined" # endif -void stm32_spi5select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi5select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); stm32_gpiowrite(g_spigpio[devid], !selected); } -uint8_t stm32_spi5status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi5status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } @@ -326,43 +326,44 @@ uint8_t stm32_spi5status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #ifdef CONFIG_SPI_CMDDATA #ifdef CONFIG_STM32F7_SPI1 -int stm32_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } #endif #ifdef CONFIG_STM32F7_SPI2 -int stm32_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } #endif #ifdef CONFIG_STM32F7_SPI3 -int stm32_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } #endif #ifdef CONFIG_STM32F7_SPI4 -int stm32_spi4cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi4cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } #endif #ifdef CONFIG_STM32F7_SPI5 -int stm32_spi5cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi5cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } #endif #ifdef CONFIG_STM32F7_SPI6 -int stm32_spi5cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi5cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { +:qa return -ENODEV; } #endif diff --git a/configs/nucleo-f303re/src/stm32_spi.c b/configs/nucleo-f303re/src/stm32_spi.c index 6251ede1da..1a7e748a17 100644 --- a/configs/nucleo-f303re/src/stm32_spi.c +++ b/configs/nucleo-f303re/src/stm32_spi.c @@ -103,7 +103,7 @@ void weak_function stm32_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_STM32_SPI1 -void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); @@ -116,33 +116,33 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, #endif } -uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32_SPI2 -void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32_SPI3 -void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } @@ -172,7 +172,7 @@ uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #ifdef CONFIG_SPI_CMDDATA #ifdef CONFIG_STM32_SPI1 -int stm32_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +int stm32_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #ifdef CONFIG_LCD_SSD1351 @@ -188,7 +188,7 @@ int stm32_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, #endif #ifdef CONFIG_STM32_SPI2 -int stm32_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +int stm32_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; @@ -196,7 +196,7 @@ int stm32_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, #endif #ifdef CONFIG_STM32_SPI3 -int stm32_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +int stm32_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; diff --git a/configs/nucleo-f4x1re/src/stm32_spi.c b/configs/nucleo-f4x1re/src/stm32_spi.c index 82026a0d26..bb56053168 100644 --- a/configs/nucleo-f4x1re/src/stm32_spi.c +++ b/configs/nucleo-f4x1re/src/stm32_spi.c @@ -141,7 +141,7 @@ void weak_function stm32_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_STM32_SPI1 -void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); @@ -160,14 +160,14 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele #endif } -uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32_SPI2 -void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); @@ -179,19 +179,19 @@ void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele #endif } -uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32_SPI3 -void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } @@ -222,21 +222,21 @@ uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #ifdef CONFIG_SPI_CMDDATA #ifdef CONFIG_STM32_SPI1 -int stm32_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } #endif #ifdef CONFIG_STM32_SPI2 -int stm32_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } #endif #ifdef CONFIG_STM32_SPI3 -int stm32_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } diff --git a/configs/nucleo-l476rg/src/stm32_spi.c b/configs/nucleo-l476rg/src/stm32_spi.c index 71d65d8a10..dcdda1a700 100644 --- a/configs/nucleo-l476rg/src/stm32_spi.c +++ b/configs/nucleo-l476rg/src/stm32_spi.c @@ -141,7 +141,7 @@ void weak_function stm32l4_spiinitialize(void) ****************************************************************************/ #ifdef CONFIG_STM32L4_SPI1 -void stm32l4_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32l4_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); @@ -160,14 +160,14 @@ void stm32l4_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool se #endif } -uint8_t stm32l4_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32l4_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32L4_SPI2 -void stm32l4_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32l4_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); @@ -179,19 +179,19 @@ void stm32l4_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool se #endif } -uint8_t stm32l4_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32l4_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32L4_SPI3 -void stm32l4_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32l4_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32l4_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32l4_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } @@ -222,21 +222,21 @@ uint8_t stm32l4_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #ifdef CONFIG_SPI_CMDDATA #ifdef CONFIG_STM32L4_SPI1 -int stm32l4_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32l4_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } #endif #ifdef CONFIG_STM32L4_SPI2 -int stm32l4_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32l4_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } #endif #ifdef CONFIG_STM32L4_SPI3 -int stm32l4_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32l4_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } diff --git a/configs/stm3210e-eval/src/stm32_spi.c b/configs/stm3210e-eval/src/stm32_spi.c index 4df6531cef..92d9af18a9 100644 --- a/configs/stm3210e-eval/src/stm32_spi.c +++ b/configs/stm3210e-eval/src/stm32_spi.c @@ -106,7 +106,7 @@ void weak_function stm32_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_STM32_SPI1 -void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); @@ -118,31 +118,31 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele } } -uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return SPI_STATUS_PRESENT; } #endif #ifdef CONFIG_STM32_SPI2 -void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { return SPI_STATUS_PRESENT; } #endif #ifdef CONFIG_STM32_SPI3 -void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) { return SPI_STATUS_PRESENT; } diff --git a/configs/stm3220g-eval/src/stm32_spi.c b/configs/stm3220g-eval/src/stm32_spi.c index 9e171b9bfa..1e806fb2bc 100644 --- a/configs/stm3220g-eval/src/stm32_spi.c +++ b/configs/stm3220g-eval/src/stm32_spi.c @@ -96,36 +96,36 @@ void weak_function stm32_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_STM32_SPI1 -void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return SPI_STATUS_PRESENT; } #endif #ifdef CONFIG_STM32_SPI2 -void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { return SPI_STATUS_PRESENT; } #endif #ifdef CONFIG_STM32_SPI3 -void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) { return SPI_STATUS_PRESENT; } diff --git a/configs/stm3240g-eval/src/stm32_spi.c b/configs/stm3240g-eval/src/stm32_spi.c index 45b7f894e1..a429ad5322 100644 --- a/configs/stm3240g-eval/src/stm32_spi.c +++ b/configs/stm3240g-eval/src/stm32_spi.c @@ -96,36 +96,36 @@ void weak_function stm32_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_STM32_SPI1 -void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return SPI_STATUS_PRESENT; } #endif #ifdef CONFIG_STM32_SPI2 -void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { return SPI_STATUS_PRESENT; } #endif #ifdef CONFIG_STM32_SPI3 -void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) { return SPI_STATUS_PRESENT; } diff --git a/configs/stm32_tiny/src/stm32_spi.c b/configs/stm32_tiny/src/stm32_spi.c index ac4e3eb68e..71bb78744c 100644 --- a/configs/stm32_tiny/src/stm32_spi.c +++ b/configs/stm32_tiny/src/stm32_spi.c @@ -109,18 +109,18 @@ void stm32_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_STM32_SPI1 -void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { } -uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32_SPI2 -void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { switch(devid) { @@ -138,7 +138,7 @@ void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele } } -uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { uint8_t status = 0; switch(devid) diff --git a/configs/stm32butterfly2/src/stm32_spi.c b/configs/stm32butterfly2/src/stm32_spi.c index fa2fd2e762..2fc3544869 100644 --- a/configs/stm32butterfly2/src/stm32_spi.c +++ b/configs/stm32butterfly2/src/stm32_spi.c @@ -73,7 +73,7 @@ void stm32_spidev_initialize(void) * Function asserts given devid based on select ****************************************************************************/ -void stm32_spi1select(struct spi_dev_s *dev, enum spi_dev_e devid, +void stm32_spi1select(struct spi_dev_s *dev, uint32_t devid, bool select) { spiinfo("INFO: Selecting spi dev: %d, state: %d\n", devid, select); @@ -91,7 +91,7 @@ void stm32_spi1select(struct spi_dev_s *dev, enum spi_dev_e devid, * Return status of devid ****************************************************************************/ -uint8_t stm32_spi1status(struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi1status(struct spi_dev_s *dev, uint32_t devid) { spiinfo("INFO: Requesting info from spi dev: %d\n", devid); diff --git a/configs/stm32f103-minimum/src/stm32_spi.c b/configs/stm32f103-minimum/src/stm32_spi.c index 2d24b7aa3d..8a4169cc2c 100644 --- a/configs/stm32f103-minimum/src/stm32_spi.c +++ b/configs/stm32f103-minimum/src/stm32_spi.c @@ -117,7 +117,7 @@ void stm32_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_STM32_SPI1 -void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { #if defined(CONFIG_CL_MFRC522) @@ -149,7 +149,7 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, #endif } -uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { uint8_t status = 0; @@ -172,12 +172,12 @@ uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #endif #ifdef CONFIG_STM32_SPI2 -void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { } -uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } @@ -209,7 +209,7 @@ uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #ifdef CONFIG_SPI_CMDDATA #ifdef CONFIG_STM32_SPI1 -int stm32_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +int stm32_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #ifdef CONFIG_LCD_ST7567 diff --git a/configs/stm32f3discovery/src/stm32_spi.c b/configs/stm32f3discovery/src/stm32_spi.c index 712db25d2d..c9edb6052e 100644 --- a/configs/stm32f3discovery/src/stm32_spi.c +++ b/configs/stm32f3discovery/src/stm32_spi.c @@ -101,38 +101,38 @@ void weak_function stm32_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_STM32_SPI1 -void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); stm32_gpiowrite(GPIO_MEMS_CS, !selected); } -uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32_SPI2 -void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32_SPI3 -void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } @@ -163,21 +163,21 @@ uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #ifdef CONFIG_SPI_CMDDATA #ifdef CONFIG_STM32_SPI1 -int stm32_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } #endif #ifdef CONFIG_STM32_SPI2 -int stm32_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } #endif #ifdef CONFIG_STM32_SPI3 -int stm32_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } diff --git a/configs/stm32f429i-disco/src/stm32_spi.c b/configs/stm32f429i-disco/src/stm32_spi.c index 69d2de2997..14b20b9b3a 100644 --- a/configs/stm32f429i-disco/src/stm32_spi.c +++ b/configs/stm32f429i-disco/src/stm32_spi.c @@ -115,43 +115,43 @@ void weak_function stm32_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_STM32_SPI1 -void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32_SPI2 -void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32_SPI3 -void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32_SPI4 -void stm32_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi4select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { #if defined(CONFIG_MTD_SST25XX) if (devid == SPIDEV_FLASH) @@ -161,14 +161,14 @@ void stm32_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele #endif } -uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32_SPI5 -void stm32_spi5select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi5select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); @@ -185,7 +185,7 @@ void stm32_spi5select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele } } -uint8_t stm32_spi5status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi5status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } @@ -216,35 +216,35 @@ uint8_t stm32_spi5status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #ifdef CONFIG_SPI_CMDDATA #ifdef CONFIG_STM32_SPI1 -int stm32_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } #endif #ifdef CONFIG_STM32_SPI2 -int stm32_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } #endif #ifdef CONFIG_STM32_SPI3 -int stm32_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } #endif #ifdef CONFIG_STM32_SPI4 -int stm32_spi4cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi4cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } #endif #ifdef CONFIG_STM32_SPI5 -int stm32_spi5cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi5cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #if defined(CONFIG_STM32F429I_DISCO_ILI9341) if (devid == SPIDEV_DISPLAY) diff --git a/configs/stm32f4discovery/src/stm32_spi.c b/configs/stm32f4discovery/src/stm32_spi.c index c6d7506fc1..77b53a8ac4 100644 --- a/configs/stm32f4discovery/src/stm32_spi.c +++ b/configs/stm32f4discovery/src/stm32_spi.c @@ -116,7 +116,7 @@ void weak_function stm32_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_STM32_SPI1 -void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); @@ -133,14 +133,14 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele } } -uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32_SPI2 -void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); @@ -158,19 +158,19 @@ void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele #endif } -uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32_SPI3 -void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } @@ -201,7 +201,7 @@ uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #ifdef CONFIG_SPI_CMDDATA #ifdef CONFIG_STM32_SPI1 -int stm32_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #if defined(CONFIG_LCD_UG2864AMBAG01) || defined(CONFIG_LCD_UG2864HSWEG01) || \ defined(CONFIG_LCD_SSD1351) @@ -230,14 +230,14 @@ int stm32_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) #endif #ifdef CONFIG_STM32_SPI2 -int stm32_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } #endif #ifdef CONFIG_STM32_SPI3 -int stm32_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } diff --git a/configs/stm32f746-ws/src/stm32_spi.c b/configs/stm32f746-ws/src/stm32_spi.c index 517ea3761b..196b8c1e24 100644 --- a/configs/stm32f746-ws/src/stm32_spi.c +++ b/configs/stm32f746-ws/src/stm32_spi.c @@ -99,72 +99,72 @@ void weak_function stm32_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_STM32F7_SPI1 -void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32F7_SPI2 -void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32F7_SPI3 -void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32F7_SPI4 -void stm32_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi4select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32F7_SPI5 -void stm32_spi5select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi5select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi5status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi5status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32F7_SPI6 -void stm32_spi6select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi6select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi6status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi6status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } @@ -195,42 +195,42 @@ uint8_t stm32_spi6status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #ifdef CONFIG_SPI_CMDDATA #ifdef CONFIG_STM32F7_SPI1 -int stm32_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } #endif #ifdef CONFIG_STM32F7_SPI2 -int stm32_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } #endif #ifdef CONFIG_STM32F7_SPI3 -int stm32_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } #endif #ifdef CONFIG_STM32F7_SPI4 -int stm32_spi4cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi4cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } #endif #ifdef CONFIG_STM32F7_SPI5 -int stm32_spi5cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi5cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } #endif #ifdef CONFIG_STM32F7_SPI6 -int stm32_spi6cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi6cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } diff --git a/configs/stm32f746g-disco/src/stm32_spi.c b/configs/stm32f746g-disco/src/stm32_spi.c index c2bea9894d..1b8035af68 100644 --- a/configs/stm32f746g-disco/src/stm32_spi.c +++ b/configs/stm32f746g-disco/src/stm32_spi.c @@ -99,60 +99,60 @@ void weak_function stm32_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_STM32F7_SPI1 -void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32F7_SPI2 -void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32F7_SPI3 -void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32F7_SPI4 -void stm32_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi4select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32F7_SPI5 -void stm32_spi5select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi5select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi5status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi5status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } @@ -183,35 +183,35 @@ uint8_t stm32_spi5status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #ifdef CONFIG_SPI_CMDDATA #ifdef CONFIG_STM32F7_SPI1 -int stm32_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } #endif #ifdef CONFIG_STM32F7_SPI2 -int stm32_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } #endif #ifdef CONFIG_STM32F7_SPI3 -int stm32_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } #endif #ifdef CONFIG_STM32F7_SPI4 -int stm32_spi4cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi4cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } #endif #ifdef CONFIG_STM32F7_SPI5 -int stm32_spi5cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi5cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } diff --git a/configs/stm32l476-mdk/src/stm32_spi.c b/configs/stm32l476-mdk/src/stm32_spi.c index 8b1cb7a8a6..ae13e9e59d 100644 --- a/configs/stm32l476-mdk/src/stm32_spi.c +++ b/configs/stm32l476-mdk/src/stm32_spi.c @@ -126,36 +126,36 @@ void weak_function stm32_spiinitialize(void) ****************************************************************************/ #ifdef CONFIG_STM32_SPI1 -void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32_SPI2 -void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32_SPI3 -void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } @@ -186,21 +186,21 @@ uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #ifdef CONFIG_SPI_CMDDATA #ifdef CONFIG_STM32_SPI1 -int stm32_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } #endif #ifdef CONFIG_STM32_SPI2 -int stm32_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } #endif #ifdef CONFIG_STM32_SPI3 -int stm32_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } diff --git a/configs/stm32l476vg-disco/src/stm32_spi.c b/configs/stm32l476vg-disco/src/stm32_spi.c index 3b8420c62a..cca4db6f82 100644 --- a/configs/stm32l476vg-disco/src/stm32_spi.c +++ b/configs/stm32l476vg-disco/src/stm32_spi.c @@ -143,7 +143,7 @@ void weak_function stm32_spiinitialize(void) ****************************************************************************/ #ifdef CONFIG_STM32_SPI1 -void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); @@ -162,14 +162,14 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele #endif } -uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32_SPI2 -void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); @@ -181,19 +181,19 @@ void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele #endif } -uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32_SPI3 -void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } @@ -224,21 +224,21 @@ uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #ifdef CONFIG_SPI_CMDDATA #ifdef CONFIG_STM32_SPI1 -int stm32_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } #endif #ifdef CONFIG_STM32_SPI2 -int stm32_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } #endif #ifdef CONFIG_STM32_SPI3 -int stm32_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } diff --git a/configs/stm32ldiscovery/src/stm32_spi.c b/configs/stm32ldiscovery/src/stm32_spi.c index d923a8b2c9..5b385f1b4d 100644 --- a/configs/stm32ldiscovery/src/stm32_spi.c +++ b/configs/stm32ldiscovery/src/stm32_spi.c @@ -102,38 +102,38 @@ void weak_function stm32_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_STM32_SPI1 -void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); stm32_gpiowrite(GPIO_MEMS_CS, !selected); } -uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32_SPI2 -void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32_SPI3 -void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } @@ -164,21 +164,21 @@ uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #ifdef CONFIG_SPI_CMDDATA #ifdef CONFIG_STM32_SPI1 -int stm32_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } #endif #ifdef CONFIG_STM32_SPI2 -int stm32_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } #endif #ifdef CONFIG_STM32_SPI3 -int stm32_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } -- GitLab From 35b3abc6b22522347fe42e0fc44bed7758a9be3e Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Fri, 28 Apr 2017 18:26:39 +0200 Subject: [PATCH 621/990] kinetis boards --- configs/freedom-k64f/src/k64_spi.c | 12 ++++++------ configs/freedom-k66f/src/k66_spi.c | 12 ++++++------ configs/freedom-kl25z/src/kl_spi.c | 12 ++++++------ configs/freedom-kl26z/src/kl_spi.c | 12 ++++++------ 4 files changed, 24 insertions(+), 24 deletions(-) diff --git a/configs/freedom-k64f/src/k64_spi.c b/configs/freedom-k64f/src/k64_spi.c index cae8680979..3fff145575 100644 --- a/configs/freedom-k64f/src/k64_spi.c +++ b/configs/freedom-k64f/src/k64_spi.c @@ -100,13 +100,13 @@ void weak_function k64_spidev_initialize(void) ************************************************************************************/ #ifdef CONFIG_KINETIS_SPI0 -void kinetis_spi0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void kinetis_spi0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); # warning "Missing logic" } -uint8_t kinetis_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t kinetis_spi0status(FAR struct spi_dev_s *dev, uint32_t devid) { # warning "Missing logic" return SPI_STATUS_PRESENT; @@ -114,13 +114,13 @@ uint8_t kinetis_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #endif #ifdef CONFIG_KINETIS_SPI1 -void kinetis_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void kinetis_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); # warning "Missing logic" } -uint8_t kinetis_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t kinetis_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { # warning "Missing logic" return SPI_STATUS_PRESENT; @@ -128,13 +128,13 @@ uint8_t kinetis_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #endif #ifdef CONFIG_KINETIS_SPI2 -void kinetis_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void kinetis_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); # warning "Missing logic" } -uint8_t kinetis_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t kinetis_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { # warning "Missing logic" return SPI_STATUS_PRESENT; diff --git a/configs/freedom-k66f/src/k66_spi.c b/configs/freedom-k66f/src/k66_spi.c index dca7c44a25..ce0c6eb78d 100644 --- a/configs/freedom-k66f/src/k66_spi.c +++ b/configs/freedom-k66f/src/k66_spi.c @@ -101,13 +101,13 @@ void weak_function k66_spidev_initialize(void) ************************************************************************************/ #ifdef CONFIG_KINETIS_SPI0 -void kinetis_spi0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void kinetis_spi0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); # warning "Missing logic" } -uint8_t kinetis_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t kinetis_spi0status(FAR struct spi_dev_s *dev, uint32_t devid) { # warning "Missing logic" return SPI_STATUS_PRESENT; @@ -115,13 +115,13 @@ uint8_t kinetis_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #endif #ifdef CONFIG_KINETIS_SPI1 -void kinetis_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void kinetis_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); # warning "Missing logic" } -uint8_t kinetis_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t kinetis_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { # warning "Missing logic" return SPI_STATUS_PRESENT; @@ -129,13 +129,13 @@ uint8_t kinetis_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #endif #ifdef CONFIG_KINETIS_SPI2 -void kinetis_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void kinetis_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); # warning "Missing logic" } -uint8_t kinetis_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t kinetis_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { # warning "Missing logic" return SPI_STATUS_PRESENT; diff --git a/configs/freedom-kl25z/src/kl_spi.c b/configs/freedom-kl25z/src/kl_spi.c index 5c41ae348c..ec26f436cd 100644 --- a/configs/freedom-kl25z/src/kl_spi.c +++ b/configs/freedom-kl25z/src/kl_spi.c @@ -139,7 +139,7 @@ void weak_function kl_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_KL_SPI0 -void kl_spi0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void kl_spi0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", @@ -165,7 +165,7 @@ void kl_spi0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, #endif #ifdef CONFIG_KL_SPI1 -void kl_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void kl_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", @@ -188,14 +188,14 @@ void kl_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, ****************************************************************************/ #ifdef CONFIG_KL_SPI0 -uint8_t kl_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t kl_spi0status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_KL_SPI1 -uint8_t kl_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t kl_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } @@ -220,14 +220,14 @@ uint8_t kl_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #ifdef CONFIG_SPI_CMDDATA #ifdef CONFIG_KL_SPI0 -int kl_spi0cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int kl_spi0cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return 0; } #endif #ifdef CONFIG_KL_SPI1 -int kl_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int kl_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return 0; } diff --git a/configs/freedom-kl26z/src/kl_spi.c b/configs/freedom-kl26z/src/kl_spi.c index 9b3cd6ff24..4c94db9fa3 100644 --- a/configs/freedom-kl26z/src/kl_spi.c +++ b/configs/freedom-kl26z/src/kl_spi.c @@ -130,7 +130,7 @@ void weak_function kl_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_KL_SPI0 -void kl_spi0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void kl_spi0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", @@ -139,7 +139,7 @@ void kl_spi0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, #endif #ifdef CONFIG_KL_SPI1 -void kl_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void kl_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", @@ -162,14 +162,14 @@ void kl_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, ****************************************************************************/ #ifdef CONFIG_KL_SPI0 -uint8_t kl_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t kl_spi0status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_KL_SPI1 -uint8_t kl_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t kl_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } @@ -194,14 +194,14 @@ uint8_t kl_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #ifdef CONFIG_SPI_CMDDATA #ifdef CONFIG_KL_SPI0 -int kl_spi0cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int kl_spi0cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return 0; } #endif #ifdef CONFIG_KL_SPI1 -int kl_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int kl_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return 0; } -- GitLab From 1bb76c43d361a4d2059e6242abdfdee0fc124c80 Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Fri, 28 Apr 2017 18:27:30 +0200 Subject: [PATCH 622/990] atmel boards --- configs/sam3u-ek/src/sam_spi.c | 4 +-- configs/sam4e-ek/src/sam_spi.c | 4 +-- configs/sam4l-xplained/src/sam_spi.c | 6 ++--- configs/sama5d3-xplained/src/sam_spi.c | 8 +++--- configs/sama5d3x-ek/src/sam_spi.c | 8 +++--- configs/sama5d4-ek/src/sam_spi.c | 8 +++--- configs/samd20-xplained/src/sam_spi.c | 36 +++++++++++++------------- configs/samd21-xplained/src/sam_spi.c | 36 +++++++++++++------------- configs/same70-xplained/src/sam_spi.c | 8 +++--- configs/saml21-xplained/src/sam_spi.c | 36 +++++++++++++------------- configs/samv71-xult/src/sam_spi.c | 8 +++--- 11 files changed, 81 insertions(+), 81 deletions(-) diff --git a/configs/sam3u-ek/src/sam_spi.c b/configs/sam3u-ek/src/sam_spi.c index 6921548360..af55cb2884 100644 --- a/configs/sam3u-ek/src/sam_spi.c +++ b/configs/sam3u-ek/src/sam_spi.c @@ -138,7 +138,7 @@ void weak_function sam_spidev_initialize(void) * ****************************************************************************/ -void sam_spi0select(enum spi_dev_e devid, bool selected) +void sam_spi0select(uint32_t devid, bool selected) { /* The touchscreen chip select is implemented as a GPIO OUTPUT that must * be controlled by this function. This is because the ADS7843E driver @@ -170,7 +170,7 @@ void sam_spi0select(enum spi_dev_e devid, bool selected) * ****************************************************************************/ -uint8_t sam_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi0status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } diff --git a/configs/sam4e-ek/src/sam_spi.c b/configs/sam4e-ek/src/sam_spi.c index a26a95c17d..90d0e345fc 100644 --- a/configs/sam4e-ek/src/sam_spi.c +++ b/configs/sam4e-ek/src/sam_spi.c @@ -140,7 +140,7 @@ void weak_function sam_spidev_initialize(void) * ****************************************************************************/ -void sam_spi0select(enum spi_dev_e devid, bool selected) +void sam_spi0select(uint32_t devid, bool selected) { switch (devid) { @@ -185,7 +185,7 @@ void sam_spi0select(enum spi_dev_e devid, bool selected) * ****************************************************************************/ -uint8_t sam_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi0status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } diff --git a/configs/sam4l-xplained/src/sam_spi.c b/configs/sam4l-xplained/src/sam_spi.c index 47e7741e50..be44a7f403 100644 --- a/configs/sam4l-xplained/src/sam_spi.c +++ b/configs/sam4l-xplained/src/sam_spi.c @@ -140,7 +140,7 @@ void weak_function sam_spidev_initialize(void) * ****************************************************************************/ -void sam_spi0select(enum spi_dev_e devid, bool selected) +void sam_spi0select(uint32_t devid, bool selected) { #ifdef CONFIG_SAM4L_XPLAINED_IOMODULE /* Select/de-select the SD card */ @@ -183,7 +183,7 @@ void sam_spi0select(enum spi_dev_e devid, bool selected) * ****************************************************************************/ -uint8_t sam_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi0status(FAR struct spi_dev_s *dev, uint32_t devid) { uint8_t ret = 0; @@ -231,7 +231,7 @@ uint8_t sam_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) ****************************************************************************/ #ifdef CONFIG_SPI_CMDDATA -int sam_spic0mddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int sam_spic0mddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #ifdef CONFIG_SAM4L_XPLAINED_OLED1MODULE if (devid == SPIDEV_DISPLAY) diff --git a/configs/sama5d3-xplained/src/sam_spi.c b/configs/sama5d3-xplained/src/sam_spi.c index 9c42a10d65..93e965ffd6 100644 --- a/configs/sama5d3-xplained/src/sam_spi.c +++ b/configs/sama5d3-xplained/src/sam_spi.c @@ -140,7 +140,7 @@ void weak_function sam_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_SAMA5_SPI0 -void sam_spi0select(enum spi_dev_e devid, bool selected) +void sam_spi0select(uint32_t devid, bool selected) { #ifdef CONFIG_MTD_AT25 /* The AT25 serial FLASH connects using NPCS0 */ @@ -154,7 +154,7 @@ void sam_spi0select(enum spi_dev_e devid, bool selected) #endif #ifdef CONFIG_SAMA5_SPI1 -void sam_spi1select(enum spi_dev_e devid, bool selected) +void sam_spi1select(uint32_t devid, bool selected) { } #endif @@ -174,14 +174,14 @@ void sam_spi1select(enum spi_dev_e devid, bool selected) ****************************************************************************/ #ifdef CONFIG_SAMA5_SPI0 -uint8_t sam_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi0status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_SAMA5_SPI0 -uint8_t sam_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } diff --git a/configs/sama5d3x-ek/src/sam_spi.c b/configs/sama5d3x-ek/src/sam_spi.c index f2932e5fb8..f4b4c00928 100644 --- a/configs/sama5d3x-ek/src/sam_spi.c +++ b/configs/sama5d3x-ek/src/sam_spi.c @@ -140,7 +140,7 @@ void weak_function sam_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_SAMA5_SPI0 -void sam_spi0select(enum spi_dev_e devid, bool selected) +void sam_spi0select(uint32_t devid, bool selected) { #ifdef CONFIG_MTD_AT25 /* The AT25 serial FLASH connects using NPCS0 */ @@ -154,7 +154,7 @@ void sam_spi0select(enum spi_dev_e devid, bool selected) #endif #ifdef CONFIG_SAMA5_SPI1 -void sam_spi1select(enum spi_dev_e devid, bool selected) +void sam_spi1select(uint32_t devid, bool selected) { } #endif @@ -174,14 +174,14 @@ void sam_spi1select(enum spi_dev_e devid, bool selected) ****************************************************************************/ #ifdef CONFIG_SAMA5_SPI0 -uint8_t sam_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi0status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_SAMA5_SPI0 -uint8_t sam_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } diff --git a/configs/sama5d4-ek/src/sam_spi.c b/configs/sama5d4-ek/src/sam_spi.c index 4b24a4b1ce..38cb1da36f 100644 --- a/configs/sama5d4-ek/src/sam_spi.c +++ b/configs/sama5d4-ek/src/sam_spi.c @@ -140,7 +140,7 @@ void weak_function sam_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_SAMA5_SPI0 -void sam_spi0select(enum spi_dev_e devid, bool selected) +void sam_spi0select(uint32_t devid, bool selected) { #ifdef CONFIG_MTD_AT25 /* The AT25 serial FLASH connects using NPCS0 */ @@ -154,7 +154,7 @@ void sam_spi0select(enum spi_dev_e devid, bool selected) #endif #ifdef CONFIG_SAMA5_SPI1 -void sam_spi1select(enum spi_dev_e devid, bool selected) +void sam_spi1select(uint32_t devid, bool selected) { } #endif @@ -174,14 +174,14 @@ void sam_spi1select(enum spi_dev_e devid, bool selected) ****************************************************************************/ #ifdef CONFIG_SAMA5_SPI0 -uint8_t sam_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi0status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_SAMA5_SPI0 -uint8_t sam_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } diff --git a/configs/samd20-xplained/src/sam_spi.c b/configs/samd20-xplained/src/sam_spi.c index 3ec3469adb..61b254eec6 100644 --- a/configs/samd20-xplained/src/sam_spi.c +++ b/configs/samd20-xplained/src/sam_spi.c @@ -148,7 +148,7 @@ void weak_function sam_spidev_initialize(void) ****************************************************************************/ #ifdef SAMDL_HAVE_SPI0 -void sam_spi0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void sam_spi0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { #ifdef CONFIG_SAMD20_XPLAINED_IOMODULE_EXT1 @@ -176,7 +176,7 @@ void sam_spi0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, #endif #ifdef SAMDL_HAVE_SPI1 -void sam_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void sam_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { #ifdef CONFIG_SAMD20_XPLAINED_IOMODULE_EXT2 @@ -204,28 +204,28 @@ void sam_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, #endif #ifdef SAMDL_HAVE_SPI2 -void sam_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void sam_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { } #endif #ifdef SAMDL_HAVE_SPI3 -void sam_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void sam_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { } #endif #ifdef SAMDL_HAVE_SPI4 -void sam_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void sam_spi4select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { } #endif #ifdef SAMDL_HAVE_SPI5 -void sam_spi5select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void sam_spi5select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { } @@ -247,7 +247,7 @@ void sam_spi5select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, ****************************************************************************/ #ifdef SAMDL_HAVE_SPI0 -uint8_t sam_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi0status(FAR struct spi_dev_s *dev, uint32_t devid) { uint8_t ret = 0; @@ -270,7 +270,7 @@ uint8_t sam_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #endif #ifdef SAMDL_HAVE_SPI1 -uint8_t sam_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { uint8_t ret = 0; @@ -293,28 +293,28 @@ uint8_t sam_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #endif #ifdef SAMDL_HAVE_SPI2 -uint8_t sam_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef SAMDL_HAVE_SPI3 -uint8_t sam_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef SAMDL_HAVE_SPI4 -uint8_t sam_spi4status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi4status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef SAMDL_HAVE_SPI5 -uint8_t sam_spi5status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi5status(FAR struct spi_dev_s *dev, uint32_t devid) { uint8_t ret = 0; return ret; @@ -347,7 +347,7 @@ uint8_t sam_spi5status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #ifdef CONFIG_SPI_CMDDATA #ifdef SAMDL_HAVE_SPI0 -int sam_spi0cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int sam_spi0cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #ifdef CONFIG_SAMD20_XPLAINED_OLED1MODULE_EXT1 if (devid == SPIDEV_DISPLAY) @@ -368,7 +368,7 @@ int sam_spi0cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) #endif #ifdef SAMDL_HAVE_SPI1 -int sam_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int sam_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #ifdef CONFIG_SAMD20_XPLAINED_OLED1MODULE_EXT2 if (devid == SPIDEV_DISPLAY) @@ -389,28 +389,28 @@ int sam_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) #endif #ifdef SAMDL_HAVE_SPI2 -int sam_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int sam_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } #endif #ifdef SAMDL_HAVE_SPI3 -int sam_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int sam_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } #endif #ifdef SAMDL_HAVE_SPI4 -int sam_spi4cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int sam_spi4cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } #endif #ifdef SAMDL_HAVE_SPI5 -int sam_spi5cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int sam_spi5cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } diff --git a/configs/samd21-xplained/src/sam_spi.c b/configs/samd21-xplained/src/sam_spi.c index eaf17020ec..275b961362 100644 --- a/configs/samd21-xplained/src/sam_spi.c +++ b/configs/samd21-xplained/src/sam_spi.c @@ -148,7 +148,7 @@ void weak_function sam_spidev_initialize(void) ****************************************************************************/ #ifdef SAMDL_HAVE_SPI0 -void sam_spi0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void sam_spi0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { #ifdef CONFIG_SAMD21_XPLAINED_IOMODULE_EXT1 @@ -176,7 +176,7 @@ void sam_spi0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, #endif #ifdef SAMDL_HAVE_SPI1 -void sam_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void sam_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { #ifdef CONFIG_SAMD21_XPLAINED_IOMODULE_EXT2 @@ -204,28 +204,28 @@ void sam_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, #endif #ifdef SAMDL_HAVE_SPI2 -void sam_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void sam_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { } #endif #ifdef SAMDL_HAVE_SPI3 -void sam_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void sam_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { } #endif #ifdef SAMDL_HAVE_SPI4 -void sam_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void sam_spi4select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { } #endif #ifdef SAMDL_HAVE_SPI5 -void sam_spi5select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void sam_spi5select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { } @@ -247,7 +247,7 @@ void sam_spi5select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, ****************************************************************************/ #ifdef SAMDL_HAVE_SPI0 -uint8_t sam_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi0status(FAR struct spi_dev_s *dev, uint32_t devid) { uint8_t ret = 0; @@ -270,7 +270,7 @@ uint8_t sam_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #endif #ifdef SAMDL_HAVE_SPI1 -uint8_t sam_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { uint8_t ret = 0; @@ -293,28 +293,28 @@ uint8_t sam_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #endif #ifdef SAMDL_HAVE_SPI2 -uint8_t sam_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef SAMDL_HAVE_SPI3 -uint8_t sam_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef SAMDL_HAVE_SPI4 -uint8_t sam_spi4status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi4status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef SAMDL_HAVE_SPI5 -uint8_t sam_spi5status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi5status(FAR struct spi_dev_s *dev, uint32_t devid) { uint8_t ret = 0; return ret; @@ -347,7 +347,7 @@ uint8_t sam_spi5status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #ifdef CONFIG_SPI_CMDDATA #ifdef SAMDL_HAVE_SPI0 -int sam_spi0cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int sam_spi0cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #ifdef CONFIG_SAMD21_XPLAINED_OLED1MODULE_EXT1 if (devid == SPIDEV_DISPLAY) @@ -368,7 +368,7 @@ int sam_spi0cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) #endif #ifdef SAMDL_HAVE_SPI1 -int sam_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int sam_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #ifdef CONFIG_SAMD21_XPLAINED_OLED1MODULE_EXT2 if (devid == SPIDEV_DISPLAY) @@ -389,28 +389,28 @@ int sam_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) #endif #ifdef SAMDL_HAVE_SPI2 -int sam_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int sam_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } #endif #ifdef SAMDL_HAVE_SPI3 -int sam_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int sam_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } #endif #ifdef SAMDL_HAVE_SPI4 -int sam_spi4cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int sam_spi4cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } #endif #ifdef SAMDL_HAVE_SPI5 -int sam_spi5cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int sam_spi5cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } diff --git a/configs/same70-xplained/src/sam_spi.c b/configs/same70-xplained/src/sam_spi.c index c21979060b..e50136df93 100644 --- a/configs/same70-xplained/src/sam_spi.c +++ b/configs/same70-xplained/src/sam_spi.c @@ -141,13 +141,13 @@ void sam_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_SAMV7_SPI0_MASTER -void sam_spi0select(enum spi_dev_e devid, bool selected) +void sam_spi0select(uint32_t devid, bool selected) { } #endif #ifdef CONFIG_SAMV7_SPI1_MASTER -void sam_spi1select(enum spi_dev_e devid, bool selected) +void sam_spi1select(uint32_t devid, bool selected) { } #endif @@ -167,14 +167,14 @@ void sam_spi1select(enum spi_dev_e devid, bool selected) ****************************************************************************/ #ifdef CONFIG_SAMV7_SPI0_MASTER -uint8_t sam_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi0status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_SAMV7_SPI1_MASTER -uint8_t sam_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } diff --git a/configs/saml21-xplained/src/sam_spi.c b/configs/saml21-xplained/src/sam_spi.c index ae1238eb2d..e4ecafd7ba 100644 --- a/configs/saml21-xplained/src/sam_spi.c +++ b/configs/saml21-xplained/src/sam_spi.c @@ -148,7 +148,7 @@ void weak_function sam_spidev_initialize(void) ****************************************************************************/ #ifdef SAMDL_HAVE_SPI0 -void sam_spi0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void sam_spi0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { #ifdef CONFIG_SAML21_XPLAINED_IOMODULE_EXT1 @@ -176,7 +176,7 @@ void sam_spi0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, #endif #ifdef SAMDL_HAVE_SPI1 -void sam_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void sam_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { #ifdef CONFIG_SAML21_XPLAINED_IOMODULE_EXT2 @@ -204,28 +204,28 @@ void sam_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, #endif #ifdef SAMDL_HAVE_SPI2 -void sam_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void sam_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { } #endif #ifdef SAMDL_HAVE_SPI3 -void sam_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void sam_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { } #endif #ifdef SAMDL_HAVE_SPI4 -void sam_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void sam_spi4select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { } #endif #ifdef SAMDL_HAVE_SPI5 -void sam_spi5select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void sam_spi5select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { } @@ -247,7 +247,7 @@ void sam_spi5select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, ****************************************************************************/ #ifdef SAMDL_HAVE_SPI0 -uint8_t sam_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi0status(FAR struct spi_dev_s *dev, uint32_t devid) { uint8_t ret = 0; @@ -270,7 +270,7 @@ uint8_t sam_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #endif #ifdef SAMDL_HAVE_SPI1 -uint8_t sam_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { uint8_t ret = 0; @@ -293,28 +293,28 @@ uint8_t sam_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #endif #ifdef SAMDL_HAVE_SPI2 -uint8_t sam_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef SAMDL_HAVE_SPI3 -uint8_t sam_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef SAMDL_HAVE_SPI4 -uint8_t sam_spi4status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi4status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef SAMDL_HAVE_SPI5 -uint8_t sam_spi5status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi5status(FAR struct spi_dev_s *dev, uint32_t devid) { uint8_t ret = 0; return ret; @@ -347,7 +347,7 @@ uint8_t sam_spi5status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #ifdef CONFIG_SPI_CMDDATA #ifdef SAMDL_HAVE_SPI0 -int sam_spi0cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int sam_spi0cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #ifdef CONFIG_SAML21_XPLAINED_OLED1MODULE_EXT1 if (devid == SPIDEV_DISPLAY) @@ -368,7 +368,7 @@ int sam_spi0cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) #endif #ifdef SAMDL_HAVE_SPI1 -int sam_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int sam_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #ifdef CONFIG_SAML21_XPLAINED_OLED1MODULE_EXT2 if (devid == SPIDEV_DISPLAY) @@ -389,28 +389,28 @@ int sam_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) #endif #ifdef SAMDL_HAVE_SPI2 -int sam_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int sam_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } #endif #ifdef SAMDL_HAVE_SPI3 -int sam_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int sam_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } #endif #ifdef SAMDL_HAVE_SPI4 -int sam_spi4cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int sam_spi4cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } #endif #ifdef SAMDL_HAVE_SPI5 -int sam_spi5cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int sam_spi5cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } diff --git a/configs/samv71-xult/src/sam_spi.c b/configs/samv71-xult/src/sam_spi.c index 58a4d30e24..eb39246e70 100644 --- a/configs/samv71-xult/src/sam_spi.c +++ b/configs/samv71-xult/src/sam_spi.c @@ -141,13 +141,13 @@ void sam_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_SAMV7_SPI0_MASTER -void sam_spi0select(enum spi_dev_e devid, bool selected) +void sam_spi0select(uint32_t devid, bool selected) { } #endif #ifdef CONFIG_SAMV7_SPI1_MASTER -void sam_spi1select(enum spi_dev_e devid, bool selected) +void sam_spi1select(uint32_t devid, bool selected) { } #endif @@ -167,14 +167,14 @@ void sam_spi1select(enum spi_dev_e devid, bool selected) ****************************************************************************/ #ifdef CONFIG_SAMV7_SPI0_MASTER -uint8_t sam_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi0status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_SAMV7_SPI1_MASTER -uint8_t sam_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t sam_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } -- GitLab From c2251e8e40a2e96c2a03fcf3d873c71907e92002 Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Fri, 28 Apr 2017 18:28:09 +0200 Subject: [PATCH 623/990] ti boards --- configs/dk-tm4c129x/src/tm4c_ssi.c | 4 ++-- configs/lm3s6432-s2e/src/lm_ssi.c | 4 ++-- configs/lm3s6965-ek/src/lm_oled.c | 2 +- configs/lm3s6965-ek/src/lm_ssi.c | 4 ++-- configs/lm3s8962-ek/src/lm_oled.c | 2 +- configs/lm3s8962-ek/src/lm_ssi.c | 4 ++-- configs/lm4f120-launchpad/src/lm4f_ssi.c | 4 ++-- configs/tm4c123g-launchpad/src/tm4c_ssi.c | 4 ++-- 8 files changed, 14 insertions(+), 14 deletions(-) diff --git a/configs/dk-tm4c129x/src/tm4c_ssi.c b/configs/dk-tm4c129x/src/tm4c_ssi.c index 8e142bfe32..fcaef493e8 100644 --- a/configs/dk-tm4c129x/src/tm4c_ssi.c +++ b/configs/dk-tm4c129x/src/tm4c_ssi.c @@ -102,14 +102,14 @@ void weak_function tm4c_ssidev_initialize(void) * ****************************************************************************/ -void tiva_ssiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void tiva_ssiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); ssi_dumpgpio("tiva_ssiselect() Entry"); ssi_dumpgpio("tiva_ssiselect() Exit"); } -uint8_t tiva_ssistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t tiva_ssistatus(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Returning SPI_STATUS_PRESENT\n"); return SPI_STATUS_PRESENT; diff --git a/configs/lm3s6432-s2e/src/lm_ssi.c b/configs/lm3s6432-s2e/src/lm_ssi.c index 5c0e771a54..b9398dc0fe 100644 --- a/configs/lm3s6432-s2e/src/lm_ssi.c +++ b/configs/lm3s6432-s2e/src/lm_ssi.c @@ -105,7 +105,7 @@ void weak_function lm_ssidev_initialize(void) * ****************************************************************************/ -void tiva_ssiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void tiva_ssiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); ssi_dumpgpio("tiva_ssiselect() Entry"); @@ -120,7 +120,7 @@ void tiva_ssiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool select ssi_dumpgpio("tiva_ssiselect() Exit"); } -uint8_t tiva_ssistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t tiva_ssistatus(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Returning SPI_STATUS_PRESENT\n"); return SPI_STATUS_PRESENT; diff --git a/configs/lm3s6965-ek/src/lm_oled.c b/configs/lm3s6965-ek/src/lm_oled.c index 2d72db7c1e..fa02d2b2e8 100644 --- a/configs/lm3s6965-ek/src/lm_oled.c +++ b/configs/lm3s6965-ek/src/lm_oled.c @@ -162,7 +162,7 @@ FAR struct lcd_dev_s *board_graphics_setup(unsigned int devno) * ****************************************************************************/ -int tiva_ssicmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int tiva_ssicmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { if (devid == SPIDEV_DISPLAY) { diff --git a/configs/lm3s6965-ek/src/lm_ssi.c b/configs/lm3s6965-ek/src/lm_ssi.c index 8cdf0b0122..52955e068d 100644 --- a/configs/lm3s6965-ek/src/lm_ssi.c +++ b/configs/lm3s6965-ek/src/lm_ssi.c @@ -110,7 +110,7 @@ void weak_function lm_ssidev_initialize(void) * ****************************************************************************/ -void tiva_ssiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void tiva_ssiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); ssi_dumpgpio("tiva_ssiselect() Entry"); @@ -132,7 +132,7 @@ void tiva_ssiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool select ssi_dumpgpio("tiva_ssiselect() Exit"); } -uint8_t tiva_ssistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t tiva_ssistatus(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Returning SPI_STATUS_PRESENT\n"); return SPI_STATUS_PRESENT; diff --git a/configs/lm3s8962-ek/src/lm_oled.c b/configs/lm3s8962-ek/src/lm_oled.c index 6e557a1220..491ee7c18f 100644 --- a/configs/lm3s8962-ek/src/lm_oled.c +++ b/configs/lm3s8962-ek/src/lm_oled.c @@ -160,7 +160,7 @@ FAR struct lcd_dev_s *board_graphics_setup(unsigned int devno) * ****************************************************************************/ -int tiva_ssicmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int tiva_ssicmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { if (devid == SPIDEV_DISPLAY) { diff --git a/configs/lm3s8962-ek/src/lm_ssi.c b/configs/lm3s8962-ek/src/lm_ssi.c index 2347895503..260127aae0 100644 --- a/configs/lm3s8962-ek/src/lm_ssi.c +++ b/configs/lm3s8962-ek/src/lm_ssi.c @@ -110,7 +110,7 @@ void weak_function lm_ssidev_initialize(void) * ****************************************************************************/ -void tiva_ssiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void tiva_ssiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); ssi_dumpgpio("tiva_ssiselect() Entry"); @@ -132,7 +132,7 @@ void tiva_ssiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool select ssi_dumpgpio("tiva_ssiselect() Exit"); } -uint8_t tiva_ssistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t tiva_ssistatus(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Returning SPI_STATUS_PRESENT\n"); return SPI_STATUS_PRESENT; diff --git a/configs/lm4f120-launchpad/src/lm4f_ssi.c b/configs/lm4f120-launchpad/src/lm4f_ssi.c index 2e8d3e49b5..d80b669db4 100644 --- a/configs/lm4f120-launchpad/src/lm4f_ssi.c +++ b/configs/lm4f120-launchpad/src/lm4f_ssi.c @@ -103,14 +103,14 @@ void weak_function lm4f_spidev_initialize(void) * ****************************************************************************/ -void tiva_ssiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void tiva_ssiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); ssi_dumpgpio("tiva_ssiselect() Entry"); ssi_dumpgpio("tiva_ssiselect() Exit"); } -uint8_t tiva_ssistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t tiva_ssistatus(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Returning SPI_STATUS_PRESENT\n"); return SPI_STATUS_PRESENT; diff --git a/configs/tm4c123g-launchpad/src/tm4c_ssi.c b/configs/tm4c123g-launchpad/src/tm4c_ssi.c index ce8ce7021c..3cdf0e3699 100644 --- a/configs/tm4c123g-launchpad/src/tm4c_ssi.c +++ b/configs/tm4c123g-launchpad/src/tm4c_ssi.c @@ -100,14 +100,14 @@ void weak_function tm4c_ssidev_initialize(void) * ****************************************************************************/ -void tiva_ssiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void tiva_ssiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); ssi_dumpgpio("tiva_ssiselect() Entry"); ssi_dumpgpio("tiva_ssiselect() Exit"); } -uint8_t tiva_ssistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t tiva_ssistatus(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Returning SPI_STATUS_PRESENT\n"); return SPI_STATUS_PRESENT; -- GitLab From 6574f8e610e5bff63774a0d9983229516e25ec63 Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Fri, 28 Apr 2017 18:28:45 +0200 Subject: [PATCH 624/990] pic32 boards --- configs/pic32mx-starterkit/src/pic32mx_spi.c | 26 +++++++------- configs/pic32mx7mmb/src/pic32_spi.c | 26 +++++++------- configs/pic32mz-starterkit/src/pic32mz_spi.c | 38 ++++++++++---------- configs/sure-pic32mx/src/pic32mx_spi.c | 4 +-- 4 files changed, 47 insertions(+), 47 deletions(-) diff --git a/configs/pic32mx-starterkit/src/pic32mx_spi.c b/configs/pic32mx-starterkit/src/pic32mx_spi.c index 4c0e2d2261..342b6797f5 100644 --- a/configs/pic32mx-starterkit/src/pic32mx_spi.c +++ b/configs/pic32mx-starterkit/src/pic32mx_spi.c @@ -102,23 +102,23 @@ void weak_function pic32mx_spidev_initialize(void) ************************************************************************************/ struct spi_dev_s; -enum spi_dev_e; +uint32_t; #ifdef CONFIG_PIC32MX_SPI1 -void pic32mx_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void pic32mx_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #warning "Missing logic" } -uint8_t pic32mx_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t pic32mx_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Returning nothing\n"); #warning "Missing logic" return 0; } #ifdef CONFIG_SPI_CMDDATA -int pic32mx_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int pic32mx_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #warning "Missing logic" return 0; @@ -127,20 +127,20 @@ int pic32mx_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cm #endif #ifdef CONFIG_PIC32MX_SPI1 -void pic32mx_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void pic32mx_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #warning "Missing logic" } -uint8_t pic32mx_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t pic32mx_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Returning nothing\n"); #warning "Missing logic" return 0; } #ifdef CONFIG_SPI_CMDDATA -int pic32mx_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int pic32mx_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #warning "Missing logic" return 0; @@ -149,20 +149,20 @@ int pic32mx_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cm #endif #ifdef CONFIG_PIC32MX_SPI3 -void pic32mx_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void pic32mx_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #warning "Missing logic" } -uint8_t pic32mx_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t pic32mx_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Returning nothing\n"); #warning "Missing logic" return 0; } #ifdef CONFIG_SPI_CMDDATA -int pic32mx_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int pic32mx_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #warning "Missing logic" return 0; @@ -171,20 +171,20 @@ int pic32mx_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cm #endif #ifdef CONFIG_PIC32MX_SPI4 -void pic32mx_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void pic32mx_spi4select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #warning "Missing logic" } -uint8_t pic32mx_spi4status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t pic32mx_spi4status(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Returning nothing\n"); #warning "Missing logic" return 0; } #ifdef CONFIG_SPI_CMDDATA -int pic32mx_spi4cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int pic32mx_spi4cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #warning "Missing logic" return 0; diff --git a/configs/pic32mx7mmb/src/pic32_spi.c b/configs/pic32mx7mmb/src/pic32_spi.c index 3cce76d53e..5af04e598c 100644 --- a/configs/pic32mx7mmb/src/pic32_spi.c +++ b/configs/pic32mx7mmb/src/pic32_spi.c @@ -128,10 +128,10 @@ void weak_function pic32mx_spidev_initialize(void) ************************************************************************************/ struct spi_dev_s; -enum spi_dev_e; +uint32_t; #ifdef CONFIG_PIC32MX_SPI1 -void pic32mx_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void pic32mx_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); @@ -141,7 +141,7 @@ void pic32mx_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool s } } -uint8_t pic32mx_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t pic32mx_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { uint8_t ret = 0; @@ -166,7 +166,7 @@ uint8_t pic32mx_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) return ret; } #ifdef CONFIG_SPI_CMDDATA -int pic32mx_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int pic32mx_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #warning "Missing logic" return 0; @@ -175,13 +175,13 @@ int pic32mx_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cm #endif #ifdef CONFIG_PIC32MX_SPI2 -void pic31mx_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void pic31mx_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #warning "Missing logic" } -uint8_t pic31mx_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t pic31mx_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Returning nothing\n"); #warning "Missing logic" @@ -189,7 +189,7 @@ uint8_t pic31mx_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) } #ifdef CONFIG_SPI_CMDDATA -int pic31mx_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int pic31mx_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #warning "Missing logic" return 0; @@ -198,13 +198,13 @@ int pic31mx_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cm #endif #ifdef CONFIG_PIC32MX_SPI3 -void pic32mx_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void pic32mx_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #warning "Missing logic" } -uint8_t pic32mx_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t pic32mx_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Returning nothing\n"); #warning "Missing logic" @@ -212,7 +212,7 @@ uint8_t pic32mx_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) } #ifdef CONFIG_SPI_CMDDATA -int pic32mx_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int pic32mx_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #warning "Missing logic" return 0; @@ -221,13 +221,13 @@ int pic32mx_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cm #endif #ifdef CONFIG_PIC32MX_SPI4 -void pic32mx_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void pic32mx_spi4select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #warning "Missing logic" } -uint8_t pic32mx_spi4status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t pic32mx_spi4status(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Returning nothing\n"); #warning "Missing logic" @@ -235,7 +235,7 @@ uint8_t pic32mx_spi4status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) } #ifdef CONFIG_SPI_CMDDATA -int pic32mx_spi4cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int pic32mx_spi4cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #warning "Missing logic" return 0; diff --git a/configs/pic32mz-starterkit/src/pic32mz_spi.c b/configs/pic32mz-starterkit/src/pic32mz_spi.c index f5093f9e6d..d3c7341cdc 100644 --- a/configs/pic32mz-starterkit/src/pic32mz_spi.c +++ b/configs/pic32mz-starterkit/src/pic32mz_spi.c @@ -100,23 +100,23 @@ void weak_function pic32mz_spidev_initialize(void) ************************************************************************************/ struct spi_dev_s; -enum spi_dev_e; +uint32_t; #ifdef CONFIG_PIC32MZ_SPI1 -void pic32mz_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void pic32mz_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #warning "Missing logic" } -uint8_t pic32mz_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t pic32mz_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Returning nothing\n"); #warning "Missing logic" return 0; } #ifdef CONFIG_SPI_CMDDATA -int pic32mz_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int pic32mz_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #warning "Missing logic" return 0; @@ -125,20 +125,20 @@ int pic32mz_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cm #endif #ifdef CONFIG_PIC32MZ_SPI2 -void pic32mz_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void pic32mz_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #warning "Missing logic" } -uint8_t pic32mz_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t pic32mz_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Returning nothing\n"); #warning "Missing logic" return 0; } #ifdef CONFIG_SPI_CMDDATA -int pic32mz_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int pic32mz_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #warning "Missing logic" return 0; @@ -147,20 +147,20 @@ int pic32mz_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cm #endif #ifdef CONFIG_PIC32MZ_SPI3 -void pic32mz_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void pic32mz_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #warning "Missing logic" } -uint8_t pic32mz_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t pic32mz_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Returning nothing\n"); #warning "Missing logic" return 0; } #ifdef CONFIG_SPI_CMDDATA -int pic32mz_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int pic32mz_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #warning "Missing logic" return 0; @@ -169,20 +169,20 @@ int pic32mz_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cm #endif #ifdef CONFIG_PIC32MZ_SPI4 -void pic32mz_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void pic32mz_spi4select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #warning "Missing logic" } -uint8_t pic32mz_spi4status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t pic32mz_spi4status(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Returning nothing\n"); #warning "Missing logic" return 0; } #ifdef CONFIG_SPI_CMDDATA -int pic32mz_spi4cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int pic32mz_spi4cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #warning "Missing logic" return 0; @@ -191,20 +191,20 @@ int pic32mz_spi4cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cm #endif #ifdef CONFIG_PIC32MZ_SPI5 -void pic32mz_spi5select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void pic32mz_spi5select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #warning "Missing logic" } -uint8_t pic32mz_spi5status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t pic32mz_spi5status(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Returning nothing\n"); #warning "Missing logic" return 0; } #ifdef CONFIG_SPI_CMDDATA -int pic32mz_spi5cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int pic32mz_spi5cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #warning "Missing logic" return 0; @@ -213,20 +213,20 @@ int pic32mz_spi5cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cm #endif #ifdef CONFIG_PIC32MZ_SPI6 -void pic32mz_spi6select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void pic32mz_spi6select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #warning "Missing logic" } -uint8_t pic32mz_spi6status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t pic32mz_spi6status(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Returning nothing\n"); #warning "Missing logic" return 0; } #ifdef CONFIG_SPI_CMDDATA -int pic32mz_spi6cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int pic32mz_spi6cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #warning "Missing logic" return 0; diff --git a/configs/sure-pic32mx/src/pic32mx_spi.c b/configs/sure-pic32mx/src/pic32mx_spi.c index 74671256ba..f0d5ed4575 100644 --- a/configs/sure-pic32mx/src/pic32mx_spi.c +++ b/configs/sure-pic32mx/src/pic32mx_spi.c @@ -174,7 +174,7 @@ void weak_function pic32mx_spidev_initialize(void) ************************************************************************************/ #ifdef CONFIG_PIC32MX_SPI2 -void pic32mx_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void pic32mx_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); @@ -195,7 +195,7 @@ void pic32mx_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool se #endif } -uint8_t pic32mx_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t pic32mx_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { uint8_t ret = 0; -- GitLab From 6d830f46e9c625ddb6a8447c41ecc29d00fa90fa Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Fri, 28 Apr 2017 18:29:43 +0200 Subject: [PATCH 625/990] nxp boards --- configs/lpcxpresso-lpc1115/src/lpc11_ssp.c | 8 ++++---- configs/lpcxpresso-lpc1768/src/lpc17_oled.c | 2 +- configs/lpcxpresso-lpc1768/src/lpc17_ssp.c | 8 ++++---- configs/mcu123-lpc214x/src/lpc2148_spi1.c | 12 ++++++------ configs/olimex-lpc-h3131/src/lpc31_spi.c | 4 ++-- configs/olimex-lpc1766stk/src/lpc17_ssp.c | 8 ++++---- configs/open1788/src/lpc17_ssp.c | 12 ++++++------ configs/u-blox-c027/src/lpc17_ssp.c | 8 ++++---- configs/zkit-arm-1769/src/lpc17_lcd.c | 2 +- configs/zkit-arm-1769/src/lpc17_spi.c | 6 +++--- configs/zkit-arm-1769/src/lpc17_ssp.c | 10 +++++----- configs/zp214xpa/src/lpc2148_spi1.c | 12 ++++++------ 12 files changed, 46 insertions(+), 46 deletions(-) diff --git a/configs/lpcxpresso-lpc1115/src/lpc11_ssp.c b/configs/lpcxpresso-lpc1115/src/lpc11_ssp.c index 0d7be5f71e..8803aaba79 100644 --- a/configs/lpcxpresso-lpc1115/src/lpc11_ssp.c +++ b/configs/lpcxpresso-lpc1115/src/lpc11_ssp.c @@ -130,7 +130,7 @@ void weak_function lpcxpresso_sspdev_initialize(void) ************************************************************************************/ #ifdef CONFIG_LPC17_SSP0 -void lpc11_ssp0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void lpc11_ssp0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); ssp_dumpgpio("lpc11_ssp0select() Entry"); @@ -140,7 +140,7 @@ void lpc11_ssp0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sel ssp_dumpgpio("lpc11_ssp0select() Exit"); } -uint8_t lpc11_ssp0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t lpc11_ssp0status(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Returning SPI_STATUS_PRESENT\n"); return SPI_STATUS_PRESENT; @@ -148,7 +148,7 @@ uint8_t lpc11_ssp0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #endif #ifdef CONFIG_LPC17_SSP1 -void lpc11_ssp1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void lpc11_ssp1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); ssp_dumpgpio("lpc11_ssp1select() Entry"); @@ -170,7 +170,7 @@ void lpc11_ssp1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sel ssp_dumpgpio("lpc11_ssp1select() Exit"); } -uint8_t lpc11_ssp1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t lpc11_ssp1status(FAR struct spi_dev_s *dev, uint32_t devid) { if (devid == SPIDEV_MMCSD) { diff --git a/configs/lpcxpresso-lpc1768/src/lpc17_oled.c b/configs/lpcxpresso-lpc1768/src/lpc17_oled.c index 063af42b2d..55280e9091 100644 --- a/configs/lpcxpresso-lpc1768/src/lpc17_oled.c +++ b/configs/lpcxpresso-lpc1768/src/lpc17_oled.c @@ -159,7 +159,7 @@ FAR struct lcd_dev_s *board_graphics_setup(unsigned int devno) * ****************************************************************************/ -int lpc17_ssp1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int lpc17_ssp1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { if (devid == SPIDEV_DISPLAY) { diff --git a/configs/lpcxpresso-lpc1768/src/lpc17_ssp.c b/configs/lpcxpresso-lpc1768/src/lpc17_ssp.c index c56ab46939..7411c9e16d 100644 --- a/configs/lpcxpresso-lpc1768/src/lpc17_ssp.c +++ b/configs/lpcxpresso-lpc1768/src/lpc17_ssp.c @@ -130,7 +130,7 @@ void weak_function lpcxpresso_sspdev_initialize(void) ************************************************************************************/ #ifdef CONFIG_LPC17_SSP0 -void lpc17_ssp0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void lpc17_ssp0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); ssp_dumpgpio("lpc17_ssp0select() Entry"); @@ -140,7 +140,7 @@ void lpc17_ssp0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sel ssp_dumpgpio("lpc17_ssp0select() Exit"); } -uint8_t lpc17_ssp0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t lpc17_ssp0status(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Returning SPI_STATUS_PRESENT\n"); return SPI_STATUS_PRESENT; @@ -148,7 +148,7 @@ uint8_t lpc17_ssp0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #endif #ifdef CONFIG_LPC17_SSP1 -void lpc17_ssp1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void lpc17_ssp1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); ssp_dumpgpio("lpc17_ssp1select() Entry"); @@ -170,7 +170,7 @@ void lpc17_ssp1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sel ssp_dumpgpio("lpc17_ssp1select() Exit"); } -uint8_t lpc17_ssp1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t lpc17_ssp1status(FAR struct spi_dev_s *dev, uint32_t devid) { if (devid == SPIDEV_MMCSD) { diff --git a/configs/mcu123-lpc214x/src/lpc2148_spi1.c b/configs/mcu123-lpc214x/src/lpc2148_spi1.c index 72f4b12ccb..bb9315dc2f 100644 --- a/configs/mcu123-lpc214x/src/lpc2148_spi1.c +++ b/configs/mcu123-lpc214x/src/lpc2148_spi1.c @@ -108,11 +108,11 @@ ****************************************************************************/ static int spi_lock(FAR struct spi_dev_s *dev, bool lock); -static void spi_select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); +static void spi_select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency); -static uint8_t spi_status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +static uint8_t spi_status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -static int spi_cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +static int spi_cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif static uint16_t spi_send(FAR struct spi_dev_s *dev, uint16_t ch); static void spi_sndblock(FAR struct spi_dev_s *dev, FAR const void *buffer, size_t nwords); @@ -210,7 +210,7 @@ static int spi_lock(FAR struct spi_dev_s *dev, bool lock) * ****************************************************************************/ -static void spi_select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +static void spi_select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { uint32_t bit = 1 << 20; @@ -301,7 +301,7 @@ static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency) * ****************************************************************************/ -static uint8_t spi_status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +static uint8_t spi_status(FAR struct spi_dev_s *dev, uint32_t devid) { /* I don't think there is anyway to determine these things on the mcu123.com * board. @@ -336,7 +336,7 @@ static uint8_t spi_status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) ****************************************************************************/ #ifdef CONFIG_SPI_CMDDATA -static int spi_cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +static int spi_cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { # error "spi_cmddata not implemented" return -ENOSYS; diff --git a/configs/olimex-lpc-h3131/src/lpc31_spi.c b/configs/olimex-lpc-h3131/src/lpc31_spi.c index c9e9c6eec5..d9b08ed3bd 100644 --- a/configs/olimex-lpc-h3131/src/lpc31_spi.c +++ b/configs/olimex-lpc-h3131/src/lpc31_spi.c @@ -99,13 +99,13 @@ void weak_function lpc31_spidev_intialize(void) * ************************************************************************************/ -void lpc31_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void lpc31_spiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #warning "Missing logic" } -uint8_t lpc31_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t lpc31_spistatus(FAR struct spi_dev_s *dev, uint32_t devid) { return SPI_STATUS_PRESENT; } diff --git a/configs/olimex-lpc1766stk/src/lpc17_ssp.c b/configs/olimex-lpc1766stk/src/lpc17_ssp.c index 7317a014b0..ebfa370d12 100644 --- a/configs/olimex-lpc1766stk/src/lpc17_ssp.c +++ b/configs/olimex-lpc1766stk/src/lpc17_ssp.c @@ -263,7 +263,7 @@ void weak_function lpc1766stk_sspdev_initialize(void) ************************************************************************************/ #ifdef CONFIG_LPC17_SSP0 -void lpc17_ssp0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void lpc17_ssp0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); if (devid == SPIDEV_DISPLAY) @@ -276,7 +276,7 @@ void lpc17_ssp0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sel } } -uint8_t lpc17_ssp0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t lpc17_ssp0status(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Returning nothing\n"); return 0; @@ -284,7 +284,7 @@ uint8_t lpc17_ssp0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #endif #ifdef CONFIG_LPC17_SSP1 -void lpc17_ssp1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void lpc17_ssp1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); if (devid == SPIDEV_MMCSD) @@ -297,7 +297,7 @@ void lpc17_ssp1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sel } } -uint8_t lpc17_ssp1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t lpc17_ssp1status(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Returning SPI_STATUS_PRESENT\n"); return SPI_STATUS_PRESENT; diff --git a/configs/open1788/src/lpc17_ssp.c b/configs/open1788/src/lpc17_ssp.c index 600b04474d..df354c770f 100644 --- a/configs/open1788/src/lpc17_ssp.c +++ b/configs/open1788/src/lpc17_ssp.c @@ -130,12 +130,12 @@ void weak_function open1788_sspdev_initialize(void) ************************************************************************************/ #ifdef CONFIG_LPC17_SSP0 -void lpc17_ssp0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void lpc17_ssp0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t lpc17_ssp0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t lpc17_ssp0status(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Returning nothing\n"); return 0; @@ -143,7 +143,7 @@ uint8_t lpc17_ssp0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #endif #ifdef CONFIG_LPC17_SSP1 -void lpc17_ssp1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void lpc17_ssp1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); if (devid == SPIDEV_TOUCHSCREEN) @@ -156,7 +156,7 @@ void lpc17_ssp1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sel } } -uint8_t lpc17_ssp1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t lpc17_ssp1status(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Returning nothing\n"); return 0; @@ -164,12 +164,12 @@ uint8_t lpc17_ssp1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #endif #ifdef CONFIG_LPC17_SSP2 -void lpc17_ssp2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void lpc17_ssp2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t lpc17_ssp2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t lpc17_ssp2status(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Returning nothing\n"); return 0; diff --git a/configs/u-blox-c027/src/lpc17_ssp.c b/configs/u-blox-c027/src/lpc17_ssp.c index 7090bcbb31..07533d055b 100644 --- a/configs/u-blox-c027/src/lpc17_ssp.c +++ b/configs/u-blox-c027/src/lpc17_ssp.c @@ -120,7 +120,7 @@ void weak_function c027_sspdev_initialize(void) ************************************************************************************/ #ifdef CONFIG_LPC17_SSP0 -void lpc17_ssp0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void lpc17_ssp0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); ssp_dumpgpio("lpc17_ssp0select() Entry"); @@ -130,7 +130,7 @@ void lpc17_ssp0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sel ssp_dumpgpio("lpc17_ssp0select() Exit"); } -uint8_t lpc17_ssp0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t lpc17_ssp0status(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Returning SPI_STATUS_PRESENT\n"); return SPI_STATUS_PRESENT; @@ -138,7 +138,7 @@ uint8_t lpc17_ssp0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #endif #ifdef CONFIG_LPC17_SSP1 -void lpc17_ssp1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void lpc17_ssp1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); ssp_dumpgpio("lpc17_ssp1select() Entry"); @@ -160,7 +160,7 @@ void lpc17_ssp1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sel ssp_dumpgpio("lpc17_ssp1select() Exit"); } -uint8_t lpc17_ssp1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t lpc17_ssp1status(FAR struct spi_dev_s *dev, uint32_t devid) { if (devid == SPIDEV_MMCSD) { diff --git a/configs/zkit-arm-1769/src/lpc17_lcd.c b/configs/zkit-arm-1769/src/lpc17_lcd.c index f029773169..db54027f3d 100644 --- a/configs/zkit-arm-1769/src/lpc17_lcd.c +++ b/configs/zkit-arm-1769/src/lpc17_lcd.c @@ -156,7 +156,7 @@ void board_lcd_uninitialize(void) * ****************************************************************************/ -int lpc17_ssp0cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int lpc17_ssp0cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { if (devid == SPIDEV_DISPLAY) { diff --git a/configs/zkit-arm-1769/src/lpc17_spi.c b/configs/zkit-arm-1769/src/lpc17_spi.c index 4418cb5bdf..c264ef403c 100644 --- a/configs/zkit-arm-1769/src/lpc17_spi.c +++ b/configs/zkit-arm-1769/src/lpc17_spi.c @@ -123,7 +123,7 @@ void weak_function zkit_spidev_initialize(void) * ************************************************************************************/ -void lpc17_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void lpc17_spiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); spi_dumpgpio("lpc17_spiselect() Entry"); @@ -138,7 +138,7 @@ void lpc17_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele spi_dumpgpio("lpc17_spiselect() Exit"); } -uint8_t lpc17_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t lpc17_spistatus(FAR struct spi_dev_s *dev, uint32_t devid) { if (devid == SPIDEV_MMCSD) { @@ -163,7 +163,7 @@ uint8_t lpc17_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid) * ****************************************************************************/ -int lpc17_spicmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int lpc17_spicmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } diff --git a/configs/zkit-arm-1769/src/lpc17_ssp.c b/configs/zkit-arm-1769/src/lpc17_ssp.c index 09cf3833c8..cc8ece694c 100644 --- a/configs/zkit-arm-1769/src/lpc17_ssp.c +++ b/configs/zkit-arm-1769/src/lpc17_ssp.c @@ -126,7 +126,7 @@ void weak_function zkit_sspdev_initialize(void) ************************************************************************************/ #ifdef CONFIG_LPC17_SSP1 -void lpc17_ssp1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void lpc17_ssp1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); ssp_dumpgpio("lpc17_ssp1select() Entry"); @@ -136,7 +136,7 @@ void lpc17_ssp1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sel ssp_dumpgpio("lpc17_ssp1select() Exit"); } -uint8_t lpc17_ssp1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t lpc17_ssp1status(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Returning SPI_STATUS_PRESENT\n"); return SPI_STATUS_PRESENT; @@ -151,7 +151,7 @@ uint8_t lpc17_ssp1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #ifdef CONFIG_SPI_CMDDATA int weak_function lpc17_ssp1cmddata(FAR struct spi_dev_s *dev, - enum spi_dev_e devid, bool cmd) + uint32_t devid, bool cmd) { return OK; } @@ -160,7 +160,7 @@ int weak_function lpc17_ssp1cmddata(FAR struct spi_dev_s *dev, #endif /* CONFIG_LPC17_SSP1 */ #ifdef CONFIG_LPC17_SSP0 -void lpc17_ssp0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void lpc17_ssp0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); ssp_dumpgpio("lpc17_ssp0select() Entry"); @@ -177,7 +177,7 @@ void lpc17_ssp0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sel ssp_dumpgpio("lpc17_ssp0select() Exit"); } -uint8_t lpc17_ssp0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t lpc17_ssp0status(FAR struct spi_dev_s *dev, uint32_t devid) { if (devid == SPIDEV_DISPLAY) { diff --git a/configs/zp214xpa/src/lpc2148_spi1.c b/configs/zp214xpa/src/lpc2148_spi1.c index 72110a423a..e9e2bc3a14 100644 --- a/configs/zp214xpa/src/lpc2148_spi1.c +++ b/configs/zp214xpa/src/lpc2148_spi1.c @@ -111,11 +111,11 @@ ****************************************************************************/ static int spi_lock(FAR struct spi_dev_s *dev, bool lock); -static void spi_select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); +static void spi_select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency); -static uint8_t spi_status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +static uint8_t spi_status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -static int spi_cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +static int spi_cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif static uint16_t spi_send(FAR struct spi_dev_s *dev, uint16_t ch); static void spi_sndblock(FAR struct spi_dev_s *dev, FAR const void *buffer, size_t nwords); @@ -213,7 +213,7 @@ static int spi_lock(FAR struct spi_dev_s *dev, bool lock) * ****************************************************************************/ -static void spi_select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +static void spi_select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { #ifdef CONFIG_DEBUG_SPI_INFO uint32_t regval; @@ -315,7 +315,7 @@ static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency) * ****************************************************************************/ -static uint8_t spi_status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +static uint8_t spi_status(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Return 0\n"); return 0; @@ -346,7 +346,7 @@ static uint8_t spi_status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) ****************************************************************************/ #ifdef CONFIG_SPI_CMDDATA -static int spi_cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +static int spi_cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #ifdef CONFIG_DEBUG_SPI_INFO uint32_t regval; -- GitLab From 68af2a9354fc0be7e568e5da401793dc7f9ba4ed Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Fri, 28 Apr 2017 18:30:23 +0200 Subject: [PATCH 626/990] more stm32 --- configs/clicker2-stm32/src/stm32_spi.c | 18 +++++++++--------- configs/cloudctrl/src/stm32_spi.c | 8 ++++---- configs/fire-stm32v2/src/stm32_spi.c | 8 ++++---- configs/hymini-stm32v/src/stm32_spi.c | 12 ++++++------ configs/mikroe-stm32f4/src/stm32_spi.c | 18 +++++++++--------- configs/olimex-stm32-p107/src/stm32_spi.c | 4 ++-- configs/olimexino-stm32/src/stm32_spi.c | 18 +++++++++--------- configs/shenzhou/src/stm32_spi.c | 8 ++++---- configs/spark/src/stm32_spi.c | 18 +++++++++--------- configs/viewtool-stm32f107/src/stm32_spi.c | 12 ++++++------ 10 files changed, 62 insertions(+), 62 deletions(-) diff --git a/configs/clicker2-stm32/src/stm32_spi.c b/configs/clicker2-stm32/src/stm32_spi.c index 9780fcdb42..1939c4c4c4 100644 --- a/configs/clicker2-stm32/src/stm32_spi.c +++ b/configs/clicker2-stm32/src/stm32_spi.c @@ -107,32 +107,32 @@ void weak_function stm32_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_STM32_SPI1 -void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32_SPI2 -void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); /* To be provided */ } -uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32_SPI3 -void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); @@ -149,7 +149,7 @@ void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele } } -uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } @@ -180,14 +180,14 @@ uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #ifdef CONFIG_SPI_CMDDATA #ifdef CONFIG_STM32_SPI1 -int stm32_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } #endif #ifdef CONFIG_STM32_SPI2 -int stm32_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { /* To be provided */ @@ -196,7 +196,7 @@ int stm32_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) #endif #ifdef CONFIG_STM32_SPI3 -int stm32_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { /* To be provided */ diff --git a/configs/cloudctrl/src/stm32_spi.c b/configs/cloudctrl/src/stm32_spi.c index 13054c3165..e64428bc4b 100644 --- a/configs/cloudctrl/src/stm32_spi.c +++ b/configs/cloudctrl/src/stm32_spi.c @@ -113,7 +113,7 @@ void weak_function stm32_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_STM32_SPI1 -void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); @@ -127,7 +127,7 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele } } -uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return SPI_STATUS_PRESENT; @@ -135,13 +135,13 @@ uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #endif #ifdef CONFIG_STM32_SPI3 -void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } diff --git a/configs/fire-stm32v2/src/stm32_spi.c b/configs/fire-stm32v2/src/stm32_spi.c index 8d28ceb07a..43ffb030b9 100644 --- a/configs/fire-stm32v2/src/stm32_spi.c +++ b/configs/fire-stm32v2/src/stm32_spi.c @@ -131,7 +131,7 @@ void weak_function stm32_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_STM32_SPI1 -void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); @@ -161,14 +161,14 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele #endif } -uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return SPI_STATUS_PRESENT; } #endif #ifdef CONFIG_STM32_SPI2 -void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); @@ -180,7 +180,7 @@ void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele } } -uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { return SPI_STATUS_PRESENT; } diff --git a/configs/hymini-stm32v/src/stm32_spi.c b/configs/hymini-stm32v/src/stm32_spi.c index 25f18c961e..3bd5b9a7e5 100644 --- a/configs/hymini-stm32v/src/stm32_spi.c +++ b/configs/hymini-stm32v/src/stm32_spi.c @@ -107,7 +107,7 @@ void stm32_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_STM32_SPI1 -void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); @@ -119,31 +119,31 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele } } -uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return SPI_STATUS_PRESENT; } #endif #ifdef CONFIG_STM32_SPI2 -void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { return SPI_STATUS_PRESENT; } #endif #ifdef CONFIG_STM32_SPI3 -void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) { return SPI_STATUS_PRESENT; } diff --git a/configs/mikroe-stm32f4/src/stm32_spi.c b/configs/mikroe-stm32f4/src/stm32_spi.c index 3831378ece..987bc2d450 100644 --- a/configs/mikroe-stm32f4/src/stm32_spi.c +++ b/configs/mikroe-stm32f4/src/stm32_spi.c @@ -121,7 +121,7 @@ void weak_function stm32_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_STM32_SPI3 -void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); @@ -162,7 +162,7 @@ void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele } } -uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) { uint8_t ret = 0; @@ -183,24 +183,24 @@ uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #endif #ifdef CONFIG_STM32_SPI2 -void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32_SPI1 -void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } @@ -231,21 +231,21 @@ uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #ifdef CONFIG_SPI_CMDDATA #ifdef CONFIG_STM32_SPI1 -int stm32_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } #endif #ifdef CONFIG_STM32_SPI2 -int stm32_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } #endif #ifdef CONFIG_STM32_SPI3 -int stm32_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } diff --git a/configs/olimex-stm32-p107/src/stm32_spi.c b/configs/olimex-stm32-p107/src/stm32_spi.c index 9a454cfcfa..ec1398542e 100644 --- a/configs/olimex-stm32-p107/src/stm32_spi.c +++ b/configs/olimex-stm32-p107/src/stm32_spi.c @@ -108,7 +108,7 @@ void weak_function stm32_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_STM32_SPI3 -void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); @@ -120,7 +120,7 @@ void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele } } -uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) { return SPI_STATUS_PRESENT; } diff --git a/configs/olimexino-stm32/src/stm32_spi.c b/configs/olimexino-stm32/src/stm32_spi.c index 249a3b39d8..672c104b72 100644 --- a/configs/olimexino-stm32/src/stm32_spi.c +++ b/configs/olimexino-stm32/src/stm32_spi.c @@ -107,7 +107,7 @@ void weak_function stm32_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_STM32_SPI1 -void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); if (devid == SPIDEV_USER) @@ -116,14 +116,14 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele } } -uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32_SPI2 -void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #if defined(CONFIG_MMCSD) @@ -134,7 +134,7 @@ void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele #endif } -uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { /* No switch on SD card socket so assume it is here */ @@ -143,12 +143,12 @@ uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #endif #ifdef CONFIG_STM32_SPI3 -void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } @@ -179,21 +179,21 @@ uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #ifdef CONFIG_SPI_CMDDATA #ifdef CONFIG_STM32_SPI1 -int stm32_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } #endif #ifdef CONFIG_STM32_SPI2 -int stm32_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } #endif #ifdef CONFIG_STM32_SPI3 -int stm32_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } diff --git a/configs/shenzhou/src/stm32_spi.c b/configs/shenzhou/src/stm32_spi.c index 1f6a45ed81..70d6753cc7 100644 --- a/configs/shenzhou/src/stm32_spi.c +++ b/configs/shenzhou/src/stm32_spi.c @@ -117,7 +117,7 @@ void weak_function stm32_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_STM32_SPI1 -void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); @@ -137,7 +137,7 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele } } -uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { /* The card detect pin is pulled up so that we detect the presence of a card * by see a low value on the input pin. @@ -153,7 +153,7 @@ uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #endif #ifdef CONFIG_STM32_SPI3 -void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); @@ -187,7 +187,7 @@ void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele } } -uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } diff --git a/configs/spark/src/stm32_spi.c b/configs/spark/src/stm32_spi.c index f631052d31..587ebeb8e3 100644 --- a/configs/spark/src/stm32_spi.c +++ b/configs/spark/src/stm32_spi.c @@ -116,19 +116,19 @@ void weak_function stm32_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_STM32_SPI1 -void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32_SPI2 -void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); @@ -151,20 +151,20 @@ void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele #endif } -uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32_SPI3 -void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } @@ -195,21 +195,21 @@ uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #ifdef CONFIG_SPI_CMDDATA #ifdef CONFIG_STM32_SPI1 -int stm32_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } #endif #ifdef CONFIG_STM32_SPI2 -int stm32_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } #endif #ifdef CONFIG_STM32_SPI3 -int stm32_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return OK; } diff --git a/configs/viewtool-stm32f107/src/stm32_spi.c b/configs/viewtool-stm32f107/src/stm32_spi.c index 3e8996f3af..7e35062acd 100644 --- a/configs/viewtool-stm32f107/src/stm32_spi.c +++ b/configs/viewtool-stm32f107/src/stm32_spi.c @@ -113,19 +113,19 @@ void weak_function stm32_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_STM32_SPI1 -void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32_SPI2 -void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); @@ -139,19 +139,19 @@ void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele #endif } -uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_STM32_SPI3 -void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); } -uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } -- GitLab From abc832272810ee654471416d186ba8964555cf18 Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Fri, 28 Apr 2017 18:31:10 +0200 Subject: [PATCH 627/990] more kinetis --- configs/kwikstik-k40/src/k40_spi.c | 12 ++++++------ configs/teensy-3.x/src/k20_spi.c | 12 ++++++------ configs/teensy-lc/src/kl_spi.c | 12 ++++++------ configs/twr-k60n512/src/k60_spi.c | 12 ++++++------ 4 files changed, 24 insertions(+), 24 deletions(-) diff --git a/configs/kwikstik-k40/src/k40_spi.c b/configs/kwikstik-k40/src/k40_spi.c index 43bb8db955..f9b554944b 100644 --- a/configs/kwikstik-k40/src/k40_spi.c +++ b/configs/kwikstik-k40/src/k40_spi.c @@ -97,13 +97,13 @@ void weak_function kinetis_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_KINETIS_SPI0 -void kinetis_spi0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void kinetis_spi0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); # warning "Missing logic" } -uint8_t kinetis_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t kinetis_spi0status(FAR struct spi_dev_s *dev, uint32_t devid) { # warning "Missing logic" return SPI_STATUS_PRESENT; @@ -111,13 +111,13 @@ uint8_t kinetis_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #endif #ifdef CONFIG_KINETIS_SPI1 -void kinetis_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void kinetis_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); # warning "Missing logic" } -uint8_t kinetis_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t kinetis_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { # warning "Missing logic" return SPI_STATUS_PRESENT; @@ -125,13 +125,13 @@ uint8_t kinetis_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #endif #ifdef CONFIG_KINETIS_SPI2 -void kinetis_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void kinetis_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); # warning "Missing logic" } -uint8_t kinetis_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t kinetis_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { # warning "Missing logic" return SPI_STATUS_PRESENT; diff --git a/configs/teensy-3.x/src/k20_spi.c b/configs/teensy-3.x/src/k20_spi.c index 3bcef38e55..b06603564a 100644 --- a/configs/teensy-3.x/src/k20_spi.c +++ b/configs/teensy-3.x/src/k20_spi.c @@ -97,13 +97,13 @@ void weak_function kinetis_spidev_initialize(void) ************************************************************************************/ #ifdef CONFIG_KINETIS_SPI0 -void kinetis_spi0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void kinetis_spi0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); # warning "Missing logic" } -uint8_t kinetis_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t kinetis_spi0status(FAR struct spi_dev_s *dev, uint32_t devid) { # warning "Missing logic" return SPI_STATUS_PRESENT; @@ -111,13 +111,13 @@ uint8_t kinetis_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #endif #ifdef CONFIG_KINETIS_SPI1 -void kinetis_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void kinetis_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); # warning "Missing logic" } -uint8_t kinetis_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t kinetis_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { # warning "Missing logic" return SPI_STATUS_PRESENT; @@ -125,13 +125,13 @@ uint8_t kinetis_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #endif #ifdef CONFIG_KINETIS_SPI2 -void kinetis_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void kinetis_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); # warning "Missing logic" } -uint8_t kinetis_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t kinetis_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { # warning "Missing logic" return SPI_STATUS_PRESENT; diff --git a/configs/teensy-lc/src/kl_spi.c b/configs/teensy-lc/src/kl_spi.c index b4d36cb755..efd1c96ce3 100644 --- a/configs/teensy-lc/src/kl_spi.c +++ b/configs/teensy-lc/src/kl_spi.c @@ -130,7 +130,7 @@ void weak_function kl_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_KL_SPI0 -void kl_spi0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void kl_spi0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", @@ -139,7 +139,7 @@ void kl_spi0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, #endif #ifdef CONFIG_KL_SPI1 -void kl_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void kl_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", @@ -162,14 +162,14 @@ void kl_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, ****************************************************************************/ #ifdef CONFIG_KL_SPI0 -uint8_t kl_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t kl_spi0status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #endif #ifdef CONFIG_KL_SPI1 -uint8_t kl_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t kl_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } @@ -194,14 +194,14 @@ uint8_t kl_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #ifdef CONFIG_SPI_CMDDATA #ifdef CONFIG_KL_SPI0 -int kl_spi0cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int kl_spi0cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return 0; } #endif #ifdef CONFIG_KL_SPI1 -int kl_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int kl_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return 0; } diff --git a/configs/twr-k60n512/src/k60_spi.c b/configs/twr-k60n512/src/k60_spi.c index 92e3649000..cdbc1a034a 100644 --- a/configs/twr-k60n512/src/k60_spi.c +++ b/configs/twr-k60n512/src/k60_spi.c @@ -97,13 +97,13 @@ void weak_function kinetis_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_KINETIS_SPI0 -void kinetis_spi0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void kinetis_spi0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); # warning "Missing logic" } -uint8_t kinetis_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t kinetis_spi0status(FAR struct spi_dev_s *dev, uint32_t devid) { # warning "Missing logic" return SPI_STATUS_PRESENT; @@ -111,13 +111,13 @@ uint8_t kinetis_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #endif #ifdef CONFIG_KINETIS_SPI1 -void kinetis_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void kinetis_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); # warning "Missing logic" } -uint8_t kinetis_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t kinetis_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { # warning "Missing logic" return SPI_STATUS_PRESENT; @@ -125,13 +125,13 @@ uint8_t kinetis_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #endif #ifdef CONFIG_KINETIS_SPI2 -void kinetis_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void kinetis_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); # warning "Missing logic" } -uint8_t kinetis_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t kinetis_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { # warning "Missing logic" return SPI_STATUS_PRESENT; -- GitLab From b78137049cdf238ee744755587ac6202daf58bed Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Fri, 28 Apr 2017 18:31:44 +0200 Subject: [PATCH 628/990] Final batch --- configs/arduino-due/src/sam_mmcsd.c | 12 ++++++------ configs/arduino-due/src/sam_touchscreen.c | 12 ++++++------ configs/demo9s12ne64/src/m9s12_spi.c | 4 ++-- configs/ea3131/src/lpc31_spi.c | 4 ++-- configs/ea3152/src/lpc31_spi.c | 4 ++-- configs/eagle100/src/lm_ssi.c | 4 ++-- configs/ekk-lm3s9b96/src/lm_ssi.c | 4 ++-- configs/maple/src/stm32_spi.c | 12 ++++++------ configs/mirtoo/src/pic32_spi2.c | 8 ++++---- configs/ne64badge/src/m9s12_spi.c | 4 ++-- configs/olimex-strp711/src/str71_spi.c | 12 ++++++------ configs/teensy-2.0/src/at90usb_spi.c | 4 ++-- 12 files changed, 42 insertions(+), 42 deletions(-) diff --git a/configs/arduino-due/src/sam_mmcsd.c b/configs/arduino-due/src/sam_mmcsd.c index b7556ea082..bd60005f84 100644 --- a/configs/arduino-due/src/sam_mmcsd.c +++ b/configs/arduino-due/src/sam_mmcsd.c @@ -109,11 +109,11 @@ * Private Function Prototypes ****************************************************************************/ -static void spi_select(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid, +static void spi_select(FAR struct spi_bitbang_s *priv, uint32_t devid, bool selected); -static uint8_t spi_status(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid); +static uint8_t spi_status(FAR struct spi_bitbang_s *priv, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -static int spi_cmddata(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid, +static int spi_cmddata(FAR struct spi_bitbang_s *priv, uint32_t devid, bool cmd); #endif @@ -142,7 +142,7 @@ static int spi_cmddata(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid, * ****************************************************************************/ -static void spi_select(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid, +static void spi_select(FAR struct spi_bitbang_s *priv, uint32_t devid, bool selected) { if (devid == SPIDEV_MMCSD) @@ -173,7 +173,7 @@ static void spi_select(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid, * ****************************************************************************/ -static uint8_t spi_status(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid) +static uint8_t spi_status(FAR struct spi_bitbang_s *priv, uint32_t devid) { if (devid == SPIDEV_MMCSD) { @@ -200,7 +200,7 @@ static uint8_t spi_status(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid) ****************************************************************************/ #ifdef CONFIG_SPI_CMDDATA -static int spi_cmddata(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid, +static int spi_cmddata(FAR struct spi_bitbang_s *priv, uint32_t devid, bool cmd) { return OK; diff --git a/configs/arduino-due/src/sam_touchscreen.c b/configs/arduino-due/src/sam_touchscreen.c index b93aa11f68..4e78c9376a 100644 --- a/configs/arduino-due/src/sam_touchscreen.c +++ b/configs/arduino-due/src/sam_touchscreen.c @@ -121,11 +121,11 @@ ****************************************************************************/ /* Lower-half SPI */ -static void spi_select(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid, +static void spi_select(FAR struct spi_bitbang_s *priv, uint32_t devid, bool selected); -static uint8_t spi_status(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid); +static uint8_t spi_status(FAR struct spi_bitbang_s *priv, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -static int spi_cmddata(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid, +static int spi_cmddata(FAR struct spi_bitbang_s *priv, uint32_t devid, bool cmd); #endif @@ -198,7 +198,7 @@ static struct ads7843e_config_s g_tscinfo = * ****************************************************************************/ -static void spi_select(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid, +static void spi_select(FAR struct spi_bitbang_s *priv, uint32_t devid, bool selected) { /* The touchscreen controller is always selected */ @@ -219,7 +219,7 @@ static void spi_select(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid, * ****************************************************************************/ -static uint8_t spi_status(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid) +static uint8_t spi_status(FAR struct spi_bitbang_s *priv, uint32_t devid) { return 0; } @@ -241,7 +241,7 @@ static uint8_t spi_status(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid) ****************************************************************************/ #ifdef CONFIG_SPI_CMDDATA -static int spi_cmddata(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid, +static int spi_cmddata(FAR struct spi_bitbang_s *priv, uint32_t devid, bool cmd) { return OK; diff --git a/configs/demo9s12ne64/src/m9s12_spi.c b/configs/demo9s12ne64/src/m9s12_spi.c index e296ee5595..a869975170 100644 --- a/configs/demo9s12ne64/src/m9s12_spi.c +++ b/configs/demo9s12ne64/src/m9s12_spi.c @@ -91,11 +91,11 @@ void weak_function hcs12_spidev_initialize(void) * ****************************************************************************/ -void hcs12_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void hcs12_spiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { } -uint8_t hcs12_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t hcs12_spistatus(FAR struct spi_dev_s *dev, uint32_t devid) { return SPI_STATUS_PRESENT; } diff --git a/configs/ea3131/src/lpc31_spi.c b/configs/ea3131/src/lpc31_spi.c index 74914bdce6..b476b11ea9 100644 --- a/configs/ea3131/src/lpc31_spi.c +++ b/configs/ea3131/src/lpc31_spi.c @@ -99,13 +99,13 @@ void weak_function lpc31_spidev_intialize(void) * ************************************************************************************/ -void lpc31_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void lpc31_spiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #warning "Missing logic" } -uint8_t lpc31_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t lpc31_spistatus(FAR struct spi_dev_s *dev, uint32_t devid) { return SPI_STATUS_PRESENT; } diff --git a/configs/ea3152/src/lpc31_spi.c b/configs/ea3152/src/lpc31_spi.c index 0995794a0f..02bf6a71fc 100644 --- a/configs/ea3152/src/lpc31_spi.c +++ b/configs/ea3152/src/lpc31_spi.c @@ -99,13 +99,13 @@ void weak_function lpc31_spidev_intialize(void) * ************************************************************************************/ -void lpc31_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void lpc31_spiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #warning "Missing logic" } -uint8_t lpc31_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t lpc31_spistatus(FAR struct spi_dev_s *dev, uint32_t devid) { return SPI_STATUS_PRESENT; } diff --git a/configs/eagle100/src/lm_ssi.c b/configs/eagle100/src/lm_ssi.c index 7befb1f87d..b6722c2ba1 100644 --- a/configs/eagle100/src/lm_ssi.c +++ b/configs/eagle100/src/lm_ssi.c @@ -107,7 +107,7 @@ void weak_function lm_ssidev_initialize(void) * ****************************************************************************/ -void tiva_ssiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void tiva_ssiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); if (devid == SPIDEV_MMCSD) @@ -120,7 +120,7 @@ void tiva_ssiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool select } } -uint8_t tiva_ssistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t tiva_ssistatus(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Returning SPI_STATUS_PRESENT\n"); return SPI_STATUS_PRESENT; diff --git a/configs/ekk-lm3s9b96/src/lm_ssi.c b/configs/ekk-lm3s9b96/src/lm_ssi.c index 911e923e84..05dbf37b5e 100644 --- a/configs/ekk-lm3s9b96/src/lm_ssi.c +++ b/configs/ekk-lm3s9b96/src/lm_ssi.c @@ -107,7 +107,7 @@ void weak_function lm_ssidev_initialize(void) * ****************************************************************************/ -void tiva_ssiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void tiva_ssiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); ssi_dumpgpio("tiva_ssiselect() Entry"); @@ -128,7 +128,7 @@ void tiva_ssiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool select ssi_dumpgpio("tiva_ssiselect() Exit"); } -uint8_t tiva_ssistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t tiva_ssistatus(FAR struct spi_dev_s *dev, uint32_t devid) { spiinfo("Returning SPI_STATUS_PRESENT\n"); return SPI_STATUS_PRESENT; diff --git a/configs/maple/src/stm32_spi.c b/configs/maple/src/stm32_spi.c index 95040a67bf..a1c9ac3fcc 100644 --- a/configs/maple/src/stm32_spi.c +++ b/configs/maple/src/stm32_spi.c @@ -104,7 +104,7 @@ void weak_function stm32_spidev_initialize(void) ****************************************************************************/ #ifdef CONFIG_STM32_SPI1 -void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); @@ -117,29 +117,29 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, # endif } -uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } -int stm32_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } #endif #ifdef CONFIG_STM32_SPI2 -void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, +void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { } -uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } -int stm32_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int stm32_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return -ENODEV; } diff --git a/configs/mirtoo/src/pic32_spi2.c b/configs/mirtoo/src/pic32_spi2.c index 3c1d513b83..6773995cdb 100644 --- a/configs/mirtoo/src/pic32_spi2.c +++ b/configs/mirtoo/src/pic32_spi2.c @@ -154,9 +154,9 @@ void weak_function pic32mx_spi2initialize(void) ************************************************************************************/ struct spi_dev_s; -enum spi_dev_e; +uint32_t; -void pic32mx_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void pic32mx_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); @@ -170,13 +170,13 @@ void pic32mx_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool s } } -uint8_t pic32mx_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t pic32mx_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) { return 0; } #ifdef CONFIG_SPI_CMDDATA -int pic32mx_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +int pic32mx_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { return 0; } diff --git a/configs/ne64badge/src/m9s12_spi.c b/configs/ne64badge/src/m9s12_spi.c index 1539d0ca47..760ebf4c1d 100644 --- a/configs/ne64badge/src/m9s12_spi.c +++ b/configs/ne64badge/src/m9s12_spi.c @@ -91,11 +91,11 @@ void weak_function hcs12_spidev_initialize(void) * ****************************************************************************/ -void hcs12_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void hcs12_spiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { } -uint8_t hcs12_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t hcs12_spistatus(FAR struct spi_dev_s *dev, uint32_t devid) { return SPI_STATUS_PRESENT; } diff --git a/configs/olimex-strp711/src/str71_spi.c b/configs/olimex-strp711/src/str71_spi.c index f14df15033..e4d27894ee 100644 --- a/configs/olimex-strp711/src/str71_spi.c +++ b/configs/olimex-strp711/src/str71_spi.c @@ -400,11 +400,11 @@ static inline void spi_drain(FAR struct str71x_spidev_s *priv); /* SPI methods */ static int spi_lock(FAR struct spi_dev_s *dev, bool lock); -static void spi_select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); +static void spi_select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency); -static uint8_t spi_status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +static uint8_t spi_status(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA -static int spi_cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +static int spi_cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); #endif static uint16_t spi_send(FAR struct spi_dev_s *dev, uint16_t wd); static void spi_sndblock(FAR struct spi_dev_s *dev, FAR const void *buffer, size_t buflen); @@ -608,7 +608,7 @@ static int spi_lock(FAR struct spi_dev_s *dev, bool lock) * ****************************************************************************/ -static void spi_select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +static void spi_select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { FAR struct str71x_spidev_s *priv = (FAR struct str71x_spidev_s *)dev; uint16_t reg16; @@ -713,7 +713,7 @@ static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency) * ****************************************************************************/ -static uint8_t spi_status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +static uint8_t spi_status(FAR struct spi_dev_s *dev, uint32_t devid) { uint8_t ret = 0; uint16_t reg16 = getreg16(STR71X_GPIO1_PD); @@ -756,7 +756,7 @@ static uint8_t spi_status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) ****************************************************************************/ #ifdef CONFIG_SPI_CMDDATA -static int spi_cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +static int spi_cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { # error "spi_cmddata not implemented" return -ENOSYS; diff --git a/configs/teensy-2.0/src/at90usb_spi.c b/configs/teensy-2.0/src/at90usb_spi.c index 6c55945b3d..db301389b9 100644 --- a/configs/teensy-2.0/src/at90usb_spi.c +++ b/configs/teensy-2.0/src/at90usb_spi.c @@ -136,7 +136,7 @@ void weak_function at90usb_spidev_initialize(void) * ************************************************************************************/ -void avr_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void avr_spiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); @@ -152,7 +152,7 @@ void avr_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool select } } -uint8_t avr_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t avr_spistatus(FAR struct spi_dev_s *dev, uint32_t devid) { uint8_t ret = 0; uint8_t regval = PINB; -- GitLab From e3d865f6c2401e2d12a437dbff2ca72511dc46d1 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 28 Apr 2017 11:02:54 -0600 Subject: [PATCH 629/990] In last changed to poll(),cConverted timeout to unsigned to eliminate the possibility of overflow of signed overflow. --- fs/vfs/fs_poll.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/fs/vfs/fs_poll.c b/fs/vfs/fs_poll.c index c828890210..55160d7faa 100644 --- a/fs/vfs/fs_poll.c +++ b/fs/vfs/fs_poll.c @@ -401,10 +401,10 @@ int poll(FAR struct pollfd *fds, nfds_t nfds, int timeout) #if (MSEC_PER_TICK * USEC_PER_MSEC) != USEC_PER_TICK && \ defined(CONFIG_HAVE_LONG_LONG) - ticks = ((long long)timeout * USEC_PER_MSEC) + (USEC_PER_TICK - 1) / + ticks = ((unsigned long long)timeout * USEC_PER_MSEC) + (USEC_PER_TICK - 1) / USEC_PER_TICK; #else - ticks = (timeout + (MSEC_PER_TICK - 1)) / MSEC_PER_TICK; + ticks = ((unsigned int)timeout + (MSEC_PER_TICK - 1)) / MSEC_PER_TICK; #endif /* Either wait for either a poll event(s), for a signal to occur, -- GitLab From 6680eb0e0c4eacba12e1676d35769272d45e70bf Mon Sep 17 00:00:00 2001 From: Simon Piriou Date: Fri, 28 Apr 2017 19:20:23 +0200 Subject: [PATCH 630/990] netdev: fix compilation errors --- net/netdev/netdev_unregister.c | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/net/netdev/netdev_unregister.c b/net/netdev/netdev_unregister.c index 57c6754a7c..b41784ee3c 100644 --- a/net/netdev/netdev_unregister.c +++ b/net/netdev/netdev_unregister.c @@ -128,10 +128,12 @@ int netdev_unregister(FAR struct net_driver_s *dev) #ifdef CONFIG_NET_ETHERNET ninfo("Unregistered MAC: %02x:%02x:%02x:%02x:%02x:%02x as dev: %s\n", - dev->d_mac.ether_addr_octet[0], dev->d_mac.ether_addr_octet[1], - dev->d_mac.ether_addr_octet[2], dev->d_mac.ether_addr_octet[3], - dev->d_mac.ether_addr_octet[4], dev->d_mac.ether_addr_octet[5], - dev->d_ifname); + dev->d_mac.ether.ether_addr_octet[0], + dev->d_mac.ether.ether_addr_octet[1], + dev->d_mac.ether.ether_addr_octet[2], + dev->d_mac.ether.ether_addr_octet[3], + dev->d_mac.ether.ether_addr_octet[4], + dev->d_mac.ether.ether_addr_octet[5], dev->d_ifname); #else ninfo("Registered dev: %s\n", dev->d_ifname); #endif -- GitLab From 0d1a79719a3d992c09e9584cd7072cc64bb43ffb Mon Sep 17 00:00:00 2001 From: Simon Piriou Date: Fri, 28 Apr 2017 19:28:29 +0200 Subject: [PATCH 631/990] bcmf: add escan ioctls support + cleanup --- configs/photon/wlan/defconfig | 2 +- drivers/wireless/ieee80211/Make.defs | 1 + drivers/wireless/ieee80211/bcmf_bdc.c | 243 +++++++++++ drivers/wireless/ieee80211/bcmf_bdc.h | 86 ++++ drivers/wireless/ieee80211/bcmf_cdc.c | 108 ++--- drivers/wireless/ieee80211/bcmf_cdc.h | 15 +- drivers/wireless/ieee80211/bcmf_driver.c | 432 ++++++++++++++------ drivers/wireless/ieee80211/bcmf_driver.h | 24 +- drivers/wireless/ieee80211/bcmf_ioctl.h | 307 +++++++++++++- drivers/wireless/ieee80211/bcmf_netdev.c | 37 +- drivers/wireless/ieee80211/bcmf_sdio.c | 1 + drivers/wireless/ieee80211/bcmf_sdio_core.h | 7 + drivers/wireless/ieee80211/bcmf_sdio_regs.h | 23 +- drivers/wireless/ieee80211/bcmf_sdpcm.c | 36 +- drivers/wireless/ieee80211/bcmf_utils.h | 12 + 15 files changed, 1097 insertions(+), 237 deletions(-) create mode 100644 drivers/wireless/ieee80211/bcmf_bdc.c create mode 100644 drivers/wireless/ieee80211/bcmf_bdc.h diff --git a/configs/photon/wlan/defconfig b/configs/photon/wlan/defconfig index ca7cd23619..190a639960 100644 --- a/configs/photon/wlan/defconfig +++ b/configs/photon/wlan/defconfig @@ -1003,7 +1003,7 @@ CONFIG_NET_ETHERNET=y # # Network Device Operations # -# CONFIG_NETDEV_IOCTL is not set +CONFIG_NETDEV_IOCTL=y # CONFIG_NETDEV_PHY_IOCTL is not set CONFIG_NETDEV_WIRELESS_IOCTL=y diff --git a/drivers/wireless/ieee80211/Make.defs b/drivers/wireless/ieee80211/Make.defs index 0586e423da..0df7f9ef8b 100644 --- a/drivers/wireless/ieee80211/Make.defs +++ b/drivers/wireless/ieee80211/Make.defs @@ -43,6 +43,7 @@ ifeq ($(CONFIG_DRIVERS_IEEE80211),y) ifeq ($(CONFIG_IEEE80211_BROADCOM_FULLMAC),y) CSRCS += bcmf_driver.c CSRCS += bcmf_cdc.c + CSRCS += bcmf_bdc.c CSRCS += bcmf_utils.c CSRCS += bcmf_netdev.c diff --git a/drivers/wireless/ieee80211/bcmf_bdc.c b/drivers/wireless/ieee80211/bcmf_bdc.c new file mode 100644 index 0000000000..8f448e5bc0 --- /dev/null +++ b/drivers/wireless/ieee80211/bcmf_bdc.c @@ -0,0 +1,243 @@ +/**************************************************************************** + * drivers/wireless/ieee80211/bcmf_bdc.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Simon Piriou + * + * 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 "bcmf_driver.h" +#include "bcmf_ioctl.h" +#include "bcmf_cdc.h" +#include "bcmf_bdc.h" +#include "bcmf_utils.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define BCMF_EVENT_ETHER_TYPE 0x6C88 /* Ether type of event frames */ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct __attribute__((packed)) bcmf_bdc_header +{ + uint8_t flags; /* bdc frame flags */ + uint8_t priority; /* bdc frame priority */ + uint8_t flags2; /* bdc frame additionnal flags */ + uint8_t data_offset; /* Offset from end of header to payload data */ +}; + +struct __attribute__((packed)) bcmf_eth_header +{ + uint16_t type; /* Vendor specific type */ + uint16_t len; /* Event data length */ + uint8_t version; /* Protocol version */ + uint8_t oui[3]; /* Organizationally unique identifier */ + uint16_t usr_type; /* User specific type */ +}; + +struct __attribute__((packed)) bcmf_event_msg +{ + struct ether_header eth; + struct bcmf_eth_header bcm_eth; + struct bcmf_event_s event; + uint8_t data[0]; +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const uint8_t bcmf_broadcom_oui[] = {0x00, 0x10, 0x18}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +struct bcmf_frame_s* bcmf_bdc_allocate_frame(FAR struct bcmf_dev_s *priv, + uint32_t len, bool block) +{ + if (len <= 0) + { + return NULL; + } + + /* Allocate data frame */ + + return priv->bus->allocate_frame(priv, + sizeof(struct bcmf_bdc_header) + len, + false, block); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +int bcmf_bdc_process_data_frame(FAR struct bcmf_dev_s *priv, + struct bcmf_frame_s *frame) +{ + wlinfo("Data message\n"); + bcmf_hexdump(frame->base, frame->len, (unsigned long)frame->base); + return OK; +} + +int bcmf_bdc_process_event_frame(FAR struct bcmf_dev_s *priv, + struct bcmf_frame_s *frame) +{ + int data_size; + struct bcmf_bdc_header *header; + struct bcmf_event_msg *event_msg; + uint32_t event_id; + event_handler_t handler; + + /* Check frame header */ + + data_size = frame->len - (int)(frame->data - frame->base); + + if (data_size < sizeof(struct bcmf_bdc_header)) + { + goto exit_invalid_frame; + } + + header = (struct bcmf_bdc_header*)frame->data; + + data_size -= sizeof(struct bcmf_bdc_header) + header->data_offset; + + if (data_size < sizeof(struct bcmf_event_msg)) + { + goto exit_invalid_frame; + } + + data_size -= sizeof(struct ether_header) + sizeof(struct bcmf_eth_header); + + /* Check ethernet header */ + + event_msg = (struct bcmf_event_msg*)(frame->data + + sizeof(struct bcmf_bdc_header) + + header->data_offset); + + if (event_msg->eth.ether_type != BCMF_EVENT_ETHER_TYPE || + memcmp(event_msg->bcm_eth.oui, bcmf_broadcom_oui, 3)) + { + goto exit_invalid_frame; + } + + event_id = bcmf_getle32(&event_msg->event.type); + + if (event_id >= BCMF_EVENT_COUNT) + { + wlinfo("Invalid event id %d\n", event_id); + return -EINVAL; + } + + /* Dispatch event to registered handler */ + + handler = priv->event_handlers[event_id]; + if (handler != NULL) + { + handler(priv, &event_msg->event, data_size); + } + + return OK; + +exit_invalid_frame: + wlerr("Invalid event frame\n"); + bcmf_hexdump(frame->base, frame->len, (unsigned long)frame->base); + return -EINVAL; +} + +int bcmf_event_register(FAR struct bcmf_dev_s *priv, event_handler_t handler, + unsigned int event_id) +{ + if (event_id >= BCMF_EVENT_COUNT) + { + /* Invalid event id */ + + return -EINVAL; + } + + priv->event_handlers[event_id] = handler; + return OK; +} + +int bcmf_event_unregister(FAR struct bcmf_dev_s *priv, + unsigned int event_id) +{ + return bcmf_event_register(priv, NULL, event_id); +} + +int bcmf_event_push_config(FAR struct bcmf_dev_s *priv) +{ + int i; + uint32_t out_len; + uint8_t event_mask[(BCMF_EVENT_COUNT+7)>>3]; + + memset(event_mask, 0, sizeof(event_mask)); + + for (i=0; ievent_handlers[i] != NULL) + { + event_mask[i>>3] |= 1 << (i & 0x7); + } + } + + /* Send event mask to chip */ + + out_len = sizeof(event_mask); + if (bcmf_cdc_iovar_request(priv, CHIP_STA_INTERFACE, true, + IOVAR_STR_EVENT_MSGS, event_mask, + &out_len)) + { + return -EIO; + } + + return OK; +} \ No newline at end of file diff --git a/drivers/wireless/ieee80211/bcmf_bdc.h b/drivers/wireless/ieee80211/bcmf_bdc.h new file mode 100644 index 0000000000..93e0b6c707 --- /dev/null +++ b/drivers/wireless/ieee80211/bcmf_bdc.h @@ -0,0 +1,86 @@ +/**************************************************************************** + * drivers/wireless/ieee80211/bcmf_bdc.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Simon Piriou + * + * 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 + ****************************************************************************/ + +#ifndef __DRIVERS_WIRELESS_IEEE80211_BCMF_BDC_H +#define __DRIVERS_WIRELESS_IEEE80211_BCMF_BDC_H + +#include "bcmf_driver.h" +#include "bcmf_ioctl.h" + +/* Event frame content */ + +struct __attribute__((packed)) bcmf_event_s +{ + uint16_t version; /* Vendor specific type */ + uint16_t flags; + uint32_t type; /* Id of received event */ + uint32_t status; /* Event status code */ + uint32_t reason; /* Reason code */ + uint32_t auth_type; + uint32_t len; /* Data size following this header */ + struct ether_addr addr; /* AP MAC address */ + char src_name[16]; /* Event source interface name */ + uint8_t dst_id; /* Event destination interface id */ + uint8_t bss_cfg_id; +}; + +/* Event callback handler */ + +typedef void (*event_handler_t)(FAR struct bcmf_dev_s *priv, + struct bcmf_event_s *event, unsigned int len); + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +int bcmf_bdc_process_data_frame(FAR struct bcmf_dev_s *priv, + struct bcmf_frame_s *frame); + +int bcmf_bdc_process_event_frame(FAR struct bcmf_dev_s *priv, + struct bcmf_frame_s *frame); + +int bcmf_event_register(FAR struct bcmf_dev_s *priv, event_handler_t handler, + unsigned int event_id); + +int bcmf_event_unregister(FAR struct bcmf_dev_s *priv, + unsigned int event_id); + +int bcmf_event_push_config(FAR struct bcmf_dev_s *priv); + +#endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_BDC_H */ \ No newline at end of file diff --git a/drivers/wireless/ieee80211/bcmf_cdc.c b/drivers/wireless/ieee80211/bcmf_cdc.c index 79a8f05030..bff79328e8 100644 --- a/drivers/wireless/ieee80211/bcmf_cdc.c +++ b/drivers/wireless/ieee80211/bcmf_cdc.c @@ -56,28 +56,24 @@ * Pre-processor Definitions ****************************************************************************/ -/* CDC flag definitions */ -#define CDC_DCMD_ERROR 0x01 /* 1=cmd failed */ -#define CDC_DCMD_SET 0x02 /* 0=get, 1=set cmd */ -#define CDC_DCMD_IF_MASK 0xF000 /* I/F index */ -#define CDC_DCMD_IF_SHIFT 12 -#define CDC_DCMD_ID_MASK 0xFFFF0000 /* id an cmd pairing */ -#define CDC_DCMD_ID_SHIFT 16 /* ID Mask shift bits */ -#define CDC_DCMD_ID(flags) \ - (((flags) & CDC_DCMD_ID_MASK) >> CDC_DCMD_ID_SHIFT) - -#define CDC_CONTROL_TIMEOUT_MS 1000 +/* Control header flags */ + +#define BCMF_CONTROL_ERROR 0x01 /* Command failure flag */ +#define BCMF_CONTROL_SET 0x02 /* Command type: SET = 1, GET = 0 */ +#define BCMF_CONTROL_INTERFACE_SHIFT 12 +#define BCMF_CONTROL_REQID_SHIFT 16 + +#define BCMF_CONTROL_TIMEOUT_MS 1000 /**************************************************************************** * Private Types ****************************************************************************/ -struct bcmf_cdc_header { - uint32_t cmd; /* dongle command value */ - uint32_t len; /* lower 16: output buflen; - * upper 16: input buflen (excludes header) */ - uint32_t flags; /* flag defns given below */ - uint32_t status; /* status code returned from the device */ +struct __attribute__((packed)) bcmf_cdc_header { + uint32_t cmd; /* Command to be sent */ + uint32_t len; /* Size of command data */ + uint32_t flags; /* cdc request flags, see above */ + uint32_t status; /* Returned status code from chip */ }; /**************************************************************************** @@ -95,6 +91,10 @@ static int bcmf_cdc_control_request(FAR struct bcmf_dev_s *priv, uint32_t ifidx, bool set, uint32_t cmd, char *name, uint8_t *data, uint32_t *len); +static int bcmf_cdc_control_request_unsafe(FAR struct bcmf_dev_s *priv, + uint32_t ifidx, bool set, uint32_t cmd, + char *name, uint8_t *data, uint32_t *len); + /**************************************************************************** * Private Data ****************************************************************************/ @@ -161,21 +161,21 @@ int bcmf_cdc_sendframe(FAR struct bcmf_dev_s *priv, uint32_t cmd, struct bcmf_cdc_header* header = (struct bcmf_cdc_header*)frame->data; - /* Setup cdc_dcmd header */ + /* Setup control frame header */ uint32_t cdc_data_len = frame->len - (uint32_t)(frame->data-frame->base); header->cmd = cmd; header->len = cdc_data_len-sizeof(struct bcmf_cdc_header); header->status = 0; - header->flags = ++priv->control_reqid << CDC_DCMD_ID_SHIFT; - header->flags |= ifidx << CDC_DCMD_IF_SHIFT; + header->flags = ++priv->control_reqid << BCMF_CONTROL_REQID_SHIFT; + header->flags |= ifidx << BCMF_CONTROL_INTERFACE_SHIFT; if (set) { - header->flags |= CDC_DCMD_SET; + header->flags |= BCMF_CONTROL_SET; } - /* Queue frame */ + /* Send frame */ return priv->bus->txframe(priv, frame); } @@ -185,10 +185,6 @@ int bcmf_cdc_control_request(FAR struct bcmf_dev_s *priv, char *name, uint8_t *data, uint32_t *len) { int ret; - struct bcmf_frame_s *frame; - uint32_t out_len = *len; - - *len = 0; /* Take device control mutex */ @@ -197,14 +193,31 @@ int bcmf_cdc_control_request(FAR struct bcmf_dev_s *priv, return ret; } + ret = bcmf_cdc_control_request_unsafe(priv, ifidx, set, cmd, + name, data, len); + + sem_post(&priv->control_mutex); + + return ret; +} + +int bcmf_cdc_control_request_unsafe(FAR struct bcmf_dev_s *priv, + uint32_t ifidx, bool set, uint32_t cmd, + char *name, uint8_t *data, uint32_t *len) +{ + int ret; + struct bcmf_frame_s *frame; + uint32_t out_len = *len; + + *len = 0; + /* Prepare control frame */ frame = bcmf_cdc_allocate_frame(priv, name, data, out_len); if (!frame) { wlerr("Cannot allocate cdc frame\n"); - ret = -ENOMEM; - goto exit_sem_post; + return -ENOMEM; } /* Setup buffer to store response */ @@ -218,14 +231,14 @@ int bcmf_cdc_control_request(FAR struct bcmf_dev_s *priv, if (ret != OK) { // TODO free allocated iovar buffer here - goto exit_sem_post; + return ret; } - ret = bcmf_sem_wait(&priv->control_timeout, CDC_CONTROL_TIMEOUT_MS); + ret = bcmf_sem_wait(&priv->control_timeout, BCMF_CONTROL_TIMEOUT_MS); if (ret != OK) { wlerr("Error while waiting for control response %d\n", ret); - goto exit_sem_post; + return ret; } *len = priv->control_rxdata_len; @@ -235,12 +248,10 @@ int bcmf_cdc_control_request(FAR struct bcmf_dev_s *priv, if (priv->control_status != 0) { wlerr("Invalid cdc status 0x%x\n", priv->control_status); - ret = -EINVAL; + return -EINVAL; } -exit_sem_post: - sem_post(&priv->control_mutex); - return ret; + return OK; } /**************************************************************************** @@ -256,6 +267,15 @@ int bcmf_cdc_iovar_request(FAR struct bcmf_dev_s *priv, data, len); } +int bcmf_cdc_iovar_request_unsafe(FAR struct bcmf_dev_s *priv, + uint32_t ifidx, bool set, char *name, + uint8_t *data, uint32_t *len) +{ + return bcmf_cdc_control_request_unsafe(priv, ifidx, set, + set ? WLC_SET_VAR : WLC_GET_VAR, name, + data, len); +} + int bcmf_cdc_ioctl(FAR struct bcmf_dev_s *priv, uint32_t ifidx, bool set, uint32_t cmd, uint8_t *data, uint32_t *len) @@ -290,7 +310,7 @@ int bcmf_cdc_process_control_frame(FAR struct bcmf_dev_s *priv, // TODO check interface ? - if (cdc_header->flags >> CDC_DCMD_ID_SHIFT == priv->control_reqid) + if (cdc_header->flags >> BCMF_CONTROL_REQID_SHIFT == priv->control_reqid) { /* Expected frame received, send it back to user */ @@ -314,20 +334,4 @@ int bcmf_cdc_process_control_frame(FAR struct bcmf_dev_s *priv, wlinfo("Got unexpected control frame\n"); return -EINVAL; -} - -int bcmf_cdc_process_event_frame(FAR struct bcmf_dev_s *priv, - struct bcmf_frame_s *frame) -{ - wlinfo("Event message\n"); - bcmf_hexdump(frame->base, frame->len, (unsigned long)frame->base); - return OK; -} - -int bcmf_cdc_process_data_frame(FAR struct bcmf_dev_s *priv, - struct bcmf_frame_s *frame) -{ - wlinfo("Data message\n"); - bcmf_hexdump(frame->base, frame->len, (unsigned long)frame->base); - return OK; } \ No newline at end of file diff --git a/drivers/wireless/ieee80211/bcmf_cdc.h b/drivers/wireless/ieee80211/bcmf_cdc.h index 2c9743e4f0..0cf3242f18 100644 --- a/drivers/wireless/ieee80211/bcmf_cdc.h +++ b/drivers/wireless/ieee80211/bcmf_cdc.h @@ -48,19 +48,22 @@ * Public Function Prototypes ****************************************************************************/ +/* Send safe cdc request */ + int bcmf_cdc_iovar_request(FAR struct bcmf_dev_s *priv, uint32_t ifidx, bool set, char *name, uint8_t *data, uint32_t *len); int bcmf_cdc_ioctl(FAR struct bcmf_dev_s *priv, uint32_t ifidx, bool set, uint32_t cmd, uint8_t *data, uint32_t *len); -int bcmf_cdc_process_control_frame(FAR struct bcmf_dev_s *priv, - struct bcmf_frame_s *frame); +/* Send cdc request without locking control_mutex */ -int bcmf_cdc_process_data_frame(FAR struct bcmf_dev_s *priv, - struct bcmf_frame_s *frame); +int bcmf_cdc_iovar_request_unsafe(FAR struct bcmf_dev_s *priv, uint32_t ifidx, + bool set, char *name, uint8_t *data, uint32_t *len); -int bcmf_cdc_process_event_frame(FAR struct bcmf_dev_s *priv, - struct bcmf_frame_s *frame); +/* Callback used by bus layer to notify cdc response frame is available */ + +int bcmf_cdc_process_control_frame(FAR struct bcmf_dev_s *priv, + struct bcmf_frame_s *frame); #endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_CDC_H */ \ No newline at end of file diff --git a/drivers/wireless/ieee80211/bcmf_driver.c b/drivers/wireless/ieee80211/bcmf_driver.c index 4aafc2b823..d2c522347a 100644 --- a/drivers/wireless/ieee80211/bcmf_driver.c +++ b/drivers/wireless/ieee80211/bcmf_driver.c @@ -48,10 +48,12 @@ #include #include +#include #include "bcmf_driver.h" #include "bcmf_cdc.h" #include "bcmf_ioctl.h" +#include "bcmf_utils.h" #include #include "bcmf_sdio.h" @@ -62,14 +64,23 @@ // TODO move elsewhere #define DOT11_BSSTYPE_ANY 2 -#define WL_SCAN_CHANNEL_TIME 40 -#define WL_SCAN_UNASSOC_TIME 40 -#define WL_SCAN_PASSIVE_TIME 120 + +#define BCMF_SCAN_TIMEOUT_TICK (5*CLOCKS_PER_SEC) /**************************************************************************** * Private Types ****************************************************************************/ +/* AP scan state machine status */ + +enum +{ + BCMF_SCAN_TIMEOUT = 0, + BCMF_SCAN_DISABLED, + BCMF_SCAN_RUN, + BCMF_SCAN_DONE +}; + /**************************************************************************** * Private Function Prototypes ****************************************************************************/ @@ -82,6 +93,16 @@ static int bcmf_driver_initialize(FAR struct bcmf_dev_s *priv); // FIXME add bcmf_netdev.h file int bcmf_netdev_register(FAR struct bcmf_dev_s *priv); +// FIXME only for debug purpose +static void bcmf_wl_default_event_handler(FAR struct bcmf_dev_s *priv, + struct bcmf_event_s *event, unsigned int len); + +static void bcmf_wl_radio_event_handler(FAR struct bcmf_dev_s *priv, + struct bcmf_event_s *event, unsigned int len); + +static void bcmf_wl_scan_event_handler(FAR struct bcmf_dev_s *priv, + struct bcmf_event_s *event, unsigned int len); + #if 0 static int bcmf_run_escan(FAR struct bcmf_dev_s *priv); #endif @@ -128,6 +149,16 @@ FAR struct bcmf_dev_s* bcmf_allocate_device(void) goto exit_free_priv; } + /* Init scan timeout timer */ + + priv->scan_status = BCMF_SCAN_DISABLED; + priv->scan_timeout = wd_create(); + if (!priv->scan_timeout) + { + ret = -ENOMEM; + goto exit_free_priv; + } + return priv; exit_free_priv: @@ -163,127 +194,6 @@ int bcmf_wl_set_mac_address(FAR struct bcmf_dev_s *priv, uint8_t *addr) return OK; } -int bcmf_dongle_scantime(FAR struct bcmf_dev_s *priv, int32_t scan_assoc_time, - int32_t scan_unassoc_time, int32_t scan_passive_time) -{ - int ret; - uint32_t out_len; - uint32_t value; - - out_len = 4; - value = scan_assoc_time; - ret = bcmf_cdc_ioctl(priv, CHIP_STA_INTERFACE, true, - WLC_SET_SCAN_CHANNEL_TIME, (uint8_t*)&value, - &out_len); - if (ret != OK) - { - return -EIO; - } - - out_len = 4; - value = scan_unassoc_time; - ret = bcmf_cdc_ioctl(priv, CHIP_STA_INTERFACE, true, - WLC_SET_SCAN_UNASSOC_TIME, (uint8_t*)&value, - &out_len); - if (ret != OK) - { - return -EIO; - } - - out_len = 4; - value = scan_passive_time; - ret = bcmf_cdc_ioctl(priv, CHIP_STA_INTERFACE, true, - WLC_SET_SCAN_PASSIVE_TIME, (uint8_t*)&value, - &out_len); - if (ret != OK) - { - return -EIO; - } - - return OK; -} - -int bcmf_dongle_initialize(FAR struct bcmf_dev_s *priv) -{ - int ret; - - ret = bcmf_wl_enable(priv, true); - if (ret) - { - return ret; - } - - ret = bcmf_dongle_scantime(priv, WL_SCAN_CHANNEL_TIME, - WL_SCAN_UNASSOC_TIME, WL_SCAN_PASSIVE_TIME); - if (ret) - { - return ret; - } - - // FIXME remove -#if 0 - /* Try scan */ - - value = 0; - out_len = 4; - ret = bcmf_cdc_ioctl(priv, CHIP_STA_INTERFACE, true, - WLC_SET_PASSIVE_SCAN, (uint8_t*)&value, &out_len); - bcmf_run_escan(priv); -#endif - - return ret; -} - -#if 0 -int bcmf_run_escan(FAR struct bcmf_dev_s *priv) -{ - int ret; - uint32_t out_len; - - /* Default request structure */ - - struct wl_escan_params *params = - (struct wl_escan_params*)kmm_malloc(sizeof(*params)); - if (!params) - { - return -ENOMEM; - } - - memset(params, 0, sizeof(*params)); - - params->version = ESCAN_REQ_VERSION; - params->action = WL_SCAN_ACTION_START; - params->sync_id = 0x1234; - - - memset(¶ms->params.bssid, 0xFF, sizeof(params->params.bssid)); - params->params.bss_type = DOT11_BSSTYPE_ANY; - params->params.scan_type = 0; /* Active scan */ - params->params.nprobes = -1; - params->params.active_time = -1; - params->params.passive_time = -1; - params->params.home_time = -1; - - params->params.channel_num = 0; - - wlinfo("start scan\n"); - - out_len = sizeof(*params); - ret = bcmf_cdc_iovar_request(priv, CHIP_STA_INTERFACE, true, - IOVAR_STR_ESCAN, (uint8_t*)params, - &out_len); - - free(params); - - if (ret != OK) - { - return -EIO; - } - - return OK; -} -#endif - int bcmf_driver_initialize(FAR struct bcmf_dev_s *priv) { int ret; @@ -344,6 +254,8 @@ int bcmf_driver_initialize(FAR struct bcmf_dev_s *priv) return -EIO; } + tmp_buf[sizeof(tmp_buf)-1] = 0; + /* Remove line feed */ out_len = strlen((char*)tmp_buf); @@ -356,14 +268,20 @@ int bcmf_driver_initialize(FAR struct bcmf_dev_s *priv) /* FIXME Configure event mask to enable all asynchronous events */ - uint8_t event_mask[16]; - memset(event_mask, 0xff, sizeof(event_mask)); + for (ret = 0; ret < BCMF_EVENT_COUNT; ret++) + { + bcmf_event_register(priv, bcmf_wl_default_event_handler, ret); + } - out_len = sizeof(event_mask); - ret = bcmf_cdc_iovar_request(priv, CHIP_STA_INTERFACE, true, - IOVAR_STR_EVENT_MSGS, event_mask, - &out_len); - if (ret != OK) + /* Register radio event */ + + bcmf_event_register(priv, bcmf_wl_radio_event_handler, WLC_E_RADIO); + + /* Register AP scan event */ + + bcmf_event_register(priv, bcmf_wl_scan_event_handler, WLC_E_ESCAN_RESULT); + + if (bcmf_event_push_config(priv)) { return -EIO; } @@ -373,6 +291,161 @@ int bcmf_driver_initialize(FAR struct bcmf_dev_s *priv) return bcmf_netdev_register(priv); } +void bcmf_wl_default_event_handler(FAR struct bcmf_dev_s *priv, + struct bcmf_event_s *event, unsigned int len) +{ + wlinfo("Got event %d from <%s>\n", bcmf_getle32(&event->type), + event->src_name); +} + +void bcmf_wl_radio_event_handler(FAR struct bcmf_dev_s *priv, + struct bcmf_event_s *event, unsigned int len) +{ + wlinfo("Got radio event %d from <%s>\n", bcmf_getle32(&event->type), + event->src_name); +} + +void bcmf_wl_scan_event_handler(FAR struct bcmf_dev_s *priv, + struct bcmf_event_s *event, unsigned int len) +{ + uint32_t status; + uint32_t reason; + uint32_t event_len; + struct wl_escan_result *result; + struct wl_bss_info *bss; + unsigned int bss_info_len; + unsigned int escan_result_len; + unsigned int bss_count = 0; + + event_len = len; + + if (priv->scan_status < BCMF_SCAN_RUN) + { + wlinfo("Got Unexpected scan event\n"); + goto exit_invalid_frame; + } + + status = bcmf_getle32(&event->status); + reason = bcmf_getle32(&event->reason); + escan_result_len = bcmf_getle32(&event->len); + + len -= sizeof(struct bcmf_event_s); + + if (len > escan_result_len) + { + len = escan_result_len; + } + if (len == sizeof(struct wl_escan_result) - sizeof(struct wl_bss_info)) + { + /* Nothing to process, may be scan done event */ + + goto wl_escan_result_processed; + } + if (len < sizeof(struct wl_escan_result)) + { + goto exit_invalid_frame; + } + + /* Process escan result payload */ + + result = (struct wl_escan_result*)&event[1]; + + if (len < result->buflen || result->buflen < sizeof(struct wl_escan_result)) + { + goto exit_invalid_frame; + } + + /* wl_escan_result already cointains a wl_bss_info field */ + + len = result->buflen - sizeof(struct wl_escan_result) + + sizeof(struct wl_bss_info); + + /* Process bss_infos */ + + bss = result->bss_info; + + do + { + bss_info_len = bss->length; + + if (len < bss_info_len) + { + wlerr("bss_len error %d %d\n", len, bss_info_len); + goto exit_invalid_frame; + } + + wlinfo("Scan result: <%.32s> %02x:%02x:%02x:%02x:%02x:%02x\n", + bss->SSID, bss->BSSID.octet[0], bss->BSSID.octet[1], + bss->BSSID.octet[2], bss->BSSID.octet[3], + bss->BSSID.octet[4], bss->BSSID.octet[5]); + + /* Process next bss_info */ + + len -= bss_info_len; + bss = (struct wl_bss_info*)((uint8_t*)bss + bss_info_len); + bss_count += 1; + } + while (len > 0 && bss_count < result->bss_count); + +wl_escan_result_processed: + + if (status == WLC_E_STATUS_PARTIAL) + { + /* More frames to come */ + + return; + } + + if (status != WLC_E_STATUS_SUCCESS) + { + wlerr("Invalid event status %d\n", status); + return; + } + + /* Scan done */ + + wlinfo("escan done event %d %d\n", status, reason); + + wd_cancel(priv->scan_timeout); + + if (!priv->scan_params) + { + /* Scan has already timedout */ + + return; + } + + free(priv->scan_params); + priv->scan_params = NULL; + priv->scan_status = BCMF_SCAN_DONE; + sem_post(&priv->control_mutex); + + return; + +exit_invalid_frame: + wlerr("Invalid scan result event\n"); + bcmf_hexdump((uint8_t*)event, event_len, (unsigned long)event); +} + +void bcmf_wl_scan_timeout(int argc, wdparm_t arg1, ...) +{ + FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s*)arg1; + + if (priv->scan_status < BCMF_SCAN_RUN) + { + /* Fatal error, invalid scan status */ + wlerr("Unexpected scan timeout\n"); + return; + } + + wlerr("Scan timeout detected\n"); + + priv->scan_status = BCMF_SCAN_TIMEOUT; + free(priv->scan_params); + priv->scan_params = NULL; + sem_post(&priv->control_mutex); +} + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -419,10 +492,107 @@ int bcmf_wl_enable(FAR struct bcmf_dev_s *priv, bool enable) ret = bcmf_cdc_ioctl(priv, CHIP_STA_INTERFACE, true, enable ? WLC_UP : WLC_DOWN, NULL, &out_len); + /* TODO wait for WLC_E_RADIO event */ + if (ret == OK) { /* TODO update device state */ } return ret; +} + +int bcmf_wl_start_scan(FAR struct bcmf_dev_s *priv) +{ + int ret; + uint32_t out_len; + uint32_t value; + + wlinfo("Enter\n"); + + /* Set active scan mode */ + + value = 0; + out_len = 4; + if (bcmf_cdc_ioctl(priv, CHIP_STA_INTERFACE, true, + WLC_SET_PASSIVE_SCAN, (uint8_t*)&value, &out_len)) + { + return -EIO; + } + + /* Lock control_mutex semaphore */ + + if ((ret = sem_wait(&priv->control_mutex)) != OK) + { + return ret; + } + + /* Default request structure */ + + priv->scan_params = (struct wl_escan_params*) + kmm_malloc(sizeof(*priv->scan_params)); + if (!priv->scan_params) + { + ret = -ENOMEM; + goto exit_sem_post; + } + + memset(priv->scan_params, 0, sizeof(*priv->scan_params)); + + priv->scan_params->version = ESCAN_REQ_VERSION; + priv->scan_params->action = WL_SCAN_ACTION_START; + priv->scan_params->sync_id = 0xabcd; /* Not used for now */ + + memset(&priv->scan_params->params.bssid, 0xFF, + sizeof(priv->scan_params->params.bssid)); + priv->scan_params->params.bss_type = DOT11_BSSTYPE_ANY; + priv->scan_params->params.scan_type = 0; /* Active scan */ + priv->scan_params->params.nprobes = -1; + priv->scan_params->params.active_time = -1; + priv->scan_params->params.passive_time = -1; + priv->scan_params->params.home_time = -1; + priv->scan_params->params.channel_num = 0; + + wlinfo("start scan\n"); + + priv->scan_status = BCMF_SCAN_RUN; + + out_len = sizeof(*priv->scan_params); + + + if (bcmf_cdc_iovar_request_unsafe(priv, CHIP_STA_INTERFACE, true, + IOVAR_STR_ESCAN, (uint8_t*)priv->scan_params, + &out_len)) + { + ret = -EIO; + goto exit_free_params; + } + + /* Start scan_timeout timer */ + + wd_start(priv->scan_timeout, BCMF_SCAN_TIMEOUT_TICK, + bcmf_wl_scan_timeout, (wdparm_t)priv); + + return OK; + +exit_free_params: + free(priv->scan_params); + priv->scan_params = NULL; +exit_sem_post: + sem_post(&priv->control_mutex); + priv->scan_status = BCMF_SCAN_DISABLED; + return ret; +} + +int bcmf_wl_is_scan_done(FAR struct bcmf_dev_s *priv) +{ + if (priv->scan_status == BCMF_SCAN_RUN) + { + return -EAGAIN; + } + if (priv->scan_status == BCMF_SCAN_DONE) + { + return OK; + } + return -EINVAL; } \ No newline at end of file diff --git a/drivers/wireless/ieee80211/bcmf_driver.h b/drivers/wireless/ieee80211/bcmf_driver.h index 346b2e15fd..edbd911845 100644 --- a/drivers/wireless/ieee80211/bcmf_driver.h +++ b/drivers/wireless/ieee80211/bcmf_driver.h @@ -44,15 +44,19 @@ #include #include +struct bcmf_dev_s; +struct bcmf_frame_s; + +#include "bcmf_bdc.h" + +struct bcmf_bus_dev_s; + /* Chip interfaces */ #define CHIP_STA_INTERFACE 0 #define CHIP_AP_INTERFACE 1 #define CHIP_P2P_INTERFACE 2 -struct bcmf_bus_dev_s; -struct bcmf_frame_s; - /* This structure contains the unique state of the Broadcom FullMAC driver */ struct bcmf_dev_s @@ -69,6 +73,9 @@ struct bcmf_dev_s struct net_driver_s bc_dev; /* Network interface structure */ + /* Event registration array */ + + event_handler_t event_handlers[BCMF_EVENT_COUNT]; // FIXME use mutex instead of semaphore sem_t control_mutex; /* Cannot handle multiple control requests */ @@ -77,6 +84,13 @@ struct bcmf_dev_s uint16_t control_rxdata_len; /* Received control frame out buffer length */ uint8_t *control_rxdata; /* Received control frame out buffer */ uint32_t control_status; /* Last received frame status */ + + /* AP Scan state machine. + * During scan, control_mutex is locked to prevent control requests */ + + int scan_status; /* Current scan status */ + WDOG_ID scan_timeout; /* Scan timeout timer */ + struct wl_escan_params *scan_params; /* Current scan parameters */ }; /* Default bus interface structure */ @@ -104,4 +118,8 @@ struct bcmf_frame_s { int bcmf_wl_enable(FAR struct bcmf_dev_s *priv, bool enable); +int bcmf_wl_start_scan(FAR struct bcmf_dev_s *priv); + +int bcmf_wl_is_scan_done(FAR struct bcmf_dev_s *priv); + #endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_DRIVER_H */ diff --git a/drivers/wireless/ieee80211/bcmf_ioctl.h b/drivers/wireless/ieee80211/bcmf_ioctl.h index d1936bb7ff..483102455a 100644 --- a/drivers/wireless/ieee80211/bcmf_ioctl.h +++ b/drivers/wireless/ieee80211/bcmf_ioctl.h @@ -106,7 +106,7 @@ typedef struct cnt_rx #define WL_BSS_INFO_VERSION 108 #define MCSSET_LEN 16 -typedef struct { +typedef struct wl_bss_info { uint32_t version; /* version field */ uint32_t length; /* byte length of data in this record, */ /* starting at version and including IEs */ @@ -2761,6 +2761,311 @@ typedef struct edcf_acparam edcf_acparam_t; /* Stop packing structures */ #pragma pack() +/** + * Enumerated list of event types + */ +typedef enum +{ + WLC_E_NONE = -1, + WLC_E_SET_SSID = 0 /** indicates status of set SSID */, + WLC_E_JOIN = 1, /** differentiates join IBSS from found (WLC_E_START) IBSS */ + WLC_E_START = 2, /** STA founded an IBSS or AP started a BSS */ + WLC_E_AUTH = 3, /** 802.11 AUTH request */ + WLC_E_AUTH_IND = 4, /** 802.11 AUTH indication */ + WLC_E_DEAUTH = 5, /** 802.11 DEAUTH request */ + WLC_E_DEAUTH_IND = 6, /** 802.11 DEAUTH indication */ + WLC_E_ASSOC = 7, /** 802.11 ASSOC request */ + WLC_E_ASSOC_IND = 8, /** 802.11 ASSOC indication */ + WLC_E_REASSOC = 9, /** 802.11 REASSOC request */ + WLC_E_REASSOC_IND = 10, /** 802.11 REASSOC indication */ + WLC_E_DISASSOC = 11, /** 802.11 DISASSOC request */ + WLC_E_DISASSOC_IND = 12, /** 802.11 DISASSOC indication */ + WLC_E_QUIET_START = 13, /** 802.11h Quiet period started */ + WLC_E_QUIET_END = 14, /** 802.11h Quiet period ended */ + WLC_E_BEACON_RX = 15, /** BEACONS received/lost indication */ + WLC_E_LINK = 16, /** generic link indication */ + WLC_E_MIC_ERROR = 17, /** TKIP MIC error occurred */ + WLC_E_NDIS_LINK = 18, /** NDIS style link indication */ + WLC_E_ROAM = 19, /** roam attempt occurred: indicate status & reason */ + WLC_E_TXFAIL = 20, /** change in dot11FailedCount (txfail) */ + WLC_E_PMKID_CACHE = 21, /** WPA2 pmkid cache indication */ + WLC_E_RETROGRADE_TSF = 22, /** current AP's TSF value went backward */ + WLC_E_PRUNE = 23, /** AP was pruned from join list for reason */ + WLC_E_AUTOAUTH = 24, /** report AutoAuth table entry match for join attempt */ + WLC_E_EAPOL_MSG = 25, /** Event encapsulating an EAPOL message */ + WLC_E_SCAN_COMPLETE = 26, /** Scan results are ready or scan was aborted */ + WLC_E_ADDTS_IND = 27, /** indicate to host addts fail/success */ + WLC_E_DELTS_IND = 28, /** indicate to host delts fail/success */ + WLC_E_BCNSENT_IND = 29, /** indicate to host of beacon transmit */ + WLC_E_BCNRX_MSG = 30, /** Send the received beacon up to the host */ + WLC_E_BCNLOST_MSG = 31, /** indicate to host loss of beacon */ + WLC_E_ROAM_PREP = 32, /** before attempting to roam */ + WLC_E_PFN_NET_FOUND = 33, /** PFN network found event */ + WLC_E_PFN_NET_LOST = 34, /** PFN network lost event */ + WLC_E_RESET_COMPLETE = 35, + WLC_E_JOIN_START = 36, + WLC_E_ROAM_START = 37, + WLC_E_ASSOC_START = 38, + WLC_E_IBSS_ASSOC = 39, + WLC_E_RADIO = 40, + WLC_E_PSM_WATCHDOG = 41, /** PSM microcode watchdog fired */ + WLC_E_CCX_ASSOC_START = 42, /** CCX association start */ + WLC_E_CCX_ASSOC_ABORT = 43, /** CCX association abort */ + WLC_E_PROBREQ_MSG = 44, /** probe request received */ + WLC_E_SCAN_CONFIRM_IND = 45, + WLC_E_PSK_SUP = 46, /** WPA Handshake */ + WLC_E_COUNTRY_CODE_CHANGED = 47, + WLC_E_EXCEEDED_MEDIUM_TIME = 48, /** WMMAC excedded medium time */ + WLC_E_ICV_ERROR = 49, /** WEP ICV error occurred */ + WLC_E_UNICAST_DECODE_ERROR = 50, /** Unsupported unicast encrypted frame */ + WLC_E_MULTICAST_DECODE_ERROR = 51, /** Unsupported multicast encrypted frame */ + WLC_E_TRACE = 52, + WLC_E_BTA_HCI_EVENT = 53, /** BT-AMP HCI event */ + WLC_E_IF = 54, /** I/F change (for wlan host notification) */ + WLC_E_P2P_DISC_LISTEN_COMPLETE = 55, /** P2P Discovery listen state expires */ + WLC_E_RSSI = 56, /** indicate RSSI change based on configured levels */ + WLC_E_PFN_SCAN_COMPLETE = 57, /** PFN completed scan of network list */ + WLC_E_EXTLOG_MSG = 58, + WLC_E_ACTION_FRAME = 59, /** Action frame reception */ + WLC_E_ACTION_FRAME_COMPLETE = 60, /** Action frame Tx complete */ + WLC_E_PRE_ASSOC_IND = 61, /** assoc request received */ + WLC_E_PRE_REASSOC_IND = 62, /** re-assoc request received */ + WLC_E_CHANNEL_ADOPTED = 63, /** channel adopted (xxx: obsoleted) */ + WLC_E_AP_STARTED = 64, /** AP started */ + WLC_E_DFS_AP_STOP = 65, /** AP stopped due to DFS */ + WLC_E_DFS_AP_RESUME = 66, /** AP resumed due to DFS */ + WLC_E_WAI_STA_EVENT = 67, /** WAI stations event */ + WLC_E_WAI_MSG = 68, /** event encapsulating an WAI message */ + WLC_E_ESCAN_RESULT = 69, /** escan result event */ + WLC_E_ACTION_FRAME_OFF_CHAN_COMPLETE = 70, /** action frame off channel complete */ /* NOTE - This used to be WLC_E_WAKE_EVENT */ + WLC_E_PROBRESP_MSG = 71, /** probe response received */ + WLC_E_P2P_PROBREQ_MSG = 72, /** P2P Probe request received */ + WLC_E_DCS_REQUEST = 73, + WLC_E_FIFO_CREDIT_MAP = 74, /** credits for D11 FIFOs. [AC0,AC1,AC2,AC3,BC_MC,ATIM] */ + WLC_E_ACTION_FRAME_RX = 75, /** Received action frame event WITH wl_event_rx_frame_data_t header */ + WLC_E_WAKE_EVENT = 76, /** Wake Event timer fired, used for wake WLAN test mode */ + WLC_E_RM_COMPLETE = 77, /** Radio measurement complete */ + WLC_E_HTSFSYNC = 78, /** Synchronize TSF with the host */ + WLC_E_OVERLAY_REQ = 79, /** request an overlay IOCTL/iovar from the host */ + WLC_E_CSA_COMPLETE_IND = 80, + WLC_E_EXCESS_PM_WAKE_EVENT = 81, /** excess PM Wake Event to inform host */ + WLC_E_PFN_SCAN_NONE = 82, /** no PFN networks around */ + WLC_E_PFN_SCAN_ALLGONE = 83, /** last found PFN network gets lost */ + WLC_E_GTK_PLUMBED = 84, + WLC_E_ASSOC_IND_NDIS = 85, /** 802.11 ASSOC indication for NDIS only */ + WLC_E_REASSOC_IND_NDIS = 86, /** 802.11 REASSOC indication for NDIS only */ + WLC_E_ASSOC_REQ_IE = 87, + WLC_E_ASSOC_RESP_IE = 88, + WLC_E_ASSOC_RECREATED = 89, /** association recreated on resume */ + WLC_E_ACTION_FRAME_RX_NDIS = 90, /** rx action frame event for NDIS only */ + WLC_E_AUTH_REQ = 91, /** authentication request received */ + WLC_E_TDLS_PEER_EVENT = 92, /** discovered peer, connected/disconnected peer */ + WLC_E_SPEEDY_RECREATE_FAIL = 93, /** fast assoc recreation failed */ + WLC_E_NATIVE = 94, /** port-specific event and payload (e.g. NDIS) */ + WLC_E_PKTDELAY_IND = 95, /** event for tx pkt delay suddently jump */ + WLC_E_AWDL_AW = 96, /** AWDL AW period starts */ + WLC_E_AWDL_ROLE = 97, /** AWDL Master/Slave/NE master role event */ + WLC_E_AWDL_EVENT = 98, /** Generic AWDL event */ + WLC_E_NIC_AF_TXS = 99, /** NIC AF txstatus */ + WLC_E_NIC_NIC_REPORT = 100, /** NIC period report */ + WLC_E_BEACON_FRAME_RX = 101, + WLC_E_SERVICE_FOUND = 102, /** desired service found */ + WLC_E_GAS_FRAGMENT_RX = 103, /** GAS fragment received */ + WLC_E_GAS_COMPLETE = 104, /** GAS sessions all complete */ + WLC_E_P2PO_ADD_DEVICE = 105, /** New device found by p2p offload */ + WLC_E_P2PO_DEL_DEVICE = 106, /** device has been removed by p2p offload */ + WLC_E_WNM_STA_SLEEP = 107, /** WNM event to notify STA enter sleep mode */ + WLC_E_TXFAIL_THRESH = 108, /** Indication of MAC tx failures (exhaustion of 802.11 retries) exceeding threshold(s) */ + WLC_E_PROXD = 109, /** Proximity Detection event */ + WLC_E_IBSS_COALESCE = 110, /** IBSS Coalescing */ + WLC_E_AWDL_RX_PRB_RESP = 111, /** AWDL RX Probe response */ + WLC_E_AWDL_RX_ACT_FRAME = 112, /** AWDL RX Action Frames */ + WLC_E_AWDL_WOWL_NULLPKT = 113, /** AWDL Wowl nulls */ + WLC_E_AWDL_PHYCAL_STATUS = 114, /** AWDL Phycal status */ + WLC_E_AWDL_OOB_AF_STATUS = 115, /** AWDL OOB AF status */ + WLC_E_AWDL_SCAN_STATUS = 116, /** Interleaved Scan status */ + WLC_E_AWDL_AW_START = 117, /** AWDL AW Start */ + WLC_E_AWDL_AW_END = 118, /** AWDL AW End */ + WLC_E_AWDL_AW_EXT = 119, /** AWDL AW Extensions */ + WLC_E_AWDL_PEER_CACHE_CONTROL = 120, + WLC_E_CSA_START_IND = 121, + WLC_E_CSA_DONE_IND = 122, + WLC_E_CSA_FAILURE_IND = 123, + WLC_E_CCA_CHAN_QUAL = 124, /** CCA based channel quality report */ + WLC_E_BSSID = 125, /** to report change in BSSID while roaming */ + WLC_E_TX_STAT_ERROR = 126, /** tx error indication */ + WLC_E_BCMC_CREDIT_SUPPORT = 127, /** credit check for BCMC supported */ + WLC_E_PSTA_PRIMARY_INTF_IND = 128, /** psta primary interface indication */ + WLC_E_LAST = 129, /** highest val + 1 for range checking */ + + WLC_E_FORCE_32_BIT = 0x7FFFFFFE /** Force enum to be stored in 32 bit variable */ +} wwd_event_num_t; + +#define BCMF_EVENT_COUNT WLC_E_LAST + + +#define WLC_SUP_STATUS_OFFSET (256) +#define WLC_DOT11_SC_STATUS_OFFSET (512) +/** + * Enumerated list of event status codes + * @note : WLC_SUP values overlap other values, so it is necessary + * to check the event type + */ +typedef enum +{ + WLC_E_STATUS_SUCCESS = 0, /** operation was successful */ + WLC_E_STATUS_FAIL = 1, /** operation failed */ + WLC_E_STATUS_TIMEOUT = 2, /** operation timed out */ + WLC_E_STATUS_NO_NETWORKS = 3, /** failed due to no matching network found */ + WLC_E_STATUS_ABORT = 4, /** operation was aborted */ + WLC_E_STATUS_NO_ACK = 5, /** protocol failure: packet not ack'd */ + WLC_E_STATUS_UNSOLICITED = 6, /** AUTH or ASSOC packet was unsolicited */ + WLC_E_STATUS_ATTEMPT = 7, /** attempt to assoc to an auto auth configuration */ + WLC_E_STATUS_PARTIAL = 8, /** scan results are incomplete */ + WLC_E_STATUS_NEWSCAN = 9, /** scan aborted by another scan */ + WLC_E_STATUS_NEWASSOC = 10, /** scan aborted due to assoc in progress */ + WLC_E_STATUS_11HQUIET = 11, /** 802.11h quiet period started */ + WLC_E_STATUS_SUPPRESS = 12, /** user disabled scanning (WLC_SET_SCANSUPPRESS) */ + WLC_E_STATUS_NOCHANS = 13, /** no allowable channels to scan */ + WLC_E_STATUS_CCXFASTRM = 14, /** scan aborted due to CCX fast roam */ + WLC_E_STATUS_CS_ABORT = 15, /** abort channel select */ + + /* for WLC_SUP messages */ + WLC_SUP_DISCONNECTED = 0 + WLC_SUP_STATUS_OFFSET, + WLC_SUP_CONNECTING = 1 + WLC_SUP_STATUS_OFFSET, + WLC_SUP_IDREQUIRED = 2 + WLC_SUP_STATUS_OFFSET, + WLC_SUP_AUTHENTICATING = 3 + WLC_SUP_STATUS_OFFSET, + WLC_SUP_AUTHENTICATED = 4 + WLC_SUP_STATUS_OFFSET, + WLC_SUP_KEYXCHANGE = 5 + WLC_SUP_STATUS_OFFSET, + WLC_SUP_KEYED = 6 + WLC_SUP_STATUS_OFFSET, + WLC_SUP_TIMEOUT = 7 + WLC_SUP_STATUS_OFFSET, + WLC_SUP_LAST_BASIC_STATE = 8 + WLC_SUP_STATUS_OFFSET, + /* Extended supplicant authentication states */ + WLC_SUP_KEYXCHANGE_WAIT_M1 = (int) WLC_SUP_AUTHENTICATED + WLC_SUP_STATUS_OFFSET, /** Waiting to receive handshake msg M1 */ + WLC_SUP_KEYXCHANGE_PREP_M2 = (int) WLC_SUP_KEYXCHANGE + WLC_SUP_STATUS_OFFSET, /** Preparing to send handshake msg M2 */ + WLC_SUP_KEYXCHANGE_WAIT_M3 = (int) WLC_SUP_LAST_BASIC_STATE + WLC_SUP_STATUS_OFFSET, /** Waiting to receive handshake msg M3 */ + WLC_SUP_KEYXCHANGE_PREP_M4 = 9 + WLC_SUP_STATUS_OFFSET, /** Preparing to send handshake msg M4 */ + WLC_SUP_KEYXCHANGE_WAIT_G1 = 10 + WLC_SUP_STATUS_OFFSET, /** Waiting to receive handshake msg G1 */ + WLC_SUP_KEYXCHANGE_PREP_G2 = 11 + WLC_SUP_STATUS_OFFSET, /** Preparing to send handshake msg G2 */ + + WLC_DOT11_SC_SUCCESS = 0 + WLC_DOT11_SC_STATUS_OFFSET, /* Successful */ + WLC_DOT11_SC_FAILURE = 1 + WLC_DOT11_SC_STATUS_OFFSET, /* Unspecified failure */ + WLC_DOT11_SC_CAP_MISMATCH = 10 + WLC_DOT11_SC_STATUS_OFFSET, /* Cannot support all requested capabilities in the Capability Information field */ + WLC_DOT11_SC_REASSOC_FAIL = 11 + WLC_DOT11_SC_STATUS_OFFSET, /* Reassociation denied due to inability to confirm that association exists */ + WLC_DOT11_SC_ASSOC_FAIL = 12 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to reason outside the scope of this standard */ + WLC_DOT11_SC_AUTH_MISMATCH = 13 + WLC_DOT11_SC_STATUS_OFFSET, /* Responding station does not support the specified authentication algorithm */ + WLC_DOT11_SC_AUTH_SEQ = 14 + WLC_DOT11_SC_STATUS_OFFSET, /* Received an Authentication frame with authentication transaction sequence number out of expected sequence */ + WLC_DOT11_SC_AUTH_CHALLENGE_FAIL = 15 + WLC_DOT11_SC_STATUS_OFFSET, /* Authentication rejected because of challenge failure */ + WLC_DOT11_SC_AUTH_TIMEOUT = 16 + WLC_DOT11_SC_STATUS_OFFSET, /* Authentication rejected due to timeout waiting for next frame in sequence */ + WLC_DOT11_SC_ASSOC_BUSY_FAIL = 17 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied because AP is unable to handle additional associated stations */ + WLC_DOT11_SC_ASSOC_RATE_MISMATCH = 18 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to requesting station not supporting all of the data rates in the BSSBasicRateSet parameter */ + WLC_DOT11_SC_ASSOC_SHORT_REQUIRED = 19 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to requesting station not supporting the Short Preamble option */ + WLC_DOT11_SC_ASSOC_PBCC_REQUIRED = 20 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to requesting station not supporting the PBCC Modulation option */ + WLC_DOT11_SC_ASSOC_AGILITY_REQUIRED = 21 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to requesting station not supporting the Channel Agility option */ + WLC_DOT11_SC_ASSOC_SPECTRUM_REQUIRED = 22 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied because Spectrum Management capability is required. */ + WLC_DOT11_SC_ASSOC_BAD_POWER_CAP = 23 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied because the info in the Power Cap element is unacceptable. */ + WLC_DOT11_SC_ASSOC_BAD_SUP_CHANNELS = 24 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied because the info in the Supported Channel element is unacceptable */ + WLC_DOT11_SC_ASSOC_SHORTSLOT_REQUIRED = 25 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to requesting station not supporting the Short Slot Time option */ + WLC_DOT11_SC_ASSOC_ERPBCC_REQUIRED = 26 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to requesting station not supporting the ER-PBCC Modulation option */ + WLC_DOT11_SC_ASSOC_DSSOFDM_REQUIRED = 27 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to requesting station not supporting the DSS-OFDM option */ + WLC_DOT11_SC_DECLINED = 37 + WLC_DOT11_SC_STATUS_OFFSET, /* request declined */ + WLC_DOT11_SC_INVALID_PARAMS = 38 + WLC_DOT11_SC_STATUS_OFFSET, /* One or more params have invalid values */ + WLC_DOT11_SC_INVALID_AKMP = 43 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to invalid AKMP */ + WLC_DOT11_SC_INVALID_MDID = 54 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to invalid MDID */ + WLC_DOT11_SC_INVALID_FTIE = 55 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to invalid FTIE */ + + WLC_E_STATUS_FORCE_32_BIT = 0x7FFFFFFE /** Force enum to be stored in 32 bit variable */ +} wwd_event_status_t; + +#define WLC_E_PRUNE_REASON_OFFSET (256) +#define WLC_E_SUP_REASON_OFFSET (512) +#define WLC_E_DOT11_RC_REASON_OFFSET (768) + + +/** + * Enumerated list of event reason codes + * @note : Several values overlap other values, so it is necessary + * to check the event type + */ +typedef enum +{ + /* roam reason codes */ + WLC_E_REASON_INITIAL_ASSOC = 0, /** initial assoc */ + WLC_E_REASON_LOW_RSSI = 1, /** roamed due to low RSSI */ + WLC_E_REASON_DEAUTH = 2, /** roamed due to DEAUTH indication */ + WLC_E_REASON_DISASSOC = 3, /** roamed due to DISASSOC indication */ + WLC_E_REASON_BCNS_LOST = 4, /** roamed due to lost beacons */ + WLC_E_REASON_FAST_ROAM_FAILED = 5, /** roamed due to fast roam failure */ + WLC_E_REASON_DIRECTED_ROAM = 6, /** roamed due to request by AP */ + WLC_E_REASON_TSPEC_REJECTED = 7, /** roamed due to TSPEC rejection */ + WLC_E_REASON_BETTER_AP = 8, /** roamed due to finding better AP */ + + /* prune reason codes */ + WLC_E_PRUNE_ENCR_MISMATCH = 1 + WLC_E_PRUNE_REASON_OFFSET, /** encryption mismatch */ + WLC_E_PRUNE_BCAST_BSSID = 2 + WLC_E_PRUNE_REASON_OFFSET, /** AP uses a broadcast BSSID */ + WLC_E_PRUNE_MAC_DENY = 3 + WLC_E_PRUNE_REASON_OFFSET, /** STA's MAC addr is in AP's MAC deny list */ + WLC_E_PRUNE_MAC_NA = 4 + WLC_E_PRUNE_REASON_OFFSET, /** STA's MAC addr is not in AP's MAC allow list */ + WLC_E_PRUNE_REG_PASSV = 5 + WLC_E_PRUNE_REASON_OFFSET, /** AP not allowed due to regulatory restriction */ + WLC_E_PRUNE_SPCT_MGMT = 6 + WLC_E_PRUNE_REASON_OFFSET, /** AP does not support STA locale spectrum mgmt */ + WLC_E_PRUNE_RADAR = 7 + WLC_E_PRUNE_REASON_OFFSET, /** AP is on a radar channel of STA locale */ + WLC_E_RSN_MISMATCH = 8 + WLC_E_PRUNE_REASON_OFFSET, /** STA does not support AP's RSN */ + WLC_E_PRUNE_NO_COMMON_RATES = 9 + WLC_E_PRUNE_REASON_OFFSET, /** No rates in common with AP */ + WLC_E_PRUNE_BASIC_RATES = 10 + WLC_E_PRUNE_REASON_OFFSET, /** STA does not support all basic rates of BSS */ + WLC_E_PRUNE_CCXFAST_PREVAP = 11 + WLC_E_PRUNE_REASON_OFFSET, /** CCX FAST ROAM: prune previous AP */ + WLC_E_PRUNE_CIPHER_NA = 12 + WLC_E_PRUNE_REASON_OFFSET, /** BSS's cipher not supported */ + WLC_E_PRUNE_KNOWN_STA = 13 + WLC_E_PRUNE_REASON_OFFSET, /** AP is already known to us as a STA */ + WLC_E_PRUNE_CCXFAST_DROAM = 14 + WLC_E_PRUNE_REASON_OFFSET, /** CCX FAST ROAM: prune unqualified AP */ + WLC_E_PRUNE_WDS_PEER = 15 + WLC_E_PRUNE_REASON_OFFSET, /** AP is already known to us as a WDS peer */ + WLC_E_PRUNE_QBSS_LOAD = 16 + WLC_E_PRUNE_REASON_OFFSET, /** QBSS LOAD - AAC is too low */ + WLC_E_PRUNE_HOME_AP = 17 + WLC_E_PRUNE_REASON_OFFSET, /** prune home AP */ + WLC_E_PRUNE_AP_BLOCKED = 18 + WLC_E_PRUNE_REASON_OFFSET, /** prune blocked AP */ + WLC_E_PRUNE_NO_DIAG_SUPPORT = 19 + WLC_E_PRUNE_REASON_OFFSET, /** prune due to diagnostic mode not supported */ + + /* WPA failure reason codes carried in the WLC_E_PSK_SUP event */ + WLC_E_SUP_OTHER = 0 + WLC_E_SUP_REASON_OFFSET, /** Other reason */ + WLC_E_SUP_DECRYPT_KEY_DATA = 1 + WLC_E_SUP_REASON_OFFSET, /** Decryption of key data failed */ + WLC_E_SUP_BAD_UCAST_WEP128 = 2 + WLC_E_SUP_REASON_OFFSET, /** Illegal use of ucast WEP128 */ + WLC_E_SUP_BAD_UCAST_WEP40 = 3 + WLC_E_SUP_REASON_OFFSET, /** Illegal use of ucast WEP40 */ + WLC_E_SUP_UNSUP_KEY_LEN = 4 + WLC_E_SUP_REASON_OFFSET, /** Unsupported key length */ + WLC_E_SUP_PW_KEY_CIPHER = 5 + WLC_E_SUP_REASON_OFFSET, /** Unicast cipher mismatch in pairwise key */ + WLC_E_SUP_MSG3_TOO_MANY_IE = 6 + WLC_E_SUP_REASON_OFFSET, /** WPA IE contains > 1 RSN IE in key msg 3 */ + WLC_E_SUP_MSG3_IE_MISMATCH = 7 + WLC_E_SUP_REASON_OFFSET, /** WPA IE mismatch in key message 3 */ + WLC_E_SUP_NO_INSTALL_FLAG = 8 + WLC_E_SUP_REASON_OFFSET, /** INSTALL flag unset in 4-way msg */ + WLC_E_SUP_MSG3_NO_GTK = 9 + WLC_E_SUP_REASON_OFFSET, /** encapsulated GTK missing from msg 3 */ + WLC_E_SUP_GRP_KEY_CIPHER = 10 + WLC_E_SUP_REASON_OFFSET, /** Multicast cipher mismatch in group key */ + WLC_E_SUP_GRP_MSG1_NO_GTK = 11 + WLC_E_SUP_REASON_OFFSET, /** encapsulated GTK missing from group msg 1 */ + WLC_E_SUP_GTK_DECRYPT_FAIL = 12 + WLC_E_SUP_REASON_OFFSET, /** GTK decrypt failure */ + WLC_E_SUP_SEND_FAIL = 13 + WLC_E_SUP_REASON_OFFSET, /** message send failure */ + WLC_E_SUP_DEAUTH = 14 + WLC_E_SUP_REASON_OFFSET, /** received FC_DEAUTH */ + WLC_E_SUP_WPA_PSK_TMO = 15 + WLC_E_SUP_REASON_OFFSET, /** WPA PSK 4-way handshake timeout */ + + DOT11_RC_RESERVED = 0 + WLC_E_DOT11_RC_REASON_OFFSET, /* d11 RC reserved */ + DOT11_RC_UNSPECIFIED = 1 + WLC_E_DOT11_RC_REASON_OFFSET, /* Unspecified reason */ + DOT11_RC_AUTH_INVAL = 2 + WLC_E_DOT11_RC_REASON_OFFSET, /* Previous authentication no longer valid */ + DOT11_RC_DEAUTH_LEAVING = 3 + WLC_E_DOT11_RC_REASON_OFFSET, /* Deauthenticated because sending station is leaving (or has left) IBSS or ESS */ + DOT11_RC_INACTIVITY = 4 + WLC_E_DOT11_RC_REASON_OFFSET, /* Disassociated due to inactivity */ + DOT11_RC_BUSY = 5 + WLC_E_DOT11_RC_REASON_OFFSET, /* Disassociated because AP is unable to handle all currently associated stations */ + DOT11_RC_INVAL_CLASS_2 = 6 + WLC_E_DOT11_RC_REASON_OFFSET, /* Class 2 frame received from nonauthenticated station */ + DOT11_RC_INVAL_CLASS_3 = 7 + WLC_E_DOT11_RC_REASON_OFFSET, /* Class 3 frame received from nonassociated station */ + DOT11_RC_DISASSOC_LEAVING = 8 + WLC_E_DOT11_RC_REASON_OFFSET, /* Disassociated because sending station is leaving (or has left) BSS */ + DOT11_RC_NOT_AUTH = 9 + WLC_E_DOT11_RC_REASON_OFFSET, /* Station requesting (re)association is not * authenticated with responding station */ + DOT11_RC_BAD_PC = 10 + WLC_E_DOT11_RC_REASON_OFFSET, /* Unacceptable power capability element */ + DOT11_RC_BAD_CHANNELS = 11 + WLC_E_DOT11_RC_REASON_OFFSET, /* Unacceptable supported channels element */ + /* 12 is unused */ + /* XXX 13-23 are WPA/802.11i reason codes defined in proto/wpa.h */ + /* 32-39 are QSTA specific reasons added in 11e */ + DOT11_RC_UNSPECIFIED_QOS = 32 + WLC_E_DOT11_RC_REASON_OFFSET, /* unspecified QoS-related reason */ + DOT11_RC_INSUFFCIENT_BW = 33 + WLC_E_DOT11_RC_REASON_OFFSET, /* QAP lacks sufficient bandwidth */ + DOT11_RC_EXCESSIVE_FRAMES = 34 + WLC_E_DOT11_RC_REASON_OFFSET, /* excessive number of frames need ack */ + DOT11_RC_TX_OUTSIDE_TXOP = 35 + WLC_E_DOT11_RC_REASON_OFFSET, /* transmitting outside the limits of txop */ + DOT11_RC_LEAVING_QBSS = 36 + WLC_E_DOT11_RC_REASON_OFFSET, /* QSTA is leaving the QBSS (or restting) */ + DOT11_RC_BAD_MECHANISM = 37 + WLC_E_DOT11_RC_REASON_OFFSET, /* does not want to use the mechanism */ + DOT11_RC_SETUP_NEEDED = 38 + WLC_E_DOT11_RC_REASON_OFFSET, /* mechanism needs a setup */ + DOT11_RC_TIMEOUT = 39 + WLC_E_DOT11_RC_REASON_OFFSET, /* timeout */ + DOT11_RC_MAX = 23 + WLC_E_DOT11_RC_REASON_OFFSET, /* Reason codes > 23 are reserved */ + + WLC_E_REASON_FORCE_32_BIT = 0x7FFFFFFE /** Force enum to be stored in 32 bit variable */ +} wwd_event_reason_t; #ifdef __cplusplus diff --git a/drivers/wireless/ieee80211/bcmf_netdev.c b/drivers/wireless/ieee80211/bcmf_netdev.c index b81ced26dd..7d9a2db225 100644 --- a/drivers/wireless/ieee80211/bcmf_netdev.c +++ b/drivers/wireless/ieee80211/bcmf_netdev.c @@ -801,6 +801,12 @@ static int bcmf_ifup(FAR struct net_driver_s *dev) priv->bc_bifup = true; #warning Missing logic + + if (bcmf_wl_enable(priv, true) != OK) + { + return -EIO; + } + return OK; } @@ -825,6 +831,8 @@ static int bcmf_ifdown(FAR struct net_driver_s *dev) FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)dev->d_private; irqstate_t flags; + bcmf_wl_enable(priv, false); + /* Disable the hardware interrupt */ flags = enter_critical_section(); @@ -1082,13 +1090,21 @@ static void bcmf_ipv6multicast(FAR struct bcmf_dev_s *priv) static int bcmf_ioctl(FAR struct net_driver_s *dev, int cmd, unsigned long arg) { - FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)dev->d_private; int ret; + FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)dev->d_private; /* Decode and dispatch the driver-specific IOCTL command */ switch (cmd) { + case SIOCSIWSCAN: + ret = bcmf_wl_start_scan(priv); + break; + + case SIOCGIWSCAN: + ret = bcmf_wl_is_scan_done(priv); + break; + case SIOCSIWFREQ: /* Set channel/frequency (Hz) */ wlwarn("WARNING: SIOCSIWFREQ not implemented\n"); ret = -ENOSYS; @@ -1150,7 +1166,7 @@ static int bcmf_ioctl(FAR struct net_driver_s *dev, int cmd, break; default: - nerr("ERROR: Unrecognized IOCTL command: %d\n", command); + nerr("ERROR: Unrecognized IOCTL command: %d\n", cmd); ret = -ENOTTY; /* Special return value for this case */ break; } @@ -1181,7 +1197,6 @@ static int bcmf_ioctl(FAR struct net_driver_s *dev, int cmd, int bcmf_netdev_register(FAR struct bcmf_dev_s *priv) { - int ret; uint32_t out_len; /* Initialize network driver structure */ @@ -1211,8 +1226,7 @@ int bcmf_netdev_register(FAR struct bcmf_dev_s *priv) * the device and/or calling bcmf_ifdown(). */ - ret = bcmf_wl_enable(priv, false); - if (ret != OK) + if (bcmf_wl_enable(priv, false) != OK) { return -EIO; } @@ -1220,23 +1234,14 @@ int bcmf_netdev_register(FAR struct bcmf_dev_s *priv) /* Query MAC address */ out_len = ETHER_ADDR_LEN; - ret = bcmf_cdc_iovar_request(priv, CHIP_STA_INTERFACE, false, + if (bcmf_cdc_iovar_request(priv, CHIP_STA_INTERFACE, false, IOVAR_STR_CUR_ETHERADDR, priv->bc_dev.d_mac.ether.ether_addr_octet, - &out_len); - if (ret != OK) + &out_len) != OK) { return -EIO; } - wlinfo("MAC address is %02X:%02X:%02X:%02X:%02X:%02X\n", - priv->bc_dev.d_mac.ether.ether_addr_octet[0], - priv->bc_dev.d_mac.ether.ether_addr_octet[1], - priv->bc_dev.d_mac.ether.ether_addr_octet[2], - priv->bc_dev.d_mac.ether.ether_addr_octet[3], - priv->bc_dev.d_mac.ether.ether_addr_octet[4], - priv->bc_dev.d_mac.ether.ether_addr_octet[5]); - /* Register the device with the OS so that socket IOCTLs can be performed */ (void)netdev_register(&priv->bc_dev, NET_LL_IEEE80211); diff --git a/drivers/wireless/ieee80211/bcmf_sdio.c b/drivers/wireless/ieee80211/bcmf_sdio.c index 6df441faaa..0756a1c685 100644 --- a/drivers/wireless/ieee80211/bcmf_sdio.c +++ b/drivers/wireless/ieee80211/bcmf_sdio.c @@ -51,6 +51,7 @@ #include #include #include +#include #include #include diff --git a/drivers/wireless/ieee80211/bcmf_sdio_core.h b/drivers/wireless/ieee80211/bcmf_sdio_core.h index 174dd86bce..46d96fe058 100644 --- a/drivers/wireless/ieee80211/bcmf_sdio_core.h +++ b/drivers/wireless/ieee80211/bcmf_sdio_core.h @@ -61,6 +61,13 @@ #define I_HMB_SW_MASK ( (uint32_t) 0x000000F0 ) #define I_HMB_FRAME_IND ( 1<<6 ) +/* tosbmailbox bits corresponding to intstatus bits */ + +#define SMB_NAK (1 << 0) /* Frame NAK */ +#define SMB_INT_ACK (1 << 1) /* Host Interrupt ACK */ +#define SMB_USE_OOB (1 << 2) /* Use OOB Wakeup */ +#define SMB_DEV_INT (1 << 3) /* Miscellaneous Interrupt */ + enum { CHIPCOMMON_CORE_ID = 0, DOT11MAC_CORE_ID, diff --git a/drivers/wireless/ieee80211/bcmf_sdio_regs.h b/drivers/wireless/ieee80211/bcmf_sdio_regs.h index bdc117accb..5f0c5cc91f 100644 --- a/drivers/wireless/ieee80211/bcmf_sdio_regs.h +++ b/drivers/wireless/ieee80211/bcmf_sdio_regs.h @@ -80,7 +80,6 @@ #define SBSDIO_WATERMARK 0x10008 /* control busy signal generation */ #define SBSDIO_DEVICE_CTL 0x10009 - /* SB Address Window Low (b15) */ #define SBSDIO_FUNC1_SBADDRLOW 0x1000A /* SB Address Window Mid (b23:b16) */ @@ -89,24 +88,34 @@ #define SBSDIO_FUNC1_SBADDRHIGH 0x1000C /* Frame Control (frame term/abort) */ #define SBSDIO_FUNC1_FRAMECTRL 0x1000D +/* Read Frame Terminate */ +#define SFC_RF_TERM (1 << 0) +/* Write Frame Terminate */ +#define SFC_WF_TERM (1 << 1) +/* CRC error for write out of sync */ +#define SFC_CRC4WOOS (1 << 2) +/* Abort all in-progress frames */ +#define SFC_ABORTALL (1 << 3) + /* ChipClockCSR (ALP/HT ctl/status) */ #define SBSDIO_FUNC1_CHIPCLKCSR 0x1000E /* Force ALP request to backplane */ -#define SBSDIO_FORCE_ALP 0x01 +#define SBSDIO_FORCE_ALP 0x01 /* Force HT request to backplane */ -#define SBSDIO_FORCE_HT 0x02 +#define SBSDIO_FORCE_HT 0x02 /* Force ILP request to backplane */ -#define SBSDIO_FORCE_ILP 0x04 +#define SBSDIO_FORCE_ILP 0x04 /* Make ALP ready (power up xtal) */ #define SBSDIO_ALP_AVAIL_REQ 0x08 /* Make HT ready (power up PLL) */ -#define SBSDIO_HT_AVAIL_REQ 0x10 +#define SBSDIO_HT_AVAIL_REQ 0x10 /* Squelch clock requests from HW */ #define SBSDIO_FORCE_HW_CLKREQ_OFF 0x20 /* Status: ALP is ready */ -#define SBSDIO_ALP_AVAIL 0x40 +#define SBSDIO_ALP_AVAIL 0x40 /* Status: HT is ready */ -#define SBSDIO_HT_AVAIL 0x80 +#define SBSDIO_HT_AVAIL 0x80 + /* SdioPullUp (on cmd, d0-d2) */ #define SBSDIO_FUNC1_SDIOPULLUP 0x1000F /* Write Frame Byte Count Low */ diff --git a/drivers/wireless/ieee80211/bcmf_sdpcm.c b/drivers/wireless/ieee80211/bcmf_sdpcm.c index e6146b5af8..6047db9c86 100644 --- a/drivers/wireless/ieee80211/bcmf_sdpcm.c +++ b/drivers/wireless/ieee80211/bcmf_sdpcm.c @@ -53,6 +53,7 @@ #include "bcmf_core.h" #include "bcmf_sdpcm.h" #include "bcmf_cdc.h" +#include "bcmf_bdc.h" #include "bcmf_utils.h" #include "bcmf_sdio_regs.h" @@ -61,23 +62,9 @@ * Pre-processor Definitions ****************************************************************************/ -/* SDA_FRAMECTRL */ -#define SFC_RF_TERM (1 << 0) /* Read Frame Terminate */ -#define SFC_WF_TERM (1 << 1) /* Write Frame Terminate */ -#define SFC_CRC4WOOS (1 << 2) /* CRC error for write out of sync */ -#define SFC_ABORTALL (1 << 3) /* Abort all in-progress frames */ - -/* tosbmailbox bits corresponding to intstatus bits */ -#define SMB_NAK (1 << 0) /* Frame NAK */ -#define SMB_INT_ACK (1 << 1) /* Host Interrupt ACK */ -#define SMB_USE_OOB (1 << 2) /* Use OOB Wakeup */ -#define SMB_DEV_INT (1 << 3) /* Miscellaneous Interrupt */ - -#define SDPCM_CONTROL_CHANNEL 0 /* Control */ -#define SDPCM_EVENT_CHANNEL 1 /* Asyc Event Indication */ -#define SDPCM_DATA_CHANNEL 2 /* Data Xmit/Recv */ -#define SDPCM_GLOM_CHANNEL 3 /* Coalesced packets */ -#define SDPCM_TEST_CHANNEL 15 /* Test/debug packets */ +#define SDPCM_CONTROL_CHANNEL 0 /* Control frame id */ +#define SDPCM_EVENT_CHANNEL 1 /* Asynchronous event frame id */ +#define SDPCM_DATA_CHANNEL 2 /* Data frame id */ #define container_of(ptr, type, member) \ (type *)( (uint8_t *)(ptr) - offsetof(type,member) ) @@ -86,7 +73,7 @@ * Private Types ****************************************************************************/ -struct bcmf_sdpcm_header { +struct __attribute__((packed)) bcmf_sdpcm_header { uint16_t size; uint16_t checksum; uint8_t sequence; @@ -262,11 +249,20 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv) break; case SDPCM_EVENT_CHANNEL: - ret = bcmf_cdc_process_event_frame(priv, &sframe->frame_header); + if (header->data_offset == header->size) + { + /* Empty event, ignore */ + + ret = OK; + } + else + { + ret = bcmf_bdc_process_event_frame(priv, &sframe->frame_header); + } break; case SDPCM_DATA_CHANNEL: - ret = bcmf_cdc_process_data_frame(priv, &sframe->frame_header); + ret = bcmf_bdc_process_data_frame(priv, &sframe->frame_header); break; default: diff --git a/drivers/wireless/ieee80211/bcmf_utils.h b/drivers/wireless/ieee80211/bcmf_utils.h index ef7b45bbfa..704cb9ec06 100644 --- a/drivers/wireless/ieee80211/bcmf_utils.h +++ b/drivers/wireless/ieee80211/bcmf_utils.h @@ -51,4 +51,16 @@ void bcmf_hexdump(uint8_t *data, unsigned int len, unsigned long offset); int bcmf_sem_wait(sem_t *sem, unsigned int timeout_ms); +static inline uint16_t bcmf_getle16(uint16_t *val) +{ + uint8_t *valb = (uint8_t*)val; + return (uint16_t)valb[0] << 8 | (uint16_t)valb[1]; +} + +static inline uint16_t bcmf_getle32(uint32_t *val) +{ + uint16_t *valw = (uint16_t*)val; + return (uint32_t)bcmf_getle16(valw)<<16 | bcmf_getle16(valw+1); +} + #endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_UTILS_H */ \ No newline at end of file -- GitLab From 5f5c82aa11851c0e24587c0c6512e3bc28aa8baf Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 28 Apr 2017 12:32:03 -0600 Subject: [PATCH 632/990] Add all network IOCTLs to include/sys/ioctl.h --- include/sys/ioctl.h | 20 +++++++++++++++++--- 1 file changed, 17 insertions(+), 3 deletions(-) diff --git a/include/sys/ioctl.h b/include/sys/ioctl.h index 985ca1357b..acbcc1d3e6 100644 --- a/include/sys/ioctl.h +++ b/include/sys/ioctl.h @@ -45,11 +45,25 @@ #include #include -/* Include network ioctls info */ +#if CONFIG_NSOCKET_DESCRIPTORS > 0 +#ifdef CONFIG_NET +/* Include network IOCTL definitions */ -#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0 -# include +# include + +#ifdef CONFIG_NETDEV_WIRELESS_IOCTL +/* Include wireless network IOCTL definitions */ + +# include +#endif +#endif /* CONFIG_NET */ + +#ifdef CONFIG_DRIVERS_WIRELESS +/* Include wireless character driver IOCTL definitions */ + +# include #endif +#endif /* CONFIG_NSOCKET_DESCRIPTORS > 0 */ /**************************************************************************** * Pre-processor Definitions -- GitLab From 1c3d0cbbdd33165a7a1292612fe519a358874fae Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 28 Apr 2017 12:41:51 -0600 Subject: [PATCH 633/990] Add all ieee802.15.4 IOCTLs to include/sys/ioctl.h --- include/sys/ioctl.h | 21 +++++++++++++++++++++ 1 file changed, 21 insertions(+) diff --git a/include/sys/ioctl.h b/include/sys/ioctl.h index acbcc1d3e6..e993a8d6b9 100644 --- a/include/sys/ioctl.h +++ b/include/sys/ioctl.h @@ -63,6 +63,27 @@ # include #endif + +#ifdef CONFIG_WIRELESS_IEEE802154 +#ifdef CONFIG_IEEE802154_DEV +/* Include ieee802.15.4 radio IOCTL definitions */ + +# include +#endif + +#ifdef CONFIG_IEEE802154_MAC +/* Include ieee802.15.4 MAC IOCTL definitions */ + +# include +#endif + +#ifdef CONFIG_IEEE802154_MAC_DEV +/* Include ieee802.15.4 character driver IOCTL definitions */ + +# include +#endif + +#endif /* CONFIG_WIRELESS_IEEE802154 */ #endif /* CONFIG_NSOCKET_DESCRIPTORS > 0 */ /**************************************************************************** -- GitLab From faeef8e70012fab64c712f1a5895ef15b0e3b8dc Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Sat, 29 Apr 2017 09:03:32 +0200 Subject: [PATCH 634/990] Make value an uint32 before shifting 16 places left --- include/nuttx/spi/spi.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/include/nuttx/spi/spi.h b/include/nuttx/spi/spi.h index 92d2ecb4b8..7d59ab0214 100644 --- a/include/nuttx/spi/spi.h +++ b/include/nuttx/spi/spi.h @@ -458,12 +458,12 @@ enum spi_devtype_e /* This builds a SPI devid from its type and index */ -#define SPIDEV_ID(type,index) (((type)&0xFFFF)<<16 | (index)&0xFFFF) +#define SPIDEV_ID(type,index) (((uint32_t)(type)&0xFFFF)<<16 | (uint32_t)(index)&0xFFFF) /* This retrieves the fields from a SPI devid */ -#define SPIDEVID_TYPE (devid) (((devid)>>16)&0xFFFF) -#define SPIDEVID_INDEX(devid) ( (devid) &0xFFFF) +#define SPIDEVID_TYPE (devid) (((uint32_t)(devid)>>16)&0xFFFF) +#define SPIDEVID_INDEX(devid) ( (uint32_t)(devid) &0xFFFF) /* These are replacement definitions for the currently used SPI device indexes. * They are meant as a compatibility measure. it is expected that new drivers -- GitLab From b6b16bf4da6a3e2a9875d561ffbab14c08703607 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 29 Apr 2017 06:59:35 -0600 Subject: [PATCH 635/990] Fix forward references that were mangled in last large changes. --- arch/arm/src/efm32/efm32_spi.h | 1 - arch/arm/src/imx1/imx_cspi.h | 1 - arch/arm/src/imx6/imx_ecspi.h | 1 - arch/arm/src/kl/kl_spi.h | 1 - arch/arm/src/lpc17xx/lpc17_spi.h | 1 - arch/arm/src/lpc2378/lpc23xx_spi.h | 1 - arch/arm/src/lpc31xx/lpc31.h | 2 -- arch/arm/src/sam34/sam_spi.h | 1 - arch/arm/src/sama5/sam_spi.h | 1 - arch/arm/src/samdl/sam_spi.h | 1 - arch/arm/src/samv7/sam_spi.h | 1 - arch/arm/src/tiva/tiva_ssi.h | 1 - arch/avr/src/avr/avr.h | 2 -- arch/hc/src/m9s12/m9s12.h | 2 -- arch/mips/src/pic32mx/pic32mx.h | 2 -- arch/mips/src/pic32mz/pic32mz-spi.h | 1 - arch/x86/src/qemu/qemu.h | 3 --- arch/z16/src/z16f/chip.h | 1 - configs/mirtoo/src/pic32_spi2.c | 1 - configs/pic32mx-starterkit/src/pic32mx_spi.c | 1 - configs/pic32mx7mmb/src/pic32_spi.c | 1 - configs/pic32mz-starterkit/src/pic32mz_spi.c | 1 - 22 files changed, 28 deletions(-) diff --git a/arch/arm/src/efm32/efm32_spi.h b/arch/arm/src/efm32/efm32_spi.h index 1108eec2ac..9e84fb68dc 100644 --- a/arch/arm/src/efm32/efm32_spi.h +++ b/arch/arm/src/efm32/efm32_spi.h @@ -52,7 +52,6 @@ ****************************************************************************/ struct spi_dev_s; /* Forward reference */ -uint32_t; /* Forward reference */ /**************************************************************************** * Name: efm32_spibus_initialize diff --git a/arch/arm/src/imx1/imx_cspi.h b/arch/arm/src/imx1/imx_cspi.h index af36d194ba..f15872c49b 100644 --- a/arch/arm/src/imx1/imx_cspi.h +++ b/arch/arm/src/imx1/imx_cspi.h @@ -178,7 +178,6 @@ extern "C" ************************************************************************************/ struct spi_dev_s; /* Forward reference */ -uint32_t; /* Forward reference */ /**************************************************************************** * Name: imx_spibus_initialize diff --git a/arch/arm/src/imx6/imx_ecspi.h b/arch/arm/src/imx6/imx_ecspi.h index 8807c23145..ac30d2291f 100644 --- a/arch/arm/src/imx6/imx_ecspi.h +++ b/arch/arm/src/imx6/imx_ecspi.h @@ -70,7 +70,6 @@ extern "C" ************************************************************************************/ struct spi_dev_s; /* Forward reference */ -uint32_t; /* Forward reference */ /************************************************************************************ * Name: imx_spibus_initialize diff --git a/arch/arm/src/kl/kl_spi.h b/arch/arm/src/kl/kl_spi.h index d2f4824b73..fd621858a6 100644 --- a/arch/arm/src/kl/kl_spi.h +++ b/arch/arm/src/kl/kl_spi.h @@ -64,7 +64,6 @@ extern "C" ************************************************************************************/ struct spi_dev_s; /* Forward reference */ -uint32_t; /* Forward reference */ /**************************************************************************** * Name: kl_spibus_initialize diff --git a/arch/arm/src/lpc17xx/lpc17_spi.h b/arch/arm/src/lpc17xx/lpc17_spi.h index 1934eb582f..27d9ba8bb9 100644 --- a/arch/arm/src/lpc17xx/lpc17_spi.h +++ b/arch/arm/src/lpc17xx/lpc17_spi.h @@ -71,7 +71,6 @@ extern "C" ************************************************************************************/ struct spi_dev_s; /* Forward reference */ -uint32_t; /* Forward reference */ /************************************************************************************ * Name: lpc17_spibus_initialize diff --git a/arch/arm/src/lpc2378/lpc23xx_spi.h b/arch/arm/src/lpc2378/lpc23xx_spi.h index 08ffcfbbbf..8b5fbda37c 100644 --- a/arch/arm/src/lpc2378/lpc23xx_spi.h +++ b/arch/arm/src/lpc2378/lpc23xx_spi.h @@ -154,7 +154,6 @@ ************************************************************************************/ struct spi_dev_s; /* Forward reference */ -uint32_t; /* Forward reference */ /**************************************************************************** * Name: lpc23_spibus_initialize diff --git a/arch/arm/src/lpc31xx/lpc31.h b/arch/arm/src/lpc31xx/lpc31.h index de9294928a..00ce6b8e35 100644 --- a/arch/arm/src/lpc31xx/lpc31.h +++ b/arch/arm/src/lpc31xx/lpc31.h @@ -185,8 +185,6 @@ void lpc31_clockconfig(void); ************************************************************************************/ struct spi_dev_s; /* Forward reference */ -uint32_t; /* Forward reference */ - FAR struct spi_dev_s *lpc31_spibus_initialize(int port); /************************************************************************************ diff --git a/arch/arm/src/sam34/sam_spi.h b/arch/arm/src/sam34/sam_spi.h index f3bebd11f1..8cebb2f121 100644 --- a/arch/arm/src/sam34/sam_spi.h +++ b/arch/arm/src/sam34/sam_spi.h @@ -110,7 +110,6 @@ extern "C" ****************************************************************************/ struct spi_dev_s; /* Forward reference */ -uint32_t; /* Forward reference */ /**************************************************************************** * Name: sam_spibus_initialize diff --git a/arch/arm/src/sama5/sam_spi.h b/arch/arm/src/sama5/sam_spi.h index ad73fdf78b..705f2248e7 100644 --- a/arch/arm/src/sama5/sam_spi.h +++ b/arch/arm/src/sama5/sam_spi.h @@ -104,7 +104,6 @@ extern "C" ****************************************************************************/ struct spi_dev_s; /* Forward reference */ -uint32_t; /* Forward reference */ /**************************************************************************** * Name: sam_spibus_initialize diff --git a/arch/arm/src/samdl/sam_spi.h b/arch/arm/src/samdl/sam_spi.h index 4bfff626a2..7e0cbfa9e0 100644 --- a/arch/arm/src/samdl/sam_spi.h +++ b/arch/arm/src/samdl/sam_spi.h @@ -87,7 +87,6 @@ extern "C" ****************************************************************************/ struct spi_dev_s; /* Forward reference */ -uint32_t; /* Forward reference */ /**************************************************************************** * Name: sam_spibus_initialize diff --git a/arch/arm/src/samv7/sam_spi.h b/arch/arm/src/samv7/sam_spi.h index fc24b289f1..762f34f67d 100644 --- a/arch/arm/src/samv7/sam_spi.h +++ b/arch/arm/src/samv7/sam_spi.h @@ -158,7 +158,6 @@ extern "C" ****************************************************************************/ struct spi_dev_s; /* Forward reference */ -uint32_t; /* Forward reference */ struct spi_sctrlr_s; /* Forward reference */ /**************************************************************************** diff --git a/arch/arm/src/tiva/tiva_ssi.h b/arch/arm/src/tiva/tiva_ssi.h index 54d2004702..d0976c2aee 100644 --- a/arch/arm/src/tiva/tiva_ssi.h +++ b/arch/arm/src/tiva/tiva_ssi.h @@ -108,7 +108,6 @@ FAR struct spi_dev_s *tiva_ssibus_initialize(int port); ****************************************************************************/ struct spi_dev_s; -uint32_t; void tiva_ssiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); uint8_t tiva_ssistatus(FAR struct spi_dev_s *dev, uint32_t devid); #ifdef CONFIG_SPI_CMDDATA diff --git a/arch/avr/src/avr/avr.h b/arch/avr/src/avr/avr.h index a06de4c024..431c925067 100644 --- a/arch/avr/src/avr/avr.h +++ b/arch/avr/src/avr/avr.h @@ -151,8 +151,6 @@ uint8_t *up_doirq(uint8_t irq, uint8_t *regs); ****************************************************************************/ struct spi_dev_s; /* Forward references */ -uint32_t; /* Forward references */ - FAR struct spi_dev_s *avr_spibus_initialize(int port); /************************************************************************************ diff --git a/arch/hc/src/m9s12/m9s12.h b/arch/hc/src/m9s12/m9s12.h index 921c4efa96..53da6a7726 100644 --- a/arch/hc/src/m9s12/m9s12.h +++ b/arch/hc/src/m9s12/m9s12.h @@ -338,8 +338,6 @@ int hcs12_ethinitialize(int intf); ****************************************************************************/ struct spi_dev_s; /* Forward reference */ -uint32_t; /* Forward reference */ - FAR struct spi_dev_s *hcs12_spibus_initialize(int port); /************************************************************************************ diff --git a/arch/mips/src/pic32mx/pic32mx.h b/arch/mips/src/pic32mx/pic32mx.h index cd2272597a..480ff80fb8 100644 --- a/arch/mips/src/pic32mx/pic32mx.h +++ b/arch/mips/src/pic32mx/pic32mx.h @@ -400,8 +400,6 @@ void pic32mx_dumpgpio(uint32_t pinset, const char *msg); ****************************************************************************/ struct spi_dev_s; /* Forward reference */ -uint32_t; /* Forward reference */ - FAR struct spi_dev_s *pic32mx_spibus_initialize(int port); /************************************************************************************ diff --git a/arch/mips/src/pic32mz/pic32mz-spi.h b/arch/mips/src/pic32mz/pic32mz-spi.h index 1cbc8e4be3..ce4d772e0a 100644 --- a/arch/mips/src/pic32mz/pic32mz-spi.h +++ b/arch/mips/src/pic32mz/pic32mz-spi.h @@ -71,7 +71,6 @@ extern "C" ************************************************************************************/ struct spi_dev_s; /* Forward reference */ -uint32_t; /* Forward reference */ /**************************************************************************** * Name: pic32mz_spibus_initialize diff --git a/arch/x86/src/qemu/qemu.h b/arch/x86/src/qemu/qemu.h index 6eada26a05..3a073376dc 100644 --- a/arch/x86/src/qemu/qemu.h +++ b/arch/x86/src/qemu/qemu.h @@ -208,8 +208,6 @@ int i486_dumpgpio(uint16_t pinset, const char *msg); ****************************************************************************/ struct spi_dev_s; /* Forward reference */ -uint32_t; /* Forward reference */ - FAR struct spi_dev_s *i486_spibus_initialize(int port); /************************************************************************************ @@ -242,7 +240,6 @@ FAR struct spi_dev_s *i486_spibus_initialize(int port); ************************************************************************************/ struct spi_dev_s; -uint32_t; #ifdef CONFIG_I486_SPI void i486_spiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); diff --git a/arch/z16/src/z16f/chip.h b/arch/z16/src/z16f/chip.h index f54a188a22..b395c6e3b5 100644 --- a/arch/z16/src/z16f/chip.h +++ b/arch/z16/src/z16f/chip.h @@ -677,7 +677,6 @@ void z16f_reset(void); #ifdef CONFIG_Z16F_ESPI struct spi_dev_s; /* Forward reference */ -uint32_t; /* Forward reference */ /* Initialize the selected SPI port */ diff --git a/configs/mirtoo/src/pic32_spi2.c b/configs/mirtoo/src/pic32_spi2.c index 6773995cdb..df7fbd3fe6 100644 --- a/configs/mirtoo/src/pic32_spi2.c +++ b/configs/mirtoo/src/pic32_spi2.c @@ -154,7 +154,6 @@ void weak_function pic32mx_spi2initialize(void) ************************************************************************************/ struct spi_dev_s; -uint32_t; void pic32mx_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { diff --git a/configs/pic32mx-starterkit/src/pic32mx_spi.c b/configs/pic32mx-starterkit/src/pic32mx_spi.c index 342b6797f5..9f8d2262ba 100644 --- a/configs/pic32mx-starterkit/src/pic32mx_spi.c +++ b/configs/pic32mx-starterkit/src/pic32mx_spi.c @@ -102,7 +102,6 @@ void weak_function pic32mx_spidev_initialize(void) ************************************************************************************/ struct spi_dev_s; -uint32_t; #ifdef CONFIG_PIC32MX_SPI1 void pic32mx_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) diff --git a/configs/pic32mx7mmb/src/pic32_spi.c b/configs/pic32mx7mmb/src/pic32_spi.c index 5af04e598c..f1d65cb8ed 100644 --- a/configs/pic32mx7mmb/src/pic32_spi.c +++ b/configs/pic32mx7mmb/src/pic32_spi.c @@ -128,7 +128,6 @@ void weak_function pic32mx_spidev_initialize(void) ************************************************************************************/ struct spi_dev_s; -uint32_t; #ifdef CONFIG_PIC32MX_SPI1 void pic32mx_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) diff --git a/configs/pic32mz-starterkit/src/pic32mz_spi.c b/configs/pic32mz-starterkit/src/pic32mz_spi.c index d3c7341cdc..1de5d9ac9d 100644 --- a/configs/pic32mz-starterkit/src/pic32mz_spi.c +++ b/configs/pic32mz-starterkit/src/pic32mz_spi.c @@ -100,7 +100,6 @@ void weak_function pic32mz_spidev_initialize(void) ************************************************************************************/ struct spi_dev_s; -uint32_t; #ifdef CONFIG_PIC32MZ_SPI1 void pic32mz_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) -- GitLab From 8262c05713ab8554ff73366b36db3d0d3a59f384 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 29 Apr 2017 08:23:59 -0600 Subject: [PATCH 636/990] sixlowpan: Can't reuse same header on each fragment. DSN needs to increment. --- net/sixlowpan/README.txt | 4 ++-- net/sixlowpan/sixlowpan_framelist.c | 18 +++++++++++++----- net/sixlowpan/sixlowpan_framer.c | 4 ++-- wireless/ieee802154/mac802154_loopback.c | 4 ++++ 4 files changed, 21 insertions(+), 9 deletions(-) diff --git a/net/sixlowpan/README.txt b/net/sixlowpan/README.txt index ca8a513d6a..5b6b4e298d 100644 --- a/net/sixlowpan/README.txt +++ b/net/sixlowpan/README.txt @@ -49,7 +49,7 @@ The length of the fragment header length is four bytes for the first header (FRAG1) and five bytes for all subsequent headers (FRAGN). For example, this is a HC1 compressed first frame of a packet - 41 88 01 cefa 3412 cdab ### 9-byte MAC header + 41 88 2a cefa 3412 cdab ### 9-byte MAC header c50e 000b ### 4-byte FRAG1 header 42 ### SIXLOWPAN_DISPATCH_HC1 fb ### RIME_HC1_HC_UDP_HC1_ENCODING @@ -66,7 +66,7 @@ this is a HC1 compressed first frame of a packet This is the second frame of the same transfer: - 41 88 01 cefa 3412 cdab ### 9-byte MAC header + 41 88 2b cefa 3412 cdab ### 9-byte MAC header e50e 000b 0d ### 5 byte FRAGN header 42 ### SIXLOWPAN_DISPATCH_HC1 fb ### RIME_HC1_HC_UDP_HC1_ENCODING diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c index c9985872ba..9f7a68a1f7 100644 --- a/net/sixlowpan/sixlowpan_framelist.c +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -281,7 +281,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, ninfo("Sending packet length %d\n", buflen); - /* Set the source and destinatino address */ + /* Set the source and destination address */ rimeaddr_copy(&g_pktaddrs[PACKETBUF_ADDR_SENDER], &ieee->i_dev.d_mac.ieee802154); @@ -348,7 +348,9 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, ninfo("Sending fragmented packet length %d\n", buflen); /* Create 1st Fragment */ - /* Add the frame header using the pre-allocated IOB. */ + /* Add the frame header using the pre-allocated IOB using the DSN + * selected by sixlowpan_send_hdrlen(). + */ verify = sixlowpan_framecreate(ieee, iob, ieee->i_panid); DEBUGASSERT(verify == framer_hdrlen); @@ -434,11 +436,17 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, iob->io_pktlen = 0; fptr = iob->io_data; - /* Copy the frame header at the beginning of the frame. */ + /* Add a new frame header to the IOB (same as the first but with a + * different DSN). + */ + + g_pktattrs[PACKETBUF_ATTR_MAC_SEQNO] = 0; - memcpy(fptr, frame1, framer_hdrlen); + verify = sixlowpan_framecreate(ieee, iob, ieee->i_panid); + DEBUGASSERT(verify == framer_hdrlen); + UNUSED(verify); - /* Move HC1/HC06/IPv6 header the frame header from first + /* Copy the HC1/HC06/IPv6 header the frame header from first * frame, into the correct location after the FRAGN header * of subsequent frames. */ diff --git a/net/sixlowpan/sixlowpan_framer.c b/net/sixlowpan/sixlowpan_framer.c index 13aa9fecd3..da52303c6c 100644 --- a/net/sixlowpan/sixlowpan_framer.c +++ b/net/sixlowpan/sixlowpan_framer.c @@ -322,12 +322,12 @@ static void sixlowpan_setup_params(FAR struct ieee802154_driver_s *ieee, if (g_pktattrs[PACKETBUF_ATTR_MAC_SEQNO] != 0) { - params->seq = g_pktattrs[PACKETBUF_ATTR_MAC_SEQNO]; + params->seq = g_pktattrs[PACKETBUF_ATTR_MAC_SEQNO] & 0xff; } else { params->seq = ieee->i_dsn++; - g_pktattrs[PACKETBUF_ATTR_MAC_SEQNO] = params->seq; + g_pktattrs[PACKETBUF_ATTR_MAC_SEQNO] = params->seq | 0x100; } /* Complete the addressing fields. */ diff --git a/wireless/ieee802154/mac802154_loopback.c b/wireless/ieee802154/mac802154_loopback.c index af1320fccf..f914b5db1a 100644 --- a/wireless/ieee802154/mac802154_loopback.c +++ b/wireless/ieee802154/mac802154_loopback.c @@ -618,6 +618,10 @@ int ieee8021514_loopback(void) priv->lo_polldog = wd_create(); /* Create periodic poll timer */ + /* Initialize the DSN to a "random" value */ + + priv->lo_ieee.i_dsn = 42; + /* Register the loopabck device with the OS so that socket IOCTLs can b * performed. */ -- GitLab From f175af3cd34b3a2f2dd4c1809c9adc7ad0080d96 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 29 Apr 2017 08:29:01 -0600 Subject: [PATCH 637/990] More missed enum spi_dev_e forward references. --- arch/arm/src/kinetis/kinetis_spi.h | 3 +-- arch/arm/src/stm32/stm32_spi.h | 3 +-- arch/arm/src/stm32f7/stm32_spi.h | 3 +-- arch/arm/src/stm32l4/stm32l4_spi.h | 3 +-- arch/arm/src/xmc4/xmc4_spi.h | 3 +-- 5 files changed, 5 insertions(+), 10 deletions(-) diff --git a/arch/arm/src/kinetis/kinetis_spi.h b/arch/arm/src/kinetis/kinetis_spi.h index bbc097199f..8222af4424 100644 --- a/arch/arm/src/kinetis/kinetis_spi.h +++ b/arch/arm/src/kinetis/kinetis_spi.h @@ -63,8 +63,7 @@ extern "C" * Public Data ************************************************************************************/ -struct spi_dev_s; -enum spi_dev_e; +struct spi_dev_s; /**************************************************************************** * Public Function Prototypes diff --git a/arch/arm/src/stm32/stm32_spi.h b/arch/arm/src/stm32/stm32_spi.h index e874441809..9c757db523 100644 --- a/arch/arm/src/stm32/stm32_spi.h +++ b/arch/arm/src/stm32/stm32_spi.h @@ -64,8 +64,7 @@ extern "C" * Public Data ************************************************************************************/ -struct spi_dev_s; -enum spi_dev_e; +struct spi_dev_s; /************************************************************************************ * Public Functions diff --git a/arch/arm/src/stm32f7/stm32_spi.h b/arch/arm/src/stm32f7/stm32_spi.h index 475459a9a1..2775107356 100644 --- a/arch/arm/src/stm32f7/stm32_spi.h +++ b/arch/arm/src/stm32f7/stm32_spi.h @@ -63,8 +63,7 @@ extern "C" #define EXTERN extern #endif -struct spi_dev_s; /* Forward reference */ -enum spi_dev_e; /* Forward reference */ +struct spi_dev_s; /* Forward reference */ /************************************************************************************ * Name: stm32_spibus_initialize diff --git a/arch/arm/src/stm32l4/stm32l4_spi.h b/arch/arm/src/stm32l4/stm32l4_spi.h index 77ba1a3f1b..223cfb2b3d 100644 --- a/arch/arm/src/stm32l4/stm32l4_spi.h +++ b/arch/arm/src/stm32l4/stm32l4_spi.h @@ -64,8 +64,7 @@ extern "C" * Public Data ************************************************************************************/ -struct spi_dev_s; -enum spi_dev_e; +struct spi_dev_s; /************************************************************************************ * Public Functions diff --git a/arch/arm/src/xmc4/xmc4_spi.h b/arch/arm/src/xmc4/xmc4_spi.h index f95257a320..5113665eda 100644 --- a/arch/arm/src/xmc4/xmc4_spi.h +++ b/arch/arm/src/xmc4/xmc4_spi.h @@ -63,8 +63,7 @@ extern "C" * Public Data ************************************************************************************/ -struct spi_dev_s; -enum spi_dev_e; +struct spi_dev_s; /**************************************************************************** * Public Function Prototypes -- GitLab From 90db11494e4f2b7616f003ecdca79d1cc88e26df Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 29 Apr 2017 08:35:46 -0600 Subject: [PATCH 638/990] spi.h: Eliminate a warning --- include/nuttx/spi/spi.h | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/include/nuttx/spi/spi.h b/include/nuttx/spi/spi.h index 7d59ab0214..1718e51946 100644 --- a/include/nuttx/spi/spi.h +++ b/include/nuttx/spi/spi.h @@ -458,12 +458,13 @@ enum spi_devtype_e /* This builds a SPI devid from its type and index */ -#define SPIDEV_ID(type,index) (((uint32_t)(type)&0xFFFF)<<16 | (uint32_t)(index)&0xFFFF) +#define SPIDEV_ID(type,index) ((((uint32_t)(type) & 0xffff) << 16) | \ + (uint32_t)(index) & 0xffff) /* This retrieves the fields from a SPI devid */ -#define SPIDEVID_TYPE (devid) (((uint32_t)(devid)>>16)&0xFFFF) -#define SPIDEVID_INDEX(devid) ( (uint32_t)(devid) &0xFFFF) +#define SPIDEVID_TYPE (devid) (((uint32_t)(devid) >> 16) & 0xffff) +#define SPIDEVID_INDEX(devid) ((uint32_t)(devid) & 0xffff) /* These are replacement definitions for the currently used SPI device indexes. * They are meant as a compatibility measure. it is expected that new drivers -- GitLab From 11e15edfdfeb2bbbaf37e7f84b95a1bff3ca42ba Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 29 Apr 2017 08:59:45 -0600 Subject: [PATCH 639/990] Change to spi.h to follow coding standard --- include/nuttx/spi/spi.h | 72 +++++++++++++++++++++-------------------- 1 file changed, 37 insertions(+), 35 deletions(-) diff --git a/include/nuttx/spi/spi.h b/include/nuttx/spi/spi.h index 1718e51946..6f4e3a2028 100644 --- a/include/nuttx/spi/spi.h +++ b/include/nuttx/spi/spi.h @@ -420,41 +420,7 @@ #define SPI_REGISTERCALLBACK(d,c,a) \ ((d)->ops->registercallback ? (d)->ops->registercallback(d,c,a) : -ENOSYS) -/**************************************************************************** - * Public Types - ****************************************************************************/ - -/* The type of the media change callback function */ - -typedef void (*spi_mediachange_t)(FAR void *arg); - -/* If the board supports multiple SPI devices types, this enumeration - * identifies which is selected or de-selected. - * There may be more than one instance of each type on a bus, see below. - */ - -enum spi_devtype_e -{ - SPIDEVTYPE_NONE = 0, /* Not a valid value */ - SPIDEVTYPE_MMCSD, /* Select SPI MMC/SD device */ - SPIDEVTYPE_FLASH, /* Select SPI FLASH device */ - SPIDEVTYPE_ETHERNET, /* Select SPI Ethernet device */ - SPIDEVTYPE_DISPLAY, /* Select SPI LCD/OLED display device */ - SPIDEVTYPE_CAMERA, /* Select SPI imaging device */ - SPIDEVTYPE_WIRELESS, /* Select SPI Wireless device */ - SPIDEVTYPE_TOUCHSCREEN, /* Select SPI touchscreen device */ - SPIDEVTYPE_EXPANDER, /* Select SPI I/O expander device */ - SPIDEVTYPE_MUX, /* Select SPI multiplexer device */ - SPIDEVTYPE_AUDIO_DATA, /* Select SPI audio codec device data port */ - SPIDEVTYPE_AUDIO_CTRL, /* Select SPI audio codec device control port */ - SPIDEVTYPE_EEPROM, /* Select SPI EEPROM device */ - SPIDEVTYPE_ACCELEROMETER, /* Select SPI Accelerometer device */ - SPIDEVTYPE_BAROMETER, /* Select SPI Pressure/Barometer device */ - SPIDEVTYPE_TEMPERATURE, /* Select SPI Temperature sensor device */ - SPIDEVTYPE_IEEE802154, /* Select SPI IEEE 802.15.4 wireless device */ - SPIDEVTYPE_CONTACTLESS, /* Select SPI Contactless device */ - SPIDEVTYPE_USER /* Board-specific values start here */ -}; +/* SPI Device Macros ********************************************************/ /* This builds a SPI devid from its type and index */ @@ -491,6 +457,42 @@ enum spi_devtype_e #define SPIDEV_CONTACTLESS SPIDEV_ID(SPIDEVTYPE_CONTACTLESS , 0) #define SPIDEV_USER SPIDEV_ID(SPIDEVTYPE_USER , 0) +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* The type of the media change callback function */ + +typedef void (*spi_mediachange_t)(FAR void *arg); + +/* If the board supports multiple SPI devices types, this enumeration + * identifies which is selected or de-selected. + * There may be more than one instance of each type on a bus, see below. + */ + +enum spi_devtype_e +{ + SPIDEVTYPE_NONE = 0, /* Not a valid value */ + SPIDEVTYPE_MMCSD, /* Select SPI MMC/SD device */ + SPIDEVTYPE_FLASH, /* Select SPI FLASH device */ + SPIDEVTYPE_ETHERNET, /* Select SPI Ethernet device */ + SPIDEVTYPE_DISPLAY, /* Select SPI LCD/OLED display device */ + SPIDEVTYPE_CAMERA, /* Select SPI imaging device */ + SPIDEVTYPE_WIRELESS, /* Select SPI Wireless device */ + SPIDEVTYPE_TOUCHSCREEN, /* Select SPI touchscreen device */ + SPIDEVTYPE_EXPANDER, /* Select SPI I/O expander device */ + SPIDEVTYPE_MUX, /* Select SPI multiplexer device */ + SPIDEVTYPE_AUDIO_DATA, /* Select SPI audio codec device data port */ + SPIDEVTYPE_AUDIO_CTRL, /* Select SPI audio codec device control port */ + SPIDEVTYPE_EEPROM, /* Select SPI EEPROM device */ + SPIDEVTYPE_ACCELEROMETER, /* Select SPI Accelerometer device */ + SPIDEVTYPE_BAROMETER, /* Select SPI Pressure/Barometer device */ + SPIDEVTYPE_TEMPERATURE, /* Select SPI Temperature sensor device */ + SPIDEVTYPE_IEEE802154, /* Select SPI IEEE 802.15.4 wireless device */ + SPIDEVTYPE_CONTACTLESS, /* Select SPI Contactless device */ + SPIDEVTYPE_USER /* Board-specific values start here */ +}; + /* Certain SPI devices may required different clocking modes */ enum spi_mode_e -- GitLab From bfc1b0a55780e6c44dd521a0fc538f6bd4820c3d Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 29 Apr 2017 09:17:41 -0600 Subject: [PATCH 640/990] I am not sure why spi.h is still generating warnings. A few more parentheses and that seems to fix the problem --- include/nuttx/spi/spi.h | 36 ++++++++++++++++++------------------ 1 file changed, 18 insertions(+), 18 deletions(-) diff --git a/include/nuttx/spi/spi.h b/include/nuttx/spi/spi.h index 6f4e3a2028..7fbdf55a57 100644 --- a/include/nuttx/spi/spi.h +++ b/include/nuttx/spi/spi.h @@ -437,25 +437,25 @@ * will use SPIDEV_ID directly. */ -#define SPIDEV_NONE SPIDEV_ID(SPIDEVTYPE_NONE , 0) -#define SPIDEV_MMCSD SPIDEV_ID(SPIDEVTYPE_MMCSD , 0) -#define SPIDEV_FLASH SPIDEV_ID(SPIDEVTYPE_FLASH , 0) -#define SPIDEV_ETHERNET SPIDEV_ID(SPIDEVTYPE_ETHERNET , 0) -#define SPIDEV_DISPLAY SPIDEV_ID(SPIDEVTYPE_DISPLAY , 0) -#define SPIDEV_CAMERA SPIDEV_ID(SPIDEVTYPE_CAMERA , 0) -#define SPIDEV_WIRELESS SPIDEV_ID(SPIDEVTYPE_WIRELESS , 0) -#define SPIDEV_TOUCHSCREEN SPIDEV_ID(SPIDEVTYPE_TOUCHSCREEN , 0) -#define SPIDEV_EXPANDER SPIDEV_ID(SPIDEVTYPE_EXPANDER , 0) -#define SPIDEV_MUX SPIDEV_ID(SPIDEVTYPE_MUX , 0) -#define SPIDEV_AUDIO_DATA SPIDEV_ID(SPIDEVTYPE_AUDIO_DATA , 0) -#define SPIDEV_AUDIO_CTRL SPIDEV_ID(SPIDEVTYPE_AUDIO_CTRL , 0) -#define SPIDEV_EEPROM SPIDEV_ID(SPIDEVTYPE_EEPROM , 0) +#define SPIDEV_NONE SPIDEV_ID(SPIDEVTYPE_NONE, 0) +#define SPIDEV_MMCSD SPIDEV_ID(SPIDEVTYPE_MMCSD, 0) +#define SPIDEV_FLASH SPIDEV_ID(SPIDEVTYPE_FLASH, 0) +#define SPIDEV_ETHERNET SPIDEV_ID(SPIDEVTYPE_ETHERNET, 0) +#define SPIDEV_DISPLAY SPIDEV_ID(SPIDEVTYPE_DISPLAY, 0) +#define SPIDEV_CAMERA SPIDEV_ID(SPIDEVTYPE_CAMERA, 0) +#define SPIDEV_WIRELESS SPIDEV_ID(SPIDEVTYPE_WIRELESS, 0) +#define SPIDEV_TOUCHSCREEN SPIDEV_ID(SPIDEVTYPE_TOUCHSCREEN, 0) +#define SPIDEV_EXPANDER SPIDEV_ID(SPIDEVTYPE_EXPANDER, 0) +#define SPIDEV_MUX SPIDEV_ID(SPIDEVTYPE_MUX, 0) +#define SPIDEV_AUDIO_DATA SPIDEV_ID(SPIDEVTYPE_AUDIO_DATA, 0) +#define SPIDEV_AUDIO_CTRL SPIDEV_ID(SPIDEVTYPE_AUDIO_CTRL, 0) +#define SPIDEV_EEPROM SPIDEV_ID(SPIDEVTYPE_EEPROM, 0) #define SPIDEV_ACCELEROMETER SPIDEV_ID(SPIDEVTYPE_ACCELEROMETER, 0) -#define SPIDEV_BAROMETER SPIDEV_ID(SPIDEVTYPE_BAROMETER , 0) -#define SPIDEV_TEMPERATURE SPIDEV_ID(SPIDEVTYPE_TEMPERATURE , 0) -#define SPIDEV_IEEE802154 SPIDEV_ID(SPIDEVTYPE_IEEE802154 , 0) -#define SPIDEV_CONTACTLESS SPIDEV_ID(SPIDEVTYPE_CONTACTLESS , 0) -#define SPIDEV_USER SPIDEV_ID(SPIDEVTYPE_USER , 0) +#define SPIDEV_BAROMETER SPIDEV_ID(SPIDEVTYPE_BAROMETER, 0) +#define SPIDEV_TEMPERATURE SPIDEV_ID(SPIDEVTYPE_TEMPERATURE, 0) +#define SPIDEV_IEEE802154 SPIDEV_ID(SPIDEVTYPE_IEEE802154, 0) +#define SPIDEV_CONTACTLESS SPIDEV_ID(SPIDEVTYPE_CONTACTLESS, 0) +#define SPIDEV_USER SPIDEV_ID(SPIDEVTYPE_USER, 0) /**************************************************************************** * Public Types -- GitLab From 87a4181ba3e2cc38f15037911770fdc43753e03c Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 29 Apr 2017 09:30:17 -0600 Subject: [PATCH 641/990] cosmetic changes --- arch/avr/src/avr/avr.h | 3 ++- arch/x86/src/qemu/qemu.h | 6 ++---- 2 files changed, 4 insertions(+), 5 deletions(-) diff --git a/arch/avr/src/avr/avr.h b/arch/avr/src/avr/avr.h index 431c925067..0326d6d848 100644 --- a/arch/avr/src/avr/avr.h +++ b/arch/avr/src/avr/avr.h @@ -95,6 +95,8 @@ extern uint16_t g_idle_topstack; #ifndef __ASSEMBLY__ +struct spi_dev_s; /* Forward references */ + /************************************************************************************ * Name: up_copystate * @@ -150,7 +152,6 @@ uint8_t *up_doirq(uint8_t irq, uint8_t *regs); * ****************************************************************************/ -struct spi_dev_s; /* Forward references */ FAR struct spi_dev_s *avr_spibus_initialize(int port); /************************************************************************************ diff --git a/arch/x86/src/qemu/qemu.h b/arch/x86/src/qemu/qemu.h index 3a073376dc..561c68da44 100644 --- a/arch/x86/src/qemu/qemu.h +++ b/arch/x86/src/qemu/qemu.h @@ -83,6 +83,8 @@ extern "C" * Public Function Prototypes ************************************************************************************/ +struct spi_dev_s; /* Forward reference */ + /************************************************************************************ * Name: i486_clockconfig * @@ -207,7 +209,6 @@ int i486_dumpgpio(uint16_t pinset, const char *msg); * ****************************************************************************/ -struct spi_dev_s; /* Forward reference */ FAR struct spi_dev_s *i486_spibus_initialize(int port); /************************************************************************************ @@ -239,8 +240,6 @@ FAR struct spi_dev_s *i486_spibus_initialize(int port); * ************************************************************************************/ -struct spi_dev_s; - #ifdef CONFIG_I486_SPI void i486_spiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected); uint8_t i486_spistatus(FAR struct spi_dev_s *dev, uint32_t devid); @@ -265,7 +264,6 @@ int i486_spicmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd); * ****************************************************************************/ -struct spi_dev_s; #ifdef CONFIG_I486_SPI void spi_flush(FAR struct spi_dev_s *dev); #endif -- GitLab From 73c78fb6908959863e63c62f9b2cc0cef8accd92 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 29 Apr 2017 15:46:37 +0000 Subject: [PATCH 642/990] spi.h edited online with Bitbucket --- include/nuttx/spi/spi.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/nuttx/spi/spi.h b/include/nuttx/spi/spi.h index 7fbdf55a57..96868de155 100644 --- a/include/nuttx/spi/spi.h +++ b/include/nuttx/spi/spi.h @@ -425,7 +425,7 @@ /* This builds a SPI devid from its type and index */ #define SPIDEV_ID(type,index) ((((uint32_t)(type) & 0xffff) << 16) | \ - (uint32_t)(index) & 0xffff) + ((uint32_t)(index) & 0xffff)) /* This retrieves the fields from a SPI devid */ -- GitLab From 80bca0736dedd9c2f3ee3b9a04eb45364d1d9fa4 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 29 Apr 2017 10:26:02 -0600 Subject: [PATCH 643/990] Update some changes from last merge that are needed on this branch. --- net/sixlowpan/sixlowpan_framelist.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c index ed7cb345a2..91e3369b81 100644 --- a/net/sixlowpan/sixlowpan_framelist.c +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -452,7 +452,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, g_pktattrs[PACKETBUF_ATTR_MAC_SEQNO] = 0; - verify = sixlowpan_framecreate(ieee, iob, ieee->i_panid); + verify = sixlowpan_framecreate(ieee, iob, dest_panid); DEBUGASSERT(verify == framer_hdrlen); UNUSED(verify); -- GitLab From e9a54775061c4c3f7de74d9823c053e62028bc53 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 29 Apr 2017 12:26:52 -0600 Subject: [PATCH 644/990] Add an instance argument to the SPIDEV definitions. --- arch/arm/src/lpc31xx/lpc31_spi.c | 6 +-- arch/sim/src/up_spiflash.c | 2 +- configs/arduino-due/src/sam_mmcsd.c | 4 +- configs/clicker2-stm32/src/stm32_spi.c | 2 +- configs/cloudctrl/src/stm32_spi.c | 2 +- configs/eagle100/src/lm_ssi.c | 2 +- configs/ekk-lm3s9b96/src/lm_ssi.c | 4 +- configs/fire-stm32v2/src/stm32_spi.c | 4 +- configs/freedom-kl25z/src/kl_spi.c | 4 +- configs/hymini-stm32v/src/stm32_spi.c | 2 +- configs/lm3s6432-s2e/src/lm_ssi.c | 2 +- configs/lm3s6965-ek/src/lm_oled.c | 2 +- configs/lm3s6965-ek/src/lm_ssi.c | 4 +- configs/lm3s8962-ek/src/lm_oled.c | 2 +- configs/lm3s8962-ek/src/lm_ssi.c | 4 +- configs/lpcxpresso-lpc1115/src/lpc11_ssp.c | 6 +-- configs/lpcxpresso-lpc1768/src/lpc17_oled.c | 2 +- configs/lpcxpresso-lpc1768/src/lpc17_ssp.c | 6 +-- configs/maple/src/stm32_spi.c | 2 +- configs/mikroe-stm32f4/src/stm32_spi.c | 12 ++--- configs/mirtoo/src/pic32_spi2.c | 4 +- configs/nucleo-f303re/src/stm32_spi.c | 4 +- configs/nucleo-f4x1re/src/stm32_spi.c | 6 +-- configs/nucleo-l476rg/src/stm32_spi.c | 6 +-- configs/olimex-lpc1766stk/src/lpc17_ssp.c | 4 +- configs/olimex-stm32-p107/src/stm32_spi.c | 2 +- configs/olimexino-stm32/src/stm32_spi.c | 4 +- configs/open1788/src/lpc17_ssp.c | 2 +- configs/pic32mx7mmb/src/pic32_spi.c | 4 +- configs/sam3u-ek/src/sam_spi.c | 2 +- configs/sam4e-ek/src/sam_spi.c | 4 +- configs/sam4l-xplained/src/sam_spi.c | 8 ++-- configs/sama5d3-xplained/src/sam_spi.c | 2 +- configs/sama5d3x-ek/src/sam_spi.c | 2 +- configs/sama5d4-ek/src/sam_spi.c | 2 +- configs/samd20-xplained/src/sam_spi.c | 16 +++---- configs/samd21-xplained/src/sam_spi.c | 16 +++---- configs/saml21-xplained/src/sam_spi.c | 16 +++---- configs/shenzhou/src/stm32_spi.c | 12 ++--- configs/spark/src/stm32_spi.c | 4 +- configs/stm3210e-eval/src/stm32_spi.c | 2 +- configs/stm32_tiny/src/stm32_spi.c | 4 +- configs/stm32butterfly2/src/stm32_spi.c | 4 +- configs/stm32f103-minimum/src/stm32_spi.c | 14 +++--- .../stm32f429i-disco/src/stm32_ili93414ws.c | 6 +-- configs/stm32f429i-disco/src/stm32_l3gd20.c | 2 +- configs/stm32f429i-disco/src/stm32_spi.c | 6 +-- configs/stm32f4discovery/src/stm32_spi.c | 8 ++-- configs/stm32l476vg-disco/src/stm32_spi.c | 6 +-- configs/sure-pic32mx/src/pic32mx_spi.c | 8 ++-- configs/u-blox-c027/src/lpc17_ssp.c | 6 +-- configs/viewtool-stm32f107/src/stm32_spi.c | 2 +- configs/zkit-arm-1769/src/lpc17_lcd.c | 2 +- configs/zkit-arm-1769/src/lpc17_spi.c | 4 +- configs/zkit-arm-1769/src/lpc17_ssp.c | 4 +- configs/zp214xpa/src/lpc2148_spi1.c | 4 +- drivers/analog/Kconfig | 2 +- drivers/analog/pga11x.c | 24 +++++----- drivers/audio/vs1053.c | 14 +++--- drivers/contactless/mfrc522.c | 4 +- drivers/contactless/pn532.c | 4 +- drivers/eeprom/spi_xx25xx.c | 16 +++---- drivers/input/ads7843e.c | 8 ++-- drivers/input/max11802.c | 24 +++++----- drivers/lcd/memlcd.c | 4 +- drivers/lcd/nokia6100.c | 4 +- drivers/lcd/p14201.c | 6 +-- drivers/lcd/ssd1306_spi.c | 4 +- drivers/lcd/ssd1351.c | 8 ++-- drivers/lcd/st7567.c | 16 +++---- drivers/lcd/ug-2864ambag01.c | 32 ++++++------- drivers/lcd/ug-9664hswag01.c | 16 +++---- drivers/mmcsd/mmcsd_spi.c | 42 ++++++++--------- drivers/mtd/at24xx.c | 2 +- drivers/mtd/at25.c | 36 +++++++-------- drivers/mtd/at45db.c | 40 ++++++++-------- drivers/mtd/is25xp.c | 44 +++++++++--------- drivers/mtd/m25px.c | 36 +++++++-------- drivers/mtd/mtd_rwbuffer.c | 2 +- drivers/mtd/mx25lx.c | 36 +++++++-------- drivers/mtd/n25qxxx.c | 2 +- drivers/mtd/ramtron.c | 24 +++++----- drivers/mtd/s25fl1.c | 2 +- drivers/mtd/sector512.c | 2 +- drivers/mtd/sst25.c | 40 ++++++++-------- drivers/mtd/sst25xx.c | 46 +++++++++---------- drivers/mtd/sst26.c | 44 +++++++++--------- drivers/mtd/w25.c | 46 +++++++++---------- drivers/net/enc28j60.c | 28 +++++------ drivers/net/encx24j600.c | 32 ++++++------- drivers/sensors/adxl345_spi.c | 12 ++--- drivers/sensors/max31855.c | 4 +- drivers/sensors/max6675.c | 4 +- drivers/sensors/mpl115a.c | 4 +- drivers/sensors/xen1210.c | 8 ++-- drivers/wireless/cc1101.c | 4 +- drivers/wireless/cc3000/cc3000.c | 4 +- drivers/wireless/ieee802154/mrf24j40.c | 8 ++-- drivers/wireless/nrf24l01.c | 12 ++--- include/nuttx/analog/pga11x.h | 2 +- include/nuttx/contactless/pn532.h | 2 +- include/nuttx/spi/spi.h | 42 ++++++++--------- 102 files changed, 536 insertions(+), 536 deletions(-) diff --git a/arch/arm/src/lpc31xx/lpc31_spi.c b/arch/arm/src/lpc31xx/lpc31_spi.c index 9f64e5d772..871eca69da 100644 --- a/arch/arm/src/lpc31xx/lpc31_spi.c +++ b/arch/arm/src/lpc31xx/lpc31_spi.c @@ -491,15 +491,15 @@ static void spi_select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) * be in board specific code..... */ switch (devid) { - case SPIDEV_FLASH: + case SPIDEV_FLASH(0): slave = 0; break; - case SPIDEV_MMCSD: + case SPIDEV_MMCSD(0): slave = 1; break; - case SPIDEV_ETHERNET: + case SPIDEV_ETHERNET(0): slave = 2; break; diff --git a/arch/sim/src/up_spiflash.c b/arch/sim/src/up_spiflash.c index 46b96e2201..677bdafd96 100644 --- a/arch/sim/src/up_spiflash.c +++ b/arch/sim/src/up_spiflash.c @@ -362,7 +362,7 @@ static void spiflash_select(FAR struct spi_dev_s *dev, uint32_t devid, { FAR struct sim_spiflashdev_s *priv = (FAR struct sim_spiflashdev_s *)dev; - if (devid == SPIDEV_FLASH) + if (devid == SPIDEV_FLASH(0)) { priv->selected = selected; diff --git a/configs/arduino-due/src/sam_mmcsd.c b/configs/arduino-due/src/sam_mmcsd.c index bd60005f84..e6d461d58f 100644 --- a/configs/arduino-due/src/sam_mmcsd.c +++ b/configs/arduino-due/src/sam_mmcsd.c @@ -145,7 +145,7 @@ static int spi_cmddata(FAR struct spi_bitbang_s *priv, uint32_t devid, static void spi_select(FAR struct spi_bitbang_s *priv, uint32_t devid, bool selected) { - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { if (selected) { @@ -175,7 +175,7 @@ static void spi_select(FAR struct spi_bitbang_s *priv, uint32_t devid, static uint8_t spi_status(FAR struct spi_bitbang_s *priv, uint32_t devid) { - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { return SPI_STATUS_PRESENT; } diff --git a/configs/clicker2-stm32/src/stm32_spi.c b/configs/clicker2-stm32/src/stm32_spi.c index 1939c4c4c4..84e0538ab6 100644 --- a/configs/clicker2-stm32/src/stm32_spi.c +++ b/configs/clicker2-stm32/src/stm32_spi.c @@ -139,7 +139,7 @@ void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) switch(devid) { #ifdef CONFIG_IEEE802154_MRF24J40 - case SPIDEV_IEEE802154: + case SPIDEV_IEEE802154(0): /* Set the GPIO low to select and high to de-select */ stm32_gpiowrite(GPIO_MB1_CS, !selected); break; diff --git a/configs/cloudctrl/src/stm32_spi.c b/configs/cloudctrl/src/stm32_spi.c index e64428bc4b..4ba4e9560a 100644 --- a/configs/cloudctrl/src/stm32_spi.c +++ b/configs/cloudctrl/src/stm32_spi.c @@ -119,7 +119,7 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) /* SPI1 connects to the SD CARD and to the SPI FLASH */ - if (devid == SPIDEV_FLASH) + if (devid == SPIDEV_FLASH(0)) { /* Set the GPIO low to select and high to de-select */ diff --git a/configs/eagle100/src/lm_ssi.c b/configs/eagle100/src/lm_ssi.c index b6722c2ba1..a65fe7c085 100644 --- a/configs/eagle100/src/lm_ssi.c +++ b/configs/eagle100/src/lm_ssi.c @@ -110,7 +110,7 @@ void weak_function lm_ssidev_initialize(void) void tiva_ssiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { /* Assert the CS pin to the card */ diff --git a/configs/ekk-lm3s9b96/src/lm_ssi.c b/configs/ekk-lm3s9b96/src/lm_ssi.c index 05dbf37b5e..cb9ee6e245 100644 --- a/configs/ekk-lm3s9b96/src/lm_ssi.c +++ b/configs/ekk-lm3s9b96/src/lm_ssi.c @@ -111,14 +111,14 @@ void tiva_ssiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); ssi_dumpgpio("tiva_ssiselect() Entry"); - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { /* Assert the CS pin to the card */ tiva_gpiowrite(SDCCS_GPIO, !selected); } #ifdef CONFIG_NX_LCDDRIVER - else if (devid == SPIDEV_DISPLAY) + else if (devid == SPIDEV_DISPLAY(0)) { /* Assert the CS pin to the display */ diff --git a/configs/fire-stm32v2/src/stm32_spi.c b/configs/fire-stm32v2/src/stm32_spi.c index 43ffb030b9..a6b86ea92a 100644 --- a/configs/fire-stm32v2/src/stm32_spi.c +++ b/configs/fire-stm32v2/src/stm32_spi.c @@ -145,14 +145,14 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) else #endif #ifdef CONFIG_ENC28J60 - if (devid == SPIDEV_ETHERNET) + if (devid == SPIDEV_ETHERNET(0)) { /* Set the GPIO low to select and high to de-select */ stm32_gpiowrite(GPIO_ENC28J60_CS, !selected); } #else - if (devid == SPIDEV_FLASH) + if (devid == SPIDEV_FLASH(0)) { /* Set the GPIO low to select and high to de-select */ diff --git a/configs/freedom-kl25z/src/kl_spi.c b/configs/freedom-kl25z/src/kl_spi.c index ec26f436cd..e952963d1b 100644 --- a/configs/freedom-kl25z/src/kl_spi.c +++ b/configs/freedom-kl25z/src/kl_spi.c @@ -146,7 +146,7 @@ void kl_spi0select(FAR struct spi_dev_s *dev, uint32_t devid, (int)devid, selected ? "assert" : "de-assert"); #ifdef CONFIG_ADXL345_SPI - if (devid == SPIDEV_ACCELEROMETER) + if (devid == SPIDEV_ACCELEROMETER(0)) { /* Active low */ @@ -155,7 +155,7 @@ void kl_spi0select(FAR struct spi_dev_s *dev, uint32_t devid, #endif #if defined(CONFIG_WL_CC3000) - if (devid == SPIDEV_WIRELESS) + if (devid == SPIDEV_WIRELESS(0)) { kl_gpiowrite(GPIO_WIFI_CS, !selected); } diff --git a/configs/hymini-stm32v/src/stm32_spi.c b/configs/hymini-stm32v/src/stm32_spi.c index 3bd5b9a7e5..568cdb2494 100644 --- a/configs/hymini-stm32v/src/stm32_spi.c +++ b/configs/hymini-stm32v/src/stm32_spi.c @@ -111,7 +111,7 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); - if (devid == SPIDEV_TOUCHSCREEN) + if (devid == SPIDEV_TOUCHSCREEN(0)) { /* Set the GPIO low to select and high to de-select */ diff --git a/configs/lm3s6432-s2e/src/lm_ssi.c b/configs/lm3s6432-s2e/src/lm_ssi.c index b9398dc0fe..7b185642fc 100644 --- a/configs/lm3s6432-s2e/src/lm_ssi.c +++ b/configs/lm3s6432-s2e/src/lm_ssi.c @@ -110,7 +110,7 @@ void tiva_ssiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); ssi_dumpgpio("tiva_ssiselect() Entry"); - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { /* Assert the CS pin to the card */ diff --git a/configs/lm3s6965-ek/src/lm_oled.c b/configs/lm3s6965-ek/src/lm_oled.c index fa02d2b2e8..93705b76cd 100644 --- a/configs/lm3s6965-ek/src/lm_oled.c +++ b/configs/lm3s6965-ek/src/lm_oled.c @@ -164,7 +164,7 @@ FAR struct lcd_dev_s *board_graphics_setup(unsigned int devno) int tiva_ssicmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { - if (devid == SPIDEV_DISPLAY) + if (devid == SPIDEV_DISPLAY(0)) { /* Set GPIO to 1 for data, 0 for command */ diff --git a/configs/lm3s6965-ek/src/lm_ssi.c b/configs/lm3s6965-ek/src/lm_ssi.c index 52955e068d..980796f4a2 100644 --- a/configs/lm3s6965-ek/src/lm_ssi.c +++ b/configs/lm3s6965-ek/src/lm_ssi.c @@ -115,14 +115,14 @@ void tiva_ssiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); ssi_dumpgpio("tiva_ssiselect() Entry"); - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { /* Assert the CS pin to the card */ tiva_gpiowrite(SDCCS_GPIO, !selected); } #ifdef CONFIG_NX_LCDDRIVER - else if (devid == SPIDEV_DISPLAY) + else if (devid == SPIDEV_DISPLAY(0)) { /* Assert the CS pin to the display */ diff --git a/configs/lm3s8962-ek/src/lm_oled.c b/configs/lm3s8962-ek/src/lm_oled.c index 491ee7c18f..cffc1e8a3c 100644 --- a/configs/lm3s8962-ek/src/lm_oled.c +++ b/configs/lm3s8962-ek/src/lm_oled.c @@ -162,7 +162,7 @@ FAR struct lcd_dev_s *board_graphics_setup(unsigned int devno) int tiva_ssicmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { - if (devid == SPIDEV_DISPLAY) + if (devid == SPIDEV_DISPLAY(0)) { /* Set GPIO to 1 for data, 0 for command */ diff --git a/configs/lm3s8962-ek/src/lm_ssi.c b/configs/lm3s8962-ek/src/lm_ssi.c index 260127aae0..3834ce5d78 100644 --- a/configs/lm3s8962-ek/src/lm_ssi.c +++ b/configs/lm3s8962-ek/src/lm_ssi.c @@ -115,14 +115,14 @@ void tiva_ssiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); ssi_dumpgpio("tiva_ssiselect() Entry"); - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { /* Assert the CS pin to the card */ tiva_gpiowrite(SDCCS_GPIO, !selected); } #ifdef CONFIG_NX_LCDDRIVER - else if (devid == SPIDEV_DISPLAY) + else if (devid == SPIDEV_DISPLAY(0)) { /* Assert the CS pin to the display */ diff --git a/configs/lpcxpresso-lpc1115/src/lpc11_ssp.c b/configs/lpcxpresso-lpc1115/src/lpc11_ssp.c index 8803aaba79..a0ae6871f1 100644 --- a/configs/lpcxpresso-lpc1115/src/lpc11_ssp.c +++ b/configs/lpcxpresso-lpc1115/src/lpc11_ssp.c @@ -153,14 +153,14 @@ void lpc11_ssp1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); ssp_dumpgpio("lpc11_ssp1select() Entry"); - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { /* Assert/de-assert the CS pin to the card */ (void)lpc11_gpiowrite(LPCXPRESSO_SD_CS, !selected); } #ifdef CONFIG_NX_LCDDRIVER - else if (devid == SPIDEV_DISPLAY) + else if (devid == SPIDEV_DISPLAY(0)) { /* Assert the CS pin to the OLED display */ @@ -172,7 +172,7 @@ void lpc11_ssp1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) uint8_t lpc11_ssp1status(FAR struct spi_dev_s *dev, uint32_t devid) { - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { /* Read the state of the card-detect bit */ diff --git a/configs/lpcxpresso-lpc1768/src/lpc17_oled.c b/configs/lpcxpresso-lpc1768/src/lpc17_oled.c index 55280e9091..62050a2297 100644 --- a/configs/lpcxpresso-lpc1768/src/lpc17_oled.c +++ b/configs/lpcxpresso-lpc1768/src/lpc17_oled.c @@ -161,7 +161,7 @@ FAR struct lcd_dev_s *board_graphics_setup(unsigned int devno) int lpc17_ssp1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { - if (devid == SPIDEV_DISPLAY) + if (devid == SPIDEV_DISPLAY(0)) { /* Set GPIO to 1 for data, 0 for command */ diff --git a/configs/lpcxpresso-lpc1768/src/lpc17_ssp.c b/configs/lpcxpresso-lpc1768/src/lpc17_ssp.c index 7411c9e16d..4aace2c26c 100644 --- a/configs/lpcxpresso-lpc1768/src/lpc17_ssp.c +++ b/configs/lpcxpresso-lpc1768/src/lpc17_ssp.c @@ -153,14 +153,14 @@ void lpc17_ssp1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); ssp_dumpgpio("lpc17_ssp1select() Entry"); - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { /* Assert/de-assert the CS pin to the card */ (void)lpc17_gpiowrite(LPCXPRESSO_SD_CS, !selected); } #ifdef CONFIG_NX_LCDDRIVER - else if (devid == SPIDEV_DISPLAY) + else if (devid == SPIDEV_DISPLAY(0)) { /* Assert the CS pin to the OLED display */ @@ -172,7 +172,7 @@ void lpc17_ssp1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) uint8_t lpc17_ssp1status(FAR struct spi_dev_s *dev, uint32_t devid) { - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { /* Read the state of the card-detect bit */ diff --git a/configs/maple/src/stm32_spi.c b/configs/maple/src/stm32_spi.c index a1c9ac3fcc..b13125d8c4 100644 --- a/configs/maple/src/stm32_spi.c +++ b/configs/maple/src/stm32_spi.c @@ -110,7 +110,7 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); # if defined(CONFIG_LCD_SHARP_MEMLCD) - if (devid == SPIDEV_DISPLAY) + if (devid == SPIDEV_DISPLAY(0)) { stm32_gpiowrite(GPIO_MEMLCD_CS, selected); } diff --git a/configs/mikroe-stm32f4/src/stm32_spi.c b/configs/mikroe-stm32f4/src/stm32_spi.c index 987bc2d450..05bb88a21a 100644 --- a/configs/mikroe-stm32f4/src/stm32_spi.c +++ b/configs/mikroe-stm32f4/src/stm32_spi.c @@ -127,11 +127,11 @@ void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #if defined(CONFIG_VS1053) - if (devid == SPIDEV_AUDIO_DATA) + if (devid == SPIDEV_AUDIO_DATA(0)) { stm32_gpiowrite(GPIO_CS_MP3_DATA, !selected); } - else if (devid == SPIDEV_AUDIO_CTRL) + else if (devid == SPIDEV_AUDIO_CTRL(0)) { stm32_gpiowrite(GPIO_CS_MP3_CMD, !selected); } @@ -139,7 +139,7 @@ void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) #endif #if defined(CONFIG_MMCSD) - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { stm32_gpiowrite(GPIO_CS_MMCSD, !selected); } @@ -147,7 +147,7 @@ void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) #endif #if defined(CONFIG_MTD_M25P) - if (devid == SPIDEV_FLASH) + if (devid == SPIDEV_FLASH(0)) { stm32_gpiowrite(GPIO_CS_FLASH, !selected); } @@ -156,7 +156,7 @@ void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) /* Must be the expansion header device */ - if (devid == SPIDEV_EXPANDER) + if (devid == SPIDEV_EXPANDER(0)) { stm32_gpiowrite(GPIO_CS_EXP_SPI3, !selected); } @@ -167,7 +167,7 @@ uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) uint8_t ret = 0; #if defined(CONFIG_MMCSD) - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { /* A low value indicates the card is present */ diff --git a/configs/mirtoo/src/pic32_spi2.c b/configs/mirtoo/src/pic32_spi2.c index df7fbd3fe6..2b74f7957b 100644 --- a/configs/mirtoo/src/pic32_spi2.c +++ b/configs/mirtoo/src/pic32_spi2.c @@ -159,11 +159,11 @@ void pic32mx_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selecte { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); - if (devid == SPIDEV_FLASH) + if (devid == SPIDEV_FLASH(0)) { pic32mx_gpiowrite(GPIO_SST25VF032B_CS, !selected); } - else if (devid == SPIDEV_MUX) + else if (devid == SPIDEV_MUX(0)) { pic32mx_gpiowrite(GPIO_PGA117_CS, !selected); } diff --git a/configs/nucleo-f303re/src/stm32_spi.c b/configs/nucleo-f303re/src/stm32_spi.c index 1a7e748a17..6e706a8509 100644 --- a/configs/nucleo-f303re/src/stm32_spi.c +++ b/configs/nucleo-f303re/src/stm32_spi.c @@ -109,7 +109,7 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #if defined(CONFIG_LCD_SSD1351) - if (devid == SPIDEV_DISPLAY) + if (devid == SPIDEV_DISPLAY(0)) { stm32_gpiowrite(GPIO_OLED_CS, !selected); } @@ -176,7 +176,7 @@ int stm32_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #ifdef CONFIG_LCD_SSD1351 - if (devid == SPIDEV_DISPLAY) + if (devid == SPIDEV_DISPLAY(0)) { (void)stm32_gpiowrite(GPIO_OLED_DC, !cmd); return OK; diff --git a/configs/nucleo-f4x1re/src/stm32_spi.c b/configs/nucleo-f4x1re/src/stm32_spi.c index bb56053168..cdcb582fd5 100644 --- a/configs/nucleo-f4x1re/src/stm32_spi.c +++ b/configs/nucleo-f4x1re/src/stm32_spi.c @@ -146,14 +146,14 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #ifdef CONFIG_WL_CC3000 - if (devid == SPIDEV_WIRELESS) + if (devid == SPIDEV_WIRELESS(0)) { stm32_gpiowrite(GPIO_SPI_CS_WIFI, !selected); } else #endif #ifdef HAVE_MMCSD - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { stm32_gpiowrite(GPIO_SPI_CS_SD_CARD, !selected); } @@ -172,7 +172,7 @@ void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #ifdef CONFIG_WL_CC3000 - if (devid == SPIDEV_WIRELESS) + if (devid == SPIDEV_WIRELESS(0)) { stm32_gpiowrite(GPIO_WIFI_CS, !selected); } diff --git a/configs/nucleo-l476rg/src/stm32_spi.c b/configs/nucleo-l476rg/src/stm32_spi.c index dcdda1a700..6e45b6f76c 100644 --- a/configs/nucleo-l476rg/src/stm32_spi.c +++ b/configs/nucleo-l476rg/src/stm32_spi.c @@ -146,14 +146,14 @@ void stm32l4_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #ifdef CONFIG_WL_CC3000 - if (devid == SPIDEV_WIRELESS) + if (devid == SPIDEV_WIRELESS(0)) { stm32l4_gpiowrite(GPIO_SPI_CS_WIFI, !selected); } else #endif #ifdef HAVE_MMCSD - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { stm32l4_gpiowrite(GPIO_SPI_CS_SD_CARD, !selected); } @@ -172,7 +172,7 @@ void stm32l4_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #ifdef CONFIG_WL_CC3000 - if (devid == SPIDEV_WIRELESS) + if (devid == SPIDEV_WIRELESS(0)) { stm32l4_gpiowrite(GPIO_WIFI_CS, !selected); } diff --git a/configs/olimex-lpc1766stk/src/lpc17_ssp.c b/configs/olimex-lpc1766stk/src/lpc17_ssp.c index ebfa370d12..5ef529f2a7 100644 --- a/configs/olimex-lpc1766stk/src/lpc17_ssp.c +++ b/configs/olimex-lpc1766stk/src/lpc17_ssp.c @@ -266,7 +266,7 @@ void weak_function lpc1766stk_sspdev_initialize(void) void lpc17_ssp0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); - if (devid == SPIDEV_DISPLAY) + if (devid == SPIDEV_DISPLAY(0)) { /* Assert/de-assert the CS pin to the card */ @@ -287,7 +287,7 @@ uint8_t lpc17_ssp0status(FAR struct spi_dev_s *dev, uint32_t devid) void lpc17_ssp1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { /* Assert/de-assert the CS pin to the card */ diff --git a/configs/olimex-stm32-p107/src/stm32_spi.c b/configs/olimex-stm32-p107/src/stm32_spi.c index ec1398542e..aa143b0888 100644 --- a/configs/olimex-stm32-p107/src/stm32_spi.c +++ b/configs/olimex-stm32-p107/src/stm32_spi.c @@ -112,7 +112,7 @@ void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); - if (devid == SPIDEV_ETHERNET) + if (devid == SPIDEV_ETHERNET(0)) { /* Set the GPIO low to select and high to de-select */ diff --git a/configs/olimexino-stm32/src/stm32_spi.c b/configs/olimexino-stm32/src/stm32_spi.c index 672c104b72..dd8fe9588c 100644 --- a/configs/olimexino-stm32/src/stm32_spi.c +++ b/configs/olimexino-stm32/src/stm32_spi.c @@ -110,7 +110,7 @@ void weak_function stm32_spidev_initialize(void) void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); - if (devid == SPIDEV_USER) + if (devid == SPIDEV_USER(0)) { stm32_gpiowrite(USER_CSn, !selected); } @@ -127,7 +127,7 @@ void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #if defined(CONFIG_MMCSD) - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { stm32_gpiowrite(MMCSD_CSn, !selected); } diff --git a/configs/open1788/src/lpc17_ssp.c b/configs/open1788/src/lpc17_ssp.c index df354c770f..e904144f24 100644 --- a/configs/open1788/src/lpc17_ssp.c +++ b/configs/open1788/src/lpc17_ssp.c @@ -146,7 +146,7 @@ uint8_t lpc17_ssp0status(FAR struct spi_dev_s *dev, uint32_t devid) void lpc17_ssp1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); - if (devid == SPIDEV_TOUCHSCREEN) + if (devid == SPIDEV_TOUCHSCREEN(0)) { /* Assert/de-assert the CS pin to the touchscreen */ diff --git a/configs/pic32mx7mmb/src/pic32_spi.c b/configs/pic32mx7mmb/src/pic32_spi.c index f1d65cb8ed..e12795b5f5 100644 --- a/configs/pic32mx7mmb/src/pic32_spi.c +++ b/configs/pic32mx7mmb/src/pic32_spi.c @@ -134,7 +134,7 @@ void pic32mx_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selecte { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { pic32mx_gpiowrite(GPIO_SD_CS, !selected); } @@ -146,7 +146,7 @@ uint8_t pic32mx_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) /* Card detect active low. */ - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { if (!pic32mx_gpioread(GPIO_SD_CD)) { diff --git a/configs/sam3u-ek/src/sam_spi.c b/configs/sam3u-ek/src/sam_spi.c index af55cb2884..a6a08e7090 100644 --- a/configs/sam3u-ek/src/sam_spi.c +++ b/configs/sam3u-ek/src/sam_spi.c @@ -149,7 +149,7 @@ void sam_spi0select(uint32_t devid, bool selected) */ #if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_ADS7843E) - if (devid == SPIDEV_TOUCHSCREEN) + if (devid == SPIDEV_TOUCHSCREEN(0)) { sam_gpiowrite(GPIO_TSC_NPCS2, !selected); } diff --git a/configs/sam4e-ek/src/sam_spi.c b/configs/sam4e-ek/src/sam_spi.c index 90d0e345fc..340210ec8c 100644 --- a/configs/sam4e-ek/src/sam_spi.c +++ b/configs/sam4e-ek/src/sam_spi.c @@ -153,7 +153,7 @@ void sam_spi0select(uint32_t devid, bool selected) * manually and hold it low throughout the SPI transfer. */ - case SPIDEV_TOUCHSCREEN: + case SPIDEV_TOUCHSCREEN(0): sam_gpiowrite(GPIO_TSC_CS, !selected); break; #endif @@ -161,7 +161,7 @@ void sam_spi0select(uint32_t devid, bool selected) #if defined(CONFIG_MTD_AT25) /* The AT25 Serial FLASH connects using NPCS3 (PA5). */ - case SPIDEV_FLASH: + case SPIDEV_FLASH(0): sam_gpiowrite(GPIO_FLASH_CS, !selected); break; #endif diff --git a/configs/sam4l-xplained/src/sam_spi.c b/configs/sam4l-xplained/src/sam_spi.c index be44a7f403..a6eeee18a2 100644 --- a/configs/sam4l-xplained/src/sam_spi.c +++ b/configs/sam4l-xplained/src/sam_spi.c @@ -145,7 +145,7 @@ void sam_spi0select(uint32_t devid, bool selected) #ifdef CONFIG_SAM4L_XPLAINED_IOMODULE /* Select/de-select the SD card */ - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { /* Active low */ @@ -160,7 +160,7 @@ void sam_spi0select(uint32_t devid, bool selected) #ifdef CONFIG_SAM4L_XPLAINED_OLED1MODULE /* Select/de-select the OLED */ - if (devid == SPIDEV_DISPLAY) + if (devid == SPIDEV_DISPLAY(0)) { /* Active low */ @@ -190,7 +190,7 @@ uint8_t sam_spi0status(FAR struct spi_dev_s *dev, uint32_t devid) #ifdef CONFIG_SAM4L_XPLAINED_IOMODULE /* Check if an SD card is present in the microSD slot */ - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { /* Active low */ @@ -234,7 +234,7 @@ uint8_t sam_spi0status(FAR struct spi_dev_s *dev, uint32_t devid) int sam_spic0mddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #ifdef CONFIG_SAM4L_XPLAINED_OLED1MODULE - if (devid == SPIDEV_DISPLAY) + if (devid == SPIDEV_DISPLAY(0)) { /* This is the Data/Command control pad which determines whether the * data bits are data or a command. diff --git a/configs/sama5d3-xplained/src/sam_spi.c b/configs/sama5d3-xplained/src/sam_spi.c index 93e965ffd6..a4e1b3d95d 100644 --- a/configs/sama5d3-xplained/src/sam_spi.c +++ b/configs/sama5d3-xplained/src/sam_spi.c @@ -145,7 +145,7 @@ void sam_spi0select(uint32_t devid, bool selected) #ifdef CONFIG_MTD_AT25 /* The AT25 serial FLASH connects using NPCS0 */ - if (devid == SPIDEV_FLASH) + if (devid == SPIDEV_FLASH(0)) { sam_piowrite(PIO_AT25_NPCS0, !selected); } diff --git a/configs/sama5d3x-ek/src/sam_spi.c b/configs/sama5d3x-ek/src/sam_spi.c index f4b4c00928..c9827f9a77 100644 --- a/configs/sama5d3x-ek/src/sam_spi.c +++ b/configs/sama5d3x-ek/src/sam_spi.c @@ -145,7 +145,7 @@ void sam_spi0select(uint32_t devid, bool selected) #ifdef CONFIG_MTD_AT25 /* The AT25 serial FLASH connects using NPCS0 */ - if (devid == SPIDEV_FLASH) + if (devid == SPIDEV_FLASH(0)) { sam_piowrite(PIO_AT25_NPCS0, !selected); } diff --git a/configs/sama5d4-ek/src/sam_spi.c b/configs/sama5d4-ek/src/sam_spi.c index 38cb1da36f..7534e373b1 100644 --- a/configs/sama5d4-ek/src/sam_spi.c +++ b/configs/sama5d4-ek/src/sam_spi.c @@ -145,7 +145,7 @@ void sam_spi0select(uint32_t devid, bool selected) #ifdef CONFIG_MTD_AT25 /* The AT25 serial FLASH connects using NPCS0 */ - if (devid == SPIDEV_FLASH) + if (devid == SPIDEV_FLASH(0)) { sam_piowrite(PIO_AT25_NPCS0, !selected); } diff --git a/configs/samd20-xplained/src/sam_spi.c b/configs/samd20-xplained/src/sam_spi.c index 61b254eec6..2367243fe5 100644 --- a/configs/samd20-xplained/src/sam_spi.c +++ b/configs/samd20-xplained/src/sam_spi.c @@ -154,7 +154,7 @@ void sam_spi0select(FAR struct spi_dev_s *dev, uint32_t devid, #ifdef CONFIG_SAMD20_XPLAINED_IOMODULE_EXT1 /* Select/de-select the SD card */ - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { /* Active low */ @@ -165,7 +165,7 @@ void sam_spi0select(FAR struct spi_dev_s *dev, uint32_t devid, #ifdef CONFIG_SAMD20_XPLAINED_OLED1MODULE_EXT1 /* Select/de-select the OLED */ - if (devid == SPIDEV_DISPLAY) + if (devid == SPIDEV_DISPLAY(0)) { /* Active low */ @@ -182,7 +182,7 @@ void sam_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, #ifdef CONFIG_SAMD20_XPLAINED_IOMODULE_EXT2 /* Select/de-select the SD card */ - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { /* Active low */ @@ -193,7 +193,7 @@ void sam_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, #ifdef CONFIG_SAMD20_XPLAINED_OLED1MODULE_EXT2 /* Select/de-select the OLED */ - if (devid == SPIDEV_DISPLAY) + if (devid == SPIDEV_DISPLAY(0)) { /* Active low */ @@ -254,7 +254,7 @@ uint8_t sam_spi0status(FAR struct spi_dev_s *dev, uint32_t devid) #ifdef CONFIG_SAMD20_XPLAINED_IOMODULE_EXT1 /* Check if an SD card is present in the microSD slot */ - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { /* Active low */ @@ -277,7 +277,7 @@ uint8_t sam_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) #ifdef CONFIG_SAMD20_XPLAINED_IOMODULE_EXT2 /* Check if an SD card is present in the microSD slot */ - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { /* Active low */ @@ -350,7 +350,7 @@ uint8_t sam_spi5status(FAR struct spi_dev_s *dev, uint32_t devid) int sam_spi0cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #ifdef CONFIG_SAMD20_XPLAINED_OLED1MODULE_EXT1 - if (devid == SPIDEV_DISPLAY) + if (devid == SPIDEV_DISPLAY(0)) { /* This is the Data/Command control pad which determines whether the * data bits are data or a command. @@ -371,7 +371,7 @@ int sam_spi0cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) int sam_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #ifdef CONFIG_SAMD20_XPLAINED_OLED1MODULE_EXT2 - if (devid == SPIDEV_DISPLAY) + if (devid == SPIDEV_DISPLAY(0)) { /* This is the Data/Command control pad which determines whether the * data bits are data or a command. diff --git a/configs/samd21-xplained/src/sam_spi.c b/configs/samd21-xplained/src/sam_spi.c index 275b961362..32dbdb62bb 100644 --- a/configs/samd21-xplained/src/sam_spi.c +++ b/configs/samd21-xplained/src/sam_spi.c @@ -154,7 +154,7 @@ void sam_spi0select(FAR struct spi_dev_s *dev, uint32_t devid, #ifdef CONFIG_SAMD21_XPLAINED_IOMODULE_EXT1 /* Select/de-select the SD card */ - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { /* Active low */ @@ -165,7 +165,7 @@ void sam_spi0select(FAR struct spi_dev_s *dev, uint32_t devid, #ifdef CONFIG_SAMD21_XPLAINED_OLED1MODULE_EXT1 /* Select/de-select the OLED */ - if (devid == SPIDEV_DISPLAY) + if (devid == SPIDEV_DISPLAY(0)) { /* Active low */ @@ -182,7 +182,7 @@ void sam_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, #ifdef CONFIG_SAMD21_XPLAINED_IOMODULE_EXT2 /* Select/de-select the SD card */ - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { /* Active low */ @@ -193,7 +193,7 @@ void sam_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, #ifdef CONFIG_SAMD21_XPLAINED_OLED1MODULE_EXT2 /* Select/de-select the OLED */ - if (devid == SPIDEV_DISPLAY) + if (devid == SPIDEV_DISPLAY(0)) { /* Active low */ @@ -254,7 +254,7 @@ uint8_t sam_spi0status(FAR struct spi_dev_s *dev, uint32_t devid) #ifdef CONFIG_SAMD21_XPLAINED_IOMODULE_EXT1 /* Check if an SD card is present in the microSD slot */ - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { /* Active low */ @@ -277,7 +277,7 @@ uint8_t sam_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) #ifdef CONFIG_SAMD21_XPLAINED_IOMODULE_EXT2 /* Check if an SD card is present in the microSD slot */ - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { /* Active low */ @@ -350,7 +350,7 @@ uint8_t sam_spi5status(FAR struct spi_dev_s *dev, uint32_t devid) int sam_spi0cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #ifdef CONFIG_SAMD21_XPLAINED_OLED1MODULE_EXT1 - if (devid == SPIDEV_DISPLAY) + if (devid == SPIDEV_DISPLAY(0)) { /* This is the Data/Command control pad which determines whether the * data bits are data or a command. @@ -371,7 +371,7 @@ int sam_spi0cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) int sam_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #ifdef CONFIG_SAMD21_XPLAINED_OLED1MODULE_EXT2 - if (devid == SPIDEV_DISPLAY) + if (devid == SPIDEV_DISPLAY(0)) { /* This is the Data/Command control pad which determines whether the * data bits are data or a command. diff --git a/configs/saml21-xplained/src/sam_spi.c b/configs/saml21-xplained/src/sam_spi.c index e4ecafd7ba..576444508d 100644 --- a/configs/saml21-xplained/src/sam_spi.c +++ b/configs/saml21-xplained/src/sam_spi.c @@ -154,7 +154,7 @@ void sam_spi0select(FAR struct spi_dev_s *dev, uint32_t devid, #ifdef CONFIG_SAML21_XPLAINED_IOMODULE_EXT1 /* Select/de-select the SD card */ - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { /* Active low */ @@ -165,7 +165,7 @@ void sam_spi0select(FAR struct spi_dev_s *dev, uint32_t devid, #ifdef CONFIG_SAML21_XPLAINED_OLED1MODULE_EXT1 /* Select/de-select the OLED */ - if (devid == SPIDEV_DISPLAY) + if (devid == SPIDEV_DISPLAY(0)) { /* Active low */ @@ -182,7 +182,7 @@ void sam_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, #ifdef CONFIG_SAML21_XPLAINED_IOMODULE_EXT2 /* Select/de-select the SD card */ - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { /* Active low */ @@ -193,7 +193,7 @@ void sam_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, #ifdef CONFIG_SAML21_XPLAINED_OLED1MODULE_EXT2 /* Select/de-select the OLED */ - if (devid == SPIDEV_DISPLAY) + if (devid == SPIDEV_DISPLAY(0)) { /* Active low */ @@ -254,7 +254,7 @@ uint8_t sam_spi0status(FAR struct spi_dev_s *dev, uint32_t devid) #ifdef CONFIG_SAML21_XPLAINED_IOMODULE_EXT1 /* Check if an SD card is present in the microSD slot */ - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { /* Active low */ @@ -277,7 +277,7 @@ uint8_t sam_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) #ifdef CONFIG_SAML21_XPLAINED_IOMODULE_EXT2 /* Check if an SD card is present in the microSD slot */ - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { /* Active low */ @@ -350,7 +350,7 @@ uint8_t sam_spi5status(FAR struct spi_dev_s *dev, uint32_t devid) int sam_spi0cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #ifdef CONFIG_SAML21_XPLAINED_OLED1MODULE_EXT1 - if (devid == SPIDEV_DISPLAY) + if (devid == SPIDEV_DISPLAY(0)) { /* This is the Data/Command control pad which determines whether the * data bits are data or a command. @@ -371,7 +371,7 @@ int sam_spi0cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) int sam_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #ifdef CONFIG_SAML21_XPLAINED_OLED1MODULE_EXT2 - if (devid == SPIDEV_DISPLAY) + if (devid == SPIDEV_DISPLAY(0)) { /* This is the Data/Command control pad which determines whether the * data bits are data or a command. diff --git a/configs/shenzhou/src/stm32_spi.c b/configs/shenzhou/src/stm32_spi.c index 70d6753cc7..6aeee5018b 100644 --- a/configs/shenzhou/src/stm32_spi.c +++ b/configs/shenzhou/src/stm32_spi.c @@ -123,13 +123,13 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) /* SPI1 connects to the SD CARD and to the SPI FLASH */ - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { /* Set the GPIO low to select and high to de-select */ stm32_gpiowrite(GPIO_SD_CS, !selected); } - else if (devid == SPIDEV_FLASH) + else if (devid == SPIDEV_FLASH(0)) { /* Set the GPIO low to select and high to de-select */ @@ -161,25 +161,25 @@ void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) * wireless module. */ - if (devid == SPIDEV_TOUCHSCREEN) + if (devid == SPIDEV_TOUCHSCREEN(0)) { /* Set the GPIO low to select and high to de-select */ stm32_gpiowrite(GPIO_TP_CS, !selected); } - else if (devid == SPIDEV_MMCSD) + else if (devid == SPIDEV_MMCSD(0)) { /* Set the GPIO low to select and high to de-select */ stm32_gpiowrite(GPIO_LCDDF_CS, !selected); } - else if (devid == SPIDEV_FLASH) + else if (devid == SPIDEV_FLASH(0)) { /* Set the GPIO low to select and high to de-select */ stm32_gpiowrite(GPIO_LCDSD_CS, !selected); } - else if (devid == SPIDEV_WIRELESS) + else if (devid == SPIDEV_WIRELESS(0)) { /* Set the GPIO low to select and high to de-select */ diff --git a/configs/spark/src/stm32_spi.c b/configs/spark/src/stm32_spi.c index 587ebeb8e3..8002196d86 100644 --- a/configs/spark/src/stm32_spi.c +++ b/configs/spark/src/stm32_spi.c @@ -134,7 +134,7 @@ void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) #if defined(CONFIG_MTD_SST25) - if (devid == SPIDEV_FLASH) + if (devid == SPIDEV_FLASH(0)) { stm32_gpiowrite(GPIO_MEM_CS, !selected); } @@ -144,7 +144,7 @@ void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) #endif #if defined(CONFIG_WL_CC3000) - if (devid == SPIDEV_WIRELESS) + if (devid == SPIDEV_WIRELESS(0)) { stm32_gpiowrite(GPIO_WIFI_CS, !selected); } diff --git a/configs/stm3210e-eval/src/stm32_spi.c b/configs/stm3210e-eval/src/stm32_spi.c index 92d9af18a9..05c0bdc292 100644 --- a/configs/stm3210e-eval/src/stm32_spi.c +++ b/configs/stm3210e-eval/src/stm32_spi.c @@ -110,7 +110,7 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); - if (devid == SPIDEV_FLASH) + if (devid == SPIDEV_FLASH(0)) { /* Set the GPIO low to select and high to de-select */ diff --git a/configs/stm32_tiny/src/stm32_spi.c b/configs/stm32_tiny/src/stm32_spi.c index 71bb78744c..abaac37b9e 100644 --- a/configs/stm32_tiny/src/stm32_spi.c +++ b/configs/stm32_tiny/src/stm32_spi.c @@ -125,7 +125,7 @@ void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) switch(devid) { #ifdef CONFIG_WL_NRF24L01 - case SPIDEV_WIRELESS: + case SPIDEV_WIRELESS(0): spiinfo("nRF24L01 device %s\n", selected ? "asserted" : "de-asserted"); /* Set the GPIO low to select and high to de-select */ @@ -144,7 +144,7 @@ uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) switch(devid) { #ifdef CONFIG_WL_NRF24L01 - case SPIDEV_WIRELESS: + case SPIDEV_WIRELESS(0): status |= SPI_STATUS_PRESENT; break; #endif diff --git a/configs/stm32butterfly2/src/stm32_spi.c b/configs/stm32butterfly2/src/stm32_spi.c index 2fc3544869..f6817f57b0 100644 --- a/configs/stm32butterfly2/src/stm32_spi.c +++ b/configs/stm32butterfly2/src/stm32_spi.c @@ -78,7 +78,7 @@ void stm32_spi1select(struct spi_dev_s *dev, uint32_t devid, { spiinfo("INFO: Selecting spi dev: %d, state: %d\n", devid, select); - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { stm32_gpiowrite(GPIO_SD_CS, !select); } @@ -95,7 +95,7 @@ uint8_t stm32_spi1status(struct spi_dev_s *dev, uint32_t devid) { spiinfo("INFO: Requesting info from spi dev: %d\n", devid); - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { if (stm32_gpioread(GPIO_SD_CD) == 0) { diff --git a/configs/stm32f103-minimum/src/stm32_spi.c b/configs/stm32f103-minimum/src/stm32_spi.c index 8a4169cc2c..0ba7df49d3 100644 --- a/configs/stm32f103-minimum/src/stm32_spi.c +++ b/configs/stm32f103-minimum/src/stm32_spi.c @@ -121,28 +121,28 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { #if defined(CONFIG_CL_MFRC522) - if (devid == SPIDEV_WIRELESS) + if (devid == SPIDEV_WIRELESS(0)) { stm32_gpiowrite(GPIO_CS_MFRC522, !selected); } #endif #ifdef CONFIG_LCD_ST7567 - if (devid == SPIDEV_DISPLAY) + if (devid == SPIDEV_DISPLAY(0)) { stm32_gpiowrite(GPIO_CS_MFRC522, !selected); } #endif #ifdef CONFIG_WL_NRF24L01 - if (devid == SPIDEV_WIRELESS) + if (devid == SPIDEV_WIRELESS(0)) { stm32_gpiowrite(GPIO_NRF24L01_CS, !selected); } #endif #ifdef CONFIG_MMCSD_SPI - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { stm32_gpiowrite(GPIO_SDCARD_CS, !selected); } @@ -154,14 +154,14 @@ uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) uint8_t status = 0; #ifdef CONFIG_WL_NRF24L01 - if (devid == SPIDEV_WIRELESS) + if (devid == SPIDEV_WIRELESS(0)) { status |= SPI_STATUS_PRESENT; } #endif #ifdef CONFIG_MMCSD_SPI - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { status |= SPI_STATUS_PRESENT; } @@ -213,7 +213,7 @@ int stm32_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #ifdef CONFIG_LCD_ST7567 - if (devid == SPIDEV_DISPLAY) + if (devid == SPIDEV_DISPLAY(0)) { /* This is the Data/Command control pad which determines whether the * data bits are data or a command. diff --git a/configs/stm32f429i-disco/src/stm32_ili93414ws.c b/configs/stm32f429i-disco/src/stm32_ili93414ws.c index 7948c03595..53cf63327e 100644 --- a/configs/stm32f429i-disco/src/stm32_ili93414ws.c +++ b/configs/stm32f429i-disco/src/stm32_ili93414ws.c @@ -855,7 +855,7 @@ static inline void stm32_ili93414ws_cmddata( { FAR struct ili93414ws_lcd_s *priv = (FAR struct ili93414ws_lcd_s *)lcd; - SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY, cmd); + SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY(0), cmd); } #else static inline void stm32_ili93414ws_cmddata( @@ -912,7 +912,7 @@ static void stm32_ili93414ws_select(FAR struct ili9341_lcd_s *lcd) */ SPI_LOCK(priv->spi, true); - SPI_SELECT(priv->spi, SPIDEV_DISPLAY, true); + SPI_SELECT(priv->spi, SPIDEV_DISPLAY(0), true); /* Configure spi and disable */ @@ -971,7 +971,7 @@ static void stm32_ili93414ws_deselect(FAR struct ili9341_lcd_s *lcd) /* de-select ili9341 and relinquish the spi bus. */ - SPI_SELECT(priv->spi, SPIDEV_DISPLAY, false); + SPI_SELECT(priv->spi, SPIDEV_DISPLAY(0), false); SPI_LOCK(priv->spi, false); } #else diff --git a/configs/stm32f429i-disco/src/stm32_l3gd20.c b/configs/stm32f429i-disco/src/stm32_l3gd20.c index 4cdc0a896e..7a8c449c62 100644 --- a/configs/stm32f429i-disco/src/stm32_l3gd20.c +++ b/configs/stm32f429i-disco/src/stm32_l3gd20.c @@ -71,7 +71,7 @@ static struct l3gd20_config_s g_l3gd20_config = { .attach = l3gd20_attach, .irq = L3GD20_IRQ, - .spi_devid = SPIDEV_ACCELEROMETER + .spi_devid = SPIDEV_ACCELEROMETER(0) }; /**************************************************************************** diff --git a/configs/stm32f429i-disco/src/stm32_spi.c b/configs/stm32f429i-disco/src/stm32_spi.c index 14b20b9b3a..16a23cc564 100644 --- a/configs/stm32f429i-disco/src/stm32_spi.c +++ b/configs/stm32f429i-disco/src/stm32_spi.c @@ -154,7 +154,7 @@ uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) void stm32_spi4select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { #if defined(CONFIG_MTD_SST25XX) - if (devid == SPIDEV_FLASH) + if (devid == SPIDEV_FLASH(0)) { stm32_gpiowrite(GPIO_CS_SST25, !selected); } @@ -173,7 +173,7 @@ void stm32_spi5select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #if defined(CONFIG_STM32F429I_DISCO_ILI9341) - if (devid == SPIDEV_DISPLAY) + if (devid == SPIDEV_DISPLAY(0)) { stm32_gpiowrite(GPIO_CS_LCD, !selected); } @@ -247,7 +247,7 @@ int stm32_spi4cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) int stm32_spi5cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #if defined(CONFIG_STM32F429I_DISCO_ILI9341) - if (devid == SPIDEV_DISPLAY) + if (devid == SPIDEV_DISPLAY(0)) { /* This is the Data/Command control pad which determines whether the * data bits are data or a command. diff --git a/configs/stm32f4discovery/src/stm32_spi.c b/configs/stm32f4discovery/src/stm32_spi.c index 77b53a8ac4..c343520e88 100644 --- a/configs/stm32f4discovery/src/stm32_spi.c +++ b/configs/stm32f4discovery/src/stm32_spi.c @@ -122,7 +122,7 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) #if defined(CONFIG_LCD_UG2864AMBAG01) || defined(CONFIG_LCD_UG2864HSWEG01) || \ defined(CONFIG_LCD_SSD1351) - if (devid == SPIDEV_DISPLAY) + if (devid == SPIDEV_DISPLAY(0)) { stm32_gpiowrite(GPIO_OLED_CS, !selected); } @@ -145,13 +145,13 @@ void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #if defined(CONFIG_MAX31855) - if (devid == SPIDEV_TEMPERATURE) + if (devid == SPIDEV_TEMPERATURE(0)) { stm32_gpiowrite(GPIO_MAX31855_CS, !selected); } #endif #if defined(CONFIG_MAX6675) - if (devid == SPIDEV_TEMPERATURE) + if (devid == SPIDEV_TEMPERATURE(0)) { stm32_gpiowrite(GPIO_MAX6675_CS, !selected); } @@ -205,7 +205,7 @@ int stm32_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { #if defined(CONFIG_LCD_UG2864AMBAG01) || defined(CONFIG_LCD_UG2864HSWEG01) || \ defined(CONFIG_LCD_SSD1351) - if (devid == SPIDEV_DISPLAY) + if (devid == SPIDEV_DISPLAY(0)) { /* "This is the Data/Command control pad which determines whether the * data bits are data or a command. diff --git a/configs/stm32l476vg-disco/src/stm32_spi.c b/configs/stm32l476vg-disco/src/stm32_spi.c index cca4db6f82..32e813b639 100644 --- a/configs/stm32l476vg-disco/src/stm32_spi.c +++ b/configs/stm32l476vg-disco/src/stm32_spi.c @@ -148,14 +148,14 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #ifdef CONFIG_WL_CC3000 - if (devid == SPIDEV_WIRELESS) + if (devid == SPIDEV_WIRELESS(0)) { stm32_gpiowrite(GPIO_SPI_CS_WIFI, !selected); } else #endif #ifdef HAVE_MMCSD - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { stm32_gpiowrite(GPIO_SPI_CS_SD_CARD, !selected); } @@ -174,7 +174,7 @@ void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #ifdef CONFIG_WL_CC3000 - if (devid == SPIDEV_WIRELESS) + if (devid == SPIDEV_WIRELESS(0)) { stm32_gpiowrite(GPIO_WIFI_CS, !selected); } diff --git a/configs/sure-pic32mx/src/pic32mx_spi.c b/configs/sure-pic32mx/src/pic32mx_spi.c index f0d5ed4575..587efd958e 100644 --- a/configs/sure-pic32mx/src/pic32mx_spi.c +++ b/configs/sure-pic32mx/src/pic32mx_spi.c @@ -181,14 +181,14 @@ void pic32mx_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected /* The SD card chip select is pulled high and active low */ #ifdef PIC32_HAVE_SD - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { pic32mx_gpiowrite(GPIO_SD_CS, !selected); } #endif #ifdef PIC32_HAVE_SOIC - if (devid == SPIDEV_FLASH) + if (devid == SPIDEV_FLASH(0)) { pic32mx_gpiowrite(GPIO_SOIC_CS, !selected); } @@ -204,7 +204,7 @@ uint8_t pic32mx_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) */ #ifdef PIC32_HAVE_SD - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { if (!pic32mx_gpioread(GPIO_SD_CD)) { @@ -223,7 +223,7 @@ uint8_t pic32mx_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) #endif #ifdef PIC32_HAVE_SOIC - if (devid == SPIDEV_FLASH) + if (devid == SPIDEV_FLASH(0)) { ret = SPI_STATUS_PRESENT; diff --git a/configs/u-blox-c027/src/lpc17_ssp.c b/configs/u-blox-c027/src/lpc17_ssp.c index 07533d055b..1b4ce631c8 100644 --- a/configs/u-blox-c027/src/lpc17_ssp.c +++ b/configs/u-blox-c027/src/lpc17_ssp.c @@ -143,14 +143,14 @@ void lpc17_ssp1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); ssp_dumpgpio("lpc17_ssp1select() Entry"); - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { /* Assert/de-assert the CS pin to the card */ (void)lpc17_gpiowrite(C027_SD_CS, !selected); } #ifdef CONFIG_NX_LCDDRIVER - else if (devid == SPIDEV_DISPLAY) + else if (devid == SPIDEV_DISPLAY(0)) { /* Assert the CS pin to the OLED display */ @@ -162,7 +162,7 @@ void lpc17_ssp1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) uint8_t lpc17_ssp1status(FAR struct spi_dev_s *dev, uint32_t devid) { - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { /* Read the state of the card-detect bit */ diff --git a/configs/viewtool-stm32f107/src/stm32_spi.c b/configs/viewtool-stm32f107/src/stm32_spi.c index 7e35062acd..aa1516e32b 100644 --- a/configs/viewtool-stm32f107/src/stm32_spi.c +++ b/configs/viewtool-stm32f107/src/stm32_spi.c @@ -132,7 +132,7 @@ void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) #ifdef CONFIG_INPUT_ADS7843E /* Select/de-select the touchscreen */ - if (devid == SPIDEV_TOUCHSCREEN) + if (devid == SPIDEV_TOUCHSCREEN(0)) { stm32_gpiowrite(GPIO_LCDTP_CS, !selected); } diff --git a/configs/zkit-arm-1769/src/lpc17_lcd.c b/configs/zkit-arm-1769/src/lpc17_lcd.c index db54027f3d..a998c7e4fb 100644 --- a/configs/zkit-arm-1769/src/lpc17_lcd.c +++ b/configs/zkit-arm-1769/src/lpc17_lcd.c @@ -158,7 +158,7 @@ void board_lcd_uninitialize(void) int lpc17_ssp0cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) { - if (devid == SPIDEV_DISPLAY) + if (devid == SPIDEV_DISPLAY(0)) { /* Set GPIO to 1 for data, 0 for command */ diff --git a/configs/zkit-arm-1769/src/lpc17_spi.c b/configs/zkit-arm-1769/src/lpc17_spi.c index c264ef403c..ec6d2773f4 100644 --- a/configs/zkit-arm-1769/src/lpc17_spi.c +++ b/configs/zkit-arm-1769/src/lpc17_spi.c @@ -128,7 +128,7 @@ void lpc17_spiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); spi_dumpgpio("lpc17_spiselect() Entry"); - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { /* Assert/de-assert the CS pin to the card */ @@ -140,7 +140,7 @@ void lpc17_spiselect(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) uint8_t lpc17_spistatus(FAR struct spi_dev_s *dev, uint32_t devid) { - if (devid == SPIDEV_MMCSD) + if (devid == SPIDEV_MMCSD(0)) { /* Read the state of the card-detect bit */ diff --git a/configs/zkit-arm-1769/src/lpc17_ssp.c b/configs/zkit-arm-1769/src/lpc17_ssp.c index cc8ece694c..b34e102d43 100644 --- a/configs/zkit-arm-1769/src/lpc17_ssp.c +++ b/configs/zkit-arm-1769/src/lpc17_ssp.c @@ -166,7 +166,7 @@ void lpc17_ssp0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) ssp_dumpgpio("lpc17_ssp0select() Entry"); #ifdef CONFIG_NX_LCDDRIVER - if (devid == SPIDEV_DISPLAY) + if (devid == SPIDEV_DISPLAY(0)) { /* Assert the CS pin to the OLED display */ @@ -179,7 +179,7 @@ void lpc17_ssp0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) uint8_t lpc17_ssp0status(FAR struct spi_dev_s *dev, uint32_t devid) { - if (devid == SPIDEV_DISPLAY) + if (devid == SPIDEV_DISPLAY(0)) { spiinfo("Returning SPI_STATUS_PRESENT\n"); return SPI_STATUS_PRESENT; diff --git a/configs/zp214xpa/src/lpc2148_spi1.c b/configs/zp214xpa/src/lpc2148_spi1.c index e9e2bc3a14..1396d9b1f7 100644 --- a/configs/zp214xpa/src/lpc2148_spi1.c +++ b/configs/zp214xpa/src/lpc2148_spi1.c @@ -220,7 +220,7 @@ static void spi_select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) #endif uint32_t bit = 1 << 20; - /* We do not bother to check if devid == SPIDEV_DISPLAY because that is the + /* We do not bother to check if devid == SPIDEV_DISPLAY(0) because that is the * only thing on the bus. */ @@ -353,7 +353,7 @@ static int spi_cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) #endif uint32_t bit = 1 << 23; - /* We do not bother to check if devid == SPIDEV_DISPLAY because that is the + /* We do not bother to check if devid == SPIDEV_DISPLAY(0) because that is the * only thing on the bus. */ diff --git a/drivers/analog/Kconfig b/drivers/analog/Kconfig index c1c7dce031..6727f67c47 100644 --- a/drivers/analog/Kconfig +++ b/drivers/analog/Kconfig @@ -116,7 +116,7 @@ config PGA11X_MULTIPLE Can be defined to support multiple PGA11X devices on board with separate chip selects (not daisy chained). Each device will require a customized SPI interface to distinguish them when SPI_SELECT is called with - devid=SPIDEV_MUX. + devid=SPIDEV_MUX(n). endif # if ADC_PGA11X endif # ADC diff --git a/drivers/analog/pga11x.c b/drivers/analog/pga11x.c index de86444b38..c8adf31494 100644 --- a/drivers/analog/pga11x.c +++ b/drivers/analog/pga11x.c @@ -278,9 +278,9 @@ static void pga11x_write(FAR struct spi_dev_s *spi, uint16_t cmd) /* Lock, select, send the 16-bit command, de-select, and un-lock. */ pga11x_lock(spi); - SPI_SELECT(spi, SPIDEV_MUX, true); + SPI_SELECT(spi, SPIDEV_MUX(0), true); pga11x_send16(spi, cmd); - SPI_SELECT(spi, SPIDEV_MUX, false); + SPI_SELECT(spi, SPIDEV_MUX(0), false); pga11x_unlock(spi); } #else @@ -293,10 +293,10 @@ static void pga11x_write(FAR struct spi_dev_s *spi, uint16_t u1cmd, uint16_t u2c */ pga11x_lock(spi); - SPI_SELECT(spi, SPIDEV_MUX, true); + SPI_SELECT(spi, SPIDEV_MUX(0), true); pga11x_send16(spi, u2cmd); pga11x_send16(spi, u1cmd); - SPI_SELECT(spi, SPIDEV_MUX, false); + SPI_SELECT(spi, SPIDEV_MUX(0), false); pga11x_unlock(spi); } #endif @@ -491,17 +491,17 @@ int pga11x_read(PGA11X_HANDLE handle, FAR struct pga11x_settings_s *settings) * for the part. */ - SPI_SELECT(spi, SPIDEV_MUX, true); + SPI_SELECT(spi, SPIDEV_MUX(0), true); pga11x_send16(spi, PGA11X_CMD_READ); pga11x_send16(spi, PGA11X_DCCMD_READ); - SPI_SELECT(spi, SPIDEV_MUX, false); + SPI_SELECT(spi, SPIDEV_MUX(0), false); /* Re-select, get the returned values, de-select, and unlock */ - SPI_SELECT(spi, SPIDEV_MUX, true); + SPI_SELECT(spi, SPIDEV_MUX(0), true); u2value = pga11x_recv16(spi); u1value = pga11x_recv16(spi); - SPI_SELECT(spi, SPIDEV_MUX, false); + SPI_SELECT(spi, SPIDEV_MUX(0), false); pga11x_unlock(spi); /* Decode the returned value */ @@ -528,15 +528,15 @@ int pga11x_read(PGA11X_HANDLE handle, FAR struct pga11x_settings_s *settings) * it is shown in the timing diagrams for the part. */ - SPI_SELECT(spi, SPIDEV_MUX, true); + SPI_SELECT(spi, SPIDEV_MUX(0), true); pga11x_send16(spi, PGA11X_CMD_READ); - SPI_SELECT(spi, SPIDEV_MUX, false); + SPI_SELECT(spi, SPIDEV_MUX(0), false); /* Re-select, get the returned value, de-select, and unlock */ - SPI_SELECT(spi, SPIDEV_MUX, true); + SPI_SELECT(spi, SPIDEV_MUX(0), true); value = pga11x_recv16(spi); - SPI_SELECT(spi, SPIDEV_MUX, false); + SPI_SELECT(spi, SPIDEV_MUX(0), false); pga11x_unlock(spi); /* Decode the returned value */ diff --git a/drivers/audio/vs1053.c b/drivers/audio/vs1053.c index 3582bf98e1..9c41e9fd78 100644 --- a/drivers/audio/vs1053.c +++ b/drivers/audio/vs1053.c @@ -292,7 +292,7 @@ static uint16_t vs1053_readreg(FAR struct vs1053_struct_s *dev, uint8_t reg) /* Select the AUDIO_CTRL device on the SPI bus */ - SPI_SELECT(spi, SPIDEV_AUDIO_CTRL, true); + SPI_SELECT(spi, SPIDEV_AUDIO_CTRL(0), true); /* Send the WRITE command followed by the address */ @@ -306,7 +306,7 @@ static uint16_t vs1053_readreg(FAR struct vs1053_struct_s *dev, uint8_t reg) /* Deselect the CODEC */ - SPI_SELECT(spi, SPIDEV_AUDIO_CTRL, false); + SPI_SELECT(spi, SPIDEV_AUDIO_CTRL(0), false); return ret; } @@ -324,7 +324,7 @@ static void vs1053_writereg(FAR struct vs1053_struct_s *dev, uint8_t reg, uint16 audinfo("Write Reg %d = 0x%0X\n", reg, val); - SPI_SELECT(spi, SPIDEV_AUDIO_CTRL, true); + SPI_SELECT(spi, SPIDEV_AUDIO_CTRL(0), true); /* Send the WRITE command followed by the address */ @@ -338,7 +338,7 @@ static void vs1053_writereg(FAR struct vs1053_struct_s *dev, uint8_t reg, uint16 /* Deselect the CODEC */ - SPI_SELECT(spi, SPIDEV_AUDIO_CTRL, false); + SPI_SELECT(spi, SPIDEV_AUDIO_CTRL(0), false); /* Short delay after a write for VS1053 processing time */ @@ -955,7 +955,7 @@ static void vs1053_feeddata(FAR struct vs1053_struct_s *dev) */ vs1053_spi_lock(spi, VS1053_DATA_FREQ); /* Lock the SPI bus */ - SPI_SELECT(spi, SPIDEV_AUDIO_DATA, true); /* Select the VS1053 data bus */ + SPI_SELECT(spi, SPIDEV_AUDIO_DATA(0), true); /* Select the VS1053 data bus */ /* Local stack copy of our active buffer */ @@ -970,7 +970,7 @@ static void vs1053_feeddata(FAR struct vs1053_struct_s *dev) } else if (!dev->endmode) { - SPI_SELECT(spi, SPIDEV_AUDIO_DATA, false); + SPI_SELECT(spi, SPIDEV_AUDIO_DATA(0), false); vs1053_spi_unlock(spi); return; } @@ -1194,7 +1194,7 @@ static void vs1053_feeddata(FAR struct vs1053_struct_s *dev) /* Deselect the SPI bus and unlock it */ err_out: - SPI_SELECT(spi, SPIDEV_AUDIO_DATA, false); + SPI_SELECT(spi, SPIDEV_AUDIO_DATA(0), false); vs1053_spi_unlock(spi); } diff --git a/drivers/contactless/mfrc522.c b/drivers/contactless/mfrc522.c index 804ea0fa4b..bf87bc31de 100644 --- a/drivers/contactless/mfrc522.c +++ b/drivers/contactless/mfrc522.c @@ -173,12 +173,12 @@ static inline void mfrc522_configspi(FAR struct spi_dev_s *spi) static inline void mfrc522_select(struct mfrc522_dev_s *dev) { - SPI_SELECT(dev->spi, SPIDEV_CONTACTLESS, true); + SPI_SELECT(dev->spi, SPIDEV_CONTACTLESS(0), true); } static inline void mfrc522_deselect(struct mfrc522_dev_s *dev) { - SPI_SELECT(dev->spi, SPIDEV_CONTACTLESS, false); + SPI_SELECT(dev->spi, SPIDEV_CONTACTLESS(0), false); } /**************************************************************************** diff --git a/drivers/contactless/pn532.c b/drivers/contactless/pn532.c index a7b2113181..974173350c 100644 --- a/drivers/contactless/pn532.c +++ b/drivers/contactless/pn532.c @@ -201,7 +201,7 @@ static inline void pn532_select(struct pn532_dev_s *dev) } else { - SPI_SELECT(dev->spi, SPIDEV_CONTACTLESS, true); + SPI_SELECT(dev->spi, SPIDEV_CONTACTLESS(0), true); } } @@ -213,7 +213,7 @@ static inline void pn532_deselect(struct pn532_dev_s *dev) } else { - SPI_SELECT(dev->spi, SPIDEV_CONTACTLESS, false); + SPI_SELECT(dev->spi, SPIDEV_CONTACTLESS(0), false); } } diff --git a/drivers/eeprom/spi_xx25xx.c b/drivers/eeprom/spi_xx25xx.c index 437dfbea85..5fb5a37fdd 100644 --- a/drivers/eeprom/spi_xx25xx.c +++ b/drivers/eeprom/spi_xx25xx.c @@ -358,7 +358,7 @@ static void ee25xx_waitwritecomplete(struct ee25xx_dev_s *priv) { /* Select this FLASH part */ - SPI_SELECT(priv->spi, SPIDEV_EEPROM, true); + SPI_SELECT(priv->spi, SPIDEV_EEPROM(0), true); /* Send "Read Status Register (RDSR)" command */ @@ -372,7 +372,7 @@ static void ee25xx_waitwritecomplete(struct ee25xx_dev_s *priv) /* Deselect the FLASH */ - SPI_SELECT(priv->spi, SPIDEV_EEPROM, false); + SPI_SELECT(priv->spi, SPIDEV_EEPROM(0), false); /* Given that writing could take up to a few milliseconds, * the following short delay in the "busy" case will allow @@ -401,11 +401,11 @@ static void ee25xx_waitwritecomplete(struct ee25xx_dev_s *priv) static void ee25xx_writeenable(FAR struct spi_dev_s *spi, int enable) { ee25xx_lock(spi); - SPI_SELECT(spi, SPIDEV_EEPROM, true); + SPI_SELECT(spi, SPIDEV_EEPROM(0), true); SPI_SEND(spi, enable ? EE25XX_CMD_WREN : EE25XX_CMD_WRDIS); - SPI_SELECT(spi, SPIDEV_EEPROM, false); + SPI_SELECT(spi, SPIDEV_EEPROM(0), false); ee25xx_unlock(spi); } @@ -420,12 +420,12 @@ static void ee25xx_writepage(FAR struct ee25xx_dev_s *eedev, uint32_t devaddr, FAR const char *data, size_t len) { ee25xx_lock(eedev->spi); - SPI_SELECT(eedev->spi, SPIDEV_EEPROM, true); + SPI_SELECT(eedev->spi, SPIDEV_EEPROM(0), true); ee25xx_sendcmd(eedev->spi, EE25XX_CMD_WRITE, eedev->addrlen, devaddr); SPI_SNDBLOCK(eedev->spi, data, len); - SPI_SELECT(eedev->spi, SPIDEV_EEPROM, false); + SPI_SELECT(eedev->spi, SPIDEV_EEPROM(0), false); ee25xx_unlock(eedev->spi); } @@ -625,7 +625,7 @@ static ssize_t ee25xx_read(FAR struct file *filep, FAR char *buffer, } ee25xx_lock(eedev->spi); - SPI_SELECT(eedev->spi, SPIDEV_EEPROM, true); + SPI_SELECT(eedev->spi, SPIDEV_EEPROM(0), true); /* STM32F4Disco: There is a 25 us delay here */ @@ -637,7 +637,7 @@ static ssize_t ee25xx_read(FAR struct file *filep, FAR char *buffer, /* STM32F4Disco: There is a 20 us delay here */ - SPI_SELECT(eedev->spi, SPIDEV_EEPROM, false); + SPI_SELECT(eedev->spi, SPIDEV_EEPROM(0), false); ee25xx_unlock(eedev->spi); /* Update the file position */ diff --git a/drivers/input/ads7843e.c b/drivers/input/ads7843e.c index 820cb873f2..5b8dc4f542 100644 --- a/drivers/input/ads7843e.c +++ b/drivers/input/ads7843e.c @@ -189,12 +189,12 @@ static void ads7843e_lock(FAR struct spi_dev_s *spi) * unlocked) */ - SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, true); + SPI_SELECT(spi, SPIDEV_TOUCHSCREEN(0), true); SPI_SETMODE(spi, CONFIG_ADS7843E_SPIMODE); SPI_SETBITS(spi, 8); (void)SPI_HWFEATURES(spi, 0); (void)SPI_SETFREQUENCY(spi, CONFIG_ADS7843E_FREQUENCY); - SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, false); + SPI_SELECT(spi, SPIDEV_TOUCHSCREEN(0), false); } /**************************************************************************** @@ -263,7 +263,7 @@ static uint16_t ads7843e_sendcmd(FAR struct ads7843e_dev_s *priv, uint8_t cmd) /* Select the ADS7843E */ - SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, true); + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN(0), true); /* Send the command */ @@ -276,7 +276,7 @@ static uint16_t ads7843e_sendcmd(FAR struct ads7843e_dev_s *priv, uint8_t cmd) /* Read the 12-bit data (LS 4 bits will be padded with zero) */ SPI_RECVBLOCK(priv->spi, buffer, 2); - SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, false); + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN(0), false); result = ((uint16_t)buffer[0] << 8) | (uint16_t)buffer[1]; result = result >> 4; diff --git a/drivers/input/max11802.c b/drivers/input/max11802.c index c3cd4c09f3..e190b5bc2e 100644 --- a/drivers/input/max11802.c +++ b/drivers/input/max11802.c @@ -231,7 +231,7 @@ static uint16_t max11802_sendcmd(FAR struct max11802_dev_s *priv, /* Select the MAX11802 */ - SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, true); + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN(0), true); /* Send the command */ @@ -240,7 +240,7 @@ static uint16_t max11802_sendcmd(FAR struct max11802_dev_s *priv, /* Read the data */ SPI_RECVBLOCK(priv->spi, buffer, 2); - SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, false); + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN(0), false); result = ((uint16_t)buffer[0] << 8) | (uint16_t)buffer[1]; *tags = result & 0xF; @@ -1225,32 +1225,32 @@ int max11802_register(FAR struct spi_dev_s *spi, /* Configure MAX11802 registers */ - SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, true); + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN(0), true); (void)SPI_SEND(priv->spi, MAX11802_CMD_MODE_WR); (void)SPI_SEND(priv->spi, MAX11802_MODE); - SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, false); + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN(0), false); - SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, true); + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN(0), true); (void)SPI_SEND(priv->spi, MAX11802_CMD_AVG_WR); (void)SPI_SEND(priv->spi, MAX11802_AVG); - SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, false); + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN(0), false); - SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, true); + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN(0), true); (void)SPI_SEND(priv->spi, MAX11802_CMD_TIMING_WR); (void)SPI_SEND(priv->spi, MAX11802_TIMING); - SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, false); + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN(0), false); - SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, true); + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN(0), true); (void)SPI_SEND(priv->spi, MAX11802_CMD_DELAY_WR); (void)SPI_SEND(priv->spi, MAX11802_DELAY); - SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, false); + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN(0), false); /* Test that the device access was successful. */ - SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, true); + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN(0), true); (void)SPI_SEND(priv->spi, MAX11802_CMD_MODE_RD); ret = SPI_SEND(priv->spi, 0); - SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, false); + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN(0), false); /* Unlock the bus */ diff --git a/drivers/lcd/memlcd.c b/drivers/lcd/memlcd.c index a7b192acae..7cd379ca5b 100644 --- a/drivers/lcd/memlcd.c +++ b/drivers/lcd/memlcd.c @@ -285,7 +285,7 @@ static void memlcd_select(FAR struct spi_dev_s *spi) */ SPI_LOCK(spi, true); - SPI_SELECT(spi, SPIDEV_DISPLAY, true); + SPI_SELECT(spi, SPIDEV_DISPLAY(0), true); /* Now make sure that the SPI bus is configured for the memlcd (it * might have gotten configured for a different device while unlocked) @@ -327,7 +327,7 @@ static void memlcd_deselect(FAR struct spi_dev_s *spi) { /* De-select memlcd and relinquish the spi bus. */ - SPI_SELECT(spi, SPIDEV_DISPLAY, false); + SPI_SELECT(spi, SPIDEV_DISPLAY(0), false); SPI_LOCK(spi, false); } diff --git a/drivers/lcd/nokia6100.c b/drivers/lcd/nokia6100.c index b67af2bada..cc28e027f7 100644 --- a/drivers/lcd/nokia6100.c +++ b/drivers/lcd/nokia6100.c @@ -661,7 +661,7 @@ static void nokia_select(FAR struct spi_dev_s *spi) lcdinfo("SELECTED\n"); SPI_LOCK(spi, true); - SPI_SELECT(spi, SPIDEV_DISPLAY, true); + SPI_SELECT(spi, SPIDEV_DISPLAY(0), true); /* Now make sure that the SPI bus is configured for the Nokia 6100 (it * might have gotten configured for a different device while unlocked) @@ -695,7 +695,7 @@ static void nokia_deselect(FAR struct spi_dev_s *spi) lcdinfo("DE-SELECTED\n"); - SPI_SELECT(spi, SPIDEV_DISPLAY, false); + SPI_SELECT(spi, SPIDEV_DISPLAY(0), false); SPI_LOCK(spi, false); } diff --git a/drivers/lcd/p14201.c b/drivers/lcd/p14201.c index 147e6414ed..4461502c4f 100644 --- a/drivers/lcd/p14201.c +++ b/drivers/lcd/p14201.c @@ -449,7 +449,7 @@ static void rit_select(FAR struct spi_dev_s *spi) */ SPI_LOCK(spi, true); - SPI_SELECT(spi, SPIDEV_DISPLAY, true); + SPI_SELECT(spi, SPIDEV_DISPLAY(0), true); /* Now make sure that the SPI bus is configured for the P14201 (it * might have gotten configured for a different device while unlocked) @@ -483,7 +483,7 @@ static void rit_deselect(FAR struct spi_dev_s *spi) { /* De-select P14201 chip and relinquish the SPI bus. */ - SPI_SELECT(spi, SPIDEV_DISPLAY, false); + SPI_SELECT(spi, SPIDEV_DISPLAY(0), false); SPI_LOCK(spi, false); } @@ -518,7 +518,7 @@ static void rit_sndbytes(FAR struct rit_dev_s *priv, FAR const uint8_t *buffer, /* Clear/set the D/Cn bit to enable command or data mode */ - (void)SPI_CMDDATA(spi, SPIDEV_DISPLAY, cmd); + (void)SPI_CMDDATA(spi, SPIDEV_DISPLAY(0), cmd); /* Loop until the entire command/data block is transferred */ diff --git a/drivers/lcd/ssd1306_spi.c b/drivers/lcd/ssd1306_spi.c index 9a547b8a16..e7a59b7cbf 100644 --- a/drivers/lcd/ssd1306_spi.c +++ b/drivers/lcd/ssd1306_spi.c @@ -130,7 +130,7 @@ void ssd1306_select(FAR struct ssd1306_dev_s *priv, bool cs) /* Select/deselect SPI device */ - SPI_SELECT(priv->spi, SPIDEV_DISPLAY, cs); + SPI_SELECT(priv->spi, SPIDEV_DISPLAY(0), cs); /* If we are deselecting the device */ @@ -154,6 +154,6 @@ void ssd1306_cmddata(FAR struct ssd1306_dev_s *priv, bool cmd) { /* Select command transfer */ - SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY, cmd); + SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY(0), cmd); } #endif /* CONFIG_LCD_SSD1306 && CONFIG_LCD_SSD1306_SPI */ diff --git a/drivers/lcd/ssd1351.c b/drivers/lcd/ssd1351.c index f88c85ff85..791040eee5 100644 --- a/drivers/lcd/ssd1351.c +++ b/drivers/lcd/ssd1351.c @@ -502,7 +502,7 @@ static void ssd1351_select(FAR struct ssd1351_dev_s *priv) ginfo("SELECTED\n"); SPI_LOCK(spi, true); - SPI_SELECT(spi, SPIDEV_DISPLAY, true); + SPI_SELECT(spi, SPIDEV_DISPLAY(0), true); /* Now make sure that the SPI bus is configured for this device (it might * have gotten configured for a different device while unlocked) @@ -532,7 +532,7 @@ static void ssd1351_deselect(FAR struct ssd1351_dev_s *priv) ginfo("DE-SELECTED\n"); - SPI_SELECT(spi, SPIDEV_DISPLAY, false); + SPI_SELECT(spi, SPIDEV_DISPLAY(0), false); SPI_LOCK(spi, false); } #endif @@ -648,7 +648,7 @@ static void ssd1351_write(FAR struct ssd1351_dev_s *priv, uint8_t cmd, /* Select command transfer */ - (void)SPI_CMDDATA(spi, SPIDEV_DISPLAY, true); + (void)SPI_CMDDATA(spi, SPIDEV_DISPLAY(0), true); /* Send the command */ @@ -660,7 +660,7 @@ static void ssd1351_write(FAR struct ssd1351_dev_s *priv, uint8_t cmd, { /* Yes, select data transfer */ - (void)SPI_CMDDATA(spi, SPIDEV_DISPLAY, false); + (void)SPI_CMDDATA(spi, SPIDEV_DISPLAY(0), false); /* Transfer all of the data */ diff --git a/drivers/lcd/st7567.c b/drivers/lcd/st7567.c index c95ffaa8a3..5de10bb7c3 100644 --- a/drivers/lcd/st7567.c +++ b/drivers/lcd/st7567.c @@ -365,7 +365,7 @@ static void st7567_select(FAR struct spi_dev_s *spi) */ SPI_LOCK(spi, true); - SPI_SELECT(spi, SPIDEV_DISPLAY, true); + SPI_SELECT(spi, SPIDEV_DISPLAY(0), true); /* Now make sure that the SPI bus is configured for the ST7567 (it * might have gotten configured for a different device while unlocked) @@ -399,7 +399,7 @@ static void st7567_deselect(FAR struct spi_dev_s *spi) { /* De-select ST7567 chip and relinquish the SPI bus. */ - SPI_SELECT(spi, SPIDEV_DISPLAY, false); + SPI_SELECT(spi, SPIDEV_DISPLAY(0), false); SPI_LOCK(spi, false); } @@ -530,7 +530,7 @@ static int st7567_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buff /* Select command transfer */ - SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY, true); + SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY(0), true); /* Set the starting position for the run */ @@ -540,7 +540,7 @@ static int st7567_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buff /* Select data transfer */ - SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY, false); + SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY(0), false); /* Then transfer all of the data */ @@ -812,7 +812,7 @@ static int st7567_setcontrast(struct lcd_dev_s *dev, unsigned int contrast) /* Select command transfer */ - SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY, true); + SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY(0), true); /* Set the contrast */ @@ -854,7 +854,7 @@ static inline void up_clear(FAR struct st7567_dev_s *priv) { /* Select command transfer */ - SPI_CMDDATA(spi, SPIDEV_DISPLAY, true); + SPI_CMDDATA(spi, SPIDEV_DISPLAY(0), true); /* Set the starting position for the run */ @@ -864,7 +864,7 @@ static inline void up_clear(FAR struct st7567_dev_s *priv) /* Select data transfer */ - SPI_CMDDATA(spi, SPIDEV_DISPLAY, false); + SPI_CMDDATA(spi, SPIDEV_DISPLAY(0), false); /* Then transfer all 96 columns of data */ @@ -924,7 +924,7 @@ FAR struct lcd_dev_s *st7567_initialize(FAR struct spi_dev_s *spi, unsigned int /* Select command transfer */ - SPI_CMDDATA(spi, SPIDEV_DISPLAY, true); + SPI_CMDDATA(spi, SPIDEV_DISPLAY(0), true); /* Set the starting position for the run */ diff --git a/drivers/lcd/ug-2864ambag01.c b/drivers/lcd/ug-2864ambag01.c index ea6175a856..1e6484f256 100644 --- a/drivers/lcd/ug-2864ambag01.c +++ b/drivers/lcd/ug-2864ambag01.c @@ -622,11 +622,11 @@ static int ug2864ambag01_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_ /* Lock and select device */ ug2864ambag01_lock(priv->spi); - SPI_SELECT(priv->spi, SPIDEV_DISPLAY, true); + SPI_SELECT(priv->spi, SPIDEV_DISPLAY(0), true); /* Select command transfer */ - SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY, true); + SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY(0), true); /* Set the starting position for the run */ /* Set the column address to the XOFFSET value */ @@ -640,7 +640,7 @@ static int ug2864ambag01_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_ /* Select data transfer */ - SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY, false); + SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY(0), false); /* Then transfer all of the data */ @@ -648,7 +648,7 @@ static int ug2864ambag01_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_ /* De-select and unlock the device */ - SPI_SELECT(priv->spi, SPIDEV_DISPLAY, false); + SPI_SELECT(priv->spi, SPIDEV_DISPLAY(0), false); ug2864ambag01_unlock(priv->spi); return OK; } @@ -892,7 +892,7 @@ static int ug2864ambag01_setpower(struct lcd_dev_s *dev, int power) /* Lock and select device */ ug2864ambag01_lock(priv->spi); - SPI_SELECT(priv->spi, SPIDEV_DISPLAY, true); + SPI_SELECT(priv->spi, SPIDEV_DISPLAY(0), true); if (power <= 0) { @@ -911,7 +911,7 @@ static int ug2864ambag01_setpower(struct lcd_dev_s *dev, int power) /* De-select and unlock the device */ - SPI_SELECT(priv->spi, SPIDEV_DISPLAY, false); + SPI_SELECT(priv->spi, SPIDEV_DISPLAY(0), false); ug2864ambag01_unlock(priv->spi); return OK; } @@ -971,11 +971,11 @@ static int ug2864ambag01_setcontrast(struct lcd_dev_s *dev, unsigned int contras /* Lock and select device */ ug2864ambag01_lock(priv->spi); - SPI_SELECT(priv->spi, SPIDEV_DISPLAY, true); + SPI_SELECT(priv->spi, SPIDEV_DISPLAY(0), true); /* Select command transfer */ - SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY, true); + SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY(0), true); /* Set the contrast */ @@ -985,7 +985,7 @@ static int ug2864ambag01_setcontrast(struct lcd_dev_s *dev, unsigned int contras /* De-select and unlock the device */ - SPI_SELECT(priv->spi, SPIDEV_DISPLAY, false); + SPI_SELECT(priv->spi, SPIDEV_DISPLAY(0), false); ug2864ambag01_unlock(priv->spi); return OK; } @@ -1029,11 +1029,11 @@ FAR struct lcd_dev_s *ug2864ambag01_initialize(FAR struct spi_dev_s *spi, unsign /* Lock and select device */ ug2864ambag01_lock(priv->spi); - SPI_SELECT(spi, SPIDEV_DISPLAY, true); + SPI_SELECT(spi, SPIDEV_DISPLAY(0), true); /* Select command transfer */ - SPI_CMDDATA(spi, SPIDEV_DISPLAY, true); + SPI_CMDDATA(spi, SPIDEV_DISPLAY(0), true); /* Configure the device */ @@ -1064,7 +1064,7 @@ FAR struct lcd_dev_s *ug2864ambag01_initialize(FAR struct spi_dev_s *spi, unsign /* De-select and unlock the device */ - SPI_SELECT(spi, SPIDEV_DISPLAY, false); + SPI_SELECT(spi, SPIDEV_DISPLAY(0), false); ug2864ambag01_unlock(priv->spi); /* Clear the display */ @@ -1112,7 +1112,7 @@ void ug2864ambag01_fill(FAR struct lcd_dev_s *dev, uint8_t color) /* Lock and select device */ ug2864ambag01_lock(priv->spi); - SPI_SELECT(priv->spi, SPIDEV_DISPLAY, true); + SPI_SELECT(priv->spi, SPIDEV_DISPLAY(0), true); /* Visit each page */ @@ -1120,7 +1120,7 @@ void ug2864ambag01_fill(FAR struct lcd_dev_s *dev, uint8_t color) { /* Select command transfer */ - SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY, true); + SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY(0), true); /* Set the column address to the XOFFSET value */ @@ -1133,7 +1133,7 @@ void ug2864ambag01_fill(FAR struct lcd_dev_s *dev, uint8_t color) /* Select data transfer */ - SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY, false); + SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY(0), false); /* Transfer one page of the selected color */ @@ -1143,7 +1143,7 @@ void ug2864ambag01_fill(FAR struct lcd_dev_s *dev, uint8_t color) /* De-select and unlock the device */ - SPI_SELECT(priv->spi, SPIDEV_DISPLAY, false); + SPI_SELECT(priv->spi, SPIDEV_DISPLAY(0), false); ug2864ambag01_unlock(priv->spi); } diff --git a/drivers/lcd/ug-9664hswag01.c b/drivers/lcd/ug-9664hswag01.c index f56c8f7cd1..96d09aea99 100644 --- a/drivers/lcd/ug-9664hswag01.c +++ b/drivers/lcd/ug-9664hswag01.c @@ -399,7 +399,7 @@ static void ug_select(FAR struct spi_dev_s *spi) */ SPI_LOCK(spi, true); - SPI_SELECT(spi, SPIDEV_DISPLAY, true); + SPI_SELECT(spi, SPIDEV_DISPLAY(0), true); /* Now make sure that the SPI bus is configured for the UG-9664HSWAG01 (it * might have gotten configured for a different device while unlocked) @@ -433,7 +433,7 @@ static void ug_deselect(FAR struct spi_dev_s *spi) { /* De-select UG-9664HSWAG01 chip and relinquish the SPI bus. */ - SPI_SELECT(spi, SPIDEV_DISPLAY, false); + SPI_SELECT(spi, SPIDEV_DISPLAY(0), false); SPI_LOCK(spi, false); } @@ -614,7 +614,7 @@ static int ug_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buffer, /* Select command transfer */ - SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY, true); + SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY(0), true); /* Set the starting position for the run */ @@ -624,7 +624,7 @@ static int ug_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buffer, /* Select data transfer */ - SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY, false); + SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY(0), false); /* Then transfer all of the data */ @@ -943,7 +943,7 @@ static int ug_setcontrast(struct lcd_dev_s *dev, unsigned int contrast) /* Select command transfer */ - SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY, true); + SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY(0), true); /* Set the contrast */ @@ -985,7 +985,7 @@ static inline void up_clear(FAR struct ug_dev_s *priv) { /* Select command transfer */ - SPI_CMDDATA(spi, SPIDEV_DISPLAY, true); + SPI_CMDDATA(spi, SPIDEV_DISPLAY(0), true); /* Set the starting position for the run */ @@ -995,7 +995,7 @@ static inline void up_clear(FAR struct ug_dev_s *priv) /* Select data transfer */ - SPI_CMDDATA(spi, SPIDEV_DISPLAY, false); + SPI_CMDDATA(spi, SPIDEV_DISPLAY(0), false); /* Then transfer all 96 columns of data */ @@ -1055,7 +1055,7 @@ FAR struct lcd_dev_s *ug_initialize(FAR struct spi_dev_s *spi, unsigned int devn /* Select command transfer */ - SPI_CMDDATA(spi, SPIDEV_DISPLAY, true); + SPI_CMDDATA(spi, SPIDEV_DISPLAY(0), true); /* Configure the device */ diff --git a/drivers/mmcsd/mmcsd_spi.c b/drivers/mmcsd/mmcsd_spi.c index 2a4cdee73d..7bf4ecdee1 100644 --- a/drivers/mmcsd/mmcsd_spi.c +++ b/drivers/mmcsd/mmcsd_spi.c @@ -842,7 +842,7 @@ static void mmcsd_checkwrprotect(FAR struct mmcsd_slot_s *slot, uint8_t *csd) * reports temporary write protect. */ - if ((SPI_STATUS(spi, SPIDEV_MMCSD) & SPI_STATUS_WRPROTECTED) != 0 || + if ((SPI_STATUS(spi, SPIDEV_MMCSD(0)) & SPI_STATUS_WRPROTECTED) != 0 || MMCSD_CSD_PERMWRITEPROTECT(csd) || MMCSD_CSD_TMPWRITEPROTECT(csd)) { @@ -1056,7 +1056,7 @@ static int mmcsd_open(FAR struct inode *inode) ret = -ENODEV; mmcsd_semtake(slot); - if ((SPI_STATUS(spi, SPIDEV_MMCSD) & SPI_STATUS_PRESENT) != 0) + if ((SPI_STATUS(spi, SPIDEV_MMCSD(0)) & SPI_STATUS_PRESENT) != 0) { /* Yes.. a card is present. Has it been initialized? */ @@ -1074,9 +1074,9 @@ static int mmcsd_open(FAR struct inode *inode) /* Make sure that the card is ready */ - SPI_SELECT(spi, SPIDEV_MMCSD, true); + SPI_SELECT(spi, SPIDEV_MMCSD(0), true); ret = mmcsd_waitready(slot); - SPI_SELECT(spi, SPIDEV_MMCSD, false); + SPI_SELECT(spi, SPIDEV_MMCSD(0), false); } errout_with_sem: @@ -1177,7 +1177,7 @@ static ssize_t mmcsd_read(FAR struct inode *inode, unsigned char *buffer, /* Select the slave */ mmcsd_semtake(slot); - SPI_SELECT(spi, SPIDEV_MMCSD, true); + SPI_SELECT(spi, SPIDEV_MMCSD(0), true); /* Single or multiple block read? */ @@ -1235,7 +1235,7 @@ static ssize_t mmcsd_read(FAR struct inode *inode, unsigned char *buffer, /* On success, return the number of sectors transfer */ - SPI_SELECT(spi, SPIDEV_MMCSD, false); + SPI_SELECT(spi, SPIDEV_MMCSD(0), false); SPI_SEND(spi, 0xff); mmcsd_semgive(slot); @@ -1244,7 +1244,7 @@ static ssize_t mmcsd_read(FAR struct inode *inode, unsigned char *buffer, return nsectors; errout_with_eio: - SPI_SELECT(spi, SPIDEV_MMCSD, false); + SPI_SELECT(spi, SPIDEV_MMCSD(0), false); mmcsd_semgive(slot); return -EIO; } @@ -1341,7 +1341,7 @@ static ssize_t mmcsd_write(FAR struct inode *inode, const unsigned char *buffer, /* Select the slave */ mmcsd_semtake(slot); - SPI_SELECT(spi, SPIDEV_MMCSD, true); + SPI_SELECT(spi, SPIDEV_MMCSD(0), true); /* Single or multiple block transfer? */ @@ -1422,7 +1422,7 @@ static ssize_t mmcsd_write(FAR struct inode *inode, const unsigned char *buffer, /* Wait until the card is no longer busy */ (void)mmcsd_waitready(slot); - SPI_SELECT(spi, SPIDEV_MMCSD, false); + SPI_SELECT(spi, SPIDEV_MMCSD(0), false); SPI_SEND(spi, 0xff); mmcsd_semgive(slot); @@ -1431,7 +1431,7 @@ static ssize_t mmcsd_write(FAR struct inode *inode, const unsigned char *buffer, return nsectors; errout_with_sem: - SPI_SELECT(spi, SPIDEV_MMCSD, false); + SPI_SELECT(spi, SPIDEV_MMCSD(0), false); mmcsd_semgive(slot); return -EIO; } @@ -1482,9 +1482,9 @@ static int mmcsd_geometry(FAR struct inode *inode, struct geometry *geometry) /* Re-sample the CSD */ mmcsd_semtake(slot); - SPI_SELECT(spi, SPIDEV_MMCSD, true); + SPI_SELECT(spi, SPIDEV_MMCSD(0), true); ret = mmcsd_getcsd(slot, csd); - SPI_SELECT(spi, SPIDEV_MMCSD, false); + SPI_SELECT(spi, SPIDEV_MMCSD(0), false); if (ret < 0) { @@ -1564,7 +1564,7 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot) * interface */ - if ((SPI_STATUS(spi, SPIDEV_MMCSD) & SPI_STATUS_PRESENT) == 0) + if ((SPI_STATUS(spi, SPIDEV_MMCSD(0)) & SPI_STATUS_PRESENT) == 0) { fwarn("WARNING: No card present\n"); slot->state |= MMCSD_SLOTSTATUS_NODISK; @@ -1602,7 +1602,7 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot) */ finfo("Send CMD0\n"); - SPI_SELECT(spi, SPIDEV_MMCSD, true); + SPI_SELECT(spi, SPIDEV_MMCSD(0), true); result = mmcsd_sendcmd(slot, &g_cmd0, 0); if (result == MMCSD_SPIR1_IDLESTATE) { @@ -1614,7 +1614,7 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot) /* De-select card and try again */ - SPI_SELECT(spi, SPIDEV_MMCSD, false); + SPI_SELECT(spi, SPIDEV_MMCSD(0), false); } /* Verify that we exit the above loop with the card reporting IDLE state */ @@ -1622,7 +1622,7 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot) if (result != MMCSD_SPIR1_IDLESTATE) { ferr("ERROR: Send CMD0 failed: R1=%02x\n", result); - SPI_SELECT(spi, SPIDEV_MMCSD, false); + SPI_SELECT(spi, SPIDEV_MMCSD(0), false); mmcsd_semgive(slot); return -EIO; } @@ -1749,7 +1749,7 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot) if (elapsed >= MMCSD_DELAY_1SEC) { ferr("ERROR: Failed to exit IDLE state\n"); - SPI_SELECT(spi, SPIDEV_MMCSD, false); + SPI_SELECT(spi, SPIDEV_MMCSD(0), false); mmcsd_semgive(slot); return -EIO; } @@ -1758,7 +1758,7 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot) if (slot->type == MMCSD_CARDTYPE_UNKNOWN) { ferr("ERROR: Failed to identify card\n"); - SPI_SELECT(spi, SPIDEV_MMCSD, false); + SPI_SELECT(spi, SPIDEV_MMCSD(0), false); mmcsd_semgive(slot); return -EIO; } @@ -1770,7 +1770,7 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot) if (result != OK) { ferr("ERROR: mmcsd_getcsd(CMD9) failed: %d\n", result); - SPI_SELECT(spi, SPIDEV_MMCSD, false); + SPI_SELECT(spi, SPIDEV_MMCSD(0), false); mmcsd_semgive(slot); return -EIO; } @@ -1814,7 +1814,7 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot) #endif slot->state &= ~MMCSD_SLOTSTATUS_NOTREADY; - SPI_SELECT(spi, SPIDEV_MMCSD, false); + SPI_SELECT(spi, SPIDEV_MMCSD(0), false); return OK; } @@ -1853,7 +1853,7 @@ static void mmcsd_mediachanged(void *arg) slot->state &= ~(MMCSD_SLOTSTATUS_NODISK | MMCSD_SLOTSTATUS_NOTREADY | MMCSD_SLOTSTATUS_MEDIACHGD); - if ((SPI_STATUS(spi, SPIDEV_MMCSD) & SPI_STATUS_PRESENT) == 0) + if ((SPI_STATUS(spi, SPIDEV_MMCSD(0)) & SPI_STATUS_PRESENT) == 0) { /* Media is not present */ diff --git a/drivers/mtd/at24xx.c b/drivers/mtd/at24xx.c index 936008a567..b9076c0846 100644 --- a/drivers/mtd/at24xx.c +++ b/drivers/mtd/at24xx.c @@ -641,7 +641,7 @@ FAR struct mtd_dev_s *at24c_initialize(FAR struct i2c_master_s *dev) /* Allocate a state structure (we allocate the structure instead of using * a fixed, static allocation so that we can handle multiple FLASH devices. * The current implementation would handle only one FLASH part per I2C - * device (only because of the SPIDEV_FLASH definition) and so would have + * device (only because of the SPIDEV_FLASH(0) definition) and so would have * to be extended to handle multiple FLASH parts on the same I2C bus. */ diff --git a/drivers/mtd/at25.c b/drivers/mtd/at25.c index 777ff3877f..c499ca2a55 100644 --- a/drivers/mtd/at25.c +++ b/drivers/mtd/at25.c @@ -218,7 +218,7 @@ static inline int at25_readid(struct at25_dev_s *priv) /* Lock the SPI bus, configure the bus, and select this FLASH part. */ at25_lock(priv->dev); - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send the "Read ID (RDID)" command and read the first three ID bytes */ @@ -228,7 +228,7 @@ static inline int at25_readid(struct at25_dev_s *priv) /* Deselect the FLASH and unlock the bus */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); at25_unlock(priv->dev); finfo("manufacturer: %02x memory: %02x\n", @@ -262,7 +262,7 @@ static void at25_waitwritecomplete(struct at25_dev_s *priv) { /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Read Status Register (RDSR)" command */ @@ -274,7 +274,7 @@ static void at25_waitwritecomplete(struct at25_dev_s *priv) /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); /* Given that writing could take up to few tens of milliseconds, and erasing * could take more. The following short delay in the "busy" case will allow @@ -304,9 +304,9 @@ static void at25_waitwritecomplete(struct at25_dev_s *priv) static void at25_writeenable(struct at25_dev_s *priv) { - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); (void)SPI_SEND(priv->dev, AT25_WREN); - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); finfo("Enabled\n"); } @@ -334,7 +334,7 @@ static inline void at25_sectorerase(struct at25_dev_s *priv, off_t sector) /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send the "Sector Erase (SE)" instruction */ @@ -351,7 +351,7 @@ static inline void at25_sectorerase(struct at25_dev_s *priv, off_t sector) /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); finfo("Erased\n"); } @@ -377,7 +377,7 @@ static inline int at25_bulkerase(struct at25_dev_s *priv) /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send the "Bulk Erase (BE)" instruction */ @@ -385,7 +385,7 @@ static inline int at25_bulkerase(struct at25_dev_s *priv) /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); finfo("Return: OK\n"); return OK; } @@ -415,7 +415,7 @@ static inline void at25_pagewrite(struct at25_dev_s *priv, FAR const uint8_t *bu /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Page Program (PP)" command */ @@ -433,7 +433,7 @@ static inline void at25_pagewrite(struct at25_dev_s *priv, FAR const uint8_t *bu /* Deselect the FLASH: Chip Select high */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); finfo("Written\n"); } @@ -535,7 +535,7 @@ static ssize_t at25_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes, /* Lock the SPI bus and select this FLASH part */ at25_lock(priv->dev); - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Read from Memory " instruction */ @@ -553,7 +553,7 @@ static ssize_t at25_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes, /* Deselect the FLASH and unlock the SPI bus */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); at25_unlock(priv->dev); finfo("return nbytes: %d\n", (int)nbytes); @@ -642,7 +642,7 @@ FAR struct mtd_dev_s *at25_initialize(FAR struct spi_dev_s *dev) /* Allocate a state structure (we allocate the structure instead of using * a fixed, static allocation so that we can handle multiple FLASH devices. * The current implementation would handle only one FLASH part per SPI - * device (only because of the SPIDEV_FLASH definition) and so would have + * device (only because of the SPIDEV_FLASH(0) definition) and so would have * to be extended to handle multiple FLASH parts on the same SPI bus. */ @@ -662,7 +662,7 @@ FAR struct mtd_dev_s *at25_initialize(FAR struct spi_dev_s *dev) /* Deselect the FLASH */ - SPI_SELECT(dev, SPIDEV_FLASH, false); + SPI_SELECT(dev, SPIDEV_FLASH(0), false); /* Identify the FLASH chip and get its capacity */ @@ -680,10 +680,10 @@ FAR struct mtd_dev_s *at25_initialize(FAR struct spi_dev_s *dev) /* Unprotect all sectors */ at25_writeenable(priv); - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); (void)SPI_SEND(priv->dev, AT25_WRSR); (void)SPI_SEND(priv->dev, AT25_SR_UNPROT); - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); } } diff --git a/drivers/mtd/at45db.c b/drivers/mtd/at45db.c index 4219c0d3b9..7f4a3f8bb9 100644 --- a/drivers/mtd/at45db.c +++ b/drivers/mtd/at45db.c @@ -312,9 +312,9 @@ static inline void at45db_unlock(FAR struct at45db_dev_s *priv) #ifdef CONFIG_AT45DB_PWRSAVE static void at45db_pwrdown(FAR struct at45db_dev_s *priv) { - SPI_SELECT(priv->spi, SPIDEV_FLASH, true); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), true); SPI_SEND(priv->spi, AT45DB_PWRDOWN); - SPI_SELECT(priv->spi, SPIDEV_FLASH, false); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), false); } #endif @@ -325,9 +325,9 @@ static void at45db_pwrdown(FAR struct at45db_dev_s *priv) #ifdef CONFIG_AT45DB_PWRSAVE static void at45db_resume(FAR struct at45db_dev_s *priv) { - SPI_SELECT(priv->spi, SPIDEV_FLASH, true); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), true); SPI_SEND(priv->spi, AT45DB_RESUME); - SPI_SELECT(priv->spi, SPIDEV_FLASH, false); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), false); up_udelay(50); } #endif @@ -347,7 +347,7 @@ static inline int at45db_rdid(FAR struct at45db_dev_s *priv) * locked the bus for exclusive access) */ - SPI_SELECT(priv->spi, SPIDEV_FLASH, true); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), true); /* Send the " Manufacturer and Device ID Read" command and read the next three * ID bytes from the FLASH. @@ -358,7 +358,7 @@ static inline int at45db_rdid(FAR struct at45db_dev_s *priv) /* Deselect the FLASH */ - SPI_SELECT(priv->spi, SPIDEV_FLASH, false); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), false); finfo("manufacturer: %02x devid1: %02x devid2: %02x\n", devid[0], devid[1], devid[2]); @@ -438,10 +438,10 @@ static inline uint8_t at45db_rdsr(FAR struct at45db_dev_s *priv) { uint8_t retval; - SPI_SELECT(priv->spi, SPIDEV_FLASH, true); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), true); SPI_SEND(priv->spi, AT45DB_RDSR); retval = SPI_SEND(priv->spi, 0xff); - SPI_SELECT(priv->spi, SPIDEV_FLASH, false); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), false); return retval; } @@ -503,9 +503,9 @@ static inline void at45db_pgerase(FAR struct at45db_dev_s *priv, off_t sector) /* Erase the page */ - SPI_SELECT(priv->spi, SPIDEV_FLASH, true); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), true); SPI_SNDBLOCK(priv->spi, erasecmd, 4); - SPI_SELECT(priv->spi, SPIDEV_FLASH, false); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), false); /* Wait for any erase to complete if we are not trying to improve write * performance. (see comments above). @@ -545,9 +545,9 @@ static inline int at32db_chiperase(FAR struct at45db_dev_s *priv) * down... */ - SPI_SELECT(priv->spi, SPIDEV_FLASH, true); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), true); SPI_SNDBLOCK(priv->spi, g_chiperase, CHIP_ERASE_SIZE); - SPI_SELECT(priv->spi, SPIDEV_FLASH, false); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), false); /* Wait for any erase to complete if we are not trying to improve write * performance. (see comments above). @@ -589,10 +589,10 @@ static inline void at45db_pgwrite(FAR struct at45db_dev_s *priv, at45db_waitbusy(priv); #endif - SPI_SELECT(priv->spi, SPIDEV_FLASH, true); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), true); SPI_SNDBLOCK(priv->spi, wrcmd, 4); SPI_SNDBLOCK(priv->spi, buffer, 1 << priv->pageshift); - SPI_SELECT(priv->spi, SPIDEV_FLASH, false); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), false); /* Wait for any erase to complete if we are not trying to improve write * performance. (see comments above). @@ -733,10 +733,10 @@ static ssize_t at45db_read(FAR struct mtd_dev_s *mtd, off_t offset, size_t nbyte /* Perform the read */ - SPI_SELECT(priv->spi, SPIDEV_FLASH, true); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), true); SPI_SNDBLOCK(priv->spi, rdcmd, 5); SPI_RECVBLOCK(priv->spi, buffer, nbytes); - SPI_SELECT(priv->spi, SPIDEV_FLASH, false); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), false); at45db_pwrdown(priv); at45db_unlock(priv); @@ -835,7 +835,7 @@ FAR struct mtd_dev_s *at45db_initialize(FAR struct spi_dev_s *spi) /* Allocate a state structure (we allocate the structure instead of using a fixed, * static allocation so that we can handle multiple FLASH devices. The current * implementation would handle only one FLASH part per SPI device (only because - * of the SPIDEV_FLASH definition) and so would have to be extended to handle + * of the SPIDEV_FLASH(0) definition) and so would have to be extended to handle * multiple FLASH parts on the same SPI bus. */ @@ -855,7 +855,7 @@ FAR struct mtd_dev_s *at45db_initialize(FAR struct spi_dev_s *spi) /* Deselect the FLASH */ - SPI_SELECT(spi, SPIDEV_FLASH, false); + SPI_SELECT(spi, SPIDEV_FLASH(0), false); /* Lock and configure the SPI bus. */ @@ -889,9 +889,9 @@ FAR struct mtd_dev_s *at45db_initialize(FAR struct spi_dev_s *spi) fwarn("WARNING: Reprogramming page size\n"); - SPI_SELECT(priv->spi, SPIDEV_FLASH, true); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), true); SPI_SNDBLOCK(priv->spi, g_binpgsize, BINPGSIZE_SIZE); - SPI_SELECT(priv->spi, SPIDEV_FLASH, false); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), false); goto errout; } diff --git a/drivers/mtd/is25xp.c b/drivers/mtd/is25xp.c index 55b677b38a..3ce5e3f0ce 100644 --- a/drivers/mtd/is25xp.c +++ b/drivers/mtd/is25xp.c @@ -253,7 +253,7 @@ static inline int is25xp_readid(struct is25xp_dev_s *priv) /* Lock the SPI bus, configure the bus, and select this FLASH part. */ is25xp_lock(priv->dev); - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send the "Read ID (RDID)" command and read the first three ID bytes */ @@ -264,7 +264,7 @@ static inline int is25xp_readid(struct is25xp_dev_s *priv) /* Deselect the FLASH and unlock the bus */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); is25xp_unlock(priv->dev); finfo("manufacturer: %02x memory: %02x capacity: %02x\n", @@ -324,7 +324,7 @@ static void is25xp_waitwritecomplete(struct is25xp_dev_s *priv) /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Read Status Register (RDSR)" command */ @@ -342,7 +342,7 @@ static void is25xp_waitwritecomplete(struct is25xp_dev_s *priv) /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); #else @@ -352,7 +352,7 @@ static void is25xp_waitwritecomplete(struct is25xp_dev_s *priv) { /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Read Status Register (RDSR)" command */ @@ -364,7 +364,7 @@ static void is25xp_waitwritecomplete(struct is25xp_dev_s *priv) /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); /* Given that writing could take up to few tens of milliseconds, and erasing * could take more. The following short delay in the "busy" case will allow @@ -394,7 +394,7 @@ static void is25xp_writeenable(struct is25xp_dev_s *priv) { /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Write Enable (WREN)" command */ @@ -402,7 +402,7 @@ static void is25xp_writeenable(struct is25xp_dev_s *priv) /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); finfo("Enabled\n"); } @@ -418,14 +418,14 @@ static void is25xp_unprotect(struct is25xp_dev_s *priv) /* Send "Write status (WRSR)" */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); SPI_SEND(priv->dev, IS25_WRSR); /* Followed by the new status value */ SPI_SEND(priv->dev, 0); - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); } /************************************************************************************ @@ -454,7 +454,7 @@ static void is25xp_sectorerase(struct is25xp_dev_s *priv, off_t sector, uint8_t /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send the "Sector Erase (SE)" or Sub-Sector Erase (SSE) instruction * that was passed in as the erase type. @@ -474,7 +474,7 @@ static void is25xp_sectorerase(struct is25xp_dev_s *priv, off_t sector, uint8_t /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); finfo("Erased\n"); } @@ -500,7 +500,7 @@ static inline int is25xp_bulkerase(struct is25xp_dev_s *priv) /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send the "Chip Erase (CER)" instruction */ @@ -508,7 +508,7 @@ static inline int is25xp_bulkerase(struct is25xp_dev_s *priv) /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); is25xp_waitwritecomplete(priv); finfo("Return: OK\n"); @@ -540,7 +540,7 @@ static inline void is25xp_pagewrite(struct is25xp_dev_s *priv, FAR const uint8_t /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Page Program (PP)" command */ @@ -559,7 +559,7 @@ static inline void is25xp_pagewrite(struct is25xp_dev_s *priv, FAR const uint8_t /* Deselect the FLASH: Chip Select high */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); finfo("Written\n"); } @@ -587,7 +587,7 @@ static inline void is25xp_bytewrite(struct is25xp_dev_s *priv, FAR const uint8_t /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Page Program (PP)" command */ @@ -606,7 +606,7 @@ static inline void is25xp_bytewrite(struct is25xp_dev_s *priv, FAR const uint8_t /* Deselect the FLASH: Chip Select high */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); finfo("Written\n"); } #endif @@ -762,7 +762,7 @@ static ssize_t is25xp_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbyte /* Lock the SPI bus and select this FLASH part */ is25xp_lock(priv->dev); - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Read from Memory " instruction */ @@ -780,7 +780,7 @@ static ssize_t is25xp_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbyte /* Deselect the FLASH and unlock the SPI bus */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); is25xp_unlock(priv->dev); finfo("return nbytes: %d\n", (int)nbytes); return nbytes; @@ -943,7 +943,7 @@ FAR struct mtd_dev_s *is25xp_initialize(FAR struct spi_dev_s *dev) /* Allocate a state structure (we allocate the structure instead of using * a fixed, static allocation so that we can handle multiple FLASH devices. * The current implementation would handle only one FLASH part per SPI - * device (only because of the SPIDEV_FLASH definition) and so would have + * device (only because of the SPIDEV_FLASH(0) definition) and so would have * to be extended to handle multiple FLASH parts on the same SPI bus. */ @@ -967,7 +967,7 @@ FAR struct mtd_dev_s *is25xp_initialize(FAR struct spi_dev_s *dev) /* Deselect the FLASH */ - SPI_SELECT(dev, SPIDEV_FLASH, false); + SPI_SELECT(dev, SPIDEV_FLASH(0), false); /* Identify the FLASH chip and get its capacity */ diff --git a/drivers/mtd/m25px.c b/drivers/mtd/m25px.c index 4402995afb..2ce37d2e38 100644 --- a/drivers/mtd/m25px.c +++ b/drivers/mtd/m25px.c @@ -317,7 +317,7 @@ static inline int m25p_readid(struct m25p_dev_s *priv) /* Lock the SPI bus, configure the bus, and select this FLASH part. */ m25p_lock(priv->dev); - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send the "Read ID (RDID)" command and read the first three ID bytes */ @@ -328,7 +328,7 @@ static inline int m25p_readid(struct m25p_dev_s *priv) /* Deselect the FLASH and unlock the bus */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); m25p_unlock(priv->dev); finfo("manufacturer: %02x memory: %02x capacity: %02x\n", @@ -432,7 +432,7 @@ static void m25p_waitwritecomplete(struct m25p_dev_s *priv) { /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Read Status Register (RDSR)" command */ @@ -444,7 +444,7 @@ static void m25p_waitwritecomplete(struct m25p_dev_s *priv) /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); /* Given that writing could take up to few tens of milliseconds, and erasing * could take more. The following short delay in the "busy" case will allow @@ -471,7 +471,7 @@ static void m25p_writeenable(struct m25p_dev_s *priv) { /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Write Enable (WREN)" command */ @@ -479,7 +479,7 @@ static void m25p_writeenable(struct m25p_dev_s *priv) /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); finfo("Enabled\n"); } @@ -518,7 +518,7 @@ static void m25p_sectorerase(struct m25p_dev_s *priv, off_t sector, uint8_t type /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send the "Sector Erase (SE)" or Sub-Sector Erase (SSE) instruction * that was passed in as the erase type. @@ -537,7 +537,7 @@ static void m25p_sectorerase(struct m25p_dev_s *priv, off_t sector, uint8_t type /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); finfo("Erased\n"); } @@ -563,7 +563,7 @@ static inline int m25p_bulkerase(struct m25p_dev_s *priv) /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send the "Bulk Erase (BE)" instruction */ @@ -571,7 +571,7 @@ static inline int m25p_bulkerase(struct m25p_dev_s *priv) /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); finfo("Return: OK\n"); return OK; } @@ -601,7 +601,7 @@ static inline void m25p_pagewrite(struct m25p_dev_s *priv, FAR const uint8_t *bu /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Page Program (PP)" command */ @@ -619,7 +619,7 @@ static inline void m25p_pagewrite(struct m25p_dev_s *priv, FAR const uint8_t *bu /* Deselect the FLASH: Chip Select high */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); finfo("Written\n"); } @@ -647,7 +647,7 @@ static inline void m25p_bytewrite(struct m25p_dev_s *priv, FAR const uint8_t *bu /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Page Program (PP)" command */ @@ -665,7 +665,7 @@ static inline void m25p_bytewrite(struct m25p_dev_s *priv, FAR const uint8_t *bu /* Deselect the FLASH: Chip Select high */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); finfo("Written\n"); } #endif @@ -809,7 +809,7 @@ static ssize_t m25p_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes, /* Lock the SPI bus and select this FLASH part */ m25p_lock(priv->dev); - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Read from Memory " instruction */ @@ -827,7 +827,7 @@ static ssize_t m25p_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes, /* Deselect the FLASH and unlock the SPI bus */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); m25p_unlock(priv->dev); finfo("return nbytes: %d\n", (int)nbytes); return nbytes; @@ -999,7 +999,7 @@ FAR struct mtd_dev_s *m25p_initialize(FAR struct spi_dev_s *dev) /* Allocate a state structure (we allocate the structure instead of using * a fixed, static allocation so that we can handle multiple FLASH devices. * The current implementation would handle only one FLASH part per SPI - * device (only because of the SPIDEV_FLASH definition) and so would have + * device (only because of the SPIDEV_FLASH(0) definition) and so would have * to be extended to handle multiple FLASH parts on the same SPI bus. */ @@ -1022,7 +1022,7 @@ FAR struct mtd_dev_s *m25p_initialize(FAR struct spi_dev_s *dev) /* Deselect the FLASH */ - SPI_SELECT(dev, SPIDEV_FLASH, false); + SPI_SELECT(dev, SPIDEV_FLASH(0), false); /* Identify the FLASH chip and get its capacity */ diff --git a/drivers/mtd/mtd_rwbuffer.c b/drivers/mtd/mtd_rwbuffer.c index 8d2ffc2d47..b775b67cfd 100644 --- a/drivers/mtd/mtd_rwbuffer.c +++ b/drivers/mtd/mtd_rwbuffer.c @@ -352,7 +352,7 @@ FAR struct mtd_dev_s *mtd_rwb_initialize(FAR struct mtd_dev_s *mtd) /* Allocate a state structure (we allocate the structure instead of using * a fixed, static allocation so that we can handle multiple FLASH devices. * The current implementation would handle only one FLASH part per SPI - * device (only because of the SPIDEV_FLASH definition) and so would have + * device (only because of the SPIDEV_FLASH(0) definition) and so would have * to be extended to handle multiple FLASH parts on the same SPI bus. */ diff --git a/drivers/mtd/mx25lx.c b/drivers/mtd/mx25lx.c index 47c447cf1b..ae4833691d 100644 --- a/drivers/mtd/mx25lx.c +++ b/drivers/mtd/mx25lx.c @@ -314,7 +314,7 @@ static inline int mx25l_readid(FAR struct mx25l_dev_s *priv) /* Lock the SPI bus, configure the bus, and select this FLASH part. */ mx25l_lock(priv->dev); - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send the "Read ID (RDID)" command and read the first three ID bytes */ @@ -325,7 +325,7 @@ static inline int mx25l_readid(FAR struct mx25l_dev_s *priv) /* Deselect the FLASH and unlock the bus */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); mx25l_unlock(priv->dev); mxlinfo("manufacturer: %02x memory: %02x capacity: %02x\n", @@ -374,7 +374,7 @@ static void mx25l_waitwritecomplete(FAR struct mx25l_dev_s *priv) { /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Read Status Register (RDSR)" command */ @@ -386,7 +386,7 @@ static void mx25l_waitwritecomplete(FAR struct mx25l_dev_s *priv) /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); /* Given that writing could take up to few tens of milliseconds, and erasing * could take more. The following short delay in the "busy" case will allow @@ -413,7 +413,7 @@ static void mx25l_writeenable(FAR struct mx25l_dev_s *priv) { /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Write Enable (WREN)" command */ @@ -421,7 +421,7 @@ static void mx25l_writeenable(FAR struct mx25l_dev_s *priv) /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); mxlinfo("Enabled\n"); } @@ -434,7 +434,7 @@ static void mx25l_writedisable(FAR struct mx25l_dev_s *priv) { /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Write Disable (WRDI)" command */ @@ -442,7 +442,7 @@ static void mx25l_writedisable(FAR struct mx25l_dev_s *priv) /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); mxlinfo("Disabled\n"); } @@ -465,7 +465,7 @@ static void mx25l_sectorerase(FAR struct mx25l_dev_s *priv, off_t sector) /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send the "Sector Erase (SE)" or "Block Erase (BE)" instruction * that was passed in as the erase type. @@ -484,7 +484,7 @@ static void mx25l_sectorerase(FAR struct mx25l_dev_s *priv, off_t sector) /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); mx25l_waitwritecomplete(priv); @@ -505,7 +505,7 @@ static inline int mx25l_chiperase(FAR struct mx25l_dev_s *priv) /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send the "Chip Erase (CE)" instruction */ @@ -513,7 +513,7 @@ static inline int mx25l_chiperase(FAR struct mx25l_dev_s *priv) /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); mx25l_waitwritecomplete(priv); @@ -540,7 +540,7 @@ static void mx25l_byteread(FAR struct mx25l_dev_s *priv, FAR uint8_t *buffer, /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Read from Memory " instruction */ @@ -562,7 +562,7 @@ static void mx25l_byteread(FAR struct mx25l_dev_s *priv, FAR uint8_t *buffer, /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); } /************************************************************************************ @@ -583,7 +583,7 @@ static inline void mx25l_pagewrite(FAR struct mx25l_dev_s *priv, /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send the "Page Program (MX25L_PP)" Command */ @@ -601,7 +601,7 @@ static inline void mx25l_pagewrite(FAR struct mx25l_dev_s *priv, /* Deselect the FLASH and setup for the next pass through the loop */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); /* Wait for any preceding write or erase operation to complete. */ @@ -988,7 +988,7 @@ FAR struct mtd_dev_s *mx25l_initialize_spi(FAR struct spi_dev_s *dev) /* Allocate a state structure (we allocate the structure instead of using * a fixed, static allocation so that we can handle multiple FLASH devices. * The current implementation would handle only one FLASH part per SPI - * device (only because of the SPIDEV_FLASH definition) and so would have + * device (only because of the SPIDEV_FLASH(0) definition) and so would have * to be extended to handle multiple FLASH parts on the same SPI bus. */ @@ -1008,7 +1008,7 @@ FAR struct mtd_dev_s *mx25l_initialize_spi(FAR struct spi_dev_s *dev) /* Deselect the FLASH */ - SPI_SELECT(dev, SPIDEV_FLASH, false); + SPI_SELECT(dev, SPIDEV_FLASH(0), false); /* Identify the FLASH chip and get its capacity */ diff --git a/drivers/mtd/n25qxxx.c b/drivers/mtd/n25qxxx.c index e5272f47ed..3ed07ac808 100644 --- a/drivers/mtd/n25qxxx.c +++ b/drivers/mtd/n25qxxx.c @@ -1406,7 +1406,7 @@ FAR struct mtd_dev_s *n25qxxx_initialize(FAR struct qspi_dev_s *qspi, bool unpro /* Allocate a state structure (we allocate the structure instead of using * a fixed, static allocation so that we can handle multiple FLASH devices. * The current implementation would handle only one FLASH part per QuadSPI - * device (only because of the QSPIDEV_FLASH definition) and so would have + * device (only because of the QSPIDEV_FLASH(0) definition) and so would have * to be extended to handle multiple FLASH parts on the same QuadSPI bus. */ diff --git a/drivers/mtd/ramtron.c b/drivers/mtd/ramtron.c index 236084fb79..ee07d18e07 100644 --- a/drivers/mtd/ramtron.c +++ b/drivers/mtd/ramtron.c @@ -381,7 +381,7 @@ static inline int ramtron_readid(struct ramtron_dev_s *priv) /* Lock the SPI bus, configure the bus, and select this FLASH part. */ ramtron_lock(priv); - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send the "Read ID (RDID)" command */ @@ -411,7 +411,7 @@ static inline int ramtron_readid(struct ramtron_dev_s *priv) /* Deselect the FLASH and unlock the bus */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); ramtron_unlock(priv->dev); /* Select part from the part list */ @@ -452,7 +452,7 @@ static int ramtron_waitwritecomplete(struct ramtron_dev_s *priv) /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Read Status Register (RDSR)" command */ @@ -475,7 +475,7 @@ static int ramtron_waitwritecomplete(struct ramtron_dev_s *priv) /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); if (retries > 0) { @@ -499,7 +499,7 @@ static void ramtron_writeenable(struct ramtron_dev_s *priv) { /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Write Enable (WREN)" command */ @@ -507,7 +507,7 @@ static void ramtron_writeenable(struct ramtron_dev_s *priv) /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); finfo("Enabled\n"); } @@ -555,7 +555,7 @@ static inline int ramtron_pagewrite(struct ramtron_dev_s *priv, FAR const uint8_ /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Page Program (PP)" command */ @@ -571,7 +571,7 @@ static inline int ramtron_pagewrite(struct ramtron_dev_s *priv, FAR const uint8_ /* Deselect the FLASH: Chip Select high */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); finfo("Written\n"); #ifdef CONFIG_RAMTRON_WRITEWAIT @@ -676,7 +676,7 @@ static ssize_t ramtron_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbyt /* Lock the SPI bus and select this FLASH part */ ramtron_lock(priv); - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Read from Memory " instruction */ @@ -709,7 +709,7 @@ static ssize_t ramtron_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbyt /* Deselect the FLASH and unlock the SPI bus */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); ramtron_unlock(priv->dev); finfo("return nbytes: %d\n", (int)nbytes); @@ -805,7 +805,7 @@ FAR struct mtd_dev_s *ramtron_initialize(FAR struct spi_dev_s *dev) /* Allocate a state structure (we allocate the structure instead of using * a fixed, static allocation so that we can handle multiple FLASH devices. * The current implementation would handle only one FLASH part per SPI - * device (only because of the SPIDEV_FLASH definition) and so would have + * device (only because of the SPIDEV_FLASH(0) definition) and so would have * to be extended to handle multiple FLASH parts on the same SPI bus. */ @@ -825,7 +825,7 @@ FAR struct mtd_dev_s *ramtron_initialize(FAR struct spi_dev_s *dev) /* Deselect the FLASH */ - SPI_SELECT(dev, SPIDEV_FLASH, false); + SPI_SELECT(dev, SPIDEV_FLASH(0), false); /* Identify the FLASH chip and get its capacity */ diff --git a/drivers/mtd/s25fl1.c b/drivers/mtd/s25fl1.c index 33a2589638..f513b68363 100644 --- a/drivers/mtd/s25fl1.c +++ b/drivers/mtd/s25fl1.c @@ -1453,7 +1453,7 @@ FAR struct mtd_dev_s *s25fl1_initialize(FAR struct qspi_dev_s *qspi, bool unprot /* Allocate a state structure (we allocate the structure instead of using * a fixed, static allocation so that we can handle multiple FLASH devices. * The current implementation would handle only one FLASH part per QuadSPI - * device (only because of the QSPIDEV_FLASH definition) and so would have + * device (only because of the QSPIDEV_FLASH(0) definition) and so would have * to be extended to handle multiple FLASH parts on the same QuadSPI bus. */ diff --git a/drivers/mtd/sector512.c b/drivers/mtd/sector512.c index 56e07c8c6a..5e0100183a 100644 --- a/drivers/mtd/sector512.c +++ b/drivers/mtd/sector512.c @@ -599,7 +599,7 @@ FAR struct mtd_dev_s *s512_initialize(FAR struct mtd_dev_s *mtd) /* Allocate a state structure (we allocate the structure instead of using * a fixed, static allocation so that we can handle multiple FLASH devices. * The current implementation would handle only one FLASH part per SPI - * device (only because of the SPIDEV_FLASH definition) and so would have + * device (only because of the SPIDEV_FLASH(0) definition) and so would have * to be extended to handle multiple FLASH parts on the same SPI bus. */ diff --git a/drivers/mtd/sst25.c b/drivers/mtd/sst25.c index 9c84c7fba9..7e4b3435e8 100644 --- a/drivers/mtd/sst25.c +++ b/drivers/mtd/sst25.c @@ -314,7 +314,7 @@ static inline int sst25_readid(struct sst25_dev_s *priv) /* Lock the SPI bus, configure the bus, and select this FLASH part. */ sst25_lock(priv->dev); - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send the "Read ID (RDID)" command and read the first three ID bytes */ @@ -325,7 +325,7 @@ static inline int sst25_readid(struct sst25_dev_s *priv) /* Deselect the FLASH and unlock the bus */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); sst25_unlock(priv->dev); finfo("manufacturer: %02x memory: %02x capacity: %02x\n", @@ -376,7 +376,7 @@ static void sst25_unprotect(struct sst25_dev_s *priv) /* Send "Write enable status (WRSR)" */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); SPI_SEND(priv->dev, SST25_WRSR); @@ -384,7 +384,7 @@ static void sst25_unprotect(struct sst25_dev_s *priv) SPI_SEND(priv->dev, 0); - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); } #endif @@ -402,7 +402,7 @@ static uint8_t sst25_waitwritecomplete(struct sst25_dev_s *priv) { /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Read Status Register (RDSR)" command */ @@ -414,7 +414,7 @@ static uint8_t sst25_waitwritecomplete(struct sst25_dev_s *priv) /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); /* Given that writing could take up to few tens of milliseconds, and erasing * could take more. The following short delay in the "busy" case will allow @@ -443,7 +443,7 @@ static inline void sst25_cmd(struct sst25_dev_s *priv, uint8_t cmd) { /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send command */ @@ -451,7 +451,7 @@ static inline void sst25_cmd(struct sst25_dev_s *priv, uint8_t cmd) /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); } /************************************************************************************ @@ -498,7 +498,7 @@ static void sst25_sectorerase(struct sst25_dev_s *priv, off_t sector) /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send the "Sector Erase (SE)" instruction */ @@ -514,7 +514,7 @@ static void sst25_sectorerase(struct sst25_dev_s *priv, off_t sector) /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); } /************************************************************************************ @@ -560,7 +560,7 @@ static void sst25_byteread(FAR struct sst25_dev_s *priv, FAR uint8_t *buffer, /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Read from Memory " instruction */ @@ -588,7 +588,7 @@ static void sst25_byteread(FAR struct sst25_dev_s *priv, FAR uint8_t *buffer, /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); } /************************************************************************************ @@ -623,7 +623,7 @@ static void sst25_bytewrite(struct sst25_dev_s *priv, FAR const uint8_t *buffer, /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Byte Program (BP)" command */ @@ -641,7 +641,7 @@ static void sst25_bytewrite(struct sst25_dev_s *priv, FAR const uint8_t *buffer, /* Deselect the FLASH and setup for the next pass through the loop */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); } /* Advance to the next byte */ @@ -704,7 +704,7 @@ static void sst25_wordwrite(struct sst25_dev_s *priv, FAR const uint8_t *buffer, /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Auto Address Increment (AAI)" command */ @@ -722,7 +722,7 @@ static void sst25_wordwrite(struct sst25_dev_s *priv, FAR const uint8_t *buffer, /* Deselect the FLASH: Chip Select high */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); /* Wait for the preceding write to complete. */ @@ -749,7 +749,7 @@ static void sst25_wordwrite(struct sst25_dev_s *priv, FAR const uint8_t *buffer, /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Auto Address Increment (AAI)" command with no address */ @@ -761,7 +761,7 @@ static void sst25_wordwrite(struct sst25_dev_s *priv, FAR const uint8_t *buffer, /* Deselect the FLASH: Chip Select high */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); /* Wait for the preceding write to complete. */ @@ -1177,7 +1177,7 @@ FAR struct mtd_dev_s *sst25_initialize(FAR struct spi_dev_s *dev) /* Allocate a state structure (we allocate the structure instead of using * a fixed, static allocation so that we can handle multiple FLASH devices. * The current implementation would handle only one FLASH part per SPI - * device (only because of the SPIDEV_FLASH definition) and so would have + * device (only because of the SPIDEV_FLASH(0) definition) and so would have * to be extended to handle multiple FLASH parts on the same SPI bus. */ @@ -1197,7 +1197,7 @@ FAR struct mtd_dev_s *sst25_initialize(FAR struct spi_dev_s *dev) /* Deselect the FLASH */ - SPI_SELECT(dev, SPIDEV_FLASH, false); + SPI_SELECT(dev, SPIDEV_FLASH(0), false); /* Identify the FLASH chip and get its capacity */ diff --git a/drivers/mtd/sst25xx.c b/drivers/mtd/sst25xx.c index 9f883483af..93aca1a383 100644 --- a/drivers/mtd/sst25xx.c +++ b/drivers/mtd/sst25xx.c @@ -264,19 +264,19 @@ static inline int sst25xx_readid(struct sst25xx_dev_s *priv) /* Lock the SPI bus, configure the bus, and select this FLASH part. */ sst25xx_lock(priv->dev); - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send the "Read ID (RDID)" command and read the first three ID bytes */ (void)SPI_SEND(priv->dev, SST25_RDID); - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); manufacturer = SPI_SEND(priv->dev, SST25_DUMMY); memory = SPI_SEND(priv->dev, SST25_DUMMY); capacity = SPI_SEND(priv->dev, SST25_DUMMY); /* Deselect the FLASH and unlock the bus */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); sst25xx_unlock(priv->dev); finfo("manufacturer: %02x memory: %02x capacity: %02x\n", @@ -326,7 +326,7 @@ static void sst25xx_waitwritecomplete(struct sst25xx_dev_s *priv) { /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Read Status Register (RDSR)" command */ @@ -338,7 +338,7 @@ static void sst25xx_waitwritecomplete(struct sst25xx_dev_s *priv) /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); /* Given that writing could take up to few tens of milliseconds, and erasing * could take more. The following short delay in the "busy" case will allow @@ -367,7 +367,7 @@ static void sst25xx_writeenable(struct sst25xx_dev_s *priv) { /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Write Enable (WREN)" command */ @@ -375,7 +375,7 @@ static void sst25xx_writeenable(struct sst25xx_dev_s *priv) /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); finfo("Enabled\n"); } @@ -387,23 +387,23 @@ static void sst25xx_unprotect(struct sst25xx_dev_s *priv) { /* Send "Write enable status (EWSR)" */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); (void)SPI_SEND(priv->dev, SST25_EWSR); /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); /* Send "Write status (WRSR)" */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); SPI_SEND(priv->dev, SST25_WRSR); /* Followed by the new status value */ SPI_SEND(priv->dev, 0); - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); } /************************************************************************************ @@ -432,7 +432,7 @@ static void sst25xx_sectorerase(struct sst25xx_dev_s *priv, off_t sector, uint8_ /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send the "Sector Erase (SE)" or Sub-Sector Erase (SSE) instruction * that was passed in as the erase type. @@ -452,7 +452,7 @@ static void sst25xx_sectorerase(struct sst25xx_dev_s *priv, off_t sector, uint8_ /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); finfo("Erased\n"); } @@ -478,7 +478,7 @@ static inline int sst25xx_bulkerase(struct sst25xx_dev_s *priv) /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send the "Bulk Erase (BE)" instruction */ @@ -486,7 +486,7 @@ static inline int sst25xx_bulkerase(struct sst25xx_dev_s *priv) /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); sst25xx_waitwritecomplete(priv); finfo("Return: OK\n"); @@ -518,7 +518,7 @@ static inline void sst25xx_pagewrite(struct sst25xx_dev_s *priv, FAR const uint8 /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Page Program (PP)" command */ @@ -537,7 +537,7 @@ static inline void sst25xx_pagewrite(struct sst25xx_dev_s *priv, FAR const uint8 /* Deselect the FLASH: Chip Select high */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); finfo("Written\n"); } @@ -565,7 +565,7 @@ static inline void sst25xx_bytewrite(struct sst25xx_dev_s *priv, FAR const uint8 /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Page Program (PP)" command */ @@ -584,7 +584,7 @@ static inline void sst25xx_bytewrite(struct sst25xx_dev_s *priv, FAR const uint8 /* Deselect the FLASH: Chip Select high */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); finfo("Written\n"); } #endif @@ -740,7 +740,7 @@ static ssize_t sst25xx_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbyt /* Lock the SPI bus and select this FLASH part */ sst25xx_lock(priv->dev); - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Read from Memory " instruction */ @@ -758,7 +758,7 @@ static ssize_t sst25xx_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbyt /* Deselect the FLASH and unlock the SPI bus */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); sst25xx_unlock(priv->dev); finfo("return nbytes: %d\n", (int)nbytes); return nbytes; @@ -921,7 +921,7 @@ FAR struct mtd_dev_s *sst25xx_initialize(FAR struct spi_dev_s *dev) /* Allocate a state structure (we allocate the structure instead of using * a fixed, static allocation so that we can handle multiple FLASH devices. * The current implementation would handle only one FLASH part per SPI - * device (only because of the SPIDEV_FLASH definition) and so would have + * device (only because of the SPIDEV_FLASH(0) definition) and so would have * to be extended to handle multiple FLASH parts on the same SPI bus. */ @@ -945,7 +945,7 @@ FAR struct mtd_dev_s *sst25xx_initialize(FAR struct spi_dev_s *dev) /* Deselect the FLASH */ - SPI_SELECT(dev, SPIDEV_FLASH, false); + SPI_SELECT(dev, SPIDEV_FLASH(0), false); /* Identify the FLASH chip and get its capacity */ diff --git a/drivers/mtd/sst26.c b/drivers/mtd/sst26.c index 2654a857e8..d2702001c3 100644 --- a/drivers/mtd/sst26.c +++ b/drivers/mtd/sst26.c @@ -323,7 +323,7 @@ static inline int sst26_readid(struct sst26_dev_s *priv) /* Lock the SPI bus, configure the bus, and select this FLASH part. */ sst26_lock(priv->dev); - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send the "Read ID (RDID)" command and read the first three ID bytes */ @@ -334,7 +334,7 @@ static inline int sst26_readid(struct sst26_dev_s *priv) /* Deselect the FLASH and unlock the bus */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); sst26_unlock(priv->dev); sstinfo("manufacturer: %02x memory: %02x capacity: %02x\n", @@ -385,7 +385,7 @@ static void sst26_waitwritecomplete(struct sst26_dev_s *priv) { /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Read Status Register (RDSR)" command */ @@ -397,7 +397,7 @@ static void sst26_waitwritecomplete(struct sst26_dev_s *priv) /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); /* Given that writing could take up to few tens of milliseconds, and erasing * could take more. The following short delay in the "busy" case will allow @@ -426,7 +426,7 @@ static void sst26_globalunlock(struct sst26_dev_s *priv) { /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Global Unlock (ULBPR)" command */ @@ -434,7 +434,7 @@ static void sst26_globalunlock(struct sst26_dev_s *priv) /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); sstinfo("Device unlocked.\n"); } @@ -447,7 +447,7 @@ static void sst26_writeenable(struct sst26_dev_s *priv) { /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Write Enable (WREN)" command */ @@ -455,7 +455,7 @@ static void sst26_writeenable(struct sst26_dev_s *priv) /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); sstinfo("Enabled\n"); } @@ -468,7 +468,7 @@ static void sst26_writedisable(struct sst26_dev_s *priv) { /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Write Disable (WRDI)" command */ @@ -476,7 +476,7 @@ static void sst26_writedisable(struct sst26_dev_s *priv) /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); sstinfo("Disabled\n"); } @@ -499,7 +499,7 @@ static void sst26_sectorerase(struct sst26_dev_s *priv, off_t sector, uint8_t ty /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send the "Sector Erase (SE)" or "Block Erase (BE)" instruction * that was passed in as the erase type. @@ -518,7 +518,7 @@ static void sst26_sectorerase(struct sst26_dev_s *priv, off_t sector, uint8_t ty /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); sst26_waitwritecomplete(priv); @@ -539,7 +539,7 @@ static inline int sst26_chiperase(struct sst26_dev_s *priv) /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send the "Chip Erase (CE)" instruction */ @@ -547,7 +547,7 @@ static inline int sst26_chiperase(struct sst26_dev_s *priv) /* Deselect the FLASH */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); sst26_waitwritecomplete(priv); @@ -572,7 +572,7 @@ static inline void sst26_pagewrite(struct sst26_dev_s *priv, /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Page Program (PP)" command */ @@ -590,7 +590,7 @@ static inline void sst26_pagewrite(struct sst26_dev_s *priv, /* Deselect the FLASH: Chip Select high */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); sst26_waitwritecomplete(priv); @@ -614,7 +614,7 @@ static inline void sst26_bytewrite(struct sst26_dev_s *priv, /* Select this FLASH part */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Page Program (PP)" command */ @@ -633,7 +633,7 @@ static inline void sst26_bytewrite(struct sst26_dev_s *priv, /* Deselect the FLASH: Chip Select high */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); sst26_waitwritecomplete(priv); @@ -737,7 +737,7 @@ static ssize_t sst26_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes /* Lock the SPI bus and select this FLASH part */ sst26_lock(priv->dev); - SPI_SELECT(priv->dev, SPIDEV_FLASH, true); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Read from Memory " instruction */ @@ -759,7 +759,7 @@ static ssize_t sst26_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes /* Deselect the FLASH and unlock the SPI bus */ - SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); sst26_unlock(priv->dev); sstinfo("return nbytes: %d\n", (int)nbytes); return nbytes; @@ -922,7 +922,7 @@ FAR struct mtd_dev_s *sst26_initialize_spi(FAR struct spi_dev_s *dev) /* Allocate a state structure (we allocate the structure instead of using * a fixed, static allocation so that we can handle multiple FLASH devices. * The current implementation would handle only one FLASH part per SPI - * device (only because of the SPIDEV_FLASH definition) and so would have + * device (only because of the SPIDEV_FLASH(0) definition) and so would have * to be extended to handle multiple FLASH parts on the same SPI bus. */ @@ -945,7 +945,7 @@ FAR struct mtd_dev_s *sst26_initialize_spi(FAR struct spi_dev_s *dev) /* Deselect the FLASH */ - SPI_SELECT(dev, SPIDEV_FLASH, false); + SPI_SELECT(dev, SPIDEV_FLASH(0), false); /* Identify the FLASH chip and get its capacity */ diff --git a/drivers/mtd/w25.c b/drivers/mtd/w25.c index 279525e1fc..79ac0a5a66 100644 --- a/drivers/mtd/w25.c +++ b/drivers/mtd/w25.c @@ -338,7 +338,7 @@ static inline int w25_readid(struct w25_dev_s *priv) /* Lock the SPI bus, configure the bus, and select this FLASH part. */ w25_lock(priv->spi); - SPI_SELECT(priv->spi, SPIDEV_FLASH, true); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), true); /* Send the "Read ID (RDID)" command and read the first three ID bytes */ @@ -349,7 +349,7 @@ static inline int w25_readid(struct w25_dev_s *priv) /* Deselect the FLASH and unlock the bus */ - SPI_SELECT(priv->spi, SPIDEV_FLASH, false); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), false); w25_unlock(priv->spi); finfo("manufacturer: %02x memory: %02x capacity: %02x\n", @@ -440,7 +440,7 @@ static void w25_unprotect(FAR struct w25_dev_s *priv) { /* Select this FLASH part */ - SPI_SELECT(priv->spi, SPIDEV_FLASH, true); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), true); /* Send "Write enable (WREN)" */ @@ -450,8 +450,8 @@ static void w25_unprotect(FAR struct w25_dev_s *priv) * the SST25 timing diagrams from which this code was leveraged.) */ - SPI_SELECT(priv->spi, SPIDEV_FLASH, false); - SPI_SELECT(priv->spi, SPIDEV_FLASH, true); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), false); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), true); /* Send "Write enable status (EWSR)" */ @@ -478,7 +478,7 @@ static uint8_t w25_waitwritecomplete(struct w25_dev_s *priv) { /* Select this FLASH part */ - SPI_SELECT(priv->spi, SPIDEV_FLASH, true); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), true); /* Send "Read Status Register (RDSR)" command */ @@ -490,7 +490,7 @@ static uint8_t w25_waitwritecomplete(struct w25_dev_s *priv) /* Deselect the FLASH */ - SPI_SELECT(priv->spi, SPIDEV_FLASH, false); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), false); /* Given that writing could take up to few tens of milliseconds, and erasing * could take more. The following short delay in the "busy" case will allow @@ -519,7 +519,7 @@ static inline void w25_wren(struct w25_dev_s *priv) { /* Select this FLASH part */ - SPI_SELECT(priv->spi, SPIDEV_FLASH, true); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), true); /* Send "Write Enable (WREN)" command */ @@ -527,7 +527,7 @@ static inline void w25_wren(struct w25_dev_s *priv) /* Deselect the FLASH */ - SPI_SELECT(priv->spi, SPIDEV_FLASH, false); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), false); } /************************************************************************************ @@ -538,7 +538,7 @@ static inline void w25_wrdi(struct w25_dev_s *priv) { /* Select this FLASH part */ - SPI_SELECT(priv->spi, SPIDEV_FLASH, true); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), true); /* Send "Write Disable (WRDI)" command */ @@ -546,7 +546,7 @@ static inline void w25_wrdi(struct w25_dev_s *priv) /* Deselect the FLASH */ - SPI_SELECT(priv->spi, SPIDEV_FLASH, false); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), false); } /************************************************************************************ @@ -569,7 +569,7 @@ static void w25_sectorerase(struct w25_dev_s *priv, off_t sector) /* Select this FLASH part */ - SPI_SELECT(priv->spi, SPIDEV_FLASH, true); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), true); /* Send the "Sector Erase (SE)" instruction */ @@ -585,7 +585,7 @@ static void w25_sectorerase(struct w25_dev_s *priv, off_t sector) /* Deselect the FLASH */ - SPI_SELECT(priv->spi, SPIDEV_FLASH, false); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), false); } /************************************************************************************ @@ -606,7 +606,7 @@ static inline int w25_chiperase(struct w25_dev_s *priv) /* Select this FLASH part */ - SPI_SELECT(priv->spi, SPIDEV_FLASH, true); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), true); /* Send the "Chip Erase (CE)" instruction */ @@ -614,7 +614,7 @@ static inline int w25_chiperase(struct w25_dev_s *priv) /* Deselect the FLASH */ - SPI_SELECT(priv->spi, SPIDEV_FLASH, false); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), false); finfo("Return: OK\n"); return OK; } @@ -641,7 +641,7 @@ static void w25_byteread(FAR struct w25_dev_s *priv, FAR uint8_t *buffer, /* Select this FLASH part */ - SPI_SELECT(priv->spi, SPIDEV_FLASH, true); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), true); /* Send "Read from Memory " instruction */ @@ -669,7 +669,7 @@ static void w25_byteread(FAR struct w25_dev_s *priv, FAR uint8_t *buffer, /* Deselect the FLASH */ - SPI_SELECT(priv->spi, SPIDEV_FLASH, false); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), false); } /************************************************************************************ @@ -699,7 +699,7 @@ static void w25_pagewrite(struct w25_dev_s *priv, FAR const uint8_t *buffer, /* Select this FLASH part */ - SPI_SELECT(priv->spi, SPIDEV_FLASH, true); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), true); /* Send the "Page Program (W25_PP)" Command */ @@ -717,7 +717,7 @@ static void w25_pagewrite(struct w25_dev_s *priv, FAR const uint8_t *buffer, /* Deselect the FLASH and setup for the next pass through the loop */ - SPI_SELECT(priv->spi, SPIDEV_FLASH, false); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), false); /* Update addresses */ @@ -755,7 +755,7 @@ static inline void w25_bytewrite(struct w25_dev_s *priv, FAR const uint8_t *buff /* Select this FLASH part */ - SPI_SELECT(priv->spi, SPIDEV_FLASH, true); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), true); /* Send "Page Program (PP)" command */ @@ -773,7 +773,7 @@ static inline void w25_bytewrite(struct w25_dev_s *priv, FAR const uint8_t *buff /* Deselect the FLASH: Chip Select high */ - SPI_SELECT(priv->spi, SPIDEV_FLASH, false); + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), false); finfo("Written\n"); } #endif /* defined(CONFIG_MTD_BYTE_WRITE) && !defined(CONFIG_W25_READONLY) */ @@ -1224,7 +1224,7 @@ FAR struct mtd_dev_s *w25_initialize(FAR struct spi_dev_s *spi) /* Allocate a state structure (we allocate the structure instead of using * a fixed, static allocation so that we can handle multiple FLASH devices. * The current implementation would handle only one FLASH part per SPI - * device (only because of the SPIDEV_FLASH definition) and so would have + * device (only because of the SPIDEV_FLASH(0) definition) and so would have * to be extended to handle multiple FLASH parts on the same SPI bus. */ @@ -1247,7 +1247,7 @@ FAR struct mtd_dev_s *w25_initialize(FAR struct spi_dev_s *spi) /* Deselect the FLASH */ - SPI_SELECT(spi, SPIDEV_FLASH, false); + SPI_SELECT(spi, SPIDEV_FLASH(0), false); /* Identify the FLASH chip and get its capacity */ diff --git a/drivers/net/enc28j60.c b/drivers/net/enc28j60.c index 90aa996c0b..a719f43d7a 100644 --- a/drivers/net/enc28j60.c +++ b/drivers/net/enc28j60.c @@ -466,7 +466,7 @@ static uint8_t enc_rdgreg2(FAR struct enc_driver_s *priv, uint8_t cmd) /* Select ENC28J60 chip */ - SPI_SELECT(priv->spi, SPIDEV_ETHERNET, true); + SPI_SELECT(priv->spi, SPIDEV_ETHERNET(0), true); /* Send the read command and collect the data. The sequence requires * 16-clocks: 8 to clock out the cmd + 8 to clock in the data. @@ -477,7 +477,7 @@ static uint8_t enc_rdgreg2(FAR struct enc_driver_s *priv, uint8_t cmd) /* De-select ENC28J60 chip */ - SPI_SELECT(priv->spi, SPIDEV_ETHERNET, false); + SPI_SELECT(priv->spi, SPIDEV_ETHERNET(0), false); enc_rddump(cmd, rddata); return rddata; @@ -509,7 +509,7 @@ static void enc_wrgreg2(FAR struct enc_driver_s *priv, uint8_t cmd, /* Select ENC28J60 chip */ - SPI_SELECT(priv->spi, SPIDEV_ETHERNET, true); + SPI_SELECT(priv->spi, SPIDEV_ETHERNET(0), true); /* Send the write command and data. The sequence requires 16-clocks: * 8 to clock out the cmd + 8 to clock out the data. @@ -520,7 +520,7 @@ static void enc_wrgreg2(FAR struct enc_driver_s *priv, uint8_t cmd, /* De-select ENC28J60 chip. */ - SPI_SELECT(priv->spi, SPIDEV_ETHERNET, false); + SPI_SELECT(priv->spi, SPIDEV_ETHERNET(0), false); enc_wrdump(cmd, wrdata); } @@ -553,7 +553,7 @@ static inline void enc_src(FAR struct enc_driver_s *priv) /* Select ENC28J60 chip */ - SPI_SELECT(priv->spi, SPIDEV_ETHERNET, true); + SPI_SELECT(priv->spi, SPIDEV_ETHERNET(0), true); /* Send the system reset command. */ @@ -574,7 +574,7 @@ static inline void enc_src(FAR struct enc_driver_s *priv) /* De-select ENC28J60 chip. */ - SPI_SELECT(priv->spi, SPIDEV_ETHERNET, false); + SPI_SELECT(priv->spi, SPIDEV_ETHERNET(0), false); enc_cmddump(ENC_SRC); } @@ -650,7 +650,7 @@ static uint8_t enc_rdbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg) /* Re-select ENC28J60 chip */ - SPI_SELECT(priv->spi, SPIDEV_ETHERNET, true); + SPI_SELECT(priv->spi, SPIDEV_ETHERNET(0), true); /* Send the RCR command and collect the data. How we collect the data * depends on if this is a PHY/CAN or not. The normal sequence requires @@ -671,7 +671,7 @@ static uint8_t enc_rdbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg) /* De-select ENC28J60 chip */ - SPI_SELECT(priv->spi, SPIDEV_ETHERNET, false); + SPI_SELECT(priv->spi, SPIDEV_ETHERNET(0), false); enc_rddump(ENC_RCR | GETADDR(ctrlreg), rddata); return rddata; } @@ -707,7 +707,7 @@ static void enc_wrbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg, /* Re-select ENC28J60 chip */ - SPI_SELECT(priv->spi, SPIDEV_ETHERNET, true); + SPI_SELECT(priv->spi, SPIDEV_ETHERNET(0), true); /* Send the WCR command and data. The sequence requires 16-clocks: * 8 to clock out the cmd + 8 to clock out the data. @@ -718,7 +718,7 @@ static void enc_wrbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg, /* De-select ENC28J60 chip. */ - SPI_SELECT(priv->spi, SPIDEV_ETHERNET, false); + SPI_SELECT(priv->spi, SPIDEV_ETHERNET(0), false); enc_wrdump(ENC_WCR | GETADDR(ctrlreg), wrdata); } @@ -861,7 +861,7 @@ static void enc_rdbuffer(FAR struct enc_driver_s *priv, FAR uint8_t *buffer, /* Select ENC28J60 chip */ - SPI_SELECT(priv->spi, SPIDEV_ETHERNET, true); + SPI_SELECT(priv->spi, SPIDEV_ETHERNET(0), true); /* Send the read buffer memory command (ignoring the response) */ @@ -873,7 +873,7 @@ static void enc_rdbuffer(FAR struct enc_driver_s *priv, FAR uint8_t *buffer, /* De-select ENC28J60 chip. */ - SPI_SELECT(priv->spi, SPIDEV_ETHERNET, false); + SPI_SELECT(priv->spi, SPIDEV_ETHERNET(0), false); enc_bmdump(ENC_WBM, buffer, buflen); } @@ -906,7 +906,7 @@ static inline void enc_wrbuffer(FAR struct enc_driver_s *priv, * "The WBM command is started by lowering the CS pin. ..." */ - SPI_SELECT(priv->spi, SPIDEV_ETHERNET, true); + SPI_SELECT(priv->spi, SPIDEV_ETHERNET(0), true); /* Send the write buffer memory command (ignoring the response) * @@ -956,7 +956,7 @@ static inline void enc_wrbuffer(FAR struct enc_driver_s *priv, * "The WBM command is terminated by bringing up the CS pin. ..." */ - SPI_SELECT(priv->spi, SPIDEV_ETHERNET, false); + SPI_SELECT(priv->spi, SPIDEV_ETHERNET(0), false); enc_bmdump(ENC_WBM, buffer, buflen+1); } diff --git a/drivers/net/encx24j600.c b/drivers/net/encx24j600.c index be66e56da5..719661a9ac 100644 --- a/drivers/net/encx24j600.c +++ b/drivers/net/encx24j600.c @@ -458,7 +458,7 @@ static void enc_cmd(FAR struct enc_driver_s *priv, uint8_t cmd, uint16_t arg) /* Select ENCX24J600 chip */ - SPI_SELECT(priv->spi, SPIDEV_ETHERNET, true); + SPI_SELECT(priv->spi, SPIDEV_ETHERNET(0), true); (void)SPI_SEND(priv->spi, cmd); /* Clock out the command */ (void)SPI_SEND(priv->spi, arg & 0xff); /* Clock out the low byte */ @@ -466,7 +466,7 @@ static void enc_cmd(FAR struct enc_driver_s *priv, uint8_t cmd, uint16_t arg) /* De-select ENCX24J600 chip. */ - SPI_SELECT(priv->spi, SPIDEV_ETHERNET, false); + SPI_SELECT(priv->spi, SPIDEV_ETHERNET(0), false); enc_wrdump(cmd, arg); } @@ -492,7 +492,7 @@ static inline void enc_setethrst(FAR struct enc_driver_s *priv) /* Select ENCX24J600 chip */ - SPI_SELECT(priv->spi, SPIDEV_ETHERNET, true); + SPI_SELECT(priv->spi, SPIDEV_ETHERNET(0), true); /* Send the system reset command. */ @@ -502,7 +502,7 @@ static inline void enc_setethrst(FAR struct enc_driver_s *priv) /* De-select ENCX24J600 chip. */ - SPI_SELECT(priv->spi, SPIDEV_ETHERNET, false); + SPI_SELECT(priv->spi, SPIDEV_ETHERNET(0), false); enc_cmddump(ENC_SETETHRST); } @@ -570,7 +570,7 @@ static uint16_t enc_rdreg(FAR struct enc_driver_s *priv, uint16_t ctrlreg) DEBUGASSERT(priv && priv->spi); DEBUGASSERT((ctrlreg & 0xe0) == 0); /* banked regeitsers only */ - SPI_SELECT(priv->spi, SPIDEV_ETHERNET, true); + SPI_SELECT(priv->spi, SPIDEV_ETHERNET(0), true); enc_setbank(priv, GETBANK(ctrlreg)); @@ -580,7 +580,7 @@ static uint16_t enc_rdreg(FAR struct enc_driver_s *priv, uint16_t ctrlreg) rddata |= SPI_SEND(priv->spi, 0) << 8; /* Clock in the high byte */ - SPI_SELECT(priv->spi, SPIDEV_ETHERNET, false); + SPI_SELECT(priv->spi, SPIDEV_ETHERNET(0), false); enc_rddump(GETADDR(ctrlreg), rddata); return rddata; @@ -610,7 +610,7 @@ static void enc_wrreg(FAR struct enc_driver_s *priv, uint16_t ctrlreg, DEBUGASSERT(priv && priv->spi); DEBUGASSERT((ctrlreg & 0xe0) == 0); /* banked regeitsers only */ - SPI_SELECT(priv->spi, SPIDEV_ETHERNET, true); + SPI_SELECT(priv->spi, SPIDEV_ETHERNET(0), true); enc_setbank(priv, GETBANK(ctrlreg)); @@ -618,7 +618,7 @@ static void enc_wrreg(FAR struct enc_driver_s *priv, uint16_t ctrlreg, SPI_SEND(priv->spi, wrdata & 0xff); /* Clock out the low byte */ SPI_SEND(priv->spi, wrdata >> 8); /* Clock out the high byte */ - SPI_SELECT(priv->spi, SPIDEV_ETHERNET, false); + SPI_SELECT(priv->spi, SPIDEV_ETHERNET(0), false); enc_wrdump(GETADDR(ctrlreg), wrdata); } @@ -688,7 +688,7 @@ static void enc_bfs(FAR struct enc_driver_s *priv, uint16_t ctrlreg, /* Select ENCX24J600 chip */ - SPI_SELECT(priv->spi, SPIDEV_ETHERNET, true); + SPI_SELECT(priv->spi, SPIDEV_ETHERNET(0), true); /* Set the bank */ @@ -704,7 +704,7 @@ static void enc_bfs(FAR struct enc_driver_s *priv, uint16_t ctrlreg, /* De-select ENCX24J600 chip. */ - SPI_SELECT(priv->spi, SPIDEV_ETHERNET, false); + SPI_SELECT(priv->spi, SPIDEV_ETHERNET(0), false); enc_bfsdump(GETADDR(ctrlreg), bits); } @@ -733,7 +733,7 @@ static void enc_bfc(FAR struct enc_driver_s *priv, uint16_t ctrlreg, /* Select ENCX24J600 chip */ - SPI_SELECT(priv->spi, SPIDEV_ETHERNET, true); + SPI_SELECT(priv->spi, SPIDEV_ETHERNET(0), true); /* Set the bank */ @@ -749,7 +749,7 @@ static void enc_bfc(FAR struct enc_driver_s *priv, uint16_t ctrlreg, /* De-select ENCX24J600 chip. */ - SPI_SELECT(priv->spi, SPIDEV_ETHERNET, false); + SPI_SELECT(priv->spi, SPIDEV_ETHERNET(0), false); enc_bfcdump(GETADDR(ctrlreg), bits); } @@ -851,7 +851,7 @@ static void enc_rdbuffer(FAR struct enc_driver_s *priv, FAR uint8_t *buffer, /* Select ENCX24J600 chip */ - SPI_SELECT(priv->spi, SPIDEV_ETHERNET, true); + SPI_SELECT(priv->spi, SPIDEV_ETHERNET(0), true); /* Send the read buffer memory command (ignoring the response) */ @@ -863,7 +863,7 @@ static void enc_rdbuffer(FAR struct enc_driver_s *priv, FAR uint8_t *buffer, /* De-select ENCX24J600 chip. */ - SPI_SELECT(priv->spi, SPIDEV_ETHERNET, false); + SPI_SELECT(priv->spi, SPIDEV_ETHERNET(0), false); enc_bmdump(ENC_RRXDATA, buffer, buflen); } @@ -891,12 +891,12 @@ static inline void enc_wrbuffer(FAR struct enc_driver_s *priv, { DEBUGASSERT(priv && priv->spi); - SPI_SELECT(priv->spi, SPIDEV_ETHERNET, true); + SPI_SELECT(priv->spi, SPIDEV_ETHERNET(0), true); SPI_SEND(priv->spi, ENC_WGPDATA); SPI_SNDBLOCK(priv->spi, buffer, buflen); - SPI_SELECT(priv->spi, SPIDEV_ETHERNET, false); + SPI_SELECT(priv->spi, SPIDEV_ETHERNET(0), false); enc_bmdump(ENC_WGPDATA, buffer, buflen); } diff --git a/drivers/sensors/adxl345_spi.c b/drivers/sensors/adxl345_spi.c index a2d524bf50..f235a1b750 100644 --- a/drivers/sensors/adxl345_spi.c +++ b/drivers/sensors/adxl345_spi.c @@ -97,7 +97,7 @@ uint8_t adxl345_getreg8(FAR struct adxl345_dev_s *priv, uint8_t regaddr) /* Select the ADXL345 */ - SPI_SELECT(priv->spi, SPIDEV_ACCELEROMETER, true); + SPI_SELECT(priv->spi, SPIDEV_ACCELEROMETER(0), true); /* Send register to read and get the next byte */ @@ -106,7 +106,7 @@ uint8_t adxl345_getreg8(FAR struct adxl345_dev_s *priv, uint8_t regaddr) /* Deselect the ADXL345 */ - SPI_SELECT(priv->spi, SPIDEV_ACCELEROMETER, false); + SPI_SELECT(priv->spi, SPIDEV_ACCELEROMETER(0), false); /* Unlock bus */ @@ -140,7 +140,7 @@ void adxl345_putreg8(FAR struct adxl345_dev_s *priv, uint8_t regaddr, /* Select the ADXL345 */ - SPI_SELECT(priv->spi, SPIDEV_ACCELEROMETER, true); + SPI_SELECT(priv->spi, SPIDEV_ACCELEROMETER(0), true); /* Send register address and set the value */ @@ -149,7 +149,7 @@ void adxl345_putreg8(FAR struct adxl345_dev_s *priv, uint8_t regaddr, /* Deselect the ADXL345 */ - SPI_SELECT(priv->spi, SPIDEV_ACCELEROMETER, false); + SPI_SELECT(priv->spi, SPIDEV_ACCELEROMETER(0), false); /* Unlock bus */ @@ -175,7 +175,7 @@ uint16_t adxl345_getreg16(FAR struct adxl345_dev_s *priv, uint8_t regaddr) /* Select the ADXL345 */ - SPI_SELECT(priv->spi, SPIDEV_ACCELEROMETER, true); + SPI_SELECT(priv->spi, SPIDEV_ACCELEROMETER(0), true); /* Send register to read and get the next 2 bytes */ @@ -184,7 +184,7 @@ uint16_t adxl345_getreg16(FAR struct adxl345_dev_s *priv, uint8_t regaddr) /* Deselect the ADXL345 */ - SPI_SELECT(priv->spi, SPIDEV_ACCELEROMETER, false); + SPI_SELECT(priv->spi, SPIDEV_ACCELEROMETER(0), false); /* Unlock bus */ diff --git a/drivers/sensors/max31855.c b/drivers/sensors/max31855.c index 97b56f42ec..b4668088dc 100644 --- a/drivers/sensors/max31855.c +++ b/drivers/sensors/max31855.c @@ -203,7 +203,7 @@ static ssize_t max31855_read(FAR struct file *filep, FAR char *buffer, size_t bu /* Enable MAX31855's chip select */ max31855_lock(priv->spi); - SPI_SELECT(priv->spi, SPIDEV_TEMPERATURE, true); + SPI_SELECT(priv->spi, SPIDEV_TEMPERATURE(0), true); /* Read temperature */ @@ -211,7 +211,7 @@ static ssize_t max31855_read(FAR struct file *filep, FAR char *buffer, size_t bu /* Disable MAX31855's chip select */ - SPI_SELECT(priv->spi, SPIDEV_TEMPERATURE, false); + SPI_SELECT(priv->spi, SPIDEV_TEMPERATURE(0), false); max31855_unlock(priv->spi); regval = (regmsb & 0xFF000000) >> 24; diff --git a/drivers/sensors/max6675.c b/drivers/sensors/max6675.c index 71a0e2d142..3d273df20f 100644 --- a/drivers/sensors/max6675.c +++ b/drivers/sensors/max6675.c @@ -199,7 +199,7 @@ static ssize_t max6675_read(FAR struct file *filep, FAR char *buffer, size_t buf /* Enable MAX6675's chip select */ max6675_lock(priv->spi); - SPI_SELECT(priv->spi, SPIDEV_TEMPERATURE, true); + SPI_SELECT(priv->spi, SPIDEV_TEMPERATURE(0), true); /* Read temperature */ @@ -207,7 +207,7 @@ static ssize_t max6675_read(FAR struct file *filep, FAR char *buffer, size_t buf /* Disable MAX6675's chip select */ - SPI_SELECT(priv->spi, SPIDEV_TEMPERATURE, false); + SPI_SELECT(priv->spi, SPIDEV_TEMPERATURE(0), false); max6675_unlock(priv->spi); regval = (regmsb & 0xFF00) >> 8; diff --git a/drivers/sensors/mpl115a.c b/drivers/sensors/mpl115a.c index c23df63eaf..4107e8986a 100644 --- a/drivers/sensors/mpl115a.c +++ b/drivers/sensors/mpl115a.c @@ -142,7 +142,7 @@ static uint8_t mpl115a_getreg8(FAR struct mpl115a_dev_s *priv, uint8_t regaddr) /* Select the MPL115A */ - SPI_SELECT(priv->spi, SPIDEV_BAROMETER, true); + SPI_SELECT(priv->spi, SPIDEV_BAROMETER(0), true); /* Send register to read and get the next byte */ @@ -151,7 +151,7 @@ static uint8_t mpl115a_getreg8(FAR struct mpl115a_dev_s *priv, uint8_t regaddr) /* Deselect the MPL115A */ - SPI_SELECT(priv->spi, SPIDEV_BAROMETER, false); + SPI_SELECT(priv->spi, SPIDEV_BAROMETER(0), false); /* Unlock bus */ diff --git a/drivers/sensors/xen1210.c b/drivers/sensors/xen1210.c index a14350921c..0603b4486f 100644 --- a/drivers/sensors/xen1210.c +++ b/drivers/sensors/xen1210.c @@ -419,7 +419,7 @@ void xen1210_getdata(FAR struct xen1210_dev_s *priv) /* Select the XEN1210 */ - SPI_SELECT(priv->spi, SPIDEV_ACCELEROMETER, true); + SPI_SELECT(priv->spi, SPIDEV_ACCELEROMETER(0), true); /* Read three times 3 bytes = 24 bits * 3 */ @@ -434,7 +434,7 @@ void xen1210_getdata(FAR struct xen1210_dev_s *priv) /* Deselect the XEN1210 */ - SPI_SELECT(priv->spi, SPIDEV_ACCELEROMETER, false); + SPI_SELECT(priv->spi, SPIDEV_ACCELEROMETER(0), false); /* Unlock bus */ @@ -472,7 +472,7 @@ void xen1210_putdata(FAR struct xen1210_dev_s *priv, uint32_t regval) /* Select the XEN1210 */ - SPI_SELECT(priv->spi, SPIDEV_ACCELEROMETER, true); + SPI_SELECT(priv->spi, SPIDEV_ACCELEROMETER(0), true); /* We need to write to 3 sensors in the daisy-chain */ /* Write three times 3 bytes */ @@ -483,7 +483,7 @@ void xen1210_putdata(FAR struct xen1210_dev_s *priv, uint32_t regval) /* Deselect the XEN1210 */ - SPI_SELECT(priv->spi, SPIDEV_ACCELEROMETER, false); + SPI_SELECT(priv->spi, SPIDEV_ACCELEROMETER(0), false); /* Unlock bus */ diff --git a/drivers/wireless/cc1101.c b/drivers/wireless/cc1101.c index e9ce3805c5..33112b42a5 100644 --- a/drivers/wireless/cc1101.c +++ b/drivers/wireless/cc1101.c @@ -312,7 +312,7 @@ static volatile int cc1101_interrupt = 0; void cc1101_access_begin(FAR struct cc1101_dev_s *dev) { (void)SPI_LOCK(dev->spi, true); - SPI_SELECT(dev->spi, SPIDEV_WIRELESS, true); + SPI_SELECT(dev->spi, SPIDEV_WIRELESS(0), true); SPI_SETMODE(dev->spi, SPIDEV_MODE0); /* CPOL=0, CPHA=0 */ SPI_SETBITS(dev->spi, 8); (void)SPI_HWFEATURES(dev->spi, 0); @@ -320,7 +320,7 @@ void cc1101_access_begin(FAR struct cc1101_dev_s *dev) void cc1101_access_end(FAR struct cc1101_dev_s *dev) { - SPI_SELECT(dev->spi, SPIDEV_WIRELESS, false); + SPI_SELECT(dev->spi, SPIDEV_WIRELESS(0), false); (void)SPI_LOCK(dev->spi, false); } diff --git a/drivers/wireless/cc3000/cc3000.c b/drivers/wireless/cc3000/cc3000.c index 6f335c99fd..4e72232dd1 100644 --- a/drivers/wireless/cc3000/cc3000.c +++ b/drivers/wireless/cc3000/cc3000.c @@ -289,7 +289,7 @@ static void cc3000_lock_and_select(FAR struct spi_dev_s *spi) */ cc3000_configspi(spi); - SPI_SELECT(spi, SPIDEV_WIRELESS, true); + SPI_SELECT(spi, SPIDEV_WIRELESS(0), true); } /**************************************************************************** @@ -313,7 +313,7 @@ static void cc3000_deselect_and_unlock(FAR struct spi_dev_s *spi) { /* De select */ - SPI_SELECT(spi, SPIDEV_WIRELESS, false); + SPI_SELECT(spi, SPIDEV_WIRELESS(0), false); /* Relinquish the SPI bus. */ diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c index 938a4f1acc..41558b9dfa 100644 --- a/drivers/wireless/ieee802154/mrf24j40.c +++ b/drivers/wireless/ieee802154/mrf24j40.c @@ -255,9 +255,9 @@ static void mrf24j40_setreg(FAR struct spi_dev_s *spi, uint32_t addr, uint8_t va buf[len++] = val; mrf24j40_lock(spi); - SPI_SELECT(spi, SPIDEV_IEEE802154, true); + SPI_SELECT(spi, SPIDEV_IEEE802154(0), true); SPI_SNDBLOCK(spi, buf, len); - SPI_SELECT(spi, SPIDEV_IEEE802154, false); + SPI_SELECT(spi, SPIDEV_IEEE802154(0), false); mrf24j40_unlock(spi); } @@ -299,9 +299,9 @@ static uint8_t mrf24j40_getreg(FAR struct spi_dev_s *spi, uint32_t addr) buf[len++] = 0xFF; /* dummy */ mrf24j40_lock (spi); - SPI_SELECT (spi, SPIDEV_IEEE802154, true); + SPI_SELECT (spi, SPIDEV_IEEE802154(0), true); SPI_EXCHANGE (spi, buf, rx, len); - SPI_SELECT (spi, SPIDEV_IEEE802154, false); + SPI_SELECT (spi, SPIDEV_IEEE802154(0), false); mrf24j40_unlock(spi); /*winfo("r[%04X]=%02X\n", addr, rx[len-1]);*/ diff --git a/drivers/wireless/nrf24l01.c b/drivers/wireless/nrf24l01.c index 8bfc725c3b..463857e2ef 100644 --- a/drivers/wireless/nrf24l01.c +++ b/drivers/wireless/nrf24l01.c @@ -281,12 +281,12 @@ static void nrf24l01_lock(FAR struct spi_dev_s *spi) * unlocked) */ - SPI_SELECT(spi, SPIDEV_WIRELESS, true); + SPI_SELECT(spi, SPIDEV_WIRELESS(0), true); SPI_SETMODE(spi, SPIDEV_MODE0); SPI_SETBITS(spi, 8); (void)SPI_HWFEATURES(spi, 0); (void)SPI_SETFREQUENCY(spi, NRF24L01_SPIFREQ); - SPI_SELECT(spi, SPIDEV_WIRELESS, false); + SPI_SELECT(spi, SPIDEV_WIRELESS(0), false); } /**************************************************************************** @@ -333,12 +333,12 @@ static inline void nrf24l01_configspi(FAR struct spi_dev_s *spi) { /* Configure SPI for the NRF24L01 module. */ - SPI_SELECT(spi, SPIDEV_WIRELESS, true); /* Useful ? */ + SPI_SELECT(spi, SPIDEV_WIRELESS(0), true); /* Useful ? */ SPI_SETMODE(spi, SPIDEV_MODE0); SPI_SETBITS(spi, 8); (void)SPI_HWFEATURES(spi, 0); (void)SPI_SETFREQUENCY(spi, NRF24L01_SPIFREQ); - SPI_SELECT(spi, SPIDEV_WIRELESS, false); + SPI_SELECT(spi, SPIDEV_WIRELESS(0), false); } /**************************************************************************** @@ -347,7 +347,7 @@ static inline void nrf24l01_configspi(FAR struct spi_dev_s *spi) static inline void nrf24l01_select(struct nrf24l01_dev_s * dev) { - SPI_SELECT(dev->spi, SPIDEV_WIRELESS, true); + SPI_SELECT(dev->spi, SPIDEV_WIRELESS(0), true); } /**************************************************************************** @@ -356,7 +356,7 @@ static inline void nrf24l01_select(struct nrf24l01_dev_s * dev) static inline void nrf24l01_deselect(struct nrf24l01_dev_s * dev) { - SPI_SELECT(dev->spi, SPIDEV_WIRELESS, false); + SPI_SELECT(dev->spi, SPIDEV_WIRELESS(0), false); } /**************************************************************************** diff --git a/include/nuttx/analog/pga11x.h b/include/nuttx/analog/pga11x.h index e4e2ebbc92..575689d22d 100644 --- a/include/nuttx/analog/pga11x.h +++ b/include/nuttx/analog/pga11x.h @@ -70,7 +70,7 @@ * CONFIG_PGA11X_MULTIPLE * Can be defined to support multiple PGA11X devices on board. Each * device will require a customized SPI interface to distinguish them - * When SPI_SELECT is called with devid=SPIDEV_MUX. + * When SPI_SELECT is called with devid=SPIDEV_MUX(n). * * Other settings that effect the driver: * CONFIG_DEBUG_SPI_ERR/WARN/INFO -- This will enable debug output from diff --git a/include/nuttx/contactless/pn532.h b/include/nuttx/contactless/pn532.h index c4bf82d8b2..145ee721b1 100644 --- a/include/nuttx/contactless/pn532.h +++ b/include/nuttx/contactless/pn532.h @@ -72,7 +72,7 @@ struct pn532_config_s { int (*reset)(uint8_t enable); - /* External CS, if NULL then SPIDEV_WIRELESS CS is used */ + /* External CS, if NULL then SPIDEV_WIRELESS(n) CS is used */ int (*select)(struct pn532_dev_s *dev, bool sel); int (*irqattach)(void* dev, xcpt_t isr); diff --git a/include/nuttx/spi/spi.h b/include/nuttx/spi/spi.h index 96868de155..ffff5e2911 100644 --- a/include/nuttx/spi/spi.h +++ b/include/nuttx/spi/spi.h @@ -433,29 +433,29 @@ #define SPIDEVID_INDEX(devid) ((uint32_t)(devid) & 0xffff) /* These are replacement definitions for the currently used SPI device indexes. - * They are meant as a compatibility measure. it is expected that new drivers - * will use SPIDEV_ID directly. + * The argument, n, is the instance number. This should be zero is there is + * only one instance of the SPI device on the bus. */ -#define SPIDEV_NONE SPIDEV_ID(SPIDEVTYPE_NONE, 0) -#define SPIDEV_MMCSD SPIDEV_ID(SPIDEVTYPE_MMCSD, 0) -#define SPIDEV_FLASH SPIDEV_ID(SPIDEVTYPE_FLASH, 0) -#define SPIDEV_ETHERNET SPIDEV_ID(SPIDEVTYPE_ETHERNET, 0) -#define SPIDEV_DISPLAY SPIDEV_ID(SPIDEVTYPE_DISPLAY, 0) -#define SPIDEV_CAMERA SPIDEV_ID(SPIDEVTYPE_CAMERA, 0) -#define SPIDEV_WIRELESS SPIDEV_ID(SPIDEVTYPE_WIRELESS, 0) -#define SPIDEV_TOUCHSCREEN SPIDEV_ID(SPIDEVTYPE_TOUCHSCREEN, 0) -#define SPIDEV_EXPANDER SPIDEV_ID(SPIDEVTYPE_EXPANDER, 0) -#define SPIDEV_MUX SPIDEV_ID(SPIDEVTYPE_MUX, 0) -#define SPIDEV_AUDIO_DATA SPIDEV_ID(SPIDEVTYPE_AUDIO_DATA, 0) -#define SPIDEV_AUDIO_CTRL SPIDEV_ID(SPIDEVTYPE_AUDIO_CTRL, 0) -#define SPIDEV_EEPROM SPIDEV_ID(SPIDEVTYPE_EEPROM, 0) -#define SPIDEV_ACCELEROMETER SPIDEV_ID(SPIDEVTYPE_ACCELEROMETER, 0) -#define SPIDEV_BAROMETER SPIDEV_ID(SPIDEVTYPE_BAROMETER, 0) -#define SPIDEV_TEMPERATURE SPIDEV_ID(SPIDEVTYPE_TEMPERATURE, 0) -#define SPIDEV_IEEE802154 SPIDEV_ID(SPIDEVTYPE_IEEE802154, 0) -#define SPIDEV_CONTACTLESS SPIDEV_ID(SPIDEVTYPE_CONTACTLESS, 0) -#define SPIDEV_USER SPIDEV_ID(SPIDEVTYPE_USER, 0) +#define SPIDEV_NONE(n) SPIDEV_ID(SPIDEVTYPE_NONE, (n)) +#define SPIDEV_MMCSD(n) SPIDEV_ID(SPIDEVTYPE_MMCSD, (n)) +#define SPIDEV_FLASH(n) SPIDEV_ID(SPIDEVTYPE_FLASH, (n)) +#define SPIDEV_ETHERNET(n) SPIDEV_ID(SPIDEVTYPE_ETHERNET, (n)) +#define SPIDEV_DISPLAY(n) SPIDEV_ID(SPIDEVTYPE_DISPLAY, (n)) +#define SPIDEV_CAMERA(n) SPIDEV_ID(SPIDEVTYPE_CAMERA, (n)) +#define SPIDEV_WIRELESS(n) SPIDEV_ID(SPIDEVTYPE_WIRELESS, (n)) +#define SPIDEV_TOUCHSCREEN(n) SPIDEV_ID(SPIDEVTYPE_TOUCHSCREEN, (n)) +#define SPIDEV_EXPANDER(n) SPIDEV_ID(SPIDEVTYPE_EXPANDER, (n)) +#define SPIDEV_MUX(n) SPIDEV_ID(SPIDEVTYPE_MUX, (n)) +#define SPIDEV_AUDIO_DATA(n) SPIDEV_ID(SPIDEVTYPE_AUDIO_DATA, (n)) +#define SPIDEV_AUDIO_CTRL(n) SPIDEV_ID(SPIDEVTYPE_AUDIO_CTRL, (n)) +#define SPIDEV_EEPROM(n) SPIDEV_ID(SPIDEVTYPE_EEPROM, (n)) +#define SPIDEV_ACCELEROMETER(n) SPIDEV_ID(SPIDEVTYPE_ACCELEROMETER, (n)) +#define SPIDEV_BAROMETER(n) SPIDEV_ID(SPIDEVTYPE_BAROMETER, (n)) +#define SPIDEV_TEMPERATURE(n) SPIDEV_ID(SPIDEVTYPE_TEMPERATURE, (n)) +#define SPIDEV_IEEE802154(n) SPIDEV_ID(SPIDEVTYPE_IEEE802154, (n)) +#define SPIDEV_CONTACTLESS(n) SPIDEV_ID(SPIDEVTYPE_CONTACTLESS, (n)) +#define SPIDEV_USER(n) SPIDEV_ID(SPIDEVTYPE_USER, (n)) /**************************************************************************** * Public Types -- GitLab From c7264eb5507cee8203d16641902c5f6329c3ad64 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 29 Apr 2017 12:28:19 -0600 Subject: [PATCH 645/990] Add an instance argument to the SPIDEV definitions. --- drivers/wireless/ieee802154/at86rf23x.c | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/drivers/wireless/ieee802154/at86rf23x.c b/drivers/wireless/ieee802154/at86rf23x.c index e3429c4d1f..8037c4005a 100644 --- a/drivers/wireless/ieee802154/at86rf23x.c +++ b/drivers/wireless/ieee802154/at86rf23x.c @@ -265,9 +265,9 @@ static void at86rf23x_setreg(FAR struct spi_dev_s *spi, uint32_t addr, reg[1] = val; at86rf23x_lock(spi); - SPI_SELECT(spi, SPIDEV_IEEE802154, true); + SPI_SELECT(spi, SPIDEV_IEEE802154(0), true); SPI_SNDBLOCK(spi, reg, 2); - SPI_SELECT(spi, SPIDEV_IEEE802154, false); + SPI_SELECT(spi, SPIDEV_IEEE802154(0), false); at86rf23x_unlock(spi); wlinfo("0x%02X->r[0x%02X]\n", val, addr); @@ -292,9 +292,9 @@ static uint8_t at86rf23x_getreg(FAR struct spi_dev_s *spi, uint32_t addr) at86rf23x_lock (spi); - SPI_SELECT(spi, SPIDEV_IEEE802154, true); + SPI_SELECT(spi, SPIDEV_IEEE802154(0), true); SPI_EXCHANGE(spi, reg, val, 2); - SPI_SELECT(spi, SPIDEV_IEEE802154, false); + SPI_SELECT(spi, SPIDEV_IEEE802154(0), false); at86rf23x_unlock(spi); @@ -359,12 +359,12 @@ static int at86rf23x_writeframe(FAR struct spi_dev_s *spi, FAR uint8_t *frame, at86rf23x_lock(spi); - SPI_SELECT(spi, SPIDEV_IEEE802154, true); + SPI_SELECT(spi, SPIDEV_IEEE802154(0), true); SPI_SNDBLOCK(spi, ®, 1); SPI_SNDBLOCK(spi, &frame, len); - SPI_SELECT(spi, SPIDEV_IEEE802154, false); + SPI_SELECT(spi, SPIDEV_IEEE802154(0), false); at86rf23x_unlock(spi); @@ -388,13 +388,13 @@ static uint8_t at86rf23x_readframe(FAR struct spi_dev_s *spi, reg = RF23X_SPI_FRAME_READ; at86rf23x_lock(spi); - SPI_SELECT(spi, SPIDEV_IEEE802154, true); + SPI_SELECT(spi, SPIDEV_IEEE802154(0), true); SPI_SNDBLOCK(spi, ®, 1); SPI_RECVBLOCK(spi, &len, 1); SPI_RECVBLOCK(spi, frame_rx, len+3); - SPI_SELECT(spi, SPIDEV_IEEE802154, false); + SPI_SELECT(spi, SPIDEV_IEEE802154(0), false); at86rf23x_unlock(spi); return len; -- GitLab From f0bbe56620f62dd4e16fd5195b1ce517fed72a99 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 29 Apr 2017 12:58:06 -0600 Subject: [PATCH 646/990] STM32F0: Add some protection. There is only one interrupt for USART3-8. Current interrupt handling logic will support only one interrupt in that range. --- arch/arm/src/stm32f0/stm32f0_uart.h | 31 ++++++++++++++++++++++++++++- 1 file changed, 30 insertions(+), 1 deletion(-) diff --git a/arch/arm/src/stm32f0/stm32f0_uart.h b/arch/arm/src/stm32f0/stm32f0_uart.h index 4fb7b1c05f..d5bd3f6ef7 100644 --- a/arch/arm/src/stm32f0/stm32f0_uart.h +++ b/arch/arm/src/stm32f0/stm32f0_uart.h @@ -79,11 +79,40 @@ # undef CONFIG_STM32F0_USART1 #endif +/* USART 3-8 are multiplexed to the same interrupt. Current interrupt + * handling logic will support only one USART in that range. That is + * not an issue for currently supported chips but could become an + * issue in the future. + */ + +#if defined(CONFIG_STM32F0_USART3) +# undef CONFIG_STM32F0_USART4 +# undef CONFIG_STM32F0_USART5 +# undef CONFIG_STM32F0_USART6 +# undef CONFIG_STM32F0_USART7 +# undef CONFIG_STM32F0_USART8 +#elif defined(CONFIG_STM32F0_USART4) +# undef CONFIG_STM32F0_USART5 +# undef CONFIG_STM32F0_USART6 +# undef CONFIG_STM32F0_USART7 +# undef CONFIG_STM32F0_USART8 +#elif defined(CONFIG_STM32F0_USART5) +# undef CONFIG_STM32F0_USART6 +# undef CONFIG_STM32F0_USART7 +# undef CONFIG_STM32F0_USART8 +#elif defined(CONFIG_STM32F0_USART6) +# undef CONFIG_STM32F0_USART7 +# undef CONFIG_STM32F0_USART8 +#elif defined(CONFIG_STM32F0_USART7) +# undef CONFIG_STM32F0_USART8 +#endif + /* Is there a USART enabled? */ #if defined(CONFIG_STM32F0_USART1) || defined(CONFIG_STM32F0_USART2) || \ defined(CONFIG_STM32F0_USART3) || defined(CONFIG_STM32F0_USART4) || \ - defined(CONFIG_STM32F0_USART5) + defined(CONFIG_STM32F0_USART5) || defined(CONFIG_STM32F0_USART6) || \ + defined(CONFIG_STM32F0_USART7) || defined(CONFIG_STM32F0_USART8) # define HAVE_USART 1 #endif -- GitLab From 84c887f48c3aa586d5daee332eb0286b31dffb9f Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 29 Apr 2017 15:53:23 -0600 Subject: [PATCH 647/990] Update a README and some comments. --- configs/nucleo-f072rb/README.txt | 32 ++++++-------------------------- include/nuttx/spi/spi.h | 7 ++++--- 2 files changed, 10 insertions(+), 29 deletions(-) diff --git a/configs/nucleo-f072rb/README.txt b/configs/nucleo-f072rb/README.txt index de1713e5ab..3f17cedb85 100644 --- a/configs/nucleo-f072rb/README.txt +++ b/configs/nucleo-f072rb/README.txt @@ -17,32 +17,12 @@ Contents Status ====== - 2017-04-27: There are many problems. On start up, I have to reset - several times before I get NSH prompt (or parts of it). Apparently the - STM32 is either hanging (perhaps in clockconfig()) or perhaps it has - taken a hard fault before it is able to generate debug output? - - There are many hardfaults during initial serial output. This change - seems to eliminate those hardfaults: - - @@ -2163,7 +2163,7 @@ static void stm32f0serial_txint(FAR struct uart_dev_s *dev, bool enable) - * interrupts disabled (note this may recurse). - */ - - - uart_xmitchars(dev); - +// uart_xmitchars(dev); - #endif - } - else - - Which implies that the hardfaults are due to runaway recursion in the - serial driver? This suggest some error in either determining when there - is TX data available or in disabling TX interrupts. - - But this not a solution. Even without the hard faults, it may hang - attempting to output the NSH greeting and prompt or hang unable to - receive input. These symptoms suggest some issue with TX and RX - interrupt handling. + 2017-04-28: After struggling with some clock configuration and FLASH wait + state issues, the board now boots and the basic NSH configurations works + without problem. + + A USB device driver was added along with support for clocking from the + HSI48. That driver remains untested. Nucleo-64 Boards ================ diff --git a/include/nuttx/spi/spi.h b/include/nuttx/spi/spi.h index ffff5e2911..ddeb222635 100644 --- a/include/nuttx/spi/spi.h +++ b/include/nuttx/spi/spi.h @@ -432,9 +432,10 @@ #define SPIDEVID_TYPE (devid) (((uint32_t)(devid) >> 16) & 0xffff) #define SPIDEVID_INDEX(devid) ((uint32_t)(devid) & 0xffff) -/* These are replacement definitions for the currently used SPI device indexes. - * The argument, n, is the instance number. This should be zero is there is - * only one instance of the SPI device on the bus. +/* These are standard definitions for the defined SPI device IDs. The index + * argument, n, is the instance number. This should be zero if there is + * only one instance of the SPI device on the SPI bus. Indices greater than + * zero discriminate the additional devices of the same type on the SPI bus. */ #define SPIDEV_NONE(n) SPIDEV_ID(SPIDEVTYPE_NONE, (n)) -- GitLab From b688d4151611183782129f7b2ac4659fcf9948a2 Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Sat, 29 Apr 2017 16:53:47 -0600 Subject: [PATCH 648/990] STM32F0 I2C: Initial cut at driver. Still a work in progress. --- arch/arm/src/stm32f0/Make.defs | 4 + arch/arm/src/stm32f0/stm32f0_i2c.c | 2064 ++++++++++++++++++++++ arch/arm/src/stm32f0/stm32f0_i2c.h | 104 ++ configs/stm32f0discovery/include/board.h | 5 + 4 files changed, 2177 insertions(+) create mode 100644 arch/arm/src/stm32f0/stm32f0_i2c.c create mode 100644 arch/arm/src/stm32f0/stm32f0_i2c.h diff --git a/arch/arm/src/stm32f0/Make.defs b/arch/arm/src/stm32f0/Make.defs index 27fb354774..408c7b77e8 100644 --- a/arch/arm/src/stm32f0/Make.defs +++ b/arch/arm/src/stm32f0/Make.defs @@ -95,6 +95,10 @@ ifeq ($(CONFIG_STM32F0_USB),y) CHIP_CSRCS += stm32f0_usbdev.c endif +ifeq ($(CONFIG_STM32F0_I2C),y) +CHIP_CSRCS += stm32f0_i2c.c +endif + ifeq ($(CONFIG_STM32F0_SPI0),y) CHIP_CSRCS += stm32f0_spi.c else diff --git a/arch/arm/src/stm32f0/stm32f0_i2c.c b/arch/arm/src/stm32f0/stm32f0_i2c.c new file mode 100644 index 0000000000..98a4db2c80 --- /dev/null +++ b/arch/arm/src/stm32f0/stm32f0_i2c.c @@ -0,0 +1,2064 @@ +/************************************************************************************ + * arch/arm/src/stm32l4/stm32f0_i2c.c + * STM32L4 I2C driver - based on STM32F3 I2C Hardware Layer - Device Driver + * + * Copyright (C) 2011 Uros Platise. All rights reserved. + * Author: Uros Platise + * Copyright (C) 2011-2013, 2016-2017 Gregory Nutt. All rights reserved. + * Author: Gregroy Nutt + * Author: John Wharington + * Author: Sebastien Lorquet + * Author: dev@ziggurat29.com + * + * 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. + * + ************************************************************************************/ + +/* Supports: + * - Master operation, 100 kHz (standard) and 400 kHz (full speed) + * - Multiple instances (shared bus) + * - Interrupt based operation + * + * Structure naming: + * - Device: structure as defined by the nuttx/i2c/i2c.h + * - Instance: represents each individual access to the I2C driver, obtained by + * the i2c_init(); it extends the Device structure from the nuttx/i2c/i2c.h; + * Instance points to OPS, to common I2C Hardware private data and contains + * its own private data, as frequency, address, mode of operation (in the future) + * - Private: Private data of an I2C Hardware + * + * TODO + * - Check for all possible deadlocks (as BUSY='1' I2C needs to be reset in HW using + * the I2C_CR1_SWRST) + * - SMBus support (hardware layer timings are already supported) and add SMBA gpio + * pin + * - Slave support with multiple addresses (on multiple instances): + * - 2 x 7-bit address or + * - 1 x 10 bit adresses + 1 x 7 bit address (?) + * - plus the broadcast address (general call) + * - Multi-master support + * - DMA (to get rid of too many CPU wake-ups and interventions) + * - Be ready for IPMI + */ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include + +#include "up_arch.h" + +#include "stm32f0_gpio.h" +#include "stm32f0_rcc.h" +#include "stm32f0_i2c.h" + +/* At least one I2C peripheral must be enabled */ + +#if defined(CONFIG_STM32F0_I2C1) || defined(CONFIG_STM32F0_I2C2) || defined(CONFIG_STM32F0_I2C3) + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Configuration ********************************************************************/ +/* CONFIG_I2C_POLLED may be set so that I2C interrupts will not be used. Instead, + * CPU-intensive polling will be used. + */ + +/* Interrupt wait timeout in seconds and milliseconds */ + +#if !defined(CONFIG_STM32F0_I2CTIMEOSEC) && !defined(CONFIG_STM32F0_I2CTIMEOMS) +# define CONFIG_STM32F0_I2CTIMEOSEC 0 +# define CONFIG_STM32F0_I2CTIMEOMS 500 /* Default is 500 milliseconds */ +#elif !defined(CONFIG_STM32F0_I2CTIMEOSEC) +# define CONFIG_STM32F0_I2CTIMEOSEC 0 /* User provided milliseconds */ +#elif !defined(CONFIG_STM32F0_I2CTIMEOMS) +# define CONFIG_STM32F0_I2CTIMEOMS 0 /* User provided seconds */ +#endif + +/* Interrupt wait time timeout in system timer ticks */ + +#ifndef CONFIG_STM32F0_I2CTIMEOTICKS +# define CONFIG_STM32F0_I2CTIMEOTICKS \ + (SEC2TICK(CONFIG_STM32F0_I2CTIMEOSEC) + MSEC2TICK(CONFIG_STM32F0_I2CTIMEOMS)) +#endif + +#ifndef CONFIG_STM32F0_I2C_DYNTIMEO_STARTSTOP +# define CONFIG_STM32F0_I2C_DYNTIMEO_STARTSTOP TICK2USEC(CONFIG_STM32F0_I2CTIMEOTICKS) +#endif + +#define I2C_OUTPUT \ + (GPIO_OUTPUT | GPIO_OUTPUT_SET | GPIO_OPENDRAIN | GPIO_SPEED_50MHz) +#define MKI2C_OUTPUT(p) \ + (((p) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | I2C_OUTPUT) + +#define I2C_CR1_TXRX \ + (I2C_CR1_RXIE | I2C_CR1_TXIE) +#define I2C_CR1_ALLINTS \ + (I2C_CR1_TXRX | I2C_CR1_TCIE | I2C_CR1_ADDRIE | I2C_CR1_ERRIE) + +#define STATUS_NACK(status) (status & I2C_INT_NACK) +#define STATUS_ADDR(status) (status & I2C_INT_ADDR) +#define STATUS_ADDR_TX(status) (status & (I2C_INT_ADDR | I2C_ISR_TXIS)) +#define STATUS_ADD10(status) (0) +#define STATUS_RXNE(status) (status & I2C_ISR_RXNE) +#define STATUS_TC(status) (status & I2C_ISR_TC) +#define STATUS_BUSY(status) (status & I2C_ISR_BUSY) + +/* Debug ****************************************************************************/ + +/* I2C event trace logic. NOTE: trace uses the internal, non-standard, low-level + * debug interface syslog() but does not require that any other debug + * is enabled. + */ + +#ifndef CONFIG_I2C_TRACE +# define stm32f0_i2c_tracereset(p) +# define stm32f0_i2c_tracenew(p,s) +# define stm32f0_i2c_traceevent(p,e,a) +# define stm32f0_i2c_tracedump(p) +#endif + +#ifndef CONFIG_I2C_NTRACE +# define CONFIG_I2C_NTRACE 32 +#endif + +/************************************************************************************ + * Private Types + ************************************************************************************/ +/* Interrupt state */ + +enum stm32f0_intstate_e +{ + INTSTATE_IDLE = 0, /* No I2C activity */ + INTSTATE_WAITING, /* Waiting for completion of interrupt activity */ + INTSTATE_DONE, /* Interrupt activity complete */ +}; + +/* Trace events */ + +enum stm32f0_trace_e +{ + I2CEVENT_NONE = 0, /* No events have occurred with this status */ + I2CEVENT_SENDADDR, /* Start/Master bit set and address sent, param = msgc */ + I2CEVENT_SENDBYTE, /* Send byte, param = dcnt */ + I2CEVENT_ITBUFEN, /* Enable buffer interrupts, param = 0 */ + I2CEVENT_RCVBYTE, /* Read more dta, param = dcnt */ + I2CEVENT_REITBUFEN, /* Re-enable buffer interrupts, param = 0 */ + I2CEVENT_DISITBUFEN, /* Disable buffer interrupts, param = 0 */ + I2CEVENT_BTFNOSTART, /* BTF on last byte with no restart, param = msgc */ + I2CEVENT_BTFRESTART, /* Last byte sent, re-starting, param = msgc */ + I2CEVENT_BTFSTOP, /* Last byte sten, send stop, param = 0 */ + I2CEVENT_ERROR /* Error occurred, param = 0 */ +}; + +/* Trace data */ + +struct stm32f0_trace_s +{ + uint32_t status; /* I2C 32-bit SR2|SR1 status */ + uint32_t count; /* Interrupt count when status change */ + enum stm32f0_intstate_e event; /* Last event that occurred with this status */ + uint32_t parm; /* Parameter associated with the event */ + systime_t time; /* First of event or first status */ +}; + +/* I2C Device hardware configuration */ + +struct stm32f0_i2c_config_s +{ + uint32_t base; /* I2C base address */ + uint32_t clk_bit; /* Clock enable bit */ + uint32_t reset_bit; /* Reset bit */ + uint32_t scl_pin; /* GPIO configuration for SCL as SCL */ + uint32_t sda_pin; /* GPIO configuration for SDA as SDA */ +#ifndef CONFIG_I2C_POLLED + int (*isr)(int, void *, void *); /* Interrupt handler */ + uint32_t irq; /* IRQ */ +#endif +}; + +/* I2C Device Private Data */ + +struct stm32f0_i2c_priv_s +{ + const struct i2c_ops_s *ops; /* Standard I2C operations */ + const struct stm32f0_i2c_config_s *config; /* Port configuration */ + int refs; /* Reference count */ + sem_t sem_excl; /* Mutual exclusion semaphore */ +#ifndef CONFIG_I2C_POLLED + sem_t sem_isr; /* Interrupt wait semaphore */ +#endif + volatile uint8_t intstate; /* Interrupt handshake (see enum stm32f0_intstate_e) */ + + uint8_t msgc; /* Message count */ + struct i2c_msg_s *msgv; /* Message list */ + uint8_t *ptr; /* Current message buffer */ + uint32_t frequency; /* Current I2C frequency */ + int dcnt; /* Current message length */ + uint16_t flags; /* Current message flags */ + bool astart; /* START sent */ + + /* I2C trace support */ + +#ifdef CONFIG_I2C_TRACE + int tndx; /* Trace array index */ + systime_t start_time; /* Time when the trace was started */ + + /* The actual trace data */ + + struct stm32f0_trace_s trace[CONFIG_I2C_NTRACE]; +#endif + + uint32_t status; /* End of transfer SR2|SR1 status */ +}; + +/************************************************************************************ + * Private Function Prototypes + ************************************************************************************/ + +static inline uint32_t stm32f0_i2c_getreg32(FAR struct stm32f0_i2c_priv_s *priv, + uint8_t offset); +static inline void stm32f0_i2c_putreg32(FAR struct stm32f0_i2c_priv_s *priv, + uint8_t offset, uint32_t value); +static inline void stm32f0_i2c_modifyreg32(FAR struct stm32f0_i2c_priv_s *priv, + uint8_t offset, uint32_t clearbits, + uint32_t setbits); +static inline void stm32f0_i2c_sem_wait(FAR struct stm32f0_i2c_priv_s *priv); +#ifdef CONFIG_STM32F0_I2C_DYNTIMEO +static useconds_t stm32f0_i2c_tousecs(int msgc, FAR struct i2c_msg_s *msgs); +#endif /* CONFIG_STM32F0_I2C_DYNTIMEO */ +static inline int stm32f0_i2c_sem_waitdone(FAR struct stm32f0_i2c_priv_s *priv); +static inline void stm32f0_i2c_sem_waitstop(FAR struct stm32f0_i2c_priv_s *priv); +static inline void stm32f0_i2c_sem_post(FAR struct stm32f0_i2c_priv_s *priv); +static inline void stm32f0_i2c_sem_init(FAR struct stm32f0_i2c_priv_s *priv); +static inline void stm32f0_i2c_sem_destroy(FAR struct stm32f0_i2c_priv_s *priv); +#ifdef CONFIG_I2C_TRACE +static void stm32f0_i2c_tracereset(FAR struct stm32f0_i2c_priv_s *priv); +static void stm32f0_i2c_tracenew(FAR struct stm32f0_i2c_priv_s *priv, + uint32_t status); +static void stm32f0_i2c_traceevent(FAR struct stm32f0_i2c_priv_s *priv, + enum stm32f0_trace_e event, uint32_t parm); +static void stm32f0_i2c_tracedump(FAR struct stm32f0_i2c_priv_s *priv); +#endif /* CONFIG_I2C_TRACE */ +static void stm32f0_i2c_setclock(FAR struct stm32f0_i2c_priv_s *priv, + uint32_t frequency); +static inline void stm32f0_i2c_sendstart(FAR struct stm32f0_i2c_priv_s *priv); +static inline void stm32f0_i2c_clrstart(FAR struct stm32f0_i2c_priv_s *priv); +static inline void stm32f0_i2c_sendstop(FAR struct stm32f0_i2c_priv_s *priv); +static inline uint32_t stm32f0_i2c_getstatus(FAR struct stm32f0_i2c_priv_s *priv); +static int stm32f0_i2c_isr(struct stm32f0_i2c_priv_s * priv); +#ifndef CONFIG_I2C_POLLED +#ifdef CONFIG_STM32F0_I2C1 +static int stm32f0_i2c1_isr(int irq, void *context, FAR void *arg); +#endif +#ifdef CONFIG_STM32F0_I2C2 +static int stm32f0_i2c2_isr(int irq, void *context, FAR void *arg); +#endif +#ifdef CONFIG_STM32F0_I2C3 +static int stm32f0_i2c3_isr(int irq, void *context, FAR void *arg); +#endif +#endif +static int stm32f0_i2c_init(FAR struct stm32f0_i2c_priv_s *priv); +static int stm32f0_i2c_deinit(FAR struct stm32f0_i2c_priv_s *priv); +static int stm32f0_i2c_transfer(FAR struct i2c_master_s *dev, + FAR struct i2c_msg_s *msgs, int count); +#ifdef CONFIG_I2C_RESET +static int stm32f0_i2c_reset(FAR struct i2c_master_s *dev); +#endif + +/************************************************************************************ + * Private Data + ************************************************************************************/ + +/* Device Structures, Instantiation */ + +const struct i2c_ops_s stm32f0_i2c_ops = +{ + .transfer = stm32f0_i2c_transfer +#ifdef CONFIG_I2C_RESET + , .reset = stm32f0_i2c_reset +#endif +}; + +#ifdef CONFIG_STM32F0_I2C1 +static const struct stm32f0_i2c_config_s stm32f0_i2c1_config = +{ + .base = STM32F0_I2C1_BASE, + .clk_bit = RCC_APB1ENR_I2C1EN, + .reset_bit = RCC_APB1RSTR_I2C1RST, + .scl_pin = GPIO_I2C1_SCL, + .sda_pin = GPIO_I2C1_SDA, +#ifndef CONFIG_I2C_POLLED + .isr = stm32f0_i2c1_isr, + .irq = STM32F0_IRQ_I2C1 +#endif +}; + +struct stm32f0_i2c_priv_s stm32f0_i2c1_priv = +{ + .ops = &stm32f0_i2c_ops, + .config = &stm32f0_i2c1_config, + .refs = 0, + .intstate = INTSTATE_IDLE, + .msgc = 0, + .msgv = NULL, + .ptr = NULL, + .dcnt = 0, + .flags = 0, + .status = 0 +}; +#endif + +#ifdef CONFIG_STM32F0_I2C2 +static const struct stm32f0_i2c_config_s stm32f0_i2c2_config = +{ + .base = STM32F0_I2C2_BASE, + .clk_bit = RCC_APB1ENR1_I2C2EN, + .reset_bit = RCC_APB1RSTR1_I2C2RST, + .scl_pin = GPIO_I2C2_SCL, + .sda_pin = GPIO_I2C2_SDA, +#ifndef CONFIG_I2C_POLLED + .isr = stm32f0_i2c2_isr, + .irq = STM32F0_IRQ_I2C2 +#endif +}; + +struct stm32f0_i2c_priv_s stm32f0_i2c2_priv = +{ + .ops = &stm32f0_i2c_ops, + .config = &stm32f0_i2c2_config, + .refs = 0, + .intstate = INTSTATE_IDLE, + .msgc = 0, + .msgv = NULL, + .ptr = NULL, + .dcnt = 0, + .flags = 0, + .status = 0 +}; +#endif + +#ifdef CONFIG_STM32F0_I2C3 +static const struct stm32f0_i2c_config_s stm32f0_i2c3_config = +{ + .base = STM32F0_I2C3_BASE, + .clk_bit = RCC_APB1ENR1_I2C3EN, + .reset_bit = RCC_APB1RSTR1_I2C3RST, + .scl_pin = GPIO_I2C3_SCL, + .sda_pin = GPIO_I2C3_SDA, +#ifndef CONFIG_I2C_POLLED + .isr = stm32f0_i2c3_isr, + .irq = STM32F0_IRQ_I2C3 +#endif +}; + +struct stm32f0_i2c_priv_s stm32f0_i2c3_priv = +{ + .ops = &stm32f0_i2c_ops, + .config = &stm32f0_i2c3_config, + .refs = 0, + .intstate = INTSTATE_IDLE, + .msgc = 0, + .msgv = NULL, + .ptr = NULL, + .dcnt = 0, + .flags = 0, + .status = 0 +}; +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32f0_i2c_getreg32 + * + * Description: + * Get a 32-bit register value by offset + * + ************************************************************************************/ + +static inline uint32_t stm32f0_i2c_getreg32(FAR struct stm32f0_i2c_priv_s *priv, + uint8_t offset) +{ + return getreg32(priv->config->base + offset); +} + +/************************************************************************************ + * Name: stm32f0_i2c_putreg32 + * + * Description: + * Put a 32-bit register value by offset + * + ************************************************************************************/ + +static inline void stm32f0_i2c_putreg32(FAR struct stm32f0_i2c_priv_s *priv, + uint8_t offset, uint32_t value) +{ + putreg32(value, priv->config->base + offset); +} + +/************************************************************************************ + * Name: stm32f0_i2c_modifyreg32 + * + * Description: + * Modify a 32-bit register value by offset + * + ************************************************************************************/ + +static inline void stm32f0_i2c_modifyreg32(FAR struct stm32f0_i2c_priv_s *priv, + uint8_t offset, uint32_t clearbits, + uint32_t setbits) +{ + modifyreg32(priv->config->base + offset, clearbits, setbits); +} + +/************************************************************************************ + * Name: stm32f0_i2c_sem_wait + * + * Description: + * Take the exclusive access, waiting as necessary + * + ************************************************************************************/ + +static inline void stm32f0_i2c_sem_wait(FAR struct stm32f0_i2c_priv_s *priv) +{ + while (sem_wait(&priv->sem_excl) != 0) + { + ASSERT(errno == EINTR); + } +} + +/************************************************************************************ + * Name: stm32f0_i2c_tousecs + * + * Description: + * Return a micro-second delay based on the number of bytes left to be processed. + * + ************************************************************************************/ + +#ifdef CONFIG_STM32F0_I2C_DYNTIMEO +static useconds_t stm32f0_i2c_tousecs(int msgc, FAR struct i2c_msg_s *msgs) +{ + size_t bytecount = 0; + int i; + + /* Count the number of bytes left to process */ + + for (i = 0; i < msgc; i++) + { + bytecount += msgs[i].length; + } + + /* Then return a number of microseconds based on a user provided scaling + * factor. + */ + + return (useconds_t)(CONFIG_STM32F0_I2C_DYNTIMEO_USECPERBYTE * bytecount); +} +#endif + +/************************************************************************************ + * Name: stm32f0_i2c_enableinterrupts + * + * Description: + * Enable I2C interrupts + * + ************************************************************************************/ + +#ifndef CONFIG_I2C_POLLED +static inline void stm32f0_i2c_enableinterrupts(struct stm32f0_i2c_priv_s *priv) +{ + stm32f0_i2c_modifyreg32(priv, STM32F0_I2C_CR1_OFFSET, 0, I2C_CR1_TXRX); +} +#endif + +/************************************************************************************ + * Name: stm32f0_i2c_disableinterrupts + * + * Description: + * Enable I2C interrupts + * + ************************************************************************************/ + +#ifndef CONFIG_I2C_POLLED +static inline void stm32f0_i2c_disableinterrupts(struct stm32f0_i2c_priv_s *priv) +{ + stm32f0_i2c_modifyreg32(priv, STM32F0_I2C_CR1_OFFSET, I2C_CR1_TXRX, 0); +} +#endif + +/************************************************************************************ + * Name: stm32f0_i2c_sem_waitdone + * + * Description: + * Wait for a transfer to complete + * + ************************************************************************************/ + +#ifndef CONFIG_I2C_POLLED +static inline int stm32f0_i2c_sem_waitdone(FAR struct stm32f0_i2c_priv_s *priv) +{ + struct timespec abstime; + irqstate_t flags; + int ret; + + flags = enter_critical_section(); + + /* Enable I2C interrupts */ + + stm32f0_i2c_modifyreg32(priv, STM32F0_I2C_CR1_OFFSET, 0, + (I2C_CR1_ALLINTS & ~I2C_CR1_TXRX)); + + /* Signal the interrupt handler that we are waiting. NOTE: Interrupts + * are currently disabled but will be temporarily re-enabled below when + * sem_timedwait() sleeps. + */ + + priv->intstate = INTSTATE_WAITING; + do + { + /* Get the current time */ + + (void)clock_gettime(CLOCK_REALTIME, &abstime); + + /* Calculate a time in the future */ + +#if CONFIG_STM32F0_I2CTIMEOSEC > 0 + abstime.tv_sec += CONFIG_STM32F0_I2CTIMEOSEC; +#endif + + /* Add a value proportional to the number of bytes in the transfer */ + +#ifdef CONFIG_STM32F0_I2C_DYNTIMEO + abstime.tv_nsec += 1000 * stm32f0_i2c_tousecs(priv->msgc, priv->msgv); + if (abstime.tv_nsec >= 1000 * 1000 * 1000) + { + abstime.tv_sec++; + abstime.tv_nsec -= 1000 * 1000 * 1000; + } + +#elif CONFIG_STM32F0_I2CTIMEOMS > 0 + abstime.tv_nsec += CONFIG_STM32F0_I2CTIMEOMS * 1000 * 1000; + if (abstime.tv_nsec >= 1000 * 1000 * 1000) + { + abstime.tv_sec++; + abstime.tv_nsec -= 1000 * 1000 * 1000; + } +#endif + /* Wait until either the transfer is complete or the timeout expires */ + + ret = sem_timedwait(&priv->sem_isr, &abstime); + if (ret != OK && errno != EINTR) + { + /* Break out of the loop on irrecoverable errors. This would + * include timeouts and mystery errors reported by sem_timedwait. + * NOTE that we try again if we are awakened by a signal (EINTR). + */ + + break; + } + } + + /* Loop until the interrupt level transfer is complete. */ + + while (priv->intstate != INTSTATE_DONE); + + /* Set the interrupt state back to IDLE */ + + priv->intstate = INTSTATE_IDLE; + + /* Disable I2C interrupts */ + + stm32f0_i2c_modifyreg32(priv, STM32F0_I2C_CR1_OFFSET, I2C_CR1_ALLINTS, 0); + + leave_critical_section(flags); + return ret; +} +#else +static inline int stm32f0_i2c_sem_waitdone(FAR struct stm32f0_i2c_priv_s *priv) +{ + systime_t timeout; + systime_t start; + systime_t elapsed; + int ret; + + /* Get the timeout value */ + +#ifdef CONFIG_STM32F0_I2C_DYNTIMEO + timeout = USEC2TICK(stm32f0_i2c_tousecs(priv->msgc, priv->msgv)); +#else + timeout = CONFIG_STM32F0_I2CTIMEOTICKS; +#endif + + /* Signal the interrupt handler that we are waiting. NOTE: Interrupts + * are currently disabled but will be temporarily re-enabled below when + * sem_timedwait() sleeps. + */ + + priv->intstate = INTSTATE_WAITING; + start = clock_systimer(); + + do + { + /* Calculate the elapsed time */ + + elapsed = clock_systimer() - start; + + /* Poll by simply calling the timer interrupt handler until it + * reports that it is done. + */ + + stm32f0_i2c_isr(priv); + } + + /* Loop until the transfer is complete. */ + + while (priv->intstate != INTSTATE_DONE && elapsed < timeout); + + i2cinfo("intstate: %d elapsed: %ld threshold: %ld status: %08x\n", + priv->intstate, (long)elapsed, (long)timeout, priv->status); + + /* Set the interrupt state back to IDLE */ + + ret = priv->intstate == INTSTATE_DONE ? OK : -ETIMEDOUT; + priv->intstate = INTSTATE_IDLE; + return ret; +} +#endif + +/************************************************************************************ + * Name: stm32f0_i2c_set_7bit_address + * + * Description: + * + ************************************************************************************/ + +static inline void +stm32f0_i2c_set_7bit_address(FAR struct stm32f0_i2c_priv_s *priv) +{ + stm32f0_i2c_modifyreg32(priv, STM32F0_I2C_CR2_OFFSET, I2C_CR2_SADD7_MASK, + ((priv->msgv->addr & 0x7F) << I2C_CR2_SADD7_SHIFT)); +} + +/************************************************************************************ + * Name: stm32f0_i2c_set_bytes_to_transfer + * + * Description: + * + ************************************************************************************/ + +static inline void +stm32f0_i2c_set_bytes_to_transfer(FAR struct stm32f0_i2c_priv_s *priv, + uint8_t n_bytes) +{ + stm32f0_i2c_modifyreg32(priv, STM32F0_I2C_CR2_OFFSET, I2C_CR2_NBYTES_MASK, + (n_bytes << I2C_CR2_NBYTES_SHIFT)); +} + +/************************************************************************************ + * Name: stm32f0_i2c_set_write_transfer_dir + * + * Description: + * + ************************************************************************************/ + +static inline void +stm32f0_i2c_set_write_transfer_dir(FAR struct stm32f0_i2c_priv_s *priv) +{ + stm32f0_i2c_modifyreg32(priv, STM32F0_I2C_CR2_OFFSET, I2C_CR2_RD_WRN, 0); +} + +/************************************************************************************ + * Name: stm32f0_i2c_set_read_transfer_dir + * + * Description: + * + ************************************************************************************/ + +static inline void +stm32f0_i2c_set_read_transfer_dir(FAR struct stm32f0_i2c_priv_s *priv) +{ + stm32f0_i2c_modifyreg32(priv, STM32F0_I2C_CR2_OFFSET, 0, I2C_CR2_RD_WRN); +} + +/************************************************************************************ + * Name: stm32f0_i2c_enable_autoend + * + * Description: + * + ************************************************************************************/ + +static inline void +stm32f0_i2c_enable_autoend(FAR struct stm32f0_i2c_priv_s *priv) +{ + stm32f0_i2c_modifyreg32(priv, STM32F0_I2C_CR2_OFFSET, 0, I2C_CR2_AUTOEND); +} + +/************************************************************************************ + * Name: stm32f0_i2c_disable_autoend + * + * Description: + * + ************************************************************************************/ + +static inline void +stm32f0_i2c_disable_autoend(FAR struct stm32f0_i2c_priv_s *priv) +{ + stm32f0_i2c_modifyreg32(priv, STM32F0_I2C_CR2_OFFSET, I2C_CR2_AUTOEND, 0); +} + +/************************************************************************************ + * Name: stm32f0_i2c_sem_waitstop + * + * Description: + * Wait for a STOP to complete + * + ************************************************************************************/ + +static inline void stm32f0_i2c_sem_waitstop(FAR struct stm32f0_i2c_priv_s *priv) +{ + systime_t start; + systime_t elapsed; + systime_t timeout; + uint32_t cr; + uint32_t sr; + + /* Select a timeout */ + +#ifdef CONFIG_STM32F0_I2C_DYNTIMEO + timeout = USEC2TICK(CONFIG_STM32F0_I2C_DYNTIMEO_STARTSTOP); +#else + timeout = CONFIG_STM32F0_I2CTIMEOTICKS; +#endif + + /* Wait as stop might still be in progress; but stop might also + * be set because of a timeout error: "The [STOP] bit is set and + * cleared by software, cleared by hardware when a Stop condition is + * detected, set by hardware when a timeout error is detected." + */ + + start = clock_systimer(); + do + { + /* Calculate the elapsed time */ + + elapsed = clock_systimer() - start; + + /* Check for STOP condition */ + + cr = stm32f0_i2c_getreg32(priv, STM32F0_I2C_CR2_OFFSET); + if ((cr & I2C_CR2_STOP) == 0) + { + return; + } + + /* Check for timeout error */ + + sr = stm32f0_i2c_getreg32(priv, STM32F0_I2C_ISR_OFFSET); + if ((sr & I2C_INT_TIMEOUT) != 0) + { + return; + } + } + + /* Loop until the stop is complete or a timeout occurs. */ + + while (elapsed < timeout); + + /* If we get here then a timeout occurred with the STOP condition + * still pending. + */ + + i2cinfo("Timeout with CR: %04x SR: %04x\n", cr, sr); +} + +/************************************************************************************ + * Name: stm32f0_i2c_sem_post + * + * Description: + * Release the mutual exclusion semaphore + * + ************************************************************************************/ + +static inline void stm32f0_i2c_sem_post(FAR struct stm32f0_i2c_priv_s *priv) +{ + sem_post(&priv->sem_excl); +} + +/************************************************************************************ + * Name: stm32f0_i2c_sem_init + * + * Description: + * Initialize semaphores + * + ************************************************************************************/ + +static inline void stm32f0_i2c_sem_init(FAR struct stm32f0_i2c_priv_s *priv) +{ + sem_init(&priv->sem_excl, 0, 1); + +#ifndef CONFIG_I2C_POLLED + /* This semaphore is used for signaling and, hence, should not have + * priority inheritance enabled. + */ + + sem_init(&priv->sem_isr, 0, 0); + sem_setprotocol(&priv->sem_isr, SEM_PRIO_NONE); +#endif +} + +/************************************************************************************ + * Name: stm32f0_i2c_sem_destroy + * + * Description: + * Destroy semaphores. + * + ************************************************************************************/ + +static inline void stm32f0_i2c_sem_destroy(FAR struct stm32f0_i2c_priv_s *priv) +{ + sem_destroy(&priv->sem_excl); +#ifndef CONFIG_I2C_POLLED + sem_destroy(&priv->sem_isr); +#endif +} + +/************************************************************************************ + * Name: stm32f0_i2c_trace* + * + * Description: + * I2C trace instrumentation + * + ************************************************************************************/ + +#ifdef CONFIG_I2C_TRACE +static void stm32f0_i2c_traceclear(FAR struct stm32f0_i2c_priv_s *priv) +{ + struct stm32f0_trace_s *trace = &priv->trace[priv->tndx]; + + trace->status = 0; /* I2C 32-bit SR2|SR1 status */ + trace->count = 0; /* Interrupt count when status change */ + trace->event = I2CEVENT_NONE; /* Last event that occurred with this status */ + trace->parm = 0; /* Parameter associated with the event */ + trace->time = 0; /* Time of first status or event */ +} + +static void stm32f0_i2c_tracereset(FAR struct stm32f0_i2c_priv_s *priv) +{ + /* Reset the trace info for a new data collection */ + + priv->tndx = 0; + priv->start_time = clock_systimer(); + stm32f0_i2c_traceclear(priv); +} + +static void stm32f0_i2c_tracenew(FAR struct stm32f0_i2c_priv_s *priv, + uint32_t status) +{ + struct stm32f0_trace_s *trace = &priv->trace[priv->tndx]; + + /* Is the current entry uninitialized? Has the status changed? */ + + if (trace->count == 0 || status != trace->status) + { + /* Yes.. Was it the status changed? */ + + if (trace->count != 0) + { + /* Yes.. bump up the trace index (unless we are out of trace entries) */ + + if (priv->tndx >= (CONFIG_I2C_NTRACE-1)) + { + i2cerr("ERROR: Trace table overflow\n"); + return; + } + + priv->tndx++; + trace = &priv->trace[priv->tndx]; + } + + /* Initialize the new trace entry */ + + stm32f0_i2c_traceclear(priv); + trace->status = status; + trace->count = 1; + trace->time = clock_systimer(); + } + else + { + /* Just increment the count of times that we have seen this status */ + + trace->count++; + } +} + +static void stm32f0_i2c_traceevent(FAR struct stm32f0_i2c_priv_s *priv, + enum stm32f0_trace_e event, uint32_t parm) +{ + struct stm32f0_trace_s *trace; + + if (event != I2CEVENT_NONE) + { + trace = &priv->trace[priv->tndx]; + + /* Initialize the new trace entry */ + + trace->event = event; + trace->parm = parm; + + /* Bump up the trace index (unless we are out of trace entries) */ + + if (priv->tndx >= (CONFIG_I2C_NTRACE-1)) + { + i2cerr("ERROR: Trace table overflow\n"); + return; + } + + priv->tndx++; + stm32f0_i2c_traceclear(priv); + } +} + +static void stm32f0_i2c_tracedump(FAR struct stm32f0_i2c_priv_s *priv) +{ + struct stm32f0_trace_s *trace; + int i; + + syslog(LOG_DEBUG, "Elapsed time: %ld\n", + (long)(clock_systimer() - priv->start_time)); + + for (i = 0; i <= priv->tndx; i++) + { + trace = &priv->trace[i]; + syslog(LOG_DEBUG, + "%2d. STATUS: %08x COUNT: %3d EVENT: %2d PARM: %08x TIME: %d\n", + i+1, trace->status, trace->count, trace->event, trace->parm, + trace->time - priv->start_time); + } +} +#endif /* CONFIG_I2C_TRACE */ + +/************************************************************************************ + * Name: stm32f0_i2c_setclock + * + * Description: + * Set the I2C clock + * + ************************************************************************************/ + +static void stm32f0_i2c_setclock(FAR struct stm32f0_i2c_priv_s *priv, uint32_t frequency) +{ + uint32_t pe; + uint8_t presc; + uint8_t s_time; + uint8_t h_time; + uint8_t scl_h_period; + uint8_t scl_l_period; + + /* XXX haque; these are the only freqs we support at the moment, until we can + * compute the values ourself. + */ + + if (frequency == 10000) + { + } + else if (frequency == 100000) + { + } + else if (frequency == 400000) + { + } + else + { +#if 1 + frequency = 1000000; +#else + frequency = 500000; +#endif + } + + /* Has the I2C bus frequency changed? */ + + if (frequency != priv->frequency) + { + /* Disable the selected I2C peripheral to configure TRISE */ + + pe = (stm32f0_i2c_getreg32(priv, STM32F0_I2C_CR1_OFFSET) & I2C_CR1_PE); + if (pe) + { + stm32f0_i2c_modifyreg32(priv, STM32F0_I2C_CR1_OFFSET, I2C_CR1_PE, 0); + } + + /* Update timing and control registers */ + + /* TODO: speed/timing calcs, taking into consideration + * STM32F0_PCLK1_FREQUENCY, or SYSCLK, or HSI16 + * clock source, RCC_CCIPR, I2CxSEL, 0 = PCKL, 1 = SCLK, 2 = HSI16, 3 = reserved +#warning "check set filters before timing, see RM0351 35.4.4 p 1112" + * analog filter; suppress spikes up to 50 ns in fast-mode and fast-mode plus + * ANFOFF cr1 + * DNF cr1; 1-15 I2CCLK periods + */ + /* RM0351 35.4.9 p 1140 */ + + if (frequency == 10000) + { +#if 1 + /* 10 KHz values from I2C timing tool with clock 80mhz */ + + presc = 0x0b; /* PRESC - (+1) prescale I2CCLK */ + scl_l_period = 0xff; /* SCLL - SCL low period in master mode */ + scl_h_period = 0xba; /* SCLH - SCL high period in master mode */ + h_time = 0x00; /* SDADEL - (+1) data hold time after SCL falling edge */ + s_time = 0x01; /* SCLDEL - (+1) data setup time from SDA edge to SCL rising edge */ + +#else + /* 10 KHz values from datasheet with clock 8mhz */ + + presc = 0x03; /* PRESC - (+1) prescale I2CCLK */ + scl_l_period = 0xc7; /* SCLL - SCL low period in master mode */ + scl_h_period = 0xc3; /* SCLH - SCL high period in master mode */ + h_time = 0x02; /* SDADEL - (+1) data hold time after SCL falling edge */ + s_time = 0x04; /* SCLDEL - (+1) data setup time from SDA edge to SCL rising edge */ +#endif + } + else if (frequency == 100000) + { +#if 1 + /* 100 KHz values from I2C timing tool with clock 80mhz */ + + presc = 0x01; /* PRESC - (+1) prescale I2CCLK */ + scl_l_period = 0xe7; /* SCLL - SCL low period in master mode */ + scl_h_period = 0x9b; /* SCLH - SCL high period in master mode */ + h_time = 0x00; /* SDADEL - (+1) data hold time after SCL falling edge */ + s_time = 0x0d; /* SCLDEL - (+1) data setup time from SDA edge to SCL rising edge */ +#else + /* 100 KHz values from datasheet with clock 8mhz */ + + presc = 0x01; + scl_l_period = 0x13; + scl_h_period = 0x0f; + h_time = 0x02; + s_time = 0x04; +#endif + } + else if (frequency == 400000) + { +#if 1 + /* 400 KHz values from I2C timing tool for clock of 80mhz */ + + presc = 0x01; /* PRESC - (+1) prescale I2CCLK */ + scl_l_period = 0x43; /* SCLL - SCL low period in master mode */ + scl_h_period = 0x13; /* SCLH - SCL high period in master mode */ + h_time = 0x00; /* SDADEL - (+1) data hold time after SCL falling edge */ + s_time = 0x07; /* SCLDEL - (+1) data setup time from SDA edge to SCL rising edge */ +#else + /* 400 KHz values from datasheet for clock of 8mhz */ + + presc = 0x00; + scl_l_period = 0x09; + scl_h_period = 0x03; + h_time = 0x01; + s_time = 0x03; +#endif + } + else + { +#if 1 + /* 1000 KHhz values from I2C timing tool for clock of 80mhz */ + + presc = 0x01; /* PRESC - (+1) prescale I2CCLK */ + scl_l_period = 0x14; /* SCLL - SCL low period in master mode */ + scl_h_period = 0x13; /* SCLH - SCL high period in master mode */ + h_time = 0x00; /* SDADEL - (+1) data hold time after SCL falling edge */ + s_time = 0x05; /* SCLDEL - (+1) data setup time from SDA edge to SCL rising edge */ + + frequency = 1000000; +#else + /* 500 KHhz values from datasheet for clock of 8mhz */ + + presc = 0x00; + scl_l_period = 0x06; + scl_h_period = 0x03; + h_time = 0x00; + s_time = 0x01; + + frequency = 500000; +#endif + } + + uint32_t timingr = + (presc << I2C_TIMINGR_PRESC_SHIFT) | + (s_time << I2C_TIMINGR_SCLDEL_SHIFT) | + (h_time << I2C_TIMINGR_SDADEL_SHIFT) | + (scl_h_period << I2C_TIMINGR_SCLH_SHIFT) | + (scl_l_period << I2C_TIMINGR_SCLL_SHIFT); + + stm32f0_i2c_putreg32(priv, STM32F0_I2C_TIMINGR_OFFSET, timingr); + + /* Re-enable the peripheral (or not) */ + + if (pe) + { + stm32f0_i2c_modifyreg32(priv, STM32F0_I2C_CR1_OFFSET, 0, I2C_CR1_PE); + } + + /* Save the new I2C frequency */ + + priv->frequency = frequency; + } +} + +/************************************************************************************ + * Name: stm32f0_i2c_sendstart + * + * Description: + * Send the START conditions/force Master mode + * + ************************************************************************************/ + +static inline void stm32f0_i2c_sendstart(FAR struct stm32f0_i2c_priv_s *priv) +{ + /* Get run-time data */ + + priv->astart = true; + priv->ptr = priv->msgv->buffer; + priv->dcnt = priv->msgv->length; + priv->flags = priv->msgv->flags; + + /* Disable ACK on receive by default and generate START */ + + stm32f0_i2c_set_bytes_to_transfer(priv, priv->dcnt); + stm32f0_i2c_set_7bit_address(priv); + if (priv->flags & I2C_M_READ) + { + stm32f0_i2c_set_read_transfer_dir(priv); + } + else + { + stm32f0_i2c_set_write_transfer_dir(priv); + } + + if (priv->msgc == 1) + { + /* stm32f0_i2c_enable_autoend(priv); */ + } + else + { + /* stm32f0_i2c_disable_autoend(priv); */ + } + + /* TODO check NACK */ + /* TODO handle NACKR? */ + + stm32f0_i2c_modifyreg32(priv, STM32F0_I2C_CR2_OFFSET, 0, I2C_CR2_START); +} + +/************************************************************************************ + * Name: stm32f0_i2c_clrstart + * + * Description: + * Clear the STOP, START or PEC condition on certain error recovery steps. + * + ************************************************************************************/ + +static inline void stm32f0_i2c_clrstart(FAR struct stm32f0_i2c_priv_s *priv) +{ + /* "Note: When the STOP, START or PEC bit is set, the software must + * not perform any write access to I2C_CR1 before this bit is + * cleared by hardware. Otherwise there is a risk of setting a + * second STOP, START or PEC request." + * + * "The [STOP] bit is set and cleared by software, cleared by hardware + * when a Stop condition is detected, set by hardware when a timeout + * error is detected. + * + * "This [START] bit is set and cleared by software and cleared by hardware + * when start is sent or PE=0." The bit must be cleared by software if the + * START is never sent. + * + * "This [PEC] bit is set and cleared by software, and cleared by hardware + * when PEC is transferred or by a START or Stop condition or when PE=0." + */ + + /* TODO check PEC (32 bit separate reg) */ + + stm32f0_i2c_modifyreg32(priv, STM32F0_I2C_CR2_OFFSET, + I2C_CR2_START | I2C_CR2_STOP, 0); +} + +/************************************************************************************ + * Name: stm32f0_i2c_sendstop + * + * Description: + * Send the STOP conditions + * + ************************************************************************************/ + +static inline void stm32f0_i2c_sendstop(FAR struct stm32f0_i2c_priv_s *priv) +{ + /* TODO check NACK */ + + stm32f0_i2c_modifyreg32(priv, STM32F0_I2C_CR2_OFFSET, 0, I2C_CR2_STOP); +} + +/************************************************************************************ + * Name: stm32f0_i2c_getstatus + * + * Description: + * Get 32-bit status (SR1 and SR2 combined) + * + ************************************************************************************/ + +static inline uint32_t stm32f0_i2c_getstatus(FAR struct stm32f0_i2c_priv_s *priv) +{ + return getreg32(priv->config->base + STM32F0_I2C_ISR_OFFSET); +} + +/************************************************************************************ + * Name: stm32f0_i2c_isr + * + * Description: + * Common logic when a message is started. Just adds the even to the trace buffer + * if enabled and adjusts the message pointer and count. + * + ************************************************************************************/ + +static inline void stm32f0_i2c_isr_startmessage(struct stm32f0_i2c_priv_s *priv) +{ + stm32f0_i2c_traceevent(priv, I2CEVENT_SENDADDR, priv->msgc); + + /* Increment to next pointer and decrement message count */ + + priv->msgv++; + priv->msgc--; +} + +/************************************************************************************ + * Name: stm32f0_i2c_clearinterrupts + * + * Description: + * Clear all interrupts + * + ************************************************************************************/ + +static inline void stm32f0_i2c_clearinterrupts(struct stm32f0_i2c_priv_s *priv) +{ +#warning "check this clears interrupts?" + stm32f0_i2c_modifyreg32(priv, STM32F0_I2C_ICR_OFFSET, 0, I2C_ICR_CLEARMASK); +} + +/************************************************************************************ + * Name: stm32f0_i2c_isr + * + * Description: + * Common Interrupt Service Routine + * + ************************************************************************************/ + +static int stm32f0_i2c_isr(struct stm32f0_i2c_priv_s *priv) +{ + uint32_t status = stm32f0_i2c_getstatus(priv); + + /* Check for new trace setup */ + + stm32f0_i2c_tracenew(priv, status); + +#warning "TODO: check clear interrupts after all actions" + + if (STATUS_NACK(status)) + { + /* wait, reset this? */ + } + else if (priv->astart) + { + stm32f0_i2c_isr_startmessage(priv); + priv->astart = false; + } + + /* Was address sent, continue with either sending or reading data */ + + if ((priv->flags & I2C_M_READ) == 0 && STATUS_ADDR_TX(status)) + { +#warning "TODO: ADDRCF clear address interrupt flag" + if (priv->dcnt > 0) + { + /* Send a byte */ + + stm32f0_i2c_traceevent(priv, I2CEVENT_SENDBYTE, priv->dcnt); + stm32f0_i2c_putreg32(priv, STM32F0_I2C_TXDR_OFFSET, *priv->ptr++); + priv->dcnt--; + } + } + else if ((priv->flags & I2C_M_READ) != 0 && STATUS_ADDR(status)) + { + /* Enable RxNE and TxE buffers in order to receive one or multiple bytes */ + +#warning "TODO: ADDRCF clear address interrupt flag" + +#ifndef CONFIG_I2C_POLLED + stm32f0_i2c_traceevent(priv, I2CEVENT_ITBUFEN, 0); + stm32f0_i2c_enableinterrupts(priv); +#endif + } + + /* More bytes to read */ + + else if (STATUS_RXNE(status)) + { + /* Read a byte, if dcnt goes < 0, then read dummy bytes to ack ISRs */ + + if (priv->dcnt > 0) + { + stm32f0_i2c_traceevent(priv, I2CEVENT_RCVBYTE, priv->dcnt); + + /* No interrupts or context switches may occur in the following + * sequence. Otherwise, additional bytes may be sent by the + * device. + */ + +#ifdef CONFIG_I2C_POLLED + irqstate_t flags = enter_critical_section(); +#endif + /* Receive a byte */ + + *priv->ptr++ = (uint8_t) stm32f0_i2c_getreg32(priv, STM32F0_I2C_RXDR_OFFSET); + + /* Disable acknowledge when last byte is to be received */ + + priv->dcnt--; + if (priv->dcnt == 1) + { + /* autoend? */ + } + +#ifdef CONFIG_I2C_POLLED + leave_critical_section(flags); +#endif + } + } + + /* Do we have more bytes to send, enable/disable buffer interrupts + * (these ISRs could be replaced by DMAs) + */ + +#ifndef CONFIG_I2C_POLLED + if (priv->dcnt > 0) + { + stm32f0_i2c_traceevent(priv, I2CEVENT_REITBUFEN, 0); + stm32f0_i2c_enableinterrupts(priv); + } + else if ((priv->dcnt == 0) && (priv->msgc == 0)) + { + stm32f0_i2c_traceevent(priv, I2CEVENT_DISITBUFEN, 0); + stm32f0_i2c_disableinterrupts(priv); + } +#endif + + /* Was last byte received or sent? Hmmm... the F2 and F4 seems to differ from + * the F1 in that BTF is not set after data is received (only RXNE). + */ + + if (priv->dcnt <= 0 && STATUS_TC(status)) + { + /* Do we need to terminate or restart after this byte? + * If there are more messages to send, then we may: + * + * - continue with repeated start + * - or just continue sending writeable part + * - or we close down by sending the stop bit + */ + + if (priv->msgc > 0) + { + if (priv->msgv->flags & I2C_M_NORESTART) + { + stm32f0_i2c_traceevent(priv, I2CEVENT_BTFNOSTART, priv->msgc); + priv->ptr = priv->msgv->buffer; + priv->dcnt = priv->msgv->length; + priv->flags = priv->msgv->flags; + priv->msgv++; + priv->msgc--; + + /* Restart this ISR! */ + +#ifndef CONFIG_I2C_POLLED + stm32f0_i2c_enableinterrupts(priv); +#endif + } + else + { + stm32f0_i2c_traceevent(priv, I2CEVENT_BTFRESTART, priv->msgc); + stm32f0_i2c_sendstart(priv); + } + } + else if (priv->msgv) + { + stm32f0_i2c_traceevent(priv, I2CEVENT_BTFSTOP, 0); + + stm32f0_i2c_sendstop(priv); + + /* Is there a thread waiting for this event (there should be) */ + +#ifndef CONFIG_I2C_POLLED + if (priv->intstate == INTSTATE_WAITING) + { + /* Yes.. inform the thread that the transfer is complete + * and wake it up. + */ + + sem_post(&priv->sem_isr); + priv->intstate = INTSTATE_DONE; + } +#else + priv->intstate = INTSTATE_DONE; +#endif + + /* Mark that we have stopped with this transaction */ + + priv->msgv = NULL; + } + } + + /* Check for errors, in which case, stop the transfer and return + * Note that in master reception mode AF becomes set on last byte + * since ACK is not returned. We should ignore this error. + */ + + if ((status & I2C_ISR_ERRORMASK) != 0) + { + stm32f0_i2c_traceevent(priv, I2CEVENT_ERROR, 0); + + /* Clear interrupt flags */ + + stm32f0_i2c_clearinterrupts(priv); + + /* Is there a thread waiting for this event (there should be) */ + +#ifndef CONFIG_I2C_POLLED + if (priv->intstate == INTSTATE_WAITING) + { + /* Yes.. inform the thread that the transfer is complete + * and wake it up. + */ + + sem_post(&priv->sem_isr); + priv->intstate = INTSTATE_DONE; + } +#else + priv->intstate = INTSTATE_DONE; +#endif + } + + priv->status = status; + return OK; +} + +/************************************************************************************ + * Name: stm32f0_i2c1_isr + * + * Description: + * I2C1 interrupt service routine + * + ************************************************************************************/ + +#ifndef CONFIG_I2C_POLLED +#ifdef CONFIG_STM32F0_I2C1 +static int stm32f0_i2c1_isr(int irq, void *context, FAR void *arg) +{ + return stm32f0_i2c_isr(&stm32f0_i2c1_priv); +} +#endif + +/************************************************************************************ + * Name: stm32f0_i2c2_isr + * + * Description: + * I2C2 interrupt service routine + * + ************************************************************************************/ + +#ifdef CONFIG_STM32F0_I2C2 +static int stm32f0_i2c2_isr(int irq, void *context, FAR void *arg) +{ + return stm32f0_i2c_isr(&stm32f0_i2c2_priv); +} +#endif + +/************************************************************************************ + * Name: stm32f0_i2c3_isr + * + * Description: + * I2C2 interrupt service routine + * + ************************************************************************************/ + +#ifdef CONFIG_STM32F0_I2C3 +static int stm32f0_i2c3_isr(int irq, void *context, FAR void *arg) +{ + return stm32f0_i2c_isr(&stm32f0_i2c3_priv); +} +#endif +#endif + +/************************************************************************************ + * Private Initialization and Deinitialization + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32f0_i2c_init + * + * Description: + * Setup the I2C hardware, ready for operation with defaults + * + ************************************************************************************/ + +static int stm32f0_i2c_init(FAR struct stm32f0_i2c_priv_s *priv) +{ + /* Power-up and configure GPIOs */ + /* Enable power and reset the peripheral */ + + modifyreg32(STM32F0_RCC_APB1ENR, 0, priv->config->clk_bit); + modifyreg32(STM32F0_RCC_APB1RSTR, 0, priv->config->reset_bit); + modifyreg32(STM32F0_RCC_APB1RSTR, priv->config->reset_bit, 0); + + /* Configure pins */ + + if (stm32f0_configgpio(priv->config->scl_pin) < 0) + { + return ERROR; + } + + if (stm32f0_configgpio(priv->config->sda_pin) < 0) + { + stm32f0_unconfiggpio(priv->config->scl_pin); + return ERROR; + } + + /* Attach ISRs */ + +#ifndef CONFIG_I2C_POLLED + irq_attach(priv->config->irq, priv->config->isr, NULL); + up_enable_irq(priv->config->irq); +#endif + + /* Set peripheral frequency, where it must be at least 2 MHz for 100 kHz + * or 4 MHz for 400 kHz. This also disables all I2C interrupts. + */ + + /* Force a frequency update */ + + priv->frequency = 0; + + /* TODO: i2c clock source RCC_CCIPR */ + /* RCC_CCIPR I2CxSEL (default is PCLK clock) */ + + stm32f0_i2c_setclock(priv, 100000); + + /* Enable I2C */ + + stm32f0_i2c_modifyreg32(priv, STM32F0_I2C_CR1_OFFSET, 0, I2C_CR1_PE); + return OK; +} + +/************************************************************************************ + * Name: stm32f0_i2c_deinit + * + * Description: + * Shutdown the I2C hardware + * + ************************************************************************************/ + +static int stm32f0_i2c_deinit(FAR struct stm32f0_i2c_priv_s *priv) +{ + /* Disable I2C */ + + stm32f0_i2c_putreg32(priv, STM32F0_I2C_CR1_OFFSET, 0); + + /* Unconfigure GPIO pins */ + + stm32f0_unconfiggpio(priv->config->scl_pin); + stm32f0_unconfiggpio(priv->config->sda_pin); + + /* Disable and detach interrupts */ + +#ifndef CONFIG_I2C_POLLED + up_disable_irq(priv->config->irq); + irq_detach(priv->config->irq); +#endif + + /* Disable clocking */ + + modifyreg32(STM32F0_RCC_APB1ENR, priv->config->clk_bit, 0); + return OK; +} + +/************************************************************************************ + * Device Driver Operations + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32f0_i2c_transfer + * + * Description: + * Generic I2C transfer function + * + ************************************************************************************/ + +static int stm32f0_i2c_transfer(FAR struct i2c_master_s *dev, FAR struct i2c_msg_s *msgs, + int count) +{ + FAR struct stm32f0_i2c_priv_s *priv = (struct stm32f0_i2c_priv_s *)dev; + uint32_t status = 0; + int ret = OK; + + DEBUGASSERT(dev != NULL && msgs != NULL && count > 0); + + /* Ensure that address or flags don't change meanwhile */ + + stm32f0_i2c_sem_wait(priv); + + /* Wait for any STOP in progress. */ + + stm32f0_i2c_sem_waitstop(priv); + + /* Clear any pending error interrupts */ + + stm32f0_i2c_clearinterrupts(priv); + + /* "Note: When the STOP, START or PEC bit is set, the software must + * not perform any write access to I2C_CR1 before this bit is + * cleared by hardware. Otherwise there is a risk of setting a + * second STOP, START or PEC request." However, if the bits are + * not cleared by hardware, then we will have to do that from hardware. + */ + + stm32f0_i2c_clrstart(priv); + + /* Old transfers are done */ + + priv->msgv = msgs; + priv->msgc = count; + + /* Reset I2C trace logic */ + + stm32f0_i2c_tracereset(priv); + + /* Set I2C clock frequency (on change it toggles I2C_CR1_PE !) + * REVISIT: Note that the frequency is set only on the first message. + * This could be extended to support different transfer frequencies for + * each message segment. + */ + + stm32f0_i2c_setclock(priv, msgs->frequency); + + /* Trigger start condition, then the process moves into the ISR. I2C + * interrupts will be enabled within stm32f0_i2c_waitdone(). + */ + + priv->status = 0; + +#ifndef CONFIG_I2C_POLLED + stm32f0_i2c_enableinterrupts(priv); +#endif + + stm32f0_i2c_sendstart(priv); + + /* Wait for an ISR, if there was a timeout, fetch latest status to get + * the BUSY flag. + */ + + if (stm32f0_i2c_sem_waitdone(priv) < 0) + { + status = stm32f0_i2c_getstatus(priv); + ret = -ETIMEDOUT; + + i2cerr("ERROR: Timed out: CR1: %08x status: %08x\n", + stm32f0_i2c_getreg32(priv, STM32F0_I2C_CR1_OFFSET), status); + + /* "Note: When the STOP, START or PEC bit is set, the software must + * not perform any write access to I2C_CR1 before this bit is + * cleared by hardware. Otherwise there is a risk of setting a + * second STOP, START or PEC request." + */ + + stm32f0_i2c_clrstart(priv); + + /* Clear busy flag in case of timeout */ + + status = priv->status & 0xffff; + } + else + { + /* clear SR2 (BUSY flag) as we've done successfully */ + + status = priv->status & 0xffff; + } + + status &= ~I2C_ISR_BUSY; +#if 0 + /* Refresh status */ + do + { + status = stm32f0_i2c_getstatus(priv); + } + while (STATUS_BUSY(status)); +#endif + + /* Check for error status conditions */ + + if ((status & I2C_ISR_ERRORMASK) != 0) + { + /* I2C_SR1_ERRORMASK is the 'OR' of the following individual bits: */ + + if (status & I2C_INT_BERR) + { + /* Bus Error */ + + ret = -EIO; + } + else if (status & I2C_INT_ARLO) + { + /* Arbitration Lost (master mode) */ + + ret = -EAGAIN; + } + + /* TODO Acknowledge failure */ + + else if (status & I2C_INT_OVR) + { + /* Overrun/Underrun */ + + ret = -EIO; + } + else if (status & I2C_INT_PECERR) + { + /* PEC Error in reception */ + + ret = -EPROTO; + } + else if (status & I2C_INT_TIMEOUT) + { + /* Timeout or Tlow Error */ + + ret = -ETIME; + } + + /* This is not an error and should never happen since SMBus is not + * enabled + */ + + else /* if (status & I2C_INT_ALERT) */ + { + /* SMBus alert is an optional signal with an interrupt line for devices + * that want to trade their ability to master for a pin. + */ + + ret = -EINTR; + } + } + + /* This is not an error, but should not happen. The BUSY signal can hang, + * however, if there are unhealthy devices on the bus that need to be reset. + * NOTE: We will only see this buy indication if stm32f0_i2c_sem_waitdone() + * fails above; Otherwise it is cleared. + */ + + else if ((status & I2C_ISR_BUSY) != 0) + { + /* I2C Bus is for some reason busy */ + + ret = -EBUSY; + } + + /* Dump the trace result */ + + stm32f0_i2c_tracedump(priv); + stm32f0_i2c_sem_post(priv); + return ret; +} + +/************************************************************************************ + * Name: stm32f0_i2c_reset + * + * Description: + * Perform an I2C bus reset in an attempt to break loose stuck I2C devices. + * + * Input Parameters: + * dev - Device-specific state data + * + * Returned Value: + * Zero (OK) on success; a negated errno value on failure. + * + ************************************************************************************/ + +#ifdef CONFIG_I2C_RESET +static int stm32f0_i2c_reset(FAR struct i2c_master_s * dev) +{ + FAR struct stm32f0_i2c_priv_s *priv = (struct stm32f0_i2c_priv_s *)dev; + unsigned int clock_count; + unsigned int stretch_count; + uint32_t scl_gpio; + uint32_t sda_gpio; + uint32_t frequency; + int ret = ERROR; + + ASSERT(dev); + + /* Our caller must own a ref */ + + ASSERT(priv->refs > 0); + + /* Lock out other clients */ + + stm32f0_i2c_sem_wait(priv); + + /* Save the current frequency */ + + frequency = priv->frequency; + + /* De-init the port */ + + stm32f0_i2c_deinit(priv); + + /* Use GPIO configuration to un-wedge the bus */ + + scl_gpio = MKI2C_OUTPUT(priv->config->scl_pin); + sda_gpio = MKI2C_OUTPUT(priv->config->sda_pin); + + /* Let SDA go high */ + + stm32f0_gpiowrite(sda_gpio, 1); + + /* Clock the bus until any slaves currently driving it let it go. */ + + clock_count = 0; + while (!stm32f0_gpioread(sda_gpio)) + { + /* Give up if we have tried too hard */ + + if (clock_count++ > 10) + { + goto out; + } + + /* Sniff to make sure that clock stretching has finished. + * + * If the bus never relaxes, the reset has failed. + */ + + stretch_count = 0; + while (!stm32f0_gpioread(scl_gpio)) + { + /* Give up if we have tried too hard */ + + if (stretch_count++ > 10) + { + goto out; + } + + up_udelay(10); + } + + /* Drive SCL low */ + + stm32f0_gpiowrite(scl_gpio, 0); + up_udelay(10); + + /* Drive SCL high again */ + + stm32f0_gpiowrite(scl_gpio, 1); + up_udelay(10); + } + + /* Generate a start followed by a stop to reset slave + * state machines. + */ + + stm32f0_gpiowrite(sda_gpio, 0); + up_udelay(10); + stm32f0_gpiowrite(scl_gpio, 0); + up_udelay(10); + stm32f0_gpiowrite(scl_gpio, 1); + up_udelay(10); + stm32f0_gpiowrite(sda_gpio, 1); + up_udelay(10); + + /* Revert the GPIO configuration. */ + + stm32f0_unconfiggpio(sda_gpio); + stm32f0_unconfiggpio(scl_gpio); + + /* Re-init the port */ + + stm32f0_i2c_init(priv); + + /* Restore the frequency */ + + stm32f0_i2c_setclock(priv, frequency); + ret = OK; + +out: + + /* Release the port for re-use by other clients */ + + stm32f0_i2c_sem_post(priv); + return ret; +} +#endif /* CONFIG_I2C_RESET */ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32f0_i2cbus_initialize + * + * Description: + * Initialize one I2C bus + * + ************************************************************************************/ + +FAR struct i2c_master_s *stm32f0_i2cbus_initialize(int port) +{ + struct stm32f0_i2c_priv_s *priv = NULL; + irqstate_t flags; + +#if STM32F0_PCLK1_FREQUENCY < 4000000 +# warning STM32F0_I2C_INIT: Peripheral clock must be at least 4 MHz to support 400 kHz operation. +#endif + +#if STM32F0_PCLK1_FREQUENCY < 2000000 +# warning STM32F0_I2C_INIT: Peripheral clock must be at least 2 MHz to support 100 kHz operation. + return NULL; +#endif + + /* Get I2C private structure. */ + + switch (port) + { +#ifdef CONFIG_STM32F0_I2C1 + case 1: + priv = (struct stm32f0_i2c_priv_s *)&stm32f0_i2c1_priv; + break; +#endif +#ifdef CONFIG_STM32F0_I2C2 + case 2: + priv = (struct stm32f0_i2c_priv_s *)&stm32f0_i2c2_priv; + break; +#endif +#ifdef CONFIG_STM32F0_I2C3 + case 3: + priv = (struct stm32f0_i2c_priv_s *)&stm32f0_i2c3_priv; + break; +#endif + default: + return NULL; + } + + /* Init private data for the first time, increment refs count, + * power-up hardware and configure GPIOs. + */ + + flags = enter_critical_section(); + + if ((volatile int)priv->refs++ == 0) + { + stm32f0_i2c_sem_init(priv); + stm32f0_i2c_init(priv); + } + + leave_critical_section(flags); + return (struct i2c_master_s *)priv; +} + +/************************************************************************************ + * Name: stm32f0_i2cbus_uninitialize + * + * Description: + * Uninitialize an I2C bus + * + ************************************************************************************/ + +int stm32f0_i2cbus_uninitialize(FAR struct i2c_master_s * dev) +{ + FAR struct stm32f0_i2c_priv_s *priv = (struct stm32f0_i2c_priv_s *)dev; + irqstate_t flags; + + ASSERT(dev); + + /* Decrement refs and check for underflow */ + + if (priv->refs == 0) + { + return ERROR; + } + + flags = enter_critical_section(); + + if (--priv->refs) + { + leave_critical_section(flags); + return OK; + } + + leave_critical_section(flags); + + /* Disable power and other HW resource (GPIO's) */ + + stm32f0_i2c_deinit(priv); + + /* Release unused resources */ + + stm32f0_i2c_sem_destroy(priv); + return OK; +} + +#endif /* CONFIG_STM32F0_I2C1 || CONFIG_STM32F0_I2C2 || CONFIG_STM32F0_I2C3 */ diff --git a/arch/arm/src/stm32f0/stm32f0_i2c.h b/arch/arm/src/stm32f0/stm32f0_i2c.h new file mode 100644 index 0000000000..29bcbdccd1 --- /dev/null +++ b/arch/arm/src/stm32f0/stm32f0_i2c.h @@ -0,0 +1,104 @@ +/**************************************************************************** + * arch/arm/src/stm32f0/stm32f0_i2c.h + * + * Copyright (C) 2009, 2011, 2013 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. + * + ****************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32F0_STM32F0_I2C_H +#define __ARCH_ARM_SRC_STM32F0_STM32F0_I2C_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include "chip.h" +#include "chip/stm32f0_i2c.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* If a dynamic timeout is selected, then a non-negative, non-zero micro- + * seconds per byte value must be provided as well. + */ + +#ifdef CONFIG_STM32F0_I2C_DYNTIMEO +# if CONFIG_STM32F0_I2C_DYNTIMEO_USECPERBYTE < 1 +# warning "Ignoring CONFIG_STM32F0_I2C_DYNTIMEO because of CONFIG_STM32F0_I2C_DYNTIMEO_USECPERBYTE" +# undef CONFIG_STM32F0_I2C_DYNTIMEO +# endif +#endif + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32f0_i2cbus_initialize + * + * Description: + * Initialize the selected I2C port. And return a unique instance of struct + * struct i2c_master_s. This function may be called to obtain multiple + * instances of the interface, each of which may be set up with a + * different frequency and slave address. + * + * Input Parameter: + * Port number (for hardware that has multiple I2C interfaces) + * + * Returned Value: + * Valid I2C device structure reference on succcess; a NULL on failure + * + ****************************************************************************/ + +FAR struct i2c_master_s *stm32f0_i2cbus_initialize(int port); + +/**************************************************************************** + * Name: stm32f0_i2cbus_uninitialize + * + * Description: + * De-initialize the selected I2C port, and power down the device. + * + * Input Parameter: + * Device structure as returned by the stm32f0_i2cbus_initialize() + * + * Returned Value: + * OK on success, ERROR when internal reference count mismatch or dev + * points to invalid hardware device. + * + ****************************************************************************/ + +int stm32f0_i2cbus_uninitialize(FAR struct i2c_master_s *dev); + +#endif /* __ARCH_ARM_SRC_STM32F0_STM32F0_I2C_H */ diff --git a/configs/stm32f0discovery/include/board.h b/configs/stm32f0discovery/include/board.h index 5829650c5b..a29d0c95f9 100644 --- a/configs/stm32f0discovery/include/board.h +++ b/configs/stm32f0discovery/include/board.h @@ -239,4 +239,9 @@ #define GPIO_USART1_TX GPIO_USART1_TX_1 #define GPIO_USART1_RX GPIO_USART1_RX_1 +/* I2C pins definition */ + +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_1 +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_1 + #endif /* __CONFIG_STM32F0DISCOVERY_INCLUDE_BOARD_H */ -- GitLab From e4d47d61cc7a5500a83b177ca32e139aaaa7a1de Mon Sep 17 00:00:00 2001 From: raiden00pl Date: Sun, 30 Apr 2017 11:05:34 +0200 Subject: [PATCH 649/990] STM32F33: Add OPAMP support --- arch/arm/src/stm32/Make.defs | 4 + arch/arm/src/stm32/chip/stm32f33xxx_opamp.h | 6 +- arch/arm/src/stm32/chip/stm32f33xxx_pinmap.h | 7 +- arch/arm/src/stm32/stm32.h | 1 + arch/arm/src/stm32/stm32_opamp.c | 1418 ++++++++++++++++++ arch/arm/src/stm32/stm32_opamp.h | 231 +++ 6 files changed, 1661 insertions(+), 6 deletions(-) create mode 100644 arch/arm/src/stm32/stm32_opamp.c create mode 100644 arch/arm/src/stm32/stm32_opamp.h diff --git a/arch/arm/src/stm32/Make.defs b/arch/arm/src/stm32/Make.defs index 970ce3ba0c..3429ba88a4 100644 --- a/arch/arm/src/stm32/Make.defs +++ b/arch/arm/src/stm32/Make.defs @@ -221,6 +221,10 @@ ifeq ($(CONFIG_COMP),y) CHIP_CSRCS += stm32_comp.c endif +ifeq ($(CONFIG_OPAMP),y) +CHIP_CSRCS += stm32_opamp.c +endif + ifeq ($(CONFIG_STM32_1WIREDRIVER),y) CHIP_CSRCS += stm32_1wire.c endif diff --git a/arch/arm/src/stm32/chip/stm32f33xxx_opamp.h b/arch/arm/src/stm32/chip/stm32f33xxx_opamp.h index a6940bb055..3a254af3a8 100644 --- a/arch/arm/src/stm32/chip/stm32f33xxx_opamp.h +++ b/arch/arm/src/stm32/chip/stm32f33xxx_opamp.h @@ -54,7 +54,7 @@ /* Register Addresses *******************************************************************************/ -#define STM32_OPAMP2_CSR (STM32_OPAMP2_BASE+STM32_OPAMP2_CSR_OFFSET) +#define STM32_OPAMP2_CSR (STM32_OPAMP_BASE+STM32_OPAMP2_CSR_OFFSET) /* Register Bitfield Definitions ****************************************************/ @@ -66,7 +66,7 @@ #define OPAMP_CSR_VPSEL_SHIFT (3) /* Bits 2-3: OPAMP non inverting input selection */ #define OPAMP_CSR_VPSEL_MASK (3 << OPAMP_CSR_VPSEL_SHIFT) /* 00: Reserved */ -# define OPAMP_CSR_VPSEL_PB13 (1 << OPAMP_CSR_VPSEL_SHIFT) /* 01: PB14 */ +# define OPAMP_CSR_VPSEL_PB14 (1 << OPAMP_CSR_VPSEL_SHIFT) /* 01: PB14 */ # define OPAMP_CSR_VPSEL_PB0 (2 << OPAMP_CSR_VPSEL_SHIFT) /* 10: PB0 */ # define OPAMP_CSR_VPSEL_PA7 (3 << OPAMP_CSR_VPSEL_SHIFT) /* 11: PA7 */ /* Bit 4: Reserved */ @@ -74,7 +74,7 @@ #define OPAMP_CSR_VMSEL_MASK (3 << OPAMP_CSR_VMSEL_SHIFT) # define OPAMP_CSR_VMSEL_PC5 (0 << OPAMP_CSR_VMSEL_SHIFT) /* 00: PC5 */ # define OPAMP_CSR_VMSEL_PA5 (1 << OPAMP_CSR_VMSEL_SHIFT) /* 01: PA5 */ -# define OPAMP_CSR_VMSEL_RESISTOR (2 << OPAMP_CSR_VMSEL_SHIFT) /* 10: Resistor feedback output */ +# define OPAMP_CSR_VMSEL_PGA (2 << OPAMP_CSR_VMSEL_SHIFT) /* 10: Resistor feedback output (PGA mode)*/ # define OPAMP_CSR_VMSEL_FOLLOWER (3 << OPAMP_CSR_VMSEL_SHIFT) /* 11: Follower mode */ #define OPAMP_CSR_TCMEN (1 << 7) /* Bit 7: Timer controlled Mux mode enable */ #define OPAMP_CSR_VMSSEL (1 << 8) /* Bit 8: OPAMP inverting input secondary selection */ diff --git a/arch/arm/src/stm32/chip/stm32f33xxx_pinmap.h b/arch/arm/src/stm32/chip/stm32f33xxx_pinmap.h index b5b97c88da..e0ad65fc1a 100644 --- a/arch/arm/src/stm32/chip/stm32f33xxx_pinmap.h +++ b/arch/arm/src/stm32/chip/stm32f33xxx_pinmap.h @@ -337,9 +337,10 @@ #define GPIO_OPAMP2_VINM_1 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN5) #define GPIO_OPAMP2_VINM_2 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN5) #define GPIO_OPAMP2_VOUT (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN6) -#define GPIO_OPAMP2_VINP_1 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN7) -#define GPIO_OPAMP2_VINP_2 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN0) -#define GPIO_OPAMP2_VINP_3 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN14) +#undef GPIO_OPAMP2_VINP_1 /* not supported in F33XX */ +#define GPIO_OPAMP2_VINP_2 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN7) +#define GPIO_OPAMP2_VINP_3 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN0) +#define GPIO_OPAMP2_VINP_4 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN14) /* TSC */ diff --git a/arch/arm/src/stm32/stm32.h b/arch/arm/src/stm32/stm32.h index 534d30246c..56225ee211 100644 --- a/arch/arm/src/stm32/stm32.h +++ b/arch/arm/src/stm32/stm32.h @@ -69,6 +69,7 @@ #include "stm32_gpio.h" #include "stm32_i2c.h" #include "stm32_ltdc.h" +#include "stm32_opamp.h" #include "stm32_pwr.h" #include "stm32_rcc.h" #include "stm32_rtc.h" diff --git a/arch/arm/src/stm32/stm32_opamp.c b/arch/arm/src/stm32/stm32_opamp.c new file mode 100644 index 0000000000..e79e8ed806 --- /dev/null +++ b/arch/arm/src/stm32/stm32_opamp.c @@ -0,0 +1,1418 @@ +/**************************************************************************** + * arch/arm/src/stm32/stm32_opamp.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Mateusz Szafoni + * + * 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 "chip.h" +#include "stm32_gpio.h" +#include "stm32_opamp.h" + +/* OPAMP "upper half" support must be enabled */ + +#ifdef CONFIG_STM32_OPAMP + +/* Some OPAMP peripheral must be enabled */ +/* Up to 4 OPAMPs in STM32F3 Series */ + +#if defined(CONFIG_STM32_OPAMP1) || defined(CONFIG_STM32_OPAMP2) || \ + defined(CONFIG_STM32_OPAMP3) || defined(CONFIG_STM32_OPAMP4) + +#ifndef CONFIG_STM32_SYSCFG +# error "SYSCFG clock enable must be set" +#endif + +/* @TODO: support for STM32F30XX opamps */ + +#if defined(CONFIG_STM32_STM32F30XX) || defined(CONFIG_STM32_STM32F33XX) + +/* Currently only STM32F33XX supported */ + +#if defined(CONFIG_STM32_STM32F30XX) +# error "Not supported yet" +#endif + +#if defined(CONFIG_STM32_STM32F33XX) +# if defined(CONFIG_STM32_OPAMP1) || defined(CONFIG_STM32_OPAMP3) || \ + defined(CONFIG_STM32_OPAMP4) +# error "STM32F33 supports only OPAMP2" +# endif +#endif + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* OPAMPs default configuration *********************************************/ + +#ifdef CONFIG_STM32_OPAMP1 +# ifndef OPAMP1_MODE +# define OPAMP1_MODE OPAMP_MODE_DEFAULT +# endif +# ifndef OPAMP1_MUX +# define OPAMP1_MUX OPAMP_MUX_DEFAULT +# endif +# ifndef OPAMP1_USERCAL +# define OPAMP1_USERCAL OPAMP_USERCAL_DEFAULT +# endif +# ifndef OPAMP1_LOCK +# define OPAMP1_LOCK OPAMP_LOCK_DEFAULT +# endif +# ifndef OPAMP1_GAIN +# define OPAMP1_GAIN OPAMP_GAIN_DEFAULT +# endif +#endif +#ifdef CONFIG_STM32_OPAMP2 +# ifndef OPAMP2_MODE +# define OPAMP2_MODE OPAMP_MODE_DEFAULT +# endif +# ifndef OPAMP2_MUX +# define OPAMP2_MUX OPAMP_MUX_DEFAULT +# endif +# ifndef OPAMP2_USERCAL +# define OPAMP2_USERCAL OPAMP_USERCAL_DEFAULT +# endif +# ifndef OPAMP2_LOCK +# define OPAMP2_LOCK OPAMP_LOCK_DEFAULT +# endif +# ifndef OPAMP2_GAIN +# define OPAMP2_GAIN OPAMP_GAIN_DEFAULT +# endif +#endif +#ifdef CONFIG_STM32_OPAMP3 +# ifndef OPAMP3_MODE +# define OPAMP3_MODE OPAMP_MODE_DEFAULT +# endif +# ifndef OPAMP3_MUX +# define OPAMP3_MUX OPAMP_MUX_DEFAULT +# endif +# ifndef OPAMP3_USERCAL +# define OPAMP3_USERCAL OPAMP_USERCAL_DEFAULT +# endif +# ifndef OPAMP3_LOCK +# define OPAMP3_LOCK OPAMP_LOCK_DEFAULT +# endif +# ifndef OPAMP3_GAIN +# define OPAMP3_GAIN OPAMP_GAIN_DEFAULT +# endif +#endif +#ifdef CONFIG_STM32_OPAMP4 +# ifndef OPAMP4_MODE +# define OPAMP4_MODE OPAMP_MODE_DEFAULT +# endif +# ifndef OPAMP4_MUX +# define OPAMP4_MUX OPAMP_MUX_DEFAULT +# endif +# ifndef OPAMP4_USERCAL +# define OPAMP4_USERCAL OPAMP_USERCAL_DEFAULT +# endif +# ifndef OPAMP4_LOCK +# define OPAMP4_LOCK OPAMP_LOCK_DEFAULT +# endif +# ifndef OPAMP4_GAIN +# define OPAMP4_GAIN OPAMP_GAIN_DEFAULT +# endif +#endif + +/* Some assertions *******************************************************/ + +/* Check OPAMPs inputs selection */ + +#ifdef CONFIG_STM32_OPAMP1 +# if (OPAMP1_MODE == OPAMP_MODE_FOLLOWER) +# define OPAMP1_VMSEL OPAMP1_VMSEL_FOLLOWER +# endif +# if (OPAMP1_MODE == OPAMP_MODE_PGA) +# define OPAMP1_VMSEL OPAMP1_VMSEL_PGA +# endif +# if (OPAMP1_MODE == OPAMP_MODE_STANDALONE) +# ifndef OPAMP1_VMSEL +# error "OPAMP1_VMSEL must be selected in standalone mode!" +# endif +# endif +# ifndef OPAMP1_VPSEL +# error "OPAMP1_VPSEL must be slected in standalone mode!" +# endif +#endif +#ifdef CONFIG_STM32_OPAMP2 +# if (OPAMP2_MODE == OPAMP_MODE_FOLLOWER) +# define OPAMP2_VMSEL OPAMP2_VMSEL_FOLLOWER +# endif +# if (OPAMP2_MODE == OPAMP_MODE_PGA) +# define OPAMP2_VMSEL OPAMP2_VMSEL_PGA +# endif +# if (OPAMP2_MODE == OPAMP_MODE_STANDALONE) +# ifndef OPAMP2_VMSEL +# error "OPAMP2_VMSEL must be selected in standalone mode!" +# endif +# endif +# ifndef OPAMP2_VPSEL +# error "OPAMP2_VPSEL must be slected in standalone mode!" +# endif +#endif +#ifdef CONFIG_STM32_OPAMP3 +# if (OPAMP3_MODE == OPAMP_MODE_FOLLOWER) +# define OPAMP3_VMSEL OPAMP3_VMSEL_FOLLOWER +# endif +# if (OPAMP3_MODE == OPAMP_MODE_PGA) +# define OPAMP3_VMSEL OPAMP3_VMSEL_PGA +# endif +# if (OPAMP3_MODE == OPAMP_MODE_STANDALONE) +# ifndef OPAMP3_VMSEL +# error "OPAMP3_VMSEL must be selected in standalone mode!" +# endif +# endif +# ifndef OPAMP3_VPSEL +# error "OPAMP3_VPSEL must be slected in standalone mode!" +# endif +#endif +#ifdef CONFIG_STM32_OPAMP4 +# if (OPAMP4_MODE == OPAMP_MODE_FOLLOWER) +# define OPAMP4_VMSEL OPAMP4_VMSEL_FOLLOWER +# endif +# if (OPAMP4_MODE == OPAMP_MODE_PGA) +# define OPAMP4_VMSEL OPAMP4_VMSEL_PGA +# endif +# if (OPAMP4_MODE == OPAMP_MODE_STANDALONE) +# ifndef OPAMP4_VMSEL +# error "OPAMP4_VMSEL must be selected in standalone mode!" +# endif +# endif +# ifndef OPAMP4_VPSEL +# error "OPAMP4_VPSEL must be slected in standalone mode!" +# endif +#endif + +/* When OPAMP MUX enabled, make sure that secondary selection inputs are configured */ + +#ifdef CONFIG_STM32_OPAMP1 +# if (OPAMP1_MUX == OPAMP_MUX_ENABLE) +# if !defined(OPAMP1_VMSSEL) || !defined(OPAMP1_VPSSEL) +# error "OPAMP1_VMSSEL and OPAMP1_VPSSEL must be selected when OPAMP1 MUX enabled!" +# endif +# endif +#endif +#ifdef CONFIG_STM32_OPAMP2 +# if (OPAMP2_MUX == OPAMP_MUX_ENABLE) +# if !defined(OPAMP2_VMSSEL) || !defined(OPAMP2_VPSSEL) +# error "OPAMP2_VMSSEL and OPAMP2_VPSSEL must be selected when OPAMP2 MUX enabled!" +# endif +# endif +#endif +#ifdef CONFIG_STM32_OPAMP3 +# if (OPAMP3_MUX == OPAMP_MUX_ENABLE) +# if !defined(OPAMP3_VMSSEL) || !defined(OPAMP3_VPSSEL) +# error "OPAMP3_VMSSEL and OPAMP3_VPSSEL must be selected when OPAMP3 MUX enabled!" +# endif +# endif +#endif +#ifdef CONFIG_STM32_OPAMP4 +# if (OPAMP4_MUX == OPAMP_MUX_ENABLE) +# if !defined(OPAMP4_VMSSEL) || !defined(OPAMP4_VPSSEL) +# error "OPAMP4_VMSSEL and OPAMP4_VPSSEL must be selected when OPAMP4 MUX enabled!" +# endif +# endif +#endif + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/* This structure describes the configuration of one OPAMP device */ + +struct stm32_opamp_s +{ + uint32_t csr; /* Control and status register */ + + uint8_t lock:1; /* OPAMP lock */ + uint8_t mux:1; /* Timer controlled MUX mode */ + uint8_t mode:2; /* OPAMP mode */ + uint8_t gain:4; /* OPAMP gain in PGA mode */ + + uint8_t vm_sel:2; /* Inverting input selection */ + uint8_t vp_sel:2; /* Non inverting input selection */ + uint8_t vms_sel:2; /* Inverting input secondary selection (MUX mode) */ + uint8_t vps_sel:2; /* Non inverting input secondary selection (Mux mode) */ + + uint16_t trim_n:5; /* Offset trimming value (NMOS) */ + uint16_t trim_p:5; /* Offset trimming value (PMOS) */ + uint16_t _reserved:6; /* reserved for calibration */ +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* OPAMP Register access */ + +static inline void opamp_modify_csr(FAR struct stm32_opamp_s *priv, + uint32_t clearbits, uint32_t setbits); +static inline uint32_t opamp_getreg_csr(FAR struct stm32_opamp_s* priv); +static inline void opamp_putreg_csr(FAR struct stm32_opamp_s* priv, + uint32_t value); +static bool stm32_opamplock_get(FAR struct stm32_opamp_s *priv); +static int stm32_opamplock(FAR struct stm32_opamp_s *priv, bool lock); + +/* Initialization */ + +static int stm32_opampconfig(FAR struct stm32_opamp_s *priv); +static int stm32_opampenable(FAR struct stm32_opamp_s *priv, bool enable); +static int stm32_opampgain_set(FAR struct stm32_opamp_s *priv, uint8_t gain); +#if 0 +static int stm32_opampcalibrate(FAR struct stm32_opamp_s *priv); +#endif + +/* OPAMP Driver Methods */ + +static void opamp_shutdown(FAR struct opamp_dev_s *dev); +static int opamp_setup(FAR struct opamp_dev_s *dev); +static int opamp_ioctl(FAR struct opamp_dev_s *dev, int cmd, unsigned long arg); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const struct opamp_ops_s g_opampops = +{ + .ao_shutdown = opamp_shutdown, + .ao_setup = opamp_setup, + .ao_ioctl = opamp_ioctl +}; + +#ifdef CONFIG_STM32_OPAMP1 +static struct stm32_opamp_s g_opamp1priv = +{ + .csr = STM32_OPAMP1_CSR, + .lock = OPAMP1_LOCK, + .mux = OPAMP1_MUX, + .mode = OPAMP1_MODE, + .vm_sel = OPAMP1_VMSEL, + .vp_sel = OPAMP1_VPSEL, +#if OPAMP1_MUX == OPAMP_MUX_ENABLE + .vms_sel = OPAMP1_VMSSEL, + .vps_sel = OPAMP1_VPSSEL, +#endif + .gain = OPAMP1_GAIN +}; + +static struct opamp_dev_s g_opamp1dev = +{ + .ad_ops = &g_opampops, + .ad_priv = &g_opamp1priv +}; +#endif + +#ifdef CONFIG_STM32_OPAMP2 +static struct stm32_opamp_s g_opamp2priv = +{ + .csr = STM32_OPAMP2_CSR, + .lock = OPAMP2_LOCK, + .mux = OPAMP2_MUX, + .mode = OPAMP2_MODE, + .vm_sel = OPAMP2_VMSEL, + .vp_sel = OPAMP2_VPSEL, +#if OPAMP2_MUX == OPAMP_MUX_ENABLE + .vms_sel = OPAMP2_VMSSEL, + .vps_sel = OPAMP2_VPSSEL, +#endif + .gain = OPAMP2_GAIN +}; + +static struct opamp_dev_s g_opamp2dev = + { + .ad_ops = &g_opampops, + .ad_priv = &g_opamp2priv + }; +#endif + +#ifdef CONFIG_STM32_OPAMP3 +static struct stm32_opamp_s g_opamp3priv = +{ + .csr = STM32_OPAMP3_CSR, + .lock = OPAMP3_LOCK, + .mux = OPAMP3_MUX, + .mode = OPAMP3_MODE, + .vm_sel = OPAMP3_VMSEL, + .vp_sel = OPAMP3_VPSEL, +#if OPAMP3_MUX == OPAMP_MUX_ENABLE + .vms_sel = OPAMP3_VMSSEL, + .vps_sel = OPAMP3_VPSSEL, +#endif + .gain = OPAMP3_GAIN +}; + +static struct opamp_dev_s g_opamp3dev = +{ + .ad_ops = &g_opampops, + .ad_priv = &g_opamp3priv +}; +#endif + +#ifdef CONFIG_STM32_OPAMP4 +static struct stm32_opamp_s g_opamp4priv = +{ + .csr = STM32_OPAMP4_CSR, + .lock = OPAMP4_LOCK, + .mux = OPAMP4_MUX, + .mode = OPAMP4_MODE, + .vm_sel = OPAMP4_VMSEL, + .vp_sel = OPAMP4_VPSEL, +#if OPAMP4_MUX == OPAMP_MUX_ENABLE + .vms_sel = OPAMP4_VMSSEL, + .vps_sel = OPAMP4_VPSSEL, +#endif + .gain = OPAMP4_GAIN +}; + +static struct opamp_dev_s g_opamp4dev = +{ + .ad_ops = &g_opampops, + .ad_priv = &g_opamp4priv +}; +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: opamp_modify_csr + * + * Description: + * Modify the value of a 32-bit OPAMP CSR register (not atomic). + * + * Input Parameters: + * priv - A reference to the OPAMP structure + * clrbits - The bits to clear + * setbits - The bits to set + * + * Returned Value: + * None + * + ****************************************************************************/ + +static inline void opamp_modify_csr(FAR struct stm32_opamp_s *priv, + uint32_t clearbits, uint32_t setbits) +{ + uint32_t csr = priv->csr; + + modifyreg32(csr, clearbits, setbits); +} + +/**************************************************************************** + * Name: opamp_getreg_csr + * + * Description: + * Read the value of an OPAMP CSR register + * + * Input Parameters: + * priv - A reference to the OPAMP structure + * + * Returned Value: + * The current contents of the OPAMP CSR register + * + ****************************************************************************/ + +static inline uint32_t opamp_getreg_csr(FAR struct stm32_opamp_s *priv) +{ + uint32_t csr = priv->csr; + + return getreg32(csr); +} + +/**************************************************************************** + * Name: opamp_putreg_csr + * + * Description: + * Write a value to an OPAMP register. + * + * Input Parameters: + * priv - A reference to the OPAMP structure + * value - The value to write to the OPAMP CSR register + * + * Returned Value: + * None + * + ****************************************************************************/ + +static inline void opamp_putreg_csr(FAR struct stm32_opamp_s *priv, + uint32_t value) +{ + uint32_t csr = priv->csr; + + putreg32(value, csr); +} + +/**************************************************************************** + * Name: stm32_opamp_opamplock_get + * + * Description: + * Get OPAMP lock bit state + * + * Input Parameters: + * priv - A reference to the OPAMP structure + * + * Returned Value: + * True if OPAMP locked, false if not locked + * + ****************************************************************************/ + +static bool stm32_opamplock_get(FAR struct stm32_opamp_s *priv) +{ + uint32_t regval; + + regval = opamp_getreg_csr(priv); + + return (((regval & OPAMP_CSR_LOCK) == 0) ? false : true); +} + +/**************************************************************************** + * Name: stm32_opamplock + * + * Description: + * Lock OPAMP CSR register + * + * Input Parameters: + * priv - A reference to the OPAMP structure + * enable - lock flag + * + * Returned Value: + * 0 on success, a negated errno value on failure + * + ****************************************************************************/ + +static int stm32_opamplock(FAR struct stm32_opamp_s *priv, bool lock) +{ + bool current; + + current = stm32_opamplock_get(priv); + + if (current) + { + if (lock == false) + { + aerr("ERROR: OPAMP LOCK can be cleared only by a system reset\n"); + + return -EPERM; + } + } + else + { + if (lock == true) + { + opamp_modify_csr(priv, 0, OPAMP_CSR_LOCK); + + priv->lock = OPAMP_LOCK_RO; + } + } + + return OK; +} + +/**************************************************************************** + * Name: stm32_opampconfig + * + * Description: + * Configure OPAMP and used I/Os + * + * Input Parameters: + * priv - A reference to the OPAMP structure + * + * Returned Value: + * 0 on success, a negated errno value on failure + * + ****************************************************************************/ + +static int stm32_opampconfig(FAR struct stm32_opamp_s *priv) +{ + uint32_t regval = 0; + int index; + + /* Get OPAMP index */ + + switch (priv->csr) + { +#ifdef CONFIG_STM32_OPAMP1 + case STM32_OPAMP1_CSR: + index = 1; + break; +#endif + +#ifdef CONFIG_STM32_OPAMP2 + case STM32_OPAMP2_CSR: + index = 2; + break; +#endif + +#ifdef CONFIG_STM32_OPAMP3 + case STM32_OPAMP3_CSR: + index = 3; + break; +#endif + +#ifdef CONFIG_STM32_OPAMP4 + case STM32_OPAMP4_CSR: + index = 4; + break; +#endif + + default: + return -EINVAL; + } + + /* Configure non inverting input */ + + switch (index) + { +#ifdef CONFIG_STM32_OPAMP1 + case 1: + { + switch (priv->vp_sel) + { + case OPAMP1_VPSEL_PA7: + stm32_configgpio(GPIO_OPAMP1_VINP_1); + regval |= OPAMP_CSR_VPSEL_PA7; + break; + + case OPAMP1_VPSEL_PA5: + stm32_configgpio(GPIO_OPAMP1_VINP_2); + regval |= OPAMP_CSR_VPSEL_PA5; + break; + + case OPAMP1_VPSEL_PA3: + stm32_configgpio(GPIO_OPAMP1_VINP_3); + regval |= OPAMP_CSR_VPSEL_PA3; + break; + + case OPAMP1_VPSEL_PA1: + stm32_configgpio(GPIO_OPAMP1_VINP_4); + regval |= OPAMP_CSR_VPSEL_PA1; + break; + + default: + return -EINVAL; + } + break; + } +#endif + +#ifdef CONFIG_STM32_OPAMP2 + case 2: + { + switch (priv->vp_sel) + { +#ifndef CONFIG_STM32_STM32F33XX + case OPAMP2_VPSEL_PD14: + stm32_configgpio(GPIO_OPAMP2_VINP_1); + regval |= OPAMP_CSR_VPSEL_PD14; + break; +#endif + case OPAMP2_VPSEL_PB14: + stm32_configgpio(GPIO_OPAMP2_VINP_2); + regval |= OPAMP_CSR_VPSEL_PB14; + break; + + case OPAMP2_VPSEL_PB0: + stm32_configgpio(GPIO_OPAMP2_VINP_3); + regval |= OPAMP_CSR_VPSEL_PB0; + break; + + case OPAMP2_VPSEL_PA7: + stm32_configgpio(GPIO_OPAMP2_VINP_4); + regval |= OPAMP_CSR_VPSEL_PA7; + break; + + default: + return -EINVAL; + } + break; + } +#endif + +#ifdef CONFIG_STM32_OPAMP3 + case 3: + { + switch (priv->vp_sel) + { + case OPAMP3_VPSEL_PB13: + stm32_configgpio(GPIO_OPAMP3_VINP_1); + regval |= OPAMP_CSR_VPSEL_PB13; + break; + + case OPAMP3_VPSEL_PA5: + stm32_configgpio(GPIO_OPAMP3_VINP_2); + regval |= OPAMP_CSR_VPSEL_PA5; + break; + + case OPAMP3_VPSEL_PA1: + stm32_configgpio(GPIO_OPAMP3_VINP_3); + regval |= OPAMP_CSR_VPSEL_PA1; + break; + + case OPAMP3_VPSEL_PB0: + stm32_configgpio(GPIO_OPAMP3_VINP_4); + regval |= OPAMP_CSR_VPSEL_PB0; + break; + + default: + return -EINVAL; + } + break; + } +#endif + +#ifdef CONFIG_STM32_OPAMP4 + case 4: + { + switch (priv->vp_sel) + { + case OPAMP4_VPSEL_PD11: + stm32_configgpio(GPIO_OPAMP4_VINP_1); + regval |= OPAMP_CSR_VPSEL_PD11; + break; + + case OPAMP4_VPSEL_PB11: + stm32_configgpio(GPIO_OPAMP4_VINP_2); + regval |= OPAMP_CSR_VPSEL_PB11; + break; + + case OPAMP4_VPSEL_PA4: + stm32_configgpio(GPIO_OPAMP4_VINP_3); + regval |= OPAMP_CSR_VPSEL_PA4; + break; + + case OPAMP4_VPSEL_PB13: + stm32_configgpio(GPIO_OPAMP4_VINP_4; + regval |= OPAMP_CSR_VPSEL_PB13; + break; + + default: + return -EINVAL; + } + break; + } +#endif + + default: + return -EINVAL; + } + + /* Configure inverting input */ + + switch (index) + { +#ifdef CONFIG_STM32_OPAMP1 + case 1: + { + switch (priv->vm_sel) + { + case OPAMP1_VSEL_PC5: + stm32_configgpio(GPIO_OPAMP1_VINM_1); + regval |= OPAMP_CSR_VMSEL_PC5; + break; + + case OPAMP1_VMSEL_PA3: + stm32_configgpio(GPIO_OPAMP1_VINM_2); + regval |= OPAMP_CSR_VMSEL_PA3; + break; + + case OPAMP1_VMSEL_PGAMODE: + regval |= OPAMP_CSR_VMSEL_PGA; + break; + + case OPAMP1_VMSEL_FOLLOWER: + regval |= OPAMP_CSR_VMSEL_FOLLOWER; + break; + + default: + return -EINVAL; + } + break; + } +#endif + +#ifdef CONFIG_STM32_OPAMP2 + case 2: + { + switch (priv->vm_sel) + { + case OPAMP2_VMSEL_PC5: + stm32_configgpio(GPIO_OPAMP2_VINM_1); + regval |= OPAMP_CSR_VMSEL_PC5; + break; + + case OPAMP2_VMSEL_PA5: + stm32_configgpio(GPIO_OPAMP2_VINM_2); + regval |= OPAMP_CSR_VMSEL_PA5; + break; + + case OPAMP2_VMSEL_PGAMODE: + regval |= OPAMP_CSR_VMSEL_PGA; + break; + + case OPAMP2_VMSEL_FOLLOWER: + regval |= OPAMP_CSR_VMSEL_FOLLOWER; + break; + + default: + return -EINVAL; + } + break; + } +#endif + +#ifdef CONFIG_STM32_OPAMP3 + case 3: + { + switch (priv->vm_sel) + { + case OPAMP3_VMSEL_PB10: + stm32_configgpio(GPIO_OPAMP3_VINM_1); + regval |= OPAMP_CSR_VMSEL_PB10; + break; + + case OPAMP3_VMSEL_PB2: + stm32_configgpio(GPIO_OPAMP3_VINM_2); + regval |= OPAMP_CSR_VMSEL_PB2; + break; + + case OPAMP3_VMSEL_PGAMODE: + regval |= OPAMP_CSR_VMSEL_PGA; + break; + + case OPAMP3_VMSEL_FOLLOWER: + regval |= OPAMP_CSR_VMSEL_FOLLOWER; + break; + + default: + return -EINVAL; + } + break; + } +#endif + +#ifdef CONFIG_STM32_OPAMP4 + case 4: + { + switch (priv->vm_sel) + { + case OPAMP4_VMSEL_PB10: + stm32_configgpio(GPIO_OPAMP4_VINM_1); + regval |= OPAMP_CSR_VMSEL_PB10; + break; + + case OPAMP4_VMSEL_PD8: + stm32_configgpio(GPIO_OPAMP4_VINM_2); + regval |= OPAMP_CSR_VMSEL_PD8; + break; + + case OPAMP4_VMSEL_PGAMODE: + regval |= OPAMP_CSR_VMSEL_PGA; + break; + + case OPAMP4_VMSEL_FOLLOWER: + regval |= OPAMP_CSR_VMSEL_FOLLOWER; + break; + + default: + return -EINVAL; + } + break; + } +#endif + + default: + return -EINVAL; + } + + if (priv->mux == 1) + { + /* Enable Timer controled Mux mode */ + + regval |= OPAMP_CSR_TCMEN; + + /* Configure non inverting secondary input */ + + switch (index) + { +#ifdef CONFIG_STM32_OPAMP1 + case 1: + { + switch (priv->vps_sel) + { + case OPAMP1_VPSEL_PA7: + stm32_configgpio(GPIO_OPAMP1_VINP_1); + regval |= OPAMP_CSR_VPSSEL_PA7; + break; + + case OPAMP1_VPSEL_PA5: + stm32_configgpio(GPIO_OPAMP1_VINP_2); + regval |= OPAMP_CSR_VPSSEL_PA5; + break; + + case OPAMP1_VPSEL_PA3: + stm32_configgpio(GPIO_OPAMP1_VINP_3); + regval |= OPAMP_CSR_VPSSEL_PA3; + break; + + case OPAMP1_VPSEL_PA1: + stm32_configgpio(GPIO_OPAMP1_VINP_4); + regval |= OPAMP_CSR_VPSSEL_PA1; + break; + + default: + return -EINVAL; + } + break; + } +#endif + +#ifdef CONFIG_STM32_OPAMP2 + case 2: + { + switch (priv->vps_sel) + { +#ifndef CONFIG_STM32_STM32F33XX + case OPAMP2_VPSEL_PD14: + stm32_configgpio(GPIO_OPAMP2_VINP_1); + regval |= OPAMP_CSR_VPSSEL_PD14; + break; +#endif + case OPAMP2_VPSEL_PB14: + stm32_configgpio(GPIO_OPAMP2_VINP_2); + regval |= OPAMP_CSR_VPSSEL_PB14; + break; + + case OPAMP2_VPSEL_PB0: + stm32_configgpio(GPIO_OPAMP2_VINP_3); + regval |= OPAMP_CSR_VPSSEL_PB0; + break; + + case OPAMP2_VPSEL_PA7: + stm32_configgpio(GPIO_OPAMP2_VINP_4); + regval |= OPAMP_CSR_VPSSEL_PA7; + break; + + default: + return -EINVAL; + } + break; + } +#endif + +#ifdef CONFIG_STM32_OPAMP3 + case 3: + { + switch (priv->vps_sel) + { + case OPAMP3_VPSEL_PB13: + stm32_configgpio(GPIO_OPAMP3_VINP_1); + regval |= OPAMP_CSR_VPSSEL_PB13; + break; + + case OPAMP3_VPSEL_PA5: + stm32_configgpio(GPIO_OPAMP3_VINP_2); + regval |= OPAMP_CSR_VPSSEL_PA5; + break; + + case OPAMP3_VPSEL_PA1: + stm32_configgpio(GPIO_OPAMP3_VINP_3); + regval |= OPAMP_CSR_VPSSEL_PA1; + break; + + case OPAMP3_VPSEL_PB0: + stm32_configgpio(GPIO_OPAMP3_VINP_4); + regval |= OPAMP_CSR_VPSSEL_PB0; + break; + + default: + return -EINVAL; + } + break; + } +#endif + +#ifdef CONFIG_STM32_OPAMP4 + case 4: + { + switch (priv->vps_sel) + { + case OPAMP4_VPSEL_PD11: + stm32_configgpio(GPIO_OPAMP4_VINP_1); + regval |= OPAMP_CSR_VPSSEL_PD11; + break; + + case OPAMP4_VPSEL_PB11: + stm32_configgpio(GPIO_OPAMP4_VINP_2); + regval |= OPAMP_CSR_VPSSEL_PB11; + break; + + case OPAMP4_VPSEL_PA4: + stm32_configgpio(GPIO_OPAMP4_VINP_3); + regval |= OPAMP_CSR_VPSSEL_PA4; + break; + + case OPAMP4_VPSEL_PB13: + stm32_configgpio(GPIO_OPAMP4_VINP_4); + regval |= OPAMP_CSR_VPSSEL_PB13; + break; + + default: + return -EINVAL; + } + break; + } +#endif + + default: + return -EINVAL; + } + + /* Configure inverting secondary input */ + + switch (index) + { +#ifdef CONFIG_STM32_OPAMP1 + case 1: + { + switch (priv->vms_sel) + { + case OPAMP1_VSEL_PC5: + stm32_configgpio(GPIO_OPAMP1_VINM_1); + regval &= ~OPAMP_CSR_VMSSEL; + break; + + case OPAMP1_VMSEL_PA3: + stm32_configgpio(GPIO_OPAMP1_VINM_2); + regval |= OPAMP_CSR_VMSSEL; + break; + + default: + return -EINVAL; + } + break; + } +#endif + +#ifdef CONFIG_STM32_OPAMP2 + case 2: + { + switch (priv->vms_sel) + { + case OPAMP2_VMSEL_PC5: + stm32_configgpio(GPIO_OPAMP2_VINM_1); + regval &= ~OPAMP_CSR_VMSSEL; + break; + + case OPAMP2_VMSEL_PA5: + stm32_configgpio(GPIO_OPAMP2_VINM_2); + regval |= OPAMP_CSR_VMSSEL; + break; + + default: + return -EINVAL; + } + break; + } +#endif + +#ifdef CONFIG_STM32_OPAMP3 + case 3: + { + switch (priv->vms_sel) + { + case OPAMP3_VMSEL_PB10: + stm32_configgpio(GPIO_OPAMP3_VINM_1); + regval &= ~OPAMP_CSR_VMSSEL; + break; + + case OPAMP3_VMSEL_PB2: + stm32_configgpio(GPIO_OPAMP3_VINM_2); + regval |= OPAMP_CSR_VMSSEL; + break; + + default: + return -EINVAL; + } + break; + } +#endif + +#ifdef CONFIG_STM32_OPAMP4 + case 4: + { + switch (priv->vms_sel) + { + case OPAMP4_VMSEL_PB10: + stm32_configgpio(GPIO_OPAMP4_VINM_1); + regval &= ~OPAMP_CSR_VMSSEL; + break; + + case OPAMP4_VMSEL_PD8: + stm32_configgpio(GPIO_OPAMP4_VINM_2); + regval |= OPAMP_CSR_VMSSEL; + break; + + default: + return -EINVAL; + } + break; + } +#endif + + default: + return -EINVAL; + } + } + + /* Save CSR register */ + + opamp_putreg_csr(priv, regval); + + /* Configure defaul gain in PGA mode */ + + stm32_opampgain_set(priv, priv->gain); + + /* Enable OPAMP */ + + stm32_opampenable(priv, true); + + /* TODO: OPAMP user calibration */ + /* stm32_opampcalibrate(priv); */ + + + /* Lock OPAMP if needed */ + + if (priv->lock == OPAMP_LOCK_RO) + { + stm32_opamplock(priv, true); + } + + return OK; +} + +/**************************************************************************** + * Name: stm32_opampenable + * + * Description: + * Enable/disable OPAMP + * + * Input Parameters: + * priv - A reference to the OPAMP structure + * enable - enable/disable flag + * + * Returned Value: + * 0 on success, a negated errno value on failure + * + ****************************************************************************/ + +static int stm32_opampenable(FAR struct stm32_opamp_s *priv, bool enable) +{ + bool lock; + + ainfo("enable: %d\n", enable ? 1 : 0); + + lock = stm32_opamplock_get(priv); + + if (lock) + { + aerr("ERROR: OPAMP locked!\n"); + + return -EPERM; + } + else + { + if (enable) + { + /* Enable the OPAMP */ + + opamp_modify_csr(priv, 0, OPAMP_CSR_OPAMPEN); + } + else + { + /* Disable the OPAMP */ + + opamp_modify_csr(priv, OPAMP_CSR_OPAMPEN, 0); + } + } + + return OK; +} + +/**************************************************************************** + * Name: stm32_opampgain_set + * + * Description: + * Set OPAMP gain + * + * Input Parameters: + * priv - A reference to the OPAMP structure + * gain - OPAMP gain + * + * Returned Value: + * 0 on success, a negated errno value on failure + * + ****************************************************************************/ + +static int stm32_opampgain_set(FAR struct stm32_opamp_s *priv, uint8_t gain) +{ + bool lock; + uint32_t regval = 0; + + lock = stm32_opamplock_get(priv); + + if (lock) + { + aerr("ERROR: OPAMP locked!\n"); + return -EPERM; + } + + regval = opamp_getreg_csr(priv); + + switch (gain) + { + case OPAMP_GAIN_2: + regval |= OPAMP_CSR_PGAGAIN_2; + break; + case OPAMP_GAIN_4: + regval |= OPAMP_CSR_PGAGAIN_4; + break; + case OPAMP_GAIN_8: + regval |= OPAMP_CSR_PGAGAIN_8; + break; + case OPAMP_GAIN_2_VM0: + regval |= OPAMP_CSR_PGAGAIN_2VM0; + break; + case OPAMP_GAIN_4_VM0: + regval |= OPAMP_CSR_PGAGAIN_4VM0; + break; + case OPAMP_GAIN_8_VM0: + regval |= OPAMP_CSR_PGAGAIN_8VM0; + break; + case OPAMP_GAIN_16_VM0: + regval |= OPAMP_CSR_PGAGAIN_16VM0; + break; + case OPAMP_GAIN_2_VM1: + regval |= OPAMP_CSR_PGAGAIN_2VM1; + break; + case OPAMP_GAIN_4_VM1: + regval |= OPAMP_CSR_PGAGAIN_4VM1; + break; + case OPAMP_GAIN_8_VM1: + regval |= OPAMP_CSR_PGAGAIN_8VM1; + break; + case OPAMP_GAIN_16_VM1: + regval |= OPAMP_CSR_PGAGAIN_16VM1; + break; + default: + aerr("ERROR: Unsupported OPAMP gain\n"); + return -EINVAL; + } + + /* Update gain in OPAMP device structure */ + + priv->gain = gain; + + return OK; + +} + +#if 0 +static int stm32_opampcalibrate(FAR struct stm32_opamp_s *priv) +{ +#warning "Missing logic" + return OK; +} +#endif + +/**************************************************************************** + * Name: opamp_shutdown + * + * Description: + * Disable the OPAMP. This method is called when the OPAMP device is closed. + * This method reverses the operation the setup method. + * Works only if OPAMP device is not locked. + * + * Input Parameters: + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void opamp_shutdown(FAR struct opamp_dev_s *dev) +{ +#warning "Missing logic" +} + +/**************************************************************************** + * Name: opamp_setup + * + * Description: + * Configure the OPAMP. This method is called the first time that the OPAMP + * device is opened. This will occur when the port is first opened. + * This setup includes configuring and attaching OPAMP interrupts. + * Interrupts are all disabled upon return. + * + * Input Parameters: + * + * Returned Value: + * + ****************************************************************************/ + +static int opamp_setup(FAR struct opamp_dev_s *dev) +{ +#warning "Missing logic" + return OK; +} + +/**************************************************************************** + * Name: opamp_ioctl + * + * Description: + * All ioctl calls will be routed through this method. + * + * Input Parameters: + * dev - pointer to device structure used by the driver + * cmd - command + * arg - arguments passed with command + * + * Returned Value: + * + ****************************************************************************/ + +static int opamp_ioctl(FAR struct opamp_dev_s* dev, int cmd, unsigned long arg) +{ +#warning "Missing logic" + return -ENOTTY; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_opampinitialize + * + * Description: + * Initialize the OPAMP. + * + * Input Parameters: + * intf - The OPAMP interface number. + * + * Returned Value: + * Valid OPAMP device structure reference on succcess; a NULL on failure. + * + * Assumptions: + * 1. Clock to the OPAMP block has enabled, + * 2. Board-specific logic has already configured + * + ****************************************************************************/ + +FAR struct opamp_dev_s* stm32_opampinitialize(int intf) +{ + FAR struct opamp_dev_s *dev; + FAR struct stm32_opamp_s *opamp; + int ret; + + switch (intf) + { +#ifdef CONFIG_STM32_OPAMP1 + case 1: + ainfo("OPAMP1 selected\n"); + dev = &g_opamp1dev; + break; +#endif + +#ifdef CONFIG_STM32_OPAMP2 + case 2: + ainfo("OPAMP2 selected\n"); + dev = &g_opamp2dev; + break; +#endif + +#ifdef CONFIG_STM32_OPAMP3 + case 3: + ainfo("OPAMP3 selected\n"); + dev = &g_opamp3dev; + break; +#endif + +#ifdef CONFIG_STM32_OPAMP4 + case 4: + ainfo("OPAMP4 selected\n"); + dev = &g_opamp4dev; + break; +#endif + + default: + aerr("ERROR: No OPAMP interface defined\n"); + return NULL; + } + + /* Configure selected OPAMP */ + + opamp = dev->ad_priv; + + ret = stm32_opampconfig(opamp); + if (ret < 0) + { + aerr("ERROR: Failed to initialize OPAMP%d: %d\n", intf, ret); + errno = -ret; + return NULL; + } + + return dev; +} + +#endif /* CONFIG_STM32_STM32F30XX || CONFIG_STM32_STM32F33XX*/ + +#endif /* CONFIG_STM32_OPAMP1 || CONFIG_STM32_OPAMP2 || + * CONFIG_STM32_OPAMP3 || CONFIG_STM32_OPAMP4 + */ + +#endif /* CONFIG_STM32_OPAMP */ diff --git a/arch/arm/src/stm32/stm32_opamp.h b/arch/arm/src/stm32/stm32_opamp.h new file mode 100644 index 0000000000..94af6990f9 --- /dev/null +++ b/arch/arm/src/stm32/stm32_opamp.h @@ -0,0 +1,231 @@ +/************************************************************************************ + * arch/arm/src/stm32/stm32_opamp.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Mateusz Szafoni + * + * 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 __ARCH_ARM_SRC_STM32_STM32_OPAMP_H +#define __ARCH_ARM_SRC_STM32_STM32_OPAMP_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include "chip.h" + +#ifdef CONFIG_STM32_OPAMP + +#if defined(CONFIG_STM32_STM32F30XX) +# error "OPAMP support for STM32F30XX not implemented yet" +#elif defined(CONFIG_STM32_STM32F33XX) +# include "chip/stm32f33xxx_opamp.h" +#endif + +#include + +/************************************************************************************ + * Pre-processor definitions + ************************************************************************************/ + +/* OPAMP operation mode */ + +#define OPAMP_MODE_STANDALONE 0 +#define OPAMP_MODE_FOLLOWER 1 +#define OPAMP_MODE_PGA 2 + +/* Timer controlled Mux mode */ + +#define OPAMP_MUX_DISABLE 0 +#define OPAMP_MUX_ENABLE 1 + +/* User callibration */ + +#define OPAMP_USERCAL_DISABLE 0 +#define OPAMP_USERCAL_ENABLE 1 + +/* Default configuration */ + +#define OPAMP_MODE_DEFAULT OPAMP_MODE_STANDALONE /* Standalone mode */ +#define OPAMP_MUX_DEFAULT OPAMP_MUX_DISABLE /* MUX disabled */ +#define OPAMP_USERCAL_DEFAULT OPAMP_USERCAL_DISABLE /* User calibration disabled */ +#define OPAMP_GAIN_DEFAULT OPAMP_GAIN_2 /* Gain in PGA mode = 2 */ +#define OPAMP_LOCK_DEFAULT OPAMP_LOCK_RW /* Do not lock CSR register */ + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/* CSR register lock state */ + +enum stm32_opamp_lock_e +{ + OPAMP_LOCK_RW, + OPAMP_LOCK_RO +}; + +/* Gain in PGA mode */ + +enum stm32_opamp_gain_e +{ + OPAMP_GAIN_2, + OPAMP_GAIN_4, + OPAMP_GAIN_8, + OPAMP_GAIN_2_VM0, + OPAMP_GAIN_4_VM0, + OPAMP_GAIN_8_VM0, + OPAMP_GAIN_16_VM0, + OPAMP_GAIN_2_VM1, + OPAMP_GAIN_4_VM1, + OPAMP_GAIN_8_VM1, + OPAMP_GAIN_16_VM1 +}; + +/* Input selection and secondary input selection use the same GPIOs */ + +#ifdef CONFIG_STM32_OPAMP1 +enum stm32_opamp1_vpsel_e +{ + OPAMP1_VPSEL_PA7, + OPAMP1_VPSEL_PA5, + OPAMP1_VPSEL_PA3, + OPAMP1_VPSEL_PA1 +}; + +enum stm32_opamp1_vmsel_e +{ + OPAMP1_VMSEL_PC5, + OPAMP1_VMSEL_PA3, + OPAMP1_VMSEL_PGAMODE, + OPAMP1_VMSEL_FOLLOWER, +}; +#endif + +#ifdef CONFIG_STM32_OPAMP2 +enum stm32_opamp2_vpsel_e +{ +#ifndef CONFIG_STM32_STM32F33XX + /* TODO: STM32F303xB/C and STM32F358C devices only */ + OPAMP2_VPSEL_PD14, +#endif + OPAMP2_VPSEL_PB14, + OPAMP2_VPSEL_PB0, + OPAMP2_VPSEL_PA7 +}; + +enum stm32_opamp2_vmsel_e +{ + OPAMP2_VMSEL_PC5, + OPAMP2_VMSEL_PA5, + OPAMP2_VMSEL_PGAMODE, + OPAMP2_VMSEL_FOLLOWER +}; +#endif + +#ifdef CONFIG_STM32_OPAMP3 +enum stm32_opamp3_vpsel_e +{ + OPAMP3_VPSEL_PB13, + OPAMP3_VPSEL_PA5, + OPAMP3_VPSEL_PA1, + OPAMP3_VPSEL_PB0 +}; + +enum stm32_opamp3_vmsel_e +{ + OPAMP3_VMSEL_PB10, + OPAMP3_VMSEL_PB2, + OPAMP3_VMSEL_PGAMODE, + OPAMP3_VMSEL_FOLLOWER +}; +#endif + +#ifdef CONFIG_STM32_OPAMP4 +enum stm32_opamp4_vpsel_e +{ + OPAMP4_VPSEL_PD11, + OPAMP4_VPSEL_PB11, + OPAMP4_VPSEL_PA4, + OPAMP4_VPSEL_PB13 +}; + +enum stm32_opamp4_vmsel_e +{ + OPAMP4_VMSEL_PB10, + OPAMP4_VMSEL_PD8, + OPAMP4_VMSEL_PGAMODE, + OPAMP4_VMSEL_FOLLOWER +}; +#endif + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +#ifndef __ASSEMBLY__ +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/**************************************************************************** +* Name: stm32_opampinitialize +* +* Description: +* Initialize the OPAMP. +* +* Input Parameters: +* intf - The OPAMP interface number. +* +* Returned Value: +* Valid OPAMP device structure reference on succcess; a NULL on failure. +* +* Assumptions: +* 1. Clock to the OPAMP block has enabled, +* 2. Board-specific logic has already configured +* +****************************************************************************/ + +FAR struct opamp_dev_s* stm32_opampinitialize(int intf); + +#undef EXTERN +#ifdef __cplusplus +} +#endif +#endif /* __ASSEMBLY__ */ + +#endif /* CONFIG_STM32_OPAMP */ +#endif /* __ARCH_ARM_SRC_STM32_STM32_OPAMP_H */ -- GitLab From 0b6190c1c48c0c9f48753ce2390b9cd91bff3a15 Mon Sep 17 00:00:00 2001 From: raiden00pl Date: Sun, 30 Apr 2017 11:11:17 +0200 Subject: [PATCH 650/990] drivers/analog: Add basic OPAMP driver --- drivers/analog/Kconfig | 6 + drivers/analog/Make.defs | 17 +++ drivers/analog/opamp.c | 243 +++++++++++++++++++++++++++++++++++ include/nuttx/analog/opamp.h | 109 ++++++++++++++++ 4 files changed, 375 insertions(+) create mode 100644 drivers/analog/opamp.c create mode 100644 include/nuttx/analog/opamp.h diff --git a/drivers/analog/Kconfig b/drivers/analog/Kconfig index 6727f67c47..64fa435f4d 100644 --- a/drivers/analog/Kconfig +++ b/drivers/analog/Kconfig @@ -141,3 +141,9 @@ config DAC_AD5410 select SPI endif # DAC + +config OPAMP + bool "Operational Amplifier" + default n + ---help--- + Select to enable support for Operational Amplifiers (OPAMPs). diff --git a/drivers/analog/Make.defs b/drivers/analog/Make.defs index 01d5a2fe8e..69d10a638d 100644 --- a/drivers/analog/Make.defs +++ b/drivers/analog/Make.defs @@ -60,6 +60,16 @@ CSRCS += comp.c endif +# Check for OPAMP devices + +ifeq ($(CONFIG_OPAMP),y) + +# Include the common OPAMP character driver + +CSRCS += opamp.c + +endif + # Check for ADC devices ifeq ($(CONFIG_ADC),y) @@ -105,6 +115,13 @@ ifeq ($(CONFIG_COMP),y) DEPPATH += --dep-path analog VPATH += :analog CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)$(DELIM)drivers$(DELIM)analog} +else +ifeq ($(CONFIG_OPAMP),y) + DEPPATH += --dep-path analog + VPATH += :analog + CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)$(DELIM)drivers$(DELIM)analog} +endif endif endif endif + diff --git a/drivers/analog/opamp.c b/drivers/analog/opamp.c new file mode 100644 index 0000000000..666b19a8ce --- /dev/null +++ b/drivers/analog/opamp.c @@ -0,0 +1,243 @@ +/**************************************************************************** + * drivers/analog/opamp.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Mateusz Szafoni + * + * 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 +#include + +#include + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static int opamp_open(FAR struct file *filep); +static int opamp_close(FAR struct file *filep); +static int opamp_ioctl(FAR struct file *filep, int cmd, unsigned long arg); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const struct file_operations opamp_fops = +{ + opamp_open, /* open */ + opamp_close, /* close */ + NULL, /* read */ + NULL, /* write */ + NULL, /* seek */ + opamp_ioctl /* ioctl */ +#ifndef CONFIG_DISABLE_POLL + , NULL /* poll */ +#endif +#ifndef CONFIG_DISABLE_PSEUDOFS_OPERATIONS + , NULL /* unlink */ +#endif +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ +/**************************************************************************** + * Name: opamp_open + * + * Description: + * This function is called whenever the OPAMP device is opened. + * + ****************************************************************************/ + +static int opamp_open(FAR struct file *filep) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct opamp_dev_s *dev = inode->i_private; + uint8_t tmp; + int ret = OK; + + /* If the port is the middle of closing, wait until the close is finished */ + + if (sem_wait(&dev->ad_closesem) != OK) + { + ret = -errno; + } + else + { + /* Increment the count of references to the device. If this the first + * time that the driver has been opened for this device, then initialize + * the device. + */ + + tmp = dev->ad_ocount + 1; + if (tmp == 0) + { + /* More than 255 opens; uint8_t overflows to zero */ + + ret = -EMFILE; + } + else + { + /* Check if this is the first time that the driver has been opened. */ + + if (tmp == 1) + { + /* Yes.. perform one time hardware initialization. */ + + irqstate_t flags = enter_critical_section(); + ret = dev->ad_ops->ao_setup(dev); + if (ret == OK) + { + /* Save the new open count on success */ + + dev->ad_ocount = tmp; + } + + leave_critical_section(flags); + } + } + + sem_post(&dev->ad_closesem); + } + + return ret; +} + +/**************************************************************************** + * Name: opamp_close + * + * Description: + * This routine is called when the OPAMP device is closed. + * It waits for the last remaining data to be sent. + * + ****************************************************************************/ + +static int opamp_close(FAR struct file *filep) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct opamp_dev_s *dev = inode->i_private; + irqstate_t flags; + int ret = OK; + + if (sem_wait(&dev->ad_closesem) != OK) + { + ret = -errno; + } + else + { + /* Decrement the references to the driver. If the reference count will + * decrement to 0, then uninitialize the driver. + */ + + if (dev->ad_ocount > 1) + { + dev->ad_ocount--; + sem_post(&dev->ad_closesem); + } + else + { + /* There are no more references to the port */ + + dev->ad_ocount = 0; + + /* Free the IRQ and disable the OPAMP device */ + + flags = enter_critical_section(); /* Disable interrupts */ + dev->ad_ops->ao_shutdown(dev); /* Disable the OPAMP */ + leave_critical_section(flags); + + sem_post(&dev->ad_closesem); + } + } + + return ret; +} + +/**************************************************************************** + * Name: opamp_ioctl +****************************************************************************/ + +static int opamp_ioctl(FAR struct file *filep, int cmd, unsigned long arg) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct opamp_dev_s *dev = inode->i_private; + int ret; + + ret = dev->ad_ops->ao_ioctl(dev, cmd, arg); + return ret; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: opamp_register + ****************************************************************************/ + +int opamp_register(FAR const char *path, FAR struct opamp_dev_s *dev) +{ + int ret; + + /* Initialize the OPAMP device structure */ + + dev->ad_ocount = 0; + + /* Initialize semaphores */ + + sem_init(&dev->ad_closesem, 0, 1); + + /* Register the OPAMP character driver */ + + ret = register_driver(path, &opamp_fops, 0444, dev); + if (ret < 0) + { + sem_destroy(&dev->ad_closesem); + } + + return ret; +} diff --git a/include/nuttx/analog/opamp.h b/include/nuttx/analog/opamp.h new file mode 100644 index 0000000000..a0f3d55be0 --- /dev/null +++ b/include/nuttx/analog/opamp.h @@ -0,0 +1,109 @@ +/************************************************************************************ + * include/nuttx/analog/opamp.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Mateusz Szafoni + * + * 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_ANALOG_OPAMP_H +#define __INCLUDE_NUTTX_ANALOG_OPAMP_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include + +#include +#include +#include +#include +#include + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +struct opamp_dev_s; +struct opamp_ops_s +{ + /* Configure the OPAMP. This method is called the first time that the OPAMP + * device is opened. This will occur when the port is first opened. + * This setup includes configuring and attaching OPAMP interrupts. Interrupts + * are all disabled upon return. + */ + + CODE int (*ao_setup)(FAR struct opamp_dev_s *dev); + + /* Disable the OPAMP. This method is called when the OPAMP device is closed. + * This method reverses the operation the setup method. + * Works only if OPAMP device is not locked. + */ + + CODE void (*ao_shutdown)(FAR struct opamp_dev_s *dev); + + /* All ioctl calls will be routed through this method */ + + CODE int (*ao_ioctl)(FAR struct opamp_dev_s *dev, int cmd, unsigned long arg); +}; + +struct opamp_dev_s +{ +#ifdef CONFIG_OPAMP + /* Fields managed by common upper half OPAMP logic */ + + uint8_t ad_ocount; /* The number of times the device has been opened */ + sem_t ad_closesem; /* Locks out new opens while close is in progress */ +#endif + + /* Fields provided by lower half OPAMP logic */ + + FAR const struct opamp_ops_s *ad_ops; /* Arch-specific operations */ + FAR void *ad_priv; /* Used by the arch-specific logic */ +}; + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +#if defined(__cplusplus) +extern "C" +{ +#endif + +int opamp_register(FAR const char *path, FAR struct opamp_dev_s *dev); + +#if defined(__cplusplus) +} +#endif + +#endif /* __INCLUDE_NUTTX_ANALOG_OPAMP_H */ -- GitLab From c3109acb29abff1ed628c4fbbda7e36d8da92dc6 Mon Sep 17 00:00:00 2001 From: raiden00pl Date: Sun, 30 Apr 2017 11:13:13 +0200 Subject: [PATCH 651/990] nucleo-f334r8: Add OPAMP support --- configs/nucleo-f334r8/include/board.h | 8 +- configs/nucleo-f334r8/src/nucleo-f334r8.h | 12 +++ configs/nucleo-f334r8/src/stm32_appinit.c | 10 +++ configs/nucleo-f334r8/src/stm32_opamp.c | 99 +++++++++++++++++++++++ 4 files changed, 128 insertions(+), 1 deletion(-) diff --git a/configs/nucleo-f334r8/include/board.h b/configs/nucleo-f334r8/include/board.h index 8d5ce807dc..ecbb7eafef 100644 --- a/configs/nucleo-f334r8/include/board.h +++ b/configs/nucleo-f334r8/include/board.h @@ -237,8 +237,14 @@ #define GPIO_USART1_RX GPIO_USART1_RX_1 /* PA10 */ #define GPIO_USART1_TX GPIO_USART1_TX_1 /* PA9 */ -/* HRTIM */ +/* COMP */ + +/* OPAMP */ +#define OPAMP2_VMSEL OPAMP2_VMSEL_PC5 +#define OPAMP2_VPSEL OPAMP2_VPSEL_PB14 + +/* HRTIM */ /* DMA channels *************************************************************/ /* ADC */ diff --git a/configs/nucleo-f334r8/src/nucleo-f334r8.h b/configs/nucleo-f334r8/src/nucleo-f334r8.h index 20b2dbbd5b..6d7d41d330 100644 --- a/configs/nucleo-f334r8/src/nucleo-f334r8.h +++ b/configs/nucleo-f334r8/src/nucleo-f334r8.h @@ -202,4 +202,16 @@ int stm32_can_setup(void); int stm32_comp_setup(void); #endif +/**************************************************************************** + * Name: stm32_opamp_setup + * + * Description: + * Initialize OPAMP peripheral for the board. + * + ****************************************************************************/ + +#ifdef CONFIG_OPAMP +int stm32_opamp_setup(void); +#endif + #endif /* __CONFIGS_NUCLEO_F334R8_SRC_NUCLEO_F334R8_H */ diff --git a/configs/nucleo-f334r8/src/stm32_appinit.c b/configs/nucleo-f334r8/src/stm32_appinit.c index 2eb43b85b0..3d1d841092 100644 --- a/configs/nucleo-f334r8/src/stm32_appinit.c +++ b/configs/nucleo-f334r8/src/stm32_appinit.c @@ -137,6 +137,16 @@ int board_app_initialize(uintptr_t arg) } #endif +#ifdef CONFIG_OPAMP + /* Initialize OPAMP and register the OPAMP driver. */ + + ret = stm32_opamp_setup(); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: stm32_opamp_setup failed: %d\n", ret); + } +#endif + UNUSED(ret); return OK; } diff --git a/configs/nucleo-f334r8/src/stm32_opamp.c b/configs/nucleo-f334r8/src/stm32_opamp.c index e69de29bb2..42d2ce370e 100644 --- a/configs/nucleo-f334r8/src/stm32_opamp.c +++ b/configs/nucleo-f334r8/src/stm32_opamp.c @@ -0,0 +1,99 @@ +/**************************************************************************** + * configs/nucleo-f334r8/src/stm32_opamp.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Mateusz Szafoni + * + * 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 "stm32.h" + +#if defined(CONFIG_OPAMP) && defined(CONFIG_STM32_OPAMP2) + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_opamp_setup + * + * Description: + * Initialize OPAMP + * + ****************************************************************************/ + +int stm32_opamp_setup(void) +{ + static bool initialized = false; + struct opamp_dev_s* opamp = NULL; + int ret; + + if (!initialized) + { + /* Get the OPAMP interface */ + +#ifdef CONFIG_STM32_OPAMP2 + opamp = stm32_opampinitialize(2); + if (opamp == NULL) + { + aerr("ERROR: Failed to get OPAMP%d interface\n", 2); + return -ENODEV; + } +#endif + + /* Register the OPAMP character driver at /dev/opamp0 */ + + ret = opamp_register("/dev/opamp0", opamp); + if (ret < 0) + { + aerr("ERROR: opamp_register failed: %d\n", ret); + return ret; + } + + initialized = true; + } + + return OK; +} + +#endif /* CONFIG_OPAMP && CONFIG_STM32_OPAMP2 */ -- GitLab From 446af7e987b814a7e39b89659cda0bf75a337a1e Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 30 Apr 2017 08:02:03 -0600 Subject: [PATCH 652/990] Nucleo-F072RB: Add support for the I2C driver used by I2C tools. --- configs/nucleo-f072rb/README.txt | 8 +++--- configs/nucleo-f072rb/include/board.h | 15 +++++++--- configs/nucleo-f072rb/src/stm32_bringup.c | 35 +++++++++++++++++++++++ 3 files changed, 50 insertions(+), 8 deletions(-) diff --git a/configs/nucleo-f072rb/README.txt b/configs/nucleo-f072rb/README.txt index 3f17cedb85..c10a1cd80a 100644 --- a/configs/nucleo-f072rb/README.txt +++ b/configs/nucleo-f072rb/README.txt @@ -135,6 +135,8 @@ Serial Console PA14 PD5 + See "Virtual COM Port" and "RS-232 Shield" below. + USART3 ------ Pins and Connectors: @@ -148,8 +150,6 @@ Serial Console PC10 D8 - See "Virtual COM Port" and "RS-232 Shield" below. - USART3 ------ Pins and Connectors: @@ -177,8 +177,8 @@ Serial Console Configuring USART2 is the same as given above. - Question: What BAUD should be configure to interface with the Virtual - COM port? 115200 8N1? + 115200 8N1 BAUD should be configure to interface with the Virtual COM + port. Default ------- diff --git a/configs/nucleo-f072rb/include/board.h b/configs/nucleo-f072rb/include/board.h index 1b45a24a51..fa1b29dad3 100644 --- a/configs/nucleo-f072rb/include/board.h +++ b/configs/nucleo-f072rb/include/board.h @@ -230,12 +230,19 @@ /* Alternate Pin Functions **********************************************************/ /* USART 1 */ -#define GPIO_USART1_TX GPIO_USART1_TX_2 -#define GPIO_USART1_RX GPIO_USART1_RX_2 +#define GPIO_USART1_TX GPIO_USART1_TX_2 /* PA9 CN10 pin 21 */ +#define GPIO_USART1_RX GPIO_USART1_RX_2 /* PA10 CN10 pin 33 */ /* USART 2 */ -#define GPIO_USART2_TX GPIO_USART2_TX_3 -#define GPIO_USART2_RX GPIO_USART2_RX_3 +#define GPIO_USART2_TX GPIO_USART2_TX_3 /* PA2 St-Link VCOM */ +#define GPIO_USART2_RX GPIO_USART2_RX_3 /* PA3 St-Link VCOM */ + +/* I2C1 */ + +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 CN5 pin 10, D15 */ +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB9 CN5 pin 9, D14 */ + +/* I2C2 */ #endif /* __CONFIG_NUCLEO_F072RB_INCLUDE_BOARD_H */ diff --git a/configs/nucleo-f072rb/src/stm32_bringup.c b/configs/nucleo-f072rb/src/stm32_bringup.c index 137e458e78..e4e15cbd71 100644 --- a/configs/nucleo-f072rb/src/stm32_bringup.c +++ b/configs/nucleo-f072rb/src/stm32_bringup.c @@ -43,8 +43,20 @@ #include #include +#include + +#include "stm32f0_i2c.h" #include "nucleo-f072rb.h" +/**************************************************************************** + * Pre-processor Defintiionis + ****************************************************************************/ + +#undef HAVE_I2C_DRIVER +#if defined(CONFIG_STM32F0_I2C1) && defined(CONFIG_I2C_DRIVER) +# define HAVE_I2C_DRIVER 1 +#endif + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -65,6 +77,9 @@ int stm32_bringup(void) { +#ifdef HAVE_I2C_DRIVER + FAR struct i2c_master_s *i2c; +#endif int ret; #ifdef CONFIG_FS_PROCFS @@ -77,6 +92,26 @@ int stm32_bringup(void) } #endif +#ifdef HAVE_I2C_DRIVER + /* Get the I2C lower half instance */ + + i2c = stm32f0_i2cbus_initialize(0); + if (i2c == NULL) + { + i2cerr("ERROR: Failed to mount procfs at /proc: %d\n", ret); + } + else + { + /* Regiser the I2C character driver */ + + ret = i2c_register(i2c, 0); + if (ret < 0) + { + i2cerr("ERROR: Failed to register I2C device: %d\n", ret); + } + } +#endif + UNUSED(ret); return OK; } -- GitLab From 193ff349ee87622dc200d3744f45938549971fbb Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 30 Apr 2017 08:02:38 -0600 Subject: [PATCH 653/990] drivers/i2c: Fix compile issus if CONFIG_DISABLE_PSEUDOFS_OPERATIONS is enabeld. --- drivers/i2c/i2c_driver.c | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/drivers/i2c/i2c_driver.c b/drivers/i2c/i2c_driver.c index 1e5024b3ec..79f3bb98e6 100644 --- a/drivers/i2c/i2c_driver.c +++ b/drivers/i2c/i2c_driver.c @@ -82,8 +82,10 @@ struct i2c_driver_s * Private Function Prototypes ****************************************************************************/ +#ifndef CONFIG_DISABLE_PSEUDOFS_OPERATIONS static int i2cdrvr_open(FAR struct file *filep); static int i2cdrvr_close(FAR struct file *filep); +#endif static ssize_t i2cdrvr_read(FAR struct file *filep, FAR char *buffer, size_t buflen); static ssize_t i2cdrvr_write(FAR struct file *filep, FAR const char *buffer, @@ -253,6 +255,7 @@ static int i2cdrvr_ioctl(FAR struct file *filep, int cmd, unsigned long arg) priv = (FAR struct i2c_driver_s *)inode->i_private; DEBUGASSERT(priv); +#ifndef CONFIG_DISABLE_PSEUDOFS_OPERATIONS /* Get exclusive access to the I2C driver state structure */ ret = sem_wait(&priv->exclsem); @@ -262,6 +265,7 @@ static int i2cdrvr_ioctl(FAR struct file *filep, int cmd, unsigned long arg) DEBUGASSERT(errcode < 0); return -errcode; } +#endif /* Process the IOCTL command */ @@ -306,7 +310,9 @@ static int i2cdrvr_ioctl(FAR struct file *filep, int cmd, unsigned long arg) break; } +#ifndef CONFIG_DISABLE_PSEUDOFS_OPERATIONS sem_post(&priv->exclsem); +#endif return ret; } -- GitLab From 0a9dd3876bf7b6ced496c9758c075f77c4995424 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 30 Apr 2017 09:19:51 -0600 Subject: [PATCH 654/990] STM32F0 I2C: Upate driver to use the standard interrupt parameter passing logic. --- arch/arm/src/stm32f0/stm32f0_i2c.c | 107 ++++++++-------------- configs/nucleo-f072rb/src/stm32_bringup.c | 8 +- 2 files changed, 43 insertions(+), 72 deletions(-) diff --git a/arch/arm/src/stm32f0/stm32f0_i2c.c b/arch/arm/src/stm32f0/stm32f0_i2c.c index 98a4db2c80..4d66aa3ac9 100644 --- a/arch/arm/src/stm32f0/stm32f0_i2c.c +++ b/arch/arm/src/stm32f0/stm32f0_i2c.c @@ -216,7 +216,6 @@ struct stm32f0_i2c_config_s uint32_t scl_pin; /* GPIO configuration for SCL as SCL */ uint32_t sda_pin; /* GPIO configuration for SDA as SDA */ #ifndef CONFIG_I2C_POLLED - int (*isr)(int, void *, void *); /* Interrupt handler */ uint32_t irq; /* IRQ */ #endif }; @@ -290,17 +289,9 @@ static inline void stm32f0_i2c_sendstart(FAR struct stm32f0_i2c_priv_s *priv); static inline void stm32f0_i2c_clrstart(FAR struct stm32f0_i2c_priv_s *priv); static inline void stm32f0_i2c_sendstop(FAR struct stm32f0_i2c_priv_s *priv); static inline uint32_t stm32f0_i2c_getstatus(FAR struct stm32f0_i2c_priv_s *priv); -static int stm32f0_i2c_isr(struct stm32f0_i2c_priv_s * priv); +static int stm32f0_i2c_isr_process(struct stm32f0_i2c_priv_s * priv); #ifndef CONFIG_I2C_POLLED -#ifdef CONFIG_STM32F0_I2C1 -static int stm32f0_i2c1_isr(int irq, void *context, FAR void *arg); -#endif -#ifdef CONFIG_STM32F0_I2C2 -static int stm32f0_i2c2_isr(int irq, void *context, FAR void *arg); -#endif -#ifdef CONFIG_STM32F0_I2C3 -static int stm32f0_i2c3_isr(int irq, void *context, FAR void *arg); -#endif +static int stm32f0_i2c_isr(int irq, void *context, FAR void *arg); #endif static int stm32f0_i2c_init(FAR struct stm32f0_i2c_priv_s *priv); static int stm32f0_i2c_deinit(FAR struct stm32f0_i2c_priv_s *priv); @@ -333,7 +324,6 @@ static const struct stm32f0_i2c_config_s stm32f0_i2c1_config = .scl_pin = GPIO_I2C1_SCL, .sda_pin = GPIO_I2C1_SDA, #ifndef CONFIG_I2C_POLLED - .isr = stm32f0_i2c1_isr, .irq = STM32F0_IRQ_I2C1 #endif }; @@ -362,7 +352,6 @@ static const struct stm32f0_i2c_config_s stm32f0_i2c2_config = .scl_pin = GPIO_I2C2_SCL, .sda_pin = GPIO_I2C2_SDA, #ifndef CONFIG_I2C_POLLED - .isr = stm32f0_i2c2_isr, .irq = STM32F0_IRQ_I2C2 #endif }; @@ -391,7 +380,6 @@ static const struct stm32f0_i2c_config_s stm32f0_i2c3_config = .scl_pin = GPIO_I2C3_SCL, .sda_pin = GPIO_I2C3_SDA, #ifndef CONFIG_I2C_POLLED - .isr = stm32f0_i2c3_isr, .irq = STM32F0_IRQ_I2C3 #endif }; @@ -424,7 +412,7 @@ struct stm32f0_i2c_priv_s stm32f0_i2c3_priv = ************************************************************************************/ static inline uint32_t stm32f0_i2c_getreg32(FAR struct stm32f0_i2c_priv_s *priv, - uint8_t offset) + uint8_t offset) { return getreg32(priv->config->base + offset); } @@ -438,7 +426,7 @@ static inline uint32_t stm32f0_i2c_getreg32(FAR struct stm32f0_i2c_priv_s *priv, ************************************************************************************/ static inline void stm32f0_i2c_putreg32(FAR struct stm32f0_i2c_priv_s *priv, - uint8_t offset, uint32_t value) + uint8_t offset, uint32_t value) { putreg32(value, priv->config->base + offset); } @@ -654,7 +642,7 @@ static inline int stm32f0_i2c_sem_waitdone(FAR struct stm32f0_i2c_priv_s *priv) * reports that it is done. */ - stm32f0_i2c_isr(priv); + stm32f0_i2c_isr_process(priv); } /* Loop until the transfer is complete. */ @@ -695,7 +683,7 @@ stm32f0_i2c_set_7bit_address(FAR struct stm32f0_i2c_priv_s *priv) static inline void stm32f0_i2c_set_bytes_to_transfer(FAR struct stm32f0_i2c_priv_s *priv, - uint8_t n_bytes) + uint8_t n_bytes) { stm32f0_i2c_modifyreg32(priv, STM32F0_I2C_CR2_OFFSET, I2C_CR2_NBYTES_MASK, (n_bytes << I2C_CR2_NBYTES_SHIFT)); @@ -1262,7 +1250,7 @@ static inline uint32_t stm32f0_i2c_getstatus(FAR struct stm32f0_i2c_priv_s *priv } /************************************************************************************ - * Name: stm32f0_i2c_isr + * Name: stm32f0_i2c_isr_startmessage * * Description: * Common logic when a message is started. Just adds the even to the trace buffer @@ -1295,14 +1283,14 @@ static inline void stm32f0_i2c_clearinterrupts(struct stm32f0_i2c_priv_s *priv) } /************************************************************************************ - * Name: stm32f0_i2c_isr + * Name: stm32f0_i2c_isr_process * * Description: * Common Interrupt Service Routine * ************************************************************************************/ -static int stm32f0_i2c_isr(struct stm32f0_i2c_priv_s *priv) +static int stm32f0_i2c_isr_process(struct stm32f0_i2c_priv_s *priv) { uint32_t status = stm32f0_i2c_getstatus(priv); @@ -1501,51 +1489,22 @@ static int stm32f0_i2c_isr(struct stm32f0_i2c_priv_s *priv) } /************************************************************************************ - * Name: stm32f0_i2c1_isr + * Name: stm32f0_i2c_isr_process * * Description: - * I2C1 interrupt service routine + * Common I2C interrupt service routine * ************************************************************************************/ #ifndef CONFIG_I2C_POLLED -#ifdef CONFIG_STM32F0_I2C1 -static int stm32f0_i2c1_isr(int irq, void *context, FAR void *arg) +static int stm32f0_i2c_isr(int irq, void *context, FAR void *arg) { - return stm32f0_i2c_isr(&stm32f0_i2c1_priv); -} -#endif - -/************************************************************************************ - * Name: stm32f0_i2c2_isr - * - * Description: - * I2C2 interrupt service routine - * - ************************************************************************************/ - -#ifdef CONFIG_STM32F0_I2C2 -static int stm32f0_i2c2_isr(int irq, void *context, FAR void *arg) -{ - return stm32f0_i2c_isr(&stm32f0_i2c2_priv); -} -#endif - -/************************************************************************************ - * Name: stm32f0_i2c3_isr - * - * Description: - * I2C2 interrupt service routine - * - ************************************************************************************/ + struct stm32f0_i2c_priv_s *priv = (struct stm32f0_i2c_priv_s *)arg; -#ifdef CONFIG_STM32F0_I2C3 -static int stm32f0_i2c3_isr(int irq, void *context, FAR void *arg) -{ - return stm32f0_i2c_isr(&stm32f0_i2c3_priv); + DEBUGASSERT(priv != NULL); + return stm32f0_i2c_isr_process(priv); } #endif -#endif /************************************************************************************ * Private Initialization and Deinitialization @@ -1561,6 +1520,8 @@ static int stm32f0_i2c3_isr(int irq, void *context, FAR void *arg) static int stm32f0_i2c_init(FAR struct stm32f0_i2c_priv_s *priv) { + int ret; + /* Power-up and configure GPIOs */ /* Enable power and reset the peripheral */ @@ -1570,21 +1531,23 @@ static int stm32f0_i2c_init(FAR struct stm32f0_i2c_priv_s *priv) /* Configure pins */ - if (stm32f0_configgpio(priv->config->scl_pin) < 0) + ret = stm32f0_configgpio(priv->config->scl_pin); + if (ret < 0) { - return ERROR; + return ret; } - if (stm32f0_configgpio(priv->config->sda_pin) < 0) + ret = stm32f0_configgpio(priv->config->sda_pin); + if (ret < 0) { stm32f0_unconfiggpio(priv->config->scl_pin); - return ERROR; + return ret; } - /* Attach ISRs */ - #ifndef CONFIG_I2C_POLLED - irq_attach(priv->config->irq, priv->config->isr, NULL); + /* Attach and enable the I2C interrupt */ + + irq_attach(priv->config->irq, stm32f0_i2c_isr, priv); up_enable_irq(priv->config->irq); #endif @@ -1848,7 +1811,7 @@ static int stm32f0_i2c_reset(FAR struct i2c_master_s * dev) uint32_t scl_gpio; uint32_t sda_gpio; uint32_t frequency; - int ret = ERROR; + int ret = -EIO; ASSERT(dev); @@ -1938,12 +1901,15 @@ static int stm32f0_i2c_reset(FAR struct i2c_master_s * dev) /* Re-init the port */ - stm32f0_i2c_init(priv); + ret = stm32f0_i2c_init(priv); + if (ret < 0) + { + i2cerr("ERROR: stm32f0_i2c_init failed: %d\n", ret); + } /* Restore the frequency */ stm32f0_i2c_setclock(priv, frequency); - ret = OK; out: @@ -1970,6 +1936,7 @@ FAR struct i2c_master_s *stm32f0_i2cbus_initialize(int port) { struct stm32f0_i2c_priv_s *priv = NULL; irqstate_t flags; + int ret; #if STM32F0_PCLK1_FREQUENCY < 4000000 # warning STM32F0_I2C_INIT: Peripheral clock must be at least 4 MHz to support 400 kHz operation. @@ -2012,7 +1979,11 @@ FAR struct i2c_master_s *stm32f0_i2cbus_initialize(int port) if ((volatile int)priv->refs++ == 0) { stm32f0_i2c_sem_init(priv); - stm32f0_i2c_init(priv); + ret = stm32f0_i2c_init(priv); + if (ret < 0) + { + i2cerr("ERROR: stm32f0_i2c_init failed: %d\n", ret); + } } leave_critical_section(flags); @@ -2038,7 +2009,7 @@ int stm32f0_i2cbus_uninitialize(FAR struct i2c_master_s * dev) if (priv->refs == 0) { - return ERROR; + return -ENODEV; } flags = enter_critical_section(); diff --git a/configs/nucleo-f072rb/src/stm32_bringup.c b/configs/nucleo-f072rb/src/stm32_bringup.c index e4e15cbd71..e3f8698a6f 100644 --- a/configs/nucleo-f072rb/src/stm32_bringup.c +++ b/configs/nucleo-f072rb/src/stm32_bringup.c @@ -95,19 +95,19 @@ int stm32_bringup(void) #ifdef HAVE_I2C_DRIVER /* Get the I2C lower half instance */ - i2c = stm32f0_i2cbus_initialize(0); + i2c = stm32f0_i2cbus_initialize(1); if (i2c == NULL) { - i2cerr("ERROR: Failed to mount procfs at /proc: %d\n", ret); + i2cerr("ERROR: Inialize I2C1: %d\n", ret); } else { /* Regiser the I2C character driver */ - ret = i2c_register(i2c, 0); + ret = i2c_register(i2c, 1); if (ret < 0) { - i2cerr("ERROR: Failed to register I2C device: %d\n", ret); + i2cerr("ERROR: Failed to register I2C1 device: %d\n", ret); } } #endif -- GitLab From dee736bd0d13218fa0625ad1ca8098641e62f256 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 30 Apr 2017 10:28:16 -0600 Subject: [PATCH 655/990] STM32F0 I2C: Pin definitions should specify open drain (and probably 50Mhz). --- arch/arm/src/stm32f0/chip/stm32f05x_pinmap.h | 94 ++++++++++---------- arch/arm/src/stm32f0/chip/stm32f07x_pinmap.h | 20 ++--- configs/nucleo-f072rb/README.txt | 4 + 3 files changed, 61 insertions(+), 57 deletions(-) diff --git a/arch/arm/src/stm32f0/chip/stm32f05x_pinmap.h b/arch/arm/src/stm32f0/chip/stm32f05x_pinmap.h index 969e4e4c42..2e63d59ead 100644 --- a/arch/arm/src/stm32f0/chip/stm32f05x_pinmap.h +++ b/arch/arm/src/stm32f0/chip/stm32f05x_pinmap.h @@ -70,22 +70,22 @@ /* ADC */ -#define GPIO_ADC_IN0 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN0) -#define GPIO_ADC_IN1 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN1) -#define GPIO_ADC_IN2 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN2) -#define GPIO_ADC_IN3 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN3) -#define GPIO_ADC_IN4 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN4) -#define GPIO_ADC_IN5 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN5) -#define GPIO_ADC_IN6 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN6) -#define GPIO_ADC_IN7 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN7) -#define GPIO_ADC_IN8 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN0) -#define GPIO_ADC_IN9 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN1) -#define GPIO_ADC_IN10 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN0) -#define GPIO_ADC_IN11 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN1) -#define GPIO_ADC_IN12 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN2) -#define GPIO_ADC_IN13 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN3) -#define GPIO_ADC_IN14 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN4) -#define GPIO_ADC_IN15 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN5) +#define GPIO_ADC_IN0 (GPIO_ANALOG | GPIO_PORTA | GPIO_PIN0) +#define GPIO_ADC_IN1 (GPIO_ANALOG | GPIO_PORTA | GPIO_PIN1) +#define GPIO_ADC_IN2 (GPIO_ANALOG | GPIO_PORTA | GPIO_PIN2) +#define GPIO_ADC_IN3 (GPIO_ANALOG | GPIO_PORTA | GPIO_PIN3) +#define GPIO_ADC_IN4 (GPIO_ANALOG | GPIO_PORTA | GPIO_PIN4) +#define GPIO_ADC_IN5 (GPIO_ANALOG | GPIO_PORTA | GPIO_PIN5) +#define GPIO_ADC_IN6 (GPIO_ANALOG | GPIO_PORTA | GPIO_PIN6) +#define GPIO_ADC_IN7 (GPIO_ANALOG | GPIO_PORTA | GPIO_PIN7) +#define GPIO_ADC_IN8 (GPIO_ANALOG | GPIO_PORTB | GPIO_PIN0) +#define GPIO_ADC_IN9 (GPIO_ANALOG | GPIO_PORTB | GPIO_PIN1) +#define GPIO_ADC_IN10 (GPIO_ANALOG | GPIO_PORTC | GPIO_PIN0) +#define GPIO_ADC_IN11 (GPIO_ANALOG | GPIO_PORTC | GPIO_PIN1) +#define GPIO_ADC_IN12 (GPIO_ANALOG | GPIO_PORTC | GPIO_PIN2) +#define GPIO_ADC_IN13 (GPIO_ANALOG | GPIO_PORTC | GPIO_PIN3) +#define GPIO_ADC_IN14 (GPIO_ANALOG | GPIO_PORTC | GPIO_PIN4) +#define GPIO_ADC_IN15 (GPIO_ANALOG | GPIO_PORTC | GPIO_PIN5) /* TIMERS */ @@ -93,44 +93,44 @@ /* USART */ -#define GPIO_USART1_TX_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN9) -#define GPIO_USART1_TX_2 (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN6) -#define GPIO_USART1_RX_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN10) -#define GPIO_USART1_RX_2 (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN7) -#define GPIO_USART1_CTS (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN11) -#define GPIO_USART1_RTS (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN12) -#define GPIO_USART1_CK (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN8) +#define GPIO_USART1_TX_1 (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN9) +#define GPIO_USART1_TX_2 (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN6) +#define GPIO_USART1_RX_1 (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN10) +#define GPIO_USART1_RX_2 (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN7) +#define GPIO_USART1_CTS (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN11) +#define GPIO_USART1_RTS (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN12) +#define GPIO_USART1_CK (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN8) -#define GPIO_USART2_CTS (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN0) -#define GPIO_USART2_RTS (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN1) -#define GPIO_USART2_TX (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN2) -#define GPIO_USART2_RX (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN3) -#define GPIO_USART2_CK (GPIO_ALT|GPIO_AF1|GPIO_PORTA|GPIO_PIN4) +#define GPIO_USART2_CTS (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN0) +#define GPIO_USART2_RTS (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN1) +#define GPIO_USART2_TX (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN2) +#define GPIO_USART2_RX (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN3) +#define GPIO_USART2_CK (GPIO_ALT | GPIO_AF1 | GPIO_PORTA | GPIO_PIN4) /* SPI */ -#define GPIO_SPI1_NSS_1 (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN4) -#define GPIO_SPI1_NSS_2 (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN15) -#define GPIO_SPI1_SCK_1 (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN5) -#define GPIO_SPI1_SCK_2 (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN3) -#define GPIO_SPI1_MISO_1 (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN6) -#define GPIO_SPI1_MISO_2 (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN4) -#define GPIO_SPI1_MOSI_1 (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN7) -#define GPIO_SPI1_MOSI_2 (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN5) -#define GPIO_SPI2_NSS (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN12) -#define GPIO_SPI2_SCK (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN13) -#define GPIO_SPI2_MISO (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN14) -#define GPIO_SPI2_MOSI (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN15) +#define GPIO_SPI1_NSS_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN4) +#define GPIO_SPI1_NSS_2 (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN15) +#define GPIO_SPI1_SCK_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN5) +#define GPIO_SPI1_SCK_2 (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN3) +#define GPIO_SPI1_MISO_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN6) +#define GPIO_SPI1_MISO_2 (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN4) +#define GPIO_SPI1_MOSI_1 (GPIO_ALT | GPIO_AF0 | GPIO_PORTA | GPIO_PIN7) +#define GPIO_SPI1_MOSI_2 (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN5) +#define GPIO_SPI2_NSS (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN12) +#define GPIO_SPI2_SCK (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN13) +#define GPIO_SPI2_MISO (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN14) +#define GPIO_SPI2_MOSI (GPIO_ALT | GPIO_AF0 | GPIO_PORTB | GPIO_PIN15) /* I2C */ -#define GPIO_I2C1_SCL_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN6) -#define GPIO_I2C1_SCL_2 (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN8) -#define GPIO_I2C1_SDA_1 (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN7) -#define GPIO_I2C1_SDA_2 (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN9) -#define GPIO_I2C1_SMBA (GPIO_ALT|GPIO_AF3|GPIO_PORTB|GPIO_PIN5) +#define GPIO_I2C1_SCL_1 (GPIO_ALT | GPIO_AF1 | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_PORTB | GPIO_PIN6) +#define GPIO_I2C1_SCL_2 (GPIO_ALT | GPIO_AF1 | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_PORTB | GPIO_PIN8) +#define GPIO_I2C1_SDA_1 (GPIO_ALT | GPIO_AF1 | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_PORTB | GPIO_PIN7) +#define GPIO_I2C1_SDA_2 (GPIO_ALT | GPIO_AF1 | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_PORTB | GPIO_PIN9) +#define GPIO_I2C1_SMBA (GPIO_ALT | GPIO_AF3 | GPIO_FLOAT | GPIO_SPEED_50MHz | GPIO_PORTB | GPIO_PIN5) -#define GPIO_I2C2_SCL (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN10) -#define GPIO_I2C2_SDA (GPIO_ALT|GPIO_AF1|GPIO_PORTB|GPIO_PIN11) +#define GPIO_I2C2_SCL (GPIO_ALT | GPIO_AF1 | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_PORTB | GPIO_PIN10) +#define GPIO_I2C2_SDA (GPIO_ALT | GPIO_AF1 | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_PORTB | GPIO_PIN11) #endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F05X_PINMAP_H */ diff --git a/arch/arm/src/stm32f0/chip/stm32f07x_pinmap.h b/arch/arm/src/stm32f0/chip/stm32f07x_pinmap.h index 213d8902b8..4ac07ab59c 100644 --- a/arch/arm/src/stm32f0/chip/stm32f07x_pinmap.h +++ b/arch/arm/src/stm32f0/chip/stm32f07x_pinmap.h @@ -144,16 +144,16 @@ /* I2C */ -#define GPIO_I2C1_SCL_1 (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN6) -#define GPIO_I2C1_SCL_2 (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN8) -#define GPIO_I2C1_SDA_1 (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN7) -#define GPIO_I2C1_SDA_2 (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN9) -#define GPIO_I2C1_SMBA (GPIO_ALT | GPIO_AF3 | GPIO_PORTB | GPIO_PIN5) - -#define GPIO_I2C2_SCL_1 (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN10) -#define GPIO_I2C2_SCL_2 (GPIO_ALT | GPIO_AF5 | GPIO_PORTB | GPIO_PIN13) -#define GPIO_I2C2_SDA_1 (GPIO_ALT | GPIO_AF1 | GPIO_PORTB | GPIO_PIN11) -#define GPIO_I2C2_SDA_2 (GPIO_ALT | GPIO_AF5 | GPIO_PORTB | GPIO_PIN14) +#define GPIO_I2C1_SCL_1 (GPIO_ALT | GPIO_AF1 | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_PORTB | GPIO_PIN6) +#define GPIO_I2C1_SCL_2 (GPIO_ALT | GPIO_AF1 | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_PORTB | GPIO_PIN8) +#define GPIO_I2C1_SDA_1 (GPIO_ALT | GPIO_AF1 | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_PORTB | GPIO_PIN7) +#define GPIO_I2C1_SDA_2 (GPIO_ALT | GPIO_AF1 | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_PORTB | GPIO_PIN9) +#define GPIO_I2C1_SMBA (GPIO_ALT | GPIO_AF3 | GPIO_FLOAT | GPIO_SPEED_50MHz | GPIO_PORTB | GPIO_PIN5) + +#define GPIO_I2C2_SCL_1 (GPIO_ALT | GPIO_AF1 | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_PORTB | GPIO_PIN10) +#define GPIO_I2C2_SCL_2 (GPIO_ALT | GPIO_AF5 | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_PORTB | GPIO_PIN13) +#define GPIO_I2C2_SDA_1 (GPIO_ALT | GPIO_AF1 | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_PORTB | GPIO_PIN11) +#define GPIO_I2C2_SDA_2 (GPIO_ALT | GPIO_AF5 | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_PORTB | GPIO_PIN14) /* I2S */ diff --git a/configs/nucleo-f072rb/README.txt b/configs/nucleo-f072rb/README.txt index c10a1cd80a..93de59220f 100644 --- a/configs/nucleo-f072rb/README.txt +++ b/configs/nucleo-f072rb/README.txt @@ -24,6 +24,10 @@ Status A USB device driver was added along with support for clocking from the HSI48. That driver remains untested. + 2017-04-30: I tried using the I2C driver with the I2C tool (apps/system/i2c). + I may have something wrong, but at present the driver is just timing out + on all transfers. + Nucleo-64 Boards ================ -- GitLab From c172d7cf634821b827abb73067a8d391891e7cef Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 30 Apr 2017 11:56:06 -0600 Subject: [PATCH 656/990] EFM32, STM32, and STM32 F7 I2C: Update to use the standard parameter passing to interrupt handlers. --- arch/arm/src/efm32/efm32_i2c.c | 56 ++++----------- arch/arm/src/stm32/stm32_i2c.c | 71 ++++--------------- arch/arm/src/stm32/stm32_i2c_alt.c | 71 ++++--------------- arch/arm/src/stm32/stm32f30xxx_i2c.c | 73 ++++--------------- arch/arm/src/stm32/stm32f40xxx_i2c.c | 101 ++++++++------------------- arch/arm/src/stm32f7/stm32_i2c.c | 90 ++++-------------------- 6 files changed, 95 insertions(+), 367 deletions(-) diff --git a/arch/arm/src/efm32/efm32_i2c.c b/arch/arm/src/efm32/efm32_i2c.c index a52cd05ead..6b14038a77 100644 --- a/arch/arm/src/efm32/efm32_i2c.c +++ b/arch/arm/src/efm32/efm32_i2c.c @@ -220,7 +220,6 @@ struct efm32_i2c_config_s uint32_t scl_pin; /* GPIO configuration for SCL as SCL */ uint32_t sda_pin; /* GPIO configuration for SDA as SDA */ #ifndef CONFIG_I2C_POLLED - int (*isr) (int, void *, void *); /* Interrupt handler */ uint32_t irq; /* Event IRQ */ #endif }; @@ -294,15 +293,10 @@ static void efm32_i2c_tracedump(FAR struct efm32_i2c_priv_s *priv); static void efm32_i2c_setclock(FAR struct efm32_i2c_priv_s *priv, uint32_t frequency); -static int efm32_i2c_isr(struct efm32_i2c_priv_s *priv); +static int efm32_i2c_isr_process(struct efm32_i2c_priv_s *priv); #ifndef CONFIG_I2C_POLLED -#ifdef CONFIG_EFM32_I2C0 -static int efm32_i2c0_isr(int irq, void *context, FAR void *arg); -#endif -#ifdef CONFIG_EFM32_I2C1 -static int efm32_i2c1_isr(int irq, void *context, FAR void *arg); -#endif +static int efm32_i2c_isr(int irq, void *context, FAR void *arg); #endif /* !CONFIG_I2C_POLLED */ static void efm32_i2c_hwreset(FAR struct efm32_i2c_priv_s *priv); @@ -343,7 +337,6 @@ static const struct efm32_i2c_config_s efm32_i2c0_config = .scl_pin = BOARD_I2C0_SCL, .sda_pin = BOARD_I2C0_SDA, #ifndef CONFIG_I2C_POLLED - .isr = efm32_i2c0_isr, .irq = EFM32_IRQ_I2C0 #endif }; @@ -371,7 +364,6 @@ static const struct efm32_i2c_config_s efm32_i2c1_config = .scl_pin = BOARD_I2C1_SCL, .sda_pin = BOARD_I2C1_SDA, #ifndef CONFIG_I2C_POLLED - .isr = efm32_i2c1_isr, .irq = EFM32_IRQ_I2C1 #endif }; @@ -632,7 +624,7 @@ static inline int efm32_i2c_sem_waitdone(FAR struct efm32_i2c_priv_s *priv) * that it is done. */ - efm32_i2c_isr(priv); + efm32_i2c_isr_process(priv); /* Calculate the elapsed time */ @@ -869,14 +861,14 @@ static void efm32_i2c_setclock(FAR struct efm32_i2c_priv_s *priv, } /**************************************************************************** - * Name: efm32_i2c_isr + * Name: efm32_i2c_isr_process * * Description: * Common Interrupt Service Routine * ****************************************************************************/ -static int efm32_i2c_isr(struct efm32_i2c_priv_s *priv) +static int efm32_i2c_isr_process(struct efm32_i2c_priv_s *priv) { for (; ; ) { @@ -1279,44 +1271,24 @@ done: return OK; } -#ifndef CONFIG_I2C_POLLED - /**************************************************************************** - * Name: efm32_i2c0_isr + * Name: efm32_i2c_isr * * Description: - * I2C0 interrupt service routine + * Common I2C interrupt service routine * ****************************************************************************/ -#ifdef CONFIG_EFM32_I2C0 -static int efm32_i2c0_isr(int irq, void *context, FAR void *arg) +#ifndef CONFIG_I2C_POLLED +static int efm32_i2c_isr(int irq, void *context, FAR void *arg) { - return efm32_i2c_isr(&efm32_i2c0_priv); -} -#endif + struct efm32_i2c_priv_s *priv = (struct efm32_i2c_priv_s *)arg; -/**************************************************************************** - * Name: efm32_i2c1_isr - * - * Description: - * I2C1 interrupt service routine - * - ****************************************************************************/ - -#ifdef CONFIG_EFM32_I2C1 -static int efm32_i2c1_isr(int irq, void *context, FAR void *arg) -{ - return efm32_i2c_isr(&efm32_i2c1_priv); + DEBUGASSERT(priv != NULL); + return efm32_i2c_isr_process(priv); } #endif -#endif - -/**************************************************************************** - * Private Initialization and Deinitialization - ****************************************************************************/ - /**************************************************************************** * Name: efm32_i2c_hwreset * @@ -1389,7 +1361,7 @@ static int efm32_i2c_init(FAR struct efm32_i2c_priv_s *priv) /* Attach ISRs */ #ifndef CONFIG_I2C_POLLED - irq_attach(priv->config->irq, priv->config->isr, NULL); + irq_attach(priv->config->irq, efm32_i2c_isr, priv); up_enable_irq(priv->config->irq); #endif @@ -1523,7 +1495,7 @@ static int efm32_i2c_transfer(FAR struct i2c_master_s *dev, * be enabled in efm32_i2c_sem_waitdone if CONFIG_I2C_POLLED is NOT defined */ - efm32_i2c_isr(priv); + efm32_i2c_isr_process(priv); /* Wait for an ISR, if there was a timeout, fetch latest status to get the * BUSY flag. diff --git a/arch/arm/src/stm32/stm32_i2c.c b/arch/arm/src/stm32/stm32_i2c.c index 666ad304ad..f754a6ad18 100644 --- a/arch/arm/src/stm32/stm32_i2c.c +++ b/arch/arm/src/stm32/stm32_i2c.c @@ -230,7 +230,6 @@ struct stm32_i2c_config_s uint32_t scl_pin; /* GPIO configuration for SCL as SCL */ uint32_t sda_pin; /* GPIO configuration for SDA as SDA */ #ifndef CONFIG_I2C_POLLED - int (*isr)(int, void *, void *); /* Interrupt handler */ uint32_t ev_irq; /* Event IRQ */ uint32_t er_irq; /* Error IRQ */ #endif @@ -313,18 +312,10 @@ static inline uint32_t stm32_i2c_disablefsmc(FAR struct stm32_i2c_priv_s *priv); static inline void stm32_i2c_enablefsmc(uint32_t ahbenr); #endif /* I2C1_FSMC_CONFLICT */ -static int stm32_i2c_isr(struct stm32_i2c_priv_s * priv); +static int stm32_i2c_isr_process(struct stm32_i2c_priv_s * priv); #ifndef CONFIG_I2C_POLLED -#ifdef CONFIG_STM32_I2C1 -static int stm32_i2c1_isr(int irq, void *context, FAR void *arg); -#endif -#ifdef CONFIG_STM32_I2C2 -static int stm32_i2c2_isr(int irq, void *context, FAR void *arg); -#endif -#ifdef CONFIG_STM32_I2C3 -static int stm32_i2c3_isr(int irq, void *context, FAR void *arg); -#endif +static int stm32_i2c_isr(int irq, void *context, FAR void *arg); #endif /* !CONFIG_I2C_POLLED */ static int stm32_i2c_init(FAR struct stm32_i2c_priv_s *priv); @@ -379,7 +370,6 @@ static const struct stm32_i2c_config_s stm32_i2c1_config = .scl_pin = GPIO_I2C1_SCL, .sda_pin = GPIO_I2C1_SDA, #ifndef CONFIG_I2C_POLLED - .isr = stm32_i2c1_isr, .ev_irq = STM32_IRQ_I2C1EV, .er_irq = STM32_IRQ_I2C1ER #endif @@ -409,7 +399,6 @@ static const struct stm32_i2c_config_s stm32_i2c2_config = .scl_pin = GPIO_I2C2_SCL, .sda_pin = GPIO_I2C2_SDA, #ifndef CONFIG_I2C_POLLED - .isr = stm32_i2c2_isr, .ev_irq = STM32_IRQ_I2C2EV, .er_irq = STM32_IRQ_I2C2ER #endif @@ -439,7 +428,6 @@ static const struct stm32_i2c_config_s stm32_i2c3_config = .scl_pin = GPIO_I2C3_SCL, .sda_pin = GPIO_I2C3_SDA, #ifndef CONFIG_I2C_POLLED - .isr = stm32_i2c3_isr, .ev_irq = STM32_IRQ_I2C3EV, .er_irq = STM32_IRQ_I2C3ER #endif @@ -678,7 +666,7 @@ static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv) * reports that it is done. */ - stm32_i2c_isr(priv); + stm32_i2c_isr_process(priv); } /* Loop until the transfer is complete. */ @@ -1172,14 +1160,14 @@ static inline void stm32_i2c_enablefsmc(uint32_t ahbenr) #endif /* I2C1_FSMC_CONFLICT */ /************************************************************************************ - * Name: stm32_i2c_isr + * Name: stm32_i2c_isr_process * * Description: * Common Interrupt Service Routine * ************************************************************************************/ -static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv) +static int stm32_i2c_isr_process(struct stm32_i2c_priv_s *priv) { uint32_t status = stm32_i2c_getstatus(priv); @@ -1459,55 +1447,22 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv) } /************************************************************************************ - * Name: stm32_i2c1_isr - * - * Description: - * I2C1 interrupt service routine - * - ************************************************************************************/ - -#ifndef CONFIG_I2C_POLLED -#ifdef CONFIG_STM32_I2C1 -static int stm32_i2c1_isr(int irq, void *context, FAR void *arg) -{ - return stm32_i2c_isr(&stm32_i2c1_priv); -} -#endif - -/************************************************************************************ - * Name: stm32_i2c2_isr + * Name: stm32_i2c_isr * * Description: - * I2C2 interrupt service routine + * Common I2C interrupt service routine * ************************************************************************************/ -#ifdef CONFIG_STM32_I2C2 +#ifdef CONFIG_I2C_POLLED static int stm32_i2c2_isr(int irq, void *context, FAR void *arg) { - return stm32_i2c_isr(&stm32_i2c2_priv); -} -#endif - -/************************************************************************************ - * Name: stm32_i2c3_isr - * - * Description: - * I2C2 interrupt service routine - * - ************************************************************************************/ + struct stm32_i2c_priv_s *priv = (struct stm32_i2c_priv_s *)arg; -#ifdef CONFIG_STM32_I2C3 -static int stm32_i2c3_isr(int irq, void *context, FAR void *arg) -{ - return stm32_i2c_isr(&stm32_i2c3_priv); + DEBUGASSERT(priv != NULL); + return stm32_i2c_isr_process(priv); } #endif -#endif - -/************************************************************************************ - * Private Initialization and Deinitialization - ************************************************************************************/ /************************************************************************************ * Name: stm32_i2c_init @@ -1543,8 +1498,8 @@ static int stm32_i2c_init(FAR struct stm32_i2c_priv_s *priv) /* Attach ISRs */ #ifndef CONFIG_I2C_POLLED - irq_attach(priv->config->ev_irq, priv->config->isr, NULL); - irq_attach(priv->config->er_irq, priv->config->isr, NULL); + irq_attach(priv->config->ev_irq, stm32_i2c_isr, priv); + irq_attach(priv->config->er_irq, stm32_i2c_isr, priv); up_enable_irq(priv->config->ev_irq); up_enable_irq(priv->config->er_irq); #endif diff --git a/arch/arm/src/stm32/stm32_i2c_alt.c b/arch/arm/src/stm32/stm32_i2c_alt.c index b115ce2795..a39248f56d 100644 --- a/arch/arm/src/stm32/stm32_i2c_alt.c +++ b/arch/arm/src/stm32/stm32_i2c_alt.c @@ -257,7 +257,6 @@ struct stm32_i2c_config_s uint32_t scl_pin; /* GPIO configuration for SCL as SCL */ uint32_t sda_pin; /* GPIO configuration for SDA as SDA */ #ifndef CONFIG_I2C_POLLED - int (*isr)(int, void *, void *); /* Interrupt handler */ uint32_t ev_irq; /* Event IRQ */ uint32_t er_irq; /* Error IRQ */ #endif @@ -342,18 +341,10 @@ static inline uint32_t stm32_i2c_disablefsmc(FAR struct stm32_i2c_priv_s *priv); static inline void stm32_i2c_enablefsmc(uint32_t ahbenr); #endif /* I2C1_FSMC_CONFLICT */ -static int stm32_i2c_isr(struct stm32_i2c_priv_s * priv); +static int stm32_i2c_isr_process(struct stm32_i2c_priv_s * priv); #ifndef CONFIG_I2C_POLLED -#ifdef CONFIG_STM32_I2C1 -static int stm32_i2c1_isr(int irq, void *context, FAR void *arg); -#endif -#ifdef CONFIG_STM32_I2C2 -static int stm32_i2c2_isr(int irq, void *context, FAR void *arg); -#endif -#ifdef CONFIG_STM32_I2C3 -static int stm32_i2c3_isr(int irq, void *context, FAR void *arg); -#endif +static int stm32_i2c_isr(int irq, void *context, FAR void *arg); #endif /* !CONFIG_I2C_POLLED */ static int stm32_i2c_init(FAR struct stm32_i2c_priv_s *priv); @@ -387,7 +378,6 @@ static const struct stm32_i2c_config_s stm32_i2c1_config = .scl_pin = GPIO_I2C1_SCL, .sda_pin = GPIO_I2C1_SDA, #ifndef CONFIG_I2C_POLLED - .isr = stm32_i2c1_isr, .ev_irq = STM32_IRQ_I2C1EV, .er_irq = STM32_IRQ_I2C1ER #endif @@ -417,7 +407,6 @@ static const struct stm32_i2c_config_s stm32_i2c2_config = .scl_pin = GPIO_I2C2_SCL, .sda_pin = GPIO_I2C2_SDA, #ifndef CONFIG_I2C_POLLED - .isr = stm32_i2c2_isr, .ev_irq = STM32_IRQ_I2C2EV, .er_irq = STM32_IRQ_I2C2ER #endif @@ -447,7 +436,6 @@ static const struct stm32_i2c_config_s stm32_i2c3_config = .scl_pin = GPIO_I2C3_SCL, .sda_pin = GPIO_I2C3_SDA, #ifndef CONFIG_I2C_POLLED - .isr = stm32_i2c3_isr, .ev_irq = STM32_IRQ_I2C3EV, .er_irq = STM32_IRQ_I2C3ER #endif @@ -686,7 +674,7 @@ static int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv) * reports that it is done. */ - stm32_i2c_isr(priv); + stm32_i2c_isr_process(priv); } /* Loop until the transfer is complete. */ @@ -1180,7 +1168,7 @@ static inline void stm32_i2c_enablefsmc(uint32_t ahbenr) #endif /* I2C1_FSMC_CONFLICT */ /************************************************************************************ - * Name: stm32_i2c_isr + * Name: stm32_i2c_isr_process * * Description: * Common interrupt service routine (ISR) that handles I2C protocol logic. @@ -1202,7 +1190,7 @@ static inline void stm32_i2c_enablefsmc(uint32_t ahbenr) * ************************************************************************************/ -static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv) +static int stm32_i2c_isr_process(struct stm32_i2c_priv_s *priv) { #ifndef CONFIG_I2C_POLLED uint32_t regval; @@ -1892,55 +1880,22 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv) } /************************************************************************************ - * Name: stm32_i2c1_isr + * Name: stm32_i2c_isr * * Description: - * I2C1 interrupt service routine + * Common I2C interrupt service routine * ************************************************************************************/ #ifndef CONFIG_I2C_POLLED -#ifdef CONFIG_STM32_I2C1 -static int stm32_i2c1_isr(int irq, void *context, FAR void *arg) -{ - return stm32_i2c_isr(&stm32_i2c1_priv); -} -#endif - -/************************************************************************************ - * Name: stm32_i2c2_isr - * - * Description: - * I2C2 interrupt service routine - * - ************************************************************************************/ - -#ifdef CONFIG_STM32_I2C2 -static int stm32_i2c2_isr(int irq, void *context, FAR void *arg) +static int stm32_i2c_isr(int irq, void *context, FAR void *arg) { - return stm32_i2c_isr(&stm32_i2c2_priv); -} -#endif + struct stm32_i2c_priv_s *priv = (struct stm32_i2c_priv_s )arg; -/************************************************************************************ - * Name: stm32_i2c3_isr - * - * Description: - * I2C2 interrupt service routine - * - ************************************************************************************/ - -#ifdef CONFIG_STM32_I2C3 -static int stm32_i2c3_isr(int irq, void *context, FAR void *arg) -{ - return stm32_i2c_isr(&stm32_i2c3_priv); + DEBUGASSERT(priv != NULL); + return stm32_i2c_isr_process(priv); } #endif -#endif - -/************************************************************************************ - * Private Initialization and Deinitialization - ************************************************************************************/ /************************************************************************************ * Name: stm32_i2c_init @@ -1976,8 +1931,8 @@ static int stm32_i2c_init(FAR struct stm32_i2c_priv_s *priv) /* Attach ISRs */ #ifndef CONFIG_I2C_POLLED - irq_attach(priv->config->ev_irq, priv->config->isr, NULL); - irq_attach(priv->config->er_irq, priv->config->isr, NULL); + irq_attach(priv->config->ev_irq, stm32_i2c_isr, priv); + irq_attach(priv->config->er_irq, stm32_i2c_isr, priv); up_enable_irq(priv->config->ev_irq); up_enable_irq(priv->config->er_irq); #endif diff --git a/arch/arm/src/stm32/stm32f30xxx_i2c.c b/arch/arm/src/stm32/stm32f30xxx_i2c.c index ba7c02ea65..539305194d 100644 --- a/arch/arm/src/stm32/stm32f30xxx_i2c.c +++ b/arch/arm/src/stm32/stm32f30xxx_i2c.c @@ -222,7 +222,6 @@ struct stm32_i2c_config_s uint32_t scl_pin; /* GPIO configuration for SCL as SCL */ uint32_t sda_pin; /* GPIO configuration for SDA as SDA */ #ifndef CONFIG_I2C_POLLED - int (*isr)(int, void *, void *); /* Interrupt handler */ uint32_t ev_irq; /* Event IRQ */ uint32_t er_irq; /* Error IRQ */ #endif @@ -301,17 +300,9 @@ static inline void stm32_i2c_sendstart(FAR struct stm32_i2c_priv_s *priv); static inline void stm32_i2c_clrstart(FAR struct stm32_i2c_priv_s *priv); static inline void stm32_i2c_sendstop(FAR struct stm32_i2c_priv_s *priv); static inline uint32_t stm32_i2c_getstatus(FAR struct stm32_i2c_priv_s *priv); -static int stm32_i2c_isr(struct stm32_i2c_priv_s * priv); +static int stm32_i2c_isr_process(struct stm32_i2c_priv_s * priv); #ifndef CONFIG_I2C_POLLED -#ifdef CONFIG_STM32_I2C1 -static int stm32_i2c1_isr(int irq, void *context, FAR void *arg); -#endif -#ifdef CONFIG_STM32_I2C2 -static int stm32_i2c2_isr(int irq, void *context, FAR void *arg); -#endif -#ifdef CONFIG_STM32_I2C3 -static int stm32_i2c3_isr(int irq, void *context, FAR void *arg); -#endif +static int stm32_i2c_isr(int irq, void *context, FAR void *arg); #endif static int stm32_i2c_init(FAR struct stm32_i2c_priv_s *priv); static int stm32_i2c_deinit(FAR struct stm32_i2c_priv_s *priv); @@ -344,7 +335,6 @@ static const struct stm32_i2c_config_s stm32_i2c1_config = .scl_pin = GPIO_I2C1_SCL, .sda_pin = GPIO_I2C1_SDA, #ifndef CONFIG_I2C_POLLED - .isr = stm32_i2c1_isr, .ev_irq = STM32_IRQ_I2C1EV, .er_irq = STM32_IRQ_I2C1ER #endif @@ -374,7 +364,6 @@ static const struct stm32_i2c_config_s stm32_i2c2_config = .scl_pin = GPIO_I2C2_SCL, .sda_pin = GPIO_I2C2_SDA, #ifndef CONFIG_I2C_POLLED - .isr = stm32_i2c2_isr, .ev_irq = STM32_IRQ_I2C2EV, .er_irq = STM32_IRQ_I2C2ER #endif @@ -404,7 +393,6 @@ static const struct stm32_i2c_config_s stm32_i2c3_config = .scl_pin = GPIO_I2C3_SCL, .sda_pin = GPIO_I2C3_SDA, #ifndef CONFIG_I2C_POLLED - .isr = stm32_i2c3_isr, .ev_irq = STM32_IRQ_I2C3EV, .er_irq = STM32_IRQ_I2C3ER #endif @@ -712,7 +700,7 @@ static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv) * reports that it is done. */ - stm32_i2c_isr(priv); + stm32_i2c_isr_process(priv); } /* Loop until the transfer is complete. */ @@ -1243,7 +1231,7 @@ static inline uint32_t stm32_i2c_getstatus(FAR struct stm32_i2c_priv_s *priv) } /************************************************************************************ - * Name: stm32_i2c_isr + * Name: stm32_i2c_isr_startmessage * * Description: * Common logic when a message is started. Just adds the even to the trace buffer @@ -1276,14 +1264,14 @@ static inline void stm32_i2c_clearinterrupts(struct stm32_i2c_priv_s *priv) } /************************************************************************************ - * Name: stm32_i2c_isr + * Name: stm32_i2c_isr_process * * Description: * Common Interrupt Service Routine * ************************************************************************************/ -static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv) +static int stm32_i2c_isr_process(struct stm32_i2c_priv_s *priv) { uint32_t status = stm32_i2c_getstatus(priv); @@ -1485,56 +1473,23 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv) } /************************************************************************************ - * Name: stm32_i2c1_isr + * Name: stm32_i2c_isr * * Description: - * I2C1 interrupt service routine + * Common I2C interrupt service routine * ************************************************************************************/ #ifndef CONFIG_I2C_POLLED -#ifdef CONFIG_STM32_I2C1 -static int stm32_i2c1_isr(int irq, void *context, FAR void *arg) +static int stm32_i2c_isr(int irq, void *context, FAR void *arg) { - return stm32_i2c_isr(&stm32_i2c1_priv); -} -#endif - -/************************************************************************************ - * Name: stm32_i2c2_isr - * - * Description: - * I2C2 interrupt service routine - * - ************************************************************************************/ + struct stm32_i2c_priv_s *priv = (struct stm32_i2c_priv_s *)arg; -#ifdef CONFIG_STM32_I2C2 -static int stm32_i2c2_isr(int irq, void *context, FAR void *arg) -{ - return stm32_i2c_isr(&stm32_i2c2_priv); + DEBUGASSERT(priv != NULL); + return stm32_i2c_isr_process(priv); } #endif -/************************************************************************************ - * Name: stm32_i2c3_isr - * - * Description: - * I2C2 interrupt service routine - * - ************************************************************************************/ - -#ifdef CONFIG_STM32_I2C3 -static int stm32_i2c3_isr(int irq, void *context, FAR void *arg) -{ - return stm32_i2c_isr(&stm32_i2c3_priv); -} -#endif -#endif - -/************************************************************************************ - * Private Initialization and Deinitialization - ************************************************************************************/ - /************************************************************************************ * Name: stm32_i2c_init * @@ -1569,8 +1524,8 @@ static int stm32_i2c_init(FAR struct stm32_i2c_priv_s *priv) /* Attach ISRs */ #ifndef CONFIG_I2C_POLLED - irq_attach(priv->config->ev_irq, priv->config->isr, NULL); - irq_attach(priv->config->er_irq, priv->config->isr, NULL); + irq_attach(priv->config->ev_irq, stm32_i2c_isr, priv); + irq_attach(priv->config->er_irq, stm32_i2c_isr, priv); up_enable_irq(priv->config->ev_irq); up_enable_irq(priv->config->er_irq); #endif diff --git a/arch/arm/src/stm32/stm32f40xxx_i2c.c b/arch/arm/src/stm32/stm32f40xxx_i2c.c index 12080928c2..1eccabd4cd 100644 --- a/arch/arm/src/stm32/stm32f40xxx_i2c.c +++ b/arch/arm/src/stm32/stm32f40xxx_i2c.c @@ -245,7 +245,6 @@ struct stm32_i2c_config_s uint32_t scl_pin; /* GPIO configuration for SCL as SCL */ uint32_t sda_pin; /* GPIO configuration for SDA as SDA */ #ifndef CONFIG_I2C_POLLED - int (*isr)(int, void *, void *); /* Interrupt handler */ uint32_t ev_irq; /* Event IRQ */ uint32_t er_irq; /* Error IRQ */ #endif @@ -339,18 +338,10 @@ static inline uint32_t stm32_i2c_disablefsmc(FAR struct stm32_i2c_priv_s *priv); static inline void stm32_i2c_enablefsmc(uint32_t ahbenr); #endif /* I2C1_FSMC_CONFLICT */ -static int stm32_i2c_isr(struct stm32_i2c_priv_s * priv); +static int stm32_i2c_isr_process(struct stm32_i2c_priv_s *priv); #ifndef CONFIG_I2C_POLLED -#ifdef CONFIG_STM32_I2C1 -static int stm32_i2c1_isr(int irq, void *context, FAR void *arg); -#endif -#ifdef CONFIG_STM32_I2C2 -static int stm32_i2c2_isr(int irq, void *context, FAR void *arg); -#endif -#ifdef CONFIG_STM32_I2C3 -static int stm32_i2c3_isr(int irq, void *context, FAR void *arg); -#endif +static int stm32_i2c_isr(int irq, void *context, FAR void *arg); #endif /* !CONFIG_I2C_POLLED */ static int stm32_i2c_init(FAR struct stm32_i2c_priv_s *priv); @@ -364,8 +355,8 @@ static int stm32_i2c_reset(FAR struct i2c_master_s *dev); /* DMA support */ #ifdef CONFIG_STM32_I2C_DMA -static void stm32_i2c_dmarxcallback(DMA_HANDLE handle, uint8_t isr, void *arg); -static void stm32_i2c_dmatxcallback(DMA_HANDLE handle, uint8_t isr, void *arg); +static void stm32_i2c_dmarxcallback(DMA_HANDLE handle, uint8_t status, void *arg); +static void stm32_i2c_dmatxcallback(DMA_HANDLE handle, uint8_t status, void *arg); #endif /************************************************************************************ @@ -412,7 +403,6 @@ static const struct stm32_i2c_config_s stm32_i2c1_config = .scl_pin = GPIO_I2C1_SCL, .sda_pin = GPIO_I2C1_SDA, #ifndef CONFIG_I2C_POLLED - .isr = stm32_i2c1_isr, .ev_irq = STM32_IRQ_I2C1EV, .er_irq = STM32_IRQ_I2C1ER #endif @@ -451,7 +441,6 @@ static const struct stm32_i2c_config_s stm32_i2c2_config = .scl_pin = GPIO_I2C2_SCL, .sda_pin = GPIO_I2C2_SDA, #ifndef CONFIG_I2C_POLLED - .isr = stm32_i2c2_isr, .ev_irq = STM32_IRQ_I2C2EV, .er_irq = STM32_IRQ_I2C2ER #endif @@ -488,7 +477,6 @@ static const struct stm32_i2c_config_s stm32_i2c3_config = .scl_pin = GPIO_I2C3_SCL, .sda_pin = GPIO_I2C3_SDA, #ifndef CONFIG_I2C_POLLED - .isr = stm32_i2c3_isr, .ev_irq = STM32_IRQ_I2C3EV, .er_irq = STM32_IRQ_I2C3ER #endif @@ -734,7 +722,7 @@ static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv) * reports that it is done. */ - stm32_i2c_isr(priv); + stm32_i2c_isr_process(priv); } /* Loop until the transfer is complete. */ @@ -1229,14 +1217,14 @@ static inline void stm32_i2c_enablefsmc(uint32_t ahbenr) #endif /* I2C1_FSMC_CONFLICT */ /************************************************************************************ - * Name: stm32_i2c_isr + * Name: stm32_i2c_isr_process * * Description: * Common Interrupt Service Routine * ************************************************************************************/ -static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv) +static int stm32_i2c_isr_process(struct stm32_i2c_priv_s *priv) { uint32_t status; #ifndef CONFIG_I2C_POLLED @@ -2069,6 +2057,24 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv) return OK; } +/************************************************************************************ + * Name: stm32_i2c_isr + * + * Description: + * Common I2C interrupt service routine + * + ************************************************************************************/ + +#ifndef CONFIG_I2C_POLLED +static int stm32_i2c_isr(int irq, void *context, FAR void *arg) +{ + struct stm32_i2c_priv_s *priv = (struct stm32_i2c_priv_s *)arg; + + DEBUGASSERT(priv != NULL); + return stm32_i2c_isr_process(priv); +} +#endif + /***************************************************************************** * Name: stm32_i2c_dmarxcallback * @@ -2119,7 +2125,7 @@ static void stm32_i2c_dmarxcallback(DMA_HANDLE handle, uint8_t status, void *arg /* let the ISR routine take care of shutting down or switching to next msg */ - stm32_i2c_isr(priv); + stm32_i2c_isr_process(priv); } #endif /* ifdef CONFIG_STM32_I2C_DMA */ @@ -2158,57 +2164,6 @@ static void stm32_i2c_dmatxcallback(DMA_HANDLE handle, uint8_t status, void *arg } #endif /* ifdef CONFIG_STM32_I2C_DMA */ -/************************************************************************************ - * Name: stm32_i2c1_isr - * - * Description: - * I2C1 interrupt service routine - * - ************************************************************************************/ - -#ifndef CONFIG_I2C_POLLED -#ifdef CONFIG_STM32_I2C1 -static int stm32_i2c1_isr(int irq, void *context, FAR void *arg) -{ - return stm32_i2c_isr(&stm32_i2c1_priv); -} -#endif - -/************************************************************************************ - * Name: stm32_i2c2_isr - * - * Description: - * I2C2 interrupt service routine - * - ************************************************************************************/ - -#ifdef CONFIG_STM32_I2C2 -static int stm32_i2c2_isr(int irq, void *context, FAR void *arg) -{ - return stm32_i2c_isr(&stm32_i2c2_priv); -} -#endif - -/************************************************************************************ - * Name: stm32_i2c3_isr - * - * Description: - * I2C2 interrupt service routine - * - ************************************************************************************/ - -#ifdef CONFIG_STM32_I2C3 -static int stm32_i2c3_isr(int irq, void *context, FAR void *arg) -{ - return stm32_i2c_isr(&stm32_i2c3_priv); -} -#endif -#endif /* CONFIG_I2C_POLLED */ - -/************************************************************************************ - * Private Initialization and Deinitialization - ************************************************************************************/ - /************************************************************************************ * Name: stm32_i2c_init * @@ -2243,8 +2198,8 @@ static int stm32_i2c_init(FAR struct stm32_i2c_priv_s *priv) /* Attach ISRs */ #ifndef CONFIG_I2C_POLLED - irq_attach(priv->config->ev_irq, priv->config->isr, NULL); - irq_attach(priv->config->er_irq, priv->config->isr, NULL); + irq_attach(priv->config->ev_irq, stm32_i2c_isr, priv); + irq_attach(priv->config->er_irq, stm32_i2c_isr, priv); up_enable_irq(priv->config->ev_irq); up_enable_irq(priv->config->er_irq); #endif diff --git a/arch/arm/src/stm32f7/stm32_i2c.c b/arch/arm/src/stm32f7/stm32_i2c.c index f87633364c..be3122ea4e 100644 --- a/arch/arm/src/stm32f7/stm32_i2c.c +++ b/arch/arm/src/stm32f7/stm32_i2c.c @@ -402,7 +402,6 @@ struct stm32_i2c_config_s uint32_t scl_pin; /* GPIO configuration for SCL as SCL */ uint32_t sda_pin; /* GPIO configuration for SDA as SDA */ #ifndef CONFIG_I2C_POLLED - int (*isr)(int, void *, void *); /* Interrupt handler */ uint32_t ev_irq; /* Event IRQ */ uint32_t er_irq; /* Error IRQ */ #endif @@ -484,20 +483,9 @@ static void stm32_i2c_setclock(FAR struct stm32_i2c_priv_s *priv, static inline void stm32_i2c_sendstart(FAR struct stm32_i2c_priv_s *priv); static inline void stm32_i2c_sendstop(FAR struct stm32_i2c_priv_s *priv); static inline uint32_t stm32_i2c_getstatus(FAR struct stm32_i2c_priv_s *priv); -static int stm32_i2c_isr(struct stm32_i2c_priv_s * priv); +static int stm32_i2c_isr_process(struct stm32_i2c_priv_s * priv); #ifndef CONFIG_I2C_POLLED -# ifdef CONFIG_STM32F7_I2C1 -static int stm32_i2c1_isr(int irq, void *context, FAR void *arg); -# endif -# ifdef CONFIG_STM32F7_I2C2 -static int stm32_i2c2_isr(int irq, void *context, FAR void *arg); -# endif -# ifdef CONFIG_STM32F7_I2C3 -static int stm32_i2c3_isr(int irq, void *context, FAR void *arg); -# endif -# ifdef CONFIG_STM32F7_I2C4 -static int stm32_i2c4_isr(int irq, void *context, FAR void *arg); -# endif +static int stm32_i2c_isr(int irq, void *context, FAR void *arg); #endif static int stm32_i2c_init(FAR struct stm32_i2c_priv_s *priv); static int stm32_i2c_deinit(FAR struct stm32_i2c_priv_s *priv); @@ -523,7 +511,6 @@ static const struct stm32_i2c_config_s stm32_i2c1_config = .scl_pin = GPIO_I2C1_SCL, .sda_pin = GPIO_I2C1_SDA, #ifndef CONFIG_I2C_POLLED - .isr = stm32_i2c1_isr, .ev_irq = STM32_IRQ_I2C1EV, .er_irq = STM32_IRQ_I2C1ER #endif @@ -553,7 +540,6 @@ static const struct stm32_i2c_config_s stm32_i2c2_config = .scl_pin = GPIO_I2C2_SCL, .sda_pin = GPIO_I2C2_SDA, #ifndef CONFIG_I2C_POLLED - .isr = stm32_i2c2_isr, .ev_irq = STM32_IRQ_I2C2EV, .er_irq = STM32_IRQ_I2C2ER #endif @@ -583,7 +569,6 @@ static const struct stm32_i2c_config_s stm32_i2c3_config = .scl_pin = GPIO_I2C3_SCL, .sda_pin = GPIO_I2C3_SDA, #ifndef CONFIG_I2C_POLLED - .isr = stm32_i2c3_isr, .ev_irq = STM32_IRQ_I2C3EV, .er_irq = STM32_IRQ_I2C3ER #endif @@ -613,7 +598,6 @@ static const struct stm32_i2c_config_s stm32_i2c4_config = .scl_pin = GPIO_I2C4_SCL, .sda_pin = GPIO_I2C4_SDA, #ifndef CONFIG_I2C_POLLED - .isr = stm32_i2c4_isr, .ev_irq = STM32_IRQ_I2C4EV, .er_irq = STM32_IRQ_I2C4ER #endif @@ -905,7 +889,7 @@ static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv) * reports that it is done. */ - stm32_i2c_isr(priv); + stm32_i2c_isr_process(priv); } /* Loop until the transfer is complete. */ @@ -1538,7 +1522,7 @@ static inline void stm32_i2c_clearinterrupts(struct stm32_i2c_priv_s *priv) } /************************************************************************************ - * Name: stm32_i2c_isr + * Name: stm32_i2c_isr_process * * Description: * Common interrupt service routine (ISR) that handles I2C protocol logic. @@ -1555,7 +1539,7 @@ static inline void stm32_i2c_clearinterrupts(struct stm32_i2c_priv_s *priv) * ************************************************************************************/ -static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv) +static int stm32_i2c_isr_process(struct stm32_i2c_priv_s *priv) { uint32_t status; @@ -2144,71 +2128,23 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv) } /************************************************************************************ - * Name: stm32_i2c1_isr + * Name: stm32_i2c_isr * * Description: - * I2C1 interrupt service routine + * Common I2C interrupt service routine * ************************************************************************************/ #ifndef CONFIG_I2C_POLLED -# ifdef CONFIG_STM32F7_I2C1 -static int stm32_i2c1_isr(int irq, void *context, FAR void *arg) +static int stm32_i2c_isr(int irq, void *context, FAR void *arg) { - return stm32_i2c_isr(&stm32_i2c1_priv); -} -# endif - -/************************************************************************************ - * Name: stm32_i2c2_isr - * - * Description: - * I2C2 interrupt service routine - * - ************************************************************************************/ + struct stm32_i2c_priv_s *priv = (struct stm32_i2c_priv_s *)arg; -# ifdef CONFIG_STM32F7_I2C2 -static int stm32_i2c2_isr(int irq, void *context, FAR void *arg) -{ - return stm32_i2c_isr(&stm32_i2c2_priv); + DEBUGASSERT(priv != NULL); + return stm32_i2c_isr_process(&stm32_i2c1_priv); } -# endif - -/************************************************************************************ - * Name: stm32_i2c3_isr - * - * Description: - * I2C2 interrupt service routine - * - ************************************************************************************/ - -# ifdef CONFIG_STM32F7_I2C3 -static int stm32_i2c3_isr(int irq, void *context, FAR void *arg) -{ - return stm32_i2c_isr(&stm32_i2c3_priv); -} -# endif - -/************************************************************************************ - * Name: stm32_i2c4_isr - * - * Description: - * I2C2 interrupt service routine - * - ************************************************************************************/ - -# ifdef CONFIG_STM32F7_I2C4 -static int stm32_i2c4_isr(int irq, void *context, FAR void *arg) -{ - return stm32_i2c_isr(&stm32_i2c4_priv); -} -# endif #endif -/************************************************************************************ - * Private Initialization and Deinitialization - ************************************************************************************/ - /************************************************************************************ * Name: stm32_i2c_init * @@ -2243,8 +2179,8 @@ static int stm32_i2c_init(FAR struct stm32_i2c_priv_s *priv) #ifndef CONFIG_I2C_POLLED /* Attach error and event interrupts to the ISRs */ - irq_attach(priv->config->ev_irq, priv->config->isr, NULL); - irq_attach(priv->config->er_irq, priv->config->isr, NULL); + irq_attach(priv->config->ev_irq, stm32_i2c_isr, priv); + irq_attach(priv->config->er_irq, stm32_i2c_isr, priv); up_enable_irq(priv->config->ev_irq); up_enable_irq(priv->config->er_irq); #endif -- GitLab From 407fe13b8f32a5645cb5ddf805f8281c1ea9670e Mon Sep 17 00:00:00 2001 From: Simon Piriou Date: Sun, 30 Apr 2017 20:28:56 +0200 Subject: [PATCH 657/990] pkt: fix compilation error --- net/pkt/pkt.h | 1 + 1 file changed, 1 insertion(+) diff --git a/net/pkt/pkt.h b/net/pkt/pkt.h index aa6237da81..250335697c 100644 --- a/net/pkt/pkt.h +++ b/net/pkt/pkt.h @@ -43,6 +43,7 @@ #include #include +#include #ifdef CONFIG_NET_PKT -- GitLab From fe77735960cd85f4ce0b914b40028b75230d458c Mon Sep 17 00:00:00 2001 From: Simon Piriou Date: Sun, 30 Apr 2017 20:29:48 +0200 Subject: [PATCH 658/990] bcmf: add netdev support for Broadcom FullMAC driver --- configs/photon/wlan/defconfig | 57 ++- drivers/wireless/ieee80211/bcmf_bdc.c | 76 +++- drivers/wireless/ieee80211/bcmf_bdc.h | 15 +- drivers/wireless/ieee80211/bcmf_cdc.c | 13 +- drivers/wireless/ieee80211/bcmf_driver.c | 76 ++-- drivers/wireless/ieee80211/bcmf_driver.h | 34 +- drivers/wireless/ieee80211/bcmf_netdev.c | 457 +++++++++-------------- drivers/wireless/ieee80211/bcmf_netdev.h | 47 +++ drivers/wireless/ieee80211/bcmf_sdio.c | 116 +++++- drivers/wireless/ieee80211/bcmf_sdio.h | 25 +- drivers/wireless/ieee80211/bcmf_sdpcm.c | 281 +++++++------- drivers/wireless/ieee80211/bcmf_sdpcm.h | 11 +- drivers/wireless/ieee80211/bcmf_utils.c | 65 ++++ drivers/wireless/ieee80211/bcmf_utils.h | 10 + 14 files changed, 790 insertions(+), 493 deletions(-) create mode 100644 drivers/wireless/ieee80211/bcmf_netdev.h diff --git a/configs/photon/wlan/defconfig b/configs/photon/wlan/defconfig index 190a639960..7f886b89b1 100644 --- a/configs/photon/wlan/defconfig +++ b/configs/photon/wlan/defconfig @@ -16,7 +16,7 @@ CONFIG_HOST_LINUX=y # # Build Configuration # -# CONFIG_APPS_DIR="../apps" +CONFIG_APPS_DIR="../apps" CONFIG_BUILD_FLAT=y # CONFIG_BUILD_2PASS is not set @@ -65,7 +65,10 @@ CONFIG_DEBUG_INFO=y # CONFIG_DEBUG_GRAPHICS is not set # CONFIG_DEBUG_LIB is not set # CONFIG_DEBUG_MM is not set -# CONFIG_DEBUG_NET is not set +CONFIG_DEBUG_NET=y +CONFIG_DEBUG_NET_ERROR=y +CONFIG_DEBUG_NET_WARN=y +CONFIG_DEBUG_NET_INFO=y CONFIG_DEBUG_WIRELESS=y CONFIG_DEBUG_WIRELESS_ERROR=y CONFIG_DEBUG_WIRELESS_WARN=y @@ -986,9 +989,9 @@ CONFIG_NET=y # # Driver buffer configuration # -CONFIG_NET_ETH_MTU=590 +CONFIG_NET_ETH_MTU=800 CONFIG_NET_ETH_TCP_RECVWNDO=536 -CONFIG_NET_GUARDSIZE=2 +CONFIG_NET_GUARDSIZE=32 # # Data link support @@ -1018,12 +1021,14 @@ CONFIG_NET_IPv4=y # CONFIG_NSOCKET_DESCRIPTORS=8 CONFIG_NET_NACTIVESOCKETS=16 -# CONFIG_NET_SOCKOPTS is not set +CONFIG_NET_SOCKOPTS=y +# CONFIG_NET_SOLINGER is not set # # Raw Socket Support # -# CONFIG_NET_PKT is not set +CONFIG_NET_PKT=y +CONFIG_NET_PKT_CONNS=1 # # Unix Domain Socket Support @@ -1049,13 +1054,19 @@ CONFIG_NET_TCP_RECVDELAY=0 # # UDP Networking # -# CONFIG_NET_UDP is not set +CONFIG_NET_UDP=y # CONFIG_NET_UDP_NO_STACK is not set +# CONFIG_NET_UDP_CHECKSUMS is not set +CONFIG_NET_UDP_CONNS=8 +CONFIG_NET_BROADCAST=y +# CONFIG_NET_RXAVAIL is not set +CONFIG_NET_UDP_READAHEAD=y # # ICMP Networking Support # -# CONFIG_NET_ICMP is not set +CONFIG_NET_ICMP=y +# CONFIG_NET_ICMP_PING is not set # # IGMPv2 Client Support @@ -1070,6 +1081,7 @@ CONFIG_NET_ARPTAB_SIZE=16 CONFIG_NET_ARP_MAXAGE=120 # CONFIG_NET_ARP_IPIN is not set # CONFIG_NET_ARP_SEND is not set +# CONFIG_NET_ARP_DUMP is not set # # User-space networking stack API @@ -1106,6 +1118,7 @@ CONFIG_FS_READABLE=y CONFIG_FS_MQUEUE_MPATH="/var/mqueue" # CONFIG_FS_RAMMAP is not set # CONFIG_FS_FAT is not set +# CONFIG_NFS is not set # CONFIG_FS_NXFFS is not set # CONFIG_FS_ROMFS is not set # CONFIG_FS_TMPFS is not set @@ -1251,6 +1264,15 @@ CONFIG_LIBC_NETDB=y # NETDB Support # # CONFIG_NETDB_HOSTFILE is not set +CONFIG_NETDB_DNSCLIENT=y +CONFIG_NETDB_DNSCLIENT_ENTRIES=8 +CONFIG_NETDB_DNSCLIENT_NAMESIZE=32 +CONFIG_NETDB_DNSCLIENT_LIFESEC=3600 +CONFIG_NETDB_DNSCLIENT_MAXRESPONSE=96 +# CONFIG_NETDB_RESOLVCONF is not set +# CONFIG_NETDB_DNSSERVER_NOADDR is not set +CONFIG_NETDB_DNSSERVER_IPv4=y +CONFIG_NETDB_DNSSERVER_IPv4ADDR=0x0a000001 # CONFIG_LIBC_IOCTL_VARIADIC is not set CONFIG_LIB_SENDFILE_BUFSIZE=512 @@ -1306,6 +1328,7 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_CONFIGDATA is not set # CONFIG_EXAMPLES_CXXTEST is not set # CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_DISCOVER is not set # CONFIG_EXAMPLES_ELF is not set # CONFIG_EXAMPLES_FTPC is not set # CONFIG_EXAMPLES_FTPD is not set @@ -1320,6 +1343,7 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set +# CONFIG_EXAMPLES_NETPKT is not set # CONFIG_EXAMPLES_NETTEST is not set # CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y @@ -1351,6 +1375,8 @@ CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_TELNETD is not set # CONFIG_EXAMPLES_TIFF is not set # CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_UDP is not set +# CONFIG_EXAMPLES_UDPBLASTER is not set # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set @@ -1391,12 +1417,20 @@ CONFIG_EXAMPLES_NSH=y # Network Utilities # # CONFIG_NETUTILS_CODECS is not set +CONFIG_NETUTILS_DHCPC=y +# CONFIG_NETUTILS_DHCPD is not set +# CONFIG_NETUTILS_DISCOVER is not set # CONFIG_NETUTILS_ESP8266 is not set # CONFIG_NETUTILS_FTPC is not set # CONFIG_NETUTILS_JSON is not set CONFIG_NETUTILS_NETLIB=y +# CONFIG_NETUTILS_NTPCLIENT is not set +CONFIG_NETUTILS_PING=y +CONFIG_NETUTILS_PING_SIGNO=13 +# CONFIG_NETUTILS_PPPD is not set # CONFIG_NETUTILS_SMTP is not set # CONFIG_NETUTILS_TELNETD is not set +# CONFIG_NETUTILS_TFTPC is not set # CONFIG_NETUTILS_WEBCLIENT is not set # CONFIG_NETUTILS_WEBSERVER is not set # CONFIG_NETUTILS_XMLRPC is not set @@ -1456,8 +1490,10 @@ CONFIG_NSH_DISABLE_LOSMART=y # CONFIG_NSH_DISABLE_MOUNT is not set # CONFIG_NSH_DISABLE_MV is not set # CONFIG_NSH_DISABLE_MW is not set +# CONFIG_NSH_DISABLE_NSLOOKUP is not set CONFIG_NSH_DISABLE_PRINTF=y # CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PING is not set # CONFIG_NSH_DISABLE_PUT is not set # CONFIG_NSH_DISABLE_PWD is not set # CONFIG_NSH_DISABLE_RM is not set @@ -1510,13 +1546,14 @@ CONFIG_NSH_NETINIT=y # # IP Address Configuration # +CONFIG_NSH_DHCPC=y # # IPv4 Addresses # -CONFIG_NSH_IPADDR=0x0a000002 -CONFIG_NSH_DRIPADDR=0x0a000001 +CONFIG_NSH_DRIPADDR=0xc0a80001 CONFIG_NSH_NETMASK=0xffffff00 +# CONFIG_NSH_DNS is not set # CONFIG_NSH_NOMAC is not set CONFIG_NSH_MAX_ROUNDTRIP=20 # CONFIG_NSH_LOGIN is not set diff --git a/drivers/wireless/ieee80211/bcmf_bdc.c b/drivers/wireless/ieee80211/bcmf_bdc.c index 8f448e5bc0..2c92232ff3 100644 --- a/drivers/wireless/ieee80211/bcmf_bdc.c +++ b/drivers/wireless/ieee80211/bcmf_bdc.c @@ -101,31 +101,29 @@ static const uint8_t bcmf_broadcom_oui[] = {0x00, 0x10, 0x18}; * Private Functions ****************************************************************************/ +/**************************************************************************** + * Public Functions + ****************************************************************************/ + struct bcmf_frame_s* bcmf_bdc_allocate_frame(FAR struct bcmf_dev_s *priv, uint32_t len, bool block) { - if (len <= 0) - { - return NULL; - } + struct bcmf_frame_s *frame; /* Allocate data frame */ - return priv->bus->allocate_frame(priv, - sizeof(struct bcmf_bdc_header) + len, - false, block); -} + // TODO check for integer overflow + frame = priv->bus->allocate_frame(priv, + sizeof(struct bcmf_bdc_header) + len, block, false); -/**************************************************************************** - * Public Functions - ****************************************************************************/ + if (!frame) + { + return NULL; + } -int bcmf_bdc_process_data_frame(FAR struct bcmf_dev_s *priv, - struct bcmf_frame_s *frame) -{ - wlinfo("Data message\n"); - bcmf_hexdump(frame->base, frame->len, (unsigned long)frame->base); - return OK; + frame->data += sizeof(struct bcmf_bdc_header); + + return frame; } int bcmf_bdc_process_event_frame(FAR struct bcmf_dev_s *priv, @@ -240,4 +238,48 @@ int bcmf_event_push_config(FAR struct bcmf_dev_s *priv) } return OK; +} + +int bcmf_bdc_transmit_frame(FAR struct bcmf_dev_s *priv, + struct bcmf_frame_s *frame) +{ + struct bcmf_bdc_header* header; + + /* Set frame data for lower layer */ + + frame->data -= sizeof(struct bcmf_bdc_header); + header = (struct bcmf_bdc_header*)frame->data; + + /* Setup data frame header */ + + header->flags = 0x20; /* Set bdc protocol version */ + header->priority = 0; // TODO handle priority + header->flags2 = CHIP_STA_INTERFACE; + header->data_offset = 0; + + /* Send frame */ + + return priv->bus->txframe(priv, frame, false); +} + +struct bcmf_frame_s* bcmf_bdc_rx_frame(FAR struct bcmf_dev_s *priv) +{ + unsigned int frame_len; + struct bcmf_frame_s *frame = priv->bus->rxframe(priv); + + /* Process bdc header */ + + frame_len = frame->len - (unsigned int)(frame->data - frame->base); + + if (frame_len < sizeof(struct bcmf_bdc_header)) + { + wlerr("Data frame too small\n"); + priv->bus->free_frame(priv, frame); + return NULL; + } + + /* Transmit frame to upper layer */ + + frame->data += sizeof(struct bcmf_bdc_header); + return frame; } \ No newline at end of file diff --git a/drivers/wireless/ieee80211/bcmf_bdc.h b/drivers/wireless/ieee80211/bcmf_bdc.h index 93e0b6c707..48003bdc5c 100644 --- a/drivers/wireless/ieee80211/bcmf_bdc.h +++ b/drivers/wireless/ieee80211/bcmf_bdc.h @@ -69,12 +69,23 @@ typedef void (*event_handler_t)(FAR struct bcmf_dev_s *priv, * Public Function Prototypes ****************************************************************************/ -int bcmf_bdc_process_data_frame(FAR struct bcmf_dev_s *priv, - struct bcmf_frame_s *frame); +/* Function called from lower layer */ int bcmf_bdc_process_event_frame(FAR struct bcmf_dev_s *priv, struct bcmf_frame_s *frame); +/* Function called from upper layer */ + +struct bcmf_frame_s* bcmf_bdc_allocate_frame(FAR struct bcmf_dev_s *priv, + uint32_t len, bool block); + +int bcmf_bdc_transmit_frame(FAR struct bcmf_dev_s *priv, + struct bcmf_frame_s *frame); + +struct bcmf_frame_s* bcmf_bdc_rx_frame(FAR struct bcmf_dev_s *priv); + +/* Event frames API */ + int bcmf_event_register(FAR struct bcmf_dev_s *priv, event_handler_t handler, unsigned int event_id); diff --git a/drivers/wireless/ieee80211/bcmf_cdc.c b/drivers/wireless/ieee80211/bcmf_cdc.c index bff79328e8..a825f6dbdd 100644 --- a/drivers/wireless/ieee80211/bcmf_cdc.c +++ b/drivers/wireless/ieee80211/bcmf_cdc.c @@ -128,13 +128,6 @@ struct bcmf_frame_s* bcmf_cdc_allocate_frame(FAR struct bcmf_dev_s *priv, data_len = 0; } - if (data_len + name_len + sizeof(struct bcmf_cdc_header) < data_len) - { - /* Integer overflow */ - - return NULL; - } - /* Allocate control frame */ frame = priv->bus->allocate_frame(priv, @@ -177,7 +170,7 @@ int bcmf_cdc_sendframe(FAR struct bcmf_dev_s *priv, uint32_t cmd, /* Send frame */ - return priv->bus->txframe(priv, frame); + return priv->bus->txframe(priv, frame, true); } int bcmf_cdc_control_request(FAR struct bcmf_dev_s *priv, @@ -230,7 +223,9 @@ int bcmf_cdc_control_request_unsafe(FAR struct bcmf_dev_s *priv, ret = bcmf_cdc_sendframe(priv, cmd, ifidx, set, frame); if (ret != OK) { - // TODO free allocated iovar buffer here + /* Free allocated iovar buffer */ + + priv->bus->free_frame(priv, frame); return ret; } diff --git a/drivers/wireless/ieee80211/bcmf_driver.c b/drivers/wireless/ieee80211/bcmf_driver.c index d2c522347a..8c623b75ad 100644 --- a/drivers/wireless/ieee80211/bcmf_driver.c +++ b/drivers/wireless/ieee80211/bcmf_driver.c @@ -49,13 +49,13 @@ #include #include +#include #include "bcmf_driver.h" #include "bcmf_cdc.h" #include "bcmf_ioctl.h" #include "bcmf_utils.h" - -#include +#include "bcmf_netdev.h" #include "bcmf_sdio.h" /**************************************************************************** @@ -90,9 +90,6 @@ static void bcmf_free_device(FAR struct bcmf_dev_s *priv); static int bcmf_driver_initialize(FAR struct bcmf_dev_s *priv); -// FIXME add bcmf_netdev.h file -int bcmf_netdev_register(FAR struct bcmf_dev_s *priv); - // FIXME only for debug purpose static void bcmf_wl_default_event_handler(FAR struct bcmf_dev_s *priv, struct bcmf_event_s *event, unsigned int len); @@ -103,9 +100,8 @@ static void bcmf_wl_radio_event_handler(FAR struct bcmf_dev_s *priv, static void bcmf_wl_scan_event_handler(FAR struct bcmf_dev_s *priv, struct bcmf_event_s *event, unsigned int len); -#if 0 -static int bcmf_run_escan(FAR struct bcmf_dev_s *priv); -#endif +static void bcmf_wl_auth_event_handler(FAR struct bcmf_dev_s *priv, + struct bcmf_event_s *event, unsigned int len); /**************************************************************************** * Private Data @@ -149,6 +145,18 @@ FAR struct bcmf_dev_s* bcmf_allocate_device(void) goto exit_free_priv; } + /* Init authentication signal semaphore */ + + if ((ret = sem_init(&priv->auth_signal, 0, 0)) != OK) + { + goto exit_free_priv; + } + + if ((ret = sem_setprotocol(&priv->auth_signal, SEM_PRIO_NONE)) != OK) + { + goto exit_free_priv; + } + /* Init scan timeout timer */ priv->scan_status = BCMF_SCAN_DISABLED; @@ -173,23 +181,27 @@ void bcmf_free_device(FAR struct bcmf_dev_s *priv) kmm_free(priv); } -int bcmf_wl_set_mac_address(FAR struct bcmf_dev_s *priv, uint8_t *addr) +int bcmf_wl_set_mac_address(FAR struct bcmf_dev_s *priv, struct ifreq *req) { int ret; - uint32_t out_len = 6; + uint32_t out_len = IFHWADDRLEN; ret = bcmf_cdc_iovar_request(priv, CHIP_STA_INTERFACE, true, - IOVAR_STR_CUR_ETHERADDR, addr, - &out_len); + IOVAR_STR_CUR_ETHERADDR, + (uint8_t*)req->ifr_hwaddr.sa_data, + &out_len); if (ret != OK) { return ret; } wlinfo("MAC address updated %02X:%02X:%02X:%02X:%02X:%02X\n", - addr[0], addr[1], addr[2], - addr[3], addr[4], addr[5]); - memcpy(priv->bc_dev.d_mac.ether.ether_addr_octet, addr, ETHER_ADDR_LEN); + req->ifr_hwaddr.sa_data[0], req->ifr_hwaddr.sa_data[1], + req->ifr_hwaddr.sa_data[2], req->ifr_hwaddr.sa_data[3], + req->ifr_hwaddr.sa_data[4], req->ifr_hwaddr.sa_data[5]); + + memcpy(priv->bc_dev.d_mac.ether.ether_addr_octet, + req->ifr_hwaddr.sa_data, ETHER_ADDR_LEN); return OK; } @@ -281,6 +293,10 @@ int bcmf_driver_initialize(FAR struct bcmf_dev_s *priv) bcmf_event_register(priv, bcmf_wl_scan_event_handler, WLC_E_ESCAN_RESULT); + /* Register SET_SSID event */ + + bcmf_event_register(priv, bcmf_wl_auth_event_handler, WLC_E_SET_SSID); + if (bcmf_event_push_config(priv)) { return -EIO; @@ -301,8 +317,25 @@ void bcmf_wl_default_event_handler(FAR struct bcmf_dev_s *priv, void bcmf_wl_radio_event_handler(FAR struct bcmf_dev_s *priv, struct bcmf_event_s *event, unsigned int len) { - wlinfo("Got radio event %d from <%s>\n", bcmf_getle32(&event->type), - event->src_name); + // wlinfo("Got radio event %d from <%s>\n", bcmf_getle32(&event->type), + // event->src_name); +} + +void bcmf_wl_auth_event_handler(FAR struct bcmf_dev_s *priv, + struct bcmf_event_s *event, unsigned int len) +{ + uint32_t type; + + type = bcmf_getle32(&event->type); + + wlinfo("Got auth event %d from <%s>\n", type, event->src_name); + + if (type == WLC_E_SET_SSID) + { + /* Auth complete */ + + sem_post(&priv->auth_signal); + } } void bcmf_wl_scan_event_handler(FAR struct bcmf_dev_s *priv, @@ -508,8 +541,6 @@ int bcmf_wl_start_scan(FAR struct bcmf_dev_s *priv) uint32_t out_len; uint32_t value; - wlinfo("Enter\n"); - /* Set active scan mode */ value = 0; @@ -517,14 +548,15 @@ int bcmf_wl_start_scan(FAR struct bcmf_dev_s *priv) if (bcmf_cdc_ioctl(priv, CHIP_STA_INTERFACE, true, WLC_SET_PASSIVE_SCAN, (uint8_t*)&value, &out_len)) { - return -EIO; + ret = -EIO; + goto exit_failed; } /* Lock control_mutex semaphore */ if ((ret = sem_wait(&priv->control_mutex)) != OK) { - return ret; + goto exit_failed; } /* Default request structure */ @@ -581,6 +613,8 @@ exit_free_params: exit_sem_post: sem_post(&priv->control_mutex); priv->scan_status = BCMF_SCAN_DISABLED; +exit_failed: + wlinfo("Failed\n"); return ret; } diff --git a/drivers/wireless/ieee80211/bcmf_driver.h b/drivers/wireless/ieee80211/bcmf_driver.h index edbd911845..c264ca5da9 100644 --- a/drivers/wireless/ieee80211/bcmf_driver.h +++ b/drivers/wireless/ieee80211/bcmf_driver.h @@ -41,6 +41,7 @@ #include #include +#include #include #include @@ -65,13 +66,13 @@ struct bcmf_dev_s bool bc_bifup; /* true:ifup false:ifdown */ WDOG_ID bc_txpoll; /* TX poll timer */ - WDOG_ID bc_txtimeout; /* TX timeout timer */ struct work_s bc_irqwork; /* For deferring interrupt work to the work queue */ struct work_s bc_pollwork; /* For deferring poll work to the work queue */ /* This holds the information visible to the NuttX network */ - struct net_driver_s bc_dev; /* Network interface structure */ + struct net_driver_s bc_dev; /* Network interface structure */ + struct bcmf_frame_s *cur_tx_frame; /* Frame used to interface network layer */ /* Event registration array */ @@ -91,35 +92,48 @@ struct bcmf_dev_s int scan_status; /* Current scan status */ WDOG_ID scan_timeout; /* Scan timeout timer */ struct wl_escan_params *scan_params; /* Current scan parameters */ + + sem_t auth_signal; /* Authentication notification signal */ }; /* Default bus interface structure */ -struct bcmf_bus_dev_s { +struct bcmf_bus_dev_s +{ void (*stop)(FAR struct bcmf_dev_s *priv); - int (*txframe)(FAR struct bcmf_dev_s *priv, struct bcmf_frame_s *frame); + int (*txframe)(FAR struct bcmf_dev_s *priv, struct bcmf_frame_s *frame, + bool control); + struct bcmf_frame_s* (*rxframe)(FAR struct bcmf_dev_s *priv); - /* Frame buffer allocation primitive + /* Frame buffer allocation primitives * len - requested payload length * control - true if control frame else false * block - true to block until free frame is available */ struct bcmf_frame_s* (*allocate_frame)(FAR struct bcmf_dev_s *priv, - unsigned int len, bool control, bool block); + unsigned int len, bool block, + bool control); + + void (*free_frame)(FAR struct bcmf_dev_s *priv, struct bcmf_frame_s* frame); }; /* bcmf frame definition */ -struct bcmf_frame_s { - uint8_t *base; /* Frame base buffer used by low level layer (SDIO) */ - uint8_t *data; /* Payload data (Control, data and event messages) */ - unsigned int len; /* Frame buffer size */ +struct bcmf_frame_s +{ + uint8_t *base; /* Frame base buffer used by low level layer (SDIO) */ + uint8_t *data; /* Payload data (Control, data and event messages) */ + uint16_t len; /* Frame buffer size */ }; +int bcmf_wl_set_mac_address(FAR struct bcmf_dev_s *priv, struct ifreq *req); + int bcmf_wl_enable(FAR struct bcmf_dev_s *priv, bool enable); int bcmf_wl_start_scan(FAR struct bcmf_dev_s *priv); int bcmf_wl_is_scan_done(FAR struct bcmf_dev_s *priv); +int bcmf_wl_associate(FAR struct bcmf_dev_s *priv); + #endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_DRIVER_H */ diff --git a/drivers/wireless/ieee80211/bcmf_netdev.c b/drivers/wireless/ieee80211/bcmf_netdev.c index 7d9a2db225..32dd54176c 100644 --- a/drivers/wireless/ieee80211/bcmf_netdev.c +++ b/drivers/wireless/ieee80211/bcmf_netdev.c @@ -64,6 +64,7 @@ #include "bcmf_driver.h" #include "bcmf_cdc.h" +#include "bcmf_bdc.h" #include "bcmf_ioctl.h" /**************************************************************************** @@ -117,43 +118,20 @@ * Private Data ****************************************************************************/ -/* These statically allocated structur would mean that only a single - * instance of the device could be supported. In order to support multiple - * devices instances, this data would have to be allocated dynamically. - */ - -/* A single packet buffer per device is used here. There might be multiple - * packet buffers in a more complex, pipelined design. - * - * NOTE that if CONFIG_IEEE80211_BROADCOM_NINTERFACES were greater than 1, you would - * need a minimum on one packetbuffer per instance. Much better to be - * allocated dynamically. - */ - -static uint8_t g_pktbuf[MAX_NET_DEV_MTU + CONFIG_NET_GUARDSIZE]; - /**************************************************************************** * Private Function Prototypes ****************************************************************************/ /* Common TX logic */ -static int bcmf_transmit(FAR struct bcmf_dev_s *priv); -static int bcmf_txpoll(FAR struct net_driver_s *dev); - -/* Interrupt handling */ - +static int bcmf_transmit(FAR struct bcmf_dev_s *priv, + struct bcmf_frame_s *frame); static void bcmf_receive(FAR struct bcmf_dev_s *priv); -static void bcmf_txdone(FAR struct bcmf_dev_s *priv); - -static void bcmf_interrupt_work(FAR void *arg); -static int bcmf_interrupt(int irq, FAR void *context, FAR void *arg); +static int bcmf_txpoll(FAR struct net_driver_s *dev); +static void bcmf_rxpoll(FAR void *arg); /* Watchdog timer expirations */ -static void bcmf_txtimeout_work(FAR void *arg); -static void bcmf_txtimeout_expiry(int argc, wdparm_t arg, ...); - static void bcmf_poll_work(FAR void *arg); static void bcmf_poll_expiry(int argc, wdparm_t arg, ...); @@ -185,61 +163,36 @@ static int bcmf_ioctl(FAR struct net_driver_s *dev, int cmd, * Private Functions ****************************************************************************/ -/**************************************************************************** - * Name: bcmf_transmit - * - * Description: - * Start hardware transmission. Called either from the txdone interrupt - * handling or from watchdog based polling. - * - * Parameters: - * priv - Reference to the driver state structure - * - * Returned Value: - * OK on success; a negated errno on failure - * - * Assumptions: - * May or may not be called from an interrupt handler. In either case, - * the network is locked. - * - ****************************************************************************/ - -static int bcmf_transmit(FAR struct bcmf_dev_s *priv) +int bcmf_netdev_alloc_tx_frame(FAR struct bcmf_dev_s *priv) { - /* Verify that the hardware is ready to send another packet. If we get - * here, then we are committed to sending a packet; Higher level logic - * must have assured that there is no transmission in progress. - */ - - /* Increment statistics */ - - NETDEV_TXPACKETS(priv->bc_dev); + if (priv->cur_tx_frame != NULL) + { + /* Frame available */ - /* Send the packet: address=priv->bc_dev.d_buf, length=priv->bc_dev.d_len */ + return OK; + } - /* Enable Tx interrupts */ + /* Allocate frame for TX */ - /* Setup the TX timeout watchdog (perhaps restarting the timer) */ + priv->cur_tx_frame = bcmf_bdc_allocate_frame(priv, MAX_NET_DEV_MTU, true); + if (!priv->cur_tx_frame) + { + wlerr("Cannot allocate TX frame\n"); + return -ENOMEM; + } - (void)wd_start(priv->bc_txtimeout, BCMF_TXTIMEOUT, - bcmf_txtimeout_expiry, 1, (wdparm_t)priv); return OK; } /**************************************************************************** - * Name: bcmf_txpoll + * Name: bcmf_transmit * * Description: - * The transmitter is available, check if the network has any outgoing - * packets ready to send. This is a callback from devif_poll(). - * devif_poll() may be called: - * - * 1. When the preceding TX packet send is complete, - * 2. When the preceding TX packet send timesout and the interface is reset - * 3. During normal TX polling + * Start hardware transmission. Called either from the txdone interrupt + * handling or from watchdog based polling. * * Parameters: - * dev - Reference to the NuttX driver state structure + * priv - Reference to the driver state structure * * Returned Value: * OK on success; a negated errno on failure @@ -250,52 +203,25 @@ static int bcmf_transmit(FAR struct bcmf_dev_s *priv) * ****************************************************************************/ -static int bcmf_txpoll(FAR struct net_driver_s *dev) +static int bcmf_transmit(FAR struct bcmf_dev_s *priv, + struct bcmf_frame_s *frame) { - FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)dev->d_private; + int ret; - /* If the polling resulted in data that should be sent out on the network, - * the field d_len is set to a value > 0. - */ + frame->len = priv->bc_dev.d_len + + (unsigned int)(frame->data - frame->base); + + ret = bcmf_bdc_transmit_frame(priv, frame); - if (priv->bc_dev.d_len > 0) + if (ret) { - /* Look up the destination MAC address and add it to the Ethernet - * header. - */ - -#ifdef CONFIG_NET_IPv4 -#ifdef CONFIG_NET_IPv6 - if (IFF_IS_IPv4(priv->bc_dev.d_flags)) -#endif - { - arp_out(&priv->bc_dev); - } -#endif /* CONFIG_NET_IPv4 */ - -#ifdef CONFIG_NET_IPv6 -#ifdef CONFIG_NET_IPv4 - else -#endif - { - neighbor_out(&priv->bc_dev); - } -#endif /* CONFIG_NET_IPv6 */ - - /* Send the packet */ - - bcmf_transmit(priv); - - /* Check if there is room in the device to hold another packet. If not, - * return a non-zero value to terminate the poll. - */ + wlerr("Failed to transmit frame\n"); + return -EIO; } - /* If zero is returned, the polling will continue until all connections have - * been examined. - */ + NETDEV_TXPACKETS(priv->bc_dev); - return 0; + return OK; } /**************************************************************************** @@ -317,8 +243,27 @@ static int bcmf_txpoll(FAR struct net_driver_s *dev) static void bcmf_receive(FAR struct bcmf_dev_s *priv) { + struct bcmf_frame_s *frame; + // wlinfo("Entry\n"); do { + /* Request frame buffer from bus interface */ + + frame = bcmf_bdc_rx_frame(priv); + + if (frame == NULL) + { + /* No more frame to process */ + break; + } + + priv->bc_dev.d_buf = frame->data; + priv->bc_dev.d_len = frame->len - (uint32_t)(frame->data - frame->base); + + wlinfo("Got frame ! %p %d\n", frame, priv->bc_dev.d_len); + // bcmf_hexdump(priv->bc_dev.d_buf, priv->bc_dev.d_len, + // (unsigned long)priv->bc_dev.d_buf); + /* Check for errors and update statistics */ /* Check if the packet is a valid size for the network buffer @@ -340,7 +285,7 @@ static void bcmf_receive(FAR struct bcmf_dev_s *priv) #ifdef CONFIG_NET_IPv4 if (BUF->type == HTONS(ETHTYPE_IP)) { - ninfo("IPv4 frame\n"); + // ninfo("IPv4 frame\n"); NETDEV_RXIPV4(&priv->bc_dev); /* Handle ARP on input then give the IPv4 packet to the network @@ -373,7 +318,13 @@ static void bcmf_receive(FAR struct bcmf_dev_s *priv) /* And send the packet */ - bcmf_transmit(priv); + bcmf_transmit(priv, frame); + } + else + { + /* Release RX frame buffer */ + + priv->bus->free_frame(priv, frame); } } else @@ -411,7 +362,13 @@ static void bcmf_receive(FAR struct bcmf_dev_s *priv) /* And send the packet */ - bcmf_transmit(priv); + bcmf_transmit(priv, frame); + } + else + { + /* Release RX frame buffer */ + + priv->bus->free_frame(priv, frame); } } else @@ -428,12 +385,19 @@ static void bcmf_receive(FAR struct bcmf_dev_s *priv) if (priv->bc_dev.d_len > 0) { - bcmf_transmit(priv); + bcmf_transmit(priv, frame); + } + else + { + /* Release RX frame buffer */ + + priv->bus->free_frame(priv, frame); } } else #endif { + wlinfo("RX dropped\n"); NETDEV_RXDROPPED(&priv->bc_dev); } } @@ -441,53 +405,89 @@ static void bcmf_receive(FAR struct bcmf_dev_s *priv) } /**************************************************************************** - * Name: bcmf_txdone + * Name: bcmf_txpoll * * Description: - * An interrupt was received indicating that the last TX packet(s) is done + * The transmitter is available, check if the network has any outgoing + * packets ready to send. This is a callback from devif_poll(). + * devif_poll() may be called: + * + * 1. When the preceding TX packet send is complete, + * 2. When the preceding TX packet send timesout and the interface is reset + * 3. During normal TX polling * * Parameters: - * priv - Reference to the driver state structure + * dev - Reference to the NuttX driver state structure * * Returned Value: - * None + * OK on success; a negated errno on failure * * Assumptions: - * The network is locked. + * May or may not be called from an interrupt handler. In either case, + * the network is locked. * ****************************************************************************/ -static void bcmf_txdone(FAR struct bcmf_dev_s *priv) +static int bcmf_txpoll(FAR struct net_driver_s *dev) { - int delay; + FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)dev->d_private; + + wlinfo("Entry\n"); + /* If the polling resulted in data that should be sent out on the network, + * the field d_len is set to a value > 0. + */ - /* Check for errors and update statistics */ + if (priv->bc_dev.d_len > 0) + { + /* Look up the destination MAC address and add it to the Ethernet + * header. + */ - NETDEV_TXDONE(priv->bc_dev); +#ifdef CONFIG_NET_IPv4 +#ifdef CONFIG_NET_IPv6 + if (IFF_IS_IPv4(priv->bc_dev.d_flags)) +#endif + { + arp_out(&priv->bc_dev); + } +#endif /* CONFIG_NET_IPv4 */ - /* Check if there are pending transmissions */ +#ifdef CONFIG_NET_IPv6 +#ifdef CONFIG_NET_IPv4 + else +#endif + { + neighbor_out(&priv->bc_dev); + } +#endif /* CONFIG_NET_IPv6 */ - /* If no further transmissions are pending, then cancel the TX timeout and - * disable further Tx interrupts. - */ + /* Send the packet */ - wd_cancel(priv->bc_txtimeout); + bcmf_transmit(priv, priv->cur_tx_frame); - /* And disable further TX interrupts. */ + /* Check if there is room in the device to hold another packet. If not, + * return a non-zero value to terminate the poll. + */ + // TODO + priv->cur_tx_frame = NULL; + return 1; + } - /* In any event, poll the network for new TX data */ + /* If zero is returned, the polling will continue until all connections have + * been examined. + */ - (void)devif_poll(&priv->bc_dev, bcmf_txpoll); + return 0; } /**************************************************************************** - * Name: bcmf_interrupt_work + * Name: bcmf_rxpoll * * Description: - * Perform interrupt related work from the worker thread + * Process RX frames * * Parameters: - * arg - The argument passed when work_queue() was called. + * arg - context of device to use * * Returned Value: * OK on success @@ -497,8 +497,9 @@ static void bcmf_txdone(FAR struct bcmf_dev_s *priv) * ****************************************************************************/ -static void bcmf_interrupt_work(FAR void *arg) +static void bcmf_rxpoll(FAR void *arg) { + // wlinfo("Entry\n"); FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)arg; /* Lock the network and serialize driver operations if necessary. @@ -509,14 +510,6 @@ static void bcmf_interrupt_work(FAR void *arg) net_lock(); - /* Process pending Ethernet interrupts */ - - /* Get and clear interrupt status bits */ - - /* Handle interrupts according to status bit settings */ - - /* Check if we received an incoming packet, if so, call bcmf_receive() */ - bcmf_receive(priv); /* Check if a packet transmission just completed. If so, call bcmf_txdone. @@ -524,153 +517,42 @@ static void bcmf_interrupt_work(FAR void *arg) * transmissions. */ - bcmf_txdone(priv); + // bcmf_txdone(priv); net_unlock(); - - /* Re-enable Ethernet interrupts */ -#warning Missing logic -} - -/**************************************************************************** - * Name: bcmf_interrupt - * - * Description: - * Hardware interrupt handler - * - * Parameters: - * irq - Number of the IRQ that generated the interrupt - * context - Interrupt register state save info (architecture-specific) - * - * Returned Value: - * OK on success - * - * Assumptions: - * - ****************************************************************************/ - -static int bcmf_interrupt(int irq, FAR void *context, FAR void *arg) -{ - FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)arg; - - DEBUGASSERT(priv != NULL); - - /* Disable further Ethernet interrupts. Because Ethernet interrupts are - * also disabled if the TX timeout event occurs, there can be no race - * condition here. - */ -#warning Missing logic - - /* TODO: Determine if a TX transfer just completed */ - - { - /* If a TX transfer just completed, then cancel the TX timeout so - * there will be no race condition between any subsequent timeout - * expiration and the deferred interrupt processing. - */ - - wd_cancel(priv->bc_txtimeout); - } - - /* Schedule to perform the interrupt processing on the worker thread. */ - - work_queue(BCMFWORK, &priv->bc_irqwork, bcmf_interrupt_work, priv, 0); - return OK; } /**************************************************************************** - * Name: bcmf_txtimeout_work + * Name: bcmf_netdev_notify_tx_done * * Description: - * Perform TX timeout related work from the worker thread - * - * Parameters: - * arg - The argument passed when work_queue() as called. - * - * Returned Value: - * OK on success + * Notify callback called when TX frame is sent and freed. * * Assumptions: - * The network is locked. * ****************************************************************************/ -static void bcmf_txtimeout_work(FAR void *arg) +void bcmf_netdev_notify_tx_done(FAR struct bcmf_dev_s *priv) { - FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)arg; + // wlinfo("Entry\n"); - /* Lock the network and serialize driver operations if necessary. - * NOTE: Serialization is only required in the case where the driver work - * is performed on an LP worker thread and where more than one LP worker - * thread has been configured. - */ - - net_lock(); - - /* Increment statistics and dump debug info */ - - NETDEV_TXTIMEOUTS(priv->bc_dev); - - /* Then reset the hardware */ - - /* Then poll the network for new XMIT data */ - - (void)devif_poll(&priv->bc_dev, bcmf_txpoll); - net_unlock(); + /* TODO TX buffer may be available, try to send again if needed */ } /**************************************************************************** - * Name: bcmf_txtimeout_expiry + * Name: bcmf_netdev_notify_rx * * Description: - * Our TX watchdog timed out. Called from the timer interrupt handler. - * The last TX never completed. Reset the hardware and start again. - * - * Parameters: - * argc - The number of available arguments - * arg - The first argument - * - * Returned Value: - * None + * Notify callback called when RX frame is available * * Assumptions: - * Global interrupts are disabled by the watchdog logic. * ****************************************************************************/ -static void bcmf_txtimeout_expiry(int argc, wdparm_t arg, ...) +void bcmf_netdev_notify_rx(FAR struct bcmf_dev_s *priv) { - FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)arg; - - /* Disable further Ethernet interrupts. This will prevent some race - * conditions with interrupt work. There is still a potential race - * condition with interrupt work that is already queued and in progress. - */ -#warning Missing logic - - /* Schedule to perform the TX timeout processing on the worker thread. */ - - work_queue(BCMFWORK, &priv->bc_irqwork, bcmf_txtimeout_work, priv, 0); -} - -/**************************************************************************** - * Name: bcmf_poll_process - * - * Description: - * Perform the periodic poll. This may be called either from watchdog - * timer logic or from the worker thread, depending upon the configuration. - * - * Parameters: - * priv - Reference to the driver state structure - * - * Returned Value: - * None - * - * Assumptions: - * - ****************************************************************************/ + /* Queue a job to process RX frames */ -static inline void bcmf_poll_process(FAR struct bcmf_dev_s *priv) -{ + work_queue(BCMFWORK, &priv->bc_pollwork, bcmf_rxpoll, priv, 0); } /**************************************************************************** @@ -692,6 +574,7 @@ static inline void bcmf_poll_process(FAR struct bcmf_dev_s *priv) static void bcmf_poll_work(FAR void *arg) { + // wlinfo("Entry\n"); FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)arg; /* Lock the network and serialize driver operations if necessary. @@ -708,17 +591,25 @@ static void bcmf_poll_work(FAR void *arg) * the TX poll if he are unable to accept another packet for transmission. */ + if (bcmf_netdev_alloc_tx_frame(priv)) + { + goto exit_unlock; + } + /* If so, update TCP timing states and poll the network for new XMIT data. * Hmmm.. might be bug here. Does this mean if there is a transmit in * progress, we will missing TCP time state updates? */ + priv->bc_dev.d_buf = priv->cur_tx_frame->data; + priv->bc_dev.d_len = 0; (void)devif_timer(&priv->bc_dev, bcmf_txpoll); /* Setup the watchdog poll timer again */ (void)wd_start(priv->bc_txpoll, BCMF_WDDELAY, bcmf_poll_expiry, 1, (wdparm_t)priv); +exit_unlock: net_unlock(); } @@ -742,6 +633,7 @@ static void bcmf_poll_work(FAR void *arg) static void bcmf_poll_expiry(int argc, wdparm_t arg, ...) { + // wlinfo("Entry\n"); FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)arg; /* Schedule to perform the interrupt processing on the worker thread. */ @@ -768,6 +660,7 @@ static void bcmf_poll_expiry(int argc, wdparm_t arg, ...) static int bcmf_ifup(FAR struct net_driver_s *dev) { + wlinfo("Entry\n"); FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)dev->d_private; #ifdef CONFIG_NET_IPv4 @@ -828,20 +721,20 @@ static int bcmf_ifup(FAR struct net_driver_s *dev) static int bcmf_ifdown(FAR struct net_driver_s *dev) { + wlinfo("Entry\n"); FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)dev->d_private; irqstate_t flags; - bcmf_wl_enable(priv, false); + // bcmf_wl_enable(priv, false); /* Disable the hardware interrupt */ flags = enter_critical_section(); #warning Missing logic - /* Cancel the TX poll timer and TX timeout timers */ + /* Cancel the TX poll timer */ wd_cancel(priv->bc_txpoll); - wd_cancel(priv->bc_txtimeout); /* Put the EMAC in its reset, non-operational state. This should be * a known configuration that will guarantee the bcmf_ifup() always @@ -874,6 +767,7 @@ static int bcmf_ifdown(FAR struct net_driver_s *dev) static void bcmf_txavail_work(FAR void *arg) { + // wlinfo("Entry\n"); FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)arg; /* Lock the network and serialize driver operations if necessary. @@ -890,11 +784,19 @@ static void bcmf_txavail_work(FAR void *arg) { /* Check if there is room in the hardware to hold another outgoing packet. */ + if (bcmf_netdev_alloc_tx_frame(priv)) + { + goto exit_unlock; + } + /* If so, then poll the network for new XMIT data */ + priv->bc_dev.d_buf = priv->cur_tx_frame->data; + priv->bc_dev.d_len = 0; (void)devif_poll(&priv->bc_dev, bcmf_txpoll); } +exit_unlock: net_unlock(); } @@ -957,6 +859,7 @@ static int bcmf_txavail(FAR struct net_driver_s *dev) #if defined(CONFIG_NET_IGMP) || defined(CONFIG_NET_ICMPv6) static int bcmf_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) { + wlinfo("Entry\n"); FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)dev->d_private; /* Add the MAC address to the hardware multicast routing table */ @@ -986,6 +889,7 @@ static int bcmf_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) #ifdef CONFIG_NET_IGMP static int bcmf_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) { + wlinfo("Entry\n"); FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)dev->d_private; /* Add the MAC address to the hardware multicast routing table */ @@ -1013,6 +917,7 @@ static int bcmf_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) #ifdef CONFIG_NET_ICMPv6 static void bcmf_ipv6multicast(FAR struct bcmf_dev_s *priv) { + wlinfo("Entry\n"); FAR struct net_driver_s *dev; uint16_t tmp16; uint8_t mac[6]; @@ -1105,6 +1010,11 @@ static int bcmf_ioctl(FAR struct net_driver_s *dev, int cmd, ret = bcmf_wl_is_scan_done(priv); break; + case SIOCSIFHWADDR: + /* Update device MAC address */ + ret = bcmf_wl_set_mac_address(priv, (struct ifreq*)arg); + break; + case SIOCSIWFREQ: /* Set channel/frequency (Hz) */ wlwarn("WARNING: SIOCSIWFREQ not implemented\n"); ret = -ENOSYS; @@ -1202,7 +1112,6 @@ int bcmf_netdev_register(FAR struct bcmf_dev_s *priv) /* Initialize network driver structure */ memset(&priv->bc_dev, 0, sizeof(priv->bc_dev)); - priv->bc_dev.d_buf = g_pktbuf; /* Single packet buffer */ priv->bc_dev.d_ifup = bcmf_ifup; /* I/F up (new IP address) callback */ priv->bc_dev.d_ifdown = bcmf_ifdown; /* I/F down callback */ priv->bc_dev.d_txavail = bcmf_txavail; /* New TX data callback */ @@ -1215,13 +1124,17 @@ int bcmf_netdev_register(FAR struct bcmf_dev_s *priv) #endif priv->bc_dev.d_private = (FAR void *)priv; /* Used to recover private state from dev */ - /* Create a watchdog for timing polling for and timing of transmisstions */ + /* Create a watchdog for timing polling */ priv->bc_txpoll = wd_create(); /* Create periodic poll timer */ - priv->bc_txtimeout = wd_create(); /* Create TX timeout timer */ DEBUGASSERT(priv->bc_txpoll != NULL && priv->bc_txtimeout != NULL); + /* Initialize network stack interface buffer */ + + priv->cur_tx_frame = NULL; + priv->bc_dev.d_buf = NULL; + /* Put the interface in the down state. This usually amounts to resetting * the device and/or calling bcmf_ifdown(). */ @@ -1235,9 +1148,9 @@ int bcmf_netdev_register(FAR struct bcmf_dev_s *priv) out_len = ETHER_ADDR_LEN; if (bcmf_cdc_iovar_request(priv, CHIP_STA_INTERFACE, false, - IOVAR_STR_CUR_ETHERADDR, - priv->bc_dev.d_mac.ether.ether_addr_octet, - &out_len) != OK) + IOVAR_STR_CUR_ETHERADDR, + priv->bc_dev.d_mac.ether.ether_addr_octet, + &out_len) != OK) { return -EIO; } diff --git a/drivers/wireless/ieee80211/bcmf_netdev.h b/drivers/wireless/ieee80211/bcmf_netdev.h new file mode 100644 index 0000000000..c062013a42 --- /dev/null +++ b/drivers/wireless/ieee80211/bcmf_netdev.h @@ -0,0 +1,47 @@ +/**************************************************************************** + * drivers/wireless/ieee80211/bcmf_netdev.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Simon Piriou + * + * 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 __DRIVERS_WIRELESS_IEEE80211_BCMF_NETDEV_H +#define __DRIVERS_WIRELESS_IEEE80211_BCMF_NETDEV_H + +#include "bcmf_driver.h" + +int bcmf_netdev_register(FAR struct bcmf_dev_s *priv); + +void bcmf_netdev_notify_rx(FAR struct bcmf_dev_s *priv); + +void bcmf_netdev_notify_tx_done(FAR struct bcmf_dev_s *priv); + +#endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_NETDEV_H */ diff --git a/drivers/wireless/ieee80211/bcmf_sdio.c b/drivers/wireless/ieee80211/bcmf_sdio.c index 0756a1c685..e54e5cda80 100644 --- a/drivers/wireless/ieee80211/bcmf_sdio.c +++ b/drivers/wireless/ieee80211/bcmf_sdio.c @@ -47,6 +47,7 @@ #include #include #include +#include #include #include @@ -60,6 +61,7 @@ #include "bcmf_sdio.h" #include "bcmf_core.h" #include "bcmf_sdpcm.h" +#include "bcmf_utils.h" #include "bcmf_sdio_core.h" #include "bcmf_sdio_regs.h" @@ -114,6 +116,13 @@ static int bcmf_sdio_find_block_size(unsigned int size); /* FIXME remove */ FAR struct bcmf_dev_s *g_sdio_priv; +/* Buffer pool for SDIO bus interface + This pool is shared between all driver devices */ + +static struct bcmf_sdio_frame g_pktframes[BCMF_PKT_POOL_SIZE]; + +// TODO free_queue should be static + /**************************************************************************** * Private Functions ****************************************************************************/ @@ -564,16 +573,28 @@ int bcmf_bus_sdio_initialize(FAR struct bcmf_dev_s *priv, sbus->sleeping = true; sbus->bus.txframe = bcmf_sdpcm_queue_frame; - sbus->bus.allocate_frame = bcmf_sdpcm_allocate_frame; + sbus->bus.rxframe = bcmf_sdpcm_get_rx_frame; + sbus->bus.allocate_frame = bcmf_sdpcm_alloc_frame; + sbus->bus.free_frame = bcmf_sdpcm_free_frame; sbus->bus.stop = NULL; // TODO /* Init transmit frames queue */ - if ((ret = sem_init(&sbus->tx_queue_mutex, 0, 1)) != OK) + if ((ret = sem_init(&sbus->queue_mutex, 0, 1)) != OK) { goto exit_free_bus; } sq_init(&sbus->tx_queue); + sq_init(&sbus->rx_queue); + sq_init(&sbus->free_queue); + + /* Setup free buffer list */ + + // FIXME this should be static to driver + for (ret = 0; ret < BCMF_PKT_POOL_SIZE; ret++) + { + bcmf_dqueue_push(&sbus->free_queue, &g_pktframes[ret].list_entry); + } /* Init thread semaphore */ @@ -622,7 +643,6 @@ int bcmf_bus_sdio_initialize(FAR struct bcmf_dev_s *priv, goto exit_uninit_hw; } - up_mdelay(100); sbus->ready = true; @@ -642,7 +662,8 @@ int bcmf_bus_sdio_initialize(FAR struct bcmf_dev_s *priv, /* Start the waitdog timer */ - wd_start(sbus->waitdog, BCMF_WAITDOG_TIMEOUT_TICK, bcmf_sdio_waitdog_timeout, 0); + wd_start(sbus->waitdog, BCMF_WAITDOG_TIMEOUT_TICK, bcmf_sdio_waitdog_timeout, + (wdparm_t)priv); /* Spawn bcmf daemon thread */ @@ -659,8 +680,6 @@ int bcmf_bus_sdio_initialize(FAR struct bcmf_dev_s *priv, sbus->thread_id = ret; - - /* sdio bus is up and running */ return OK; @@ -685,7 +704,6 @@ int bcmf_chipinitialize(FAR struct bcmf_sdio_dev_s *sbus) { return ret; } - wlinfo("chip id is 0x%x\n", value); int chipid = value & 0xffff; switch (chipid) @@ -705,11 +723,12 @@ int bcmf_chipinitialize(FAR struct bcmf_sdio_dev_s *sbus) void bcmf_sdio_waitdog_timeout(int argc, wdparm_t arg1, ...) { - FAR struct bcmf_dev_s *priv = g_sdio_priv; + FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s*)arg1; FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s*)priv->bus; /* Notify bcmf thread */ + wlinfo("Notify bcmf thread\n"); sem_post(&sbus->thread_signal); } @@ -739,7 +758,7 @@ int bcmf_sdio_thread(int argc, char **argv) /* Restart the waitdog timer */ wd_start(sbus->waitdog, BCMF_WAITDOG_TIMEOUT_TICK, - bcmf_sdio_waitdog_timeout, 0); + bcmf_sdio_waitdog_timeout, (wdparm_t)priv); /* Wake up device */ @@ -789,6 +808,15 @@ int bcmf_sdio_thread(int argc, char **argv) ret = bcmf_sdpcm_sendframe(priv); } while (ret == OK); + /* Check if RX frames are available */ + + if (sbus->intstatus & I_HMB_FRAME_IND) + { + /* Try again */ + wlinfo("Try read again\n"); + continue; + } + /* If we're done for now, turn off clock request. */ // TODO add wakelock @@ -798,4 +826,74 @@ int bcmf_sdio_thread(int argc, char **argv) wlinfo("Exit\n"); return 0; +} + +struct bcmf_sdio_frame* bcmf_sdio_allocate_frame(FAR struct bcmf_dev_s *priv, + bool block, bool tx) +{ + FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s*)priv->bus; + struct bcmf_sdio_frame *sframe; + dq_entry_t *entry = NULL; + + while (1) + { + if (sem_wait(&sbus->queue_mutex)) + { + PANIC(); + } + + // if (!tx || sbus->tx_queue_count < BCMF_PKT_POOL_SIZE-1) + { + if ((entry = bcmf_dqueue_pop_tail(&sbus->free_queue)) != NULL) + { + if (tx) + { + sbus->tx_queue_count += 1; + } + + sem_post(&sbus->queue_mutex); + break; + } + } + + sem_post(&sbus->queue_mutex); + + if (block) + { + // TODO use signaling semaphore + wlinfo("alloc failed %d\n", tx); + up_mdelay(100); + continue; + } + wlinfo("No avail buffer\n"); + return NULL; + } + + sframe = container_of(entry, struct bcmf_sdio_frame, list_entry); + + sframe->header.len = HEADER_SIZE + MAX_NET_DEV_MTU; + sframe->header.base = sframe->data; + sframe->header.data = sframe->data; + sframe->tx = tx; + return sframe; +} + +void bcmf_sdio_free_frame(FAR struct bcmf_dev_s *priv, + struct bcmf_sdio_frame *sframe) +{ + // wlinfo("free %p\n", sframe); + FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s*)priv->bus; + + if (sem_wait(&sbus->queue_mutex)) + { + PANIC(); + } + + bcmf_dqueue_push(&sbus->free_queue, &sframe->list_entry); + + if (sframe->tx) + { + sbus->tx_queue_count -= 1; + } + sem_post(&sbus->queue_mutex); } \ No newline at end of file diff --git a/drivers/wireless/ieee80211/bcmf_sdio.h b/drivers/wireless/ieee80211/bcmf_sdio.h index 228fbb8d18..d21365a1c4 100644 --- a/drivers/wireless/ieee80211/bcmf_sdio.h +++ b/drivers/wireless/ieee80211/bcmf_sdio.h @@ -49,6 +49,10 @@ #include "bcmf_sdio_core.h" +#define HEADER_SIZE 0x12 /* Default sdpcm + bdc header size */ +// TODO move to Kconfig +#define BCMF_PKT_POOL_SIZE 4 /* Frame pool size */ + /**************************************************************************** * Public Types ****************************************************************************/ @@ -93,8 +97,21 @@ struct bcmf_sdio_dev_s uint8_t tx_seq; /* Transmit sequence number (next) */ uint8_t rx_seq; /* Receive sequence number (expected) */ - sem_t tx_queue_mutex; /* Lock for transmit queue */ + sem_t queue_mutex; /* Lock for TX/RX/free queues */ + dq_queue_t free_queue; /* Queue of available frames */ dq_queue_t tx_queue; /* Queue of frames to tramsmit */ + dq_queue_t rx_queue; /* Queue of frames used to receive */ + volatile int tx_queue_count; /* Count of items in TX queue */ +}; + +/* Structure used to manage SDIO frames */ + +struct bcmf_sdio_frame { + struct bcmf_frame_s header; + bool tx; + dq_entry_t list_entry; + uint8_t data[HEADER_SIZE + MAX_NET_DEV_MTU + + CONFIG_NET_GUARDSIZE]; }; /**************************************************************************** @@ -120,4 +137,10 @@ int bcmf_read_reg(FAR struct bcmf_sdio_dev_s *sbus, uint8_t function, int bcmf_write_reg(FAR struct bcmf_sdio_dev_s *sbus, uint8_t function, uint32_t address, uint8_t reg); +struct bcmf_sdio_frame* bcmf_sdio_allocate_frame(FAR struct bcmf_dev_s *priv, + bool block, bool tx); + +void bcmf_sdio_free_frame(FAR struct bcmf_dev_s *priv, + struct bcmf_sdio_frame *sframe); + #endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_SDIO_H */ \ No newline at end of file diff --git a/drivers/wireless/ieee80211/bcmf_sdpcm.c b/drivers/wireless/ieee80211/bcmf_sdpcm.c index 6047db9c86..065dafb61b 100644 --- a/drivers/wireless/ieee80211/bcmf_sdpcm.c +++ b/drivers/wireless/ieee80211/bcmf_sdpcm.c @@ -42,6 +42,7 @@ #include #include +#include #include #include @@ -56,6 +57,8 @@ #include "bcmf_bdc.h" #include "bcmf_utils.h" + #include "bcmf_netdev.h" + #include "bcmf_sdio_regs.h" /**************************************************************************** @@ -66,9 +69,6 @@ #define SDPCM_EVENT_CHANNEL 1 /* Asynchronous event frame id */ #define SDPCM_DATA_CHANNEL 2 /* Data frame id */ -#define container_of(ptr, type, member) \ - (type *)( (uint8_t *)(ptr) - offsetof(type,member) ) - /**************************************************************************** * Private Types ****************************************************************************/ @@ -85,11 +85,6 @@ struct __attribute__((packed)) bcmf_sdpcm_header { uint16_t padding; }; -struct bcmf_sdpcm_frame { - struct bcmf_frame_s frame_header; - dq_entry_t list_entry; -}; - /**************************************************************************** * Private Function Prototypes ****************************************************************************/ @@ -117,9 +112,10 @@ int bcmf_sdpcm_rxfail(FAR struct bcmf_sdio_dev_s *sbus, bool retry) /* TODO Wait until the packet has been flushed (device/FIFO stable) */ - /* Send NAK to retry to read frame */ if (retry) { + /* Send NAK to retry to read frame */ + bcmf_write_sbregb(sbus, CORE_BUS_REG(sbus->chip->core_base[SDIOD_CORE_ID], tosbmailbox), SMB_NAK); @@ -141,18 +137,7 @@ int bcmf_sdpcm_process_header(FAR struct bcmf_sdio_dev_s *sbus, /* Update tx credits */ - // wlinfo("update credit %x %x %x\n", header->credit, - // sbus->tx_seq, sbus->max_seq); - - if (header->credit - sbus->tx_seq > 0x40) - { - wlerr("seq %d: max tx seq number error\n", sbus->tx_seq); - sbus->max_seq = sbus->tx_seq + 2; - } - else - { - sbus->max_seq = header->credit; - } + sbus->max_seq = header->credit; return OK; } @@ -161,20 +146,25 @@ int bcmf_sdpcm_process_header(FAR struct bcmf_sdio_dev_s *sbus, * Public Functions ****************************************************************************/ -// FIXME remove -uint8_t tmp_buffer[1024]; int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv) { int ret; uint16_t len, checksum; struct bcmf_sdpcm_header *header; - struct bcmf_sdpcm_frame *sframe; + struct bcmf_sdio_frame *sframe; FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s*)priv->bus; - /* TODO request free frame buffer */ + /* Request free frame buffer */ - sframe = (struct bcmf_sdpcm_frame*)tmp_buffer; - header = (struct bcmf_sdpcm_header*)&sframe[1]; + sframe = bcmf_sdio_allocate_frame(priv, false, false); + + if (sframe == NULL) + { + wlinfo("fail alloc\n"); + return -EAGAIN; + } + + header = (struct bcmf_sdpcm_header*)sframe->data; /* Read header */ @@ -193,7 +183,8 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv) if (!(len | checksum)) { - return -ENODATA; + ret = -ENODATA; + goto exit_free_frame; } if (((~len & 0xffff) ^ checksum) || len < sizeof(struct bcmf_sdpcm_header)) @@ -203,25 +194,23 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv) goto exit_abort; } - // FIXME define for size - if (len > sizeof(tmp_buffer)) + if (len > sframe->header.len) { - wlerr("Frame is too large, cancel %d\n", len); + wlerr("Frame is too large, cancel %d %d\n", len, sframe->header.len); ret = -ENOMEM; goto exit_abort; } /* Read remaining frame data */ - // TODO allocate buffer ret = bcmf_transfer_bytes(sbus, false, 2, 0, (uint8_t*)header+4, len - 4); if (ret != OK) { ret = -EIO; - goto exit_free_abort; + goto exit_abort; } - // wlinfo("Receive frame\n"); + // wlinfo("Receive frame %p %d\n", sframe, len); // bcmf_hexdump((uint8_t*)header, header->size, (unsigned int)header); /* Process and validate header */ @@ -234,19 +223,18 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv) goto exit_free_frame; } - /* Setup new frame structure */ + /* Update frame structure */ - sframe->frame_header.len = header->size; - sframe->frame_header.data = (uint8_t*)header + header->data_offset; - sframe->frame_header.base = (uint8_t*)header; + sframe->header.len = header->size; + sframe->header.data += header->data_offset; /* Process received frame content */ switch (header->channel & 0x0f) { case SDPCM_CONTROL_CHANNEL: - ret = bcmf_cdc_process_control_frame(priv, &sframe->frame_header); - break; + ret = bcmf_cdc_process_control_frame(priv, &sframe->header); + goto exit_free_frame; case SDPCM_EVENT_CHANNEL: if (header->data_offset == header->size) @@ -257,34 +245,49 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv) } else { - ret = bcmf_bdc_process_event_frame(priv, &sframe->frame_header); + ret = bcmf_bdc_process_event_frame(priv, &sframe->header); } - break; + goto exit_free_frame; case SDPCM_DATA_CHANNEL: - ret = bcmf_bdc_process_data_frame(priv, &sframe->frame_header); + + /* Queue frame and notify network layer frame is available */ + + if (sem_wait(&sbus->queue_mutex)) + { + PANIC(); + } + bcmf_dqueue_push(&sbus->rx_queue, &sframe->list_entry); + sem_post(&sbus->queue_mutex); + + bcmf_netdev_notify_rx(priv); + + /* Upper layer have to free all received frames */ + + ret = OK; break; default: wlerr("Got unexpected message type %d\n", header->channel); - ret = OK; + ret = -EINVAL; + goto exit_free_frame; } -exit_free_frame: - // TODO free frame buffer return ret; -exit_free_abort: - // TODO free frame buffer exit_abort: bcmf_sdpcm_rxfail(sbus, false); +exit_free_frame: + bcmf_sdio_free_frame(priv, sframe); return ret; } int bcmf_sdpcm_sendframe(FAR struct bcmf_dev_s *priv) { int ret; - struct bcmf_sdpcm_frame *sframe; + bool is_txframe; + dq_entry_t *entry; + struct bcmf_sdio_frame *sframe; struct bcmf_sdpcm_header *header; FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s*)priv->bus; @@ -303,25 +306,25 @@ int bcmf_sdpcm_sendframe(FAR struct bcmf_dev_s *priv) } - if ((ret = sem_wait(&sbus->tx_queue_mutex)) != OK) + if (sem_wait(&sbus->queue_mutex)) { - return ret; + PANIC(); } - sframe = container_of(sbus->tx_queue.tail, - struct bcmf_sdpcm_frame, list_entry); - header = (struct bcmf_sdpcm_header*)sframe->frame_header.base; + entry = sbus->tx_queue.tail; + sframe = container_of(entry, struct bcmf_sdio_frame, list_entry); + header = (struct bcmf_sdpcm_header*)sframe->header.base; /* Set frame sequence id */ header->sequence = sbus->tx_seq++; - // wlinfo("Send frame\n"); - // bcmf_hexdump(sframe->frame_header.base, sframe->frame_header.len, - // (unsigned long)sframe->frame_header.base); + // wlinfo("Send frame %p\n", sframe); + // bcmf_hexdump(sframe->header.base, sframe->header.len, + // (unsigned long)sframe->header.base); - ret = bcmf_transfer_bytes(sbus, true, 2, 0, sframe->frame_header.base, - sframe->frame_header.len); + ret = bcmf_transfer_bytes(sbus, true, 2, 0, sframe->header.base, + sframe->header.len); if (ret != OK) { wlinfo("fail send frame %d\n", ret); @@ -332,128 +335,130 @@ int bcmf_sdpcm_sendframe(FAR struct bcmf_dev_s *priv) /* Frame sent, remove it from queue */ - if (sbus->tx_queue.head == &sframe->list_entry) - { - /* List is empty */ + bcmf_dqueue_pop_tail(&sbus->tx_queue); + sem_post(&sbus->queue_mutex); + is_txframe = sframe->tx; - sbus->tx_queue.head = NULL; - sbus->tx_queue.tail = NULL; - } - else + /* Free frame buffer */ + + bcmf_sdio_free_frame(priv, sframe); + + if (is_txframe) { - sbus->tx_queue.tail = sframe->list_entry.blink; - sframe->list_entry.blink->flink = sbus->tx_queue.head; - } + /* Notify upper layer at least one TX buffer is available */ - /* TODO free frame buffer */ + bcmf_netdev_notify_tx_done(priv); + } - goto exit_post_sem; + return OK; exit_abort: // bcmf_sdpcm_txfail(sbus, false); -exit_post_sem: - sem_post(&sbus->tx_queue_mutex); + sem_post(&sbus->queue_mutex); return ret; } -// FIXME remove -uint8_t tmp_buffer2[512]; -struct bcmf_frame_s* bcmf_sdpcm_allocate_frame(FAR struct bcmf_dev_s *priv, - unsigned int len, bool control, bool block) +int bcmf_sdpcm_queue_frame(FAR struct bcmf_dev_s *priv, + struct bcmf_frame_s *frame, bool control) { - unsigned int frame_len; - - /* Integer overflow check */ - - if (len > 512) - { - return NULL; - } - - frame_len = len + sizeof(struct bcmf_sdpcm_frame) - + sizeof(struct bcmf_sdpcm_header); - if (!control) - { - /* Data frames needs 2 bytes padding */ - - frame_len += 2; - } - - if (frame_len > 512) - { - return NULL; - } - - // FIXME allocate buffer and use max_size instead of 512 - // allocate buffer len + sizeof(struct bcmf_sdpcm_frame) - - struct bcmf_sdpcm_frame *sframe = (struct bcmf_sdpcm_frame*)tmp_buffer2; - struct bcmf_sdpcm_header *header = (struct bcmf_sdpcm_header*)&sframe[1]; + FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s*)priv->bus; + struct bcmf_sdio_frame *sframe = (struct bcmf_sdio_frame*)frame; + struct bcmf_sdpcm_header *header = (struct bcmf_sdpcm_header*)sframe->data; /* Prepare sw header */ memset(header, 0, sizeof(struct bcmf_sdpcm_header)); - header->size = frame_len - sizeof(struct bcmf_sdpcm_frame); + header->size = frame->len; header->checksum = ~header->size; + header->data_offset = (uint8_t)(frame->data - frame->base); if (control) { header->channel = SDPCM_CONTROL_CHANNEL; - header->data_offset = sizeof(struct bcmf_sdpcm_header); } else { header->channel = SDPCM_DATA_CHANNEL; - header->data_offset = sizeof(struct bcmf_sdpcm_header)+2; } - sframe->frame_header.len = header->size; - sframe->frame_header.base = (uint8_t*)header; - sframe->frame_header.data = (uint8_t*)header + header->data_offset; + /* Add frame in tx queue */ + + if (sem_wait(&sbus->queue_mutex)) + { + PANIC(); + } + + bcmf_dqueue_push(&sbus->tx_queue, &sframe->list_entry); + + sem_post(&sbus->queue_mutex); + + /* Notify bcmf thread tx frame is ready */ + + sem_post(&sbus->thread_signal); - return &sframe->frame_header; + return OK; } -int bcmf_sdpcm_queue_frame(FAR struct bcmf_dev_s *priv, - struct bcmf_frame_s *frame) +struct bcmf_frame_s* bcmf_sdpcm_alloc_frame(FAR struct bcmf_dev_s *priv, + unsigned int len, bool block, + bool control) { - int ret; - FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s*)priv->bus; - struct bcmf_sdpcm_frame *sframe = (struct bcmf_sdpcm_frame*)frame; - - /* Add frame in tx queue */ + struct bcmf_sdio_frame *sframe; + unsigned int header_len = sizeof(struct bcmf_sdpcm_header); - if ((ret = sem_wait(&sbus->tx_queue_mutex)) != OK) + if (!control) { - return ret; + header_len += 2; /* Data frames need alignment padding */ } - if (sbus->tx_queue.head == NULL) + if (len + header_len > MAX_NET_DEV_MTU + HEADER_SIZE || + len > len + header_len) { - /* List is empty */ + wlerr("Invalid size %d\n", len); + return NULL; + } - sbus->tx_queue.head = &sframe->list_entry; - sbus->tx_queue.tail = &sframe->list_entry; + /* Allocate a frame for RX in case of control frame */ - sframe->list_entry.flink = &sframe->list_entry; - sframe->list_entry.blink = &sframe->list_entry; - } - else + sframe = bcmf_sdio_allocate_frame(priv, block, !control); + + if (sframe == NULL) { - /* Insert entry at list head */ + return NULL; + } + + sframe->header.len = header_len + len; + sframe->header.data += header_len; + return &sframe->header; +} + - sframe->list_entry.flink = sbus->tx_queue.head; - sframe->list_entry.blink = sbus->tx_queue.tail; +void bcmf_sdpcm_free_frame(FAR struct bcmf_dev_s *priv, + struct bcmf_frame_s *frame) +{ + return bcmf_sdio_free_frame(priv, (struct bcmf_sdio_frame*)frame); +} + +struct bcmf_frame_s* bcmf_sdpcm_get_rx_frame(FAR struct bcmf_dev_s *priv) +{ + dq_entry_t *entry; + struct bcmf_sdio_frame *sframe; + FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s*)priv->bus; - sbus->tx_queue.head->blink = &sframe->list_entry; - sbus->tx_queue.head = &sframe->list_entry; + if (sem_wait(&sbus->queue_mutex)) + { + PANIC(); } - sem_post(&sbus->tx_queue_mutex); + entry = bcmf_dqueue_pop_tail(&sbus->rx_queue); - /* Notify bcmf thread tx frame is ready */ + sem_post(&sbus->queue_mutex); - sem_post(&sbus->thread_signal); + if (entry == NULL) + { + return NULL; + } - return OK; + sframe = container_of(entry, struct bcmf_sdio_frame, list_entry); + return &sframe->header; } \ No newline at end of file diff --git a/drivers/wireless/ieee80211/bcmf_sdpcm.h b/drivers/wireless/ieee80211/bcmf_sdpcm.h index eedcb60050..f1091fd519 100644 --- a/drivers/wireless/ieee80211/bcmf_sdpcm.h +++ b/drivers/wireless/ieee80211/bcmf_sdpcm.h @@ -51,10 +51,13 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv); int bcmf_sdpcm_sendframe(FAR struct bcmf_dev_s *priv); int bcmf_sdpcm_queue_frame(FAR struct bcmf_dev_s *priv, - struct bcmf_frame_s *frame); + struct bcmf_frame_s *frame, bool control); -struct bcmf_frame_s *bcmf_sdpcm_allocate_frame(FAR struct bcmf_dev_s *priv, - unsigned int len, bool control, - bool block); +void bcmf_sdpcm_free_frame(FAR struct bcmf_dev_s *priv, struct bcmf_frame_s *frame); + +struct bcmf_frame_s* bcmf_sdpcm_alloc_frame(FAR struct bcmf_dev_s *priv, + unsigned int len, bool block, bool control); + +struct bcmf_frame_s* bcmf_sdpcm_get_rx_frame(FAR struct bcmf_dev_s *priv); #endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_SDPCM_H */ \ No newline at end of file diff --git a/drivers/wireless/ieee80211/bcmf_utils.c b/drivers/wireless/ieee80211/bcmf_utils.c index 7a9c780671..4fb126356e 100644 --- a/drivers/wireless/ieee80211/bcmf_utils.c +++ b/drivers/wireless/ieee80211/bcmf_utils.c @@ -43,6 +43,7 @@ #include #include #include +#include #include "bcmf_utils.h" @@ -114,4 +115,68 @@ int bcmf_sem_wait(sem_t *sem, unsigned int timeout_ms) } return sem_timedwait(sem, &abstime); +} + +void bcmf_dqueue_push(dq_queue_t *queue, dq_entry_t *entry) +{ + if (queue->head == NULL) + { + /* List is empty */ + + queue->tail = entry; + + entry->flink = entry; + entry->blink = entry; + } + else + { + /* Insert entry at list head */ + + entry->flink = queue->head; + entry->blink = queue->tail; + + queue->head->blink = entry; + } + + queue->head = entry; +} + +dq_entry_t* bcmf_dqueue_pop_tail(dq_queue_t *queue) +{ + dq_entry_t *entry = queue->tail; + + if (queue->head == queue->tail) + { + /* List is empty */ + + queue->head = NULL; + queue->tail = NULL; + } + else + { + /* Pop from queue tail */ + + queue->tail = entry->blink; + entry->blink->flink = queue->head; + } + + return entry; +} + +void bcmf_squeue_push(sq_queue_t *queue, sq_entry_t *entry) +{ + entry->flink = queue->head; + queue->head = entry; +} + +sq_entry_t* bcmf_squeue_pop(sq_queue_t *queue) +{ + sq_entry_t *entry = queue->head; + + if (queue->head != NULL) + { + queue->head = entry->flink; + } + + return entry; } \ No newline at end of file diff --git a/drivers/wireless/ieee80211/bcmf_utils.h b/drivers/wireless/ieee80211/bcmf_utils.h index 704cb9ec06..1800cfc28b 100644 --- a/drivers/wireless/ieee80211/bcmf_utils.h +++ b/drivers/wireless/ieee80211/bcmf_utils.h @@ -42,6 +42,10 @@ #include #include +#include + +#define container_of(ptr, type, member) \ + (type *)( (uint8_t *)(ptr) - offsetof(type,member) ) /**************************************************************************** * Public Function Prototypes @@ -51,6 +55,12 @@ void bcmf_hexdump(uint8_t *data, unsigned int len, unsigned long offset); int bcmf_sem_wait(sem_t *sem, unsigned int timeout_ms); +sq_entry_t* bcmf_squeue_pop(sq_queue_t *queue); +void bcmf_squeue_push(sq_queue_t *queue, sq_entry_t *entry); + +dq_entry_t* bcmf_dqueue_pop_tail(dq_queue_t *queue); +void bcmf_dqueue_push(dq_queue_t *queue, dq_entry_t *entry); + static inline uint16_t bcmf_getle16(uint16_t *val) { uint8_t *valb = (uint8_t*)val; -- GitLab From 0597eb5587e508b17d5f246f170bc5fcae24aece Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 30 Apr 2017 12:41:19 -0600 Subject: [PATCH 659/990] Fix a typo introduced in last commit. --- arch/arm/src/stm32/stm32_i2c_alt.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/arch/arm/src/stm32/stm32_i2c_alt.c b/arch/arm/src/stm32/stm32_i2c_alt.c index a39248f56d..21f6696732 100644 --- a/arch/arm/src/stm32/stm32_i2c_alt.c +++ b/arch/arm/src/stm32/stm32_i2c_alt.c @@ -1890,7 +1890,7 @@ static int stm32_i2c_isr_process(struct stm32_i2c_priv_s *priv) #ifndef CONFIG_I2C_POLLED static int stm32_i2c_isr(int irq, void *context, FAR void *arg) { - struct stm32_i2c_priv_s *priv = (struct stm32_i2c_priv_s )arg; + struct stm32_i2c_priv_s *priv = (struct stm32_i2c_priv_s *)arg; DEBUGASSERT(priv != NULL); return stm32_i2c_isr_process(priv); -- GitLab From a8ce97715b8b0603365b0df01476f186535747bf Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 30 Apr 2017 14:44:39 -0600 Subject: [PATCH 660/990] Tiva I2C: Update to use the standard parameter passing to interrupt handlers. --- arch/arm/src/tiva/tiva_i2c.c | 288 ++--------------------------------- 1 file changed, 12 insertions(+), 276 deletions(-) diff --git a/arch/arm/src/tiva/tiva_i2c.c b/arch/arm/src/tiva/tiva_i2c.c index 558a72554c..4fe0e54d42 100644 --- a/arch/arm/src/tiva/tiva_i2c.c +++ b/arch/arm/src/tiva/tiva_i2c.c @@ -195,7 +195,6 @@ struct tiva_i2c_config_s uint32_t scl_pin; /* GPIO configuration for SCL as SCL */ uint32_t sda_pin; /* GPIO configuration for SDA as SDA */ #ifndef CONFIG_I2C_POLLED - int (*isr)(int, void *, void *); /* Interrupt handler */ uint8_t irq; /* IRQ number */ #endif uint8_t devno; /* I2Cn where n = devno */ @@ -282,39 +281,10 @@ static void tiva_i2c_tracedump(struct tiva_i2c_priv_s *priv); static void tiva_i2c_startxfr(struct tiva_i2c_priv_s *priv); static void tiva_i2c_nextxfr(struct tiva_i2c_priv_s *priv, uint32_t cmd); -static int tiva_i2c_interrupt(struct tiva_i2c_priv_s * priv, uint32_t status); +static int tiva_i2c_process(struct tiva_i2c_priv_s * priv, uint32_t status); #ifndef CONFIG_I2C_POLLED -#ifdef CONFIG_TIVA_I2C0 -static int tiva_i2c0_interrupt(int irq, void *context, FAR void *arg); -#endif -#ifdef CONFIG_TIVA_I2C1 -static int tiva_i2c1_interrupt(int irq, void *context, FAR void *arg); -#endif -#ifdef CONFIG_TIVA_I2C2 -static int tiva_i2c2_interrupt(int irq, void *context, FAR void *arg); -#endif -#ifdef CONFIG_TIVA_I2C3 -static int tiva_i2c3_interrupt(int irq, void *context, FAR void *arg); -#endif -#ifdef CONFIG_TIVA_I2C4 -static int tiva_i2c4_interrupt(int irq, void *context, FAR void *arg); -#endif -#ifdef CONFIG_TIVA_I2C5 -static int tiva_i2c5_interrupt(int irq, void *context, FAR void *arg); -#endif -#ifdef CONFIG_TIVA_I2C6 -static int tiva_i2c6_interrupt(int irq, void *context, FAR void *arg); -#endif -#ifdef CONFIG_TIVA_I2C7 -static int tiva_i2c7_interrupt(int irq, void *context, FAR void *arg); -#endif -#ifdef CONFIG_TIVA_I2C8 -static int tiva_i2c8_interrupt(int irq, void *context, FAR void *arg); -#endif -#ifdef CONFIG_TIVA_I2C9 -static int tiva_i2c9_interrupt(int irq, void *context, FAR void *arg); -#endif +static int tiva_i2c_interrupt(int irq, void *context, FAR void *arg); #endif /* !CONFIG_I2C_POLLED */ static int tiva_i2c_initialize(struct tiva_i2c_priv_s *priv, uint32_t frequency); @@ -353,7 +323,6 @@ static const struct tiva_i2c_config_s tiva_i2c0_config = .scl_pin = GPIO_I2C0_SCL, .sda_pin = GPIO_I2C0_SDA, #ifndef CONFIG_I2C_POLLED - .isr = tiva_i2c0_interrupt, .irq = TIVA_IRQ_I2C0, #endif .devno = 0, @@ -375,7 +344,6 @@ static const struct tiva_i2c_config_s tiva_i2c1_config = .scl_pin = GPIO_I2C1_SCL, .sda_pin = GPIO_I2C1_SDA, #ifndef CONFIG_I2C_POLLED - .isr = tiva_i2c1_interrupt, .irq = TIVA_IRQ_I2C1, #endif .devno = 1, @@ -397,7 +365,6 @@ static const struct tiva_i2c_config_s tiva_i2c2_config = .scl_pin = GPIO_I2C2_SCL, .sda_pin = GPIO_I2C2_SDA, #ifndef CONFIG_I2C_POLLED - .isr = tiva_i2c2_interrupt, .irq = TIVA_IRQ_I2C2, #endif .devno = 2, @@ -419,7 +386,6 @@ static const struct tiva_i2c_config_s tiva_i2c3_config = .scl_pin = GPIO_I2C3_SCL, .sda_pin = GPIO_I2C3_SDA, #ifndef CONFIG_I2C_POLLED - .isr = tiva_i2c3_interrupt, .irq = TIVA_IRQ_I2C3, #endif .devno = 3, @@ -441,7 +407,6 @@ static const struct tiva_i2c_config_s tiva_i2c4_config = .scl_pin = GPIO_I2C4_SCL, .sda_pin = GPIO_I2C4_SDA, #ifndef CONFIG_I2C_POLLED - .isr = tiva_i2c4_interrupt, .irq = TIVA_IRQ_I2C4, #endif .devno = 4, @@ -463,7 +428,6 @@ static const struct tiva_i2c_config_s tiva_i2c5_config = .scl_pin = GPIO_I2C5_SCL, .sda_pin = GPIO_I2C5_SDA, #ifndef CONFIG_I2C_POLLED - .isr = tiva_i2c5_interrupt, .irq = TIVA_IRQ_I2C5, #endif .devno = 5, @@ -485,7 +449,6 @@ static const struct tiva_i2c_config_s tiva_i2c6_config = .scl_pin = GPIO_I2C6_SCL, .sda_pin = GPIO_I2C6_SDA, #ifndef CONFIG_I2C_POLLED - .isr = tiva_i2c6_interrupt, .irq = TIVA_IRQ_I2C6, #endif .devno = 6, @@ -507,7 +470,6 @@ static const struct tiva_i2c_config_s tiva_i2c7_config = .scl_pin = GPIO_I2C7_SCL, .sda_pin = GPIO_I2C7_SDA, #ifndef CONFIG_I2C_POLLED - .isr = tiva_i2c7_interrupt, .irq = TIVA_IRQ_I2C7, #endif .devno = 7, @@ -529,7 +491,6 @@ static const struct tiva_i2c_config_s tiva_i2c8_config = .scl_pin = GPIO_I2C8_SCL, .sda_pin = GPIO_I2C8_SDA, #ifndef CONFIG_I2C_POLLED - .isr = tiva_i2c8_interrupt, .irq = TIVA_IRQ_I2C8, #endif .devno = 8, @@ -551,7 +512,6 @@ static const struct tiva_i2c_config_s tiva_i2c9_config = .scl_pin = GPIO_I2C9_SCL, .sda_pin = GPIO_I2C9_SDA, #ifndef CONFIG_I2C_POLLED - .isr = tiva_i2c9_interrupt, .irq = TIVA_IRQ_I2C9, #endif .devno = 9, @@ -846,7 +806,7 @@ static inline int tiva_i2c_sem_waitdone(struct tiva_i2c_priv_s *priv) * interrupt status until it reports that it is done. */ - tiva_i2c_interrupt(priv, status); + tiva_i2c_process(priv, status); /* Calculate the elapsed time */ @@ -1186,14 +1146,14 @@ static void tiva_i2c_nextxfr(struct tiva_i2c_priv_s *priv, uint32_t cmd) } /************************************************************************************ - * Name: tiva_i2c_interrupt + * Name: tiva_i2c_process * * Description: * Common Interrupt Service Routine * ************************************************************************************/ -static int tiva_i2c_interrupt(struct tiva_i2c_priv_s *priv, uint32_t status) +static int tiva_i2c_process(struct tiva_i2c_priv_s *priv, uint32_t status) { /* Check for new trace setup */ @@ -1411,252 +1371,28 @@ static int tiva_i2c_interrupt(struct tiva_i2c_priv_s *priv, uint32_t status) } /************************************************************************************ - * Name: tiva_i2c0_interrupt + * Name: tiva_i2c_interrupt * * Description: - * I2C0 interrupt service routine + * Common I2C interrupt service routine * ************************************************************************************/ #if !defined(CONFIG_I2C_POLLED) && defined(CONFIG_TIVA_I2C0) -static int tiva_i2c0_interrupt(int irq, void *context, void *arg) -{ - struct tiva_i2c_priv_s *priv; - uint32_t status; - - /* Read the masked interrupt status */ - - priv = &tiva_i2c0_priv; - status = tiva_i2c_getreg(priv, TIVA_I2CM_MIS_OFFSET); - - /* Let the common interrupt handler do the rest of the work */ - - return tiva_i2c_interrupt(priv, status); -} -#endif - -/************************************************************************************ - * Name: tiva_i2c1_interrupt - * - * Description: - * I2C1 interrupt service routine - * - ************************************************************************************/ - -#if !defined(CONFIG_I2C_POLLED) && defined(CONFIG_TIVA_I2C1) -static int tiva_i2c1_interrupt(int irq, void *context, FAR void *arg) -{ - struct tiva_i2c_priv_s *priv; - uint32_t status; - - /* Read the masked interrupt status */ - - priv = &tiva_i2c1_priv; - status = tiva_i2c_getreg(priv, TIVA_I2CM_MIS_OFFSET); - - /* Let the common interrupt handler do the rest of the work */ - - return tiva_i2c_interrupt(priv, status); -} -#endif - -/************************************************************************************ - * Name: tiva_i2c2_interrupt - * - * Description: - * I2C2 interrupt service routine - * - ************************************************************************************/ - -#if !defined(CONFIG_I2C_POLLED) && defined(CONFIG_TIVA_I2C2) -static int tiva_i2c2_interrupt(int irq, void *context, FAR void *arg) -{ - struct tiva_i2c_priv_s *priv; - uint32_t status; - - /* Read the masked interrupt status */ - - priv = &tiva_i2c2_priv; - status = tiva_i2c_getreg(priv, TIVA_I2CM_MIS_OFFSET); - - /* Let the common interrupt handler do the rest of the work */ - - return tiva_i2c_interrupt(priv, status); -} -#endif - -/************************************************************************************ - * Name: tiva_i2c3_interrupt - * - * Description: - * I2C2 interrupt service routine - * - ************************************************************************************/ - -#if !defined(CONFIG_I2C_POLLED) && defined(CONFIG_TIVA_I2C3) -static int tiva_i2c3_interrupt(int irq, void *context, FAR void *arg) +static int tiva_i2c_interrupt(int irq, void *context, void *arg) { - struct tiva_i2c_priv_s *priv; + struct tiva_i2c_priv_s *priv = (struct tiva_i2c_priv_s *)arg; uint32_t status; - /* Read the masked interrupt status */ - - priv = &tiva_i2c3_priv; - status = tiva_i2c_getreg(priv, TIVA_I2CM_MIS_OFFSET); - - /* Let the common interrupt handler do the rest of the work */ - - return tiva_i2c_interrupt(priv, status); -} -#endif - -/************************************************************************************ - * Name: tiva_i2c4_interrupt - * - * Description: - * I2C4 interrupt service routine - * - ************************************************************************************/ - -#if !defined(CONFIG_I2C_POLLED) && defined(CONFIG_TIVA_I2C4) -static int tiva_i2c4_interrupt(int irq, void *context, FAR void *arg) -{ - struct tiva_i2c_priv_s *priv; - uint32_t status; - - /* Read the masked interrupt status */ - - priv = &tiva_i2c4_priv; - status = tiva_i2c_getreg(priv, TIVA_I2CM_MIS_OFFSET); - - /* Let the common interrupt handler do the rest of the work */ - - return tiva_i2c_interrupt(priv, status); -} -#endif - -/************************************************************************************ - * Name: tiva_i2c5_interrupt - * - * Description: - * I2C5 interrupt service routine - * - ************************************************************************************/ - -#if !defined(CONFIG_I2C_POLLED) && defined(CONFIG_TIVA_I2C5) -static int tiva_i2c5_interrupt(int irq, void *context, FAR void *arg) -{ - struct tiva_i2c_priv_s *priv; - uint32_t status; - - /* Read the masked interrupt status */ - - priv = &tiva_i2c5_priv; - status = tiva_i2c_getreg(priv, TIVA_I2CM_MIS_OFFSET); - - /* Let the common interrupt handler do the rest of the work */ - - return tiva_i2c_interrupt(priv, status); -} -#endif - -/************************************************************************************ - * Name: tiva_i2c6_interrupt - * - * Description: - * I2C6 interrupt service routine - * - ************************************************************************************/ - -#if !defined(CONFIG_I2C_POLLED) && defined(CONFIG_TIVA_I2C6) -static int tiva_i2c6_interrupt(int irq, void *context, FAR void *arg) -{ - struct tiva_i2c_priv_s *priv; - uint32_t status; - - /* Read the masked interrupt status */ - - priv = &tiva_i2c6_priv; - status = tiva_i2c_getreg(priv, TIVA_I2CM_MIS_OFFSET); - - /* Let the common interrupt handler do the rest of the work */ - - return tiva_i2c_interrupt(priv, status); -} -#endif - -/************************************************************************************ - * Name: tiva_i2c7_interrupt - * - * Description: - * I2C7 interrupt service routine - * - ************************************************************************************/ - -#if !defined(CONFIG_I2C_POLLED) && defined(CONFIG_TIVA_I2C7) -static int tiva_i2c7_interrupt(int irq, void *context, FAR void *arg) -{ - struct tiva_i2c_priv_s *priv; - uint32_t status; - - /* Read the masked interrupt status */ - - priv = &tiva_i2c7_priv; - status = tiva_i2c_getreg(priv, TIVA_I2CM_MIS_OFFSET); - - /* Let the common interrupt handler do the rest of the work */ - - return tiva_i2c_interrupt(priv, status); -} -#endif - -/************************************************************************************ - * Name: tiva_i2c8_interrupt - * - * Description: - * I2C8 interrupt service routine - * - ************************************************************************************/ - -#if !defined(CONFIG_I2C_POLLED) && defined(CONFIG_TIVA_I2C8) -static int tiva_i2c8_interrupt(int irq, void *context, FAR void *arg) -{ - struct tiva_i2c_priv_s *priv; - uint32_t status; - - /* Read the masked interrupt status */ - - priv = &tiva_i2c8_priv; - status = tiva_i2c_getreg(priv, TIVA_I2CM_MIS_OFFSET); - - /* Let the common interrupt handler do the rest of the work */ - - return tiva_i2c_interrupt(priv, status); -} -#endif - -/************************************************************************************ - * Name: tiva_i2c9_interrupt - * - * Description: - * I2C9 interrupt service routine - * - ************************************************************************************/ - -#if !defined(CONFIG_I2C_POLLED) && defined(CONFIG_TIVA_I2C9) -static int tiva_i2c9_interrupt(int irq, void *context, FAR void *arg) -{ - struct tiva_i2c_priv_s *priv; - uint32_t status; + DEBUGASSERT(priv != NULL); /* Read the masked interrupt status */ - priv = &tiva_i2c9_priv; status = tiva_i2c_getreg(priv, TIVA_I2CM_MIS_OFFSET); /* Let the common interrupt handler do the rest of the work */ - return tiva_i2c_interrupt(priv, status); + return tiva_i2c_process(priv, status); } #endif @@ -1758,7 +1494,7 @@ static int tiva_i2c_initialize(struct tiva_i2c_priv_s *priv, uint32_t frequency) */ #ifndef CONFIG_I2C_POLLED - (void)irq_attach(config->irq, config->isr, NULL); + (void)irq_attach(config->irq, tiva_i2c_interrupt, priv); up_enable_irq(config->irq); #endif -- GitLab From 38948fb65460adc5062f46cb033b4af47ec09559 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 30 Apr 2017 17:40:10 -0600 Subject: [PATCH 661/990] ieee802.11: Bring some BSD licensed header files in from FreeBSD. --- include/nuttx/analog/ltc1867l.h | 4 +- include/nuttx/sensors/lis2dh.h | 16 +- include/nuttx/wireless/ieee80211/ieee80211.h | 889 ++++++++++++++++++ .../wireless/ieee80211/ieee80211_cypto.h | 119 +++ 4 files changed, 1018 insertions(+), 10 deletions(-) create mode 100644 include/nuttx/wireless/ieee80211/ieee80211.h create mode 100644 include/nuttx/wireless/ieee80211/ieee80211_cypto.h diff --git a/include/nuttx/analog/ltc1867l.h b/include/nuttx/analog/ltc1867l.h index 447ba494b1..1a74f5c786 100644 --- a/include/nuttx/analog/ltc1867l.h +++ b/include/nuttx/analog/ltc1867l.h @@ -97,12 +97,12 @@ enum ltc1867l_analog_input_mode_e LTC1867L_BIPOLAR = 0, }; -struct ltc1867l_channel_config_s +begin_packed_struct struct ltc1867l_channel_config_s { uint8_t channel; /* This will be the channel number returned in struct adc_msg_s for a conversion */ enum ltc1867l_analog_multiplexer_config_e analog_multiplexer_config; /* Analog multiplexer configuration */ enum ltc1867l_analog_input_mode_e analog_inputMode; /* Analog input mode */ -} packed_struct; +} end_packed_struct; /**************************************************************************** * Public Function Prototypes diff --git a/include/nuttx/sensors/lis2dh.h b/include/nuttx/sensors/lis2dh.h index bede2795c2..7d05c0caef 100644 --- a/include/nuttx/sensors/lis2dh.h +++ b/include/nuttx/sensors/lis2dh.h @@ -273,25 +273,25 @@ enum lis2dh_interrupt_mode LIS2DH_6D_POSITION = 0xc0, }; -struct lis2dh_vector_s +begin_packed_struct struct lis2dh_vector_s { int16_t x, y, z; -} packed_struct; +} end_packed_struct; -struct lis2dh_res_header +begin_packed_struct struct lis2dh_res_header { uint8_t meas_count; bool int1_occurred; uint8_t int1_source; bool int2_occurred; uint8_t int2_source; -} packed_struct; +} end_packed_struct; -struct lis2dh_result +begin_packed_struct struct lis2dh_result { struct lis2dh_res_header header; struct lis2dh_vector_s measurements[0]; -} packed_struct; +} end_packed_struct; struct lis2dh_setup { @@ -402,12 +402,12 @@ struct lis2dh_config_s CODE bool (*read_int2_pin)(void); }; -struct lis2dh_raw_data_s +begin_packed_struct struct lis2dh_raw_data_s { uint16_t out_x; uint16_t out_y; uint16_t out_z; -} packed_struct; +} end_packed_struct; typedef struct lis2dh_raw_data_s lis2dh_raw_data_t; diff --git a/include/nuttx/wireless/ieee80211/ieee80211.h b/include/nuttx/wireless/ieee80211/ieee80211.h new file mode 100644 index 0000000000..71cc273da8 --- /dev/null +++ b/include/nuttx/wireless/ieee80211/ieee80211.h @@ -0,0 +1,889 @@ +/**************************************************************************** + * include/nuttx/wireless/ieee80211/ieee80211.h + * 802.11 protocol definitions. + * + * Copyright (c) 2002, 2003 Sam Leffler, Errno Consulting + * 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. + * + * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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_WIRELESS_IEEE80211_IEEE80211_H +#define __INCLUDE_NUTTX_WIRELESS_IEEE80211_IEEE80211_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define IEEE80211_ADDR_LEN 6 /* size of 802.11 address */ + +/* is 802.11 address multicast/broadcast? */ + +#define IEEE80211_IS_MULTICAST(_a) (*(_a) & 0x01) + +/* htframe */ + +#define IEEE80211_FC0_VERSION_MASK 0x03 +#define IEEE80211_FC0_VERSION_SHIFT 0 +#define IEEE80211_FC0_VERSION_0 0x00 +#define IEEE80211_FC0_TYPE_MASK 0x0c +#define IEEE80211_FC0_TYPE_SHIFT 2 +#define IEEE80211_FC0_TYPE_MGT 0x00 +#define IEEE80211_FC0_TYPE_CTL 0x04 +#define IEEE80211_FC0_TYPE_DATA 0x08 + +#define IEEE80211_FC0_SUBTYPE_MASK 0xf0 +#define IEEE80211_FC0_SUBTYPE_SHIFT 4 + +/* for TYPE_MGT */ + +#define IEEE80211_FC0_SUBTYPE_ASSOC_REQ 0x00 +#define IEEE80211_FC0_SUBTYPE_ASSOC_RESP 0x10 +#define IEEE80211_FC0_SUBTYPE_REASSOC_REQ 0x20 +#define IEEE80211_FC0_SUBTYPE_REASSOC_RESP 0x30 +#define IEEE80211_FC0_SUBTYPE_PROBE_REQ 0x40 +#define IEEE80211_FC0_SUBTYPE_PROBE_RESP 0x50 +#define IEEE80211_FC0_SUBTYPE_BEACON 0x80 +#define IEEE80211_FC0_SUBTYPE_ATIM 0x90 +#define IEEE80211_FC0_SUBTYPE_DISASSOC 0xa0 +#define IEEE80211_FC0_SUBTYPE_AUTH 0xb0 +#define IEEE80211_FC0_SUBTYPE_DEAUTH 0xc0 +#define IEEE80211_FC0_SUBTYPE_ACTION 0xd0 +#define IEEE80211_FC0_SUBTYPE_ACTION_NOACK 0xe0 /* 11n */ + +/* for TYPE_CTL */ + +#define IEEE80211_FC0_SUBTYPE_WRAPPER 0x70 /* 11n */ +#define IEEE80211_FC0_SUBTYPE_BAR 0x80 +#define IEEE80211_FC0_SUBTYPE_BA 0x90 +#define IEEE80211_FC0_SUBTYPE_PS_POLL 0xa0 +#define IEEE80211_FC0_SUBTYPE_RTS 0xb0 +#define IEEE80211_FC0_SUBTYPE_CTS 0xc0 +#define IEEE80211_FC0_SUBTYPE_ACK 0xd0 +#define IEEE80211_FC0_SUBTYPE_CF_END 0xe0 +#define IEEE80211_FC0_SUBTYPE_CF_END_ACK 0xf0 + +/* for TYPE_DATA (bit combination) */ + +#define IEEE80211_FC0_SUBTYPE_DATA 0x00 +#define IEEE80211_FC0_SUBTYPE_CF_ACK 0x10 +#define IEEE80211_FC0_SUBTYPE_CF_POLL 0x20 +#define IEEE80211_FC0_SUBTYPE_CF_ACPL 0x30 +#define IEEE80211_FC0_SUBTYPE_NODATA 0x40 +#define IEEE80211_FC0_SUBTYPE_CFACK 0x50 +#define IEEE80211_FC0_SUBTYPE_CFPOLL 0x60 +#define IEEE80211_FC0_SUBTYPE_CF_ACK_CF_ACK 0x70 +#define IEEE80211_FC0_SUBTYPE_QOS 0x80 + +#define IEEE80211_FC1_DIR_MASK 0x03 +#define IEEE80211_FC1_DIR_NODS 0x00 /* STA->STA */ +#define IEEE80211_FC1_DIR_TODS 0x01 /* STA->AP */ +#define IEEE80211_FC1_DIR_FROMDS 0x02 + /* AP ->STA */ +#define IEEE80211_FC1_DIR_DSTODS 0x03 + /* AP ->AP */ + +#define IEEE80211_FC1_MORE_FRAG 0x04 +#define IEEE80211_FC1_RETRY 0x08 +#define IEEE80211_FC1_PWR_MGT 0x10 +#define IEEE80211_FC1_MORE_DATA 0x20 +#define IEEE80211_FC1_PROTECTED 0x40 +#define IEEE80211_FC1_WEP 0x40 /* pre-RSNA compat */ +#define IEEE80211_FC1_ORDER 0x80 +#define IEEE80211_FC1_BITS \ + "\20\03MORE_FRAG\04RETRY\05PWR_MGT\06MORE_DATA" \ + "\07PROTECTED\08ORDER" + +/* Sequence Control field (see 7.1.3.4). */ + +#define IEEE80211_SEQ_FRAG_MASK 0x000f +#define IEEE80211_SEQ_FRAG_SHIFT 0 +#define IEEE80211_SEQ_SEQ_MASK 0xfff0 +#define IEEE80211_SEQ_SEQ_SHIFT 4 + +#define IEEE80211_NWID_LEN 32 +#define IEEE80211_MMIE_LEN 18 /* 11w */ + +/* QoS Control field (see 7.1.3.5). */ + +#define IEEE80211_QOS_TXOP 0xff00 +#define IEEE80211_QOS_AMSDU 0x0080 /* 11n */ +#define IEEE80211_QOS_ACK_POLICY_NORMAL 0x0000 +#define IEEE80211_QOS_ACK_POLICY_NOACK 0x0020 +#define IEEE80211_QOS_ACK_POLICY_NOEXPLACK 0x0040 +#define IEEE80211_QOS_ACK_POLICY_BA 0x0060 +#define IEEE80211_QOS_ACK_POLICY_MASK 0x0060 +#define IEEE80211_QOS_ACK_POLICY_SHIFT 5 +#define IEEE80211_QOS_EOSP 0x0010 +#define IEEE80211_QOS_TID 0x000f + +/* Capability Information field (see 7.3.1.4) */ + +#define IEEE80211_CAPINFO_ESS 0x0001 +#define IEEE80211_CAPINFO_IBSS 0x0002 +#define IEEE80211_CAPINFO_CF_POLLABLE 0x0004 +#define IEEE80211_CAPINFO_CF_POLLREQ 0x0008 +#define IEEE80211_CAPINFO_PRIVACY 0x0010 +#define IEEE80211_CAPINFO_SHORT_PREAMBLE 0x0020 +#define IEEE80211_CAPINFO_PBCC 0x0040 +#define IEEE80211_CAPINFO_CHNL_AGILITY 0x0080 +#define IEEE80211_CAPINFO_SPECTRUM_MGMT 0x0100 +#define IEEE80211_CAPINFO_QOS 0x0200 +#define IEEE80211_CAPINFO_SHORT_SLOTTIME 0x0400 +#define IEEE80211_CAPINFO_APSD 0x0800 + +/* bit 12 is reserved */ + +#define IEEE80211_CAPINFO_DSSSOFDM 0x2000 +#define IEEE80211_CAPINFO_DELAYED_B_ACK 0x4000 +#define IEEE80211_CAPINFO_IMMEDIATE_B_ACK 0x8000 +#define IEEE80211_CAPINFO_BITS \ + "\10\01ESS\02IBSS\03CF_POLLABLE\04CF_POLLREQ" \ + "\05PRIVACY\06SHORT_PREAMBLE\07PBCC\10CHNL_AGILITY" \ + "\11SPECTRUM_MGMT\12QOS\13SHORT_SLOTTIME\14APSD" \ + "\16DSSSOFDM\17DELAYED_B_ACK\20IMMEDIATE_B_ACK" + +/* Block Ack Action field values (see Table 7-54). */ + +#define IEEE80211_ACTION_ADDBA_REQ 0 +#define IEEE80211_ACTION_ADDBA_RESP 1 +#define IEEE80211_ACTION_DELBA 2 + +/* SA Query Action field values (see Table 7-57l). */ + +#define IEEE80211_ACTION_SA_QUERY_REQ 0 +#define IEEE80211_ACTION_SA_QUERY_RESP 1 + +/* HT Action field values (see Table 7-57m). */ + +#define IEEE80211_ACTION_NOTIFYCW 0 + +#define IEEE80211_RATE_BASIC 0x80 +#define IEEE80211_RATE_VAL 0x7f +#define IEEE80211_RATE_SIZE 8 /* 802.11 standard */ +#define IEEE80211_RATE_MAXSIZE 15 /* max rates we'll handle */ + +/* BlockAck/BlockAckReq Control field (see Figure 7-13). */ + +#define IEEE80211_BA_ACK_POLICY 0x0001 +#define IEEE80211_BA_MULTI_TID 0x0002 +#define IEEE80211_BA_COMPRESSED 0x0004 +#define IEEE80211_BA_TID_INFO_MASK 0xf000 +#define IEEE80211_BA_TID_INFO_SHIFT 12 + +/* DELBA Parameter Set field (see Figure 7-34). */ + +#define IEEE80211_DELBA_INITIATOR 0x0800 + +/* ERP information element (see 7.3.2.13). */ + +#define IEEE80211_ERP_NON_ERP_PRESENT 0x01 +#define IEEE80211_ERP_USE_PROTECTION 0x02 +#define IEEE80211_ERP_BARKER_MODE 0x04 + +/* RSN capabilities (see 7.3.2.25.3). */ + +#define IEEE80211_RSNCAP_PREAUTH 0x0001 +#define IEEE80211_RSNCAP_NOPAIRWISE 0x0002 +#define IEEE80211_RSNCAP_PTKSA_RCNT_MASK 0x000c +#define IEEE80211_RSNCAP_PTKSA_RCNT_SHIFT 2 +#define IEEE80211_RSNCAP_GTKSA_RCNT_MASK 0x0030 +#define IEEE80211_RSNCAP_GTKSA_RCNT_SHIFT 4 +#define IEEE80211_RSNCAP_RCNT1 0 +#define IEEE80211_RSNCAP_RCNT2 1 +#define IEEE80211_RSNCAP_RCNT4 2 +#define IEEE80211_RSNCAP_RCNT16 3 +#define IEEE80211_RSNCAP_MFPR 0x0040 /* 11w */ +#define IEEE80211_RSNCAP_MFPC 0x0080 /* 11w */ +#define IEEE80211_RSNCAP_PEERKEYENA 0x0200 +#define IEEE80211_RSNCAP_SPPAMSDUC 0x0400 /* 11n */ +#define IEEE80211_RSNCAP_SPPAMSDUR 0x0800 /* 11n */ +#define IEEE80211_RSNCAP_PBAC 0x1000 /* 11n */ + +/* HT Capabilities Info (see 7.3.2.57.2). */ + +#define IEEE80211_HTCAP_LDPC 0x00000001 +#define IEEE80211_HTCAP_CBW20_40 0x00000002 +#define IEEE80211_HTCAP_SMPS_MASK 0x0000000c +#define IEEE80211_HTCAP_SMPS_SHIFT 2 +#define IEEE80211_HTCAP_SMPS_STA 0 +#define IEEE80211_HTCAP_SMPS_DYN 1 +#define IEEE80211_HTCAP_SMPS_DIS 3 +#define IEEE80211_HTCAP_GF 0x00000010 +#define IEEE80211_HTCAP_SGI20 0x00000020 +#define IEEE80211_HTCAP_SGI40 0x00000040 +#define IEEE80211_HTCAP_TXSTBC 0x00000080 +#define IEEE80211_HTCAP_RXSTBC_MASK 0x00000300 +#define IEEE80211_HTCAP_RXSTBC_SHIFT 8 +#define IEEE80211_HTCAP_DELAYEDBA 0x00000400 +#define IEEE80211_HTCAP_AMSDU7935 0x00000800 +#define IEEE80211_HTCAP_DSSSCCK40 0x00001000 +#define IEEE80211_HTCAP_PSMP 0x00002000 +#define IEEE80211_HTCAP_40INTOLERANT 0x00004000 +#define IEEE80211_HTCAP_LSIGTXOPPROT 0x00008000 + +/* HT Extended Capabilities (see 7.3.2.57.5).*/ + +#define IEEE80211_HTXCAP_PCO 0x0001 +#define IEEE80211_HTXCAP_PCOTT_MASK 0x0006 +#define IEEE80211_HTXCAP_PCOTT_SHIFT 1 +#define IEEE80211_HTXCAP_PCOTT_400 1 +#define IEEE80211_HTXCAP_PCOTT_1500 2 +#define IEEE80211_HTXCAP_PCOTT_5000 3 + +/* Bits 3-7 are reserved. */ + +#define IEEE80211_HTXCAP_MFB_MASK 0x0300 +#define IEEE80211_HTXCAP_MFB_SHIFT 8 +#define IEEE80211_HTXCAP_MFB_NONE 0 +#define IEEE80211_HTXCAP_MFB_UNSOL 2 +#define IEEE80211_HTXCAP_MFB_BOTH 3 +#define IEEE80211_HTXCAP_HTC 0x0400 +#define IEEE80211_HTXCAP_RDRESP 0x0800 + +/* Bits 12-15 are reserved. */ + +/* Transmit Beamforming (TxBF) Capabilities (see 7.3.2.57.6). */ + +#define IEEE80211_TXBFCAP_IMPLICIT_RX 0x00000001 +#define IEEE80211_TXBFCAP_RSSC 0x00000002 +#define IEEE80211_TXBFCAP_TSSC 0x00000004 +#define IEEE80211_TXBFCAP_RNDP 0x00000008 +#define IEEE80211_TXBFCAP_TNDP 0x00000010 +#define IEEE80211_TXBFCAP_IMPLICIT_TX 0x00000020 +#define IEEE80211_TXBFCAP_CALIB_MASK 0x000000c0 +#define IEEE80211_TXBFCAP_CALIB_SHIFT 6 +#define IEEE80211_TXBFCAP_TX_CSI 0x00000100 + +/* Antenna Selection (ASEL) Capability (see 7.3.2.57.7). */ + +#define IEEE80211_ASELCAP_ASEL 0x01 +#define IEEE80211_ASELCAP_CSIFB 0x02 + +/* Bit 7 is reserved. */ + +/* HT Operation element (see 7.3.2.58). */ + +/* Byte 1. */ + +#define IEEE80211_HTOP0_SCO_MASK 0x03 +#define IEEE80211_HTOP0_SCO_SHIFT 0 +#define IEEE80211_HTOP0_SCO_SCN 0 +#define IEEE80211_HTOP0_SCO_SCA 1 +#define IEEE80211_HTOP0_SCO_SCB 3 +#define IEEE80211_HTOP0_CHW 0x04 +#define IEEE80211_HTOP0_RIFS 0x08 +#define IEEE80211_HTOP0_SPSMP 0x10 +#define IEEE80211_HTOP0_SIG_MASK 0xe0 +#define IEEE80211_HTOP0_SIG_SHIFT 5 + +/* Bytes 2-3. */ + +#define IEEE80211_HTOP1_PROT_MASK 0x0003 +#define IEEE80211_HTOP1_PROT_SHIFT 0 +#define IEEE80211_HTOP1_NONGTSTA 0x0004 + +/* Bit 3 is reserved. */ + +#define IEEE80211_HTOP1_OBSS_NONHTSTA 0x0010 + +/* Bits 5-15 are reserved. */ + +/* Bytes 4-5. */ + +/* Bits 0-5 are reserved. */ + +#define IEEE80211_HTOP2_DUALBEACON 0x0040 +#define IEEE80211_HTOP2_DUALCTSPROT 0x0080 +#define IEEE80211_HTOP2_STBCBEACON 0x0100 +#define IEEE80211_HTOP2_LSIGTXOP 0x0200 +#define IEEE80211_HTOP2_PCOACTIVE 0x0400 +#define IEEE80211_HTOP2_PCOPHASE40 0x0800 + +/* Bits 12-15 are reserved. */ + +/* EDCA Access Categories. */ + +#define EDCA_NUM_AC 4 + +/* Number of TID values (traffic identifier) */ + +#define IEEE80211_NUM_TID 16 + +/* Atheros private advanced capabilities info */ + +#define ATHEROS_CAP_TURBO_PRIME 0x01 +#define ATHEROS_CAP_COMPRESSION 0x02 +#define ATHEROS_CAP_FAST_FRAME 0x04 + +/* bits 3-6 reserved */ + +#define ATHEROS_CAP_BOOST 0x80 + +/* Organizationally Unique Identifiers. + * See http://standards.ieee.org/regauth/oui/oui.txt for a list. + */ + +#define ATHEROS_OUI ((const uint8_t[]){ 0x00, 0x03, 0x7f }) +#define BROADCOM_OUI ((const uint8_t[]){ 0x00, 0x90, 0x4c }) +#define IEEE80211_OUI ((const uint8_t[]){ 0x00, 0x0f, 0xac }) +#define MICROSOFT_OUI ((const uint8_t[]){ 0x00, 0x50, 0xf2 }) + +#define IEEE80211_AUTH_ALGORITHM(auth) \ + ((auth)[0] | ((auth)[1] << 8)) +#define IEEE80211_AUTH_TRANSACTION(auth) \ + ((auth)[2] | ((auth)[3] << 8)) +#define IEEE80211_AUTH_STATUS(auth) \ + ((auth)[4] | ((auth)[5] << 8)) + +/* Authentication Algorithm Number field (see 7.3.1.1). */ + +#define IEEE80211_AUTH_ALG_OPEN 0x0000 +#define IEEE80211_AUTH_ALG_SHARED 0x0001 +#define IEEE80211_AUTH_ALG_LEAP 0x0080 + +/* WEP */ + +#define IEEE80211_WEP_KEYLEN 5 /* 40bit */ +#define IEEE80211_WEP_NKID 4 /* number of key ids */ +#define IEEE80211_CHALLENGE_LEN 128 + +/* WEP header constants */ + +#define IEEE80211_WEP_IVLEN 3 /* 24bit */ +#define IEEE80211_WEP_KIDLEN 1 /* 1 octet */ +#define IEEE80211_WEP_CRCLEN 4 /* CRC-32 */ +#define IEEE80211_CRC_LEN 4 +#define IEEE80211_WEP_TOTLEN \ + (IEEE80211_WEP_IVLEN + IEEE80211_WEP_KIDLEN + IEEE80211_WEP_CRCLEN) + +/* 802.11i defines an extended IV for use with non-WEP ciphers. + * When the EXTIV bit is set in the key id byte an additional + * 4 bytes immediately follow the IV for TKIP. For CCMP the + * EXTIV bit is likewise set but the 8 bytes represent the + * CCMP header rather than IV+extended-IV. + */ + +#define IEEE80211_WEP_EXTIV 0x20 +#define IEEE80211_WEP_EXTIVLEN 4 /* extended IV length */ +#define IEEE80211_WEP_MICLEN 8 /* trailing MIC */ + +/* Maximum acceptable MTU is: + * IEEE80211_MAX_LEN - WEP overhead - CRC - + * QoS overhead - RSN/WPA overhead + * Min is arbitrarily chosen > IEEE80211_MIN_LEN. The default + * mtu is Ethernet-compatible. + */ + +#define IEEE80211_MTU_MAX 2290 +#define IEEE80211_MTU_MIN 32 + +#define IEEE80211_MAX_LEN \ + (2300 + IEEE80211_CRC_LEN + \ + (IEEE80211_WEP_IVLEN + IEEE80211_WEP_KIDLEN + IEEE80211_WEP_CRCLEN)) +#define IEEE80211_ACK_LEN \ + (sizeof(struct ieee80211_frame_ack) + IEEE80211_CRC_LEN) +#define IEEE80211_MIN_LEN \ + (sizeof(struct ieee80211_frame_min) + IEEE80211_CRC_LEN) + +/* The 802.11 spec says at most 2007 stations may be + * associated at once. For most AP's this is way more + * than is feasible so we use a default of 1800. This + * number may be overridden by the driver and/or by + * user configuration. + */ + +#define IEEE80211_AID_MAX 2007 +#define IEEE80211_AID_DEF 1800 +#define IEEE80211_AID(b) ((b) &~ 0xc000) + +/* RTS frame length parameters. The default is specified in + * the 802.11 spec. The max may be wrong for jumbo frames. + */ + +#define IEEE80211_RTS_DEFAULT 512 +#define IEEE80211_RTS_MIN 1 +#define IEEE80211_RTS_MAX IEEE80211_MAX_LEN + +#define IEEE80211_PLCP_SERVICE 0x00 +#define IEEE80211_PLCP_SERVICE_PBCC 0x08 /* PBCC encoded */ +#define IEEE80211_PLCP_SERVICE_LENEXT 0x80 /* length extension bit */ + +/* One Time Unit (TU) is 1Kus = 1024 microseconds. */ + +#define IEEE80211_DUR_TU 1024 + +/* IEEE 802.11b durations for DSSS PHY in microseconds */ + +#define IEEE80211_DUR_DS_LONG_PREAMBLE 144 +#define IEEE80211_DUR_DS_SHORT_PREAMBLE 72 +#define IEEE80211_DUR_DS_PREAMBLE_DIFFERENCE \ + (IEEE80211_DUR_DS_LONG_PREAMBLE - IEEE80211_DUR_DS_SHORT_PREAMBLE) +#define IEEE80211_DUR_DS_FAST_PLCPHDR 24 +#define IEEE80211_DUR_DS_SLOW_PLCPHDR 48 +#define IEEE80211_DUR_DS_PLCPHDR_DIFFERENCE \ + (IEEE80211_DUR_DS_SLOW_PLCPHDR - IEEE80211_DUR_DS_FAST_PLCPHDR) +#define IEEE80211_DUR_DS_SLOW_ACK 112 +#define IEEE80211_DUR_DS_FAST_ACK 56 +#define IEEE80211_DUR_DS_SLOW_CTS 112 +#define IEEE80211_DUR_DS_FAST_CTS 56 +#define IEEE80211_DUR_DS_SLOT 20 +#define IEEE80211_DUR_DS_SIFS 10 +#define IEEE80211_DUR_DS_PIFS \ + (IEEE80211_DUR_DS_SIFS + IEEE80211_DUR_DS_SLOT) +#define IEEE80211_DUR_DS_DIFS \ + (IEEE80211_DUR_DS_SIFS + 2 * IEEE80211_DUR_DS_SLOT) +#define IEEE80211_DUR_DS_EIFS (IEEE80211_DUR_DS_SIFS + \ + IEEE80211_DUR_DS_SLOW_ACK + \ + IEEE80211_DUR_DS_LONG_PREAMBLE + \ + IEEE80211_DUR_DS_SLOW_PLCPHDR + \ + IEEE80211_DUR_DIFS) + +/* The RSNA key descriptor used by IEEE 802.11 does not use the IEEE 802.1X + * key descriptor. Instead, it uses the key descriptor described in 8.5.2. + */ + +#define EAPOL_KEY_NONCE_LEN 32 +#define EAPOL_KEY_IV_LEN 16 +#define EAPOL_KEY_MIC_LEN 16 + +/* Pairwise Transient Key (see 8.5.1.2) */ + +#define IEEE80211_PMKID_LEN 16 +#define IEEE80211_SMKID_LEN 16 + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* Generic definitions for IEEE 802.11 frames */ + +begin_packed_struct struct ieee80211_frame +{ + uint8_t i_fc[2]; + uint8_t i_dur[2]; + uint8_t i_addr1[IEEE80211_ADDR_LEN]; + uint8_t i_addr2[IEEE80211_ADDR_LEN]; + uint8_t i_addr3[IEEE80211_ADDR_LEN]; + uint8_t i_seq[2]; +} end_packed_struct; + +begin_packed_struct struct ieee80211_qosframe +{ + uint8_t i_fc[2]; + uint8_t i_dur[2]; + uint8_t i_addr1[IEEE80211_ADDR_LEN]; + uint8_t i_addr2[IEEE80211_ADDR_LEN]; + uint8_t i_addr3[IEEE80211_ADDR_LEN]; + uint8_t i_seq[2]; + uint8_t i_qos[2]; +} end_packet_struct; + +begin_packed_struct struct ieee80211_htframe /* 11n */ +{ + uint8_t i_fc[2]; + uint8_t i_dur[2]; + uint8_t i_addr1[IEEE80211_ADDR_LEN]; + uint8_t i_addr2[IEEE80211_ADDR_LEN]; + uint8_t i_addr3[IEEE80211_ADDR_LEN]; + uint8_t i_seq[2]; + uint8_t i_qos[2]; + uint8_t i_ht[4]; +} end_packet_struct; + +begin_packed_struct struct ieee80211_frame_addr4 +{ + uint8_t i_fc[2]; + uint8_t i_dur[2]; + uint8_t i_addr1[IEEE80211_ADDR_LEN]; + uint8_t i_addr2[IEEE80211_ADDR_LEN]; + uint8_t i_addr3[IEEE80211_ADDR_LEN]; + uint8_t i_seq[2]; + uint8_t i_addr4[IEEE80211_ADDR_LEN]; +} end_packet_struct; + +begin_packed_struct struct ieee80211_qosframe_addr4 +{ + uint8_t i_fc[2]; + uint8_t i_dur[2]; + uint8_t i_addr1[IEEE80211_ADDR_LEN]; + uint8_t i_addr2[IEEE80211_ADDR_LEN]; + uint8_t i_addr3[IEEE80211_ADDR_LEN]; + uint8_t i_seq[2]; + uint8_t i_addr4[IEEE80211_ADDR_LEN]; + uint8_t i_qos[2]; +} end_packet_struct; + +begin_packed_struct struct ieee80211_htframe_addr4 /* 11n */ +{ + uint8_t i_fc[2]; + uint8_t i_dur[2]; + uint8_t i_addr1[IEEE80211_ADDR_LEN]; + uint8_t i_addr2[IEEE80211_ADDR_LEN]; + uint8_t i_addr3[IEEE80211_ADDR_LEN]; + uint8_t i_seq[2]; + uint8_t i_addr4[IEEE80211_ADDR_LEN]; + uint8_t i_qos[2]; + uint8_t i_ht[4]; +} end_packet_struct; + +/* Control frames. */ + +begin_packed_struct struct ieee80211_frame_min +{ + uint8_t i_fc[2]; + uint8_t i_dur[2]; + uint8_t i_addr1[IEEE80211_ADDR_LEN]; + uint8_t i_addr2[IEEE80211_ADDR_LEN]; + + /* FCS */ + +} end_packet_struct; + +begin_packed_struct struct ieee80211_frame_rts +{ + uint8_t i_fc[2]; + uint8_t i_dur[2]; + uint8_t i_ra[IEEE80211_ADDR_LEN]; + uint8_t i_ta[IEEE80211_ADDR_LEN]; + + /* FCS */ + +} end_packet_struct; + +struct ieee80211_frame_cts +{ + uint8_t i_fc[2]; + uint8_t i_dur[2]; + uint8_t i_ra[IEEE80211_ADDR_LEN]; + + /* FCS */ + +} end_packet_struct; + +struct ieee80211_frame_ack +{ + uint8_t i_fc[2]; + uint8_t i_dur[2]; + uint8_t i_ra[IEEE80211_ADDR_LEN]; + + /* FCS */ + +} end_packet_struct; + +struct ieee80211_frame_pspoll +{ + uint8_t i_fc[2]; + uint8_t i_aid[2]; + uint8_t i_bssid[IEEE80211_ADDR_LEN]; + uint8_t i_ta[IEEE80211_ADDR_LEN]; + + /* FCS */ + +} end_packet_struct; + +struct ieee80211_frame_cfend +{ /* NB: also CF-End+CF-Ack */ + uint8_t i_fc[2]; + uint8_t i_dur[2]; /* should be zero */ + uint8_t i_ra[IEEE80211_ADDR_LEN]; + uint8_t i_bssid[IEEE80211_ADDR_LEN]; + + /* FCS */ + +} end_packet_struct; + +/* Information elements (see Table 7-26). */ + +enum +{ + IEEE80211_ELEMID_SSID = 0, + IEEE80211_ELEMID_RATES = 1, + IEEE80211_ELEMID_FHPARMS = 2, + IEEE80211_ELEMID_DSPARMS = 3, + IEEE80211_ELEMID_CFPARMS = 4, + IEEE80211_ELEMID_TIM = 5, + IEEE80211_ELEMID_IBSSPARMS = 6, + IEEE80211_ELEMID_COUNTRY = 7, + IEEE80211_ELEMID_QBSS_LOAD = 11, + IEEE80211_ELEMID_EDCAPARMS = 12, + IEEE80211_ELEMID_CHALLENGE = 16, + + /* 17-31 reserved for challenge text extension */ + + IEEE80211_ELEMID_ERP = 42, + IEEE80211_ELEMID_HTCAPS = 45, /* 11n */ + IEEE80211_ELEMID_QOS_CAP = 46, + IEEE80211_ELEMID_RSN = 48, + IEEE80211_ELEMID_XRATES = 50, + IEEE80211_ELEMID_TIE = 56, /* 11r */ + IEEE80211_ELEMID_HTOP = 61, /* 11n */ + IEEE80211_ELEMID_MMIE = 76, /* 11w */ + IEEE80211_ELEMID_TPC = 150, + IEEE80211_ELEMID_CCKM = 156, + IEEE80211_ELEMID_VENDOR = 221 /* vendor private */ +}; + +/* Action field category values (see Table 7-24). */ + +enum +{ + IEEE80211_CATEG_SPECTRUM = 0, + IEEE80211_CATEG_QOS = 1, + IEEE80211_CATEG_DLS = 2, + IEEE80211_CATEG_BA = 3, + IEEE80211_CATEG_HT = 7, /* 11n */ + IEEE80211_CATEG_SA_QUERY = 8 /* 11w */ +}; + +/* EDCA Access Categories. */ + +enum ieee80211_edca_ac +{ + EDCA_AC_BK = 1, /* Background */ + EDCA_AC_BE = 0, /* Best Effort */ + EDCA_AC_VI = 2, /* Video */ + EDCA_AC_VO = 3 /* Voice */ +}; + +/* Authentication Transaction Sequence Number field (see 7.3.1.2). */ + +enum +{ + IEEE80211_AUTH_OPEN_REQUEST = 1, + IEEE80211_AUTH_OPEN_RESPONSE = 2 +}; + +enum +{ + IEEE80211_AUTH_SHARED_REQUEST = 1, + IEEE80211_AUTH_SHARED_CHALLENGE = 2, + IEEE80211_AUTH_SHARED_RESPONSE = 3, + IEEE80211_AUTH_SHARED_PASS = 4 +}; + +/* Reason codes (see Table 22). */ + +enum +{ + IEEE80211_REASON_UNSPECIFIED = 1, + IEEE80211_REASON_AUTH_EXPIRE = 2, + IEEE80211_REASON_AUTH_LEAVE = 3, + IEEE80211_REASON_ASSOC_EXPIRE = 4, + IEEE80211_REASON_ASSOC_TOOMANY = 5, + IEEE80211_REASON_NOT_AUTHED = 6, + IEEE80211_REASON_NOT_ASSOCED = 7, + IEEE80211_REASON_ASSOC_LEAVE = 8, + IEEE80211_REASON_ASSOC_NOT_AUTHED = 9, + + /* XXX the following two reason codes are not correct */ + + IEEE80211_REASON_RSN_REQUIRED = 11, + IEEE80211_REASON_RSN_INCONSISTENT = 12, + + IEEE80211_REASON_IE_INVALID = 13, + IEEE80211_REASON_MIC_FAILURE = 14, + IEEE80211_REASON_4WAY_TIMEOUT = 15, + IEEE80211_REASON_GROUP_TIMEOUT = 16, + IEEE80211_REASON_RSN_DIFFERENT_IE = 17, + IEEE80211_REASON_BAD_GROUP_CIPHER = 18, + IEEE80211_REASON_BAD_PAIRWISE_CIPHER = 19, + IEEE80211_REASON_BAD_AKMP = 20, + IEEE80211_REASON_RSN_IE_VER_UNSUP = 21, + IEEE80211_REASON_RSN_IE_BAD_CAP = 22, + + IEEE80211_REASON_CIPHER_REJ_POLICY = 24, + + IEEE80211_REASON_SETUP_REQUIRED = 38, + IEEE80211_REASON_TIMEOUT = 39 +}; + +/* Status codes (see Table 23). */ + +enum +{ + IEEE80211_STATUS_SUCCESS = 0, + IEEE80211_STATUS_UNSPECIFIED = 1, + IEEE80211_STATUS_CAPINFO = 10, + IEEE80211_STATUS_NOT_ASSOCED = 11, + IEEE80211_STATUS_OTHER = 12, + IEEE80211_STATUS_ALG = 13, + IEEE80211_STATUS_SEQUENCE = 14, + IEEE80211_STATUS_CHALLENGE = 15, + IEEE80211_STATUS_TIMEOUT = 16, + IEEE80211_STATUS_TOOMANY = 17, + IEEE80211_STATUS_BASIC_RATE = 18, + IEEE80211_STATUS_SP_REQUIRED = 19, + IEEE80211_STATUS_PBCC_REQUIRED = 20, + IEEE80211_STATUS_CA_REQUIRED = 21, + IEEE80211_STATUS_TOO_MANY_STATIONS = 22, + IEEE80211_STATUS_RATES = 23, + IEEE80211_STATUS_SHORTSLOT_REQUIRED = 25, + IEEE80211_STATUS_DSSSOFDM_REQUIRED = 26, + + IEEE80211_STATUS_TRY_AGAIN_LATER = 30, + IEEE80211_STATUS_MFP_POLICY = 31, + + IEEE80211_STATUS_REFUSED = 37, + IEEE80211_STATUS_INVALID_PARAM = 38, + + IEEE80211_STATUS_IE_INVALID = 40, + IEEE80211_STATUS_BAD_GROUP_CIPHER = 41, + IEEE80211_STATUS_BAD_PAIRWISE_CIPHER = 42, + IEEE80211_STATUS_BAD_AKMP = 43, + IEEE80211_STATUS_RSN_IE_VER_UNSUP = 44, + + IEEE80211_STATUS_CIPHER_REJ_POLICY = 46, +}; + +struct ieee80211_eapol_key +{ + uint8_t version; + +#define EAPOL_VERSION 1 + + uint8_t type; + +/* IEEE Std 802.1X-2004, 7.5.4 (only type EAPOL-Key is used here) */ + +#define EAP_PACKET 0 +#define EAPOL_START 1 +#define EAPOL_LOGOFF 2 +#define EAPOL_KEY 3 +#define EAPOL_ASF_ALERT 4 + + uint8_t len[2]; + uint8_t desc; + +/* IEEE Std 802.1X-2004, 7.6.1 */ + +#define EAPOL_KEY_DESC_RC4 1 /* Deprecated */ +#define EAPOL_KEY_DESC_IEEE80211 2 +#define EAPOL_KEY_DESC_WPA 254 /* Non-standard WPA */ + + uint8_t info[2]; + +#define EAPOL_KEY_VERSION_MASK 0x7 +#define EAPOL_KEY_DESC_V1 1 +#define EAPOL_KEY_DESC_V2 2 +#define EAPOL_KEY_DESC_V3 3 /* 11r */ +#define EAPOL_KEY_PAIRWISE (1 << 3) +#define EAPOL_KEY_INSTALL (1 << 6) /* I */ +#define EAPOL_KEY_KEYACK (1 << 7) /* A */ +#define EAPOL_KEY_KEYMIC (1 << 8) /* M */ +#define EAPOL_KEY_SECURE (1 << 9) /* S */ +#define EAPOL_KEY_ERROR (1 << 10) +#define EAPOL_KEY_REQUEST (1 << 11) +#define EAPOL_KEY_ENCRYPTED (1 << 12) +#define EAPOL_KEY_SMK (1 << 13) + +/* WPA compatibility */ + +#define EAPOL_KEY_WPA_KID_MASK 0x3 +#define EAPOL_KEY_WPA_KID_SHIFT 4 +#define EAPOL_KEY_WPA_TX EAPOL_KEY_INSTALL + + uint8_t keylen[2]; + uint8_t replaycnt[8]; + uint8_t nonce[EAPOL_KEY_NONCE_LEN]; + uint8_t iv[EAPOL_KEY_IV_LEN]; + uint8_t rsc[8]; + uint8_t reserved[8]; + uint8_t mic[EAPOL_KEY_MIC_LEN]; + uint8_t paylen[2]; +} end_packet_struct; + +/* Pairwise Transient Key (see 8.5.1.2) */ + +struct ieee80211_ptk +{ + uint8_t kck[16]; /* Key Confirmation Key */ + uint8_t kek[16]; /* Key Encryption Key */ + uint8_t tk[32]; /* Temporal Key */ +} end_packet_struct; + +/* Key Data Encapsulation (see Table 62) */ + +enum +{ + IEEE80211_KDE_GTK = 1, + IEEE80211_KDE_MACADDR = 3, + IEEE80211_KDE_PMKID = 4, + IEEE80211_KDE_SMK = 5, + IEEE80211_KDE_NONCE = 6, + IEEE80211_KDE_LIFETIME = 7, + IEEE80211_KDE_ERROR = 8, + IEEE80211_KDE_IGTK = 9 /* 11w */ +}; + +/**************************************************************************** + * Inline Functions + ****************************************************************************/ + +static inline int ieee80211_has_seq(FAR const struct ieee80211_frame *wh) +{ + return (wh->i_fc[0] & IEEE80211_FC0_TYPE_MASK) != IEEE80211_FC0_TYPE_CTL; +} + +static inline int ieee80211_has_addr4(FAR const struct ieee80211_frame *wh) +{ + return (wh->i_fc[1] & IEEE80211_FC1_DIR_MASK) == IEEE80211_FC1_DIR_DSTODS; +} + +static inline int ieee80211_has_qos(FAR const struct ieee80211_frame *wh) +{ + return (wh->i_fc[0] & + (IEEE80211_FC0_TYPE_MASK | IEEE80211_FC0_SUBTYPE_QOS)) == + (IEEE80211_FC0_TYPE_DATA | IEEE80211_FC0_SUBTYPE_QOS); +} + +static inline int ieee80211_has_htc(FAR const struct ieee80211_frame *wh) +{ + return (wh->i_fc[1] & IEEE80211_FC1_ORDER) && + (ieee80211_has_qos(wh) || + (wh->i_fc[0] & IEEE80211_FC0_TYPE_MASK) == IEEE80211_FC0_TYPE_MGT); +} + +static inline uint16_t ieee80211_get_qos(FAR const struct ieee80211_frame *wh) +{ + FAR const uint8_t *frm; + + if (ieee80211_has_addr4(wh)) + { + frm = ((FAR const struct ieee80211_qosframe_addr4 *)wh)->i_qos; + } + else + { + frm = ((FAR const struct ieee80211_qosframe *)wh)->i_qos; + } + + return letoh16(*(FAR const uint16_t *)frm); +} + +#endif /* __INCLUDE_NUTTX_WIRELESS_IEEE80211_IEEE80211_H */ diff --git a/include/nuttx/wireless/ieee80211/ieee80211_cypto.h b/include/nuttx/wireless/ieee80211/ieee80211_cypto.h new file mode 100644 index 0000000000..44a9d91b66 --- /dev/null +++ b/include/nuttx/wireless/ieee80211/ieee80211_cypto.h @@ -0,0 +1,119 @@ +/**************************************************************************** + * net/ieee80211/ieee80211_crypto.h + * 802.11 protocol crypto-related definitions. + * + * Copyright (c) 2007,2008 Damien Bergamini + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ****************************************************************************/ + +#ifndef __NET_IEEE80211_IEEE80211_CRYPTO_H +#define __NET_IEEE80211_IEEE80211_CRYPTO_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define IEEE80211_KEYBUF_SIZE 16 + +#define IEEE80211_TKIP_HDRLEN 8 +#define IEEE80211_TKIP_MICLEN 8 +#define IEEE80211_TKIP_ICVLEN 4 +#define IEEE80211_CCMP_HDRLEN 8 +#define IEEE80211_CCMP_MICLEN 8 + +#define IEEE80211_PMK_LEN 32 + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* 802.11 ciphers */ + +enum ieee80211_cipher +{ + IEEE80211_CIPHER_NONE = 0x00000000, + IEEE80211_CIPHER_USEGROUP = 0x00000001, + IEEE80211_CIPHER_WEP40 = 0x00000002, + IEEE80211_CIPHER_TKIP = 0x00000004, + IEEE80211_CIPHER_CCMP = 0x00000008, + IEEE80211_CIPHER_WEP104 = 0x00000010, + IEEE80211_CIPHER_BIP = 0x00000020 /* 11w */ +}; + +/* 802.11 Authentication and Key Management Protocols */ + +enum ieee80211_akm +{ + IEEE80211_AKM_NONE = 0x00000000, + IEEE80211_AKM_8021X = 0x00000001, + IEEE80211_AKM_PSK = 0x00000002, + IEEE80211_AKM_SHA256_8021X = 0x00000004, /* 11w */ + IEEE80211_AKM_SHA256_PSK = 0x00000008 /* 11w */ +}; + +struct ieee80211_key +{ + uint8_t k_id; /* Identifier (0-5) */ + enum ieee80211_cipher k_cipher; + unsigned int k_flags; + +#define IEEE80211_KEY_GROUP 0x00000001 /* Group data key */ +#define IEEE80211_KEY_TX 0x00000002 /* Tx+Rx */ +#define IEEE80211_KEY_IGTK 0x00000004 /* Integrity group key */ + + unsigned int k_len; + uint64_t k_rsc[IEEE80211_NUM_TID]; + uint64_t k_mgmt_rsc; + uint64_t k_tsc; + uint8_t k_key[32]; + FAR void *k_priv; +}; + +/* Entry in the PMKSA cache */ + +struct ieee80211_pmk +{ + sq_entry_t pmk_next; + enum ieee80211_akm pmk_akm; + uint32_t pmk_lifetime; + +#define IEEE80211_PMK_INFINITE 0 + + uint8_t pmk_pmkid[IEEE80211_PMKID_LEN]; + uint8_t pmk_macaddr[IEEE80211_ADDR_LEN]; + uint8_t pmk_key[IEEE80211_PMK_LEN]; +}; + +/**************************************************************************** + * Inline Functions + ****************************************************************************/ + +static __inline int ieee80211_is_8021x_akm(enum ieee80211_akm akm) +{ + return akm == IEEE80211_AKM_8021X || akm == IEEE80211_AKM_SHA256_8021X; +} + +static __inline int ieee80211_is_sha256_akm(enum ieee80211_akm akm) +{ + return akm == IEEE80211_AKM_SHA256_8021X || akm == IEEE80211_AKM_SHA256_PSK; +} + +#endif /* __NET_IEEE80211_IEEE80211_CRYPTO_H */ \ No newline at end of file -- GitLab From 1a98a17204c385a177a935f3a7e52eaf4e6d5fb1 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 30 Apr 2017 17:44:29 -0600 Subject: [PATCH 662/990] Cosmetic --- include/nuttx/wireless/ieee80211/ieee80211_cypto.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/include/nuttx/wireless/ieee80211/ieee80211_cypto.h b/include/nuttx/wireless/ieee80211/ieee80211_cypto.h index 44a9d91b66..d421cc8346 100644 --- a/include/nuttx/wireless/ieee80211/ieee80211_cypto.h +++ b/include/nuttx/wireless/ieee80211/ieee80211_cypto.h @@ -2,7 +2,7 @@ * net/ieee80211/ieee80211_crypto.h * 802.11 protocol crypto-related definitions. * - * Copyright (c) 2007,2008 Damien Bergamini + * Copyright (c) 2007, 2008 Damien Bergamini * * Permission to use, copy, modify, and distribute this software for any * purpose with or without fee is hereby granted, provided that the above @@ -18,8 +18,8 @@ * ****************************************************************************/ -#ifndef __NET_IEEE80211_IEEE80211_CRYPTO_H -#define __NET_IEEE80211_IEEE80211_CRYPTO_H +#ifndef __INCLUDE_NUTTX_WIRELESS_IEEE80211_IEEE80211_CRYPTO_H +#define __INCLUDE_NUTTX_WIRELESS_IEEE80211_IEEE80211_CRYPTO_H /**************************************************************************** * Included Files @@ -116,4 +116,4 @@ static __inline int ieee80211_is_sha256_akm(enum ieee80211_akm akm) return akm == IEEE80211_AKM_SHA256_8021X || akm == IEEE80211_AKM_SHA256_PSK; } -#endif /* __NET_IEEE80211_IEEE80211_CRYPTO_H */ \ No newline at end of file +#endif /* __INCLUDE_NUTTX_WIRELESS_IEEE80211_IEEE80211_CRYPTO_H */ -- GitLab From b1ff257215280007303b7d5a173246e7333feb47 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Mon, 1 May 2017 09:27:06 -0400 Subject: [PATCH 663/990] wireless/ieee802154: Minor fixes to account for moved IOCTL definitions --- include/nuttx/wireless/ieee802154/ieee802154_ioctl.h | 6 +++++- wireless/ieee802154/mac802154_device.c | 6 +----- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_ioctl.h b/include/nuttx/wireless/ieee802154/ieee802154_ioctl.h index 24ac37369f..533e2f3853 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_ioctl.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_ioctl.h @@ -67,7 +67,11 @@ * Public Types ************************************************************************************/ -/* To be provided */ +struct mac802154dev_notify_s +{ + uint8_t mn_signo; /* Signal number to use in the notification */ +}; + #endif /* CONFIG_WIRELESS_IEEE802154 */ #endif /* __INCLUDE_NUTTX_WIRELESS_IEEE802154_IEEE802154_IOCTL_H */ diff --git a/wireless/ieee802154/mac802154_device.c b/wireless/ieee802154/mac802154_device.c index 19d3a5bc41..9721a5a7fe 100644 --- a/wireless/ieee802154/mac802154_device.c +++ b/wireless/ieee802154/mac802154_device.c @@ -50,6 +50,7 @@ #include #include +#include #include #include "mac802154.h" @@ -67,11 +68,6 @@ * Private Types ****************************************************************************/ -struct mac802154dev_notify_s -{ - uint8_t mn_signo; /* Signal number to use in the notification */ -}; - /* This structure describes the state of one open mac driver instance */ struct mac802154dev_open_s -- GitLab From c4007a111c2d22abd25320386d8999c3599a23ae Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Mon, 1 May 2017 09:27:40 -0400 Subject: [PATCH 664/990] wireless/ieee802154: Fixes semaphore logic and list logic --- drivers/wireless/ieee802154/mrf24j40.c | 4 + .../wireless/ieee802154/ieee802154_mac.h | 5 +- wireless/ieee802154/mac802154.c | 94 +++++++++++++++++-- wireless/ieee802154/mac802154_device.c | 8 +- 4 files changed, 97 insertions(+), 14 deletions(-) diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c index e65e48c108..6b602b739d 100644 --- a/drivers/wireless/ieee802154/mrf24j40.c +++ b/drivers/wireless/ieee802154/mrf24j40.c @@ -1819,6 +1819,10 @@ FAR struct ieee802154_radio_s *mrf24j40_init(FAR struct spi_dev_s *spi, return NULL; } + /* Allow exclusive access to the privmac struct */ + + sem_init(&dev->exclsem, 0, 1); + dev->radio.ops = &mrf24j40_devops; dev->lower = lower; diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index fc2b57c8f7..1a8e324ce2 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -536,11 +536,12 @@ struct ieee802154_data_req_s * to continue and make the struct "variable length" */ - uint8_t msdu[1]; + uint8_t msdu[IEEE802154_MAX_MAC_PAYLOAD_SIZE]; }; #define SIZEOF_IEEE802154_DATA_REQ_S(n) \ - (sizeof(struct ieee802154_data_req_s) + (n) - 1) + (sizeof(struct ieee802154_data_req_s) \ + - IEEE802154_MAX_MAC_PAYLOAD_SIZE + (n)) /***************************************************************************** * Primitive: MCPS-DATA.confirm diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index 54e5782b41..f6b5f5f455 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -337,6 +337,78 @@ static inline int mac802154_takesem(sem_t *sem) return OK; } +/**************************************************************************** + * Name: mac802154_push_csma + * + * Description: + * Push a CSMA transaction onto the list + * + ****************************************************************************/ + +static void mac802154_push_csma(FAR struct ieee802154_privmac_s *priv, + FAR struct mac802154_trans_s *trans) +{ + /* Ensure the transactions forward link is NULL */ + + trans->flink = NULL; + + /* If the tail is not empty, make the transaction pointed to by the tail, + * point to the new transaction */ + + if (priv->csma_tail != NULL) + { + priv->csma_tail->flink = trans; + } + + /* Point the tail at the new transaction */ + + priv->csma_tail = trans; + + /* If the head is NULL, we need to point it at the transaction since there + * is only one transaction in the list at this point */ + + if (priv->csma_head == NULL) + { + priv->csma_head = trans; + } +} + +/**************************************************************************** + * Name: mac802154_pop_csma + * + * Description: + * Pop a CSMA transaction from the list + * + ****************************************************************************/ + +static FAR struct mac802154_trans_s * + mac802154_pop_csma(FAR struct ieee802154_privmac_s *priv) +{ + FAR struct mac802154_trans_s *trans; + + if (priv->csma_head == NULL) + { + return NULL; + } + + /* Get the transaction from the head of the list */ + + trans = priv->csma_head; + + /* Move the head pointer to the next transaction */ + + priv->csma_head = trans->flink; + + /* If the head is now NULL, the list is empty, so clear the tail too */ + + if (priv->csma_head == NULL) + { + priv->csma_tail = NULL; + } + + return trans; +} + /**************************************************************************** * Name: mac802154_defaultmib * @@ -398,14 +470,11 @@ static int mac802154_poll_csma(FAR const struct ieee802154_radiocb_s *radiocb, /* Check to see if there are any CSMA transactions waiting */ - if (priv->csma_head) - { - /* Pop a CSMA transaction off the list */ - - trans = priv->csma_head; - priv->csma_head = priv->csma_head->flink; + trans = mac802154_pop_csma(priv); + mac802154_givesem(&priv->exclsem); - mac802154_givesem(&priv->exclsem); + if (trans != NULL) + { /* Setup the transmit descriptor */ @@ -426,7 +495,6 @@ static int mac802154_poll_csma(FAR const struct ieee802154_radiocb_s *radiocb, return (trans->mhr_len + trans->d_len); } - mac802154_givesem(&priv->exclsem); return 0; } @@ -673,6 +741,10 @@ MACHANDLE mac802154_create(FAR struct ieee802154_radio_s *radiodev) { return NULL; } + + /* Allow exclusive access to the privmac struct */ + + sem_init(&mac->exclsem, 0, 1); /* Initialize fields */ @@ -939,6 +1011,8 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) trans.msdu_handle = req->msdu_handle; + sem_init(&trans.sem, 0, 1); + /* If the TxOptions parameter specifies that a GTS transmission is required, * the MAC sublayer will determine whether it has a valid GTS as described * 5.1.7.3. If a valid GTS could not be found, the MAC sublayer will discard @@ -1000,8 +1074,7 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) { /* Link the transaction into the CSMA transaction list */ - priv->csma_tail->flink = &trans; - priv->csma_tail = &trans; + mac802154_push_csma(priv, &trans); /* We no longer need to have the MAC layer locked. */ @@ -1015,6 +1088,7 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) } } + sem_destroy(&trans.sem); return OK; } diff --git a/wireless/ieee802154/mac802154_device.c b/wireless/ieee802154/mac802154_device.c index 9721a5a7fe..5c31cdf140 100644 --- a/wireless/ieee802154/mac802154_device.c +++ b/wireless/ieee802154/mac802154_device.c @@ -425,8 +425,8 @@ static ssize_t mac802154dev_write(FAR struct file *filep, /* Check to make sure that the buffer is big enough to hold at least one * packet. */ - if ((len >= SIZEOF_IEEE802154_DATA_REQ_S(1)) && - (len <= SIZEOF_IEEE802154_DATA_REQ_S(IEEE802154_MAX_MAC_PAYLOAD_SIZE))) + if ((len < SIZEOF_IEEE802154_DATA_REQ_S(1)) || + (len > SIZEOF_IEEE802154_DATA_REQ_S(IEEE802154_MAX_MAC_PAYLOAD_SIZE))) { wlerr("ERROR: buffer isn't an ieee802154_data_req_s: %lu\n", (unsigned long)len); @@ -463,6 +463,8 @@ static ssize_t mac802154dev_write(FAR struct file *filep, dwait.mw_flink = dev->md_dwait; dev->md_dwait = &dwait; + sem_init(&dwait.mw_sem, 0, 1); + mac802154dev_givesem(&dev->md_exclsem); } @@ -484,6 +486,7 @@ static ssize_t mac802154dev_write(FAR struct file *filep, { /* This should only happen if the wait was canceled by an signal */ + sem_destroy(&dwait.mw_sem); DEBUGASSERT(errno == EINTR); return -EINTR; } @@ -493,6 +496,7 @@ static ssize_t mac802154dev_write(FAR struct file *filep, * the list in order to perform the sem_post. */ + sem_destroy(&dwait.mw_sem); return dwait.mw_status; } -- GitLab From 0e3438b85409b510669c64ad7452afa2cf08aa97 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 1 May 2017 15:19:14 -0600 Subject: [PATCH 665/990] clicker2-stm32: Add protected build knsh configuration. --- configs/clicker2-stm32/README.txt | 80 ++ configs/clicker2-stm32/knsh/Make.defs | 122 ++ configs/clicker2-stm32/knsh/defconfig | 1332 ++++++++++++++++++ include/nuttx/wireless/ieee80211/ieee80211.h | 1 + 4 files changed, 1535 insertions(+) create mode 100644 configs/clicker2-stm32/knsh/Make.defs create mode 100644 configs/clicker2-stm32/knsh/defconfig diff --git a/configs/clicker2-stm32/README.txt b/configs/clicker2-stm32/README.txt index 810072c99c..bcc2cc93f6 100644 --- a/configs/clicker2-stm32/README.txt +++ b/configs/clicker2-stm32/README.txt @@ -224,6 +224,86 @@ Configurations Configuration sub-directories ----------------------------- + knsh: + + This is identical to the nsh configuration below except that NuttX + is built as a protected mode, monolithic module and the user applications + are built separately. + + It is recommends to use a special make command; not just 'make' but make + with the following two arguments: + + make pass1 pass2 + + In the normal case (just 'make'), make will attempt to build both user- + and kernel-mode blobs more or less interleaved. This actual works! + However, for me it is very confusing so I prefer the above make command: + Make the user-space binaries first (pass1), then make the kernel-space + binaries (pass2) + + NOTES: + + 1. At the end of the build, there will be several files in the top-level + NuttX build directory: + + PASS1: + nuttx_user.elf - The pass1 user-space ELF file + nuttx_user.hex - The pass1 Intel HEX format file (selected in defconfig) + User.map - Symbols in the user-space ELF file + + PASS2: + nuttx - The pass2 kernel-space ELF file + nuttx.hex - The pass2 Intel HEX file (selected in defconfig) + System.map - Symbols in the kernel-space ELF file + + The J-Link programmer will accept files in .hex, .mot, .srec, and .bin + formats. The St-Link programmer will accept files in hex and .bin + formats. + + 2. Combining .hex files. If you plan to use the .hex files with your + debugger or FLASH utility, then you may need to combine the two hex + files into a single .hex file. Here is how you can do that. + + a. The 'tail' of the nuttx.hex file should look something like this + (with my comments added): + + $ tail nuttx.hex + # 00, data records + ... + :10 9DC0 00 01000000000800006400020100001F0004 + :10 9DD0 00 3B005A0078009700B500D400F300110151 + :08 9DE0 00 30014E016D0100008D + # 05, Start Linear Address Record + :04 0000 05 0800 0419 D2 + # 01, End Of File record + :00 0000 01 FF + + Use an editor such as vi to remove the 05 and 01 records. + + b. The 'head' of the nuttx_user.hex file should look something like + this (again with my comments added): + + $ head nuttx_user.hex + # 04, Extended Linear Address Record + :02 0000 04 0801 F1 + # 00, data records + :10 8000 00 BD89 01084C800108C8110208D01102087E + :10 8010 00 0010 00201C1000201C1000203C16002026 + :10 8020 00 4D80 01085D80010869800108ED83010829 + ... + + Nothing needs to be done here. The nuttx_user.hex file should + be fine. + + c. Combine the edited nuttx.hex and un-edited nuttx_user.hex + file to produce a single combined hex file: + + $ cat nuttx.hex nuttx_user.hex >combined.hex + + Then use the combined.hex file with the to write the FLASH image. + If you do this a lot, you will probably want to invest a little time + to develop a tool to automate these steps. + nsh: Configures the NuttShell (nsh) located at examples/nsh. This diff --git a/configs/clicker2-stm32/knsh/Make.defs b/configs/clicker2-stm32/knsh/Make.defs new file mode 100644 index 0000000000..c9139eeba7 --- /dev/null +++ b/configs/clicker2-stm32/knsh/Make.defs @@ -0,0 +1,122 @@ +############################################################################ +# configs/clicker2-stm32/knsh/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. +# +############################################################################ + +include ${TOPDIR}/.config +include ${TOPDIR}/tools/Config.mk +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs + +LDSCRIPT = flash.ld + +ifeq ($(WINTOOL),y) + # Windows-native toolchains + DIRLINK = $(TOPDIR)/tools/copydir.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mkwindeps.sh + ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" + ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" +else + # Linux/Cygwin-native toolchain + MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT) + ARCHINCLUDES = -I. -isystem $(TOPDIR)/include + ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) +endif + +CC = $(CROSSDEV)gcc +CXX = $(CROSSDEV)g++ +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(CROSSDEV)ar rcs +NM = $(CROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump + +ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} +ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} + +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + ARCHOPTIMIZATION = -g +endif + +ifneq ($(CONFIG_DEBUG_NOOPT),y) + ARCHOPTIMIZATION += $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer +endif + +ARCHCFLAGS = -fno-builtin +ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fcheck-new -fno-rtti +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow -Wundef +ARCHWARNINGSXX = -Wall -Wshadow -Wundef +ARCHDEFINES = +ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 + +CFLAGS = $(ARCHCFLAGS) $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) +CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +NXFLATLDFLAGS1 = -r -d -warn-common +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections +LDNXFLATFLAGS = -e main -s 2048 + +# Loadable module definitions + +CMODULEFLAGS = $(CFLAGS) -mlong-calls # --target1-abs + +LDMODULEFLAGS = -r -e module_initialize +ifeq ($(WINTOOL),y) + LDMODULEFLAGS += -T "${shell cygpath -w $(TOPDIR)/libc/modlib/gnu-elf.ld}" +else + LDMODULEFLAGS += -T $(TOPDIR)/libc/modlib/gnu-elf.ld +endif + +ASMEXT = .S +OBJEXT = .o +LIBEXT = .a +EXEEXT = + +ifneq ($(CROSSDEV),arm-nuttx-elf-) + LDFLAGS += -nostartfiles -nodefaultlibs +endif +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + LDFLAGS += -g +endif + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -Wundef -g -pipe +HOSTLDFLAGS = diff --git a/configs/clicker2-stm32/knsh/defconfig b/configs/clicker2-stm32/knsh/defconfig new file mode 100644 index 0000000000..ed981e5a97 --- /dev/null +++ b/configs/clicker2-stm32/knsh/defconfig @@ -0,0 +1,1332 @@ +# +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# + +# +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set +# CONFIG_DEFAULT_SMALL is not set +CONFIG_HOST_LINUX=y +# CONFIG_HOST_OSX is not set +# CONFIG_HOST_WINDOWS is not set +# CONFIG_HOST_OTHER is not set + +# +# Build Configuration +# +# CONFIG_APPS_DIR="../apps" +# CONFIG_BUILD_FLAT is not set +CONFIG_BUILD_PROTECTED=y +CONFIG_BUILD_2PASS=y +CONFIG_PASS1_TARGET="all" +CONFIG_PASS1_BUILDIR="configs/clicker2-stm32/kernel" +CONFIG_PASS1_OBJECT="" +CONFIG_NUTTX_USERSPACE=0x08020000 + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +CONFIG_INTELHEX_BINARY=y +# CONFIG_MOTOROLA_SREC is not set +CONFIG_RAW_BINARY=y +# CONFIG_UBOOT_UIMAGE is not set + +# +# Customize Header Files +# +# CONFIG_ARCH_STDINT_H is not set +# CONFIG_ARCH_STDBOOL_H is not set +# CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_FLOAT_H is not set +# CONFIG_ARCH_STDARG_H is not set +# CONFIG_ARCH_DEBUG_H is not set + +# +# Debug Options +# +CONFIG_DEBUG_ALERT=y +# CONFIG_DEBUG_FEATURES is not set +CONFIG_ARCH_HAVE_STACKCHECK=y +# CONFIG_STACK_COLORATION is not set +CONFIG_ARCH_HAVE_HEAPCHECK=y +# CONFIG_HEAP_COLORATION is not set +# CONFIG_DEBUG_SYMBOLS is not set +CONFIG_ARCH_HAVE_CUSTOMOPT=y +# CONFIG_DEBUG_NOOPT is not set +# CONFIG_DEBUG_CUSTOMOPT is not set +CONFIG_DEBUG_FULLOPT=y + +# +# System Type +# +CONFIG_ARCH_ARM=y +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_MISOC is not set +# CONFIG_ARCH_RENESAS is not set +# CONFIG_ARCH_RISCV is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_XTENSA is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="arm" + +# +# ARM Options +# +# CONFIG_ARCH_CHIP_A1X is not set +# CONFIG_ARCH_CHIP_C5471 is not set +# CONFIG_ARCH_CHIP_DM320 is not set +# CONFIG_ARCH_CHIP_EFM32 is not set +# CONFIG_ARCH_CHIP_IMX1 is not set +# CONFIG_ARCH_CHIP_IMX6 is not set +# CONFIG_ARCH_CHIP_KINETIS is not set +# CONFIG_ARCH_CHIP_KL is not set +# CONFIG_ARCH_CHIP_LM is not set +# CONFIG_ARCH_CHIP_TIVA is not set +# CONFIG_ARCH_CHIP_LPC11XX is not set +# CONFIG_ARCH_CHIP_LPC17XX is not set +# CONFIG_ARCH_CHIP_LPC214X is not set +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_NUC1XX is not set +# CONFIG_ARCH_CHIP_SAMA5 is not set +# CONFIG_ARCH_CHIP_SAMD is not set +# CONFIG_ARCH_CHIP_SAML is not set +# CONFIG_ARCH_CHIP_SAM34 is not set +# CONFIG_ARCH_CHIP_SAMV7 is not set +CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set +# CONFIG_ARCH_CHIP_STM32F7 is not set +# CONFIG_ARCH_CHIP_STM32L4 is not set +# CONFIG_ARCH_CHIP_STR71X is not set +# CONFIG_ARCH_CHIP_TMS570 is not set +# CONFIG_ARCH_CHIP_XMC4 is not set +# CONFIG_ARCH_ARM7TDMI is not set +# CONFIG_ARCH_ARM926EJS is not set +# CONFIG_ARCH_ARM920T is not set +# CONFIG_ARCH_CORTEXM0 is not set +# CONFIG_ARCH_CORTEXM23 is not set +# CONFIG_ARCH_CORTEXM3 is not set +# CONFIG_ARCH_CORTEXM33 is not set +CONFIG_ARCH_CORTEXM4=y +# CONFIG_ARCH_CORTEXM7 is not set +# CONFIG_ARCH_CORTEXA5 is not set +# CONFIG_ARCH_CORTEXA8 is not set +# CONFIG_ARCH_CORTEXA9 is not set +# CONFIG_ARCH_CORTEXR4 is not set +# CONFIG_ARCH_CORTEXR4F is not set +# CONFIG_ARCH_CORTEXR5 is not set +# CONFIG_ARCH_CORTEX5F is not set +# CONFIG_ARCH_CORTEXR7 is not set +# CONFIG_ARCH_CORTEXR7F is not set +CONFIG_ARCH_FAMILY="armv7-m" +CONFIG_ARCH_CHIP="stm32" +# CONFIG_ARM_TOOLCHAIN_IAR is not set +CONFIG_ARM_TOOLCHAIN_GNU=y +# CONFIG_ARMV7M_USEBASEPRI is not set +CONFIG_ARCH_HAVE_CMNVECTOR=y +# CONFIG_ARMV7M_CMNVECTOR is not set +# CONFIG_ARMV7M_LAZYFPU is not set +CONFIG_ARCH_HAVE_FPU=y +# CONFIG_ARCH_HAVE_DPFPU is not set +CONFIG_ARCH_FPU=y +# CONFIG_ARCH_HAVE_TRUSTZONE is not set +CONFIG_ARM_HAVE_MPU_UNIFIED=y +CONFIG_ARM_MPU=y +CONFIG_ARM_MPU_NREGIONS=8 + +# +# ARMV7M Configuration Options +# +# CONFIG_ARMV7M_HAVE_ICACHE is not set +# CONFIG_ARMV7M_HAVE_DCACHE is not set +# CONFIG_ARMV7M_HAVE_ITCM is not set +# CONFIG_ARMV7M_HAVE_DTCM is not set +# CONFIG_ARMV7M_TOOLCHAIN_IARL is not set +# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set +# CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set +# CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL is not set +CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL=y +CONFIG_ARMV7M_HAVE_STACKCHECK=y +# CONFIG_ARMV7M_STACKCHECK is not set +# CONFIG_ARMV7M_ITMSYSLOG is not set +# CONFIG_SERIAL_TERMIOS is not set + +# +# STM32 Configuration Options +# +# CONFIG_ARCH_CHIP_STM32L151C6 is not set +# CONFIG_ARCH_CHIP_STM32L151C8 is not set +# CONFIG_ARCH_CHIP_STM32L151CB is not set +# CONFIG_ARCH_CHIP_STM32L151R6 is not set +# CONFIG_ARCH_CHIP_STM32L151R8 is not set +# CONFIG_ARCH_CHIP_STM32L151RB is not set +# CONFIG_ARCH_CHIP_STM32L151V6 is not set +# CONFIG_ARCH_CHIP_STM32L151V8 is not set +# CONFIG_ARCH_CHIP_STM32L151VB is not set +# CONFIG_ARCH_CHIP_STM32L152C6 is not set +# CONFIG_ARCH_CHIP_STM32L152C8 is not set +# CONFIG_ARCH_CHIP_STM32L152CB is not set +# CONFIG_ARCH_CHIP_STM32L152R6 is not set +# CONFIG_ARCH_CHIP_STM32L152R8 is not set +# CONFIG_ARCH_CHIP_STM32L152RB is not set +# CONFIG_ARCH_CHIP_STM32L152V6 is not set +# CONFIG_ARCH_CHIP_STM32L152V8 is not set +# CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set +# CONFIG_ARCH_CHIP_STM32L162ZD is not set +# CONFIG_ARCH_CHIP_STM32L162VE is not set +# CONFIG_ARCH_CHIP_STM32F100C8 is not set +# CONFIG_ARCH_CHIP_STM32F100CB is not set +# CONFIG_ARCH_CHIP_STM32F100R8 is not set +# CONFIG_ARCH_CHIP_STM32F100RB is not set +# CONFIG_ARCH_CHIP_STM32F100RC is not set +# CONFIG_ARCH_CHIP_STM32F100RD is not set +# CONFIG_ARCH_CHIP_STM32F100RE is not set +# CONFIG_ARCH_CHIP_STM32F100V8 is not set +# CONFIG_ARCH_CHIP_STM32F100VB is not set +# CONFIG_ARCH_CHIP_STM32F100VC is not set +# CONFIG_ARCH_CHIP_STM32F100VD is not set +# CONFIG_ARCH_CHIP_STM32F100VE is not set +# CONFIG_ARCH_CHIP_STM32F102CB is not set +# CONFIG_ARCH_CHIP_STM32F103T8 is not set +# CONFIG_ARCH_CHIP_STM32F103TB is not set +# CONFIG_ARCH_CHIP_STM32F103C4 is not set +# CONFIG_ARCH_CHIP_STM32F103C8 is not set +# CONFIG_ARCH_CHIP_STM32F103CB is not set +# CONFIG_ARCH_CHIP_STM32F103R8 is not set +# CONFIG_ARCH_CHIP_STM32F103RB is not set +# CONFIG_ARCH_CHIP_STM32F103RC is not set +# CONFIG_ARCH_CHIP_STM32F103RD is not set +# CONFIG_ARCH_CHIP_STM32F103RE is not set +# CONFIG_ARCH_CHIP_STM32F103RG is not set +# CONFIG_ARCH_CHIP_STM32F103V8 is not set +# CONFIG_ARCH_CHIP_STM32F103VB is not set +# CONFIG_ARCH_CHIP_STM32F103VC is not set +# CONFIG_ARCH_CHIP_STM32F103VE is not set +# CONFIG_ARCH_CHIP_STM32F103ZE is not set +# CONFIG_ARCH_CHIP_STM32F105VB is not set +# CONFIG_ARCH_CHIP_STM32F105RB is not set +# CONFIG_ARCH_CHIP_STM32F107VC is not set +# CONFIG_ARCH_CHIP_STM32F205RG is not set +# CONFIG_ARCH_CHIP_STM32F207IG is not set +# CONFIG_ARCH_CHIP_STM32F207ZE is not set +# CONFIG_ARCH_CHIP_STM32F302K6 is not set +# CONFIG_ARCH_CHIP_STM32F302K8 is not set +# CONFIG_ARCH_CHIP_STM32F302CB is not set +# CONFIG_ARCH_CHIP_STM32F302CC is not set +# CONFIG_ARCH_CHIP_STM32F302RB is not set +# CONFIG_ARCH_CHIP_STM32F302RC is not set +# CONFIG_ARCH_CHIP_STM32F302VB is not set +# CONFIG_ARCH_CHIP_STM32F302VC is not set +# CONFIG_ARCH_CHIP_STM32F303K6 is not set +# CONFIG_ARCH_CHIP_STM32F303K8 is not set +# CONFIG_ARCH_CHIP_STM32F303C6 is not set +# CONFIG_ARCH_CHIP_STM32F303C8 is not set +# CONFIG_ARCH_CHIP_STM32F303CB is not set +# CONFIG_ARCH_CHIP_STM32F303CC is not set +# CONFIG_ARCH_CHIP_STM32F303RB is not set +# CONFIG_ARCH_CHIP_STM32F303RC is not set +# CONFIG_ARCH_CHIP_STM32F303RD is not set +# CONFIG_ARCH_CHIP_STM32F303RE is not set +# CONFIG_ARCH_CHIP_STM32F303VB is not set +# CONFIG_ARCH_CHIP_STM32F303VC is not set +# CONFIG_ARCH_CHIP_STM32F334K4 is not set +# CONFIG_ARCH_CHIP_STM32F334K6 is not set +# CONFIG_ARCH_CHIP_STM32F334K8 is not set +# CONFIG_ARCH_CHIP_STM32F334C4 is not set +# CONFIG_ARCH_CHIP_STM32F334C6 is not set +# CONFIG_ARCH_CHIP_STM32F334C8 is not set +# CONFIG_ARCH_CHIP_STM32F334R4 is not set +# CONFIG_ARCH_CHIP_STM32F334R6 is not set +# CONFIG_ARCH_CHIP_STM32F334R8 is not set +# CONFIG_ARCH_CHIP_STM32F372C8 is not set +# CONFIG_ARCH_CHIP_STM32F372R8 is not set +# CONFIG_ARCH_CHIP_STM32F372V8 is not set +# CONFIG_ARCH_CHIP_STM32F372CB is not set +# CONFIG_ARCH_CHIP_STM32F372RB is not set +# CONFIG_ARCH_CHIP_STM32F372VB is not set +# CONFIG_ARCH_CHIP_STM32F372CC is not set +# CONFIG_ARCH_CHIP_STM32F372RC is not set +# CONFIG_ARCH_CHIP_STM32F372VC is not set +# CONFIG_ARCH_CHIP_STM32F373C8 is not set +# CONFIG_ARCH_CHIP_STM32F373R8 is not set +# CONFIG_ARCH_CHIP_STM32F373V8 is not set +# CONFIG_ARCH_CHIP_STM32F373CB is not set +# CONFIG_ARCH_CHIP_STM32F373RB is not set +# CONFIG_ARCH_CHIP_STM32F373VB is not set +# CONFIG_ARCH_CHIP_STM32F373CC is not set +# CONFIG_ARCH_CHIP_STM32F373RC is not set +# CONFIG_ARCH_CHIP_STM32F373VC is not set +# CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F411RE is not set +# CONFIG_ARCH_CHIP_STM32F411VE is not set +# CONFIG_ARCH_CHIP_STM32F405RG is not set +# CONFIG_ARCH_CHIP_STM32F405VG is not set +# CONFIG_ARCH_CHIP_STM32F405ZG is not set +# CONFIG_ARCH_CHIP_STM32F407VE is not set +CONFIG_ARCH_CHIP_STM32F407VG=y +# CONFIG_ARCH_CHIP_STM32F407ZE is not set +# CONFIG_ARCH_CHIP_STM32F407ZG is not set +# CONFIG_ARCH_CHIP_STM32F407IE is not set +# CONFIG_ARCH_CHIP_STM32F407IG is not set +# CONFIG_ARCH_CHIP_STM32F427V is not set +# CONFIG_ARCH_CHIP_STM32F427Z is not set +# CONFIG_ARCH_CHIP_STM32F427I is not set +# CONFIG_ARCH_CHIP_STM32F429V is not set +# CONFIG_ARCH_CHIP_STM32F429Z is not set +# CONFIG_ARCH_CHIP_STM32F429I is not set +# CONFIG_ARCH_CHIP_STM32F429B is not set +# CONFIG_ARCH_CHIP_STM32F429N is not set +# CONFIG_ARCH_CHIP_STM32F446M is not set +# CONFIG_ARCH_CHIP_STM32F446R is not set +# CONFIG_ARCH_CHIP_STM32F446V is not set +# CONFIG_ARCH_CHIP_STM32F446Z is not set +# CONFIG_ARCH_CHIP_STM32F469A is not set +# CONFIG_ARCH_CHIP_STM32F469I is not set +# CONFIG_ARCH_CHIP_STM32F469B is not set +# CONFIG_ARCH_CHIP_STM32F469N is not set +CONFIG_STM32_FLASH_CONFIG_DEFAULT=y +# CONFIG_STM32_FLASH_CONFIG_4 is not set +# CONFIG_STM32_FLASH_CONFIG_6 is not set +# CONFIG_STM32_FLASH_CONFIG_8 is not set +# CONFIG_STM32_FLASH_CONFIG_B is not set +# CONFIG_STM32_FLASH_CONFIG_C is not set +# CONFIG_STM32_FLASH_CONFIG_D is not set +# CONFIG_STM32_FLASH_CONFIG_E is not set +# CONFIG_STM32_FLASH_CONFIG_F is not set +# CONFIG_STM32_FLASH_CONFIG_G is not set +# CONFIG_STM32_FLASH_CONFIG_I is not set +# CONFIG_STM32_STM32L15XX is not set +# CONFIG_STM32_ENERGYLITE is not set +# CONFIG_STM32_STM32F10XX is not set +# CONFIG_STM32_VALUELINE is not set +# CONFIG_STM32_CONNECTIVITYLINE is not set +# CONFIG_STM32_PERFORMANCELINE is not set +# CONFIG_STM32_USBACCESSLINE is not set +# CONFIG_STM32_HIGHDENSITY is not set +# CONFIG_STM32_MEDIUMDENSITY is not set +# CONFIG_STM32_LOWDENSITY is not set +# CONFIG_STM32_STM32F20XX is not set +# CONFIG_STM32_STM32F205 is not set +# CONFIG_STM32_STM32F207 is not set +# CONFIG_STM32_STM32F30XX is not set +# CONFIG_STM32_STM32F302 is not set +# CONFIG_STM32_STM32F303 is not set +# CONFIG_STM32_STM32F33XX is not set +# CONFIG_STM32_STM32F37XX is not set +CONFIG_STM32_STM32F40XX=y +# CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F411 is not set +# CONFIG_STM32_STM32F405 is not set +CONFIG_STM32_STM32F407=y +# CONFIG_STM32_STM32F427 is not set +# CONFIG_STM32_STM32F429 is not set +# CONFIG_STM32_STM32F446 is not set +# CONFIG_STM32_STM32F469 is not set +# CONFIG_STM32_DFU is not set + +# +# STM32 Peripheral Support +# +CONFIG_STM32_HAVE_CCM=y +# CONFIG_STM32_HAVE_USBDEV is not set +CONFIG_STM32_HAVE_OTGFS=y +CONFIG_STM32_HAVE_FSMC=y +# CONFIG_STM32_HAVE_HRTIM1 is not set +# CONFIG_STM32_HAVE_LTDC is not set +CONFIG_STM32_HAVE_USART3=y +CONFIG_STM32_HAVE_UART4=y +CONFIG_STM32_HAVE_UART5=y +CONFIG_STM32_HAVE_USART6=y +# CONFIG_STM32_HAVE_UART7 is not set +# CONFIG_STM32_HAVE_UART8 is not set +CONFIG_STM32_HAVE_TIM1=y +CONFIG_STM32_HAVE_TIM2=y +CONFIG_STM32_HAVE_TIM3=y +CONFIG_STM32_HAVE_TIM4=y +CONFIG_STM32_HAVE_TIM5=y +CONFIG_STM32_HAVE_TIM6=y +CONFIG_STM32_HAVE_TIM7=y +CONFIG_STM32_HAVE_TIM8=y +CONFIG_STM32_HAVE_TIM9=y +CONFIG_STM32_HAVE_TIM10=y +CONFIG_STM32_HAVE_TIM11=y +CONFIG_STM32_HAVE_TIM12=y +CONFIG_STM32_HAVE_TIM13=y +CONFIG_STM32_HAVE_TIM14=y +# CONFIG_STM32_HAVE_TIM15 is not set +# CONFIG_STM32_HAVE_TIM16 is not set +# CONFIG_STM32_HAVE_TIM17 is not set +CONFIG_STM32_HAVE_ADC2=y +CONFIG_STM32_HAVE_ADC3=y +# CONFIG_STM32_HAVE_ADC4 is not set +# CONFIG_STM32_HAVE_ADC1_DMA is not set +# CONFIG_STM32_HAVE_ADC2_DMA is not set +# CONFIG_STM32_HAVE_ADC3_DMA is not set +# CONFIG_STM32_HAVE_ADC4_DMA is not set +# CONFIG_STM32_HAVE_SDADC1 is not set +# CONFIG_STM32_HAVE_SDADC2 is not set +# CONFIG_STM32_HAVE_SDADC3 is not set +# CONFIG_STM32_HAVE_SDADC1_DMA is not set +# CONFIG_STM32_HAVE_SDADC2_DMA is not set +# CONFIG_STM32_HAVE_SDADC3_DMA is not set +CONFIG_STM32_HAVE_CAN1=y +CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set +# CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set +# CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set +# CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set +CONFIG_STM32_HAVE_DAC1=y +CONFIG_STM32_HAVE_DAC2=y +CONFIG_STM32_HAVE_RNG=y +CONFIG_STM32_HAVE_ETHMAC=y +CONFIG_STM32_HAVE_I2C2=y +CONFIG_STM32_HAVE_I2C3=y +CONFIG_STM32_HAVE_SPI2=y +CONFIG_STM32_HAVE_SPI3=y +# CONFIG_STM32_HAVE_SPI4 is not set +# CONFIG_STM32_HAVE_SPI5 is not set +# CONFIG_STM32_HAVE_SPI6 is not set +# CONFIG_STM32_HAVE_SAIPLL is not set +# CONFIG_STM32_HAVE_I2SPLL is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set +# CONFIG_STM32_ADC1 is not set +# CONFIG_STM32_ADC2 is not set +# CONFIG_STM32_ADC3 is not set +# CONFIG_STM32_BKPSRAM is not set +# CONFIG_STM32_CAN1 is not set +# CONFIG_STM32_CAN2 is not set +# CONFIG_STM32_CCMDATARAM is not set +# CONFIG_STM32_CRC is not set +# CONFIG_STM32_CRYP is not set +# CONFIG_STM32_DMA1 is not set +# CONFIG_STM32_DMA2 is not set +# CONFIG_STM32_DAC1 is not set +# CONFIG_STM32_DAC2 is not set +# CONFIG_STM32_DCMI is not set +# CONFIG_STM32_ETHMAC is not set +# CONFIG_STM32_FSMC is not set +# CONFIG_STM32_HASH is not set +# CONFIG_STM32_I2C1 is not set +# CONFIG_STM32_I2C2 is not set +# CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set +# CONFIG_STM32_OTGFS is not set +# CONFIG_STM32_OTGHS is not set +CONFIG_STM32_PWR=y +# CONFIG_STM32_RNG is not set +# CONFIG_STM32_SDIO is not set +# CONFIG_STM32_SPI1 is not set +# CONFIG_STM32_SPI2 is not set +# CONFIG_STM32_SPI3 is not set +CONFIG_STM32_SYSCFG=y +# CONFIG_STM32_TIM1 is not set +# CONFIG_STM32_TIM2 is not set +# CONFIG_STM32_TIM3 is not set +# CONFIG_STM32_TIM4 is not set +# CONFIG_STM32_TIM5 is not set +# CONFIG_STM32_TIM6 is not set +# CONFIG_STM32_TIM7 is not set +# CONFIG_STM32_TIM8 is not set +# CONFIG_STM32_TIM9 is not set +# CONFIG_STM32_TIM10 is not set +# CONFIG_STM32_TIM11 is not set +# CONFIG_STM32_TIM12 is not set +# CONFIG_STM32_TIM13 is not set +# CONFIG_STM32_TIM14 is not set +# CONFIG_STM32_USART1 is not set +# CONFIG_STM32_USART2 is not set +CONFIG_STM32_USART3=y +# CONFIG_STM32_UART4 is not set +# CONFIG_STM32_UART5 is not set +# CONFIG_STM32_USART6 is not set +# CONFIG_STM32_IWDG is not set +# CONFIG_STM32_WWDG is not set +# CONFIG_STM32_NOEXT_VECTORS is not set + +# +# Alternate Pin Mapping +# +# CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set +# CONFIG_STM32_JTAG_DISABLE is not set +# CONFIG_STM32_JTAG_FULL_ENABLE is not set +# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y +# CONFIG_STM32_FORCEPOWER is not set +# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set +CONFIG_STM32_CCMEXCLUDE=y + +# +# Timer Configuration +# +# CONFIG_STM32_ONESHOT is not set +# CONFIG_STM32_FREERUN is not set +# CONFIG_STM32_TIM1_CAP is not set +# CONFIG_STM32_TIM2_CAP is not set +# CONFIG_STM32_TIM3_CAP is not set +# CONFIG_STM32_TIM4_CAP is not set +# CONFIG_STM32_TIM5_CAP is not set +# CONFIG_STM32_TIM8_CAP is not set +# CONFIG_STM32_TIM9_CAP is not set +# CONFIG_STM32_TIM10_CAP is not set +# CONFIG_STM32_TIM11_CAP is not set +# CONFIG_STM32_TIM12_CAP is not set +# CONFIG_STM32_TIM13_CAP is not set +# CONFIG_STM32_TIM14_CAP is not set +CONFIG_STM32_USART=y +CONFIG_STM32_SERIALDRIVER=y + +# +# U[S]ART Configuration +# + +# +# U[S]ART Device Configuration +# +CONFIG_STM32_USART3_SERIALDRIVER=y +# CONFIG_STM32_USART3_1WIREDRIVER is not set +# CONFIG_USART3_RS485 is not set + +# +# Serial Driver Configuration +# +# CONFIG_SERIAL_DISABLE_REORDERING is not set +# CONFIG_STM32_FLOWCONTROL_BROKEN is not set +# CONFIG_STM32_USART_BREAKS is not set +# CONFIG_STM32_USART_SINGLEWIRE is not set +# CONFIG_STM32_HAVE_RTC_COUNTER is not set +# CONFIG_STM32_HAVE_RTC_SUBSECONDS is not set + +# +# USB FS Host Configuration +# + +# +# USB HS Host Configuration +# + +# +# USB Host Debug Configuration +# + +# +# USB Device Configuration +# + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_VECNOTIRQ is not set +# CONFIG_ARCH_DMA is not set +CONFIG_ARCH_HAVE_IRQPRIO=y +# CONFIG_ARCH_L2CACHE is not set +# CONFIG_ARCH_HAVE_COHERENT_DCACHE is not set +# CONFIG_ARCH_HAVE_ADDRENV is not set +# CONFIG_ARCH_NEED_ADDRENV_MAPPING is not set +# CONFIG_ARCH_HAVE_MULTICPU is not set +CONFIG_ARCH_HAVE_VFORK=y +# CONFIG_ARCH_HAVE_MMU is not set +CONFIG_ARCH_HAVE_MPU=y +# CONFIG_ARCH_NAND_HWECC is not set +# CONFIG_ARCH_HAVE_EXTCLK is not set +# CONFIG_ARCH_HAVE_POWEROFF is not set +CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set +CONFIG_ARCH_USE_MPU=y +# CONFIG_ARCH_IRQPRIO is not set +CONFIG_ARCH_STACKDUMP=y +# CONFIG_ENDIAN_BIG is not set +# CONFIG_ARCH_IDLE_CUSTOM is not set +# CONFIG_ARCH_HAVE_RAMFUNCS is not set +CONFIG_ARCH_HAVE_RAMVECTORS=y +# CONFIG_ARCH_RAMVECTORS is not set +# CONFIG_ARCH_MINIMAL_VECTORTABLE is not set + +# +# Board Settings +# +CONFIG_BOARD_LOOPSPERMSEC=16717 +# CONFIG_ARCH_CALIBRATION is not set + +# +# Interrupt options +# +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y +CONFIG_ARCH_INTERRUPTSTACK=0 +CONFIG_ARCH_HAVE_HIPRI_INTERRUPT=y +# CONFIG_ARCH_HIPRI_INTERRUPT is not set + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Boot Memory Configuration +# +CONFIG_RAM_START=0x20000000 +CONFIG_RAM_SIZE=131072 +# CONFIG_ARCH_HAVE_SDRAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_CLICKER2_STM32=y +# CONFIG_ARCH_BOARD_STM32F4_DISCOVERY is not set +# CONFIG_ARCH_BOARD_MIKROE_STM32F4 is not set +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="clicker2-stm32" + +# +# Common Board Options +# +CONFIG_ARCH_HAVE_LEDS=y +CONFIG_ARCH_LEDS=y +CONFIG_ARCH_HAVE_BUTTONS=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_HAVE_IRQBUTTONS=y +CONFIG_ARCH_IRQBUTTONS=y + +# +# Board-Specific Options +# +# CONFIG_CLICKER2_STM32_MB1_SPI is not set +# CONFIG_CLICKER2_STM32_MB2_SPI is not set +# CONFIG_BOARD_CRASHDUMP is not set +CONFIG_LIB_BOARDCTL=y +# CONFIG_BOARDCTL_RESET is not set +# CONFIG_BOARDCTL_UNIQUEID is not set +# CONFIG_BOARDCTL_TSCTEST is not set +# CONFIG_BOARDCTL_GRAPHICS is not set +# CONFIG_BOARDCTL_IOCTL is not set + +# +# RTOS Features +# +CONFIG_DISABLE_OS_API=y +# CONFIG_DISABLE_POSIX_TIMERS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_DISABLE_SIGNALS is not set +# CONFIG_DISABLE_MQUEUE is not set +# CONFIG_DISABLE_ENVIRON is not set + +# +# Clocks and Timers +# +CONFIG_ARCH_HAVE_TICKLESS=y +# CONFIG_SCHED_TICKLESS is not set +CONFIG_USEC_PER_TICK=10000 +# CONFIG_SYSTEM_TIME64 is not set +# CONFIG_CLOCK_MONOTONIC is not set +CONFIG_ARCH_HAVE_TIMEKEEPING=y +# CONFIG_JULIAN_TIME is not set +CONFIG_START_YEAR=2017 +CONFIG_START_MONTH=3 +CONFIG_START_DAY=25 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=8 +CONFIG_WDOG_INTRESERVE=1 +CONFIG_PREALLOC_TIMERS=4 + +# +# Tasks and Scheduling +# +# CONFIG_SPINLOCK is not set +# CONFIG_INIT_NONE is not set +CONFIG_INIT_ENTRYPOINT=y +# CONFIG_INIT_FILEPATH is not set +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_RR_INTERVAL=200 +# CONFIG_SCHED_SPORADIC is not set +CONFIG_TASK_NAME_SIZE=32 +CONFIG_MAX_TASKS=16 +# CONFIG_SCHED_HAVE_PARENT is not set +CONFIG_SCHED_WAITPID=y + +# +# Pthread Options +# +# CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set +CONFIG_NPTHREAD_KEYS=4 +# CONFIG_PTHREAD_CLEANUP is not set +# CONFIG_CANCELLATION_POINTS is not set + +# +# Performance Monitoring +# +# CONFIG_SCHED_CPULOAD is not set +# CONFIG_SCHED_INSTRUMENTATION is not set + +# +# Files and I/O +# +CONFIG_DEV_CONSOLE=y +# CONFIG_FDCLONE_DISABLE is not set +# CONFIG_FDCLONE_STDIO is not set +CONFIG_SDCLONE_DISABLE=y +CONFIG_NFILE_DESCRIPTORS=8 +CONFIG_NFILE_STREAMS=8 +CONFIG_NAME_MAX=32 +# CONFIG_PRIORITY_INHERITANCE is not set + +# +# RTOS hooks +# +CONFIG_BOARD_INITIALIZE=y +# CONFIG_BOARD_INITTHREAD is not set +# CONFIG_SCHED_STARTHOOK is not set +# CONFIG_SCHED_ATEXIT is not set +# CONFIG_SCHED_ONEXIT is not set + +# +# Signal Numbers +# +CONFIG_SIG_SIGUSR1=1 +CONFIG_SIG_SIGUSR2=2 +CONFIG_SIG_SIGALARM=3 +CONFIG_SIG_SIGCONDTIMEDOUT=16 +CONFIG_SIG_SIGWORK=17 + +# +# POSIX Message Queue Options +# +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_MQ_MAXMSGSIZE=32 +# CONFIG_MODULE is not set + +# +# Work queue support +# +CONFIG_SCHED_WORKQUEUE=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=192 +CONFIG_SCHED_HPWORKPERIOD=50000 +CONFIG_SCHED_HPWORKSTACKSIZE=2048 +# CONFIG_SCHED_LPWORK is not set + +# +# Stack and heap information +# +CONFIG_IDLETHREAD_STACKSIZE=1024 +CONFIG_USERMAIN_STACKSIZE=2048 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=2048 +CONFIG_LIB_SYSCALL=y +CONFIG_SYS_RESERVED=8 +CONFIG_SYS_NNEST=2 + +# +# Device Drivers +# +CONFIG_DISABLE_POLL=y +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_DEV_URANDOM is not set +# CONFIG_DEV_LOOP is not set + +# +# Buffering +# + +# +# Common I/O Buffer Support +# +# CONFIG_DRIVERS_IOB is not set +# CONFIG_DRVR_WRITEBUFFER is not set +# CONFIG_DRVR_READAHEAD is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_ARCH_HAVE_PWM_PULSECOUNT is not set +# CONFIG_ARCH_HAVE_PWM_MULTICHAN is not set +# CONFIG_PWM is not set +CONFIG_ARCH_HAVE_I2CRESET=y +# CONFIG_I2C is not set +# CONFIG_ARCH_HAVE_SPI_CRCGENERATION is not set +# CONFIG_ARCH_HAVE_SPI_CS_CONTROL is not set +CONFIG_ARCH_HAVE_SPI_BITORDER=y +# CONFIG_SPI is not set +# CONFIG_I2S is not set + +# +# Timer Driver Support +# +# CONFIG_TIMER is not set +# CONFIG_ONESHOT is not set +# CONFIG_RTC is not set +# CONFIG_WATCHDOG is not set +# CONFIG_ANALOG is not set +# CONFIG_AUDIO_DEVICES is not set +# CONFIG_VIDEO_DEVICES is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set + +# +# IO Expander/GPIO Support +# +# CONFIG_IOEXPANDER is not set +# CONFIG_DEV_GPIO is not set + +# +# LCD Driver Support +# +# CONFIG_LCD is not set +# CONFIG_SLCD is not set + +# +# LED Support +# +# CONFIG_USERLED is not set +# CONFIG_RGBLED is not set +# CONFIG_PCA9635PW is not set +# CONFIG_NCP5623C is not set +# CONFIG_MMCSD is not set +# CONFIG_MODEM is not set +# CONFIG_MTD is not set +# CONFIG_EEPROM is not set +# CONFIG_PIPES is not set +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +CONFIG_SERIAL=y +# CONFIG_DEV_LOWCONSOLE is not set +# CONFIG_SERIAL_REMOVABLE is not set +CONFIG_SERIAL_CONSOLE=y +# CONFIG_16550_UART is not set +# CONFIG_UART_SERIALDRIVER is not set +# CONFIG_UART0_SERIALDRIVER is not set +# CONFIG_UART1_SERIALDRIVER is not set +# CONFIG_UART2_SERIALDRIVER is not set +# CONFIG_UART3_SERIALDRIVER is not set +# CONFIG_UART4_SERIALDRIVER is not set +# CONFIG_UART5_SERIALDRIVER is not set +# CONFIG_UART6_SERIALDRIVER is not set +# CONFIG_UART7_SERIALDRIVER is not set +# CONFIG_UART8_SERIALDRIVER is not set +# CONFIG_SCI0_SERIALDRIVER is not set +# CONFIG_SCI1_SERIALDRIVER is not set +# CONFIG_USART0_SERIALDRIVER is not set +# CONFIG_USART1_SERIALDRIVER is not set +# CONFIG_USART2_SERIALDRIVER is not set +CONFIG_USART3_SERIALDRIVER=y +# CONFIG_USART4_SERIALDRIVER is not set +# CONFIG_USART5_SERIALDRIVER is not set +# CONFIG_USART6_SERIALDRIVER is not set +# CONFIG_USART7_SERIALDRIVER is not set +# CONFIG_USART8_SERIALDRIVER is not set +# CONFIG_OTHER_UART_SERIALDRIVER is not set +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +# CONFIG_SERIAL_IFLOWCONTROL is not set +# CONFIG_SERIAL_OFLOWCONTROL is not set +# CONFIG_SERIAL_DMA is not set +CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y +CONFIG_USART3_SERIAL_CONSOLE=y +# CONFIG_OTHER_SERIAL_CONSOLE is not set +# CONFIG_NO_SERIAL_CONSOLE is not set + +# +# USART3 Configuration +# +CONFIG_USART3_RXBUFSIZE=256 +CONFIG_USART3_TXBUFSIZE=256 +CONFIG_USART3_BAUD=115200 +CONFIG_USART3_BITS=8 +CONFIG_USART3_PARITY=0 +CONFIG_USART3_2STOP=0 +# CONFIG_USART3_IFLOWCONTROL is not set +# CONFIG_USART3_OFLOWCONTROL is not set +# CONFIG_USART3_DMA is not set +# CONFIG_PSEUDOTERM is not set +# CONFIG_USBDEV is not set +# CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set +# CONFIG_HAVE_USBTRACE is not set +# CONFIG_DRIVERS_WIRELESS is not set +# CONFIG_DRIVERS_CONTACTLESS is not set + +# +# System Logging +# +# CONFIG_ARCH_SYSLOG is not set +# CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_INTBUFFER is not set +# CONFIG_SYSLOG_TIMESTAMP is not set +CONFIG_SYSLOG_SERIAL_CONSOLE=y +# CONFIG_SYSLOG_CHAR is not set +CONFIG_SYSLOG_CONSOLE=y +# CONFIG_SYSLOG_NONE is not set +# CONFIG_SYSLOG_FILE is not set +# CONFIG_SYSLOG_CHARDEV is not set + +# +# Networking Support +# +# CONFIG_ARCH_HAVE_NET is not set +# CONFIG_ARCH_HAVE_PHY is not set +# CONFIG_NET is not set + +# +# Crypto API +# +# CONFIG_CRYPTO is not set + +# +# File Systems +# + +# +# File system configuration +# +# CONFIG_DISABLE_MOUNTPOINT is not set +# CONFIG_FS_AUTOMOUNTER is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_PSEUDOFS_SOFTLINKS is not set +CONFIG_FS_READABLE=y +CONFIG_FS_WRITABLE=y +# CONFIG_FS_NAMED_SEMAPHORES is not set +CONFIG_FS_MQUEUE_MPATH="/var/mqueue" +# CONFIG_FS_RAMMAP is not set +# CONFIG_FS_FAT is not set +# CONFIG_FS_NXFFS is not set +# CONFIG_FS_ROMFS is not set +# CONFIG_FS_TMPFS is not set +# CONFIG_FS_SMARTFS is not set +CONFIG_FS_PROCFS=y +# CONFIG_FS_PROCFS_REGISTER is not set + +# +# Exclude individual procfs entries +# +# CONFIG_FS_PROCFS_EXCLUDE_PROCESS is not set +# CONFIG_FS_PROCFS_EXCLUDE_UPTIME is not set +# CONFIG_FS_PROCFS_EXCLUDE_KMM is not set +# CONFIG_FS_PROCFS_EXCLUDE_MOUNTS is not set +# CONFIG_FS_UNIONFS is not set + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +CONFIG_MM_KERNEL_HEAP=y +CONFIG_MM_KERNEL_HEAPSIZE=8192 +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=1 +# CONFIG_ARCH_HAVE_HEAP2 is not set +# CONFIG_GRAN is not set + +# +# Audio Support +# +# CONFIG_AUDIO is not set + +# +# Wireless Support +# + +# +# Binary Loader +# +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_BINFMT_EXEPATH is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +# CONFIG_PIC is not set +# CONFIG_SYMTAB_ORDEREDBYNAME is not set + +# +# Library Routines +# + +# +# Standard C Library Options +# + +# +# Standard C I/O +# +# CONFIG_STDIO_DISABLE_BUFFERING is not set +CONFIG_STDIO_BUFFER_SIZE=64 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +# CONFIG_NOPRINTF_FIELDWIDTH is not set +# CONFIG_LIBC_FLOATINGPOINT is not set +CONFIG_LIBC_LONG_LONG=y +# CONFIG_LIBC_SCANSET is not set +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_MEMCPY_VIK is not set +# CONFIG_LIBM is not set + +# +# Architecture-Specific Support +# +CONFIG_ARCH_LOWPUTC=y +# CONFIG_ARCH_ROMGETC is not set +# CONFIG_LIBC_ARCH_MEMCPY is not set +# CONFIG_LIBC_ARCH_MEMCMP is not set +# CONFIG_LIBC_ARCH_MEMMOVE is not set +# CONFIG_LIBC_ARCH_MEMSET is not set +# CONFIG_LIBC_ARCH_STRCHR is not set +# CONFIG_LIBC_ARCH_STRCMP is not set +# CONFIG_LIBC_ARCH_STRCPY is not set +# CONFIG_LIBC_ARCH_STRNCPY is not set +# CONFIG_LIBC_ARCH_STRLEN is not set +# CONFIG_LIBC_ARCH_STRNLEN is not set +# CONFIG_LIBC_ARCH_ELF is not set +# CONFIG_ARMV7M_MEMCPY is not set + +# +# stdlib Options +# +CONFIG_LIB_RAND_ORDER=1 +CONFIG_LIB_HOMEDIR="/" +CONFIG_LIBC_TMPDIR="/tmp" +CONFIG_LIBC_MAX_TMPFILE=32 + +# +# Program Execution Options +# +# CONFIG_LIBC_EXECFUNCS is not set +CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024 +CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=2048 + +# +# errno Decode Support +# +# CONFIG_LIBC_STRERROR is not set +# CONFIG_LIBC_PERROR_STDOUT is not set + +# +# memcpy/memset Options +# +# CONFIG_MEMSET_OPTSPEED is not set +# CONFIG_LIBC_DLLFCN is not set +# CONFIG_LIBC_MODLIB is not set +# CONFIG_LIBC_WCHAR is not set +# CONFIG_LIBC_LOCALE is not set + +# +# Time/Time Zone Support +# +# CONFIG_LIBC_LOCALTIME is not set +# CONFIG_TIME_EXTENDED is not set +CONFIG_ARCH_HAVE_TLS=y + +# +# Thread Local Storage (TLS) +# +# CONFIG_TLS is not set + +# +# Network-Related Options +# +# CONFIG_LIBC_IPv4_ADDRCONV is not set +# CONFIG_LIBC_IPv6_ADDRCONV is not set +# CONFIG_LIBC_NETDB is not set + +# +# NETDB Support +# +# CONFIG_NETDB_HOSTFILE is not set +# CONFIG_LIBC_IOCTL_VARIADIC is not set +CONFIG_LIB_SENDFILE_BUFSIZE=512 + +# +# Non-standard Library Support +# +# CONFIG_LIB_CRC64_FAST is not set +# CONFIG_LIB_KBDCODEC is not set +# CONFIG_LIB_SLCDCODEC is not set + +# +# User Work Queue Support +# +# CONFIG_LIB_USRWORK is not set +# CONFIG_LIB_HEX2BIN is not set + +# +# Basic CXX Support +# +# CONFIG_C99_BOOL8 is not set +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +# CONFIG_CXX_NEWLONG is not set + +# +# LLVM C++ Library (libcxx) +# +# CONFIG_LIBCXX is not set + +# +# uClibc++ Standard C++ Library +# +# CONFIG_UCLIBCXX is not set + +# +# Application Configuration +# + +# +# CAN Utilities +# + +# +# Examples +# +# CONFIG_EXAMPLES_BUTTONS is not set +# CONFIG_EXAMPLES_CCTYPE is not set +# CONFIG_EXAMPLES_CHAT is not set +# CONFIG_EXAMPLES_CONFIGDATA is not set +# CONFIG_EXAMPLES_CXXTEST is not set +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FSTEST is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HELLOXX is not set +# CONFIG_EXAMPLES_HIDKBD is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_JSON is not set +# CONFIG_EXAMPLES_KEYPADTEST is not set +# CONFIG_EXAMPLES_MEDIA is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MODBUS is not set +# CONFIG_EXAMPLES_MOUNT is not set +CONFIG_EXAMPLES_NSH=y +CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NXLINES is not set +# CONFIG_EXAMPLES_NXTERM is not set +# CONFIG_EXAMPLES_NXTEXT is not set +# CONFIG_EXAMPLES_OSTEST is not set +# CONFIG_EXAMPLES_PCA9635 is not set +# CONFIG_EXAMPLES_POSIXSPAWN is not set +# CONFIG_EXAMPLES_PPPD is not set +# CONFIG_EXAMPLES_RFID_READUID is not set +# CONFIG_EXAMPLES_RGBLED is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERIALBLASTER is not set +# CONFIG_EXAMPLES_SERIALRX is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_SLCD is not set +# CONFIG_EXAMPLES_SMART is not set +# CONFIG_EXAMPLES_SMP is not set +# CONFIG_EXAMPLES_STAT is not set +# CONFIG_EXAMPLES_TCPECHO is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_USBSERIAL is not set +# CONFIG_EXAMPLES_WATCHDOG is not set +# CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set + +# +# File System Utilities +# +# CONFIG_FSUTILS_INIFILE is not set +# CONFIG_FSUTILS_PASSWD is not set + +# +# GPS Utilities +# +# CONFIG_GPSUTILS_MINMEA_LIB is not set + +# +# Graphics Support +# +# CONFIG_TIFF is not set +# CONFIG_GRAPHICS_TRAVELER is not set + +# +# Interpreters +# +# CONFIG_INTERPRETERS_BAS is not set +# CONFIG_INTERPRETERS_FICL is not set +# CONFIG_INTERPRETERS_MICROPYTHON is not set +# CONFIG_INTERPRETERS_MINIBASIC is not set +# CONFIG_INTERPRETERS_PCODE is not set + +# +# FreeModBus +# +# CONFIG_MODBUS is not set + +# +# Network Utilities +# +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_ESP8266 is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_JSON is not set +# CONFIG_NETUTILS_SMTP is not set + +# +# NSH Library +# +CONFIG_NSH_LIBRARY=y +# CONFIG_NSH_MOTD is not set + +# +# Command Line Configuration +# +CONFIG_NSH_READLINE=y +# CONFIG_NSH_CLE is not set +CONFIG_NSH_LINELEN=64 +# CONFIG_NSH_DISABLE_SEMICOLON is not set +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_MAXARGUMENTS=6 +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_NESTDEPTH=3 +# CONFIG_NSH_DISABLEBG is not set + +# +# Disable Individual commands +# +# CONFIG_NSH_DISABLE_ADDROUTE is not set +# CONFIG_NSH_DISABLE_BASENAME is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_CMP is not set +CONFIG_NSH_DISABLE_DATE=y +CONFIG_NSH_DISABLE_DD=y +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_DELROUTE is not set +# CONFIG_NSH_DISABLE_DIRNAME is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_FREE is not set +CONFIG_NSH_DISABLE_GET=y +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_HEXDUMP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +CONFIG_NSH_DISABLE_IFUPDOWN=y +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOSETUP is not set +CONFIG_NSH_DISABLE_LOSMART=y +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MB is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +CONFIG_NSH_DISABLE_MKRD=y +# CONFIG_NSH_DISABLE_MH is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_MW is not set +CONFIG_NSH_DISABLE_PRINTF=y +# CONFIG_NSH_DISABLE_PS is not set +CONFIG_NSH_DISABLE_PUT=y +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SH is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNAME is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_NSH_DISABLE_WGET=y +# CONFIG_NSH_DISABLE_XD is not set +CONFIG_NSH_MMCSDMINOR=0 + +# +# Configure Command Options +# +# CONFIG_NSH_CMDOPT_DF_H is not set +CONFIG_NSH_CODECS_BUFSIZE=128 +CONFIG_NSH_CMDOPT_HEXDUMP=y +CONFIG_NSH_PROC_MOUNTPOINT="/proc" +CONFIG_NSH_FILEIOSIZE=512 + +# +# Scripting Support +# +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_LOOPS is not set + +# +# Console Configuration +# +CONFIG_NSH_CONSOLE=y +# CONFIG_NSH_ALTCONDEV is not set +# CONFIG_NSH_ARCHINIT is not set +# CONFIG_NSH_LOGIN is not set +# CONFIG_NSH_CONSOLE_LOGIN is not set + +# +# NxWidgets/NxWM +# + +# +# Platform-specific Support +# +# CONFIG_PLATFORM_CONFIGDATA is not set + +# +# System Libraries and NSH Add-Ons +# +# CONFIG_SYSTEM_CLE is not set +# CONFIG_SYSTEM_CUTERM is not set +# CONFIG_SYSTEM_FREE is not set +# CONFIG_SYSTEM_HEX2BIN is not set +# CONFIG_SYSTEM_HEXED is not set +# CONFIG_SYSTEM_INSTALL is not set +# CONFIG_SYSTEM_RAMTEST is not set +CONFIG_READLINE_HAVE_EXTMATCH=y +CONFIG_SYSTEM_READLINE=y +CONFIG_READLINE_ECHO=y +# CONFIG_READLINE_TABCOMPLETION is not set +# CONFIG_READLINE_CMD_HISTORY is not set +# CONFIG_SYSTEM_SUDOKU is not set +# CONFIG_SYSTEM_SYSTEM is not set +# CONFIG_SYSTEM_TEE is not set +# CONFIG_SYSTEM_UBLOXMODEM is not set +# CONFIG_SYSTEM_VI is not set +# CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# diff --git a/include/nuttx/wireless/ieee80211/ieee80211.h b/include/nuttx/wireless/ieee80211/ieee80211.h index 71cc273da8..b109487d0b 100644 --- a/include/nuttx/wireless/ieee80211/ieee80211.h +++ b/include/nuttx/wireless/ieee80211/ieee80211.h @@ -8,6 +8,7 @@ * 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 -- GitLab From ccfdef6ddff2fc87d775dc8b00c367d7295bcdde Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Mon, 1 May 2017 17:41:57 -0600 Subject: [PATCH 666/990] STM32F0: Fix I2C frequency table --- arch/arm/src/stm32f0/stm32f0_i2c.c | 81 +++++++----------------------- 1 file changed, 19 insertions(+), 62 deletions(-) diff --git a/arch/arm/src/stm32f0/stm32f0_i2c.c b/arch/arm/src/stm32f0/stm32f0_i2c.c index 4d66aa3ac9..c7f2cc940a 100644 --- a/arch/arm/src/stm32f0/stm32f0_i2c.c +++ b/arch/arm/src/stm32f0/stm32f0_i2c.c @@ -1037,88 +1037,45 @@ static void stm32f0_i2c_setclock(FAR struct stm32f0_i2c_priv_s *priv, uint32_t f if (frequency == 10000) { -#if 1 - /* 10 KHz values from I2C timing tool with clock 80mhz */ - - presc = 0x0b; /* PRESC - (+1) prescale I2CCLK */ - scl_l_period = 0xff; /* SCLL - SCL low period in master mode */ - scl_h_period = 0xba; /* SCLH - SCL high period in master mode */ - h_time = 0x00; /* SDADEL - (+1) data hold time after SCL falling edge */ - s_time = 0x01; /* SCLDEL - (+1) data setup time from SDA edge to SCL rising edge */ + /* 10 KHz values from I2C timing tool with clock 8mhz */ -#else - /* 10 KHz values from datasheet with clock 8mhz */ - - presc = 0x03; /* PRESC - (+1) prescale I2CCLK */ + presc = 0x01; /* PRESC - (+1) prescale I2CCLK */ scl_l_period = 0xc7; /* SCLL - SCL low period in master mode */ scl_h_period = 0xc3; /* SCLH - SCL high period in master mode */ h_time = 0x02; /* SDADEL - (+1) data hold time after SCL falling edge */ s_time = 0x04; /* SCLDEL - (+1) data setup time from SDA edge to SCL rising edge */ -#endif } else if (frequency == 100000) { -#if 1 - /* 100 KHz values from I2C timing tool with clock 80mhz */ + /* 100 KHz values from I2C timing tool with clock 8mhz */ presc = 0x01; /* PRESC - (+1) prescale I2CCLK */ - scl_l_period = 0xe7; /* SCLL - SCL low period in master mode */ - scl_h_period = 0x9b; /* SCLH - SCL high period in master mode */ - h_time = 0x00; /* SDADEL - (+1) data hold time after SCL falling edge */ - s_time = 0x0d; /* SCLDEL - (+1) data setup time from SDA edge to SCL rising edge */ -#else - /* 100 KHz values from datasheet with clock 8mhz */ - - presc = 0x01; - scl_l_period = 0x13; - scl_h_period = 0x0f; - h_time = 0x02; - s_time = 0x04; -#endif + scl_l_period = 0x13; /* SCLL - SCL low period in master mode */ + scl_h_period = 0x0f; /* SCLH - SCL high period in master mode */ + h_time = 0x02; /* SDADEL - (+1) data hold time after SCL falling edge */ + s_time = 0x04; /* SCLDEL - (+1) data setup time from SDA edge to SCL rising edge */ } else if (frequency == 400000) { -#if 1 - /* 400 KHz values from I2C timing tool for clock of 80mhz */ + /* 400 KHz values from I2C timing tool for clock of 8mhz */ - presc = 0x01; /* PRESC - (+1) prescale I2CCLK */ - scl_l_period = 0x43; /* SCLL - SCL low period in master mode */ - scl_h_period = 0x13; /* SCLH - SCL high period in master mode */ - h_time = 0x00; /* SDADEL - (+1) data hold time after SCL falling edge */ - s_time = 0x07; /* SCLDEL - (+1) data setup time from SDA edge to SCL rising edge */ -#else - /* 400 KHz values from datasheet for clock of 8mhz */ - - presc = 0x00; - scl_l_period = 0x09; - scl_h_period = 0x03; - h_time = 0x01; - s_time = 0x03; -#endif + presc = 0x00; /* PRESC - (+1) prescale I2CCLK */ + scl_l_period = 0x09; /* SCLL - SCL low period in master mode */ + scl_h_period = 0x03; /* SCLH - SCL high period in master mode */ + h_time = 0x01; /* SDADEL - (+1) data hold time after SCL falling edge */ + s_time = 0x03; /* SCLDEL - (+1) data setup time from SDA edge to SCL rising edge */ } else { -#if 1 - /* 1000 KHhz values from I2C timing tool for clock of 80mhz */ + /* 1000 KHhz values from I2C timing tool for clock of 8mhz */ - presc = 0x01; /* PRESC - (+1) prescale I2CCLK */ - scl_l_period = 0x14; /* SCLL - SCL low period in master mode */ - scl_h_period = 0x13; /* SCLH - SCL high period in master mode */ + presc = 0x00; /* PRESC - (+1) prescale I2CCLK */ + scl_l_period = 0x06; /* SCLL - SCL low period in master mode */ + scl_h_period = 0x03; /* SCLH - SCL high period in master mode */ h_time = 0x00; /* SDADEL - (+1) data hold time after SCL falling edge */ - s_time = 0x05; /* SCLDEL - (+1) data setup time from SDA edge to SCL rising edge */ - - frequency = 1000000; -#else - /* 500 KHhz values from datasheet for clock of 8mhz */ - - presc = 0x00; - scl_l_period = 0x06; - scl_h_period = 0x03; - h_time = 0x00; - s_time = 0x01; + s_time = 0x01; /* SCLDEL - (+1) data setup time from SDA edge to SCL rising edge */ - frequency = 500000; -#endif + frequency = 1000000; } uint32_t timingr = -- GitLab From c59a5efcae52670e7faccde330cd5c9612852091 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 1 May 2017 17:52:51 -0600 Subject: [PATCH 667/990] STM32F0: I2C frequency quantization. Add logic to get closer if an oddball frequency is used. --- arch/arm/src/stm32f0/stm32f0_i2c.c | 20 +++++++++----------- 1 file changed, 9 insertions(+), 11 deletions(-) diff --git a/arch/arm/src/stm32f0/stm32f0_i2c.c b/arch/arm/src/stm32f0/stm32f0_i2c.c index c7f2cc940a..c782754fc3 100644 --- a/arch/arm/src/stm32f0/stm32f0_i2c.c +++ b/arch/arm/src/stm32f0/stm32f0_i2c.c @@ -990,25 +990,25 @@ static void stm32f0_i2c_setclock(FAR struct stm32f0_i2c_priv_s *priv, uint32_t f uint8_t scl_l_period; /* XXX haque; these are the only freqs we support at the moment, until we can - * compute the values ourself. + * compute the values ourself. Pick the highest supported frequency that does + * not exceed the requested frequency. */ - if (frequency == 10000) + if (frequency < 100000) { + frequency = 10000; /* 0Hz <= frequency < 100KHz: Use 10Khz */ } - else if (frequency == 100000) + else if (frequency < 400000) { + frequency = 100000; /* 100KHz <= frequency < 400KHz: Use 100KHz */ } - else if (frequency == 400000) + else if (frequency < 1000000) { + frequency = 400000; /* 400KHz <= frequency < 1MHz: Use 400Khz */ } else { -#if 1 - frequency = 1000000; -#else - frequency = 500000; -#endif + frequency = 1000000; /* 1MHz <= frequency: Use 1Mhz */ } /* Has the I2C bus frequency changed? */ @@ -1074,8 +1074,6 @@ static void stm32f0_i2c_setclock(FAR struct stm32f0_i2c_priv_s *priv, uint32_t f scl_h_period = 0x03; /* SCLH - SCL high period in master mode */ h_time = 0x00; /* SDADEL - (+1) data hold time after SCL falling edge */ s_time = 0x01; /* SCLDEL - (+1) data setup time from SDA edge to SCL rising edge */ - - frequency = 1000000; } uint32_t timingr = -- GitLab From 03bd3688bc7a2f79429e61b54cb7776f3300faaa Mon Sep 17 00:00:00 2001 From: EunBong Song Date: Tue, 2 May 2017 07:14:04 -0600 Subject: [PATCH 668/990] pthread: Fix compilation error on pthread_cond_wait when CONFIG_CANCELLATION_POINTS and CONFIG_PTHREAD_MUTEX_UNSAFE are enabled. --- sched/pthread/pthread.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sched/pthread/pthread.h b/sched/pthread/pthread.h index 69e08e1445..14a5797bb8 100644 --- a/sched/pthread/pthread.h +++ b/sched/pthread/pthread.h @@ -121,7 +121,7 @@ void pthread_mutex_inconsistent(FAR struct pthread_tcb_s *tcb); # define pthread_mutex_give(m) pthread_givesemaphore(&(m)->sem) #endif -#ifdef CONFIG_CANCELLATION_POINTS +#if defined(CONFIG_CANCELLATION_POINTS) && !defined(CONFIG_PTHREAD_MUTEX_UNSAFE) uint16_t pthread_disable_cancel(void); void pthread_enable_cancel(uint16_t oldstate); #else -- GitLab From 1829282442b242bf18f37ffe7319e033bf3b2c0a Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Tue, 2 May 2017 15:36:18 +0300 Subject: [PATCH 669/990] configs: add nucleo-l496zg board files --- configs/Kconfig | 42 +- configs/nucleo-144/README.txt | 24 +- configs/nucleo-144/src/stm32_appinitialize.c | 3 +- configs/nucleo-l476rg/README.txt | 4 +- configs/nucleo-l476rg/scripts/l476rg.ld | 2 +- configs/nucleo-l496zg/Kconfig | 223 +++ configs/nucleo-l496zg/README.txt | 378 +++++ configs/nucleo-l496zg/include/board.h | 458 ++++++ configs/nucleo-l496zg/nsh/Make.defs | 112 ++ configs/nucleo-l496zg/nsh/defconfig | 1294 +++++++++++++++++ configs/nucleo-l496zg/scripts/kernel-space.ld | 109 ++ configs/nucleo-l496zg/scripts/l496zg-flash.ld | 119 ++ configs/nucleo-l496zg/scripts/memory.ld | 129 ++ configs/nucleo-l496zg/scripts/user-space.ld | 111 ++ configs/nucleo-l496zg/src/.gitignore | 2 + configs/nucleo-l496zg/src/Makefile | 72 + configs/nucleo-l496zg/src/nucleo-144.h | 285 ++++ configs/nucleo-l496zg/src/stm32_adc.c | 174 +++ .../nucleo-l496zg/src/stm32_appinitialize.c | 200 +++ configs/nucleo-l496zg/src/stm32_autoleds.c | 188 +++ configs/nucleo-l496zg/src/stm32_boot.c | 109 ++ configs/nucleo-l496zg/src/stm32_buttons.c | 120 ++ configs/nucleo-l496zg/src/stm32_dma_alloc.c | 117 ++ configs/nucleo-l496zg/src/stm32_sdio.c | 180 +++ configs/nucleo-l496zg/src/stm32_spi.c | 362 +++++ configs/nucleo-l496zg/src/stm32_usb.c | 331 +++++ configs/nucleo-l496zg/src/stm32_userleds.c | 144 ++ 27 files changed, 5274 insertions(+), 18 deletions(-) create mode 100644 configs/nucleo-l496zg/Kconfig create mode 100644 configs/nucleo-l496zg/README.txt create mode 100644 configs/nucleo-l496zg/include/board.h create mode 100644 configs/nucleo-l496zg/nsh/Make.defs create mode 100644 configs/nucleo-l496zg/nsh/defconfig create mode 100644 configs/nucleo-l496zg/scripts/kernel-space.ld create mode 100644 configs/nucleo-l496zg/scripts/l496zg-flash.ld create mode 100644 configs/nucleo-l496zg/scripts/memory.ld create mode 100644 configs/nucleo-l496zg/scripts/user-space.ld create mode 100644 configs/nucleo-l496zg/src/.gitignore create mode 100644 configs/nucleo-l496zg/src/Makefile create mode 100644 configs/nucleo-l496zg/src/nucleo-144.h create mode 100644 configs/nucleo-l496zg/src/stm32_adc.c create mode 100644 configs/nucleo-l496zg/src/stm32_appinitialize.c create mode 100644 configs/nucleo-l496zg/src/stm32_autoleds.c create mode 100644 configs/nucleo-l496zg/src/stm32_boot.c create mode 100644 configs/nucleo-l496zg/src/stm32_buttons.c create mode 100644 configs/nucleo-l496zg/src/stm32_dma_alloc.c create mode 100644 configs/nucleo-l496zg/src/stm32_sdio.c create mode 100644 configs/nucleo-l496zg/src/stm32_spi.c create mode 100644 configs/nucleo-l496zg/src/stm32_usb.c create mode 100644 configs/nucleo-l496zg/src/stm32_userleds.c diff --git a/configs/Kconfig b/configs/Kconfig index 24632785d3..5a13b9a0a1 100644 --- a/configs/Kconfig +++ b/configs/Kconfig @@ -708,7 +708,7 @@ config ARCH_BOARD_NUCLEO_144 select ARCH_HAVE_IRQBUTTONS ---help--- STMicro Nucleo-144 development board featuring STMicroelectronics - F2, F3, F4 and F7 MCU families. The board is a "Hardware pattern" + F2, F3, F4, F7 and L4 MCU families. The board is a "Hardware pattern" that can be populated with the 144 pin package of the following MCUs: Target STM32 Order code @@ -716,14 +716,44 @@ config ARCH_BOARD_NUCLEO_144 STM32F303ZET6 NUCLEO-F303ZE STM32F429ZIT6 NUCLEO-F429ZI STM32F446ZET6 NUCLEO-F446ZE + STM32F746ZGT6 NUCLEO-F746ZG + STM32F767ZIT6 NUCLEO-F767ZI + STM32L496ZGT6 NUCLEO-L496ZG + STM32L496ZGT6P NUCLEO-L496ZG-P - Supported in this release are: + Supported in this configuration are: - NUCLEO-F746ZG - STM32F746ZGT6 a 216MHz Cortex-M7, w/FPU - 1024KiB - Flash memory and 320KiB SRAM. + NUCLEO-F746ZG - STM32F746ZGT6 a 216MHz Cortex-M7, w/FPU - + 1024KiB Flash memory and 320KiB SRAM. NUCLEO-F767ZI - STM32F767ZIT6 a 216MHz Cortex-M7, w/DPFPU - 2048KiB Flash memory and 512KiB SRAM. +config ARCH_BOARD_NUCLEO_L496ZG + bool "STM32L496 Nucleo L496ZG" + depends on ARCH_CHIP_STM32L496ZG + select ARCH_HAVE_LEDS + select ARCH_HAVE_BUTTONS + select ARCH_HAVE_IRQBUTTONS + ---help--- + STMicro Nucleo-144 development board featuring STMicroelectronics + F2, F3, F4, F7 and L4 MCU families. The board is a "Hardware pattern" + that can be populated with the 144 pin package of the following MCUs: + + Target STM32 Order code + STM32F207ZGT6 NUCLEO-F207ZG + STM32F303ZET6 NUCLEO-F303ZE + STM32F429ZIT6 NUCLEO-F429ZI + STM32F446ZET6 NUCLEO-F446ZE + STM32F746ZGT6 NUCLEO-F746ZG + STM32F767ZIT6 NUCLEO-F767ZI + STM32L496ZGT6 NUCLEO-L496ZG + STM32L496ZGT6P NUCLEO-L496ZG-P + + Supported in this configuration are: + + NUCLEO-L496ZG - STM32L496ZGT6 a 80MHz Cortex-M4, w/FPU - + 1024KiB Flash memory and 320KiB SRAM. + config ARCH_BOARD_NUCLEO_F072RB bool "STM32F072 Nucleo F072RB" depends on ARCH_CHIP_STM32F072RB @@ -1518,6 +1548,7 @@ config ARCH_BOARD default "nucleo-f334r8" if ARCH_BOARD_NUCLEO_F334R8 default "nucleo-f4x1re" if ARCH_BOARD_NUCLEO_F401RE || ARCH_BOARD_NUCLEO_F411RE default "nucleo-l476rg" if ARCH_BOARD_NUCLEO_L476RG + default "nucleo-l496zg" if ARCH_BOARD_NUCLEO_L496ZG default "qemu-i486" if ARCH_BOARD_QEMU_I486 default "sabre-6quad" if ARCH_BOARD_SABRE_6QUAD default "sama5d2-xult" if ARCH_BOARD_SAMA5D2_XULT @@ -1835,6 +1866,9 @@ endif if ARCH_BOARD_NUCLEO_L476RG source "configs/nucleo-l476rg/Kconfig" endif +if ARCH_BOARD_NUCLEO_L496ZG +source "configs/nucleo-l496zg/Kconfig" +endif if ARCH_BOARD_QEMU_I486 source "configs/qemu-i486/Kconfig" endif diff --git a/configs/nucleo-144/README.txt b/configs/nucleo-144/README.txt index db816dd5c6..51edb92e35 100644 --- a/configs/nucleo-144/README.txt +++ b/configs/nucleo-144/README.txt @@ -32,14 +32,17 @@ Nucleo-144 Boards: The Nucleo-144 is a standard board for use with several STM32 parts in the LQFP144 package. Variants include - STM32 Part Board Variant Name - ------------- ------------------ - STM32F207ZGT6 NUCLEO-F207ZG - STM32F303ZET6 NUCLEO-F303ZE - STM32F429ZIT6 NUCLEO-F429ZI - STM32F446ZET6 NUCLEO-F446ZE - STM32F746ZGT6 NUCLEO-F746ZG - STM32F767ZIT6 NUCLEO-F767ZI + STM32 Part Board Variant Name + ------------- ------------------ + STM32F207ZGT6 NUCLEO-F207ZG + STM32F303ZET6 NUCLEO-F303ZE + STM32F429ZIT6 NUCLEO-F429ZI + STM32F446ZET6 NUCLEO-F446ZE + STM32F746ZGT6 NUCLEO-F746ZG + STM32F767ZIT6 NUCLEO-F767ZI + STM32L496ZGT6 NUCLEO-L496ZG + STM32L496ZGT6P NUCLEO-L496ZG-P + ------------- ------------------ This directory is intended to support all Nucleo-144 variants since the @@ -48,9 +51,10 @@ board design provides uniformity in the documentation from ST and should allow us to quickly change configurations by just cloning a configuration and changing the CPU choice and board initialization. Unfortunately for the developer, the CPU specific information must be extracted from the -common information in the documentation. +common information in the documentation. The exception are the STM32L496ZG +boards, which are supported by configs/nucleo-l496zg -Please read the User Manaul UM1727: Getting started with STM32 Nucleo board +Please read the User Manual UM1727: Getting started with STM32 Nucleo board software development tools and take note of the Powering options for the board (6.3 Power supply and power selection) and the Solder bridges based hardware configuration changes that are configurable (6.11 Solder bridges). diff --git a/configs/nucleo-144/src/stm32_appinitialize.c b/configs/nucleo-144/src/stm32_appinitialize.c index 86febc3e85..a4ad8423bd 100644 --- a/configs/nucleo-144/src/stm32_appinitialize.c +++ b/configs/nucleo-144/src/stm32_appinitialize.c @@ -1,5 +1,5 @@ /**************************************************************************** - * config/nucleo-144/src/stm32_appinitilaize.c + * config/nucleo-144/src/stm32_appinitialize.c * * Copyright (C) 2016 Gregory Nutt. All rights reserved. * Authors: Gregory Nutt @@ -42,6 +42,7 @@ #include #include +#include #include #include diff --git a/configs/nucleo-l476rg/README.txt b/configs/nucleo-l476rg/README.txt index f216b93cf7..d3312ff354 100644 --- a/configs/nucleo-l476rg/README.txt +++ b/configs/nucleo-l476rg/README.txt @@ -6,9 +6,9 @@ NucleoL476RG board from ST Micro. See http://www.st.com/nucleo-l476rg -NucleoF476RG: +NucleoL476RG: - Microprocessor: 32-bit ARM Cortex M4 at 80MHz STM32F476RGT6 + Microprocessor: 32-bit ARM Cortex M4 at 80MHz STM32L476RGT6 Memory: 1024 KB Flash and 96+32 KB SRAM ADC: 2×12-bit, 2.4 MSPS A/D converter: up to 24 channels DMA: 16-stream DMA controllers with FIFOs and burst support diff --git a/configs/nucleo-l476rg/scripts/l476rg.ld b/configs/nucleo-l476rg/scripts/l476rg.ld index 94c512fec5..eba5e9c65a 100644 --- a/configs/nucleo-l476rg/scripts/l476rg.ld +++ b/configs/nucleo-l476rg/scripts/l476rg.ld @@ -34,7 +34,7 @@ * ****************************************************************************/ -/* The STM32F411RE has 512Kb of FLASH beginning at address 0x0800:0000 and +/* The STM32L476RG has 512Kb of FLASH beginning at address 0x0800:0000 and * 128Kb of SRAM beginning at address 0x2000:0000. When booting from FLASH, * FLASH memory is aliased to address 0x0000:0000 where the code expects to * begin execution by jumping to the entry point in the 0x0800:0000 address diff --git a/configs/nucleo-l496zg/Kconfig b/configs/nucleo-l496zg/Kconfig new file mode 100644 index 0000000000..af61775c0b --- /dev/null +++ b/configs/nucleo-l496zg/Kconfig @@ -0,0 +1,223 @@ +# +# For a description of the syntax of this configuration file, +# see the file kconfig-language.txt in the NuttX tools repository. +# + +if ARCH_BOARD_NUCLEO_144 + +choice + prompt "Select Console wiring." + default NUCLEO_ARDUINO + ---help--- + Select where you will connect the console. + + Virtual COM Port: + + Advantage: Use the ST-Link as a console. No Extra wiring + neded. + + Disdvantage: Not the best choice for initial bring up. + + ARDUINO Connector: + + Advantage: You have a shield so it is + easy. + + Disdvantage: You loose the use of the + other functions on PC6, PC7 + + STM32F7 + ARDUIONO FUNCTION GPIO + -- ----- --------- ---- + DO RX USART6_RX PG9 + D1 TX USART6_TX PG14 + -- ----- --------- --- + + OR + + Morpho Connector: + + STM32F7 + MORPHO FUNCTION GPIO + -------- --------- ----- + CN12-64 USART8_RX PE0 + CN11-61 USART8_TX PE1 + -------- --------- ----- + +config NUCLEO_CONSOLE_ARDUINO + bool "ARDUINO Connector" + select STM32F7_USART6 + select USART6_SERIALDRIVER + select USART6_SERIAL_CONSOLE + +config NUCLEO_CONSOLE_VIRTUAL + bool "Virtual Comport" + select STM32F7_USART3 + select USART3_SERIALDRIVER + select USART3_SERIAL_CONSOLE + +config NUCLEO_CONSOLE_MORPHO + bool "Morpho Connector" + select STM32F7_UART8 + select UART8_SERIALDRIVER + select UART8_SERIAL_CONSOLE + +config NUCLEO_CONSOLE_NONE + bool "No Console" + +endchoice # "Select Console wiring" + +config NUCLEO_SPI_TEST + bool "Enable SPI test" + default n + ---help--- + Enable Spi test - initalize and configure SPI to send + NUCLEO_SPI_TEST_MESSAGE text. The text is sent on the + selected SPI Buses with the configured parameters. + Note the CS lines will not be asserted. + +if NUCLEO_SPI_TEST + +config NUCLEO_SPI_TEST_MESSAGE + string "Text to Send on SPI Bus(es)" + default "Hello World" + depends on NUCLEO_SPI_TEST + ---help--- + Text to sent on SPI bus(es) + +config NUCLEO_SPI1_TEST + bool "Test SPI bus 1" + default n + depends on NUCLEO_SPI_TEST + ---help--- + Enable Spi test - on SPI BUS 1 + +if NUCLEO_SPI1_TEST + +config NUCLEO_SPI1_TEST_FREQ + int "SPI 1 Clock Freq in Hz" + default 1000000 + depends on NUCLEO_SPI1_TEST + ---help--- + Sets SPI 1 Clock Freq + +config NUCLEO_SPI1_TEST_BITS + int "SPI 1 number of bits" + default 8 + depends on NUCLEO_SPI1_TEST + ---help--- + Sets SPI 1 bit length + +choice + prompt "SPI BUS 1 Clock Mode" + default NUCLEO_SPI1_TEST_MODE3 + ---help--- + Sets SPI 1 clock mode + +config NUCLEO_SPI1_TEST_MODE0 + bool "CPOL=0 CHPHA=0" + +config NUCLEO_SPI1_TEST_MODE1 + bool "CPOL=0 CHPHA=1" + +config NUCLEO_SPI1_TEST_MODE2 + bool "CPOL=1 CHPHA=0" + +config NUCLEO_SPI1_TEST_MODE3 + bool "CPOL=1 CHPHA=1" + +endchoice # "SPI BUS 1 Clock Mode" + +endif # NUCLEO_SPI1_TEST + +config NUCLEO_SPI2_TEST + bool "Test SPI bus 2" + default n + depends on NUCLEO_SPI_TEST + ---help--- + Enable Spi test - on SPI BUS 2 + +if NUCLEO_SPI2_TEST + +config NUCLEO_SPI2_TEST_FREQ + int "SPI 2 Clock Freq in Hz" + default 12000000 + depends on NUCLEO_SPI2_TEST + ---help--- + Sets SPI 2 Clock Freq + +config NUCLEO_SPI2_TEST_BITS + int "SPI 2 number of bits" + default 8 + depends on NUCLEO_SPI2_TEST + ---help--- + Sets SPI 2 bit length + +choice + prompt "SPI BUS 2 Clock Mode" + default NUCLEO_SPI2_TEST_MODE3 + ---help--- + Sets SPI 2 clock mode + +config NUCLEO_SPI2_TEST_MODE0 + bool "CPOL=0 CHPHA=0" + +config NUCLEO_SPI2_TEST_MODE1 + bool "CPOL=0 CHPHA=1" + +config NUCLEO_SPI2_TEST_MODE2 + bool "CPOL=1 CHPHA=0" + +config NUCLEO_SPI2_TEST_MODE3 + bool "CPOL=1 CHPHA=1" + +endchoice # "SPI BUS 2 Clock Mode" + +endif # NUCLEO_SPI2_TEST + +config NUCLEO_SPI3_TEST + bool "Test SPI bus 3" + default n + depends on NUCLEO_SPI_TEST + ---help--- + Enable Spi test - on SPI BUS 3 + +if NUCLEO_SPI3_TEST + +config NUCLEO_SPI3_TEST_FREQ + int "SPI 3 Clock Freq in Hz" + default 40000000 + depends on NUCLEO_SPI3_TEST + ---help--- + Sets SPI 3 Clock Freq + +config NUCLEO_SPI3_TEST_BITS + int "SPI 3 number of bits" + default 8 + depends on NUCLEO_SPI3_TEST + ---help--- + Sets SPI 3 bit length + +choice + prompt "SPI BUS 3 Clock Mode" + default NUCLEO_SPI3_TEST_MODE3 + ---help--- + Sets SPI 3 clock mode + +config NUCLEO_SPI3_TEST_MODE0 + bool "CPOL=0 CHPHA=0" + +config NUCLEO_SPI3_TEST_MODE1 + bool "CPOL=0 CHPHA=1" + +config NUCLEO_SPI3_TEST_MODE2 + bool "CPOL=1 CHPHA=0" + +config NUCLEO_SPI3_TEST_MODE3 + bool "CPOL=1 CHPHA=1" + +endchoice # "SPI BUS 3 Clock Mode" + +endif # NUCLEO_SPI3_TEST +endif # NUCLEO_SPI_TEST +endif # ARCH_BOARD_NUCLEO_144 diff --git a/configs/nucleo-l496zg/README.txt b/configs/nucleo-l496zg/README.txt new file mode 100644 index 0000000000..0dffae0c61 --- /dev/null +++ b/configs/nucleo-l496zg/README.txt @@ -0,0 +1,378 @@ +README +====== + +This README discusses issues unique to NuttX configurations for the STMicro +Nucleo-144 board. See + +http://www.st.com/content/ccc/resource/technical/document/data_brief/group0/7b/df/1d/e9/64/55/43/8d/DM00247910/files/DM00247910.pdf/jcr:content/translations/en.DM00247910.pdf + +Contents +======== + + - Nucleo-144 Boards + - Nucleo L496ZG + - Hardware + - Button + - LED + - U[S]ARTs and Serial Consoles + - SPI + - SDIO - MMC + - SPI Test + - Configurations + nsh + +Nucleo-144 Boards: +================= + +The Nucleo-144 is a standard board for use with several STM32 parts in the +LQFP144 package. Variants include + + STM32 Part Board Variant Name + ------------- ------------------ + STM32F207ZGT6 NUCLEO-F207ZG + STM32F303ZET6 NUCLEO-F303ZE + STM32F429ZIT6 NUCLEO-F429ZI + STM32F446ZET6 NUCLEO-F446ZE + STM32F746ZGT6 NUCLEO-F746ZG + STM32F767ZIT6 NUCLEO-F767ZI + STM32L496ZGT6 NUCLEO-L496ZG + STM32L496ZGT6P NUCLEO-L496ZG-P + + ------------- ------------------ + +This directory supports the L4 variants of Nucleo-144 + +Please read the User Manual UM2179: Getting started with STM32 Nucleo board +software development tools and take note of the Powering options for the +board (6.3 Power supply and power selection) and the Solder bridges based +hardware configuration changes that are configurable (6.11 Solder bridges). + +Also note that UM1727 is not valid for L4 Nucleo-144 boards! + +Common Board Features: +--------------------- + + Peripherals: 8 leds, 2 push button (3 LEDs, 1 button) under software + control + Debug: STLINK/V2-1 debugger/programmer Uses a STM32F103CB to + provide a ST-Link for programming, debug similar to the + OpenOcd FTDI function - USB to JTAG front-end. + + Expansion I/F: ST Zio and Extended Ardino and Morpho Headers + +Nucleo L496ZG +============= + +ST Nucleo L496ZG board from ST Micro is supported. See + +http://www.st.com/content/st_com/en/products/evaluation-tools/product-evaluation-tools/mcu-eval-tools/stm32-mcu-eval-tools/stm32-mcu-nucleo/nucleo-l496zg.html + +The Nucleo L496ZG order part number is NUCLEO-L496ZG. It is one member of +the STM32 Nucleo-144 board family. + +NUCLEO-L496ZG Features: +---------------------- + + Microprocessor: STM32L496ZGT6 Core: ARM 32-bit Cortex®-M4 CPU with FPU, + 80 MHz, MPU, and DSP instructions. + Memory: 1024 KB Flash 320KB of SRAM (including 64KB of SRAM2) + ADC: 3×12-bit: up to 24 channels + DMA: 2 X 7-stream DMA controllers with FIFOs and burst support + Timers: Up to 13 timers: (2x 16-bit lowpower), two 32-bit timers, + 2x watchdogs, SysTick + GPIO: 114 I/O ports with interrupt capability + LCD: LCD-TFT Controller, Parallel interface + I2C: 4 × I2C interfaces (SMBus/PMBus) + U[S]ARTs: 3 USARTs, 2 UARTs (27 Mbit/s, ISO7816 interface, LIN, IrDA, + modem control) + SPI/12Ss: 6/3 (simplex) (up to 50 Mbit/s), 3 with muxed simplex I2S + for audio class accuracy via internal audio PLL or external + clock + QSPI: Dual mode Quad-SPI + SAIs: 2 Serial Audio Interfaces + CAN: 2 X CAN interface + SDMMC interface + USB: USB 2.0 full-speed device/host/OTG controller with on-chip + PHY + Camera Interface: 8/14 Bit + CRC calculation unit + TRG: True random number generator + RTC + +See https://developer.mbed.org/platforms/ST-Nucleo-L496ZG for additional +information about this board. + +Hardware +======== +< Section needs updating > + + GPIO - there are 144 I/O lines on the STM32L4xxZx with various pins pined out + on the Nucleo 144. + + Keep in mind that: + 1) The I/O is 3.3 Volt not 5 Volt like on the Arduino products. + 2) The Nucleo-144 board family has 3 pages of Solder Bridges AKA Solder + Blobs (SB) that can alter the factory configuration. We will note SB + in effect but will assume the facitory defualt settings. + + Our main concern is establishing a console and LED utilization for + debugging. Because so many pins can be multiplexed with so many functions, + the above mentioned graphic may be helpful in indentifying a serial port. + + There are 4 choices that can be made from the menuconfig: + + CONFIG_NUCLEO_CONSOLE_ARDUINO or CONFIG_NUCLEO_CONSOLE_MORPHO or + CONFIG_NUCLEO_CONSOLE_VIRTUAL or CONFIG_NUCLEO_CONSOLE_NONE + + The CONFIG_NUCLEO_CONSOLE_NONE makes no preset for the console. You should still visit + the U[S]ART selection and Device Drivers to disable any U[S]ART reamaing. + + The CONFIG_NUCLEO_CONSOLE_ARDUINO configurations assume that you are using a + standard Arduio RS-232 shield with the serial interface with RX on pin D0 and + TX on pin D1 from USART6: + + -------- --------------- + STM32F7 + ARDUIONO FUNCTION GPIO + -- ----- --------- ----- + DO RX USART6_RX PG9 + D1 TX USART6_TX PG14 + -- ----- --------- ----- + + The CONFIG_NUCLEO_CONSOLE_MORPHO configurations uses Serial Port 8 (USART8) + with TX on PE1 and RX on PE0. + Serial + ------ + SERIAL_RX PE_0 + SERIAL_TX PE_1 + + The CONFIG_NUCLEO_CONSOLE_VIRTUAL configurations uses Serial Port 3 (USART3) + with TX on PD8 and RX on PD9. + Serial + ------ + SERIAL_RX PD9 + SERIAL_TX PD8 + + These signals are internally connected to the on board ST-Link + + Of course if your design has used those pins you can choose a completely + different U[S]ART to use as the console. In that Case, you will need to edit + the include/board.h to select different U[S]ART and / or pin selections. + + Buttons + ------- + B1 USER: the user button is connected to the I/O PC13 (Tamper support, SB173 + ON and SB180 OFF) + + LEDs + ---- + The Board provides a 3 user LEDs, LD1-LD3 + LED1 (Green) PB_0 (SB120 ON and SB119 OFF) + LED2 (Blue) PB_7 (SB139 ON) + LED3 (Red) PB_14 (SP118 ON) + + - When the I/O is HIGH value, the LEDs are on. + - When the I/O is LOW, the LEDs are off. + + These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is + defined. In that case, the usage by the board port is defined in + include/board.h and src/stm32_autoleds.c. The LEDs are used to encode OS + related events as follows when the LEDs are available: + + SYMBOL Meaning RED GREEN BLUE + ------------------- ----------------------- --- ----- ---- + + LED_STARTED NuttX has been started OFF OFF OFF + LED_HEAPALLOCATE Heap has been allocated OFF OFF ON + LED_IRQSENABLED Interrupts enabled OFF ON OFF + LED_STACKCREATED Idle stack created OFF ON ON + LED_INIRQ In an interrupt NC NC ON (momentary) + LED_SIGNAL In a signal handler NC ON OFF (momentary) + LED_ASSERTION An assertion failed ON NC ON (momentary) + LED_PANIC The system has crashed ON OFF OFF (flashing 2Hz) + LED_IDLE MCU is is sleep mode ON OFF OFF + + +OFF - means that the OS is still initializing. Initialization is very fast + so if you see this at all, it probably means that the system is + hanging up somewhere in the initialization phases. + +GREEN - This means that the OS completed initialization. + +BLUE - Whenever and interrupt or signal handler is entered, the BLUE LED is + illuminated and extinguished when the interrupt or signal handler + exits. + +VIOLET - If a recovered assertion occurs, the RED and blue LED will be + illuminated briefly while the assertion is handled. You will + probably never see this. + +Flashing RED - In the event of a fatal crash, all other LEDs will be + extinguished and RED LED will FLASH at a 2Hz rate. + + + Thus if the GREEN LED is lit, NuttX has successfully booted and is, + apparently, running normally. If the RED LED is flashing at + approximately 2Hz, then a fatal error has been detected and the system has + halted. + +Serial Consoles +=============== +< Section needs updating > + + USART6 (CONFIG_NUCLEO_CONSOLE_ARDUINO) + ------ + STM32F7 + ARDUIONO FUNCTION GPIO + -- ----- --------- ----- + DO RX USART6_RX PG9 + D1 TX USART6_TX PG14 + -- ----- --------- ----- + + You must use a 3.3 TTL to RS-232 converter or a USB to 3.3V TTL + + Nucleo 144 FTDI TTL-232R-3V3 + ------------- ------------------- + TXD - D1-TXD - RXD - Pin 5 (Yellow) + RXD - D0-RXD - TXD - Pin 4 (Orange) + GND GND - GND Pin 1 (Black) + ------------- ------------------- + + *Note you will be reverse RX/TX + + Use make menuconfig to configure USART6 as the console: + + CONFIG_STM32F7_USART6=y + CONFIG_USARTs_SERIALDRIVER=y + CONFIG_USARTS_SERIAL_CONSOLE=y + CONFIG_USART6_RXBUFSIZE=256 + CONFIG_USART6_TXBUFSIZE=256 + CONFIG_USART6_BAUD=115200 + CONFIG_USART6_BITS=8 + CONFIG_USART6_PARITY=0 + CONFIG_USART6_2STOP=0 + + USART8 (CONFIG_NUCLEO_CONSOLE_MORPHO) + ------ + + Pins and Connectors: + FUNC GPIO Connector + Pin NAME + ---- --- ------- ---- + TXD: PE1 CN11-61, PE1 + RXD: PE0 CN12-64, PE0 + CN10-33, D34 + ---- --- ------- ---- + + + You must use a 3.3 TTL to RS-232 converter or a USB to 3.3V TTL + + Nucleo 144 FTDI TTL-232R-3V3 + ------------- ------------------- + TXD - CN11-61 - RXD - Pin 5 (Yellow) + RXD - CN12-64 - TXD - Pin 4 (Orange) + GND CN12-63 - GND Pin 1 (Black) + ------------- ------------------- + + *Note you will be reverse RX/TX + + Use make menuconfig to configure USART8 as the console: + + CONFIG_STM32L4_UART8=y + CONFIG_UART8_SERIALDRIVER=y + CONFIG_UART8_SERIAL_CONSOLE=y + CONFIG_UART8_RXBUFSIZE=256 + CONFIG_UART8_TXBUFSIZE=256 + CONFIG_UART8_BAUD=115200 + CONFIG_UART8_BITS=8 + CONFIG_UART8_PARITY=0 + CONFIG_UART8_2STOP=0 + + Virtual COM Port (CONFIG_NUCLEO_CONSOLE_VIRTUAL) + ---------------- + Yet another option is to use USART3 and the USB virtual COM port. This + option may be more convenient for long term development, but is painful + to use during board bring-up. + + Solder Bridges. This configuration requires: + + PD8 USART3 TX SB5 ON and SB7 OFF (Default) + PD9 USART3 RX SB6 ON and SB4 OFF (Default) + + Configuring USART3 is the same as given above but add the S and #3. + + Question: What BAUD should be configure to interface with the Virtual + COM port? 115200 8N1? + + Default + ------- + As shipped, SB4 and SB7 are open and SB5 and SB6 closed, so the + virtual COM port is enabled. + + +SPI +--- + Since this board is so generic, having a quick way to vet the SPI + configuration seams in order. So the board provides a quick test + that can be selected vi CONFIG_NUCLEO_SPI_TEST that will initalise + the selected buses (SPI1-SPI3) and send some text on the bus at + application initalization time board_app_initialize. + +SDIO +---- + To test the SD performace one can use a SparkFun microSD Sniffer + from https://www.sparkfun.com/products/9419 or similar board + and connect it as follows: + + VCC V3.3 CN11 16 + GND GND CN11-8 + CMD PD2 CN11-4 + CLK PC12 CN11-3 + DAT0 - PC8 CN12-2 + DAT1 - PC9 CN12-1 + DAT2 PC10 CN11-1 + CD PC11 CN11-2 + +Configurations +============== + +nsh: +---- + Configures the NuttShell (nsh) located at apps/examples/nsh for the + Nucleo-144 boards. The Configuration enables the serial interfaces + on USART6. Support for builtin applications is enabled, but in the base + configuration no builtin applications are selected (see NOTES below). + + NOTES: + + 1. This configuration uses the mconf-based configuration tool. To + change this configuration using that tool, you should: + + a. Build and install the kconfig-mconf tool. See nuttx/README.txt + see additional README.txt files in the NuttX tools repository. + + b. If this is the intall configuration then Execute + 'cd tools && ./configure.sh nucleo-144/nsh && cd ..' + in nuttx/ in order to start configuration process. + Caution: Doing this step more than once will overwrite .config with + the contents of the nucleo-144/nsh/defconfig file. + + c. Execute 'make oldconfig' in nuttx/ in order to refresh the + configuration. + + d. Execute 'make menuconfig' in nuttx/ in order to start the + reconfiguration process. + + e. Save the .config file to reuse it in the future starting at step d. + + 2. By default, this configuration uses the ARM GNU toolchain + for Linux. That can easily be reconfigured, of course. + + CONFIG_HOST_LINUX=y : Builds under Linux + CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL=y : ARM GNU for Linux + + 3. Although the default console is USART3 (which would correspond to + the Virtual COM port) I have done all testing with the console + device configured for UART8 (see instruction above under "Serial + Consoles). + diff --git a/configs/nucleo-l496zg/include/board.h b/configs/nucleo-l496zg/include/board.h new file mode 100644 index 0000000000..7f4bc3b5af --- /dev/null +++ b/configs/nucleo-l496zg/include/board.h @@ -0,0 +1,458 @@ +/************************************************************************************ + * configs/nucleo-l496zg/include/board.h + * + * Copyright (C) 2016 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * Mark Olsson + * David Sidrane + * + * 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 __CONFIG_NUCLEO_L496ZG_INCLUDE_BOARD_H +#define __CONFIG_NUCLEO_L496ZG_INCLUDE_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#ifndef __ASSEMBLY__ +# include +#endif + +#ifdef __KERNEL__ +#include "stm32l4_rcc.h" +#ifdef CONFIG_STM32L4_SDMMC1 +# include "stm32l4_sdmmc.h" +#endif +#endif + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ +/* The Nucleo-144 board provides the following clock sources: + * + * MCO: 8 MHz from MCO output of ST-LINK is used as input clock + * X2: 32.768 KHz crystal for LSE + * X3: HSE crystal oscillator (not provided) + * + * So we have these clock source available within the STM32 + * + * HSI: 16 MHz RC factory-trimmed + * LSI: 32 KHz RC + * HSE: 8 MHz from MCO output of ST-LINK + * LSE: 32.768 kHz + */ + + +#define STM32_BOARD_XTAL 8000000ul + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL +#define STM32_LSE_FREQUENCY 32768 + +#define HSI_CLOCK_CONFIG + +#if defined(HSI_CLOCK_CONFIG) + +#define STM32L4_BOARD_USEHSI + +/* Prescaler common to all PLL inputs; will be 1 */ + +#define STM32L4_PLLCFG_PLLM RCC_PLLCFG_PLLM(1) + +/* 'main' PLL config; we use this to generate our system clock via the R + * output. We set it up as 16 MHz / 1 * 10 / 2 = 80 MHz + * + * XXX NOTE: currently the main PLL is implicitly turned on and is implicitly + * the system clock; this should be configurable since not all applications may + * want things done this way. + */ + +#define STM32L4_PLLCFG_PLLN RCC_PLLCFG_PLLN(10) +#define STM32L4_PLLCFG_PLLP 0 +#undef STM32L4_PLLCFG_PLLP_ENABLED +#define STM32L4_PLLCFG_PLLQ RCC_PLLCFG_PLLQ_2 +#define STM32L4_PLLCFG_PLLQ_ENABLED +#define STM32L4_PLLCFG_PLLR RCC_PLLCFG_PLLR_2 +#define STM32L4_PLLCFG_PLLR_ENABLED + +/* 'SAIPLL1' is used to generate the 48 MHz clock, since we can't + * do that with the main PLL's N value. We set N = 13, and enable + * the Q output (ultimately for CLK48) with /4. So, + * 16 MHz / 1 * 12 / 4 = 48 MHz + * + * XXX NOTE: currently the SAIPLL /must/ be explicitly selected in the + * menuconfig, or else all this is a moot point, and the various 48 MHz + * peripherals will not work (RNG at present). I would suggest removing + * that option from Kconfig altogether, and simply making it an option + * that is selected via a #define here, like all these other params. + */ + +#define STM32L4_PLLSAI1CFG_PLLN RCC_PLLSAI1CFG_PLLN(12) +#define STM32L4_PLLSAI1CFG_PLLP 0 +#undef STM32L4_PLLSAI1CFG_PLLP_ENABLED +#define STM32L4_PLLSAI1CFG_PLLQ RCC_PLLSAI1CFG_PLLQ_4 +#define STM32L4_PLLSAI1CFG_PLLQ_ENABLED +#define STM32L4_PLLSAI1CFG_PLLR 0 +#undef STM32L4_PLLSAI1CFG_PLLR_ENABLED + +/* 'SAIPLL2' is not used in this application */ + +#define STM32L4_PLLSAI2CFG_PLLN RCC_PLLSAI2CFG_PLLN(8) +#define STM32L4_PLLSAI2CFG_PLLP 0 +#undef STM32L4_PLLSAI2CFG_PLLP_ENABLED +#define STM32L4_PLLSAI2CFG_PLLR 0 +#undef STM32L4_PLLSAI2CFG_PLLR_ENABLED + +#define STM32L4_SYSCLK_FREQUENCY 80000000ul + +/* CLK48 will come from PLLSAI1 (implicitly Q) */ + +#define STM32L4_USE_CLK48 1 +#define STM32L4_CLK48_SEL RCC_CCIPR_CLK48SEL_PLLSAI1 + +/* Enable the LSE oscillator, used automatically trim the MSI, and for RTC */ + +#define STM32L4_USE_LSE 1 + +/* AHB clock (HCLK) is SYSCLK (80MHz) */ + +#define STM32L4_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */ +#define STM32L4_HCLK_FREQUENCY STM32L4_SYSCLK_FREQUENCY +#define STM32L4_BOARD_HCLK STM32L4_HCLK_FREQUENCY /* Same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/1 (80MHz) */ + +#define STM32L4_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLK /* PCLK1 = HCLK / 1 */ +#define STM32L4_PCLK1_FREQUENCY (STM32L4_HCLK_FREQUENCY/1) + +/* Timers driven from APB1 will be twice PCLK1 */ +/* REVISIT : this can be configured */ + +#define STM32L4_APB1_TIM2_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM3_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM4_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM5_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM6_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM7_CLKIN (2*STM32L4_PCLK1_FREQUENCY) + +/* APB2 clock (PCLK2) is HCLK (80MHz) */ + +#define STM32L4_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK /* PCLK2 = HCLK / 1 */ +#define STM32L4_PCLK2_FREQUENCY (STM32L4_HCLK_FREQUENCY/1) + +/* Timers driven from APB2 will be twice PCLK2 */ +/* REVISIT : this can be configured */ + +#define STM32L4_APB2_TIM1_CLKIN (2*STM32L4_PCLK2_FREQUENCY) +#define STM32L4_APB2_TIM8_CLKIN (2*STM32L4_PCLK2_FREQUENCY) + +/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx + * otherwise frequency is 2xAPBx. + * Note: TIM1,8 are on APB2, others on APB1 + */ +/* REVISIT : this can be configured */ + +#elif defined(HSE_CLOCK_CONFIG) + +# error "Not implemented" + +#endif + +/* SDMMC dividers. Note that slower clocking is required when DMA is disabled + * in order to avoid RX overrun/TX underrun errors due to delayed responses + * to service FIFOs in interrupt driven mode. These values have not been + * tuned!!! + * + * SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(118+2)=400 KHz + */ + +#define STM32_SDMMC_INIT_CLKDIV (118 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) + +/* DMA ON: SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(1+2)=16 MHz + * DMA OFF: SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(2+2)=12 MHz + */ + +#ifdef CONFIG_SDIO_DMA +# define STM32_SDMMC_MMCXFR_CLKDIV (1 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_MMCXFR_CLKDIV (2 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif + +/* DMA ON: SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(1+2)=16 MHz + * DMA OFF: SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(2+2)=12 MHz + */ + +#ifdef CONFIG_SDIO_DMA +# define STM32_SDMMC_SDXFR_CLKDIV (1 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_SDXFR_CLKDIV (2 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif + +#if defined(CONFIG_STM32L4_SDMMC2) +# define GPIO_SDMMC2_D0 GPIO_SDMMC2_D0_1 +# define GPIO_SDMMC2_D1 GPIO_SDMMC2_D1_1 +# define GPIO_SDMMC2_D2 GPIO_SDMMC2_D2_1 +# define GPIO_SDMMC2_D3 GPIO_SDMMC2_D3_1 +#endif + +/* DMA Channel/Stream Selections *****************************************************/ +/* Stream selections are arbitrary for now but might become important in the future + * if we set aside more DMA channels/streams. + * + * SDMMC DMA is on DMA2 + * + * SDMMC1 DMA + * DMAMAP_SDMMC1_1 = Channel 4, Stream 3 + * DMAMAP_SDMMC1_2 = Channel 4, Stream 6 + * + * SDMMC2 DMA + * DMAMAP_SDMMC2_1 = Channel 11, Stream 0 + * DMAMAP_SDMMC3_2 = Channel 11, Stream 5 + */ + +#define DMAMAP_SDMMC1 DMAMAP_SDMMC1_1 +#define DMAMAP_SDMMC2 DMAMAP_SDMMC2_1 + + +/* FLASH wait states + * + * --------- ---------- ----------- + * VDD MAX SYSCLK WAIT STATES + * --------- ---------- ----------- + * 1.7-2.1 V 180 MHz 8 + * 2.1-2.4 V 216 MHz 9 + * 2.4-2.7 V 216 MHz 8 + * 2.7-3.6 V 216 MHz 7 + * --------- ---------- ----------- + */ + +#define BOARD_FLASH_WAITSTATES 7 + +/* LED definitions ******************************************************************/ +/* The Nucleo-144 board has numerous LEDs but only three, LD1 a Green LED, LD2 a Blue + * LED and LD3 a Red LED, that can be controlled by software. The following + * definitions assume the default Solder Bridges are installed. + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way. + * The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +#define BOARD_LED1 0 +#define BOARD_LED2 1 +#define BOARD_LED3 2 +#define BOARD_NLEDS 3 + +#define BOARD_LED_GREEN BOARD_LED1 +#define BOARD_LED_BLUE BOARD_LED2 +#define BOARD_LED_RED BOARD_LED3 + +/* LED bits for use with board_userled_all() */ + +#define BOARD_LED1_BIT (1 << BOARD_LED1) +#define BOARD_LED2_BIT (1 << BOARD_LED2) +#define BOARD_LED3_BIT (1 << BOARD_LED3) + +/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in + * include/board.h and src/stm32_autoleds.c. The LEDs are used to encode OS-related + * events as follows: + * + * + * SYMBOL Meaning LED state + * Red Green Blue + * ---------------------- -------------------------- ------ ------ ----*/ + +#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */ +#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */ +#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */ +#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */ +#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */ +#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */ +#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */ +#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */ +#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */ + +/* Thus if the Green LED is statically on, NuttX has successfully booted and + * is, apparently, running normally. If the Red LED is flashing at + * approximately 2Hz, then a fatal error has been detected and the system + * has halted. + */ + +/* Button definitions ***************************************************************/ +/* The Nucleo-L496ZG supports one button: Pushbutton B1, labeled "User", is + * connected to GPIO PC13. A high value will be sensed when the button is depressed. + */ + +#define BUTTON_USER 0 +#define NUM_BUTTONS 1 +#define BUTTON_USER_BIT (1 << BUTTON_USER) + +/* Alternate function pin selections ************************************************/ + +#define GPIO_USART2_TX GPIO_USART2_TX_2 +#define GPIO_USART2_RX GPIO_USART2_RX_2 +#define GPIO_USART3_TX GPIO_USART3_TX_2 +#define GPIO_USART3_RX GPIO_USART3_RX_2 + +#if defined(CONFIG_NUCLEO_CONSOLE_ARDUINO) +/* USART6: + * + * These configurations assume that you are using a standard Arduio RS-232 shield + * with the serial interface with RX on pin D0 and TX on pin D1: + * + * -------- --------------- + * STM32F7 + * ARDUIONO FUNCTION GPIO + * -- ----- --------- ----- + * DO RX USART6_RX PG9 + * D1 TX USART6_TX PG14 + * -- ----- --------- ----- + */ + + # define GPIO_USART6_RX GPIO_USART6_RX_2 + # define GPIO_USART6_TX GPIO_USART6_TX_2 +#endif + +/* USART3: + * Use USART3 and the USB virtual COM port +*/ + +#if defined(CONFIG_NUCLEO_CONSOLE_VIRTUAL) +/* LPUART1 is connector to Virtual COM port PG6 and PG7, but there is no lpserial. */ +//#define GPIO_USART2_TX GPIO_LPUART1_TX_3 +//#define GPIO_USART2_RX GPIO_LPUART1_RX_3 +# error "No Nucleo virtual console before lpserial is unimplemented" +#endif + +/* DMA channels *************************************************************/ +/* ADC */ + +#define ADC1_DMA_CHAN DMAMAP_ADC1_1 +#define ADC2_DMA_CHAN DMAMAP_ADC2_1 +#define ADC3_DMA_CHAN DMAMAP_ADC3_1 + +/* SPI + * + * + * PA6 SPI1_MISO CN12-13 + * PA7 SPI1_MOSI CN12-15 + * PA5 SPI1_SCK CN12-11 + * + * PB14 SPI2_MISO CN12-28 + * PB15 SPI2_MOSI CN12-26 + * PB13 SPI2_SCK CN12-30 + * + * PB4 SPI3_MISO CN12-27 + * PB5 SPI3_MOSI CN12-29 + * PB3 SPI3_SCK CN12-31 + */ + +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 +#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1 + +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1 +#define GPIO_SPI2_SCK GPIO_SPI2_SCK_3 + +#define GPIO_SPI3_MISO GPIO_SPI3_MISO_1 +#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_2 +#define GPIO_SPI3_SCK GPIO_SPI3_SCK_1 + +/* I2C + * + * + * PB8 I2C1_SCL CN12-3 + * PB9 I2C1_SDA CN12-5 + + * PB10 I2C2_SCL CN11-51 + * PB11 I2C2_SDA CN12-18 + * + * PA8 I2C3_SCL CN12-23 + * PC9 I2C3_SDA CN12-1 + * + */ + +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 + +#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1 +#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1 + +#define GPIO_I2C3_SCL GPIO_I2C3_SCL_1 +#define GPIO_I2C3_SDA GPIO_I2C3_SDA_1 + +#define GPIO_I2C4_SCL GPIO_I2C4_SCL_1 +#define GPIO_I2C4_SDA GPIO_I2C4_SDA_1 + +/************************************************************************************ + * Public Data + ************************************************************************************/ +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32l4_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +void stm32l4_boardinitialize(void); + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __CONFIG_NUCLEO_L496ZG_INCLUDE_BOARD_H */ diff --git a/configs/nucleo-l496zg/nsh/Make.defs b/configs/nucleo-l496zg/nsh/Make.defs new file mode 100644 index 0000000000..95317b930c --- /dev/null +++ b/configs/nucleo-l496zg/nsh/Make.defs @@ -0,0 +1,112 @@ +############################################################################ +# configs/nucleo-144/l496-nsh/Make.defs +# +# Copyright (C) 2014 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. +# +############################################################################ + +include ${TOPDIR}/.config +include ${TOPDIR}/tools/Config.mk +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs + +LDSCRIPT = l496zg-flash.ld + +ifeq ($(WINTOOL),y) + # Windows-native toolchains + DIRLINK = $(TOPDIR)/tools/copydir.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh + ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" + ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" +else + # Linux/Cygwin-native toolchain + MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT) + ARCHINCLUDES = -I. -isystem $(TOPDIR)/include + ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) +endif + +CC = $(CROSSDEV)gcc +CXX = $(CROSSDEV)g++ +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(ARCROSSDEV)ar rcs +NM = $(ARCROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump + +ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} +ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} + +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + ARCHOPTIMIZATION = -g +endif + +ifneq ($(CONFIG_DEBUG_NOOPT),y) + ARCHOPTIMIZATION += $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer +endif + +ARCHCFLAGS = -fno-builtin +ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fcheck-new -fno-rtti +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow -Wundef +ARCHWARNINGSXX = -Wall -Wshadow -Wundef +ARCHDEFINES = +ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 + +CFLAGS = $(ARCHCFLAGS) $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) +CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +NXFLATLDFLAGS1 = -r -d -warn-common +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections +LDNXFLATFLAGS = -e main -s 2048 + +ASMEXT = .S +OBJEXT = .o +LIBEXT = .a +EXEEXT = + +ifneq ($(CROSSDEV),arm-nuttx-elf-) + LDFLAGS += -nostartfiles -nodefaultlibs +endif +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + LDFLAGS += -g +endif + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -Wundef -g -pipe +HOSTLDFLAGS = + diff --git a/configs/nucleo-l496zg/nsh/defconfig b/configs/nucleo-l496zg/nsh/defconfig new file mode 100644 index 0000000000..3808958bd4 --- /dev/null +++ b/configs/nucleo-l496zg/nsh/defconfig @@ -0,0 +1,1294 @@ +# +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# + +# +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set +# CONFIG_DEFAULT_SMALL is not set +CONFIG_HOST_LINUX=y +# CONFIG_HOST_OSX is not set +# CONFIG_HOST_WINDOWS is not set +# CONFIG_HOST_OTHER is not set + +# +# Build Configuration +# +CONFIG_APPS_DIR="../apps" +CONFIG_BUILD_FLAT=y +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +# CONFIG_INTELHEX_BINARY is not set +# CONFIG_MOTOROLA_SREC is not set +CONFIG_RAW_BINARY=y +# CONFIG_UBOOT_UIMAGE is not set + +# +# Customize Header Files +# +# CONFIG_ARCH_STDINT_H is not set +# CONFIG_ARCH_STDBOOL_H is not set +# CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_FLOAT_H is not set +# CONFIG_ARCH_STDARG_H is not set +# CONFIG_ARCH_DEBUG_H is not set + +# +# Debug Options +# +CONFIG_DEBUG_ALERT=y +CONFIG_DEBUG_FEATURES=y + +# +# Debug SYSLOG Output Controls +# +CONFIG_DEBUG_ERROR=y +CONFIG_DEBUG_WARN=y +CONFIG_DEBUG_INFO=y +CONFIG_DEBUG_ASSERTIONS=y + +# +# Subsystem Debug Options +# +# CONFIG_DEBUG_BINFMT is not set +# CONFIG_DEBUG_FS is not set +# CONFIG_DEBUG_GRAPHICS is not set +# CONFIG_DEBUG_LIB is not set +# CONFIG_DEBUG_MM is not set +# CONFIG_DEBUG_SCHED is not set + +# +# OS Function Debug Options +# +# CONFIG_DEBUG_DMA is not set +# CONFIG_DEBUG_IRQ is not set + +# +# Driver Debug Options +# +# CONFIG_DEBUG_LEDS is not set +# CONFIG_DEBUG_ANALOG is not set +# CONFIG_DEBUG_GPIO is not set +# CONFIG_DEBUG_I2C is not set +# CONFIG_DEBUG_RTC is not set +# CONFIG_DEBUG_SPI is not set +# CONFIG_DEBUG_TIMER is not set +CONFIG_ARCH_HAVE_STACKCHECK=y +CONFIG_STACK_COLORATION=y +CONFIG_ARCH_HAVE_HEAPCHECK=y +# CONFIG_HEAP_COLORATION is not set +CONFIG_DEBUG_SYMBOLS=y +CONFIG_ARCH_HAVE_CUSTOMOPT=y +CONFIG_DEBUG_NOOPT=y +# CONFIG_DEBUG_CUSTOMOPT is not set +# CONFIG_DEBUG_FULLOPT is not set + +# +# System Type +# +CONFIG_ARCH_ARM=y +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_MISOC is not set +# CONFIG_ARCH_RENESAS is not set +# CONFIG_ARCH_RISCV is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_XTENSA is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="arm" + +# +# ARM Options +# +# CONFIG_ARCH_CHIP_A1X is not set +# CONFIG_ARCH_CHIP_C5471 is not set +# CONFIG_ARCH_CHIP_DM320 is not set +# CONFIG_ARCH_CHIP_EFM32 is not set +# CONFIG_ARCH_CHIP_IMX1 is not set +# CONFIG_ARCH_CHIP_IMX6 is not set +# CONFIG_ARCH_CHIP_KINETIS is not set +# CONFIG_ARCH_CHIP_KL is not set +# CONFIG_ARCH_CHIP_LM is not set +# CONFIG_ARCH_CHIP_TIVA is not set +# CONFIG_ARCH_CHIP_LPC11XX is not set +# CONFIG_ARCH_CHIP_LPC17XX is not set +# CONFIG_ARCH_CHIP_LPC214X is not set +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_NUC1XX is not set +# CONFIG_ARCH_CHIP_SAMA5 is not set +# CONFIG_ARCH_CHIP_SAMD is not set +# CONFIG_ARCH_CHIP_SAML is not set +# CONFIG_ARCH_CHIP_SAM34 is not set +# CONFIG_ARCH_CHIP_SAMV7 is not set +# CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set +# CONFIG_ARCH_CHIP_STM32F7 is not set +CONFIG_ARCH_CHIP_STM32L4=y +# CONFIG_ARCH_CHIP_STR71X is not set +# CONFIG_ARCH_CHIP_TMS570 is not set +# CONFIG_ARCH_CHIP_XMC4 is not set +# CONFIG_ARCH_ARM7TDMI is not set +# CONFIG_ARCH_ARM926EJS is not set +# CONFIG_ARCH_ARM920T is not set +# CONFIG_ARCH_CORTEXM0 is not set +# CONFIG_ARCH_CORTEXM23 is not set +# CONFIG_ARCH_CORTEXM3 is not set +# CONFIG_ARCH_CORTEXM33 is not set +CONFIG_ARCH_CORTEXM4=y +# CONFIG_ARCH_CORTEXM7 is not set +# CONFIG_ARCH_CORTEXA5 is not set +# CONFIG_ARCH_CORTEXA8 is not set +# CONFIG_ARCH_CORTEXA9 is not set +# CONFIG_ARCH_CORTEXR4 is not set +# CONFIG_ARCH_CORTEXR4F is not set +# CONFIG_ARCH_CORTEXR5 is not set +# CONFIG_ARCH_CORTEX5F is not set +# CONFIG_ARCH_CORTEXR7 is not set +# CONFIG_ARCH_CORTEXR7F is not set +CONFIG_ARCH_FAMILY="armv7-m" +CONFIG_ARCH_CHIP="stm32l4" +# CONFIG_ARM_TOOLCHAIN_IAR is not set +CONFIG_ARM_TOOLCHAIN_GNU=y +# CONFIG_ARMV7M_USEBASEPRI is not set +CONFIG_ARCH_HAVE_CMNVECTOR=y +CONFIG_ARMV7M_CMNVECTOR=y +# CONFIG_ARMV7M_LAZYFPU is not set +CONFIG_ARCH_HAVE_FPU=y +CONFIG_ARCH_HAVE_DPFPU=y +# CONFIG_ARCH_FPU is not set +# CONFIG_ARCH_HAVE_TRUSTZONE is not set +CONFIG_ARM_HAVE_MPU_UNIFIED=y +# CONFIG_ARM_MPU is not set +# CONFIG_DEBUG_HARDFAULT is not set + +# +# ARMV7M Configuration Options +# +# CONFIG_ARMV7M_HAVE_ICACHE is not set +# CONFIG_ARMV7M_HAVE_DCACHE is not set +CONFIG_ARMV7M_HAVE_ITCM=y +CONFIG_ARMV7M_HAVE_DTCM=y +# CONFIG_ARMV7M_ITCM is not set +# CONFIG_ARMV7M_DTCM is not set +# CONFIG_ARMV7M_TOOLCHAIN_IARL is not set +# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set +# CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set +CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL=y +# CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL is not set +CONFIG_ARMV7M_HAVE_STACKCHECK=y +CONFIG_ARMV7M_STACKCHECK=y +# CONFIG_ARMV7M_ITMSYSLOG is not set +CONFIG_SERIAL_TERMIOS=y +# CONFIG_USART2_RS485 is not set +# CONFIG_USART2_RXDMA is not set +# CONFIG_USART3_RS485 is not set +# CONFIG_USART3_RXDMA is not set +# CONFIG_SERIAL_DISABLE_REORDERING is not set + +# +# STM32L4 Configuration Options +# +# CONFIG_ARCH_CHIP_STM32L432KB is not set +# CONFIG_ARCH_CHIP_STM32L432KC is not set +# CONFIG_ARCH_CHIP_STM32L442KC is not set +# CONFIG_ARCH_CHIP_STM32L451CC is not set +# CONFIG_ARCH_CHIP_STM32L451CE is not set +# CONFIG_ARCH_CHIP_STM32L451RC is not set +# CONFIG_ARCH_CHIP_STM32L451RE is not set +# CONFIG_ARCH_CHIP_STM32L451VC is not set +# CONFIG_ARCH_CHIP_STM32L451VE is not set +# CONFIG_ARCH_CHIP_STM32L452CC is not set +# CONFIG_ARCH_CHIP_STM32L452CE is not set +# CONFIG_ARCH_CHIP_STM32L452RC is not set +# CONFIG_ARCH_CHIP_STM32L452RE is not set +# CONFIG_ARCH_CHIP_STM32L452VC is not set +# CONFIG_ARCH_CHIP_STM32L452VE is not set +# CONFIG_ARCH_CHIP_STM32L462CE is not set +# CONFIG_ARCH_CHIP_STM32L462RE is not set +# CONFIG_ARCH_CHIP_STM32L462VE is not set +# CONFIG_ARCH_CHIP_STM32L476RG is not set +# CONFIG_ARCH_CHIP_STM32L476RE is not set +# CONFIG_ARCH_CHIP_STM32L486 is not set +# CONFIG_ARCH_CHIP_STM32L496ZE is not set +CONFIG_ARCH_CHIP_STM32L496ZG=y +# CONFIG_ARCH_CHIP_STM32L4A6 is not set +# CONFIG_STM32L4_STM32L4X1 is not set +# CONFIG_STM32L4_STM32L4X2 is not set +# CONFIG_STM32L4_STM32L4X3 is not set +# CONFIG_STM32L4_STM32L4X5 is not set +CONFIG_STM32L4_STM32L4X6=y +# CONFIG_STM32L4_STM32L431XX is not set +# CONFIG_STM32L4_STM32L432XX is not set +# CONFIG_STM32L4_STM32L433XX is not set +# CONFIG_STM32L4_STM32L442XX is not set +# CONFIG_STM32L4_STM32L443XX is not set +# CONFIG_STM32L4_STM32L451XX is not set +# CONFIG_STM32L4_STM32L452XX is not set +# CONFIG_STM32L4_STM32L462XX is not set +# CONFIG_STM32L4_STM32L471XX is not set +# CONFIG_STM32L4_STM32L476XX is not set +# CONFIG_STM32L4_STM32L486XX is not set +CONFIG_STM32L4_STM32L496XX=y +# CONFIG_STM32L4_STM32L4A6XX is not set +CONFIG_STM32L4_FLASH_OVERRIDE_DEFAULT=y +# CONFIG_STM32L4_FLASH_OVERRIDE_B is not set +# CONFIG_STM32L4_FLASH_OVERRIDE_C is not set +# CONFIG_STM32L4_FLASH_OVERRIDE_E is not set +# CONFIG_STM32L4_FLASH_OVERRIDE_G is not set +# CONFIG_STM32L4_FLASH_CONFIG_E is not set +CONFIG_STM32L4_FLASH_CONFIG_G=y +# CONFIG_STM32L4_IO_CONFIG_K is not set +# CONFIG_STM32L4_IO_CONFIG_C is not set +# CONFIG_STM32L4_IO_CONFIG_R is not set +# CONFIG_STM32L4_IO_CONFIG_J is not set +# CONFIG_STM32L4_IO_CONFIG_M is not set +# CONFIG_STM32L4_IO_CONFIG_V is not set +# CONFIG_STM32L4_IO_CONFIG_Q is not set +CONFIG_STM32L4_IO_CONFIG_Z=y +# CONFIG_STM32L4_IO_CONFIG_A is not set + +# +# STM32L4 SRAM2 Options +# +CONFIG_STM32L4_SRAM2_HEAP=y +CONFIG_STM32L4_SRAM2_INIT=y + +# +# STM32L4 Peripherals +# + +# +# STM32L4 Peripheral Support +# +CONFIG_STM32L4_HAVE_ADC2=y +CONFIG_STM32L4_HAVE_ADC3=y +# CONFIG_STM32L4_HAVE_AES is not set +CONFIG_STM32L4_HAVE_CAN2=y +CONFIG_STM32L4_HAVE_COMP=y +CONFIG_STM32L4_HAVE_DAC2=y +CONFIG_STM32L4_HAVE_DCMI=y +CONFIG_STM32L4_HAVE_DFSDM1=y +CONFIG_STM32L4_HAVE_DMA2D=y +# CONFIG_STM32L4_HAVE_HASH is not set +CONFIG_STM32L4_HAVE_I2C4=y +CONFIG_STM32L4_HAVE_LCD=y +# CONFIG_STM32L4_HAVE_LTDC is not set +CONFIG_STM32L4_HAVE_LPTIM1=y +CONFIG_STM32L4_HAVE_LPTIM2=y +CONFIG_STM32L4_HAVE_OTGFS=y +CONFIG_STM32L4_HAVE_SAI1=y +CONFIG_STM32L4_HAVE_SAI2=y +CONFIG_STM32L4_HAVE_SDMMC1=y +CONFIG_STM32L4_HAVE_TIM3=y +CONFIG_STM32L4_HAVE_TIM7=y +CONFIG_STM32L4_ADC=y +# CONFIG_STM32L4_CAN is not set +# CONFIG_STM32L4_DAC is not set +CONFIG_STM32L4_DMA=y +CONFIG_STM32L4_I2C=y +# CONFIG_STM32L4_SAI is not set +CONFIG_STM32L4_SPI=y +CONFIG_STM32L4_USART=y +# CONFIG_STM32L4_LPTIM is not set + +# +# AHB1 Peripherals +# +CONFIG_STM32L4_DMA1=y +CONFIG_STM32L4_DMA2=y +# CONFIG_STM32L4_CRC is not set +# CONFIG_STM32L4_TSC is not set + +# +# AHB2 Peripherals +# +CONFIG_STM32L4_OTGFS=y +CONFIG_STM32L4_ADC1=y +# CONFIG_STM32L4_ADC2 is not set +# CONFIG_STM32L4_ADC3 is not set +# CONFIG_STM32L4_DCMI is not set +# CONFIG_STM32L4_DMA2D is not set +CONFIG_STM32L4_RNG=y +# CONFIG_STM32L4_SAI1_A is not set +# CONFIG_STM32L4_SAI1_B is not set +# CONFIG_STM32L4_SAI2_A is not set +# CONFIG_STM32L4_SAI2_B is not set + +# +# AHB3 Peripherals +# +# CONFIG_STM32L4_FMC is not set +# CONFIG_STM32L4_QSPI is not set + +# +# APB1 Peripherals +# +CONFIG_STM32L4_PWR=y +# CONFIG_STM32L4_TIM2 is not set +# CONFIG_STM32L4_TIM3 is not set +# CONFIG_STM32L4_TIM4 is not set +# CONFIG_STM32L4_TIM5 is not set +# CONFIG_STM32L4_TIM6 is not set +# CONFIG_STM32L4_TIM7 is not set +# CONFIG_STM32L4_LCD is not set +CONFIG_STM32L4_SPI2=y +CONFIG_STM32L4_SPI3=y +# CONFIG_STM32L4_USART1 is not set +CONFIG_STM32L4_USART2=y +CONFIG_STM32L4_USART3=y +# CONFIG_STM32L4_UART4 is not set +# CONFIG_STM32L4_UART5 is not set +CONFIG_STM32L4_I2C1=y +CONFIG_STM32L4_I2C2=y +CONFIG_STM32L4_I2C3=y +CONFIG_STM32L4_I2C4=y +# CONFIG_STM32L4_CAN1 is not set +# CONFIG_STM32L4_CAN2 is not set +# CONFIG_STM32L4_DAC1 is not set +# CONFIG_STM32L4_DAC2 is not set +# CONFIG_STM32L4_OPAMP is not set +# CONFIG_STM32L4_LPTIM1 is not set +CONFIG_STM32L4_LPUART1=y +# CONFIG_STM32L4_SWPMI is not set +# CONFIG_STM32L4_LPTIM2 is not set + +# +# APB2 Peripherals +# +CONFIG_STM32L4_SYSCFG=y +CONFIG_STM32L4_FIREWALL=y +# CONFIG_STM32L4_SDMMC1 is not set +# CONFIG_STM32L4_TIM1 is not set +CONFIG_STM32L4_SPI1=y +# CONFIG_STM32L4_TIM8 is not set +# CONFIG_STM32L4_TIM15 is not set +# CONFIG_STM32L4_TIM16 is not set +# CONFIG_STM32L4_TIM17 is not set +# CONFIG_STM32L4_COMP is not set +# CONFIG_STM32L4_SAI1 is not set +# CONFIG_STM32L4_SAI2 is not set +# CONFIG_STM32L4_DFSDM1 is not set + +# +# Other Peripherals +# +# CONFIG_STM32L4_BKPSRAM is not set +# CONFIG_STM32L4_IWDG is not set +# CONFIG_STM32L4_WWDG is not set +CONFIG_STM32L4_FLASH_PREFETCH=y +CONFIG_STM32L4_DISABLE_IDLE_SLEEP_DURING_DEBUG=y +# CONFIG_ARCH_BOARD_STM32L4_CUSTOM_CLOCKCONFIG is not set +CONFIG_STM32L4_RTC_LSECLOCK=y +# CONFIG_STM32L4_RTC_LSICLOCK is not set +# CONFIG_STM32L4_RTC_HSECLOCK is not set +CONFIG_STM32L4_SAI1PLL=y +# CONFIG_STM32L4_SAI2PLL is not set + +# +# Timer Configuration +# +# CONFIG_STM32L4_ONESHOT is not set +# CONFIG_STM32L4_FREERUN is not set +# CONFIG_STM32L4_TIM3_CAP is not set + +# +# ADC Configuration +# +CONFIG_STM32L4_HAVE_USART1=y +CONFIG_STM32L4_HAVE_USART2=y +CONFIG_STM32L4_HAVE_USART3=y +CONFIG_STM32L4_HAVE_UART4=y +CONFIG_STM32L4_HAVE_UART5=y + +# +# U[S]ART Configuration +# +# CONFIG_STM32L4_FLOWCONTROL_BROKEN is not set +# CONFIG_STM32L4_USART_BREAKS is not set + +# +# SPI Configuration +# +# CONFIG_STM32L4_SPI_INTERRUPTS is not set +# CONFIG_STM32L4_SPI_DMA is not set + +# +# I2C Configuration +# +# CONFIG_STM32L4_I2C_DYNTIMEO is not set +CONFIG_STM32L4_I2CTIMEOSEC=0 +CONFIG_STM32L4_I2CTIMEOMS=500 +CONFIG_STM32L4_I2CTIMEOTICKS=500 +# CONFIG_STM32L4_I2C_DUTY16_9 is not set + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_VECNOTIRQ is not set +CONFIG_ARCH_DMA=y +CONFIG_ARCH_HAVE_IRQPRIO=y +# CONFIG_ARCH_L2CACHE is not set +# CONFIG_ARCH_HAVE_COHERENT_DCACHE is not set +# CONFIG_ARCH_HAVE_ADDRENV is not set +# CONFIG_ARCH_NEED_ADDRENV_MAPPING is not set +# CONFIG_ARCH_HAVE_MULTICPU is not set +CONFIG_ARCH_HAVE_VFORK=y +# CONFIG_ARCH_HAVE_MMU is not set +CONFIG_ARCH_HAVE_MPU=y +# CONFIG_ARCH_NAND_HWECC is not set +# CONFIG_ARCH_HAVE_EXTCLK is not set +# CONFIG_ARCH_HAVE_POWEROFF is not set +CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set +# CONFIG_ARCH_USE_MPU is not set +# CONFIG_ARCH_IRQPRIO is not set +CONFIG_ARCH_STACKDUMP=y +# CONFIG_ENDIAN_BIG is not set +# CONFIG_ARCH_IDLE_CUSTOM is not set +# CONFIG_ARCH_HAVE_RAMFUNCS is not set +CONFIG_ARCH_HAVE_RAMVECTORS=y +# CONFIG_ARCH_RAMVECTORS is not set +# CONFIG_ARCH_MINIMAL_VECTORTABLE is not set + +# +# Board Settings +# +CONFIG_BOARD_LOOPSPERMSEC=8499 +# CONFIG_ARCH_CALIBRATION is not set + +# +# Interrupt options +# +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y +CONFIG_ARCH_INTERRUPTSTACK=2048 +CONFIG_ARCH_HAVE_HIPRI_INTERRUPT=y +# CONFIG_ARCH_HIPRI_INTERRUPT is not set + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Boot Memory Configuration +# +CONFIG_RAM_START=0x20000000 +CONFIG_RAM_SIZE=98304 +# CONFIG_ARCH_HAVE_SDRAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_NUCLEO_L496ZG=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="nucleo-l496zg" + +# +# Common Board Options +# +CONFIG_ARCH_HAVE_LEDS=y +CONFIG_ARCH_LEDS=y +CONFIG_ARCH_HAVE_BUTTONS=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_HAVE_IRQBUTTONS=y +CONFIG_ARCH_IRQBUTTONS=y + +# +# Board-Specific Options +# +# CONFIG_BOARD_CRASHDUMP is not set +CONFIG_LIB_BOARDCTL=y +# CONFIG_BOARDCTL_RESET is not set +# CONFIG_BOARDCTL_UNIQUEID is not set +# CONFIG_BOARDCTL_TSCTEST is not set +# CONFIG_BOARDCTL_GRAPHICS is not set +# CONFIG_BOARDCTL_IOCTL is not set + +# +# RTOS Features +# +CONFIG_DISABLE_OS_API=y +# CONFIG_DISABLE_POSIX_TIMERS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_DISABLE_SIGNALS is not set +# CONFIG_DISABLE_MQUEUE is not set +# CONFIG_DISABLE_ENVIRON is not set + +# +# Clocks and Timers +# +CONFIG_ARCH_HAVE_TICKLESS=y +# CONFIG_SCHED_TICKLESS is not set +CONFIG_USEC_PER_TICK=10000 +# CONFIG_SYSTEM_TIME64 is not set +# CONFIG_CLOCK_MONOTONIC is not set +# CONFIG_ARCH_HAVE_TIMEKEEPING is not set +# CONFIG_JULIAN_TIME is not set +CONFIG_START_YEAR=2017 +CONFIG_START_MONTH=1 +CONFIG_START_DAY=1 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=8 +CONFIG_WDOG_INTRESERVE=1 +CONFIG_PREALLOC_TIMERS=4 + +# +# Tasks and Scheduling +# +# CONFIG_SPINLOCK is not set +# CONFIG_INIT_NONE is not set +CONFIG_INIT_ENTRYPOINT=y +# CONFIG_INIT_FILEPATH is not set +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_RR_INTERVAL=200 +# CONFIG_SCHED_SPORADIC is not set +CONFIG_TASK_NAME_SIZE=0 +CONFIG_MAX_TASKS=16 +# CONFIG_SCHED_HAVE_PARENT is not set +CONFIG_SCHED_WAITPID=y + +# +# Pthread Options +# +# CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set +CONFIG_NPTHREAD_KEYS=4 +# CONFIG_PTHREAD_CLEANUP is not set +# CONFIG_CANCELLATION_POINTS is not set + +# +# Performance Monitoring +# +# CONFIG_SCHED_CPULOAD is not set +# CONFIG_SCHED_INSTRUMENTATION is not set + +# +# Files and I/O +# +CONFIG_DEV_CONSOLE=y +# CONFIG_FDCLONE_DISABLE is not set +# CONFIG_FDCLONE_STDIO is not set +CONFIG_SDCLONE_DISABLE=y +CONFIG_NFILE_DESCRIPTORS=8 +CONFIG_NFILE_STREAMS=8 +CONFIG_NAME_MAX=32 +# CONFIG_PRIORITY_INHERITANCE is not set + +# +# RTOS hooks +# +# CONFIG_BOARD_INITIALIZE is not set +# CONFIG_SCHED_STARTHOOK is not set +# CONFIG_SCHED_ATEXIT is not set +# CONFIG_SCHED_ONEXIT is not set + +# +# Signal Numbers +# +CONFIG_SIG_SIGUSR1=1 +CONFIG_SIG_SIGUSR2=2 +CONFIG_SIG_SIGALARM=3 +CONFIG_SIG_SIGCONDTIMEDOUT=16 + +# +# POSIX Message Queue Options +# +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_MQ_MAXMSGSIZE=32 +# CONFIG_MODULE is not set + +# +# Work queue support +# +# CONFIG_SCHED_WORKQUEUE is not set +# CONFIG_SCHED_HPWORK is not set +# CONFIG_SCHED_LPWORK is not set + +# +# Stack and heap information +# +CONFIG_IDLETHREAD_STACKSIZE=1024 +CONFIG_USERMAIN_STACKSIZE=2048 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=2048 +# CONFIG_LIB_SYSCALL is not set + +# +# Device Drivers +# +CONFIG_DISABLE_POLL=y +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +CONFIG_ARCH_HAVE_RNG=y +CONFIG_DEV_RANDOM=y +# CONFIG_DEV_URANDOM is not set +# CONFIG_DEV_LOOP is not set + +# +# Buffering +# + +# +# Common I/O Buffer Support +# +# CONFIG_DRIVERS_IOB is not set +# CONFIG_DRVR_WRITEBUFFER is not set +# CONFIG_DRVR_READAHEAD is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_ARCH_HAVE_PWM_PULSECOUNT is not set +# CONFIG_ARCH_HAVE_PWM_MULTICHAN is not set +# CONFIG_PWM is not set +CONFIG_ARCH_HAVE_I2CRESET=y +CONFIG_I2C=y +# CONFIG_I2C_SLAVE is not set +# CONFIG_I2C_POLLED is not set +CONFIG_I2C_RESET=y +# CONFIG_I2C_TRACE is not set +CONFIG_I2C_DRIVER=y +# CONFIG_ARCH_HAVE_SPI_CRCGENERATION is not set +# CONFIG_ARCH_HAVE_SPI_CS_CONTROL is not set +CONFIG_ARCH_HAVE_SPI_BITORDER=y +CONFIG_SPI=y +# CONFIG_SPI_SLAVE is not set +CONFIG_SPI_EXCHANGE=y +# CONFIG_SPI_CMDDATA is not set +# CONFIG_SPI_CALLBACK is not set +# CONFIG_SPI_HWFEATURES is not set +# CONFIG_SPI_BITORDER is not set +# CONFIG_SPI_CS_DELAY_CONTROL is not set +# CONFIG_SPI_DRIVER is not set +# CONFIG_SPI_BITBANG is not set +# CONFIG_I2S is not set + +# +# Timer Driver Support +# +# CONFIG_TIMER is not set +# CONFIG_ONESHOT is not set +CONFIG_RTC=y +CONFIG_RTC_DATETIME=y +CONFIG_RTC_ALARM=y +CONFIG_RTC_NALARMS=2 +CONFIG_RTC_DRIVER=y +CONFIG_RTC_IOCTL=y +# CONFIG_RTC_EXTERNAL is not set +# CONFIG_WATCHDOG is not set +# CONFIG_TIMERS_CS2100CP is not set +CONFIG_ANALOG=y +# CONFIG_ADC is not set +# CONFIG_COMP is not set +# CONFIG_DAC is not set +# CONFIG_AUDIO_DEVICES is not set +# CONFIG_VIDEO_DEVICES is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set + +# +# IO Expander/GPIO Support +# +# CONFIG_IOEXPANDER is not set +# CONFIG_DEV_GPIO is not set + +# +# LCD Driver Support +# +# CONFIG_LCD is not set +# CONFIG_SLCD is not set + +# +# LED Support +# +# CONFIG_USERLED is not set +# CONFIG_RGBLED is not set +# CONFIG_PCA9635PW is not set +# CONFIG_NCP5623C is not set +# CONFIG_MMCSD is not set +# CONFIG_MODEM is not set +# CONFIG_MTD is not set +# CONFIG_EEPROM is not set +# CONFIG_PIPES is not set +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +CONFIG_SERIAL=y +# CONFIG_DEV_LOWCONSOLE is not set +# CONFIG_SERIAL_REMOVABLE is not set +CONFIG_SERIAL_CONSOLE=y +# CONFIG_16550_UART is not set +# CONFIG_UART_SERIALDRIVER is not set +# CONFIG_UART0_SERIALDRIVER is not set +# CONFIG_UART1_SERIALDRIVER is not set +# CONFIG_UART2_SERIALDRIVER is not set +# CONFIG_UART3_SERIALDRIVER is not set +# CONFIG_UART4_SERIALDRIVER is not set +# CONFIG_UART5_SERIALDRIVER is not set +# CONFIG_UART6_SERIALDRIVER is not set +# CONFIG_UART7_SERIALDRIVER is not set +# CONFIG_UART8_SERIALDRIVER is not set +# CONFIG_SCI0_SERIALDRIVER is not set +# CONFIG_SCI1_SERIALDRIVER is not set +# CONFIG_USART0_SERIALDRIVER is not set +# CONFIG_USART1_SERIALDRIVER is not set +CONFIG_USART2_SERIALDRIVER=y +CONFIG_USART3_SERIALDRIVER=y +# CONFIG_USART4_SERIALDRIVER is not set +# CONFIG_USART5_SERIALDRIVER is not set +# CONFIG_USART6_SERIALDRIVER is not set +# CONFIG_USART7_SERIALDRIVER is not set +# CONFIG_USART8_SERIALDRIVER is not set +# CONFIG_OTHER_UART_SERIALDRIVER is not set +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +# CONFIG_SERIAL_IFLOWCONTROL is not set +# CONFIG_SERIAL_OFLOWCONTROL is not set +# CONFIG_SERIAL_DMA is not set +# CONFIG_SERIAL_TIOCSERGSTRUCT is not set +CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y +# CONFIG_USART2_SERIAL_CONSOLE is not set +CONFIG_USART3_SERIAL_CONSOLE=y +# CONFIG_OTHER_SERIAL_CONSOLE is not set +# CONFIG_NO_SERIAL_CONSOLE is not set + +# +# USART2 Configuration +# +CONFIG_USART2_RXBUFSIZE=256 +CONFIG_USART2_TXBUFSIZE=256 +CONFIG_USART2_BAUD=115200 +CONFIG_USART2_BITS=8 +CONFIG_USART2_PARITY=0 +CONFIG_USART2_2STOP=0 +# CONFIG_USART2_IFLOWCONTROL is not set +# CONFIG_USART2_OFLOWCONTROL is not set +# CONFIG_USART2_DMA is not set + +# +# USART3 Configuration +# +CONFIG_USART3_RXBUFSIZE=256 +CONFIG_USART3_TXBUFSIZE=256 +CONFIG_USART3_BAUD=115200 +CONFIG_USART3_BITS=8 +CONFIG_USART3_PARITY=0 +CONFIG_USART3_2STOP=0 +# CONFIG_USART3_IFLOWCONTROL is not set +# CONFIG_USART3_OFLOWCONTROL is not set +# CONFIG_USART3_DMA is not set +# CONFIG_PSEUDOTERM is not set +# CONFIG_USBDEV is not set +# CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set +# CONFIG_HAVE_USBTRACE is not set +# CONFIG_DRIVERS_WIRELESS is not set +# CONFIG_DRIVERS_CONTACTLESS is not set + +# +# System Logging +# +# CONFIG_ARCH_SYSLOG is not set +# CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_INTBUFFER is not set +# CONFIG_SYSLOG_TIMESTAMP is not set +CONFIG_SYSLOG_SERIAL_CONSOLE=y +# CONFIG_SYSLOG_CHAR is not set +CONFIG_SYSLOG_CONSOLE=y +# CONFIG_SYSLOG_NONE is not set +# CONFIG_SYSLOG_FILE is not set +# CONFIG_SYSLOG_CHARDEV is not set + +# +# Networking Support +# +# CONFIG_ARCH_HAVE_NET is not set +# CONFIG_ARCH_HAVE_PHY is not set +# CONFIG_NET is not set + +# +# Crypto API +# +# CONFIG_CRYPTO is not set + +# +# File Systems +# + +# +# File system configuration +# +# CONFIG_DISABLE_MOUNTPOINT is not set +# CONFIG_FS_AUTOMOUNTER is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_PSEUDOFS_SOFTLINKS is not set +CONFIG_FS_READABLE=y +# CONFIG_FS_WRITABLE is not set +# CONFIG_FS_NAMED_SEMAPHORES is not set +CONFIG_FS_MQUEUE_MPATH="/var/mqueue" +# CONFIG_FS_RAMMAP is not set +# CONFIG_FS_FAT is not set +# CONFIG_FS_NXFFS is not set +# CONFIG_FS_ROMFS is not set +# CONFIG_FS_TMPFS is not set +# CONFIG_FS_SMARTFS is not set +# CONFIG_FS_BINFS is not set +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_REGISTER=y + +# +# Exclude individual procfs entries +# +# CONFIG_FS_PROCFS_EXCLUDE_PROCESS is not set +# CONFIG_FS_PROCFS_EXCLUDE_UPTIME is not set +# CONFIG_FS_PROCFS_EXCLUDE_MOUNTS is not set +# CONFIG_FS_UNIONFS is not set + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=2 +# CONFIG_ARCH_HAVE_HEAP2 is not set +# CONFIG_GRAN is not set + +# +# Audio Support +# +# CONFIG_AUDIO is not set + +# +# Wireless Support +# + +# +# Binary Loader +# +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_BINFMT_EXEPATH is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +CONFIG_BUILTIN=y +# CONFIG_PIC is not set +# CONFIG_SYMTAB_ORDEREDBYNAME is not set + +# +# Library Routines +# + +# +# Standard C Library Options +# + +# +# Standard C I/O +# +# CONFIG_STDIO_DISABLE_BUFFERING is not set +CONFIG_STDIO_BUFFER_SIZE=64 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +# CONFIG_NOPRINTF_FIELDWIDTH is not set +# CONFIG_LIBC_FLOATINGPOINT is not set +CONFIG_LIBC_LONG_LONG=y +# CONFIG_LIBC_SCANSET is not set +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_MEMCPY_VIK is not set +# CONFIG_LIBM is not set + +# +# Architecture-Specific Support +# +CONFIG_ARCH_LOWPUTC=y +# CONFIG_ARCH_ROMGETC is not set +# CONFIG_LIBC_ARCH_MEMCPY is not set +# CONFIG_LIBC_ARCH_MEMCMP is not set +# CONFIG_LIBC_ARCH_MEMMOVE is not set +# CONFIG_LIBC_ARCH_MEMSET is not set +# CONFIG_LIBC_ARCH_STRCHR is not set +# CONFIG_LIBC_ARCH_STRCMP is not set +# CONFIG_LIBC_ARCH_STRCPY is not set +# CONFIG_LIBC_ARCH_STRNCPY is not set +# CONFIG_LIBC_ARCH_STRLEN is not set +# CONFIG_LIBC_ARCH_STRNLEN is not set +# CONFIG_LIBC_ARCH_ELF is not set +# CONFIG_ARMV7M_MEMCPY is not set + +# +# stdlib Options +# +CONFIG_LIB_RAND_ORDER=1 +CONFIG_LIB_HOMEDIR="/" + +# +# Program Execution Options +# +# CONFIG_LIBC_EXECFUNCS is not set +CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024 +CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=2048 + +# +# errno Decode Support +# +# CONFIG_LIBC_STRERROR is not set +# CONFIG_LIBC_PERROR_STDOUT is not set + +# +# memcpy/memset Options +# +# CONFIG_MEMSET_OPTSPEED is not set +# CONFIG_LIBC_DLLFCN is not set +# CONFIG_LIBC_MODLIB is not set +# CONFIG_LIBC_WCHAR is not set +# CONFIG_LIBC_LOCALE is not set + +# +# Time/Time Zone Support +# +# CONFIG_LIBC_LOCALTIME is not set +# CONFIG_TIME_EXTENDED is not set +CONFIG_ARCH_HAVE_TLS=y + +# +# Thread Local Storage (TLS) +# +# CONFIG_TLS is not set + +# +# Network-Related Options +# +# CONFIG_LIBC_IPv4_ADDRCONV is not set +# CONFIG_LIBC_IPv6_ADDRCONV is not set +# CONFIG_LIBC_NETDB is not set + +# +# NETDB Support +# +# CONFIG_NETDB_HOSTFILE is not set +# CONFIG_LIBC_IOCTL_VARIADIC is not set +CONFIG_LIB_SENDFILE_BUFSIZE=512 + +# +# Non-standard Library Support +# +# CONFIG_LIB_CRC64_FAST is not set +# CONFIG_LIB_KBDCODEC is not set +# CONFIG_LIB_SLCDCODEC is not set +# CONFIG_LIB_HEX2BIN is not set + +# +# Basic CXX Support +# +# CONFIG_C99_BOOL8 is not set +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +# CONFIG_CXX_NEWLONG is not set + +# +# LLVM C++ Library (libcxx) +# +# CONFIG_LIBCXX is not set + +# +# uClibc++ Standard C++ Library +# +# CONFIG_UCLIBCXX is not set + +# +# Application Configuration +# + +# +# Built-In Applications +# +CONFIG_BUILTIN_PROXY_STACKSIZE=1024 + +# +# CAN Utilities +# + +# +# Examples +# +CONFIG_EXAMPLES_ALARM=y +CONFIG_EXAMPLES_ALARM_PRIORITY=100 +CONFIG_EXAMPLES_ALARM_STACKSIZE=2048 +CONFIG_EXAMPLES_ALARM_DEVPATH="/dev/rtc0" +CONFIG_EXAMPLES_ALARM_SIGNO=1 +# CONFIG_EXAMPLES_BUTTONS is not set +# CONFIG_EXAMPLES_CCTYPE is not set +# CONFIG_EXAMPLES_CHAT is not set +# CONFIG_EXAMPLES_CONFIGDATA is not set +# CONFIG_EXAMPLES_CXXTEST is not set +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HELLOXX is not set +# CONFIG_EXAMPLES_HIDKBD is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_JSON is not set +# CONFIG_EXAMPLES_KEYPADTEST is not set +# CONFIG_EXAMPLES_MEDIA is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MODBUS is not set +# CONFIG_EXAMPLES_MOUNT is not set +CONFIG_EXAMPLES_NSH=y +CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXLINES is not set +# CONFIG_EXAMPLES_NXTERM is not set +# CONFIG_EXAMPLES_NXTEXT is not set +CONFIG_EXAMPLES_OSTEST=y +CONFIG_EXAMPLES_OSTEST_LOOPS=1 +CONFIG_EXAMPLES_OSTEST_STACKSIZE=8192 +CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=8 +CONFIG_EXAMPLES_OSTEST_RR_RANGE=10000 +CONFIG_EXAMPLES_OSTEST_RR_RUNS=10 +CONFIG_EXAMPLES_OSTEST_WAITRESULT=y +# CONFIG_EXAMPLES_PCA9635 is not set +# CONFIG_EXAMPLES_POSIXSPAWN is not set +# CONFIG_EXAMPLES_PPPD is not set +CONFIG_EXAMPLES_RANDOM=y +CONFIG_EXAMPLES_MAXSAMPLES=64 +CONFIG_EXAMPLES_NSAMPLES=8 +# CONFIG_EXAMPLES_RFID_READUID is not set +# CONFIG_EXAMPLES_RGBLED is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERIALBLASTER is not set +# CONFIG_EXAMPLES_SERIALRX is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_SLCD is not set +# CONFIG_EXAMPLES_SMART is not set +# CONFIG_EXAMPLES_SMART_TEST is not set +# CONFIG_EXAMPLES_SMP is not set +# CONFIG_EXAMPLES_STAT is not set +# CONFIG_EXAMPLES_TCPECHO is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_USBSERIAL is not set +# CONFIG_EXAMPLES_WATCHDOG is not set +# CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set + +# +# File System Utilities +# +# CONFIG_FSUTILS_INIFILE is not set +# CONFIG_FSUTILS_PASSWD is not set + +# +# GPS Utilities +# +# CONFIG_GPSUTILS_MINMEA_LIB is not set + +# +# Graphics Support +# +# CONFIG_TIFF is not set +# CONFIG_GRAPHICS_TRAVELER is not set + +# +# Interpreters +# +# CONFIG_INTERPRETERS_BAS is not set +# CONFIG_INTERPRETERS_FICL is not set +# CONFIG_INTERPRETERS_MICROPYTHON is not set +# CONFIG_INTERPRETERS_MINIBASIC is not set +# CONFIG_INTERPRETERS_PCODE is not set + +# +# FreeModBus +# +# CONFIG_MODBUS is not set + +# +# Network Utilities +# +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_ESP8266 is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_JSON is not set +# CONFIG_NETUTILS_SMTP is not set + +# +# NSH Library +# +CONFIG_NSH_LIBRARY=y +# CONFIG_NSH_MOTD is not set + +# +# Command Line Configuration +# +CONFIG_NSH_READLINE=y +# CONFIG_NSH_CLE is not set +CONFIG_NSH_LINELEN=64 +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_CMDPARMS is not set +CONFIG_NSH_MAXARGUMENTS=6 +# CONFIG_NSH_ARGCAT is not set +CONFIG_NSH_NESTDEPTH=3 +# CONFIG_NSH_DISABLEBG is not set +CONFIG_NSH_BUILTIN_APPS=y + +# +# Disable Individual commands +# +# CONFIG_NSH_DISABLE_ADDROUTE is not set +# CONFIG_NSH_DISABLE_BASENAME is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_CMP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_DD is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_DELROUTE is not set +# CONFIG_NSH_DISABLE_DIRNAME is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_HEXDUMP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +CONFIG_NSH_DISABLE_IFUPDOWN=y +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOSETUP is not set +CONFIG_NSH_DISABLE_LOSMART=y +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MB is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKRD is not set +# CONFIG_NSH_DISABLE_MH is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_MW is not set +CONFIG_NSH_DISABLE_PRINTF=y +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set +# CONFIG_NSH_DISABLE_PUT is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SH is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNAME is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +# CONFIG_NSH_DISABLE_WGET is not set +# CONFIG_NSH_DISABLE_XD is not set +CONFIG_NSH_MMCSDMINOR=0 + +# +# Configure Command Options +# +# CONFIG_NSH_CMDOPT_DF_H is not set +# CONFIG_NSH_CMDOPT_DD_STATS is not set +CONFIG_NSH_CODECS_BUFSIZE=128 +CONFIG_NSH_CMDOPT_HEXDUMP=y +CONFIG_NSH_PROC_MOUNTPOINT="/proc" +CONFIG_NSH_FILEIOSIZE=512 + +# +# Scripting Support +# +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_LOOPS is not set + +# +# Console Configuration +# +CONFIG_NSH_CONSOLE=y +# CONFIG_NSH_ALTCONDEV is not set +CONFIG_NSH_ARCHINIT=y +# CONFIG_NSH_LOGIN is not set +# CONFIG_NSH_CONSOLE_LOGIN is not set + +# +# NxWidgets/NxWM +# + +# +# Platform-specific Support +# +# CONFIG_PLATFORM_CONFIGDATA is not set + +# +# System Libraries and NSH Add-Ons +# +# CONFIG_SYSTEM_CLE is not set +# CONFIG_SYSTEM_CUTERM is not set +# CONFIG_SYSTEM_FREE is not set +# CONFIG_SYSTEM_HEX2BIN is not set +# CONFIG_SYSTEM_HEXED is not set +CONFIG_SYSTEM_I2CTOOL=y +CONFIG_I2CTOOL_MINBUS=0 +CONFIG_I2CTOOL_MAXBUS=3 +CONFIG_I2CTOOL_MINADDR=0x03 +CONFIG_I2CTOOL_MAXADDR=0x77 +CONFIG_I2CTOOL_MAXREGADDR=0xff +CONFIG_I2CTOOL_DEFFREQ=400000 +# CONFIG_SYSTEM_INSTALL is not set +# CONFIG_SYSTEM_RAMTEST is not set +CONFIG_READLINE_HAVE_EXTMATCH=y +CONFIG_SYSTEM_READLINE=y +CONFIG_READLINE_ECHO=y +CONFIG_READLINE_TABCOMPLETION=y +CONFIG_READLINE_MAX_BUILTINS=64 +CONFIG_READLINE_MAX_EXTCMDS=64 +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_READLINE_CMD_HISTORY_LINELEN=80 +CONFIG_READLINE_CMD_HISTORY_LEN=16 +CONFIG_SYSTEM_STACKMONITOR=y +CONFIG_SYSTEM_STACKMONITOR_STACKSIZE=2048 +CONFIG_SYSTEM_STACKMONITOR_PRIORITY=50 +CONFIG_SYSTEM_STACKMONITOR_INTERVAL=2 +# CONFIG_SYSTEM_SUDOKU is not set +# CONFIG_SYSTEM_SYSTEM is not set +CONFIG_SYSTEM_TEE=y +CONFIG_SYSTEM_TEE_STACKSIZE=1536 +CONFIG_SYSTEM_TEE_PRIORITY=100 +# CONFIG_SYSTEM_UBLOXMODEM is not set +# CONFIG_SYSTEM_VI is not set +# CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# diff --git a/configs/nucleo-l496zg/scripts/kernel-space.ld b/configs/nucleo-l496zg/scripts/kernel-space.ld new file mode 100644 index 0000000000..166d4f0bbc --- /dev/null +++ b/configs/nucleo-l496zg/scripts/kernel-space.ld @@ -0,0 +1,109 @@ +/**************************************************************************** + * configs/nucleo-144/scripts/kernel-space.ld + * + * Copyright (C) 2016 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. + * + ****************************************************************************/ + +/* NOTE: This depends on the memory.ld script having been included prior to + * this script. + */ + +OUTPUT_ARCH(arm) +ENTRY(_stext) +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + } > kflash + + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > kflash + + .ARM.extab : { + *(.ARM.extab*) + } > kflash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > kflash + + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > ksram AT > kflash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + _ebss = ABSOLUTE(.); + } > ksram + + /* Stabs debugging sections */ + + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/configs/nucleo-l496zg/scripts/l496zg-flash.ld b/configs/nucleo-l496zg/scripts/l496zg-flash.ld new file mode 100644 index 0000000000..e4ccd435c7 --- /dev/null +++ b/configs/nucleo-l496zg/scripts/l496zg-flash.ld @@ -0,0 +1,119 @@ +/**************************************************************************** + * configs/nucleo-l496zg/scripts/l496zg-flash.ld + * + * Copyright (C) 2014 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Sebastien Lorquet + * + * 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. + * + ****************************************************************************/ + +/* The STM32L496ZG has 1024Kb of FLASH beginning at address 0x0800:0000 and + * 256Kb of SRAM beginning at address 0x2000:0000. When booting from FLASH, + * FLASH memory is aliased to address 0x0000:0000 where the code expects to + * begin execution by jumping to the entry point in the 0x0800:0000 address + * range. + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x08000000, LENGTH = 1024K + sram (rwx) : ORIGIN = 0x20000000, LENGTH = 256K +} + +OUTPUT_ARCH(arm) +ENTRY(_stext) +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + } > flash + + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + /* The STM32L496ZG has 256Kb of SRAM beginning at the following address */ + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/configs/nucleo-l496zg/scripts/memory.ld b/configs/nucleo-l496zg/scripts/memory.ld new file mode 100644 index 0000000000..2308c38ec8 --- /dev/null +++ b/configs/nucleo-l496zg/scripts/memory.ld @@ -0,0 +1,129 @@ +/**************************************************************************** + * configs/nucleo-144/scripts/memory.ld + * + * Copyright (C) 2016 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. + * + ****************************************************************************/ + +/* The STM32F746NGH6 has 1024Kb of main FLASH memory. This FLASH memory can + * be accessed from either the AXIM interface at address 0x0800:0000 or from + * the ITCM interface at address 0x0020:0000. + * + * Additional information, including the option bytes, is available at at + * FLASH at address 0x1ff0:0000 (AXIM) or 0x0010:0000 (ITCM). + * + * In the STM32F746NGH6, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash on ITCM at 0x0020:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x0010:0000 + * + * NuttX does not modify these option byes. On the unmodified STM32F746G + * DISCO board, the BOOT0 pin is at ground so by default, the STM32 will boot + * to address 0x0020:0000 in ITCM FLASH. + * + * The STM32F746NGH6 also has 320Kb of data SRAM (in addition to ITCM SRAM). + * SRAM is split up into three blocks: + * + * 1) 64Kb of DTCM SRM beginning at address 0x2000:0000 + * 2) 240Kb of SRAM1 beginning at address 0x2001:0000 + * 3) 16Kb of SRAM2 beginning at address 0x2004:c000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + * + * For MPU support, the kernel-mode NuttX section is assumed to be 128Kb of + * FLASH and 4Kb of SRAM. That is an excessive amount for the kernel which + * should fit into 64KB and, of course, can be optimized as needed (See + * also configs/stm32f746g-disco/scripts/kernel-space.ld). Allowing the + * additional does permit addition debug instrumentation to be added to the + * kernel space without overflowing the partition. + * + * Alignment of the user space FLASH partition is also a critical factor: + * The user space FLASH partition will be spanned with a single region of + * size 2**n bytes. The alignment of the user-space region must be the same. + * As a consequence, as the user-space increases in size, the alignment + * requirement also increases. + * + * This alignment requirement means that the largest user space FLASH region + * you can have will be 512KB at it would have to be positioned at + * 0x08800000. If you change this address, don't forget to change the + * CONFIG_NUTTX_USERSPACE configuration setting to match and to modify + * the check in kernel/userspace.c. + * + * For the same reasons, the maximum size of the SRAM mapping is limited to + * 4KB. Both of these alignment limitations could be reduced by using + * multiple regions to map the FLASH/SDRAM range or perhaps with some + * clever use of subregions. + * + * A detailed memory map for the 112KB SRAM region is as follows: + * + * 0x20001 0000: Kernel .data region. Typical size: 0.1KB + * ------- ---- Kernel .bss region. Typical size: 1.8KB + * 0x20001 0800: Kernel IDLE thread stack (approximate). Size is + * determined by CONFIG_IDLETHREAD_STACKSIZE and + * adjustments for alignment. Typical is 1KB. + * ------- ---- Padded to 4KB + * 0x20001 1000: User .data region. Size is variable. + * ------- ---- User .bss region Size is variable. + * 0x20001 2000: Beginning of kernel heap. Size determined by + * CONFIG_MM_KERNEL_HEAPSIZE. + * ------- ---- Beginning of user heap. Can vary with other settings. + * 0x20004 c000: End+1 of SRAM1 + */ + +MEMORY +{ + /* ITCM boot address */ + + itcm (rwx) : ORIGIN = 0x00200000, LENGTH = 1024K + + /* 1024KB FLASH */ + + kflash (rx) : ORIGIN = 0x08000000, LENGTH = 128K + uflash (rx) : ORIGIN = 0x08020000, LENGTH = 128K + xflash (rx) : ORIGIN = 0x08040000, LENGTH = 768K + + /* 240KB of contiguous SRAM1 */ + + ksram (rwx) : ORIGIN = 0x20010000, LENGTH = 4K + usram (rwx) : ORIGIN = 0x20011000, LENGTH = 4K + xsram (rwx) : ORIGIN = 0x20012000, LENGTH = 240K - 8K + + /* DTCM SRAM */ + + dtcm (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + sram2 (rwx) : ORIGIN = 0x2004c000, LENGTH = 16K +} diff --git a/configs/nucleo-l496zg/scripts/user-space.ld b/configs/nucleo-l496zg/scripts/user-space.ld new file mode 100644 index 0000000000..871d8e055f --- /dev/null +++ b/configs/nucleo-l496zg/scripts/user-space.ld @@ -0,0 +1,111 @@ +/**************************************************************************** + * configs/nucleo-144/scripts/user-space.ld + * + * Copyright (C) 2016 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. + * + ****************************************************************************/ + +/* NOTE: This depends on the memory.ld script having been included prior to + * this script. + */ + +OUTPUT_ARCH(arm) +SECTIONS +{ + .userspace : { + *(.userspace) + } > uflash + + .text : { + _stext = ABSOLUTE(.); + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + } > uflash + + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > uflash + + .ARM.extab : { + *(.ARM.extab*) + } > uflash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > uflash + + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > usram AT > uflash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + _ebss = ABSOLUTE(.); + } > usram + + /* Stabs debugging sections */ + + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/configs/nucleo-l496zg/src/.gitignore b/configs/nucleo-l496zg/src/.gitignore new file mode 100644 index 0000000000..726d936e1e --- /dev/null +++ b/configs/nucleo-l496zg/src/.gitignore @@ -0,0 +1,2 @@ +/.depend +/Make.dep diff --git a/configs/nucleo-l496zg/src/Makefile b/configs/nucleo-l496zg/src/Makefile new file mode 100644 index 0000000000..d30f3bc75e --- /dev/null +++ b/configs/nucleo-l496zg/src/Makefile @@ -0,0 +1,72 @@ +############################################################################ +# configs/nucleo-l496zg/src/Makefile +# +# Copyright (C) 2015 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# David Sidrane +# +# 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. +# +############################################################################ + +-include $(TOPDIR)/Make.defs + +ASRCS = +CSRCS = stm32_boot.c + +ifeq ($(CONFIG_ARCH_LEDS),y) +CSRCS += stm32_autoleds.c +else +CSRCS += stm32_userleds.c +endif + +ifeq ($(CONFIG_ARCH_BUTTONS),y) +CSRCS += stm32_buttons.c +endif + +ifeq ($(CONFIG_LIB_BOARDCTL),y) +CSRCS += stm32_appinitialize.c +endif + +ifeq ($(CONFIG_SPI),y) +CSRCS += stm32_spi.c +endif + +ifeq ($(CONFIG_ADC),y) +CSRCS += stm32_adc.c +endif + +ifeq ($(CONFIG_MMCSD),y) +CSRCS += stm32_sdio.c +endif + +ifeq ($(CONFIG_STM32L4_OTGFS),y) +CSRCS += stm32_usb.c +endif + +include $(TOPDIR)/configs/Board.mk diff --git a/configs/nucleo-l496zg/src/nucleo-144.h b/configs/nucleo-l496zg/src/nucleo-144.h new file mode 100644 index 0000000000..fc4bc9381c --- /dev/null +++ b/configs/nucleo-l496zg/src/nucleo-144.h @@ -0,0 +1,285 @@ +/************************************************************************************ + * configs/nucleo-l496zg/src/nucleo-144.h + * + * Copyright (C) 2016 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * Mark Olsson + * David Sidrane + * + * 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 __CONFIGS_NUCLEO_L496ZG_SRC_NUCLEO_144_H +#define __CONFIGS_NUCLEO_L496ZG_SRC_NUCLEO_144_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Configuration ********************************************************************/ + +/* procfs File System */ + +#ifdef CONFIG_FS_PROCFS +# ifdef CONFIG_NSH_PROC_MOUNTPOINT +# define STM32_PROCFS_MOUNTPOINT CONFIG_NSH_PROC_MOUNTPOINT +# else +# define STM32_PROCFS_MOUNTPOINT "/proc" +# endif +#endif + +/* Nucleo-144 GPIO Pin Definitions **************************************************/ +/* LED + * + * The Nucleo-144 board has numerous LEDs but only three, LD1 a Green LED, LD2 a + * Blue LED and LD3 a Red LED, that can be controlled by software. The following definitions assume + * the default Solder Bridges are installed. + */ + +#define GPIO_LD1 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | GPIO_OUTPUT_CLEAR | \ + GPIO_PORTC | GPIO_PIN7) +#define GPIO_LD2 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | GPIO_OUTPUT_CLEAR | \ + GPIO_PORTB | GPIO_PIN7) +#define GPIO_LD3 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | GPIO_OUTPUT_CLEAR | \ + GPIO_PORTB | GPIO_PIN14) + +#define GPIO_LED_GREEN GPIO_LD1 +#define GPIO_LED_BLUE GPIO_LD2 +#define GPIO_LED_RED GPIO_LD3 + +#define LED_DRIVER_PATH "/dev/userleds" + +/* BUTTONS + * + * The Blue pushbutton B1, labeled "User", is connected to GPIO PC13. A high value + * will be sensed when the button is depressed. + * Note: + * 1) That the EXTI is included in the definition to enable an interrupt on this + * IO. + * 2) The following definitions assume the default Solder Bridges are installed. + */ + +#define GPIO_BTN_USER (GPIO_INPUT | GPIO_FLOAT | GPIO_EXTI | GPIO_PORTC | GPIO_PIN13) + +/* SPI ***************************************************************************/ + +#define GPIO_SPI_CS (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | \ + GPIO_OUTPUT_SET) + +#define GPIO_SPI1_CS0 (GPIO_SPI_CS | GPIO_PORTD | GPIO_PIN14) +#define GPIO_SPI1_CS1 (GPIO_SPI_CS | GPIO_PORTC | GPIO_PIN15) +#define GPIO_SPI1_CS2 (GPIO_SPI_CS | GPIO_PORTC | GPIO_PIN14) +#define GPIO_SPI1_CS3 (GPIO_SPI_CS | GPIO_PORTC | GPIO_PIN2) +#define GPIO_SPI2_CS0 (GPIO_SPI_CS | GPIO_PORTD | GPIO_PIN7) +#define GPIO_SPI2_CS1 (GPIO_SPI_CS | GPIO_PORTG | GPIO_PIN1) +#define GPIO_SPI2_CS2 (GPIO_SPI_CS | GPIO_PORTG | GPIO_PIN2) +#define GPIO_SPI2_CS3 (GPIO_SPI_CS | GPIO_PORTG | GPIO_PIN3) +#define GPIO_SPI3_CS0 (GPIO_SPI_CS | GPIO_PORTG | GPIO_PIN4) +#define GPIO_SPI3_CS1 (GPIO_SPI_CS | GPIO_PORTG | GPIO_PIN5) +#define GPIO_SPI3_CS2 (GPIO_SPI_CS | GPIO_PORTG | GPIO_PIN6) +#define GPIO_SPI3_CS3 (GPIO_SPI_CS | GPIO_PORTG | GPIO_PIN7) + +/* Logical SPI Chip Selects used to index */ + +#define NUCLEO_SPI_BUS1_CS0 0 +#define NUCLEO_SPI_BUS1_CS1 1 +#define NUCLEO_SPI_BUS1_CS2 2 +#define NUCLEO_SPI_BUS1_CS3 3 +#define NUCLEO_SPI_BUS2_CS0 4 +#define NUCLEO_SPI_BUS2_CS1 5 +#define NUCLEO_SPI_BUS2_CS2 6 +#define NUCLEO_SPI_BUS2_CS3 7 +#define NUCLEO_SPI_BUS3_CS0 8 +#define NUCLEO_SPI_BUS3_CS1 9 +#define NUCLEO_SPI_BUS3_CS2 10 +#define NUCLEO_SPI_BUS3_CS3 11 + +#if defined(CONFIG_STM32L4_SDMMC1) || defined(CONFIG_STM32L4_SDMMC2) +# define HAVE_SDIO +#endif + +#if defined(CONFIG_DISABLE_MOUNTPOINT) || !defined(CONFIG_MMCSD_SDIO) +# undef HAVE_SDIO +#endif + +#define SDIO_SLOTNO 0 /* Only one slot */ + +#ifdef HAVE_SDIO + +# if defined(CONFIG_STM32L4_SDMMC1) +# define GPIO_SDMMC1_NCD (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI | GPIO_PORTC | GPIO_PIN6) +# endif + +# if defined(CONFIG_NSH_MMCSDSLOTNO) && (CONFIG_NSH_MMCSDSLOTNO != 0) +# warning "Only one MMC/SD slot, slot 0" +# define CONFIG_NSH_MMCSDSLOTNO SDIO_SLOTNO +# endif + +# if defined(CONFIG_NSH_MMCSDMINOR) +# define SDIO_MINOR CONFIG_NSH_MMCSDMINOR +# else +# define SDIO_MINOR 0 +# endif + + /* SD card bringup does not work if performed on the IDLE thread because it + * will cause waiting. Use either: + * + * CONFIG_LIB_BOARDCTL=y, OR + * CONFIG_BOARD_INITIALIZE=y && CONFIG_BOARD_INITTHREAD=y + */ + +# if defined(CONFIG_BOARD_INITIALIZE) && !defined(CONFIG_LIB_BOARDCTL) && \ + !defined(CONFIG_BOARD_INITTHREAD) +# warning SDIO initialization cannot be perfomed on the IDLE thread +# undef HAVE_SDIO +# endif +#endif + +/* USB OTG FS + * + * PA9 OTG_FS_VBUS VBUS sensing (also connected to the green LED) + * PG6 OTG_FS_PowerSwitchOn + * PG5 OTG_FS_Overcurrent + */ + +#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|\ + GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN9) + +#define GPIO_OTGFS_PWRON (GPIO_OUTPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|\ + GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN6) + +#ifdef CONFIG_USBHOST +# define GPIO_OTGFS_OVER (GPIO_INPUT|GPIO_EXTI|GPIO_FLOAT|\ + GPIO_SPEED_100MHz|GPIO_PUSHPULL|\ + GPIO_PORTG|GPIO_PIN5) + +#else +# define GPIO_OTGFS_OVER (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|\ + GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN5) +#endif + +/************************************************************************************ + * Public data + ************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_spidev_initialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the Nucleo-144 board. + * + ************************************************************************************/ + +#if defined(CONFIG_SPI) +void stm32_spidev_initialize(void); +#endif + +/************************************************************************************ + * Name: stm32_spidev_bus_test + * + * Description: + * Called to create the defined SPI buses and test them by initializing them + * and sending the NUCLEO_SPI_TEST (no chip select). + * + ************************************************************************************/ + +#if defined(CONFIG_NUCLEO_SPI_TEST) +int stm32_spidev_bus_test(void); +#endif + +/************************************************************************************ + * Name: stm32_dma_alloc_init + * + * Description: + * Called to create a FAT DMA allocator + * + * Returned Value: + * 0 on success or -ENOMEM + * + ************************************************************************************/ + +void stm32_dma_alloc_init(void); + +#if defined (CONFIG_FAT_DMAMEMORY) +int stm32_dma_alloc_init(void); +#endif + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Called at application startup time to initialize the SCMMC functionality. + * + ****************************************************************************/ + +#ifdef CONFIG_MMCSD +int stm32_sdio_initialize(void); +#endif + +/************************************************************************************ + * Name: stm32_usbinitialize + * + * Description: + * Called from stm32_usbinitialize very early in inialization to setup USB-related + * GPIO pins for the nucleo-144 board. + * + ************************************************************************************/ + +#ifdef CONFIG_STM32L4_OTGFS +void stm32_usbinitialize(void); +#endif + +/************************************************************************************ + * Name: stm32_adc_setup + * + * Description: + * Initialize ADC and register the ADC driver. + * + ************************************************************************************/ + +#ifdef CONFIG_ADC +int stm32_adc_setup(void); +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __CONFIGS_NUCLEO_L496ZG_SRC_NUCLEO_144_H */ diff --git a/configs/nucleo-l496zg/src/stm32_adc.c b/configs/nucleo-l496zg/src/stm32_adc.c new file mode 100644 index 0000000000..250cd58def --- /dev/null +++ b/configs/nucleo-l496zg/src/stm32_adc.c @@ -0,0 +1,174 @@ +/************************************************************************************ + * configs/nucleo-144/src/stm32_adc.c + * + * Copyright (C) 2016 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. + * + ************************************************************************************/ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include + +#include +#include +#include + +#include "chip.h" +#include "stm32l4_gpio.h" +#include "stm32l4_adc.h" +#include "nucleo-144.h" + +#ifdef CONFIG_ADC + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Configuration ********************************************************************/ +/* Up to 3 ADC interfaces are supported */ + +#if STM32L4_NADC < 3 +# undef CONFIG_STM32L4_ADC3 +#endif + +#if STM32L4_NADC < 2 +# undef CONFIG_STM32L4_ADC2 +#endif + +#if STM32L4_NADC < 1 +# undef CONFIG_STM32L4_ADC1 +#endif + +#if defined(CONFIG_STM32L4_ADC1) || defined(CONFIG_STM32L4_ADC2) || defined(CONFIG_STM32L4_ADC3) +#ifndef CONFIG_STM32L4_ADC1 +# warning "Channel information only available for ADC1" +#endif + +/* The number of ADC channels in the conversion list */ + +#define ADC1_NCHANNELS 1 + +/************************************************************************************ + * Private Data + ************************************************************************************/ + +/* Identifying number of each ADC channel: Variable Resistor. + * + * {1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 15}; + */ + +#ifdef CONFIG_STM32L4_ADC1 +static const uint8_t g_chanlist[ADC1_NCHANNELS] = {3}; + +/* Configurations of pins used byte each ADC channels + * + * {GPIO_ADC1_IN1, GPIO_ADC1_IN2, GPIO_ADC1_IN3, GPIO_ADC1_IN4, GPIO_ADC1_IN5, + * GPIO_ADC1_IN6, GPIO_ADC1_IN7, GPIO_ADC1_IN8, GPIO_ADC1_IN9, GPIO_ADC1_IN10, + * GPIO_ADC1_IN11, GPIO_ADC1_IN12, GPIO_ADC1_IN13, GPIO_ADC1_IN15}; + */ + +static const uint32_t g_pinlist[ADC1_NCHANNELS] = {GPIO_ADC1_IN3}; +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_adc_setup + * + * Description: + * Initialize ADC and register the ADC driver. + * + ************************************************************************************/ + +int stm32_adc_setup(void) +{ +#ifdef CONFIG_STM32L4_ADC1 + static bool initialized = false; + struct adc_dev_s *adc; + int ret; + int i; + + /* Check if we have already initialized */ + + if (!initialized) + { + /* Configure the pins as analog inputs for the selected channels */ + + for (i = 0; i < ADC1_NCHANNELS; i++) + { + if (g_pinlist[i] != 0) + { + stm32l4_configgpio(g_pinlist[i]); + } + } + + /* Call stm32_adcinitialize() to get an instance of the ADC interface */ + + adc = stm32l4_adc_initialize(1, g_chanlist, ADC1_NCHANNELS); + if (adc == NULL) + { + aerr("ERROR: Failed to get ADC interface\n"); + return -ENODEV; + } + + /* Register the ADC driver at "/dev/adc0" */ + + ret = adc_register("/dev/adc0", adc); + if (ret < 0) + { + aerr("ERROR: adc_register failed: %d\n", ret); + return ret; + } + + /* Now we are initialized */ + + initialized = true; + } + + return OK; +#else + return -ENOSYS; +#endif +} + +#endif /* CONFIG_STM32L4_ADC1 || CONFIG_STM32L4_ADC2 || CONFIG_STM32L4_ADC3 */ +#endif /* CONFIG_ADC */ diff --git a/configs/nucleo-l496zg/src/stm32_appinitialize.c b/configs/nucleo-l496zg/src/stm32_appinitialize.c new file mode 100644 index 0000000000..677f184b61 --- /dev/null +++ b/configs/nucleo-l496zg/src/stm32_appinitialize.c @@ -0,0 +1,200 @@ +/**************************************************************************** + * config/nucleo-144/src/stm32_appinitialize.c + * + * Copyright (C) 2016 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * Mark Olsson + * David Sidrane + * + * 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 "nucleo-144.h" +#include + +#include "stm32l4_i2c.h" + +/**************************************************************************** + * Private Data + ***************************************************************************/ + +#if defined(CONFIG_STM32L4_I2C1) +struct i2c_master_s* i2c1; +#endif +#if defined(CONFIG_STM32L4_I2C2) +struct i2c_master_s* i2c2; +#endif +#if defined(CONFIG_STM32L4_I2C3) +struct i2c_master_s* i2c3; +#endif +#if defined(CONFIG_STM32L4_I2C4) +struct i2c_master_s* i2c4; +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; the meaning of the argument is a contract + * between the board-specific initalization logic and the the + * matching application logic. The value cold be such things as a + * mode enumeration value, a set of DIP switch switch settings, a + * pointer to configuration data read from a file or serial FLASH, + * or whatever you would like to do with it. Every implementation + * should accept zero/NULL as a default configuration. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ + +int board_app_initialize(uintptr_t arg) +{ + int ret; + +#ifdef CONFIG_FS_PROCFS + /* Mount the procfs file system */ + + ret = mount(NULL, STM32_PROCFS_MOUNTPOINT, "procfs", 0, NULL); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: Failed to mount procfs at %s: %d\n", + STM32_PROCFS_MOUNTPOINT, ret); + } +#endif + +#if !defined(CONFIG_ARCH_LEDS) && defined(CONFIG_USERLED_LOWER) + /* Register the LED driver */ + + ret = userled_lower_initialize(LED_DRIVER_PATH); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: userled_lower_initialize() failed: %d\n", ret); + } +#endif + +#ifdef CONFIG_ADC + /* Initialize ADC and register the ADC driver. */ + + ret = stm32_adc_setup(); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: stm32_adc_setup failed: %d\n", ret); + } +#endif + +#if defined(CONFIG_FAT_DMAMEMORY) + if (stm32_dma_alloc_init() < 0) + { + syslog(LOG_ERR, "DMA alloc FAILED"); + } +#endif + +#if defined(CONFIG_NUCLEO_SPI_TEST) + /* Create SPI interfaces */ + + ret = stm32_spidev_bus_test(); + if (ret != OK) + { + syslog(LOG_ERR, "ERROR: Failed to initialize SPI interfaces: %d\n", ret); + return ret; + } +#endif + +#if defined(CONFIG_MMCSD) + /* Configure SDIO */ + /* Initialize the SDIO block driver */ + + ret = stm32l4_sdio_initialize(); + if (ret != OK) + { + ferr("ERROR: Failed to initialize MMC/SD driver: %d\n", ret); + return ret; + } +#endif + +#if defined(CONFIG_I2C) + /* Configure I2C */ + + /* REVISIT: this is ugly! */ + +#if defined(CONFIG_STM32L4_I2C1) + i2c1 = stm32l4_i2cbus_initialize(1); +#endif +#if defined(CONFIG_STM32L4_I2C2) + i2c2 = stm32l4_i2cbus_initialize(2); +#endif +#if defined(CONFIG_STM32L4_I2C3) + i2c3 = stm32l4_i2cbus_initialize(3); +#endif +#if defined(CONFIG_STM32L4_I2C4) + i2c4 = stm32l4_i2cbus_initialize(4); +#endif +#ifdef CONFIG_I2C_DRIVER +#if defined(CONFIG_STM32L4_I2C1) + i2c_register(i2c1, 1); +#endif +#if defined(CONFIG_STM32L4_I2C2) + i2c_register(i2c2, 2); +#endif +#if defined(CONFIG_STM32L4_I2C3) + i2c_register(i2c3, 3); +#endif +#if defined(CONFIG_STM32L4_I2C4) + i2c_register(i2c4, 4); +#endif +#endif +#endif /* CONFIG_I2C */ + + UNUSED(ret); + return OK; +} diff --git a/configs/nucleo-l496zg/src/stm32_autoleds.c b/configs/nucleo-l496zg/src/stm32_autoleds.c new file mode 100644 index 0000000000..f92b9da855 --- /dev/null +++ b/configs/nucleo-l496zg/src/stm32_autoleds.c @@ -0,0 +1,188 @@ +/**************************************************************************** + * configs/nucleo-144/src/stm32_autoleds.c + * + * Copyright (C) 2016 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * David Sidrane + * + * 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 "stm32l4_gpio.h" +#include "nucleo-144.h" +#ifdef CONFIG_ARCH_LEDS + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define ARRAYSIZE(x) (sizeof((x)) / sizeof((x)[0])) + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* Indexed by BOARD_LED_ */ + +static const uint32_t g_ledmap[BOARD_NLEDS] = +{ + GPIO_LED_GREEN, + GPIO_LED_BLUE, + GPIO_LED_RED, +}; + +static bool g_initialized; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static void phy_set_led(int led, bool state) +{ + /* Active High */ + + stm32l4_gpiowrite(g_ledmap[led], state); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_autoled_initialize + ****************************************************************************/ + +void board_autoled_initialize(void) +{ + int i; + + /* Configure the LD1 GPIO for output. Initial state is OFF */ + + for (i = 0; i < ARRAYSIZE(g_ledmap); i++) + { + stm32l4_configgpio(g_ledmap[i]); + } +} + +/**************************************************************************** + * Name: board_autoled_on + ****************************************************************************/ + +void board_autoled_on(int led) +{ + switch (led) + { + default: + break; + + case LED_HEAPALLOCATE: + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_IRQSENABLED: + phy_set_led(BOARD_LED_BLUE, false); + phy_set_led(BOARD_LED_GREEN, true); + break; + + case LED_STACKCREATED: + phy_set_led(BOARD_LED_GREEN, true); + phy_set_led(BOARD_LED_BLUE, true); + g_initialized = true; + break; + + case LED_INIRQ: + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_SIGNAL: + phy_set_led(BOARD_LED_GREEN, true); + break; + + case LED_ASSERTION: + phy_set_led(BOARD_LED_RED, true); + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_PANIC: + phy_set_led(BOARD_LED_RED, true); + break; + + case LED_IDLE : /* IDLE */ + phy_set_led(BOARD_LED_RED, true); + break; + } +} + +/**************************************************************************** + * Name: board_autoled_off + ****************************************************************************/ + +void board_autoled_off(int led) +{ + switch (led) + { + default: + break; + + case LED_SIGNAL: + phy_set_led(BOARD_LED_GREEN, false); + break; + + case LED_INIRQ: + phy_set_led(BOARD_LED_BLUE, false); + break; + + case LED_ASSERTION: + phy_set_led(BOARD_LED_RED, false); + phy_set_led(BOARD_LED_BLUE, false); + break; + + case LED_PANIC: + phy_set_led(BOARD_LED_RED, false); + break; + + case LED_IDLE : /* IDLE */ + phy_set_led(BOARD_LED_RED, false); + break; + } +} + +#endif /* CONFIG_ARCH_LEDS */ diff --git a/configs/nucleo-l496zg/src/stm32_boot.c b/configs/nucleo-l496zg/src/stm32_boot.c new file mode 100644 index 0000000000..5cf32fbb22 --- /dev/null +++ b/configs/nucleo-l496zg/src/stm32_boot.c @@ -0,0 +1,109 @@ +/************************************************************************************ + * configs/nucleo-144/src/stm32_boot.c + * + * Copyright (C) 2016 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * David Sidrane + * + * 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 "up_arch.h" +#include "nucleo-144.h" + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32l4_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +void stm32l4_boardinitialize(void) +{ +#ifdef CONFIG_ARCH_LEDS + /* Configure on-board LEDs if LED support has been selected. */ + + board_autoled_initialize(); +#endif + +#if defined(CONFIG_STM32L4_OTGFS) || defined(CONFIG_STM32L4_HOST) + stm32_usbinitialize(); +#endif + +#if defined(CONFIG_SPI) + /* Configure SPI chip selects */ + + stm32_spidev_initialize(); +#endif +} + +/************************************************************************************ + * Name: board_initialize + * + * Description: + * If CONFIG_BOARD_INITIALIZE is selected, then an additional initialization call + * will be performed in the boot-up sequence to a function called + * board_initialize(). board_initialize() will be called immediately after + * up_initialize() is called and just before the initial application is started. + * This additional initialization phase may be used, for example, to initialize + * board-specific device drivers. + * + ************************************************************************************/ + +#ifdef CONFIG_BOARD_INITIALIZE +void board_initialize(void) +{ +#if defined(CONFIG_NSH_LIBRARY) && !defined(CONFIG_LIB_BOARDCTL) + /* Perform NSH initialization here instead of from the NSH. This + * alternative NSH initialization is necessary when NSH is ran in user-space + * but the initialization function must run in kernel space. + */ + + (void)board_app_initialize(0); +#endif +} +#endif diff --git a/configs/nucleo-l496zg/src/stm32_buttons.c b/configs/nucleo-l496zg/src/stm32_buttons.c new file mode 100644 index 0000000000..46f7392ddb --- /dev/null +++ b/configs/nucleo-l496zg/src/stm32_buttons.c @@ -0,0 +1,120 @@ +/**************************************************************************** + * configs/nucleo-144/src/stm32_buttons.c + * + * Copyright (C) 2016-2017 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * David Sidrane + * + * 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 "stm32l4_gpio.h" +#include "nucleo-144.h" + +#ifdef CONFIG_ARCH_BUTTONS + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_button_initialize + * + * Description: + * board_button_initialize() must be called to initialize button resources. + * After that, board_buttons() may be called to collect the current state + * of all buttons or board_button_irq() may be called to register button + * interrupt handlers. + * + ****************************************************************************/ + +void board_button_initialize(void) +{ + stm32l4_configgpio(GPIO_BTN_USER); +} + +/**************************************************************************** + * Name: board_buttons + ****************************************************************************/ + +uint32_t board_buttons(void) +{ + return stm32l4_gpioread(GPIO_BTN_USER) ? 1 : 0; +} + +/************************************************************************************ + * Button support. + * + * Description: + * board_button_initialize() must be called to initialize button resources. After + * that, board_buttons() may be called to collect the current state of all + * buttons or board_button_irq() may be called to register button interrupt + * handlers. + * + * After board_button_initialize() has been called, board_buttons() may be called to + * collect the state of all buttons. board_buttons() returns an 32-bit bit set + * with each bit associated with a button. See the BUTTON_*_BIT + * definitions in board.h for the meaning of each bit. + * + * board_button_irq() may be called to register an interrupt handler that will + * be called when a button is depressed or released. The ID value is a + * button enumeration value that uniquely identifies a button resource. See the + * BUTTON_* definitions in board.h for the meaning of enumeration + * value. + * + ************************************************************************************/ + +#ifdef CONFIG_ARCH_IRQBUTTONS +int board_button_irq(int id, xcpt_t irqhandler, FAR void *arg) +{ + int ret = -EINVAL; + + if (id == BUTTON_USER) + { + ret = stm32l4_gpiosetevent(GPIO_BTN_USER, true, true, true, irqhandler, arg); + } + + return ret; +} +#endif +#endif /* CONFIG_ARCH_BUTTONS */ diff --git a/configs/nucleo-l496zg/src/stm32_dma_alloc.c b/configs/nucleo-l496zg/src/stm32_dma_alloc.c new file mode 100644 index 0000000000..7ce0af1790 --- /dev/null +++ b/configs/nucleo-l496zg/src/stm32_dma_alloc.c @@ -0,0 +1,117 @@ +/**************************************************************************** + * configs/nucleo-144/stc/stm32_dma_alloc.c + * + * Copyright (C) 2016 PX4 Development Team. 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 PX4 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 "nucleo-144.h" + +#if defined(CONFIG_FAT_DMAMEMORY) + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +#if !defined(CONFIG_GRAN) +# error microSD DMA support requires CONFIG_GRAN +#endif + +#define BOARD_DMA_ALLOC_POOL_SIZE (8*512) + +/************************************************************************************ + * Private Data + ************************************************************************************/ + +static GRAN_HANDLE dma_allocator; + +/* The DMA heap size constrains the total number of things that can be + * ready to do DMA at a time. + * + * For example, FAT DMA depends on one sector-sized buffer per filesystem plus + * one sector-sized buffer per file. + * + * We use a fundamental alignment / granule size of 64B; this is sufficient + * to guarantee alignment for the largest STM32 DMA burst (16 beats x 32bits). + */ + +static uint8_t g_dma_heap[BOARD_DMA_ALLOC_POOL_SIZE] __attribute__((aligned(64))); + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_dma_alloc_init + * + * Description: + * All boards may optionally provide this API to instantiate a pool of + * memory for uses with FAST FS DMA operations. + * + ************************************************************************************/ + +int stm32_dma_alloc_init(void) +{ + dma_allocator = gran_initialize(g_dma_heap, + sizeof(g_dma_heap), + 7, /* 128B granule - must be > alignment (XXX bug?) */ + 6); /* 64B alignment */ + + if (dma_allocator == NULL) + { + return -ENOMEM; + } + + return OK; +} + +/* DMA-aware allocator stubs for the FAT filesystem. */ + +void *fat_dma_alloc(size_t size) +{ + return gran_alloc(dma_allocator, size); +} + +void fat_dma_free(FAR void *memory, size_t size) +{ + gran_free(dma_allocator, memory, size); +} + +#endif /* CONFIG_FAT_DMAMEMORY */ diff --git a/configs/nucleo-l496zg/src/stm32_sdio.c b/configs/nucleo-l496zg/src/stm32_sdio.c new file mode 100644 index 0000000000..6a0a21dffb --- /dev/null +++ b/configs/nucleo-l496zg/src/stm32_sdio.c @@ -0,0 +1,180 @@ +/**************************************************************************** + * config/nucleo-144/src/stm32_sdio.c + * + * Copyright (C) 2014, 2016-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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "nucleo-144.h" +#include "stm32l4_gpio.h" +#include "stm32l4_sdmmc.h" + +#ifdef CONFIG_MMCSD + + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +/* Card detections requires card support and a card detection GPIO */ + +#define HAVE_NCD 1 +#if !defined(GPIO_SDMMC1_NCD) +# undef HAVE_NCD +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static FAR struct sdio_dev_s *g_sdio_dev; +#ifdef HAVE_NCD +static bool g_sd_inserted = 0xff; /* Impossible value */ +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_ncd_interrupt + * + * Description: + * Card detect interrupt handler. + * + ****************************************************************************/ + +#ifdef HAVE_NCD +static int stm32_ncd_interrupt(int irq, FAR void *context) +{ + bool present; + + present = !stm32_gpioread(GPIO_SDMMC1_NCD); + if (g_sdio_dev && present != g_sd_inserted) + { + sdio_mediachange(g_sdio_dev, present); + g_sd_inserted = present; + } + + return OK; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void) +{ + int ret; + +#ifdef HAVE_NCD + /* Card detect */ + + bool cd_status; + + /* Configure the card detect GPIO */ + + stm32_configgpio(GPIO_SDMMC1_NCD); + + /* Register an interrupt handler for the card detect pin */ + + (void)stm32_gpiosetevent(GPIO_SDMMC1_NCD, true, true, true, + stm32_ncd_interrupt, NULL); +#endif + + /* Mount the SDIO-based MMC/SD block driver */ + /* First, get an instance of the SDIO interface */ + + finfo("Initializing SDIO slot %d\n", SDIO_SLOTNO); + + g_sdio_dev = sdio_initialize(SDIO_SLOTNO); + if (!g_sdio_dev) + { + ferr("ERROR: Failed to initialize SDIO slot %d\n", SDIO_SLOTNO); + return -ENODEV; + } + + /* Now bind the SDIO interface to the MMC/SD driver */ + + finfo("Bind SDIO to the MMC/SD driver, minor=%d\n", SDIO_MINOR); + + ret = mmcsd_slotinitialize(SDIO_MINOR, g_sdio_dev); + if (ret != OK) + { + ferr("ERROR: Failed to bind SDIO to the MMC/SD driver: %d\n", ret); + return ret; + } + + finfo("Successfully bound SDIO to the MMC/SD driver\n"); + +#ifdef HAVE_NCD + /* Use SD card detect pin to check if a card is g_sd_inserted */ + + cd_status = !stm32_gpioread(GPIO_SDMMC1_NCD); + finfo("Card detect : %d\n", cd_status); + + sdio_mediachange(g_sdio_dev, cd_status); +#else + /* Assume that the SD card is inserted. What choice do we have? */ + + sdio_mediachange(g_sdio_dev, true); +#endif + + return OK; +} + +#endif /* HAVE_SDIO */ diff --git a/configs/nucleo-l496zg/src/stm32_spi.c b/configs/nucleo-l496zg/src/stm32_spi.c new file mode 100644 index 0000000000..ce8af8151f --- /dev/null +++ b/configs/nucleo-l496zg/src/stm32_spi.c @@ -0,0 +1,362 @@ +/************************************************************************************ + * configs/nucleo-144/src/stm32_spi.c + * + * Copyright (C) 2016 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * David Sidrane + * + * 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 "up_arch.h" +#include "chip.h" +#include "stm32l4_gpio.h" +#include "stm32l4_spi.h" + +#include "nucleo-144.h" + +#if defined(CONFIG_SPI) + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +#define ARRAYSIZE(x) (sizeof((x)) / sizeof((x)[0])) + +#if defined(CONFIG_NUCLEO_SPI1_TEST) +# if defined(CONFIG_NUCLEO_SPI1_TEST_MODE0) +# define CONFIG_NUCLEO_SPI1_TEST_MODE SPIDEV_MODE0 +# elif defined(CONFIG_NUCLEO_SPI1_TEST_MODE1) +# define CONFIG_NUCLEO_SPI1_TEST_MODE SPIDEV_MODE1 +# elif defined(CONFIG_NUCLEO_SPI1_TEST_MODE2) +# define CONFIG_NUCLEO_SPI1_TEST_MODE SPIDEV_MODE2 +# elif defined(CONFIG_NUCLEO_SPI1_TEST_MODE3) +# define CONFIG_NUCLEO_SPI1_TEST_MODE SPIDEV_MODE3 +# else +# error "No CONFIG_NUCLEO_SPI1_TEST_MODEx defined" +# endif +#endif + +#if defined(CONFIG_NUCLEO_SPI2_TEST) +# if defined(CONFIG_NUCLEO_SPI2_TEST_MODE0) +# define CONFIG_NUCLEO_SPI2_TEST_MODE SPIDEV_MODE0 +# elif defined(CONFIG_NUCLEO_SPI2_TEST_MODE1) +# define CONFIG_NUCLEO_SPI2_TEST_MODE SPIDEV_MODE1 +# elif defined(CONFIG_NUCLEO_SPI2_TEST_MODE2) +# define CONFIG_NUCLEO_SPI2_TEST_MODE SPIDEV_MODE2 +# elif defined(CONFIG_NUCLEO_SPI2_TEST_MODE3) +# define CONFIG_NUCLEO_SPI2_TEST_MODE SPIDEV_MODE3 +# else +# error "No CONFIG_NUCLEO_SPI2_TEST_MODEx defined" +# endif +#endif + +#if defined(CONFIG_NUCLEO_SPI3_TEST) +# if defined(CONFIG_NUCLEO_SPI3_TEST_MODE0) +# define CONFIG_NUCLEO_SPI3_TEST_MODE SPIDEV_MODE0 +# elif defined(CONFIG_NUCLEO_SPI3_TEST_MODE1) +# define CONFIG_NUCLEO_SPI3_TEST_MODE SPIDEV_MODE1 +# elif defined(CONFIG_NUCLEO_SPI3_TEST_MODE2) +# define CONFIG_NUCLEO_SPI3_TEST_MODE SPIDEV_MODE2 +# elif defined(CONFIG_NUCLEO_SPI3_TEST_MODE3) +# define CONFIG_NUCLEO_SPI3_TEST_MODE SPIDEV_MODE3 +# else +# error "No CONFIG_NUCLEO_SPI3_TEST_MODEx defined" +# endif +#endif + +/************************************************************************************ + * Private Data + ************************************************************************************/ + +/* Indexed by NUCLEO_SPI_BUSx_CSx */ + +static const uint32_t g_spigpio[] = +{ +#if defined(GPIO_SPI1_CS0) + GPIO_SPI1_CS0, +#endif +#if defined(GPIO_SPI1_CS1) + GPIO_SPI1_CS1, +#endif +#if defined(GPIO_SPI1_CS2) + GPIO_SPI1_CS2, +#endif +#if defined(GPIO_SPI1_CS3) + GPIO_SPI1_CS3, +#endif +#if defined(GPIO_SPI2_CS0) + GPIO_SPI2_CS0, +#endif +#if defined(GPIO_SPI2_CS1) + GPIO_SPI2_CS1, +#endif +#if defined(GPIO_SPI2_CS2) + GPIO_SPI2_CS2, +#endif +#if defined(GPIO_SPI2_CS3) + GPIO_SPI2_CS3, +#endif +#if defined(GPIO_SPI3_CS0) + GPIO_SPI3_CS0, +#endif +#if defined(GPIO_SPI3_CS1) + GPIO_SPI3_CS1, +#endif +#if defined(GPIO_SPI3_CS2) + GPIO_SPI3_CS2, +#endif +#if defined(GPIO_SPI3_CS3) + GPIO_SPI3_CS3, +#endif +}; + +#if defined(CONFIG_NUCLEO_SPI_TEST) +# if defined(CONFIG_STM32L4_SPI1) +struct spi_dev_s *spi1; +# endif +# if defined(CONFIG_STM32L4_SPI2) +struct spi_dev_s *spi2; +# endif +# if defined(CONFIG_STM32L4_SPI3) +struct spi_dev_s *spi3; +# endif +#endif + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_spidev_initialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the Nucleo-144 board. + * + ************************************************************************************/ + +void weak_function stm32_spidev_initialize(void) +{ + int i; + + /* Configure SPI CS GPIO for output */ + + for (i = 0; i < ARRAYSIZE(g_spigpio); i++) + { + stm32l4_configgpio(g_spigpio[i]); + } +} + +/**************************************************************************** + * Name: stm32_spi1/2/3/4/5select and stm32_spi1/2/3/4/5status + * + * Description: + * The external functions, stm32_spi1/2/3select and stm32_spi1/2/3status must be + * provided by board-specific logic. They are implementations of the select + * and status methods of the SPI interface defined by struct spi_ops_s (see + * include/nuttx/spi/spi.h). All other methods (including stm32_spibus_initialize()) + * are provided by common STM32 logic. To use this common SPI logic on your + * board: + * + * 1. Provide logic in stm32_boardinitialize() to configure SPI chip select + * pins. + * 2. Provide stm32_spi1/2/3select() and stm32_spi1/2/3status() functions in your + * board-specific logic. These functions will perform chip selection and + * status operations using GPIOs in the way your board is configured. + * 3. Add a calls to stm32_spibus_initialize() in your low level application + * initialization logic + * 4. The handle returned by stm32_spibus_initialize() may then be used to bind the + * SPI driver to higher level logic (e.g., calling + * mmcsd_spislotinitialize(), for example, will bind the SPI driver to + * the SPI MMC/SD driver). + * + ****************************************************************************/ + +#ifdef CONFIG_STM32L4_SPI1 +void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) +{ + spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); + stm32l4_gpiowrite(g_spigpio[devid], !selected); +} + +uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) +{ + return 0; +} +#endif + +#ifdef CONFIG_STM32L4_SPI2 +void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) +{ + spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); + stm32l4_gpiowrite(g_spigpio[devid], !selected); +} + +uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) +{ + return 0; +} +#endif + +#ifdef CONFIG_STM32L4_SPI3 +void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) +{ + spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); + stm32l4_gpiowrite(g_spigpio[devid], !selected); +} + +uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) +{ + return 0; +} +#endif + +/**************************************************************************** + * Name: stm32_spi1cmddata + * + * Description: + * Set or clear the SH1101A A0 or SD1306 D/C n bit to select data (true) + * or command (false). This function must be provided by platform-specific + * logic. This is an implementation of the cmddata method of the SPI + * interface defined by struct spi_ops_s (see include/nuttx/spi/spi.h). + * + * Input Parameters: + * + * spi - SPI device that controls the bus the device that requires the CMD/ + * DATA selection. + * devid - If there are multiple devices on the bus, this selects which one + * to select cmd or data. NOTE: This design restricts, for example, + * one one SPI display per SPI bus. + * cmd - true: select command; false: select data + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_SPI_CMDDATA +#ifdef CONFIG_STM32L4_SPI1 +int stm32_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) +{ + return -ENODEV; +} +#endif + +#ifdef CONFIG_STM32L4_SPI2 +int stm32_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) +{ + return -ENODEV; +} +#endif + +#ifdef CONFIG_STM32L4_SPI3 +int stm32_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) +{ + return -ENODEV; +} +#endif + +#endif /* CONFIG_SPI_CMDDATA */ + +#if defined(CONFIG_NUCLEO_SPI_TEST) +int stm32_spidev_bus_test(void) +{ + /* Configure and test SPI-*/ + + uint8_t *tx = (uint8_t *)CONFIG_NUCLEO_SPI_TEST_MESSAGE; + +#if defined(CONFIG_NUCLEO_SPI1_TEST) + spi1 = stm32l3_spibus_initialize(1); + + if (!spi1) + { + syslog(LOG_ERR, "ERROR Failed to initialize SPI port 1\n"); + return -ENODEV; + } + + /* Default SPI1 to NUCLEO_SPI1_FREQ and mode */ + + SPI_SETFREQUENCY(spi1, CONFIG_NUCLEO_SPI1_TEST_FREQ); + SPI_SETBITS(spi1, CONFIG_NUCLEO_SPI1_TEST_BITS); + SPI_SETMODE(spi1, CONFIG_NUCLEO_SPI1_TEST_MODE); + SPI_EXCHANGE(spi1, tx, NULL, ARRAYSIZE(CONFIG_NUCLEO_SPI_TEST_MESSAGE)); +#endif + +#if defined(CONFIG_NUCLEO_SPI2_TEST) + spi2 = stm32l4_spibus_initialize(2); + + if (!spi2) + { + syslog(LOG_ERR, "ERROR Failed to initialize SPI port 2\n"); + return -ENODEV; + } + + /* Default SPI2 to NUCLEO_SPI2_FREQ and mode */ + + SPI_SETFREQUENCY(spi2, CONFIG_NUCLEO_SPI2_TEST_FREQ); + SPI_SETBITS(spi2, CONFIG_NUCLEO_SPI2_TEST_BITS); + SPI_SETMODE(spi2, CONFIG_NUCLEO_SPI2_TEST_MODE); + SPI_EXCHANGE(spi2, tx, NULL, ARRAYSIZE(CONFIG_NUCLEO_SPI_TEST_MESSAGE)); +#endif + +#if defined(CONFIG_NUCLEO_SPI3_TEST) + spi3 = stm32l4_spibus_initialize(3); + + if (!spi3) + { + syslog(LOG_ERR, "ERROR Failed to initialize SPI port 2\n"); + return -ENODEV; + } + + /* Default SPI3 to NUCLEO_SPI3_FREQ and mode */ + + SPI_SETFREQUENCY(spi3, CONFIG_NUCLEO_SPI3_TEST_FREQ); + SPI_SETBITS(spi3, CONFIG_NUCLEO_SPI3_TEST_BITS); + SPI_SETMODE(spi3, CONFIG_NUCLEO_SPI3_TEST_MODE); + SPI_EXCHANGE(spi3, tx, NULL, ARRAYSIZE(CONFIG_NUCLEO_SPI_TEST_MESSAGE)); +#endif + + return OK; +} +#endif /* NUCLEO_SPI_TEST */ +#endif /* defined(CONFIG_SPI) */ diff --git a/configs/nucleo-l496zg/src/stm32_usb.c b/configs/nucleo-l496zg/src/stm32_usb.c new file mode 100644 index 0000000000..74d8d46d25 --- /dev/null +++ b/configs/nucleo-l496zg/src/stm32_usb.c @@ -0,0 +1,331 @@ +/************************************************************************************ + * configs//nucleo-144/src/stm32_usb.c + * + * Copyright (C) 2016-2017 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * David Sidrane + * + * 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 + +#include "up_arch.h" +#include "chip.h" +#include "stm32l4_gpio.h" +#include "stm32l4_otgfs.h" +#include "nucleo-144.h" + +#ifdef CONFIG_STM32L4_OTGFS + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +#if defined(CONFIG_USBDEV) || defined(CONFIG_USBHOST) +# define HAVE_USB 1 +#else +# warning "CONFIG_STM32_OTGFS is enabled but neither CONFIG_USBDEV nor CONFIG_USBHOST" +# undef HAVE_USB +#endif + +#ifndef CONFIG_NUCLEO144_USBHOST_PRIO +# define CONFIG_NUCLEO144_USBHOST_PRIO 100 +#endif + +#ifndef CONFIG_NUCLEO_USBHOST_STACKSIZE +# define CONFIG_NUCLEO_USBHOST_STACKSIZE 1024 +#endif + +/************************************************************************************ + * Private Data + ************************************************************************************/ + +#ifdef CONFIG_USBHOST +static struct usbhost_connection_s *g_usbconn; +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: usbhost_waiter + * + * Description: + * Wait for USB devices to be connected. + * + ************************************************************************************/ + +#ifdef CONFIG_USBHOST +static int usbhost_waiter(int argc, char *argv[]) +{ + struct usbhost_hubport_s *hport; + + uinfo("Running\n"); + for (;;) + { + /* Wait for the device to change state */ + + DEBUGVERIFY(CONN_WAIT(g_usbconn, &hport)); + uinfo("%s\n", hport->connected ? "connected" : "disconnected"); + + /* Did we just become connected? */ + + if (hport->connected) + { + /* Yes.. enumerate the newly connected device */ + + (void)CONN_ENUMERATE(g_usbconn, hport); + } + } + + /* Keep the compiler from complaining */ + + return 0; +} +#endif + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_usbinitialize + * + * Description: + * Called from stm32_usbinitialize very early in inialization to setup USB-related + * GPIO pins for the nucleo-144 board. + * + ************************************************************************************/ + +void stm32_usbinitialize(void) +{ + /* The OTG FS has an internal soft pull-up. No GPIO configuration is required */ + + /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */ + +#ifdef CONFIG_STM32L4_OTGFS + stm32l4_configgpio(GPIO_OTGFS_VBUS); + stm32l4_configgpio(GPIO_OTGFS_PWRON); + stm32l4_configgpio(GPIO_OTGFS_OVER); +#endif +} + +/*********************************************************************************** + * Name: stm32_usbhost_initialize + * + * Description: + * Called at application startup time to initialize the USB host functionality. + * This function will start a thread that will monitor for device + * connection/disconnection events. + * + ***********************************************************************************/ + +#ifdef CONFIG_USBHOST +int stm32_usbhost_initialize(void) +{ + int pid; +#if defined(CONFIG_USBHOST_HUB) || defined(CONFIG_USBHOST_MSC) || \ + defined(CONFIG_USBHOST_HIDKBD) || defined(CONFIG_USBHOST_HIDMOUSE) + int ret; +#endif + + /* First, register all of the class drivers needed to support the drivers + * that we care about: + */ + + uinfo("Register class drivers\n"); + +#ifdef CONFIG_USBHOST_HUB + /* Initialize USB hub class support */ + + ret = usbhost_hub_initialize(); + if (ret < 0) + { + uerr("ERROR: usbhost_hub_initialize failed: %d\n", ret); + } +#endif + +#ifdef CONFIG_USBHOST_MSC + /* Register the USB mass storage class class */ + + ret = usbhost_msc_initialize(); + if (ret != OK) + { + uerr("ERROR: Failed to register the mass storage class: %d\n", ret); + } +#endif + +#ifdef CONFIG_USBHOST_CDCACM + /* Register the CDC/ACM serial class */ + + ret = usbhost_cdcacm_initialize(); + if (ret != OK) + { + uerr("ERROR: Failed to register the CDC/ACM serial class: %d\n", ret); + } +#endif + +#ifdef CONFIG_USBHOST_HIDKBD + /* Initialize the HID keyboard class */ + + ret = usbhost_kbdinit(); + if (ret != OK) + { + uerr("ERROR: Failed to register the HID keyboard class\n"); + } +#endif + +#ifdef CONFIG_USBHOST_HIDMOUSE + /* Initialize the HID mouse class */ + + ret = usbhost_mouse_init(); + if (ret != OK) + { + uerr("ERROR: Failed to register the HID mouse class\n"); + } +#endif + + /* Then get an instance of the USB host interface */ + + uinfo("Initialize USB host\n"); + g_usbconn = stm32l4_otgfshost_initialize(0); + if (g_usbconn) + { + /* Start a thread to handle device connection. */ + + uinfo("Start usbhost_waiter\n"); + + pid = task_create("usbhost", CONFIG_STM32F4DISCO_USBHOST_PRIO, + CONFIG_STM32F4DISCO_USBHOST_STACKSIZE, + (main_t)usbhost_waiter, (FAR char * const *)NULL); + return pid < 0 ? -ENOEXEC : OK; + } + + return -ENODEV; +} +#endif + +/*********************************************************************************** + * Name: stm32_usbhost_vbusdrive + * + * Description: + * Enable/disable driving of VBUS 5V output. This function must be provided be + * each platform that implements the STM32 OTG FS host interface + * + * "On-chip 5 V VBUS generation is not supported. For this reason, a charge pump + * or, if 5 V are available on the application board, a basic power switch, must + * be added externally to drive the 5 V VBUS line. The external charge pump can + * be driven by any GPIO output. When the application decides to power on VBUS + * using the chosen GPIO, it must also set the port power bit in the host port + * control and status register (PPWR bit in OTG_FS_HPRT). + * + * "The application uses this field to control power to this port, and the core + * clears this bit on an overcurrent condition." + * + * Input Parameters: + * iface - For future growth to handle multiple USB host interface. Should be zero. + * enable - true: enable VBUS power; false: disable VBUS power + * + * Returned Value: + * None + * + ***********************************************************************************/ + +#ifdef CONFIG_USBHOST +void stm32_usbhost_vbusdrive(int iface, bool enable) +{ + DEBUGASSERT(iface == 0); + + /* Set the Power Switch by driving the active low enable pin */ + + stm32l4_gpiowrite(GPIO_OTGFS_PWRON, !enable); +} +#endif + +/************************************************************************************ + * Name: stm32_setup_overcurrent + * + * Description: + * Setup to receive an interrupt-level callback if an overcurrent condition is + * detected. + * + * Input Parameter: + * handler - New overcurrent interrupt handler + * arg - The argument provided for the interrupt handler + * + * Returned value: + * Zero (OK) is returned on success. Otherwise, a negated errno value is returned + * to indicate the nature of the failure. + * + ************************************************************************************/ + +#ifdef CONFIG_USBHOST +int stm32_setup_overcurrent(xcpt_t handler, void *arg) +{ + return stm32l4_gpiosetevent(GPIO_OTGFS_OVER, true, true, true, handler, arg); +} +#endif + +/************************************************************************************ + * Name: stm32_usbsuspend + * + * Description: + * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is + * used. This function is called whenever the USB enters or leaves suspend mode. + * This is an opportunity for the board logic to shutdown clocks, power, etc. + * while the USB is suspended. + * + ************************************************************************************/ + +#ifdef CONFIG_USBDEV +void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) +{ + uinfo("resume: %d\n", resume); +} +#endif + +#endif /* CONFIG_STM32_OTGFS */ diff --git a/configs/nucleo-l496zg/src/stm32_userleds.c b/configs/nucleo-l496zg/src/stm32_userleds.c new file mode 100644 index 0000000000..e2a91a5216 --- /dev/null +++ b/configs/nucleo-l496zg/src/stm32_userleds.c @@ -0,0 +1,144 @@ +/**************************************************************************** + * configs/nucleo-144/src/stm32_userleds.c + * + * Copyright (C) 2016 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * Mark Olsson + * David Sidrane + * + * 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 "stm32l4_gpio.h" +#include "nucleo-144.h" + +#ifndef CONFIG_ARCH_LEDS + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define ARRAYSIZE(x) (sizeof((x)) / sizeof((x)[0])) + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* This array maps an LED number to GPIO pin configuration and is indexed by + * BOARD_LED_ + */ + +static const uint32_t g_ledcfg[BOARD_NLEDS] = +{ + GPIO_LED_GREEN, + GPIO_LED_BLUE, + GPIO_LED_RED, +}; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_userled_initialize + * + * Description: + * If CONFIG_ARCH_LEDS is defined, then NuttX will control the on-board + * LEDs. If CONFIG_ARCH_LEDS is not defined, then the + * board_userled_initialize() is available to initialize the LED from user + * application logic. + * + ****************************************************************************/ + +void board_userled_initialize(void) +{ + int i; + + /* Configure LED1-3 GPIOs for output */ + + for (i = 0; i < ARRAYSIZE(g_ledcfg); i++) + { + stm32l4_configgpio(g_ledcfg[i]); + } +} + +/**************************************************************************** + * Name: board_userled + * + * Description: + * If CONFIG_ARCH_LEDS is defined, then NuttX will control the on-board + * LEDs. If CONFIG_ARCH_LEDS is not defined, then the board_userled() is + * available to control the LED from user application logic. + * + ****************************************************************************/ + +void board_userled(int led, bool ledon) +{ + if ((unsigned)led < ARRAYSIZE(g_ledcfg)) + { + stm32l4_gpiowrite(g_ledcfg[led], ledon); + } +} + +/**************************************************************************** + * Name: board_userled_all + * + * Description: + * If CONFIG_ARCH_LEDS is defined, then NuttX will control the on-board + * LEDs. If CONFIG_ARCH_LEDS is not defined, then the board_userled_all() is + * available to control the LED from user application logic. NOTE: since + * there is only a single LED on-board, this is function is not very useful. + * + ****************************************************************************/ + +void board_userled_all(uint8_t ledset) +{ + int i; + + /* Configure LED1-3 GPIOs for output */ + + for (i = 0; i < ARRAYSIZE(g_ledcfg); i++) + { + stm32l4_gpiowrite(g_ledcfg[i], (ledset & (1 << i)) != 0); + } +} + +#endif /* !CONFIG_ARCH_LEDS */ -- GitLab From f01ceffc0d5a48b2b89057369e473414c6093d90 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Tue, 2 May 2017 15:39:54 +0300 Subject: [PATCH 670/990] configs: add nucleo-f091rc board files --- configs/Kconfig | 13 + configs/nucleo-f091rc/Kconfig | 8 + configs/nucleo-f091rc/README.txt | 319 ++++++ configs/nucleo-f091rc/include/board.h | 241 +++++ configs/nucleo-f091rc/nsh/Make.defs | 113 ++ configs/nucleo-f091rc/nsh/defconfig | 1118 ++++++++++++++++++++ configs/nucleo-f091rc/scripts/flash.ld | 127 +++ configs/nucleo-f091rc/src/.gitignore | 2 + configs/nucleo-f091rc/src/Makefile | 56 + configs/nucleo-f091rc/src/nucleo-f091rc.h | 123 +++ configs/nucleo-f091rc/src/stm32_appinit.c | 87 ++ configs/nucleo-f091rc/src/stm32_autoleds.c | 96 ++ configs/nucleo-f091rc/src/stm32_boot.c | 94 ++ configs/nucleo-f091rc/src/stm32_bringup.c | 82 ++ configs/nucleo-f091rc/src/stm32_buttons.c | 128 +++ configs/nucleo-f091rc/src/stm32_userleds.c | 217 ++++ 16 files changed, 2824 insertions(+) create mode 100644 configs/nucleo-f091rc/Kconfig create mode 100644 configs/nucleo-f091rc/README.txt create mode 100644 configs/nucleo-f091rc/include/board.h create mode 100644 configs/nucleo-f091rc/nsh/Make.defs create mode 100644 configs/nucleo-f091rc/nsh/defconfig create mode 100644 configs/nucleo-f091rc/scripts/flash.ld create mode 100644 configs/nucleo-f091rc/src/.gitignore create mode 100644 configs/nucleo-f091rc/src/Makefile create mode 100644 configs/nucleo-f091rc/src/nucleo-f091rc.h create mode 100644 configs/nucleo-f091rc/src/stm32_appinit.c create mode 100644 configs/nucleo-f091rc/src/stm32_autoleds.c create mode 100644 configs/nucleo-f091rc/src/stm32_boot.c create mode 100644 configs/nucleo-f091rc/src/stm32_bringup.c create mode 100644 configs/nucleo-f091rc/src/stm32_buttons.c create mode 100644 configs/nucleo-f091rc/src/stm32_userleds.c diff --git a/configs/Kconfig b/configs/Kconfig index 5a13b9a0a1..6daffc80e0 100644 --- a/configs/Kconfig +++ b/configs/Kconfig @@ -763,6 +763,15 @@ config ARCH_BOARD_NUCLEO_F072RB ---help--- STMicro Nucleo F072RB board based on the STMicro STM32F072RBT6 MCU. +config ARCH_BOARD_NUCLEO_F091RC + bool "STM32F091 Nucleo F091RC" + depends on ARCH_CHIP_STM32F091RC + select ARCH_HAVE_LEDS + select ARCH_HAVE_BUTTONS + select ARCH_HAVE_IRQBUTTONS + ---help--- + STMicro Nucleo F091RC board based on the STMicro STM32F091RCT6 MCU. + config ARCH_BOARD_NUCLEO_F303RE bool "STM32F303 Nucleo F303RE" depends on ARCH_CHIP_STM32F303RE @@ -1544,6 +1553,7 @@ config ARCH_BOARD default "pic32mz-starterkit" if ARCH_BOARD_PIC32MZ_STARTERKIT default "nucleo-144" if ARCH_BOARD_NUCLEO_144 default "nucleo-f072rb" if ARCH_BOARD_NUCLEO_F072RB + default "nucleo-f091rc" if ARCH_BOARD_NUCLEO_F091RC default "nucleo-f303re" if ARCH_BOARD_NUCLEO_F303RE default "nucleo-f334r8" if ARCH_BOARD_NUCLEO_F334R8 default "nucleo-f4x1re" if ARCH_BOARD_NUCLEO_F401RE || ARCH_BOARD_NUCLEO_F411RE @@ -1854,6 +1864,9 @@ endif if ARCH_BOARD_NUCLEO_F072RB source "configs/nucleo-f072rb/Kconfig" endif +if ARCH_BOARD_NUCLEO_F091RC +source "configs/nucleo-f091rc/Kconfig" +endif if ARCH_BOARD_NUCLEO_F303RE source "configs/nucleo-f303re/Kconfig" endif diff --git a/configs/nucleo-f091rc/Kconfig b/configs/nucleo-f091rc/Kconfig new file mode 100644 index 0000000000..0c1fe76f6c --- /dev/null +++ b/configs/nucleo-f091rc/Kconfig @@ -0,0 +1,8 @@ +# +# For a description of the syntax of this configuration file, +# see the file kconfig-language.txt in the NuttX tools repository. +# + +if ARCH_BOARD_NUCLEO_F091RC + +endif diff --git a/configs/nucleo-f091rc/README.txt b/configs/nucleo-f091rc/README.txt new file mode 100644 index 0000000000..86b60014f7 --- /dev/null +++ b/configs/nucleo-f091rc/README.txt @@ -0,0 +1,319 @@ +Nucleo-F091RC README +==================== + + This README file discusess the port of NuttX to the STMicro Nucleo-F091RC + board. That board features the STM32F091RCT6 MCU with 256KiB of FLASH + and 32KiB of SRAM. + +Contents +======== + + - Nucleo-64 Boards + - LEDs + - Buttons + - Serial Console + - Configurations + +Nucleo-64 Boards +================ + + The Nucleo-F091RC is a member of the Nucleo-64 board family. The Nucleo-64 + is a standard board for use with several STM32 parts in the LQFP64 package. + Variants including: + + Order code Targeted STM32 + ------------- -------------- + NUCLEO-F030R8 STM32F030R8T6 + NUCLEO-F070RB STM32F070RBT6 + NUCLEO-F072RB STM32F072RBT6 + NUCLEO-F091RC STM32F091RCT6 + NUCLEO-F103RB STM32F103RBT6 + NUCLEO-F302R8 STM32F302R8T6 + NUCLEO-F303RE STM32F303RET6 + NUCLEO-F334R8 STM32F334R8T6 + NUCLEO-F401RE STM32F401RET6 + NUCLEO-F410RB STM32F410RBT6 + NUCLEO-F411RE STM32F411RET6 + NUCLEO-F446RE STM32F446RET6 + NUCLEO-L053R8 STM32L053R8T6 + NUCLEO-L073RZ STM32L073RZT6 + NUCLEO-L152RE STM32L152RET6 + NUCLEO-L452RE STM32L452RET6 + NUCLEO-L476RG STM32L476RGT6 + +LEDs +==== + + The Nucleo-64 board has one user controlable LED, User LD2. This green + LED is a user LED connected to Arduino signal D13 corresponding to STM32 + I/O PA5 (PB13 on other some other Nucleo-64 boards). + + - When the I/O is HIGH value, the LED is on + - When the I/O is LOW, the LED is off + + These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is + defined. In that case, the usage by the board port is defined in + include/board.h and src/stm32_autoleds.c. The LEDs are used to encode + OS-related events as follows when the red LED (PE24) is available: + + SYMBOL Meaning LD2 + ------------------- ----------------------- ----------- + LED_STARTED NuttX has been started OFF + LED_HEAPALLOCATE Heap has been allocated OFF + LED_IRQSENABLED Interrupts enabled OFF + LED_STACKCREATED Idle stack created ON + LED_INIRQ In an interrupt No change + LED_SIGNAL In a signal handler No change + LED_ASSERTION An assertion failed No change + LED_PANIC The system has crashed Blinking + LED_IDLE MCU is is sleep mode Not used + + Thus if LD2, NuttX has successfully booted and is, apparently, running + normally. If LD2 is flashing at approximately 2Hz, then a fatal error + has been detected and the system has halted. + +Buttons +======= + + B1 USER: the user button is connected to the I/O PC13 (pin 2) of the STM32 + microcontroller. + +Serial Console +============== + + USART1 + ------ + Pins and Connectors: + + RXD: PA10 D3 CN9 pin 3, CN10 pin 33 + PB7 CN7 pin 21 + TXD: PA9 D8 CN5 pin 1, CN10 pin 21 + PB6 D10 CN5 pin 3, CN10 pin 17 + + NOTE: You may need to edit the include/board.h to select different USART1 + pin selections. + + TTL to RS-232 converter connection: + + Nucleo CN10 STM32F072RB + ----------- ------------ + Pin 21 PA9 USART1_TX *Warning you make need to reverse RX/TX on + Pin 33 PA10 USART1_RX some RS-232 converters + Pin 20 GND + Pin 8 U5V + + To configure USART1 as the console: + + CONFIG_STM32_USART1=y + CONFIG_USART1_SERIALDRIVER=y + CONFIG_USART1_SERIAL_CONSOLE=y + CONFIG_USART1_RXBUFSIZE=256 + CONFIG_USART1_TXBUFSIZE=256 + CONFIG_USART1_BAUD=115200 + CONFIG_USART1_BITS=8 + CONFIG_USART1_PARITY=0 + CONFIG_USART1_2STOP=0 + + USART2 + ------ + Pins and Connectors: + + RXD: PA3 To be provided + PA15 + PD6 + TXD: PA2 + PA14 + PD5 + + USART3 + ------ + Pins and Connectors: + + RXD: PB11 To be provided + PC5 + PC11 + D9 + TXD: PB10 + PC4 + PC10 + D8 + + See "Virtual COM Port" and "RS-232 Shield" below. + + USART3 + ------ + Pins and Connectors: + + RXD: PA1 To be provided + PC11 + TXD: PA0 + PC10 + + Virtual COM Port + ---------------- + Yet another option is to use UART2 and the USB virtual COM port. This + option may be more convenient for long term development, but is painful + to use during board bring-up. + + Solder Bridges. This configuration requires: + + - SB62 and SB63 Open: PA2 and PA3 on STM32 MCU are disconnected to D1 + and D0 (pin 7 and pin 8) on Arduino connector CN9 and ST Morpho + connector CN10. + + - SB13 and SB14 Closed: PA2 and PA3 on STM32F103C8T6 (ST-LINK MCU) are + connected to PA3 and PA2 on STM32 MCU to have USART communication + between them. Thus SB61, SB62 and SB63 should be OFF. + + Configuring USART2 is the same as given above. + + Question: What BAUD should be configure to interface with the Virtual + COM port? 115200 8N1? + + Default + ------- + As shipped, SB62 and SB63 are open and SB13 and SB14 closed, so the + virtual COM port is enabled. + + RS-232 Shield + ------------- + Supports a single RS-232 connected via + + Nucleo STM32F4x1RE Shield + --------- --------------- -------- + CN9 Pin 1 PA3 USART2_RXD RXD + CN9 Pin 2 PA2 USART2_TXD TXD + + Support for this shield is enabled by selecting USART2 and configuring + SB13, 14, 62, and 63 as described above under "Virtual COM Port" + +Configurations +============== + + Information Common to All Configurations + ---------------------------------------- + Each configuration is maintained in a sub-directory and can be + selected as follow: + + cd tools + ./configure.sh nucleo-f091rc/ + cd - + + Before building, make sure the PATH environment variable includes the + correct path to the directory than holds your toolchain binaries. + + And then build NuttX by simply typing the following. At the conclusion of + the make, the nuttx binary will reside in an ELF file called, simply, nuttx. + + make oldconfig + make + + The that is provided above as an argument to the tools/configure.sh + must be is one of the following. + + NOTES: + + 1. These configurations use the mconf-based configuration tool. To + change any of these configurations using that tool, you should: + + a. Build and install the kconfig-mconf tool. See nuttx/README.txt + see additional README.txt files in the NuttX tools repository. + + b. Execute 'make menuconfig' in nuttx/ in order to start the + reconfiguration process. + + 2. Unless stated otherwise, all configurations generate console + output on USART2, as described above under "Serial Console". The + elevant configuration settings are listed below: + + CONFIG_STM32_USART2=y + CONFIG_STM32_USART2_SERIALDRIVER=y + CONFIG_STM32_USART=y + + CONFIG_USART2_SERIALDRIVER=y + CONFIG_USART2_SERIAL_CONSOLE=y + + CONFIG_USART2_RXBUFSIZE=256 + CONFIG_USART2_TXBUFSIZE=256 + CONFIG_USART2_BAUD=115200 + CONFIG_USART2_BITS=8 + CONFIG_USART2_PARITY=0 + CONFIG_USART2_2STOP=0 + + 3. All of these configurations are set up to build under Linux using the + "GNU Tools for ARM Embedded Processors" that is maintained by ARM + (unless stated otherwise in the description of the configuration). + + https://launchpad.net/gcc-arm-embedded + + That toolchain selection can easily be reconfigured using + 'make menuconfig'. Here are the relevant current settings: + + Build Setup: + CONFIG_HOST_LINUX=y : Linux environment + + System Type -> Toolchain: + CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL=y : GNU ARM EABI toolchain + + Configuration sub-directories + ----------------------------- + + nsh: + + Configures the NuttShell (nsh) located at examples/nsh. This + configuration is focused on low level, command-line driver testing. + + NOTES: + + 1. This initial release of this configuration was very minimal, but + also very small: + + $ size nuttx + text data bss dec hex filename + 32000 92 1172 33264 81f0 nuttx + + The current version, additional features have been enabled: board + bring-up initialization, button support, the procfs file system, + and NSH built-in application support. The size increased as follows: + + $ size nuttx + text data bss dec hex filename + 40231 92 1208 41531 a23b nuttx + + Those additional features cost about 8KiB FLASH. I believe that is a + good use of the STM32F072RB's FLASH, but if you interested in the + more minimal configuration, here is what was changed: + + Removed + + CONFIG_BINFMT_DISABLE=y + CONFIG_DISABLE_MOUNTPOINT=y + CONFIG_NSH_DISABLE_CD=y + + Added: + + CONFIG_ARCH_BUTTONS=y + CONFIG_ARCH_IRQBUTTONS=y + + CONFIG_BUILTIN=y + CONFIG_BUILTIN_PROXY_STACKSIZE=1024 + + CONFIG_FS_PROCFS=y + CONFIG_NSH_PROC_MOUNTPOINT="/proc" + + CONFIG_LIB_BOARDCTL=y + CONFIG_NSH_ARCHINIT=y + CONFIG_NSH_BUILTIN_APPS=y + + Support for NSH built-in applications is enabled for future use. + However, no built applications are enabled in this base configuration. + + 2. C++ support for applications is NOT enabled. That could be enabled + with the following configuration changes: + + CONFIG_HAVE_CXX=y + CONFIG_HAVE_CXXINITIALIZE=y + CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y + + And also support fo C++ constructors under + apps/platform/nucleo-stm32f072rb. diff --git a/configs/nucleo-f091rc/include/board.h b/configs/nucleo-f091rc/include/board.h new file mode 100644 index 0000000000..be7e3f5a9e --- /dev/null +++ b/configs/nucleo-f091rc/include/board.h @@ -0,0 +1,241 @@ +/************************************************************************************ + * configs/nucleo-f091rc/include/board.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Alan Carvalho de Assis + * + * 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 __CONFIG_NUCLEO_F091RC_INCLUDE_BOARD_H +#define __CONFIG_NUCLEO_F091RC_INCLUDE_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#ifndef __ASSEMBLY__ +# include +#endif + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ +/* Four different clock sources can be used to drive the system clock (SYSCLK): + * + * - HSI high-speed internal oscillator clock + * Generated from an internal 8 MHz RC oscillator + * - HSE high-speed external oscillator clock + * Normally driven by an external crystal (X3). However, this crystal is not + * fitted on the Nucleo-F091RC board. + * - PLL clock + * - MSI multispeed internal oscillator clock + * The MSI clock signal is generated from an internal RC oscillator. Seven frequency + * ranges are available: 65.536 kHz, 131.072 kHz, 262.144 kHz, 524.288 kHz, 1.048 MHz, + * 2.097 MHz (default value) and 4.194 MHz. + * + * The devices have the following two secondary clock sources + * - LSI low-speed internal RC clock + * Drives the watchdog and RTC. Approximately 37KHz + * - LSE low-speed external oscillator clock + * Driven by 32.768KHz crystal (X2) on the OSC32_IN and OSC32_OUT pins. + */ + +#define STM32F0_BOARD_XTAL 8000000ul /* X3 on board (not fitted)*/ + +#define STM32F0_HSI_FREQUENCY 8000000ul /* Approximately 8MHz */ +#define STM32F0_HSI14_FREQUENCY 14000000ul /* HSI14 for ADC */ +#define STM32F0_HSI48_FREQUENCY 48000000ul /* HSI48 for USB, only some STM32F0xx */ +#define STM32F0_HSE_FREQUENCY STM32F0_BOARD_XTAL +#define STM32F0_LSI_FREQUENCY 40000 /* Approximately 40KHz */ +#define STM32F0_LSE_FREQUENCY 32768 /* X2 on board */ + +/* PLL Configuration + * + * - PLL source is HSI -> 8MHz input (nominal) + * - PLL source predivider 2 -> 4MHz divided down PLL VCO clock output + * - PLL multipler is 12 -> 48MHz PLL VCO clock output (for USB) + * + * Resulting SYSCLK frequency is 8MHz x 12 / 2 = 48MHz + * + * USB: + * If the USB interface is used in the application, it requires a precise + * 48MHz clock which can be generated from either the (1) the internal + * main PLL with the HSE clock source using an HSE crystal oscillator. In + * this case, the PLL VCO clock (defined by STM32F0_CFGR_PLLMUL) must be + * programmed to output a 96 MHz frequency. This is required to provide a + * 48MHz clock to the (USBCLK = PLLVCO/2). Or (2) by using the internal + * 48MHz oscillator in automatic trimming mode. The synchronization for + * this oscillator can be taken from the USB data stream itself (SOF + * signalization) which allows crystal-less operation. + * SYSCLK + * The system clock is derived from the PLL VCO divided by the output + * division factor. + * Limitations: + * - 96 MHz as PLLVCO when the product is in range 1 (1.8V), + * - 48 MHz as PLLVCO when the product is in range 2 (1.5V), + * - 24 MHz when the product is in range 3 (1.2V). + * - Output division to avoid exceeding 32 MHz as SYSCLK. + * - The minimum input clock frequency for PLL is 2 MHz (when using HSE as + * PLL source). + */ + +#define STM32F0_CFGR_PLLSRC RCC_CFGR_PLLSRC_HSId2 /* Source is HSI/2 */ +#define STM32F0_PLLSRC_FREQUENCY (STM32F0_HSI_FREQUENCY/2) /* 8MHz / 2 = 4MHz */ +#ifdef CONFIG_STM32F0_USB +# undef STM32F0_CFGR2_PREDIV /* Not used with source HSI/2 */ +# define STM32F0_CFGR_PLLMUL RCC_CFGR_PLLMUL_CLKx12 /* PLLMUL = 12 */ +# define STM32F0_PLL_FREQUENCY (12*STM32F0_PLLSRC_FREQUENCY) /* PLL VCO Frequency is 48MHz */ +#else +# undef STM32F0_CFGR2_PREDIV /* Not used with source HSI/2 */ +# define STM32F0_CFGR_PLLMUL RCC_CFGR_PLLMUL_CLKx12 /* PLLMUL = 12 */ +# define STM32F0_PLL_FREQUENCY (12*STM32F0_PLLSRC_FREQUENCY) /* PLL VCO Frequency is 48MHz */ +#endif + +/* Use the PLL and set the SYSCLK source to be the divided down PLL VCO output + * frequency (STM32F0_PLL_FREQUENCY divided by the PLLDIV value). + */ + +#define STM32F0_SYSCLK_SW RCC_CFGR_SW_PLL /* Use the PLL as the SYSCLK */ +#define STM32F0_SYSCLK_SWS RCC_CFGR_SWS_PLL +#ifdef CONFIG_STM32F0_USB +# define STM32F0_SYSCLK_FREQUENCY STM32F0_PLL_FREQUENCY /* SYSCLK frequency is PLL VCO = 48MHz */ +#else +# define STM32F0_SYSCLK_FREQUENCY STM32F0_PLL_FREQUENCY /* SYSCLK frequency is PLL VCO = 48MHz */ +#endif + +#define STM32F0_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK +#define STM32F0_HCLK_FREQUENCY STM32F0_SYSCLK_FREQUENCY +#define STM32F0_BOARD_HCLK STM32F0_HCLK_FREQUENCY /* Same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK (48MHz) */ + +#define STM32F0_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLK +#define STM32F0_PCLK1_FREQUENCY (STM32F0_HCLK_FREQUENCY) + +/* APB2 clock (PCLK2) is HCLK (48MHz) */ + +#define STM32F0_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK +#define STM32F0_PCLK2_FREQUENCY STM32F0_HCLK_FREQUENCY +#define STM32F0_APB2_CLKIN (STM32F0_PCLK2_FREQUENCY) + +/* APB1 timers 1-3, 6-7, and 14-17 will receive PCLK1 */ + +#define STM32F0_APB1_TIM1_CLKIN (STM32F0_PCLK1_FREQUENCY) +#define STM32F0_APB1_TIM2_CLKIN (STM32F0_PCLK1_FREQUENCY) +#define STM32F0_APB1_TIM3_CLKIN (STM32F0_PCLK1_FREQUENCY) + +#define STM32F0_APB1_TIM6_CLKIN (STM32F0_PCLK1_FREQUENCY) +#define STM32F0_APB1_TIM7_CLKIN (STM32F0_PCLK1_FREQUENCY) + +#define STM32F0_APB1_TIM14_CLKIN (STM32F0_PCLK1_FREQUENCY) +#define STM32F0_APB1_TIM15_CLKIN (STM32F0_PCLK1_FREQUENCY) +#define STM32F0_APB1_TIM16_CLKIN (STM32F0_PCLK1_FREQUENCY) +#define STM32F0_APB1_TIM17_CLKIN (STM32F0_PCLK1_FREQUENCY) + +/* LED definitions ******************************************************************/ +/* LEDs + * + * The Nucleo-64 board has one user controlable LED, User LD2. This green + * LED is a user LED connected to Arduino signal D13 corresponding to STM32 + * I/O PA5 (PB13 on other some other Nucleo-64 boards). + * + * - When the I/O is HIGH value, the LED is on + * - When the I/O is LOW, the LED is off + */ + +/* LED index values for use with board_userled() */ + +#define BOARD_LD2 0 +#define BOARD_NLEDS 1 + +/* LED bits for use with board_userled_all() */ + +#define BOARD_LD2_BIT (1 << BOARD_LD2) + +/* These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is + * defined. In that case, the usage by the board port is defined in + * include/board.h and src/sam_leds.c. The LEDs are used to encode OS-related + * events as follows when the red LED (PE24) is available: + * + * SYMBOL Meaning LD2 + * ------------------- ----------------------- ----------- + * LED_STARTED NuttX has been started OFF + * LED_HEAPALLOCATE Heap has been allocated OFF + * LED_IRQSENABLED Interrupts enabled OFF + * LED_STACKCREATED Idle stack created ON + * LED_INIRQ In an interrupt No change + * LED_SIGNAL In a signal handler No change + * LED_ASSERTION An assertion failed No change + * LED_PANIC The system has crashed Blinking + * LED_IDLE MCU is is sleep mode Not used + * + * Thus if LD2, NuttX has successfully booted and is, apparently, running + * normally. If LD2 is flashing at approximately 2Hz, then a fatal error + * has been detected and the system has halted. + */ + +#define LED_STARTED 0 +#define LED_HEAPALLOCATE 0 +#define LED_IRQSENABLED 0 +#define LED_STACKCREATED 1 +#define LED_INIRQ 2 +#define LED_SIGNAL 2 +#define LED_ASSERTION 2 +#define LED_PANIC 1 + +/* Button definitions ***************************************************************/ +/* Buttons + * + * B1 USER: the user button is connected to the I/O PC13 (pin 2) of the STM32 + * microcontroller. + */ + +#define BUTTON_USER 0 +#define NUM_BUTTONS 1 + +#define BUTTON_USER_BIT (1 << BUTTON_USER) + +/* Alternate Pin Functions **********************************************************/ +/* USART 1 */ + +#define GPIO_USART1_TX GPIO_USART1_TX_2 +#define GPIO_USART1_RX GPIO_USART1_RX_2 + +/* USART 2 */ + +#define GPIO_USART2_TX GPIO_USART2_TX_3 +#define GPIO_USART2_RX GPIO_USART2_RX_3 + +#endif /* __CONFIG_NUCLEO_F091RC_INCLUDE_BOARD_H */ diff --git a/configs/nucleo-f091rc/nsh/Make.defs b/configs/nucleo-f091rc/nsh/Make.defs new file mode 100644 index 0000000000..eb0863ab3d --- /dev/null +++ b/configs/nucleo-f091rc/nsh/Make.defs @@ -0,0 +1,113 @@ +############################################################################ +# configs/nucleo-f091rc/nsh/Make.defs +# +# Copyright (C) 2017 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# Alan Carvalho de Assis +# +# 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. +# +############################################################################ + +include ${TOPDIR}/.config +include ${TOPDIR}/tools/Config.mk +include ${TOPDIR}/arch/arm/src/armv6-m/Toolchain.defs + +LDSCRIPT = flash.ld + +ifeq ($(WINTOOL),y) + # Windows-native toolchains + DIRLINK = $(TOPDIR)/tools/copydir.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mkwindeps.sh + ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" + ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" +else + # Linux/Cygwin-native toolchain + MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT) + ARCHINCLUDES = -I. -isystem $(TOPDIR)/include + ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) +endif + +CC = $(CROSSDEV)gcc +CXX = $(CROSSDEV)g++ +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(ARCROSSDEV)ar rcs +NM = $(ARCROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump + +ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} +ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} + +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + ARCHOPTIMIZATION = -g +endif + +ifneq ($(CONFIG_DEBUG_NOOPT),y) + ARCHOPTIMIZATION += $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer +endif + +ARCHCFLAGS = -fno-builtin +ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fcheck-new -fno-rtti +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow -Wundef +ARCHWARNINGSXX = -Wall -Wshadow -Wundef +ARCHDEFINES = +ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 + +CFLAGS = $(ARCHCFLAGS) $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) +CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +NXFLATLDFLAGS1 = -r -d -warn-common +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections +LDNXFLATFLAGS = -e main -s 2048 + +ASMEXT = .S +OBJEXT = .o +LIBEXT = .a +EXEEXT = + +ifneq ($(CROSSDEV),arm-nuttx-elf-) + LDFLAGS += -nostartfiles -nodefaultlibs +endif +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + LDFLAGS += -g +endif + + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -Wundef -g -pipe +HOSTLDFLAGS = diff --git a/configs/nucleo-f091rc/nsh/defconfig b/configs/nucleo-f091rc/nsh/defconfig new file mode 100644 index 0000000000..54bf325dca --- /dev/null +++ b/configs/nucleo-f091rc/nsh/defconfig @@ -0,0 +1,1118 @@ +# +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# + +# +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set +CONFIG_DEFAULT_SMALL=y +CONFIG_HOST_LINUX=y +# CONFIG_HOST_OSX is not set +# CONFIG_HOST_WINDOWS is not set +# CONFIG_HOST_OTHER is not set + +# +# Build Configuration +# +CONFIG_APPS_DIR="../apps" +CONFIG_BUILD_FLAT=y +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +# CONFIG_INTELHEX_BINARY is not set +# CONFIG_MOTOROLA_SREC is not set +CONFIG_RAW_BINARY=y +# CONFIG_UBOOT_UIMAGE is not set + +# +# Customize Header Files +# +# CONFIG_ARCH_STDINT_H is not set +# CONFIG_ARCH_STDBOOL_H is not set +# CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_FLOAT_H is not set +# CONFIG_ARCH_STDARG_H is not set +# CONFIG_ARCH_DEBUG_H is not set + +# +# Debug Options +# +CONFIG_DEBUG_ALERT=y +CONFIG_DEBUG_FEATURES=y + +# +# Debug SYSLOG Output Controls +# +CONFIG_DEBUG_ERROR=y +CONFIG_DEBUG_WARN=y +CONFIG_DEBUG_INFO=y +CONFIG_DEBUG_ASSERTIONS=y + +# +# Subsystem Debug Options +# +# CONFIG_DEBUG_BINFMT is not set +# CONFIG_DEBUG_FS is not set +# CONFIG_DEBUG_GRAPHICS is not set +# CONFIG_DEBUG_LIB is not set +# CONFIG_DEBUG_MM is not set +# CONFIG_DEBUG_SCHED is not set + +# +# OS Function Debug Options +# +# CONFIG_DEBUG_IRQ is not set + +# +# Driver Debug Options +# +# CONFIG_DEBUG_LEDS is not set +# CONFIG_DEBUG_GPIO is not set +# CONFIG_DEBUG_TIMER is not set +CONFIG_ARCH_HAVE_STACKCHECK=y +# CONFIG_STACK_COLORATION is not set +# CONFIG_ARCH_HAVE_HEAPCHECK is not set +CONFIG_DEBUG_SYMBOLS=y +CONFIG_ARCH_HAVE_CUSTOMOPT=y +# CONFIG_DEBUG_NOOPT is not set +# CONFIG_DEBUG_CUSTOMOPT is not set +CONFIG_DEBUG_FULLOPT=y + +# +# System Type +# +CONFIG_ARCH_ARM=y +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_MISOC is not set +# CONFIG_ARCH_RENESAS is not set +# CONFIG_ARCH_RISCV is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_XTENSA is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="arm" + +# +# ARM Options +# +# CONFIG_ARCH_CHIP_A1X is not set +# CONFIG_ARCH_CHIP_C5471 is not set +# CONFIG_ARCH_CHIP_DM320 is not set +# CONFIG_ARCH_CHIP_EFM32 is not set +# CONFIG_ARCH_CHIP_IMX1 is not set +# CONFIG_ARCH_CHIP_IMX6 is not set +# CONFIG_ARCH_CHIP_KINETIS is not set +# CONFIG_ARCH_CHIP_KL is not set +# CONFIG_ARCH_CHIP_LM is not set +# CONFIG_ARCH_CHIP_TIVA is not set +# CONFIG_ARCH_CHIP_LPC11XX is not set +# CONFIG_ARCH_CHIP_LPC17XX is not set +# CONFIG_ARCH_CHIP_LPC214X is not set +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_NUC1XX is not set +# CONFIG_ARCH_CHIP_SAMA5 is not set +# CONFIG_ARCH_CHIP_SAMD is not set +# CONFIG_ARCH_CHIP_SAML is not set +# CONFIG_ARCH_CHIP_SAM34 is not set +# CONFIG_ARCH_CHIP_SAMV7 is not set +# CONFIG_ARCH_CHIP_STM32 is not set +CONFIG_ARCH_CHIP_STM32F0=y +# CONFIG_ARCH_CHIP_STM32F7 is not set +# CONFIG_ARCH_CHIP_STM32L4 is not set +# CONFIG_ARCH_CHIP_STR71X is not set +# CONFIG_ARCH_CHIP_TMS570 is not set +# CONFIG_ARCH_CHIP_XMC4 is not set +# CONFIG_ARCH_ARM7TDMI is not set +# CONFIG_ARCH_ARM926EJS is not set +# CONFIG_ARCH_ARM920T is not set +CONFIG_ARCH_CORTEXM0=y +# CONFIG_ARCH_CORTEXM23 is not set +# CONFIG_ARCH_CORTEXM3 is not set +# CONFIG_ARCH_CORTEXM33 is not set +# CONFIG_ARCH_CORTEXM4 is not set +# CONFIG_ARCH_CORTEXM7 is not set +# CONFIG_ARCH_CORTEXA5 is not set +# CONFIG_ARCH_CORTEXA8 is not set +# CONFIG_ARCH_CORTEXA9 is not set +# CONFIG_ARCH_CORTEXR4 is not set +# CONFIG_ARCH_CORTEXR4F is not set +# CONFIG_ARCH_CORTEXR5 is not set +# CONFIG_ARCH_CORTEX5F is not set +# CONFIG_ARCH_CORTEXR7 is not set +# CONFIG_ARCH_CORTEXR7F is not set +CONFIG_ARCH_FAMILY="armv6-m" +CONFIG_ARCH_CHIP="stm32f0" +# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARM_TOOLCHAIN_GNU is not set +CONFIG_ARCH_HAVE_CMNVECTOR=y +# CONFIG_ARMV7M_CMNVECTOR is not set +# CONFIG_ARMV7M_LAZYFPU is not set +# CONFIG_ARCH_HAVE_FPU is not set +# CONFIG_ARCH_HAVE_DPFPU is not set +# CONFIG_ARCH_HAVE_TRUSTZONE is not set +# CONFIG_ARM_HAVE_MPU_UNIFIED is not set + +# +# ARMV6M Configuration Options +# +# CONFIG_ARMV6M_TOOLCHAIN_BUILDROOT is not set +# CONFIG_ARMV6M_TOOLCHAIN_CODEREDL is not set +# CONFIG_ARMV6M_TOOLCHAIN_CODESOURCERYL is not set +CONFIG_ARMV6M_TOOLCHAIN_GNU_EABIL=y +# CONFIG_SERIAL_TERMIOS is not set +# CONFIG_USART2_RS485 is not set + +# +# STM32F0xx Configuration Options +# +# CONFIG_ARCH_CHIP_STM32F030C6 is not set +# CONFIG_ARCH_CHIP_STM32F030C8 is not set +# CONFIG_ARCH_CHIP_STM32F030CC is not set +# CONFIG_ARCH_CHIP_STM32F030F4 is not set +# CONFIG_ARCH_CHIP_STM32F030K6 is not set +# CONFIG_ARCH_CHIP_STM32F030R8 is not set +# CONFIG_ARCH_CHIP_STM32F030RC is not set +# CONFIG_ARCH_CHIP_STM32F031C4 is not set +# CONFIG_ARCH_CHIP_STM32F031C6 is not set +# CONFIG_ARCH_CHIP_STM32F031E6 is not set +# CONFIG_ARCH_CHIP_STM32F031F4 is not set +# CONFIG_ARCH_CHIP_STM32F031F6 is not set +# CONFIG_ARCH_CHIP_STM32F031G4 is not set +# CONFIG_ARCH_CHIP_STM32F031G6 is not set +# CONFIG_ARCH_CHIP_STM32F031K4 is not set +# CONFIG_ARCH_CHIP_STM32F031K6 is not set +# CONFIG_ARCH_CHIP_STM32F038C6 is not set +# CONFIG_ARCH_CHIP_STM32F038E6 is not set +# CONFIG_ARCH_CHIP_STM32F038F6 is not set +# CONFIG_ARCH_CHIP_STM32F038G6 is not set +# CONFIG_ARCH_CHIP_STM32F038K6 is not set +# CONFIG_ARCH_CHIP_STM32F042C4 is not set +# CONFIG_ARCH_CHIP_STM32F042C6 is not set +# CONFIG_ARCH_CHIP_STM32F042F4 is not set +# CONFIG_ARCH_CHIP_STM32F042F6 is not set +# CONFIG_ARCH_CHIP_STM32F042G4 is not set +# CONFIG_ARCH_CHIP_STM32F042G6 is not set +# CONFIG_ARCH_CHIP_STM32F042K4 is not set +# CONFIG_ARCH_CHIP_STM32F042K6 is not set +# CONFIG_ARCH_CHIP_STM32F042T6 is not set +# CONFIG_ARCH_CHIP_STM32F048C6 is not set +# CONFIG_ARCH_CHIP_STM32F048G6 is not set +# CONFIG_ARCH_CHIP_STM32F048T6 is not set +# CONFIG_ARCH_CHIP_STM32F051C4 is not set +# CONFIG_ARCH_CHIP_STM32F051C6 is not set +# CONFIG_ARCH_CHIP_STM32F051C8 is not set +# CONFIG_ARCH_CHIP_STM32F051K4 is not set +# CONFIG_ARCH_CHIP_STM32F051K6 is not set +# CONFIG_ARCH_CHIP_STM32F051K8 is not set +# CONFIG_ARCH_CHIP_STM32F051R4 is not set +# CONFIG_ARCH_CHIP_STM32F051R6 is not set +# CONFIG_ARCH_CHIP_STM32F051R8 is not set +# CONFIG_ARCH_CHIP_STM32F051T8 is not set +# CONFIG_ARCH_CHIP_STM32F058C8 is not set +# CONFIG_ARCH_CHIP_STM32F058R8 is not set +# CONFIG_ARCH_CHIP_STM32F058T8 is not set +# CONFIG_ARCH_CHIP_STM32F070C6 is not set +# CONFIG_ARCH_CHIP_STM32F070CB is not set +# CONFIG_ARCH_CHIP_STM32F070F6 is not set +# CONFIG_ARCH_CHIP_STM32F070RB is not set +# CONFIG_ARCH_CHIP_STM32F071C8 is not set +# CONFIG_ARCH_CHIP_STM32F071CB is not set +# CONFIG_ARCH_CHIP_STM32F071RB is not set +# CONFIG_ARCH_CHIP_STM32F071V8 is not set +# CONFIG_ARCH_CHIP_STM32F071VB is not set +# CONFIG_ARCH_CHIP_STM32F072C8 is not set +# CONFIG_ARCH_CHIP_STM32F072CB is not set +# CONFIG_ARCH_CHIP_STM32F072R8 is not set +# CONFIG_ARCH_CHIP_STM32F072RB is not set +# CONFIG_ARCH_CHIP_STM32F072V8 is not set +# CONFIG_ARCH_CHIP_STM32F072VB is not set +# CONFIG_ARCH_CHIP_STM32F078CB is not set +# CONFIG_ARCH_CHIP_STM32F078RB is not set +# CONFIG_ARCH_CHIP_STM32F078VB is not set +# CONFIG_ARCH_CHIP_STM32F091CB is not set +# CONFIG_ARCH_CHIP_STM32F091CC is not set +# CONFIG_ARCH_CHIP_STM32F091RB is not set +CONFIG_ARCH_CHIP_STM32F091RC=y +# CONFIG_ARCH_CHIP_STM32F091VB is not set +# CONFIG_ARCH_CHIP_STM32F091VC is not set +# CONFIG_ARCH_CHIP_STM32F098CC is not set +# CONFIG_ARCH_CHIP_STM32F098RC is not set +# CONFIG_ARCH_CHIP_STM32F098VC is not set +# CONFIG_STM32F0_STM32F03X is not set +# CONFIG_STM32F0_STM32F04X is not set +# CONFIG_STM32F0_STM32F05X is not set +# CONFIG_STM32F0_STM32F07X is not set +CONFIG_STM32F0_STM32F09X=y +# CONFIG_STM32F0_VALUELINE is not set +CONFIG_STM32F0_ACCESSLINE=y +# CONFIG_STM32F0_LOWVOLTLINE is not set +# CONFIG_STM32F0_USBLINE is not set +# CONFIG_STM32F0_DFU is not set +CONFIG_STM32F0_SYSTICK_CORECLK=y +# CONFIG_STM32F0_SYSTICK_CORECLK_DIV16 is not set + +# +# STM32 Peripheral Support +# +# CONFIG_STM32F0_HAVE_CCM is not set +CONFIG_STM32F0_HAVE_HSI48=y +# CONFIG_STM32F0_HAVE_USBDEV is not set +# CONFIG_STM32F0_HAVE_FSMC is not set +# CONFIG_STM32F0_HAVE_HRTIM1 is not set +CONFIG_STM32F0_HAVE_USART3=y +CONFIG_STM32F0_HAVE_USART4=y +CONFIG_STM32F0_HAVE_USART5=y +# CONFIG_STM32F0_HAVE_USART6 is not set +# CONFIG_STM32F0_HAVE_USART7 is not set +# CONFIG_STM32F0_HAVE_USART8 is not set +CONFIG_STM32F0_HAVE_TIM1=y +CONFIG_STM32F0_HAVE_TIM2=y +CONFIG_STM32F0_HAVE_TIM3=y +CONFIG_STM32F0_HAVE_TIM6=y +CONFIG_STM32F0_HAVE_TIM7=y +CONFIG_STM32F0_HAVE_TIM14=y +CONFIG_STM32F0_HAVE_TIM15=y +CONFIG_STM32F0_HAVE_TIM16=y +CONFIG_STM32F0_HAVE_TIM17=y +# CONFIG_STM32F0_HAVE_TSC is not set +CONFIG_STM32F0_HAVE_ADC2=y +# CONFIG_STM32F0_HAVE_ADC3 is not set +# CONFIG_STM32F0_HAVE_ADC4 is not set +# CONFIG_STM32F0_HAVE_ADC1_DMA is not set +# CONFIG_STM32F0_HAVE_ADC2_DMA is not set +# CONFIG_STM32F0_HAVE_ADC3_DMA is not set +# CONFIG_STM32F0_HAVE_ADC4_DMA is not set +# CONFIG_STM32F0_HAVE_SDADC1 is not set +# CONFIG_STM32F0_HAVE_SDADC2 is not set +# CONFIG_STM32F0_HAVE_SDADC3 is not set +# CONFIG_STM32F0_HAVE_SDADC1_DMA is not set +# CONFIG_STM32F0_HAVE_SDADC2_DMA is not set +# CONFIG_STM32F0_HAVE_SDADC3_DMA is not set +CONFIG_STM32F0_HAVE_CAN1=y +# CONFIG_STM32F0_HAVE_COMP1 is not set +# CONFIG_STM32F0_HAVE_COMP2 is not set +# CONFIG_STM32F0_HAVE_COMP3 is not set +# CONFIG_STM32F0_HAVE_COMP4 is not set +# CONFIG_STM32F0_HAVE_COMP5 is not set +# CONFIG_STM32F0_HAVE_COMP6 is not set +# CONFIG_STM32F0_HAVE_COMP7 is not set +# CONFIG_STM32F0_HAVE_DAC1 is not set +# CONFIG_STM32F0_HAVE_DAC2 is not set +# CONFIG_STM32F0_HAVE_RNG is not set +# CONFIG_STM32F0_HAVE_I2C2 is not set +# CONFIG_STM32F0_HAVE_I2C3 is not set +CONFIG_STM32F0_HAVE_SPI2=y +CONFIG_STM32F0_HAVE_SPI3=y +# CONFIG_STM32F0_HAVE_SPI4 is not set +# CONFIG_STM32F0_HAVE_SPI5 is not set +# CONFIG_STM32F0_HAVE_SPI6 is not set +# CONFIG_STM32F0_HAVE_SAIPLL is not set +# CONFIG_STM32F0_HAVE_I2SPLL is not set +# CONFIG_STM32F0_HAVE_OPAMP1 is not set +# CONFIG_STM32F0_HAVE_OPAMP2 is not set +# CONFIG_STM32F0_HAVE_OPAMP3 is not set +# CONFIG_STM32F0_HAVE_OPAMP4 is not set +# CONFIG_STM32F0_ADC1 is not set +# CONFIG_STM32F0_ADC2 is not set +# CONFIG_STM32F0_COMP is not set +# CONFIG_STM32F0_BKP is not set +# CONFIG_STM32F0_BKPSRAM is not set +# CONFIG_STM32F0_CAN1 is not set +# CONFIG_STM32F0_CRC is not set +# CONFIG_STM32F0_DMA1 is not set +# CONFIG_STM32F0_DMA2 is not set +# CONFIG_STM32F0_I2C1 is not set +CONFIG_STM32F0_PWR=y +# CONFIG_STM32F0_SDIO is not set +# CONFIG_STM32F0_SPI1 is not set +# CONFIG_STM32F0_SPI2 is not set +# CONFIG_STM32F0_SPI3 is not set +CONFIG_STM32F0_SYSCFG=y +# CONFIG_STM32F0_TIM1 is not set +# CONFIG_STM32F0_TIM2 is not set +# CONFIG_STM32F0_TIM3 is not set +# CONFIG_STM32F0_TIM6 is not set +# CONFIG_STM32F0_TIM7 is not set +# CONFIG_STM32F0_TIM14 is not set +# CONFIG_STM32F0_TIM15 is not set +# CONFIG_STM32F0_TIM16 is not set +# CONFIG_STM32F0_TIM17 is not set +# CONFIG_STM32F0_USART1 is not set +CONFIG_STM32F0_USART2=y +# CONFIG_STM32F0_USART3 is not set +# CONFIG_STM32F0_USART4 is not set +# CONFIG_STM32F0_USART5 is not set +# CONFIG_STM32F0_IWDG is not set +# CONFIG_STM32F0_WWDG is not set +CONFIG_STM32F0_USART=y +CONFIG_STM32F0_SERIALDRIVER=y + +# +# U[S]ART Configuration +# + +# +# U[S]ART Device Configuration +# +CONFIG_STM32F0_USART2_SERIALDRIVER=y +# CONFIG_STM32F0_USART2_1WIREDRIVER is not set + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_VECNOTIRQ is not set +# CONFIG_ARCH_DMA is not set +CONFIG_ARCH_HAVE_IRQPRIO=y +# CONFIG_ARCH_L2CACHE is not set +# CONFIG_ARCH_HAVE_COHERENT_DCACHE is not set +# CONFIG_ARCH_HAVE_ADDRENV is not set +# CONFIG_ARCH_NEED_ADDRENV_MAPPING is not set +# CONFIG_ARCH_HAVE_MULTICPU is not set +CONFIG_ARCH_HAVE_VFORK=y +# CONFIG_ARCH_HAVE_MMU is not set +# CONFIG_ARCH_HAVE_MPU is not set +# CONFIG_ARCH_NAND_HWECC is not set +# CONFIG_ARCH_HAVE_EXTCLK is not set +# CONFIG_ARCH_HAVE_POWEROFF is not set +CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_IRQPRIO is not set +CONFIG_ARCH_STACKDUMP=y +# CONFIG_ENDIAN_BIG is not set +# CONFIG_ARCH_IDLE_CUSTOM is not set +# CONFIG_ARCH_HAVE_RAMFUNCS is not set +# CONFIG_ARCH_HAVE_RAMVECTORS is not set +# CONFIG_ARCH_MINIMAL_VECTORTABLE is not set + +# +# Board Settings +# +CONFIG_BOARD_LOOPSPERMSEC=2796 +# CONFIG_ARCH_CALIBRATION is not set + +# +# Interrupt options +# +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y +CONFIG_ARCH_INTERRUPTSTACK=0 +# CONFIG_ARCH_HAVE_HIPRI_INTERRUPT is not set + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Boot Memory Configuration +# +CONFIG_RAM_START=0x20000000 +CONFIG_RAM_SIZE=32768 +# CONFIG_ARCH_HAVE_SDRAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_NUCLEO_F091RC=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="nucleo-f091rc" + +# +# Common Board Options +# +CONFIG_ARCH_HAVE_LEDS=y +CONFIG_ARCH_LEDS=y +CONFIG_ARCH_HAVE_BUTTONS=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_HAVE_IRQBUTTONS=y +CONFIG_ARCH_IRQBUTTONS=y + +# +# Board-Specific Options +# +# CONFIG_BOARD_CRASHDUMP is not set +CONFIG_LIB_BOARDCTL=y +# CONFIG_BOARDCTL_RESET is not set +# CONFIG_BOARDCTL_UNIQUEID is not set +# CONFIG_BOARDCTL_TSCTEST is not set +# CONFIG_BOARDCTL_GRAPHICS is not set +# CONFIG_BOARDCTL_IOCTL is not set + +# +# RTOS Features +# +CONFIG_DISABLE_OS_API=y +CONFIG_DISABLE_POSIX_TIMERS=y +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_DISABLE_SIGNALS is not set +CONFIG_DISABLE_MQUEUE=y +CONFIG_DISABLE_ENVIRON=y + +# +# Clocks and Timers +# +CONFIG_USEC_PER_TICK=10000 +# CONFIG_SYSTEM_TIME64 is not set +# CONFIG_CLOCK_MONOTONIC is not set +# CONFIG_ARCH_HAVE_TIMEKEEPING is not set +# CONFIG_JULIAN_TIME is not set +CONFIG_START_YEAR=2013 +CONFIG_START_MONTH=5 +CONFIG_START_DAY=19 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=4 +CONFIG_WDOG_INTRESERVE=0 +CONFIG_PREALLOC_TIMERS=0 + +# +# Tasks and Scheduling +# +# CONFIG_SPINLOCK is not set +# CONFIG_INIT_NONE is not set +CONFIG_INIT_ENTRYPOINT=y +# CONFIG_INIT_FILEPATH is not set +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_RR_INTERVAL=200 +# CONFIG_SCHED_SPORADIC is not set +CONFIG_TASK_NAME_SIZE=0 +CONFIG_MAX_TASKS=8 +# CONFIG_SCHED_HAVE_PARENT is not set +CONFIG_SCHED_WAITPID=y + +# +# Pthread Options +# +# CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set +CONFIG_NPTHREAD_KEYS=0 +# CONFIG_PTHREAD_CLEANUP is not set +# CONFIG_CANCELLATION_POINTS is not set + +# +# Performance Monitoring +# +# CONFIG_SCHED_CPULOAD is not set +# CONFIG_SCHED_INSTRUMENTATION is not set + +# +# Files and I/O +# +CONFIG_DEV_CONSOLE=y +# CONFIG_FDCLONE_DISABLE is not set +# CONFIG_FDCLONE_STDIO is not set +CONFIG_SDCLONE_DISABLE=y +CONFIG_NFILE_DESCRIPTORS=6 +CONFIG_NFILE_STREAMS=6 +CONFIG_NAME_MAX=32 +# CONFIG_PRIORITY_INHERITANCE is not set + +# +# RTOS hooks +# +# CONFIG_BOARD_INITIALIZE is not set +# CONFIG_SCHED_STARTHOOK is not set +# CONFIG_SCHED_ATEXIT is not set +# CONFIG_SCHED_ONEXIT is not set + +# +# Signal Numbers +# +CONFIG_SIG_SIGUSR1=1 +CONFIG_SIG_SIGUSR2=2 +CONFIG_SIG_SIGALARM=3 +CONFIG_SIG_SIGCONDTIMEDOUT=16 +# CONFIG_MODULE is not set + +# +# Work queue support +# +# CONFIG_SCHED_WORKQUEUE is not set +# CONFIG_SCHED_HPWORK is not set +# CONFIG_SCHED_LPWORK is not set + +# +# Stack and heap information +# +CONFIG_IDLETHREAD_STACKSIZE=1024 +CONFIG_USERMAIN_STACKSIZE=1536 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=1536 +# CONFIG_LIB_SYSCALL is not set + +# +# Device Drivers +# +CONFIG_DISABLE_POLL=y +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_DEV_URANDOM is not set +# CONFIG_DEV_LOOP is not set + +# +# Buffering +# + +# +# Common I/O Buffer Support +# +# CONFIG_DRIVERS_IOB is not set +# CONFIG_DRVR_WRITEBUFFER is not set +# CONFIG_DRVR_READAHEAD is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_ARCH_HAVE_PWM_PULSECOUNT is not set +# CONFIG_ARCH_HAVE_PWM_MULTICHAN is not set +# CONFIG_PWM is not set +# CONFIG_ARCH_HAVE_I2CRESET is not set +# CONFIG_I2C is not set +# CONFIG_ARCH_HAVE_SPI_CRCGENERATION is not set +# CONFIG_ARCH_HAVE_SPI_CS_CONTROL is not set +# CONFIG_ARCH_HAVE_SPI_BITORDER is not set +# CONFIG_SPI is not set +# CONFIG_I2S is not set + +# +# Timer Driver Support +# +# CONFIG_TIMER is not set +# CONFIG_ONESHOT is not set +# CONFIG_RTC is not set +# CONFIG_WATCHDOG is not set +# CONFIG_ANALOG is not set +# CONFIG_AUDIO_DEVICES is not set +# CONFIG_VIDEO_DEVICES is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set + +# +# IO Expander/GPIO Support +# +# CONFIG_IOEXPANDER is not set +# CONFIG_DEV_GPIO is not set + +# +# LCD Driver Support +# +# CONFIG_LCD is not set +# CONFIG_SLCD is not set + +# +# LED Support +# +# CONFIG_USERLED is not set +# CONFIG_RGBLED is not set +# CONFIG_PCA9635PW is not set +# CONFIG_NCP5623C is not set +# CONFIG_MMCSD is not set +# CONFIG_MODEM is not set +# CONFIG_MTD is not set +# CONFIG_EEPROM is not set +# CONFIG_PIPES is not set +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +CONFIG_SERIAL=y +# CONFIG_DEV_LOWCONSOLE is not set +# CONFIG_SERIAL_REMOVABLE is not set +CONFIG_SERIAL_CONSOLE=y +# CONFIG_16550_UART is not set +# CONFIG_UART_SERIALDRIVER is not set +# CONFIG_UART0_SERIALDRIVER is not set +# CONFIG_UART1_SERIALDRIVER is not set +# CONFIG_UART2_SERIALDRIVER is not set +# CONFIG_UART3_SERIALDRIVER is not set +# CONFIG_UART4_SERIALDRIVER is not set +# CONFIG_UART5_SERIALDRIVER is not set +# CONFIG_UART6_SERIALDRIVER is not set +# CONFIG_UART7_SERIALDRIVER is not set +# CONFIG_UART8_SERIALDRIVER is not set +# CONFIG_SCI0_SERIALDRIVER is not set +# CONFIG_SCI1_SERIALDRIVER is not set +# CONFIG_USART0_SERIALDRIVER is not set +# CONFIG_USART1_SERIALDRIVER is not set +CONFIG_USART2_SERIALDRIVER=y +# CONFIG_USART3_SERIALDRIVER is not set +# CONFIG_USART4_SERIALDRIVER is not set +# CONFIG_USART5_SERIALDRIVER is not set +# CONFIG_USART6_SERIALDRIVER is not set +# CONFIG_USART7_SERIALDRIVER is not set +# CONFIG_USART8_SERIALDRIVER is not set +# CONFIG_OTHER_UART_SERIALDRIVER is not set +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +# CONFIG_SERIAL_IFLOWCONTROL is not set +# CONFIG_SERIAL_OFLOWCONTROL is not set +# CONFIG_SERIAL_DMA is not set +# CONFIG_SERIAL_TIOCSERGSTRUCT is not set +CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y +CONFIG_USART2_SERIAL_CONSOLE=y +# CONFIG_OTHER_SERIAL_CONSOLE is not set +# CONFIG_NO_SERIAL_CONSOLE is not set + +# +# USART2 Configuration +# +CONFIG_USART2_RXBUFSIZE=256 +CONFIG_USART2_TXBUFSIZE=256 +CONFIG_USART2_BAUD=115200 +CONFIG_USART2_BITS=8 +CONFIG_USART2_PARITY=0 +CONFIG_USART2_2STOP=0 +# CONFIG_USART2_IFLOWCONTROL is not set +# CONFIG_USART2_OFLOWCONTROL is not set +# CONFIG_USART2_DMA is not set +# CONFIG_PSEUDOTERM is not set +# CONFIG_USBDEV is not set +# CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set +# CONFIG_HAVE_USBTRACE is not set +# CONFIG_DRIVERS_WIRELESS is not set +# CONFIG_DRIVERS_CONTACTLESS is not set + +# +# System Logging +# +# CONFIG_ARCH_SYSLOG is not set +# CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_INTBUFFER is not set +# CONFIG_SYSLOG_TIMESTAMP is not set +CONFIG_SYSLOG_SERIAL_CONSOLE=y +# CONFIG_SYSLOG_CHAR is not set +CONFIG_SYSLOG_CONSOLE=y +# CONFIG_SYSLOG_NONE is not set +# CONFIG_SYSLOG_FILE is not set +# CONFIG_SYSLOG_CHARDEV is not set + +# +# Networking Support +# +# CONFIG_ARCH_HAVE_NET is not set +# CONFIG_ARCH_HAVE_PHY is not set +# CONFIG_NET is not set + +# +# Crypto API +# +# CONFIG_CRYPTO is not set + +# +# File Systems +# + +# +# File system configuration +# +# CONFIG_DISABLE_MOUNTPOINT is not set +# CONFIG_FS_AUTOMOUNTER is not set +CONFIG_DISABLE_PSEUDOFS_OPERATIONS=y +CONFIG_FS_READABLE=y +# CONFIG_FS_WRITABLE is not set +# CONFIG_FS_NAMED_SEMAPHORES is not set +# CONFIG_FS_RAMMAP is not set +# CONFIG_FS_FAT is not set +# CONFIG_FS_NXFFS is not set +# CONFIG_FS_ROMFS is not set +# CONFIG_FS_TMPFS is not set +# CONFIG_FS_SMARTFS is not set +# CONFIG_FS_BINFS is not set +CONFIG_FS_PROCFS=y +# CONFIG_FS_PROCFS_REGISTER is not set + +# +# Exclude individual procfs entries +# +# CONFIG_FS_PROCFS_EXCLUDE_PROCESS is not set +# CONFIG_FS_PROCFS_EXCLUDE_UPTIME is not set +# CONFIG_FS_PROCFS_EXCLUDE_MOUNTS is not set +# CONFIG_FS_UNIONFS is not set + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +CONFIG_MM_SMALL=y +CONFIG_MM_REGIONS=1 +# CONFIG_ARCH_HAVE_HEAP2 is not set +# CONFIG_GRAN is not set + +# +# Audio Support +# +# CONFIG_AUDIO is not set + +# +# Wireless Support +# + +# +# Binary Loader +# +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +CONFIG_BUILTIN=y +# CONFIG_PIC is not set +# CONFIG_SYMTAB_ORDEREDBYNAME is not set + +# +# Library Routines +# + +# +# Standard C Library Options +# + +# +# Standard C I/O +# +CONFIG_STDIO_DISABLE_BUFFERING=y +CONFIG_NUNGET_CHARS=0 +# CONFIG_NOPRINTF_FIELDWIDTH is not set +# CONFIG_LIBC_FLOATINGPOINT is not set +# CONFIG_LIBC_LONG_LONG is not set +# CONFIG_LIBC_SCANSET is not set +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_MEMCPY_VIK is not set +# CONFIG_LIBM is not set + +# +# Architecture-Specific Support +# +CONFIG_ARCH_LOWPUTC=y +# CONFIG_ARCH_ROMGETC is not set +# CONFIG_LIBC_ARCH_MEMCPY is not set +# CONFIG_LIBC_ARCH_MEMCMP is not set +# CONFIG_LIBC_ARCH_MEMMOVE is not set +# CONFIG_LIBC_ARCH_MEMSET is not set +# CONFIG_LIBC_ARCH_STRCHR is not set +# CONFIG_LIBC_ARCH_STRCMP is not set +# CONFIG_LIBC_ARCH_STRCPY is not set +# CONFIG_LIBC_ARCH_STRNCPY is not set +# CONFIG_LIBC_ARCH_STRLEN is not set +# CONFIG_LIBC_ARCH_STRNLEN is not set +# CONFIG_LIBC_ARCH_ELF is not set + +# +# stdlib Options +# +CONFIG_LIB_RAND_ORDER=1 + +# +# Program Execution Options +# +# CONFIG_LIBC_EXECFUNCS is not set +CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024 +CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=1536 + +# +# errno Decode Support +# +# CONFIG_LIBC_STRERROR is not set +# CONFIG_LIBC_PERROR_STDOUT is not set + +# +# memcpy/memset Options +# +# CONFIG_MEMSET_OPTSPEED is not set +# CONFIG_LIBC_DLLFCN is not set +# CONFIG_LIBC_MODLIB is not set +# CONFIG_LIBC_WCHAR is not set +# CONFIG_LIBC_LOCALE is not set + +# +# Time/Time Zone Support +# +# CONFIG_TIME_EXTENDED is not set +CONFIG_ARCH_HAVE_TLS=y + +# +# Thread Local Storage (TLS) +# +# CONFIG_TLS is not set + +# +# Network-Related Options +# +# CONFIG_LIBC_IPv4_ADDRCONV is not set +# CONFIG_LIBC_IPv6_ADDRCONV is not set +# CONFIG_LIBC_NETDB is not set + +# +# NETDB Support +# +# CONFIG_NETDB_HOSTFILE is not set +# CONFIG_LIBC_IOCTL_VARIADIC is not set +CONFIG_LIB_SENDFILE_BUFSIZE=512 + +# +# Non-standard Library Support +# +# CONFIG_LIB_CRC64_FAST is not set +# CONFIG_LIB_KBDCODEC is not set +# CONFIG_LIB_SLCDCODEC is not set +# CONFIG_LIB_HEX2BIN is not set + +# +# Basic CXX Support +# +# CONFIG_C99_BOOL8 is not set +# CONFIG_HAVE_CXX is not set + +# +# Application Configuration +# + +# +# Built-In Applications +# +CONFIG_BUILTIN_PROXY_STACKSIZE=1024 + +# +# CAN Utilities +# + +# +# Examples +# +# CONFIG_EXAMPLES_BUTTONS is not set +# CONFIG_EXAMPLES_CCTYPE is not set +# CONFIG_EXAMPLES_CHAT is not set +# CONFIG_EXAMPLES_CONFIGDATA is not set +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HIDKBD is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_JSON is not set +# CONFIG_EXAMPLES_KEYPADTEST is not set +# CONFIG_EXAMPLES_MEDIA is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MODBUS is not set +# CONFIG_EXAMPLES_MOUNT is not set +CONFIG_EXAMPLES_NSH=y +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXLINES is not set +# CONFIG_EXAMPLES_NXTERM is not set +# CONFIG_EXAMPLES_NXTEXT is not set +# CONFIG_EXAMPLES_OSTEST is not set +# CONFIG_EXAMPLES_PCA9635 is not set +# CONFIG_EXAMPLES_POSIXSPAWN is not set +# CONFIG_EXAMPLES_PPPD is not set +# CONFIG_EXAMPLES_RFID_READUID is not set +# CONFIG_EXAMPLES_RGBLED is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERIALBLASTER is not set +# CONFIG_EXAMPLES_SERIALRX is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_SLCD is not set +# CONFIG_EXAMPLES_SMART is not set +# CONFIG_EXAMPLES_SMART_TEST is not set +# CONFIG_EXAMPLES_SMP is not set +# CONFIG_EXAMPLES_STAT is not set +# CONFIG_EXAMPLES_TCPECHO is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_USBSERIAL is not set +# CONFIG_EXAMPLES_WATCHDOG is not set +# CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set + +# +# File System Utilities +# +# CONFIG_FSUTILS_INIFILE is not set +# CONFIG_FSUTILS_PASSWD is not set + +# +# GPS Utilities +# +# CONFIG_GPSUTILS_MINMEA_LIB is not set + +# +# Graphics Support +# +# CONFIG_TIFF is not set +# CONFIG_GRAPHICS_TRAVELER is not set + +# +# Interpreters +# +# CONFIG_INTERPRETERS_BAS is not set +# CONFIG_INTERPRETERS_FICL is not set +# CONFIG_INTERPRETERS_MICROPYTHON is not set +# CONFIG_INTERPRETERS_MINIBASIC is not set +# CONFIG_INTERPRETERS_PCODE is not set + +# +# FreeModBus +# +# CONFIG_MODBUS is not set + +# +# Network Utilities +# +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_ESP8266 is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_JSON is not set +# CONFIG_NETUTILS_SMTP is not set + +# +# NSH Library +# +CONFIG_NSH_LIBRARY=y +# CONFIG_NSH_MOTD is not set + +# +# Command Line Configuration +# +CONFIG_NSH_READLINE=y +# CONFIG_NSH_CLE is not set +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_DISABLE_SEMICOLON=y +# CONFIG_NSH_CMDPARMS is not set +CONFIG_NSH_MAXARGUMENTS=6 +# CONFIG_NSH_ARGCAT is not set +CONFIG_NSH_NESTDEPTH=3 +# CONFIG_NSH_DISABLEBG is not set +CONFIG_NSH_BUILTIN_APPS=y + +# +# Disable Individual commands +# +CONFIG_NSH_DISABLE_ADDROUTE=y +CONFIG_NSH_DISABLE_BASENAME=y +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +CONFIG_NSH_DISABLE_CP=y +CONFIG_NSH_DISABLE_CMP=y +CONFIG_NSH_DISABLE_DATE=y +CONFIG_NSH_DISABLE_DD=y +CONFIG_NSH_DISABLE_DF=y +CONFIG_NSH_DISABLE_DELROUTE=y +CONFIG_NSH_DISABLE_DIRNAME=y +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_FREE is not set +CONFIG_NSH_DISABLE_GET=y +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_HEXDUMP is not set +CONFIG_NSH_DISABLE_IFCONFIG=y +CONFIG_NSH_DISABLE_IFUPDOWN=y +# CONFIG_NSH_DISABLE_KILL is not set +CONFIG_NSH_DISABLE_LOSETUP=y +CONFIG_NSH_DISABLE_LOSMART=y +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MB is not set +CONFIG_NSH_DISABLE_MKDIR=y +CONFIG_NSH_DISABLE_MKRD=y +# CONFIG_NSH_DISABLE_MH is not set +CONFIG_NSH_DISABLE_MOUNT=y +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_MW is not set +CONFIG_NSH_DISABLE_PRINTF=y +# CONFIG_NSH_DISABLE_PS is not set +CONFIG_NSH_DISABLE_PUT=y +# CONFIG_NSH_DISABLE_PWD is not set +CONFIG_NSH_DISABLE_RM=y +CONFIG_NSH_DISABLE_RMDIR=y +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SH is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +CONFIG_NSH_DISABLE_TIME=y +# CONFIG_NSH_DISABLE_TEST is not set +CONFIG_NSH_DISABLE_UMOUNT=y +CONFIG_NSH_DISABLE_UNAME=y +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_NSH_DISABLE_WGET=y +# CONFIG_NSH_DISABLE_XD is not set +CONFIG_NSH_MMCSDMINOR=0 + +# +# Configure Command Options +# +CONFIG_NSH_CODECS_BUFSIZE=128 +# CONFIG_NSH_CMDOPT_HEXDUMP is not set +CONFIG_NSH_PROC_MOUNTPOINT="/proc" +CONFIG_NSH_FILEIOSIZE=64 + +# +# Scripting Support +# +CONFIG_NSH_DISABLESCRIPT=y + +# +# Console Configuration +# +CONFIG_NSH_CONSOLE=y +# CONFIG_NSH_ALTCONDEV is not set +CONFIG_NSH_ARCHINIT=y +# CONFIG_NSH_LOGIN is not set +# CONFIG_NSH_CONSOLE_LOGIN is not set + +# +# NxWidgets/NxWM +# + +# +# Platform-specific Support +# +# CONFIG_PLATFORM_CONFIGDATA is not set + +# +# System Libraries and NSH Add-Ons +# +# CONFIG_SYSTEM_CLE is not set +# CONFIG_SYSTEM_CUTERM is not set +# CONFIG_SYSTEM_FREE is not set +# CONFIG_SYSTEM_HEX2BIN is not set +# CONFIG_SYSTEM_HEXED is not set +# CONFIG_SYSTEM_INSTALL is not set +# CONFIG_SYSTEM_RAMTEST is not set +CONFIG_READLINE_HAVE_EXTMATCH=y +CONFIG_SYSTEM_READLINE=y +CONFIG_READLINE_ECHO=y +# CONFIG_READLINE_TABCOMPLETION is not set +# CONFIG_READLINE_CMD_HISTORY is not set +# CONFIG_SYSTEM_SUDOKU is not set +# CONFIG_SYSTEM_SYSTEM is not set +# CONFIG_SYSTEM_TEE is not set +# CONFIG_SYSTEM_UBLOXMODEM is not set +# CONFIG_SYSTEM_VI is not set +# CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# diff --git a/configs/nucleo-f091rc/scripts/flash.ld b/configs/nucleo-f091rc/scripts/flash.ld new file mode 100644 index 0000000000..35bd797b0f --- /dev/null +++ b/configs/nucleo-f091rc/scripts/flash.ld @@ -0,0 +1,127 @@ +/**************************************************************************** + * configs/nucleo-f091rc/scripts/flash.ld + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Alan Carvalho de Assis + * + * 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. + * + ****************************************************************************/ + +/* The STM32F091RCT6 has 256Kb of FLASH beginning at address 0x0800:0000 and + * 32Kb of SRAM at address 0x20000000. + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x08000000, LENGTH = 256K + sram (rwx) : ORIGIN = 0x20000000, LENGTH = 32K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +SECTIONS +{ + .text : + { + _stext = ABSOLUTE(.); + *(.vectors) + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + } > flash + + .init_section : + { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : + { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : + { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : + { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : + { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/configs/nucleo-f091rc/src/.gitignore b/configs/nucleo-f091rc/src/.gitignore new file mode 100644 index 0000000000..726d936e1e --- /dev/null +++ b/configs/nucleo-f091rc/src/.gitignore @@ -0,0 +1,2 @@ +/.depend +/Make.dep diff --git a/configs/nucleo-f091rc/src/Makefile b/configs/nucleo-f091rc/src/Makefile new file mode 100644 index 0000000000..03c9119f06 --- /dev/null +++ b/configs/nucleo-f091rc/src/Makefile @@ -0,0 +1,56 @@ +############################################################################ +# configs/nucleo-f091rc/src/Makefile +# +# Copyright (C) 2017 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# Alan Carvalho de Assis +# +# 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. +# +############################################################################ + +-include $(TOPDIR)/Make.defs + +ASRCS = +CSRCS = stm32_boot.c stm32_bringup.c + +ifeq ($(CONFIG_ARCH_LEDS),y) +CSRCS += stm32_autoleds.c +else +CSRCS += stm32_userleds.c +endif + +ifeq ($(CONFIG_ARCH_BUTTONS),y) +CSRCS += stm32_buttons.c +endif + +ifeq ($(CONFIG_LIB_BOARDCTL),y) +CSRCS += stm32_appinit.c +endif + +include $(TOPDIR)/configs/Board.mk diff --git a/configs/nucleo-f091rc/src/nucleo-f091rc.h b/configs/nucleo-f091rc/src/nucleo-f091rc.h new file mode 100644 index 0000000000..4cd683af24 --- /dev/null +++ b/configs/nucleo-f091rc/src/nucleo-f091rc.h @@ -0,0 +1,123 @@ +/**************************************************************************** + * configs/nucleo-f091rc/src/nucleo-f091rc.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Alan Carvalho de Assis + * + * 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 __CONFIGS_NUCLEO_F091RC_SRC_NUCLEO_F091RC_H +#define __CONFIGS_NUCLEO_F091RC_SRC_NUCLEO_F091RC_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +#include "stm32f0_gpio.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ +/* How many SPI modules does this chip support? */ + +#if STM32F0_NSPI < 1 +# undef CONFIG_STM32F0_SPI1 +# undef CONFIG_STM32F0_SPI2 +# undef CONFIG_STM32F0_SPI3 +#elif STM32F0_NSPI < 2 +# undef CONFIG_STM32F0_SPI2 +# undef CONFIG_STM32F0_SPI3 +#elif STM32F0_NSPI < 3 +# undef CONFIG_STM32F0_SPI3 +#endif + +/* Nucleo-F091RC GPIOs ******************************************************/ +/* LED. User LD2: the green LED is a user LED connected to Arduino signal + * D13 corresponding to MCU I/O PA5 (pin 21) or PB13 (pin 34) depending on + * the STM32 target. + * + * - When the I/O is HIGH value, the LED is on. + * - When the I/O is LOW, the LED is off. + */ + +#define GPIO_LD2 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_10MHz | \ + GPIO_OUTPUT_CLEAR | GPIO_PORTA | GPIO_PIN5) + +/* Button definitions *******************************************************/ +/* B1 USER: the user button is connected to the I/O PC13 (pin 2) of the STM32 + * microcontroller. + */ + +#define MIN_IRQBUTTON BUTTON_USER +#define MAX_IRQBUTTON BUTTON_USER +#define NUM_IRQBUTTONS 1 + +#define GPIO_BTN_USER (GPIO_INPUT | GPIO_FLOAT | GPIO_EXTI | \ + GPIO_PORTC | GPIO_PIN13) + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/**************************************************************************** + * Public data + ****************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_bringup + * + * Description: + * Perform architecture-specific initialization + * + * CONFIG_BOARD_INITIALIZE=y : + * Called from board_initialize(). + * + * CONFIG_BOARD_INITIALIZE=n && CONFIG_LIB_BOARDCTL=y : + * Called from the NSH library + * + ****************************************************************************/ + +int stm32_bringup(void); + +#endif /* __ASSEMBLY__ */ +#endif /* __CONFIGS_NUCLEO_F091RC_SRC_NUCLEO_F091RC_H */ diff --git a/configs/nucleo-f091rc/src/stm32_appinit.c b/configs/nucleo-f091rc/src/stm32_appinit.c new file mode 100644 index 0000000000..784c155b6b --- /dev/null +++ b/configs/nucleo-f091rc/src/stm32_appinit.c @@ -0,0 +1,87 @@ +/**************************************************************************** + * config/nucleo-f091rc/src/stm32_appinit.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Alan Carvalho de Assis + * + * 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 "nucleo-f091rc.h" + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; the meaning of the argument is a contract + * between the board-specific initalization logic and the the + * matching application logic. The value cold be such things as a + * mode enumeration value, a set of DIP switch switch settings, a + * pointer to configuration data read from a file or serial FLASH, + * or whatever you would like to do with it. Every implementation + * should accept zero/NULL as a default configuration. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ + +int board_app_initialize(uintptr_t arg) +{ + /* Did we already initialize via board_initialize()? */ + +#ifndef CONFIG_BOARD_INITIALIZE + return stm32_bringup(); +#else + return OK; +#endif +} diff --git a/configs/nucleo-f091rc/src/stm32_autoleds.c b/configs/nucleo-f091rc/src/stm32_autoleds.c new file mode 100644 index 0000000000..1f093e4c8e --- /dev/null +++ b/configs/nucleo-f091rc/src/stm32_autoleds.c @@ -0,0 +1,96 @@ +/**************************************************************************** + * configs/nucleo-f091rc/src/stm32_autoleds.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "up_arch.h" +#include "up_internal.h" +#include "stm32f0_gpio.h" +#include "nucleo-f091rc.h" + +#ifdef CONFIG_ARCH_LEDS + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_autoled_initialize + ****************************************************************************/ + +void board_autoled_initialize(void) +{ + /* Configure LD2 GPIO for output */ + + stm32f0_configgpio(GPIO_LD2); +} + +/**************************************************************************** + * Name: board_autoled_on + ****************************************************************************/ + +void board_autoled_on(int led) +{ + if (led == 1) + { + stm32f0_gpiowrite(GPIO_LD2, true); + } +} + +/**************************************************************************** + * Name: board_autoled_off + ****************************************************************************/ + +void board_autoled_off(int led) +{ + if (led == 1) + { + stm32f0_gpiowrite(GPIO_LD2, false); + } +} + +#endif /* CONFIG_ARCH_LEDS */ diff --git a/configs/nucleo-f091rc/src/stm32_boot.c b/configs/nucleo-f091rc/src/stm32_boot.c new file mode 100644 index 0000000000..5e50fcabba --- /dev/null +++ b/configs/nucleo-f091rc/src/stm32_boot.c @@ -0,0 +1,94 @@ +/************************************************************************************ + * configs/nucleo-f091rc/src/stm32f0_boot.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Alan Carvalho de Assis + * + * 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 "up_arch.h" +#include "nucleo-f091rc.h" + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32f0_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the intitialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +void stm32f0_boardinitialize(void) +{ +#ifdef CONFIG_ARCH_LEDS + /* Configure on-board LEDs if LED support has been selected. */ + + board_autoled_initialize(); +#endif +} + +/**************************************************************************** + * Name: board_initialize + * + * Description: + * If CONFIG_BOARD_INITIALIZE is selected, then an additional + * initialization call will be performed in the boot-up sequence to a + * function called board_initialize(). board_initialize() will be + * called immediately after up_initialize() is called and just before the + * initial application is started. This additional initialization phase + * may be used, for example, to initialize board-specific device drivers. + * + ****************************************************************************/ + +#ifdef CONFIG_BOARD_INITIALIZE +void board_initialize(void) +{ + /* Perform board-specific initialization here if so configured */ + + (void)stm32_bringup(); +} +#endif diff --git a/configs/nucleo-f091rc/src/stm32_bringup.c b/configs/nucleo-f091rc/src/stm32_bringup.c new file mode 100644 index 0000000000..bae9f6aa2c --- /dev/null +++ b/configs/nucleo-f091rc/src/stm32_bringup.c @@ -0,0 +1,82 @@ +/**************************************************************************** + * config/nucleo-f091rc/src/stm32_bringup.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include "nucleo-f091rc.h" + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_bringup + * + * Description: + * Perform architecture-specific initialization + * + * CONFIG_BOARD_INITIALIZE=y : + * Called from board_initialize(). + * + * CONFIG_BOARD_INITIALIZE=n && CONFIG_LIB_BOARDCTL=y : + * Called from the NSH library + * + ****************************************************************************/ + +int stm32_bringup(void) +{ + int ret; + +#ifdef CONFIG_FS_PROCFS + /* Mount the procfs file system */ + + ret = mount(NULL, "/proc", "procfs", 0, NULL); + if (ret < 0) + { + ferr("ERROR: Failed to mount procfs at /proc: %d\n", ret); + } +#endif + + UNUSED(ret); + return OK; +} diff --git a/configs/nucleo-f091rc/src/stm32_buttons.c b/configs/nucleo-f091rc/src/stm32_buttons.c new file mode 100644 index 0000000000..53ada3736b --- /dev/null +++ b/configs/nucleo-f091rc/src/stm32_buttons.c @@ -0,0 +1,128 @@ +/**************************************************************************** + * configs/nucleo-f091rc/src/stm32_buttons.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include +#include +#include + +#include "stm32f0_gpio.h" +#include "nucleo-f091rc.h" + +#ifdef CONFIG_ARCH_BUTTONS + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_button_initialize + * + * Description: + * board_button_initialize() must be called to initialize button resources. + * After that, board_buttons() may be called to collect the current state + * of all buttons or board_button_irq() may be called to register button + * interrupt handlers. + * + ****************************************************************************/ + +void board_button_initialize(void) +{ + /* Configure the single button as an input. NOTE that EXTI interrupts are + * also configured for the pin. + */ + + stm32f0_configgpio(GPIO_BTN_USER); +} + +/**************************************************************************** + * Name: board_buttons + ****************************************************************************/ + +uint32_t board_buttons(void) +{ + /* Check that state of each USER button. A LOW value means that the key is + * pressed. + */ + + bool released = stm32f0_gpioread(GPIO_BTN_USER); + return !released; +} + +/************************************************************************************ + * Button support. + * + * Description: + * board_button_initialize() must be called to initialize button resources. After + * that, board_buttons() may be called to collect the current state of all + * buttons or board_button_irq() may be called to register button interrupt + * handlers. + * + * After board_button_initialize() has been called, board_buttons() may be called to + * collect the state of all buttons. board_buttons() returns an 32-bit bit set + * with each bit associated with a button. See the BUTTON_*_BIT + * definitions in board.h for the meaning of each bit. + * + * board_button_irq() may be called to register an interrupt handler that will + * be called when a button is depressed or released. The ID value is a + * button enumeration value that uniquely identifies a button resource. See the + * BUTTON_* definitions in board.h for the meaning of enumeration + * value. + * + ************************************************************************************/ + +#ifdef CONFIG_ARCH_IRQBUTTONS +int board_button_irq(int id, xcpt_t irqhandler, FAR void *arg) +{ + int ret = -EINVAL; + + if (id == BUTTON_USER) + { + ret = stm32f0_gpiosetevent(GPIO_BTN_USER, true, true, true, irqhandler, arg); + } + + return ret; +} +#endif +#endif /* CONFIG_ARCH_BUTTONS */ diff --git a/configs/nucleo-f091rc/src/stm32_userleds.c b/configs/nucleo-f091rc/src/stm32_userleds.c new file mode 100644 index 0000000000..b13c1882b7 --- /dev/null +++ b/configs/nucleo-f091rc/src/stm32_userleds.c @@ -0,0 +1,217 @@ +/**************************************************************************** + * configs/nucleo-f091rc/src/stm32_userleds.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "up_arch.h" +#include "up_internal.h" +#include "stm32f0_gpio.h" +#include "nucleo-f091rc.h" + +#ifndef CONFIG_ARCH_LEDS + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* LED Power Management */ + +#ifdef CONFIG_PM +static void led_pm_notify(struct pm_callback_s *cb, int domain, + enum pm_state_e pmstate); +static int led_pm_prepare(struct pm_callback_s *cb, int domain, + enum pm_state_e pmstate); +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +#ifdef CONFIG_PM +static struct pm_callback_s g_ledscb = +{ + .notify = led_pm_notify, + .prepare = led_pm_prepare, +}; +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: led_pm_notify + * + * Description: + * Notify the driver of new power state. This callback is called after + * all drivers have had the opportunity to prepare for the new power state. + * + ****************************************************************************/ + +#ifdef CONFIG_PM +static void led_pm_notify(struct pm_callback_s *cb, int domain, + enum pm_state_e pmstate) +{ + switch (pmstate) + { + case(PM_NORMAL): + { + /* Restore normal LEDs operation */ + + } + break; + + case(PM_IDLE): + { + /* Entering IDLE mode - Turn leds off */ + + } + break; + + case(PM_STANDBY): + { + /* Entering STANDBY mode - Logic for PM_STANDBY goes here */ + + } + break; + + case(PM_SLEEP): + { + /* Entering SLEEP mode - Logic for PM_SLEEP goes here */ + + } + break; + + default: + { + /* Should not get here */ + + } + break; + } +} +#endif + +/**************************************************************************** + * Name: led_pm_prepare + * + * Description: + * Request the driver to prepare for a new power state. This is a warning + * that the system is about to enter into a new power state. The driver + * should begin whatever operations that may be required to enter power + * state. The driver may abort the state change mode by returning a + * non-zero value from the callback function. + * + ****************************************************************************/ + +#ifdef CONFIG_PM +static int led_pm_prepare(struct pm_callback_s *cb, int domain, + enum pm_state_e pmstate) +{ + /* No preparation to change power modes is required by the LEDs driver. + * We always accept the state change by returning OK. + */ + + return OK; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_userled_initialize + ****************************************************************************/ + +void board_userled_initialize(void) +{ + /* Configure LD2 GPIO for output */ + + stm32f0_configgpio(GPIO_LD2); +} + +/**************************************************************************** + * Name: board_userled + ****************************************************************************/ + +void board_userled(int led, bool ledon) +{ + if (led == 1) + { + stm32f0_gpiowrite(GPIO_LD2, ldeon); + } +} + +/**************************************************************************** + * Name: board_userled_all + ****************************************************************************/ + +void board_userled_all(uint8_t ledset) +{ + if (led == 1) + { + stm32f0_gpiowrite(GPIO_LD2, (ledset & BOARD_LD2_BIT) != 0); + } +} + +/**************************************************************************** + * Name: stm32f0_led_pminitialize + ****************************************************************************/ + +#ifdef CONFIG_PM +void stm32f0_led_pminitialize(void) +{ + /* Register to receive power management callbacks */ + + int ret = pm_register(&g_ledscb); + DEBUGASSERT(ret == OK); + UNUSED(ret); +} +#endif /* CONFIG_PM */ + +#endif /* !CONFIG_ARCH_LEDS */ -- GitLab From 0eb14e9baacac40c5b019fe80fda57748249ac66 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Tue, 2 May 2017 16:05:34 +0300 Subject: [PATCH 671/990] STM32L4: don't think these chips have DPFPU, DTCM or ITCM --- arch/arm/src/stm32l4/Kconfig | 12 ++++++++++++ arch/arm/src/stm32l4/Make.defs | 7 ------- arch/arm/src/stm32l4/stm32l4_dtcm.c | 0 arch/arm/src/stm32l4/stm32l4_procfs_dtcm.c | 0 4 files changed, 12 insertions(+), 7 deletions(-) delete mode 100644 arch/arm/src/stm32l4/stm32l4_dtcm.c delete mode 100644 arch/arm/src/stm32l4/stm32l4_procfs_dtcm.c diff --git a/arch/arm/src/stm32l4/Kconfig b/arch/arm/src/stm32l4/Kconfig index 5af9603644..b95328ca16 100644 --- a/arch/arm/src/stm32l4/Kconfig +++ b/arch/arm/src/stm32l4/Kconfig @@ -61,6 +61,18 @@ endchoice # STM32 L4 Chip Selection # Chip families config STM32L4_STM32L4X3 + bool + default n + select STM32L4_HAVE_USART1 + select STM32L4_HAVE_USART2 + select STM32L4_HAVE_USART3 if !(STM32L4_L432XX || STM32L4_L442XX) + select STM32L4_HAVE_LPTIM1 + select STM32L4_HAVE_LPTIM2 + select STM32L4_HAVE_COMP + select STM32L4_HAVE_SAI1 + select STM32L4_HAVE_LCD if !(STM32L4_STM32L4X1 || STM32L4_STM32L4X2) + +config STM32L4_STM32L4X5 bool default n select STM32L4_HAVE_USART1 diff --git a/arch/arm/src/stm32l4/Make.defs b/arch/arm/src/stm32l4/Make.defs index 359875b63c..49ee972539 100644 --- a/arch/arm/src/stm32l4/Make.defs +++ b/arch/arm/src/stm32l4/Make.defs @@ -127,13 +127,6 @@ ifeq ($(CONFIG_BUILD_PROTECTED),y) CHIP_CSRCS += stm32l4_userspace.c stm32l4_mpuinit.c endif -ifeq ($(CONFIG_ARMV7M_DTCM),y) -CHIP_CSRCS += stm32l4_dtcm.c -ifeq ($(CONFIG_STM32L4_DTCM_PROCFS),y) -CHIP_CSRCS += stm32l4_procfs_dtcm.c -endif -endif - ifeq ($(CONFIG_STM32L4_DMA),y) CHIP_CSRCS += stm32l4_dma.c endif diff --git a/arch/arm/src/stm32l4/stm32l4_dtcm.c b/arch/arm/src/stm32l4/stm32l4_dtcm.c deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/arch/arm/src/stm32l4/stm32l4_procfs_dtcm.c b/arch/arm/src/stm32l4/stm32l4_procfs_dtcm.c deleted file mode 100644 index e69de29bb2..0000000000 -- GitLab From a59b7bc932fc590f832722819c87a156153b387f Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Tue, 2 May 2017 12:27:43 +0300 Subject: [PATCH 672/990] STM32L4: add GPIO_PORTI definition Signed-off-by: Juha Niskanen --- arch/arm/include/stm32l4/chip.h | 6 +++++- arch/arm/src/stm32l4/chip/stm32l4x6xx_gpio.h | 13 +++++++++++++ arch/arm/src/stm32l4/stm32l4_gpio.c | 3 +++ arch/arm/src/stm32l4/stm32l4_gpio.h | 1 + arch/arm/src/stm32l4/stm32l4x6xx_rcc.c | 3 +++ 5 files changed, 25 insertions(+), 1 deletion(-) diff --git a/arch/arm/include/stm32l4/chip.h b/arch/arm/include/stm32l4/chip.h index 52c5ccae69..7cd275e280 100644 --- a/arch/arm/include/stm32l4/chip.h +++ b/arch/arm/include/stm32l4/chip.h @@ -108,8 +108,12 @@ # define STM32L4_NSAI 2 /* SAI1-2 */ # define STM32L4_NSDMMC 1 /* SDMMC interface */ # define STM32L4_NDMA 2 /* DMA1-2 */ +#if defined(CONFIG_STM32L4_STM32L496XX) +# define STM32L4_NPORTS 9 /* 9 GPIO ports, GPIOA-I */ +#else # define STM32L4_NPORTS 8 /* 8 GPIO ports, GPIOA-H */ -# define STM32L4_NADC 3 /* 12-bit ADC1-3, 24 channels (except V series) */ +#endif +# define STM32L4_NADC 3 /* 12-bit ADC1-3, upto 24 channels */ # define STM32L4_NDAC 2 /* 12-bit DAC1-2 */ # define STM32L4_NCRC 1 /* CRC */ # define STM32L4_NCOMP 2 /* Comparators */ diff --git a/arch/arm/src/stm32l4/chip/stm32l4x6xx_gpio.h b/arch/arm/src/stm32l4/chip/stm32l4x6xx_gpio.h index 2e72915e82..f4f32e7f92 100644 --- a/arch/arm/src/stm32l4/chip/stm32l4x6xx_gpio.h +++ b/arch/arm/src/stm32l4/chip/stm32l4x6xx_gpio.h @@ -166,6 +166,19 @@ # define STM32L4_GPIOH_AFRH (STM32L4_GPIOH_BASE+STM32L4_GPIO_AFRH_OFFSET) #endif +#if STM32L4_NPORTS > 8 +# define STM32L4_GPIOI_MODER (STM32L4_GPIOI_BASE+STM32L4_GPIO_MODER_OFFSET) +# define STM32L4_GPIOI_OTYPER (STM32L4_GPIOI_BASE+STM32L4_GPIO_OTYPER_OFFSET) +# define STM32L4_GPIOI_OSPEED (STM32L4_GPIOI_BASE+STM32L4_GPIO_OSPEED_OFFSET) +# define STM32L4_GPIOI_PUPDR (STM32L4_GPIOI_BASE+STM32L4_GPIO_PUPDR_OFFSET) +# define STM32L4_GPIOI_IDR (STM32L4_GPIOI_BASE+STM32L4_GPIO_IDR_OFFSET) +# define STM32L4_GPIOI_ODR (STM32L4_GPIOI_BASE+STM32L4_GPIO_ODR_OFFSET) +# define STM32L4_GPIOI_BSRR (STM32L4_GPIOI_BASE+STM32L4_GPIO_BSRR_OFFSET) +# define STM32L4_GPIOI_LCKR (STM32L4_GPIOI_BASE+STM32L4_GPIO_LCKR_OFFSET) +# define STM32L4_GPIOI_AFRL (STM32L4_GPIOI_BASE+STM32L4_GPIO_AFRL_OFFSET) +# define STM32L4_GPIOI_AFRH (STM32L4_GPIOI_BASE+STM32L4_GPIO_AFRH_OFFSET) +#endif + /* Register Bitfield Definitions ****************************************************/ /* GPIO port mode register */ diff --git a/arch/arm/src/stm32l4/stm32l4_gpio.c b/arch/arm/src/stm32l4/stm32l4_gpio.c index 007c3b8514..049c40fd2c 100644 --- a/arch/arm/src/stm32l4/stm32l4_gpio.c +++ b/arch/arm/src/stm32l4/stm32l4_gpio.c @@ -88,6 +88,9 @@ const uint32_t g_gpiobase[STM32L4_NPORTS] = #if STM32L4_NPORTS > 7 STM32L4_GPIOH_BASE, #endif +#if STM32L4_NPORTS > 8 + STM32L4_GPIOI_BASE, +#endif }; /**************************************************************************** diff --git a/arch/arm/src/stm32l4/stm32l4_gpio.h b/arch/arm/src/stm32l4/stm32l4_gpio.h index f4175d817e..57076a83ed 100644 --- a/arch/arm/src/stm32l4/stm32l4_gpio.h +++ b/arch/arm/src/stm32l4/stm32l4_gpio.h @@ -212,6 +212,7 @@ # define GPIO_PORTF (5 << GPIO_PORT_SHIFT) /* GPIOF */ # define GPIO_PORTG (6 << GPIO_PORT_SHIFT) /* GPIOG */ # define GPIO_PORTH (7 << GPIO_PORT_SHIFT) /* GPIOH */ +# define GPIO_PORTI (8 << GPIO_PORT_SHIFT) /* GPIOI */ /* This identifies the bit in the port: * diff --git a/arch/arm/src/stm32l4/stm32l4x6xx_rcc.c b/arch/arm/src/stm32l4/stm32l4x6xx_rcc.c index c043c100fa..08344fa0ba 100644 --- a/arch/arm/src/stm32l4/stm32l4x6xx_rcc.c +++ b/arch/arm/src/stm32l4/stm32l4x6xx_rcc.c @@ -210,6 +210,9 @@ static inline void rcc_enableahb2(void) #endif #if STM32L4_NPORTS > 7 | RCC_AHB2ENR_GPIOHEN +#endif +#if STM32L4_NPORTS > 8 + | RCC_AHB2ENR_GPIOIEN #endif ); #endif -- GitLab From f02d98d15e27f5c28dfd48ffbc88623f6129433c Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Tue, 2 May 2017 09:12:56 -0400 Subject: [PATCH 673/990] wireless/ieee802154: Changes transmit data path to use IOBs and exposes function for getting size of MAC header --- drivers/wireless/ieee802154/mrf24j40.c | 108 +++----- .../wireless/ieee802154/ieee802154_ioctl.h | 5 + .../wireless/ieee802154/ieee802154_mac.h | 38 ++- .../wireless/ieee802154/ieee802154_radio.h | 8 +- wireless/ieee802154/mac802154.c | 242 +++++++++++------- wireless/ieee802154/mac802154.h | 11 + wireless/ieee802154/mac802154_device.c | 63 +++-- 7 files changed, 261 insertions(+), 214 deletions(-) diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c index 6b602b739d..f883b55054 100644 --- a/drivers/wireless/ieee802154/mrf24j40.c +++ b/drivers/wireless/ieee802154/mrf24j40.c @@ -138,9 +138,10 @@ struct mrf24j40_radio_s /* Buffer Allocations */ struct mrf24j40_txdesc_s csma_desc; - struct mrf24j40_txdesc_s gts_desc[MRF24J40_GTS_SLOTS]; + FAR struct iob_s *csma_frame; - uint8_t tx_buf[IEEE802154_MAX_PHY_PACKET_SIZE]; + struct mrf24j40_txdesc_s gts_desc[MRF24J40_GTS_SLOTS]; + FAR struct iob_s *gts_frame[MRF24J40_GTS_SLOTS]; }; /**************************************************************************** @@ -174,11 +175,11 @@ static void mrf24j40_dopoll_csma(FAR void *arg); static void mrf24j40_dopoll_gts(FAR void *arg); static int mrf24j40_csma_setup(FAR struct mrf24j40_radio_s *dev, - FAR uint8_t *buf, uint16_t buf_len); + FAR struct iob_s *frame); static int mrf24j40_gts_setup(FAR struct mrf24j40_radio_s *dev, uint8_t gts, - FAR uint8_t *buf, uint16_t buf_len); + FAR struct iob_s *frame); static int mrf24j40_setup_fifo(FAR struct mrf24j40_radio_s *dev, - FAR uint8_t *buf, uint16_t buf_len, uint32_t fifo_addr); + FAR struct iob_s *frame, uint32_t fifo_addr); /* IOCTL helpers */ @@ -224,10 +225,8 @@ static int mrf24j40_bind(FAR struct ieee802154_radio_s *radio, static int mrf24j40_ioctl(FAR struct ieee802154_radio_s *radio, int cmd, unsigned long arg); static int mrf24j40_rxenable(FAR struct ieee802154_radio_s *radio); -static int mrf24j40_transmit(FAR struct ieee802154_radio_s *radio, - FAR uint8_t *buf, uint16_t buf_len); -static int mrf24j40_txnotify_csma(FAR struct ieee802154_radio_s *radio); -static int mrf24j40_txnotify_gts(FAR struct ieee802154_radio_s *radio); +static int mrf24j40_txnotify_csma(FAR struct ieee802154_radio_s *radio); +static int mrf24j40_txnotify_gts(FAR struct ieee802154_radio_s *radio); /**************************************************************************** * Private Data @@ -327,9 +326,7 @@ static void mrf24j40_dopoll_csma(FAR void *arg) FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)arg; int len = 0; - /* Need to get exlusive access to the device so that we can use the copy - * buffer. - */ + /* Get exclusive access to the driver */ while (sem_wait(&dev->exclsem) != 0) { } @@ -340,7 +337,7 @@ static void mrf24j40_dopoll_csma(FAR void *arg) /* need to somehow allow for a handle to be passed */ len = dev->radiocb->poll_csma(dev->radiocb, &dev->csma_desc.pub, - &dev->tx_buf[0]); + &dev->csma_frame); if (len > 0) { /* Now the txdesc is in use */ @@ -349,7 +346,7 @@ static void mrf24j40_dopoll_csma(FAR void *arg) /* Setup the transaction on the device in the CSMA FIFO */ - mrf24j40_csma_setup(dev, &dev->tx_buf[0], len); + mrf24j40_csma_setup(dev, dev->csma_frame); } } @@ -421,9 +418,7 @@ static void mrf24j40_dopoll_gts(FAR void *arg) int gts = 0; int len = 0; - /* Need to get exclusive access to the device so that we can use the copy - * buffer. - */ + /* Get exclusive access to the driver */ while (sem_wait(&dev->exclsem) != 0) { } @@ -432,7 +427,7 @@ static void mrf24j40_dopoll_gts(FAR void *arg) if (!dev->gts_desc[gts].busy) { len = dev->radiocb->poll_gts(dev->radiocb, &dev->gts_desc[gts].pub, - &dev->tx_buf[0]); + &dev->gts_frame[0]); if (len > 0) { /* Now the txdesc is in use */ @@ -441,7 +436,7 @@ static void mrf24j40_dopoll_gts(FAR void *arg) /* Setup the transaction on the device in the open GTS FIFO */ - mrf24j40_gts_setup(dev, gts, &dev->tx_buf[0], len); + mrf24j40_gts_setup(dev, gts, dev->gts_frame[0]); } } } @@ -1327,52 +1322,6 @@ static int mrf24j40_energydetect(FAR struct mrf24j40_radio_s *dev, return OK; } -/* Packet exchange */ - -/**************************************************************************** - * Name: mrf24j40_transmit - * - * Description: - * Send a regular packet over the air. - * - ****************************************************************************/ - -static int mrf24j40_transmit(FAR struct ieee802154_radio_s *radio, - FAR uint8_t *buf, uint16_t buf_len) -{ - FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)radio; - uint8_t reg; - int ret; - - mrf24j40_pacontrol(dev, MRF24J40_PA_AUTO); - - /* Enable tx int */ - - reg = mrf24j40_getreg(dev->spi, MRF24J40_INTCON); - reg &= ~MRF24J40_INTCON_TXNIE; - mrf24j40_setreg(dev->spi, MRF24J40_INTCON, reg); - - /* Setup the FIFO */ - - ret = mrf24j40_setup_fifo(dev, buf, buf_len, MRF24J40_TXNORM_FIFO); - - /* If the frame control field contains - * an acknowledgment request, set the TXNACKREQ bit. - * See IEEE 802.15.4/2003 7.2.1.1 page 112 for info. - */ - - reg = MRF24J40_TXNCON_TXNTRIG; - if (buf[0] & IEEE802154_FRAMECTRL_ACKREQ) - { - reg |= MRF24J40_TXNCON_TXNACKREQ; - } - - /* Trigger packet emission */ - - mrf24j40_setreg(dev->spi, MRF24J40_TXNCON, reg); - return ret; -} - /**************************************************************************** * Name: mrf24j40_csma_setup * @@ -1382,7 +1331,7 @@ static int mrf24j40_transmit(FAR struct ieee802154_radio_s *radio, ****************************************************************************/ static int mrf24j40_csma_setup(FAR struct mrf24j40_radio_s *dev, - FAR uint8_t *buf, uint16_t buf_len) + FAR struct iob_s *frame) { uint8_t reg; int ret; @@ -1397,7 +1346,7 @@ static int mrf24j40_csma_setup(FAR struct mrf24j40_radio_s *dev, /* Setup the FIFO */ - ret = mrf24j40_setup_fifo(dev, buf, buf_len, MRF24J40_TXNORM_FIFO); + ret = mrf24j40_setup_fifo(dev, frame, MRF24J40_TXNORM_FIFO); /* If the frame control field contains * an acknowledgment request, set the TXNACKREQ bit. @@ -1405,7 +1354,7 @@ static int mrf24j40_csma_setup(FAR struct mrf24j40_radio_s *dev, */ reg = MRF24J40_TXNCON_TXNTRIG; - if (buf[0] & IEEE802154_FRAMECTRL_ACKREQ) + if (frame->io_data[0] & IEEE802154_FRAMECTRL_ACKREQ) { reg |= MRF24J40_TXNCON_TXNACKREQ; } @@ -1425,7 +1374,7 @@ static int mrf24j40_csma_setup(FAR struct mrf24j40_radio_s *dev, ****************************************************************************/ static int mrf24j40_gts_setup(FAR struct mrf24j40_radio_s *dev, uint8_t fifo, - FAR uint8_t *buf, uint16_t buf_len) + FAR struct iob_s *frame) { return -ENOTTY; } @@ -1438,8 +1387,7 @@ static int mrf24j40_gts_setup(FAR struct mrf24j40_radio_s *dev, uint8_t fifo, ****************************************************************************/ static int mrf24j40_setup_fifo(FAR struct mrf24j40_radio_s *dev, - FAR uint8_t *buf, uint16_t buf_len, - uint32_t fifo_addr) + FAR struct iob_s *frame, uint32_t fifo_addr) { int ret; int hlen = 3; /* Include frame control and seq number */ @@ -1447,8 +1395,8 @@ static int mrf24j40_setup_fifo(FAR struct mrf24j40_radio_s *dev, /* Analyze frame control to compute header length */ - frame_ctrl = buf[0]; - frame_ctrl |= (buf[1] << 8); + frame_ctrl = frame->io_data[0]; + frame_ctrl |= (frame->io_data[1] << 8); if ((frame_ctrl & IEEE802154_FRAMECTRL_DADDR)== IEEE802154_ADDRMODE_SHORT) { @@ -1479,13 +1427,13 @@ static int mrf24j40_setup_fifo(FAR struct mrf24j40_radio_s *dev, /* Frame length */ - mrf24j40_setreg(dev->spi, fifo_addr++, buf_len); + mrf24j40_setreg(dev->spi, fifo_addr++, frame->io_len); /* Frame data */ - for (ret = 0; ret < buf_len; ret++) /* this sets the correct val for ret */ + for (ret = 0; ret < frame->io_len; ret++) /* this sets the correct val for ret */ { - mrf24j40_setreg(dev->spi, fifo_addr++, buf[ret]); + mrf24j40_setreg(dev->spi, fifo_addr++, frame->io_data[ret]); } return ret; @@ -1525,6 +1473,10 @@ static void mrf24j40_irqwork_txnorm(FAR struct mrf24j40_radio_s *dev) dev->csma_desc.busy = 0; + /* Free the IOB */ + + iob_free(dev->csma_frame); + mrf24j40_dopoll_csma(dev); } @@ -1571,6 +1523,10 @@ static void mrf24j40_irqwork_txgts(FAR struct mrf24j40_radio_s *dev, dev->gts_desc[gts].busy = 0; + /* Free the IOB */ + + iob_free(dev->gts_frame[gts]); + mrf24j40_dopoll_gts(dev); } diff --git a/include/nuttx/wireless/ieee802154/ieee802154_ioctl.h b/include/nuttx/wireless/ieee802154/ieee802154_ioctl.h index 533e2f3853..019fedd55a 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_ioctl.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_ioctl.h @@ -72,6 +72,11 @@ struct mac802154dev_notify_s uint8_t mn_signo; /* Signal number to use in the notification */ }; +struct mac802154dev_txframe_s +{ + FAR struct ieee802154_frame_meta_s *meta; + FAR uint8_t *payload; +}; #endif /* CONFIG_WIRELESS_IEEE802154 */ #endif /* __INCLUDE_NUTTX_WIRELESS_IEEE802154_IEEE802154_IOCTL_H */ diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index 1a8e324ce2..422e4d88fb 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -474,20 +474,12 @@ enum ieee802154_scantype_e IEEE802154_SCANTYPE_ORPHAN }; -/* Primitive Semantics *******************************************************/ - -/***************************************************************************** - * Primitive: MCPS-DATA.request - * - * Description: - * Requests the transfer of data to another device. - * - *****************************************************************************/ - -struct ieee802154_data_req_s +struct ieee802154_frame_meta_s { enum ieee802154_addr_mode_e src_addr_mode; /* Source Address Mode */ struct ieee802154_addr_s dest_addr; /* Destination Address */ + + uint8_t msdu_handle; /* Handle assoc. with MSDU */ /* Number of bytes contained in the MAC Service Data Unit (MSDU) * to be transmitted by the MAC sublayer enitity @@ -498,7 +490,6 @@ struct ieee802154_data_req_s uint16_t msdu_length; - uint8_t msdu_handle; /* Handle assoc. with MSDU */ struct { uint8_t ack_tx : 1; /* Acknowledge TX? */ @@ -530,18 +521,23 @@ struct ieee802154_data_req_s #endif enum ieee802154_ranging_e ranging; +}; - /* The MAC service data unit array that is to be transmitted - * This must be at the end of the struct to allow the array - * to continue and make the struct "variable length" - */ +/* Primitive Semantics *******************************************************/ - uint8_t msdu[IEEE802154_MAX_MAC_PAYLOAD_SIZE]; -}; +/***************************************************************************** + * Primitive: MCPS-DATA.request + * + * Description: + * Requests the transfer of data to another device. + * + *****************************************************************************/ -#define SIZEOF_IEEE802154_DATA_REQ_S(n) \ - (sizeof(struct ieee802154_data_req_s) \ - - IEEE802154_MAX_MAC_PAYLOAD_SIZE + (n)) +struct ieee802154_data_req_s +{ + FAR struct ieee802154_frame_meta_s *meta; /* Metadata describing the req */ + FAR struct iob_s *frame; /* Frame IOB with payload */ +}; /***************************************************************************** * Primitive: MCPS-DATA.confirm diff --git a/include/nuttx/wireless/ieee802154/ieee802154_radio.h b/include/nuttx/wireless/ieee802154/ieee802154_radio.h index 54e08969d9..e976ec2075 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_radio.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_radio.h @@ -195,13 +195,15 @@ struct ieee802154_rxdesc_s struct ieee802154_radiocb_s { CODE int (*poll_csma) (FAR const struct ieee802154_radiocb_s *radiocb, - FAR struct ieee802154_txdesc_s *tx_desc, FAR uint8_t *buf); + FAR struct ieee802154_txdesc_s *tx_desc, + FAR struct iob_s **frame); CODE int (*poll_gts) (FAR const struct ieee802154_radiocb_s *radiocb, - FAR struct ieee802154_txdesc_s *tx_desc, FAR uint8_t *buf); + FAR struct ieee802154_txdesc_s *tx_desc, + FAR struct iob_s **frame); CODE void (*txdone) (FAR const struct ieee802154_radiocb_s *radiocb, FAR const struct ieee802154_txdesc_s *tx_desc); CODE void (*rxframe) (FAR const struct ieee802154_radiocb_s *radiocb, - FAR const struct ieee8021254_rxdesc_s *rx_desc, + FAR const struct ieee802154_rxdesc_s *rx_desc, FAR struct iob_s *frame); }; diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index f6b5f5f455..1dbd3a65c2 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -86,15 +86,8 @@ struct mac802154_trans_s /* Supports a singly linked list */ FAR struct mac802154_trans_s *flink; - + FAR struct iob_s *frame; uint8_t msdu_handle; - - FAR uint8_t *mhr_buf; - uint8_t mhr_len; - - FAR uint8_t *d_buf; - uint8_t d_len; - sem_t sem; }; @@ -291,23 +284,26 @@ static int mac802154_applymib(FAR struct ieee802154_privmac_s *priv); static int mac802154_poll_csma(FAR const struct ieee802154_radiocb_s *radiocb, FAR struct ieee802154_txdesc_s *tx_desc, - FAR uint8_t *buf); + FAR struct iob_s **frame); static int mac802154_poll_gts(FAR const struct ieee802154_radiocb_s *radiocb, FAR struct ieee802154_txdesc_s *tx_desc, - FAR uint8_t *buf); + FAR struct iob_s **frame); static void mac802154_txdone(FAR const struct ieee802154_radiocb_s *radiocb, FAR const struct ieee802154_txdesc_s *tx_desc); static void mac802154_rxframe(FAR const struct ieee802154_radiocb_s *radiocb, - FAR struct ieee802154_rxdesc_s *rx_desc, + FAR const struct ieee802154_rxdesc_s *rx_desc, FAR struct iob_s *frame); /**************************************************************************** * Private Data ****************************************************************************/ +/* Map between ieee802154_addr_mode_e enum and actual address length */ + +static const uint8_t mac802154_addr_length[4] = {0, 0, 2, 8}; /**************************************************************************** * Private Functions @@ -452,7 +448,7 @@ static int mac802154_applymib(FAR struct ieee802154_privmac_s *priv) static int mac802154_poll_csma(FAR const struct ieee802154_radiocb_s *radiocb, FAR struct ieee802154_txdesc_s *tx_desc, - FAR uint8_t *buf) + FAR struct iob_s **frame) { FAR struct mac802154_radiocb_s *cb = (FAR struct mac802154_radiocb_s *)radiocb; @@ -475,24 +471,19 @@ static int mac802154_poll_csma(FAR const struct ieee802154_radiocb_s *radiocb, if (trans != NULL) { - /* Setup the transmit descriptor */ tx_desc->handle = trans->msdu_handle; - /* Copy the frame into the buffer */ - - memcpy(&buf[0], trans->mhr_buf, trans->mhr_len); - memcpy(&buf[trans->mhr_len], trans->d_buf, trans->d_len); + *frame = trans->frame; /* Now that we've passed off the data, notify the waiting thread. * NOTE: The transaction was allocated on the waiting thread's stack so * it will be automatically deallocated when that thread awakens and - * returns. - */ + * returns. */ sem_post(&trans->sem); - return (trans->mhr_len + trans->d_len); + return (trans->frame->io_len); } return 0; @@ -511,7 +502,7 @@ static int mac802154_poll_csma(FAR const struct ieee802154_radiocb_s *radiocb, static int mac802154_poll_gts(FAR const struct ieee802154_radiocb_s *radiocb, FAR struct ieee802154_txdesc_s *tx_desc, - FAR uint8_t *buf) + FAR struct iob_s **frame) { FAR struct mac802154_radiocb_s *cb = (FAR struct mac802154_radiocb_s *)radiocb; @@ -643,7 +634,7 @@ static void mac802154_txdone_worker(FAR void *arg) ****************************************************************************/ static void mac802154_rxframe(FAR const struct ieee802154_radiocb_s *radiocb, - FAR struct ieee802154_rxdesc_s *rx_desc, + FAR const struct ieee802154_rxdesc_s *rx_desc, FAR struct iob_s *frame) { FAR struct mac802154_radiocb_s *cb = @@ -844,6 +835,82 @@ int mac802154_ioctl(MACHANDLE mac, int cmd, unsigned long arg) * MAC Interface Operations ****************************************************************************/ +/**************************************************************************** + * Name: mac802154_get_mhrlen + * + * Description: + * Calculate the MAC header length given the frame meta-data. + * + ****************************************************************************/ + +int mac802154_get_mhrlen(MACHANDLE mac, + FAR struct ieee802154_frame_meta_s *meta) +{ + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; + int ret = 3; /* Always frame control (2 bytes) and seq. num (1 byte) */ + + /* Check to make sure both the dest address and the source address are not set + * to NONE */ + + if (meta->dest_addr.mode == IEEE802154_ADDRMODE_NONE && + meta->src_addr_mode == IEEE802154_ADDRMODE_NONE) + { + return -EINVAL; + } + + /* The source address can only be set to NONE if the device is the PAN coord */ + + if (meta->src_addr_mode == IEEE802154_ADDRMODE_NONE && !priv->is_coord) + { + return -EINVAL; + } + + /* Add the destination address length */ + + ret += mac802154_addr_length[meta->dest_addr.mode]; + + /* Add the source address length */ + + ret += mac802154_addr_length[ meta->src_addr_mode]; + + /* If both destination and source addressing information is present, the MAC + * sublayer shall compare the destination and source PAN identifiers. + * [1] pg. 41. + */ + + if (meta->src_addr_mode != IEEE802154_ADDRMODE_NONE && + meta->dest_addr.mode != IEEE802154_ADDRMODE_NONE) + { + /* If the PAN identifiers are identical, the PAN ID Compression field + * shall be set to one, and the source PAN identifier shall be omitted + * from the transmitted frame. [1] pg. 41. + */ + + if (meta->dest_addr.panid == priv->addr.panid) + { + ret += 2; /* 2 bytes for destination PAN ID */ + return ret; + } + } + + /* If we are here, PAN ID compression is off, so include the dest and source + * PAN ID if the respective address is included + */ + + if (meta->src_addr_mode != IEEE802154_ADDRMODE_NONE) + { + ret += 2; /* 2 bytes for source PAN ID */ + } + + if (meta->dest_addr.mode != IEEE802154_ADDRMODE_NONE) + { + ret += 2; /* 2 bytes for destination PAN ID */ + } + + return ret; +} + /**************************************************************************** * Name: mac802154_req_data * @@ -860,73 +927,70 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; FAR struct mac802154_trans_s trans; - struct mac802154_unsec_mhr_s mhr; + FAR struct ieee802154_frame_meta_s *meta = req->meta; + uint16_t *frame_ctrl; + uint8_t mhr_len = 3; /* Start assuming frame control and seq. num */ int ret; + + /* Check the required frame size */ - /* Start off assuming there is only the frame_control field in the MHR */ - - mhr.length = 2; + if (req->frame->io_len > IEEE802154_MAX_PHY_PACKET_SIZE) + { + return -E2BIG; + } - /* Do a preliminary check to make sure the MSDU isn't too long for even - * the best case. - */ + /* Cast the first two bytes of the IOB to a uint16_t frame control field */ - if (req->msdu_length > IEEE802154_MAX_MAC_PAYLOAD_SIZE) - { - return -EINVAL; - } + frame_ctrl = (uint16_t *)&req->frame->io_data[0]; /* Ensure we start with a clear frame control field */ - mhr.u.frame_control = 0; + *frame_ctrl = 0; /* Set the frame type to Data */ - mhr.u.frame_control |= IEEE802154_FRAME_DATA << - IEEE802154_FRAMECTRL_SHIFT_FTYPE; + *frame_ctrl |= IEEE802154_FRAME_DATA << IEEE802154_FRAMECTRL_SHIFT_FTYPE; /* If the msduLength is greater than aMaxMACSafePayloadSize, the MAC * sublayer will set the Frame Version to one. [1] pg. 118. */ - if (req->msdu_length > IEEE802154_MAX_SAFE_MAC_PAYLOAD_SIZE) + if (meta->msdu_length > IEEE802154_MAX_SAFE_MAC_PAYLOAD_SIZE) { - mhr.u.frame_control |= IEEE802154_FRAMECTRL_VERSION; + *frame_ctrl |= IEEE802154_FRAMECTRL_VERSION; } /* If the TXOptions parameter specifies that an acknowledged transmission * is required, the AR field will be set appropriately, as described in * 5.1.6.4 [1] pg. 118. */ - - mhr.u.frame_control |= (req->msdu_flags.ack_tx << - IEEE802154_FRAMECTRL_SHIFT_ACKREQ); + + *frame_ctrl |= (meta->msdu_flags.ack_tx << IEEE802154_FRAMECTRL_SHIFT_ACKREQ); /* If the destination address is present, copy the PAN ID and one of the - * addresses, depending on mode, into the MHR . + * addresses, depending on mode, into the MHR. */ - if (req->dest_addr.mode != IEEE802154_ADDRMODE_NONE) + if (meta->dest_addr.mode != IEEE802154_ADDRMODE_NONE) { - memcpy(&mhr.u.data[mhr.length], &req->dest_addr.panid, 2); - mhr.length += 2; + memcpy(&req->frame->io_data[mhr_len], &meta->dest_addr.panid, 2); + mhr_len += 2; - if (req->dest_addr.mode == IEEE802154_ADDRMODE_SHORT) + if (meta->dest_addr.mode == IEEE802154_ADDRMODE_SHORT) { - memcpy(&mhr.u.data[mhr.length], &req->dest_addr.saddr, 2); - mhr.length += 2; + memcpy(&req->frame->io_data[mhr_len], &meta->dest_addr.saddr, 2); + mhr_len += 2; } - else if (req->dest_addr.mode == IEEE802154_ADDRMODE_EXTENDED) + else if (meta->dest_addr.mode == IEEE802154_ADDRMODE_EXTENDED) { - memcpy(&mhr.u.data[mhr.length], &req->dest_addr.eaddr, 8); - mhr.length += 8; + memcpy(&req->frame->io_data[mhr_len], &meta->dest_addr.eaddr, 8); + mhr_len += 8; } } - /* Set the destination addr mode inside the frame contorl field */ + /* Set the destination addr mode inside the frame control field */ - mhr.u.frame_control |= (req->dest_addr.mode << - IEEE802154_FRAMECTRL_SHIFT_DADDR); + *frame_ctrl |= (meta->dest_addr.mode << IEEE802154_FRAMECTRL_SHIFT_DADDR); /* From this point on, we need exclusive access to the privmac struct */ @@ -942,75 +1006,70 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) * [1] pg. 41. */ - if (req->src_addr_mode != IEEE802154_ADDRMODE_NONE && - req->dest_addr.mode != IEEE802154_ADDRMODE_NONE) + if (meta->src_addr_mode != IEEE802154_ADDRMODE_NONE && + meta->dest_addr.mode != IEEE802154_ADDRMODE_NONE) { /* If the PAN identifiers are identical, the PAN ID Compression field * shall be set to one, and the source PAN identifier shall be omitted * from the transmitted frame. [1] pg. 41. */ - if (req->dest_addr.panid == priv->addr.panid) + if (meta->dest_addr.panid == priv->addr.panid) { - mhr.u.frame_control |= IEEE802154_FRAMECTRL_PANIDCOMP; + *frame_ctrl |= IEEE802154_FRAMECTRL_PANIDCOMP; } } - if (req->src_addr_mode != IEEE802154_ADDRMODE_NONE) + if (meta->src_addr_mode != IEEE802154_ADDRMODE_NONE) { /* If the destination address is not included, or if PAN ID Compression * is off, we need to include the Source PAN ID. */ - if ((req->dest_addr.mode == IEEE802154_ADDRMODE_NONE) || - (mhr.u.frame_control & IEEE802154_FRAMECTRL_PANIDCOMP)) + if ((meta->dest_addr.mode == IEEE802154_ADDRMODE_NONE) || + (*frame_ctrl & IEEE802154_FRAMECTRL_PANIDCOMP)) { - memcpy(&mhr.u.data[mhr.length], &priv->addr.panid, 2); - mhr.length += 2; + memcpy(&req->frame->io_data[mhr_len], &priv->addr.panid, 2); + mhr_len += 2; } - if (req->src_addr_mode == IEEE802154_ADDRMODE_SHORT) + if (meta->src_addr_mode == IEEE802154_ADDRMODE_SHORT) { - memcpy(&mhr.u.data[mhr.length], &priv->addr.saddr, 2); - mhr.length += 2; + memcpy(&req->frame->io_data[mhr_len], &priv->addr.saddr, 2); + mhr_len += 2; } - else if (req->src_addr_mode == IEEE802154_ADDRMODE_EXTENDED) + else if (meta->src_addr_mode == IEEE802154_ADDRMODE_EXTENDED) { - memcpy(&mhr.u.data[mhr.length], &priv->addr.eaddr, 8); - mhr.length += 8; + memcpy(&req->frame->io_data[mhr_len], &priv->addr.eaddr, 8); + mhr_len += 8; } } /* Set the source addr mode inside the frame control field */ - mhr.u.frame_control |= (req->src_addr_mode << - IEEE802154_FRAMECTRL_SHIFT_SADDR); + *frame_ctrl |= (meta->src_addr_mode << IEEE802154_FRAMECTRL_SHIFT_SADDR); /* Each time a data or a MAC command frame is generated, the MAC sublayer * shall copy the value of macDSN into the Sequence Number field of the MHR * of the outgoing frame and then increment it by one. [1] pg. 40. */ - mhr.u.data[mhr.length++] = priv->dsn++; + req->frame->io_data[2] = priv->dsn++; - /* Now that we know which fields are included in the header, we can make - * sure we actually have enough room in the PSDU. + /* The MAC header we just created must never have exceeded where the app + * data starts. This should never happen since the offset should have + * been set via the same logic to calculate the header length as the logic + * here that created the header */ - if (mhr.length + req->msdu_length + IEEE802154_MFR_LENGTH > - IEEE802154_MAX_PHY_PACKET_SIZE) - { - return -E2BIG; - } + DEBUGASSERT(mhr_len == req->frame->io_offset); - trans.mhr_buf = &mhr.u.data[0]; - trans.mhr_len = mhr.length; + req->frame->io_offset = 0; /* Set the offset to 0 to include the header */ - trans.d_buf = &req->msdu[0]; - trans.d_len = req->msdu_length; - - trans.msdu_handle = req->msdu_handle; + /* Setup our transaction */ + trans.msdu_handle = meta->msdu_handle; + trans.frame = req->frame; sem_init(&trans.sem, 0, 1); /* If the TxOptions parameter specifies that a GTS transmission is required, @@ -1025,7 +1084,7 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) * [1] pg. 118. */ - if (req->msdu_flags.gts_tx) + if (meta->msdu_flags.gts_tx) { /* TODO: Support GTS transmission. This should just change where we link * the transaction. Instead of going in the CSMA transaction list, it @@ -1044,7 +1103,7 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) * described in 5.1.5 and 5.1.6.3. [1] */ - if (req->msdu_flags.indirect_tx) + if (meta->msdu_flags.indirect_tx) { /* If the TxOptions parameter specifies that an indirect transmission * is required and if the device receiving this primitive is not a @@ -1053,24 +1112,22 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) * transmission option will be ignored. [1] */ - if (priv->is_coord && req->dest_addr.mode != IEEE802154_ADDRMODE_NONE) + if (priv->is_coord && meta->dest_addr.mode != IEEE802154_ADDRMODE_NONE) { /* Link the transaction into the indirect_trans list */ - priv->indirect_tail->flink = &trans; - priv->indirect_tail = &trans; } else { /* Override the setting since it wasn't valid */ - req->msdu_flags.indirect_tx = 0; + meta->msdu_flags.indirect_tx = 0; } } /* If this is a direct transmission not during a GTS */ - if (!req->msdu_flags.indirect_tx) + if (!meta->msdu_flags.indirect_tx) { /* Link the transaction into the CSMA transaction list */ @@ -1092,7 +1149,6 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) return OK; } - /**************************************************************************** * Name: mac802154_req_purge * diff --git a/wireless/ieee802154/mac802154.h b/wireless/ieee802154/mac802154.h index 00235d025b..ea582e4e7a 100644 --- a/wireless/ieee802154/mac802154.h +++ b/wireless/ieee802154/mac802154.h @@ -97,6 +97,17 @@ int mac802154_ioctl(MACHANDLE mac, int cmd, unsigned long arg); * MAC Interface Operations ****************************************************************************/ +/**************************************************************************** + * Name: mac802154_get_mhrlen + * + * Description: + * Calculate the MAC header length given the frame meta-data. + * + ****************************************************************************/ + +int mac802154_get_mhrlen(MACHANDLE mac, + FAR struct ieee802154_frame_meta_s *meta); + /**************************************************************************** * Name: mac802154_req_data * diff --git a/wireless/ieee802154/mac802154_device.c b/wireless/ieee802154/mac802154_device.c index 5c31cdf140..998cca074f 100644 --- a/wireless/ieee802154/mac802154_device.c +++ b/wireless/ieee802154/mac802154_device.c @@ -50,6 +50,8 @@ #include #include +#include + #include #include @@ -373,17 +375,6 @@ static ssize_t mac802154dev_read(FAR struct file *filep, FAR char *buffer, DEBUGASSERT(inode->i_private); dev = (FAR struct mac802154_chardevice_s *)inode->i_private; - /* Check to make sure that the buffer is big enough to hold at least one - * packet. - */ - - if ((len >= SIZEOF_IEEE802154_DATA_REQ_S(1)) && - (len <= SIZEOF_IEEE802154_DATA_REQ_S(IEEE802154_MAX_MAC_PAYLOAD_SIZE))) - { - wlerr("ERROR: buffer too small: %lu\n", (unsigned long)len); - return -EINVAL; - } - /* Get exclusive access to the driver structure */ ret = mac802154dev_takesem(&dev->md_exclsem); @@ -413,7 +404,9 @@ static ssize_t mac802154dev_write(FAR struct file *filep, { FAR struct inode *inode; FAR struct mac802154_chardevice_s *dev; - FAR struct ieee802154_data_req_s *req; + FAR struct mac802154dev_txframe_s *tx; + FAR struct iob_s *iob; + struct ieee802154_data_req_s req; struct mac802154dev_dwait_s dwait; int ret; @@ -422,20 +415,44 @@ static ssize_t mac802154dev_write(FAR struct file *filep, DEBUGASSERT(inode->i_private); dev = (FAR struct mac802154_chardevice_s *)inode->i_private; - /* Check to make sure that the buffer is big enough to hold at least one - * packet. */ + /* Check if the struct is write */ - if ((len < SIZEOF_IEEE802154_DATA_REQ_S(1)) || - (len > SIZEOF_IEEE802154_DATA_REQ_S(IEEE802154_MAX_MAC_PAYLOAD_SIZE))) + if (len != sizeof(struct mac802154dev_txframe_s)) { - wlerr("ERROR: buffer isn't an ieee802154_data_req_s: %lu\n", + wlerr("ERROR: buffer isn't a mac802154dev_txframe_s: %lu\n", (unsigned long)len); return -EINVAL; } DEBUGASSERT(buffer != NULL); - req = (FAR struct ieee802154_data_req_s *)buffer; + tx = (FAR struct mac802154dev_txframe_s *)buffer; + + /* Allocate an IOB to put the frame in */ + + iob = iob_alloc(false); + DEBUGASSERT(iob != NULL); + + iob->io_flink = NULL; + iob->io_len = 0; + iob->io_offset = 0; + iob->io_pktlen = 0; + + /* Get the MAC header length */ + + ret = mac802154_get_mhrlen(dev->md_mac, tx->meta); + if (ret < 0) + { + wlerr("ERROR: TX meta-data is invalid"); + return ret; + } + + iob->io_offset = ret; + iob->io_len = iob->io_offset; + + memcpy(&iob->io_data[iob->io_offset], tx->payload, tx->meta->msdu_length); + + iob->io_len += tx->meta->msdu_length; /* If this is a blocking operation, we need to setup a wait struct so we * can unblock when the packet transmission has finished. If this is a @@ -456,21 +473,25 @@ static ssize_t mac802154dev_write(FAR struct file *filep, /* Setup the wait struct */ - dwait.mw_handle = req->msdu_handle; + dwait.mw_handle = tx->meta->msdu_handle; /* Link the wait struct */ dwait.mw_flink = dev->md_dwait; dev->md_dwait = &dwait; - sem_init(&dwait.mw_sem, 0, 1); + sem_init(&dwait.mw_sem, 0, 0); + sem_setprotocol(&dwait.mw_sem, SEM_PRIO_NONE); mac802154dev_givesem(&dev->md_exclsem); } + req.meta = tx->meta; + req.frame = iob; + /* Pass the request to the MAC layer */ - ret = mac802154_req_data(dev->md_mac, req); + ret = mac802154_req_data(dev->md_mac, &req); if (ret < 0) { -- GitLab From 40b5c4602415b16e6f982c66acc2c261ad9c8326 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 2 May 2017 08:02:35 -0600 Subject: [PATCH 674/990] STM32L4: Delete more references to DFPU, ITCM, and DTCM. --- arch/arm/src/stm32l4/Kconfig | 9 --------- 1 file changed, 9 deletions(-) diff --git a/arch/arm/src/stm32l4/Kconfig b/arch/arm/src/stm32l4/Kconfig index b95328ca16..28be165f44 100644 --- a/arch/arm/src/stm32l4/Kconfig +++ b/arch/arm/src/stm32l4/Kconfig @@ -103,18 +103,12 @@ config STM32L4_STM32L476XX default n select STM32L4_STM32L4X6 select ARCH_HAVE_FPU - select ARCH_HAVE_DPFPU # REVISIT - select ARMV7M_HAVE_ITCM - select ARMV7M_HAVE_DTCM config STM32L4_STM32L486XX bool default n select STM32L4_STM32L4X6 select ARCH_HAVE_FPU - select ARCH_HAVE_DPFPU # REVISIT - select ARMV7M_HAVE_ITCM - select ARMV7M_HAVE_DTCM select STM32L4_FLASH_1024KB config STM32L4_STM32L496XX @@ -122,9 +116,6 @@ config STM32L4_STM32L496XX default n select STM32L4_STM32L4X6 select ARCH_HAVE_FPU - select ARCH_HAVE_DPFPU # REVISIT - select ARMV7M_HAVE_ITCM - select ARMV7M_HAVE_DTCM select STM32L4_HAVE_I2C4 select STM32L4_HAVE_CAN2 select STM32L4_HAVE_DCMI -- GitLab From 91b3efa706da76df70541ae8fa2d40fc8c932a18 Mon Sep 17 00:00:00 2001 From: Simon Piriou Date: Tue, 2 May 2017 08:41:13 -0600 Subject: [PATCH 675/990] Extend wireless.h with definitions needed by wext. --- include/nuttx/wireless/wireless.h | 80 +++++++++++++++++++++++++++++++ 1 file changed, 80 insertions(+) diff --git a/include/nuttx/wireless/wireless.h b/include/nuttx/wireless/wireless.h index a07a4cbf70..0b5367dbff 100644 --- a/include/nuttx/wireless/wireless.h +++ b/include/nuttx/wireless/wireless.h @@ -197,6 +197,71 @@ #define IW_SCAN_MAX_DATA 4096 /* Maximum size of returned data */ +/* SIOCSIWAUTH/SIOCGIWAUTH struct iw_param flags */ + +#define IW_AUTH_INDEX 0x0FFF +#define IW_AUTH_FLAGS 0xF000 + +/* SIOCSIWAUTH/SIOCGIWAUTH parameters (0 .. 4095) + * (IW_AUTH_INDEX mask in struct iw_param flags; this is the index of the + * parameter that is being set/get to; value will be read/written to + * struct iw_param value field) + */ + +#define IW_AUTH_WPA_VERSION 0 +#define IW_AUTH_CIPHER_PAIRWISE 1 +#define IW_AUTH_CIPHER_GROUP 2 +#define IW_AUTH_KEY_MGMT 3 +#define IW_AUTH_TKIP_COUNTERMEASURES 4 +#define IW_AUTH_DROP_UNENCRYPTED 5 +#define IW_AUTH_80211_AUTH_ALG 6 +#define IW_AUTH_WPA_ENABLED 7 +#define IW_AUTH_RX_UNENCRYPTED_EAPOL 8 +#define IW_AUTH_ROAMING_CONTROL 9 +#define IW_AUTH_PRIVACY_INVOKED 10 + +/* IW_AUTH_WPA_VERSION values (bit field) */ + +#define IW_AUTH_WPA_VERSION_DISABLED 0x00000001 +#define IW_AUTH_WPA_VERSION_WPA 0x00000002 +#define IW_AUTH_WPA_VERSION_WPA2 0x00000004 + +/* IW_AUTH_PAIRWISE_CIPHER and IW_AUTH_GROUP_CIPHER values (bit field) */ + +#define IW_AUTH_CIPHER_NONE 0x00000001 +#define IW_AUTH_CIPHER_WEP40 0x00000002 +#define IW_AUTH_CIPHER_TKIP 0x00000004 +#define IW_AUTH_CIPHER_CCMP 0x00000008 +#define IW_AUTH_CIPHER_WEP104 0x00000010 + +/* IW_AUTH_KEY_MGMT values (bit field) */ + +#define IW_AUTH_KEY_MGMT_802_1X 1 +#define IW_AUTH_KEY_MGMT_PSK 2 + +/* IW_AUTH_80211_AUTH_ALG values (bit field) */ + +#define IW_AUTH_ALG_OPEN_SYSTEM 0x00000001 +#define IW_AUTH_ALG_SHARED_KEY 0x00000002 +#define IW_AUTH_ALG_LEAP 0x00000004 + +/* IW_AUTH_ROAMING_CONTROL values */ + +#define IW_AUTH_ROAMING_ENABLE 0 /* driver/firmware based roaming */ +#define IW_AUTH_ROAMING_DISABLE 1 /* user space program used for roaming + * control */ + +/* SIOCSIWENCODEEXT definitions */ + +#define IW_ENCODE_SEQ_MAX_SIZE 8 + +/* struct iw_encode_ext ->alg */ + +#define IW_ENCODE_ALG_NONE 0 +#define IW_ENCODE_ALG_WEP 1 +#define IW_ENCODE_ALG_TKIP 2 +#define IW_ENCODE_ALG_CCMP 3 + /************************************************************************************ * Public Types ************************************************************************************/ @@ -318,5 +383,20 @@ struct iw_event union iwreq_data u; /* Fixed IOCTL payload */ }; +/* WPA support */ + +struct iw_encode_ext +{ + uint32_t ext_flags; /* IW_ENCODE_EXT_* */ + uint8_t tx_seq[IW_ENCODE_SEQ_MAX_SIZE]; /* LSB first */ + uint8_t rx_seq[IW_ENCODE_SEQ_MAX_SIZE]; /* LSB first */ + struct sockaddr addr; /* ff:ff:ff:ff:ff:ff for broadcast/multicast + * (group) keys or unicast address for + * individual keys */ + uint16_t alg; /* IW_ENCODE_ALG_* */ + uint16_t key_len; + uint8_t key[0]; +}; + #endif /* CONFIG_DRIVERS_WIRELESS */ #endif /* __INCLUDE_NUTTX_WIRELESS_WIRELESS_H */ -- GitLab From bd5d6ce98648636d1171cd15a068c227de05b5c2 Mon Sep 17 00:00:00 2001 From: Simon Piriou Date: Tue, 2 May 2017 08:48:13 -0600 Subject: [PATCH 676/990] bcmf: implement basic wext interface for authentication --- drivers/wireless/ieee80211/bcmf_driver.c | 297 +++++++++++++++++++++-- drivers/wireless/ieee80211/bcmf_driver.h | 15 +- drivers/wireless/ieee80211/bcmf_netdev.c | 17 +- drivers/wireless/ieee80211/bcmf_utils.c | 5 +- 4 files changed, 311 insertions(+), 23 deletions(-) diff --git a/drivers/wireless/ieee80211/bcmf_driver.c b/drivers/wireless/ieee80211/bcmf_driver.c index 8c623b75ad..791a8394ba 100644 --- a/drivers/wireless/ieee80211/bcmf_driver.c +++ b/drivers/wireless/ieee80211/bcmf_driver.c @@ -66,6 +66,7 @@ #define DOT11_BSSTYPE_ANY 2 #define BCMF_SCAN_TIMEOUT_TICK (5*CLOCKS_PER_SEC) +#define BCMF_AUTH_TIMEOUT_MS 10000 /**************************************************************************** * Private Types @@ -103,6 +104,9 @@ static void bcmf_wl_scan_event_handler(FAR struct bcmf_dev_s *priv, static void bcmf_wl_auth_event_handler(FAR struct bcmf_dev_s *priv, struct bcmf_event_s *event, unsigned int len); +static int bcmf_wl_get_interface(FAR struct bcmf_dev_s *priv, + struct iwreq *iwr); + /**************************************************************************** * Private Data ****************************************************************************/ @@ -212,12 +216,13 @@ int bcmf_driver_initialize(FAR struct bcmf_dev_s *priv) uint32_t out_len; uint32_t value; uint8_t tmp_buf[64]; + int interface = CHIP_STA_INTERFACE; /* Disable TX Gloming feature */ out_len = 4; *(uint32_t*)tmp_buf = 0; - ret = bcmf_cdc_iovar_request(priv, CHIP_STA_INTERFACE, false, + ret = bcmf_cdc_iovar_request(priv, interface, false, IOVAR_STR_TX_GLOM, tmp_buf, &out_len); if (ret != OK) @@ -229,8 +234,8 @@ int bcmf_driver_initialize(FAR struct bcmf_dev_s *priv) out_len = 4; value = 0; - ret = bcmf_cdc_ioctl(priv, CHIP_STA_INTERFACE, true, - WLC_SET_PM, (uint8_t*)&value, &out_len); + ret = bcmf_cdc_ioctl(priv, interface, true, WLC_SET_PM, + (uint8_t*)&value, &out_len); if (ret != OK) { return ret; @@ -240,8 +245,8 @@ int bcmf_driver_initialize(FAR struct bcmf_dev_s *priv) out_len = 4; value = GMODE_AUTO; - ret = bcmf_cdc_ioctl(priv, CHIP_STA_INTERFACE, true, - WLC_SET_GMODE, (uint8_t*)&value, &out_len); + ret = bcmf_cdc_ioctl(priv, interface, true, WLC_SET_GMODE, + (uint8_t*)&value, &out_len); if (ret != OK) { return ret; @@ -251,14 +256,27 @@ int bcmf_driver_initialize(FAR struct bcmf_dev_s *priv) out_len = 4; value = 1; - ret = bcmf_cdc_iovar_request(priv, CHIP_STA_INTERFACE, true, - IOVAR_STR_ROAM_OFF, (uint8_t*)&value, - &out_len); - + ret = bcmf_cdc_iovar_request(priv, interface, true, IOVAR_STR_ROAM_OFF, + (uint8_t*)&value, + &out_len); + + /* TODO configure EAPOL version to default */ + + out_len = 8; + ((uint32_t*)tmp_buf)[0] = interface; + ((uint32_t*)tmp_buf)[1] = (uint32_t)-1; + + if (bcmf_cdc_iovar_request(priv, interface, true, + "bsscfg:"IOVAR_STR_SUP_WPA2_EAPVER, tmp_buf, + &out_len)) + { + return -EIO; + } + /* Query firmware version string */ out_len = sizeof(tmp_buf); - ret = bcmf_cdc_iovar_request(priv, CHIP_STA_INTERFACE, false, + ret = bcmf_cdc_iovar_request(priv, interface, false, IOVAR_STR_VERSION, tmp_buf, &out_len); if (ret != OK) @@ -293,9 +311,18 @@ int bcmf_driver_initialize(FAR struct bcmf_dev_s *priv) bcmf_event_register(priv, bcmf_wl_scan_event_handler, WLC_E_ESCAN_RESULT); - /* Register SET_SSID event */ + /* Register authentication related events */ + bcmf_event_register(priv, bcmf_wl_auth_event_handler, WLC_E_ASSOC_IND_NDIS); + bcmf_event_register(priv, bcmf_wl_auth_event_handler, WLC_E_AUTH); + bcmf_event_register(priv, bcmf_wl_auth_event_handler, WLC_E_ASSOC); + bcmf_event_register(priv, bcmf_wl_auth_event_handler, WLC_E_LINK); + bcmf_event_register(priv, bcmf_wl_auth_event_handler, WLC_E_PSK_SUP); + bcmf_event_register(priv, bcmf_wl_auth_event_handler, WLC_E_JOIN); bcmf_event_register(priv, bcmf_wl_auth_event_handler, WLC_E_SET_SSID); + bcmf_event_register(priv, bcmf_wl_auth_event_handler, WLC_E_DEAUTH_IND); + bcmf_event_register(priv, bcmf_wl_auth_event_handler, WLC_E_DISASSOC); + bcmf_event_register(priv, bcmf_wl_auth_event_handler, WLC_E_DISASSOC_IND); if (bcmf_event_push_config(priv)) { @@ -325,15 +352,21 @@ void bcmf_wl_auth_event_handler(FAR struct bcmf_dev_s *priv, struct bcmf_event_s *event, unsigned int len) { uint32_t type; + uint32_t status; type = bcmf_getle32(&event->type); + status = bcmf_getle32(&event->status); wlinfo("Got auth event %d from <%s>\n", type, event->src_name); - if (type == WLC_E_SET_SSID) + bcmf_hexdump((uint8_t*)event, len, (unsigned long)event); + + if (type == WLC_E_SET_SSID && status == WLC_E_STATUS_SUCCESS) { /* Auth complete */ + priv->auth_status = OK; + sem_post(&priv->auth_signal); } } @@ -397,7 +430,7 @@ void bcmf_wl_scan_event_handler(FAR struct bcmf_dev_s *priv, bss = result->bss_info; - do + while (len > 0 && bss_count < result->bss_count) { bss_info_len = bss->length; @@ -418,7 +451,6 @@ void bcmf_wl_scan_event_handler(FAR struct bcmf_dev_s *priv, bss = (struct wl_bss_info*)((uint8_t*)bss + bss_info_len); bss_count += 1; } - while (len > 0 && bss_count < result->bss_count); wl_escan_result_processed: @@ -479,6 +511,12 @@ void bcmf_wl_scan_timeout(int argc, wdparm_t arg1, ...) sem_post(&priv->control_mutex); } +int bcmf_wl_get_interface(FAR struct bcmf_dev_s *priv, struct iwreq *iwr) +{ + // TODO resolve interface using iwr->ifr_name + return CHIP_STA_INTERFACE; +} + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -629,4 +667,233 @@ int bcmf_wl_is_scan_done(FAR struct bcmf_dev_s *priv) return OK; } return -EINVAL; -} \ No newline at end of file +} + +int bcmf_wl_set_auth_param(FAR struct bcmf_dev_s *priv, struct iwreq *iwr) +{ + int ret = -ENOSYS; + int interface; + uint32_t out_len; + + interface = bcmf_wl_get_interface(priv, iwr); + + if (interface < 0) + { + return -EINVAL; + } + + switch (iwr->u.param.flags & IW_AUTH_INDEX) + { + case IW_AUTH_WPA_VERSION: + { + uint32_t wpa_version[2]; + uint32_t auth_mode; + + switch (iwr->u.param.value) + { + case IW_AUTH_WPA_VERSION_DISABLED: + wpa_version[1] = 0; + auth_mode = WPA_AUTH_DISABLED; + break; + case IW_AUTH_WPA_VERSION_WPA: + wpa_version[1] = 1; + auth_mode = WPA_AUTH_PSK; + break; + case IW_AUTH_WPA_VERSION_WPA2: + wpa_version[1] = 1; + auth_mode = WPA2_AUTH_PSK; + break; + default: + wlerr("Invalid wpa version %d\n", iwr->u.param.value); + return -EINVAL; + } + + out_len = 8; + wpa_version[0] = interface; + + if (bcmf_cdc_iovar_request(priv, interface, true, + "bsscfg:"IOVAR_STR_SUP_WPA, + (uint8_t*)wpa_version, + &out_len)) + { + return -EIO; + } + + out_len = 4; + if(bcmf_cdc_ioctl(priv, interface, true, WLC_SET_WPA_AUTH, + (uint8_t*)&auth_mode, &out_len)) + { + return -EIO; + } + } + return OK; + + case IW_AUTH_CIPHER_PAIRWISE: + case IW_AUTH_CIPHER_GROUP: + { + uint32_t cipher_mode; + uint32_t wep_auth = 0; + + switch (iwr->u.param.value) + { + case IW_AUTH_CIPHER_WEP40: + case IW_AUTH_CIPHER_WEP104: + cipher_mode = WEP_ENABLED; + wep_auth = 1; + break; + case IW_AUTH_CIPHER_TKIP: + cipher_mode = TKIP_ENABLED; + break; + case IW_AUTH_CIPHER_CCMP: + cipher_mode = AES_ENABLED; + break; + default: + wlerr("Invalid cipher mode %d\n", iwr->u.param.value); + return -EINVAL; + } + + out_len = 4; + if(bcmf_cdc_ioctl(priv, interface, true, + WLC_SET_WSEC, (uint8_t*)&cipher_mode, &out_len)) + { + return -EIO; + } + + /* Set authentication mode */ + + out_len = 4; + if(bcmf_cdc_ioctl(priv, interface, true, + WLC_SET_AUTH, (uint8_t*)&wep_auth, &out_len)) + { + return -EIO; + } + } + return OK; + + case IW_AUTH_KEY_MGMT: + case IW_AUTH_TKIP_COUNTERMEASURES: + case IW_AUTH_DROP_UNENCRYPTED: + case IW_AUTH_80211_AUTH_ALG: + case IW_AUTH_WPA_ENABLED: + case IW_AUTH_RX_UNENCRYPTED_EAPOL: + case IW_AUTH_ROAMING_CONTROL: + case IW_AUTH_PRIVACY_INVOKED: + default: + wlerr("Unknown cmd %d\n", iwr->u.param.flags); + break; + } + + return ret; +} + +int bcmf_wl_set_mode(FAR struct bcmf_dev_s *priv, struct iwreq *iwr) +{ + int interface; + uint32_t out_len; + uint32_t value; + + interface = bcmf_wl_get_interface(priv, iwr); + + if (interface < 0) + { + return -EINVAL; + } + + out_len = 4; + value = iwr->u.mode == IW_MODE_INFRA ? 1 : 0; + if(bcmf_cdc_ioctl(priv, interface, true, + WLC_SET_INFRA, (uint8_t*)&value, &out_len)) + { + return -EIO; + } + + return OK; +} + +int bcmf_wl_set_encode_ext(FAR struct bcmf_dev_s *priv, struct iwreq *iwr) +{ + int interface; + struct iw_encode_ext *ext; + uint32_t out_len; + wsec_pmk_t psk; + + interface = bcmf_wl_get_interface(priv, iwr); + + if (interface < 0) + { + return -EINVAL; + } + + ext = (struct iw_encode_ext*)iwr->u.encoding.pointer; + + switch (ext->alg) + { + case IW_ENCODE_ALG_TKIP: + break; + case IW_ENCODE_ALG_CCMP: + break; + case IW_ENCODE_ALG_NONE: + case IW_ENCODE_ALG_WEP: + default: + wlerr("Unknown algo %d\n", ext->alg); + return -EINVAL; + } + + memset(&psk, 0, sizeof(wsec_pmk_t)); + memcpy(psk.key, &ext->key, ext->key_len); + psk.key_len = ext->key_len; + psk.flags = WSEC_PASSPHRASE; + + out_len = sizeof(psk); + return bcmf_cdc_ioctl(priv, interface, true, + WLC_SET_WSEC_PMK, (uint8_t*)&psk, &out_len); +} + +int bcmf_wl_set_ssid(FAR struct bcmf_dev_s *priv, struct iwreq *iwr) +{ + int ret; + int interface; + uint32_t out_len; + wlc_ssid_t ssid; + + interface = bcmf_wl_get_interface(priv, iwr); + + if (interface < 0) + { + return -EINVAL; + } + + ssid.SSID_len = iwr->u.essid.length; + memcpy(ssid.SSID, iwr->u.essid.pointer, iwr->u.essid.length); + + /* Configure AP SSID and trig authentication request */ + + out_len = sizeof(ssid); + if(bcmf_cdc_ioctl(priv, interface, true, + WLC_SET_SSID, (uint8_t*)&ssid, &out_len)) + { + return -EIO; + } + + ret = bcmf_sem_wait(&priv->auth_signal, BCMF_AUTH_TIMEOUT_MS); + + wlinfo("semwait done ! %d\n", ret); + + if (ret) + { + wlerr("Associate request timeout\n"); + return -EINVAL; + } + + switch (priv->auth_status) + { + case OK: + wlinfo("AP Join ok\n"); + break; + + default: + wlerr("AP join failed %d\n", priv->auth_status); + return -EINVAL; + } + return OK; + } diff --git a/drivers/wireless/ieee80211/bcmf_driver.h b/drivers/wireless/ieee80211/bcmf_driver.h index c264ca5da9..27b2e51a40 100644 --- a/drivers/wireless/ieee80211/bcmf_driver.h +++ b/drivers/wireless/ieee80211/bcmf_driver.h @@ -94,6 +94,7 @@ struct bcmf_dev_s struct wl_escan_params *scan_params; /* Current scan parameters */ sem_t auth_signal; /* Authentication notification signal */ + int auth_status; /* Authentication status */ }; /* Default bus interface structure */ @@ -126,14 +127,26 @@ struct bcmf_frame_s uint16_t len; /* Frame buffer size */ }; +/* IOCTLs network interface implementation */ + int bcmf_wl_set_mac_address(FAR struct bcmf_dev_s *priv, struct ifreq *req); int bcmf_wl_enable(FAR struct bcmf_dev_s *priv, bool enable); +/* IOCTLs AP scan interface implementation */ + int bcmf_wl_start_scan(FAR struct bcmf_dev_s *priv); int bcmf_wl_is_scan_done(FAR struct bcmf_dev_s *priv); -int bcmf_wl_associate(FAR struct bcmf_dev_s *priv); +/* IOCTLs authentication interface implementation */ + +int bcmf_wl_set_auth_param(FAR struct bcmf_dev_s *priv, struct iwreq *iwr); + +int bcmf_wl_set_encode_ext(FAR struct bcmf_dev_s *priv, struct iwreq *iwr); + +int bcmf_wl_set_mode(FAR struct bcmf_dev_s *priv, struct iwreq *iwr); + +int bcmf_wl_set_ssid(FAR struct bcmf_dev_s *priv, struct iwreq *iwr); #endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_DRIVER_H */ diff --git a/drivers/wireless/ieee80211/bcmf_netdev.c b/drivers/wireless/ieee80211/bcmf_netdev.c index 32dd54176c..7422991f49 100644 --- a/drivers/wireless/ieee80211/bcmf_netdev.c +++ b/drivers/wireless/ieee80211/bcmf_netdev.c @@ -1010,11 +1010,18 @@ static int bcmf_ioctl(FAR struct net_driver_s *dev, int cmd, ret = bcmf_wl_is_scan_done(priv); break; - case SIOCSIFHWADDR: - /* Update device MAC address */ + case SIOCSIFHWADDR: /* Set device MAC address */ ret = bcmf_wl_set_mac_address(priv, (struct ifreq*)arg); break; + case SIOCSIWAUTH: + ret = bcmf_wl_set_auth_param(priv, (struct iwreq*)arg); + break; + + case SIOCSIWENCODEEXT: + ret = bcmf_wl_set_encode_ext(priv, (struct iwreq*)arg); + break; + case SIOCSIWFREQ: /* Set channel/frequency (Hz) */ wlwarn("WARNING: SIOCSIWFREQ not implemented\n"); ret = -ENOSYS; @@ -1026,8 +1033,7 @@ static int bcmf_ioctl(FAR struct net_driver_s *dev, int cmd, break; case SIOCSIWMODE: /* Set operation mode */ - wlwarn("WARNING: SIOCSIWMODE not implemented\n"); - ret = -ENOSYS; + ret = bcmf_wl_set_mode(priv, (struct iwreq*)arg); break; case SIOCGIWMODE: /* Get operation mode */ @@ -1046,8 +1052,7 @@ static int bcmf_ioctl(FAR struct net_driver_s *dev, int cmd, break; case SIOCSIWESSID: /* Set ESSID (network name) */ - wlwarn("WARNING: SIOCSIWESSID not implemented\n"); - ret = -ENOSYS; + ret = bcmf_wl_set_ssid(priv, (struct iwreq*)arg); break; case SIOCGIWESSID: /* Get ESSID */ diff --git a/drivers/wireless/ieee80211/bcmf_utils.c b/drivers/wireless/ieee80211/bcmf_utils.c index 4fb126356e..b45f649f1e 100644 --- a/drivers/wireless/ieee80211/bcmf_utils.c +++ b/drivers/wireless/ieee80211/bcmf_utils.c @@ -101,12 +101,15 @@ void bcmf_hexdump(uint8_t *data, unsigned int len, unsigned long offset) int bcmf_sem_wait(sem_t *sem, unsigned int timeout_ms) { struct timespec abstime; + unsigned int timeout_sec; /* Get the current time */ (void)clock_gettime(CLOCK_REALTIME, &abstime); - abstime.tv_nsec += 1000 * 1000* timeout_ms; + timeout_sec = timeout_ms/1000; + abstime.tv_sec += timeout_sec; + abstime.tv_nsec += 1000 * 1000* (timeout_ms % 1000); if (abstime.tv_nsec >= 1000 * 1000 * 1000) { -- GitLab From db4fd71f4fb148eee0b133517c2e0f126396c51c Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Tue, 2 May 2017 17:18:15 +0200 Subject: [PATCH 677/990] first attempt at a nucleo-l432kc board --- configs/nucleo-l432kc/Kconfig | 21 + configs/nucleo-l432kc/README.txt | 508 ++++++++ configs/nucleo-l432kc/include/board.h | 271 ++++ configs/nucleo-l432kc/include/nucleo-l432kc.h | 510 ++++++++ configs/nucleo-l432kc/nsh/Make.defs | 112 ++ configs/nucleo-l432kc/nsh/defconfig | 1102 +++++++++++++++++ configs/nucleo-l432kc/scripts/l432kc.ld | 119 ++ configs/nucleo-l432kc/src/Makefile | 71 ++ configs/nucleo-l432kc/src/nucleo-l432kc.h | 390 ++++++ configs/nucleo-l432kc/src/stm32_adc.c | 148 +++ configs/nucleo-l432kc/src/stm32_appinit.c | 342 +++++ configs/nucleo-l432kc/src/stm32_autoleds.c | 96 ++ configs/nucleo-l432kc/src/stm32_boot.c | 128 ++ configs/nucleo-l432kc/src/stm32_buttons.c | 126 ++ configs/nucleo-l432kc/src/stm32_pwm.c | 272 ++++ configs/nucleo-l432kc/src/stm32_qencoder.c | 83 ++ configs/nucleo-l432kc/src/stm32_spi.c | 202 +++ configs/nucleo-l432kc/src/stm32_timer.c | 82 ++ configs/nucleo-l432kc/src/stm32_userleds.c | 217 ++++ 19 files changed, 4800 insertions(+) create mode 100644 configs/nucleo-l432kc/Kconfig create mode 100644 configs/nucleo-l432kc/README.txt create mode 100644 configs/nucleo-l432kc/include/board.h create mode 100644 configs/nucleo-l432kc/include/nucleo-l432kc.h create mode 100644 configs/nucleo-l432kc/nsh/Make.defs create mode 100644 configs/nucleo-l432kc/nsh/defconfig create mode 100644 configs/nucleo-l432kc/scripts/l432kc.ld create mode 100644 configs/nucleo-l432kc/src/Makefile create mode 100644 configs/nucleo-l432kc/src/nucleo-l432kc.h create mode 100644 configs/nucleo-l432kc/src/stm32_adc.c create mode 100644 configs/nucleo-l432kc/src/stm32_appinit.c create mode 100644 configs/nucleo-l432kc/src/stm32_autoleds.c create mode 100644 configs/nucleo-l432kc/src/stm32_boot.c create mode 100644 configs/nucleo-l432kc/src/stm32_buttons.c create mode 100644 configs/nucleo-l432kc/src/stm32_pwm.c create mode 100644 configs/nucleo-l432kc/src/stm32_qencoder.c create mode 100644 configs/nucleo-l432kc/src/stm32_spi.c create mode 100644 configs/nucleo-l432kc/src/stm32_timer.c create mode 100644 configs/nucleo-l432kc/src/stm32_userleds.c diff --git a/configs/nucleo-l432kc/Kconfig b/configs/nucleo-l432kc/Kconfig new file mode 100644 index 0000000000..6c35982a4c --- /dev/null +++ b/configs/nucleo-l432kc/Kconfig @@ -0,0 +1,21 @@ +# +# For a description of the syntax of this configuration file, +# see the file kconfig-language.txt in the NuttX tools repository. +# + +if ARCH_BOARD_NUCLEO_L432KC + +config NUCLEO_L432KC_AJOY_MINBUTTONS + bool "Minimal Joystick Buttons" + default n if !STM32_USART1 + default y if STM32_USART1 + depends on AJOYSTICK + ---help--- + The Itead Joystick shield supports analog X/Y position and up to 5 + buttons. Some of these buttons may conflict with other resources + (Button F, for example, conflicts with the default USART1 pin usage). + Selecting this option will return the number of buttons to the + minimal set: SELECT (joystick down), FIRE (BUTTON B), and JUMP + (BUTTON A). + +endif # ARCH_BOARD_NUCLEO_L432KC diff --git a/configs/nucleo-l432kc/README.txt b/configs/nucleo-l432kc/README.txt new file mode 100644 index 0000000000..0c642daa1b --- /dev/null +++ b/configs/nucleo-l432kc/README.txt @@ -0,0 +1,508 @@ +README +====== + +This README discusses issues unique to NuttX configurations for the ST +Nucleoi-l432kc board from ST Micro. See + + http://www.st.com/nucleo-l432kc + +NucleoF476RG: + + Microprocessor: 32-bit ARM Cortex M4 at 80MHz STM32L432KCU6 + Memory: 256 KB Flash and 64 KB SRAM + ADC: 2×12-bit, 2.4 MSPS A/D converter: up to 24 channels + DMA: 16-stream DMA controllers with FIFOs and burst support + Timers: Up to 11 timers: up to five 16-bit, one 32-bit, two low-power + 16 bit timers, two watchdog timers, and a SysTick timer + GPIO: Up to 26 I/O ports with interrupt capability, most 5v tolerant + I2C: Up to 2 × I2C interfaces + USARTs: Up to 3 USARTs, 2 UARTs, 1 LPUART + SPIs: Up to 2 SPIs + SAIs: 1 dual-channel audio interface + CAN interface + SDIO interface + QSPI interface + USB: USB 2.0 full-speed device/host/OTG controller with on-chip PHY + CRC calculation unit + RTC + +Board features: + + Peripherals: 1 led, 1 push button + Debug: Serial wire debug and JTAG interfaces via on-board micro-usb stlink v2.1 + Expansion I/F Arduino Nano Headers + + Uses a STM32F103 to provide a ST-Link for programming, debug similar to the + OpenOcd FTDI function - USB to JTAG front-end. + + See http://mbed.org/platforms/ST-Nucleo-L432KC for more + information about these boards. + +Contents +======== + + - Nucleo-32 Boards + - Development Environment + - GNU Toolchain Options + - IDEs + - NuttX EABI "buildroot" Toolchain + - NXFLAT Toolchain + - Hardware + - Button + - LED + - USARTs and Serial Consoles + - QFN32 + - mbed + - Configurations + +Nucleo-32 Boards +================ + +The Nucleo-L432KC is a member of the Nucleo-64 board family. The Nucleo-64 +is a standard board for use with several STM32 parts in the LQFP64 package. +Variants include + + Order code Targeted STM32 + ------------- -------------- + NUCLEO-F031K6 STM32F031K6T6 + NUCLEO-F042K6 STM32F042K6T6 + NUCLEO-F303K8 STM32F303K8T6 + NUCLEO-L011K4 STM32L011K4T6 + NUCLEO-L031K6 STM32L031K6T6 + NUCLEO-L432KC STM32L432KCU6 + +Development Environment +======================= + + Either Linux or Cygwin on Windows can be used for the development environment. + The source has been built only using the GNU toolchain (see below). Other + toolchains will likely cause problems. + +GNU Toolchain Options +===================== + + Toolchain Configurations + ------------------------ + The NuttX make system has been modified to support the following different + toolchain options. + + 1. The CodeSourcery GNU toolchain, + 2. The Atollic Toolchain, + 3. The devkitARM GNU toolchain, + 4. Raisonance GNU toolchain, or + 5. The NuttX buildroot Toolchain (see below). + + All testing has been conducted using the CodeSourcery toolchain for Linux. + To use the Atollic, devkitARM, Raisonance GNU, or NuttX buildroot toolchain, + you simply need to add one of the following configuration options to your + .config (or defconfig) file: + + CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYW=n : CodeSourcery under Windows + CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL=y : CodeSourcery under Linux + CONFIG_ARMV7M_TOOLCHAIN_ATOLLIC=y : The Atollic toolchain under Windows + CONFIG_ARMV7M_TOOLCHAIN_DEVKITARM=n : devkitARM under Windows + CONFIG_ARMV7M_TOOLCHAIN_RAISONANCE=y : Raisonance RIDE7 under Windows + CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=n : NuttX buildroot under Linux or Cygwin (default) + + If you change the default toolchain, then you may also have to modify the + PATH environment variable to include the path to the toolchain binaries. + + NOTE: There are several limitations to using a Windows based toolchain in a + Cygwin environment. The three biggest are: + + 1. The Windows toolchain cannot follow Cygwin paths. Path conversions are + performed automatically in the Cygwin makefiles using the 'cygpath' utility + but you might easily find some new path problems. If so, check out 'cygpath -w' + + 2. Windows toolchains cannot follow Cygwin symbolic links. Many symbolic links + are used in Nuttx (e.g., include/arch). The make system works around these + problems for the Windows tools by copying directories instead of linking them. + But this can also cause some confusion for you: For example, you may edit + a file in a "linked" directory and find that your changes had no effect. + That is because you are building the copy of the file in the "fake" symbolic + directory. If you use a Windows toolchain, you should get in the habit of + making like this: + + V=1 make clean_context all 2>&1 |tee mout + + An alias in your .bashrc file might make that less painful. + + 3. Dependencies are not made when using Windows versions of the GCC. This is + because the dependencies are generated using Windows pathes which do not + work with the Cygwin make. + + MKDEP = $(TOPDIR)/tools/mknulldeps.sh + + The Atollic "Pro" and "Lite" Toolchain + -------------------------------------- + One problem that I had with the Atollic toolchains is that the provide a gcc.exe + and g++.exe in the same bin/ file as their ARM binaries. If the Atollic bin/ path + appears in your PATH variable before /usr/bin, then you will get the wrong gcc + when you try to build host executables. This will cause to strange, uninterpretable + errors build some host binaries in tools/ when you first make. + + Also, the Atollic toolchains are the only toolchains that have built-in support for + the FPU in these configurations. If you plan to use the Cortex-M4 FPU, you will + need to use the Atollic toolchain for now. See the FPU section below for more + information. + + The Atollic "Lite" Toolchain + ---------------------------- + The free, "Lite" version of the Atollic toolchain does not support C++ nor + does it support ar, nm, objdump, or objdcopy. If you use the Atollic "Lite" + toolchain, you will have to set: + + CONFIG_HAVE_CXX=n + + In order to compile successfully. Otherwise, you will get errors like: + + "C++ Compiler only available in TrueSTUDIO Professional" + + The make may then fail in some of the post link processing because of some of + the other missing tools. The Make.defs file replaces the ar and nm with + the default system x86 tool versions and these seem to work okay. Disable all + of the following to avoid using objcopy: + + CONFIG_RRLOAD_BINARY=n + CONFIG_INTELHEX_BINARY=n + CONFIG_MOTOROLA_SREC=n + CONFIG_RAW_BINARY=n + + devkitARM + --------- + The devkitARM toolchain includes a version of MSYS make. Make sure that the + the paths to Cygwin's /bin and /usr/bin directories appear BEFORE the devkitARM + path or will get the wrong version of make. + +IDEs +==== + + NuttX is built using command-line make. It can be used with an IDE, but some + effort will be required to create the project. + + Makefile Build + -------------- + Under Eclipse, it is pretty easy to set up an "empty makefile project" and + simply use the NuttX makefile to build the system. That is almost for free + under Linux. Under Windows, you will need to set up the "Cygwin GCC" empty + makefile project in order to work with Windows (Google for "Eclipse Cygwin" - + there is a lot of help on the internet). + + Using Sourcery CodeBench from http://www.mentor.com/embedded-software/sourcery-tools/sourcery-codebench/overview + Download and install the latest version (as of this writting it was + sourceryg++-2013.05-64-arm-none-eabi) + + Import the project from git. + File->import->Git-URI, then import a Exiting code as a Makefile progject + from the working directory the git clone was done to. + + Select the Sourcery CodeBench for ARM EABI. N.B. You must do one command line + build, before the make will work in CodeBench. + + Native Build + ------------ + Here are a few tips before you start that effort: + + 1) Select the toolchain that you will be using in your .config file + 2) Start the NuttX build at least one time from the Cygwin command line + before trying to create your project. This is necessary to create + certain auto-generated files and directories that will be needed. + 3) Set up include pathes: You will need include/, arch/arm/src/stm32, + arch/arm/src/common, arch/arm/src/armv7-m, and sched/. + 4) All assembly files need to have the definition option -D __ASSEMBLY__ + on the command line. + + Startup files will probably cause you some headaches. The NuttX startup file + is arch/arm/src/stm32/stm32_vectors.S. With RIDE, I have to build NuttX + one time from the Cygwin command line in order to obtain the pre-built + startup object needed by RIDE. + +NuttX EABI "buildroot" Toolchain +================================ + + A GNU GCC-based toolchain is assumed. The PATH environment variable should + be modified to point to the correct path to the Cortex-M3 GCC toolchain (if + different from the default in your PATH variable). + + If you have no Cortex-M3 toolchain, one can be downloaded from the NuttX + Bitbucket download site (https://bitbucket.org/nuttx/buildroot/downloads/). + This GNU toolchain builds and executes in the Linux or Cygwin environment. + + 1. You must have already configured Nuttx in /nuttx. + + $ (cd tools; ./configure.sh nucleo-f4x1re/f401-nsh) + $ make qconfig + $ V=1 make context all 2>&1 | tee mout + + Use the f411-nsh configuration if you have the Nucleo-F411RE board. + + 2. Download the latest buildroot package into + + 3. unpack the buildroot tarball. The resulting directory may + have versioning information on it like buildroot-x.y.z. If so, + rename /buildroot-x.y.z to /buildroot. + + 4. cd /buildroot + + 5. cp configs/cortexm3-eabi-defconfig-4.6.3 .config + + 6. make oldconfig + + 7. make + + 8. Make sure that the PATH variable includes the path to the newly built + binaries. + + See the file configs/README.txt in the buildroot source tree. That has more + details PLUS some special instructions that you will need to follow if you are + building a Cortex-M3 toolchain for Cygwin under Windows. + + NOTE: Unfortunately, the 4.6.3 EABI toolchain is not compatible with the + the NXFLAT tools. See the top-level TODO file (under "Binary loaders") for + more information about this problem. If you plan to use NXFLAT, please do not + use the GCC 4.6.3 EABI toolchain; instead use the GCC 4.3.3 EABI toolchain. + +NXFLAT Toolchain +================ + + If you are *not* using the NuttX buildroot toolchain and you want to use + the NXFLAT tools, then you will still have to build a portion of the buildroot + tools -- just the NXFLAT tools. The buildroot with the NXFLAT tools can + be downloaded from the NuttX Bitbucket download site + (https://bitbucket.org/nuttx/nuttx/downloads/). + + This GNU toolchain builds and executes in the Linux or Cygwin environment. + + 1. You must have already configured Nuttx in /nuttx. + + cd tools + ./configure.sh lpcxpresso-lpc1768/ + + 2. Download the latest buildroot package into + + 3. unpack the buildroot tarball. The resulting directory may + have versioning information on it like buildroot-x.y.z. If so, + rename /buildroot-x.y.z to /buildroot. + + 4. cd /buildroot + + 5. cp configs/cortexm3-defconfig-nxflat .config + + 6. make oldconfig + + 7. make + + 8. Make sure that the PATH variable includes the path to the newly built + NXFLAT binaries. + +mbed +==== + + The Nucleo-F401RE includes boot loader from mbed: + + https://mbed.org/platforms/ST-Nucleo-F401RE/ + https://mbed.org/handbook/Homepage + + Using the mbed loader: + + 1. Connect the Nucleo-F4x1RE to the host PC using the USB connector. + 2. A new file system will appear called NUCLEO; open it with Windows + Explorer (assuming that you are using Windows). + 3. Drag and drop nuttx.bin into the MBED window. This will load the + nuttx.bin binary into the Nucleo-L432kc. The NUCLEO window will + close then re-open and the Nucleo-L432KC will be running the new code. + +Hardware +======== + + GPIO + ---- + SERIAL_TX=PA_2 USER_BUTTON=PC_13 + SERIAL_RX=PA_3 LED1 =PA_5 + + A0=PA_0 USART2RX D0=PA_3 D8 =PA_9 + A1=PA_1 USART2TX D1=PA_2 D9 =PC_7 + A2=PA_4 D2=PA_10 WIFI_CS=D10=PB_6 SPI_CS + A3=PB_0 WIFI_INT=D3=PB_3 D11=PA_7 SPI_MOSI + A4=PC_1 SDCS=D4=PB_5 D12=PA_6 SPI_MISO + A5=PC_0 WIFI_EN=D5=PB_4 LED1=D13=PA_5 SPI_SCK + LED2=D6=PB_10 I2C1_SDA=D14=PB_9 Probe + D7=PA_8 I2C1_SCL=D15=PB_8 Probe + + From: https://mbed.org/platforms/ST-Nucleo-F401RE/ + + Buttons + ------- + B1 USER: the user button is connected to the I/O PC13 (pin 2) of the STM32 + microcontroller. + + LEDs + ---- + The Nucleo F401RE and Nucleo F411RE provide a single user LED, LD2. LD2 + is the green LED connected to Arduino signal D13 corresponding to MCU I/O + PA5 (pin 21) or PB13 (pin 34) depending on the STM32target. + + - When the I/O is HIGH value, the LED is on. + - When the I/O is LOW, the LED is off. + + These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is + defined. In that case, the usage by the board port is defined in + include/board.h and src/sam_leds.c. The LEDs are used to encode OS-related + events as follows when the red LED (PE24) is available: + + SYMBOL Meaning LD2 + ------------------- ----------------------- ----------- + LED_STARTED NuttX has been started OFF + LED_HEAPALLOCATE Heap has been allocated OFF + LED_IRQSENABLED Interrupts enabled OFF + LED_STACKCREATED Idle stack created ON + LED_INIRQ In an interrupt No change + LED_SIGNAL In a signal handler No change + LED_ASSERTION An assertion failed No change + LED_PANIC The system has crashed Blinking + LED_IDLE MCU is is sleep mode Not used + + Thus if LD2, NuttX has successfully booted and is, apparently, running + normally. If LD2 is flashing at approximately 2Hz, then a fatal error + has been detected and the system has halted. + +Serial Consoles +=============== + + USART1 + ------ + Pins and Connectors: + + RXD: PA11 CN10 pin 14 + PB7 CN7 pin 21 + TXD: PA10 CN9 pin 3, CN10 pin 33 + PB6 CN5 pin 3, CN10 pin 17 + + NOTE: You may need to edit the include/board.h to select different USART1 + pin selections. + + TTL to RS-232 converter connection: + + Nucleo CN10 STM32F4x1RE + ----------- ------------ + Pin 21 PA9 USART1_RX *Warning you make need to reverse RX/TX on + Pin 33 PA10 USART1_TX some RS-232 converters + Pin 20 GND + Pin 8 U5V + + To configure USART1 as the console: + + CONFIG_STM32_USART1=y + CONFIG_USART1_SERIALDRIVER=y + CONFIG_USART1_SERIAL_CONSOLE=y + CONFIG_USART1_RXBUFSIZE=256 + CONFIG_USART1_TXBUFSIZE=256 + CONFIG_USART1_BAUD=115200 + CONFIG_USART1_BITS=8 + CONFIG_USART1_PARITY=0 + CONFIG_USART1_2STOP=0 + + USART2 + ----- + Pins and Connectors: + + RXD: PA3 CN9 pin 1 (See SB13, 14, 62, 63). CN10 pin 37 + PD6 + TXD: PA2 CN9 pin 2(See SB13, 14, 62, 63). CN10 pin 35 + PD5 + + UART2 is the default in all of these configurations. + + TTL to RS-232 converter connection: + + Nucleo CN9 STM32F4x1RE + ----------- ------------ + Pin 1 PA3 USART2_RX *Warning you make need to reverse RX/TX on + Pin 2 PA2 USART2_TX some RS-232 converters + + Solder Bridges. This configuration requires: + + - SB62 and SB63 Closed: PA2 and PA3 on STM32 MCU are connected to D1 and D0 + (pin 7 and pin 8) on Arduino connector CN9 and ST Morpho connector CN10 + as USART signals. Thus SB13 and SB14 should be OFF. + + - SB13 and SB14 Open: PA2 and PA3 on STM32F103C8T6 (ST-LINK MCU) are + disconnected to PA3 and PA2 on STM32 MCU. + + To configure USART2 as the console: + + CONFIG_STM32_USART2=y + CONFIG_USART2_SERIALDRIVER=y + CONFIG_USART2_SERIAL_CONSOLE=y + CONFIG_USART2_RXBUFSIZE=256 + CONFIG_USART2_TXBUFSIZE=256 + CONFIG_USART2_BAUD=115200 + CONFIG_USART2_BITS=8 + CONFIG_USART2_PARITY=0 + CONFIG_USART2_2STOP=0 + + Virtual COM Port + ---------------- + Yet another option is to use UART2 and the USB virtual COM port. This + option may be more convenient for long term development, but is painful + to use during board bring-up. + + Solder Bridges. This configuration requires: + + - SB62 and SB63 Open: PA2 and PA3 on STM32 MCU are disconnected to D1 + and D0 (pin 7 and pin 8) on Arduino connector CN9 and ST Morpho + connector CN10. + + - SB13 and SB14 Closed: PA2 and PA3 on STM32F103C8T6 (ST-LINK MCU) are + connected to PA3 and PA2 on STM32 MCU to have USART communication + between them. Thus SB61, SB62 and SB63 should be OFF. + + Configuring USART2 is the same as given above. + + Question: What BAUD should be configure to interface with the Virtual + COM port? 115200 8N1? + + Default + ------- + As shipped, SB62 and SB63 are open and SB13 and SB14 closed, so the + virtual COM port is enabled. + +Configurations +============== + + nsh: + --------- + Configures the NuttShell (nsh) located at apps/examples/nsh for the + Nucleo-F401RE board. The Configuration enables the serial interfaces + on UART2. Support for builtin applications is enabled, but in the base + configuration no builtin applications are selected (see NOTES below). + + NOTES: + + 1. This configuration uses the mconf-based configuration tool. To + change this configuration using that tool, you should: + + a. Build and install the kconfig-mconf tool. See nuttx/README.txt + see additional README.txt files in the NuttX tools repository. + + b. Execute 'make menuconfig' in nuttx/ in order to start the + reconfiguration process. + + 2. By default, this configuration uses the CodeSourcery toolchain + for Linux. That can easily be reconfigured, of course. + + CONFIG_HOST_LINUX=y : Builds under Linux + CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL=y : CodeSourcery for Linux + + 3. Although the default console is USART2 (which would correspond to + the Virtual COM port) I have done all testing with the console + device configured for USART1 (see instruction above under "Serial + Consoles). I have been using a TTL-to-RS-232 converter connected + as shown below: + + Nucleo CN10 STM32F4x1RE + ----------- ------------ + Pin 21 PA9 USART1_RX *Warning you make need to reverse RX/TX on + Pin 33 PA10 USART1_TX some RS-232 converters + Pin 20 GND + Pin 8 U5V diff --git a/configs/nucleo-l432kc/include/board.h b/configs/nucleo-l432kc/include/board.h new file mode 100644 index 0000000000..7109f47a1a --- /dev/null +++ b/configs/nucleo-l432kc/include/board.h @@ -0,0 +1,271 @@ +/************************************************************************************ + * configs/nucleo-l432kc/include/board.h + * + * Copyright (C) 2016 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. + * + ************************************************************************************/ + +#ifndef __CONFIGS_NUCLEO_L432KC_INCLUDE_BOARD_H +#define __CONFIGS_NUCLEO_L432KC_INCLUDE_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#ifndef __ASSEMBLY__ +# include +#endif + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ + +#if defined(CONFIG_ARCH_CHIP_STM32L432KC) +# include +#endif + +/* DMA Channel/Stream Selections ****************************************************/ +/* Stream selections are arbitrary for now but might become important in the future + * is we set aside more DMA channels/streams. + */ + +/* Values defined in arch/arm/src/stm32l4/chip/stm32l4x6xx_dma.h */ + +#define DMACHAN_SDMMC DMACHAN_SDMMC_1 /* 2 choices */ + +#define DMACHAN_SPI1_RX DMACHAN_SPI1_RX_1 /* 2 choices */ +#define DMACHAN_SPI1_TX DMACHAN_SPI1_TX_1 /* 2 choices */ + +/* UART RX DMA configurations */ + +#define DMACHAN_USART1_RX DMACHAN_USART1_RX_2 + +/* Alternate function pin selections ************************************************/ + +/* USART1: + * RXD: PA10 CN9 pin 3, CN10 pin 33 + * PB7 CN7 pin 21 + * TXD: PA9 CN5 pin 1, CN10 pin 21 + * PB6 CN5 pin 3, CN10 pin 17 + */ + +#if 1 +# define GPIO_USART1_RX GPIO_USART1_RX_1 /* PA10 */ +# define GPIO_USART1_TX GPIO_USART1_TX_1 /* PA9 */ +#else +# define GPIO_USART1_RX GPIO_USART1_RX_2 /* PB7 */ +# define GPIO_USART1_TX GPIO_USART1_TX_2 /* PB6 */ +#endif + +/* USART2: Connected to STLInk Debug via PA2, PA3 + * RXD: PA3 CN9 pin 1 (See SB13, 14, 62, 63). CN10 pin 37 + * PD6 + * TXD: PA2 CN9 pin 2 (See SB13, 14, 62, 63). CN10 pin 35 + * PD5 + */ + +#define GPIO_USART2_RX GPIO_USART2_RX_1 /* PA3 */ +#define GPIO_USART2_TX GPIO_USART2_TX_1 /* PA2 */ +#define GPIO_USART2_RTS GPIO_USART2_RTS_2 +#define GPIO_USART2_CTS GPIO_USART2_CTS_2 + +#define GPIO_UART4_RX GPIO_UART4_RX_1 /* PA1 */ +#define GPIO_UART4_TX GPIO_UART4_TX_1 /* PA0 */ + +/* I2C + * + * The optional _GPIO configurations allow the I2C driver to manually + * reset the bus to clear stuck slaves. They match the pin configuration, + * but are normally-high GPIOs. + */ + +#define GPIO_I2C1_SCL \ + (GPIO_I2C1_SCL_2 | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET) +#define GPIO_I2C1_SDA \ + (GPIO_I2C1_SDA_2 | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET) +#define GPIO_I2C1_SCL_GPIO \ + (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | \ + GPIO_PORTB | GPIO_PIN8) +#define GPIO_I2C1_SDA_GPIO \ + (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | \ + GPIO_PORTB | GPIO_PIN9) + +#define GPIO_I2C2_SCL \ + (GPIO_I2C2_SCL_1 | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET) +#define GPIO_I2C2_SDA \ + (GPIO_I2C2_SDA_1 | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET) +#define GPIO_I2C2_SCL_GPIO \ + (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | \ + GPIO_PORTB | GPIO_PIN10) +#define GPIO_I2C2_SDA_GPIO \ + (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | \ + GPIO_PORTB | GPIO_PIN11) + +/* SPI */ + +/* SPI1 is available on the arduino protocol at positions D11/12/13 */ + +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /*PA6*/ +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 /*PA7*/ +#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1 /*PA5*/ + +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 /*PB14*/ +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1 /*PB15*/ +#define GPIO_SPI2_SCK GPIO_SPI2_SCK_2 /*PB13*/ + +/* LEDs + * + * The Nucleo l476RG board provides a single user LED, LD2. LD2 + * is the green LED connected to Arduino signal D13 corresponding to MCU I/O + * PA5 (pin 21) or PB13 (pin 34) depending on the STM32 target. + * + * - When the I/O is HIGH value, the LED is on. + * - When the I/O is LOW, the LED is off. + */ + +/* LED index values for use with board_userled() */ + +#define BOARD_LD2 0 +#define BOARD_NLEDS 1 + +/* LED bits for use with board_userled_all() */ + +#define BOARD_LD2_BIT (1 << BOARD_LD2) + +/* These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is + * defined. In that case, the usage by the board port is defined in + * include/board.h and src/sam_leds.c. The LEDs are used to encode OS-related + * events as follows when the red LED (PE24) is available: + * + * SYMBOL Meaning LD2 + * ------------------- ----------------------- ----------- + * LED_STARTED NuttX has been started OFF + * LED_HEAPALLOCATE Heap has been allocated OFF + * LED_IRQSENABLED Interrupts enabled OFF + * LED_STACKCREATED Idle stack created ON + * LED_INIRQ In an interrupt No change + * LED_SIGNAL In a signal handler No change + * LED_ASSERTION An assertion failed No change + * LED_PANIC The system has crashed Blinking + * LED_IDLE MCU is is sleep mode Not used + * + * Thus if LD2, NuttX has successfully booted and is, apparently, running + * normally. If LD2 is flashing at approximately 2Hz, then a fatal error + * has been detected and the system has halted. + */ + +#define LED_STARTED 0 +#define LED_HEAPALLOCATE 0 +#define LED_IRQSENABLED 0 +#define LED_STACKCREATED 1 +#define LED_INIRQ 1 +#define LED_SIGNAL 2 +#define LED_ASSERTION 2 +#define LED_PANIC 1 + +/* Buttons + * + * B1 USER: the user button is connected to the I/O PC13 (pin 2) of the STM32 + * microcontroller. + */ + +#define BUTTON_USER 0 +#define NUM_BUTTONS 1 + +#define BUTTON_USER_BIT (1 << BUTTON_USER) + +/* Quadrature encoder + * Default is to use timer 5 (32-bit) and encoder on PA0/PA1 + */ + +#define GPIO_TIM2_CH1IN GPIO_TIM2_CH1IN_1 +#define GPIO_TIM2_CH2IN GPIO_TIM2_CH2IN_1 + +#define GPIO_TIM3_CH1IN GPIO_TIM3_CH1IN_3 +#define GPIO_TIM3_CH2IN GPIO_TIM3_CH2IN_3 + +#define GPIO_TIM5_CH1IN GPIO_TIM5_CH1IN_1 +#define GPIO_TIM5_CH2IN GPIO_TIM5_CH2IN_1 + +/* PWM output for full bridge, uses config 1, because port E is N/A on QFP64 + * CH1 | 1(A8) 2(E9) + * CH2 | 1(A9) 2(E11) + * CHN1 | 1(A7) 2(B13) 3(E8) + * CHN2 | 1(B0) 2(B14) 3(E10) + */ + +#define GPIO_TIM1_CH1OUT GPIO_TIM1_CH1OUT_1 +#define GPIO_TIM1_CH1NOUT GPIO_TIM1_CH1N_1 +#define GPIO_TIM1_CH2OUT GPIO_TIM1_CH2OUT_1 +#define GPIO_TIM1_CH2NOUT GPIO_TIM1_CH2N_1 + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ +/************************************************************************************ + * Name: stm32l4_boardinitialize + * + * Description: + * All STM32L4 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +void stm32l4_boardinitialize(void); + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __CONFIGS_NUCLEO_F476RG_INCLUDE_BOARD_H */ diff --git a/configs/nucleo-l432kc/include/nucleo-l432kc.h b/configs/nucleo-l432kc/include/nucleo-l432kc.h new file mode 100644 index 0000000000..eed8f15d26 --- /dev/null +++ b/configs/nucleo-l432kc/include/nucleo-l432kc.h @@ -0,0 +1,510 @@ +/************************************************************************************ + * configs/nucleo-l432kc/include/nucleo-l432kc.h + * + * Copyright (C) 2016 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. + * + ************************************************************************************/ + +#ifndef __CONFIGS_NUCLEO_L432KC_INCLUDE_NUCLEO_L432KC_H +#define __CONFIGS_NUCLEO_L432KC_INCLUDE_NUCLEO_L432KC_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#ifndef __ASSEMBLY__ +# include +#endif + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +#if 1 +# define HSI_CLOCK_CONFIG /* HSI-16 clock configuration */ +#elif 0 +/* Make sure you installed one! */ + +# define HSE_CLOCK_CONFIG /* HSE with 8 MHz xtal */ +#else +# define MSI_CLOCK_CONFIG /* MSI @ 4 MHz autotrimmed via LSE */ +#endif + +/* Clocking *************************************************************************/ + +#if defined(HSI_CLOCK_CONFIG) +/* The NUCLEOL432KC supports both HSE and LSE crystals (X2 and X3). However, as + * shipped, the X3 crystal is not populated. Therefore the Nucleo-L432KC + * will need to run off the 16MHz HSI clock, or the 32khz-synced MSI. + * + * System Clock source : PLL (HSI) + * SYSCLK(Hz) : 80000000 Determined by PLL configuration + * HCLK(Hz) : 80000000 (STM32L4_RCC_CFGR_HPRE) (Max 80 MHz) + * AHB Prescaler : 1 (STM32L4_RCC_CFGR_HPRE) (Max 80 MHz) + * APB1 Prescaler : 1 (STM32L4_RCC_CFGR_PPRE1) (Max 80 MHz) + * APB2 Prescaler : 1 (STM32L4_RCC_CFGR_PPRE2) (Max 80 MHz) + * HSI Frequency(Hz) : 16000000 (nominal) + * PLLM : 1 (STM32L4_PLLCFG_PLLM) + * PLLN : 10 (STM32L4_PLLCFG_PLLN) + * PLLP : 0 (STM32L4_PLLCFG_PLLP) + * PLLQ : 0 (STM32L4_PLLCFG_PLLQ) + * PLLR : 2 (STM32L4_PLLCFG_PLLR) + * PLLSAI1N : 12 + * PLLSAI1Q : 4 + * Flash Latency(WS) : 4 + * Prefetch Buffer : OFF + * 48MHz for USB OTG FS, : Doable if required using PLLSAI1 or MSI + * SDIO and RNG clock + */ + +/* HSI - 16 MHz RC factory-trimmed + * LSI - 32 KHz RC + * MSI - variable up to 48 MHz, synchronized to LSE + * HSE - not installed + * LSE - 32.768 kHz installed + */ + +#define STM32L4_HSI_FREQUENCY 16000000ul +#define STM32L4_LSI_FREQUENCY 32000 +#define STM32L4_LSE_FREQUENCY 32768 + +#define STM32L4_BOARD_USEHSI 1 + +/* XXX sysclk mux = pllclk */ + +/* XXX pll source mux = hsi */ + +/* REVISIT: Trimming of the HSI and MSI is not yet supported. */ + +/* Main PLL Configuration. + * + * Formulae: + * + * VCO input frequency = PLL input clock frequency / PLLM, 1 <= PLLM <= 8 + * VCO output frequency = VCO input frequency × PLLN, 8 <= PLLN <= 86, frequency range 64 to 344 MHz + * PLL output P (SAI3) clock frequency = VCO frequency / PLLP, PLLP = 7, or 17, or 0 to disable + * PLL output Q (48M1) clock frequency = VCO frequency / PLLQ, PLLQ = 2, 4, 6, or 8, or 0 to disable + * PLL output R (CLK) clock frequency = VCO frequency / PLLR, PLLR = 2, 4, 6, or 8, or 0 to disable + * + * PLL output P is used for SAI + * PLL output Q is used for OTG FS, SDMMC, RNG + * PLL output R is used for SYSCLK + * PLLP = 0 (not used) + * PLLQ = 0 (not used) + * PLLR = 2 + * PLLN = 10 + * PLLM = 1 + * + * We will configure like this + * + * PLL source is HSI + * + * PLL_REF = STM32L4_HSI_FREQUENCY / PLLM + * = 16,000,000 / 1 + * = 16,000,000 + * + * PLL_VCO = PLL_REF * PLLN + * = 16,000,000 * 10 + * = 160,000,000 + * + * PLL_CLK = PLL_VCO / PLLR + * = 160,000,000 / 2 = 80,000,000 + * PLL_48M1 = disabled + * PLL_SAI3 = disabled + * + * ---------------------------------------- + * + * PLLSAI1 Configuration + * + * The clock input and M divider are identical to the main PLL. + * However the multiplier and postscalers are independent. + * The PLLSAI1 is configured only if CONFIG_STM32L4_SAI1PLL is defined + * + * SAI1VCO input frequency = PLL input clock frequency + * SAI1VCO output frequency = SAI1VCO input frequency × PLLSAI1N, 8 <= PLLSAI1N <= 86, frequency range 64 to 344 MHz + * SAI1PLL output P (SAI1) clock frequency = SAI1VCO frequency / PLLSAI1P, PLLP = 7, or 17, or 0 to disable + * SAI1PLL output Q (48M2) clock frequency = SAI1VCO frequency / PLLSAI1Q, PLLQ = 2, 4, 6, or 8, or 0 to disable + * SAI1PLL output R (ADC1) clock frequency = SAI1VCO frequency / PLLSAI1R, PLLR = 2, 4, 6, or 8, or 0 to disable + * + * We will configure like this + * + * PLLSAI1 disabled + * + * ---------------------------------------- + * + * PLLSAI2 Configuration + * + * The clock input and M divider are identical to the main PLL. + * However the multiplier and postscalers are independent. + * The PLLSAI2 is configured only if CONFIG_STM32L4_SAI2PLL is defined + * + * SAI2VCO input frequency = PLL input clock frequency + * SAI2VCO output frequency = SAI2VCO input frequency × PLLSAI2N, 8 <= PLLSAI1N <= 86, frequency range 64 to 344 MHz + * SAI2PLL output P (SAI2) clock frequency = SAI2VCO frequency / PLLSAI2P, PLLP = 7, or 17, or 0 to disable + * SAI2PLL output R (ADC2) clock frequency = SAI2VCO frequency / PLLSAI2R, PLLR = 2, 4, 6, or 8, or 0 to disable + * + * We will configure like this + * + * PLLSAI2 disabled + * + * ---------------------------------------- + * + * TODO: The STM32L is a low power peripheral and all these clocks should be configurable at runtime. + * + * ---------------------------------------- + * + * TODO These clock sources can be configured in Kconfig (this is not a board feature) + * USART1 + * USART2 + * USART3 + * UART4 + * UART5 + * LPUART1 + * I2C1 + * I2C2 + * I2C3 + * LPTIM1 + * LPTIM2 + * SAI1 + * SAI2 + * CLK48 + * ADC + * SWPMI + * DFSDM + */ + +/* prescaler common to all PLL inputs; will be 1 (XXX source is implicitly + as per comment above HSI) */ + +#define STM32L4_PLLCFG_PLLM RCC_PLLCFG_PLLM(1) + +/* 'main' PLL config; we use this to generate our system clock via the R + * output. We set it up as 16 MHz / 1 * 10 / 2 = 80 MHz + * + * XXX NOTE: currently the main PLL is implicitly turned on and is implicitly + * the system clock; this should be configurable since not all applications may + * want things done this way. + */ + +#define STM32L4_PLLCFG_PLLN RCC_PLLCFG_PLLN(10) +#define STM32L4_PLLCFG_PLLP 0 +#undef STM32L4_PLLCFG_PLLP_ENABLED +#define STM32L4_PLLCFG_PLLQ RCC_PLLCFG_PLLQ_2 +#define STM32L4_PLLCFG_PLLQ_ENABLED +#define STM32L4_PLLCFG_PLLR RCC_PLLCFG_PLLR(2) +#define STM32L4_PLLCFG_PLLR_ENABLED + +/* 'SAIPLL1' is used to generate the 48 MHz clock, since we can't + * do that with the main PLL's N value. We set N = 12, and enable + * the Q output (ultimately for CLK48) with /4. So, + * 16 MHz / 1 * 12 / 4 = 48 MHz + * + * XXX NOTE: currently the SAIPLL /must/ be explicitly selected in the + * menuconfig, or else all this is a moot point, and the various 48 MHz + * peripherals will not work (RNG at present). I would suggest removing + * that option from Kconfig altogether, and simply making it an option + * that is selected via a #define here, like all these other params. + */ + +#define STM32L4_PLLSAI1CFG_PLLN RCC_PLLSAI1CFG_PLLN(12) +#define STM32L4_PLLSAI1CFG_PLLP 0 +#undef STM32L4_PLLSAI1CFG_PLLP_ENABLED +#define STM32L4_PLLSAI1CFG_PLLQ RCC_PLLSAI1CFG_PLLQ_4 +#define STM32L4_PLLSAI1CFG_PLLQ_ENABLED +#define STM32L4_PLLSAI1CFG_PLLR 0 +#undef STM32L4_PLLSAI1CFG_PLLR_ENABLED + +/* 'SAIPLL2' is not used in this application */ + +#define STM32L4_PLLSAI2CFG_PLLN RCC_PLLSAI2CFG_PLLN(8) +#define STM32L4_PLLSAI2CFG_PLLP 0 +#undef STM32L4_PLLSAI2CFG_PLLP_ENABLED +#define STM32L4_PLLSAI2CFG_PLLR 0 +#undef STM32L4_PLLSAI2CFG_PLLR_ENABLED + +#define STM32L4_SYSCLK_FREQUENCY 80000000ul + +/* CLK48 will come from PLLSAI1 (implicitly Q) */ + +#define STM32L4_USE_CLK48 +#define STM32L4_CLK48_SEL RCC_CCIPR_CLK48SEL_PLLSAI1 + +/* enable the LSE oscillator, used automatically trim the MSI, and for RTC */ + +#define STM32L4_USE_LSE 1 + +/* AHB clock (HCLK) is SYSCLK (80MHz) */ + +#define STM32L4_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */ +#define STM32L4_HCLK_FREQUENCY STM32L4_SYSCLK_FREQUENCY +#define STM32L4_BOARD_HCLK STM32L4_HCLK_FREQUENCY /* Same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/1 (80MHz) */ + +#define STM32L4_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLK /* PCLK1 = HCLK / 1 */ +#define STM32L4_PCLK1_FREQUENCY (STM32L4_HCLK_FREQUENCY/1) + +/* Timers driven from APB1 will be twice PCLK1 */ +/* REVISIT : this can be configured */ + +#define STM32L4_APB1_TIM2_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM3_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM4_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM5_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM6_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM7_CLKIN (2*STM32L4_PCLK1_FREQUENCY) + +/* APB2 clock (PCLK2) is HCLK (80MHz) */ + +#define STM32L4_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK /* PCLK2 = HCLK / 1 */ +#define STM32L4_PCLK2_FREQUENCY (STM32L4_HCLK_FREQUENCY/1) + +/* Timers driven from APB2 will be twice PCLK2 */ +/* REVISIT : this can be configured */ + +#define STM32L4_APB2_TIM1_CLKIN (2*STM32L4_PCLK2_FREQUENCY) +#define STM32L4_APB2_TIM8_CLKIN (2*STM32L4_PCLK2_FREQUENCY) + +/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx + * otherwise frequency is 2xAPBx. + * Note: TIM1,8 are on APB2, others on APB1 + */ +/* REVISIT : this can be configured */ + +/* TODO SDMMC */ + +#elif defined(HSE_CLOCK_CONFIG) + +/* Use the HSE */ + +#define STM32L4_BOARD_USEHSE 1 + +/* XXX sysclk mux = pllclk */ + +/* XXX pll source mux = hse */ + +/* Prescaler common to all PLL inputs */ + +#define STM32L4_PLLCFG_PLLM RCC_PLLCFG_PLLM(1) + +/* 'main' PLL config; we use this to generate our system clock */ + +#define STM32L4_PLLCFG_PLLN RCC_PLLCFG_PLLN(20) +#define STM32L4_PLLCFG_PLLP 0 +#undef STM32L4_PLLCFG_PLLP_ENABLED +#define STM32L4_PLLCFG_PLLQ 0 +#undef STM32L4_PLLCFG_PLLQ_ENABLED +#define STM32L4_PLLCFG_PLLR RCC_PLLCFG_PLLR_2 +#define STM32L4_PLLCFG_PLLR_ENABLED + +/* 'SAIPLL1' is used to generate the 48 MHz clock */ + +#define STM32L4_PLLSAI1CFG_PLLN RCC_PLLSAI1CFG_PLLN(12) +#define STM32L4_PLLSAI1CFG_PLLP 0 +#undef STM32L4_PLLSAI1CFG_PLLP_ENABLED +#define STM32L4_PLLSAI1CFG_PLLQ RCC_PLLSAI1CFG_PLLQ_2 +#define STM32L4_PLLSAI1CFG_PLLQ_ENABLED +#define STM32L4_PLLSAI1CFG_PLLR 0 +#undef STM32L4_PLLSAI1CFG_PLLR_ENABLED + +/* 'SAIPLL2' is not used in this application */ + +#define STM32L4_PLLSAI2CFG_PLLN RCC_PLLSAI2CFG_PLLN(8) +#define STM32L4_PLLSAI2CFG_PLLP 0 +#undef STM32L4_PLLSAI2CFG_PLLP_ENABLED +#define STM32L4_PLLSAI2CFG_PLLR 0 +#undef STM32L4_PLLSAI2CFG_PLLR_ENABLED + +#define STM32L4_SYSCLK_FREQUENCY 80000000ul + +/* Enable CLK48; get it from PLLSAI1 */ + +#define STM32L4_USE_CLK48 +#define STM32L4_CLK48_SEL RCC_CCIPR_CLK48SEL_PLLSAI1 + +/* Enable LSE (for the RTC) */ + +#define STM32L4_USE_LSE 1 + +/* Configure the HCLK divisor (for the AHB bus, core, memory, and DMA */ + +#define STM32L4_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */ +#define STM32L4_HCLK_FREQUENCY STM32L4_SYSCLK_FREQUENCY +#define STM32L4_BOARD_HCLK STM32L4_HCLK_FREQUENCY /* Same as above, to satisfy compiler */ + +/* Configure the APB1 prescaler */ + +#define STM32L4_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLK /* PCLK1 = HCLK / 1 */ +#define STM32L4_PCLK1_FREQUENCY (STM32L4_HCLK_FREQUENCY/1) + +#define STM32L4_APB1_TIM2_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM3_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM4_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM5_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM6_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM7_CLKIN (2*STM32L4_PCLK1_FREQUENCY) + +/* Configure the APB2 prescaler */ + +#define STM32L4_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK /* PCLK2 = HCLK / 1 */ +#define STM32L4_PCLK2_FREQUENCY (STM32L4_HCLK_FREQUENCY/1) + +#define STM32L4_APB2_TIM1_CLKIN (2*STM32L4_PCLK2_FREQUENCY) +#define STM32L4_APB2_TIM8_CLKIN (2*STM32L4_PCLK2_FREQUENCY) + +#elif defined(MSI_CLOCK_CONFIG) + +/* Use the MSI; frequ = 4 MHz; autotrim from LSE */ + +#define STM32L4_BOARD_USEMSI 1 +#define STM32L4_BOARD_MSIRANGE RCC_CR_MSIRANGE_4M + +/* XXX sysclk mux = pllclk */ + +/* XXX pll source mux = msi */ + +/* prescaler common to all PLL inputs */ + +#define STM32L4_PLLCFG_PLLM RCC_PLLCFG_PLLM(1) + +/* 'main' PLL config; we use this to generate our system clock */ + +#define STM32L4_PLLCFG_PLLN RCC_PLLCFG_PLLN(40) +#define STM32L4_PLLCFG_PLLP 0 +#undef STM32L4_PLLCFG_PLLP_ENABLED +#define STM32L4_PLLCFG_PLLQ 0 +#undef STM32L4_PLLCFG_PLLQ_ENABLED +#define STM32L4_PLLCFG_PLLR RCC_PLLCFG_PLLR_2 +#define STM32L4_PLLCFG_PLLR_ENABLED + +/* 'SAIPLL1' is used to generate the 48 MHz clock */ + +#define STM32L4_PLLSAI1CFG_PLLN RCC_PLLSAI1CFG_PLLN(24) +#define STM32L4_PLLSAI1CFG_PLLP 0 +#undef STM32L4_PLLSAI1CFG_PLLP_ENABLED +#define STM32L4_PLLSAI1CFG_PLLQ RCC_PLLSAI1CFG_PLLQ_2 +#define STM32L4_PLLSAI1CFG_PLLQ_ENABLED +#define STM32L4_PLLSAI1CFG_PLLR 0 +#undef STM32L4_PLLSAI1CFG_PLLR_ENABLED + +/* 'SAIPLL2' is not used in this application */ + +#define STM32L4_PLLSAI2CFG_PLLN RCC_PLLSAI2CFG_PLLN(8) +#define STM32L4_PLLSAI2CFG_PLLP 0 +#undef STM32L4_PLLSAI2CFG_PLLP_ENABLED +#define STM32L4_PLLSAI2CFG_PLLR 0 +#undef STM32L4_PLLSAI2CFG_PLLR_ENABLED + +#define STM32L4_SYSCLK_FREQUENCY 80000000ul + +/* Enable CLK48; get it from PLLSAI1 */ + +#define STM32L4_USE_CLK48 +#define STM32L4_CLK48_SEL RCC_CCIPR_CLK48SEL_PLLSAI1 + +/* Enable LSE (for the RTC) */ + +#define STM32L4_USE_LSE 1 + +/* Configure the HCLK divisor (for the AHB bus, core, memory, and DMA */ + +#define STM32L4_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */ +#define STM32L4_HCLK_FREQUENCY STM32L4_SYSCLK_FREQUENCY +#define STM32L4_BOARD_HCLK STM32L4_HCLK_FREQUENCY /* Same as above, to satisfy compiler */ + +/* Configure the APB1 prescaler */ + +#define STM32L4_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLK /* PCLK1 = HCLK / 1 */ +#define STM32L4_PCLK1_FREQUENCY (STM32L4_HCLK_FREQUENCY/1) + +#define STM32L4_APB1_TIM2_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM3_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM4_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM5_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM6_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM7_CLKIN (2*STM32L4_PCLK1_FREQUENCY) + +/* Configure the APB2 prescaler */ + +#define STM32L4_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK /* PCLK2 = HCLK / 1 */ +#define STM32L4_PCLK2_FREQUENCY (STM32L4_HCLK_FREQUENCY/1) + +#define STM32L4_APB2_TIM1_CLKIN (2*STM32L4_PCLK2_FREQUENCY) +#define STM32L4_APB2_TIM8_CLKIN (2*STM32L4_PCLK2_FREQUENCY) + +#endif + +/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx + * otherwise frequency is 2xAPBx. + * Note: TIM1,8,15,16,17 are on APB2, others on APB1 + */ + +#define BOARD_TIM1_FREQUENCY STM32L4_HCLK_FREQUENCY +#define BOARD_TIM2_FREQUENCY (STM32L4_HCLK_FREQUENCY / 2) +#define BOARD_TIM3_FREQUENCY (STM32L4_HCLK_FREQUENCY / 2) +#define BOARD_TIM4_FREQUENCY (STM32L4_HCLK_FREQUENCY / 2) +#define BOARD_TIM5_FREQUENCY (STM32L4_HCLK_FREQUENCY / 2) +#define BOARD_TIM6_FREQUENCY (STM32L4_HCLK_FREQUENCY / 2) +#define BOARD_TIM7_FREQUENCY (STM32L4_HCLK_FREQUENCY / 2) +#define BOARD_TIM8_FREQUENCY STM32L4_HCLK_FREQUENCY +#define BOARD_TIM15_FREQUENCY STM32L4_HCLK_FREQUENCY +#define BOARD_TIM16_FREQUENCY STM32L4_HCLK_FREQUENCY +#define BOARD_TIM17_FREQUENCY STM32L4_HCLK_FREQUENCY +#define BOARD_LPTIM1_FREQUENCY (STM32L4_HCLK_FREQUENCY / 2) +#define BOARD_LPTIM2_FREQUENCY (STM32L4_HCLK_FREQUENCY / 2) + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __CONFIGS_NUCLEO_L432KC_INCLUDE_NUCLEO_L432KC_H */ diff --git a/configs/nucleo-l432kc/nsh/Make.defs b/configs/nucleo-l432kc/nsh/Make.defs new file mode 100644 index 0000000000..8276975feb --- /dev/null +++ b/configs/nucleo-l432kc/nsh/Make.defs @@ -0,0 +1,112 @@ +############################################################################ +# configs/nucleo-l432kc/nsh/Make.defs +# +# Copyright (C) 2014 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. +# +############################################################################ + +include ${TOPDIR}/.config +include ${TOPDIR}/tools/Config.mk +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs + +LDSCRIPT = l432kc.ld + +ifeq ($(WINTOOL),y) + # Windows-native toolchains + DIRLINK = $(TOPDIR)/tools/copydir.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh + ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" + ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" +else + # Linux/Cygwin-native toolchain + MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT) + ARCHINCLUDES = -I. -isystem $(TOPDIR)/include + ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) +endif + +CC = $(CROSSDEV)gcc +CXX = $(CROSSDEV)g++ +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(ARCROSSDEV)ar rcs +NM = $(ARCROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump + +ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} +ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} + +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + ARCHOPTIMIZATION = -g +endif + +ifneq ($(CONFIG_DEBUG_NOOPT),y) + ARCHOPTIMIZATION += $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer +endif + +ARCHCFLAGS = -fno-builtin +ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fcheck-new -fno-rtti +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow -Wundef +ARCHWARNINGSXX = -Wall -Wshadow -Wundef +ARCHDEFINES = +ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 + +CFLAGS = $(ARCHCFLAGS) $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) +CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +NXFLATLDFLAGS1 = -r -d -warn-common +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections +LDNXFLATFLAGS = -e main -s 2048 + +ASMEXT = .S +OBJEXT = .o +LIBEXT = .a +EXEEXT = + +ifneq ($(CROSSDEV),arm-nuttx-elf-) + LDFLAGS += -nostartfiles -nodefaultlibs +endif +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + LDFLAGS += -g +endif + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -Wundef -g -pipe +HOSTLDFLAGS = + diff --git a/configs/nucleo-l432kc/nsh/defconfig b/configs/nucleo-l432kc/nsh/defconfig new file mode 100644 index 0000000000..f78446519f --- /dev/null +++ b/configs/nucleo-l432kc/nsh/defconfig @@ -0,0 +1,1102 @@ +# +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# + +# +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set +# CONFIG_DEFAULT_SMALL is not set +CONFIG_HOST_LINUX=y +# CONFIG_HOST_OSX is not set +# CONFIG_HOST_WINDOWS is not set +# CONFIG_HOST_OTHER is not set + +# +# Build Configuration +# +# CONFIG_APPS_DIR="../apps" +CONFIG_BUILD_FLAT=y +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +CONFIG_INTELHEX_BINARY=y +# CONFIG_MOTOROLA_SREC is not set +CONFIG_RAW_BINARY=y +# CONFIG_UBOOT_UIMAGE is not set + +# +# Customize Header Files +# +# CONFIG_ARCH_STDINT_H is not set +# CONFIG_ARCH_STDBOOL_H is not set +# CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_FLOAT_H is not set +# CONFIG_ARCH_STDARG_H is not set +# CONFIG_ARCH_DEBUG_H is not set + +# +# Debug Options +# +CONFIG_DEBUG_ALERT=y +# CONFIG_DEBUG_FEATURES is not set +CONFIG_ARCH_HAVE_STACKCHECK=y +# CONFIG_STACK_COLORATION is not set +CONFIG_ARCH_HAVE_HEAPCHECK=y +# CONFIG_HEAP_COLORATION is not set +CONFIG_DEBUG_SYMBOLS=y +CONFIG_ARCH_HAVE_CUSTOMOPT=y +CONFIG_DEBUG_NOOPT=y +# CONFIG_DEBUG_CUSTOMOPT is not set +# CONFIG_DEBUG_FULLOPT is not set + +# +# System Type +# +CONFIG_ARCH_ARM=y +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_MISOC is not set +# CONFIG_ARCH_RENESAS is not set +# CONFIG_ARCH_RISCV is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_XTENSA is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="arm" + +# +# ARM Options +# +# CONFIG_ARCH_CHIP_A1X is not set +# CONFIG_ARCH_CHIP_C5471 is not set +# CONFIG_ARCH_CHIP_DM320 is not set +# CONFIG_ARCH_CHIP_EFM32 is not set +# CONFIG_ARCH_CHIP_IMX1 is not set +# CONFIG_ARCH_CHIP_IMX6 is not set +# CONFIG_ARCH_CHIP_KINETIS is not set +# CONFIG_ARCH_CHIP_KL is not set +# CONFIG_ARCH_CHIP_LM is not set +# CONFIG_ARCH_CHIP_TIVA is not set +# CONFIG_ARCH_CHIP_LPC11XX is not set +# CONFIG_ARCH_CHIP_LPC17XX is not set +# CONFIG_ARCH_CHIP_LPC214X is not set +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_NUC1XX is not set +# CONFIG_ARCH_CHIP_SAMA5 is not set +# CONFIG_ARCH_CHIP_SAMD is not set +# CONFIG_ARCH_CHIP_SAML is not set +# CONFIG_ARCH_CHIP_SAM34 is not set +# CONFIG_ARCH_CHIP_SAMV7 is not set +# CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F7 is not set +CONFIG_ARCH_CHIP_STM32L4=y +# CONFIG_ARCH_CHIP_STR71X is not set +# CONFIG_ARCH_CHIP_TMS570 is not set +# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_ARM7TDMI is not set +# CONFIG_ARCH_ARM926EJS is not set +# CONFIG_ARCH_ARM920T is not set +# CONFIG_ARCH_CORTEXM0 is not set +# CONFIG_ARCH_CORTEXM23 is not set +# CONFIG_ARCH_CORTEXM3 is not set +# CONFIG_ARCH_CORTEXM33 is not set +CONFIG_ARCH_CORTEXM4=y +# CONFIG_ARCH_CORTEXM7 is not set +# CONFIG_ARCH_CORTEXA5 is not set +# CONFIG_ARCH_CORTEXA8 is not set +# CONFIG_ARCH_CORTEXA9 is not set +# CONFIG_ARCH_CORTEXR4 is not set +# CONFIG_ARCH_CORTEXR4F is not set +# CONFIG_ARCH_CORTEXR5 is not set +# CONFIG_ARCH_CORTEX5F is not set +# CONFIG_ARCH_CORTEXR7 is not set +# CONFIG_ARCH_CORTEXR7F is not set +CONFIG_ARCH_FAMILY="armv7-m" +CONFIG_ARCH_CHIP="stm32l4" +# CONFIG_ARM_TOOLCHAIN_IAR is not set +CONFIG_ARM_TOOLCHAIN_GNU=y +# CONFIG_ARMV7M_USEBASEPRI is not set +CONFIG_ARCH_HAVE_CMNVECTOR=y +CONFIG_ARMV7M_CMNVECTOR=y +# CONFIG_ARMV7M_LAZYFPU is not set +CONFIG_ARCH_HAVE_FPU=y +CONFIG_ARCH_HAVE_DPFPU=y +# CONFIG_ARCH_FPU is not set +# CONFIG_ARCH_HAVE_TRUSTZONE is not set +CONFIG_ARM_HAVE_MPU_UNIFIED=y +# CONFIG_ARM_MPU is not set + +# +# ARMV7M Configuration Options +# +# CONFIG_ARMV7M_HAVE_ICACHE is not set +# CONFIG_ARMV7M_HAVE_DCACHE is not set +CONFIG_ARMV7M_HAVE_ITCM=y +CONFIG_ARMV7M_HAVE_DTCM=y +# CONFIG_ARMV7M_ITCM is not set +# CONFIG_ARMV7M_DTCM is not set +# CONFIG_ARMV7M_TOOLCHAIN_IARL is not set +# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set +# CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set +CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL=y +# CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL is not set +CONFIG_ARMV7M_HAVE_STACKCHECK=y +# CONFIG_ARMV7M_STACKCHECK is not set +# CONFIG_ARMV7M_ITMSYSLOG is not set +# CONFIG_SERIAL_TERMIOS is not set +# CONFIG_USART2_RS485 is not set +# CONFIG_USART2_RXDMA is not set +# CONFIG_SERIAL_DISABLE_REORDERING is not set + +# +# STM32L4 Configuration Options +# +CONFIG_ARCH_CHIP_STM32L476RG=y +# CONFIG_ARCH_CHIP_STM32L476RE is not set +# CONFIG_ARCH_CHIP_STM32L486 is not set +# CONFIG_STM32L4_STM32L4X3 is not set +CONFIG_STM32L4_STM32L4X6=y +CONFIG_STM32L4_STM32L476XX=y +# CONFIG_STM32L4_STM32L486XX is not set +# CONFIG_STM32L4_FLASH_256KB is not set +# CONFIG_STM32L4_FLASH_512KB is not set +CONFIG_STM32L4_FLASH_1024KB=y + +# +# STM32L4 SRAM2 Options +# +CONFIG_STM32L4_SRAM2_HEAP=y +CONFIG_STM32L4_SRAM2_INIT=y + +# +# STM32L4 Peripherals +# + +# +# STM32L4 Peripheral Support +# +# CONFIG_STM32L4_HAVE_LTDC is not set +CONFIG_STM32L4_HAVE_LPTIM1=y +CONFIG_STM32L4_HAVE_LPTIM2=y +CONFIG_STM32L4_HAVE_COMP=y +CONFIG_STM32L4_HAVE_SAI1=y +CONFIG_STM32L4_HAVE_SAI2=y +# CONFIG_STM32L4_ADC is not set +# CONFIG_STM32L4_CAN is not set +# CONFIG_STM32L4_DAC is not set +CONFIG_STM32L4_DMA=y +# CONFIG_STM32L4_I2C is not set +# CONFIG_STM32L4_SAI is not set +# CONFIG_STM32L4_SPI is not set +CONFIG_STM32L4_USART=y +# CONFIG_STM32L4_LPTIM is not set + +# +# AHB1 Peripherals +# +CONFIG_STM32L4_DMA1=y +CONFIG_STM32L4_DMA2=y +# CONFIG_STM32L4_CRC is not set +# CONFIG_STM32L4_TSC is not set + +# +# AHB2 Peripherals +# +# CONFIG_STM32L4_OTGFS is not set +# CONFIG_STM32L4_ADC1 is not set +# CONFIG_STM32L4_ADC2 is not set +# CONFIG_STM32L4_ADC3 is not set +# CONFIG_STM32L4_AES is not set +CONFIG_STM32L4_RNG=y +# CONFIG_STM32L4_SAI1_A is not set +# CONFIG_STM32L4_SAI1_B is not set +# CONFIG_STM32L4_SAI2_A is not set +# CONFIG_STM32L4_SAI2_B is not set + +# +# AHB3 Peripherals +# +# CONFIG_STM32L4_FMC is not set +# CONFIG_STM32L4_QSPI is not set + +# +# APB1 Peripherals +# +CONFIG_STM32L4_PWR=y +# CONFIG_STM32L4_TIM2 is not set +# CONFIG_STM32L4_TIM3 is not set +# CONFIG_STM32L4_TIM4 is not set +# CONFIG_STM32L4_TIM5 is not set +# CONFIG_STM32L4_TIM6 is not set +# CONFIG_STM32L4_TIM7 is not set +# CONFIG_STM32L4_LCD is not set +# CONFIG_STM32L4_SPI2 is not set +# CONFIG_STM32L4_SPI3 is not set +# CONFIG_STM32L4_USART1 is not set +CONFIG_STM32L4_USART2=y +# CONFIG_STM32L4_USART3 is not set +# CONFIG_STM32L4_UART4 is not set +# CONFIG_STM32L4_UART5 is not set +# CONFIG_STM32L4_I2C1 is not set +# CONFIG_STM32L4_I2C2 is not set +# CONFIG_STM32L4_I2C3 is not set +# CONFIG_STM32L4_CAN1 is not set +# CONFIG_STM32L4_DAC1 is not set +# CONFIG_STM32L4_DAC2 is not set +# CONFIG_STM32L4_OPAMP is not set +# CONFIG_STM32L4_LPTIM1 is not set +# CONFIG_STM32L4_LPUART1 is not set +# CONFIG_STM32L4_SWPMI is not set +# CONFIG_STM32L4_LPTIM2 is not set + +# +# APB2 Peripherals +# +CONFIG_STM32L4_SYSCFG=y +CONFIG_STM32L4_FIREWALL=y +# CONFIG_STM32L4_SDMMC1 is not set +# CONFIG_STM32L4_TIM1 is not set +# CONFIG_STM32L4_SPI1 is not set +# CONFIG_STM32L4_TIM8 is not set +# CONFIG_STM32L4_TIM15 is not set +# CONFIG_STM32L4_TIM16 is not set +# CONFIG_STM32L4_TIM17 is not set +# CONFIG_STM32L4_COMP is not set +# CONFIG_STM32L4_SAI1 is not set +# CONFIG_STM32L4_SAI2 is not set +# CONFIG_STM32L4_DFSDM is not set + +# +# Other Peripherals +# +# CONFIG_STM32L4_BKPSRAM is not set +# CONFIG_STM32L4_IWDG is not set +# CONFIG_STM32L4_WWDG is not set +CONFIG_STM32L4_FLASH_PREFETCH=y +CONFIG_STM32L4_DISABLE_IDLE_SLEEP_DURING_DEBUG=y +# CONFIG_ARCH_BOARD_STM32L4_CUSTOM_CLOCKCONFIG is not set +CONFIG_STM32L4_RTC_LSECLOCK=y +# CONFIG_STM32L4_RTC_LSICLOCK is not set +# CONFIG_STM32L4_RTC_HSECLOCK is not set +CONFIG_STM32L4_SAI1PLL=y +# CONFIG_STM32L4_SAI2PLL is not set + +# +# Timer Configuration +# +# CONFIG_STM32L4_ONESHOT is not set +# CONFIG_STM32L4_FREERUN is not set +CONFIG_STM32L4_HAVE_USART1=y +CONFIG_STM32L4_HAVE_USART2=y +CONFIG_STM32L4_HAVE_USART3=y +CONFIG_STM32L4_HAVE_UART4=y +CONFIG_STM32L4_HAVE_UART5=y + +# +# U[S]ART Configuration +# +# CONFIG_STM32L4_FLOWCONTROL_BROKEN is not set +# CONFIG_STM32L4_USART_BREAKS is not set + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_VECNOTIRQ is not set +CONFIG_ARCH_DMA=y +CONFIG_ARCH_HAVE_IRQPRIO=y +# CONFIG_ARCH_L2CACHE is not set +# CONFIG_ARCH_HAVE_COHERENT_DCACHE is not set +# CONFIG_ARCH_HAVE_ADDRENV is not set +# CONFIG_ARCH_NEED_ADDRENV_MAPPING is not set +# CONFIG_ARCH_HAVE_MULTICPU is not set +CONFIG_ARCH_HAVE_VFORK=y +# CONFIG_ARCH_HAVE_MMU is not set +CONFIG_ARCH_HAVE_MPU=y +# CONFIG_ARCH_NAND_HWECC is not set +# CONFIG_ARCH_HAVE_EXTCLK is not set +# CONFIG_ARCH_HAVE_POWEROFF is not set +CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_USE_MPU is not set +# CONFIG_ARCH_IRQPRIO is not set +CONFIG_ARCH_STACKDUMP=y +# CONFIG_ENDIAN_BIG is not set +# CONFIG_ARCH_IDLE_CUSTOM is not set +# CONFIG_ARCH_HAVE_RAMFUNCS is not set +CONFIG_ARCH_HAVE_RAMVECTORS=y +# CONFIG_ARCH_RAMVECTORS is not set +# CONFIG_ARCH_MINIMAL_VECTORTABLE is not set + +# +# Board Settings +# +CONFIG_BOARD_LOOPSPERMSEC=8499 +# CONFIG_ARCH_CALIBRATION is not set + +# +# Interrupt options +# +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y +CONFIG_ARCH_INTERRUPTSTACK=2048 +CONFIG_ARCH_HAVE_HIPRI_INTERRUPT=y +# CONFIG_ARCH_HIPRI_INTERRUPT is not set + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Boot Memory Configuration +# +CONFIG_RAM_START=0x20000000 +CONFIG_RAM_SIZE=98304 +# CONFIG_ARCH_HAVE_SDRAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_NUCLEO_L476RG=y +# CONFIG_ARCH_BOARD_STM32L476VG_DISCO is not set +# CONFIG_ARCH_BOARD_STM32L476_MDK is not set +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="nucleo-l476rg" + +# +# Common Board Options +# +CONFIG_ARCH_HAVE_LEDS=y +CONFIG_ARCH_LEDS=y +CONFIG_ARCH_HAVE_BUTTONS=y +# CONFIG_ARCH_BUTTONS is not set +CONFIG_ARCH_HAVE_IRQBUTTONS=y + +# +# Board-Specific Options +# +# CONFIG_BOARD_CRASHDUMP is not set +CONFIG_LIB_BOARDCTL=y +# CONFIG_BOARDCTL_RESET is not set +# CONFIG_BOARDCTL_UNIQUEID is not set +# CONFIG_BOARDCTL_TSCTEST is not set +# CONFIG_BOARDCTL_GRAPHICS is not set +# CONFIG_BOARDCTL_IOCTL is not set + +# +# RTOS Features +# +CONFIG_DISABLE_OS_API=y +# CONFIG_DISABLE_POSIX_TIMERS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_DISABLE_SIGNALS is not set +# CONFIG_DISABLE_MQUEUE is not set +# CONFIG_DISABLE_ENVIRON is not set + +# +# Clocks and Timers +# +CONFIG_ARCH_HAVE_TICKLESS=y +# CONFIG_SCHED_TICKLESS is not set +CONFIG_USEC_PER_TICK=10000 +# CONFIG_SYSTEM_TIME64 is not set +# CONFIG_CLOCK_MONOTONIC is not set +# CONFIG_ARCH_HAVE_TIMEKEEPING is not set +# CONFIG_JULIAN_TIME is not set +CONFIG_START_YEAR=2017 +CONFIG_START_MONTH=1 +CONFIG_START_DAY=1 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=8 +CONFIG_WDOG_INTRESERVE=1 +CONFIG_PREALLOC_TIMERS=4 + +# +# Tasks and Scheduling +# +# CONFIG_SPINLOCK is not set +# CONFIG_INIT_NONE is not set +CONFIG_INIT_ENTRYPOINT=y +# CONFIG_INIT_FILEPATH is not set +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_RR_INTERVAL=200 +# CONFIG_SCHED_SPORADIC is not set +CONFIG_TASK_NAME_SIZE=0 +CONFIG_MAX_TASKS=16 +# CONFIG_SCHED_HAVE_PARENT is not set +CONFIG_SCHED_WAITPID=y + +# +# Pthread Options +# +# CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_NPTHREAD_KEYS=4 +# CONFIG_PTHREAD_CLEANUP is not set +# CONFIG_CANCELLATION_POINTS is not set + +# +# Performance Monitoring +# +# CONFIG_SCHED_CPULOAD is not set +# CONFIG_SCHED_INSTRUMENTATION is not set + +# +# Files and I/O +# +CONFIG_DEV_CONSOLE=y +# CONFIG_FDCLONE_DISABLE is not set +# CONFIG_FDCLONE_STDIO is not set +CONFIG_SDCLONE_DISABLE=y +CONFIG_NFILE_DESCRIPTORS=8 +CONFIG_NFILE_STREAMS=8 +CONFIG_NAME_MAX=32 +# CONFIG_PRIORITY_INHERITANCE is not set + +# +# RTOS hooks +# +# CONFIG_BOARD_INITIALIZE is not set +# CONFIG_SCHED_STARTHOOK is not set +# CONFIG_SCHED_ATEXIT is not set +# CONFIG_SCHED_ONEXIT is not set + +# +# Signal Numbers +# +CONFIG_SIG_SIGUSR1=1 +CONFIG_SIG_SIGUSR2=2 +CONFIG_SIG_SIGALARM=3 +CONFIG_SIG_SIGCONDTIMEDOUT=16 + +# +# POSIX Message Queue Options +# +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_MQ_MAXMSGSIZE=32 +# CONFIG_MODULE is not set + +# +# Work queue support +# +# CONFIG_SCHED_WORKQUEUE is not set +# CONFIG_SCHED_HPWORK is not set +# CONFIG_SCHED_LPWORK is not set + +# +# Stack and heap information +# +CONFIG_IDLETHREAD_STACKSIZE=1024 +CONFIG_USERMAIN_STACKSIZE=2048 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=2048 +# CONFIG_LIB_SYSCALL is not set + +# +# Device Drivers +# +CONFIG_DISABLE_POLL=y +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +CONFIG_ARCH_HAVE_RNG=y +CONFIG_DEV_RANDOM=y +# CONFIG_DEV_URANDOM is not set +# CONFIG_DEV_LOOP is not set + +# +# Buffering +# +# CONFIG_DRVR_WRITEBUFFER is not set +# CONFIG_DRVR_READAHEAD is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_ARCH_HAVE_PWM_PULSECOUNT is not set +# CONFIG_ARCH_HAVE_PWM_MULTICHAN is not set +# CONFIG_PWM is not set +CONFIG_ARCH_HAVE_I2CRESET=y +# CONFIG_I2C is not set +# CONFIG_ARCH_HAVE_SPI_CRCGENERATION is not set +# CONFIG_ARCH_HAVE_SPI_CS_CONTROL is not set +CONFIG_ARCH_HAVE_SPI_BITORDER=y +CONFIG_SPI=y +# CONFIG_SPI_SLAVE is not set +CONFIG_SPI_EXCHANGE=y +# CONFIG_SPI_CMDDATA is not set +# CONFIG_SPI_CALLBACK is not set +# CONFIG_SPI_HWFEATURES is not set +# CONFIG_SPI_BITORDER is not set +# CONFIG_SPI_CS_DELAY_CONTROL is not set +# CONFIG_SPI_DRIVER is not set +# CONFIG_SPI_BITBANG is not set +# CONFIG_I2S is not set + +# +# Timer Driver Support +# +# CONFIG_TIMER is not set +# CONFIG_ONESHOT is not set +CONFIG_RTC=y +CONFIG_RTC_DATETIME=y +CONFIG_RTC_ALARM=y +CONFIG_RTC_NALARMS=2 +CONFIG_RTC_DRIVER=y +CONFIG_RTC_IOCTL=y +# CONFIG_RTC_EXTERNAL is not set +# CONFIG_WATCHDOG is not set +# CONFIG_ANALOG is not set +# CONFIG_AUDIO_DEVICES is not set +# CONFIG_VIDEO_DEVICES is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set + +# +# IO Expander/GPIO Support +# +# CONFIG_IOEXPANDER is not set +# CONFIG_DEV_GPIO is not set + +# +# LCD Driver Support +# +# CONFIG_LCD is not set +# CONFIG_SLCD is not set + +# +# LED Support +# +# CONFIG_USERLED is not set +# CONFIG_RGBLED is not set +# CONFIG_PCA9635PW is not set +# CONFIG_NCP5623C is not set +# CONFIG_MMCSD is not set +# CONFIG_MODEM is not set +# CONFIG_MTD is not set +# CONFIG_EEPROM is not set +# CONFIG_PIPES is not set +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +CONFIG_SERIAL=y +# CONFIG_DEV_LOWCONSOLE is not set +# CONFIG_SERIAL_REMOVABLE is not set +CONFIG_SERIAL_CONSOLE=y +# CONFIG_16550_UART is not set +# CONFIG_UART_SERIALDRIVER is not set +# CONFIG_UART0_SERIALDRIVER is not set +# CONFIG_UART1_SERIALDRIVER is not set +# CONFIG_UART2_SERIALDRIVER is not set +# CONFIG_UART3_SERIALDRIVER is not set +# CONFIG_UART4_SERIALDRIVER is not set +# CONFIG_UART5_SERIALDRIVER is not set +# CONFIG_UART6_SERIALDRIVER is not set +# CONFIG_UART7_SERIALDRIVER is not set +# CONFIG_UART8_SERIALDRIVER is not set +# CONFIG_SCI0_SERIALDRIVER is not set +# CONFIG_SCI1_SERIALDRIVER is not set +# CONFIG_USART0_SERIALDRIVER is not set +# CONFIG_USART1_SERIALDRIVER is not set +CONFIG_USART2_SERIALDRIVER=y +# CONFIG_USART3_SERIALDRIVER is not set +# CONFIG_USART4_SERIALDRIVER is not set +# CONFIG_USART5_SERIALDRIVER is not set +# CONFIG_USART6_SERIALDRIVER is not set +# CONFIG_USART7_SERIALDRIVER is not set +# CONFIG_USART8_SERIALDRIVER is not set +# CONFIG_OTHER_UART_SERIALDRIVER is not set +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +# CONFIG_SERIAL_IFLOWCONTROL is not set +# CONFIG_SERIAL_OFLOWCONTROL is not set +# CONFIG_SERIAL_DMA is not set +CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y +CONFIG_USART2_SERIAL_CONSOLE=y +# CONFIG_OTHER_SERIAL_CONSOLE is not set +# CONFIG_NO_SERIAL_CONSOLE is not set + +# +# USART2 Configuration +# +CONFIG_USART2_RXBUFSIZE=256 +CONFIG_USART2_TXBUFSIZE=256 +CONFIG_USART2_BAUD=115200 +CONFIG_USART2_BITS=8 +CONFIG_USART2_PARITY=0 +CONFIG_USART2_2STOP=0 +# CONFIG_USART2_IFLOWCONTROL is not set +# CONFIG_USART2_OFLOWCONTROL is not set +# CONFIG_USART2_DMA is not set +# CONFIG_PSEUDOTERM is not set +# CONFIG_USBDEV is not set +# CONFIG_USBHOST is not set +# CONFIG_HAVE_USBTRACE is not set +# CONFIG_DRIVERS_WIRELESS is not set +# CONFIG_DRIVERS_CONTACTLESS is not set + +# +# System Logging +# +# CONFIG_ARCH_SYSLOG is not set +# CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_INTBUFFER is not set +# CONFIG_SYSLOG_TIMESTAMP is not set +CONFIG_SYSLOG_SERIAL_CONSOLE=y +# CONFIG_SYSLOG_CHAR is not set +CONFIG_SYSLOG_CONSOLE=y +# CONFIG_SYSLOG_NONE is not set +# CONFIG_SYSLOG_FILE is not set +# CONFIG_SYSLOG_CHARDEV is not set + +# +# Networking Support +# +# CONFIG_ARCH_HAVE_NET is not set +# CONFIG_ARCH_HAVE_PHY is not set +# CONFIG_NET is not set + +# +# Crypto API +# +# CONFIG_CRYPTO is not set + +# +# File Systems +# + +# +# File system configuration +# +# CONFIG_DISABLE_MOUNTPOINT is not set +# CONFIG_FS_AUTOMOUNTER is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_PSEUDOFS_SOFTLINKS is not set +# CONFIG_FS_READABLE is not set +# CONFIG_FS_WRITABLE is not set +# CONFIG_FS_NAMED_SEMAPHORES is not set +CONFIG_FS_MQUEUE_MPATH="/var/mqueue" +# CONFIG_FS_RAMMAP is not set +# CONFIG_FS_FAT is not set +# CONFIG_FS_NXFFS is not set +# CONFIG_FS_ROMFS is not set +# CONFIG_FS_TMPFS is not set +# CONFIG_FS_SMARTFS is not set +# CONFIG_FS_BINFS is not set +# CONFIG_FS_PROCFS is not set +# CONFIG_FS_UNIONFS is not set + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=2 +# CONFIG_ARCH_HAVE_HEAP2 is not set +# CONFIG_GRAN is not set + +# +# Audio Support +# +# CONFIG_AUDIO is not set + +# +# Wireless Support +# + +# +# Binary Loader +# +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_BINFMT_EXEPATH is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +CONFIG_BUILTIN=y +# CONFIG_PIC is not set +# CONFIG_SYMTAB_ORDEREDBYNAME is not set + +# +# Library Routines +# + +# +# Standard C Library Options +# + +# +# Standard C I/O +# +# CONFIG_STDIO_DISABLE_BUFFERING is not set +CONFIG_STDIO_BUFFER_SIZE=64 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +# CONFIG_NOPRINTF_FIELDWIDTH is not set +# CONFIG_LIBC_FLOATINGPOINT is not set +CONFIG_LIBC_LONG_LONG=y +# CONFIG_LIBC_SCANSET is not set +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_MEMCPY_VIK is not set +# CONFIG_LIBM is not set + +# +# Architecture-Specific Support +# +CONFIG_ARCH_LOWPUTC=y +# CONFIG_ARCH_ROMGETC is not set +# CONFIG_LIBC_ARCH_MEMCPY is not set +# CONFIG_LIBC_ARCH_MEMCMP is not set +# CONFIG_LIBC_ARCH_MEMMOVE is not set +# CONFIG_LIBC_ARCH_MEMSET is not set +# CONFIG_LIBC_ARCH_STRCHR is not set +# CONFIG_LIBC_ARCH_STRCMP is not set +# CONFIG_LIBC_ARCH_STRCPY is not set +# CONFIG_LIBC_ARCH_STRNCPY is not set +# CONFIG_LIBC_ARCH_STRLEN is not set +# CONFIG_LIBC_ARCH_STRNLEN is not set +# CONFIG_LIBC_ARCH_ELF is not set +# CONFIG_ARMV7M_MEMCPY is not set + +# +# stdlib Options +# +CONFIG_LIB_RAND_ORDER=1 +CONFIG_LIB_HOMEDIR="/" + +# +# Program Execution Options +# +# CONFIG_LIBC_EXECFUNCS is not set +CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024 +CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=2048 + +# +# errno Decode Support +# +# CONFIG_LIBC_STRERROR is not set +# CONFIG_LIBC_PERROR_STDOUT is not set + +# +# memcpy/memset Options +# +# CONFIG_MEMSET_OPTSPEED is not set +# CONFIG_LIBC_DLLFCN is not set +# CONFIG_LIBC_MODLIB is not set +# CONFIG_LIBC_WCHAR is not set +# CONFIG_LIBC_LOCALE is not set + +# +# Time/Time Zone Support +# +# CONFIG_LIBC_LOCALTIME is not set +# CONFIG_TIME_EXTENDED is not set +CONFIG_ARCH_HAVE_TLS=y + +# +# Thread Local Storage (TLS) +# +# CONFIG_TLS is not set + +# +# Network-Related Options +# +# CONFIG_LIBC_IPv4_ADDRCONV is not set +# CONFIG_LIBC_IPv6_ADDRCONV is not set +# CONFIG_LIBC_NETDB is not set + +# +# NETDB Support +# +# CONFIG_LIBC_IOCTL_VARIADIC is not set +CONFIG_LIB_SENDFILE_BUFSIZE=512 + +# +# Non-standard Library Support +# +# CONFIG_LIB_CRC64_FAST is not set +# CONFIG_LIB_KBDCODEC is not set +# CONFIG_LIB_SLCDCODEC is not set +# CONFIG_LIB_HEX2BIN is not set + +# +# Basic CXX Support +# +# CONFIG_C99_BOOL8 is not set +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +# CONFIG_CXX_NEWLONG is not set + +# +# LLVM C++ Library (libcxx) +# +# CONFIG_LIBCXX is not set + +# +# uClibc++ Standard C++ Library +# +# CONFIG_UCLIBCXX is not set + +# +# Application Configuration +# + +# +# Built-In Applications +# +CONFIG_BUILTIN_PROXY_STACKSIZE=1024 + +# +# CAN Utilities +# + +# +# Examples +# +CONFIG_EXAMPLES_ALARM=y +CONFIG_EXAMPLES_ALARM_PRIORITY=100 +CONFIG_EXAMPLES_ALARM_STACKSIZE=2048 +CONFIG_EXAMPLES_ALARM_DEVPATH="/dev/rtc0" +CONFIG_EXAMPLES_ALARM_SIGNO=1 +# CONFIG_EXAMPLES_BUTTONS is not set +# CONFIG_EXAMPLES_CCTYPE is not set +# CONFIG_EXAMPLES_CHAT is not set +# CONFIG_EXAMPLES_CONFIGDATA is not set +# CONFIG_EXAMPLES_CXXTEST is not set +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HELLOXX is not set +# CONFIG_EXAMPLES_HIDKBD is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_JSON is not set +# CONFIG_EXAMPLES_KEYPADTEST is not set +# CONFIG_EXAMPLES_MEDIA is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MODBUS is not set +# CONFIG_EXAMPLES_MOUNT is not set +# CONFIG_EXAMPLES_NRF24L01TERM is not set +CONFIG_EXAMPLES_NSH=y +CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NXLINES is not set +# CONFIG_EXAMPLES_NXTERM is not set +# CONFIG_EXAMPLES_NXTEXT is not set +CONFIG_EXAMPLES_OSTEST=y +CONFIG_EXAMPLES_OSTEST_LOOPS=1 +CONFIG_EXAMPLES_OSTEST_STACKSIZE=8192 +CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=8 +CONFIG_EXAMPLES_OSTEST_RR_RANGE=10000 +CONFIG_EXAMPLES_OSTEST_RR_RUNS=10 +CONFIG_EXAMPLES_OSTEST_WAITRESULT=y +# CONFIG_EXAMPLES_PCA9635 is not set +# CONFIG_EXAMPLES_POSIXSPAWN is not set +# CONFIG_EXAMPLES_PPPD is not set +CONFIG_EXAMPLES_RANDOM=y +CONFIG_EXAMPLES_MAXSAMPLES=64 +CONFIG_EXAMPLES_NSAMPLES=8 +# CONFIG_EXAMPLES_RFID_READUID is not set +# CONFIG_EXAMPLES_RGBLED is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERIALBLASTER is not set +# CONFIG_EXAMPLES_SERIALRX is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_SLCD is not set +# CONFIG_EXAMPLES_SMART is not set +# CONFIG_EXAMPLES_SMART_TEST is not set +# CONFIG_EXAMPLES_SMP is not set +# CONFIG_EXAMPLES_STAT is not set +# CONFIG_EXAMPLES_TCPECHO is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_USBSERIAL is not set +# CONFIG_EXAMPLES_WATCHDOG is not set +# CONFIG_EXAMPLES_WEBSERVER is not set + +# +# File System Utilities +# +# CONFIG_FSUTILS_INIFILE is not set + +# +# GPS Utilities +# +# CONFIG_GPSUTILS_MINMEA_LIB is not set + +# +# Graphics Support +# +# CONFIG_TIFF is not set +# CONFIG_GRAPHICS_TRAVELER is not set + +# +# Interpreters +# +# CONFIG_INTERPRETERS_FICL is not set +# CONFIG_INTERPRETERS_MICROPYTHON is not set +# CONFIG_INTERPRETERS_MINIBASIC is not set +# CONFIG_INTERPRETERS_PCODE is not set + +# +# FreeModBus +# +# CONFIG_MODBUS is not set + +# +# Network Utilities +# +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_ESP8266 is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_JSON is not set +# CONFIG_NETUTILS_SMTP is not set + +# +# NSH Library +# +CONFIG_NSH_LIBRARY=y +# CONFIG_NSH_MOTD is not set + +# +# Command Line Configuration +# +CONFIG_NSH_READLINE=y +# CONFIG_NSH_CLE is not set +CONFIG_NSH_LINELEN=64 +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_CMDPARMS is not set +CONFIG_NSH_MAXARGUMENTS=6 +# CONFIG_NSH_ARGCAT is not set +CONFIG_NSH_NESTDEPTH=3 +# CONFIG_NSH_DISABLEBG is not set +CONFIG_NSH_BUILTIN_APPS=y + +# +# Disable Individual commands +# +# CONFIG_NSH_DISABLE_ADDROUTE is not set +# CONFIG_NSH_DISABLE_BASENAME is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_CMP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_DD is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_DELROUTE is not set +# CONFIG_NSH_DISABLE_DIRNAME is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_HEXDUMP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +CONFIG_NSH_DISABLE_IFUPDOWN=y +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOSETUP is not set +CONFIG_NSH_DISABLE_LOSMART=y +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MB is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKRD is not set +# CONFIG_NSH_DISABLE_MH is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_MW is not set +CONFIG_NSH_DISABLE_PRINTF=y +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PUT is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SH is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNAME is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +# CONFIG_NSH_DISABLE_WGET is not set +# CONFIG_NSH_DISABLE_XD is not set +CONFIG_NSH_MMCSDMINOR=0 + +# +# Configure Command Options +# +# CONFIG_NSH_CMDOPT_DF_H is not set +# CONFIG_NSH_CMDOPT_DD_STATS is not set +CONFIG_NSH_CODECS_BUFSIZE=128 +# CONFIG_NSH_CMDOPT_HEXDUMP is not set +CONFIG_NSH_FILEIOSIZE=512 + +# +# Scripting Support +# +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_LOOPS is not set + +# +# Console Configuration +# +CONFIG_NSH_CONSOLE=y +# CONFIG_NSH_ALTCONDEV is not set +CONFIG_NSH_ARCHINIT=y +# CONFIG_NSH_LOGIN is not set +# CONFIG_NSH_CONSOLE_LOGIN is not set + +# +# NxWidgets/NxWM +# + +# +# Platform-specific Support +# +# CONFIG_PLATFORM_CONFIGDATA is not set + +# +# System Libraries and NSH Add-Ons +# +# CONFIG_SYSTEM_CLE is not set +# CONFIG_SYSTEM_CUTERM is not set +# CONFIG_SYSTEM_FREE is not set +# CONFIG_SYSTEM_HEX2BIN is not set +# CONFIG_SYSTEM_HEXED is not set +# CONFIG_SYSTEM_INSTALL is not set +# CONFIG_SYSTEM_RAMTEST is not set +CONFIG_READLINE_HAVE_EXTMATCH=y +CONFIG_SYSTEM_READLINE=y +CONFIG_READLINE_ECHO=y +# CONFIG_READLINE_TABCOMPLETION is not set +# CONFIG_READLINE_CMD_HISTORY is not set +# CONFIG_SYSTEM_SUDOKU is not set +# CONFIG_SYSTEM_SYSTEM is not set +# CONFIG_SYSTEM_TEE is not set +# CONFIG_SYSTEM_UBLOXMODEM is not set +# CONFIG_SYSTEM_VI is not set +# CONFIG_SYSTEM_ZMODEM is not set diff --git a/configs/nucleo-l432kc/scripts/l432kc.ld b/configs/nucleo-l432kc/scripts/l432kc.ld new file mode 100644 index 0000000000..bfac18b41f --- /dev/null +++ b/configs/nucleo-l432kc/scripts/l432kc.ld @@ -0,0 +1,119 @@ +/**************************************************************************** + * configs/nucleo-l432kc/scripts/l432kc.ld + * + * Copyright (C) 2014 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Sebastien Lorquet + * + * 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. + * + ****************************************************************************/ + +/* The STM32F411RE has 512Kb of FLASH beginning at address 0x0800:0000 and + * 128Kb of SRAM beginning at address 0x2000:0000. When booting from FLASH, + * FLASH memory is aliased to address 0x0000:0000 where the code expects to + * begin execution by jumping to the entry point in the 0x0800:0000 address + * range. + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x08000000, LENGTH = 512K + sram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K +} + +OUTPUT_ARCH(arm) +ENTRY(_stext) +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + } > flash + + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + /* The STM32L432KC has 96Kb of SRAM beginning at the following address */ + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/configs/nucleo-l432kc/src/Makefile b/configs/nucleo-l432kc/src/Makefile new file mode 100644 index 0000000000..fe944ec443 --- /dev/null +++ b/configs/nucleo-l432kc/src/Makefile @@ -0,0 +1,71 @@ +############################################################################ +# configs/nucleo-l432kc/src/Makefile +# +# Copyright (C) 2014 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. +# +############################################################################ + +-include $(TOPDIR)/Make.defs + +ASRCS = +CSRCS = stm32_boot.c stm32_spi.c + +ifeq ($(CONFIG_ARCH_LEDS),y) +CSRCS += stm32_autoleds.c +else +CSRCS += stm32_userleds.c +endif + +ifeq ($(CONFIG_ARCH_BUTTONS),y) +CSRCS += stm32_buttons.c +endif + +ifeq ($(CONFIG_ADC),y) +CSRCS += stm32_adc.c +endif + +ifeq ($(CONFIG_QENCODER),y) +CSRCS += stm32_qencoder.c +endif + +ifeq ($(CONFIG_PWM),y) +CSRCS += stm32_pwm.c +endif + +ifeq ($(CONFIG_TIMER),y) +CSRCS += stm32_timer.c +endif + +ifeq ($(CONFIG_LIB_BOARDCTL),y) +CSRCS += stm32_appinit.c +endif + +include $(TOPDIR)/configs/Board.mk diff --git a/configs/nucleo-l432kc/src/nucleo-l432kc.h b/configs/nucleo-l432kc/src/nucleo-l432kc.h new file mode 100644 index 0000000000..cbf549251e --- /dev/null +++ b/configs/nucleo-l432kc/src/nucleo-l432kc.h @@ -0,0 +1,390 @@ +/************************************************************************************ + * configs/nucleo-l432kc/src/nucleo-l432kc.h + * + * Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved. + * Authors: Frank Bennett + * Gregory Nutt + * Sebastien Lorquet + * + * 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 __CONFIGS_NUCLEO_L432KC_SRC_NUCLEO_L432KC_H +#define __CONFIGS_NUCLEO_L432KC_SRC_NUCLEO_L432KC_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* Configuration ********************************************************************/ + +#define HAVE_PROC 1 +#define HAVE_RTC_DRIVER 1 +#define HAVE_MMCSD 1 + +#if !defined(CONFIG_FS_PROCFS) +# undef HAVE_PROC +#endif + +#if defined(HAVE_PROC) && defined(CONFIG_DISABLE_MOUNTPOINT) +# warning Mountpoints disabled. No procfs support +# undef HAVE_PROC +#endif + +/* Check if we can support the RTC driver */ + +#if !defined(CONFIG_RTC) || !defined(CONFIG_RTC_DRIVER) +# undef HAVE_RTC_DRIVER +#endif + +#if !defined(CONFIG_STM32L4_SDIO) || !defined(CONFIG_MMCSD) || \ + !defined(CONFIG_MMCSD_SDIO) +# undef HAVE_MMCSD +#endif + +/* LED. User LD2: the green LED is a user LED connected to Arduino signal D13 + * corresponding to MCU I/O PA5 (pin 21) or PB13 (pin 34) depending on the STM32 + * target. + * + * - When the I/O is HIGH value, the LED is on. + * - When the I/O is LOW, the LED is off. + */ + +#define GPIO_LD2 \ + (GPIO_PORTA | GPIO_PIN5 | GPIO_OUTPUT_CLEAR | GPIO_OUTPUT | GPIO_PULLUP | \ + GPIO_SPEED_50MHz) + +/* Buttons + * + * B1 USER: the user button is connected to the I/O PC13 (pin 2) of the STM32 + * microcontroller. + */ + +#define MIN_IRQBUTTON BUTTON_USER +#define MAX_IRQBUTTON BUTTON_USER +#define NUM_IRQBUTTONS 1 + +#define GPIO_BTN_USER \ + (GPIO_INPUT |GPIO_FLOAT |GPIO_EXTI | GPIO_PORTC | GPIO_PIN13) + +/* The shield uses the following pins: + * + * +5V + * GND + * SERIAL_TX=PA_2 USER_BUTTON=PC_13 + * SERIAL_RX=PA_3 LD2=PA_5 + * + * Analog Digital + * A0=PA_0 USART2RX D0=PA_3 D8 =PA_9 + * A1=PA_1 USART2TX D1=PA_2 D9 =PC_7 + * A2=PA_4 D2=PA_10 WIFI_CS=D10=PB_6 SPI_CS + * A3=PB_0 WIFI_INT=D3=PB_3 D11=PA_7 SPI_MOSI + * A4=PC_1 SD_CS=D4=PB_5 D12=PA_6 SPI_MISO + * A5=PC_0 WIFI_EN=D5=PB_4 LD2=D13=PA_5 SPI_SCK + * LED2=D6=PB_10 I2C1_SDA=D14=PB_9 WIFI Probe + * D7=PA_8 I2C1_SCL=D15=PB_8 WIFI Probe + * + * mostly from: https://mbed.org/platforms/ST-Nucleo-F401RE/ + * + */ + +#ifdef CONFIG_WL_CC3000 +# define GPIO_WIFI_INT (GPIO_PORTB | GPIO_PIN3 | GPIO_INPUT | \ + GPIO_PULLUP | GPIO_EXTI) +# define GPIO_WIFI_EN (GPIO_PORTB | GPIO_PIN4 | GPIO_OUTPUT_CLEAR | \ + GPIO_OUTPUT | GPIO_PULLUP | GPIO_SPEED_50MHz) +# define GPIO_WIFI_CS (GPIO_PORTB | GPIO_PIN6 | GPIO_OUTPUT_SET | \ + GPIO_OUTPUT | GPIO_PULLUP | GPIO_SPEED_50MHz) +# define GPIO_D14 (GPIO_PORTB | GPIO_PIN9 | GPIO_OUTPUT_CLEAR | \ + GPIO_OUTPUT | GPIO_PULLUP | GPIO_SPEED_50MHz) +# define GPIO_D15 (GPIO_PORTB | GPIO_PIN8 | GPIO_OUTPUT_CLEAR | \ + GPIO_OUTPUT | GPIO_PULLUP | GPIO_SPEED_50MHz) +# define GPIO_D0 (GPIO_PORTA | GPIO_PIN3 | GPIO_INPUT | \ + GPIO_PULLUP) +# define GPIO_D1 (GPIO_PORTA | GPIO_PIN2 | GPIO_OUTPUT_CLEAR | \ + GPIO_PULLUP) +# define GPIO_D2 (GPIO_PORTA | GPIO_PIN10 | GPIO_OUTPUT_CLEAR | \ + GPIO_OUTPUT | GPIO_PULLUP | GPIO_SPEED_50MHz) +# define GPIO_A0 (GPIO_PORTA | GPIO_PIN0 | GPIO_OUTPUT_SET | \ + GPIO_OUTPUT | GPIO_PULLUP | GPIO_SPEED_50MHz) +# define GPIO_A1 (GPIO_PORTA | GPIO_PIN1 | GPIO_OUTPUT_SET | \ + GPIO_OUTPUT | GPIO_PULLUP | GPIO_SPEED_50MHz) +# define GPIO_A2 (GPIO_PORTA | GPIO_PIN4 | GPIO_INPUT | \ + GPIO_PULLUP) +# define GPIO_A3 (GPIO_PORTB | GPIO_PIN0 | GPIO_INPUT | \ + GPIO_PULLUP) +#endif + +/* SPI1 off */ + +#define GPIO_SPI1_MOSI_OFF (GPIO_INPUT | GPIO_PULLDOWN | \ + GPIO_PORTA | GPIO_PIN7) +#define GPIO_SPI1_MISO_OFF (GPIO_INPUT | GPIO_PULLDOWN | \ + GPIO_PORTA | GPIO_PIN6) +#define GPIO_SPI1_SCK_OFF (GPIO_INPUT | GPIO_PULLDOWN | \ + GPIO_PORTA | GPIO_PIN5) + +/* SPI1 chip selects off */ + +#ifdef CONFIG_WL_CC3000 +# define GPIO_SPI_CS_WIFI_OFF \ + (GPIO_INPUT | GPIO_PULLDOWN | GPIO_SPEED_2MHz | \ + GPIO_PORTB | GPIO_PIN6) +#endif + +#ifdef HAVE_MMCSD +# define GPIO_SPI_CS_SD_CARD_OFF \ + (GPIO_INPUT | GPIO_PULLDOWN | GPIO_SPEED_2MHz | \ + GPIO_PORTB | GPIO_PIN5) +#endif + +/* SPI chip selects */ + +#ifdef CONFIG_WL_CC3000 +# define GPIO_SPI_CS_WIFI \ + (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_2MHz | \ + GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN6) +#endif + +#ifdef HAVE_MMCSD +# define GPIO_SPI_CS_SD_CARD \ + (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_2MHz | \ + GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN5) +#endif + +/* Devices on the onboard bus. + * + * Note that these are unshifted addresses. + */ + +#define NUCLEO_I2C_OBDEV_LED 0x55 +#define NUCLEO_I2C_OBDEV_HMC5883 0x1e + +/* User GPIOs + * + * GPIO0-1 are for probing WIFI status + */ + +#ifdef CONFIG_WL_CC3000 +# define GPIO_GPIO0_INPUT \ + (GPIO_INPUT | GPIO_PULLUP | GPIO_PORTB | GPIO_PIN8) +# define GPIO_GPIO1_INPUT \ + (GPIO_INPUT | GPIO_PULLUP | GPIO_PORTB | GPIO_PIN9) +# define GPIO_GPIO0_OUTPUT \ + (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_2MHz | \ + GPIO_OUTPUT_CLEAR | GPIO_PORTB | GPIO_PIN8) +# define GPIO_GPIO1_OUTPUT \ + (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_2MHz | \ + GPIO_OUTPUT_CLEAR | GPIO_PORTB | GPIO_PIN9) +#endif + +/* Itead Joystick Shield + * + * See http://imall.iteadstudio.com/im120417014.html for more information + * about this joystick. + * + * --------- ----------------- --------------------------------- + * ARDUINO ITEAD NUCLEO-F4x1 + * PIN NAME SIGNAL SIGNAL + * --------- ----------------- --------------------------------- + * D3 Button E Output PB3 + * D4 Button D Output PB5 + * D5 Button C Output PB4 + * D6 Button B Output PB10 + * D7 Button A Output PA8 + * D8 Button F Output PA9 + * D9 Button G Output PC7 + * A0 Joystick Y Output PA0 ADC1_0 + * A1 Joystick X Output PA1 ADC1_1 + * --------- ----------------- --------------------------------- + * + * All buttons are pulled on the shield. A sensed low value indicates + * when the button is pressed. + * + * NOTE: Button F cannot be used with the default USART1 configuration + * because PA9 is configured for USART1_RX by default. Use select + * different USART1 pins in the board.h file or select a different + * USART or select CONFIG_NUCLEO_L432KC_AJOY_MINBUTTONS which will + * eliminate all but buttons A, B, and C. + */ + +#define ADC_XOUPUT 1 /* X output is on ADC channel 1 */ +#define ADC_YOUPUT 0 /* Y output is on ADC channel 0 */ + +#define GPIO_BUTTON_A \ + (GPIO_INPUT | GPIO_PULLUP |GPIO_EXTI | GPIO_PORTA | GPIO_PIN8) +#define GPIO_BUTTON_B \ + (GPIO_INPUT | GPIO_PULLUP |GPIO_EXTI | GPIO_PORTB | GPIO_PIN10) +#define GPIO_BUTTON_C \ + (GPIO_INPUT | GPIO_PULLUP |GPIO_EXTI | GPIO_PORTB | GPIO_PIN4) +#define GPIO_BUTTON_D \ + (GPIO_INPUT | GPIO_PULLUP |GPIO_EXTI | GPIO_PORTB | GPIO_PIN5) +#define GPIO_BUTTON_E \ + (GPIO_INPUT | GPIO_PULLUP |GPIO_EXTI | GPIO_PORTB | GPIO_PIN3) +#define GPIO_BUTTON_F \ + (GPIO_INPUT | GPIO_PULLUP |GPIO_EXTI | GPIO_PORTA | GPIO_PIN9) +#define GPIO_BUTTON_G \ + (GPIO_INPUT | GPIO_PULLUP |GPIO_EXTI | GPIO_PORTC | GPIO_PIN7) + +/* Itead Joystick Signal interpretation: + * + * --------- ----------------------- --------------------------- + * BUTTON TYPE NUTTX ALIAS + * --------- ----------------------- --------------------------- + * Button A Large button A JUMP/BUTTON 3 + * Button B Large button B FIRE/BUTTON 2 + * Button C Joystick select button SELECT/BUTTON 1 + * Button D Tiny Button D BUTTON 6 + * Button E Tiny Button E BUTTON 7 + * Button F Large Button F BUTTON 4 + * Button G Large Button G BUTTON 5 + * --------- ----------------------- --------------------------- + */ + +#define GPIO_BUTTON_1 GPIO_BUTTON_C +#define GPIO_BUTTON_2 GPIO_BUTTON_B +#define GPIO_BUTTON_3 GPIO_BUTTON_A +#define GPIO_BUTTON_4 GPIO_BUTTON_F +#define GPIO_BUTTON_5 GPIO_BUTTON_G +#define GPIO_BUTTON_6 GPIO_BUTTON_D +#define GPIO_BUTTON_7 GPIO_BUTTON_E + +#define GPIO_SELECT GPIO_BUTTON_1 +#define GPIO_FIRE GPIO_BUTTON_2 +#define GPIO_JUMP GPIO_BUTTON_3 + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/* Global driver instances */ + +#ifdef CONFIG_STM32L4_SPI1 +extern struct spi_dev_s *g_spi1; +#endif +#ifdef CONFIG_STM32L4_SPI2 +extern struct spi_dev_s *g_spi2; +#endif +#ifdef HAVE_MMCSD +extern struct sdio_dev_s *g_sdio; +#endif + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32l4_spiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins. + * + ************************************************************************************/ + +void stm32l4_spiinitialize(void); + +/************************************************************************************ + * Name: stm32l4_usbinitialize + * + * Description: + * Called to setup USB-related GPIO pins. + * + ************************************************************************************/ + +void stm32l4_usbinitialize(void); + +/************************************************************************************ + * Name: stm32l4_pwm_setup + * + * Description: + * Initialize PWM and register the PWM device. + * + ************************************************************************************/ + +#ifdef CONFIG_PWM +int stm32l4_pwm_setup(void); +#endif + +/************************************************************************************ + * Name: stm32l4_adc_setup + * + * Description: + * Initialize ADC and register the ADC driver. + * + ************************************************************************************/ + +#ifdef CONFIG_ADC +int stm32l4_adc_setup(void); +#endif + +/**************************************************************************** + * Name: board_ajoy_initialize + * + * Description: + * Initialize and register the button joystick driver + * + ****************************************************************************/ + +#ifdef CONFIG_AJOYSTICK +int board_ajoy_initialize(void); +#endif + +/**************************************************************************** + * Name: board_timer_driver_initialize + * + * Description: + * Initialize and register a timer + * + ****************************************************************************/ + +#ifdef CONFIG_TIMER +int board_timer_driver_initialize(FAR const char *devpath, int timer); +#endif + +/**************************************************************************** + * Name: stm32l4_qencoder_initialize + * + * Description: + * Initialize and register a qencoder + * + ****************************************************************************/ + +#ifdef CONFIG_QENCODER +int stm32l4_qencoder_initialize(FAR const char *devpath, int timer); +#endif + +#endif /* __CONFIGS_NUCLEO_L432KC_SRC_NUCLEO_L432KC_H */ diff --git a/configs/nucleo-l432kc/src/stm32_adc.c b/configs/nucleo-l432kc/src/stm32_adc.c new file mode 100644 index 0000000000..ddff398463 --- /dev/null +++ b/configs/nucleo-l432kc/src/stm32_adc.c @@ -0,0 +1,148 @@ +/************************************************************************************ + * configs/nucleo-l432kc/src/stm32_adc.c + * + * Copyright (C) 2014, 2016 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. + * + ************************************************************************************/ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include + +#include +#include +#include + +#include "chip.h" +#include "up_arch.h" + +#include "stm32l4_pwm.h" +#include "nucleo-l432kc.h" + +#ifdef CONFIG_STM32_ADC1 + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* The number of ADC channels in the conversion list */ + +#ifdef CONFIG_ADC_DMA +# define ADC1_NCHANNELS 2 +#else +# define ADC1_NCHANNELS 1 +#endif + +/************************************************************************************ + * Private Data + ************************************************************************************/ +/* Identifying number of each ADC channel. */ + +#ifdef CONFIG_AJOYSTICK +#ifdef CONFIG_ADC_DMA +/* The Itead analog joystick gets inputs on ADC_IN0 and ADC_IN1 */ + +static const uint8_t g_adc1_chanlist[ADC1_NCHANNELS] = {0, 1}; + +/* Configurations of pins used byte each ADC channels */ + +static const uint32_t g_adc1_pinlist[ADC1_NCHANNELS] = {GPIO_ADC1_IN0, GPIO_ADC1_IN0}; + +#else +/* Without DMA, only a single channel can be supported */ + +/* The Itead analog joystick gets input on ADC_IN0 */ + +static const uint8_t g_adc1_chanlist[ADC1_NCHANNELS] = {0}; + +/* Configurations of pins used byte each ADC channels */ + +static const uint32_t g_adc1_pinlist[ADC1_NCHANNELS] = {GPIO_ADC1_IN0}; + +#endif /* CONFIG_ADC_DMA */ +#endif /* CONFIG_AJOYSTICK */ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_adc_setup + * + * Description: + * Initialize ADC and register the ADC driver. + * + ************************************************************************************/ + +int stm32_adc_setup(void) +{ + struct adc_dev_s *adc; + int ret; + int i; + + /* Configure the pins as analog inputs for the selected channels */ + + for (i = 0; i < ADC1_NCHANNELS; i++) + { + stm32_configgpio(g_adc1_pinlist[i]); + } + + /* Call stm32_adcinitialize() to get an instance of the ADC interface */ + + adc = stm32_adcinitialize(1, g_adc1_chanlist, ADC1_NCHANNELS); + if (adc == NULL) + { + aerr("ERROR: Failed to get ADC interface\n"); + return -ENODEV; + } + + /* Register the ADC driver at "/dev/adc0" */ + + ret = adc_register("/dev/adc0", adc); + if (ret < 0) + { + aerr("ERROR: adc_register failed: %d\n", ret); + return ret; + } + + return OK; +} + +#endif /* CONFIG_STM32_ADC1 */ diff --git a/configs/nucleo-l432kc/src/stm32_appinit.c b/configs/nucleo-l432kc/src/stm32_appinit.c new file mode 100644 index 0000000000..c486838650 --- /dev/null +++ b/configs/nucleo-l432kc/src/stm32_appinit.c @@ -0,0 +1,342 @@ +/**************************************************************************** + * configs/nucleo-l432kc/src/stm32l4_appinit.c + * + * Copyright (C) 2016 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +#include + +#include "nucleo-l432kc.h" + +#ifdef HAVE_RTC_DRIVER +# include +# include "stm32l4_rtc.h" +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_netinitialize + * + * Description: + * Dummy function expected to start-up logic. + * + ****************************************************************************/ + +#ifdef CONFIG_WL_CC3000 +void up_netinitialize(void) +{ +} +#endif + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; the meaning of the argument is a contract + * between the board-specific initalization logic and the the + * matching application logic. The value cold be such things as a + * mode enumeration value, a set of DIP switch switch settings, a + * pointer to configuration data read from a file or serial FLASH, + * or whatever you would like to do with it. Every implementation + * should accept zero/NULL as a default configuration. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ + +int board_app_initialize(uintptr_t arg) +{ +#ifdef HAVE_RTC_DRIVER + FAR struct rtc_lowerhalf_s *rtclower; +#endif +#ifdef CONFIG_QENCODER + int index; + char buf[9]; +#endif + int ret; + + (void)ret; + +#ifdef HAVE_PROC + /* Mount the proc filesystem */ + + syslog(LOG_INFO, "Mounting procfs to /proc\n"); + + ret = mount(NULL, CONFIG_NSH_PROC_MOUNTPOINT, "procfs", 0, NULL); + if (ret < 0) + { + syslog(LOG_ERR, + "ERROR: Failed to mount the PROC filesystem: %d (%d)\n", + ret, errno); + return ret; + } +#endif + +#ifdef HAVE_RTC_DRIVER + /* Instantiate the STM32L4 lower-half RTC driver */ + + rtclower = stm32l4_rtc_lowerhalf(); + if (!rtclower) + { + serr("ERROR: Failed to instantiate the RTC lower-half driver\n"); + return -ENOMEM; + } + else + { + /* Bind the lower half driver and register the combined RTC driver + * as /dev/rtc0 + */ + + ret = rtc_initialize(0, rtclower); + if (ret < 0) + { + serr("ERROR: Failed to bind/register the RTC driver: %d\n", ret); + return ret; + } + } +#endif + +#ifdef HAVE_MMCSD + /* First, get an instance of the SDIO interface */ + + g_sdio = sdio_initialize(CONFIG_NSH_MMCSDSLOTNO); + if (!g_sdio) + { + syslog(LOG_ERR, "ERROR: Failed to initialize SDIO slot %d\n", + CONFIG_NSH_MMCSDSLOTNO); + return -ENODEV; + } + + /* Now bind the SDIO interface to the MMC/SD driver */ + + ret = mmcsd_slotinitialize(CONFIG_NSH_MMCSDMINOR, g_sdio); + if (ret != OK) + { + syslog(LOG_ERR, + "ERROR: Failed to bind SDIO to the MMC/SD driver: %d\n", + ret); + return ret; + } + + /* Then let's guess and say that there is a card in the slot. There is no + * card detect GPIO. + */ + + sdio_mediachange(g_sdio, true); + + syslog(LOG_INFO, "[boot] Initialized SDIO\n"); +#endif + +#ifdef CONFIG_PWM + /* Initialize PWM and register the PWM device. */ + + ret = stm32l4_pwm_setup(); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: stm32l4_pwm_setup() failed: %d\n", ret); + } +#endif + +#ifdef CONFIG_ADC + /* Initialize ADC and register the ADC driver. */ + + ret = stm32l4_adc_setup(); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: stm32l4_adc_setup failed: %d\n", ret); + } +#endif + +#ifdef CONFIG_AJOYSTICK + /* Initialize and register the joystick driver */ + + ret = board_ajoy_initialize(); + if (ret != OK) + { + syslog(LOG_ERR, + "ERROR: Failed to register the joystick driver: %d\n", + ret); + return ret; + } +#endif + +#ifdef CONFIG_TIMER + /* Initialize and register the timer driver */ + + ret = board_timer_driver_initialize("/dev/timer0", 2); + if (ret != OK) + { + syslog(LOG_ERR, + "ERROR: Failed to register the timer driver: %d\n", + ret); + return ret; + } +#endif + +#ifdef CONFIG_QENCODER + + /* Initialize and register the qencoder driver */ + + index = 0; + +#ifdef CONFIG_STM32L4_TIM1_QE + sprintf(buf, "/dev/qe%d", index++); + ret = stm32l4_qencoder_initialize(buf, 1); + if (ret != OK) + { + syslog(LOG_ERR, + "ERROR: Failed to register the qencoder: %d\n", + ret); + return ret; + } +#endif + +#ifdef CONFIG_STM32L4_TIM2_QE + sprintf(buf, "/dev/qe%d", index++); + ret = stm32l4_qencoder_initialize(buf, 2); + if (ret != OK) + { + syslog(LOG_ERR, + "ERROR: Failed to register the qencoder: %d\n", + ret); + return ret; + } +#endif + +#ifdef CONFIG_STM32L4_TIM3_QE + sprintf(buf, "/dev/qe%d", index++); + ret = stm32l4_qencoder_initialize(buf, 3); + if (ret != OK) + { + syslog(LOG_ERR, + "ERROR: Failed to register the qencoder: %d\n", + ret); + return ret; + } +#endif + +#ifdef CONFIG_STM32L4_TIM4_QE + sprintf(buf, "/dev/qe%d", index++); + ret = stm32l4_qencoder_initialize(buf, 4); + if (ret != OK) + { + syslog(LOG_ERR, + "ERROR: Failed to register the qencoder: %d\n", + ret); + return ret; + } +#endif + +#ifdef CONFIG_STM32L4_TIM5_QE + sprintf(buf, "/dev/qe%d", index++); + ret = stm32l4_qencoder_initialize(buf, 5); + if (ret != OK) + { + syslog(LOG_ERR, + "ERROR: Failed to register the qencoder: %d\n", + ret); + return ret; + } +#endif + +#ifdef CONFIG_STM32L4_TIM8_QE + sprintf(buf, "/dev/qe%d", index++); + ret = stm32l4_qencoder_initialize(buf, 8); + if (ret != OK) + { + syslog(LOG_ERR, + "ERROR: Failed to register the qencoder: %d\n", + ret); + return ret; + } +#endif + +#endif + + UNUSED(ret); + return OK; +} + +#ifdef CONFIG_BOARDCTL_IOCTL +int board_ioctl(unsigned int cmd, uintptr_t arg) +{ + return -ENOTTY; +} +#endif + +#if defined(CONFIG_BOARDCTL_UNIQUEID) +int board_uniqueid(uint8_t *uniqueid) +{ + if (uniqueid == 0) + { + return -EINVAL; + } + + stm32l4_get_uniqueid(uniqueid); + return OK; +} +#endif + diff --git a/configs/nucleo-l432kc/src/stm32_autoleds.c b/configs/nucleo-l432kc/src/stm32_autoleds.c new file mode 100644 index 0000000000..da0b66952e --- /dev/null +++ b/configs/nucleo-l432kc/src/stm32_autoleds.c @@ -0,0 +1,96 @@ +/**************************************************************************** + * configs/nucleo-l432kc/src/stm32l4_autoleds.c + * + * Copyright (C) 2014-2015 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "up_arch.h" +#include "up_internal.h" +#include "stm32l4.h" +#include "nucleo-l432kc.h" + +#ifdef CONFIG_ARCH_LEDS + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_autoled_initialize + ****************************************************************************/ + +void board_autoled_initialize(void) +{ + /* Configure LD2 GPIO for output */ + + stm32l4_configgpio(GPIO_LD2); +} + +/**************************************************************************** + * Name: board_autoled_on + ****************************************************************************/ + +void board_autoled_on(int led) +{ + if (led == 1) + { + stm32l4_gpiowrite(GPIO_LD2, true); + } +} + +/**************************************************************************** + * Name: board_autoled_off + ****************************************************************************/ + +void board_autoled_off(int led) +{ + if (led == 1) + { + stm32l4_gpiowrite(GPIO_LD2, false); + } +} + +#endif /* CONFIG_ARCH_LEDS */ diff --git a/configs/nucleo-l432kc/src/stm32_boot.c b/configs/nucleo-l432kc/src/stm32_boot.c new file mode 100644 index 0000000000..e460316949 --- /dev/null +++ b/configs/nucleo-l432kc/src/stm32_boot.c @@ -0,0 +1,128 @@ +/************************************************************************************ + * configs/nucleo-l432kc/src/stm32l4_boot.c + * + * Copyright (C) 2014-2015 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Librae + * + * 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 "up_arch.h" +#include "nucleo-l432kc.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/************************************************************************************ + * Private Data + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32l4_boardinitialize + * + * Description: + * All STM32L4 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +void stm32l4_boardinitialize(void) +{ + /* Configure on-board LEDs if LED support has been selected. */ + +#ifdef CONFIG_ARCH_LEDS + board_autoled_initialize(); +#endif + + /* Configure SPI chip selects if 1) SP2 is not disabled, and 2) the weak function + * stm32l4_spiinitialize() has been brought into the link. + */ + +#if defined(CONFIG_STM32L4_SPI1) || defined(CONFIG_STM32L4_SPI2) || defined(CONFIG_STM32L4_SPI3) + stm32l4_spiinitialize(); +#endif + + /* Initialize USB is 1) USBDEV is selected, 2) the USB controller is not + * disabled, and 3) the weak function stm32l4_usbinitialize() has been brought + * into the build. + */ + +#if defined(CONFIG_USBDEV) && defined(CONFIG_STM32L4_USB) + stm32l4_usbinitialize(); +#endif +} + +/**************************************************************************** + * Name: board_initialize + * + * Description: + * If CONFIG_BOARD_INITIALIZE is selected, then an additional + * initialization call will be performed in the boot-up sequence to a + * function called board_initialize(). board_initialize() will be + * called immediately after up_intiialize() is called and just before the + * initial application is started. This additional initialization phase + * may be used, for example, to initialize board-specific device drivers. + * + ****************************************************************************/ + +#ifdef CONFIG_BOARD_INITIALIZE +void board_initialize(void) +{ + /* Perform NSH initialization here instead of from the NSH. This + * alternative NSH initialization is necessary when NSH is ran in user-space + * but the initialization function must run in kernel space. + */ + +#if defined(CONFIG_NSH_LIBRARY) && !defined(CONFIG_NSH_ARCHINIT) + board_app_initialize(0); +#endif + +} +#endif diff --git a/configs/nucleo-l432kc/src/stm32_buttons.c b/configs/nucleo-l432kc/src/stm32_buttons.c new file mode 100644 index 0000000000..5f380c0497 --- /dev/null +++ b/configs/nucleo-l432kc/src/stm32_buttons.c @@ -0,0 +1,126 @@ +/**************************************************************************** + * configs/nucleo-l432kc/src/stm32_buttons.c + * + * Copyright (C) 2014-2015, 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include +#include +#include + +#include "nucleo-l432kc.h" + +#ifdef CONFIG_ARCH_BUTTONS + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_button_initialize + * + * Description: + * board_button_initialize() must be called to initialize button resources. + * After that, board_buttons() may be called to collect the current state + * of all buttons or board_button_irq() may be called to register button + * interrupt handlers. + * + ****************************************************************************/ + +void board_button_initialize(void) +{ + /* Configure the single button as an input. NOTE that EXTI interrupts are + * also configured for the pin. + */ + + stm32_configgpio(GPIO_BTN_USER); +} + +/**************************************************************************** + * Name: board_buttons + ****************************************************************************/ + +uint32_t board_buttons(void) +{ + /* Check that state of each USER button. A LOW value means that the key is + * pressed. + */ + + bool released = stm32_gpioread(GPIO_BTN_USER); + return !released; +} + +/************************************************************************************ + * Button support. + * + * Description: + * board_button_initialize() must be called to initialize button resources. After + * that, board_buttons() may be called to collect the current state of all + * buttons or board_button_irq() may be called to register button interrupt + * handlers. + * + * After board_button_initialize() has been called, board_buttons() may be called to + * collect the state of all buttons. board_buttons() returns an 32-bit bit set + * with each bit associated with a button. See the BUTTON_*_BIT + * definitions in board.h for the meaning of each bit. + * + * board_button_irq() may be called to register an interrupt handler that will + * be called when a button is depressed or released. The ID value is a + * button enumeration value that uniquely identifies a button resource. See the + * BUTTON_* definitions in board.h for the meaning of enumeration + * value. + * + ************************************************************************************/ + +#ifdef CONFIG_ARCH_IRQBUTTONS +int board_button_irq(int id, xcpt_t irqhandler, FAR void *arg) +{ + int ret = -EINVAL; + + if (id == BUTTON_USER) + { + ret = stm32_gpiosetevent(GPIO_BTN_USER, true, true, true, irqhandler, arg); + } + + return ret; +} +#endif +#endif /* CONFIG_ARCH_BUTTONS */ diff --git a/configs/nucleo-l432kc/src/stm32_pwm.c b/configs/nucleo-l432kc/src/stm32_pwm.c new file mode 100644 index 0000000000..24a520324c --- /dev/null +++ b/configs/nucleo-l432kc/src/stm32_pwm.c @@ -0,0 +1,272 @@ +/************************************************************************************ + * configs/nucleo-l432kc/src/stm32l4_pwm.c + * + * Copyright (C) 2011, 2015-2016 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Copyright (C) 2016 Sebastien Lorquet. All rights reserved. + * Author: Sebastien Lorquet + * + * 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 "chip.h" +#include "up_arch.h" +#include "stm32l4_pwm.h" +#include "nucleo-l432kc.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* Configuration *******************************************************************/ +/* PWM + * + * The STM3240G-Eval has no real on-board PWM devices, but the board can be + * configured to output a pulse train using variously unused pins on the board for + * PWM output (see board.h for details of pins). + */ + +#ifdef CONFIG_PWM + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32l4_pwm_setup + * + * Description: + * Initialize PWM and register the PWM device. + * + ************************************************************************************/ + +int stm32l4_pwm_setup(void) +{ + static bool initialized = false; + struct pwm_lowerhalf_s *pwm; + int ret; + + /* Have we already initialized? */ + + if (!initialized) + { + /* Call stm32l4_pwminitialize() to get an instance of the PWM interface */ + + /* PWM + * + * The Nucleo-l432kc has no real on-board PWM devices, but the board can be + * configured to output a pulse train using TIM1 or 8, or others (see board.h). + * Let's figure out which the user has configured. + */ + +#if defined(CONFIG_STM32L4_TIM1_PWM) + pwm = stm32l4_pwminitialize(1); + if (!pwm) + { + aerr("ERROR: Failed to get the STM32L4 PWM lower half\n"); + return -ENODEV; + } + + /* Register the PWM driver at "/dev/pwm0" */ + + ret = pwm_register("/dev/pwm0", pwm); + if (ret < 0) + { + aerr("ERROR: pwm_register failed: %d\n", ret); + return ret; + } +#endif + +#if defined(CONFIG_STM32L4_TIM2_PWM) + pwm = stm32l4_pwminitialize(2); + if (!pwm) + { + aerr("ERROR: Failed to get the STM32L4 PWM lower half\n"); + return -ENODEV; + } + + /* Register the PWM driver at "/dev/pwm1" */ + + ret = pwm_register("/dev/pwm1", pwm); + if (ret < 0) + { + aerr("ERROR: pwm_register failed: %d\n", ret); + return ret; + } +#endif + +#if defined(CONFIG_STM32L4_TIM3_PWM) + pwm = stm32l4_pwminitialize(3); + if (!pwm) + { + aerr("ERROR: Failed to get the STM32L4 PWM lower half\n"); + return -ENODEV; + } + + /* Register the PWM driver at "/dev/pwm2" */ + + ret = pwm_register("/dev/pwm2", pwm); + if (ret < 0) + { + aerr("ERROR: pwm_register failed: %d\n", ret); + return ret; + } +#endif + +#if defined(CONFIG_STM32L4_TIM4_PWM) + pwm = stm32l4_pwminitialize(4); + if (!pwm) + { + aerr("ERROR: Failed to get the STM32L4 PWM lower half\n"); + return -ENODEV; + } + + /* Register the PWM driver at "/dev/pwm3" */ + + ret = pwm_register("/dev/pwm3", pwm); + if (ret < 0) + { + aerr("ERROR: pwm_register failed: %d\n", ret); + return ret; + } +#endif + +#if defined(CONFIG_STM32L4_TIM5_PWM) + pwm = stm32l4_pwminitialize(5); + if (!pwm) + { + aerr("ERROR: Failed to get the STM32L4 PWM lower half\n"); + return -ENODEV; + } + + /* Register the PWM driver at "/dev/pwm4" */ + + ret = pwm_register("/dev/pwm4", pwm); + if (ret < 0) + { + aerr("ERROR: pwm_register failed: %d\n", ret); + return ret; + } +#endif + +#if defined(CONFIG_STM32L4_TIM8_PWM) + pwm = stm32l4_pwminitialize(8); + if (!pwm) + { + aerr("ERROR: Failed to get the STM32L4 PWM lower half\n"); + return -ENODEV; + } + + /* Register the PWM driver at "/dev/pwm5" */ + + ret = pwm_register("/dev/pwm5", pwm); + if (ret < 0) + { + aerr("ERROR: pwm_register failed: %d\n", ret); + return ret; + } +#endif + +#if defined(CONFIG_STM32L4_TIM15_PWM) + pwm = stm32l4_pwminitialize(15); + if (!pwm) + { + aerr("ERROR: Failed to get the STM32L4 PWM lower half\n"); + return -ENODEV; + } + + /* Register the PWM driver at "/dev/pwm6" */ + + ret = pwm_register("/dev/pwm6", pwm); + if (ret < 0) + { + aerr("ERROR: pwm_register failed: %d\n", ret); + return ret; + } +#endif + +#if defined(CONFIG_STM32L4_TIM16_PWM) + pwm = stm32l4_pwminitialize(16); + if (!pwm) + { + aerr("ERROR: Failed to get the STM32L4 PWM lower half\n"); + return -ENODEV; + } + + /* Register the PWM driver at "/dev/pwm7" */ + + ret = pwm_register("/dev/pwm7", pwm); + if (ret < 0) + { + aerr("ERROR: pwm_register failed: %d\n", ret); + return ret; + } +#endif + +#if defined(CONFIG_STM32L4_TIM17_PWM) + pwm = stm32l4_pwminitialize(17); + if (!pwm) + { + aerr("ERROR: Failed to get the STM32L4 PWM lower half\n"); + return -ENODEV; + } + + /* Register the PWM driver at "/dev/pwm8" */ + + ret = pwm_register("/dev/pwm8", pwm); + if (ret < 0) + { + aerr("ERROR: pwm_register failed: %d\n", ret); + return ret; + } +#endif + /* Now we are initialized */ + + initialized = true; + } + + return OK; +} + +#endif /* CONFIG_PWM */ + diff --git a/configs/nucleo-l432kc/src/stm32_qencoder.c b/configs/nucleo-l432kc/src/stm32_qencoder.c new file mode 100644 index 0000000000..3b11c120bf --- /dev/null +++ b/configs/nucleo-l432kc/src/stm32_qencoder.c @@ -0,0 +1,83 @@ +/************************************************************************************ + * configs/nucleo-l432kc/src/stm32_qencoder.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Copyright (C) 2016 Sebastien Lorquet. All rights reserved. + * Author: Sebastien Lorquet + * + * 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 "chip.h" +#include "up_arch.h" +#include "stm32l4_qencoder.h" +#include "nucleo-l432kc.h" + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: qe_devinit + * + * Description: + * All STM32L4 architectures must provide the following interface to work with + * examples/qencoder. + * + ************************************************************************************/ + +int stm32l4_qencoder_initialize(FAR const char *devpath, int timer) +{ + int ret; + + /* Initialize a quadrature encoder interface. */ + + sninfo("Initializing the quadrature encoder using TIM%d\n", timer); + ret = stm32l4_qeinitialize(devpath, timer); + if (ret < 0) + { + snerr("ERROR: stm32l4_qeinitialize failed: %d\n", ret); + } + + return ret; +} diff --git a/configs/nucleo-l432kc/src/stm32_spi.c b/configs/nucleo-l432kc/src/stm32_spi.c new file mode 100644 index 0000000000..04f307c40c --- /dev/null +++ b/configs/nucleo-l432kc/src/stm32_spi.c @@ -0,0 +1,202 @@ +/**************************************************************************** + * configs/nucleo-l432kc/src/stm32l4_spi.c + * + * Copyright (C) 2014 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. + * + ****************************************************************************/ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include + +#include "nucleo-l432kc.h" + +#if defined(CONFIG_STM32L4_SPI1) || defined(CONFIG_STM32L4_SPI2) + +/************************************************************************************ + * Public Data + ************************************************************************************/ +/* Global driver instances */ + +#ifdef CONFIG_STM32L4_SPI1 +struct spi_dev_s *g_spi1; +#endif +#ifdef CONFIG_STM32L4_SPI2 +struct spi_dev_s *g_spi2; +#endif + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32l4_spiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the Nucleo-L432KC board. + * + ************************************************************************************/ + +void stm32l4_spiinitialize(void) +{ +#ifdef CONFIG_STM32L4_SPI1 + + g_spi1 = stm32l4_spibus_initialize(1); + +#ifdef HAVE_MMCSD + stm32l4_configgpio(GPIO_SPI_CS_SD_CARD); +#endif + + _info("SPI1 initialized\n"); + +#ifdef CONFIG_STM32L4_SPI2 + /* Configure SPI-based devices */ + + g_spi2 = stm32l4_spibus_initialize(2); + + /* Setup CS, EN & IRQ line IOs */ + + _info("SPI2 initialized\n"); +#endif +} + +/**************************************************************************** + * Name: stm32l4_spi1/2select and stm32l4_spi1/2status + * + * Description: + * The external functions, stm32l4_spi1/2select and stm32l4_spi1/2status must be + * provided by board-specific logic. They are implementations of the select + * and status methods of the SPI interface defined by struct spi_ops_s (see + * include/nuttx/spi/spi.h). All other methods (including up_spiinitialize()) + * are provided by common STM32 logic. To use this common SPI logic on your + * board: + * + * 1. Provide logic in stm32l4_boardinitialize() to configure SPI chip select + * pins. + * 2. Provide stm32l4_spi1/2select() and stm32l4_spi1/2status() functions in your + * board-specific logic. These functions will perform chip selection and + * status operations using GPIOs in the way your board is configured. + * 3. Add a calls to up_spiinitialize() in your low level application + * initialization logic + * 4. The handle returned by up_spiinitialize() may then be used to bind the + * SPI driver to higher level logic (e.g., calling + * mmcsd_spislotinitialize(), for example, will bind the SPI driver to + * the SPI MMC/SD driver). + * + ****************************************************************************/ + +#ifdef CONFIG_STM32L4_SPI1 +void stm32l4_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) +{ + spiinfo("devid: %08X CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); + +#ifdef HAVE_MMCSD + if (devid == SPIDEV_MMCSD(0)) + { + stm32l4_gpiowrite(GPIO_SPI_CS_SD_CARD, !selected); + } +#endif + +} + +uint8_t stm32l4_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) +{ + return 0; +} +#endif + +#ifdef CONFIG_STM32L4_SPI2 +void stm32l4_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) +{ + spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); + +} + +uint8_t stm32l4_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) +{ + return 0; +} +#endif + +/**************************************************************************** + * Name: stm32l4_spi1cmddata + * + * Description: + * Set or clear the SH1101A A0 or SD1306 D/C n bit to select data (true) + * or command (false). This function must be provided by platform-specific + * logic. This is an implementation of the cmddata method of the SPI + * interface defined by struct spi_ops_s (see include/nuttx/spi/spi.h). + * + * Input Parameters: + * + * spi - SPI device that controls the bus the device that requires the CMD/ + * DATA selection. + * devid - If there are multiple devices on the bus, this selects which one + * to select cmd or data. NOTE: This design restricts, for example, + * one one SPI display per SPI bus. + * cmd - true: select command; false: select data + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_SPI_CMDDATA +#ifdef CONFIG_STM32L4_SPI1 +int stm32l4_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) +{ + return OK; +} +#endif + +#ifdef CONFIG_STM32L4_SPI2 +int stm32l4_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) +{ + return OK; +} +#endif +#endif /* CONFIG_SPI_CMDDATA */ + +#endif /* CONFIG_STM32L4_SPI1 || CONFIG_STM32L4_SPI2 */ diff --git a/configs/nucleo-l432kc/src/stm32_timer.c b/configs/nucleo-l432kc/src/stm32_timer.c new file mode 100644 index 0000000000..8750ba76b9 --- /dev/null +++ b/configs/nucleo-l432kc/src/stm32_timer.c @@ -0,0 +1,82 @@ +/**************************************************************************** + * config/nucleo-l432kc/src/stm32_timer.c + * + * Copyright (C) 2015 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Copied from nucleo-f303 by Sebastien Lorquet + * + * 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 "stm32l4_tim.h" +#include "nucleo-l432kc.h" + +#ifdef CONFIG_TIMER + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_timer_driver_initialize + * + * Description: + * Configure the timer driver. + * + * Input Parameters: + * devpath - The full path to the timer device. This should be of the + * form /dev/timer0 + * timer - The timer's number. + * + * Returned Values: + * Zero (OK) is returned on success; A negated errno value is returned + * to indicate the nature of any failure. + * + ****************************************************************************/ + +int board_timer_driver_initialize(FAR const char *devpath, int timer) +{ + return stm32l4_timer_initialize(devpath, timer); +} + +#endif diff --git a/configs/nucleo-l432kc/src/stm32_userleds.c b/configs/nucleo-l432kc/src/stm32_userleds.c new file mode 100644 index 0000000000..1ed437ced7 --- /dev/null +++ b/configs/nucleo-l432kc/src/stm32_userleds.c @@ -0,0 +1,217 @@ +/**************************************************************************** + * configs/nucleo-l432kc/src/stm32_userleds.c + * + * Copyright (C) 2014-2016 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "up_arch.h" +#include "up_internal.h" +#include "stm32l4.h" +#include "nucleo-l432kc.h" + +#ifndef CONFIG_ARCH_LEDS + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* LED Power Management */ + +#ifdef CONFIG_PM +static void led_pm_notify(struct pm_callback_s *cb, int domain, + enum pm_state_e pmstate); +static int led_pm_prepare(struct pm_callback_s *cb, int domain, + enum pm_state_e pmstate); +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +#ifdef CONFIG_PM +static struct pm_callback_s g_ledscb = +{ + .notify = led_pm_notify, + .prepare = led_pm_prepare, +}; +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: led_pm_notify + * + * Description: + * Notify the driver of new power state. This callback is called after + * all drivers have had the opportunity to prepare for the new power state. + * + ****************************************************************************/ + +#ifdef CONFIG_PM +static void led_pm_notify(struct pm_callback_s *cb, int domain, + enum pm_state_e pmstate) +{ + switch (pmstate) + { + case(PM_NORMAL): + { + /* Restore normal LEDs operation */ + + } + break; + + case(PM_IDLE): + { + /* Entering IDLE mode - Turn leds off */ + + } + break; + + case(PM_STANDBY): + { + /* Entering STANDBY mode - Logic for PM_STANDBY goes here */ + + } + break; + + case(PM_SLEEP): + { + /* Entering SLEEP mode - Logic for PM_SLEEP goes here */ + + } + break; + + default: + { + /* Should not get here */ + + } + break; + } +} +#endif + +/**************************************************************************** + * Name: led_pm_prepare + * + * Description: + * Request the driver to prepare for a new power state. This is a warning + * that the system is about to enter into a new power state. The driver + * should begin whatever operations that may be required to enter power + * state. The driver may abort the state change mode by returning a + * non-zero value from the callback function. + * + ****************************************************************************/ + +#ifdef CONFIG_PM +static int led_pm_prepare(struct pm_callback_s *cb, int domain, + enum pm_state_e pmstate) +{ + /* No preparation to change power modes is required by the LEDs driver. + * We always accept the state change by returning OK. + */ + + return OK; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_userled_initialize + ****************************************************************************/ + +void board_userled_initialize(void) +{ + /* Configure LD2 GPIO for output */ + + stm32_configgpio(GPIO_LD2); +} + +/**************************************************************************** + * Name: board_userled + ****************************************************************************/ + +void board_userled(int led, bool ledon) +{ + if (led == 1) + { + stm32_gpiowrite(GPIO_LD2, ldeon); + } +} + +/**************************************************************************** + * Name: board_userled_all + ****************************************************************************/ + +void board_userled_all(uint8_t ledset) +{ + if (led == 1) + { + stm32_gpiowrite(GPIO_LD2, (ledset & BOARD_LD2_BIT) != 0); + } +} + +/**************************************************************************** + * Name: stm32_led_pminitialize + ****************************************************************************/ + +#ifdef CONFIG_PM +void stm32_led_pminitialize(void) +{ + /* Register to receive power management callbacks */ + + int ret = pm_register(&g_ledscb); + DEBUGASSERT(ret == OK); + UNUSED(ret); +} +#endif /* CONFIG_PM */ + +#endif /* !CONFIG_ARCH_LEDS */ -- GitLab From fa060b79010c147a44492b8504a589cca04c6774 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 2 May 2017 09:40:12 -0600 Subject: [PATCH 678/990] photon/wlan: Update defconfig --- configs/photon/wlan/defconfig | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/configs/photon/wlan/defconfig b/configs/photon/wlan/defconfig index 7f886b89b1..a616dd914f 100644 --- a/configs/photon/wlan/defconfig +++ b/configs/photon/wlan/defconfig @@ -1306,10 +1306,6 @@ CONFIG_HAVE_CXXINITIALIZE=y # Application Configuration # -# -# NxWidgets/NxWM -# - # # Built-In Applications # @@ -1418,6 +1414,7 @@ CONFIG_EXAMPLES_NSH=y # # CONFIG_NETUTILS_CODECS is not set CONFIG_NETUTILS_DHCPC=y +CONFIG_NETUTILS_DHCPC_DEVNAME="wlan0" # CONFIG_NETUTILS_DHCPD is not set # CONFIG_NETUTILS_DISCOVER is not set # CONFIG_NETUTILS_ESP8266 is not set @@ -1559,6 +1556,10 @@ CONFIG_NSH_MAX_ROUNDTRIP=20 # CONFIG_NSH_LOGIN is not set # CONFIG_NSH_CONSOLE_LOGIN is not set +# +# NxWidgets/NxWM +# + # # Platform-specific Support # @@ -1594,3 +1595,4 @@ CONFIG_WIRELESS_WAPI=y CONFIG_WIRELESS_WAPI_CMDTOOL=y CONFIG_WIRELESS_WAPI_STACKSIZE=2048 CONFIG_WIRELESS_WAPI_PRIORITY=100 +CONFIG_WIRELESS_WEXT=y -- GitLab From fbe02dfe6b124cad2a7b39cb306a8f66caef6fb7 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 2 May 2017 10:07:31 -0600 Subject: [PATCH 679/990] net/pkt: Eliminate a warning. --- net/pkt/pkt.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/net/pkt/pkt.h b/net/pkt/pkt.h index aa6237da81..a1005f1d93 100644 --- a/net/pkt/pkt.h +++ b/net/pkt/pkt.h @@ -94,7 +94,8 @@ extern "C" * Public Function Prototypes ****************************************************************************/ -struct eth_hdr_s; /* Forward reference */ +struct net_driver_s; /* Forward reference */ +struct eth_hdr_s; /* Forward reference */ /* Defined in pkt_conn.c ****************************************************/ /**************************************************************************** -- GitLab From 74e016d01369944b025c10761240e572d4f3dd89 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Tue, 2 May 2017 12:36:01 +0300 Subject: [PATCH 680/990] STM32F7: flash: macro naming errors, there is no FLASH_CONFIG_F for F7 Signed-off-by: Juha Niskanen --- arch/arm/src/stm32f7/Kconfig | 14 +++++------- .../src/stm32f7/chip/stm32f74xx75xx_flash.h | 16 ++++++-------- .../src/stm32f7/chip/stm32f76xx77xx_flash.h | 22 +++++++++---------- 3 files changed, 23 insertions(+), 29 deletions(-) diff --git a/arch/arm/src/stm32f7/Kconfig b/arch/arm/src/stm32f7/Kconfig index ae131dd2f1..95e931abc2 100644 --- a/arch/arm/src/stm32f7/Kconfig +++ b/arch/arm/src/stm32f7/Kconfig @@ -26,7 +26,7 @@ config ARCH_CHIP_STM32F745VE select STM32F7_FLASH_CONFIG_E select STM32F7_IO_CONFIG_V ---help--- - STM32 F7 Cortex M7, 512 320K FLASH, 320K (240+16+64) Kb SRAM + STM32 F7 Cortex M7, 512 FLASH, 320K (240+16+64) Kb SRAM config ARCH_CHIP_STM32F745IG bool "STM32F745IG" @@ -835,7 +835,7 @@ config STM32F7_FLASH_CONFIG_E bool default n -config STM32F7_FLASH_CONFIG_I +config STM32F7_FLASH_CONFIG_G bool default n @@ -844,7 +844,7 @@ config STM32F7_FLASH_CONFIG_I default n choice - prompt "Overrdide Flash Size Designator" + prompt "Override Flash Size Designator" depends on ARCH_CHIP_STM32F7 default STM32F7_FLASH_OVERRIDE_DEFAULT ---help--- @@ -862,7 +862,7 @@ choice Examples: If the STM32F745VE is chosen, the Flash configuration would be 'E', if a variant of - the part with a 2048 KiB Flash is released in the future one could simply select + the part with a 2048 KiB Flash is released in the future one could simply select the 'I' designator here. If an STM32F7xxx Series parts is chosen the default Flash configuration will be set @@ -880,7 +880,7 @@ config STM32F7_FLASH_OVERRIDE_G config STM32F7_FLASH_OVERRIDE_I bool "I 2048KiB" -endchoice # "Overrdide Flash Size Designator" +endchoice # "Override Flash Size Designator" menu "STM32 Peripheral Support" @@ -895,7 +895,6 @@ config STM32F7_HAVE_FSMC bool default n - config STM32F7_HAVE_ETHRNET bool default n @@ -928,7 +927,6 @@ config STM32F7_HAVE_ADC3_DMA bool default n - config STM32F7_HAVE_CAN3 bool default n @@ -966,7 +964,7 @@ config STM32F7_HAVE_DFSDM1 default n # These "hidden" settings are the OR of individual peripheral selections -# indicating that the general capabilitiy is required. +# indicating that the general capability is required. config STM32F7_ADC bool diff --git a/arch/arm/src/stm32f7/chip/stm32f74xx75xx_flash.h b/arch/arm/src/stm32f7/chip/stm32f74xx75xx_flash.h index 74c2759fc9..a7624471d0 100644 --- a/arch/arm/src/stm32f7/chip/stm32f74xx75xx_flash.h +++ b/arch/arm/src/stm32f7/chip/stm32f74xx75xx_flash.h @@ -56,13 +56,11 @@ #define _K(x) ((x)*1024) #if !defined(CONFIG_STM32F7_FLASH_OVERRIDE_DEFAULT) && \ - !defined(CONFIG_STM32_FLASH_OVERRIDE_E) && \ - !defined(CONFIG_STM32_FLASH_OVERRIDE_F) && \ - !defined(CONFIG_STM32_FLASH_OVERRIDE_G) && \ - !defined(CONFIG_STM32_FLASH_CONFIG_E) && \ - !defined(CONFIG_STM32_FLASH_CONFIG_F) && \ - !defined(CONFIG_STM32_FLASH_CONFIG_G) -# define CONFIG_STM32_FLASH_OVERRIDE_E + !defined(CONFIG_STM32F7_FLASH_OVERRIDE_E) && \ + !defined(CONFIG_STM32F7_FLASH_OVERRIDE_G) && \ + !defined(CONFIG_STM32F7_FLASH_CONFIG_E) && \ + !defined(CONFIG_STM32F7_FLASH_CONFIG_G) +# define CONFIG_STM32F7_FLASH_OVERRIDE_E # warning "Flash size not defined defaulting to 512KiB (E)" #endif @@ -82,14 +80,14 @@ # endif #endif -#if defined(CONFIG_STM32_FLASH_CONFIG_E) +#if defined(CONFIG_STM32F7_FLASH_CONFIG_E) # define STM32_FLASH_NPAGES 6 # define STM32_FLASH_SIZE _K((4 * 32) + (1 * 128) + (1 * 256)) # define STM32_FLASH_SIZES {_K(32), _K(32), _K(32), _K(32), \ _K(128), _K(256)} -#elif defined(CONFIG_STM32_FLASH_CONFIG_G) +#elif defined(CONFIG_STM32F7_FLASH_CONFIG_G) # define STM32_FLASH_NPAGES 8 # define STM32_FLASH_SIZE _K((4 * 32) + (1 * 128) + (3 * 256)) diff --git a/arch/arm/src/stm32f7/chip/stm32f76xx77xx_flash.h b/arch/arm/src/stm32f7/chip/stm32f76xx77xx_flash.h index 0b6f764c36..9ceeff0221 100644 --- a/arch/arm/src/stm32f7/chip/stm32f76xx77xx_flash.h +++ b/arch/arm/src/stm32f7/chip/stm32f76xx77xx_flash.h @@ -56,15 +56,13 @@ #define _K(x) ((x)*1024) #if !defined(CONFIG_STM32F7_FLASH_OVERRIDE_DEFAULT) && \ - !defined(CONFIG_STM32_FLASH_OVERRIDE_E) && \ - !defined(CONFIG_STM32_FLASH_OVERRIDE_F) && \ - !defined(CONFIG_STM32_FLASH_OVERRIDE_G) && \ - !defined(CONFIG_STM32_FLASH_OVERRIDE_I) && \ - !defined(CONFIG_STM32_FLASH_CONFIG_E) && \ - !defined(CONFIG_STM32_FLASH_CONFIG_F) && \ - !defined(CONFIG_STM32_FLASH_CONFIG_G) && \ - !defined(CONFIG_STM32_FLASH_CONFIG_I) -# define CONFIG_STM32_FLASH_OVERRIDE_E + !defined(CONFIG_STM32F7_FLASH_OVERRIDE_E) && \ + !defined(CONFIG_STM32F7_FLASH_OVERRIDE_G) && \ + !defined(CONFIG_STM32F7_FLASH_OVERRIDE_I) && \ + !defined(CONFIG_STM32F7_FLASH_CONFIG_E) && \ + !defined(CONFIG_STM32F7_FLASH_CONFIG_G) && \ + !defined(CONFIG_STM32F7_FLASH_CONFIG_I) +# define CONFIG_STM32F7_FLASH_OVERRIDE_E # warning "Flash size not defined defaulting to 512KiB (E)" #endif @@ -89,21 +87,21 @@ # endif #endif -#if defined(CONFIG_STM32_FLASH_CONFIG_E) +#if defined(CONFIG_STM32F7_FLASH_CONFIG_E) # define STM32_FLASH_NPAGES 6 # define STM32_FLASH_SIZE _K((4 * 32) + (1 * 128) + (1 * 256)) # define STM32_FLASH_SIZES {_K(32), _K(32), _K(32), _K(32), \ _K(128), _K(256)} -#elif defined(CONFIG_STM32_FLASH_CONFIG_G) +#elif defined(CONFIG_STM32F7_FLASH_CONFIG_G) # define STM32_FLASH_NPAGES 8 # define STM32_FLASH_SIZE _K((4 * 32) + (1 * 128) + (3 * 256)) # define STM32_FLASH_SIZES {_K(32), _K(32), _K(32), _K(32), \ _K(128), _K(256), _K(256), _K(256)} -#elif defined(CONFIG_STM32_FLASH_CONFIG_I) +#elif defined(CONFIG_STM32F7_FLASH_CONFIG_I) # define STM32_FLASH_NPAGES 12 # define STM32_FLASH_SIZE _K((4 * 32) + (1 * 128) + (7 * 256)) -- GitLab From ad3b941c443725cff945932619873e1f3b4681ca Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Tue, 2 May 2017 12:30:11 +0300 Subject: [PATCH 681/990] STM32L4: stm32l4x6xx_pinmap: update I2C4 and DCMI pins Signed-off-by: Juha Niskanen --- .../arm/src/stm32l4/chip/stm32l4x6xx_pinmap.h | 36 +++++++++++++++++-- arch/arm/src/stm32l4/stm32l4_i2c.c | 2 +- 2 files changed, 34 insertions(+), 4 deletions(-) diff --git a/arch/arm/src/stm32l4/chip/stm32l4x6xx_pinmap.h b/arch/arm/src/stm32l4/chip/stm32l4x6xx_pinmap.h index 19f90a0148..4fd685b717 100644 --- a/arch/arm/src/stm32l4/chip/stm32l4x6xx_pinmap.h +++ b/arch/arm/src/stm32l4/chip/stm32l4x6xx_pinmap.h @@ -163,7 +163,36 @@ #define GPIO_DCMI_HSYNC_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTA|GPIO_PIN4) #define GPIO_DCMI_HSYNC_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTD|GPIO_PIN8) #define GPIO_DCMI_VSYNC_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN7) -/* TODO: DCMI data pins missing */ +#define GPIO_DCMI_VSYNC_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTI|GPIO_PIN5) + +#define GPIO_DCMI_D0_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTA|GPIO_PIN9) +#define GPIO_DCMI_D0_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTC|GPIO_PIN6) +#define GPIO_DCMI_D1_1 (GPIO_ALT|GPIO_AF5|GPIO_PORTA|GPIO_PIN10) +#define GPIO_DCMI_D1_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTC|GPIO_PIN7) +#define GPIO_DCMI_D2_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTC|GPIO_PIN8) +#define GPIO_DCMI_D2_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTE|GPIO_PIN0) +#define GPIO_DCMI_D3_1 (GPIO_ALT|GPIO_AF4|GPIO_PORTC|GPIO_PIN9) +#define GPIO_DCMI_D3_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTE|GPIO_PIN1) +#define GPIO_DCMI_D4_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTC|GPIO_PIN11) +#define GPIO_DCMI_D4_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTE|GPIO_PIN4) +#define GPIO_DCMI_D5_1 (GPIO_ALT|GPIO_AF4|GPIO_PORTD|GPIO_PIN3) +#define GPIO_DCMI_D5_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN6) +#define GPIO_DCMI_D6_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN8) +#define GPIO_DCMI_D6_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTE|GPIO_PIN5) +#define GPIO_DCMI_D7_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN9) +#define GPIO_DCMI_D7_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTE|GPIO_PIN6) +#define GPIO_DCMI_D8_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTC|GPIO_PIN10) +#define GPIO_DCMI_D8_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTH|GPIO_PIN6) +#define GPIO_DCMI_D9_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTC|GPIO_PIN12) +#define GPIO_DCMI_D9_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTH|GPIO_PIN7) +#define GPIO_DCMI_D10_1 (GPIO_ALT|GPIO_AF4|GPIO_PORTD|GPIO_PIN6) +#define GPIO_DCMI_D10_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN5) +#define GPIO_DCMI_D11_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTD|GPIO_PIN2) +#define GPIO_DCMI_D11_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTF|GPIO_PIN10) +#define GPIO_DCMI_D12_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN4) +#define GPIO_DCMI_D12_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTF|GPIO_PIN11) +#define GPIO_DCMI_D13_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTG|GPIO_PIN15) +#define GPIO_DCMI_D13_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTI|GPIO_PIN0) /* Digital Filter for Sigma-Delta Modulators (DFSDM) */ @@ -300,14 +329,15 @@ #define GPIO_I2C4_SDA_2 (GPIO_ALT|GPIO_AF3 |GPIO_PORTB|GPIO_PIN11) #define GPIO_I2C4_SDA_3 (GPIO_ALT|GPIO_AF2 |GPIO_PORTC|GPIO_PIN1) #define GPIO_I2C4_SDA_4 (GPIO_ALT|GPIO_AF4 |GPIO_PORTD|GPIO_PIN13) +#define GPIO_I2C4_SDA_5 (GPIO_ALT|GPIO_AF4 |GPIO_PORTF|GPIO_PIN15) #define GPIO_I2C4_SCL_1 (GPIO_ALT|GPIO_AF5 |GPIO_PORTB|GPIO_PIN6) #define GPIO_I2C4_SCL_2 (GPIO_ALT|GPIO_AF3 |GPIO_PORTB|GPIO_PIN10) #define GPIO_I2C4_SCL_3 (GPIO_ALT|GPIO_AF2 |GPIO_PORTC|GPIO_PIN0) #define GPIO_I2C4_SCL_4 (GPIO_ALT|GPIO_AF4 |GPIO_PORTD|GPIO_PIN12) +#define GPIO_I2C4_SCL_5 (GPIO_ALT|GPIO_AF4 |GPIO_PORTF|GPIO_PIN14) #define GPIO_I2C4_SMBA_1 (GPIO_ALT|GPIO_AF5 |GPIO_PORTA|GPIO_PIN14) #define GPIO_I2C4_SMBA_2 (GPIO_ALT|GPIO_AF4 |GPIO_PORTD|GPIO_PIN11) -#define GPIO_I2C4_SMBA_3 (GPIO_ALT|GPIO_AF4 |GPIO_PORTD|GPIO_PIN11) -#define GPIO_I2C4_SMBA_4 (GPIO_ALT|GPIO_AF4 |GPIO_PORTF|GPIO_PIN13) +#define GPIO_I2C4_SMBA_3 (GPIO_ALT|GPIO_AF4 |GPIO_PORTF|GPIO_PIN13) /* JTAG */ diff --git a/arch/arm/src/stm32l4/stm32l4_i2c.c b/arch/arm/src/stm32l4/stm32l4_i2c.c index 9be4419de4..58c2fa780f 100644 --- a/arch/arm/src/stm32l4/stm32l4_i2c.c +++ b/arch/arm/src/stm32l4/stm32l4_i2c.c @@ -1535,7 +1535,7 @@ static int stm32l4_i2c_isr_process(struct stm32l4_i2c_priv_s *priv) #ifdef CONFIG_STM32L4_I2C2 static int stm32l4_i2c_isr(int irq, void *context, FAR void *arg) { - struct stm32l4_i2c_priv_s *priv = (struct stm32l4_i2c_priv_s *priv)arg; + struct stm32l4_i2c_priv_s *priv = (struct stm32l4_i2c_priv_s *)arg; DEBUGASSERT(priv != NULL); return stm32l4_i2c_isr_process(priv); -- GitLab From 6157653acaf0125944883eb0722fc0a90f867cf5 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 2 May 2017 14:34:11 -0600 Subject: [PATCH 682/990] Update some comments --- net/pkt/pkt.h | 3 --- 1 file changed, 3 deletions(-) diff --git a/net/pkt/pkt.h b/net/pkt/pkt.h index a1005f1d93..69a35296dd 100644 --- a/net/pkt/pkt.h +++ b/net/pkt/pkt.h @@ -97,7 +97,6 @@ extern "C" struct net_driver_s; /* Forward reference */ struct eth_hdr_s; /* Forward reference */ -/* Defined in pkt_conn.c ****************************************************/ /**************************************************************************** * Name: pkt_initialize() * @@ -159,7 +158,6 @@ struct pkt_conn_s *pkt_active(FAR struct eth_hdr_s *buf); struct pkt_conn_s *pkt_nextconn(FAR struct pkt_conn_s *conn); -/* Defined in pkt_callback.c ************************************************/ /**************************************************************************** * Name: pkt_callback * @@ -177,7 +175,6 @@ struct pkt_conn_s *pkt_nextconn(FAR struct pkt_conn_s *conn); uint16_t pkt_callback(FAR struct net_driver_s *dev, FAR struct pkt_conn_s *conn, uint16_t flags); -/* Defined in pkt_input.c ***************************************************/ /**************************************************************************** * Name: pkt_input * -- GitLab From 2ece0c57dd6d7d77f44faa0c47d1c6bf0b3ad2ac Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 2 May 2017 14:42:40 -0600 Subject: [PATCH 683/990] Remove dangling whitespace at the end of lines --- drivers/wireless/ieee802154/at86rf23x.c | 2 +- drivers/wireless/ieee802154/mrf24j40.c | 18 +- drivers/wireless/ieee802154/mrf24j40.h | 6 +- .../wireless/ieee802154/ieee802154_mac.h | 146 +- .../wireless/ieee802154/ieee802154_radio.h | 8 +- wireless/ieee802154/mac802154.c | 2852 ++++++++--------- wireless/ieee802154/mac802154.h | 2 +- wireless/ieee802154/mac802154_device.c | 2 +- 8 files changed, 1518 insertions(+), 1518 deletions(-) diff --git a/drivers/wireless/ieee802154/at86rf23x.c b/drivers/wireless/ieee802154/at86rf23x.c index 8037c4005a..24a4d5ca39 100644 --- a/drivers/wireless/ieee802154/at86rf23x.c +++ b/drivers/wireless/ieee802154/at86rf23x.c @@ -217,7 +217,7 @@ static const struct ieee802154_radioops_s at86rf23x_devops = /**************************************************************************** * Private Functions ****************************************************************************/ - + /**************************************************************************** * Name: at86rf23x_lock * diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c index f883b55054..c703933acc 100644 --- a/drivers/wireless/ieee802154/mrf24j40.c +++ b/drivers/wireless/ieee802154/mrf24j40.c @@ -114,7 +114,7 @@ struct mrf24j40_txdesc_s struct mrf24j40_radio_s { struct ieee802154_radio_s radio; /* The public device instance */ - FAR struct ieee802154_radiocb_s *radiocb; /* Registered callbacks */ + FAR struct ieee802154_radiocb_s *radiocb; /* Registered callbacks */ /* Low-level MCU-specific support */ @@ -310,7 +310,7 @@ static int mrf24j40_txnotify_csma(FAR struct ieee802154_radio_s *radio) * 2. When new TX data is available (mrf24j40_txnotify_csma), and * 3. After a TX timeout to restart the sending process * (mrf24j40_txtimeout_csma). - * + * * Parameters: * radio - Reference to the radio driver state structure * @@ -329,7 +329,7 @@ static void mrf24j40_dopoll_csma(FAR void *arg) /* Get exclusive access to the driver */ while (sem_wait(&dev->exclsem) != 0) { } - + /* If this a CSMA transaction and we have room in the CSMA fifo */ if (!dev->csma_desc.busy) @@ -401,7 +401,7 @@ static int mrf24j40_txnotify_gts(FAR struct ieee802154_radio_s *radio) * 2. When new TX data is available (mrf24j40_txnotify_gts), and * 3. After a TX timeout to restart the sending process * (mrf24j40_txtimeout_gts). - * + * * Parameters: * arg - Reference to the radio driver state structure * @@ -440,7 +440,7 @@ static void mrf24j40_dopoll_gts(FAR void *arg) } } } - + sem_post(&dev->exclsem); } @@ -754,7 +754,7 @@ static int mrf24j40_getchannel(FAR struct mrf24j40_radio_s *dev, FAR uint8_t *chan) { *chan = dev->channel; - + return OK; } @@ -1369,7 +1369,7 @@ static int mrf24j40_csma_setup(FAR struct mrf24j40_radio_s *dev, * Name: mrf24j40_gts_setup * * Description: - * Setup a GTS transaction in one of the GTS FIFOs + * Setup a GTS transaction in one of the GTS FIFOs * ****************************************************************************/ @@ -1435,7 +1435,7 @@ static int mrf24j40_setup_fifo(FAR struct mrf24j40_radio_s *dev, { mrf24j40_setreg(dev->spi, fifo_addr++, frame->io_data[ret]); } - + return ret; } @@ -1764,7 +1764,7 @@ FAR struct ieee802154_radio_s *mrf24j40_init(FAR struct spi_dev_s *spi, { return NULL; } - + /* Attach irq */ if (lower->attach(lower, mrf24j40_interrupt, dev) != OK) diff --git a/drivers/wireless/ieee802154/mrf24j40.h b/drivers/wireless/ieee802154/mrf24j40.h index 585fae513a..f9a8a35a5d 100644 --- a/drivers/wireless/ieee802154/mrf24j40.h +++ b/drivers/wireless/ieee802154/mrf24j40.h @@ -167,10 +167,10 @@ /* RXMCR bits */ -#define MRF24J40_RXMCR_PROMI (1 << 0) /* Enable promisc mode (rx all valid packets) */ -#define MRF24J40_RXMCR_ERRPKT 0x02 /* Do not check CRC */ +#define MRF24J40_RXMCR_PROMI (1 << 0) /* Enable promisc mode (rx all valid packets) */ +#define MRF24J40_RXMCR_ERRPKT 0x02 /* Do not check CRC */ #define MRF24J40_RXMCR_COORD 0x04 /* Enable coordinator mode ??? DIFFERENCE ??? - not used in datasheet! */ -#define MRF24J40_RXMCR_PANCOORD 0x08 /* Enable PAN coordinator mode ??? DIFFERENCE ??? */ +#define MRF24J40_RXMCR_PANCOORD 0x08 /* Enable PAN coordinator mode ??? DIFFERENCE ??? */ #define MRF24J40_RXMCR_NOACKRSP 0x20 /* Enable auto ACK when a packet is rxed */ /* TXMCR bits */ diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index 422e4d88fb..a51e885287 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -68,7 +68,7 @@ /* IEEE 802.15.4 MAC Character Driver IOCTL Commands ************************/ -/* The IEEE 802.15.4 standard specifies a MLME Service Access Point (SAP) +/* The IEEE 802.15.4 standard specifies a MLME Service Access Point (SAP) * including a series of primitives that are used as an interface between * the MLME and the next highest layer. There are 4 types of primitives: * @@ -76,7 +76,7 @@ * - Indication * - Response * - Confirm - * + * * Of these, Request and Response primitives are sent from the next highest layer * to the MLME. Indication and Confirm primitives are used to notify the next * highest layer of changes or actions that have taken place. @@ -130,7 +130,7 @@ #define IEEE802154_SADDR_BCAST (uint16_t)0xFFFE #define IEEE802154_EADDR_UNSPEC (uint8_t*)"\xff\xff\xff\xff\xff\xff\xff\xff" -/* Frame control field masks, 2 bytes +/* Frame control field masks, 2 bytes * Seee IEEE 802.15.4/2011 5.2.1.1 page 57 */ @@ -178,11 +178,11 @@ #define IEEE802154_MAX_MPDU_UNSEC_OVERHEAD \ (IEEE802154_MAX_UNSEC_MHR_OVERHEAD + IEEE802154_MFR_LENGTH) - + #define IEEE802154_MAX_SAFE_MAC_PAYLOAD_SIZE \ (IEEE802154_MAX_PHY_PACKET_SIZE - IEEE802154_MAX_MPDU_UNSEC_OVERHEAD) - + #define IEEE802154_MAX_MAC_PAYLOAD_SIZE \ (IEEE802154_MAX_PHY_PACKET_SIZE - IEEE802154_MIN_MPDU_OVERHEAD) @@ -346,7 +346,7 @@ struct ieee802154_addr_s { /* Address mode. Short or Extended */ - enum ieee802154_addr_mode_e mode; + enum ieee802154_addr_mode_e mode; uint16_t panid; /* PAN identifier, can be IEEE802154_PAN_UNSPEC */ uint16_t saddr; /* short address */ @@ -444,7 +444,7 @@ struct ieee802154_pend_addr_s { uint8_t num_short_addr : 3; /* Number of short addresses pending */ uint8_t reserved_3 : 1; /* Reserved bit */ - uint8_t num_ext_addr : 3; /* Number of extended addresses pending */ + uint8_t num_ext_addr : 3; /* Number of extended addresses pending */ uint8_t reserved_7 : 1; /* Reserved bit */ } pa_addr; } u; @@ -480,9 +480,9 @@ struct ieee802154_frame_meta_s struct ieee802154_addr_s dest_addr; /* Destination Address */ uint8_t msdu_handle; /* Handle assoc. with MSDU */ - - /* Number of bytes contained in the MAC Service Data Unit (MSDU) - * to be transmitted by the MAC sublayer enitity + + /* Number of bytes contained in the MAC Service Data Unit (MSDU) + * to be transmitted by the MAC sublayer enitity * Note: This could be a uint8_t but if anyone ever wants to use * non-standard frame lengths, they may want a length larger than * a uint8_t. @@ -492,7 +492,7 @@ struct ieee802154_frame_meta_s struct { - uint8_t ack_tx : 1; /* Acknowledge TX? */ + uint8_t ack_tx : 1; /* Acknowledge TX? */ uint8_t gts_tx : 1; /* 1=GTS used for TX, 0=CAP used for TX */ uint8_t indirect_tx : 1; /* Should indirect transmission be used? */ } msdu_flags; @@ -513,7 +513,7 @@ struct ieee802154_frame_meta_s * 0, 16, 64, 1024, 4096 */ - uint16_t uwb_presym_rep; + uint16_t uwb_presym_rep; /* The UWB Data Rate to be used for the transmission */ @@ -526,11 +526,11 @@ struct ieee802154_frame_meta_s /* Primitive Semantics *******************************************************/ /***************************************************************************** - * Primitive: MCPS-DATA.request + * Primitive: MCPS-DATA.request * * Description: - * Requests the transfer of data to another device. - * + * Requests the transfer of data to another device. + * *****************************************************************************/ struct ieee802154_data_req_s @@ -540,11 +540,11 @@ struct ieee802154_data_req_s }; /***************************************************************************** - * Primitive: MCPS-DATA.confirm + * Primitive: MCPS-DATA.confirm * * Description: * Reports the results of a request to transfer data to another device. - * + * *****************************************************************************/ struct ieee802154_data_conf_s @@ -553,11 +553,11 @@ struct ieee802154_data_conf_s }; /***************************************************************************** - * Primitive: MCPS-DATA.indication + * Primitive: MCPS-DATA.indication * * Description: * Indicates the reception of data from another device. - * + * *****************************************************************************/ struct ieee802154_data_ind_s @@ -577,13 +577,13 @@ struct ieee802154_data_ind_s * the beginning of the ranging exchange */ - uint32_t rng_counter_start; + uint32_t rng_counter_start; /* A count of the time units corresponding to an RMARKER at the antenna at * end of the ranging exchange */ - uint32_t rng_counter_stop; + uint32_t rng_counter_stop; /* A count of the time units in a message exchange over which the tracking * offset was measured @@ -597,18 +597,18 @@ struct ieee802154_data_ind_s uint32_t rng_offset; - /* The Figure of Merit (FoM) characterizing the ranging measurement */ + /* The Figure of Merit (FoM) characterizing the ranging measurement */ - uint8_t rng_fom; + uint8_t rng_fom; #endif }; /***************************************************************************** - * Primitive: MCPS-PURGE.request + * Primitive: MCPS-PURGE.request * * Description: * Allows the next higher layer to purge an MSDU from the transaction queue. - * + * *****************************************************************************/ struct ieee802154_purge_req_s @@ -617,12 +617,12 @@ struct ieee802154_purge_req_s }; /***************************************************************************** - * Primitive: MCPS-PURGE.confirm + * Primitive: MCPS-PURGE.confirm * * Description: * Allows the MAC sublayer to notify the next higher layer of the success of * its request to purge an MSDU from the transaction queue. - * + * *****************************************************************************/ struct ieee802154_purge_conf_s @@ -632,11 +632,11 @@ struct ieee802154_purge_conf_s }; /***************************************************************************** - * Primitive: MLME-ASSOCIATE.request + * Primitive: MLME-ASSOCIATE.request * * Description: * Used by a device to request an association with a coordinator. - * + * *****************************************************************************/ struct ieee802154_assoc_req_s @@ -660,11 +660,11 @@ struct ieee802154_assoc_req_s }; /***************************************************************************** - * Primitive: MLME-ASSOCIATE.indication + * Primitive: MLME-ASSOCIATE.indication * * Description: * Used to indicate the reception of an association request command. - * + * *****************************************************************************/ struct ieee802154_assoc_ind_s @@ -685,11 +685,11 @@ struct ieee802154_assoc_ind_s }; /***************************************************************************** - * Primitive: MLME-ASSOCIATE.response + * Primitive: MLME-ASSOCIATE.response * * Description: * Used to initiate a response to an MLME-ASSOCIATE.indication primitive. - * + * *****************************************************************************/ struct ieee802154_assoc_resp_s @@ -700,7 +700,7 @@ struct ieee802154_assoc_resp_s /* Status of association attempt */ - enum ieee802154_status_e status; + enum ieee802154_status_e status; #ifdef CONFIG_IEEE802154_SECURITY /* Security information if enabled */ @@ -710,12 +710,12 @@ struct ieee802154_assoc_resp_s }; /***************************************************************************** - * Primitive: MLME-ASSOCIATE.confirm + * Primitive: MLME-ASSOCIATE.confirm * * Description: * Used to inform the next higher layer of the initiating device whether its * request to associate was successful or unsuccessful. - * + * *****************************************************************************/ struct ieee802154_assoc_conf_s @@ -739,13 +739,13 @@ struct ieee802154_assoc_conf_s }; /***************************************************************************** - * Primitive: MLME-DISASSOCIATE.request + * Primitive: MLME-DISASSOCIATE.request * * Description: * Used by an associated device to notify the coordinator of its intent to * leave the PAN. It is also used by the coordinator to instruct an * associated device to leave the PAN. - * + * *****************************************************************************/ struct ieee802154_disassoc_req_s @@ -768,11 +768,11 @@ struct ieee802154_disassoc_req_s }; /***************************************************************************** - * Primitive: MLME-DISASSOCIATE.indication + * Primitive: MLME-DISASSOCIATE.indication * * Description: * Used to indicate the reception of a disassociation notification command. - * + * *****************************************************************************/ struct ieee802154_disassoc_ind_s @@ -793,11 +793,11 @@ struct ieee802154_disassoc_ind_s }; /***************************************************************************** - * Primitive: MLME-DISASSOCIATE.confirm + * Primitive: MLME-DISASSOCIATE.confirm * * Description: * Reports the results of an MLME-DISASSOCIATE.request primitive. - * + * *****************************************************************************/ struct ieee802154_disassoc_conf_s @@ -812,7 +812,7 @@ struct ieee802154_disassoc_conf_s }; /***************************************************************************** - * Primitive: MLME-BEACONNOTIFY.indication + * Primitive: MLME-BEACONNOTIFY.indication * * Description: * Used to send parameters contained within a beacon frame received by the @@ -820,7 +820,7 @@ struct ieee802154_disassoc_conf_s * FALSE or when the beacon frame contains one or more octets of payload. The * primitive also sends a measure of the LQI and the time the beacon frame * was received. - * + * *****************************************************************************/ struct ieee802154_beaconnotify_ind_s @@ -837,7 +837,7 @@ struct ieee802154_beaconnotify_ind_s uint8_t sdu_length; /* Number of octets contained in the beacon * payload of the received beacond frame */ - + /* Beacon payload */ uint8_t sdu[IEEE802154_MAX_BEACON_PAYLOAD_LENGTH]; @@ -848,11 +848,11 @@ struct ieee802154_beaconnotify_ind_s - IEEE802154_MAX_BEACON_PAYLOAD_LENGTH + (n)) /***************************************************************************** - * Primitive: MLME-COMM-STATUS.indication + * Primitive: MLME-COMM-STATUS.indication * * Description: * Allows the MLME to indicate a communications status. - * + * *****************************************************************************/ struct ieee802154_commstatus_ind_s @@ -869,11 +869,11 @@ struct ieee802154_commstatus_ind_s }; /***************************************************************************** - * Primitive: MLME-GET.request + * Primitive: MLME-GET.request * * Description: * Requests information about a given PIB attribute. - * + * *****************************************************************************/ struct ieee802154_get_req_s @@ -882,11 +882,11 @@ struct ieee802154_get_req_s }; /***************************************************************************** - * Primitive: MLME-GET.confirm + * Primitive: MLME-GET.confirm * * Description: * Reports the results of an information request from the PIB. - * + * *****************************************************************************/ struct ieee802154_get_conf_s @@ -903,7 +903,7 @@ struct ieee802154_get_conf_s * Allows a device to send a request to the PAN coordinator to allocate a new * GTS or to deallocate an existing GTS. This primitive is also used by the * PAN coordinator to initiate a GTS deallocation. - * + * *****************************************************************************/ struct ieee802154_gts_req_s @@ -923,7 +923,7 @@ struct ieee802154_gts_req_s * Description: * Reports the results of a request to allocate a new GTS or to deallocate an * existing GTS. - * + * *****************************************************************************/ struct ieee802154_gts_conf_s @@ -938,7 +938,7 @@ struct ieee802154_gts_conf_s * Description: * Indicates that a GTS has been allocated or that a previously allocated * GTS has been deallocated. - * + * *****************************************************************************/ struct ieee802154_gts_ind_s @@ -959,7 +959,7 @@ struct ieee802154_gts_ind_s * Description: * Generated by the MLME of a coordinator and issued to its next higher layer * on receipt of an orphan notification command. - * + * *****************************************************************************/ struct ieee802154_orphan_ind_s @@ -979,7 +979,7 @@ struct ieee802154_orphan_ind_s * Description: * Allows the next higher layer of a coordinator to respond to the * MLME-ORPHAN.indication primitive. - * + * *****************************************************************************/ struct ieee802154_orphan_resp_s @@ -999,7 +999,7 @@ struct ieee802154_orphan_resp_s * Description: * Used by the next higher layer to request that the MLME performs a reset * operation. - * + * *****************************************************************************/ struct ieee802154_reset_req_s @@ -1012,7 +1012,7 @@ struct ieee802154_reset_req_s * * Description: * Reports the results of the reset operation. - * + * *****************************************************************************/ struct ieee802154_reset_conf_s @@ -1026,7 +1026,7 @@ struct ieee802154_reset_conf_s * Description: * Allows the next higher layer to request that the receiver is either * enabled for a finite period of time or disabled. - * + * *****************************************************************************/ struct ieee802154_rxenable_req_s @@ -1035,7 +1035,7 @@ struct ieee802154_rxenable_req_s * receiver is to be enabled or disabled. */ - uint32_t rxon_time; + uint32_t rxon_time; /* Number of symbols for which the receiver is to be enabled */ @@ -1051,7 +1051,7 @@ struct ieee802154_rxenable_req_s * * Description: * Reports the results of the attempt to enable or disable the receiver. - * + * *****************************************************************************/ struct ieee802154_rxenable_conf_s @@ -1064,7 +1064,7 @@ struct ieee802154_rxenable_conf_s * * Description: * Used to initiate a channel scan over a given list of channels. - * + * *****************************************************************************/ struct ieee802154_scan_req_s @@ -1090,7 +1090,7 @@ struct ieee802154_scan_req_s * * Description: * Reports the result of the channel scan request. - * + * *****************************************************************************/ struct ieee802154_scan_conf_s @@ -1108,7 +1108,7 @@ struct ieee802154_scan_conf_s * * Description: * Attempts to write the given value to the indicated PIB attribute. - * + * *****************************************************************************/ struct ieee802154_set_req_s @@ -1122,7 +1122,7 @@ struct ieee802154_set_req_s * * Description: * Reports the results of an attempt to write a value to a PIB attribute. - * + * *****************************************************************************/ struct ieee802154_set_conf_s @@ -1139,7 +1139,7 @@ struct ieee802154_set_conf_s * superframe configuration. This primitive is also used by a device already * associated with an existing PAN to begin using a new superframe * configuration. - * + * *****************************************************************************/ struct ieee802154_start_req_s @@ -1148,7 +1148,7 @@ struct ieee802154_start_req_s uint8_t ch_num; uint8_t ch_page; - uint32_t start_time : 24; + uint32_t start_time : 24; uint32_t beacon_order : 8; uint8_t sf_order; @@ -1171,7 +1171,7 @@ struct ieee802154_start_req_s * Description: * Reports the results of the attempt to start using a new superframe * configuration. - * + * *****************************************************************************/ struct ieee802154_start_conf_s @@ -1185,7 +1185,7 @@ struct ieee802154_start_conf_s * Description: * Requests to synchronize with the coordinator by acquiring and, if * specified, tracking its beacons. - * + * *****************************************************************************/ struct ieee802154_sync_req_s @@ -1200,7 +1200,7 @@ struct ieee802154_sync_req_s * * Description: * Indicates the loss of synchronization with a coordinator. - * + * *****************************************************************************/ struct ieee802154_syncloss_ind_s @@ -1221,8 +1221,8 @@ struct ieee802154_syncloss_ind_s * Primitive: MLME-POLL.request * * Description: - * Prompts the device to request data from the coordinator. - * + * Prompts the device to request data from the coordinator. + * *****************************************************************************/ struct ieee802154_poll_req_s @@ -1241,7 +1241,7 @@ struct ieee802154_poll_req_s * * Description: * Reports the results of a request to poll the coordinator for data. - * + * *****************************************************************************/ struct ieee802154_poll_conf_s diff --git a/include/nuttx/wireless/ieee802154/ieee802154_radio.h b/include/nuttx/wireless/ieee802154/ieee802154_radio.h index e976ec2075..9a80658664 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_radio.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_radio.h @@ -162,18 +162,18 @@ struct ieee802154_netradio_s * identical members but with a different name. */ #ifdef CONFIG_IEEE802154_RANGING -#define IEEE802154_TXDESC_FIELDS \ +#define IEEE802154_TXDESC_FIELDS \ uint8_t handle; \ uint32_t timestamp; \ uint8_t status; #else -#define IEEE802154_TXDESC_FIELDS \ +#define IEEE802154_TXDESC_FIELDS \ uint8_t handle; \ uint32_t timestamp; \ uint8_t status; bool rng_rcvd; \ - uint32_t rng_counter_start; \ - uint32_t rng_counter_stop; \ + uint32_t rng_counter_start; \ + uint32_t rng_counter_stop; \ uint32_t rng_tracking_interval; \ uint32_t rng_offset;\ uint8_t rng_fom; diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index 1dbd3a65c2..39bdb2ec2a 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -1,1426 +1,1426 @@ -/**************************************************************************** - * wireless/ieee802154/mac802154.c - * - * Copyright (C) 2016 Sebastien Lorquet. All rights reserved. - * Author: Sebastien Lorquet - * - * 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 "mac802154.h" - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ -/* Configuration ************************************************************/ -/* If processing is not done at the interrupt level, then work queue support - * is required. - */ - -#if !defined(CONFIG_SCHED_WORKQUEUE) -# error Work queue support is required in this configuration (CONFIG_SCHED_WORKQUEUE) -#else - - /* Use the low priority work queue if possible */ - -# if defined(CONFIG_MAC802154_HPWORK) -# define MAC802154_WORK HPWORK -# elif defined(CONFIG_MAC802154_LPWORK) -# define MAC802154_WORK LPWORK -# else -# error Neither CONFIG_MAC802154_HPWORK nor CONFIG_MAC802154_LPWORK defined -# endif -#endif - -/**************************************************************************** - * Private Types - ****************************************************************************/ - -struct mac802154_trans_s -{ - /* Supports a singly linked list */ - - FAR struct mac802154_trans_s *flink; - FAR struct iob_s *frame; - uint8_t msdu_handle; - sem_t sem; -}; - -struct mac802154_unsec_mhr_s -{ - uint8_t length; - union - { - uint16_t frame_control; - uint8_t data[IEEE802154_MAX_UNSEC_MHR_OVERHEAD]; - } u; -}; - -struct mac802154_radiocb_s -{ - struct ieee802154_radiocb_s cb; - FAR struct ieee802154_privmac_s *priv; -}; - -/* The privmac structure holds the internal state of the MAC and is the - * underlying represention of the opaque MACHANDLE. It contains storage for - * the IEEE802.15.4 MIB attributes. - */ - -struct ieee802154_privmac_s -{ - FAR struct ieee802154_radio_s *radio; /* Contained IEEE802.15.4 radio dev */ - FAR const struct ieee802154_maccb_s *cb; /* Contained MAC callbacks */ - FAR struct mac802154_radiocb_s radiocb; /* Interface to bind to radio */ - - sem_t exclsem; /* Support exclusive access */ - - struct work_s tx_work; - struct work_s rx_work; - - /* Support a singly linked list of transactions that will be sent using the - * CSMA algorithm. On a non-beacon enabled PAN, these transactions will be - * sent whenever. On a beacon-enabled PAN, these transactions will be sent - * during the CAP of the Coordinator's superframe. - */ - - FAR struct mac802154_trans_s *csma_head; - FAR struct mac802154_trans_s *csma_tail; - - /* Support a singly linked list of transactions that will be sent indirectly. - * This list should only be used by a MAC acting as a coordinator. These - * transactions will stay here until the data is extracted by the destination - * device sending a Data Request MAC command or if too much time passes. This - * list should also be used to populate the address list of the outgoing - * beacon frame. - */ - - FAR struct mac802154_trans_s *indirect_head; - FAR struct mac802154_trans_s *indirect_tail; - - uint8_t txdesc_count; - struct ieee802154_txdesc_s txdesc[CONFIG_IEEE802154_NTXDESC]; - - /* Support a singly linked list of frames received */ - FAR struct iob_s *rxframes_head; - FAR struct iob_s *rxframes_tail; - - /* MAC PIB attributes, grouped to save memory */ - - /* Holds all address information (Extended, Short, and PAN ID) for the MAC. */ - - struct ieee802154_addr_s addr; - - /* Holds all address information (Extended, Short) for Coordinator */ - - struct ieee802154_addr_s coord_addr; - - /* The maximum number of symbols to wait for an acknowledgement frame to - * arrive following a transmitted data frame. [1] pg. 126 - * - * NOTE: This may be able to be a 16-bit or even an 8-bit number. I wasn't - * sure at the time what the range of reasonable values was. - */ - - uint32_t ack_wait_dur; - - /* The maximum time to wait either for a frame intended as a response to a - * data request frame or for a broadcast frame following a beacon with the - * Frame Pending field set to one. [1] pg. 127 - * - * NOTE: This may be able to be a 16-bit or even an 8-bit number. I wasn't - * sure at the time what the range of reasonable values was. - */ - - uint32_t max_frame_wait_time; - - /* The maximum time (in unit periods) that a transaction is stored by a - * coordinator and indicated in its beacon. - */ - - uint16_t trans_persist_time; - - /* Contents of beacon payload */ - - uint8_t beacon_payload[IEEE802154_MAX_BEACON_PAYLOAD_LENGTH]; - uint8_t beacon_payload_len; /* Length of beacon payload */ - - uint8_t batt_life_ext_periods; /* # of backoff periods during which rx is - * enabled after the IFS following beacon */ - - uint8_t bsn; /* Seq. num added to tx beacon frame */ - uint8_t dsn; /* Seq. num added to tx data or MAC frame */ - uint8_t max_retries; /* Max # of retries alloed after tx failure */ - - /* The maximum time, in multiples of aBaseSuperframeDuration, a device shall - * wait for a response command frame to be available following a request - * command frame. [1] 128. - */ - - uint8_t resp_wait_time; - - /* The total transmit duration (including PHY header and FCS) specified in - * symbols. [1] pg. 129. - */ - - uint32_t tx_total_dur; - - /* Start of 32-bit bitfield */ - - uint32_t is_assoc : 1; /* Are we associated to the PAN */ - uint32_t assoc_permit : 1; /* Are we allowing assoc. as a coord. */ - uint32_t auto_req : 1; /* Automatically send data req. if addr - * addr is in the beacon frame */ - - uint32_t batt_life_ext : 1; /* Is BLE enabled */ - uint32_t gts_permit : 1; /* Is PAN Coord. accepting GTS reqs. */ - uint32_t promiscuous_mode : 1; /* Is promiscuous mode on? */ - uint32_t ranging_supported : 1; /* Does MAC sublayer support ranging */ - uint32_t rx_when_idle : 1; /* Recvr. on during idle periods */ - uint32_t sec_enabled : 1; /* Does MAC sublayer have security en. */ - - uint32_t max_csma_backoffs : 3; /* Max num backoffs for CSMA algorithm - * before declaring ch access failure */ - - uint32_t beacon_order : 4; /* Freq. that beacon is transmitted */ - - uint32_t superframe_order : 4; /* Length of active portion of outgoing - * superframe, including the beacon */ - - /* The offset, measured is symbols, between the symbol boundary at which the - * MLME captures the timestamp of each transmitted and received frame, and - * the onset of the first symbol past the SFD, namely the first symbol of - * the frames [1] pg. 129. - */ - - uint32_t sync_symb_offset : 12; - - /* End of 32-bit bitfield */ - - /* Start of 32-bit bitfield */ - - uint32_t beacon_tx_time : 24; /* Time of last beacon transmit */ - uint32_t min_be : 4; /* Min value of backoff exponent (BE) */ - uint32_t max_be : 4; /* Max value of backoff exponent (BE) */ - - /* End of 32-bit bitfield */ - - /* Start of 32-bit bitfield */ - - uint32_t tx_ctrl_active_dur : 17; /* Duration for which tx is permitted to - * be active */ - uint32_t tx_ctrl_pause_dur : 1; /* Duration after tx before another tx is - * permitted. 0=2000, 1= 10000 */ - uint32_t timestamp_support : 1; /* Does MAC layer supports timestamping */ - uint32_t is_coord : 1; /* Is this device acting as coordinator */ - /* 12-bits remaining */ - - /* End of 32-bit bitfield. */ - - /* TODO: Add Security-related MAC PIB attributes */ -}; - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -static inline int mac802154_takesem(sem_t *sem); -#define mac802154_givesem(s) sem_post(s); - -static void mac802154_txdone_worker(FAR void *arg); -static void mac802154_rxframe_worker(FAR void *arg); - -/* Internal Functions */ - -static int mac802154_defaultmib(FAR struct ieee802154_privmac_s *priv); -static int mac802154_applymib(FAR struct ieee802154_privmac_s *priv); - -/* IEEE 802.15.4 PHY Interface OPs */ - -static int mac802154_poll_csma(FAR const struct ieee802154_radiocb_s *radiocb, - FAR struct ieee802154_txdesc_s *tx_desc, - FAR struct iob_s **frame); - -static int mac802154_poll_gts(FAR const struct ieee802154_radiocb_s *radiocb, - FAR struct ieee802154_txdesc_s *tx_desc, - FAR struct iob_s **frame); - -static void mac802154_txdone(FAR const struct ieee802154_radiocb_s *radiocb, - FAR const struct ieee802154_txdesc_s *tx_desc); - -static void mac802154_rxframe(FAR const struct ieee802154_radiocb_s *radiocb, - FAR const struct ieee802154_rxdesc_s *rx_desc, - FAR struct iob_s *frame); - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/* Map between ieee802154_addr_mode_e enum and actual address length */ - -static const uint8_t mac802154_addr_length[4] = {0, 0, 2, 8}; - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: mac802154_semtake - * - * Description: - * Acquire the semaphore used for access serialization. - * - ****************************************************************************/ - -static inline int mac802154_takesem(sem_t *sem) -{ - /* Take a count from the semaphore, possibly waiting */ - - if (sem_wait(sem) < 0) - { - /* EINTR is the only error that we expect */ - - int errcode = get_errno(); - DEBUGASSERT(errcode == EINTR); - return -errcode; - } - - return OK; -} - -/**************************************************************************** - * Name: mac802154_push_csma - * - * Description: - * Push a CSMA transaction onto the list - * - ****************************************************************************/ - -static void mac802154_push_csma(FAR struct ieee802154_privmac_s *priv, - FAR struct mac802154_trans_s *trans) -{ - /* Ensure the transactions forward link is NULL */ - - trans->flink = NULL; - - /* If the tail is not empty, make the transaction pointed to by the tail, - * point to the new transaction */ - - if (priv->csma_tail != NULL) - { - priv->csma_tail->flink = trans; - } - - /* Point the tail at the new transaction */ - - priv->csma_tail = trans; - - /* If the head is NULL, we need to point it at the transaction since there - * is only one transaction in the list at this point */ - - if (priv->csma_head == NULL) - { - priv->csma_head = trans; - } -} - -/**************************************************************************** - * Name: mac802154_pop_csma - * - * Description: - * Pop a CSMA transaction from the list - * - ****************************************************************************/ - -static FAR struct mac802154_trans_s * - mac802154_pop_csma(FAR struct ieee802154_privmac_s *priv) -{ - FAR struct mac802154_trans_s *trans; - - if (priv->csma_head == NULL) - { - return NULL; - } - - /* Get the transaction from the head of the list */ - - trans = priv->csma_head; - - /* Move the head pointer to the next transaction */ - - priv->csma_head = trans->flink; - - /* If the head is now NULL, the list is empty, so clear the tail too */ - - if (priv->csma_head == NULL) - { - priv->csma_tail = NULL; - } - - return trans; -} - -/**************************************************************************** - * Name: mac802154_defaultmib - * - * Description: - * Set the MIB to its default values. - * - ****************************************************************************/ - -static int mac802154_defaultmib(FAR struct ieee802154_privmac_s *priv) -{ - /* TODO: Set all MAC fields to default values */ - - return OK; -} - -/**************************************************************************** - * Name: mac802154_applymib - * - * Description: - * Some parts of the MIB must be sent to the radio device. This routine - * calls the radio device routines to store the related parameters in the - * radio driver. It must be called each time a MIB parameter is changed. - * - ****************************************************************************/ - -static int mac802154_applymib(FAR struct ieee802154_privmac_s *priv) -{ - return OK; -} - -/**************************************************************************** - * Name: mac802154_poll_csma - * - * Description: - * Called from the radio driver through the callback struct. This function is - * called when the radio has room for another CSMA transaction. If the MAC - * layer has a CSMA transaction, it copies it into the supplied buffer and - * returns the length. A descriptor is also populated with the transaction. - * - ****************************************************************************/ - -static int mac802154_poll_csma(FAR const struct ieee802154_radiocb_s *radiocb, - FAR struct ieee802154_txdesc_s *tx_desc, - FAR struct iob_s **frame) -{ - FAR struct mac802154_radiocb_s *cb = - (FAR struct mac802154_radiocb_s *)radiocb; - FAR struct ieee802154_privmac_s *priv; - FAR struct mac802154_trans_s *trans; - - DEBUGASSERT(cb != NULL && cb->priv != NULL); - priv = cb->priv; - - /* Get exclusive access to the driver structure. We don't care about any - * signals so if we see one, just go back to trying to get access again. - */ - - while (mac802154_takesem(&priv->exclsem) != 0); - - /* Check to see if there are any CSMA transactions waiting */ - - trans = mac802154_pop_csma(priv); - mac802154_givesem(&priv->exclsem); - - if (trans != NULL) - { - /* Setup the transmit descriptor */ - - tx_desc->handle = trans->msdu_handle; - - *frame = trans->frame; - - /* Now that we've passed off the data, notify the waiting thread. - * NOTE: The transaction was allocated on the waiting thread's stack so - * it will be automatically deallocated when that thread awakens and - * returns. */ - - sem_post(&trans->sem); - return (trans->frame->io_len); - } - - return 0; -} - -/**************************************************************************** - * Name: mac802154_poll_gts - * - * Description: - * Called from the radio driver through the callback struct. This function is - * called when the radio has room for another GTS transaction. If the MAC - * layer has a GTS transaction, it copies it into the supplied buffer and - * returns the length. A descriptor is also populated with the transaction. - * - ****************************************************************************/ - -static int mac802154_poll_gts(FAR const struct ieee802154_radiocb_s *radiocb, - FAR struct ieee802154_txdesc_s *tx_desc, - FAR struct iob_s **frame) -{ - FAR struct mac802154_radiocb_s *cb = - (FAR struct mac802154_radiocb_s *)radiocb; - FAR struct ieee802154_privmac_s *priv; - FAR struct mac802154_trans_s *trans; - int ret = 0; - - DEBUGASSERT(cb != NULL && cb->priv != NULL); - priv = cb->priv; - - /* Get exclusive access to the driver structure. We don't care about any - * signals so if we see one, just go back to trying to get access again. - */ - - while (mac802154_takesem(&priv->exclsem) != 0); - -#warning Missing logic. - - mac802154_givesem(&priv->exclsem); - - return 0; -} - -/**************************************************************************** - * Name: mac802154_txdone - * - * Description: - * Called from the radio driver through the callback struct. This function is - * called when the radio has completed a transaction. The txdesc passed gives - * provides information about the completed transaction including the original - * handle provided when the transaction was created and the status of the - * transaction. This function copies the descriptor and schedules work to - * handle the transaction without blocking the radio. - * - ****************************************************************************/ - -static void mac802154_txdone(FAR const struct ieee802154_radiocb_s *radiocb, - FAR const struct ieee802154_txdesc_s *tx_desc) -{ - FAR struct mac802154_radiocb_s *cb = - (FAR struct mac802154_radiocb_s *)radiocb; - FAR struct ieee802154_privmac_s *priv; - - DEBUGASSERT(cb != NULL && cb->priv != NULL); - priv = cb->priv; - - /* Get exclusive access to the driver structure. We don't care about any - * signals so if we see one, just go back to trying to get access again. - */ - - while (mac802154_takesem(&priv->exclsem) != 0); - - /* Check to see if there is an available tx descriptor slot. If there is - * not we simply drop the notification */ - - if (priv->txdesc_count < CONFIG_IEEE802154_NTXDESC) - { - /* Copy the txdesc over and link it into our list */ - - memcpy(&priv->txdesc[priv->txdesc_count++], tx_desc, - sizeof(struct ieee802154_txdesc_s)); - } - else - { - wlinfo("MAC802154: No room for TX Desc.\n"); - } - - mac802154_givesem(&priv->exclsem); - - /* Schedule work with the work queue to process the completion further */ - - if (work_available(&priv->tx_work)) - { - work_queue(MAC802154_WORK, &priv->tx_work, mac802154_txdone_worker, - (FAR void *)priv, 0); - } -} - -/**************************************************************************** - * Name: mac802154_txdone_worker - * - * Description: - * Worker function scheduled from mac802154_txdone. This function pops any - * TX descriptors off of the list and calls the next highest layers callback - * to inform the layer of the completed transaction and the status of it. - * - ****************************************************************************/ - -static void mac802154_txdone_worker(FAR void *arg) -{ - FAR struct ieee802154_privmac_s *priv = - (FAR struct ieee802154_privmac_s *)arg; - int i = 0; - - /* Get exclusive access to the driver structure. We don't care about any - * signals so if we see one, just go back to trying to get access again. - */ - - while (mac802154_takesem(&priv->exclsem) != 0); - - /* For each pending TX descriptor, send an application callback */ - - for (i = 0; i < priv->txdesc_count; i++) - { - priv->cb->mcps_notify(priv->cb, IEEE802154_NOTIFY_CONF_DATA, - (FAR const union ieee802154_mcps_notify_u *) &priv->txdesc[i]); - } - - /* We've handled all the descriptors and no further desc could have been added - * since we have the struct locked */ - - priv->txdesc_count = 0; - - mac802154_givesem(&priv->exclsem); -} - -/**************************************************************************** - * Name: mac802154_rxframe - * - * Description: - * Called from the radio driver through the callback struct. This function is - * called when the radio has received a frame. The frame is passed in an iob, - * so that we can free it when we are done processing. A pointer to the RX - * descriptor is passed along with the iob, but it must be copied here as it - * is allocated directly on the caller's stack. We simply link the frame, - * copy the RX descriptor, and schedule a worker to process the frame later so - * that we do not hold up the radio. - * - ****************************************************************************/ - -static void mac802154_rxframe(FAR const struct ieee802154_radiocb_s *radiocb, - FAR const struct ieee802154_rxdesc_s *rx_desc, - FAR struct iob_s *frame) -{ - FAR struct mac802154_radiocb_s *cb = - (FAR struct mac802154_radiocb_s *)radiocb; - FAR struct ieee802154_privmac_s *priv; - FAR struct ieee802154_rxdesc_s *desc; - - DEBUGASSERT(cb != NULL && cb->priv != NULL); - priv = cb->priv; - - /* Get exclusive access to the driver structure. We don't care about any - * signals so if we see one, just go back to trying to get access again. - */ - - while (mac802154_takesem(&priv->exclsem) != 0); - - /* TODO: Copy the frame descriptor to some type of list */ - - /* Push the iob onto the tail of the frame list for processing */ - - priv->rxframes_tail->io_flink = frame; - priv->rxframes_tail = frame; - - mac802154_givesem(&priv->exclsem); - - /* Schedule work with the work queue to process the completion further */ - - if (work_available(&priv->rx_work)) - { - work_queue(MAC802154_WORK, &priv->rx_work, mac802154_rxframe_worker, - (FAR void *)priv, 0); - } -} - -/**************************************************************************** - * Name: mac802154_rxframe_worker - * - * Description: - * Worker function scheduled from mac802154_rxframe. This function processes - * any frames in the list. Frames intended to be consumed by the MAC layer - * will not produce any callbacks to the next highest layer. Frames intended - * for the application layer will be forwarded to them. - * - ****************************************************************************/ - -static void mac802154_rxframe_worker(FAR void *arg) -{ - FAR struct ieee802154_privmac_s *priv = - (FAR struct ieee802154_privmac_s *)arg; - - /* The radio layer is responsible for handling all ACKs and retries. If for - * some reason an ACK gets here, just throw it out. - */ -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: mac802154_create - * - * Description: - * Create a 802.15.4 MAC device from a 802.15.4 compatible radio device. - * - * The returned MAC structure should be passed to either the next highest - * layer in the network stack, or registered with a mac802154dev character - * or network drivers. In any of these scenarios, the next highest layer - * should register a set of callbacks with the MAC layer by setting the - * mac->cbs member. - * - * NOTE: This API does not create any device accessible to userspace. If - * you want to call these APIs from userspace, you have to wrap your mac - * in a character device via mac802154_device.c. - * - * Input Parameters: - * radiodev - an instance of an IEEE 802.15.4 radio - * - * Returned Value: - * An opaque reference to the MAC state data. - * - ****************************************************************************/ - -MACHANDLE mac802154_create(FAR struct ieee802154_radio_s *radiodev) -{ - FAR struct ieee802154_privmac_s *mac; - FAR struct ieee802154_radiocb_s *radiocb; - - /* Allocate object */ - - mac = (FAR struct ieee802154_privmac_s *) - kmm_zalloc(sizeof(struct ieee802154_privmac_s)); - - if (mac == NULL) - { - return NULL; - } - - /* Allow exclusive access to the privmac struct */ - - sem_init(&mac->exclsem, 0, 1); - - /* Initialize fields */ - - mac->radio = radiodev; - - mac802154_defaultmib(mac); - mac802154_applymib(mac); - - /* Initialize the Radio callbacks */ - - mac->radiocb.priv = mac; - - radiocb = &mac->radiocb.cb; - radiocb->poll_csma = mac802154_poll_csma; - radiocb->poll_gts = mac802154_poll_gts; - radiocb->txdone = mac802154_txdone; - radiocb->rxframe = mac802154_rxframe; - - /* Bind our callback structure */ - - radiodev->ops->bind(radiodev, &mac->radiocb.cb); - - return (MACHANDLE)mac; -} - -/**************************************************************************** - * Name: mac802154_bind - * - * Description: - * Bind the MAC callback table to the MAC state. - * - * Parameters: - * mac - Reference to the MAC driver state structure - * cb - MAC callback operations - * - * Returned Value: - * OK on success; Negated errno on failure. - * - ****************************************************************************/ - -int mac802154_bind(MACHANDLE mac, FAR const struct ieee802154_maccb_s *cb) -{ - FAR struct ieee802154_privmac_s *priv = - (FAR struct ieee802154_privmac_s *)mac; - - priv->cb = cb; - return OK; -} - -/**************************************************************************** - * Name: mac802154_ioctl - * - * Description: - * Handle MAC and radio IOCTL commands directed to the MAC. - * - * Parameters: - * mac - Reference to the MAC driver state structure - * cmd - The IOCTL command - * arg - The argument for the IOCTL command - * - * Returned Value: - * OK on success; Negated errno on failure. - * - ****************************************************************************/ - -int mac802154_ioctl(MACHANDLE mac, int cmd, unsigned long arg) -{ - FAR struct ieee802154_privmac_s *priv = - (FAR struct ieee802154_privmac_s *)mac; - int ret = -EINVAL; - - DEBUGASSERT(priv != NULL); - - /* Check for IOCTLs aimed at the IEEE802.15.4 MAC layer */ - - if (_MAC802154IOCVALID(cmd)) - { - /* Handle the MAC IOCTL command */ -#warning Missing logic - } - - /* No, other IOCTLs must be aimed at the IEEE802.15.4 radio layer */ - - else - { - DEBUGASSERT(priv->radio != NULL && - priv->radio->ops != NULL && - priv->radio->ops->ioctl != NULL); - - ret = priv->radio->ops->ioctl(priv->radio, cmd, arg); - } - - return ret; -} - -/**************************************************************************** - * MAC Interface Operations - ****************************************************************************/ - -/**************************************************************************** - * Name: mac802154_get_mhrlen - * - * Description: - * Calculate the MAC header length given the frame meta-data. - * - ****************************************************************************/ - -int mac802154_get_mhrlen(MACHANDLE mac, - FAR struct ieee802154_frame_meta_s *meta) -{ - FAR struct ieee802154_privmac_s *priv = - (FAR struct ieee802154_privmac_s *)mac; - int ret = 3; /* Always frame control (2 bytes) and seq. num (1 byte) */ - - /* Check to make sure both the dest address and the source address are not set - * to NONE */ - - if (meta->dest_addr.mode == IEEE802154_ADDRMODE_NONE && - meta->src_addr_mode == IEEE802154_ADDRMODE_NONE) - { - return -EINVAL; - } - - /* The source address can only be set to NONE if the device is the PAN coord */ - - if (meta->src_addr_mode == IEEE802154_ADDRMODE_NONE && !priv->is_coord) - { - return -EINVAL; - } - - /* Add the destination address length */ - - ret += mac802154_addr_length[meta->dest_addr.mode]; - - /* Add the source address length */ - - ret += mac802154_addr_length[ meta->src_addr_mode]; - - /* If both destination and source addressing information is present, the MAC - * sublayer shall compare the destination and source PAN identifiers. - * [1] pg. 41. - */ - - if (meta->src_addr_mode != IEEE802154_ADDRMODE_NONE && - meta->dest_addr.mode != IEEE802154_ADDRMODE_NONE) - { - /* If the PAN identifiers are identical, the PAN ID Compression field - * shall be set to one, and the source PAN identifier shall be omitted - * from the transmitted frame. [1] pg. 41. - */ - - if (meta->dest_addr.panid == priv->addr.panid) - { - ret += 2; /* 2 bytes for destination PAN ID */ - return ret; - } - } - - /* If we are here, PAN ID compression is off, so include the dest and source - * PAN ID if the respective address is included - */ - - if (meta->src_addr_mode != IEEE802154_ADDRMODE_NONE) - { - ret += 2; /* 2 bytes for source PAN ID */ - } - - if (meta->dest_addr.mode != IEEE802154_ADDRMODE_NONE) - { - ret += 2; /* 2 bytes for destination PAN ID */ - } - - return ret; -} - -/**************************************************************************** - * Name: mac802154_req_data - * - * Description: - * The MCPS-DATA.request primitive requests the transfer of a data SPDU - * (i.e., MSDU) from a local SSCS entity to a single peer SSCS entity. - * Confirmation is returned via the - * struct ieee802154_maccb_s->conf_data callback. - * - ****************************************************************************/ - -int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) -{ - FAR struct ieee802154_privmac_s *priv = - (FAR struct ieee802154_privmac_s *)mac; - FAR struct mac802154_trans_s trans; - FAR struct ieee802154_frame_meta_s *meta = req->meta; - uint16_t *frame_ctrl; - uint8_t mhr_len = 3; /* Start assuming frame control and seq. num */ - int ret; - - /* Check the required frame size */ - - if (req->frame->io_len > IEEE802154_MAX_PHY_PACKET_SIZE) - { - return -E2BIG; - } - - /* Cast the first two bytes of the IOB to a uint16_t frame control field */ - - frame_ctrl = (uint16_t *)&req->frame->io_data[0]; - - /* Ensure we start with a clear frame control field */ - - *frame_ctrl = 0; - - /* Set the frame type to Data */ - - *frame_ctrl |= IEEE802154_FRAME_DATA << IEEE802154_FRAMECTRL_SHIFT_FTYPE; - - /* If the msduLength is greater than aMaxMACSafePayloadSize, the MAC - * sublayer will set the Frame Version to one. [1] pg. 118. - */ - - if (meta->msdu_length > IEEE802154_MAX_SAFE_MAC_PAYLOAD_SIZE) - { - *frame_ctrl |= IEEE802154_FRAMECTRL_VERSION; - } - - /* If the TXOptions parameter specifies that an acknowledged transmission - * is required, the AR field will be set appropriately, as described in - * 5.1.6.4 [1] pg. 118. - */ - - *frame_ctrl |= (meta->msdu_flags.ack_tx << IEEE802154_FRAMECTRL_SHIFT_ACKREQ); - - /* If the destination address is present, copy the PAN ID and one of the - * addresses, depending on mode, into the MHR. - */ - - if (meta->dest_addr.mode != IEEE802154_ADDRMODE_NONE) - { - memcpy(&req->frame->io_data[mhr_len], &meta->dest_addr.panid, 2); - mhr_len += 2; - - if (meta->dest_addr.mode == IEEE802154_ADDRMODE_SHORT) - { - memcpy(&req->frame->io_data[mhr_len], &meta->dest_addr.saddr, 2); - mhr_len += 2; - } - else if (meta->dest_addr.mode == IEEE802154_ADDRMODE_EXTENDED) - { - memcpy(&req->frame->io_data[mhr_len], &meta->dest_addr.eaddr, 8); - mhr_len += 8; - } - } - - /* Set the destination addr mode inside the frame control field */ - - *frame_ctrl |= (meta->dest_addr.mode << IEEE802154_FRAMECTRL_SHIFT_DADDR); - - /* From this point on, we need exclusive access to the privmac struct */ - - ret = mac802154_takesem(&priv->exclsem); - if (ret < 0) - { - wlerr("ERROR: mac802154_takesem failed: %d\n", ret); - return ret; - } - - /* If both destination and source addressing information is present, the MAC - * sublayer shall compare the destination and source PAN identifiers. - * [1] pg. 41. - */ - - if (meta->src_addr_mode != IEEE802154_ADDRMODE_NONE && - meta->dest_addr.mode != IEEE802154_ADDRMODE_NONE) - { - /* If the PAN identifiers are identical, the PAN ID Compression field - * shall be set to one, and the source PAN identifier shall be omitted - * from the transmitted frame. [1] pg. 41. - */ - - if (meta->dest_addr.panid == priv->addr.panid) - { - *frame_ctrl |= IEEE802154_FRAMECTRL_PANIDCOMP; - } - } - - if (meta->src_addr_mode != IEEE802154_ADDRMODE_NONE) - { - /* If the destination address is not included, or if PAN ID Compression - * is off, we need to include the Source PAN ID. - */ - - if ((meta->dest_addr.mode == IEEE802154_ADDRMODE_NONE) || - (*frame_ctrl & IEEE802154_FRAMECTRL_PANIDCOMP)) - { - memcpy(&req->frame->io_data[mhr_len], &priv->addr.panid, 2); - mhr_len += 2; - } - - if (meta->src_addr_mode == IEEE802154_ADDRMODE_SHORT) - { - memcpy(&req->frame->io_data[mhr_len], &priv->addr.saddr, 2); - mhr_len += 2; - } - else if (meta->src_addr_mode == IEEE802154_ADDRMODE_EXTENDED) - { - memcpy(&req->frame->io_data[mhr_len], &priv->addr.eaddr, 8); - mhr_len += 8; - } - } - - /* Set the source addr mode inside the frame control field */ - - *frame_ctrl |= (meta->src_addr_mode << IEEE802154_FRAMECTRL_SHIFT_SADDR); - - /* Each time a data or a MAC command frame is generated, the MAC sublayer - * shall copy the value of macDSN into the Sequence Number field of the MHR - * of the outgoing frame and then increment it by one. [1] pg. 40. - */ - - req->frame->io_data[2] = priv->dsn++; - - /* The MAC header we just created must never have exceeded where the app - * data starts. This should never happen since the offset should have - * been set via the same logic to calculate the header length as the logic - * here that created the header - */ - - DEBUGASSERT(mhr_len == req->frame->io_offset); - - req->frame->io_offset = 0; /* Set the offset to 0 to include the header */ - - /* Setup our transaction */ - - trans.msdu_handle = meta->msdu_handle; - trans.frame = req->frame; - sem_init(&trans.sem, 0, 1); - - /* If the TxOptions parameter specifies that a GTS transmission is required, - * the MAC sublayer will determine whether it has a valid GTS as described - * 5.1.7.3. If a valid GTS could not be found, the MAC sublayer will discard - * the MSDU. If a valid GTS was found, the MAC sublayer will defer, if - * necessary, until the GTS. If the TxOptions parameter specifies that a GTS - * transmission is not required, the MAC sublayer will transmit the MSDU using - * either slotted CSMA-CA in the CAP for a beacon-enabled PAN or unslotted - * CSMA-CA for a nonbeacon-enabled PAN. Specifying a GTS transmission in the - * TxOptions parameter overrides an indirect transmission request. - * [1] pg. 118. - */ - - if (meta->msdu_flags.gts_tx) - { - /* TODO: Support GTS transmission. This should just change where we link - * the transaction. Instead of going in the CSMA transaction list, it - * should be linked to the GTS' transaction list. We'll need to check if - * the GTS is valid, and then find the GTS, before linking. Note, we also - * don't have to try and kick-off any transmission here. - */ - - return -ENOTSUP; - } - else - { - /* If the TxOptions parameter specifies that an indirect transmission is - * required and this primitive is received by the MAC sublayer of a - * coordinator, the data frame is sent using indirect transmission, as - * described in 5.1.5 and 5.1.6.3. [1] - */ - - if (meta->msdu_flags.indirect_tx) - { - /* If the TxOptions parameter specifies that an indirect transmission - * is required and if the device receiving this primitive is not a - * coordinator, the destination address is not present, or the - * TxOptions parameter also specifies a GTS transmission, the indirect - * transmission option will be ignored. [1] - */ - - if (priv->is_coord && meta->dest_addr.mode != IEEE802154_ADDRMODE_NONE) - { - /* Link the transaction into the indirect_trans list */ - - } - else - { - /* Override the setting since it wasn't valid */ - - meta->msdu_flags.indirect_tx = 0; - } - } - - /* If this is a direct transmission not during a GTS */ - - if (!meta->msdu_flags.indirect_tx) - { - /* Link the transaction into the CSMA transaction list */ - - mac802154_push_csma(priv, &trans); - - /* We no longer need to have the MAC layer locked. */ - - mac802154_givesem(&priv->exclsem); - - /* Notify the radio driver that there is data available */ - - priv->radio->ops->txnotify_csma(priv->radio); - - sem_wait(&trans.sem); - } - } - - sem_destroy(&trans.sem); - return OK; -} - -/**************************************************************************** - * Name: mac802154_req_purge - * - * Description: - * The MCPS-PURGE.request primitive allows the next higher layer to purge - * an MSDU from the transaction queue. Confirmation is returned via - * the struct ieee802154_maccb_s->conf_purge callback. - * - ****************************************************************************/ - -int mac802154_req_purge(MACHANDLE mac, FAR struct ieee802154_purge_req_s *req) -{ - FAR struct ieee802154_privmac_s *priv = - (FAR struct ieee802154_privmac_s *)mac; - return -ENOTTY; -} - -/**************************************************************************** - * Name: mac802154_req_associate - * - * Description: - * The MLME-ASSOCIATE.request primitive allows a device to request an - * association with a coordinator. Confirmation is returned via the - * struct ieee802154_maccb_s->conf_associate callback. - * - ****************************************************************************/ - -int mac802154_req_associate(MACHANDLE mac, - FAR struct ieee802154_assoc_req_s *req) -{ - FAR struct ieee802154_privmac_s *priv = - (FAR struct ieee802154_privmac_s *)mac; - - /* Set the channel of the PHY layer */ - - /* Set the channel page of the PHY layer */ - - /* Set the macPANId */ - - /* Set either the macCoordExtendedAddress and macCoordShortAddress - * depending on the CoordAddrMode in the primitive. - */ - - if (req->coord_addr.mode == IEEE802154_ADDRMODE_EXTENDED) - { - - } - else if (req->coord_addr.mode == IEEE802154_ADDRMODE_EXTENDED) - { - - } - else - { - return -EINVAL; - } - - return -ENOTTY; -} - -/**************************************************************************** - * Name: mac802154_req_disassociate - * - * Description: - * The MLME-DISASSOCIATE.request primitive is used by an associated device to - * notify the coordinator of its intent to leave the PAN. It is also used by - * the coordinator to instruct an associated device to leave the PAN. - * Confirmation is returned via the - * struct ieee802154_maccb_s->conf_disassociate callback. - * - ****************************************************************************/ - -int mac802154_req_disassociate(MACHANDLE mac, - FAR struct ieee802154_disassoc_req_s *req) -{ - FAR struct ieee802154_privmac_s *priv = - (FAR struct ieee802154_privmac_s *)mac; - return -ENOTTY; -} - -/**************************************************************************** - * Name: mac802154_req_get - * - * Description: - * The MLME-GET.request primitive requests information about a given PIB - * attribute. Actual data is returned via the - * struct ieee802154_maccb_s->conf_get callback. - * - ****************************************************************************/ - -int mac802154_req_get(MACHANDLE mac, FAR struct ieee802154_get_req_s *req) -{ - FAR struct ieee802154_privmac_s *priv = - (FAR struct ieee802154_privmac_s *)mac; - return -ENOTTY; -} - -/**************************************************************************** - * Name: mac802154_req_gts - * - * Description: - * The MLME-GTS.request primitive allows a device to send a request to the PAN - * coordinator to allocate a new GTS or to deallocate an existing GTS. - * Confirmation is returned via the - * struct ieee802154_maccb_s->conf_gts callback. - * - ****************************************************************************/ - -int mac802154_req_gts(MACHANDLE mac, FAR struct ieee802154_gts_req_s *req) -{ - FAR struct ieee802154_privmac_s *priv = - (FAR struct ieee802154_privmac_s *)mac; - return -ENOTTY; -} - -/**************************************************************************** - * Name: mac802154_req_reset - * - * Description: - * The MLME-RESET.request primitive allows the next higher layer to request - * that the MLME performs a reset operation. Confirmation is returned via - * the struct ieee802154_maccb_s->conf_reset callback. - * - ****************************************************************************/ - -int mac802154_req_reset(MACHANDLE mac, FAR struct ieee802154_reset_req_s *req) -{ - FAR struct ieee802154_privmac_s * priv = - (FAR struct ieee802154_privmac_s *) mac; - return -ENOTTY; -} - -/**************************************************************************** - * Name: mac802154_req_rxenable - * - * Description: - * The MLME-RX-ENABLE.request primitive allows the next higher layer to - * request that the receiver is enable for a finite period of time. - * Confirmation is returned via the - * struct ieee802154_maccb_s->conf_rxenable callback. - * - ****************************************************************************/ - -int mac802154_req_rxenable(MACHANDLE mac, - FAR struct ieee802154_rxenable_req_s *req) -{ - FAR struct ieee802154_privmac_s * priv = - (FAR struct ieee802154_privmac_s *)mac; - return -ENOTTY; -} - -/**************************************************************************** - * Name: mac802154_req_scan - * - * Description: - * The MLME-SCAN.request primitive is used to initiate a channel scan over a - * given list of channels. A device can use a channel scan to measure the - * energy on the channel, search for the coordinator with which it associated, - * or search for all coordinators transmitting beacon frames within the POS of - * the scanning device. Scan results are returned - * via MULTIPLE calls to the struct ieee802154_maccb_s->conf_scan callback. - * This is a difference with the official 802.15.4 specification, implemented - * here to save memory. - * - ****************************************************************************/ - -int mac802154_req_scan(MACHANDLE mac, FAR struct ieee802154_scan_req_s *req) -{ - FAR struct ieee802154_privmac_s *priv = - (FAR struct ieee802154_privmac_s *)mac; - return -ENOTTY; -} - -/**************************************************************************** - * Name: mac802154_req_set - * - * Description: - * The MLME-SET.request primitive attempts to write the given value to the - * indicated MAC PIB attribute. Confirmation is returned via the - * struct ieee802154_maccb_s->conf_set callback. - * - ****************************************************************************/ - -int mac802154_req_set(MACHANDLE mac, FAR struct ieee802154_set_req_s *req) -{ - FAR struct ieee802154_privmac_s *priv = - (FAR struct ieee802154_privmac_s *)mac; - return -ENOTTY; -} - -/**************************************************************************** - * Name: mac802154_req_start - * - * Description: - * The MLME-START.request primitive makes a request for the device to start - * using a new superframe configuration. Confirmation is returned - * via the struct ieee802154_maccb_s->conf_start callback. - * - ****************************************************************************/ - -int mac802154_req_start(MACHANDLE mac, FAR struct ieee802154_start_req_s *req) -{ - FAR struct ieee802154_privmac_s *priv = - (FAR struct ieee802154_privmac_s *)mac; - return -ENOTTY; -} - -/**************************************************************************** - * Name: mac802154_req_sync - * - * Description: - * The MLME-SYNC.request primitive requests to synchronize with the - * coordinator by acquiring and, if specified, tracking its beacons. - * Confirmation is returned via the - * struct ieee802154_maccb_s->int_commstatus callback. TOCHECK. - * - ****************************************************************************/ - -int mac802154_req_sync(MACHANDLE mac, FAR struct ieee802154_sync_req_s *req) -{ - FAR struct ieee802154_privmac_s *priv = - (FAR struct ieee802154_privmac_s *)mac; - return -ENOTTY; -} - -/**************************************************************************** - * Name: mac802154_req_poll - * - * Description: - * The MLME-POLL.request primitive prompts the device to request data from - * the coordinator. Confirmation is returned via the - * struct ieee802154_maccb_s->conf_poll callback, followed by a - * struct ieee802154_maccb_s->ind_data callback. - * - ****************************************************************************/ - -int mac802154_req_poll(MACHANDLE mac, FAR struct ieee802154_poll_req_s *req) -{ - FAR struct ieee802154_privmac_s *priv = - (FAR struct ieee802154_privmac_s *)mac; - return -ENOTTY; -} - -/**************************************************************************** - * Name: mac802154_rsp_associate - * - * Description: - * The MLME-ASSOCIATE.response primitive is used to initiate a response to - * an MLME-ASSOCIATE.indication primitive. - * - ****************************************************************************/ - -int mac802154_rsp_associate(MACHANDLE mac, - FAR struct ieee802154_assoc_resp_s *resp) -{ - FAR struct ieee802154_privmac_s *priv = - (FAR struct ieee802154_privmac_s *)mac; - return -ENOTTY; -} - -/**************************************************************************** - * Name: mac802154_rsp_orphan - * - * Description: - * The MLME-ORPHAN.response primitive allows the next higher layer of a - * coordinator to respond to the MLME-ORPHAN.indication primitive. - * - ****************************************************************************/ - -int mac802154_rsp_orphan(MACHANDLE mac, - FAR struct ieee802154_orphan_resp_s *resp) -{ - FAR struct ieee802154_privmac_s *priv = - (FAR struct ieee802154_privmac_s *)mac; - return -ENOTTY; -} +/**************************************************************************** + * wireless/ieee802154/mac802154.c + * + * Copyright (C) 2016 Sebastien Lorquet. All rights reserved. + * Author: Sebastien Lorquet + * + * 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 "mac802154.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ +/* Configuration ************************************************************/ +/* If processing is not done at the interrupt level, then work queue support + * is required. + */ + +#if !defined(CONFIG_SCHED_WORKQUEUE) +# error Work queue support is required in this configuration (CONFIG_SCHED_WORKQUEUE) +#else + + /* Use the low priority work queue if possible */ + +# if defined(CONFIG_MAC802154_HPWORK) +# define MAC802154_WORK HPWORK +# elif defined(CONFIG_MAC802154_LPWORK) +# define MAC802154_WORK LPWORK +# else +# error Neither CONFIG_MAC802154_HPWORK nor CONFIG_MAC802154_LPWORK defined +# endif +#endif + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct mac802154_trans_s +{ + /* Supports a singly linked list */ + + FAR struct mac802154_trans_s *flink; + FAR struct iob_s *frame; + uint8_t msdu_handle; + sem_t sem; +}; + +struct mac802154_unsec_mhr_s +{ + uint8_t length; + union + { + uint16_t frame_control; + uint8_t data[IEEE802154_MAX_UNSEC_MHR_OVERHEAD]; + } u; +}; + +struct mac802154_radiocb_s +{ + struct ieee802154_radiocb_s cb; + FAR struct ieee802154_privmac_s *priv; +}; + +/* The privmac structure holds the internal state of the MAC and is the + * underlying represention of the opaque MACHANDLE. It contains storage for + * the IEEE802.15.4 MIB attributes. + */ + +struct ieee802154_privmac_s +{ + FAR struct ieee802154_radio_s *radio; /* Contained IEEE802.15.4 radio dev */ + FAR const struct ieee802154_maccb_s *cb; /* Contained MAC callbacks */ + FAR struct mac802154_radiocb_s radiocb; /* Interface to bind to radio */ + + sem_t exclsem; /* Support exclusive access */ + + struct work_s tx_work; + struct work_s rx_work; + + /* Support a singly linked list of transactions that will be sent using the + * CSMA algorithm. On a non-beacon enabled PAN, these transactions will be + * sent whenever. On a beacon-enabled PAN, these transactions will be sent + * during the CAP of the Coordinator's superframe. + */ + + FAR struct mac802154_trans_s *csma_head; + FAR struct mac802154_trans_s *csma_tail; + + /* Support a singly linked list of transactions that will be sent indirectly. + * This list should only be used by a MAC acting as a coordinator. These + * transactions will stay here until the data is extracted by the destination + * device sending a Data Request MAC command or if too much time passes. This + * list should also be used to populate the address list of the outgoing + * beacon frame. + */ + + FAR struct mac802154_trans_s *indirect_head; + FAR struct mac802154_trans_s *indirect_tail; + + uint8_t txdesc_count; + struct ieee802154_txdesc_s txdesc[CONFIG_IEEE802154_NTXDESC]; + + /* Support a singly linked list of frames received */ + FAR struct iob_s *rxframes_head; + FAR struct iob_s *rxframes_tail; + + /* MAC PIB attributes, grouped to save memory */ + + /* Holds all address information (Extended, Short, and PAN ID) for the MAC. */ + + struct ieee802154_addr_s addr; + + /* Holds all address information (Extended, Short) for Coordinator */ + + struct ieee802154_addr_s coord_addr; + + /* The maximum number of symbols to wait for an acknowledgement frame to + * arrive following a transmitted data frame. [1] pg. 126 + * + * NOTE: This may be able to be a 16-bit or even an 8-bit number. I wasn't + * sure at the time what the range of reasonable values was. + */ + + uint32_t ack_wait_dur; + + /* The maximum time to wait either for a frame intended as a response to a + * data request frame or for a broadcast frame following a beacon with the + * Frame Pending field set to one. [1] pg. 127 + * + * NOTE: This may be able to be a 16-bit or even an 8-bit number. I wasn't + * sure at the time what the range of reasonable values was. + */ + + uint32_t max_frame_wait_time; + + /* The maximum time (in unit periods) that a transaction is stored by a + * coordinator and indicated in its beacon. + */ + + uint16_t trans_persist_time; + + /* Contents of beacon payload */ + + uint8_t beacon_payload[IEEE802154_MAX_BEACON_PAYLOAD_LENGTH]; + uint8_t beacon_payload_len; /* Length of beacon payload */ + + uint8_t batt_life_ext_periods; /* # of backoff periods during which rx is + * enabled after the IFS following beacon */ + + uint8_t bsn; /* Seq. num added to tx beacon frame */ + uint8_t dsn; /* Seq. num added to tx data or MAC frame */ + uint8_t max_retries; /* Max # of retries alloed after tx failure */ + + /* The maximum time, in multiples of aBaseSuperframeDuration, a device shall + * wait for a response command frame to be available following a request + * command frame. [1] 128. + */ + + uint8_t resp_wait_time; + + /* The total transmit duration (including PHY header and FCS) specified in + * symbols. [1] pg. 129. + */ + + uint32_t tx_total_dur; + + /* Start of 32-bit bitfield */ + + uint32_t is_assoc : 1; /* Are we associated to the PAN */ + uint32_t assoc_permit : 1; /* Are we allowing assoc. as a coord. */ + uint32_t auto_req : 1; /* Automatically send data req. if addr + * addr is in the beacon frame */ + + uint32_t batt_life_ext : 1; /* Is BLE enabled */ + uint32_t gts_permit : 1; /* Is PAN Coord. accepting GTS reqs. */ + uint32_t promiscuous_mode : 1; /* Is promiscuous mode on? */ + uint32_t ranging_supported : 1; /* Does MAC sublayer support ranging */ + uint32_t rx_when_idle : 1; /* Recvr. on during idle periods */ + uint32_t sec_enabled : 1; /* Does MAC sublayer have security en. */ + + uint32_t max_csma_backoffs : 3; /* Max num backoffs for CSMA algorithm + * before declaring ch access failure */ + + uint32_t beacon_order : 4; /* Freq. that beacon is transmitted */ + + uint32_t superframe_order : 4; /* Length of active portion of outgoing + * superframe, including the beacon */ + + /* The offset, measured is symbols, between the symbol boundary at which the + * MLME captures the timestamp of each transmitted and received frame, and + * the onset of the first symbol past the SFD, namely the first symbol of + * the frames [1] pg. 129. + */ + + uint32_t sync_symb_offset : 12; + + /* End of 32-bit bitfield */ + + /* Start of 32-bit bitfield */ + + uint32_t beacon_tx_time : 24; /* Time of last beacon transmit */ + uint32_t min_be : 4; /* Min value of backoff exponent (BE) */ + uint32_t max_be : 4; /* Max value of backoff exponent (BE) */ + + /* End of 32-bit bitfield */ + + /* Start of 32-bit bitfield */ + + uint32_t tx_ctrl_active_dur : 17; /* Duration for which tx is permitted to + * be active */ + uint32_t tx_ctrl_pause_dur : 1; /* Duration after tx before another tx is + * permitted. 0=2000, 1= 10000 */ + uint32_t timestamp_support : 1; /* Does MAC layer supports timestamping */ + uint32_t is_coord : 1; /* Is this device acting as coordinator */ + /* 12-bits remaining */ + + /* End of 32-bit bitfield. */ + + /* TODO: Add Security-related MAC PIB attributes */ +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static inline int mac802154_takesem(sem_t *sem); +#define mac802154_givesem(s) sem_post(s); + +static void mac802154_txdone_worker(FAR void *arg); +static void mac802154_rxframe_worker(FAR void *arg); + +/* Internal Functions */ + +static int mac802154_defaultmib(FAR struct ieee802154_privmac_s *priv); +static int mac802154_applymib(FAR struct ieee802154_privmac_s *priv); + +/* IEEE 802.15.4 PHY Interface OPs */ + +static int mac802154_poll_csma(FAR const struct ieee802154_radiocb_s *radiocb, + FAR struct ieee802154_txdesc_s *tx_desc, + FAR struct iob_s **frame); + +static int mac802154_poll_gts(FAR const struct ieee802154_radiocb_s *radiocb, + FAR struct ieee802154_txdesc_s *tx_desc, + FAR struct iob_s **frame); + +static void mac802154_txdone(FAR const struct ieee802154_radiocb_s *radiocb, + FAR const struct ieee802154_txdesc_s *tx_desc); + +static void mac802154_rxframe(FAR const struct ieee802154_radiocb_s *radiocb, + FAR const struct ieee802154_rxdesc_s *rx_desc, + FAR struct iob_s *frame); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* Map between ieee802154_addr_mode_e enum and actual address length */ + +static const uint8_t mac802154_addr_length[4] = {0, 0, 2, 8}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: mac802154_semtake + * + * Description: + * Acquire the semaphore used for access serialization. + * + ****************************************************************************/ + +static inline int mac802154_takesem(sem_t *sem) +{ + /* Take a count from the semaphore, possibly waiting */ + + if (sem_wait(sem) < 0) + { + /* EINTR is the only error that we expect */ + + int errcode = get_errno(); + DEBUGASSERT(errcode == EINTR); + return -errcode; + } + + return OK; +} + +/**************************************************************************** + * Name: mac802154_push_csma + * + * Description: + * Push a CSMA transaction onto the list + * + ****************************************************************************/ + +static void mac802154_push_csma(FAR struct ieee802154_privmac_s *priv, + FAR struct mac802154_trans_s *trans) +{ + /* Ensure the transactions forward link is NULL */ + + trans->flink = NULL; + + /* If the tail is not empty, make the transaction pointed to by the tail, + * point to the new transaction */ + + if (priv->csma_tail != NULL) + { + priv->csma_tail->flink = trans; + } + + /* Point the tail at the new transaction */ + + priv->csma_tail = trans; + + /* If the head is NULL, we need to point it at the transaction since there + * is only one transaction in the list at this point */ + + if (priv->csma_head == NULL) + { + priv->csma_head = trans; + } +} + +/**************************************************************************** + * Name: mac802154_pop_csma + * + * Description: + * Pop a CSMA transaction from the list + * + ****************************************************************************/ + +static FAR struct mac802154_trans_s * + mac802154_pop_csma(FAR struct ieee802154_privmac_s *priv) +{ + FAR struct mac802154_trans_s *trans; + + if (priv->csma_head == NULL) + { + return NULL; + } + + /* Get the transaction from the head of the list */ + + trans = priv->csma_head; + + /* Move the head pointer to the next transaction */ + + priv->csma_head = trans->flink; + + /* If the head is now NULL, the list is empty, so clear the tail too */ + + if (priv->csma_head == NULL) + { + priv->csma_tail = NULL; + } + + return trans; +} + +/**************************************************************************** + * Name: mac802154_defaultmib + * + * Description: + * Set the MIB to its default values. + * + ****************************************************************************/ + +static int mac802154_defaultmib(FAR struct ieee802154_privmac_s *priv) +{ + /* TODO: Set all MAC fields to default values */ + + return OK; +} + +/**************************************************************************** + * Name: mac802154_applymib + * + * Description: + * Some parts of the MIB must be sent to the radio device. This routine + * calls the radio device routines to store the related parameters in the + * radio driver. It must be called each time a MIB parameter is changed. + * + ****************************************************************************/ + +static int mac802154_applymib(FAR struct ieee802154_privmac_s *priv) +{ + return OK; +} + +/**************************************************************************** + * Name: mac802154_poll_csma + * + * Description: + * Called from the radio driver through the callback struct. This function is + * called when the radio has room for another CSMA transaction. If the MAC + * layer has a CSMA transaction, it copies it into the supplied buffer and + * returns the length. A descriptor is also populated with the transaction. + * + ****************************************************************************/ + +static int mac802154_poll_csma(FAR const struct ieee802154_radiocb_s *radiocb, + FAR struct ieee802154_txdesc_s *tx_desc, + FAR struct iob_s **frame) +{ + FAR struct mac802154_radiocb_s *cb = + (FAR struct mac802154_radiocb_s *)radiocb; + FAR struct ieee802154_privmac_s *priv; + FAR struct mac802154_trans_s *trans; + + DEBUGASSERT(cb != NULL && cb->priv != NULL); + priv = cb->priv; + + /* Get exclusive access to the driver structure. We don't care about any + * signals so if we see one, just go back to trying to get access again. + */ + + while (mac802154_takesem(&priv->exclsem) != 0); + + /* Check to see if there are any CSMA transactions waiting */ + + trans = mac802154_pop_csma(priv); + mac802154_givesem(&priv->exclsem); + + if (trans != NULL) + { + /* Setup the transmit descriptor */ + + tx_desc->handle = trans->msdu_handle; + + *frame = trans->frame; + + /* Now that we've passed off the data, notify the waiting thread. + * NOTE: The transaction was allocated on the waiting thread's stack so + * it will be automatically deallocated when that thread awakens and + * returns. */ + + sem_post(&trans->sem); + return (trans->frame->io_len); + } + + return 0; +} + +/**************************************************************************** + * Name: mac802154_poll_gts + * + * Description: + * Called from the radio driver through the callback struct. This function is + * called when the radio has room for another GTS transaction. If the MAC + * layer has a GTS transaction, it copies it into the supplied buffer and + * returns the length. A descriptor is also populated with the transaction. + * + ****************************************************************************/ + +static int mac802154_poll_gts(FAR const struct ieee802154_radiocb_s *radiocb, + FAR struct ieee802154_txdesc_s *tx_desc, + FAR struct iob_s **frame) +{ + FAR struct mac802154_radiocb_s *cb = + (FAR struct mac802154_radiocb_s *)radiocb; + FAR struct ieee802154_privmac_s *priv; + FAR struct mac802154_trans_s *trans; + int ret = 0; + + DEBUGASSERT(cb != NULL && cb->priv != NULL); + priv = cb->priv; + + /* Get exclusive access to the driver structure. We don't care about any + * signals so if we see one, just go back to trying to get access again. + */ + + while (mac802154_takesem(&priv->exclsem) != 0); + +#warning Missing logic. + + mac802154_givesem(&priv->exclsem); + + return 0; +} + +/**************************************************************************** + * Name: mac802154_txdone + * + * Description: + * Called from the radio driver through the callback struct. This function is + * called when the radio has completed a transaction. The txdesc passed gives + * provides information about the completed transaction including the original + * handle provided when the transaction was created and the status of the + * transaction. This function copies the descriptor and schedules work to + * handle the transaction without blocking the radio. + * + ****************************************************************************/ + +static void mac802154_txdone(FAR const struct ieee802154_radiocb_s *radiocb, + FAR const struct ieee802154_txdesc_s *tx_desc) +{ + FAR struct mac802154_radiocb_s *cb = + (FAR struct mac802154_radiocb_s *)radiocb; + FAR struct ieee802154_privmac_s *priv; + + DEBUGASSERT(cb != NULL && cb->priv != NULL); + priv = cb->priv; + + /* Get exclusive access to the driver structure. We don't care about any + * signals so if we see one, just go back to trying to get access again. + */ + + while (mac802154_takesem(&priv->exclsem) != 0); + + /* Check to see if there is an available tx descriptor slot. If there is + * not we simply drop the notification */ + + if (priv->txdesc_count < CONFIG_IEEE802154_NTXDESC) + { + /* Copy the txdesc over and link it into our list */ + + memcpy(&priv->txdesc[priv->txdesc_count++], tx_desc, + sizeof(struct ieee802154_txdesc_s)); + } + else + { + wlinfo("MAC802154: No room for TX Desc.\n"); + } + + mac802154_givesem(&priv->exclsem); + + /* Schedule work with the work queue to process the completion further */ + + if (work_available(&priv->tx_work)) + { + work_queue(MAC802154_WORK, &priv->tx_work, mac802154_txdone_worker, + (FAR void *)priv, 0); + } +} + +/**************************************************************************** + * Name: mac802154_txdone_worker + * + * Description: + * Worker function scheduled from mac802154_txdone. This function pops any + * TX descriptors off of the list and calls the next highest layers callback + * to inform the layer of the completed transaction and the status of it. + * + ****************************************************************************/ + +static void mac802154_txdone_worker(FAR void *arg) +{ + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)arg; + int i = 0; + + /* Get exclusive access to the driver structure. We don't care about any + * signals so if we see one, just go back to trying to get access again. + */ + + while (mac802154_takesem(&priv->exclsem) != 0); + + /* For each pending TX descriptor, send an application callback */ + + for (i = 0; i < priv->txdesc_count; i++) + { + priv->cb->mcps_notify(priv->cb, IEEE802154_NOTIFY_CONF_DATA, + (FAR const union ieee802154_mcps_notify_u *) &priv->txdesc[i]); + } + + /* We've handled all the descriptors and no further desc could have been added + * since we have the struct locked */ + + priv->txdesc_count = 0; + + mac802154_givesem(&priv->exclsem); +} + +/**************************************************************************** + * Name: mac802154_rxframe + * + * Description: + * Called from the radio driver through the callback struct. This function is + * called when the radio has received a frame. The frame is passed in an iob, + * so that we can free it when we are done processing. A pointer to the RX + * descriptor is passed along with the iob, but it must be copied here as it + * is allocated directly on the caller's stack. We simply link the frame, + * copy the RX descriptor, and schedule a worker to process the frame later so + * that we do not hold up the radio. + * + ****************************************************************************/ + +static void mac802154_rxframe(FAR const struct ieee802154_radiocb_s *radiocb, + FAR const struct ieee802154_rxdesc_s *rx_desc, + FAR struct iob_s *frame) +{ + FAR struct mac802154_radiocb_s *cb = + (FAR struct mac802154_radiocb_s *)radiocb; + FAR struct ieee802154_privmac_s *priv; + FAR struct ieee802154_rxdesc_s *desc; + + DEBUGASSERT(cb != NULL && cb->priv != NULL); + priv = cb->priv; + + /* Get exclusive access to the driver structure. We don't care about any + * signals so if we see one, just go back to trying to get access again. + */ + + while (mac802154_takesem(&priv->exclsem) != 0); + + /* TODO: Copy the frame descriptor to some type of list */ + + /* Push the iob onto the tail of the frame list for processing */ + + priv->rxframes_tail->io_flink = frame; + priv->rxframes_tail = frame; + + mac802154_givesem(&priv->exclsem); + + /* Schedule work with the work queue to process the completion further */ + + if (work_available(&priv->rx_work)) + { + work_queue(MAC802154_WORK, &priv->rx_work, mac802154_rxframe_worker, + (FAR void *)priv, 0); + } +} + +/**************************************************************************** + * Name: mac802154_rxframe_worker + * + * Description: + * Worker function scheduled from mac802154_rxframe. This function processes + * any frames in the list. Frames intended to be consumed by the MAC layer + * will not produce any callbacks to the next highest layer. Frames intended + * for the application layer will be forwarded to them. + * + ****************************************************************************/ + +static void mac802154_rxframe_worker(FAR void *arg) +{ + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)arg; + + /* The radio layer is responsible for handling all ACKs and retries. If for + * some reason an ACK gets here, just throw it out. + */ +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: mac802154_create + * + * Description: + * Create a 802.15.4 MAC device from a 802.15.4 compatible radio device. + * + * The returned MAC structure should be passed to either the next highest + * layer in the network stack, or registered with a mac802154dev character + * or network drivers. In any of these scenarios, the next highest layer + * should register a set of callbacks with the MAC layer by setting the + * mac->cbs member. + * + * NOTE: This API does not create any device accessible to userspace. If + * you want to call these APIs from userspace, you have to wrap your mac + * in a character device via mac802154_device.c. + * + * Input Parameters: + * radiodev - an instance of an IEEE 802.15.4 radio + * + * Returned Value: + * An opaque reference to the MAC state data. + * + ****************************************************************************/ + +MACHANDLE mac802154_create(FAR struct ieee802154_radio_s *radiodev) +{ + FAR struct ieee802154_privmac_s *mac; + FAR struct ieee802154_radiocb_s *radiocb; + + /* Allocate object */ + + mac = (FAR struct ieee802154_privmac_s *) + kmm_zalloc(sizeof(struct ieee802154_privmac_s)); + + if (mac == NULL) + { + return NULL; + } + + /* Allow exclusive access to the privmac struct */ + + sem_init(&mac->exclsem, 0, 1); + + /* Initialize fields */ + + mac->radio = radiodev; + + mac802154_defaultmib(mac); + mac802154_applymib(mac); + + /* Initialize the Radio callbacks */ + + mac->radiocb.priv = mac; + + radiocb = &mac->radiocb.cb; + radiocb->poll_csma = mac802154_poll_csma; + radiocb->poll_gts = mac802154_poll_gts; + radiocb->txdone = mac802154_txdone; + radiocb->rxframe = mac802154_rxframe; + + /* Bind our callback structure */ + + radiodev->ops->bind(radiodev, &mac->radiocb.cb); + + return (MACHANDLE)mac; +} + +/**************************************************************************** + * Name: mac802154_bind + * + * Description: + * Bind the MAC callback table to the MAC state. + * + * Parameters: + * mac - Reference to the MAC driver state structure + * cb - MAC callback operations + * + * Returned Value: + * OK on success; Negated errno on failure. + * + ****************************************************************************/ + +int mac802154_bind(MACHANDLE mac, FAR const struct ieee802154_maccb_s *cb) +{ + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; + + priv->cb = cb; + return OK; +} + +/**************************************************************************** + * Name: mac802154_ioctl + * + * Description: + * Handle MAC and radio IOCTL commands directed to the MAC. + * + * Parameters: + * mac - Reference to the MAC driver state structure + * cmd - The IOCTL command + * arg - The argument for the IOCTL command + * + * Returned Value: + * OK on success; Negated errno on failure. + * + ****************************************************************************/ + +int mac802154_ioctl(MACHANDLE mac, int cmd, unsigned long arg) +{ + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; + int ret = -EINVAL; + + DEBUGASSERT(priv != NULL); + + /* Check for IOCTLs aimed at the IEEE802.15.4 MAC layer */ + + if (_MAC802154IOCVALID(cmd)) + { + /* Handle the MAC IOCTL command */ +#warning Missing logic + } + + /* No, other IOCTLs must be aimed at the IEEE802.15.4 radio layer */ + + else + { + DEBUGASSERT(priv->radio != NULL && + priv->radio->ops != NULL && + priv->radio->ops->ioctl != NULL); + + ret = priv->radio->ops->ioctl(priv->radio, cmd, arg); + } + + return ret; +} + +/**************************************************************************** + * MAC Interface Operations + ****************************************************************************/ + +/**************************************************************************** + * Name: mac802154_get_mhrlen + * + * Description: + * Calculate the MAC header length given the frame meta-data. + * + ****************************************************************************/ + +int mac802154_get_mhrlen(MACHANDLE mac, + FAR struct ieee802154_frame_meta_s *meta) +{ + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; + int ret = 3; /* Always frame control (2 bytes) and seq. num (1 byte) */ + + /* Check to make sure both the dest address and the source address are not set + * to NONE */ + + if (meta->dest_addr.mode == IEEE802154_ADDRMODE_NONE && + meta->src_addr_mode == IEEE802154_ADDRMODE_NONE) + { + return -EINVAL; + } + + /* The source address can only be set to NONE if the device is the PAN coord */ + + if (meta->src_addr_mode == IEEE802154_ADDRMODE_NONE && !priv->is_coord) + { + return -EINVAL; + } + + /* Add the destination address length */ + + ret += mac802154_addr_length[meta->dest_addr.mode]; + + /* Add the source address length */ + + ret += mac802154_addr_length[ meta->src_addr_mode]; + + /* If both destination and source addressing information is present, the MAC + * sublayer shall compare the destination and source PAN identifiers. + * [1] pg. 41. + */ + + if (meta->src_addr_mode != IEEE802154_ADDRMODE_NONE && + meta->dest_addr.mode != IEEE802154_ADDRMODE_NONE) + { + /* If the PAN identifiers are identical, the PAN ID Compression field + * shall be set to one, and the source PAN identifier shall be omitted + * from the transmitted frame. [1] pg. 41. + */ + + if (meta->dest_addr.panid == priv->addr.panid) + { + ret += 2; /* 2 bytes for destination PAN ID */ + return ret; + } + } + + /* If we are here, PAN ID compression is off, so include the dest and source + * PAN ID if the respective address is included + */ + + if (meta->src_addr_mode != IEEE802154_ADDRMODE_NONE) + { + ret += 2; /* 2 bytes for source PAN ID */ + } + + if (meta->dest_addr.mode != IEEE802154_ADDRMODE_NONE) + { + ret += 2; /* 2 bytes for destination PAN ID */ + } + + return ret; +} + +/**************************************************************************** + * Name: mac802154_req_data + * + * Description: + * The MCPS-DATA.request primitive requests the transfer of a data SPDU + * (i.e., MSDU) from a local SSCS entity to a single peer SSCS entity. + * Confirmation is returned via the + * struct ieee802154_maccb_s->conf_data callback. + * + ****************************************************************************/ + +int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) +{ + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; + FAR struct mac802154_trans_s trans; + FAR struct ieee802154_frame_meta_s *meta = req->meta; + uint16_t *frame_ctrl; + uint8_t mhr_len = 3; /* Start assuming frame control and seq. num */ + int ret; + + /* Check the required frame size */ + + if (req->frame->io_len > IEEE802154_MAX_PHY_PACKET_SIZE) + { + return -E2BIG; + } + + /* Cast the first two bytes of the IOB to a uint16_t frame control field */ + + frame_ctrl = (uint16_t *)&req->frame->io_data[0]; + + /* Ensure we start with a clear frame control field */ + + *frame_ctrl = 0; + + /* Set the frame type to Data */ + + *frame_ctrl |= IEEE802154_FRAME_DATA << IEEE802154_FRAMECTRL_SHIFT_FTYPE; + + /* If the msduLength is greater than aMaxMACSafePayloadSize, the MAC + * sublayer will set the Frame Version to one. [1] pg. 118. + */ + + if (meta->msdu_length > IEEE802154_MAX_SAFE_MAC_PAYLOAD_SIZE) + { + *frame_ctrl |= IEEE802154_FRAMECTRL_VERSION; + } + + /* If the TXOptions parameter specifies that an acknowledged transmission + * is required, the AR field will be set appropriately, as described in + * 5.1.6.4 [1] pg. 118. + */ + + *frame_ctrl |= (meta->msdu_flags.ack_tx << IEEE802154_FRAMECTRL_SHIFT_ACKREQ); + + /* If the destination address is present, copy the PAN ID and one of the + * addresses, depending on mode, into the MHR. + */ + + if (meta->dest_addr.mode != IEEE802154_ADDRMODE_NONE) + { + memcpy(&req->frame->io_data[mhr_len], &meta->dest_addr.panid, 2); + mhr_len += 2; + + if (meta->dest_addr.mode == IEEE802154_ADDRMODE_SHORT) + { + memcpy(&req->frame->io_data[mhr_len], &meta->dest_addr.saddr, 2); + mhr_len += 2; + } + else if (meta->dest_addr.mode == IEEE802154_ADDRMODE_EXTENDED) + { + memcpy(&req->frame->io_data[mhr_len], &meta->dest_addr.eaddr, 8); + mhr_len += 8; + } + } + + /* Set the destination addr mode inside the frame control field */ + + *frame_ctrl |= (meta->dest_addr.mode << IEEE802154_FRAMECTRL_SHIFT_DADDR); + + /* From this point on, we need exclusive access to the privmac struct */ + + ret = mac802154_takesem(&priv->exclsem); + if (ret < 0) + { + wlerr("ERROR: mac802154_takesem failed: %d\n", ret); + return ret; + } + + /* If both destination and source addressing information is present, the MAC + * sublayer shall compare the destination and source PAN identifiers. + * [1] pg. 41. + */ + + if (meta->src_addr_mode != IEEE802154_ADDRMODE_NONE && + meta->dest_addr.mode != IEEE802154_ADDRMODE_NONE) + { + /* If the PAN identifiers are identical, the PAN ID Compression field + * shall be set to one, and the source PAN identifier shall be omitted + * from the transmitted frame. [1] pg. 41. + */ + + if (meta->dest_addr.panid == priv->addr.panid) + { + *frame_ctrl |= IEEE802154_FRAMECTRL_PANIDCOMP; + } + } + + if (meta->src_addr_mode != IEEE802154_ADDRMODE_NONE) + { + /* If the destination address is not included, or if PAN ID Compression + * is off, we need to include the Source PAN ID. + */ + + if ((meta->dest_addr.mode == IEEE802154_ADDRMODE_NONE) || + (*frame_ctrl & IEEE802154_FRAMECTRL_PANIDCOMP)) + { + memcpy(&req->frame->io_data[mhr_len], &priv->addr.panid, 2); + mhr_len += 2; + } + + if (meta->src_addr_mode == IEEE802154_ADDRMODE_SHORT) + { + memcpy(&req->frame->io_data[mhr_len], &priv->addr.saddr, 2); + mhr_len += 2; + } + else if (meta->src_addr_mode == IEEE802154_ADDRMODE_EXTENDED) + { + memcpy(&req->frame->io_data[mhr_len], &priv->addr.eaddr, 8); + mhr_len += 8; + } + } + + /* Set the source addr mode inside the frame control field */ + + *frame_ctrl |= (meta->src_addr_mode << IEEE802154_FRAMECTRL_SHIFT_SADDR); + + /* Each time a data or a MAC command frame is generated, the MAC sublayer + * shall copy the value of macDSN into the Sequence Number field of the MHR + * of the outgoing frame and then increment it by one. [1] pg. 40. + */ + + req->frame->io_data[2] = priv->dsn++; + + /* The MAC header we just created must never have exceeded where the app + * data starts. This should never happen since the offset should have + * been set via the same logic to calculate the header length as the logic + * here that created the header + */ + + DEBUGASSERT(mhr_len == req->frame->io_offset); + + req->frame->io_offset = 0; /* Set the offset to 0 to include the header */ + + /* Setup our transaction */ + + trans.msdu_handle = meta->msdu_handle; + trans.frame = req->frame; + sem_init(&trans.sem, 0, 1); + + /* If the TxOptions parameter specifies that a GTS transmission is required, + * the MAC sublayer will determine whether it has a valid GTS as described + * 5.1.7.3. If a valid GTS could not be found, the MAC sublayer will discard + * the MSDU. If a valid GTS was found, the MAC sublayer will defer, if + * necessary, until the GTS. If the TxOptions parameter specifies that a GTS + * transmission is not required, the MAC sublayer will transmit the MSDU using + * either slotted CSMA-CA in the CAP for a beacon-enabled PAN or unslotted + * CSMA-CA for a nonbeacon-enabled PAN. Specifying a GTS transmission in the + * TxOptions parameter overrides an indirect transmission request. + * [1] pg. 118. + */ + + if (meta->msdu_flags.gts_tx) + { + /* TODO: Support GTS transmission. This should just change where we link + * the transaction. Instead of going in the CSMA transaction list, it + * should be linked to the GTS' transaction list. We'll need to check if + * the GTS is valid, and then find the GTS, before linking. Note, we also + * don't have to try and kick-off any transmission here. + */ + + return -ENOTSUP; + } + else + { + /* If the TxOptions parameter specifies that an indirect transmission is + * required and this primitive is received by the MAC sublayer of a + * coordinator, the data frame is sent using indirect transmission, as + * described in 5.1.5 and 5.1.6.3. [1] + */ + + if (meta->msdu_flags.indirect_tx) + { + /* If the TxOptions parameter specifies that an indirect transmission + * is required and if the device receiving this primitive is not a + * coordinator, the destination address is not present, or the + * TxOptions parameter also specifies a GTS transmission, the indirect + * transmission option will be ignored. [1] + */ + + if (priv->is_coord && meta->dest_addr.mode != IEEE802154_ADDRMODE_NONE) + { + /* Link the transaction into the indirect_trans list */ + + } + else + { + /* Override the setting since it wasn't valid */ + + meta->msdu_flags.indirect_tx = 0; + } + } + + /* If this is a direct transmission not during a GTS */ + + if (!meta->msdu_flags.indirect_tx) + { + /* Link the transaction into the CSMA transaction list */ + + mac802154_push_csma(priv, &trans); + + /* We no longer need to have the MAC layer locked. */ + + mac802154_givesem(&priv->exclsem); + + /* Notify the radio driver that there is data available */ + + priv->radio->ops->txnotify_csma(priv->radio); + + sem_wait(&trans.sem); + } + } + + sem_destroy(&trans.sem); + return OK; +} + +/**************************************************************************** + * Name: mac802154_req_purge + * + * Description: + * The MCPS-PURGE.request primitive allows the next higher layer to purge + * an MSDU from the transaction queue. Confirmation is returned via + * the struct ieee802154_maccb_s->conf_purge callback. + * + ****************************************************************************/ + +int mac802154_req_purge(MACHANDLE mac, FAR struct ieee802154_purge_req_s *req) +{ + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; + return -ENOTTY; +} + +/**************************************************************************** + * Name: mac802154_req_associate + * + * Description: + * The MLME-ASSOCIATE.request primitive allows a device to request an + * association with a coordinator. Confirmation is returned via the + * struct ieee802154_maccb_s->conf_associate callback. + * + ****************************************************************************/ + +int mac802154_req_associate(MACHANDLE mac, + FAR struct ieee802154_assoc_req_s *req) +{ + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; + + /* Set the channel of the PHY layer */ + + /* Set the channel page of the PHY layer */ + + /* Set the macPANId */ + + /* Set either the macCoordExtendedAddress and macCoordShortAddress + * depending on the CoordAddrMode in the primitive. + */ + + if (req->coord_addr.mode == IEEE802154_ADDRMODE_EXTENDED) + { + + } + else if (req->coord_addr.mode == IEEE802154_ADDRMODE_EXTENDED) + { + + } + else + { + return -EINVAL; + } + + return -ENOTTY; +} + +/**************************************************************************** + * Name: mac802154_req_disassociate + * + * Description: + * The MLME-DISASSOCIATE.request primitive is used by an associated device to + * notify the coordinator of its intent to leave the PAN. It is also used by + * the coordinator to instruct an associated device to leave the PAN. + * Confirmation is returned via the + * struct ieee802154_maccb_s->conf_disassociate callback. + * + ****************************************************************************/ + +int mac802154_req_disassociate(MACHANDLE mac, + FAR struct ieee802154_disassoc_req_s *req) +{ + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; + return -ENOTTY; +} + +/**************************************************************************** + * Name: mac802154_req_get + * + * Description: + * The MLME-GET.request primitive requests information about a given PIB + * attribute. Actual data is returned via the + * struct ieee802154_maccb_s->conf_get callback. + * + ****************************************************************************/ + +int mac802154_req_get(MACHANDLE mac, FAR struct ieee802154_get_req_s *req) +{ + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; + return -ENOTTY; +} + +/**************************************************************************** + * Name: mac802154_req_gts + * + * Description: + * The MLME-GTS.request primitive allows a device to send a request to the PAN + * coordinator to allocate a new GTS or to deallocate an existing GTS. + * Confirmation is returned via the + * struct ieee802154_maccb_s->conf_gts callback. + * + ****************************************************************************/ + +int mac802154_req_gts(MACHANDLE mac, FAR struct ieee802154_gts_req_s *req) +{ + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; + return -ENOTTY; +} + +/**************************************************************************** + * Name: mac802154_req_reset + * + * Description: + * The MLME-RESET.request primitive allows the next higher layer to request + * that the MLME performs a reset operation. Confirmation is returned via + * the struct ieee802154_maccb_s->conf_reset callback. + * + ****************************************************************************/ + +int mac802154_req_reset(MACHANDLE mac, FAR struct ieee802154_reset_req_s *req) +{ + FAR struct ieee802154_privmac_s * priv = + (FAR struct ieee802154_privmac_s *) mac; + return -ENOTTY; +} + +/**************************************************************************** + * Name: mac802154_req_rxenable + * + * Description: + * The MLME-RX-ENABLE.request primitive allows the next higher layer to + * request that the receiver is enable for a finite period of time. + * Confirmation is returned via the + * struct ieee802154_maccb_s->conf_rxenable callback. + * + ****************************************************************************/ + +int mac802154_req_rxenable(MACHANDLE mac, + FAR struct ieee802154_rxenable_req_s *req) +{ + FAR struct ieee802154_privmac_s * priv = + (FAR struct ieee802154_privmac_s *)mac; + return -ENOTTY; +} + +/**************************************************************************** + * Name: mac802154_req_scan + * + * Description: + * The MLME-SCAN.request primitive is used to initiate a channel scan over a + * given list of channels. A device can use a channel scan to measure the + * energy on the channel, search for the coordinator with which it associated, + * or search for all coordinators transmitting beacon frames within the POS of + * the scanning device. Scan results are returned + * via MULTIPLE calls to the struct ieee802154_maccb_s->conf_scan callback. + * This is a difference with the official 802.15.4 specification, implemented + * here to save memory. + * + ****************************************************************************/ + +int mac802154_req_scan(MACHANDLE mac, FAR struct ieee802154_scan_req_s *req) +{ + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; + return -ENOTTY; +} + +/**************************************************************************** + * Name: mac802154_req_set + * + * Description: + * The MLME-SET.request primitive attempts to write the given value to the + * indicated MAC PIB attribute. Confirmation is returned via the + * struct ieee802154_maccb_s->conf_set callback. + * + ****************************************************************************/ + +int mac802154_req_set(MACHANDLE mac, FAR struct ieee802154_set_req_s *req) +{ + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; + return -ENOTTY; +} + +/**************************************************************************** + * Name: mac802154_req_start + * + * Description: + * The MLME-START.request primitive makes a request for the device to start + * using a new superframe configuration. Confirmation is returned + * via the struct ieee802154_maccb_s->conf_start callback. + * + ****************************************************************************/ + +int mac802154_req_start(MACHANDLE mac, FAR struct ieee802154_start_req_s *req) +{ + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; + return -ENOTTY; +} + +/**************************************************************************** + * Name: mac802154_req_sync + * + * Description: + * The MLME-SYNC.request primitive requests to synchronize with the + * coordinator by acquiring and, if specified, tracking its beacons. + * Confirmation is returned via the + * struct ieee802154_maccb_s->int_commstatus callback. TOCHECK. + * + ****************************************************************************/ + +int mac802154_req_sync(MACHANDLE mac, FAR struct ieee802154_sync_req_s *req) +{ + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; + return -ENOTTY; +} + +/**************************************************************************** + * Name: mac802154_req_poll + * + * Description: + * The MLME-POLL.request primitive prompts the device to request data from + * the coordinator. Confirmation is returned via the + * struct ieee802154_maccb_s->conf_poll callback, followed by a + * struct ieee802154_maccb_s->ind_data callback. + * + ****************************************************************************/ + +int mac802154_req_poll(MACHANDLE mac, FAR struct ieee802154_poll_req_s *req) +{ + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; + return -ENOTTY; +} + +/**************************************************************************** + * Name: mac802154_rsp_associate + * + * Description: + * The MLME-ASSOCIATE.response primitive is used to initiate a response to + * an MLME-ASSOCIATE.indication primitive. + * + ****************************************************************************/ + +int mac802154_rsp_associate(MACHANDLE mac, + FAR struct ieee802154_assoc_resp_s *resp) +{ + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; + return -ENOTTY; +} + +/**************************************************************************** + * Name: mac802154_rsp_orphan + * + * Description: + * The MLME-ORPHAN.response primitive allows the next higher layer of a + * coordinator to respond to the MLME-ORPHAN.indication primitive. + * + ****************************************************************************/ + +int mac802154_rsp_orphan(MACHANDLE mac, + FAR struct ieee802154_orphan_resp_s *resp) +{ + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; + return -ENOTTY; +} diff --git a/wireless/ieee802154/mac802154.h b/wireless/ieee802154/mac802154.h index ea582e4e7a..d0d7e82ce2 100644 --- a/wireless/ieee802154/mac802154.h +++ b/wireless/ieee802154/mac802154.h @@ -105,7 +105,7 @@ int mac802154_ioctl(MACHANDLE mac, int cmd, unsigned long arg); * ****************************************************************************/ -int mac802154_get_mhrlen(MACHANDLE mac, +int mac802154_get_mhrlen(MACHANDLE mac, FAR struct ieee802154_frame_meta_s *meta); /**************************************************************************** diff --git a/wireless/ieee802154/mac802154_device.c b/wireless/ieee802154/mac802154_device.c index 998cca074f..83798b4734 100644 --- a/wireless/ieee802154/mac802154_device.c +++ b/wireless/ieee802154/mac802154_device.c @@ -446,7 +446,7 @@ static ssize_t mac802154dev_write(FAR struct file *filep, wlerr("ERROR: TX meta-data is invalid"); return ret; } - + iob->io_offset = ret; iob->io_len = iob->io_offset; -- GitLab From 4ec14bb2e4cfe36d73accf9f59f940d71b9f80f7 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 2 May 2017 16:03:26 -0600 Subject: [PATCH 684/990] 6loWPAN: Add basic call path to interface with the MAC layer through the MAC network driver. Logic has not yet been implemented. This is just a structural change in preparation for additional changes. --- include/nuttx/net/sixlowpan.h | 29 +++ .../wireless/ieee802154/ieee802154_mac.h | 2 +- wireless/ieee802154/mac802154_loopback.c | 187 +++++++++++++++--- wireless/ieee802154/mac802154_netdev.c | 118 +++++++++-- 4 files changed, 295 insertions(+), 41 deletions(-) diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index f67ac0d98e..2e65199513 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -402,6 +402,8 @@ * frame list. */ +struct ieee802154_frame_meta_s; /* Forward reference */ + struct ieee802154_driver_s { /* This definitiona must appear first in the structure definition to @@ -498,6 +500,33 @@ struct ieee802154_driver_s systime_t i_time; #endif /* CONFIG_NET_6LOWPAN_FRAG */ + + /* MAC network driver callback functions **********************************/ + /************************************************************************** + * Name: mac802154_get_mhrlen + * + * Description: + * Calculate the MAC header length given the frame meta-data. + * + **************************************************************************/ + + CODE int (*i_get_mhrlen)(FAR struct ieee802154_driver_s *netdev, + FAR struct ieee802154_frame_meta_s *meta); + + /************************************************************************** + * Name: mac802154_req_data + * + * Description: + * The MCPS-DATA.request primitive requests the transfer of a data SPDU + * (i.e., MSDU) from a local SSCS entity to a single peer SSCS entity. + * Confirmation is returned via the + * struct ieee802154_maccb_s->conf_data callback. + * + **************************************************************************/ + + CODE int (*i_req_data)(FAR struct ieee802154_driver_s *netdev, + FAR struct ieee802154_frame_meta_s *meta, + FAR struct iob_s *frames); }; /**************************************************************************** diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index a51e885287..4231374371 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -479,7 +479,7 @@ struct ieee802154_frame_meta_s enum ieee802154_addr_mode_e src_addr_mode; /* Source Address Mode */ struct ieee802154_addr_s dest_addr; /* Destination Address */ - uint8_t msdu_handle; /* Handle assoc. with MSDU */ + uint8_t msdu_handle; /* Handle assoc. with MSDU */ /* Number of bytes contained in the MAC Service Data Unit (MSDU) * to be transmitted by the MAC sublayer enitity diff --git a/wireless/ieee802154/mac802154_loopback.c b/wireless/ieee802154/mac802154_loopback.c index 9733065f46..92a30d3519 100644 --- a/wireless/ieee802154/mac802154_loopback.c +++ b/wireless/ieee802154/mac802154_loopback.c @@ -83,6 +83,10 @@ #define LO_WDDELAY (1*CLK_TCK) +/* Fake value for MAC header length */ + +#define MAC_HDRLEN 9 + /**************************************************************************** * Private Types ****************************************************************************/ @@ -98,6 +102,8 @@ struct lo_driver_s uint16_t lo_panid; /* Fake PAN ID for testing */ WDOG_ID lo_polldog; /* TX poll timer */ struct work_s lo_work; /* For deferring poll work to the work queue */ + FAR struct iob_s *head; /* Head of IOBs queued for loopback */ + FAR struct iob_s *tail; /* Tail of IOBs queued for loopback */ /* This holds the information visible to the NuttX network */ @@ -117,33 +123,39 @@ static uint8_t g_iobuffer[CONFIG_NET_6LOWPAN_MTU + CONFIG_NET_GUARDSIZE]; /* Polling logic */ -static int lo_txpoll(FAR struct net_driver_s *dev); +static int lo_loopback(FAR struct net_driver_s *dev); +static void lo_loopback_work(FAR void *arg); static void lo_poll_work(FAR void *arg); static void lo_poll_expiry(int argc, wdparm_t arg, ...); /* NuttX callback functions */ -static int lo_ifup(FAR struct net_driver_s *dev); -static int lo_ifdown(FAR struct net_driver_s *dev); +static int lo_ifup(FAR struct net_driver_s *dev); +static int lo_ifdown(FAR struct net_driver_s *dev); static void lo_txavail_work(FAR void *arg); -static int lo_txavail(FAR struct net_driver_s *dev); +static int lo_txavail(FAR struct net_driver_s *dev); #if defined(CONFIG_NET_IGMP) || defined(CONFIG_NET_ICMPv6) -static int lo_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac); +static int lo_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac); #ifdef CONFIG_NET_IGMP -static int lo_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac); +static int lo_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac); #endif #endif #ifdef CONFIG_NETDEV_IOCTL static int lo_ioctl(FAR struct net_driver_s *dev, int cmd, unsigned long arg); #endif +static int lo_get_mhrlen(FAR struct ieee802154_driver_s *netdev, + FAR struct ieee802154_frame_meta_s *meta); +static int lo_req_data(FAR struct ieee802154_driver_s *netdev, + FAR struct ieee802154_frame_meta_s *meta, + FAR struct iob_s *frames); /**************************************************************************** * Private Functions ****************************************************************************/ /**************************************************************************** - * Name: lo_txpoll + * Name: lo_loopback * * Description: * Check if the network has any outgoing packets ready to send. This is @@ -162,7 +174,7 @@ static int lo_ioctl(FAR struct net_driver_s *dev, int cmd, * ****************************************************************************/ -static int lo_txpoll(FAR struct net_driver_s *dev) +static int lo_loopback(FAR struct net_driver_s *dev) { FAR struct lo_driver_s *priv = (FAR struct lo_driver_s *)dev->d_private; FAR struct iob_s *head; @@ -270,6 +282,34 @@ static int lo_txpoll(FAR struct net_driver_s *dev) return 0; } +/**************************************************************************** + * Name: lo_loopback_work + * + * Description: + * Perform loopback of received frames. + * + * Parameters: + * arg - The argument passed when work_queue() as called. + * + * Returned Value: + * OK on success + * + * Assumptions: + * The network is locked + * + ****************************************************************************/ + +static void lo_loopback_work(FAR void *arg) +{ + FAR struct lo_driver_s *priv = (FAR struct lo_driver_s *)arg; + + /* Perform the loopback */ + + net_lock(); + (void)lo_loopback(&priv->lo_ieee.i_dev); + net_unlock(); +} + /**************************************************************************** * Name: lo_poll_work * @@ -295,7 +335,7 @@ static void lo_poll_work(FAR void *arg) net_lock(); priv->lo_txdone = false; - (void)devif_timer(&priv->lo_ieee.i_dev, lo_txpoll); + (void)devif_timer(&priv->lo_ieee.i_dev, lo_loopback); /* Was something received and looped back? */ @@ -304,7 +344,7 @@ static void lo_poll_work(FAR void *arg) /* Yes, poll again for more TX data */ priv->lo_txdone = false; - (void)devif_poll(&priv->lo_ieee.i_dev, lo_txpoll); + (void)devif_poll(&priv->lo_ieee.i_dev, lo_loopback); } /* Setup the watchdog poll timer again */ @@ -458,7 +498,7 @@ static void lo_txavail_work(FAR void *arg) /* If so, then poll the network for new XMIT data */ priv->lo_txdone = false; - (void)devif_poll(&priv->lo_ieee.i_dev, lo_txpoll); + (void)devif_poll(&priv->lo_ieee.i_dev, lo_loopback); } while (priv->lo_txdone); } @@ -492,8 +532,8 @@ static int lo_txavail(FAR struct net_driver_s *dev) ninfo("Available: %u\n", work_available(&priv->lo_work)); /* Is our single work structure available? It may not be if there are - * pending interrupt actions and we will have to ignore the Tx - * availability action. + * pending actions and we will have to ignore the Tx availability + * action. */ if (work_available(&priv->lo_work)) @@ -644,6 +684,92 @@ static int lo_ioctl(FAR struct net_driver_s *dev, int cmd, } #endif +/**************************************************************************** + * Name: lo_get_mhrlen + * + * Description: + * Calculate the MAC header length given the frame meta-data. + * + ****************************************************************************/ + +static int lo_get_mhrlen(FAR struct ieee802154_driver_s *netdev, + FAR struct ieee802154_frame_meta_s *meta) +{ + return MAC_HDRLEN; +} + +/**************************************************************************** + * Name: lo_req_data + * + * Description: + * The MCPS-DATA.request primitive requests the transfer of a data SPDU + * (i.e., MSDU) from a local SSCS entity to a single peer SSCS entity. + * Confirmation is returned via the + * struct ieee802154_maccb_s->conf_data callback. + * + ****************************************************************************/ + +static int lo_req_data(FAR struct ieee802154_driver_s *netdev, + FAR struct ieee802154_frame_meta_s *meta, + FAR struct iob_s *frames) +{ + FAR struct lo_driver_s *priv; + FAR struct iob_s *iob; + + DEBUGASSERT(netdev != NULL && netdev->i_dev.d_private != NULL && iob != NULL); + priv = (FAR struct lo_driver_s *)netdev->i_dev.d_private; + + /* Add the incoming list of frames to queue of frames to loopback */ + + for (iob = frames; iob != NULL; iob = frames) + { + /* Increment statistics */ + + NETDEV_RXPACKETS(&priv->lo_ieee.i_dev); + + /* Remove the IOB from the queue */ + + frames = iob->io_flink; + iob->io_flink = NULL; + + /* Just zero the MAC header for test purposes */ + + DEBUGASSERT(iob->io_offset == MAC_HDRLEN); + memset(iob->io_data, 0, MAC_HDRLEN); + + /* Add the IOB to the tail of teh queue of frames to be looped back */ + + if (priv->tail == NULL) + { + priv->head = iob; + } + else + { + priv->tail->io_flink = iob; + } + + /* Find the new tail of the IOB queue */ + + for (priv->tail = iob, iob = iob->io_flink; + iob != NULL; + priv->tail = iob, iob = iob->io_flink); + } + + /* Is our single work structure available? It may not be if there are + * pending actions and we will have to ignore the Tx availability + * action. + */ + + if (work_available(&priv->lo_work)) + { + /* Schedule to serialize the poll on the worker thread. */ + + work_queue(LPBKWORK, &priv->lo_work, lo_loopback_work, priv, 0); + } + + return OK; +} + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -666,7 +792,8 @@ static int lo_ioctl(FAR struct net_driver_s *dev, int cmd, int ieee8021514_loopback(void) { - FAR struct lo_driver_s *priv; + FAR struct lo_driver_s *priv; + FAR struct ieee802154_driver_s *ieee; FAR struct net_driver_s *dev; ninfo("Initializing\n"); @@ -679,27 +806,33 @@ int ieee8021514_loopback(void) memset(priv, 0, sizeof(struct lo_driver_s)); - dev = &priv->lo_ieee.i_dev; - dev->d_ifup = lo_ifup; /* I/F up (new IP address) callback */ - dev->d_ifdown = lo_ifdown; /* I/F down callback */ - dev->d_txavail = lo_txavail; /* New TX data callback */ + ieee = &priv->lo_ieee; + dev = &ieee->i_dev; + dev->d_ifup = lo_ifup; /* I/F up (new IP address) callback */ + dev->d_ifdown = lo_ifdown; /* I/F down callback */ + dev->d_txavail = lo_txavail; /* New TX data callback */ #ifdef CONFIG_NET_IGMP - dev->d_addmac = lo_addmac; /* Add multicast MAC address */ - dev->d_rmmac = lo_rmmac; /* Remove multicast MAC address */ + dev->d_addmac = lo_addmac; /* Add multicast MAC address */ + dev->d_rmmac = lo_rmmac; /* Remove multicast MAC address */ #endif #ifdef CONFIG_NETDEV_IOCTL - dev->d_ioctl = lo_ioctl; /* Handle network IOCTL commands */ + dev->d_ioctl = lo_ioctl; /* Handle network IOCTL commands */ #endif - dev->d_buf = g_iobuffer; /* Attach the IO buffer */ - dev->d_private = (FAR void *)priv; /* Used to recover private state from dev */ + dev->d_buf = g_iobuffer; /* Attach the IO buffer */ + dev->d_private = (FAR void *)priv; /* Used to recover private state from dev */ - /* Create a watchdog for timing polling for and timing of transmissions */ + /* Initialize the DSN to a "random" value */ - priv->lo_polldog = wd_create(); /* Create periodic poll timer */ + ieee->i_dsn = 42; - /* Initialize the DSN to a "random" value */ + /* Initialize the Network frame-related callbacks */ + + ieee->i_get_mhrlen = lo_get_mhrlen; /* Get MAC header length */ + ieee->i_req_data = lo_req_data; /* Enqueue frame for transmission */ + + /* Create a watchdog for timing polling for and timing of transmissions */ - priv->lo_ieee.i_dsn = 42; + priv->lo_polldog = wd_create(); /* Create periodic poll timer */ /* Register the loopabck device with the OS so that socket IOCTLs can b * performed. diff --git a/wireless/ieee802154/mac802154_netdev.c b/wireless/ieee802154/mac802154_netdev.c index 18b2d6e1cd..f0e4f43cbe 100644 --- a/wireless/ieee802154/mac802154_netdev.c +++ b/wireless/ieee802154/mac802154_netdev.c @@ -257,6 +257,11 @@ static void macnet_ipv6multicast(FAR struct macnet_driver_s *priv); static int macnet_ioctl(FAR struct net_driver_s *dev, int cmd, unsigned long arg); #endif +static int macnet_get_mhrlen(FAR struct ieee802154_driver_s *netdev, + FAR struct ieee802154_frame_meta_s *meta); +static int macnet_req_data(FAR struct ieee802154_driver_s *netdev, + FAR struct ieee802154_frame_meta_s *meta, + FAR struct iob_s *frames); /**************************************************************************** * Private Functions @@ -1494,6 +1499,86 @@ static int macnet_ioctl(FAR struct net_driver_s *dev, int cmd, } #endif +/**************************************************************************** + * Name: macnet_get_mhrlen + * + * Description: + * Calculate the MAC header length given the frame meta-data. + * + ****************************************************************************/ + +static int macnet_get_mhrlen(FAR struct ieee802154_driver_s *netdev, + FAR struct ieee802154_frame_meta_s *meta) +{ + FAR struct macnet_driver_s *priv; + + DEBUGASSERT(netdev != NULL && netdev->i_dev.d_private != NULL && iob != NULL); + priv = (FAR struct macnet_driver_s *)netdev->i_dev.d_private; + + return mac802154_get_mhrlen(priv->md_mac, meta); +} + +/**************************************************************************** + * Name: macnet_req_data + * + * Description: + * The MCPS-DATA.request primitive requests the transfer of a data SPDU + * (i.e., MSDU) from a local SSCS entity to a single peer SSCS entity. + * Confirmation is returned via the + * struct ieee802154_maccb_s->conf_data callback. + * + ****************************************************************************/ + +static int macnet_req_data(FAR struct ieee802154_driver_s *netdev, + FAR struct ieee802154_frame_meta_s *meta, + FAR struct iob_s *frames) +{ + FAR struct macnet_driver_s *priv; + struct ieee802154_data_req_s req; + FAR struct iob_s *iob; + int ret; + + DEBUGASSERT(netdev != NULL && netdev->i_dev.d_private != NULL && iob != NULL); + priv = (FAR struct macnet_driver_s *)netdev->i_dev.d_private; + + /* Add the incoming list of frames to the MAC's outgoing queue */ + + for (iob = frames; iob != NULL; iob = frames) + { + /* Increment statistics */ + + NETDEV_RXPACKETS(&priv->lo_ieee.i_dev); + + /* Remove the IOB from the queue */ + + frames = iob->io_flink; + iob->io_flink = NULL; + + /* Transfer the frame to the MAC */ + + req.meta = mets; + req.frame = iob; + ret = mac802154_req_data(priv->md_mac, req); + if (ret < 0) + { + wlerr("ERROR: mac802154_req_data failed: %d\n", ret); + + iob_free(iob); + for (iob = frames; ; iob != NULL; iob = frames) + { + /* Remove the IOB from the queue and free */ + + frames = iob->io_flink; + iob_free(iob); + } + + return ret; + } + } + + return OK; +} + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -1517,7 +1602,8 @@ static int macnet_ioctl(FAR struct net_driver_s *dev, int cmd, int mac802154netdev_register(MACHANDLE mac) { FAR struct macnet_driver_s *priv; - FAR struct net_driver_s *dev; + FAR struct ieee802154_driver_s *ieee; + FAR struct net_driver_s *dev; FAR struct ieee802154_maccb_s *maccb; FAR uint8_t *pktbuf; int ret; @@ -1549,28 +1635,34 @@ int mac802154netdev_register(MACHANDLE mac) /* Initialize the driver structure */ - dev = &priv->md_dev.i_dev; - dev->d_buf = pktbuf; /* Single packet buffer */ - dev->d_ifup = macnet_ifup; /* I/F up (new IP address) callback */ - dev->d_ifdown = macnet_ifdown; /* I/F down callback */ - dev->d_txavail = macnet_txavail; /* New TX data callback */ + ieee = &priv->lo_ieee; + dev = &ieee->i_dev; + dev->d_buf = pktbuf; /* Single packet buffer */ + dev->d_ifup = macnet_ifup; /* I/F up (new IP address) callback */ + dev->d_ifdown = macnet_ifdown; /* I/F down callback */ + dev->d_txavail = macnet_txavail; /* New TX data callback */ #ifdef CONFIG_NET_IGMP - dev->d_addmac = macnet_addmac; /* Add multicast MAC address */ - dev->d_rmmac = macnet_rmmac; /* Remove multicast MAC address */ + dev->d_addmac = macnet_addmac; /* Add multicast MAC address */ + dev->d_rmmac = macnet_rmmac; /* Remove multicast MAC address */ #endif #ifdef CONFIG_NETDEV_IOCTL - dev->d_ioctl = macnet_ioctl; /* Handle network IOCTL commands */ + dev->d_ioctl = macnet_ioctl; /* Handle network IOCTL commands */ #endif - dev->d_private = (FAR void *)priv; /* Used to recover private state from dev */ + dev->d_private = (FAR void *)priv; /* Used to recover private state from dev */ /* Create a watchdog for timing polling for and timing of transmisstions */ - priv->md_mac = mac; /* Save the MAC interface instance */ - priv->md_txpoll = wd_create(); /* Create periodic poll timer */ - priv->md_txtimeout = wd_create(); /* Create TX timeout timer */ + priv->md_mac = mac; /* Save the MAC interface instance */ + priv->md_txpoll = wd_create(); /* Create periodic poll timer */ + priv->md_txtimeout = wd_create(); /* Create TX timeout timer */ DEBUGASSERT(priv->md_txpoll != NULL && priv->md_txtimeout != NULL); + /* Initialize the Network frame-related callbacks */ + + ieee->i_get_mhrlen = macnet_get_mhrlen; /* Get MAC header length */ + ieee->i_req_data = macnet_req_data; /* Enqueue frame for transmission */ + /* Initialize the MAC callbacks */ priv->md_cb.mc_priv = priv; -- GitLab From 0afae22638f90026f2c3f7b72f89fa4a43433f74 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 3 May 2017 08:01:30 -0600 Subject: [PATCH 685/990] MAC: meta data must be const to assure that it is not modified. --- include/nuttx/wireless/ieee802154/ieee802154_mac.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index 4231374371..8c97669c54 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -504,7 +504,7 @@ struct ieee802154_frame_meta_s #endif #ifdef CONFIG_IEEE802154_UWB - /* The UWB Pulse Repetion Frequency to be used for the transmission */ + /* The UWB Pulse Repetition Frequency to be used for the transmission */ enum ieee802154_uwbprf_e uwb_prf; @@ -535,8 +535,8 @@ struct ieee802154_frame_meta_s struct ieee802154_data_req_s { - FAR struct ieee802154_frame_meta_s *meta; /* Metadata describing the req */ - FAR struct iob_s *frame; /* Frame IOB with payload */ + FAR const struct ieee802154_frame_meta_s *meta; /* Metadata describing the req */ + FAR struct iob_s *frame; /* Frame IOB with payload */ }; /***************************************************************************** -- GitLab From 1ac1b6e68f40f0a7e1e6b8497d32e2970ef51bdf Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 3 May 2017 08:04:20 -0600 Subject: [PATCH 686/990] MAC: meta data must be const to assure that it is not modified. --- wireless/ieee802154/mac802154.c | 4 ++-- wireless/ieee802154/mac802154.h | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index 39bdb2ec2a..491641da99 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -844,7 +844,7 @@ int mac802154_ioctl(MACHANDLE mac, int cmd, unsigned long arg) ****************************************************************************/ int mac802154_get_mhrlen(MACHANDLE mac, - FAR struct ieee802154_frame_meta_s *meta) + FAR const struct ieee802154_frame_meta_s *meta) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; @@ -927,7 +927,7 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; FAR struct mac802154_trans_s trans; - FAR struct ieee802154_frame_meta_s *meta = req->meta; + FAR const struct ieee802154_frame_meta_s *meta = req->meta; uint16_t *frame_ctrl; uint8_t mhr_len = 3; /* Start assuming frame control and seq. num */ int ret; diff --git a/wireless/ieee802154/mac802154.h b/wireless/ieee802154/mac802154.h index d0d7e82ce2..8042b84c33 100644 --- a/wireless/ieee802154/mac802154.h +++ b/wireless/ieee802154/mac802154.h @@ -106,7 +106,7 @@ int mac802154_ioctl(MACHANDLE mac, int cmd, unsigned long arg); ****************************************************************************/ int mac802154_get_mhrlen(MACHANDLE mac, - FAR struct ieee802154_frame_meta_s *meta); + FAR const struct ieee802154_frame_meta_s *meta); /**************************************************************************** * Name: mac802154_req_data -- GitLab From 893c42561f0191fe6c9f5291dd4037714025b0d9 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Tue, 2 May 2017 13:58:57 -0400 Subject: [PATCH 687/990] wireless/ieee802154: Sets up default PIB attributes --- wireless/ieee802154/mac802154.c | 58 +++++++++++++++++++++++++++++++-- 1 file changed, 55 insertions(+), 3 deletions(-) diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index 491641da99..4c906a669d 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -219,8 +219,8 @@ struct ieee802154_privmac_s uint32_t batt_life_ext : 1; /* Is BLE enabled */ uint32_t gts_permit : 1; /* Is PAN Coord. accepting GTS reqs. */ - uint32_t promiscuous_mode : 1; /* Is promiscuous mode on? */ - uint32_t ranging_supported : 1; /* Does MAC sublayer support ranging */ + uint32_t promisc_mode : 1; /* Is promiscuous mode on? */ + uint32_t rng_support : 1; /* Does MAC sublayer support ranging */ uint32_t rx_when_idle : 1; /* Recvr. on during idle periods */ uint32_t sec_enabled : 1; /* Does MAC sublayer have security en. */ @@ -415,7 +415,59 @@ static FAR struct mac802154_trans_s * static int mac802154_defaultmib(FAR struct ieee802154_privmac_s *priv) { - /* TODO: Set all MAC fields to default values */ + priv->is_assoc = false; /* Not associated with a PAN */ + priv->assoc_permit = false; /* Device (if coord) not accepting association */ + priv->auto_req = true; /* Auto send data req if addr. in beacon */ + priv->batt_life_ext = false; /* BLE disabled */ + priv->beacon_payload_len = 0; /* Beacon payload NULL */ + priv->beacon_order = 15; /* Non-beacon enabled network */ + priv->superframe_order = 15; /* Length of active portion of outgoing SF */ + priv->beacon_tx_time = 0; /* Device never sent a beacon */ + priv->bsn = + priv->dsn = + priv->gts_permit = true; /* PAN Coord accepting GTS requests */ + priv->min_be = 3; /* Min value of backoff exponent (BE) */ + priv->max_be = 5; /* Max value of backoff exponent (BE) */ + priv->max_csma_backoffs = 4; /* Max # of backoffs before failure */ + priv->max_retries = 3; /* Max # of retries allowed after failure */ + priv->promisc_mode = false; /* Device not in promiscuous mode */ + priv->rng_support = false; /* Ranging not yet supported */ + priv->resp_wait_time = 32; /* 32 SF durations */ + priv->rx_on_idle = false; /* Don't receive while idle */ + priv->sec_enabled = false; /* Security disabled by default */ + priv->tx_total_dur = 0; /* 0 transmit duration */ + + priv->trans_persist_time = 0x01F4; + + + /* Reset the Coordinator address */ + + priv->coord_addr.mode = IEEE802154_ADDRMODE_NONE; + priv->coord_addr.saddr = IEEE802154_SADDR_UNSPEC; + memcpy(&priv->coord_addr.eaddr[0], IEEE802154_EADDR_UNSPEC, 8); + + /* Reset the device's address */ + + priv->addr.mode = IEEE802154_ADDRMODE_NONE; + priv->addr.pan_id = IEEE802154_PAN_UNSPEC; + priv->addr.saddr = IEEE802154_SADDR_UNSPEC; + memcpy(&priv->addr.eaddr[0], IEEE802154_EADDR_UNSPEC, 8); + + + /* These attributes are effected and determined based on the PHY. Need to + * figure out how to "share" attributes between the radio driver and this + * MAC layer + * + * macAckWaitDuration + * macBattLifeExtPeriods + * macMaxFrameTotalWaitTime + * macLIFSPeriod + * macSIFSPeriod + * macSyncSymbolOffset + * macTimestampSupported + * macTxControlActiveDuration + * macTxControlPauseDuration + */ return OK; } -- GitLab From 653a0217f2ff4d48fd76f775a67822d0279af684 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Tue, 2 May 2017 13:59:22 -0400 Subject: [PATCH 688/990] wireless/ieee802154: Finishes some IOCTL logic for MAC layer --- .../wireless/ieee802154/ieee802154_mac.h | 6 +- wireless/ieee802154/mac802154.c | 100 +++++++++++++++--- wireless/ieee802154/mac802154.h | 12 +-- wireless/ieee802154/mac802154_device.c | 14 +-- 4 files changed, 100 insertions(+), 32 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index 8c97669c54..68369ab75f 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -168,7 +168,7 @@ #define IEEE802154_GTS_DESC_PERSISTENCE_TIME 4 #define IEEE802154_MAX_BEACON_OVERHEAD 75 -#define IEEE802154_MAX_BEACON_PAYLOAD_LENGTH \ +#define IEEE802154_MAX_BEACON_PAYLOAD_LEN \ (IEEE802154_MAX_PHY_PACKET_SIZE - IEEE802154_MAX_BEACON_OVERHEAD) #define IEEE802154_MAX_LOST_BEACONS 4 @@ -840,12 +840,12 @@ struct ieee802154_beaconnotify_ind_s /* Beacon payload */ - uint8_t sdu[IEEE802154_MAX_BEACON_PAYLOAD_LENGTH]; + uint8_t sdu[IEEE802154_MAX_BEACON_PAYLOAD_LEN]; }; #define SIZEOF_IEEE802154_BEACONNOTIFY_IND_S(n) \ (sizeof(struct ieee802154_beaconnotify_ind_s) \ - - IEEE802154_MAX_BEACON_PAYLOAD_LENGTH + (n)) + - IEEE802154_MAX_BEACON_PAYLOAD_LEN + (n)) /***************************************************************************** * Primitive: MLME-COMM-STATUS.indication diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index 4c906a669d..56b220181a 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -187,7 +187,7 @@ struct ieee802154_privmac_s /* Contents of beacon payload */ - uint8_t beacon_payload[IEEE802154_MAX_BEACON_PAYLOAD_LENGTH]; + uint8_t beacon_payload[IEEE802154_MAX_BEACON_PAYLOAD_LEN]; uint8_t beacon_payload_len; /* Length of beacon payload */ uint8_t batt_life_ext_periods; /* # of backoff periods during which rx is @@ -219,8 +219,8 @@ struct ieee802154_privmac_s uint32_t batt_life_ext : 1; /* Is BLE enabled */ uint32_t gts_permit : 1; /* Is PAN Coord. accepting GTS reqs. */ - uint32_t promisc_mode : 1; /* Is promiscuous mode on? */ - uint32_t rng_support : 1; /* Does MAC sublayer support ranging */ + uint32_t promisc_mode : 1; /* Is promiscuous mode on? */ + uint32_t rng_support : 1; /* Does MAC sublayer support ranging */ uint32_t rx_when_idle : 1; /* Recvr. on during idle periods */ uint32_t sec_enabled : 1; /* Does MAC sublayer have security en. */ @@ -423,8 +423,9 @@ static int mac802154_defaultmib(FAR struct ieee802154_privmac_s *priv) priv->beacon_order = 15; /* Non-beacon enabled network */ priv->superframe_order = 15; /* Length of active portion of outgoing SF */ priv->beacon_tx_time = 0; /* Device never sent a beacon */ - priv->bsn = - priv->dsn = +#warning Set BSN and DSN to random values! + priv->bsn = 0; + priv->dsn = 0; priv->gts_permit = true; /* PAN Coord accepting GTS requests */ priv->min_be = 3; /* Min value of backoff exponent (BE) */ priv->max_be = 5; /* Max value of backoff exponent (BE) */ @@ -433,7 +434,7 @@ static int mac802154_defaultmib(FAR struct ieee802154_privmac_s *priv) priv->promisc_mode = false; /* Device not in promiscuous mode */ priv->rng_support = false; /* Ranging not yet supported */ priv->resp_wait_time = 32; /* 32 SF durations */ - priv->rx_on_idle = false; /* Don't receive while idle */ + priv->rx_when_idle = false; /* Don't receive while idle */ priv->sec_enabled = false; /* Security disabled by default */ priv->tx_total_dur = 0; /* 0 transmit duration */ @@ -449,7 +450,7 @@ static int mac802154_defaultmib(FAR struct ieee802154_privmac_s *priv) /* Reset the device's address */ priv->addr.mode = IEEE802154_ADDRMODE_NONE; - priv->addr.pan_id = IEEE802154_PAN_UNSPEC; + priv->addr.panid = IEEE802154_PAN_UNSPEC; priv->addr.saddr = IEEE802154_SADDR_UNSPEC; memcpy(&priv->addr.eaddr[0], IEEE802154_EADDR_UNSPEC, 8); @@ -859,6 +860,9 @@ int mac802154_ioctl(MACHANDLE mac, int cmd, unsigned long arg) (FAR struct ieee802154_privmac_s *)mac; int ret = -EINVAL; + FAR union ieee802154_macarg_u *macarg = + (FAR union ieee802154_macarg_u *)((uintptr_t)arg); + DEBUGASSERT(priv != NULL); /* Check for IOCTLs aimed at the IEEE802.15.4 MAC layer */ @@ -866,7 +870,75 @@ int mac802154_ioctl(MACHANDLE mac, int cmd, unsigned long arg) if (_MAC802154IOCVALID(cmd)) { /* Handle the MAC IOCTL command */ -#warning Missing logic + + switch (cmd) + { + case MAC802154IOC_MLME_ASSOC_REQUEST: + { + mac802154_req_associate(mac, &macarg->assocreq); + } + break; + case MAC802154IOC_MLME_ASSOC_RESPONSE: + { + mac802154_resp_associate(mac, &macarg->assocresp); + } + break; + case MAC802154IOC_MLME_DISASSOC_REQUEST: + { + mac802154_req_disassociate(mac, &macarg->disassocreq); + } + break; + case MAC802154IOC_MLME_GET_REQUEST: + { + mac802154_req_get(mac, &macarg->getreq); + } + break; + case MAC802154IOC_MLME_GTS_REQUEST: + { + mac802154_req_gts(mac, &macarg->gtsreq); + } + break; + case MAC802154IOC_MLME_ORPHAN_RESPONSE: + { + mac802154_resp_orphan(mac, &macarg->orphanresp); + } + break; + case MAC802154IOC_MLME_RESET_REQUEST: + { + mac802154_req_reset(mac, &macarg->resetreq); + } + break; + case MAC802154IOC_MLME_RXENABLE_REQUEST: + { + mac802154_req_rxenable(mac, &macarg->rxenabreq); + } + break; + case MAC802154IOC_MLME_SCAN_REQUEST: + { + mac802154_req_scan(mac, &macarg->scanreq); + } + break; + case MAC802154IOC_MLME_SET_REQUEST: + { + mac802154_req_set(mac, &macarg->setreq); + } + break; + case MAC802154IOC_MLME_START_REQUEST: + { + mac802154_req_start(mac, &macarg->startreq); + } + break; + case MAC802154IOC_MLME_SYNC_REQUEST: + { + mac802154_req_sync(mac, &macarg->syncreq); + } + break; + case MAC802154IOC_MLME_POLL_REQUEST: + { + mac802154_req_poll(mac, &macarg->pollreq); + } + break; + } } /* No, other IOCTLs must be aimed at the IEEE802.15.4 radio layer */ @@ -1444,7 +1516,7 @@ int mac802154_req_poll(MACHANDLE mac, FAR struct ieee802154_poll_req_s *req) } /**************************************************************************** - * Name: mac802154_rsp_associate + * Name: mac802154_resp_associate * * Description: * The MLME-ASSOCIATE.response primitive is used to initiate a response to @@ -1452,8 +1524,8 @@ int mac802154_req_poll(MACHANDLE mac, FAR struct ieee802154_poll_req_s *req) * ****************************************************************************/ -int mac802154_rsp_associate(MACHANDLE mac, - FAR struct ieee802154_assoc_resp_s *resp) +int mac802154_resp_associate(MACHANDLE mac, + FAR struct ieee802154_assoc_resp_s *resp) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; @@ -1461,7 +1533,7 @@ int mac802154_rsp_associate(MACHANDLE mac, } /**************************************************************************** - * Name: mac802154_rsp_orphan + * Name: mac802154_resp_orphan * * Description: * The MLME-ORPHAN.response primitive allows the next higher layer of a @@ -1469,8 +1541,8 @@ int mac802154_rsp_associate(MACHANDLE mac, * ****************************************************************************/ -int mac802154_rsp_orphan(MACHANDLE mac, - FAR struct ieee802154_orphan_resp_s *resp) +int mac802154_resp_orphan(MACHANDLE mac, + FAR struct ieee802154_orphan_resp_s *resp) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; diff --git a/wireless/ieee802154/mac802154.h b/wireless/ieee802154/mac802154.h index 8042b84c33..17df17ebda 100644 --- a/wireless/ieee802154/mac802154.h +++ b/wireless/ieee802154/mac802154.h @@ -282,7 +282,7 @@ int mac802154_req_sync(MACHANDLE mac, FAR struct ieee802154_sync_req_s *req); int mac802154_req_poll(MACHANDLE mac, FAR struct ieee802154_poll_req_s *req); /**************************************************************************** - * Name: mac802154_rsp_associate + * Name: mac802154_resp_associate * * Description: * The MLME-ASSOCIATE.response primitive is used to initiate a response to @@ -290,11 +290,11 @@ int mac802154_req_poll(MACHANDLE mac, FAR struct ieee802154_poll_req_s *req); * ****************************************************************************/ -int mac802154_rsp_associate(MACHANDLE mac, - FAR struct ieee802154_assoc_resp_s *resp); +int mac802154_resp_associate(MACHANDLE mac, + FAR struct ieee802154_assoc_resp_s *resp); /**************************************************************************** - * Name: mac802154_rsp_orphan + * Name: mac802154_resp_orphan * * Description: * The MLME-ORPHAN.response primitive allows the next higher layer of a @@ -302,8 +302,8 @@ int mac802154_rsp_associate(MACHANDLE mac, * ****************************************************************************/ -int mac802154_rsp_orphan(MACHANDLE mac, - FAR struct ieee802154_orphan_resp_s *resp); +int mac802154_resp_orphan(MACHANDLE mac, + FAR struct ieee802154_orphan_resp_s *resp); #undef EXTERN #ifdef __cplusplus diff --git a/wireless/ieee802154/mac802154_device.c b/wireless/ieee802154/mac802154_device.c index 83798b4734..7f76e8cd3d 100644 --- a/wireless/ieee802154/mac802154_device.c +++ b/wireless/ieee802154/mac802154_device.c @@ -602,17 +602,13 @@ static int mac802154dev_ioctl(FAR struct file *filep, int cmd, } break; #endif - - case MAC802154IOC_MLME_ASSOC_REQUEST: + default: { - FAR struct ieee802154_assoc_req_s *req = - (FAR struct ieee802154_assoc_req_s *)((uintptr_t)arg); + /* Forward any unrecognized commands to the MAC layer */ + + mac802154_ioctl(dev->md_mac, cmd, arg); } - break; - - default: - wlerr("ERROR: Unrecognized command %ld\n", cmd); - ret = -EINVAL; + break; } -- GitLab From 858685e977a55e05814736abed444961c966abf2 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 3 May 2017 09:40:42 -0600 Subject: [PATCH 689/990] 6loWPAN: Changes to use new MAC interfaces. Incomplete and needs some clean-up of dangling, unused definitions. --- include/nuttx/net/netdev.h | 6 +- include/nuttx/net/sixlowpan.h | 231 +++++-------- net/sixlowpan/sixlowpan_framelist.c | 107 +++--- net/sixlowpan/sixlowpan_framer.c | 399 ++++------------------- net/sixlowpan/sixlowpan_input.c | 168 +++------- net/sixlowpan/sixlowpan_internal.h | 160 ++++----- net/sixlowpan/sixlowpan_send.c | 7 +- wireless/ieee802154/mac802154_loopback.c | 111 ++----- wireless/ieee802154/mac802154_netdev.c | 107 +----- 9 files changed, 335 insertions(+), 961 deletions(-) diff --git a/include/nuttx/net/netdev.h b/include/nuttx/net/netdev.h index eb84a7774f..7f8e4041f4 100644 --- a/include/nuttx/net/netdev.h +++ b/include/nuttx/net/netdev.h @@ -437,7 +437,9 @@ int ipv6_input(FAR struct net_driver_s *dev); #ifdef CONFIG_NET_6LOWPAN struct ieee802154_driver_s; /* See sixlowpan.h */ -int sixlowpan_input(FAR struct ieee802154_driver_s *ieee); +struct iob_s; /* See iob.h */ +int sixlowpan_input(FAR struct ieee802154_driver_s *ieee, + FAR struct iob_s *framelist); #endif /**************************************************************************** @@ -513,7 +515,7 @@ int devif_timer(FAR struct net_driver_s *dev, devif_poll_callback_t callback); * * If no Neighbor Table entry is found for the destination IPv6 address, * the packet in the d_buf[] is replaced by an ICMPv6 Neighbor Solict - * request packet for the IPv6 address. The IPv6 packet is dropped and + * request packet for the IPv6 address. The IPv6 packet is dropped and * it is assumed that the higher level protocols (e.g., TCP) eventually * will retransmit the dropped packet. * diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index 2e65199513..85c95329dc 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -1,6 +1,7 @@ /**************************************************************************** * include/nuttx/net/sixlowpan.h - * Header file for the 6lowpan implementation (RFC4944 and draft-hui-6lowpan-hc-01) + * Header file for the 6lowpan implementation (RFC4944 and + * draft-hui-6lowpan-hc-01) * * Copyright (C) 2017, Gregory Nutt, all rights reserved * Author: Gregory Nutt @@ -271,61 +272,6 @@ (a)[4] == 0 && (a)[5] == 0 && (a)[6] == 0 && \ (((a)[7] & HTONS(0xff00)) == 0x0000)) -/* Frame buffer helper macros ***********************************************/ -/* The IEEE802.15.4 MAC driver structures includes a list of IOB - * structures, i_framelist, containing frames to be sent by the driver or - * that were received by the driver. The IOB structure is defined in - * include/nuttx/drivers/iob.h. The length of data in the IOB is provided by - * the io_len field of the IOB structure. - * - * NOTE that IOBs must be configured such that CONFIG_IOB_BUFSIZE >= - * CONFIG_NET_6LOWPAN_FRAMELEN - * - * 1. On a TX poll, the IEEE802.15.4 MAC driver should provide its driver - * structure with i_framelist set to NULL. At the conclusion of the - * poll, if there are frames to be sent, they will have been added to - * the i_framelist. The non-empty frame list is the indication that - * there is data to be sent. - * - * The IEEE802.15.4 may use the FRAME_IOB_EMPTY() macro to determine - * if there there frames to be sent. If so, it should remove each - * frame from the frame list using the FRAME_IOB_REMOVE() macro and send - * it. That macro will return NULL when all of the frames have been - * sent. - * - * After sending each frame, the driver must return the IOB to the pool - * of free IOBs using the FROM_IOB_FREE() macro. - */ - - -#define FRAME_IOB_EMPTY(ieee) ((ieee)->i_framelist == NULL) -#define FRAME_IOB_REMOVE(ieee, iob) \ - do \ - { \ - (iob) = (ieee)->i_framelist; \ - (ieee)->i_framelist = (iob)->io_flink; \ - (iob)->io_flink = NULL; \ - } \ - while (0) -#define FRAME_IOB_FREE(iob) iob_free(iob) - -/* 2. When receiving data, the IEEE802.15.4 MAC driver should receive the - * frame data directly into the payload area of an IOB structure. That - * IOB structure may be obtained using the FRAME_IOB_ALLOC() macro. The - * single frame should be added to the frame list using FRAME_IOB_ADD() - * (it will be a list of length one) . The MAC driver should then inform - * the network of the by calling sixlowpan_input(). - */ - -#define FRAME_IOB_ALLOC() iob_alloc(false) -#define FRAME_IOB_ADD(ieee, iob) \ - do \ - { \ - (iob)->io_flink = (ieee)->i_framelist; \ - (ieee)->i_framelist = (iob); \ - } \ - while (0) - /**************************************************************************** * Public Types ****************************************************************************/ @@ -335,18 +281,21 @@ * difference is that fragmentation must be supported. * * The IEEE802.15.4 MAC does not use the d_buf packet buffer directly. - * Rather, it uses a list smaller frame buffers, i_framelist. + * Rather, it uses a list smaller frame buffers. * - * - The packet fragment data is provided to an IOB in the i_framelist - * buffer each time that the IEEE802.15.4 MAC needs to send more data. - * The length of the frame is provided in the io_len field of the IOB. + * - The packet fragment data is provided in an IOB in the via the + * i_req_data() interface method each time that the IEEE802.15.4 MAC + * needs to send more data. The length of the frame is provided in the + * io_len field of the IOB. * * In this case, the d_buf is not used at all and, if fact, may be * NULL. * * - Received frames are provided by IEEE802.15.4 MAC to the network - * via and IOB in i_framelist with length io_len for reassembly in - * d_buf; d_len will hold the size of the reassembled packet. + * via an IOB parameter in the sixlowpan_submit() interface. The + * length of the frawme is io_len and will be uncompressed and possibly + * reassembled in the d_buf; d_len will hold the size of the + * reassembled packet. * * In this case, a d_buf of size CONFIG_NET_6LOWPAN_MTU must be provided. * @@ -360,49 +309,40 @@ * this structure. In general, all fields must be set to NULL. In * addtion: * - * 1. i_dsn must be set to a random value. After that, it will be managed - * by the network. - * - * 2. On a TX poll, the IEEE802.15.4 MAC driver should provide its driver - * structure with i_framelist set to NULL. At the conclusion of the - * poll, if there are frames to be sent, they will have been added to - * the i_framelist. The non-empty frame list at the conclusion of the - * TX poll is the indication that is data to be sent. - * - * The IEEE802.15.4 may use the FRAME_IOB_EMPTY() macro to determine - * if there there frames to be sent. If so, it should remove each - * frame from the frame list using the FRAME_IOB_REMOVE() macro and send - * it. That macro will return NULL when all of the frames have been - * sent. + * 1. On a TX poll, the IEEE802.15.4 MAC driver should provide its driver + * structure. During the course of the poll, the networking layer may + * generate outgoing frames. These frames will by provided to the MAC + * driver via the req_data() method. * - * After sending each frame, the driver must return the IOB to the pool - * of free IOBs using the FROM_IOB_FREE() macro. + * After sending each frame through the radio, the MAC driver must + * return the frame to the pool of free IOBs using the iob_free(). * - * 3. When receiving data both buffers must be provided: + * 2. When receiving data both buffers must be provided: * * The IEEE802.15.4 MAC driver should receive the frame data directly - * into the payload area of an IOB structure. That IOB structure may be - * obtained using the FRAME_IOB_ALLOC() macro. The single frame should - * be added to the frame list using FRAME_IOB_ADD() (it will be a list of - * length one). + * into the payload area of an IOB frame structure. That IOB structure + * may be obtained using the iob_alloc() function. * * The larger dev.d_buf must have a size 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. + * of the protocol, CONFIG_NET_6LOWPAN_MTU, plus CONFIG_NET_GUARDSIZE. + * 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. * * The MAC driver should then inform the network of the by calling - * sixlowpan_input(). + * sixlowpan_input(). That single frame (or, perhaps, list of frames) + * should be provided as second argument of that call. * - * Normally, the network will free the IOB and will nullify the frame - * list. But ss a complexity, the result of receiving a frame may be - * that the network may respond provide an outgoing frames in the - * frame list. + * The network will free the IOB by calling iob_free after it has + * processed the incoming frame. As a complexity, the result of + * receiving a frame may be that the network may respond provide an + * outgoing frames in the via a nested calle to the req_data() method. */ struct ieee802154_frame_meta_s; /* Forward reference */ +struct iob_s; /* Forward reference */ struct ieee802154_driver_s { @@ -414,33 +354,22 @@ struct ieee802154_driver_s /* IEEE802.15.4 MAC-specific definitions follow. */ - /* The i_framelist is used to hold a outgoing frames contained in IOB - * structures. When the IEEE802.15.4 device polls for new TX data, the - * outgoing frame(s) containing the packet fragments are placed in IOBs - * and queued in i_framelist. - * - * The i_framelist is similary used to hold incoming frames in IOB - * structures. The IEEE802.15.4 MAC driver must receive frames in an IOB, - * place the IOB in the i_framelist, and call sixlowpan_input(). + /* The msdu_handle is basically an id for the frame. The standard just + * says that the next highest layer should determine it. It is used in + * three places * - * The IEEE802.15.4 MAC driver design may be concurrently sending and - * requesting new frames using lists of IOBs. That IOB frame buffer - * management must be managed by the IEEE802.15.4 MAC driver. - */ - - FAR struct iob_s *i_framelist; - - /* Driver Configuration ***************************************************/ - /* i_dsn. The sequence number in the range 0x00-0xff added to the - * transmitted data or MAC command frame. The default is a random value - * within that range. + * 1. When you do that data request + * 2. When the transmission is complete, the conf_data is called with + * that handle so that the user can be notified of the frames success/ + * failure + * 3. For a req_purge, to basically "cancel" the transaction. This is + * often particularly useful on a coordinator that has indirect data + * waiting to be requested from another device * - * This field must be initialized to a random number by the IEEE802.15.4 - * MAC driver. It sill be subsequently incremented on each frame by the - * network logic. + * Here is a simple frame counter. */ - uint8_t i_dsn; + uint8_t i_msdu_handle; #if CONFIG_NET_6LOWPAN_FRAG /* Fragmentation Support *************************************************/ @@ -511,7 +440,7 @@ struct ieee802154_driver_s **************************************************************************/ CODE int (*i_get_mhrlen)(FAR struct ieee802154_driver_s *netdev, - FAR struct ieee802154_frame_meta_s *meta); + FAR const struct ieee802154_frame_meta_s *meta); /************************************************************************** * Name: mac802154_req_data @@ -525,7 +454,7 @@ struct ieee802154_driver_s **************************************************************************/ CODE int (*i_req_data)(FAR struct ieee802154_driver_s *netdev, - FAR struct ieee802154_frame_meta_s *meta, + FAR const struct ieee802154_frame_meta_s *meta, FAR struct iob_s *frames); }; @@ -539,25 +468,32 @@ struct ieee802154_driver_s * Description: * Process an incoming 6loWPAN frame. * - * This function is called when the device driver has received a 6loWPAN - * frame from the network. The frame from the device driver must be - * provided in a IOB present in the i_framelist: The frame data is in the - * IOB io_data[] buffer and the length of the frame is in the IOB io_len - * field. Only a single IOB is expected in the i_framelist. This incoming - * data will be processed one frame at a time. - * - * An non-NULL d_buf of size CONFIG_NET_6LOWPAN_MTU must also be provided. - * The frame will be decompressed and placed in the d_buf. Fragmented - * packets will also be reassembled in the d_buf as they are received - * (meaning for the driver, that two packet buffers are required: One for - * reassembly of RX packets and one used for TX polling). - * - * After each frame is processed into d_buf, the IOB is removed and - * deallocated. i_framelist will be nullified. If reassembly is - * incomplete, this function will return to called with i_framelist - * equal to NULL. The partially reassembled packet must be preserved by - * the IEEE802.15.4 MAC and provided again when the next frame is - * received. + * This function is called when the device driver has received an + * IEEE802.15.4 frame from the network. The frame from the device + * driver must be provided in by the IOB frame argument of the + * function call: + * + * - The frame data is in the IOB io_data[] buffer, + * - The length of the frame is in the IOB io_len field, and + * - The offset past the IEEE802.15.4 MAC header is provided in the + * io_offset field. + * + * The frame argument may refer to a single frame (a list of length one) + * or may it be the head of a list of multiple frames. + * + * - The io_flink field points to the next frame in the list (if enable) + * - The last frame in the list will have io_flink == NULL. + * + * An non-NULL d_buf of size CONFIG_NET_6LOWPAN_MTU + CONFIG_NET_GUARDSIZE + * must also be provided. The frame will be decompressed and placed in + * the d_buf. Fragmented packets will also be reassembled in the d_buf as + * they are received (meaning for the driver, that two packet buffers are + * required: One for reassembly of RX packets and one used for TX polling). + * + * After each frame is processed into d_buf, the IOB is deallocated. If + * reassembly is incomplete, the partially reassembled packet must be + * preserved by the IEEE802.15.4 MAC network drvier sand provided again + * when the next frame is received. * * When the packet in the d_buf is fully reassembled, it will be provided * to the network as with any other received packet. d_len will be set @@ -565,28 +501,25 @@ struct ieee802154_driver_s * * After the network processes the packet, d_len will be set to zero. * Network logic may also decide to send a response to the packet. In - * that case, the outgoing network packet will be placed in d_buf the - * d_buf and d_len will be set to a non-zero value. That case is handled - * by this function. + * that case, the outgoing network packet will be placed in d_buf and + * d_len will be set to a non-zero value. That case is handled by this + * function. * * If that case occurs, the packet will be converted to a list of - * compressed and possibly fragmented frames in i_framelist as with other - * TX operations. - * - * So from the standpoint of the IEEE802.15.4 MAC driver, there are two - * possible results: (1) i_framelist is NULL meaning that the frame - * was fully processed and freed, or (2) i_framelist is non-NULL meaning - * that there are outgoing frame(s) to be sent. + * compressed and possibly fragmented frames and provided to the MAC + * network driver via the req_data() method as with other TX operations. * * Input Parameters: - * ieee - The IEEE802.15.4 MAC network driver interface. + * ieee - The IEEE802.15.4 MAC network driver interface. + * framelist - The head of an incoming list of frames. * * Returned Value: * Ok is returned on success; Othewise a negated errno value is returned. * ****************************************************************************/ -int sixlowpan_input(FAR struct ieee802154_driver_s *ieee); +int sixlowpan_input(FAR struct ieee802154_driver_s *ieee, + FAR struct iob_s *framelist); #endif /* CONFIG_NET_6LOWPAN */ #endif /* __INCLUDE_NUTTX_NET_SIXLOWPAN_H */ diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c index 91e3369b81..e4e769c0ce 100644 --- a/net/sixlowpan/sixlowpan_framelist.c +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -55,6 +55,7 @@ #include #include +#include #include "sixlowpan/sixlowpan_internal.h" @@ -183,9 +184,8 @@ static void sixlowpan_compress_ipv6hdr(FAR const struct ipv6_hdr_s *ipv6hdr, * * The payload data is in the caller 'buf' and is of length 'buflen'. * Compressed headers will be added and if necessary the packet is - * fragmented. The resulting packet/fragments are put in ieee->i_framelist - * and the entire list of frames will be delivered to the 802.15.4 MAC via - * ieee->i_framelist. + * fragmented. The resulting packet/fragments are submitted to the MAC + * where they are queue for transfer. * * Input Parameters: * ieee - The IEEE802.15.4 MAC driver instance @@ -211,6 +211,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, FAR const void *buf, size_t buflen, FAR const struct rimeaddr_s *destmac) { + struct ieee802154_frame_meta_s meta; FAR struct iob_s *iob; FAR uint8_t *fptr; int framer_hdrlen; @@ -221,6 +222,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, #ifdef CONFIG_NET_6LOWPAN_FRAG uint16_t outlen = 0; #endif + int ret; /* Initialize global data. Locking the network guarantees that we have * exclusive use of the global values for intermediate calculations. @@ -297,18 +299,33 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, dest_panid = 0xffff; (void)sixlowpan_src_panid(ieee, &dest_panid); + /* Based on the collected attributes and addresses, construct the MAC meta + * data structure that we need to interface with the IEEE802.15.4 MAC. + */ + + ret = sixlowpan_meta_data(dest_panid, &meta); + if (ret < 0) + { + nerr("ERROR: sixlowpan_meta_data() failed: %d\n", ret); + } + /* Pre-calculate frame header length. */ - framer_hdrlen = sixlowpan_send_hdrlen(ieee, dest_panid); + framer_hdrlen = sixlowpan_frame_hdrlen(ieee, &meta); if (framer_hdrlen < 0) { /* Failed to determine the size of the header failed. */ - nerr("ERROR: sixlowpan_send_hdrlen() failed: %d\n", framer_hdrlen); + nerr("ERROR: sixlowpan_frame_hdrlen() failed: %d\n", framer_hdrlen); return framer_hdrlen; } - g_frame_hdrlen = framer_hdrlen; + /* This sill be the initial offset into io_data. Valid data begins at + * this offset and must be reflected in io_offset. + */ + + g_frame_hdrlen = framer_hdrlen; + iob->io_offset = framer_hdrlen; #ifndef CONFIG_NET_6LOWPAN_COMPRESSION_IPv6 if (buflen >= CONFIG_NET_6LOWPAN_COMPRESSION_THRESHOLD) @@ -338,15 +355,15 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, if (buflen > (CONFIG_NET_6LOWPAN_FRAMELEN - g_frame_hdrlen)) { #ifdef CONFIG_NET_6LOWPAN_FRAG - /* ieee->i_framelist will hold the generated frames; frames will be + /* qhead will hold the generated frame list; frames will be * added at qtail. */ + FAR struct iob_s *qhead; FAR struct iob_s *qtail; FAR uint8_t *frame1; FAR uint8_t *fragptr; uint16_t frag1_hdrlen; - int verify; /* 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. @@ -358,13 +375,6 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, ninfo("Sending fragmented packet length %d\n", buflen); /* Create 1st Fragment */ - /* Add the frame header using the pre-allocated IOB using the DSN - * selected by sixlowpan_send_hdrlen(). - */ - - verify = sixlowpan_framecreate(ieee, iob, dest_panid); - DEBUGASSERT(verify == framer_hdrlen); - UNUSED(verify); /* Move HC1/HC06/IPv6 header to make space for the FRAG1 header at the * beginning of the frame. @@ -405,8 +415,8 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, /* Set outlen to what we already sent from the IP payload */ - iob->io_len = paysize + g_frame_hdrlen; - outlen = paysize; + iob->io_len = paysize + g_frame_hdrlen; + outlen = paysize; ninfo("First fragment: length %d, tag %d\n", paysize, ieee->i_dgramtag); @@ -415,17 +425,17 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, /* Add the first frame to the IOB queue */ - ieee->i_framelist = iob; - qtail = iob; + qhead = iob; + qtail = iob; /* Keep track of the total amount of data queue */ - iob->io_pktlen = iob->io_len; + iob->io_pktlen = iob->io_len; /* Create following fragments */ - frame1 = iob->io_data; - frag1_hdrlen = g_frame_hdrlen; + frame1 = iob->io_data; + frag1_hdrlen = g_frame_hdrlen; while (outlen < buflen) { @@ -442,20 +452,10 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, iob->io_flink = NULL; iob->io_len = 0; - iob->io_offset = 0; + iob->io_offset = framer_hdrlen; iob->io_pktlen = 0; fptr = iob->io_data; - /* Add a new frame header to the IOB (same as the first but with a - * different DSN). - */ - - g_pktattrs[PACKETBUF_ATTR_MAC_SEQNO] = 0; - - verify = sixlowpan_framecreate(ieee, iob, dest_panid); - DEBUGASSERT(verify == framer_hdrlen); - UNUSED(verify); - /* Copy the HC1/HC06/IPv6 header the frame header from first * frame, into the correct location after the FRAGN header * of subsequent frames. @@ -508,9 +508,23 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, /* Keep track of the total amount of data queue */ - ieee->i_framelist->io_pktlen += iob->io_len; + qhead->io_pktlen += iob->io_len; } + /* Submit all of the fragments to the MAC */ + + while (qhead != NULL) + { + iob = qhead; + qhead = iob->io_flink; + + ret = sixlowpan_frame_submit(ieee, &meta, iob); + if (ret < 0) + { + nerr("ERROR: sixlowpan_frame_submit() failed: %d\n", ret); + } + } + /* Update the datagram TAG value */ ieee->i_dgramtag++; @@ -524,34 +538,27 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, } else { - int verify; - /* The packet does not need to be fragmented just copy the "payload" * and send in one frame. */ - /* Add the frame header to the preallocated IOB. */ - - verify = sixlowpan_framecreate(ieee, iob, dest_panid); - DEBUGASSERT(verify == framer_hdrlen); - UNUSED(verify); - - /* Copy the payload and queue */ + /* Copy the payload into the frame. */ memcpy(fptr + g_frame_hdrlen, buf, buflen); - iob->io_len = buflen + g_frame_hdrlen; + iob->io_len = buflen + g_frame_hdrlen; + iob->io_pktlen = iob->io_len; ninfo("Non-fragmented: length %d\n", iob->io_len); sixlowpan_dumpbuffer("Outgoing frame", (FAR const uint8_t *)iob->io_data, iob->io_len); - /* Add the first frame to the IOB queue */ - - ieee->i_framelist = iob; - - /* Keep track of the total amount of data queue */ + /* Submit the frame to the MAC */ - iob->io_pktlen = iob->io_len; + ret = sixlowpan_frame_submit(ieee, &meta, iob); + if (ret < 0) + { + nerr("ERROR: sixlowpan_frame_submit() failed: %d\n", ret); + } } return OK; diff --git a/net/sixlowpan/sixlowpan_framer.c b/net/sixlowpan/sixlowpan_framer.c index b85819993e..9a32310d02 100644 --- a/net/sixlowpan/sixlowpan_framer.c +++ b/net/sixlowpan/sixlowpan_framer.c @@ -52,31 +52,16 @@ #include #include #include +#include #include #include "nuttx/net/net.h" +#include "nuttx/wireless/ieee802154/ieee802154_mac.h" #include "sixlowpan/sixlowpan_internal.h" #ifdef CONFIG_NET_6LOWPAN -/**************************************************************************** - * Private Types - ****************************************************************************/ - -/* Structure that contains the lengths of the various addressing and - * security fields in the 802.15.4 header. - */ - -struct field_length_s -{ - uint8_t dest_pid_len; /* Length (in bytes) of destination PAN ID field */ - uint8_t dest_addr_len; /* Length (in bytes) of destination address field */ - uint8_t src_pid_len; /* Length (in bytes) of source PAN ID field */ - uint8_t src_addr_len; /* Length (in bytes) of source address field */ - uint8_t aux_sec_len; /* Length (in bytes) of aux security header field */ -}; - /**************************************************************************** * Public Functions ****************************************************************************/ @@ -138,172 +123,47 @@ static bool sixlowpan_addrnull(FAR uint8_t *addr) return true; } - -/**************************************************************************** - * Name: sixlowpan_fieldlengths - * - * Description: - * Return the lengths associated fields of the IEEE802.15.4 header. - * - * Input parameters: - * finfo - IEEE802.15.4 header info (input) - * flen - Field length info (output) - * - * Returned Value: - * None - * - ****************************************************************************/ - -static void sixlowpan_fieldlengths(FAR struct frame802154_s *finfo, - FAR struct field_length_s *flen) -{ - /* Initialize to all zero */ - - memset(flen, 0, sizeof(struct field_length_s)); - - /* Determine lengths of each field based on fcf and other args */ - - if ((finfo->fcf.dest_addr_mode & 3) != 0) - { - flen->dest_pid_len = 2; - } - - if ((finfo->fcf.src_addr_mode & 3) != 0) - { - flen->src_pid_len = 2; - } - - /* Set PAN ID compression bit if src pan id matches dest pan id. */ - - if ((finfo->fcf.dest_addr_mode & 3) != 0 && - (finfo->fcf.src_addr_mode & 3) != 0 && - finfo->src_pid == finfo->dest_pid) - { - /* Indicate source PANID compression */ - - finfo->fcf.panid_compression = 1; - - /* Compressed header, only do dest pid. - * - * REVISIT: This was commented out in corresponding Contiki logic, but - * is needed to match sixlowpan_recv_hdrlen(). - */ - - flen->src_pid_len = 0; - } - - /* Determine address lengths */ - - flen->dest_addr_len = sixlowpan_addrlen(finfo->fcf.dest_addr_mode & 3); - flen->src_addr_len = sixlowpan_addrlen(finfo->fcf.src_addr_mode & 3); - - /* Aux security header */ - -#if 0 /* TODO Aux security header not yet implemented */ - if ((finfo->fcf.security_enabled & 1) != 0) - { - switch(finfo->aux_hdr.security_control.key_id_mode) - { - case 0: - flen->aux_sec_len = 5; /* Minimum value */ - break; - - case 1: - flen->aux_sec_len = 6; - break; - - case 2: - flen->aux_sec_len = 10; - break; - - case 3: - flen->aux_sec_len = 14; - break; - - default: - break; - } - } -#endif -} - -/**************************************************************************** - * Name: sixlowpan_fieldlengths - * - * Description: - * Return the lengths associated fields of the IEEE802.15.4 header. - * - * Input parameters: - * finfo - IEEE802.15.4 header info (input) - * flen - Field length info (output) - * - * Returned Value: - * None - * - ****************************************************************************/ - -static int sixlowpan_flen_hdrlen(FAR const struct field_length_s *flen) -{ - return 3 + flen->dest_pid_len + flen->dest_addr_len + - flen->src_pid_len + flen->src_addr_len + flen->aux_sec_len; -} - /**************************************************************************** - * Name: sixlowpan_802154_hdrlen - * - * Description: - * Calculates the length of the frame header. This function is meant to - * be called by a higher level function, that interfaces to a MAC. - * - * Input parameters: - * finfo - IEEE802.15.4 header info that specifies the frame to send. - * - * Returned Value: - * The length of the frame header. - * + * Public Functions ****************************************************************************/ -static int sixlowpan_802154_hdrlen(FAR struct frame802154_s *finfo) -{ - struct field_length_s flen; - - sixlowpan_fieldlengths(finfo, &flen); - return sixlowpan_flen_hdrlen(&flen); -} - /**************************************************************************** - * Name: sixlowpan_setup_params + * Name: sixlowpan_meta_data * * Description: - * Configure frame parmeters structure. + * Based on the collected attributes and addresses, construct the MAC meta + * data structure that we need to interface with the IEEE802.15.4 MAC. * - * Input parameters: - * ieee - A reference IEEE802.15.4 MAC network device structure. - * iob - The IOB in which to create the frame. + * Input Parameters: * dest_panid - PAN ID of the destination. May be 0xffff if the destination * is not associated. - * params - Where to put the parmeters + * meta - Location to return the corresponding meta data. * * Returned Value: - * None. + * Ok is returned on success; Othewise a negated errno value is returned. + * + * Assumptions: + * Called with the network locked. * ****************************************************************************/ -static void sixlowpan_setup_params(FAR struct ieee802154_driver_s *ieee, - uint16_t dest_panid, - FAR struct frame802154_s *params) +int sixlowpan_meta_data(uint16_t dest_panid, + FAR struct ieee802154_frame_meta_s *meta) { +#if 0 /* To be provided */ + /* Set up the frame parameters */ + uint16_t src_panid; bool rcvrnull; /* Initialize all prameters to all zero */ - memset(params, 0, sizeof(params)); + memset(meta, 0, sizeof(struct ieee802154_frame_meta_s)); /* Build the FCF (Only non-zero elements need to be initialized). */ - params->fcf.frame_type = FRAME802154_DATAFRAME; - params->fcf.frame_pending = g_pktattrs[PACKETBUF_ATTR_PENDING]; + meta->fcf.frame_type = FRAME802154_DATAFRAME; + meta->fcf.frame_pending = g_pktattrs[PACKETBUF_ATTR_PENDING]; /* If the output address is NULL in the Rime buf, then it is broadcast * on the 802.15.4 network. @@ -312,24 +172,12 @@ static void sixlowpan_setup_params(FAR struct ieee802154_driver_s *ieee, rcvrnull = sixlowpan_addrnull(g_pktaddrs[PACKETBUF_ADDR_RECEIVER].u8); if (rcvrnull) { - params->fcf.ack_required = g_pktattrs[PACKETBUF_ATTR_MAC_ACK]; + meta->fcf.ack_required = g_pktattrs[PACKETBUF_ATTR_MAC_ACK]; } /* Insert IEEE 802.15.4 (2003) version bit. */ - params->fcf.frame_version = FRAME802154_IEEE802154_2003; - - /* Increment and set the data sequence number. */ - - if (g_pktattrs[PACKETBUF_ATTR_MAC_SEQNO] != 0) - { - params->seq = g_pktattrs[PACKETBUF_ATTR_MAC_SEQNO] & 0xff; - } - else - { - params->seq = ieee->i_dsn++; - g_pktattrs[PACKETBUF_ATTR_MAC_SEQNO] = params->seq | 0x100; - } + meta->fcf.frame_version = FRAME802154_IEEE802154_2003; /* Complete the addressing fields. */ /* Get the source PAN ID from the IEEE802.15.4 radio driver */ @@ -339,8 +187,8 @@ static void sixlowpan_setup_params(FAR struct ieee802154_driver_s *ieee, /* Set the source and destination PAN ID. */ - params->src_pid = src_panid; - params->dest_pid = dest_panid; + meta->src_pid = src_panid; + meta->dest_pid = dest_panid; /* If the output address is NULL in the Rime buf, then it is broadcast * on the 802.15.4 network. @@ -350,46 +198,46 @@ static void sixlowpan_setup_params(FAR struct ieee802154_driver_s *ieee, { /* Broadcast requires short address mode. */ - params->fcf.dest_addr_mode = FRAME802154_SHORTADDRMODE; - params->dest_addr[0] = 0xff; - params->dest_addr[1] = 0xff; + meta->fcf.dest_addr_mode = FRAME802154_SHORTADDRMODE; + meta->dest_addr[0] = 0xff; + meta->dest_addr[1] = 0xff; } else { /* Copy the destination address */ - rimeaddr_copy((struct rimeaddr_s *)¶ms->dest_addr, + rimeaddr_copy((struct rimeaddr_s *)&meta->dest_addr, g_pktaddrs[PACKETBUF_ADDR_RECEIVER].u8); /* Use short destination address mode if so configured */ #ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED - params->fcf.dest_addr_mode = FRAME802154_LONGADDRMODE; + meta->fcf.dest_addr_mode = FRAME802154_LONGADDRMODE; #else - params->fcf.dest_addr_mode = FRAME802154_SHORTADDRMODE; + meta->fcf.dest_addr_mode = FRAME802154_SHORTADDRMODE; #endif } /* Set the source address to the node address assigned to the device */ - rimeaddr_copy((struct rimeaddr_s *)¶ms->src_addr, + rimeaddr_copy((struct rimeaddr_s *)&meta->src_addr, &ieee->i_dev.d_mac.ieee802154); /* Use short soruce address mode if so configured */ #ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED - params->fcf.src_addr_mode = FRAME802154_LONGADDRMODE; + meta->fcf.src_addr_mode = FRAME802154_LONGADDRMODE; #else - params->fcf.src_addr_mode = FRAME802154_SHORTADDRMODE; + meta->fcf.src_addr_mode = FRAME802154_SHORTADDRMODE; +#endif #endif -} -/**************************************************************************** - * Public Functions - ****************************************************************************/ +#warning Missing logic + return -ENOSYS; +} /**************************************************************************** - * Name: sixlowpan_send_hdrlen + * Name: sixlowpan_frame_hdrlen * * Description: * This function is before the first frame has been sent in order to @@ -397,9 +245,8 @@ static void sixlowpan_setup_params(FAR struct ieee802154_driver_s *ieee, * buffer is required to make this determination. * * Input parameters: - * ieee - A reference IEEE802.15.4 MAC network device structure. - * dest_panid - PAN ID of the destination. May be 0xffff if the destination - * is not associated. + * ieee - A reference IEEE802.15.4 MAC network device structure. + * meta - Meta data that describes the MAC header * * Returned Value: * The frame header length is returnd on success; otherwise, a negated @@ -407,171 +254,37 @@ static void sixlowpan_setup_params(FAR struct ieee802154_driver_s *ieee, * ****************************************************************************/ -int sixlowpan_send_hdrlen(FAR struct ieee802154_driver_s *ieee, - uint16_t dest_panid) +int sixlowpan_frame_hdrlen(FAR struct ieee802154_driver_s *ieee, + FAR const struct ieee802154_frame_meta_s *meta) { - struct frame802154_s params; - - /* Set up the frame parameters */ - - sixlowpan_setup_params(ieee, dest_panid, ¶ms); - - /* Return the length of the header */ - - return sixlowpan_802154_hdrlen(¶ms); + return ieee->i_get_mhrlen(ieee, meta); } /**************************************************************************** - * Name: sixlowpan_802154_framecreate - * - * Description: - * Creates a frame for transmission over the air. This function is meant - * to be called by a higher level function, that interfaces to a MAC. - * - * Input parameters: - * finfo - Pointer to struct EEE802.15.4 header structure that specifies - * the frame to send. - * buf - Pointer to the buffer to use for the frame. - * buflen - The length of the buffer to use for the frame. - * finfo - Specifies the frame to send. - * - * Returned Value: - * The length of the frame header or 0 if there was insufficient space in - * the buffer for the frame headers. - * - ****************************************************************************/ - -int sixlowpan_802154_framecreate(FAR struct frame802154_s *finfo, - FAR uint8_t *buf, int buflen) -{ - struct field_length_s flen; - uint8_t pos; - int hdrlen; - int i; - - sixlowpan_fieldlengths(finfo, &flen); - - hdrlen = sixlowpan_flen_hdrlen(&flen); - if (hdrlen > buflen) - { - /* Too little space for headers. */ - - return 0; - } - - /* OK, now we have field lengths. Time to actually construct the outgoing - * frame, and store it in the provided buffer - */ - - buf[0] = ((finfo->fcf.frame_type & 7) << FRAME802154_FRAMETYPE_SHIFT) | - ((finfo->fcf.security_enabled & 1) << FRAME802154_SECENABLED_SHIFT) | - ((finfo->fcf.frame_pending & 1) << FRAME802154_FRAMEPENDING_SHIFT) | - ((finfo->fcf.ack_required & 1) << FRAME802154_ACKREQUEST_SHIFT) | - ((finfo->fcf.panid_compression & 1) << FRAME802154_PANIDCOMP_SHIFT); - buf[1] = ((finfo->fcf.dest_addr_mode & 3) << FRAME802154_DSTADDR_SHIFT) | - ((finfo->fcf.frame_version & 3) << FRAME802154_VERSION_SHIFT) | - ((finfo->fcf.src_addr_mode & 3) << FRAME802154_SRCADDR_SHIFT); - - /* Sequence number */ - - buf[2] = finfo->seq; - pos = 3; - - /* Destination PAN ID */ - - if (flen.dest_pid_len == 2) - { - buf[pos++] = finfo->dest_pid & 0xff; - buf[pos++] = (finfo->dest_pid >> 8) & 0xff; - } - - /* Destination address */ - - for (i = flen.dest_addr_len; i > 0; i--) - { - buf[pos++] = finfo->dest_addr[i - 1]; - } - - /* Source PAN ID */ - - if (flen.src_pid_len == 2) - { - buf[pos++] = finfo->src_pid & 0xff; - buf[pos++] = (finfo->src_pid >> 8) & 0xff; - } - - /* Source address */ - - for (i = flen.src_addr_len; i > 0; i--) - { - buf[pos++] = finfo->src_addr[i - 1]; - } - - /* Aux header */ - -#if 0 /* TODO Aux security header not yet implemented */ - if (flen.aux_sec_len) - { - pos += flen.aux_sec_len; - } -#endif - - DEBUGASSERT(pos == hdrlen); - return (int)pos; -} - -/**************************************************************************** - * Name: sixlowpan_framecreate + * Name: sixlowpan_frame_submit * * Description: * This function is called after eiether (1) the IEEE802.15.4 MAC driver - * polls for TX data or (2) after the IEEE802.15.4 MAC driver provides an - * in frame and the network responds with an outgoing packet. It creates - * the IEEE802.15.4 header in the frame buffer. + * polls for TX data or (2) after the IEEE802.15.4 MAC driver provides a + * new incoming frame and the network responds with an outgoing packet. It + * submits any new outgoing frame to the MAC. * * Input parameters: - * ieee - A reference IEEE802.15.4 MAC network device structure. - * iob - The IOB in which to create the frame. - * dest_panid - PAN ID of the destination. May be 0xffff if the destination - * is not associated. + * ieee - A reference IEEE802.15.4 MAC network device structure. + * meta - Meta data that describes the MAC header + * frame - The IOB containing the frame to be submitted. * * Returned Value: - * The frame header length is returnd on success; otherwise, a negated - * errno value is return on failure. + * Zero (OK) is returned on success; otherwise, a negated errno value is + * return on any failure. * ****************************************************************************/ -int sixlowpan_framecreate(FAR struct ieee802154_driver_s *ieee, - FAR struct iob_s *iob, uint16_t dest_panid) +int sixlowpan_frame_submit(FAR struct ieee802154_driver_s *ieee, + FAR const struct ieee802154_frame_meta_s *meta, + FAR struct iob_s *frame) { - struct frame802154_s params; - int hdrlen; - - /* Set up the frame parameters */ - - sixlowpan_setup_params(ieee, dest_panid, ¶ms); - - /* Get the length of the header */ - - hdrlen = sixlowpan_802154_hdrlen(¶ms); - - /* Then create the frame */ - - sixlowpan_802154_framecreate(¶ms, iob->io_data, hdrlen); - - wlinfo("Frame type: %02x hdrlen: %d\n", - params.fcf.frame_type, hdrlen); -#ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED - wlinfo("Dest address: %02x:%02x:%02x:%02x:%02x:%02x:%02x:%02x\n", - params.dest_addr[0], params.dest_addr[1], params.dest_addr[2], - params.dest_addr[3], params.dest_addr[4], params.dest_addr[5], - params.dest_addr[6], params.dest_addr[7]); -#else - wlinfo("Dest address: %02x:%02x\n", - params.dest_addr[0], params.dest_addr[1]); -#endif - - return hdrlen; + return ieee->i_req_data(ieee, meta, frame); } #endif /* CONFIG_NET_6LOWPAN */ diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index bccd97677b..0c573913d9 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -129,92 +129,6 @@ static uint8_t g_bitbucket[UNCOMP_MAXHDR]; * Private Functions ****************************************************************************/ -/**************************************************************************** - * Name: sixlowpan_recv_hdrlen - * - * Description: - * Get the length of the IEEE802.15.4 FCF header on the received frame. - * - * Input Parameters: - * ieee - The IEEE802.15.4 MAC network driver interface. - * iob - The IOB containing the frame. - * - * Returned Value: - * Ok is returned on success; Othewise a negated errno value is returned. - * - * Assumptions: - * Network is locked - * - ****************************************************************************/ - -int sixlowpan_recv_hdrlen(FAR const uint8_t *fptr) -{ - uint16_t hdrlen; - uint8_t addrmode; - - /* Minimum header: 2 byte FCF + 1 byte sequence number */ - - hdrlen = 3; - - /* Account for destination address size */ - - addrmode = (fptr[1] & FRAME802154_DSTADDR_MASK) >> FRAME802154_DSTADDR_SHIFT; - if (addrmode == FRAME802154_SHORTADDRMODE) - { - /* 2 byte dest PAN + 2 byte dest short address */ - - hdrlen += 4; - } - else if (addrmode == FRAME802154_LONGADDRMODE) - { - /* 2 byte dest PAN + 8 byte dest long address */ - - hdrlen += 10; - } - else if (addrmode != FRAME802154_NOADDR) - { - nwarn("WARNING: Unrecognized address mode\n"); - - return -ENOSYS; - } - else if ((fptr[0] & (1 << FRAME802154_PANIDCOMP_SHIFT)) != 0) - { - nwarn("WARNING: PAN compression, but no destination address\n"); - - return -EINVAL; - } - - /* Account for source address size */ - - addrmode = (fptr[1] & FRAME802154_SRCADDR_MASK) >> FRAME802154_SRCADDR_SHIFT; - if (addrmode == FRAME802154_NOADDR) - { - return hdrlen; - } - else - { - /* Add source PANID if PANIDs are not compressed */ - - if ((fptr[0] & (1 << FRAME802154_PANIDCOMP_SHIFT)) == 0) - { - hdrlen += 2; - } - - /* Add the length of the source address */ - - if (addrmode == FRAME802154_SHORTADDRMODE) - { - return hdrlen + 2; - } - else if (addrmode == FRAME802154_LONGADDRMODE) - { - return hdrlen + 8; - } - } - - return 0; -} - /**************************************************************************** * Name: sixlowpan_compress_ipv6hdr * @@ -245,7 +159,7 @@ static void sixlowpan_uncompress_ipv6hdr(FAR uint8_t *fptr, FAR uint8_t *bptr) { FAR struct ipv6_hdr_s *ipv6 = (FAR struct ipv6_hdr_s *)bptr; uint16_t protosize; - + /* Put uncompressed IPv6 header in d_buf. */ g_frame_hdrlen += SIXLOWPAN_IPV6_HDR_LEN; @@ -355,8 +269,8 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, * This size includes both fragmentation and FCF headers. */ - fptr = iob->io_data; - hdrsize = sixlowpan_recv_hdrlen(fptr); + fptr = iob->io_data; /* Frame data is in I/O buffer */ + hdrsize = iob->io_offset; /* Offset past the MAC header */ if (hdrsize < 0) { nwarn("Invalid IEEE802.15.2 header: %d\n", hdrsize); @@ -729,25 +643,32 @@ static int sixlowpan_dispatch(FAR struct ieee802154_driver_s *ieee) * Description: * Process an incoming 6loWPAN frame. * - * This function is called when the device driver has received a 6loWPAN - * frame from the network. The frame from the device driver must be - * provided in a IOB present in the i_framelist: The frame data is in the - * IOB io_data[] buffer and the length of the frame is in the IOB io_len - * field. Only a single IOB is expected in the i_framelist. This incoming - * data will be processed one frame at a time. - * - * An non-NULL d_buf of size CONFIG_NET_6LOWPAN_MTU must also be provided. - * The frame will be decompressed and placed in the d_buf. Fragmented - * packets will also be reassembled in the d_buf as they are received - * (meaning for the driver, that two packet buffers are required: One for - * reassembly of RX packets and one used for TX polling). - * - * After each frame is processed into d_buf, the IOB is removed and - * deallocated. i_framelist will be nullified. If reassembly is - * incomplete, this function will return to called with i_framelist - * equal to NULL. The partially reassembled packet must be preserved by - * the IEEE802.15.4 MAC and provided again when the next frame is - * received. + * This function is called when the device driver has received an + * IEEE802.15.4 frame from the network. The frame from the device + * driver must be provided in by the IOB frame argument of the + * function call: + * + * - The frame data is in the IOB io_data[] buffer, + * - The length of the frame is in the IOB io_len field, and + * - The offset past the IEEE802.15.4 MAC header is provided in the + * io_offset field. + * + * The frame argument may refer to a single frame (a list of length one) + * or may it be the head of a list of multiple frames. + * + * - The io_flink field points to the next frame in the list (if enable) + * - The last frame in the list will have io_flink == NULL. + * + * An non-NULL d_buf of size CONFIG_NET_6LOWPAN_MTU + CONFIG_NET_GUARDSIZE + * must also be provided. The frame will be decompressed and placed in + * the d_buf. Fragmented packets will also be reassembled in the d_buf as + * they are received (meaning for the driver, that two packet buffers are + * required: One for reassembly of RX packets and one used for TX polling). + * + * After each frame is processed into d_buf, the IOB is deallocated. If + * reassembly is incomplete, the partially reassembled packet must be + * preserved by the IEEE802.15.4 MAC network drvier sand provided again + * when the next frame is received. * * When the packet in the d_buf is fully reassembled, it will be provided * to the network as with any other received packet. d_len will be set @@ -755,43 +676,40 @@ static int sixlowpan_dispatch(FAR struct ieee802154_driver_s *ieee) * * After the network processes the packet, d_len will be set to zero. * Network logic may also decide to send a response to the packet. In - * that case, the outgoing network packet will be placed in d_buf the - * d_buf and d_len will be set to a non-zero value. That case is handled - * by this function. + * that case, the outgoing network packet will be placed in d_buf and + * d_len will be set to a non-zero value. That case is handled by this + * function. * * If that case occurs, the packet will be converted to a list of - * compressed and possibly fragmented frames in i_framelist as with other - * TX operations. - * - * So from the standpoint of the IEEE802.15.4 MAC driver, there are two - * possible results: (1) i_framelist is NULL meaning that the frame - * was fully processed and freed, or (2) i_framelist is non-NULL meaning - * that there are outgoing frame(s) to be sent. + * compressed and possibly fragmented frames and provided to the MAC + * network driver via the req_data() method as with other TX operations. * * Input Parameters: - * ieee - The IEEE802.15.4 MAC network driver interface. + * ieee - The IEEE802.15.4 MAC network driver interface. + * framelist - The head of an incoming list of frames. * * Returned Value: * Ok is returned on success; Othewise a negated errno value is returned. * ****************************************************************************/ -int sixlowpan_input(FAR struct ieee802154_driver_s *ieee) +int sixlowpan_input(FAR struct ieee802154_driver_s *ieee, + FAR struct iob_s *framelist) { int ret = -EINVAL; - DEBUGASSERT(ieee != NULL && !FRAME_IOB_EMPTY(ieee)); + DEBUGASSERT(ieee != NULL && framelist != NULL); - /* Verify that an IOB is provided in the device structure */ + /* Verify that an frame has been provided. */ - while (!FRAME_IOB_EMPTY(ieee)) + while (framelist != NULL) { FAR struct iob_s *iob; /* Remove the IOB containing the frame from the device structure */ - FRAME_IOB_REMOVE(ieee, iob); - DEBUGASSERT(iob != NULL); + iob = framelist; + framelist = iob->io_flink; sixlowpan_dumpbuffer("Incoming frame", iob->io_data, iob->io_len); diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index 08b2fc445c..8eecb3b49b 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -107,28 +107,27 @@ #define PACKETBUF_ATTR_LISTEN_TIME 7 #define PACKETBUF_ATTR_TRANSMIT_TIME 8 #define PACKETBUF_ATTR_MAX_MAC_TRANSMISSIONS 9 -#define PACKETBUF_ATTR_MAC_SEQNO 10 -#define PACKETBUF_ATTR_MAC_ACK 11 +#define PACKETBUF_ATTR_MAC_ACK 10 /* Scope 1 attributes: used between two neighbors only. */ -#define PACKETBUF_ATTR_RELIABLE 12 -#define PACKETBUF_ATTR_PACKET_ID 13 -#define PACKETBUF_ATTR_PACKET_TYPE 14 -#define PACKETBUF_ATTR_REXMIT 15 -#define PACKETBUF_ATTR_MAX_REXMIT 16 -#define PACKETBUF_ATTR_NUM_REXMIT 17 -#define PACKETBUF_ATTR_PENDING 18 +#define PACKETBUF_ATTR_RELIABLE 11 +#define PACKETBUF_ATTR_PACKET_ID 12 +#define PACKETBUF_ATTR_PACKET_TYPE 13 +#define PACKETBUF_ATTR_REXMIT 14 +#define PACKETBUF_ATTR_MAX_REXMIT 15 +#define PACKETBUF_ATTR_NUM_REXMIT 16 +#define PACKETBUF_ATTR_PENDING 17 /* Scope 2 attributes: used between end-to-end nodes. */ -#define PACKETBUF_ATTR_HOPS 11 -#define PACKETBUF_ATTR_TTL 20 -#define PACKETBUF_ATTR_EPACKET_ID 21 -#define PACKETBUF_ATTR_EPACKET_TYPE 22 -#define PACKETBUF_ATTR_ERELIABLE 23 +#define PACKETBUF_ATTR_HOPS 18 +#define PACKETBUF_ATTR_TTL 19 +#define PACKETBUF_ATTR_EPACKET_ID 20 +#define PACKETBUF_ATTR_EPACKET_TYPE 21 +#define PACKETBUF_ATTR_ERELIABLE 22 -#define PACKETBUF_NUM_ATTRS 24 +#define PACKETBUF_NUM_ATTRS 23 /* Addresses (indices into g_pktaddrs) */ @@ -188,69 +187,6 @@ struct ipv6icmp_hdr_s struct icmpv6_iphdr_s icmp; }; -/* IEEE802.15.4 Frame Definitions *******************************************/ -/* The IEEE 802.15.4 frame has a number of constant/fixed fields that can be - * counted to make frame construction and max payload calculations easier. - * These include: - * - * 1. FCF - 2 bytes - Fixed - * 2. Sequence number - 1 byte - Fixed - * 3. Addressing fields - 4 - 20 bytes - Variable - * 4. Aux security header - 0 - 14 bytes - Variable - * 5. CRC - 2 bytes - Fixed -*/ - -/* Defines the bitfields of the frame control field (FCF). */ - -struct frame802154_fcf_s -{ - uint8_t frame_type; /* 3 bit. Frame type field, see 802.15.4 */ - uint8_t security_enabled; /* 1 bit. True if security is used in this frame */ - uint8_t frame_pending; /* 1 bit. True if sender has more data to send */ - uint8_t ack_required; /* 1 bit. Is an ack frame required? */ - uint8_t panid_compression; /* 1 bit. Is this a compressed header? */ - /* 3 bit. Unused bits */ - uint8_t dest_addr_mode; /* 2 bit. Destination address mode, see 802.15.4 */ - uint8_t frame_version; /* 2 bit. 802.15.4 frame version */ - uint8_t src_addr_mode; /* 2 bit. Source address mode, see 802.15.4 */ -}; - -/* 802.15.4 security control bitfield. See section 7.6.2.2.1 in 802.15.4 - * specification. - */ - -struct frame802154_scf_s -{ - uint8_t security_level; /* 3 bit. security level */ - uint8_t key_id_mode; /* 2 bit. Key identifier mode */ - uint8_t reserved; /* 3 bit. Reserved bits */ -}; - -/* 802.15.4 Aux security header */ - -struct frame802154_aux_hdr_s -{ - struct frame802154_scf_s security_control; /* Security control bitfield */ - uint32_t frame_counter; /* Frame counter, used for security */ - uint8_t key[9]; /* The key itself, or an index to the key */ -}; - -/* Parameters used by the frame802154_create() function. These parameters - * are used in the 802.15.4 frame header. See the 802.15.4 specification - * for details. - */ - -struct frame802154_s -{ - struct frame802154_fcf_s fcf; /* Frame control field */ - uint8_t seq; /* Sequence number */ - uint16_t dest_pid; /* Destination PAN ID */ - uint8_t dest_addr[8]; /* Destination address */ - uint16_t src_pid; /* Source PAN ID */ - uint8_t src_addr[8]; /* Source address */ - struct frame802154_aux_hdr_s aux_hdr; /* Aux security header */ -}; - /**************************************************************************** * Public Data ****************************************************************************/ @@ -313,9 +249,8 @@ struct iob_s; /* Forward reference */ * * The payload data is in the caller 'buf' and is of length 'buflen'. * Compressed headers will be added and if necessary the packet is - * fragmented. The resulting packet/fragments are put in ieee->i_framelist - * and the entire list of frames will be delivered to the 802.15.4 MAC via - * ieee->i_framelist. + * fragmented. The resulting packet/fragments are submitted to the MAC + * via the network driver i_req_data method. * * Input Parameters: * dev - The IEEE802.15.4 MAC network driver interface. @@ -344,7 +279,30 @@ int sixlowpan_send(FAR struct net_driver_s *dev, uint16_t timeout); /**************************************************************************** - * Name: sixlowpan_send_hdrlen + * Name: sixlowpan_meta_data + * + * Description: + * Based on the collected attributes and addresses, construct the MAC meta + * data structure that we need to interface with the IEEE802.15.4 MAC. + * + * Input Parameters: + * dest_panid - PAN ID of the destination. May be 0xffff if the destination + * is not associated. + * meta - Location to return the corresponding meta data. + * + * Returned Value: + * Ok is returned on success; Othewise a negated errno value is returned. + * + * Assumptions: + * Called with the network locked. + * + ****************************************************************************/ + +int sixlowpan_meta_data(uint16_t dest_panid, + FAR struct ieee802154_frame_meta_s *meta); + +/**************************************************************************** + * Name: sixlowpan_frame_hdrlen * * Description: * This function is before the first frame has been sent in order to @@ -352,9 +310,8 @@ int sixlowpan_send(FAR struct net_driver_s *dev, * buffer is required to make this determination. * * Input parameters: - * ieee - A reference IEEE802.15.4 MAC network device structure. - * dest_panid - PAN ID of the destination. May be 0xffff if the destination - * is not associated. + * ieee - A reference IEEE802.15.4 MAC network device structure. + * meta - Meta data that describes the MAC header * * Returned Value: * The frame header length is returnd on success; otherwise, a negated @@ -362,30 +319,32 @@ int sixlowpan_send(FAR struct net_driver_s *dev, * ****************************************************************************/ -int sixlowpan_send_hdrlen(FAR struct ieee802154_driver_s *ieee, - uint16_t dest_panid); +int sixlowpan_frame_hdrlen(FAR struct ieee802154_driver_s *ieee, + FAR const struct ieee802154_frame_meta_s *meta); /**************************************************************************** - * Name: sixlowpan_framecreate + * Name: sixlowpan_frame_submit * * Description: - * This function is called after the IEEE802.15.4 MAC driver polls for - * TX data. It creates the IEEE802.15.4 header in the frame buffer. + * This function is called after eiether (1) the IEEE802.15.4 MAC driver + * polls for TX data or (2) after the IEEE802.15.4 MAC driver provides a + * new incoming frame and the network responds with an outgoing packet. It + * submits any new outgoing frame to the MAC. * * Input parameters: - * ieee - A reference IEEE802.15.4 MAC network device structure. - * iob - The IOB in which to create the frame. - * dest_panid - PAN ID of the destination. May be 0xffff if the destination - * is not associated. + * ieee - A reference IEEE802.15.4 MAC network device structure. + * meta - Meta data that describes the MAC header + * frame - The IOB containing the frame to be submitted. * * Returned Value: - * The frame header length is returnd on success; otherwise, a negated - * errno value is return on failure. + * Zero (OK) is returned on success; otherwise, a negated errno value is + * return on any failure. * ****************************************************************************/ -int sixlowpan_framecreate(FAR struct ieee802154_driver_s *ieee, - FAR struct iob_s *iob, uint16_t dest_panid); +int sixlowpan_frame_submit(FAR struct ieee802154_driver_s *ieee, + FAR const struct ieee802154_frame_meta_s *meta, + FAR struct iob_s *frame); /**************************************************************************** * Name: sixlowpan_queue_frames @@ -397,9 +356,8 @@ int sixlowpan_framecreate(FAR struct ieee802154_driver_s *ieee, * * The payload data is in the caller 'buf' and is of length 'buflen'. * Compressed headers will be added and if necessary the packet is - * fragmented. The resulting packet/fragments are put in ieee->i_framelist - * and the entire list of frames will be delivered to the 802.15.4 MAC via - * ieee->i_framelist. + * fragmented. The resulting packet/fragments are submitted to the MAC + * via the network driver i_req_data method. * * Input Parameters: * ieee - The IEEE802.15.4 MAC driver instance diff --git a/net/sixlowpan/sixlowpan_send.c b/net/sixlowpan/sixlowpan_send.c index 3ad68554ae..64b7088735 100644 --- a/net/sixlowpan/sixlowpan_send.c +++ b/net/sixlowpan/sixlowpan_send.c @@ -246,11 +246,10 @@ end_wait: * it to be sent on an 802.15.4 network using 6lowpan. Called from common * UDP/TCP send logic. * - * The payload data is in the caller 'buf' and is of length 'len'. + * The payload data is in the caller 'buf' and is of length 'buflen'. * Compressed headers will be added and if necessary the packet is - * fragmented. The resulting packet/fragments are put in ieee->i_framelist - * and the entire list of frames will be delivered to the 802.15.4 MAC via - * ieee->i_framelist. + * fragmented. The resulting packet/fragments are submitted to the MAC + * via the network driver i_req_data method. * * Input Parameters: * dev - The IEEE802.15.4 MAC network driver interface. diff --git a/wireless/ieee802154/mac802154_loopback.c b/wireless/ieee802154/mac802154_loopback.c index 92a30d3519..3d2fcf144f 100644 --- a/wireless/ieee802154/mac802154_loopback.c +++ b/wireless/ieee802154/mac802154_loopback.c @@ -102,8 +102,8 @@ struct lo_driver_s uint16_t lo_panid; /* Fake PAN ID for testing */ WDOG_ID lo_polldog; /* TX poll timer */ struct work_s lo_work; /* For deferring poll work to the work queue */ - FAR struct iob_s *head; /* Head of IOBs queued for loopback */ - FAR struct iob_s *tail; /* Tail of IOBs queued for loopback */ + FAR struct iob_s *lo_head; /* Head of IOBs queued for loopback */ + FAR struct iob_s *lo_tail; /* Tail of IOBs queued for loopback */ /* This holds the information visible to the NuttX network */ @@ -145,9 +145,9 @@ static int lo_ioctl(FAR struct net_driver_s *dev, int cmd, unsigned long arg); #endif static int lo_get_mhrlen(FAR struct ieee802154_driver_s *netdev, - FAR struct ieee802154_frame_meta_s *meta); + FAR const struct ieee802154_frame_meta_s *meta); static int lo_req_data(FAR struct ieee802154_driver_s *netdev, - FAR struct ieee802154_frame_meta_s *meta, + FAR const struct ieee802154_frame_meta_s *meta, FAR struct iob_s *frames); /**************************************************************************** @@ -177,43 +177,15 @@ static int lo_req_data(FAR struct ieee802154_driver_s *netdev, static int lo_loopback(FAR struct net_driver_s *dev) { FAR struct lo_driver_s *priv = (FAR struct lo_driver_s *)dev->d_private; - FAR struct iob_s *head; - FAR struct iob_s *tail; FAR struct iob_s *iob; int ret; - if (dev->d_len > 0 || priv->lo_ieee.i_framelist != NULL) - { - ninfo("d_len: %u i_framelist: %p\n", - dev->d_len, priv->lo_ieee.i_framelist); - - /* The only two valid settings are: - * - * 1. Nothing to send: - * dev->d_len == 0 && priv->lo_ieee.i_framelist == NULL - * 2. Outgoing packet has been converted to IEEE802.15.4 frames: - * dev->d_len == 0 && priv->lo_ieee.i_framelist != NULL - */ - - DEBUGASSERT(dev->d_len == 0 && priv->lo_ieee.i_framelist != NULL); - } - - /* Remove the queued IOBs from driver structure */ - - head = priv->lo_ieee.i_framelist; - - /* Find the tail of the IOB queue */ - - for (tail = NULL, iob = head; - iob != NULL; - tail = iob, iob = iob->io_flink); - - /* Loop while there frames to be sent, i.e., while the IOB list is not - * emtpy. Sending, of course, just means relaying back through the network + /* Loop while there frames to be sent, i.e., while the freme list is not + * emtpy. Sending, of course, just means relaying back through the network * for this driver. */ - while (head != NULL) + while (priv->lo_head != NULL) { /* Increment statistics */ @@ -221,24 +193,23 @@ static int lo_loopback(FAR struct net_driver_s *dev) /* Remove the IOB from the queue */ - iob = head; - head = iob->io_flink; + iob = priv->lo_head; + priv->lo_head = iob->io_flink; iob->io_flink = NULL; - /* Is the queue now empty? */ + /* Did the framelist become empty? */ - if (head == NULL) + if (priv->lo_head == NULL) { - tail = NULL; + priv->lo_tail = NULL; } /* Return the next frame to the network */ - iob->io_flink = NULL; - priv->lo_ieee.i_framelist = iob; + ninfo("Send frame %p to the network: Offset=%u Length=%u\n", + iob, iob->io_offset, iob->io_len); - ninfo("Send frame %p to the network. Length=%u\n", iob, iob->io_len); - ret = sixlowpan_input(&priv->lo_ieee); + ret = sixlowpan_input(&priv->lo_ieee, iob); /* Increment statistics */ @@ -250,33 +221,6 @@ static int lo_loopback(FAR struct net_driver_s *dev) NETDEV_TXERRORS(&priv->lo_ieee.i_dev); NETDEV_ERRORS(&priv->lo_ieee.i_dev); } - - /* What if the network responds with more frames to send? */ - - if (priv->lo_ieee.i_framelist != NULL) - { - /* Append the new list to the tail of the queue */ - - iob = priv->lo_ieee.i_framelist; - priv->lo_ieee.i_framelist = NULL; - - if (tail == NULL) - { - head = iob; - } - else - { - tail->io_flink = iob; - } - - /* Find the new tail of the IOB queue */ - - for (tail = iob, iob = iob->io_flink; - iob != NULL; - tail = iob, iob = iob->io_flink); - } - - priv->lo_txdone = true; } return 0; @@ -693,7 +637,7 @@ static int lo_ioctl(FAR struct net_driver_s *dev, int cmd, ****************************************************************************/ static int lo_get_mhrlen(FAR struct ieee802154_driver_s *netdev, - FAR struct ieee802154_frame_meta_s *meta) + FAR const struct ieee802154_frame_meta_s *meta) { return MAC_HDRLEN; } @@ -710,13 +654,14 @@ static int lo_get_mhrlen(FAR struct ieee802154_driver_s *netdev, ****************************************************************************/ static int lo_req_data(FAR struct ieee802154_driver_s *netdev, - FAR struct ieee802154_frame_meta_s *meta, + FAR const struct ieee802154_frame_meta_s *meta, FAR struct iob_s *frames) { FAR struct lo_driver_s *priv; FAR struct iob_s *iob; - DEBUGASSERT(netdev != NULL && netdev->i_dev.d_private != NULL && iob != NULL); + DEBUGASSERT(netdev != NULL && netdev->i_dev.d_private != NULL && + frames != NULL); priv = (FAR struct lo_driver_s *)netdev->i_dev.d_private; /* Add the incoming list of frames to queue of frames to loopback */ @@ -737,22 +682,18 @@ static int lo_req_data(FAR struct ieee802154_driver_s *netdev, DEBUGASSERT(iob->io_offset == MAC_HDRLEN); memset(iob->io_data, 0, MAC_HDRLEN); - /* Add the IOB to the tail of teh queue of frames to be looped back */ + /* Add the IOB to the tail of the queue of frames to be looped back */ - if (priv->tail == NULL) + if (priv->lo_tail == NULL) { - priv->head = iob; + priv->lo_head = iob; } else { - priv->tail->io_flink = iob; + priv->lo_tail->io_flink = iob; } - /* Find the new tail of the IOB queue */ - - for (priv->tail = iob, iob = iob->io_flink; - iob != NULL; - priv->tail = iob, iob = iob->io_flink); + priv->lo_tail = iob; } /* Is our single work structure available? It may not be if there are @@ -821,10 +762,6 @@ int ieee8021514_loopback(void) dev->d_buf = g_iobuffer; /* Attach the IO buffer */ dev->d_private = (FAR void *)priv; /* Used to recover private state from dev */ - /* Initialize the DSN to a "random" value */ - - ieee->i_dsn = 42; - /* Initialize the Network frame-related callbacks */ ieee->i_get_mhrlen = lo_get_mhrlen; /* Get MAC header length */ diff --git a/wireless/ieee802154/mac802154_netdev.c b/wireless/ieee802154/mac802154_netdev.c index f0e4f43cbe..a5816205e4 100644 --- a/wireless/ieee802154/mac802154_netdev.c +++ b/wireless/ieee802154/mac802154_netdev.c @@ -140,16 +140,6 @@ struct macnet_driver_s WDOG_ID md_txtimeout; /* TX timeout timer */ struct work_s md_irqwork; /* Defer interupt work to the work queue */ struct work_s md_pollwork; /* Defer poll work to the work queue */ - - /* This is queue of outgoing, ready-to-send frames that will be sent - * indirectly. This list should only be used by a MAC acting as a - * coordinator. These transactions will stay here until the data is - * extracted by the destination device sending a Data Request MAC - * command or if too much time passes. - */ - - FAR volatile struct iob_s *md_head; - FAR volatile struct iob_s *md_tail; }; /**************************************************************************** @@ -258,9 +248,9 @@ static int macnet_ioctl(FAR struct net_driver_s *dev, int cmd, unsigned long arg); #endif static int macnet_get_mhrlen(FAR struct ieee802154_driver_s *netdev, - FAR struct ieee802154_frame_meta_s *meta); + FAR const struct ieee802154_frame_meta_s *meta); static int macnet_req_data(FAR struct ieee802154_driver_s *netdev, - FAR struct ieee802154_frame_meta_s *meta, + FAR const struct ieee802154_frame_meta_s *meta, FAR struct iob_s *frames); /**************************************************************************** @@ -654,57 +644,6 @@ static int macnet_transmit(FAR struct macnet_driver_s *priv) return OK; } -/**************************************************************************** - * Name: macnet_txqueue - * - * Description: - * Add new frames from the network to the list of outgoing frames. - * - * Parameters: - * dev - Reference to the NuttX driver state structure - * - * Returned Value: - * OK on success; a negated errno on failure - * - * Assumptions: - * May or may not be called from an interrupt handler. In either case, - * the network is locked. - * - ****************************************************************************/ - -static void macnet_txqueue(FAR struct net_driver_s *dev) -{ - /* Check if there is a new list of outgoing frames from the network. */ - - if (priv->lo_ieee.i_framelist != NULL) - { - /* Yes.. Remove the frame list from the driver structure */ - - iob = priv->lo_ieee.i_framelist; - priv->lo_ieee.i_framelist = NULL; - - /* Append the new list to the tail of the queue of outgoing frames. */ - - if (priv->md_tail == NULL) - { - priv->md_head = iob; - } - else - { - priv->md_tail->io_flink = iob; - } - - /* Find the new tail of the outgoing frame queue */ - - for (priv->md_tail = iob, iob = iob->io_flink; - iob != NULL; - priv->md_tail = iob, iob = iob->io_flink); - - /* Notify the radio driver that there is data available */ -#warning Missing logic - } -} - /**************************************************************************** * Name: macnet_txpoll * @@ -724,30 +663,12 @@ static void macnet_txqueue(FAR struct net_driver_s *dev) * OK on success; a negated errno on failure * * Assumptions: - * May or may not be called from an interrupt handler. In either case, - * the network is locked. + * The network is locked. * ****************************************************************************/ static int macnet_txpoll(FAR struct net_driver_s *dev) { - FAR struct macnet_driver_s *priv = - (FAR struct macnet_driver_s *)dev->d_private; - FAR struct iob_s *iob; - - /* If the polling resulted in data that should be sent out, the field - * i_framelist will set to a new, outgoing list of frames. - */ - - if (priv->lo_ieee.i_framelist != NULL) - { - /* Remove the frame list from the driver structure and append it to - * the tail of the ist of outgoing frames. - */ - - macnet_txqueue(priv); - } - /* If zero is returned, the polling will continue until all connections have * been examined. */ @@ -781,6 +702,7 @@ static void macnet_receive(FAR struct macnet_driver_s *priv) net_lock(); iob = iob_alloc(false); +#warning Allocated by radio layer, right? if (iob == NULL) { nerr("ERROR: Failed to allocate an IOB\n") @@ -796,22 +718,7 @@ static void macnet_receive(FAR struct macnet_driver_s *priv) /* Transfer the frame to the network logic */ - priv->md_dev.framelist = iob; - sixlowpan_input(&priv->md_dev); - - /* If the above function invocation resulted in data that should be sent - * out, the field i_framelist will have been set to a new, outgoing list - * of frames. - */ - - if (priv->md_dev.i_framelist != NULL) - { - /* Remove the frame list from the driver structure and append it to - * the tail of the ist of outgoing frames. - */ - - macnet_txqueue(priv); - } + sixlowpan_input(&priv->md_dev, iob); } /**************************************************************************** @@ -1508,7 +1415,7 @@ static int macnet_ioctl(FAR struct net_driver_s *dev, int cmd, ****************************************************************************/ static int macnet_get_mhrlen(FAR struct ieee802154_driver_s *netdev, - FAR struct ieee802154_frame_meta_s *meta) + FAR const struct ieee802154_frame_meta_s *meta) { FAR struct macnet_driver_s *priv; @@ -1530,7 +1437,7 @@ static int macnet_get_mhrlen(FAR struct ieee802154_driver_s *netdev, ****************************************************************************/ static int macnet_req_data(FAR struct ieee802154_driver_s *netdev, - FAR struct ieee802154_frame_meta_s *meta, + FAR const struct ieee802154_frame_meta_s *meta, FAR struct iob_s *frames) { FAR struct macnet_driver_s *priv; -- GitLab From 2c2cddd44bb4ffea699aac7a5bd5b2c9bc07e60e Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Wed, 3 May 2017 11:14:06 -0400 Subject: [PATCH 690/990] wireless/ieee802154: Starts work on setting PIB attributes --- .../wireless/ieee802154/ieee802154_mac.h | 67 ++++++++++++++----- wireless/ieee802154/mac802154.c | 39 ++++++++++- 2 files changed, 86 insertions(+), 20 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index 68369ab75f..f91fbbceae 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -206,7 +206,7 @@ enum ieee802154_status_e { - IEEE802154_STATUS_OK = 0, + IEEE802154_STATUS_SUCCESS = 0, IEEE802154_STATUS_BEACON_LOSS = 0xE0, IEEE802154_STATUS_CHANNEL_ACCESS_FAILURE, IEEE802154_STATUS_DENIED, @@ -455,7 +455,49 @@ struct ieee802154_pend_addr_s union ieee802154_attr_val_u { - /* TODO: Finish this */ + uint8_t eaddr[8]; + uint16_t saddr; + uint16_t pan_id; + + uint8_t coord_eaddr[8]; + uint16_t coord_saddr; + + uint8_t is_assoc : 1; + uint8_t assoc_permit : 1; + uint8_t auto_req : 1; + uint8_t batt_life_ext : 1; + uint8_t gts_permit : 1; + uint8_t promisc_mode : 1; + uint8_t rng_support : 1; + uint8_t resp_wait_time; + uint8_t rx_when_idle : 1; + uint8_t sec_enabled : 1; + uint8_t timestamp_support : 1; + + uint32_t ack_wait_dur; + uint8_t batt_life_ext_periods; + uint8_t max_csma_backoffs : 3; + uint8_t max_be : 4; + uint8_t min_be : 4; + uint32_t max_frame_wait_time; + uint8_t max_retries; + uint8_t lifs_period; + uint8_t sifs_period; + uint32_t sync_symb_offset : 12; + uint16_t trans_persist_time; + uint32_t tx_ctrl_active_dur; + uint32_t tx_ctrl_pause_dur; + uint32_t tx_total_dur; + + uint8_t beacon_payload[IEEE802154_PIB_MAC_BEACON_PAYLOAD_LEN]; + uint8_t beacon_payload_len; + uint8_t beacon_order; + uint32_t beacon_tx_time : 24; + + uint8_t superframe_order; + + uint8_t bsn; + uint8_t dsn; }; struct ieee802154_gts_info_s @@ -1109,6 +1151,12 @@ struct ieee802154_scan_conf_s * Description: * Attempts to write the given value to the indicated PIB attribute. * + * NOTE: The standard specifies that confirmation should be indicated via + * the asynchronous MLME-SET.confirm primitve. However, in our implementation + * there is no reason not to synchronously return the status immediately. + * Therefore, we do merge the functionality of the MLME-SET.request and + * MLME-SET.confirm primitives together. + * *****************************************************************************/ struct ieee802154_set_req_s @@ -1117,20 +1165,6 @@ struct ieee802154_set_req_s union ieee802154_attr_val_u attr_value; }; -/***************************************************************************** - * Primitive: MLME-SET.confirm - * - * Description: - * Reports the results of an attempt to write a value to a PIB attribute. - * - *****************************************************************************/ - -struct ieee802154_set_conf_s -{ - enum ieee802154_status_e status; - enum ieee802154_pib_attr_e pib_attr; -}; - /***************************************************************************** * Primitive: MLME-START.request * @@ -1258,7 +1292,6 @@ union ieee802154_mlme_notify_u struct ieee802154_reset_conf_s resetconf; struct ieee802154_rxenable_conf_s rxenableconf; struct ieee802154_scan_conf_s scanconf; - struct ieee802154_set_conf_s setconf; struct ieee802154_start_conf_s startconf; struct ieee802154_poll_conf_s pollconf; diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index 56b220181a..3f42d006c8 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -1450,8 +1450,13 @@ int mac802154_req_scan(MACHANDLE mac, FAR struct ieee802154_scan_req_s *req) * * Description: * The MLME-SET.request primitive attempts to write the given value to the - * indicated MAC PIB attribute. Confirmation is returned via the - * struct ieee802154_maccb_s->conf_set callback. + * indicated MAC PIB attribute. + * + * NOTE: The standard specifies that confirmation should be indicated via + * the asynchronous MLME-SET.confirm primitve. However, in our implementation + * there is no reason not to synchronously return the status immediately. + * Therefore, we do merge the functionality of the MLME-SET.request and + * MLME-SET.confirm primitives together. * ****************************************************************************/ @@ -1459,7 +1464,35 @@ int mac802154_req_set(MACHANDLE mac, FAR struct ieee802154_set_req_s *req) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; - return -ENOTTY; + union ieee802154_radioarg_u radio_arg; + int ret; + + switch (req->pib_attr) + { + case IEEE802154_PIB_MAC_EXTENDED_ADDR: + { + /* Set the attribute in the structure to the new value */ + + memcpy(&priv->addr.eaddr[0], &req->attr_value.eaddr[0], 8); + + + /* The radio device needs to be updated as well */ + + memcpy(&radio_arg.eaddr[0], &priv->addr.eaddr[0], 8); + ret = priv->radio->ops->ioctl(priv->radio, PHY802154IOC_SET_EADDR, + (unsigned long)&radio_arg); + + ret = IEEE802154_STATUS_SUCCESS; + } + break; + default: + { + ret = -IEEE802154_STATUS_UNSUPPORTED_ATTRIBUTE; + } + break; + } + + return ret; } /**************************************************************************** -- GitLab From cf988309aad3b5f8f308ae2c6d1d8f0ac20ed251 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 3 May 2017 11:13:07 -0600 Subject: [PATCH 691/990] 6loWPAN: Fixes hang in loopback test. --- include/nuttx/net/sixlowpan.h | 24 ++++-- net/sixlowpan/sixlowpan_framelist.c | 23 +++-- net/sixlowpan/sixlowpan_framer.c | 27 ------ wireless/ieee802154/mac802154_loopback.c | 105 ++++++++++++----------- wireless/ieee802154/mac802154_netdev.c | 34 +++++--- 5 files changed, 107 insertions(+), 106 deletions(-) diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index 85c95329dc..507f08eb51 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -437,6 +437,14 @@ struct ieee802154_driver_s * Description: * Calculate the MAC header length given the frame meta-data. * + * Input parameters: + * netdev - The networkd device that will mediate the MAC interface + * meta - Meta data needed to recreate the MAC header + * + * Returned Value: + * A non-negative MAC headeer length is returned on success; a negated + * errno value is returned on any failure. + * **************************************************************************/ CODE int (*i_get_mhrlen)(FAR struct ieee802154_driver_s *netdev, @@ -446,16 +454,22 @@ struct ieee802154_driver_s * Name: mac802154_req_data * * Description: - * The MCPS-DATA.request primitive requests the transfer of a data SPDU - * (i.e., MSDU) from a local SSCS entity to a single peer SSCS entity. - * Confirmation is returned via the - * struct ieee802154_maccb_s->conf_data callback. + * Requests the transfer of a list of frames to the MAC. + * + * Input parameters: + * netdev - The networkd device that will mediate the MAC interface + * meta - Meta data needed to recreate the MAC header + * framelist - Head of a list of frames to be transferred. + * + * Returned Value: + * Zero (OK) returned on success; a negated errno value is returned on + * any failure. * **************************************************************************/ CODE int (*i_req_data)(FAR struct ieee802154_driver_s *netdev, FAR const struct ieee802154_frame_meta_s *meta, - FAR struct iob_s *frames); + FAR struct iob_s *framelist); }; /**************************************************************************** diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c index e4e769c0ce..fb03af457f 100644 --- a/net/sixlowpan/sixlowpan_framelist.c +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -511,19 +511,16 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, qhead->io_pktlen += iob->io_len; } - /* Submit all of the fragments to the MAC */ - - while (qhead != NULL) - { - iob = qhead; - qhead = iob->io_flink; - - ret = sixlowpan_frame_submit(ieee, &meta, iob); - if (ret < 0) - { - nerr("ERROR: sixlowpan_frame_submit() failed: %d\n", ret); - } - } + /* Submit all of the fragments to the MAC. We send all frames back- + * to-back like this to eliminate any possible condition where some + * frame which is not a fragment from this sequence from intervening. + */ + + ret = sixlowpan_frame_submit(ieee, &meta, qhead); + if (ret < 0) + { + nerr("ERROR: sixlowpan_frame_submit() failed: %d\n", ret); + } /* Update the datagram TAG value */ diff --git a/net/sixlowpan/sixlowpan_framer.c b/net/sixlowpan/sixlowpan_framer.c index 9a32310d02..47afecf6af 100644 --- a/net/sixlowpan/sixlowpan_framer.c +++ b/net/sixlowpan/sixlowpan_framer.c @@ -66,33 +66,6 @@ * Public Functions ****************************************************************************/ -/**************************************************************************** - * Name: sixlowpan_addrlen - * - * Description: - * Return the address length associated with a 2-bit address mode - * - * Input parameters: - * addrmode - The address mode - * - * Returned Value: - * The address length associated with the address mode. - * - ****************************************************************************/ - -static inline uint8_t sixlowpan_addrlen(uint8_t addrmode) -{ - switch (addrmode) - { - case FRAME802154_SHORTADDRMODE: /* 16-bit address */ - return 2; - case FRAME802154_LONGADDRMODE: /* 64-bit address */ - return 8; - default: - return 0; - } -} - /**************************************************************************** * Name: sixlowpan_addrnull * diff --git a/wireless/ieee802154/mac802154_loopback.c b/wireless/ieee802154/mac802154_loopback.c index 3d2fcf144f..c4cb8de153 100644 --- a/wireless/ieee802154/mac802154_loopback.c +++ b/wireless/ieee802154/mac802154_loopback.c @@ -98,7 +98,7 @@ struct lo_driver_s { bool lo_bifup; /* true:ifup false:ifdown */ - bool lo_txdone; /* One RX packet was looped back */ + bool lo_pending; /* True: TX poll pending */ uint16_t lo_panid; /* Fake PAN ID for testing */ WDOG_ID lo_polldog; /* TX poll timer */ struct work_s lo_work; /* For deferring poll work to the work queue */ @@ -148,7 +148,7 @@ static int lo_get_mhrlen(FAR struct ieee802154_driver_s *netdev, FAR const struct ieee802154_frame_meta_s *meta); static int lo_req_data(FAR struct ieee802154_driver_s *netdev, FAR const struct ieee802154_frame_meta_s *meta, - FAR struct iob_s *frames); + FAR struct iob_s *framelist); /**************************************************************************** * Private Functions @@ -180,13 +180,15 @@ static int lo_loopback(FAR struct net_driver_s *dev) FAR struct iob_s *iob; int ret; - /* Loop while there frames to be sent, i.e., while the freme list is not + /* Loop while there framelist to be sent, i.e., while the freme list is not * emtpy. Sending, of course, just means relaying back through the network * for this driver. */ while (priv->lo_head != NULL) { + ninfo("Looping frame IOB %p\n", iob); + /* Increment statistics */ NETDEV_RXPACKETS(&priv->lo_ieee.i_dev); @@ -230,7 +232,7 @@ static int lo_loopback(FAR struct net_driver_s *dev) * Name: lo_loopback_work * * Description: - * Perform loopback of received frames. + * Perform loopback of received framelist. * * Parameters: * arg - The argument passed when work_queue() as called. @@ -278,19 +280,8 @@ static void lo_poll_work(FAR void *arg) /* Perform the poll */ net_lock(); - priv->lo_txdone = false; (void)devif_timer(&priv->lo_ieee.i_dev, lo_loopback); - /* Was something received and looped back? */ - - while (priv->lo_txdone) - { - /* Yes, poll again for more TX data */ - - priv->lo_txdone = false; - (void)devif_poll(&priv->lo_ieee.i_dev, lo_loopback); - } - /* Setup the watchdog poll timer again */ (void)wd_start(priv->lo_polldog, LO_WDDELAY, lo_poll_expiry, 1, priv); @@ -319,14 +310,18 @@ static void lo_poll_expiry(int argc, wdparm_t arg, ...) { FAR struct lo_driver_s *priv = (FAR struct lo_driver_s *)arg; - if (!work_available(&priv->lo_work)) + if (!work_available(&priv->lo_work) || priv->lo_head != NULL) { nwarn("WARNING: lo_work NOT available\n"); + priv->lo_pending = true; } + else + { + /* Schedule to perform the interrupt processing on the worker thread. */ - /* Schedule to perform the interrupt processing on the worker thread. */ - - work_queue(LPBKWORK, &priv->lo_work, lo_poll_work, priv, 0); + priv->lo_pending = false; + work_queue(LPBKWORK, &priv->lo_work, lo_poll_work, priv, 0); + } } /**************************************************************************** @@ -430,21 +425,16 @@ static void lo_txavail_work(FAR void *arg) { FAR struct lo_driver_s *priv = (FAR struct lo_driver_s *)arg; - ninfo("IP up: %u\n", priv->lo_bifup); + ninfo("TX available work. IP up: %u\n", priv->lo_bifup); /* Ignore the notification if the interface is not yet up */ net_lock(); if (priv->lo_bifup) { - do - { - /* If so, then poll the network for new XMIT data */ + /* If so, then poll the network for new XMIT data */ - priv->lo_txdone = false; - (void)devif_poll(&priv->lo_ieee.i_dev, lo_loopback); - } - while (priv->lo_txdone); + (void)devif_poll(&priv->lo_ieee.i_dev, lo_loopback); } net_unlock(); @@ -480,10 +470,16 @@ static int lo_txavail(FAR struct net_driver_s *dev) * action. */ - if (work_available(&priv->lo_work)) + if (!work_available(&priv->lo_work) || priv->lo_head != NULL) + { + nwarn("WARNING: lo_work NOT available\n"); + priv->lo_pending = true; + } + else { - /* Schedule to serialize the poll on the worker thread. */ + /* Schedule to perform the interrupt processing on the worker thread. */ + priv->lo_pending = false; work_queue(LPBKWORK, &priv->lo_work, lo_txavail_work, priv, 0); } @@ -634,6 +630,14 @@ static int lo_ioctl(FAR struct net_driver_s *dev, int cmd, * Description: * Calculate the MAC header length given the frame meta-data. * + * Input parameters: + * netdev - The networkd device that will mediate the MAC interface + * meta - Meta data needed to recreate the MAC header + * + * Returned Value: + * A non-negative MAC headeer length is returned on success; a negated + * errno value is returned on any failure. + * ****************************************************************************/ static int lo_get_mhrlen(FAR struct ieee802154_driver_s *netdev, @@ -646,27 +650,33 @@ static int lo_get_mhrlen(FAR struct ieee802154_driver_s *netdev, * Name: lo_req_data * * Description: - * The MCPS-DATA.request primitive requests the transfer of a data SPDU - * (i.e., MSDU) from a local SSCS entity to a single peer SSCS entity. - * Confirmation is returned via the - * struct ieee802154_maccb_s->conf_data callback. + * Requests the transfer of a list of frames to the MAC. + * + * Input parameters: + * netdev - The networkd device that will mediate the MAC interface + * meta - Meta data needed to recreate the MAC header + * framelist - Head of a list of frames to be transferred. + * + * Returned Value: + * Zero (OK) returned on success; a negated errno value is returned on + * any failure. * ****************************************************************************/ static int lo_req_data(FAR struct ieee802154_driver_s *netdev, FAR const struct ieee802154_frame_meta_s *meta, - FAR struct iob_s *frames) + FAR struct iob_s *framelist) { FAR struct lo_driver_s *priv; FAR struct iob_s *iob; DEBUGASSERT(netdev != NULL && netdev->i_dev.d_private != NULL && - frames != NULL); + framelist != NULL); priv = (FAR struct lo_driver_s *)netdev->i_dev.d_private; - /* Add the incoming list of frames to queue of frames to loopback */ + /* Add the incoming list of framelist to queue of framelist to loopback */ - for (iob = frames; iob != NULL; iob = frames) + for (iob = framelist; iob != NULL; iob = framelist) { /* Increment statistics */ @@ -674,15 +684,17 @@ static int lo_req_data(FAR struct ieee802154_driver_s *netdev, /* Remove the IOB from the queue */ - frames = iob->io_flink; + framelist = iob->io_flink; iob->io_flink = NULL; + ninfo("Queuing frame IOB %p\n", iob); + /* Just zero the MAC header for test purposes */ DEBUGASSERT(iob->io_offset == MAC_HDRLEN); memset(iob->io_data, 0, MAC_HDRLEN); - /* Add the IOB to the tail of the queue of frames to be looped back */ + /* Add the IOB to the tail of the queue of framelist to be looped back */ if (priv->lo_tail == NULL) { @@ -696,18 +708,9 @@ static int lo_req_data(FAR struct ieee802154_driver_s *netdev, priv->lo_tail = iob; } - /* Is our single work structure available? It may not be if there are - * pending actions and we will have to ignore the Tx availability - * action. - */ - - if (work_available(&priv->lo_work)) - { - /* Schedule to serialize the poll on the worker thread. */ - - work_queue(LPBKWORK, &priv->lo_work, lo_loopback_work, priv, 0); - } + /* Schedule to serialize the poll on the worker thread. */ + work_queue(LPBKWORK, &priv->lo_work, lo_loopback_work, priv, 0); return OK; } @@ -771,7 +774,7 @@ int ieee8021514_loopback(void) priv->lo_polldog = wd_create(); /* Create periodic poll timer */ - /* Register the loopabck device with the OS so that socket IOCTLs can b + /* Register the loopabck device with the OS so that socket IOCTLs can be * performed. */ diff --git a/wireless/ieee802154/mac802154_netdev.c b/wireless/ieee802154/mac802154_netdev.c index a5816205e4..b81ad465bc 100644 --- a/wireless/ieee802154/mac802154_netdev.c +++ b/wireless/ieee802154/mac802154_netdev.c @@ -251,7 +251,7 @@ static int macnet_get_mhrlen(FAR struct ieee802154_driver_s *netdev, FAR const struct ieee802154_frame_meta_s *meta); static int macnet_req_data(FAR struct ieee802154_driver_s *netdev, FAR const struct ieee802154_frame_meta_s *meta, - FAR struct iob_s *frames); + FAR struct iob_s *framelist); /**************************************************************************** * Private Functions @@ -1412,6 +1412,14 @@ static int macnet_ioctl(FAR struct net_driver_s *dev, int cmd, * Description: * Calculate the MAC header length given the frame meta-data. * + * Input parameters: + * netdev - The networkd device that will mediate the MAC interface + * meta - Meta data needed to recreate the MAC header + * + * Returned Value: + * A non-negative MAC headeer length is returned on success; a negated + * errno value is returned on any failure. + * ****************************************************************************/ static int macnet_get_mhrlen(FAR struct ieee802154_driver_s *netdev, @@ -1429,16 +1437,22 @@ static int macnet_get_mhrlen(FAR struct ieee802154_driver_s *netdev, * Name: macnet_req_data * * Description: - * The MCPS-DATA.request primitive requests the transfer of a data SPDU - * (i.e., MSDU) from a local SSCS entity to a single peer SSCS entity. - * Confirmation is returned via the - * struct ieee802154_maccb_s->conf_data callback. + * Requests the transfer of a list of frames to the MAC. + * + * Input parameters: + * netdev - The networkd device that will mediate the MAC interface + * meta - Meta data needed to recreate the MAC header + * framelist - Head of a list of frames to be transferred. + * + * Returned Value: + * Zero (OK) returned on success; a negated errno value is returned on + * any failure. * ****************************************************************************/ static int macnet_req_data(FAR struct ieee802154_driver_s *netdev, FAR const struct ieee802154_frame_meta_s *meta, - FAR struct iob_s *frames) + FAR struct iob_s *framelist) { FAR struct macnet_driver_s *priv; struct ieee802154_data_req_s req; @@ -1450,7 +1464,7 @@ static int macnet_req_data(FAR struct ieee802154_driver_s *netdev, /* Add the incoming list of frames to the MAC's outgoing queue */ - for (iob = frames; iob != NULL; iob = frames) + for (iob = framelist; iob != NULL; iob = framelist) { /* Increment statistics */ @@ -1458,7 +1472,7 @@ static int macnet_req_data(FAR struct ieee802154_driver_s *netdev, /* Remove the IOB from the queue */ - frames = iob->io_flink; + framelist = iob->io_flink; iob->io_flink = NULL; /* Transfer the frame to the MAC */ @@ -1471,11 +1485,11 @@ static int macnet_req_data(FAR struct ieee802154_driver_s *netdev, wlerr("ERROR: mac802154_req_data failed: %d\n", ret); iob_free(iob); - for (iob = frames; ; iob != NULL; iob = frames) + for (iob = framelist; ; iob != NULL; iob = framelist) { /* Remove the IOB from the queue and free */ - frames = iob->io_flink; + framelist = iob->io_flink; iob_free(iob); } -- GitLab From ba32b6581392439701b6341b0ddf4332b8374ced Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Wed, 3 May 2017 13:26:06 -0400 Subject: [PATCH 692/990] wireless/ieee802154: Simplifies some primitive prototypes --- .../wireless/ieee802154/ieee802154_ioctl.h | 4 +- .../wireless/ieee802154/ieee802154_mac.h | 86 ++----------- wireless/ieee802154/mac802154.c | 114 +++++++++++------- wireless/ieee802154/mac802154.h | 66 +++++++--- wireless/ieee802154/mac802154_device.c | 14 +-- 5 files changed, 135 insertions(+), 149 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_ioctl.h b/include/nuttx/wireless/ieee802154/ieee802154_ioctl.h index 019fedd55a..cd5550057c 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_ioctl.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_ioctl.h @@ -48,6 +48,8 @@ #include #include +#include + #ifdef CONFIG_WIRELESS_IEEE802154 /************************************************************************************ @@ -74,7 +76,7 @@ struct mac802154dev_notify_s struct mac802154dev_txframe_s { - FAR struct ieee802154_frame_meta_s *meta; + struct ieee802154_frame_meta_s meta; FAR uint8_t *payload; }; diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index f91fbbceae..5b6ba898ad 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -462,17 +462,17 @@ union ieee802154_attr_val_u uint8_t coord_eaddr[8]; uint16_t coord_saddr; - uint8_t is_assoc : 1; - uint8_t assoc_permit : 1; - uint8_t auto_req : 1; - uint8_t batt_life_ext : 1; - uint8_t gts_permit : 1; - uint8_t promisc_mode : 1; - uint8_t rng_support : 1; - uint8_t resp_wait_time; - uint8_t rx_when_idle : 1; - uint8_t sec_enabled : 1; - uint8_t timestamp_support : 1; + bool is_assoc; + bool assoc_permit; + bool auto_req; + bool batt_life_ext; + bool gts_permit; + bool promisc_mode; + bool rng_support; + bool resp_wait_time; + bool rx_when_idle; + bool sec_enabled; + bool timestamp_support; uint32_t ack_wait_dur; uint8_t batt_life_ext_periods; @@ -567,20 +567,6 @@ struct ieee802154_frame_meta_s /* Primitive Semantics *******************************************************/ -/***************************************************************************** - * Primitive: MCPS-DATA.request - * - * Description: - * Requests the transfer of data to another device. - * - *****************************************************************************/ - -struct ieee802154_data_req_s -{ - FAR const struct ieee802154_frame_meta_s *meta; /* Metadata describing the req */ - FAR struct iob_s *frame; /* Frame IOB with payload */ -}; - /***************************************************************************** * Primitive: MCPS-DATA.confirm * @@ -658,21 +644,6 @@ struct ieee802154_purge_req_s uint8_t msdu_handle; /* Handle assoc. with MSDU */ }; -/***************************************************************************** - * Primitive: MCPS-PURGE.confirm - * - * Description: - * Allows the MAC sublayer to notify the next higher layer of the success of - * its request to purge an MSDU from the transaction queue. - * - *****************************************************************************/ - -struct ieee802154_purge_conf_s -{ - uint8_t msdu_handle; /* Handle assoc. with MSDU */ - enum ieee802154_status_e status; /* The status of the MSDU transmission */ -}; - /***************************************************************************** * Primitive: MLME-ASSOCIATE.request * @@ -921,21 +892,7 @@ struct ieee802154_commstatus_ind_s struct ieee802154_get_req_s { enum ieee802154_pib_attr_e pib_attr; -}; - -/***************************************************************************** - * Primitive: MLME-GET.confirm - * - * Description: - * Reports the results of an information request from the PIB. - * - *****************************************************************************/ - -struct ieee802154_get_conf_s -{ - enum ieee802154_status_e status; - enum ieee802154_pib_attr_e pib_attr; - union ieee802154_attr_val_u attr_value; + FAR union ieee802154_attr_val_u *attr_value; }; /***************************************************************************** @@ -1049,19 +1006,6 @@ struct ieee802154_reset_req_s bool rst_pibattr; }; -/***************************************************************************** - * Primitive: MLME-RESET.confirm - * - * Description: - * Reports the results of the reset operation. - * - *****************************************************************************/ - -struct ieee802154_reset_conf_s -{ - enum ieee802154_status_e status; -}; - /***************************************************************************** * Primitive: MLME-RXENABLE.request * @@ -1287,9 +1231,7 @@ union ieee802154_mlme_notify_u { struct ieee802154_assoc_conf_s assocconf; struct ieee802154_disassoc_conf_s disassocconf; - struct ieee802154_get_conf_s getconf; struct ieee802154_gts_conf_s gtsconf; - struct ieee802154_reset_conf_s resetconf; struct ieee802154_rxenable_conf_s rxenableconf; struct ieee802154_scan_conf_s scanconf; struct ieee802154_start_conf_s startconf; @@ -1307,7 +1249,6 @@ union ieee802154_mlme_notify_u union ieee802154_mcps_notify_u { struct ieee802154_data_conf_s dataconf; - struct ieee802154_purge_conf_s purgeconf; struct ieee802154_data_ind_s dataind; }; @@ -1362,19 +1303,16 @@ enum ieee802154_macnotify_e /* MCPS Notifications */ IEEE802154_NOTIFY_CONF_DATA = 0x00, - IEEE802154_NOTIFY_CONF_PURGE, IEEE802154_NOTIFY_IND_DATA, /* MLME Notifications */ IEEE802154_NOTIFY_CONF_ASSOC, IEEE802154_NOTIFY_CONF_DISASSOC, - IEEE802154_NOTIFY_CONF_GET, IEEE802154_NOTIFY_CONF_GTS, IEEE802154_NOTIFY_CONF_RESET, IEEE802154_NOTIFY_CONF_RXENABLE, IEEE802154_NOTIFY_CONF_SCAN, - IEEE802154_NOTIFY_CONF_SET, IEEE802154_NOTIFY_CONF_START, IEEE802154_NOTIFY_CONF_POLL, diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index 3f42d006c8..2b373a51da 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -890,7 +890,8 @@ int mac802154_ioctl(MACHANDLE mac, int cmd, unsigned long arg) break; case MAC802154IOC_MLME_GET_REQUEST: { - mac802154_req_get(mac, &macarg->getreq); + mac802154_req_get(mac, macarg->getreq.pib_attr, + macarg->getreq.attr_value); } break; case MAC802154IOC_MLME_GTS_REQUEST: @@ -905,7 +906,7 @@ int mac802154_ioctl(MACHANDLE mac, int cmd, unsigned long arg) break; case MAC802154IOC_MLME_RESET_REQUEST: { - mac802154_req_reset(mac, &macarg->resetreq); + mac802154_req_reset(mac, macarg->resetreq.rst_pibattr); } break; case MAC802154IOC_MLME_RXENABLE_REQUEST: @@ -1046,26 +1047,27 @@ int mac802154_get_mhrlen(MACHANDLE mac, * ****************************************************************************/ -int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) +int mac802154_req_data(MACHANDLE mac, + FAR const struct ieee802154_frame_meta_s *meta, + FAR struct iob_s *frame) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; FAR struct mac802154_trans_s trans; - FAR const struct ieee802154_frame_meta_s *meta = req->meta; uint16_t *frame_ctrl; uint8_t mhr_len = 3; /* Start assuming frame control and seq. num */ int ret; /* Check the required frame size */ - if (req->frame->io_len > IEEE802154_MAX_PHY_PACKET_SIZE) + if (frame->io_len > IEEE802154_MAX_PHY_PACKET_SIZE) { return -E2BIG; } /* Cast the first two bytes of the IOB to a uint16_t frame control field */ - frame_ctrl = (uint16_t *)&req->frame->io_data[0]; + frame_ctrl = (uint16_t *)&frame->io_data[0]; /* Ensure we start with a clear frame control field */ @@ -1097,17 +1099,17 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) if (meta->dest_addr.mode != IEEE802154_ADDRMODE_NONE) { - memcpy(&req->frame->io_data[mhr_len], &meta->dest_addr.panid, 2); + memcpy(&frame->io_data[mhr_len], &meta->dest_addr.panid, 2); mhr_len += 2; if (meta->dest_addr.mode == IEEE802154_ADDRMODE_SHORT) { - memcpy(&req->frame->io_data[mhr_len], &meta->dest_addr.saddr, 2); + memcpy(&frame->io_data[mhr_len], &meta->dest_addr.saddr, 2); mhr_len += 2; } else if (meta->dest_addr.mode == IEEE802154_ADDRMODE_EXTENDED) { - memcpy(&req->frame->io_data[mhr_len], &meta->dest_addr.eaddr, 8); + memcpy(&frame->io_data[mhr_len], &meta->dest_addr.eaddr, 8); mhr_len += 8; } } @@ -1153,18 +1155,18 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) if ((meta->dest_addr.mode == IEEE802154_ADDRMODE_NONE) || (*frame_ctrl & IEEE802154_FRAMECTRL_PANIDCOMP)) { - memcpy(&req->frame->io_data[mhr_len], &priv->addr.panid, 2); + memcpy(&frame->io_data[mhr_len], &priv->addr.panid, 2); mhr_len += 2; } if (meta->src_addr_mode == IEEE802154_ADDRMODE_SHORT) { - memcpy(&req->frame->io_data[mhr_len], &priv->addr.saddr, 2); + memcpy(&frame->io_data[mhr_len], &priv->addr.saddr, 2); mhr_len += 2; } else if (meta->src_addr_mode == IEEE802154_ADDRMODE_EXTENDED) { - memcpy(&req->frame->io_data[mhr_len], &priv->addr.eaddr, 8); + memcpy(&frame->io_data[mhr_len], &priv->addr.eaddr, 8); mhr_len += 8; } } @@ -1178,7 +1180,7 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) * of the outgoing frame and then increment it by one. [1] pg. 40. */ - req->frame->io_data[2] = priv->dsn++; + frame->io_data[2] = priv->dsn++; /* The MAC header we just created must never have exceeded where the app * data starts. This should never happen since the offset should have @@ -1186,14 +1188,14 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) * here that created the header */ - DEBUGASSERT(mhr_len == req->frame->io_offset); + DEBUGASSERT(mhr_len == frame->io_offset); - req->frame->io_offset = 0; /* Set the offset to 0 to include the header */ + frame->io_offset = 0; /* Set the offset to 0 to include the header */ /* Setup our transaction */ trans.msdu_handle = meta->msdu_handle; - trans.frame = req->frame; + trans.frame = frame; sem_init(&trans.sem, 0, 1); /* If the TxOptions parameter specifies that a GTS transmission is required, @@ -1234,6 +1236,9 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) * coordinator, the destination address is not present, or the * TxOptions parameter also specifies a GTS transmission, the indirect * transmission option will be ignored. [1] + * + * NOTE: We don't just ignore the parameter. Instead, we throw an + * error, since this really shouldn't be happening. */ if (priv->is_coord && meta->dest_addr.mode != IEEE802154_ADDRMODE_NONE) @@ -1243,15 +1248,10 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) } else { - /* Override the setting since it wasn't valid */ - - meta->msdu_flags.indirect_tx = 0; + return -EINVAL; } } - - /* If this is a direct transmission not during a GTS */ - - if (!meta->msdu_flags.indirect_tx) + else { /* Link the transaction into the CSMA transaction list */ @@ -1281,9 +1281,15 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req) * an MSDU from the transaction queue. Confirmation is returned via * the struct ieee802154_maccb_s->conf_purge callback. * + * NOTE: The standard specifies that confirmation should be indicated via + * the asynchronous MLME-PURGE.confirm primitve. However, in our + * implementation we synchronously return the status from the request. + * Therefore, we merge the functionality of the MLME-PURGE.request and + * MLME-PURGE.confirm primitives together. + * ****************************************************************************/ -int mac802154_req_purge(MACHANDLE mac, FAR struct ieee802154_purge_req_s *req) +int mac802154_req_purge(MACHANDLE mac, uint8_t msdu_handle) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; @@ -1352,22 +1358,6 @@ int mac802154_req_disassociate(MACHANDLE mac, return -ENOTTY; } -/**************************************************************************** - * Name: mac802154_req_get - * - * Description: - * The MLME-GET.request primitive requests information about a given PIB - * attribute. Actual data is returned via the - * struct ieee802154_maccb_s->conf_get callback. - * - ****************************************************************************/ - -int mac802154_req_get(MACHANDLE mac, FAR struct ieee802154_get_req_s *req) -{ - FAR struct ieee802154_privmac_s *priv = - (FAR struct ieee802154_privmac_s *)mac; - return -ENOTTY; -} /**************************************************************************** * Name: mac802154_req_gts @@ -1392,12 +1382,21 @@ int mac802154_req_gts(MACHANDLE mac, FAR struct ieee802154_gts_req_s *req) * * Description: * The MLME-RESET.request primitive allows the next higher layer to request - * that the MLME performs a reset operation. Confirmation is returned via - * the struct ieee802154_maccb_s->conf_reset callback. + * that the MLME performs a reset operation. + * + * NOTE: The standard specifies that confirmation should be provided via + * via the asynchronous MLME-RESET.confirm primitve. However, in our + * implementation we synchronously return the value immediately. Therefore, + * we merge the functionality of the MLME-RESET.request and MLME-RESET.confirm + * primitives together. + * + * Input Parameters: + * mac - Handle to the MAC layer instance + * rst_pibattr - Whether or not to reset the MAC PIB attributes to defaults * ****************************************************************************/ -int mac802154_req_reset(MACHANDLE mac, FAR struct ieee802154_reset_req_s *req) +int mac802154_req_reset(MACHANDLE mac, bool rst_pibattr) { FAR struct ieee802154_privmac_s * priv = (FAR struct ieee802154_privmac_s *) mac; @@ -1445,6 +1444,29 @@ int mac802154_req_scan(MACHANDLE mac, FAR struct ieee802154_scan_req_s *req) return -ENOTTY; } +/**************************************************************************** + * Name: mac802154_req_get + * + * Description: + * The MLME-GET.request primitive requests information about a given PIB + * attribute. + * + * NOTE: The standard specifies that the attribute value should be returned + * via the asynchronous MLME-GET.confirm primitve. However, in our + * implementation, we synchronously return the value immediately.Therefore, we + * merge the functionality of the MLME-GET.request and MLME-GET.confirm + * primitives together. + * + ****************************************************************************/ + +int mac802154_req_get(MACHANDLE mac, enum ieee802154_pib_attr_e pib_attr, + FAR union ieee802154_attr_val_u *attr_value) +{ + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; + return -ENOTTY; +} + /**************************************************************************** * Name: mac802154_req_set * @@ -1454,9 +1476,9 @@ int mac802154_req_scan(MACHANDLE mac, FAR struct ieee802154_scan_req_s *req) * * NOTE: The standard specifies that confirmation should be indicated via * the asynchronous MLME-SET.confirm primitve. However, in our implementation - * there is no reason not to synchronously return the status immediately. - * Therefore, we do merge the functionality of the MLME-SET.request and - * MLME-SET.confirm primitives together. + * we synchronously return the status from the request. Therefore, we do merge + * the functionality of the MLME-SET.request and MLME-SET.confirm primitives + * together. * ****************************************************************************/ diff --git a/wireless/ieee802154/mac802154.h b/wireless/ieee802154/mac802154.h index 17df17ebda..883d0180ee 100644 --- a/wireless/ieee802154/mac802154.h +++ b/wireless/ieee802154/mac802154.h @@ -119,7 +119,9 @@ int mac802154_get_mhrlen(MACHANDLE mac, * ****************************************************************************/ -int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req); +int mac802154_req_data(MACHANDLE mac, + FAR const struct ieee802154_frame_meta_s *meta, + FAR struct iob_s *frame); /**************************************************************************** * Name: mac802154_req_purge @@ -129,9 +131,15 @@ int mac802154_req_data(MACHANDLE mac, FAR struct ieee802154_data_req_s *req); * an MSDU from the transaction queue. Confirmation is returned via * the struct ieee802154_maccb_s->conf_purge callback. * + * NOTE: The standard specifies that confirmation should be indicated via + * the asynchronous MLME-PURGE.confirm primitve. However, in our + * implementation we synchronously return the status from the request. + * Therefore, we merge the functionality of the MLME-PURGE.request and + * MLME-PURGE.confirm primitives together. + * ****************************************************************************/ -int mac802154_req_purge(MACHANDLE mac, FAR struct ieee802154_purge_req_s *req); +int mac802154_req_purge(MACHANDLE mac, uint8_t msdu_handle); /**************************************************************************** * Name: mac802154_req_associate @@ -163,18 +171,6 @@ int mac802154_req_associate(MACHANDLE mac, int mac802154_req_disassociate(MACHANDLE mac, FAR struct ieee802154_disassoc_req_s *req); -/**************************************************************************** - * Name: mac802154_req_get - * - * Description: - * The MLME-GET.request primitive requests information about a given PIB - * attribute. Actual data is returned via the - * struct ieee802154_maccb_s->conf_get callback. - * - ****************************************************************************/ - -int mac802154_req_get(MACHANDLE mac, FAR struct ieee802154_get_req_s *req); - /**************************************************************************** * Name: mac802154_req_gts * @@ -193,12 +189,21 @@ int mac802154_req_gts(MACHANDLE mac, FAR struct ieee802154_gts_req_s *req); * * Description: * The MLME-RESET.request primitive allows the next higher layer to request - * that the MLME performs a reset operation. Confirmation is returned via - * the struct ieee802154_maccb_s->conf_reset callback. + * that the MLME performs a reset operation. + * + * NOTE: The standard specifies that confirmation should be provided via + * via the asynchronous MLME-RESET.confirm primitve. However, in our + * implementation we synchronously return the value immediately. Therefore, + * we merge the functionality of the MLME-RESET.request and MLME-RESET.confirm + * primitives together. + * + * Input Parameters: + * mac - Handle to the MAC layer instance + * rst_pibattr - Whether or not to reset the MAC PIB attributes to defaults * ****************************************************************************/ -int mac802154_req_reset(MACHANDLE mac, FAR struct ieee802154_reset_req_s *req); +int mac802154_req_reset(MACHANDLE mac, bool rst_pibattr); /**************************************************************************** * Name: mac802154_req_rxenable @@ -231,13 +236,36 @@ int mac802154_req_rxenable(MACHANDLE mac, int mac802154_req_scan(MACHANDLE mac, FAR struct ieee802154_scan_req_s *req); +/**************************************************************************** + * Name: mac802154_req_get + * + * Description: + * The MLME-GET.request primitive requests information about a given PIB + * attribute. + * + * NOTE: The standard specifies that the attribute value should be returned + * via the asynchronous MLME-GET.confirm primitve. However, in our + * implementation, we synchronously return the value immediately.Therefore, we + * merge the functionality of the MLME-GET.request and MLME-GET.confirm + * primitives together. + * + ****************************************************************************/ + +int mac802154_req_get(MACHANDLE mac, enum ieee802154_pib_attr_e pib_attr, + FAR union ieee802154_attr_val_u *attr_value); + /**************************************************************************** * Name: mac802154_req_set * * Description: * The MLME-SET.request primitive attempts to write the given value to the - * indicated MAC PIB attribute. Confirmation is returned via the - * struct ieee802154_maccb_s->conf_set callback. + * indicated MAC PIB attribute. + * + * NOTE: The standard specifies that confirmation should be indicated via + * the asynchronous MLME-SET.confirm primitve. However, in our implementation + * we synchronously return the status from the request. Therefore, we do merge + * the functionality of the MLME-SET.request and MLME-SET.confirm primitives + * together. * ****************************************************************************/ diff --git a/wireless/ieee802154/mac802154_device.c b/wireless/ieee802154/mac802154_device.c index 7f76e8cd3d..d78e7acfdc 100644 --- a/wireless/ieee802154/mac802154_device.c +++ b/wireless/ieee802154/mac802154_device.c @@ -406,7 +406,6 @@ static ssize_t mac802154dev_write(FAR struct file *filep, FAR struct mac802154_chardevice_s *dev; FAR struct mac802154dev_txframe_s *tx; FAR struct iob_s *iob; - struct ieee802154_data_req_s req; struct mac802154dev_dwait_s dwait; int ret; @@ -440,7 +439,7 @@ static ssize_t mac802154dev_write(FAR struct file *filep, /* Get the MAC header length */ - ret = mac802154_get_mhrlen(dev->md_mac, tx->meta); + ret = mac802154_get_mhrlen(dev->md_mac, &tx->meta); if (ret < 0) { wlerr("ERROR: TX meta-data is invalid"); @@ -450,9 +449,9 @@ static ssize_t mac802154dev_write(FAR struct file *filep, iob->io_offset = ret; iob->io_len = iob->io_offset; - memcpy(&iob->io_data[iob->io_offset], tx->payload, tx->meta->msdu_length); + memcpy(&iob->io_data[iob->io_offset], tx->payload, tx->meta.msdu_length); - iob->io_len += tx->meta->msdu_length; + iob->io_len += tx->meta.msdu_length; /* If this is a blocking operation, we need to setup a wait struct so we * can unblock when the packet transmission has finished. If this is a @@ -473,7 +472,7 @@ static ssize_t mac802154dev_write(FAR struct file *filep, /* Setup the wait struct */ - dwait.mw_handle = tx->meta->msdu_handle; + dwait.mw_handle = tx->meta.msdu_handle; /* Link the wait struct */ @@ -486,12 +485,9 @@ static ssize_t mac802154dev_write(FAR struct file *filep, mac802154dev_givesem(&dev->md_exclsem); } - req.meta = tx->meta; - req.frame = iob; - /* Pass the request to the MAC layer */ - ret = mac802154_req_data(dev->md_mac, &req); + ret = mac802154_req_data(dev->md_mac, &tx->meta, iob); if (ret < 0) { -- GitLab From b5e1ea4bef87a24752e3b2c41f13884650873604 Mon Sep 17 00:00:00 2001 From: Simon Piriou Date: Wed, 3 May 2017 23:19:28 +0200 Subject: [PATCH 693/990] bcmf: fix frame not freed when dropped + cleanup --- drivers/wireless/ieee80211/bcmf_bdc.c | 8 - drivers/wireless/ieee80211/bcmf_bdc.h | 1 - drivers/wireless/ieee80211/bcmf_cdc.c | 4 - drivers/wireless/ieee80211/bcmf_chip_43362.c | 3 +- drivers/wireless/ieee80211/bcmf_core.c | 4 - drivers/wireless/ieee80211/bcmf_driver.c | 132 ++-- drivers/wireless/ieee80211/bcmf_driver.h | 7 +- drivers/wireless/ieee80211/bcmf_ioctl.h | 770 +++++++++---------- drivers/wireless/ieee80211/bcmf_netdev.c | 40 +- drivers/wireless/ieee80211/bcmf_sdio.c | 3 - drivers/wireless/ieee80211/bcmf_sdio_core.h | 310 ++++---- drivers/wireless/ieee80211/bcmf_sdio_regs.h | 181 +++-- drivers/wireless/ieee80211/bcmf_utils.c | 18 - drivers/wireless/ieee80211/bcmf_utils.h | 3 - include/nuttx/wireless/wireless.h | 75 +- 15 files changed, 758 insertions(+), 801 deletions(-) diff --git a/drivers/wireless/ieee80211/bcmf_bdc.c b/drivers/wireless/ieee80211/bcmf_bdc.c index 2c92232ff3..a9dd3b3a81 100644 --- a/drivers/wireless/ieee80211/bcmf_bdc.c +++ b/drivers/wireless/ieee80211/bcmf_bdc.c @@ -87,20 +87,12 @@ struct __attribute__((packed)) bcmf_event_msg uint8_t data[0]; }; -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - /**************************************************************************** * Private Data ****************************************************************************/ static const uint8_t bcmf_broadcom_oui[] = {0x00, 0x10, 0x18}; -/**************************************************************************** - * Private Functions - ****************************************************************************/ - /**************************************************************************** * Public Functions ****************************************************************************/ diff --git a/drivers/wireless/ieee80211/bcmf_bdc.h b/drivers/wireless/ieee80211/bcmf_bdc.h index 48003bdc5c..905dc7209f 100644 --- a/drivers/wireless/ieee80211/bcmf_bdc.h +++ b/drivers/wireless/ieee80211/bcmf_bdc.h @@ -41,7 +41,6 @@ #define __DRIVERS_WIRELESS_IEEE80211_BCMF_BDC_H #include "bcmf_driver.h" -#include "bcmf_ioctl.h" /* Event frame content */ diff --git a/drivers/wireless/ieee80211/bcmf_cdc.c b/drivers/wireless/ieee80211/bcmf_cdc.c index a825f6dbdd..c45bbef1b5 100644 --- a/drivers/wireless/ieee80211/bcmf_cdc.c +++ b/drivers/wireless/ieee80211/bcmf_cdc.c @@ -95,10 +95,6 @@ static int bcmf_cdc_control_request_unsafe(FAR struct bcmf_dev_s *priv, uint32_t ifidx, bool set, uint32_t cmd, char *name, uint8_t *data, uint32_t *len); -/**************************************************************************** - * Private Data - ****************************************************************************/ - /**************************************************************************** * Private Functions ****************************************************************************/ diff --git a/drivers/wireless/ieee80211/bcmf_chip_43362.c b/drivers/wireless/ieee80211/bcmf_chip_43362.c index 5637173c95..891cf7784a 100644 --- a/drivers/wireless/ieee80211/bcmf_chip_43362.c +++ b/drivers/wireless/ieee80211/bcmf_chip_43362.c @@ -34,7 +34,8 @@ ****************************************************************************/ #include "bcmf_sdio.h" - +#include + #define WRAPPER_REGISTER_OFFSET 0x100000 extern const char bcm43362_nvram_image[]; diff --git a/drivers/wireless/ieee80211/bcmf_core.c b/drivers/wireless/ieee80211/bcmf_core.c index 77cd59f314..e51e88c876 100644 --- a/drivers/wireless/ieee80211/bcmf_core.c +++ b/drivers/wireless/ieee80211/bcmf_core.c @@ -94,10 +94,6 @@ static int bcmf_upload_binary(FAR struct bcmf_sdio_dev_s *sbusv, static int bcmf_upload_nvram(FAR struct bcmf_sdio_dev_s *sbus); -/**************************************************************************** - * Private Data - ****************************************************************************/ - /**************************************************************************** * Private Functions ****************************************************************************/ diff --git a/drivers/wireless/ieee80211/bcmf_driver.c b/drivers/wireless/ieee80211/bcmf_driver.c index 791a8394ba..78f3ee0b86 100644 --- a/drivers/wireless/ieee80211/bcmf_driver.c +++ b/drivers/wireless/ieee80211/bcmf_driver.c @@ -62,9 +62,7 @@ * Pre-processor Definitions ****************************************************************************/ -// TODO move elsewhere -#define DOT11_BSSTYPE_ANY 2 - +#define DOT11_BSSTYPE_ANY 2 #define BCMF_SCAN_TIMEOUT_TICK (5*CLOCKS_PER_SEC) #define BCMF_AUTH_TIMEOUT_MS 10000 @@ -107,10 +105,6 @@ static void bcmf_wl_auth_event_handler(FAR struct bcmf_dev_s *priv, static int bcmf_wl_get_interface(FAR struct bcmf_dev_s *priv, struct iwreq *iwr); -/**************************************************************************** - * Private Data - ****************************************************************************/ - /**************************************************************************** * Private Functions ****************************************************************************/ @@ -440,10 +434,10 @@ void bcmf_wl_scan_event_handler(FAR struct bcmf_dev_s *priv, goto exit_invalid_frame; } - wlinfo("Scan result: <%.32s> %02x:%02x:%02x:%02x:%02x:%02x\n", - bss->SSID, bss->BSSID.octet[0], bss->BSSID.octet[1], - bss->BSSID.octet[2], bss->BSSID.octet[3], - bss->BSSID.octet[4], bss->BSSID.octet[5]); + wlinfo("Scan result: <%.32s> %02x:%02x:%02x:%02x:%02x:%02x\n", bss->SSID, + bss->BSSID.ether_addr_octet[0], bss->BSSID.ether_addr_octet[1], + bss->BSSID.ether_addr_octet[3], bss->BSSID.ether_addr_octet[3], + bss->BSSID.ether_addr_octet[4], bss->BSSID.ether_addr_octet[5]); /* Process next bss_info */ @@ -473,15 +467,6 @@ wl_escan_result_processed: wd_cancel(priv->scan_timeout); - if (!priv->scan_params) - { - /* Scan has already timedout */ - - return; - } - - free(priv->scan_params); - priv->scan_params = NULL; priv->scan_status = BCMF_SCAN_DONE; sem_post(&priv->control_mutex); @@ -506,8 +491,6 @@ void bcmf_wl_scan_timeout(int argc, wdparm_t arg1, ...) wlerr("Scan timeout detected\n"); priv->scan_status = BCMF_SCAN_TIMEOUT; - free(priv->scan_params); - priv->scan_params = NULL; sem_post(&priv->control_mutex); } @@ -573,15 +556,72 @@ int bcmf_wl_enable(FAR struct bcmf_dev_s *priv, bool enable) return ret; } -int bcmf_wl_start_scan(FAR struct bcmf_dev_s *priv) +int bcmf_wl_start_scan(FAR struct bcmf_dev_s *priv, struct iwreq *iwr) { int ret; uint32_t out_len; uint32_t value; + int interface; + struct iw_scan_req *req; + struct wl_escan_params scan_params; + + interface = bcmf_wl_get_interface(priv, iwr); + + if (interface < 0) + { + return -EINVAL; + } + + memset(&scan_params, 0, sizeof(scan_params)); + + scan_params.version = ESCAN_REQ_VERSION; + scan_params.action = WL_SCAN_ACTION_START; + scan_params.sync_id = 0xabcd; /* Not used for now */ + + memset(&scan_params.params.bssid, 0xFF, + sizeof(scan_params.params.bssid)); + + scan_params.params.bss_type = DOT11_BSSTYPE_ANY; + scan_params.params.nprobes = -1; + scan_params.params.active_time = -1; + scan_params.params.passive_time = -1; + scan_params.params.home_time = -1; + scan_params.params.channel_num = 0; + + if (iwr->u.data.pointer && iwr->u.data.length >= sizeof(*req)) + { + req = (struct iw_scan_req*)iwr->u.data.pointer; + + memcpy(&scan_params.params.bssid, req->bssid.sa_data, + sizeof(scan_params.params.bssid)); + + scan_params.params.scan_type = + req->scan_type == IW_SCAN_TYPE_ACTIVE ? 0:1; + + if (iwr->u.data.flags & IW_SCAN_THIS_ESSID && + req->essid_len < sizeof(scan_params.params.ssid.SSID)) + { + /* Scan specific ESSID */ + + memcpy(scan_params.params.ssid.SSID, req->essid, req->essid_len); + scan_params.params.ssid.SSID_len = req->essid_len; + } + } + else + { + /* Default scan parameters */ + + wlinfo("Use default scan parameters\n"); + + memset(&scan_params.params.bssid, 0xFF, + sizeof(scan_params.params.bssid)); + + scan_params.params.scan_type = 0; /* Active scan */ + } /* Set active scan mode */ - value = 0; + value = scan_params.params.scan_type; out_len = 4; if (bcmf_cdc_ioctl(priv, CHIP_STA_INTERFACE, true, WLC_SET_PASSIVE_SCAN, (uint8_t*)&value, &out_len)) @@ -597,45 +637,18 @@ int bcmf_wl_start_scan(FAR struct bcmf_dev_s *priv) goto exit_failed; } - /* Default request structure */ - - priv->scan_params = (struct wl_escan_params*) - kmm_malloc(sizeof(*priv->scan_params)); - if (!priv->scan_params) - { - ret = -ENOMEM; - goto exit_sem_post; - } - - memset(priv->scan_params, 0, sizeof(*priv->scan_params)); - - priv->scan_params->version = ESCAN_REQ_VERSION; - priv->scan_params->action = WL_SCAN_ACTION_START; - priv->scan_params->sync_id = 0xabcd; /* Not used for now */ - - memset(&priv->scan_params->params.bssid, 0xFF, - sizeof(priv->scan_params->params.bssid)); - priv->scan_params->params.bss_type = DOT11_BSSTYPE_ANY; - priv->scan_params->params.scan_type = 0; /* Active scan */ - priv->scan_params->params.nprobes = -1; - priv->scan_params->params.active_time = -1; - priv->scan_params->params.passive_time = -1; - priv->scan_params->params.home_time = -1; - priv->scan_params->params.channel_num = 0; - wlinfo("start scan\n"); priv->scan_status = BCMF_SCAN_RUN; - out_len = sizeof(*priv->scan_params); - + out_len = sizeof(scan_params); if (bcmf_cdc_iovar_request_unsafe(priv, CHIP_STA_INTERFACE, true, - IOVAR_STR_ESCAN, (uint8_t*)priv->scan_params, + IOVAR_STR_ESCAN, (uint8_t*)&scan_params, &out_len)) { ret = -EIO; - goto exit_free_params; + goto exit_sem_post; } /* Start scan_timeout timer */ @@ -645,9 +658,6 @@ int bcmf_wl_start_scan(FAR struct bcmf_dev_s *priv) return OK; -exit_free_params: - free(priv->scan_params); - priv->scan_params = NULL; exit_sem_post: sem_post(&priv->control_mutex); priv->scan_status = BCMF_SCAN_DISABLED; @@ -656,8 +666,12 @@ exit_failed: return ret; } -int bcmf_wl_is_scan_done(FAR struct bcmf_dev_s *priv) +int bcmf_wl_get_scan_results(FAR struct bcmf_dev_s *priv, struct iwreq *iwr) { + /* Not implemented yet, set len to zero */ + + iwr->u.data.length = 0; + if (priv->scan_status == BCMF_SCAN_RUN) { return -EAGAIN; @@ -896,4 +910,4 @@ int bcmf_wl_set_ssid(FAR struct bcmf_dev_s *priv, struct iwreq *iwr) return -EINVAL; } return OK; - } + } \ No newline at end of file diff --git a/drivers/wireless/ieee80211/bcmf_driver.h b/drivers/wireless/ieee80211/bcmf_driver.h index 27b2e51a40..3e38ff4f93 100644 --- a/drivers/wireless/ieee80211/bcmf_driver.h +++ b/drivers/wireless/ieee80211/bcmf_driver.h @@ -45,6 +45,8 @@ #include #include +#include "bcmf_ioctl.h" + struct bcmf_dev_s; struct bcmf_frame_s; @@ -91,7 +93,6 @@ struct bcmf_dev_s int scan_status; /* Current scan status */ WDOG_ID scan_timeout; /* Scan timeout timer */ - struct wl_escan_params *scan_params; /* Current scan parameters */ sem_t auth_signal; /* Authentication notification signal */ int auth_status; /* Authentication status */ @@ -135,9 +136,9 @@ int bcmf_wl_enable(FAR struct bcmf_dev_s *priv, bool enable); /* IOCTLs AP scan interface implementation */ -int bcmf_wl_start_scan(FAR struct bcmf_dev_s *priv); +int bcmf_wl_start_scan(FAR struct bcmf_dev_s *priv, struct iwreq *iwr); -int bcmf_wl_is_scan_done(FAR struct bcmf_dev_s *priv); +int bcmf_wl_get_scan_results(FAR struct bcmf_dev_s *priv, struct iwreq *iwr); /* IOCTLs authentication interface implementation */ diff --git a/drivers/wireless/ieee80211/bcmf_ioctl.h b/drivers/wireless/ieee80211/bcmf_ioctl.h index 483102455a..f37fd608bc 100644 --- a/drivers/wireless/ieee80211/bcmf_ioctl.h +++ b/drivers/wireless/ieee80211/bcmf_ioctl.h @@ -36,90 +36,53 @@ * Custom OID/ioctl definitions for * Broadcom 802.11abg Networking Device Driver */ -#ifndef _wlioctl_h_ -#define _wlioctl_h_ +#ifndef __DRIVERS_WIRELESS_IEEE80211_BCMF_IOCTL_H +#define __DRIVERS_WIRELESS_IEEE80211_BCMF_IOCTL_H #include +#include -#ifdef __cplusplus -extern "C" { -#endif - -#define ACTION_FRAME_SIZE 1040 typedef uint16_t wl_chanspec_t; typedef uint16_t chanspec_t; -#define ETHER_ADDR_LEN 6 -typedef struct ether_addr_dup -{ - uint8_t octet[ETHER_ADDR_LEN]; -} wl_ether_addr_t; -struct wl_ether_header -{ - uint8_t ether_dhost[ETHER_ADDR_LEN]; - uint8_t ether_shost[ETHER_ADDR_LEN]; - uint16_t ether_type; -}; + +#define ACTION_FRAME_SIZE 1040 + typedef struct wl_action_frame { - wl_ether_addr_t da; - uint16_t len; - uint32_t packetId; - uint8_t data[ACTION_FRAME_SIZE]; + struct ether_addr da; + uint16_t len; + uint32_t packetId; + uint8_t data[ACTION_FRAME_SIZE]; } wl_action_frame_t; -/* ether types */ -#define ETHER_TYPE_LEN 2 -#define ETHER_TYPE_MIN 0x0600 /* Anything less than MIN is a length */ -#define ETHER_TYPE_IP 0x0800 /* IP */ -#define ETHER_TYPE_ARP 0x0806 /* ARP */ -#define ETHER_TYPE_8021Q 0x8100 /* 802.1Q */ -#define ETHER_TYPE_802_1X 0x888e /* 802.1x */ -#ifdef BCMWAPI_WPI -#define ETHER_TYPE_WAI 0x88b4 /* WAPI WAI */ -#endif /* BCMWAPI_WPI */ -#define ETHER_TYPE_802_1X_PREAUTH 0x88c7 /* 802.1x preauthentication */ -#define WL_WIFI_ACTION_FRAME_SIZE sizeof(struct wl_action_frame) -#define BWL_DEFAULT_PACKING - -#define RWL_ACTION_WIFI_CATEGORY 127 -#define RWL_WIFI_OUI_BYTE1 0x90 -#define RWL_WIFI_OUI_BYTE2 0x4C -#define RWL_WIFI_OUI_BYTE3 0x0F -#define RWL_WIFI_ACTION_FRAME_SIZE sizeof(struct dot11_action_wifi_vendor_specific) -#define RWL_WIFI_DEFAULT 0x00 -#define RWL_WIFI_FIND_MY_PEER 0x09 -#define RWL_WIFI_FOUND_PEER 0x0A -#define RWL_ACTION_WIFI_FRAG_TYPE 0x55 + typedef struct ssid_info { uint8_t ssid_len; uint8_t ssid[32]; } ssid_info_t; + typedef struct cnt_rx { uint32_t cnt_rxundec; uint32_t cnt_rxframe; } cnt_rx_t; -#define RWL_REF_MAC_ADDRESS_OFFSET 17 -#define RWL_DUT_MAC_ADDRESS_OFFSET 23 -#define RWL_WIFI_CLIENT_CHANNEL_OFFSET 50 -#define RWL_WIFI_SERVER_CHANNEL_OFFSET 51 -#define WL_BSS_INFO_VERSION 108 -#define MCSSET_LEN 16 + +#define MCSSET_LEN 16 typedef struct wl_bss_info { uint32_t version; /* version field */ uint32_t length; /* byte length of data in this record, */ /* starting at version and including IEs */ - wl_ether_addr_t BSSID; + struct ether_addr BSSID; uint16_t beacon_period; /* units are Kusec */ uint16_t capability; /* Capability information */ uint8_t SSID_len; uint8_t SSID[32]; struct { - uint32_t count; /* # rates in this set */ + uint32_t count; /* # rates in this set */ uint8_t rates[16]; /* rates in 500kbps units w/hi bit set if basic */ } rateset; /* supported rates */ - wl_chanspec_t chanspec; /* chanspec for bss */ + wl_chanspec_t chanspec; /* chanspec for bss */ uint16_t atim_window; /* units are Kusec */ uint8_t dtim_period; /* DTIM period */ int16_t RSSI; /* receive signal strength (in dBm) */ @@ -145,15 +108,17 @@ typedef struct wlc_ssid uint32_t SSID_len; uint8_t SSID[32]; } wlc_ssid_t; + #define WL_BSSTYPE_INFRA 1 #define WL_BSSTYPE_INDEP 0 #define WL_BSSTYPE_ANY 2 #define WL_SCANFLAGS_PASSIVE 0x01 #define WL_SCANFLAGS_PROHIBITED 0x04 + typedef struct wl_scan_params { wlc_ssid_t ssid; - wl_ether_addr_t bssid; + struct ether_addr bssid; int8_t bss_type; int8_t scan_type; int32_t nprobes; @@ -163,6 +128,7 @@ typedef struct wl_scan_params int32_t channel_num; uint16_t channel_list[1]; } wl_scan_params_t; + #define WL_SCAN_PARAMS_FIXED_SIZE (64) #define WL_SCAN_PARAMS_COUNT_MASK (0x0000ffff) #define WL_SCAN_PARAMS_NSSID_SHIFT (16) @@ -170,6 +136,7 @@ typedef struct wl_scan_params #define WL_SCAN_ACTION_CONTINUE (2) #define WL_SCAN_ACTION_ABORT (3) #define ISCAN_REQ_VERSION (1) + typedef struct wl_iscan_params { uint32_t version; @@ -177,7 +144,9 @@ typedef struct wl_iscan_params uint16_t scan_duration; wl_scan_params_t params; } wl_iscan_params_t; + #define WL_ISCAN_PARAMS_FIXED_SIZE (offsetof(wl_iscan_params_t, params) + sizeof(wlc_ssid_t)) + typedef struct wl_scan_results { uint32_t buflen; @@ -185,6 +154,7 @@ typedef struct wl_scan_results uint32_t count; wl_bss_info_t bss_info[1]; } wl_scan_results_t; + #define WL_SCAN_RESULTS_FIXED_SIZE (12) #define WL_SCAN_RESULTS_SUCCESS (0) #define WL_SCAN_RESULTS_PARTIAL (1) @@ -192,6 +162,7 @@ typedef struct wl_scan_results #define WL_SCAN_RESULTS_ABORTED (3) #define WL_SCAN_RESULTS_NO_MEM (4) #define ESCAN_REQ_VERSION 1 + typedef struct wl_escan_params { uint32_t version; @@ -199,7 +170,9 @@ typedef struct wl_escan_params uint16_t sync_id; wl_scan_params_t params; } wl_escan_params_t; + #define WL_ESCAN_PARAMS_FIXED_SIZE (offsetof(wl_escan_params_t, params) + sizeof(wlc_ssid_t)) + typedef struct wl_escan_result { uint32_t buflen; @@ -208,15 +181,19 @@ typedef struct wl_escan_result uint16_t bss_count; wl_bss_info_t bss_info[1]; } wl_escan_result_t; + #define WL_ESCAN_RESULTS_FIXED_SIZE (sizeof(wl_escan_result_t) - sizeof(wl_bss_info_t)) + typedef struct wl_iscan_results { uint32_t status; wl_scan_results_t results; } wl_iscan_results_t; + #define WL_ISCAN_RESULTS_FIXED_SIZE \ (WL_SCAN_RESULTS_FIXED_SIZE + offsetof(wl_iscan_results_t, results)) #define WL_MAXRATES_IN_SET 16 /* max # of rates in a rateset */ + typedef struct wl_rateset { uint32_t count; /* # rates in this set */ @@ -230,20 +207,16 @@ typedef struct wl_uint32_list } wl_uint32_list_t; typedef struct wl_join_scan_params { - uint8_t scan_type; /* 0 use default, active or passive scan */ - int32_t nprobes; /* -1 use default, number of probes per channel */ - int32_t active_time; /* -1 use default, dwell time per channel for - * active scanning - */ - int32_t passive_time; /* -1 use default, dwell time per channel - * for passive scanning - */ - int32_t home_time; /* -1 use default, dwell time for the home channel - * between channel scans - */ + uint8_t scan_type; /* 0 use default, active or passive scan */ + int32_t nprobes; /* -1 use default, number of probes per channel */ + int32_t active_time; /* -1 use default, dwell time per channel for + * active scanning */ + int32_t passive_time; /* -1 use default, dwell time per channel + * for passive scanning */ + int32_t home_time; /* -1 use default, dwell time for the home channel + * between channel scans */ } wl_join_scan_params_t; -#if !defined(ESTA_POSTMOGRIFY_REMOVAL) #define NRATE_MCS_INUSE (0x00000080) #define NRATE_RATE_MASK (0x0000007f) #define NRATE_STF_MASK (0x0000ff00) @@ -271,19 +244,23 @@ typedef struct wl_join_scan_params { #define ANT_SELCFG_RX_UNICAST (1) #define ANT_SELCFG_TX_DEF (2) #define ANT_SELCFG_RX_DEF (3) + typedef struct { uint8_t ant_config[ANT_SELCFG_MAX]; uint8_t num_antcfg; } wlc_antselcfg_t; + #define HIGHEST_SINGLE_STREAM_MCS (7) #define WLC_CNTRY_BUF_SZ (4) + typedef struct wl_country { int8_t country_abbrev[WLC_CNTRY_BUF_SZ]; int32_t rev; int8_t ccode[WLC_CNTRY_BUF_SZ]; } wl_country_t; + typedef struct wl_channels_in_country { uint32_t buflen; @@ -292,6 +269,7 @@ typedef struct wl_channels_in_country uint32_t count; uint32_t channel[1]; } wl_channels_in_country_t; + typedef struct wl_country_list { uint32_t buflen; @@ -300,14 +278,16 @@ typedef struct wl_country_list uint32_t count; int8_t country_abbrev[1]; } wl_country_list_t; -#define WL_NUM_RPI_BINS 8 -#define WL_RM_TYPE_BASIC 1 -#define WL_RM_TYPE_CCA 2 -#define WL_RM_TYPE_RPI 3 -#define WL_RM_FLAG_PARALLEL (1<<0) -#define WL_RM_FLAG_LATE (1<<1) -#define WL_RM_FLAG_INCAPABLE (1<<2) -#define WL_RM_FLAG_REFUSED (1<<3) + +#define WL_NUM_RPI_BINS 8 +#define WL_RM_TYPE_BASIC 1 +#define WL_RM_TYPE_CCA 2 +#define WL_RM_TYPE_RPI 3 +#define WL_RM_FLAG_PARALLEL (1<<0) +#define WL_RM_FLAG_LATE (1<<1) +#define WL_RM_FLAG_INCAPABLE (1<<2) +#define WL_RM_FLAG_REFUSED (1<<3) + typedef struct wl_rm_req_elt { int8_t type; @@ -318,6 +298,7 @@ typedef struct wl_rm_req_elt uint32_t tsf_l; uint32_t dur; } wl_rm_req_elt_t; + typedef struct wl_rm_req { uint32_t token; @@ -326,7 +307,9 @@ typedef struct wl_rm_req void* cb_arg; wl_rm_req_elt_t req[1]; } wl_rm_req_t; + #define WL_RM_REQ_FIXED_LEN offsetof(wl_rm_req_t, req) + typedef struct wl_rm_rep_elt { int8_t type; @@ -339,8 +322,10 @@ typedef struct wl_rm_rep_elt uint32_t len; uint8_t data[1]; } wl_rm_rep_elt_t; + #define WL_RM_REP_ELT_FIXED_LEN 24 #define WL_RPI_REP_BIN_NUM 8 + typedef struct wl_rm_rpi_rep { uint8_t rpi[WL_RPI_REP_BIN_NUM]; @@ -352,25 +337,29 @@ typedef struct wl_rm_rep uint32_t len; wl_rm_rep_elt_t rep[1]; } wl_rm_rep_t; + #define WL_RM_REP_FIXED_LEN 8 -#endif -#define CRYPTO_ALGO_OFF 0 -#define CRYPTO_ALGO_WEP1 1 -#define CRYPTO_ALGO_TKIP 2 -#define CRYPTO_ALGO_WEP128 3 -#define CRYPTO_ALGO_AES_CCM 4 -#define CRYPTO_ALGO_AES_OCB_MSDU 5 -#define CRYPTO_ALGO_AES_OCB_MPDU 6 -#define CRYPTO_ALGO_NALG 7 -#define WSEC_GEN_MIC_ERROR 0x0001 -#define WSEC_GEN_REPLAY 0x0002 -#define WSEC_GEN_ICV_ERROR 0x0004 -#define WL_SOFT_KEY (1 << 0) -#define WL_PRIMARY_KEY (1 << 1) -#define WL_KF_RES_4 (1 << 4) -#define WL_KF_RES_5 (1 << 5) -#define WL_IBSS_PEER_GROUP_KEY (1 << 6) -#define DOT11_MAX_KEY_SIZE 32 + +#define CRYPTO_ALGO_OFF 0 +#define CRYPTO_ALGO_WEP1 1 +#define CRYPTO_ALGO_TKIP 2 +#define CRYPTO_ALGO_WEP128 3 +#define CRYPTO_ALGO_AES_CCM 4 +#define CRYPTO_ALGO_AES_OCB_MSDU 5 +#define CRYPTO_ALGO_AES_OCB_MPDU 6 +#define CRYPTO_ALGO_NALG 7 + +#define WSEC_GEN_MIC_ERROR 0x0001 +#define WSEC_GEN_REPLAY 0x0002 +#define WSEC_GEN_ICV_ERROR 0x0004 + +#define WL_SOFT_KEY (1 << 0) +#define WL_PRIMARY_KEY (1 << 1) +#define WL_KF_RES_4 (1 << 4) +#define WL_KF_RES_5 (1 << 5) +#define WL_IBSS_PEER_GROUP_KEY (1 << 6) +#define DOT11_MAX_KEY_SIZE 32 + typedef struct wl_wsec_key { uint32_t index; @@ -389,11 +378,13 @@ typedef struct wl_wsec_key uint16_t lo; } rxiv; uint32_t pad_5[2]; - wl_ether_addr_t ea; + struct ether_addr ea; } wl_wsec_key_t; + #define WSEC_MIN_PSK_LEN 8 #define WSEC_MAX_PSK_LEN 64 #define WSEC_PASSPHRASE (1<<0) + typedef struct { uint16_t key_len; @@ -407,98 +398,93 @@ typedef struct #define TKIP_ENABLED 0x0002 #define AES_ENABLED 0x0004 #define WSEC_SWFLAG 0x0008 -#ifdef BCMCCX -#define CKIP_KP_ENABLED 0x0010 -#define CKIP_MIC_ENABLED 0x0020 -#endif #define SES_OW_ENABLED 0x0040 -#ifdef WLFIPS -#define FIPS_ENABLED 0x0080 -#endif -#ifdef BCMWAPI_WPI -#define SMS4_ENABLED 0x0100 -#endif #define WPA_AUTH_DISABLED 0x0000 #define WPA_AUTH_NONE 0x0001 #define WPA_AUTH_UNSPECIFIED 0x0002 #define WPA_AUTH_PSK 0x0004 -#if defined(BCMCCX) || defined(BCMEXTCCX) -#define WPA_AUTH_CCKM 0x0008 -#define WPA2_AUTH_CCKM 0x0010 -#endif #define WPA2_AUTH_UNSPECIFIED 0x0040 #define WPA2_AUTH_PSK 0x0080 #define BRCM_AUTH_PSK 0x0100 #define BRCM_AUTH_DPT 0x0200 -#ifdef BCMWAPI_WPI -#define WPA_AUTH_WAPI 0x0400 -#endif #define WPA_AUTH_PFN_ANY 0xffffffff -#define MAXPMKID 16 +#define MAXPMKID 16 #define WPA2_PMKID_LEN 16 + typedef struct _pmkid { - wl_ether_addr_t BSSID; + struct ether_addr BSSID; uint8_t PMKID[WPA2_PMKID_LEN]; } pmkid_t; + typedef struct _pmkid_list { uint32_t npmkid; pmkid_t pmkid[1]; } pmkid_list_t; + typedef struct _pmkid_cand { - wl_ether_addr_t BSSID; + struct ether_addr BSSID; uint8_t preauth; } pmkid_cand_t; + typedef struct _pmkid_cand_list { uint32_t npmkid_cand; pmkid_cand_t pmkid_cand[1]; } pmkid_cand_list_t; -#if !defined(ESTA_POSTMOGRIFY_REMOVAL) + typedef struct wl_led_info { uint32_t index; uint32_t behavior; uint8_t activehi; } wl_led_info_t; + struct wl_dot11_assoc_req { uint16_t capability; uint16_t listen; }; + struct wl_dot11_assoc_resp { uint16_t capability; uint16_t status; uint16_t aid; }; + typedef struct wl_assoc_info { uint32_t req_len; uint32_t resp_len; uint32_t flags; struct wl_dot11_assoc_req req; - wl_ether_addr_t reassoc_bssid; + struct ether_addr reassoc_bssid; struct wl_dot11_assoc_resp resp; } wl_assoc_info_t; + #define WLC_ASSOC_REQ_IS_REASSOC 0x01 + typedef struct { uint32_t byteoff; uint32_t nbytes; uint16_t buf[1]; } srom_rw_t; + typedef struct { uint32_t source; uint32_t byteoff; uint32_t nbytes; } cis_rw_t; -#define WLC_CIS_DEFAULT 0 + +#define WLC_CIS_DEFAULT 0 #define WLC_CIS_SROM 1 -#define WLC_CIS_OTP 2 +#define WLC_CIS_OTP 2 + typedef struct { uint32_t byteoff; @@ -506,9 +492,11 @@ typedef struct uint32_t size; uint32_t band; } rw_reg_t; -#define WL_ATTEN_APP_INPUT_PCL_OFF 0 + +#define WL_ATTEN_APP_INPUT_PCL_OFF 0 #define WL_ATTEN_PCL_ON 1 -#define WL_ATTEN_PCL_OFF 2 +#define WL_ATTEN_PCL_OFF 2 + typedef struct { uint16_t auto_ctrl; @@ -516,6 +504,7 @@ typedef struct uint16_t radio; uint16_t txctl1; } atten_t; + struct wme_tx_params_s { uint8_t short_retry; @@ -525,19 +514,21 @@ struct wme_tx_params_s uint16_t max_rate; }; typedef struct wme_tx_params_s wme_tx_params_t; + #define WL_WME_TX_PARAMS_IO_BYTES (sizeof(wme_tx_params_t) * AC_COUNT) #define WL_PWRIDX_PCL_OFF -2 #define WL_PWRIDX_PCL_ON -1 #define WL_PWRIDX_LOWER_LIMIT -2 #define WL_PWRIDX_UPPER_LIMIT 63 -#endif + typedef struct { uint32_t val; - wl_ether_addr_t ea; + struct ether_addr ea; } scb_val_t; -#if !defined(ESTA_POSTMOGRIFY_REMOVAL) + #define BCM_MAC_STATUS_INDICATION (0x40010200L) + typedef struct { uint16_t ver; @@ -545,7 +536,7 @@ typedef struct uint16_t cap; uint32_t flags; uint32_t idle; - wl_ether_addr_t ea; + struct ether_addr ea; wl_rateset_t rateset; uint32_t in; uint32_t listen_interval_inms; @@ -556,11 +547,12 @@ typedef struct uint32_t tx_rate; uint32_t rx_rate; } sta_info_t; + #define WL_OLD_STAINFO_SIZE offsetof(sta_info_t, tx_pkts) -#define WL_STA_VER 2 -#define WL_STA_BRCM 0x1 -#define WL_STA_WME 0x2 -#define WL_STA_ABCAP 0x4 +#define WL_STA_VER 2 +#define WL_STA_BRCM 0x1 +#define WL_STA_WME 0x2 +#define WL_STA_ABCAP 0x4 #define WL_STA_AUTHE 0x8 #define WL_STA_ASSOC 0x10 #define WL_STA_AUTHO 0x20 @@ -574,7 +566,7 @@ typedef struct #define WL_STA_N_CAP 0x2000 #define WL_STA_SCBSTATS 0x4000 #define WL_WDS_LINKUP WL_STA_WDS_LINKUP -#endif + typedef struct channel_info { int32_t hw_channel; @@ -584,7 +576,7 @@ typedef struct channel_info struct mac_list { uint32_t count; - wl_ether_addr_t ea[1]; + struct ether_addr ea[1]; }; typedef struct get_pktcnt { @@ -603,7 +595,7 @@ typedef struct wl_ioctl uint32_t used; uint32_t needed; } wl_ioctl_t; -#if !defined(ESTA_POSTMOGRIFY_REMOVAL) + typedef struct wlc_rev_info { uint32_t vendorid; @@ -622,26 +614,30 @@ typedef struct wlc_rev_info uint32_t phyrev; uint32_t anarev; } wlc_rev_info_t; + #define WL_REV_INFO_LEGACY_LENGTH 48 #define WL_BRAND_MAX 10 + typedef struct wl_instance_info { uint32_t instance; int8_t brand[WL_BRAND_MAX]; } wl_instance_info_t; + typedef struct wl_txfifo_sz { uint8_t fifo; uint8_t size; } wl_txfifo_sz_t; + #define WLC_IOV_NAME_LEN 30 + typedef struct wlc_iov_trx_s { uint8_t module; uint8_t type; int8_t name[WLC_IOV_NAME_LEN]; } wlc_iov_trx_t; -#endif #define IOVAR_STR_BSSCFG_WPA_AUTH "bsscfg:wpa_auth" #define IOVAR_STR_BSSCFG_WSEC "bsscfg:wsec" @@ -999,9 +995,6 @@ typedef struct wlc_iov_trx_s #define WLC_GET_RANDOM_BYTES ( (uint32_t) 319 ) #define WLC_LAST ( (uint32_t) 320 ) -#ifndef EPICTRL_COOKIE -#define EPICTRL_COOKIE 0xABADCEDE -#endif #define CMN_IOCTL_OFF 0x180 #define WL_OID_BASE 0xFFE41420 #define OID_WL_GETINSTANCE (WL_OID_BASE + WLC_GET_INSTANCE) @@ -1031,21 +1024,6 @@ typedef struct wlc_iov_trx_s #define WL_DECRYPT_STATUS_UNKNOWN 3 #define WLC_UPGRADE_SUCCESS 0 #define WLC_UPGRADE_PENDING 1 -#ifdef CONFIG_USBRNDIS_RETAIL -typedef struct -{ - int8_t* name; - void* param; -}ndconfig_item_t; -#endif -#ifdef EXT_STA -typedef struct _wl_assoc_result -{ - ulong associated; - ulong NDIS_auth; - ulong NDIS_infra; -}wl_assoc_result_t; -#endif #define WL_RADIO_SW_DISABLE (1<<0) #define WL_RADIO_HW_DISABLE (1<<1) #define WL_RADIO_MPC_DISABLE (1<<2) @@ -1129,6 +1107,7 @@ typedef struct _wl_assoc_result #define WLAN_MANUAL (2) #define WLAN_AUTO (3) #define AUTO_ACTIVE (1 << 7) + typedef struct wl_aci_args { int32_t enter_aci_thresh; @@ -1144,8 +1123,9 @@ typedef struct wl_aci_args uint16_t nphy_b_energy_md_aci; uint16_t nphy_b_energy_hi_aci; } wl_aci_args_t; + #define WL_ACI_ARGS_LEGACY_LENGTH 16 -#if !defined(ESTA_POSTMOGRIFY_REMOVAL) + typedef struct { int32_t npulses; @@ -1168,26 +1148,30 @@ typedef struct uint16_t t2_min; uint32_t version; } wl_radar_args_t; + #define WL_RADAR_ARGS_VERSION 1 -#define WL_RADAR_DETECTOR_OFF 0 -#define WL_RADAR_DETECTOR_ON 1 -#define WL_RADAR_SIMULATED 2 -#define WL_RSSI_ANT_VERSION 1 -#define WL_RSSI_ANT_MAX 4 +#define WL_RADAR_DETECTOR_OFF 0 +#define WL_RADAR_DETECTOR_ON 1 +#define WL_RADAR_SIMULATED 2 +#define WL_RSSI_ANT_VERSION 1 +#define WL_RSSI_ANT_MAX 4 + typedef struct { uint32_t version; uint32_t count; int8_t rssi_ant[WL_RSSI_ANT_MAX]; } wl_rssi_ant_t; + #define WL_DFS_CACSTATE_IDLE 0 -#define WL_DFS_CACSTATE_PREISM_CAC 1 -#define WL_DFS_CACSTATE_ISM 2 -#define WL_DFS_CACSTATE_CSA 3 -#define WL_DFS_CACSTATE_POSTISM_CAC 4 -#define WL_DFS_CACSTATE_PREISM_OOC 5 -#define WL_DFS_CACSTATE_POSTISM_OOC 6 -#define WL_DFS_CACSTATES 7 +#define WL_DFS_CACSTATE_PREISM_CAC 1 +#define WL_DFS_CACSTATE_ISM 2 +#define WL_DFS_CACSTATE_CSA 3 +#define WL_DFS_CACSTATE_POSTISM_CAC 4 +#define WL_DFS_CACSTATE_PREISM_OOC 5 +#define WL_DFS_CACSTATE_POSTISM_OOC 6 +#define WL_DFS_CACSTATES 7 + typedef struct { uint32_t state; @@ -1195,7 +1179,9 @@ typedef struct wl_chanspec_t chanspec_cleared; uint16_t pad; } wl_dfs_status_t; + #define NUM_PWRCTRL_RATES 12 + typedef struct { uint8_t txpwr_band_max[NUM_PWRCTRL_RATES]; @@ -1212,23 +1198,25 @@ typedef struct int8_t txpwr_antgain[2]; uint8_t txpwr_est_Pout_gofdm; } tx_power_legacy_t; -#define WL_TX_POWER_RATES 45 -#define WL_TX_POWER_CCK_FIRST 0 -#define WL_TX_POWER_CCK_NUM 4 + +#define WL_TX_POWER_RATES 45 +#define WL_TX_POWER_CCK_FIRST 0 +#define WL_TX_POWER_CCK_NUM 4 #define WL_TX_POWER_OFDM_FIRST 4 -#define WL_TX_POWER_OFDM_NUM 8 -#define WL_TX_POWER_MCS_SISO_NUM 8 -#define WL_TX_POWER_MCS20_FIRST 12 -#define WL_TX_POWER_MCS20_NUM 16 -#define WL_TX_POWER_MCS40_FIRST 28 -#define WL_TX_POWER_MCS40_NUM 17 -#define WL_TX_POWER_MCS20SISO_NUM 8 +#define WL_TX_POWER_OFDM_NUM 8 +#define WL_TX_POWER_MCS_SISO_NUM 8 +#define WL_TX_POWER_MCS20_FIRST 12 +#define WL_TX_POWER_MCS20_NUM 16 +#define WL_TX_POWER_MCS40_FIRST 28 +#define WL_TX_POWER_MCS40_NUM 17 +#define WL_TX_POWER_MCS20SISO_NUM 8 #define WL_TX_POWER_MCS40_LAST 44 -#define WL_TX_POWER_F_ENABLED 1 -#define WL_TX_POWER_F_HW 2 -#define WL_TX_POWER_F_MIMO 4 -#define WL_TX_POWER_F_SISO 8 -#define WL_TX_POWER_F_40M_CAP 16 +#define WL_TX_POWER_F_ENABLED 1 +#define WL_TX_POWER_F_HW 2 +#define WL_TX_POWER_F_MIMO 4 +#define WL_TX_POWER_F_SISO 8 +#define WL_TX_POWER_F_40M_CAP 16 + typedef struct { uint32_t flags; @@ -1245,37 +1233,39 @@ typedef struct uint8_t board_limit[WL_TX_POWER_RATES]; uint8_t target[WL_TX_POWER_RATES]; } tx_power_t; + typedef struct tx_inst_power { uint8_t txpwr_est_Pout[2]; uint8_t txpwr_est_Pout_gofdm; } tx_inst_power_t; -#define WLC_MEASURE_TPC 1 -#define WLC_MEASURE_CHANNEL_BASIC 2 -#define WLC_MEASURE_CHANNEL_CCA 3 -#define WLC_MEASURE_CHANNEL_RPI 4 -#define SPECT_MNGMT_OFF 0 -#define SPECT_MNGMT_LOOSE_11H 1 -#define SPECT_MNGMT_STRICT_11H 2 -#define SPECT_MNGMT_STRICT_11D 3 -#define SPECT_MNGMT_LOOSE_11H_D 4 + +#define WLC_MEASURE_TPC 1 +#define WLC_MEASURE_CHANNEL_BASIC 2 +#define WLC_MEASURE_CHANNEL_CCA 3 +#define WLC_MEASURE_CHANNEL_RPI 4 +#define SPECT_MNGMT_OFF 0 +#define SPECT_MNGMT_LOOSE_11H 1 +#define SPECT_MNGMT_STRICT_11H 2 +#define SPECT_MNGMT_STRICT_11D 3 +#define SPECT_MNGMT_LOOSE_11H_D 4 #define WL_CHAN_VALID_HW (1 << 0) #define WL_CHAN_VALID_SW (1 << 1) -#define WL_CHAN_BAND_5G (1 << 2) -#define WL_CHAN_RADAR (1 << 3) +#define WL_CHAN_BAND_5G (1 << 2) +#define WL_CHAN_RADAR (1 << 3) #define WL_CHAN_INACTIVE (1 << 4) -#define WL_CHAN_PASSIVE (1 << 5) -#define WL_CHAN_RESTRICTED (1 << 6) -#define WL_BTC_DISABLE 0 -#define WL_BTC_ENABLE (1 << 0) -#define WL_BTC_PREMPT (1 << 1) -#define WL_BTC_PARTIAL (1 << 2) -#define WL_BTC_DEFAULT (1 << 3) -#define WL_BTC_HYBRID (WL_BTC_ENABLE | WL_BTC_PARTIAL) -#define WL_INF_BTC_DISABLE 0 -#define WL_INF_BTC_ENABLE 1 -#define WL_INF_BTC_AUTO 3 -#define WL_BTC_DEFWIRE 0 +#define WL_CHAN_PASSIVE (1 << 5) +#define WL_CHAN_RESTRICTED (1 << 6) +#define WL_BTC_DISABLE 0 +#define WL_BTC_ENABLE (1 << 0) +#define WL_BTC_PREMPT (1 << 1) +#define WL_BTC_PARTIAL (1 << 2) +#define WL_BTC_DEFAULT (1 << 3) +#define WL_BTC_HYBRID (WL_BTC_ENABLE | WL_BTC_PARTIAL) +#define WL_INF_BTC_DISABLE 0 +#define WL_INF_BTC_ENABLE 1 +#define WL_INF_BTC_AUTO 3 +#define WL_BTC_DEFWIRE 0 #define WL_BTC_2WIRE 2 #define WL_BTC_3WIRE 3 #define WL_BTC_4WIRE 4 @@ -1284,85 +1274,79 @@ typedef struct tx_inst_power #define WL_BTC_FLAG_ACTIVE_PROT (1 << 2) #define WL_BTC_FLAG_SIM_RSP (1 << 3) #define WL_BTC_FLAG_PS_PROTECT (1 << 4) -#define WL_BTC_FLAG_SIM_TX_LP (1 << 5) +#define WL_BTC_FLAG_SIM_TX_LP (1 << 5) #define WL_BTC_FLAG_ECI (1 << 6) -#endif -#define WL_ERROR_VAL 0x00000001 -#define WL_TRACE_VAL 0x00000002 -#define WL_PRHDRS_VAL 0x00000004 -#define WL_PRPKT_VAL 0x00000008 -#define WL_INFORM_VAL 0x00000010 -#define WL_TMP_VAL 0x00000020 -#define WL_OID_VAL 0x00000040 +#define WL_ERROR_VAL 0x00000001 +#define WL_TRACE_VAL 0x00000002 +#define WL_PRHDRS_VAL 0x00000004 +#define WL_PRPKT_VAL 0x00000008 +#define WL_INFORM_VAL 0x00000010 +#define WL_TMP_VAL 0x00000020 +#define WL_OID_VAL 0x00000040 #define WL_RATE_VAL 0x00000080 -#define WL_ASSOC_VAL 0x00000100 -#define WL_PRUSR_VAL 0x00000200 -#define WL_PS_VAL 0x00000400 -#define WL_TXPWR_VAL 0x00000800 +#define WL_ASSOC_VAL 0x00000100 +#define WL_PRUSR_VAL 0x00000200 +#define WL_PS_VAL 0x00000400 +#define WL_TXPWR_VAL 0x00000800 #define WL_PORT_VAL 0x00001000 #define WL_DUAL_VAL 0x00002000 #define WL_WSEC_VAL 0x00004000 -#define WL_WSEC_DUMP_VAL 0x00008000 -#define WL_LOG_VAL 0x00010000 -#define WL_NRSSI_VAL 0x00020000 +#define WL_WSEC_DUMP_VAL 0x00008000 +#define WL_LOG_VAL 0x00010000 +#define WL_NRSSI_VAL 0x00020000 #define WL_LOFT_VAL 0x00040000 -#define WL_REGULATORY_VAL 0x00080000 -#define WL_PHYCAL_VAL 0x00100000 -#define WL_RADAR_VAL 0x00200000 -#define WL_MPC_VAL 0x00400000 -#define WL_APSTA_VAL 0x00800000 -#define WL_DFS_VAL 0x01000000 -#define WL_BA_VAL 0x02000000 -#if defined(WLNINTENDO) -#define WL_NITRO_VAL 0x04000000 -#endif +#define WL_REGULATORY_VAL 0x00080000 +#define WL_PHYCAL_VAL 0x00100000 +#define WL_RADAR_VAL 0x00200000 +#define WL_MPC_VAL 0x00400000 +#define WL_APSTA_VAL 0x00800000 +#define WL_DFS_VAL 0x01000000 +#define WL_BA_VAL 0x02000000 #define WL_MBSS_VAL 0x04000000 -#define WL_CAC_VAL 0x08000000 -#define WL_AMSDU_VAL 0x10000000 -#define WL_AMPDU_VAL 0x20000000 -#define WL_FFPLD_VAL 0x40000000 -#if defined(WLNINTENDO) -#define WL_NIN_VAL 0x80000000 -#endif +#define WL_CAC_VAL 0x08000000 +#define WL_AMSDU_VAL 0x10000000 +#define WL_AMPDU_VAL 0x20000000 +#define WL_FFPLD_VAL 0x40000000 #define WL_DPT_VAL 0x00000001 #define WL_SCAN_VAL 0x00000002 #define WL_WOWL_VAL 0x00000004 #define WL_COEX_VAL 0x00000008 #define WL_RTDC_VAL 0x00000010 -#define WL_BTA_VAL 0x00000040 -#define WL_LED_NUMGPIO 16 -#define WL_LED_OFF 0 -#define WL_LED_ON 1 -#define WL_LED_ACTIVITY 2 -#define WL_LED_RADIO 3 -#define WL_LED_ARADIO 4 -#define WL_LED_BRADIO 5 -#define WL_LED_BGMODE 6 -#define WL_LED_WI1 7 -#define WL_LED_WI2 8 -#define WL_LED_WI3 9 -#define WL_LED_ASSOC 10 -#define WL_LED_INACTIVE 11 -#define WL_LED_ASSOCACT 12 -#define WL_LED_NUMBEHAVIOR 13 -#define WL_LED_BEH_MASK 0x7f -#define WL_LED_AL_MASK 0x80 +#define WL_BTA_VAL 0x00000040 +#define WL_LED_NUMGPIO 16 +#define WL_LED_OFF 0 +#define WL_LED_ON 1 +#define WL_LED_ACTIVITY 2 +#define WL_LED_RADIO 3 +#define WL_LED_ARADIO 4 +#define WL_LED_BRADIO 5 +#define WL_LED_BGMODE 6 +#define WL_LED_WI1 7 +#define WL_LED_WI2 8 +#define WL_LED_WI3 9 +#define WL_LED_ASSOC 10 +#define WL_LED_INACTIVE 11 +#define WL_LED_ASSOCACT 12 +#define WL_LED_NUMBEHAVIOR 13 +#define WL_LED_BEH_MASK 0x7f +#define WL_LED_AL_MASK 0x80 #define WL_NUMCHANNELS 64 -#define WL_NUMCHANSPECS 100 -#define WL_WDS_WPA_ROLE_AUTH 0 -#define WL_WDS_WPA_ROLE_SUP 1 -#define WL_WDS_WPA_ROLE_AUTO 255 -#define WL_EVENTING_MASK_LEN ((WLC_E_LAST + 7) / 8) - -#define VNDR_IE_CMD_LEN 4 -#define VNDR_IE_BEACON_FLAG 0x1 -#define VNDR_IE_PRBRSP_FLAG 0x2 -#define VNDR_IE_ASSOCRSP_FLAG 0x4 -#define VNDR_IE_AUTHRSP_FLAG 0x8 -#define VNDR_IE_PRBREQ_FLAG 0x10 -#define VNDR_IE_ASSOCREQ_FLAG 0x20 -#define VNDR_IE_CUSTOM_FLAG 0x100 -#define VNDR_IE_INFO_HDR_LEN (sizeof(uint32_t)) +#define WL_NUMCHANSPECS 100 +#define WL_WDS_WPA_ROLE_AUTH 0 +#define WL_WDS_WPA_ROLE_SUP 1 +#define WL_WDS_WPA_ROLE_AUTO 255 +#define WL_EVENTING_MASK_LEN ((WLC_E_LAST + 7) / 8) + +#define VNDR_IE_CMD_LEN 4 +#define VNDR_IE_BEACON_FLAG 0x1 +#define VNDR_IE_PRBRSP_FLAG 0x2 +#define VNDR_IE_ASSOCRSP_FLAG 0x4 +#define VNDR_IE_AUTHRSP_FLAG 0x8 +#define VNDR_IE_PRBREQ_FLAG 0x10 +#define VNDR_IE_ASSOCREQ_FLAG 0x20 +#define VNDR_IE_CUSTOM_FLAG 0x100 +#define VNDR_IE_INFO_HDR_LEN (sizeof(uint32_t)) + struct wl_vndr_ie { uint8_t id; @@ -1371,35 +1355,39 @@ struct wl_vndr_ie uint8_t data[1]; }; typedef struct wl_vndr_ie wl_vndr_ie_t; + typedef struct { uint32_t pktflag; wl_vndr_ie_t vndr_ie_data; } vndr_ie_info_t; + typedef struct { int32_t iecount; vndr_ie_info_t vndr_ie_list[1]; } vndr_ie_buf_t; + typedef struct { int8_t cmd[VNDR_IE_CMD_LEN]; vndr_ie_buf_t vndr_ie_buffer; } vndr_ie_setbuf_t; + #define WL_JOIN_PREF_RSSI 1 -#define WL_JOIN_PREF_WPA 2 +#define WL_JOIN_PREF_WPA 2 #define WL_JOIN_PREF_BAND 3 -#define WLJP_BAND_ASSOC_PREF 255 -#define WL_WPA_ACP_MCS_ANY "\x00\x00\x00\x00" +#define WLJP_BAND_ASSOC_PREF 255 +#define WL_WPA_ACP_MCS_ANY "\x00\x00\x00\x00" + struct tsinfo_arg { uint8_t octets[3]; }; -#define NFIFO 6 -#define WL_CNT_T_VERSION 6 -#define WL_CNT_EXT_T_VERSION 1 - +#define NFIFO 6 +#define WL_CNT_T_VERSION 6 +#define WL_CNT_EXT_T_VERSION 1 typedef struct { @@ -2214,66 +2202,36 @@ typedef struct wl_mkeep_alive_pkt { #define WL_MKEEP_ALIVE_FIXED_LEN offsetof(wl_mkeep_alive_pkt_t, data) #define WL_MKEEP_ALIVE_PRECISION 500 -#if !defined(ESTA_POSTMOGRIFY_REMOVAL) -#ifdef WLBA -#define WLC_BA_CNT_VERSION 1 -typedef struct wlc_ba_cnt -{ - uint16_t version; - uint16_t length; - uint32_t txpdu; - uint32_t txsdu; - uint32_t txfc; - uint32_t txfci; - uint32_t txretrans; - uint32_t txbatimer; - uint32_t txdrop; - uint32_t txaddbareq; - uint32_t txaddbaresp; - uint32_t txdelba; - uint32_t txba; - uint32_t txbar; - uint32_t txpad[4]; - uint32_t rxpdu; - uint32_t rxqed; - uint32_t rxdup; - uint32_t rxnobuf; - uint32_t rxaddbareq; - uint32_t rxaddbaresp; - uint32_t rxdelba; - uint32_t rxba; - uint32_t rxbar; - uint32_t rxinvba; - uint32_t rxbaholes; - uint32_t rxunexp; - uint32_t rxpad[4]; -}wlc_ba_cnt_t; -#endif struct ampdu_tid_control { uint8_t tid; uint8_t enable; }; + struct wl_msglevel2 { uint32_t low; uint32_t high; }; + struct ampdu_ea_tid { - wl_ether_addr_t ea; + struct ether_addr ea; uint8_t tid; }; + struct ampdu_retry_tid { uint8_t tid; uint8_t retry; }; + struct ampdu_ba_sizes { uint8_t ba_tx_wsize; uint8_t ba_rx_wsize; }; + #define DPT_DISCOVERY_MANUAL 0x01 #define DPT_DISCOVERY_AUTO 0x02 #define DPT_DISCOVERY_SCAN 0x04 @@ -2287,7 +2245,7 @@ struct ampdu_ba_sizes #define DPT_MANUAL_EP_DELETE 3 typedef struct dpt_iovar { - wl_ether_addr_t ea; + struct ether_addr ea; uint8_t mode; uint32_t pad; } dpt_iovar_t; @@ -2349,7 +2307,7 @@ typedef struct tspec_arg } tspec_arg_t; typedef struct tspec_per_sta_arg { - wl_ether_addr_t ea; + struct ether_addr ea; struct tspec_arg ts; } tspec_per_sta_arg_t; typedef struct wme_max_bandwidth @@ -2366,16 +2324,6 @@ typedef struct wme_max_bandwidth #define TSPEC_REJECTED 2 #define TSPEC_UNKNOWN 3 #define TSPEC_STATUS_MASK 7 -#ifdef BCMCCX -#define WL_WLAN_ASSOC_REASON_NORMAL_NETWORK 0 -#define WL_WLAN_ASSOC_REASON_ROAM_FROM_CELLULAR_NETWORK 1 -#define WL_WLAN_ASSOC_REASON_ROAM_FROM_LAN 2 -#define WL_WLAN_ASSOC_REASON_MAX 2 -#endif -#ifdef WLAFTERBURNER -#define WL_SWFL_ABBFL 0x0001 -#define WL_SWFL_ABENCORE 0x0002 -#endif #define WL_SWFL_NOHWRADIO 0x0004 #define WL_LIFETIME_MAX 0xFFFF typedef struct wl_lifetime @@ -2390,15 +2338,17 @@ typedef struct wl_chan_switch wl_chanspec_t chspec; uint8_t reg; } wl_chan_switch_t; -#endif + #define WLC_ROAM_TRIGGER_DEFAULT 0 #define WLC_ROAM_TRIGGER_BANDWIDTH 1 #define WLC_ROAM_TRIGGER_DISTANCE 2 #define WLC_ROAM_TRIGGER_MAX_VALUE 2 + enum { PFN_LIST_ORDER, PFN_RSSI }; + #define SORT_CRITERIA_BIT 0 #define AUTO_NET_SWITCH_BIT 1 #define ENABLE_BKGRD_SCAN_BIT 2 @@ -2410,6 +2360,7 @@ enum #define IMMEDIATE_SCAN_MASK 0x08 #define AUTO_CONNECT_MASK 0x10 #define PFN_VERSION 1 + typedef struct wl_pfn_param { int32_t version; @@ -2418,6 +2369,7 @@ typedef struct wl_pfn_param int16_t flags; int16_t rssi_margin; } wl_pfn_param_t; + typedef struct wl_pfn { wlc_ssid_t ssid; @@ -2426,19 +2378,14 @@ typedef struct wl_pfn int32_t auth; uint32_t wpa_auth; int32_t wsec; -#ifdef WLPFN_AUTO_CONNECT -union -{ - wl_wsec_key_t sec_key; - wsec_pmk_t wpa_sec_key; -}pfn_security; -#endif } wl_pfn_t; + #define TOE_TX_CSUM_OL 0x00000001 #define TOE_RX_CSUM_OL 0x00000002 #define TOE_ERRTEST_TX_CSUM 0x00000001 #define TOE_ERRTEST_RX_CSUM 0x00000002 #define TOE_ERRTEST_RX_CSUM2 0x00000004 + struct toe_ol_stats_t { uint32_t tx_summed; @@ -2461,6 +2408,7 @@ struct toe_ol_stats_t uint32_t rx_udp_errinj; uint32_t rx_icmp_errinj; }; + #define ARP_OL_AGENT 0x00000001 #define ARP_OL_SNOOP 0x00000002 #define ARP_OL_HOST_AUTO_REPLY 0x00000004 @@ -2468,6 +2416,7 @@ struct toe_ol_stats_t #define ARP_ERRTEST_REPLY_PEER 0x1 #define ARP_ERRTEST_REPLY_HOST 0x2 #define ARP_MULTIHOMING_MAX 8 + struct arp_ol_stats_t { uint32_t host_ip_entries; @@ -2483,24 +2432,30 @@ struct arp_ol_stats_t uint32_t peer_reply_drop; uint32_t peer_service; }; + typedef struct wl_keep_alive_pkt { uint32_t period_msec; uint16_t len_bytes; uint8_t data[1]; } wl_keep_alive_pkt_t; + #define WL_KEEP_ALIVE_FIXED_LEN offsetof(wl_keep_alive_pkt_t, data) + typedef enum wl_pkt_filter_type { WL_PKT_FILTER_TYPE_PATTERN_MATCH } wl_pkt_filter_type_t; + #define WL_PKT_FILTER_TYPE wl_pkt_filter_type_t + typedef struct wl_pkt_filter_pattern { uint32_t offset; uint32_t size_bytes; uint8_t mask_and_pattern[1]; } wl_pkt_filter_pattern_t; + typedef struct wl_pkt_filter { uint32_t id; @@ -2511,30 +2466,37 @@ typedef struct wl_pkt_filter wl_pkt_filter_pattern_t pattern; } u; } wl_pkt_filter_t; + #define WL_PKT_FILTER_FIXED_LEN offsetof(wl_pkt_filter_t, u) #define WL_PKT_FILTER_PATTERN_FIXED_LEN offsetof(wl_pkt_filter_pattern_t, mask_and_pattern) + typedef struct wl_pkt_filter_enable { uint32_t id; uint32_t enable; } wl_pkt_filter_enable_t; + typedef struct wl_pkt_filter_list { uint32_t num; wl_pkt_filter_t filter[1]; } wl_pkt_filter_list_t; + #define WL_PKT_FILTER_LIST_FIXED_LEN offsetof(wl_pkt_filter_list_t, filter) + typedef struct wl_pkt_filter_stats { uint32_t num_pkts_matched; uint32_t num_pkts_forwarded; uint32_t num_pkts_discarded; } wl_pkt_filter_stats_t; + typedef struct wl_seq_cmd_ioctl { uint32_t cmd; uint32_t len; } wl_seq_cmd_ioctl_t; + #define WL_SEQ_CMD_ALIGN_BYTES 4 #define WL_SEQ_CMDS_GET_IOCTL_FILTER(cmd) \ (((cmd) == WLC_GET_MAGIC) || \ @@ -2549,6 +2511,7 @@ typedef struct wl_seq_cmd_ioctl #define WL_PKTENG_PER_RX_STOP 0x08 #define WL_PKTENG_PER_MASK 0xff #define WL_PKTENG_SYNCHRONOUS 0x100 + typedef struct wl_pkteng { uint32_t flags; @@ -2556,13 +2519,15 @@ typedef struct wl_pkteng uint32_t nframes; uint32_t length; uint8_t seqno; - wl_ether_addr_t dest; - wl_ether_addr_t src; + struct ether_addr dest; + struct ether_addr src; } wl_pkteng_t; + #define NUM_80211b_RATES 4 #define NUM_80211ag_RATES 8 #define NUM_80211n_RATES 32 #define NUM_80211_RATES (NUM_80211b_RATES+NUM_80211ag_RATES+NUM_80211n_RATES) + typedef struct wl_pkteng_stats { uint32_t lostfrmcnt; @@ -2570,44 +2535,7 @@ typedef struct wl_pkteng_stats int32_t snr; uint16_t rxpktcnt[NUM_80211_RATES + 1]; } wl_pkteng_stats_t; -#if !defined(BCMDONGLEHOST) || defined(BCMINTERNAL) || defined(WLTEST) -typedef struct wl_sslpnphy_papd_debug_data -{ - uint8_t psat_pwr; - uint8_t psat_indx; - uint8_t final_idx; - uint8_t start_idx; - int32_t min_phase; - int32_t voltage; - int8_t temperature; -} wl_sslpnphy_papd_debug_data_t; -typedef struct wl_sslpnphy_debug_data -{ - int16_t papdcompRe[64]; - int16_t papdcompIm[64]; -} wl_sslpnphy_debug_data_t; -typedef struct wl_sslpnphy_spbdump_data -{ - uint16_t tbl_length; - int16_t spbreal[256]; - int16_t spbimg[256]; -} wl_sslpnphy_spbdump_data_t; -typedef struct wl_sslpnphy_percal_debug_data -{ - uint32_t cur_idx; - uint32_t tx_drift; - uint8_t prev_cal_idx; - uint32_t percal_ctr; - int32_t nxt_cal_idx; - uint32_t force_1idxcal; - uint32_t onedxacl_req; - int32_t last_cal_volt; - int8_t last_cal_temp; - uint32_t vbat_ripple; - uint32_t exit_route; - int32_t volt_winner; -} wl_sslpnphy_percal_debug_data_t; -#endif + #define WL_WOWL_MAGIC (1 << 0) #define WL_WOWL_NET (1 << 1) #define WL_WOWL_DIS (1 << 2) @@ -2616,6 +2544,7 @@ typedef struct wl_sslpnphy_percal_debug_data #define WL_WOWL_TST (1 << 5) #define WL_WOWL_BCAST (1 << 15) #define MAGIC_PKT_MINLEN 102 + typedef struct { uint32_t masksize; @@ -2623,48 +2552,48 @@ typedef struct uint32_t patternoffset; uint32_t patternsize; } wl_wowl_pattern_t; + typedef struct { uint32_t count; wl_wowl_pattern_t pattern[1]; } wl_wowl_pattern_list_t; + typedef struct { uint8_t pci_wakeind; uint16_t ucode_wakeind; } wl_wowl_wakeind_t; + typedef struct wl_txrate_class { uint8_t init_rate; uint8_t min_rate; uint8_t max_rate; } wl_txrate_class_t; -#if defined(DSLCPE_DELAY) -#define WL_DELAYMODE_DEFER 0 -#define WL_DELAYMODE_FORCE 1 -#define WL_DELAYMODE_AUTO 2 -#endif -#define WLC_OBSS_SCAN_PASSIVE_DWELL_DEFAULT 100 -#define WLC_OBSS_SCAN_PASSIVE_DWELL_MIN 5 -#define WLC_OBSS_SCAN_PASSIVE_DWELL_MAX 1000 -#define WLC_OBSS_SCAN_ACTIVE_DWELL_DEFAULT 20 -#define WLC_OBSS_SCAN_ACTIVE_DWELL_MIN 10 -#define WLC_OBSS_SCAN_ACTIVE_DWELL_MAX 1000 -#define WLC_OBSS_SCAN_WIDTHSCAN_INTERVAL_DEFAULT 300 -#define WLC_OBSS_SCAN_WIDTHSCAN_INTERVAL_MIN 10 -#define WLC_OBSS_SCAN_WIDTHSCAN_INTERVAL_MAX 900 -#define WLC_OBSS_SCAN_CHANWIDTH_TRANSITION_DLY_DEFAULT 5 -#define WLC_OBSS_SCAN_CHANWIDTH_TRANSITION_DLY_MIN 5 -#define WLC_OBSS_SCAN_CHANWIDTH_TRANSITION_DLY_MAX 100 -#define WLC_OBSS_SCAN_PASSIVE_TOTAL_PER_CHANNEL_DEFAULT 200 -#define WLC_OBSS_SCAN_PASSIVE_TOTAL_PER_CHANNEL_MIN 200 -#define WLC_OBSS_SCAN_PASSIVE_TOTAL_PER_CHANNEL_MAX 10000 -#define WLC_OBSS_SCAN_ACTIVE_TOTAL_PER_CHANNEL_DEFAULT 20 -#define WLC_OBSS_SCAN_ACTIVE_TOTAL_PER_CHANNEL_MIN 20 -#define WLC_OBSS_SCAN_ACTIVE_TOTAL_PER_CHANNEL_MAX 10000 -#define WLC_OBSS_SCAN_ACTIVITY_THRESHOLD_DEFAULT 25 -#define WLC_OBSS_SCAN_ACTIVITY_THRESHOLD_MIN 0 -#define WLC_OBSS_SCAN_ACTIVITY_THRESHOLD_MAX 100 + +#define WLC_OBSS_SCAN_PASSIVE_DWELL_DEFAULT 100 +#define WLC_OBSS_SCAN_PASSIVE_DWELL_MIN 5 +#define WLC_OBSS_SCAN_PASSIVE_DWELL_MAX 1000 +#define WLC_OBSS_SCAN_ACTIVE_DWELL_DEFAULT 20 +#define WLC_OBSS_SCAN_ACTIVE_DWELL_MIN 10 +#define WLC_OBSS_SCAN_ACTIVE_DWELL_MAX 1000 +#define WLC_OBSS_SCAN_WIDTHSCAN_INTERVAL_DEFAULT 300 +#define WLC_OBSS_SCAN_WIDTHSCAN_INTERVAL_MIN 10 +#define WLC_OBSS_SCAN_WIDTHSCAN_INTERVAL_MAX 900 +#define WLC_OBSS_SCAN_CHANWIDTH_TRANSITION_DLY_DEFAULT 5 +#define WLC_OBSS_SCAN_CHANWIDTH_TRANSITION_DLY_MIN 5 +#define WLC_OBSS_SCAN_CHANWIDTH_TRANSITION_DLY_MAX 100 +#define WLC_OBSS_SCAN_PASSIVE_TOTAL_PER_CHANNEL_DEFAULT 200 +#define WLC_OBSS_SCAN_PASSIVE_TOTAL_PER_CHANNEL_MIN 200 +#define WLC_OBSS_SCAN_PASSIVE_TOTAL_PER_CHANNEL_MAX 10000 +#define WLC_OBSS_SCAN_ACTIVE_TOTAL_PER_CHANNEL_DEFAULT 20 +#define WLC_OBSS_SCAN_ACTIVE_TOTAL_PER_CHANNEL_MIN 20 +#define WLC_OBSS_SCAN_ACTIVE_TOTAL_PER_CHANNEL_MAX 10000 +#define WLC_OBSS_SCAN_ACTIVITY_THRESHOLD_DEFAULT 25 +#define WLC_OBSS_SCAN_ACTIVITY_THRESHOLD_MIN 0 +#define WLC_OBSS_SCAN_ACTIVITY_THRESHOLD_MAX 100 + typedef struct wl_obss_scan_arg { int16_t passive_dwell; @@ -2675,41 +2604,44 @@ typedef struct wl_obss_scan_arg int16_t chanwidth_transition_delay; int16_t activity_threshold; } wl_obss_scan_arg_t; -#define WL_OBSS_SCAN_PARAM_LEN sizeof(wl_obss_scan_arg_t) + +#define WL_OBSS_SCAN_PARAM_LEN sizeof(wl_obss_scan_arg_t) #define WL_MIN_NUM_OBSS_SCAN_ARG 7 #define WL_COEX_INFO_MASK 0x07 -#define WL_COEX_INFO_REQ 0x01 -#define WL_COEX_40MHZ_INTOLERANT 0x02 -#define WL_COEX_WIDTH20 0x04 +#define WL_COEX_INFO_REQ 0x01 +#define WL_COEX_40MHZ_INTOLERANT 0x02 +#define WL_COEX_WIDTH20 0x04 + typedef struct wl_action_obss_coex_req { uint8_t info; uint8_t num; uint8_t ch_list[1]; } wl_action_obss_coex_req_t; + #define MAX_RSSI_LEVELS 8 + typedef struct wl_rssi_event { uint32_t rate_limit_msec; uint8_t num_rssi_levels; int8_t rssi_levels[MAX_RSSI_LEVELS]; } wl_rssi_event_t; -#define WLFEATURE_DISABLE_11N 0x00000001 -#define WLFEATURE_DISABLE_11N_STBC_TX 0x00000002 -#define WLFEATURE_DISABLE_11N_STBC_RX 0x00000004 -#define WLFEATURE_DISABLE_11N_SGI_TX 0x00000008 -#define WLFEATURE_DISABLE_11N_SGI_RX 0x00000010 -#define WLFEATURE_DISABLE_11N_AMPDU_TX 0x00000020 -#define WLFEATURE_DISABLE_11N_AMPDU_RX 0x00000040 -#define WLFEATURE_DISABLE_11N_GF 0x00000080 - +#define WLFEATURE_DISABLE_11N 0x00000001 +#define WLFEATURE_DISABLE_11N_STBC_TX 0x00000002 +#define WLFEATURE_DISABLE_11N_STBC_RX 0x00000004 +#define WLFEATURE_DISABLE_11N_SGI_TX 0x00000008 +#define WLFEATURE_DISABLE_11N_SGI_RX 0x00000010 +#define WLFEATURE_DISABLE_11N_AMPDU_TX 0x00000020 +#define WLFEATURE_DISABLE_11N_AMPDU_RX 0x00000040 +#define WLFEATURE_DISABLE_11N_GF 0x00000080 #pragma pack(1) typedef struct sta_prbreq_wps_ie_hdr { - wl_ether_addr_t staAddr; + struct ether_addr staAddr; uint16_t ieLen; } sta_prbreq_wps_ie_hdr_t; @@ -2725,7 +2657,6 @@ typedef struct sta_prbreq_wps_ie_list uint8_t ieDataList[1]; } sta_prbreq_wps_ie_list_t; - /* EDCF related items from 802.11.h */ /* ACI from 802.11.h */ @@ -2757,7 +2688,6 @@ struct edcf_acparam { } ; typedef struct edcf_acparam edcf_acparam_t; - /* Stop packing structures */ #pragma pack() @@ -2899,13 +2829,13 @@ typedef enum WLC_E_LAST = 129, /** highest val + 1 for range checking */ WLC_E_FORCE_32_BIT = 0x7FFFFFFE /** Force enum to be stored in 32 bit variable */ -} wwd_event_num_t; +} wl_event_num_t; #define BCMF_EVENT_COUNT WLC_E_LAST - #define WLC_SUP_STATUS_OFFSET (256) #define WLC_DOT11_SC_STATUS_OFFSET (512) + /** * Enumerated list of event status codes * @note : WLC_SUP values overlap other values, so it is necessary @@ -2975,13 +2905,12 @@ typedef enum WLC_DOT11_SC_INVALID_FTIE = 55 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to invalid FTIE */ WLC_E_STATUS_FORCE_32_BIT = 0x7FFFFFFE /** Force enum to be stored in 32 bit variable */ -} wwd_event_status_t; +} wl_event_status_t; #define WLC_E_PRUNE_REASON_OFFSET (256) #define WLC_E_SUP_REASON_OFFSET (512) #define WLC_E_DOT11_RC_REASON_OFFSET (768) - /** * Enumerated list of event reason codes * @note : Several values overlap other values, so it is necessary @@ -3065,11 +2994,6 @@ typedef enum DOT11_RC_MAX = 23 + WLC_E_DOT11_RC_REASON_OFFSET, /* Reason codes > 23 are reserved */ WLC_E_REASON_FORCE_32_BIT = 0x7FFFFFFE /** Force enum to be stored in 32 bit variable */ -} wwd_event_reason_t; - - -#ifdef __cplusplus -} /* extern "C" */ -#endif +} wl_event_reason_t; -#endif +#endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_IOCTL_H */ diff --git a/drivers/wireless/ieee80211/bcmf_netdev.c b/drivers/wireless/ieee80211/bcmf_netdev.c index 7422991f49..fafae13bb2 100644 --- a/drivers/wireless/ieee80211/bcmf_netdev.c +++ b/drivers/wireless/ieee80211/bcmf_netdev.c @@ -257,22 +257,17 @@ static void bcmf_receive(FAR struct bcmf_dev_s *priv) break; } + if (!priv->bc_bifup) + { + /* Interface down, drop frame */ + priv->bus->free_frame(priv, frame); + continue; + } + priv->bc_dev.d_buf = frame->data; priv->bc_dev.d_len = frame->len - (uint32_t)(frame->data - frame->base); - wlinfo("Got frame ! %p %d\n", frame, priv->bc_dev.d_len); - // bcmf_hexdump(priv->bc_dev.d_buf, priv->bc_dev.d_len, - // (unsigned long)priv->bc_dev.d_buf); - - /* Check for errors and update statistics */ - - /* Check if the packet is a valid size for the network buffer - * configuration. - */ - - /* Copy the data data from the hardware to priv->bc_dev.d_buf. Set - * amount of data in priv->bc_dev.d_len - */ + wlinfo("Got frame %p %d\n", frame, priv->bc_dev.d_len); #ifdef CONFIG_NET_PKT /* When packet sockets are enabled, feed the frame into the packet tap */ @@ -285,7 +280,7 @@ static void bcmf_receive(FAR struct bcmf_dev_s *priv) #ifdef CONFIG_NET_IPv4 if (BUF->type == HTONS(ETHTYPE_IP)) { - // ninfo("IPv4 frame\n"); + ninfo("IPv4 frame\n"); NETDEV_RXIPV4(&priv->bc_dev); /* Handle ARP on input then give the IPv4 packet to the network @@ -399,6 +394,7 @@ static void bcmf_receive(FAR struct bcmf_dev_s *priv) { wlinfo("RX dropped\n"); NETDEV_RXDROPPED(&priv->bc_dev); + priv->bus->free_frame(priv, frame); } } while (1); /* While there are more packets to be processed */ @@ -693,12 +689,6 @@ static int bcmf_ifup(FAR struct net_driver_s *dev) /* Enable the hardware interrupt */ priv->bc_bifup = true; -#warning Missing logic - - if (bcmf_wl_enable(priv, true) != OK) - { - return -EIO; - } return OK; } @@ -725,8 +715,6 @@ static int bcmf_ifdown(FAR struct net_driver_s *dev) FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)dev->d_private; irqstate_t flags; - // bcmf_wl_enable(priv, false); - /* Disable the hardware interrupt */ flags = enter_critical_section(); @@ -1003,11 +991,11 @@ static int bcmf_ioctl(FAR struct net_driver_s *dev, int cmd, switch (cmd) { case SIOCSIWSCAN: - ret = bcmf_wl_start_scan(priv); + ret = bcmf_wl_start_scan(priv, (struct ifreq*)arg); break; case SIOCGIWSCAN: - ret = bcmf_wl_is_scan_done(priv); + ret = bcmf_wl_get_scan_results(priv, (struct ifreq*)arg); break; case SIOCSIFHWADDR: /* Set device MAC address */ @@ -1144,7 +1132,9 @@ int bcmf_netdev_register(FAR struct bcmf_dev_s *priv) * the device and/or calling bcmf_ifdown(). */ - if (bcmf_wl_enable(priv, false) != OK) + /* Enable chip */ + + if (bcmf_wl_enable(priv, true) != OK) { return -EIO; } diff --git a/drivers/wireless/ieee80211/bcmf_sdio.c b/drivers/wireless/ieee80211/bcmf_sdio.c index e54e5cda80..4d6324090a 100644 --- a/drivers/wireless/ieee80211/bcmf_sdio.c +++ b/drivers/wireless/ieee80211/bcmf_sdio.c @@ -66,9 +66,6 @@ #include "bcmf_sdio_core.h" #include "bcmf_sdio_regs.h" -// TODO remove -#include "bcmf_ioctl.h" - /* Supported chip configurations */ #ifdef CONFIG_IEEE80211_BROADCOM_BCM43362 extern const struct bcmf_sdio_chip bcmf_43362_config_sdio; diff --git a/drivers/wireless/ieee80211/bcmf_sdio_core.h b/drivers/wireless/ieee80211/bcmf_sdio_core.h index 46d96fe058..eb4f4a9803 100644 --- a/drivers/wireless/ieee80211/bcmf_sdio_core.h +++ b/drivers/wireless/ieee80211/bcmf_sdio_core.h @@ -14,49 +14,49 @@ * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. */ -#ifndef BCMF_SDIO_CHIP_H_ -#define BCMF_SDIO_CHIP_H_ +#ifndef __DRIVERS_WIRELESS_IEEE80211_BCMF_SDIO_CORE_H +#define __DRIVERS_WIRELESS_IEEE80211_BCMF_SDIO_CORE_H #include -#ifndef PAD -#define _PADLINE(line) pad ## line -#define _XSTR(line) _PADLINE(line) -#define PAD _XSTR(__LINE__) +#ifndef PAD +#define _PADLINE(line) pad ## line +#define _XSTR(line) _PADLINE(line) +#define PAD _XSTR(__LINE__) #endif /* SDIO device ID */ -#define SDIO_DEVICE_ID_BROADCOM_43143 43143 -#define SDIO_DEVICE_ID_BROADCOM_43241 0x4324 -#define SDIO_DEVICE_ID_BROADCOM_4329 0x4329 -#define SDIO_DEVICE_ID_BROADCOM_4330 0x4330 -#define SDIO_DEVICE_ID_BROADCOM_4334 0x4334 -#define SDIO_DEVICE_ID_BROADCOM_4335_4339 0x4335 -#define SDIO_DEVICE_ID_BROADCOM_43362 43362 +#define SDIO_DEVICE_ID_BROADCOM_43143 43143 +#define SDIO_DEVICE_ID_BROADCOM_43241 0x4324 +#define SDIO_DEVICE_ID_BROADCOM_4329 0x4329 +#define SDIO_DEVICE_ID_BROADCOM_4330 0x4330 +#define SDIO_DEVICE_ID_BROADCOM_4334 0x4334 +#define SDIO_DEVICE_ID_BROADCOM_4335_4339 0x4335 +#define SDIO_DEVICE_ID_BROADCOM_43362 43362 /* * Core reg address translation. * Both macro's returns a 32 bits byte address on the backplane bus. */ #define CORE_CC_REG(base, field) \ - (base + offsetof(struct chipcregs, field)) + (base + offsetof(struct chipcregs, field)) #define CORE_BUS_REG(base, field) \ - (base + offsetof(struct sdpcmd_regs, field)) + (base + offsetof(struct sdpcmd_regs, field)) #define CORE_SB(base, field) \ - (base + offsetof(struct sbconfig, field)) + (base + offsetof(struct sbconfig, field)) -#define BRCMF_MAX_CORENUM 6 -#define SI_ENUM_BASE 0x18000000 /* Enumeration space base */ +#define BRCMF_MAX_CORENUM 6 +#define SI_ENUM_BASE 0x18000000 /* Enumeration space base */ /* Target state register description */ -#define SSB_TMSLOW_RESET 0x00000001 /* Reset */ -#define SSB_TMSLOW_REJECT 0x00000002 /* Reject (Standard Backplane) */ -#define SSB_TMSLOW_REJECT_23 0x00000004 /* Reject (Backplane rev 2.3) */ -#define SSB_TMSLOW_CLOCK 0x00010000 /* Clock Enable */ -#define SSB_TMSLOW_FGC 0x00020000 /* Force Gated Clocks On */ -#define SSB_TMSLOW_PE 0x40000000 /* Power Management Enable */ -#define SSB_TMSLOW_BE 0x80000000 /* BIST Enable */ +#define SSB_TMSLOW_RESET 0x00000001 /* Reset */ +#define SSB_TMSLOW_REJECT 0x00000002 /* Reject (Standard Backplane) */ +#define SSB_TMSLOW_REJECT_23 0x00000004 /* Reject (Backplane rev 2.3) */ +#define SSB_TMSLOW_CLOCK 0x00010000 /* Clock Enable */ +#define SSB_TMSLOW_FGC 0x00020000 /* Force Gated Clocks On */ +#define SSB_TMSLOW_PE 0x40000000 /* Power Management Enable */ +#define SSB_TMSLOW_BE 0x80000000 /* BIST Enable */ #define I_HMB_SW_MASK ( (uint32_t) 0x000000F0 ) #define I_HMB_FRAME_IND ( 1<<6 ) @@ -78,142 +78,142 @@ enum { }; struct chip_core_info { - uint16_t id; - uint16_t rev; - uint32_t base; - uint32_t wrapbase; - uint32_t caps; - uint32_t cib; + uint16_t id; + uint16_t rev; + uint32_t base; + uint32_t wrapbase; + uint32_t caps; + uint32_t cib; }; struct sbconfig { - uint8_t PAD[0xf00]; - uint32_t PAD[2]; - uint32_t sbipsflag; /* initiator port ocp slave flag */ - uint32_t PAD[3]; - uint32_t sbtpsflag; /* target port ocp slave flag */ - uint32_t PAD[11]; - uint32_t sbtmerrloga; /* (sonics >= 2.3) */ - uint32_t PAD; - uint32_t sbtmerrlog; /* (sonics >= 2.3) */ - uint32_t PAD[3]; - uint32_t sbadmatch3; /* address match3 */ - uint32_t PAD; - uint32_t sbadmatch2; /* address match2 */ - uint32_t PAD; - uint32_t sbadmatch1; /* address match1 */ - uint32_t PAD[7]; - uint32_t sbimstate; /* initiator agent state */ - uint32_t sbintvec; /* interrupt mask */ - uint32_t sbtmstatelow; /* target state */ - uint32_t sbtmstatehigh; /* target state */ - uint32_t sbbwa0; /* bandwidth allocation table0 */ - uint32_t PAD; - uint32_t sbimconfiglow; /* initiator configuration */ - uint32_t sbimconfighigh; /* initiator configuration */ - uint32_t sbadmatch0; /* address match0 */ - uint32_t PAD; - uint32_t sbtmconfiglow; /* target configuration */ - uint32_t sbtmconfighigh; /* target configuration */ - uint32_t sbbconfig; /* broadcast configuration */ - uint32_t PAD; - uint32_t sbbstate; /* broadcast state */ - uint32_t PAD[3]; - uint32_t sbactcnfg; /* activate configuration */ - uint32_t PAD[3]; - uint32_t sbflagst; /* current sbflags */ - uint32_t PAD[3]; - uint32_t sbidlow; /* identification */ - uint32_t sbidhigh; /* identification */ + uint8_t PAD[0xf00]; + uint32_t PAD[2]; + uint32_t sbipsflag; /* initiator port ocp slave flag */ + uint32_t PAD[3]; + uint32_t sbtpsflag; /* target port ocp slave flag */ + uint32_t PAD[11]; + uint32_t sbtmerrloga; /* (sonics >= 2.3) */ + uint32_t PAD; + uint32_t sbtmerrlog; /* (sonics >= 2.3) */ + uint32_t PAD[3]; + uint32_t sbadmatch3; /* address match3 */ + uint32_t PAD; + uint32_t sbadmatch2; /* address match2 */ + uint32_t PAD; + uint32_t sbadmatch1; /* address match1 */ + uint32_t PAD[7]; + uint32_t sbimstate; /* initiator agent state */ + uint32_t sbintvec; /* interrupt mask */ + uint32_t sbtmstatelow; /* target state */ + uint32_t sbtmstatehigh; /* target state */ + uint32_t sbbwa0; /* bandwidth allocation table0 */ + uint32_t PAD; + uint32_t sbimconfiglow; /* initiator configuration */ + uint32_t sbimconfighigh; /* initiator configuration */ + uint32_t sbadmatch0; /* address match0 */ + uint32_t PAD; + uint32_t sbtmconfiglow; /* target configuration */ + uint32_t sbtmconfighigh; /* target configuration */ + uint32_t sbbconfig; /* broadcast configuration */ + uint32_t PAD; + uint32_t sbbstate; /* broadcast state */ + uint32_t PAD[3]; + uint32_t sbactcnfg; /* activate configuration */ + uint32_t PAD[3]; + uint32_t sbflagst; /* current sbflags */ + uint32_t PAD[3]; + uint32_t sbidlow; /* identification */ + uint32_t sbidhigh; /* identification */ }; /* sdio core registers */ struct sdpcmd_regs { - uint32_t corecontrol; /* 0x00, rev8 */ - uint32_t corestatus; /* rev8 */ - uint32_t PAD[1]; - uint32_t biststatus; /* rev8 */ - - /* PCMCIA access */ - uint16_t pcmciamesportaladdr; /* 0x010, rev8 */ - uint16_t PAD[1]; - uint16_t pcmciamesportalmask; /* rev8 */ - uint16_t PAD[1]; - uint16_t pcmciawrframebc; /* rev8 */ - uint16_t PAD[1]; - uint16_t pcmciaunderflowtimer; /* rev8 */ - uint16_t PAD[1]; - - /* interrupt */ - uint32_t intstatus; /* 0x020, rev8 */ - uint32_t hostintmask; /* rev8 */ - uint32_t intmask; /* rev8 */ - uint32_t sbintstatus; /* rev8 */ - uint32_t sbintmask; /* rev8 */ - uint32_t funcintmask; /* rev4 */ - uint32_t PAD[2]; - uint32_t tosbmailbox; /* 0x040, rev8 */ - uint32_t tohostmailbox; /* rev8 */ - uint32_t tosbmailboxdata; /* rev8 */ - uint32_t tohostmailboxdata; /* rev8 */ - - /* synchronized access to registers in SDIO clock domain */ - uint32_t sdioaccess; /* 0x050, rev8 */ - uint32_t PAD[3]; - - /* PCMCIA frame control */ - uint8_t pcmciaframectrl; /* 0x060, rev8 */ - uint8_t PAD[3]; - uint8_t pcmciawatermark; /* rev8 */ - uint8_t PAD[155]; - - /* interrupt batching control */ - uint32_t intrcvlazy; /* 0x100, rev8 */ - uint32_t PAD[3]; - - /* counters */ - uint32_t cmd52rd; /* 0x110, rev8 */ - uint32_t cmd52wr; /* rev8 */ - uint32_t cmd53rd; /* rev8 */ - uint32_t cmd53wr; /* rev8 */ - uint32_t abort; /* rev8 */ - uint32_t datacrcerror; /* rev8 */ - uint32_t rdoutofsync; /* rev8 */ - uint32_t wroutofsync; /* rev8 */ - uint32_t writebusy; /* rev8 */ - uint32_t readwait; /* rev8 */ - uint32_t readterm; /* rev8 */ - uint32_t writeterm; /* rev8 */ - uint32_t PAD[40]; - uint32_t clockctlstatus; /* rev8 */ - uint32_t PAD[7]; - - uint32_t PAD[128]; /* DMA engines */ - - /* SDIO/PCMCIA CIS region */ - char cis[512]; /* 0x400-0x5ff, rev6 */ - - /* PCMCIA function control registers */ - char pcmciafcr[256]; /* 0x600-6ff, rev6 */ - uint16_t PAD[55]; - - /* PCMCIA backplane access */ - uint16_t backplanecsr; /* 0x76E, rev6 */ - uint16_t backplaneaddr0; /* rev6 */ - uint16_t backplaneaddr1; /* rev6 */ - uint16_t backplaneaddr2; /* rev6 */ - uint16_t backplaneaddr3; /* rev6 */ - uint16_t backplanedata0; /* rev6 */ - uint16_t backplanedata1; /* rev6 */ - uint16_t backplanedata2; /* rev6 */ - uint16_t backplanedata3; /* rev6 */ - uint16_t PAD[31]; - - /* sprom "size" & "blank" info */ - uint16_t spromstatus; /* 0x7BE, rev2 */ - uint32_t PAD[464]; - - uint16_t PAD[0x80]; + uint32_t corecontrol; /* 0x00, rev8 */ + uint32_t corestatus; /* rev8 */ + uint32_t PAD[1]; + uint32_t biststatus; /* rev8 */ + + /* PCMCIA access */ + uint16_t pcmciamesportaladdr; /* 0x010, rev8 */ + uint16_t PAD[1]; + uint16_t pcmciamesportalmask; /* rev8 */ + uint16_t PAD[1]; + uint16_t pcmciawrframebc; /* rev8 */ + uint16_t PAD[1]; + uint16_t pcmciaunderflowtimer; /* rev8 */ + uint16_t PAD[1]; + + /* interrupt */ + uint32_t intstatus; /* 0x020, rev8 */ + uint32_t hostintmask; /* rev8 */ + uint32_t intmask; /* rev8 */ + uint32_t sbintstatus; /* rev8 */ + uint32_t sbintmask; /* rev8 */ + uint32_t funcintmask; /* rev4 */ + uint32_t PAD[2]; + uint32_t tosbmailbox; /* 0x040, rev8 */ + uint32_t tohostmailbox; /* rev8 */ + uint32_t tosbmailboxdata; /* rev8 */ + uint32_t tohostmailboxdata; /* rev8 */ + + /* synchronized access to registers in SDIO clock domain */ + uint32_t sdioaccess; /* 0x050, rev8 */ + uint32_t PAD[3]; + + /* PCMCIA frame control */ + uint8_t pcmciaframectrl; /* 0x060, rev8 */ + uint8_t PAD[3]; + uint8_t pcmciawatermark; /* rev8 */ + uint8_t PAD[155]; + + /* interrupt batching control */ + uint32_t intrcvlazy; /* 0x100, rev8 */ + uint32_t PAD[3]; + + /* counters */ + uint32_t cmd52rd; /* 0x110, rev8 */ + uint32_t cmd52wr; /* rev8 */ + uint32_t cmd53rd; /* rev8 */ + uint32_t cmd53wr; /* rev8 */ + uint32_t abort; /* rev8 */ + uint32_t datacrcerror; /* rev8 */ + uint32_t rdoutofsync; /* rev8 */ + uint32_t wroutofsync; /* rev8 */ + uint32_t writebusy; /* rev8 */ + uint32_t readwait; /* rev8 */ + uint32_t readterm; /* rev8 */ + uint32_t writeterm; /* rev8 */ + uint32_t PAD[40]; + uint32_t clockctlstatus; /* rev8 */ + uint32_t PAD[7]; + + uint32_t PAD[128]; /* DMA engines */ + + /* SDIO/PCMCIA CIS region */ + char cis[512]; /* 0x400-0x5ff, rev6 */ + + /* PCMCIA function control registers */ + char pcmciafcr[256]; /* 0x600-6ff, rev6 */ + uint16_t PAD[55]; + + /* PCMCIA backplane access */ + uint16_t backplanecsr; /* 0x76E, rev6 */ + uint16_t backplaneaddr0; /* rev6 */ + uint16_t backplaneaddr1; /* rev6 */ + uint16_t backplaneaddr2; /* rev6 */ + uint16_t backplaneaddr3; /* rev6 */ + uint16_t backplanedata0; /* rev6 */ + uint16_t backplanedata1; /* rev6 */ + uint16_t backplanedata2; /* rev6 */ + uint16_t backplanedata3; /* rev6 */ + uint16_t PAD[31]; + + /* sprom "size" & "blank" info */ + uint16_t spromstatus; /* 0x7BE, rev2 */ + uint32_t PAD[464]; + + uint16_t PAD[0x80]; }; -#endif /* _BCMF_SDIO_CHIP_H_ */ +#endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_SDIO_CORE_H */ diff --git a/drivers/wireless/ieee80211/bcmf_sdio_regs.h b/drivers/wireless/ieee80211/bcmf_sdio_regs.h index 5f0c5cc91f..c92898af53 100644 --- a/drivers/wireless/ieee80211/bcmf_sdio_regs.h +++ b/drivers/wireless/ieee80211/bcmf_sdio_regs.h @@ -14,163 +14,158 @@ * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. */ -#ifndef _BRCM_SDH_H_ -#define _BRCM_SDH_H_ +#ifndef __DRIVERS_WIRELESS_IEEE80211_BCMF_SDIO_REGS_H +#define __DRIVERS_WIRELESS_IEEE80211_BCMF_SDIO_REGS_H -#define SDIO_FUNC_0 0 -#define SDIO_FUNC_1 1 -#define SDIO_FUNC_2 2 +#define SDIO_FUNC_0 0 +#define SDIO_FUNC_1 1 +#define SDIO_FUNC_2 2 -#define SDIOD_FBR_SIZE 0x100 +#define SDIOD_FBR_SIZE 0x100 /* io_en */ -#define SDIO_FUNC_ENABLE_1 0x02 -#define SDIO_FUNC_ENABLE_2 0x04 +#define SDIO_FUNC_ENABLE_1 0x02 +#define SDIO_FUNC_ENABLE_2 0x04 /* io_rdys */ -#define SDIO_FUNC_READY_1 0x02 -#define SDIO_FUNC_READY_2 0x04 +#define SDIO_FUNC_READY_1 0x02 +#define SDIO_FUNC_READY_2 0x04 /* intr_status */ -#define INTR_STATUS_FUNC1 0x2 -#define INTR_STATUS_FUNC2 0x4 +#define INTR_STATUS_FUNC1 0x2 +#define INTR_STATUS_FUNC2 0x4 /* Maximum number of I/O funcs */ -#define SDIOD_MAX_IOFUNCS 7 +#define SDIOD_MAX_IOFUNCS 7 /* mask of register map */ -#define REG_F0_REG_MASK 0x7FF -#define REG_F1_MISC_MASK 0x1FFFF +#define REG_F0_REG_MASK 0x7FF +#define REG_F1_MISC_MASK 0x1FFFF /* as of sdiod rev 0, supports 3 functions */ -#define SBSDIO_NUM_FUNCTION 3 +#define SBSDIO_NUM_FUNCTION 3 /* function 0 vendor specific CCCR registers */ -#define SDIO_CCCR_BRCM_CARDCAP 0xf0 -#define SDIO_CCCR_BRCM_CARDCAP_CMD14_SUPPORT 0x02 -#define SDIO_CCCR_BRCM_CARDCAP_CMD14_EXT 0x04 -#define SDIO_CCCR_BRCM_CARDCAP_CMD_NODEC 0x08 -#define SDIO_CCCR_BRCM_CARDCTRL 0xf1 -#define SDIO_CCCR_BRCM_CARDCTRL_WLANRESET 0x02 -#define SDIO_CCCR_BRCM_SEPINT 0xf2 - -#define SDIO_SEPINT_MASK 0x01 -#define SDIO_SEPINT_OE 0x02 -#define SDIO_SEPINT_ACT_HI 0x04 +#define SDIO_CCCR_BRCM_CARDCAP 0xf0 +#define SDIO_CCCR_BRCM_CARDCAP_CMD14_SUPPORT 0x02 +#define SDIO_CCCR_BRCM_CARDCAP_CMD14_EXT 0x04 +#define SDIO_CCCR_BRCM_CARDCAP_CMD_NODEC 0x08 +#define SDIO_CCCR_BRCM_CARDCTRL 0xf1 +#define SDIO_CCCR_BRCM_CARDCTRL_WLANRESET 0x02 +#define SDIO_CCCR_BRCM_SEPINT 0xf2 + +#define SDIO_SEPINT_MASK 0x01 +#define SDIO_SEPINT_OE 0x02 +#define SDIO_SEPINT_ACT_HI 0x04 /* function 1 miscellaneous registers */ /* sprom command and status */ -#define SBSDIO_SPROM_CS 0x10000 +#define SBSDIO_SPROM_CS 0x10000 /* sprom info register */ -#define SBSDIO_SPROM_INFO 0x10001 +#define SBSDIO_SPROM_INFO 0x10001 /* sprom indirect access data byte 0 */ -#define SBSDIO_SPROM_DATA_LOW 0x10002 +#define SBSDIO_SPROM_DATA_LOW 0x10002 /* sprom indirect access data byte 1 */ -#define SBSDIO_SPROM_DATA_HIGH 0x10003 +#define SBSDIO_SPROM_DATA_HIGH 0x10003 /* sprom indirect access addr byte 0 */ -#define SBSDIO_SPROM_ADDR_LOW 0x10004 +#define SBSDIO_SPROM_ADDR_LOW 0x10004 /* sprom indirect access addr byte 0 */ -#define SBSDIO_SPROM_ADDR_HIGH 0x10005 +#define SBSDIO_SPROM_ADDR_HIGH 0x10005 /* xtal_pu (gpio) output */ -#define SBSDIO_CHIP_CTRL_DATA 0x10006 +#define SBSDIO_CHIP_CTRL_DATA 0x10006 /* xtal_pu (gpio) enable */ -#define SBSDIO_CHIP_CTRL_EN 0x10007 +#define SBSDIO_CHIP_CTRL_EN 0x10007 /* rev < 7, watermark for sdio device */ -#define SBSDIO_WATERMARK 0x10008 +#define SBSDIO_WATERMARK 0x10008 /* control busy signal generation */ -#define SBSDIO_DEVICE_CTL 0x10009 +#define SBSDIO_DEVICE_CTL 0x10009 /* SB Address Window Low (b15) */ -#define SBSDIO_FUNC1_SBADDRLOW 0x1000A +#define SBSDIO_FUNC1_SBADDRLOW 0x1000A /* SB Address Window Mid (b23:b16) */ -#define SBSDIO_FUNC1_SBADDRMID 0x1000B +#define SBSDIO_FUNC1_SBADDRMID 0x1000B /* SB Address Window High (b31:b24) */ -#define SBSDIO_FUNC1_SBADDRHIGH 0x1000C +#define SBSDIO_FUNC1_SBADDRHIGH 0x1000C /* Frame Control (frame term/abort) */ -#define SBSDIO_FUNC1_FRAMECTRL 0x1000D +#define SBSDIO_FUNC1_FRAMECTRL 0x1000D /* Read Frame Terminate */ -#define SFC_RF_TERM (1 << 0) +#define SFC_RF_TERM (1 << 0) /* Write Frame Terminate */ -#define SFC_WF_TERM (1 << 1) +#define SFC_WF_TERM (1 << 1) /* CRC error for write out of sync */ -#define SFC_CRC4WOOS (1 << 2) +#define SFC_CRC4WOOS (1 << 2) /* Abort all in-progress frames */ -#define SFC_ABORTALL (1 << 3) +#define SFC_ABORTALL (1 << 3) /* ChipClockCSR (ALP/HT ctl/status) */ -#define SBSDIO_FUNC1_CHIPCLKCSR 0x1000E +#define SBSDIO_FUNC1_CHIPCLKCSR 0x1000E /* Force ALP request to backplane */ -#define SBSDIO_FORCE_ALP 0x01 +#define SBSDIO_FORCE_ALP 0x01 /* Force HT request to backplane */ -#define SBSDIO_FORCE_HT 0x02 +#define SBSDIO_FORCE_HT 0x02 /* Force ILP request to backplane */ -#define SBSDIO_FORCE_ILP 0x04 +#define SBSDIO_FORCE_ILP 0x04 /* Make ALP ready (power up xtal) */ -#define SBSDIO_ALP_AVAIL_REQ 0x08 +#define SBSDIO_ALP_AVAIL_REQ 0x08 /* Make HT ready (power up PLL) */ -#define SBSDIO_HT_AVAIL_REQ 0x10 +#define SBSDIO_HT_AVAIL_REQ 0x10 /* Squelch clock requests from HW */ -#define SBSDIO_FORCE_HW_CLKREQ_OFF 0x20 +#define SBSDIO_FORCE_HW_CLKREQ_OFF 0x20 /* Status: ALP is ready */ -#define SBSDIO_ALP_AVAIL 0x40 +#define SBSDIO_ALP_AVAIL 0x40 /* Status: HT is ready */ -#define SBSDIO_HT_AVAIL 0x80 +#define SBSDIO_HT_AVAIL 0x80 /* SdioPullUp (on cmd, d0-d2) */ -#define SBSDIO_FUNC1_SDIOPULLUP 0x1000F +#define SBSDIO_FUNC1_SDIOPULLUP 0x1000F /* Write Frame Byte Count Low */ -#define SBSDIO_FUNC1_WFRAMEBCLO 0x10019 +#define SBSDIO_FUNC1_WFRAMEBCLO 0x10019 /* Write Frame Byte Count High */ -#define SBSDIO_FUNC1_WFRAMEBCHI 0x1001A +#define SBSDIO_FUNC1_WFRAMEBCHI 0x1001A /* Read Frame Byte Count Low */ -#define SBSDIO_FUNC1_RFRAMEBCLO 0x1001B +#define SBSDIO_FUNC1_RFRAMEBCLO 0x1001B /* Read Frame Byte Count High */ -#define SBSDIO_FUNC1_RFRAMEBCHI 0x1001C +#define SBSDIO_FUNC1_RFRAMEBCHI 0x1001C /* MesBusyCtl (rev 11) */ -#define SBSDIO_FUNC1_MESBUSYCTRL 0x1001D +#define SBSDIO_FUNC1_MESBUSYCTRL 0x1001D /* Sdio Core Rev 12 */ -#define SBSDIO_FUNC1_WAKEUPCTRL 0x1001E -#define SBSDIO_FUNC1_WCTRL_ALPWAIT_MASK 0x1 -#define SBSDIO_FUNC1_WCTRL_ALPWAIT_SHIFT 0 -#define SBSDIO_FUNC1_WCTRL_HTWAIT_MASK 0x2 -#define SBSDIO_FUNC1_WCTRL_HTWAIT_SHIFT 1 -#define SBSDIO_FUNC1_SLEEPCSR 0x1001F -#define SBSDIO_FUNC1_SLEEPCSR_KSO_MASK 0x1 -#define SBSDIO_FUNC1_SLEEPCSR_KSO_SHIFT 0 -#define SBSDIO_FUNC1_SLEEPCSR_KSO_EN 1 -#define SBSDIO_FUNC1_SLEEPCSR_DEVON_MASK 0x2 -#define SBSDIO_FUNC1_SLEEPCSR_DEVON_SHIFT 1 - -#define SBSDIO_AVBITS (SBSDIO_HT_AVAIL | SBSDIO_ALP_AVAIL) -#define SBSDIO_ALPAV(regval) ((regval) & SBSDIO_AVBITS) -#define SBSDIO_HTAV(regval) (((regval) & SBSDIO_AVBITS) == SBSDIO_AVBITS) -#define SBSDIO_ALPONLY(regval) (SBSDIO_ALPAV(regval) && !SBSDIO_HTAV(regval)) +#define SBSDIO_FUNC1_WAKEUPCTRL 0x1001E +#define SBSDIO_FUNC1_WCTRL_ALPWAIT_MASK 0x1 +#define SBSDIO_FUNC1_WCTRL_ALPWAIT_SHIFT 0 +#define SBSDIO_FUNC1_WCTRL_HTWAIT_MASK 0x2 +#define SBSDIO_FUNC1_WCTRL_HTWAIT_SHIFT 1 + +#define SBSDIO_FUNC1_SLEEPCSR 0x1001F +#define SBSDIO_FUNC1_SLEEPCSR_KSO_MASK 0x1 +#define SBSDIO_FUNC1_SLEEPCSR_KSO_SHIFT 0 +#define SBSDIO_FUNC1_SLEEPCSR_KSO_EN 1 +#define SBSDIO_FUNC1_SLEEPCSR_DEVON_MASK 0x2 +#define SBSDIO_FUNC1_SLEEPCSR_DEVON_SHIFT 1 + +#define SBSDIO_AVBITS (SBSDIO_HT_AVAIL | SBSDIO_ALP_AVAIL) +#define SBSDIO_ALPAV(regval) ((regval) & SBSDIO_AVBITS) +#define SBSDIO_HTAV(regval) (((regval) & SBSDIO_AVBITS) == SBSDIO_AVBITS) +#define SBSDIO_ALPONLY(regval) (SBSDIO_ALPAV(regval) && !SBSDIO_HTAV(regval)) #define SBSDIO_CLKAV(regval, alponly) \ - (SBSDIO_ALPAV(regval) && (alponly ? 1 : SBSDIO_HTAV(regval))) + (SBSDIO_ALPAV(regval) && (alponly ? 1 : SBSDIO_HTAV(regval))) -#define SBSDIO_FUNC1_MISC_REG_START 0x10000 /* f1 misc register start */ -#define SBSDIO_FUNC1_MISC_REG_LIMIT 0x1001F /* f1 misc register end */ +#define SBSDIO_FUNC1_MISC_REG_START 0x10000 /* f1 misc register start */ +#define SBSDIO_FUNC1_MISC_REG_LIMIT 0x1001F /* f1 misc register end */ /* function 1 OCP space */ /* sb offset addr is <= 15 bits, 32k */ -#define SBSDIO_SB_OFT_ADDR_MASK 0x07FFF -#define SBSDIO_SB_OFT_ADDR_LIMIT 0x08000 +#define SBSDIO_SB_OFT_ADDR_MASK 0x07FFF +#define SBSDIO_SB_OFT_ADDR_LIMIT 0x08000 /* with b15, maps to 32-bit SB access */ -#define SBSDIO_SB_ACCESS_2_4B_FLAG 0x08000 +#define SBSDIO_SB_ACCESS_2_4B_FLAG 0x08000 /* valid bits in SBSDIO_FUNC1_SBADDRxxx regs */ -#define SBSDIO_SBADDRLOW_MASK 0x80 /* Valid bits in SBADDRLOW */ -#define SBSDIO_SBADDRMID_MASK 0xff /* Valid bits in SBADDRMID */ -#define SBSDIO_SBADDRHIGH_MASK 0xffU /* Valid bits in SBADDRHIGH */ +#define SBSDIO_SBADDRLOW_MASK 0x80 /* Valid bits in SBADDRLOW */ +#define SBSDIO_SBADDRMID_MASK 0xff /* Valid bits in SBADDRMID */ +#define SBSDIO_SBADDRHIGH_MASK 0xffU /* Valid bits in SBADDRHIGH */ /* Address bits from SBADDR regs */ -#define SBSDIO_SBWINDOW_MASK 0xffff8000 +#define SBSDIO_SBWINDOW_MASK 0xffff8000 -/* Packet alignment for most efficient SDIO (can change based on platform) */ -#define BRCMF_SDALIGN (1 << 6) - -/* watchdog polling interval in ms */ -#define BRCMF_WD_POLL_MS 10 - -#endif /* _BRCM_SDH_H_ */ +#endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_SDIO_REGS_H */ diff --git a/drivers/wireless/ieee80211/bcmf_utils.c b/drivers/wireless/ieee80211/bcmf_utils.c index b45f649f1e..c82908f6ab 100644 --- a/drivers/wireless/ieee80211/bcmf_utils.c +++ b/drivers/wireless/ieee80211/bcmf_utils.c @@ -163,23 +163,5 @@ dq_entry_t* bcmf_dqueue_pop_tail(dq_queue_t *queue) entry->blink->flink = queue->head; } - return entry; -} - -void bcmf_squeue_push(sq_queue_t *queue, sq_entry_t *entry) -{ - entry->flink = queue->head; - queue->head = entry; -} - -sq_entry_t* bcmf_squeue_pop(sq_queue_t *queue) -{ - sq_entry_t *entry = queue->head; - - if (queue->head != NULL) - { - queue->head = entry->flink; - } - return entry; } \ No newline at end of file diff --git a/drivers/wireless/ieee80211/bcmf_utils.h b/drivers/wireless/ieee80211/bcmf_utils.h index 1800cfc28b..e79c44bdcf 100644 --- a/drivers/wireless/ieee80211/bcmf_utils.h +++ b/drivers/wireless/ieee80211/bcmf_utils.h @@ -55,9 +55,6 @@ void bcmf_hexdump(uint8_t *data, unsigned int len, unsigned long offset); int bcmf_sem_wait(sem_t *sem, unsigned int timeout_ms); -sq_entry_t* bcmf_squeue_pop(sq_queue_t *queue); -void bcmf_squeue_push(sq_queue_t *queue, sq_entry_t *entry); - dq_entry_t* bcmf_dqueue_pop_tail(dq_queue_t *queue); void bcmf_dqueue_push(dq_queue_t *queue, dq_entry_t *entry); diff --git a/include/nuttx/wireless/wireless.h b/include/nuttx/wireless/wireless.h index 0b5367dbff..5455e14d4f 100644 --- a/include/nuttx/wireless/wireless.h +++ b/include/nuttx/wireless/wireless.h @@ -195,7 +195,33 @@ /* Scan-related */ -#define IW_SCAN_MAX_DATA 4096 /* Maximum size of returned data */ +/* Scanning request flags */ +#define IW_SCAN_DEFAULT 0x0000 /* Default scan of the driver */ +#define IW_SCAN_ALL_ESSID 0x0001 /* Scan all ESSIDs */ +#define IW_SCAN_THIS_ESSID 0x0002 /* Scan only this ESSID */ +#define IW_SCAN_ALL_FREQ 0x0004 /* Scan all Frequencies */ +#define IW_SCAN_THIS_FREQ 0x0008 /* Scan only this Frequency */ +#define IW_SCAN_ALL_MODE 0x0010 /* Scan all Modes */ +#define IW_SCAN_THIS_MODE 0x0020 /* Scan only this Mode */ +#define IW_SCAN_ALL_RATE 0x0040 /* Scan all Bit-Rates */ +#define IW_SCAN_THIS_RATE 0x0080 /* Scan only this Bit-Rate */ +/* struct iw_scan_req scan_type */ +#define IW_SCAN_TYPE_ACTIVE 0 +#define IW_SCAN_TYPE_PASSIVE 1 +/* Maximum size of returned data */ +#define IW_SCAN_MAX_DATA 4096 /* In bytes */ + +/* Scan capability flags - in (struct iw_range *)->scan_capa */ +#define IW_SCAN_CAPA_NONE 0x00 +#define IW_SCAN_CAPA_ESSID 0x01 +#define IW_SCAN_CAPA_BSSID 0x02 +#define IW_SCAN_CAPA_CHANNEL 0x04 +#define IW_SCAN_CAPA_MODE 0x08 +#define IW_SCAN_CAPA_RATE 0x10 +#define IW_SCAN_CAPA_TYPE 0x20 +#define IW_SCAN_CAPA_TIME 0x40 + +#define IW_SCAN_MAX_DATA 4096 /* Maximum size of returned data */ /* SIOCSIWAUTH/SIOCGIWAUTH struct iw_param flags */ @@ -398,5 +424,52 @@ struct iw_encode_ext uint8_t key[0]; }; +/* + * Optional data for scan request + * + * Note: these optional parameters are controlling parameters for the + * scanning behavior, these do not apply to getting scan results + * (SIOCGIWSCAN). Drivers are expected to keep a local BSS table and + * provide a merged results with all BSSes even if the previous scan + * request limited scanning to a subset, e.g., by specifying an SSID. + * Especially, scan results are required to include an entry for the + * current BSS if the driver is in Managed mode and associated with an AP. + */ +struct iw_scan_req +{ + uint8_t scan_type; /* IW_SCAN_TYPE_{ACTIVE,PASSIVE} */ + uint8_t essid_len; + uint8_t num_channels; /* num entries in channel_list; + * 0 = scan all allowed channels */ + uint8_t flags; /* reserved as padding; use zero, this may + * be used in the future for adding flags + * to request different scan behavior */ + struct sockaddr bssid; /* ff:ff:ff:ff:ff:ff for broadcast BSSID or + * individual address of a specific BSS */ + + /* + * Use this ESSID if IW_SCAN_THIS_ESSID flag is used instead of using + * the current ESSID. This allows scan requests for specific ESSID + * without having to change the current ESSID and potentially breaking + * the current association. + */ + uint8_t essid[IW_ESSID_MAX_SIZE]; + + /* + * Optional parameters for changing the default scanning behavior. + * These are based on the MLME-SCAN.request from IEEE Std 802.11. + * TU is 1.024 ms. If these are set to 0, driver is expected to use + * reasonable default values. min_channel_time defines the time that + * will be used to wait for the first reply on each channel. If no + * replies are received, next channel will be scanned after this. If + * replies are received, total time waited on the channel is defined by + * max_channel_time. + */ + uint32_t min_channel_time; /* in TU */ + uint32_t max_channel_time; /* in TU */ + + struct iw_freq channel_list[IW_MAX_FREQUENCIES]; +}; + #endif /* CONFIG_DRIVERS_WIRELESS */ #endif /* __INCLUDE_NUTTX_WIRELESS_WIRELESS_H */ -- GitLab From 9b5ac5640917a8a38d4ae2f6e8611e91e81edc06 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Wed, 3 May 2017 23:10:48 +0000 Subject: [PATCH 694/990] Fixed typo and backward ifdef --- arch/arm/src/stm32/stm32_i2c.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/arch/arm/src/stm32/stm32_i2c.c b/arch/arm/src/stm32/stm32_i2c.c index f754a6ad18..5f3e1c2c5c 100644 --- a/arch/arm/src/stm32/stm32_i2c.c +++ b/arch/arm/src/stm32/stm32_i2c.c @@ -1454,8 +1454,8 @@ static int stm32_i2c_isr_process(struct stm32_i2c_priv_s *priv) * ************************************************************************************/ -#ifdef CONFIG_I2C_POLLED -static int stm32_i2c2_isr(int irq, void *context, FAR void *arg) +#ifndef CONFIG_I2C_POLLED +static int stm32_i2c_isr(int irq, void *context, FAR void *arg) { struct stm32_i2c_priv_s *priv = (struct stm32_i2c_priv_s *)arg; -- GitLab From 1e054a2d3b1e3fb7be4348d88e35db3773e836b9 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 3 May 2017 17:33:35 -0600 Subject: [PATCH 695/990] STM32 I2C: More backward tests of CONFIG_I2C_POLLED. Needs to be reviewed. --- arch/arm/src/stm32/stm32_i2c.c | 4 ++-- arch/arm/src/stm32/stm32f30xxx_i2c.c | 4 ++-- arch/arm/src/stm32f0/stm32f0_i2c.c | 4 ++-- arch/arm/src/stm32f7/stm32_i2c.c | 4 ++-- arch/arm/src/stm32l4/stm32l4_i2c.c | 4 ++-- 5 files changed, 10 insertions(+), 10 deletions(-) diff --git a/arch/arm/src/stm32/stm32_i2c.c b/arch/arm/src/stm32/stm32_i2c.c index 5f3e1c2c5c..6a08e14143 100644 --- a/arch/arm/src/stm32/stm32_i2c.c +++ b/arch/arm/src/stm32/stm32_i2c.c @@ -1272,7 +1272,7 @@ static int stm32_i2c_isr_process(struct stm32_i2c_priv_s *priv) * device. */ -#ifdef CONFIG_I2C_POLLED +#ifndef CONFIG_I2C_POLLED irqstate_t flags = enter_critical_section(); #endif /* Receive a byte */ @@ -1287,7 +1287,7 @@ static int stm32_i2c_isr_process(struct stm32_i2c_priv_s *priv) stm32_i2c_modifyreg(priv, STM32_I2C_CR1_OFFSET, I2C_CR1_ACK, 0); } -#ifdef CONFIG_I2C_POLLED +#ifndef CONFIG_I2C_POLLED leave_critical_section(flags); #endif } diff --git a/arch/arm/src/stm32/stm32f30xxx_i2c.c b/arch/arm/src/stm32/stm32f30xxx_i2c.c index 539305194d..9d616b7489 100644 --- a/arch/arm/src/stm32/stm32f30xxx_i2c.c +++ b/arch/arm/src/stm32/stm32f30xxx_i2c.c @@ -1332,7 +1332,7 @@ static int stm32_i2c_isr_process(struct stm32_i2c_priv_s *priv) * device. */ -#ifdef CONFIG_I2C_POLLED +#ifndef CONFIG_I2C_POLLED irqstate_t flags = enter_critical_section(); #endif /* Receive a byte */ @@ -1347,7 +1347,7 @@ static int stm32_i2c_isr_process(struct stm32_i2c_priv_s *priv) /* autoend? */ } -#ifdef CONFIG_I2C_POLLED +#ifndef CONFIG_I2C_POLLED leave_critical_section(flags); #endif } diff --git a/arch/arm/src/stm32f0/stm32f0_i2c.c b/arch/arm/src/stm32f0/stm32f0_i2c.c index c782754fc3..b8f7ede7d6 100644 --- a/arch/arm/src/stm32f0/stm32f0_i2c.c +++ b/arch/arm/src/stm32f0/stm32f0_i2c.c @@ -1306,7 +1306,7 @@ static int stm32f0_i2c_isr_process(struct stm32f0_i2c_priv_s *priv) * device. */ -#ifdef CONFIG_I2C_POLLED +#ifndef CONFIG_I2C_POLLED irqstate_t flags = enter_critical_section(); #endif /* Receive a byte */ @@ -1321,7 +1321,7 @@ static int stm32f0_i2c_isr_process(struct stm32f0_i2c_priv_s *priv) /* autoend? */ } -#ifdef CONFIG_I2C_POLLED +#ifndef CONFIG_I2C_POLLED leave_critical_section(flags); #endif } diff --git a/arch/arm/src/stm32f7/stm32_i2c.c b/arch/arm/src/stm32f7/stm32_i2c.c index be3122ea4e..d85023e6c5 100644 --- a/arch/arm/src/stm32f7/stm32_i2c.c +++ b/arch/arm/src/stm32f7/stm32_i2c.c @@ -1776,7 +1776,7 @@ static int stm32_i2c_isr_process(struct stm32_i2c_priv_s *priv) * sequence. Otherwise, additional bytes may be received. */ -#ifdef CONFIG_I2C_POLLED +#ifndef CONFIG_I2C_POLLED irqstate_t state = enter_critical_section(); #endif /* Receive a byte */ @@ -1793,7 +1793,7 @@ static int stm32_i2c_isr_process(struct stm32_i2c_priv_s *priv) priv->dcnt--; -#ifdef CONFIG_I2C_POLLED +#ifndef CONFIG_I2C_POLLED leave_critical_section(state); #endif } diff --git a/arch/arm/src/stm32l4/stm32l4_i2c.c b/arch/arm/src/stm32l4/stm32l4_i2c.c index 58c2fa780f..956dd8c788 100644 --- a/arch/arm/src/stm32l4/stm32l4_i2c.c +++ b/arch/arm/src/stm32l4/stm32l4_i2c.c @@ -1384,7 +1384,7 @@ static int stm32l4_i2c_isr_process(struct stm32l4_i2c_priv_s *priv) * device. */ -#ifdef CONFIG_I2C_POLLED +#ifndef CONFIG_I2C_POLLED irqstate_t flags = enter_critical_section(); #endif /* Receive a byte */ @@ -1399,7 +1399,7 @@ static int stm32l4_i2c_isr_process(struct stm32l4_i2c_priv_s *priv) /* autoend? */ } -#ifdef CONFIG_I2C_POLLED +#ifndef CONFIG_I2C_POLLED leave_critical_section(flags); #endif } -- GitLab From 97f149a40b8f074a0a94a4002c888ffc857eb86d Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 3 May 2017 18:20:57 -0600 Subject: [PATCH 696/990] Photon: Cosmetic changes to style detected by tools/nxstyle --- drivers/wireless/ieee80211/bcmf_bdc.c | 34 +- drivers/wireless/ieee80211/bcmf_bdc.h | 6 +- drivers/wireless/ieee80211/bcmf_cdc.c | 22 +- drivers/wireless/ieee80211/bcmf_chip_43362.c | 16 +- drivers/wireless/ieee80211/bcmf_core.c | 16 +- drivers/wireless/ieee80211/bcmf_core.h | 4 +- drivers/wireless/ieee80211/bcmf_driver.c | 74 +- drivers/wireless/ieee80211/bcmf_driver.h | 6 +- drivers/wireless/ieee80211/bcmf_ioctl.h | 3089 +++++++++--------- drivers/wireless/ieee80211/bcmf_netdev.c | 17 +- drivers/wireless/ieee80211/bcmf_sdio.c | 48 +- drivers/wireless/ieee80211/bcmf_sdio.h | 15 +- drivers/wireless/ieee80211/bcmf_sdio_core.h | 293 +- drivers/wireless/ieee80211/bcmf_sdio_regs.h | 83 +- drivers/wireless/ieee80211/bcmf_sdpcm.c | 34 +- drivers/wireless/ieee80211/bcmf_sdpcm.h | 9 +- drivers/wireless/ieee80211/bcmf_utils.c | 10 +- drivers/wireless/ieee80211/bcmf_utils.h | 10 +- drivers/wireless/ieee80211/mmc_sdio.c | 80 +- 19 files changed, 1991 insertions(+), 1875 deletions(-) diff --git a/drivers/wireless/ieee80211/bcmf_bdc.c b/drivers/wireless/ieee80211/bcmf_bdc.c index a9dd3b3a81..a2a31a3f3f 100644 --- a/drivers/wireless/ieee80211/bcmf_bdc.c +++ b/drivers/wireless/ieee80211/bcmf_bdc.c @@ -97,8 +97,8 @@ static const uint8_t bcmf_broadcom_oui[] = {0x00, 0x10, 0x18}; * Public Functions ****************************************************************************/ -struct bcmf_frame_s* bcmf_bdc_allocate_frame(FAR struct bcmf_dev_s *priv, - uint32_t len, bool block) +struct bcmf_frame_s *bcmf_bdc_allocate_frame(FAR struct bcmf_dev_s *priv, + uint32_t len, bool block) { struct bcmf_frame_s *frame; @@ -136,7 +136,7 @@ int bcmf_bdc_process_event_frame(FAR struct bcmf_dev_s *priv, goto exit_invalid_frame; } - header = (struct bcmf_bdc_header*)frame->data; + header = (struct bcmf_bdc_header *)frame->data; data_size -= sizeof(struct bcmf_bdc_header) + header->data_offset; @@ -149,9 +149,9 @@ int bcmf_bdc_process_event_frame(FAR struct bcmf_dev_s *priv, /* Check ethernet header */ - event_msg = (struct bcmf_event_msg*)(frame->data + - sizeof(struct bcmf_bdc_header) + - header->data_offset); + event_msg = (struct bcmf_event_msg *)(frame->data + + sizeof(struct bcmf_bdc_header) + + header->data_offset); if (event_msg->eth.ether_type != BCMF_EVENT_ETHER_TYPE || memcmp(event_msg->bcm_eth.oui, bcmf_broadcom_oui, 3)) @@ -207,15 +207,15 @@ int bcmf_event_push_config(FAR struct bcmf_dev_s *priv) { int i; uint32_t out_len; - uint8_t event_mask[(BCMF_EVENT_COUNT+7)>>3]; + uint8_t event_mask[(BCMF_EVENT_COUNT + 7) >> 3]; memset(event_mask, 0, sizeof(event_mask)); - for (i=0; ievent_handlers[i] != NULL) { - event_mask[i>>3] |= 1 << (i & 0x7); + event_mask[i >> 3] |= 1 << (i & 0x7); } } @@ -233,20 +233,20 @@ int bcmf_event_push_config(FAR struct bcmf_dev_s *priv) } int bcmf_bdc_transmit_frame(FAR struct bcmf_dev_s *priv, - struct bcmf_frame_s *frame) + struct bcmf_frame_s *frame) { - struct bcmf_bdc_header* header; + struct bcmf_bdc_header *header; /* Set frame data for lower layer */ frame->data -= sizeof(struct bcmf_bdc_header); - header = (struct bcmf_bdc_header*)frame->data; + header = (struct bcmf_bdc_header *)frame->data; /* Setup data frame header */ - header->flags = 0x20; /* Set bdc protocol version */ - header->priority = 0; // TODO handle priority - header->flags2 = CHIP_STA_INTERFACE; + header->flags = 0x20; /* Set bdc protocol version */ + header->priority = 0; // TODO handle priority + header->flags2 = CHIP_STA_INTERFACE; header->data_offset = 0; /* Send frame */ @@ -254,7 +254,7 @@ int bcmf_bdc_transmit_frame(FAR struct bcmf_dev_s *priv, return priv->bus->txframe(priv, frame, false); } -struct bcmf_frame_s* bcmf_bdc_rx_frame(FAR struct bcmf_dev_s *priv) +struct bcmf_frame_s *bcmf_bdc_rx_frame(FAR struct bcmf_dev_s *priv) { unsigned int frame_len; struct bcmf_frame_s *frame = priv->bus->rxframe(priv); @@ -274,4 +274,4 @@ struct bcmf_frame_s* bcmf_bdc_rx_frame(FAR struct bcmf_dev_s *priv) frame->data += sizeof(struct bcmf_bdc_header); return frame; -} \ No newline at end of file +} diff --git a/drivers/wireless/ieee80211/bcmf_bdc.h b/drivers/wireless/ieee80211/bcmf_bdc.h index 905dc7209f..37d9225b5e 100644 --- a/drivers/wireless/ieee80211/bcmf_bdc.h +++ b/drivers/wireless/ieee80211/bcmf_bdc.h @@ -75,13 +75,13 @@ int bcmf_bdc_process_event_frame(FAR struct bcmf_dev_s *priv, /* Function called from upper layer */ -struct bcmf_frame_s* bcmf_bdc_allocate_frame(FAR struct bcmf_dev_s *priv, - uint32_t len, bool block); +struct bcmf_frame_s *bcmf_bdc_allocate_frame(FAR struct bcmf_dev_s *priv, + uint32_t len, bool block); int bcmf_bdc_transmit_frame(FAR struct bcmf_dev_s *priv, struct bcmf_frame_s *frame); -struct bcmf_frame_s* bcmf_bdc_rx_frame(FAR struct bcmf_dev_s *priv); +struct bcmf_frame_s *bcmf_bdc_rx_frame(FAR struct bcmf_dev_s *priv); /* Event frames API */ diff --git a/drivers/wireless/ieee80211/bcmf_cdc.c b/drivers/wireless/ieee80211/bcmf_cdc.c index c45bbef1b5..06efd9ec5c 100644 --- a/drivers/wireless/ieee80211/bcmf_cdc.c +++ b/drivers/wireless/ieee80211/bcmf_cdc.c @@ -80,7 +80,7 @@ struct __attribute__((packed)) bcmf_cdc_header { * Private Function Prototypes ****************************************************************************/ -static struct bcmf_frame_s* bcmf_cdc_allocate_frame( +static struct bcmf_frame_s *bcmf_cdc_allocate_frame( FAR struct bcmf_dev_s *priv, char *name, uint8_t *data, uint32_t len); @@ -99,8 +99,9 @@ static int bcmf_cdc_control_request_unsafe(FAR struct bcmf_dev_s *priv, * Private Functions ****************************************************************************/ -struct bcmf_frame_s* bcmf_cdc_allocate_frame(FAR struct bcmf_dev_s *priv, - char *name, uint8_t *data, uint32_t len) +struct bcmf_frame_s *bcmf_cdc_allocate_frame(FAR struct bcmf_dev_s *priv, + char *name, uint8_t *data, + uint32_t len) { uint32_t data_len; uint16_t name_len; @@ -145,10 +146,10 @@ struct bcmf_frame_s* bcmf_cdc_allocate_frame(FAR struct bcmf_dev_s *priv, } int bcmf_cdc_sendframe(FAR struct bcmf_dev_s *priv, uint32_t cmd, - int ifidx, bool set, struct bcmf_frame_s *frame) + int ifidx, bool set, struct bcmf_frame_s *frame) { - struct bcmf_cdc_header* header = - (struct bcmf_cdc_header*)frame->data; + struct bcmf_cdc_header *header = + (struct bcmf_cdc_header *)frame->data; /* Setup control frame header */ @@ -290,7 +291,7 @@ int bcmf_cdc_process_control_frame(FAR struct bcmf_dev_s *priv, return -EINVAL; } - cdc_header = (struct bcmf_cdc_header*)frame->data; + cdc_header = (struct bcmf_cdc_header *)frame->data; if (data_size < cdc_header->len || data_size < sizeof(struct bcmf_cdc_header) + cdc_header->len) @@ -315,8 +316,9 @@ int bcmf_cdc_process_control_frame(FAR struct bcmf_dev_s *priv, priv->control_rxdata_len, cdc_header->len); priv->control_rxdata_len = cdc_header->len; } - memcpy(priv->control_rxdata, (uint8_t*)&cdc_header[1], - priv->control_rxdata_len); + + memcpy(priv->control_rxdata, (uint8_t *)&cdc_header[1], + priv->control_rxdata_len); } sem_post(&priv->control_timeout); @@ -325,4 +327,4 @@ int bcmf_cdc_process_control_frame(FAR struct bcmf_dev_s *priv, wlinfo("Got unexpected control frame\n"); return -EINVAL; -} \ No newline at end of file +} diff --git a/drivers/wireless/ieee80211/bcmf_chip_43362.c b/drivers/wireless/ieee80211/bcmf_chip_43362.c index 891cf7784a..7bea6584dc 100644 --- a/drivers/wireless/ieee80211/bcmf_chip_43362.c +++ b/drivers/wireless/ieee80211/bcmf_chip_43362.c @@ -44,7 +44,8 @@ extern const unsigned int bcm43362_nvram_image_len; extern const uint8_t bcm43362_firmware_image[]; extern const unsigned int bcm43362_firmware_image_len; -const struct bcmf_sdio_chip bcmf_43362_config_sdio = { +const struct bcmf_sdio_chip bcmf_43362_config_sdio = +{ /* General chip stats */ @@ -52,7 +53,8 @@ const struct bcmf_sdio_chip bcmf_43362_config_sdio = { /* Backplane architecture */ - .core_base = { + .core_base = + { [CHIPCOMMON_CORE_ID] = 0x18000000, /* Chipcommon core register base */ [DOT11MAC_CORE_ID] = 0x18001000, /* dot11mac core register base */ [SDIOD_CORE_ID] = 0x18002000, /* SDIOD Device core register base */ @@ -66,9 +68,9 @@ const struct bcmf_sdio_chip bcmf_43362_config_sdio = { // TODO find something smarter than using image_len references - .firmware_image = (uint8_t*)bcm43362_firmware_image, - .firmware_image_size = (unsigned int*)&bcm43362_firmware_image_len, + .firmware_image = (uint8_t *)bcm43362_firmware_image, + .firmware_image_size = (unsigned int *)&bcm43362_firmware_image_len, - .nvram_image = (uint8_t*)bcm43362_nvram_image, - .nvram_image_size = (unsigned int*)&bcm43362_nvram_image_len -}; \ No newline at end of file + .nvram_image = (uint8_t *)bcm43362_nvram_image, + .nvram_image_size = (unsigned int *)&bcm43362_nvram_image_len +}; diff --git a/drivers/wireless/ieee80211/bcmf_core.c b/drivers/wireless/ieee80211/bcmf_core.c index e51e88c876..64606b7a71 100644 --- a/drivers/wireless/ieee80211/bcmf_core.c +++ b/drivers/wireless/ieee80211/bcmf_core.c @@ -190,23 +190,23 @@ int bcmf_upload_nvram(FAR struct bcmf_sdio_dev_s *sbus) ret = bcmf_upload_binary(sbus, sbus->chip->ram_size - 4 - nvram_sz, sbus->chip->nvram_image, *sbus->chip->nvram_image_size); - if ( ret != OK) - { + if (ret != OK) + { return ret; - } + } - /* generate length token */ + /* Generate length token */ token = nvram_sz / 4; token = (~token << 16) | (token & 0x0000FFFF); /* Write the length token to the last word */ - ret = bcmf_write_sbreg(sbus, sbus->chip->ram_size - 4, (uint8_t*)&token, 4); - if ( ret != OK) - { + ret = bcmf_write_sbreg(sbus, sbus->chip->ram_size - 4, (uint8_t *)&token, 4); + if (ret != OK) + { return ret; - } + } return OK; } diff --git a/drivers/wireless/ieee80211/bcmf_core.h b/drivers/wireless/ieee80211/bcmf_core.h index 074196cded..00f859601c 100644 --- a/drivers/wireless/ieee80211/bcmf_core.h +++ b/drivers/wireless/ieee80211/bcmf_core.h @@ -64,7 +64,7 @@ static inline int bcmf_read_sbregb(FAR struct bcmf_sdio_dev_s *sbus, static inline int bcmf_read_sbregw(FAR struct bcmf_sdio_dev_s *sbus, uint32_t address, uint32_t *reg) { - return bcmf_read_sbreg(sbus, address, (uint8_t*)reg, 4); + return bcmf_read_sbreg(sbus, address, (uint8_t *)reg, 4); } static inline int bcmf_write_sbregb(FAR struct bcmf_sdio_dev_s *sbus, @@ -76,7 +76,7 @@ static inline int bcmf_write_sbregb(FAR struct bcmf_sdio_dev_s *sbus, static inline int bcmf_write_sbregw(FAR struct bcmf_sdio_dev_s *sbus, uint32_t address, uint32_t reg) { - return bcmf_write_sbreg(sbus, address, (uint8_t*)®, 4); + return bcmf_write_sbreg(sbus, address, (uint8_t *)®, 4); } #endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_CORE_H */ diff --git a/drivers/wireless/ieee80211/bcmf_driver.c b/drivers/wireless/ieee80211/bcmf_driver.c index 78f3ee0b86..8e62c6049a 100644 --- a/drivers/wireless/ieee80211/bcmf_driver.c +++ b/drivers/wireless/ieee80211/bcmf_driver.c @@ -84,12 +84,13 @@ enum * Private Function Prototypes ****************************************************************************/ -static FAR struct bcmf_dev_s* bcmf_allocate_device(void); +static FAR struct bcmf_dev_s *bcmf_allocate_device(void); static void bcmf_free_device(FAR struct bcmf_dev_s *priv); static int bcmf_driver_initialize(FAR struct bcmf_dev_s *priv); // FIXME only for debug purpose + static void bcmf_wl_default_event_handler(FAR struct bcmf_dev_s *priv, struct bcmf_event_s *event, unsigned int len); @@ -109,7 +110,7 @@ static int bcmf_wl_get_interface(FAR struct bcmf_dev_s *priv, * Private Functions ****************************************************************************/ -FAR struct bcmf_dev_s* bcmf_allocate_device(void) +FAR struct bcmf_dev_s *bcmf_allocate_device(void) { int ret; FAR struct bcmf_dev_s *priv; @@ -186,7 +187,7 @@ int bcmf_wl_set_mac_address(FAR struct bcmf_dev_s *priv, struct ifreq *req) ret = bcmf_cdc_iovar_request(priv, CHIP_STA_INTERFACE, true, IOVAR_STR_CUR_ETHERADDR, - (uint8_t*)req->ifr_hwaddr.sa_data, + (uint8_t *)req->ifr_hwaddr.sa_data, &out_len); if (ret != OK) { @@ -215,10 +216,10 @@ int bcmf_driver_initialize(FAR struct bcmf_dev_s *priv) /* Disable TX Gloming feature */ out_len = 4; - *(uint32_t*)tmp_buf = 0; + *(uint32_t *)tmp_buf = 0; ret = bcmf_cdc_iovar_request(priv, interface, false, - IOVAR_STR_TX_GLOM, tmp_buf, - &out_len); + IOVAR_STR_TX_GLOM, tmp_buf, + &out_len); if (ret != OK) { return -EIO; @@ -229,7 +230,7 @@ int bcmf_driver_initialize(FAR struct bcmf_dev_s *priv) out_len = 4; value = 0; ret = bcmf_cdc_ioctl(priv, interface, true, WLC_SET_PM, - (uint8_t*)&value, &out_len); + (uint8_t *)&value, &out_len); if (ret != OK) { return ret; @@ -240,7 +241,7 @@ int bcmf_driver_initialize(FAR struct bcmf_dev_s *priv) out_len = 4; value = GMODE_AUTO; ret = bcmf_cdc_ioctl(priv, interface, true, WLC_SET_GMODE, - (uint8_t*)&value, &out_len); + (uint8_t *)&value, &out_len); if (ret != OK) { return ret; @@ -251,14 +252,14 @@ int bcmf_driver_initialize(FAR struct bcmf_dev_s *priv) out_len = 4; value = 1; ret = bcmf_cdc_iovar_request(priv, interface, true, IOVAR_STR_ROAM_OFF, - (uint8_t*)&value, + (uint8_t *)&value, &out_len); /* TODO configure EAPOL version to default */ out_len = 8; - ((uint32_t*)tmp_buf)[0] = interface; - ((uint32_t*)tmp_buf)[1] = (uint32_t)-1; + ((uint32_t *)tmp_buf)[0] = interface; + ((uint32_t *)tmp_buf)[1] = (uint32_t)-1; if (bcmf_cdc_iovar_request(priv, interface, true, "bsscfg:"IOVAR_STR_SUP_WPA2_EAPVER, tmp_buf, @@ -282,10 +283,10 @@ int bcmf_driver_initialize(FAR struct bcmf_dev_s *priv) /* Remove line feed */ - out_len = strlen((char*)tmp_buf); - if (out_len > 0 && tmp_buf[out_len-1] == '\n') + out_len = strlen((char *)tmp_buf); + if (out_len > 0 && tmp_buf[out_len - 1] == '\n') { - tmp_buf[out_len-1] = 0; + tmp_buf[out_len - 1] = 0; } wlinfo("fw version <%s>\n", tmp_buf); @@ -353,7 +354,7 @@ void bcmf_wl_auth_event_handler(FAR struct bcmf_dev_s *priv, wlinfo("Got auth event %d from <%s>\n", type, event->src_name); - bcmf_hexdump((uint8_t*)event, len, (unsigned long)event); + bcmf_hexdump((uint8_t *)event, len, (unsigned long)event); if (type == WLC_E_SET_SSID && status == WLC_E_STATUS_SUCCESS) { @@ -408,7 +409,7 @@ void bcmf_wl_scan_event_handler(FAR struct bcmf_dev_s *priv, /* Process escan result payload */ - result = (struct wl_escan_result*)&event[1]; + result = (struct wl_escan_result *)&event[1]; if (len < result->buflen || result->buflen < sizeof(struct wl_escan_result)) { @@ -442,7 +443,7 @@ void bcmf_wl_scan_event_handler(FAR struct bcmf_dev_s *priv, /* Process next bss_info */ len -= bss_info_len; - bss = (struct wl_bss_info*)((uint8_t*)bss + bss_info_len); + bss = (struct wl_bss_info *)((uint8_t *)bss + bss_info_len); bss_count += 1; } @@ -474,12 +475,12 @@ wl_escan_result_processed: exit_invalid_frame: wlerr("Invalid scan result event\n"); - bcmf_hexdump((uint8_t*)event, event_len, (unsigned long)event); + bcmf_hexdump((uint8_t *)event, event_len, (unsigned long)event); } void bcmf_wl_scan_timeout(int argc, wdparm_t arg1, ...) { - FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s*)arg1; + FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)arg1; if (priv->scan_status < BCMF_SCAN_RUN) { @@ -590,7 +591,7 @@ int bcmf_wl_start_scan(FAR struct bcmf_dev_s *priv, struct iwreq *iwr) if (iwr->u.data.pointer && iwr->u.data.length >= sizeof(*req)) { - req = (struct iw_scan_req*)iwr->u.data.pointer; + req = (struct iw_scan_req *)iwr->u.data.pointer; memcpy(&scan_params.params.bssid, req->bssid.sa_data, sizeof(scan_params.params.bssid)); @@ -624,7 +625,7 @@ int bcmf_wl_start_scan(FAR struct bcmf_dev_s *priv, struct iwreq *iwr) value = scan_params.params.scan_type; out_len = 4; if (bcmf_cdc_ioctl(priv, CHIP_STA_INTERFACE, true, - WLC_SET_PASSIVE_SCAN, (uint8_t*)&value, &out_len)) + WLC_SET_PASSIVE_SCAN, (uint8_t *)&value, &out_len)) { ret = -EIO; goto exit_failed; @@ -644,7 +645,7 @@ int bcmf_wl_start_scan(FAR struct bcmf_dev_s *priv, struct iwreq *iwr) out_len = sizeof(scan_params); if (bcmf_cdc_iovar_request_unsafe(priv, CHIP_STA_INTERFACE, true, - IOVAR_STR_ESCAN, (uint8_t*)&scan_params, + IOVAR_STR_ESCAN, (uint8_t *)&scan_params, &out_len)) { ret = -EIO; @@ -727,15 +728,15 @@ int bcmf_wl_set_auth_param(FAR struct bcmf_dev_s *priv, struct iwreq *iwr) if (bcmf_cdc_iovar_request(priv, interface, true, "bsscfg:"IOVAR_STR_SUP_WPA, - (uint8_t*)wpa_version, + (uint8_t *)wpa_version, &out_len)) { return -EIO; } out_len = 4; - if(bcmf_cdc_ioctl(priv, interface, true, WLC_SET_WPA_AUTH, - (uint8_t*)&auth_mode, &out_len)) + if (bcmf_cdc_ioctl(priv, interface, true, WLC_SET_WPA_AUTH, + (uint8_t *)&auth_mode, &out_len)) { return -EIO; } @@ -767,8 +768,8 @@ int bcmf_wl_set_auth_param(FAR struct bcmf_dev_s *priv, struct iwreq *iwr) } out_len = 4; - if(bcmf_cdc_ioctl(priv, interface, true, - WLC_SET_WSEC, (uint8_t*)&cipher_mode, &out_len)) + if (bcmf_cdc_ioctl(priv, interface, true, + WLC_SET_WSEC, (uint8_t *)&cipher_mode, &out_len)) { return -EIO; } @@ -776,8 +777,8 @@ int bcmf_wl_set_auth_param(FAR struct bcmf_dev_s *priv, struct iwreq *iwr) /* Set authentication mode */ out_len = 4; - if(bcmf_cdc_ioctl(priv, interface, true, - WLC_SET_AUTH, (uint8_t*)&wep_auth, &out_len)) + if (bcmf_cdc_ioctl(priv, interface, true, + WLC_SET_AUTH, (uint8_t *)&wep_auth, &out_len)) { return -EIO; } @@ -815,8 +816,8 @@ int bcmf_wl_set_mode(FAR struct bcmf_dev_s *priv, struct iwreq *iwr) out_len = 4; value = iwr->u.mode == IW_MODE_INFRA ? 1 : 0; - if(bcmf_cdc_ioctl(priv, interface, true, - WLC_SET_INFRA, (uint8_t*)&value, &out_len)) + if (bcmf_cdc_ioctl(priv, interface, true, + WLC_SET_INFRA, (uint8_t *)&value, &out_len)) { return -EIO; } @@ -838,7 +839,7 @@ int bcmf_wl_set_encode_ext(FAR struct bcmf_dev_s *priv, struct iwreq *iwr) return -EINVAL; } - ext = (struct iw_encode_ext*)iwr->u.encoding.pointer; + ext = (struct iw_encode_ext *)iwr->u.encoding.pointer; switch (ext->alg) { @@ -860,7 +861,7 @@ int bcmf_wl_set_encode_ext(FAR struct bcmf_dev_s *priv, struct iwreq *iwr) out_len = sizeof(psk); return bcmf_cdc_ioctl(priv, interface, true, - WLC_SET_WSEC_PMK, (uint8_t*)&psk, &out_len); + WLC_SET_WSEC_PMK, (uint8_t *)&psk, &out_len); } int bcmf_wl_set_ssid(FAR struct bcmf_dev_s *priv, struct iwreq *iwr) @@ -883,8 +884,8 @@ int bcmf_wl_set_ssid(FAR struct bcmf_dev_s *priv, struct iwreq *iwr) /* Configure AP SSID and trig authentication request */ out_len = sizeof(ssid); - if(bcmf_cdc_ioctl(priv, interface, true, - WLC_SET_SSID, (uint8_t*)&ssid, &out_len)) + if (bcmf_cdc_ioctl(priv, interface, true, + WLC_SET_SSID, (uint8_t *)&ssid, &out_len)) { return -EIO; } @@ -910,4 +911,5 @@ int bcmf_wl_set_ssid(FAR struct bcmf_dev_s *priv, struct iwreq *iwr) return -EINVAL; } return OK; - } \ No newline at end of file + } + \ No newline at end of file diff --git a/drivers/wireless/ieee80211/bcmf_driver.h b/drivers/wireless/ieee80211/bcmf_driver.h index 3e38ff4f93..937427a49b 100644 --- a/drivers/wireless/ieee80211/bcmf_driver.h +++ b/drivers/wireless/ieee80211/bcmf_driver.h @@ -105,18 +105,18 @@ struct bcmf_bus_dev_s void (*stop)(FAR struct bcmf_dev_s *priv); int (*txframe)(FAR struct bcmf_dev_s *priv, struct bcmf_frame_s *frame, bool control); - struct bcmf_frame_s* (*rxframe)(FAR struct bcmf_dev_s *priv); + struct bcmf_frame_s *(*rxframe)(FAR struct bcmf_dev_s *priv); /* Frame buffer allocation primitives * len - requested payload length * control - true if control frame else false * block - true to block until free frame is available */ - struct bcmf_frame_s* (*allocate_frame)(FAR struct bcmf_dev_s *priv, + struct bcmf_frame_s *(*allocate_frame)(FAR struct bcmf_dev_s *priv, unsigned int len, bool block, bool control); - void (*free_frame)(FAR struct bcmf_dev_s *priv, struct bcmf_frame_s* frame); + void (*free_frame)(FAR struct bcmf_dev_s *priv, struct bcmf_frame_s *frame); }; /* bcmf frame definition */ diff --git a/drivers/wireless/ieee80211/bcmf_ioctl.h b/drivers/wireless/ieee80211/bcmf_ioctl.h index f37fd608bc..7c4cc235f2 100644 --- a/drivers/wireless/ieee80211/bcmf_ioctl.h +++ b/drivers/wireless/ieee80211/bcmf_ioctl.h @@ -1,4 +1,4 @@ -/* +/**************************************************************************** * Copyright (c) 2015 Broadcom * All rights reserved. * @@ -31,7 +31,8 @@ * 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. - */ + * + ****************************************************************************/ /* * Custom OID/ioctl definitions for * Broadcom 802.11abg Networking Device Driver @@ -49,64 +50,66 @@ typedef uint16_t chanspec_t; typedef struct wl_action_frame { - struct ether_addr da; - uint16_t len; - uint32_t packetId; - uint8_t data[ACTION_FRAME_SIZE]; + struct ether_addr da; + uint16_t len; + uint32_t packetId; + uint8_t data[ACTION_FRAME_SIZE]; } wl_action_frame_t; typedef struct ssid_info { - uint8_t ssid_len; - uint8_t ssid[32]; + uint8_t ssid_len; + uint8_t ssid[32]; } ssid_info_t; typedef struct cnt_rx { - uint32_t cnt_rxundec; - uint32_t cnt_rxframe; + uint32_t cnt_rxundec; + uint32_t cnt_rxframe; } cnt_rx_t; #define MCSSET_LEN 16 -typedef struct wl_bss_info { - uint32_t version; /* version field */ - uint32_t length; /* byte length of data in this record, */ - /* starting at version and including IEs */ - struct ether_addr BSSID; - uint16_t beacon_period; /* units are Kusec */ - uint16_t capability; /* Capability information */ - uint8_t SSID_len; - uint8_t SSID[32]; - struct { - uint32_t count; /* # rates in this set */ - uint8_t rates[16]; /* rates in 500kbps units w/hi bit set if basic */ - } rateset; /* supported rates */ - wl_chanspec_t chanspec; /* chanspec for bss */ - uint16_t atim_window; /* units are Kusec */ - uint8_t dtim_period; /* DTIM period */ - int16_t RSSI; /* receive signal strength (in dBm) */ - int8_t phy_noise; /* noise (in dBm) */ - - uint8_t n_cap; /* BSS is 802.11N Capable */ - uint32_t nbss_cap; /* 802.11N BSS Capabilities (based on HT_CAP_*) */ - uint8_t ctl_ch; /* 802.11N BSS control channel number */ - uint32_t reserved32[1]; /* Reserved for expansion of BSS properties */ - uint8_t flags; /* flags */ - uint8_t reserved[3]; /* Reserved for expansion of BSS properties */ - uint8_t basic_mcs[MCSSET_LEN]; /* 802.11N BSS required MCS set */ - - uint16_t ie_offset; /* offset at which IEs start, from beginning */ - uint32_t ie_length; /* byte length of Information Elements */ - int16_t SNR; /* average SNR of during frame reception */ - /* Add new fields here */ - /* variable length Information Elements */ +typedef struct wl_bss_info +{ + uint32_t version; /* version field */ + uint32_t length; /* byte length of data in this record, */ + /* starting at version and including IEs */ + struct ether_addr BSSID; + uint16_t beacon_period; /* units are Kusec */ + uint16_t capability; /* Capability information */ + uint8_t SSID_len; + uint8_t SSID[32]; + struct + { + uint32_t count; /* # rates in this set */ + uint8_t rates[16]; /* rates in 500kbps units w/hi bit set if basic */ + } rateset; /* supported rates */ + wl_chanspec_t chanspec; /* chanspec for bss */ + uint16_t atim_window; /* units are Kusec */ + uint8_t dtim_period; /* DTIM period */ + int16_t RSSI; /* receive signal strength (in dBm) */ + int8_t phy_noise; /* noise (in dBm) */ + + uint8_t n_cap; /* BSS is 802.11N Capable */ + uint32_t nbss_cap; /* 802.11N BSS Capabilities (based on HT_CAP_*) */ + uint8_t ctl_ch; /* 802.11N BSS control channel number */ + uint32_t reserved32[1]; /* Reserved for expansion of BSS properties */ + uint8_t flags; /* flags */ + uint8_t reserved[3]; /* Reserved for expansion of BSS properties */ + uint8_t basic_mcs[MCSSET_LEN]; /* 802.11N BSS required MCS set */ + + uint16_t ie_offset; /* offset at which IEs start, from beginning */ + uint32_t ie_length; /* byte length of Information Elements */ + int16_t SNR; /* average SNR of during frame reception */ + /* Add new fields here */ + /* variable length Information Elements */ } wl_bss_info_t; typedef struct wlc_ssid { - uint32_t SSID_len; - uint8_t SSID[32]; + uint32_t SSID_len; + uint8_t SSID[32]; } wlc_ssid_t; #define WL_BSSTYPE_INFRA 1 @@ -117,16 +120,16 @@ typedef struct wlc_ssid typedef struct wl_scan_params { - wlc_ssid_t ssid; - struct ether_addr bssid; - int8_t bss_type; - int8_t scan_type; - int32_t nprobes; - int32_t active_time; - int32_t passive_time; - int32_t home_time; - int32_t channel_num; - uint16_t channel_list[1]; + wlc_ssid_t ssid; + struct ether_addr bssid; + int8_t bss_type; + int8_t scan_type; + int32_t nprobes; + int32_t active_time; + int32_t passive_time; + int32_t home_time; + int32_t channel_num; + uint16_t channel_list[1]; } wl_scan_params_t; #define WL_SCAN_PARAMS_FIXED_SIZE (64) @@ -139,20 +142,20 @@ typedef struct wl_scan_params typedef struct wl_iscan_params { - uint32_t version; - uint16_t action; - uint16_t scan_duration; - wl_scan_params_t params; + uint32_t version; + uint16_t action; + uint16_t scan_duration; + wl_scan_params_t params; } wl_iscan_params_t; #define WL_ISCAN_PARAMS_FIXED_SIZE (offsetof(wl_iscan_params_t, params) + sizeof(wlc_ssid_t)) typedef struct wl_scan_results { - uint32_t buflen; - uint32_t version; - uint32_t count; - wl_bss_info_t bss_info[1]; + uint32_t buflen; + uint32_t version; + uint32_t count; + wl_bss_info_t bss_info[1]; } wl_scan_results_t; #define WL_SCAN_RESULTS_FIXED_SIZE (12) @@ -165,56 +168,57 @@ typedef struct wl_scan_results typedef struct wl_escan_params { - uint32_t version; - uint16_t action; - uint16_t sync_id; - wl_scan_params_t params; + uint32_t version; + uint16_t action; + uint16_t sync_id; + wl_scan_params_t params; } wl_escan_params_t; #define WL_ESCAN_PARAMS_FIXED_SIZE (offsetof(wl_escan_params_t, params) + sizeof(wlc_ssid_t)) typedef struct wl_escan_result { - uint32_t buflen; - uint32_t version; - uint16_t sync_id; - uint16_t bss_count; - wl_bss_info_t bss_info[1]; + uint32_t buflen; + uint32_t version; + uint16_t sync_id; + uint16_t bss_count; + wl_bss_info_t bss_info[1]; } wl_escan_result_t; #define WL_ESCAN_RESULTS_FIXED_SIZE (sizeof(wl_escan_result_t) - sizeof(wl_bss_info_t)) typedef struct wl_iscan_results { - uint32_t status; - wl_scan_results_t results; + uint32_t status; + wl_scan_results_t results; } wl_iscan_results_t; #define WL_ISCAN_RESULTS_FIXED_SIZE \ - (WL_SCAN_RESULTS_FIXED_SIZE + offsetof(wl_iscan_results_t, results)) + (WL_SCAN_RESULTS_FIXED_SIZE + offsetof(wl_iscan_results_t, results)) #define WL_MAXRATES_IN_SET 16 /* max # of rates in a rateset */ typedef struct wl_rateset { - uint32_t count; /* # rates in this set */ - uint8_t rates[WL_MAXRATES_IN_SET]; /* rates in 500kbps units w/hi bit set if basic */ + uint32_t count; /* # rates in this set */ + uint8_t rates[WL_MAXRATES_IN_SET]; /* rates in 500kbps units w/hi bit set if basic */ } wl_rateset_t; typedef struct wl_uint32_list { - uint32_t count; - uint32_t element[1]; + uint32_t count; + uint32_t element[1]; } wl_uint32_list_t; -typedef struct wl_join_scan_params { - uint8_t scan_type; /* 0 use default, active or passive scan */ - int32_t nprobes; /* -1 use default, number of probes per channel */ - int32_t active_time; /* -1 use default, dwell time per channel for - * active scanning */ - int32_t passive_time; /* -1 use default, dwell time per channel - * for passive scanning */ - int32_t home_time; /* -1 use default, dwell time for the home channel - * between channel scans */ +typedef struct wl_join_scan_params +{ + uint8_t scan_type; /* 0 use default, active or passive scan */ + int32_t nprobes; /* -1 use default, number of probes per channel */ + int32_t active_time; /* -1 use default, dwell time per channel for + * active scanning */ + int32_t passive_time; /* -1 use default, dwell time per channel + * for passive scanning */ + int32_t home_time; /* -1 use default, dwell time for the home channel + * between channel scans */ } wl_join_scan_params_t; #define NRATE_MCS_INUSE (0x00000080) @@ -247,8 +251,8 @@ typedef struct wl_join_scan_params { typedef struct { - uint8_t ant_config[ANT_SELCFG_MAX]; - uint8_t num_antcfg; + uint8_t ant_config[ANT_SELCFG_MAX]; + uint8_t num_antcfg; } wlc_antselcfg_t; #define HIGHEST_SINGLE_STREAM_MCS (7) @@ -256,27 +260,27 @@ typedef struct typedef struct wl_country { - int8_t country_abbrev[WLC_CNTRY_BUF_SZ]; - int32_t rev; - int8_t ccode[WLC_CNTRY_BUF_SZ]; + int8_t country_abbrev[WLC_CNTRY_BUF_SZ]; + int32_t rev; + int8_t ccode[WLC_CNTRY_BUF_SZ]; } wl_country_t; typedef struct wl_channels_in_country { - uint32_t buflen; - uint32_t band; - int8_t country_abbrev[WLC_CNTRY_BUF_SZ]; - uint32_t count; - uint32_t channel[1]; + uint32_t buflen; + uint32_t band; + int8_t country_abbrev[WLC_CNTRY_BUF_SZ]; + uint32_t count; + uint32_t channel[1]; } wl_channels_in_country_t; typedef struct wl_country_list { - uint32_t buflen; - uint32_t band_set; - uint32_t band; - uint32_t count; - int8_t country_abbrev[1]; + uint32_t buflen; + uint32_t band_set; + uint32_t band; + uint32_t count; + int8_t country_abbrev[1]; } wl_country_list_t; #define WL_NUM_RPI_BINS 8 @@ -290,37 +294,37 @@ typedef struct wl_country_list typedef struct wl_rm_req_elt { - int8_t type; - int8_t flags; - wl_chanspec_t chanspec; - uint32_t token; - uint32_t tsf_h; - uint32_t tsf_l; - uint32_t dur; + int8_t type; + int8_t flags; + wl_chanspec_t chanspec; + uint32_t token; + uint32_t tsf_h; + uint32_t tsf_l; + uint32_t dur; } wl_rm_req_elt_t; typedef struct wl_rm_req { - uint32_t token; - uint32_t count; - void* cb; - void* cb_arg; - wl_rm_req_elt_t req[1]; + uint32_t token; + uint32_t count; + void *cb; + void *cb_arg; + wl_rm_req_elt_t req[1]; } wl_rm_req_t; #define WL_RM_REQ_FIXED_LEN offsetof(wl_rm_req_t, req) typedef struct wl_rm_rep_elt { - int8_t type; - int8_t flags; - wl_chanspec_t chanspec; - uint32_t token; - uint32_t tsf_h; - uint32_t tsf_l; - uint32_t dur; - uint32_t len; - uint8_t data[1]; + int8_t type; + int8_t flags; + wl_chanspec_t chanspec; + uint32_t token; + uint32_t tsf_h; + uint32_t tsf_l; + uint32_t dur; + uint32_t len; + uint8_t data[1]; } wl_rm_rep_elt_t; #define WL_RM_REP_ELT_FIXED_LEN 24 @@ -328,14 +332,14 @@ typedef struct wl_rm_rep_elt typedef struct wl_rm_rpi_rep { - uint8_t rpi[WL_RPI_REP_BIN_NUM]; - int8_t rpi_max[WL_RPI_REP_BIN_NUM]; + uint8_t rpi[WL_RPI_REP_BIN_NUM]; + int8_t rpi_max[WL_RPI_REP_BIN_NUM]; } wl_rm_rpi_rep_t; typedef struct wl_rm_rep { - uint32_t token; - uint32_t len; - wl_rm_rep_elt_t rep[1]; + uint32_t token; + uint32_t len; + wl_rm_rep_elt_t rep[1]; } wl_rm_rep_t; #define WL_RM_REP_FIXED_LEN 8 @@ -362,23 +366,23 @@ typedef struct wl_rm_rep typedef struct wl_wsec_key { - uint32_t index; - uint32_t len; - uint8_t data[DOT11_MAX_KEY_SIZE]; - uint32_t pad_1[18]; - uint32_t algo; - uint32_t flags; - uint32_t pad_2[2]; - int32_t pad_3; - int32_t iv_initialized; - int32_t pad_4; - struct - { - uint32_t hi; - uint16_t lo; - } rxiv; - uint32_t pad_5[2]; - struct ether_addr ea; + uint32_t index; + uint32_t len; + uint8_t data[DOT11_MAX_KEY_SIZE]; + uint32_t pad_1[18]; + uint32_t algo; + uint32_t flags; + uint32_t pad_2[2]; + int32_t pad_3; + int32_t iv_initialized; + int32_t pad_4; + struct + { + uint32_t hi; + uint16_t lo; + } rxiv; + uint32_t pad_5[2]; + struct ether_addr ea; } wl_wsec_key_t; #define WSEC_MIN_PSK_LEN 8 @@ -387,9 +391,9 @@ typedef struct wl_wsec_key typedef struct { - uint16_t key_len; - uint16_t flags; - uint8_t key[WSEC_MAX_PSK_LEN]; + uint16_t key_len; + uint16_t flags; + uint8_t key[WSEC_MAX_PSK_LEN]; } wsec_pmk_t; #define OPEN_AUTH 0x0000 @@ -413,72 +417,72 @@ typedef struct typedef struct _pmkid { - struct ether_addr BSSID; - uint8_t PMKID[WPA2_PMKID_LEN]; + struct ether_addr BSSID; + uint8_t PMKID[WPA2_PMKID_LEN]; } pmkid_t; typedef struct _pmkid_list { - uint32_t npmkid; - pmkid_t pmkid[1]; + uint32_t npmkid; + pmkid_t pmkid[1]; } pmkid_list_t; typedef struct _pmkid_cand { - struct ether_addr BSSID; - uint8_t preauth; + struct ether_addr BSSID; + uint8_t preauth; } pmkid_cand_t; typedef struct _pmkid_cand_list { - uint32_t npmkid_cand; - pmkid_cand_t pmkid_cand[1]; + uint32_t npmkid_cand; + pmkid_cand_t pmkid_cand[1]; } pmkid_cand_list_t; typedef struct wl_led_info { - uint32_t index; - uint32_t behavior; - uint8_t activehi; + uint32_t index; + uint32_t behavior; + uint8_t activehi; } wl_led_info_t; struct wl_dot11_assoc_req { - uint16_t capability; - uint16_t listen; + uint16_t capability; + uint16_t listen; }; struct wl_dot11_assoc_resp { - uint16_t capability; - uint16_t status; - uint16_t aid; + uint16_t capability; + uint16_t status; + uint16_t aid; }; typedef struct wl_assoc_info { - uint32_t req_len; - uint32_t resp_len; - uint32_t flags; - struct wl_dot11_assoc_req req; - struct ether_addr reassoc_bssid; - struct wl_dot11_assoc_resp resp; + uint32_t req_len; + uint32_t resp_len; + uint32_t flags; + struct wl_dot11_assoc_req req; + struct ether_addr reassoc_bssid; + struct wl_dot11_assoc_resp resp; } wl_assoc_info_t; #define WLC_ASSOC_REQ_IS_REASSOC 0x01 typedef struct { - uint32_t byteoff; - uint32_t nbytes; - uint16_t buf[1]; + uint32_t byteoff; + uint32_t nbytes; + uint16_t buf[1]; } srom_rw_t; typedef struct { - uint32_t source; - uint32_t byteoff; - uint32_t nbytes; + uint32_t source; + uint32_t byteoff; + uint32_t nbytes; } cis_rw_t; #define WLC_CIS_DEFAULT 0 @@ -487,10 +491,10 @@ typedef struct typedef struct { - uint32_t byteoff; - uint32_t val; - uint32_t size; - uint32_t band; + uint32_t byteoff; + uint32_t val; + uint32_t size; + uint32_t band; } rw_reg_t; #define WL_ATTEN_APP_INPUT_PCL_OFF 0 @@ -499,19 +503,19 @@ typedef struct typedef struct { - uint16_t auto_ctrl; - uint16_t bb; - uint16_t radio; - uint16_t txctl1; + uint16_t auto_ctrl; + uint16_t bb; + uint16_t radio; + uint16_t txctl1; } atten_t; struct wme_tx_params_s { - uint8_t short_retry; - uint8_t short_fallback; - uint8_t long_retry; - uint8_t long_fallback; - uint16_t max_rate; + uint8_t short_retry; + uint8_t short_fallback; + uint8_t long_retry; + uint8_t long_fallback; + uint16_t max_rate; }; typedef struct wme_tx_params_s wme_tx_params_t; @@ -523,29 +527,29 @@ typedef struct wme_tx_params_s wme_tx_params_t; typedef struct { - uint32_t val; - struct ether_addr ea; + uint32_t val; + struct ether_addr ea; } scb_val_t; #define BCM_MAC_STATUS_INDICATION (0x40010200L) typedef struct { - uint16_t ver; - uint16_t len; - uint16_t cap; - uint32_t flags; - uint32_t idle; - struct ether_addr ea; - wl_rateset_t rateset; - uint32_t in; - uint32_t listen_interval_inms; - uint32_t tx_pkts; - uint32_t tx_failures; - uint32_t rx_ucast_pkts; - uint32_t rx_mcast_pkts; - uint32_t tx_rate; - uint32_t rx_rate; + uint16_t ver; + uint16_t len; + uint16_t cap; + uint32_t flags; + uint32_t idle; + struct ether_addr ea; + wl_rateset_t rateset; + uint32_t in; + uint32_t listen_interval_inms; + uint32_t tx_pkts; + uint32_t tx_failures; + uint32_t rx_ucast_pkts; + uint32_t rx_mcast_pkts; + uint32_t tx_rate; + uint32_t rx_rate; } sta_info_t; #define WL_OLD_STAINFO_SIZE offsetof(sta_info_t, tx_pkts) @@ -569,50 +573,50 @@ typedef struct typedef struct channel_info { - int32_t hw_channel; - int32_t target_channel; - int32_t scan_channel; + int32_t hw_channel; + int32_t target_channel; + int32_t scan_channel; } channel_info_t; struct mac_list { - uint32_t count; - struct ether_addr ea[1]; + uint32_t count; + struct ether_addr ea[1]; }; typedef struct get_pktcnt { - uint32_t rx_good_pkt; - uint32_t rx_bad_pkt; - uint32_t tx_good_pkt; - uint32_t tx_bad_pkt; - uint32_t rx_ocast_good_pkt; + uint32_t rx_good_pkt; + uint32_t rx_bad_pkt; + uint32_t tx_good_pkt; + uint32_t tx_bad_pkt; + uint32_t rx_ocast_good_pkt; } get_pktcnt_t; typedef struct wl_ioctl { - uint32_t cmd; - void* buf; - uint32_t len; - uint8_t set; - uint32_t used; - uint32_t needed; + uint32_t cmd; + void *buf; + uint32_t len; + uint8_t set; + uint32_t used; + uint32_t needed; } wl_ioctl_t; typedef struct wlc_rev_info { - uint32_t vendorid; - uint32_t deviceid; - uint32_t radiorev; - uint32_t chiprev; - uint32_t corerev; - uint32_t boardid; - uint32_t boardvendor; - uint32_t boardrev; - uint32_t driverrev; - uint32_t ucoderev; - uint32_t bus; - uint32_t chipnum; - uint32_t phytype; - uint32_t phyrev; - uint32_t anarev; + uint32_t vendorid; + uint32_t deviceid; + uint32_t radiorev; + uint32_t chiprev; + uint32_t corerev; + uint32_t boardid; + uint32_t boardvendor; + uint32_t boardrev; + uint32_t driverrev; + uint32_t ucoderev; + uint32_t bus; + uint32_t chipnum; + uint32_t phytype; + uint32_t phyrev; + uint32_t anarev; } wlc_rev_info_t; #define WL_REV_INFO_LEGACY_LENGTH 48 @@ -620,23 +624,23 @@ typedef struct wlc_rev_info typedef struct wl_instance_info { - uint32_t instance; - int8_t brand[WL_BRAND_MAX]; + uint32_t instance; + int8_t brand[WL_BRAND_MAX]; } wl_instance_info_t; typedef struct wl_txfifo_sz { - uint8_t fifo; - uint8_t size; + uint8_t fifo; + uint8_t size; } wl_txfifo_sz_t; #define WLC_IOV_NAME_LEN 30 typedef struct wlc_iov_trx_s { - uint8_t module; - uint8_t type; - int8_t name[WLC_IOV_NAME_LEN]; + uint8_t module; + uint8_t type; + int8_t name[WLC_IOV_NAME_LEN]; } wlc_iov_trx_t; #define IOVAR_STR_BSSCFG_WPA_AUTH "bsscfg:wpa_auth" @@ -1110,43 +1114,43 @@ typedef struct wlc_iov_trx_s typedef struct wl_aci_args { - int32_t enter_aci_thresh; - int32_t exit_aci_thresh; - int32_t usec_spin; - int32_t glitch_delay; - uint16_t nphy_adcpwr_enter_thresh; - uint16_t nphy_adcpwr_exit_thresh; - uint16_t nphy_repeat_ctr; - uint16_t nphy_num_samples; - uint16_t nphy_undetect_window_sz; - uint16_t nphy_b_energy_lo_aci; - uint16_t nphy_b_energy_md_aci; - uint16_t nphy_b_energy_hi_aci; + int32_t enter_aci_thresh; + int32_t exit_aci_thresh; + int32_t usec_spin; + int32_t glitch_delay; + uint16_t nphy_adcpwr_enter_thresh; + uint16_t nphy_adcpwr_exit_thresh; + uint16_t nphy_repeat_ctr; + uint16_t nphy_num_samples; + uint16_t nphy_undetect_window_sz; + uint16_t nphy_b_energy_lo_aci; + uint16_t nphy_b_energy_md_aci; + uint16_t nphy_b_energy_hi_aci; } wl_aci_args_t; #define WL_ACI_ARGS_LEGACY_LENGTH 16 typedef struct { - int32_t npulses; - int32_t ncontig; - int32_t min_pw; - int32_t max_pw; - uint16_t thresh0; - uint16_t thresh1; - uint16_t blank; - uint16_t fmdemodcfg; - int32_t npulses_lp; - int32_t min_pw_lp; - int32_t max_pw_lp; - int32_t min_fm_lp; - int32_t max_deltat_lp; - int32_t min_deltat; - int32_t max_deltat; - uint16_t autocorr; - uint16_t st_level_time; - uint16_t t2_min; - uint32_t version; + int32_t npulses; + int32_t ncontig; + int32_t min_pw; + int32_t max_pw; + uint16_t thresh0; + uint16_t thresh1; + uint16_t blank; + uint16_t fmdemodcfg; + int32_t npulses_lp; + int32_t min_pw_lp; + int32_t max_pw_lp; + int32_t min_fm_lp; + int32_t max_deltat_lp; + int32_t min_deltat; + int32_t max_deltat; + uint16_t autocorr; + uint16_t st_level_time; + uint16_t t2_min; + uint32_t version; } wl_radar_args_t; #define WL_RADAR_ARGS_VERSION 1 @@ -1158,9 +1162,9 @@ typedef struct typedef struct { - uint32_t version; - uint32_t count; - int8_t rssi_ant[WL_RSSI_ANT_MAX]; + uint32_t version; + uint32_t count; + int8_t rssi_ant[WL_RSSI_ANT_MAX]; } wl_rssi_ant_t; #define WL_DFS_CACSTATE_IDLE 0 @@ -1174,29 +1178,29 @@ typedef struct typedef struct { - uint32_t state; - uint32_t duration; - wl_chanspec_t chanspec_cleared; - uint16_t pad; + uint32_t state; + uint32_t duration; + wl_chanspec_t chanspec_cleared; + uint16_t pad; } wl_dfs_status_t; #define NUM_PWRCTRL_RATES 12 typedef struct { - uint8_t txpwr_band_max[NUM_PWRCTRL_RATES]; - uint8_t txpwr_limit[NUM_PWRCTRL_RATES]; - uint8_t txpwr_local_max; - uint8_t txpwr_local_constraint; - uint8_t txpwr_chan_reg_max; - uint8_t txpwr_target[2][NUM_PWRCTRL_RATES]; - uint8_t txpwr_est_Pout[2]; - uint8_t txpwr_opo[NUM_PWRCTRL_RATES]; - uint8_t txpwr_bphy_cck_max[NUM_PWRCTRL_RATES]; - uint8_t txpwr_bphy_ofdm_max; - uint8_t txpwr_aphy_max[NUM_PWRCTRL_RATES]; - int8_t txpwr_antgain[2]; - uint8_t txpwr_est_Pout_gofdm; + uint8_t txpwr_band_max[NUM_PWRCTRL_RATES]; + uint8_t txpwr_limit[NUM_PWRCTRL_RATES]; + uint8_t txpwr_local_max; + uint8_t txpwr_local_constraint; + uint8_t txpwr_chan_reg_max; + uint8_t txpwr_target[2][NUM_PWRCTRL_RATES]; + uint8_t txpwr_est_Pout[2]; + uint8_t txpwr_opo[NUM_PWRCTRL_RATES]; + uint8_t txpwr_bphy_cck_max[NUM_PWRCTRL_RATES]; + uint8_t txpwr_bphy_ofdm_max; + uint8_t txpwr_aphy_max[NUM_PWRCTRL_RATES]; + int8_t txpwr_antgain[2]; + uint8_t txpwr_est_Pout_gofdm; } tx_power_legacy_t; #define WL_TX_POWER_RATES 45 @@ -1219,25 +1223,25 @@ typedef struct typedef struct { - uint32_t flags; - wl_chanspec_t chanspec; - wl_chanspec_t local_chanspec; - uint8_t local_max; - uint8_t local_constraint; - int8_t antgain[2]; - uint8_t rf_cores; - uint8_t est_Pout[4]; - uint8_t est_Pout_cck; - uint8_t user_limit[WL_TX_POWER_RATES]; - uint8_t reg_limit[WL_TX_POWER_RATES]; - uint8_t board_limit[WL_TX_POWER_RATES]; - uint8_t target[WL_TX_POWER_RATES]; + uint32_t flags; + wl_chanspec_t chanspec; + wl_chanspec_t local_chanspec; + uint8_t local_max; + uint8_t local_constraint; + int8_t antgain[2]; + uint8_t rf_cores; + uint8_t est_Pout[4]; + uint8_t est_Pout_cck; + uint8_t user_limit[WL_TX_POWER_RATES]; + uint8_t reg_limit[WL_TX_POWER_RATES]; + uint8_t board_limit[WL_TX_POWER_RATES]; + uint8_t target[WL_TX_POWER_RATES]; } tx_power_t; typedef struct tx_inst_power { - uint8_t txpwr_est_Pout[2]; - uint8_t txpwr_est_Pout_gofdm; + uint8_t txpwr_est_Pout[2]; + uint8_t txpwr_est_Pout_gofdm; } tx_inst_power_t; #define WLC_MEASURE_TPC 1 @@ -1349,29 +1353,29 @@ typedef struct tx_inst_power struct wl_vndr_ie { - uint8_t id; - uint8_t len; - uint8_t oui[3]; - uint8_t data[1]; + uint8_t id; + uint8_t len; + uint8_t oui[3]; + uint8_t data[1]; }; typedef struct wl_vndr_ie wl_vndr_ie_t; typedef struct { - uint32_t pktflag; - wl_vndr_ie_t vndr_ie_data; + uint32_t pktflag; + wl_vndr_ie_t vndr_ie_data; } vndr_ie_info_t; typedef struct { - int32_t iecount; - vndr_ie_info_t vndr_ie_list[1]; + int32_t iecount; + vndr_ie_info_t vndr_ie_list[1]; } vndr_ie_buf_t; typedef struct { - int8_t cmd[VNDR_IE_CMD_LEN]; - vndr_ie_buf_t vndr_ie_buffer; + int8_t cmd[VNDR_IE_CMD_LEN]; + vndr_ie_buf_t vndr_ie_buffer; } vndr_ie_setbuf_t; #define WL_JOIN_PREF_RSSI 1 @@ -1382,7 +1386,7 @@ typedef struct struct tsinfo_arg { - uint8_t octets[3]; + uint8_t octets[3]; }; #define NFIFO 6 @@ -1391,811 +1395,813 @@ struct tsinfo_arg typedef struct { - uint16_t version; /* see definition of WL_CNT_T_VERSION */ - uint16_t length; /* length of entire structure */ - - /* transmit stat counters */ - uint32_t txframe; /* tx data frames */ - uint32_t txbyte; /* tx data bytes */ - uint32_t txretrans; /* tx mac retransmits */ - uint32_t txerror; /* tx data errors (derived: sum of others) */ - uint32_t txctl; /* tx management frames */ - uint32_t txprshort; /* tx short preamble frames */ - uint32_t txserr; /* tx status errors */ - uint32_t txnobuf; /* tx out of buffers errors */ - uint32_t txnoassoc; /* tx discard because we're not associated */ - uint32_t txrunt; /* tx runt frames */ - uint32_t txchit; /* tx header cache hit (fastpath) */ - uint32_t txcmiss; /* tx header cache miss (slowpath) */ - - /* transmit chip error counters */ - uint32_t txuflo; /* tx fifo underflows */ - uint32_t txphyerr; /* tx phy errors (indicated in tx status) */ - uint32_t txphycrs; /* PR8861/8963 counter */ - - /* receive stat counters */ - uint32_t rxframe; /* rx data frames */ - uint32_t rxbyte; /* rx data bytes */ - uint32_t rxerror; /* rx data errors (derived: sum of others) */ - uint32_t rxctl; /* rx management frames */ - uint32_t rxnobuf; /* rx out of buffers errors */ - uint32_t rxnondata; /* rx non data frames in the data channel errors */ - uint32_t rxbadds; /* rx bad DS errors */ - uint32_t rxbadcm; /* rx bad control or management frames */ - uint32_t rxfragerr; /* rx fragmentation errors */ - uint32_t rxrunt; /* rx runt frames */ - uint32_t rxgiant; /* rx giant frames */ - uint32_t rxnoscb; /* rx no scb error */ - uint32_t rxbadproto; /* rx invalid frames */ - uint32_t rxbadsrcmac; /* rx frames with Invalid Src Mac */ - uint32_t rxbadda; /* rx frames tossed for invalid da */ - uint32_t rxfilter; /* rx frames filtered out */ - - /* receive chip error counters */ - uint32_t rxoflo; /* rx fifo overflow errors */ - uint32_t rxuflo[NFIFO]; /* rx dma descriptor underflow errors */ - - uint32_t d11cnt_txrts_off; /* d11cnt txrts value when reset d11cnt */ - uint32_t d11cnt_rxcrc_off; /* d11cnt rxcrc value when reset d11cnt */ - uint32_t d11cnt_txnocts_off; /* d11cnt txnocts value when reset d11cnt */ - - /* misc counters */ - uint32_t dmade; /* tx/rx dma descriptor errors */ - uint32_t dmada; /* tx/rx dma data errors */ - uint32_t dmape; /* tx/rx dma descriptor protocol errors */ - uint32_t reset; /* reset count */ - uint32_t tbtt; /* cnts the TBTT int's */ - uint32_t txdmawar; /* # occurrences of PR15420 workaround */ - uint32_t pkt_callback_reg_fail; /* callbacks register failure */ - - /* MAC counters: 32-bit version of d11.h's macstat_t */ - uint32_t txallfrm; /* total number of frames sent, incl. Data, ACK, RTS, CTS, - * Control Management (includes retransmissions) - */ - uint32_t txrtsfrm; /* number of RTS sent out by the MAC */ - uint32_t txctsfrm; /* number of CTS sent out by the MAC */ - uint32_t txackfrm; /* number of ACK frames sent out */ - uint32_t txdnlfrm; /* Not used */ - uint32_t txbcnfrm; /* beacons transmitted */ - uint32_t txfunfl[8]; /* per-fifo tx underflows */ - uint32_t txtplunfl; /* Template underflows (mac was too slow to transmit ACK/CTS - * or BCN) - */ - uint32_t txphyerror; /* Transmit phy error, type of error is reported in tx-status for - * driver enqueued frames - */ - uint32_t rxfrmtoolong; /* Received frame longer than legal limit (2346 bytes) */ - uint32_t rxfrmtooshrt; /* Received frame did not contain enough bytes for its frame type */ - uint32_t rxinvmachdr; /* Either the protocol version != 0 or frame type not - * data/control/management - */ - uint32_t rxbadfcs; /* number of frames for which the CRC check failed in the MAC */ - uint32_t rxbadplcp; /* parity check of the PLCP header failed */ - uint32_t rxcrsglitch; /* PHY was able to correlate the preamble but not the header */ - uint32_t rxstrt; /* Number of received frames with a good PLCP - * (i.e. passing parity check) - */ - uint32_t rxdfrmucastmbss; /* Number of received DATA frames with good FCS and matching RA */ - uint32_t rxmfrmucastmbss; /* number of received mgmt frames with good FCS and matching RA */ - uint32_t rxcfrmucast; /* number of received CNTRL frames with good FCS and matching RA */ - uint32_t rxrtsucast; /* number of unicast RTS addressed to the MAC (good FCS) */ - uint32_t rxctsucast; /* number of unicast CTS addressed to the MAC (good FCS) */ - uint32_t rxackucast; /* number of ucast ACKS received (good FCS) */ - uint32_t rxdfrmocast; /* number of received DATA frames (good FCS and not matching RA) */ - uint32_t rxmfrmocast; /* number of received MGMT frames (good FCS and not matching RA) */ - uint32_t rxcfrmocast; /* number of received CNTRL frame (good FCS and not matching RA) */ - uint32_t rxrtsocast; /* number of received RTS not addressed to the MAC */ - uint32_t rxctsocast; /* number of received CTS not addressed to the MAC */ - uint32_t rxdfrmmcast; /* number of RX Data multicast frames received by the MAC */ - uint32_t rxmfrmmcast; /* number of RX Management multicast frames received by the MAC */ - uint32_t rxcfrmmcast; /* number of RX Control multicast frames received by the MAC - * (unlikely to see these) - */ - uint32_t rxbeaconmbss; /* beacons received from member of BSS */ - uint32_t rxdfrmucastobss; /* number of unicast frames addressed to the MAC from - * other BSS (WDS FRAME) - */ - uint32_t rxbeaconobss; /* beacons received from other BSS */ - uint32_t rxrsptmout; /* Number of response timeouts for transmitted frames - * expecting a response - */ - uint32_t bcntxcancl; /* transmit beacons canceled due to receipt of beacon (IBSS) */ - uint32_t rxf0ovfl; /* Number of receive fifo 0 overflows */ - uint32_t rxf1ovfl; /* Number of receive fifo 1 overflows (obsolete) */ - uint32_t rxf2ovfl; /* Number of receive fifo 2 overflows (obsolete) */ - uint32_t txsfovfl; /* Number of transmit status fifo overflows (obsolete) */ - uint32_t pmqovfl; /* Number of PMQ overflows */ - uint32_t rxcgprqfrm; /* Number of received Probe requests that made it into - * the PRQ fifo - */ - uint32_t rxcgprsqovfl; /* Rx Probe Request Que overflow in the AP */ - uint32_t txcgprsfail; /* Tx Probe Response Fail. AP sent probe response but did - * not get ACK - */ - uint32_t txcgprssuc; /* Tx Probe Response Success (ACK was received) */ - uint32_t prs_timeout; /* Number of probe requests that were dropped from the PRQ - * fifo because a probe response could not be sent out within - * the time limit defined in M_PRS_MAXTIME - */ - uint32_t rxnack; /* XXX Number of NACKS received (Afterburner) */ - uint32_t frmscons; /* XXX Number of frames completed without transmission because of an - * Afterburner re-queue - */ - uint32_t txnack; /* XXX Number of NACKs transmitted (Afterburner) */ - uint32_t txglitch_nack; /* obsolete */ - uint32_t txburst; /* obsolete */ - - /* 802.11 MIB counters, pp. 614 of 802.11 reaff doc. */ - uint32_t txfrag; /* dot11TransmittedFragmentCount */ - uint32_t txmulti; /* dot11MulticastTransmittedFrameCount */ - uint32_t txfail; /* dot11FailedCount */ - uint32_t txretry; /* dot11RetryCount */ - uint32_t txretrie; /* dot11MultipleRetryCount */ - uint32_t rxdup; /* dot11FrameduplicateCount */ - uint32_t txrts; /* dot11RTSSuccessCount */ - uint32_t txnocts; /* dot11RTSFailureCount */ - uint32_t txnoack; /* dot11ACKFailureCount */ - uint32_t rxfrag; /* dot11ReceivedFragmentCount */ - uint32_t rxmulti; /* dot11MulticastReceivedFrameCount */ - uint32_t rxcrc; /* dot11FCSErrorCount */ - uint32_t txfrmsnt; /* dot11TransmittedFrameCount (bogus MIB?) */ - uint32_t rxundec; /* dot11WEPUndecryptableCount */ - - /* WPA2 counters (see rxundec for DecryptFailureCount) */ - uint32_t tkipmicfaill; /* TKIPLocalMICFailures */ - uint32_t tkipcntrmsr; /* TKIPCounterMeasuresInvoked */ - uint32_t tkipreplay; /* TKIPReplays */ - uint32_t ccmpfmterr; /* CCMPFormatErrors */ - uint32_t ccmpreplay; /* CCMPReplays */ - uint32_t ccmpundec; /* CCMPDecryptErrors */ - uint32_t fourwayfail; /* FourWayHandshakeFailures */ - uint32_t wepundec; /* dot11WEPUndecryptableCount */ - uint32_t wepicverr; /* dot11WEPICVErrorCount */ - uint32_t decsuccess; /* DecryptSuccessCount */ - uint32_t tkipicverr; /* TKIPICVErrorCount */ - uint32_t wepexcluded; /* dot11WEPExcludedCount */ - - uint32_t rxundec_mcst; /* dot11WEPUndecryptableCount */ - - /* WPA2 counters (see rxundec for DecryptFailureCount) */ - uint32_t tkipmicfaill_mcst; /* TKIPLocalMICFailures */ - uint32_t tkipcntrmsr_mcst; /* TKIPCounterMeasuresInvoked */ - uint32_t tkipreplay_mcst; /* TKIPReplays */ - uint32_t ccmpfmterr_mcst; /* CCMPFormatErrors */ - uint32_t ccmpreplay_mcst; /* CCMPReplays */ - uint32_t ccmpundec_mcst; /* CCMPDecryptErrors */ - uint32_t fourwayfail_mcst; /* FourWayHandshakeFailures */ - uint32_t wepundec_mcst; /* dot11WEPUndecryptableCount */ - uint32_t wepicverr_mcst; /* dot11WEPICVErrorCount */ - uint32_t decsuccess_mcst; /* DecryptSuccessCount */ - uint32_t tkipicverr_mcst; /* TKIPICVErrorCount */ - uint32_t wepexcluded_mcst; /* dot11WEPExcludedCount */ - - uint32_t txchanrej; /* Tx frames suppressed due to channel rejection */ - uint32_t txexptime; /* Tx frames suppressed due to timer expiration */ - uint32_t psmwds; /* Count PSM watchdogs */ - uint32_t phywatchdog; /* Count Phy watchdogs (triggered by ucode) */ - - /* MBSS counters, AP only */ - uint32_t prq_entries_handled; /* PRQ entries read in */ - uint32_t prq_undirected_entries; /* which were bcast bss & ssid */ - uint32_t prq_bad_entries; /* which could not be translated to info */ - uint32_t atim_suppress_count; /* TX suppressions on ATIM fifo */ - uint32_t bcn_template_not_ready; /* Template marked in use on send bcn ... */ - uint32_t bcn_template_not_ready_done; /* ...but "DMA done" interrupt rcvd */ - uint32_t late_tbtt_dpc; /* TBTT DPC did not happen in time */ - - /* per-rate receive stat counters */ - uint32_t rx1mbps; /* packets rx at 1Mbps */ - uint32_t rx2mbps; /* packets rx at 2Mbps */ - uint32_t rx5mbps5; /* packets rx at 5.5Mbps */ - uint32_t rx6mbps; /* packets rx at 6Mbps */ - uint32_t rx9mbps; /* packets rx at 9Mbps */ - uint32_t rx11mbps; /* packets rx at 11Mbps */ - uint32_t rx12mbps; /* packets rx at 12Mbps */ - uint32_t rx18mbps; /* packets rx at 18Mbps */ - uint32_t rx24mbps; /* packets rx at 24Mbps */ - uint32_t rx36mbps; /* packets rx at 36Mbps */ - uint32_t rx48mbps; /* packets rx at 48Mbps */ - uint32_t rx54mbps; /* packets rx at 54Mbps */ - uint32_t rx108mbps; /* packets rx at 108mbps */ - uint32_t rx162mbps; /* packets rx at 162mbps */ - uint32_t rx216mbps; /* packets rx at 216 mbps */ - uint32_t rx270mbps; /* packets rx at 270 mbps */ - uint32_t rx324mbps; /* packets rx at 324 mbps */ - uint32_t rx378mbps; /* packets rx at 378 mbps */ - uint32_t rx432mbps; /* packets rx at 432 mbps */ - uint32_t rx486mbps; /* packets rx at 486 mbps */ - uint32_t rx540mbps; /* packets rx at 540 mbps */ - - /* pkteng rx frame stats */ - uint32_t pktengrxducast; /* unicast frames rxed by the pkteng code */ - uint32_t pktengrxdmcast; /* multicast frames rxed by the pkteng code */ - - uint32_t rfdisable; /* count of radio disables */ - uint32_t bphy_rxcrsglitch; /* PHY count of bphy glitches */ - - uint32_t txmpdu_sgi; /* count for sgi transmit */ - uint32_t rxmpdu_sgi; /* count for sgi received */ - uint32_t txmpdu_stbc; /* count for stbc transmit */ - uint32_t rxmpdu_stbc; /* count for stbc received */ + uint16_t version; /* see definition of WL_CNT_T_VERSION */ + uint16_t length; /* length of entire structure */ + + /* transmit stat counters */ + uint32_t txframe; /* tx data frames */ + uint32_t txbyte; /* tx data bytes */ + uint32_t txretrans; /* tx mac retransmits */ + uint32_t txerror; /* tx data errors (derived: sum of others) */ + uint32_t txctl; /* tx management frames */ + uint32_t txprshort; /* tx short preamble frames */ + uint32_t txserr; /* tx status errors */ + uint32_t txnobuf; /* tx out of buffers errors */ + uint32_t txnoassoc; /* tx discard because we're not associated */ + uint32_t txrunt; /* tx runt frames */ + uint32_t txchit; /* tx header cache hit (fastpath) */ + uint32_t txcmiss; /* tx header cache miss (slowpath) */ + + /* transmit chip error counters */ + uint32_t txuflo; /* tx fifo underflows */ + uint32_t txphyerr; /* tx phy errors (indicated in tx status) */ + uint32_t txphycrs; /* PR8861/8963 counter */ + + /* receive stat counters */ + uint32_t rxframe; /* rx data frames */ + uint32_t rxbyte; /* rx data bytes */ + uint32_t rxerror; /* rx data errors (derived: sum of others) */ + uint32_t rxctl; /* rx management frames */ + uint32_t rxnobuf; /* rx out of buffers errors */ + uint32_t rxnondata; /* rx non data frames in the data channel errors */ + uint32_t rxbadds; /* rx bad DS errors */ + uint32_t rxbadcm; /* rx bad control or management frames */ + uint32_t rxfragerr; /* rx fragmentation errors */ + uint32_t rxrunt; /* rx runt frames */ + uint32_t rxgiant; /* rx giant frames */ + uint32_t rxnoscb; /* rx no scb error */ + uint32_t rxbadproto; /* rx invalid frames */ + uint32_t rxbadsrcmac; /* rx frames with Invalid Src Mac */ + uint32_t rxbadda; /* rx frames tossed for invalid da */ + uint32_t rxfilter; /* rx frames filtered out */ + + /* receive chip error counters */ + uint32_t rxoflo; /* rx fifo overflow errors */ + uint32_t rxuflo[NFIFO]; /* rx dma descriptor underflow errors */ + + uint32_t d11cnt_txrts_off; /* d11cnt txrts value when reset d11cnt */ + uint32_t d11cnt_rxcrc_off; /* d11cnt rxcrc value when reset d11cnt */ + uint32_t d11cnt_txnocts_off; /* d11cnt txnocts value when reset d11cnt */ + + /* misc counters */ + uint32_t dmade; /* tx/rx dma descriptor errors */ + uint32_t dmada; /* tx/rx dma data errors */ + uint32_t dmape; /* tx/rx dma descriptor protocol errors */ + uint32_t reset; /* reset count */ + uint32_t tbtt; /* cnts the TBTT int's */ + uint32_t txdmawar; /* # occurrences of PR15420 workaround */ + uint32_t pkt_callback_reg_fail; /* callbacks register failure */ + + /* MAC counters: 32-bit version of d11.h's macstat_t */ + uint32_t txallfrm; /* total number of frames sent, incl. Data, ACK, RTS, CTS, + * Control Management (includes retransmissions) + */ + uint32_t txrtsfrm; /* number of RTS sent out by the MAC */ + uint32_t txctsfrm; /* number of CTS sent out by the MAC */ + uint32_t txackfrm; /* number of ACK frames sent out */ + uint32_t txdnlfrm; /* Not used */ + uint32_t txbcnfrm; /* beacons transmitted */ + uint32_t txfunfl[8]; /* per-fifo tx underflows */ + uint32_t txtplunfl; /* Template underflows (mac was too slow to transmit ACK/CTS + * or BCN) + */ + uint32_t txphyerror; /* Transmit phy error, type of error is reported in tx-status for + * driver enqueued frames + */ + uint32_t rxfrmtoolong; /* Received frame longer than legal limit (2346 bytes) */ + uint32_t rxfrmtooshrt; /* Received frame did not contain enough bytes for its frame type */ + uint32_t rxinvmachdr; /* Either the protocol version != 0 or frame type not + * data/control/management + */ + uint32_t rxbadfcs; /* number of frames for which the CRC check failed in the MAC */ + uint32_t rxbadplcp; /* parity check of the PLCP header failed */ + uint32_t rxcrsglitch; /* PHY was able to correlate the preamble but not the header */ + uint32_t rxstrt; /* Number of received frames with a good PLCP + * (i.e. passing parity check) + */ + uint32_t rxdfrmucastmbss; /* Number of received DATA frames with good FCS and matching RA */ + uint32_t rxmfrmucastmbss; /* number of received mgmt frames with good FCS and matching RA */ + uint32_t rxcfrmucast; /* number of received CNTRL frames with good FCS and matching RA */ + uint32_t rxrtsucast; /* number of unicast RTS addressed to the MAC (good FCS) */ + uint32_t rxctsucast; /* number of unicast CTS addressed to the MAC (good FCS) */ + uint32_t rxackucast; /* number of ucast ACKS received (good FCS) */ + uint32_t rxdfrmocast; /* number of received DATA frames (good FCS and not matching RA) */ + uint32_t rxmfrmocast; /* number of received MGMT frames (good FCS and not matching RA) */ + uint32_t rxcfrmocast; /* number of received CNTRL frame (good FCS and not matching RA) */ + uint32_t rxrtsocast; /* number of received RTS not addressed to the MAC */ + uint32_t rxctsocast; /* number of received CTS not addressed to the MAC */ + uint32_t rxdfrmmcast; /* number of RX Data multicast frames received by the MAC */ + uint32_t rxmfrmmcast; /* number of RX Management multicast frames received by the MAC */ + uint32_t rxcfrmmcast; /* number of RX Control multicast frames received by the MAC + * (unlikely to see these) + */ + uint32_t rxbeaconmbss; /* beacons received from member of BSS */ + uint32_t rxdfrmucastobss; /* number of unicast frames addressed to the MAC from + * other BSS (WDS FRAME) + */ + uint32_t rxbeaconobss; /* beacons received from other BSS */ + uint32_t rxrsptmout; /* Number of response timeouts for transmitted frames + * expecting a response + */ + uint32_t bcntxcancl; /* transmit beacons canceled due to receipt of beacon (IBSS) */ + uint32_t rxf0ovfl; /* Number of receive fifo 0 overflows */ + uint32_t rxf1ovfl; /* Number of receive fifo 1 overflows (obsolete) */ + uint32_t rxf2ovfl; /* Number of receive fifo 2 overflows (obsolete) */ + uint32_t txsfovfl; /* Number of transmit status fifo overflows (obsolete) */ + uint32_t pmqovfl; /* Number of PMQ overflows */ + uint32_t rxcgprqfrm; /* Number of received Probe requests that made it into + * the PRQ fifo + */ + uint32_t rxcgprsqovfl; /* Rx Probe Request Que overflow in the AP */ + uint32_t txcgprsfail; /* Tx Probe Response Fail. AP sent probe response but did + * not get ACK + */ + uint32_t txcgprssuc; /* Tx Probe Response Success (ACK was received) */ + uint32_t prs_timeout; /* Number of probe requests that were dropped from the PRQ + * fifo because a probe response could not be sent out within + * the time limit defined in M_PRS_MAXTIME + */ + uint32_t rxnack; /* XXX Number of NACKS received (Afterburner) */ + uint32_t frmscons; /* XXX Number of frames completed without transmission because of an + * Afterburner re-queue + */ + uint32_t txnack; /* XXX Number of NACKs transmitted (Afterburner) */ + uint32_t txglitch_nack; /* obsolete */ + uint32_t txburst; /* obsolete */ + + /* 802.11 MIB counters, pp. 614 of 802.11 reaff doc. */ + uint32_t txfrag; /* dot11TransmittedFragmentCount */ + uint32_t txmulti; /* dot11MulticastTransmittedFrameCount */ + uint32_t txfail; /* dot11FailedCount */ + uint32_t txretry; /* dot11RetryCount */ + uint32_t txretrie; /* dot11MultipleRetryCount */ + uint32_t rxdup; /* dot11FrameduplicateCount */ + uint32_t txrts; /* dot11RTSSuccessCount */ + uint32_t txnocts; /* dot11RTSFailureCount */ + uint32_t txnoack; /* dot11ACKFailureCount */ + uint32_t rxfrag; /* dot11ReceivedFragmentCount */ + uint32_t rxmulti; /* dot11MulticastReceivedFrameCount */ + uint32_t rxcrc; /* dot11FCSErrorCount */ + uint32_t txfrmsnt; /* dot11TransmittedFrameCount (bogus MIB?) */ + uint32_t rxundec; /* dot11WEPUndecryptableCount */ + + /* WPA2 counters (see rxundec for DecryptFailureCount) */ + uint32_t tkipmicfaill; /* TKIPLocalMICFailures */ + uint32_t tkipcntrmsr; /* TKIPCounterMeasuresInvoked */ + uint32_t tkipreplay; /* TKIPReplays */ + uint32_t ccmpfmterr; /* CCMPFormatErrors */ + uint32_t ccmpreplay; /* CCMPReplays */ + uint32_t ccmpundec; /* CCMPDecryptErrors */ + uint32_t fourwayfail; /* FourWayHandshakeFailures */ + uint32_t wepundec; /* dot11WEPUndecryptableCount */ + uint32_t wepicverr; /* dot11WEPICVErrorCount */ + uint32_t decsuccess; /* DecryptSuccessCount */ + uint32_t tkipicverr; /* TKIPICVErrorCount */ + uint32_t wepexcluded; /* dot11WEPExcludedCount */ + + uint32_t rxundec_mcst; /* dot11WEPUndecryptableCount */ + + /* WPA2 counters (see rxundec for DecryptFailureCount) */ + uint32_t tkipmicfaill_mcst; /* TKIPLocalMICFailures */ + uint32_t tkipcntrmsr_mcst; /* TKIPCounterMeasuresInvoked */ + uint32_t tkipreplay_mcst; /* TKIPReplays */ + uint32_t ccmpfmterr_mcst; /* CCMPFormatErrors */ + uint32_t ccmpreplay_mcst; /* CCMPReplays */ + uint32_t ccmpundec_mcst; /* CCMPDecryptErrors */ + uint32_t fourwayfail_mcst; /* FourWayHandshakeFailures */ + uint32_t wepundec_mcst; /* dot11WEPUndecryptableCount */ + uint32_t wepicverr_mcst; /* dot11WEPICVErrorCount */ + uint32_t decsuccess_mcst; /* DecryptSuccessCount */ + uint32_t tkipicverr_mcst; /* TKIPICVErrorCount */ + uint32_t wepexcluded_mcst; /* dot11WEPExcludedCount */ + + uint32_t txchanrej; /* Tx frames suppressed due to channel rejection */ + uint32_t txexptime; /* Tx frames suppressed due to timer expiration */ + uint32_t psmwds; /* Count PSM watchdogs */ + uint32_t phywatchdog; /* Count Phy watchdogs (triggered by ucode) */ + + /* MBSS counters, AP only */ + uint32_t prq_entries_handled; /* PRQ entries read in */ + uint32_t prq_undirected_entries; /* which were bcast bss & ssid */ + uint32_t prq_bad_entries; /* which could not be translated to info */ + uint32_t atim_suppress_count; /* TX suppressions on ATIM fifo */ + uint32_t bcn_template_not_ready; /* Template marked in use on send bcn ... */ + uint32_t bcn_template_not_ready_done; /* ...but "DMA done" interrupt rcvd */ + uint32_t late_tbtt_dpc; /* TBTT DPC did not happen in time */ + + /* per-rate receive stat counters */ + uint32_t rx1mbps; /* packets rx at 1Mbps */ + uint32_t rx2mbps; /* packets rx at 2Mbps */ + uint32_t rx5mbps5; /* packets rx at 5.5Mbps */ + uint32_t rx6mbps; /* packets rx at 6Mbps */ + uint32_t rx9mbps; /* packets rx at 9Mbps */ + uint32_t rx11mbps; /* packets rx at 11Mbps */ + uint32_t rx12mbps; /* packets rx at 12Mbps */ + uint32_t rx18mbps; /* packets rx at 18Mbps */ + uint32_t rx24mbps; /* packets rx at 24Mbps */ + uint32_t rx36mbps; /* packets rx at 36Mbps */ + uint32_t rx48mbps; /* packets rx at 48Mbps */ + uint32_t rx54mbps; /* packets rx at 54Mbps */ + uint32_t rx108mbps; /* packets rx at 108mbps */ + uint32_t rx162mbps; /* packets rx at 162mbps */ + uint32_t rx216mbps; /* packets rx at 216 mbps */ + uint32_t rx270mbps; /* packets rx at 270 mbps */ + uint32_t rx324mbps; /* packets rx at 324 mbps */ + uint32_t rx378mbps; /* packets rx at 378 mbps */ + uint32_t rx432mbps; /* packets rx at 432 mbps */ + uint32_t rx486mbps; /* packets rx at 486 mbps */ + uint32_t rx540mbps; /* packets rx at 540 mbps */ + + /* pkteng rx frame stats */ + uint32_t pktengrxducast; /* unicast frames rxed by the pkteng code */ + uint32_t pktengrxdmcast; /* multicast frames rxed by the pkteng code */ + + uint32_t rfdisable; /* count of radio disables */ + uint32_t bphy_rxcrsglitch; /* PHY count of bphy glitches */ + + uint32_t txmpdu_sgi; /* count for sgi transmit */ + uint32_t rxmpdu_sgi; /* count for sgi received */ + uint32_t txmpdu_stbc; /* count for stbc transmit */ + uint32_t rxmpdu_stbc; /* count for stbc received */ } wl_cnt_ver_six_t; -typedef struct { - uint16_t version; /* see definition of WL_CNT_T_VERSION */ - uint16_t length; /* length of entire structure */ - - /* transmit stat counters */ - uint32_t txframe; /* tx data frames */ - uint32_t txbyte; /* tx data bytes */ - uint32_t txretrans; /* tx mac retransmits */ - uint32_t txerror; /* tx data errors (derived: sum of others) */ - uint32_t txctl; /* tx management frames */ - uint32_t txprshort; /* tx short preamble frames */ - uint32_t txserr; /* tx status errors */ - uint32_t txnobuf; /* tx out of buffers errors */ - uint32_t txnoassoc; /* tx discard because we're not associated */ - uint32_t txrunt; /* tx runt frames */ - uint32_t txchit; /* tx header cache hit (fastpath) */ - uint32_t txcmiss; /* tx header cache miss (slowpath) */ - - /* transmit chip error counters */ - uint32_t txuflo; /* tx fifo underflows */ - uint32_t txphyerr; /* tx phy errors (indicated in tx status) */ - uint32_t txphycrs; /* PR8861/8963 counter */ - - /* receive stat counters */ - uint32_t rxframe; /* rx data frames */ - uint32_t rxbyte; /* rx data bytes */ - uint32_t rxerror; /* rx data errors (derived: sum of others) */ - uint32_t rxctl; /* rx management frames */ - uint32_t rxnobuf; /* rx out of buffers errors */ - uint32_t rxnondata; /* rx non data frames in the data channel errors */ - uint32_t rxbadds; /* rx bad DS errors */ - uint32_t rxbadcm; /* rx bad control or management frames */ - uint32_t rxfragerr; /* rx fragmentation errors */ - uint32_t rxrunt; /* rx runt frames */ - uint32_t rxgiant; /* rx giant frames */ - uint32_t rxnoscb; /* rx no scb error */ - uint32_t rxbadproto; /* rx invalid frames */ - uint32_t rxbadsrcmac; /* rx frames with Invalid Src Mac */ - uint32_t rxbadda; /* rx frames tossed for invalid da */ - uint32_t rxfilter; /* rx frames filtered out */ - - /* receive chip error counters */ - uint32_t rxoflo; /* rx fifo overflow errors */ - uint32_t rxuflo[NFIFO]; /* rx dma descriptor underflow errors */ - - uint32_t d11cnt_txrts_off; /* d11cnt txrts value when reset d11cnt */ - uint32_t d11cnt_rxcrc_off; /* d11cnt rxcrc value when reset d11cnt */ - uint32_t d11cnt_txnocts_off; /* d11cnt txnocts value when reset d11cnt */ - - /* misc counters */ - uint32_t dmade; /* tx/rx dma descriptor errors */ - uint32_t dmada; /* tx/rx dma data errors */ - uint32_t dmape; /* tx/rx dma descriptor protocol errors */ - uint32_t reset; /* reset count */ - uint32_t tbtt; /* cnts the TBTT int's */ - uint32_t txdmawar; /* # occurrences of PR15420 workaround */ - uint32_t pkt_callback_reg_fail; /* callbacks register failure */ - - /* MAC counters: 32-bit version of d11.h's macstat_t */ - uint32_t txallfrm; /* total number of frames sent, incl. Data, ACK, RTS, CTS, - * Control Management (includes retransmissions) - */ - uint32_t txrtsfrm; /* number of RTS sent out by the MAC */ - uint32_t txctsfrm; /* number of CTS sent out by the MAC */ - uint32_t txackfrm; /* number of ACK frames sent out */ - uint32_t txdnlfrm; /* Not used */ - uint32_t txbcnfrm; /* beacons transmitted */ - uint32_t txfunfl[8]; /* per-fifo tx underflows */ - uint32_t txtplunfl; /* Template underflows (mac was too slow to transmit ACK/CTS - * or BCN) - */ - uint32_t txphyerror; /* Transmit phy error, type of error is reported in tx-status for - * driver enqueued frames - */ - uint32_t rxfrmtoolong; /* Received frame longer than legal limit (2346 bytes) */ - uint32_t rxfrmtooshrt; /* Received frame did not contain enough bytes for its frame type */ - uint32_t rxinvmachdr; /* Either the protocol version != 0 or frame type not - * data/control/management - */ - uint32_t rxbadfcs; /* number of frames for which the CRC check failed in the MAC */ - uint32_t rxbadplcp; /* parity check of the PLCP header failed */ - uint32_t rxcrsglitch; /* PHY was able to correlate the preamble but not the header */ - uint32_t rxstrt; /* Number of received frames with a good PLCP - * (i.e. passing parity check) - */ - uint32_t rxdfrmucastmbss; /* Number of received DATA frames with good FCS and matching RA */ - uint32_t rxmfrmucastmbss; /* number of received mgmt frames with good FCS and matching RA */ - uint32_t rxcfrmucast; /* number of received CNTRL frames with good FCS and matching RA */ - uint32_t rxrtsucast; /* number of unicast RTS addressed to the MAC (good FCS) */ - uint32_t rxctsucast; /* number of unicast CTS addressed to the MAC (good FCS) */ - uint32_t rxackucast; /* number of ucast ACKS received (good FCS) */ - uint32_t rxdfrmocast; /* number of received DATA frames (good FCS and not matching RA) */ - uint32_t rxmfrmocast; /* number of received MGMT frames (good FCS and not matching RA) */ - uint32_t rxcfrmocast; /* number of received CNTRL frame (good FCS and not matching RA) */ - uint32_t rxrtsocast; /* number of received RTS not addressed to the MAC */ - uint32_t rxctsocast; /* number of received CTS not addressed to the MAC */ - uint32_t rxdfrmmcast; /* number of RX Data multicast frames received by the MAC */ - uint32_t rxmfrmmcast; /* number of RX Management multicast frames received by the MAC */ - uint32_t rxcfrmmcast; /* number of RX Control multicast frames received by the MAC - * (unlikely to see these) - */ - uint32_t rxbeaconmbss; /* beacons received from member of BSS */ - uint32_t rxdfrmucastobss; /* number of unicast frames addressed to the MAC from - * other BSS (WDS FRAME) - */ - uint32_t rxbeaconobss; /* beacons received from other BSS */ - uint32_t rxrsptmout; /* Number of response timeouts for transmitted frames - * expecting a response - */ - uint32_t bcntxcancl; /* transmit beacons canceled due to receipt of beacon (IBSS) */ - uint32_t rxf0ovfl; /* Number of receive fifo 0 overflows */ - uint32_t rxf1ovfl; /* Number of receive fifo 1 overflows (obsolete) */ - uint32_t rxf2ovfl; /* Number of receive fifo 2 overflows (obsolete) */ - uint32_t txsfovfl; /* Number of transmit status fifo overflows (obsolete) */ - uint32_t pmqovfl; /* Number of PMQ overflows */ - uint32_t rxcgprqfrm; /* Number of received Probe requests that made it into - * the PRQ fifo - */ - uint32_t rxcgprsqovfl; /* Rx Probe Request Que overflow in the AP */ - uint32_t txcgprsfail; /* Tx Probe Response Fail. AP sent probe response but did - * not get ACK - */ - uint32_t txcgprssuc; /* Tx Probe Response Success (ACK was received) */ - uint32_t prs_timeout; /* Number of probe requests that were dropped from the PRQ - * fifo because a probe response could not be sent out within - * the time limit defined in M_PRS_MAXTIME - */ - uint32_t rxnack; /* obsolete */ - uint32_t frmscons; /* obsolete */ - uint32_t txnack; /* obsolete */ - uint32_t txglitch_nack; /* obsolete */ - uint32_t txburst; /* obsolete */ - - /* 802.11 MIB counters, pp. 614 of 802.11 reaff doc. */ - uint32_t txfrag; /* dot11TransmittedFragmentCount */ - uint32_t txmulti; /* dot11MulticastTransmittedFrameCount */ - uint32_t txfail; /* dot11FailedCount */ - uint32_t txretry; /* dot11RetryCount */ - uint32_t txretrie; /* dot11MultipleRetryCount */ - uint32_t rxdup; /* dot11FrameduplicateCount */ - uint32_t txrts; /* dot11RTSSuccessCount */ - uint32_t txnocts; /* dot11RTSFailureCount */ - uint32_t txnoack; /* dot11ACKFailureCount */ - uint32_t rxfrag; /* dot11ReceivedFragmentCount */ - uint32_t rxmulti; /* dot11MulticastReceivedFrameCount */ - uint32_t rxcrc; /* dot11FCSErrorCount */ - uint32_t txfrmsnt; /* dot11TransmittedFrameCount (bogus MIB?) */ - uint32_t rxundec; /* dot11WEPUndecryptableCount */ - - /* WPA2 counters (see rxundec for DecryptFailureCount) */ - uint32_t tkipmicfaill; /* TKIPLocalMICFailures */ - uint32_t tkipcntrmsr; /* TKIPCounterMeasuresInvoked */ - uint32_t tkipreplay; /* TKIPReplays */ - uint32_t ccmpfmterr; /* CCMPFormatErrors */ - uint32_t ccmpreplay; /* CCMPReplays */ - uint32_t ccmpundec; /* CCMPDecryptErrors */ - uint32_t fourwayfail; /* FourWayHandshakeFailures */ - uint32_t wepundec; /* dot11WEPUndecryptableCount */ - uint32_t wepicverr; /* dot11WEPICVErrorCount */ - uint32_t decsuccess; /* DecryptSuccessCount */ - uint32_t tkipicverr; /* TKIPICVErrorCount */ - uint32_t wepexcluded; /* dot11WEPExcludedCount */ - - uint32_t txchanrej; /* Tx frames suppressed due to channel rejection */ - uint32_t psmwds; /* Count PSM watchdogs */ - uint32_t phywatchdog; /* Count Phy watchdogs (triggered by ucode) */ - - /* MBSS counters, AP only */ - uint32_t prq_entries_handled; /* PRQ entries read in */ - uint32_t prq_undirected_entries; /* which were bcast bss & ssid */ - uint32_t prq_bad_entries; /* which could not be translated to info */ - uint32_t atim_suppress_count; /* TX suppressions on ATIM fifo */ - uint32_t bcn_template_not_ready; /* Template marked in use on send bcn ... */ - uint32_t bcn_template_not_ready_done; /* ...but "DMA done" interrupt rcvd */ - uint32_t late_tbtt_dpc; /* TBTT DPC did not happen in time */ - - /* per-rate receive stat counters */ - uint32_t rx1mbps; /* packets rx at 1Mbps */ - uint32_t rx2mbps; /* packets rx at 2Mbps */ - uint32_t rx5mbps5; /* packets rx at 5.5Mbps */ - uint32_t rx6mbps; /* packets rx at 6Mbps */ - uint32_t rx9mbps; /* packets rx at 9Mbps */ - uint32_t rx11mbps; /* packets rx at 11Mbps */ - uint32_t rx12mbps; /* packets rx at 12Mbps */ - uint32_t rx18mbps; /* packets rx at 18Mbps */ - uint32_t rx24mbps; /* packets rx at 24Mbps */ - uint32_t rx36mbps; /* packets rx at 36Mbps */ - uint32_t rx48mbps; /* packets rx at 48Mbps */ - uint32_t rx54mbps; /* packets rx at 54Mbps */ - uint32_t rx108mbps; /* packets rx at 108mbps */ - uint32_t rx162mbps; /* packets rx at 162mbps */ - uint32_t rx216mbps; /* packets rx at 216 mbps */ - uint32_t rx270mbps; /* packets rx at 270 mbps */ - uint32_t rx324mbps; /* packets rx at 324 mbps */ - uint32_t rx378mbps; /* packets rx at 378 mbps */ - uint32_t rx432mbps; /* packets rx at 432 mbps */ - uint32_t rx486mbps; /* packets rx at 486 mbps */ - uint32_t rx540mbps; /* packets rx at 540 mbps */ - - /* pkteng rx frame stats */ - uint32_t pktengrxducast; /* unicast frames rxed by the pkteng code */ - uint32_t pktengrxdmcast; /* multicast frames rxed by the pkteng code */ - - uint32_t rfdisable; /* count of radio disables */ - uint32_t bphy_rxcrsglitch; /* PHY count of bphy glitches */ - - uint32_t txexptime; /* Tx frames suppressed due to timer expiration */ - - uint32_t txmpdu_sgi; /* count for sgi transmit */ - uint32_t rxmpdu_sgi; /* count for sgi received */ - uint32_t txmpdu_stbc; /* count for stbc transmit */ - uint32_t rxmpdu_stbc; /* count for stbc received */ - - uint32_t rxundec_mcst; /* dot11WEPUndecryptableCount */ - - /* WPA2 counters (see rxundec for DecryptFailureCount) */ - uint32_t tkipmicfaill_mcst; /* TKIPLocalMICFailures */ - uint32_t tkipcntrmsr_mcst; /* TKIPCounterMeasuresInvoked */ - uint32_t tkipreplay_mcst; /* TKIPReplays */ - uint32_t ccmpfmterr_mcst; /* CCMPFormatErrors */ - uint32_t ccmpreplay_mcst; /* CCMPReplays */ - uint32_t ccmpundec_mcst; /* CCMPDecryptErrors */ - uint32_t fourwayfail_mcst; /* FourWayHandshakeFailures */ - uint32_t wepundec_mcst; /* dot11WEPUndecryptableCount */ - uint32_t wepicverr_mcst; /* dot11WEPICVErrorCount */ - uint32_t decsuccess_mcst; /* DecryptSuccessCount */ - uint32_t tkipicverr_mcst; /* TKIPICVErrorCount */ - uint32_t wepexcluded_mcst; /* dot11WEPExcludedCount */ - - uint32_t dma_hang; /* count for stbc received */ - } wl_cnt_ver_seven_t; - - -typedef struct { - uint16_t version; /* see definition of WL_CNT_T_VERSION */ - uint16_t length; /* length of entire structure */ - - /* transmit stat counters */ - uint32_t txframe; /* tx data frames */ - uint32_t txbyte; /* tx data bytes */ - uint32_t txretrans; /* tx mac retransmits */ - uint32_t txerror; /* tx data errors (derived: sum of others) */ - uint32_t txctl; /* tx management frames */ - uint32_t txprshort; /* tx short preamble frames */ - uint32_t txserr; /* tx status errors */ - uint32_t txnobuf; /* tx out of buffers errors */ - uint32_t txnoassoc; /* tx discard because we're not associated */ - uint32_t txrunt; /* tx runt frames */ - uint32_t txchit; /* tx header cache hit (fastpath) */ - uint32_t txcmiss; /* tx header cache miss (slowpath) */ - - /* transmit chip error counters */ - uint32_t txuflo; /* tx fifo underflows */ - uint32_t txphyerr; /* tx phy errors (indicated in tx status) */ - uint32_t txphycrs; /* PR8861/8963 counter */ - - /* receive stat counters */ - uint32_t rxframe; /* rx data frames */ - uint32_t rxbyte; /* rx data bytes */ - uint32_t rxerror; /* rx data errors (derived: sum of others) */ - uint32_t rxctl; /* rx management frames */ - uint32_t rxnobuf; /* rx out of buffers errors */ - uint32_t rxnondata; /* rx non data frames in the data channel errors */ - uint32_t rxbadds; /* rx bad DS errors */ - uint32_t rxbadcm; /* rx bad control or management frames */ - uint32_t rxfragerr; /* rx fragmentation errors */ - uint32_t rxrunt; /* rx runt frames */ - uint32_t rxgiant; /* rx giant frames */ - uint32_t rxnoscb; /* rx no scb error */ - uint32_t rxbadproto; /* rx invalid frames */ - uint32_t rxbadsrcmac; /* rx frames with Invalid Src Mac */ - uint32_t rxbadda; /* rx frames tossed for invalid da */ - uint32_t rxfilter; /* rx frames filtered out */ - - /* receive chip error counters */ - uint32_t rxoflo; /* rx fifo overflow errors */ - uint32_t rxuflo[NFIFO]; /* rx dma descriptor underflow errors */ - - uint32_t d11cnt_txrts_off; /* d11cnt txrts value when reset d11cnt */ - uint32_t d11cnt_rxcrc_off; /* d11cnt rxcrc value when reset d11cnt */ - uint32_t d11cnt_txnocts_off; /* d11cnt txnocts value when reset d11cnt */ - - /* misc counters */ - uint32_t dmade; /* tx/rx dma descriptor errors */ - uint32_t dmada; /* tx/rx dma data errors */ - uint32_t dmape; /* tx/rx dma descriptor protocol errors */ - uint32_t reset; /* reset count */ - uint32_t tbtt; /* cnts the TBTT int's */ - uint32_t txdmawar; /* # occurrences of PR15420 workaround */ - uint32_t pkt_callback_reg_fail; /* callbacks register failure */ - - /* MAC counters: 32-bit version of d11.h's macstat_t */ - uint32_t txallfrm; /* total number of frames sent, incl. Data, ACK, RTS, CTS, - * Control Management (includes retransmissions) - */ - uint32_t txrtsfrm; /* number of RTS sent out by the MAC */ - uint32_t txctsfrm; /* number of CTS sent out by the MAC */ - uint32_t txackfrm; /* number of ACK frames sent out */ - uint32_t txdnlfrm; /* Not used */ - uint32_t txbcnfrm; /* beacons transmitted */ - uint32_t txfunfl[6]; /* per-fifo tx underflows */ - uint32_t rxtoolate; /* receive too late */ - uint32_t txfbw; /* transmit at fallback bw (dynamic bw) */ - uint32_t txtplunfl; /* Template underflows (mac was too slow to transmit ACK/CTS - * or BCN) - */ - uint32_t txphyerror; /* Transmit phy error, type of error is reported in tx-status for - * driver enqueued frames - */ - uint32_t rxfrmtoolong; /* Received frame longer than legal limit (2346 bytes) */ - uint32_t rxfrmtooshrt; /* Received frame did not contain enough bytes for its frame type */ - uint32_t rxinvmachdr; /* Either the protocol version != 0 or frame type not - * data/control/management - */ - uint32_t rxbadfcs; /* number of frames for which the CRC check failed in the MAC */ - uint32_t rxbadplcp; /* parity check of the PLCP header failed */ - uint32_t rxcrsglitch; /* PHY was able to correlate the preamble but not the header */ - uint32_t rxstrt; /* Number of received frames with a good PLCP - * (i.e. passing parity check) - */ - uint32_t rxdfrmucastmbss; /* Number of received DATA frames with good FCS and matching RA */ - uint32_t rxmfrmucastmbss; /* number of received mgmt frames with good FCS and matching RA */ - uint32_t rxcfrmucast; /* number of received CNTRL frames with good FCS and matching RA */ - uint32_t rxrtsucast; /* number of unicast RTS addressed to the MAC (good FCS) */ - uint32_t rxctsucast; /* number of unicast CTS addressed to the MAC (good FCS) */ - uint32_t rxackucast; /* number of ucast ACKS received (good FCS) */ - uint32_t rxdfrmocast; /* number of received DATA frames (good FCS and not matching RA) */ - uint32_t rxmfrmocast; /* number of received MGMT frames (good FCS and not matching RA) */ - uint32_t rxcfrmocast; /* number of received CNTRL frame (good FCS and not matching RA) */ - uint32_t rxrtsocast; /* number of received RTS not addressed to the MAC */ - uint32_t rxctsocast; /* number of received CTS not addressed to the MAC */ - uint32_t rxdfrmmcast; /* number of RX Data multicast frames received by the MAC */ - uint32_t rxmfrmmcast; /* number of RX Management multicast frames received by the MAC */ - uint32_t rxcfrmmcast; /* number of RX Control multicast frames received by the MAC - * (unlikely to see these) - */ - uint32_t rxbeaconmbss; /* beacons received from member of BSS */ - uint32_t rxdfrmucastobss; /* number of unicast frames addressed to the MAC from - * other BSS (WDS FRAME) - */ - uint32_t rxbeaconobss; /* beacons received from other BSS */ - uint32_t rxrsptmout; /* Number of response timeouts for transmitted frames - * expecting a response - */ - uint32_t bcntxcancl; /* transmit beacons canceled due to receipt of beacon (IBSS) */ - uint32_t rxf0ovfl; /* Number of receive fifo 0 overflows */ - uint32_t rxf1ovfl; /* Number of receive fifo 1 overflows (obsolete) */ - uint32_t rxf2ovfl; /* Number of receive fifo 2 overflows (obsolete) */ - uint32_t txsfovfl; /* Number of transmit status fifo overflows (obsolete) */ - uint32_t pmqovfl; /* Number of PMQ overflows */ - uint32_t rxcgprqfrm; /* Number of received Probe requests that made it into - * the PRQ fifo - */ - uint32_t rxcgprsqovfl; /* Rx Probe Request Que overflow in the AP */ - uint32_t txcgprsfail; /* Tx Probe Response Fail. AP sent probe response but did - * not get ACK - */ - uint32_t txcgprssuc; /* Tx Probe Response Success (ACK was received) */ - uint32_t prs_timeout; /* Number of probe requests that were dropped from the PRQ - * fifo because a probe response could not be sent out within - * the time limit defined in M_PRS_MAXTIME - */ - uint32_t rxnack; /* obsolete */ - uint32_t frmscons; /* obsolete */ - uint32_t txnack; /* obsolete */ - uint32_t rxback; /* blockack rxcnt */ - uint32_t txback; /* blockack txcnt */ - - /* 802.11 MIB counters, pp. 614 of 802.11 reaff doc. */ - uint32_t txfrag; /* dot11TransmittedFragmentCount */ - uint32_t txmulti; /* dot11MulticastTransmittedFrameCount */ - uint32_t txfail; /* dot11FailedCount */ - uint32_t txretry; /* dot11RetryCount */ - uint32_t txretrie; /* dot11MultipleRetryCount */ - uint32_t rxdup; /* dot11FrameduplicateCount */ - uint32_t txrts; /* dot11RTSSuccessCount */ - uint32_t txnocts; /* dot11RTSFailureCount */ - uint32_t txnoack; /* dot11ACKFailureCount */ - uint32_t rxfrag; /* dot11ReceivedFragmentCount */ - uint32_t rxmulti; /* dot11MulticastReceivedFrameCount */ - uint32_t rxcrc; /* dot11FCSErrorCount */ - uint32_t txfrmsnt; /* dot11TransmittedFrameCount (bogus MIB?) */ - uint32_t rxundec; /* dot11WEPUndecryptableCount */ - - /* WPA2 counters (see rxundec for DecryptFailureCount) */ - uint32_t tkipmicfaill; /* TKIPLocalMICFailures */ - uint32_t tkipcntrmsr; /* TKIPCounterMeasuresInvoked */ - uint32_t tkipreplay; /* TKIPReplays */ - uint32_t ccmpfmterr; /* CCMPFormatErrors */ - uint32_t ccmpreplay; /* CCMPReplays */ - uint32_t ccmpundec; /* CCMPDecryptErrors */ - uint32_t fourwayfail; /* FourWayHandshakeFailures */ - uint32_t wepundec; /* dot11WEPUndecryptableCount */ - uint32_t wepicverr; /* dot11WEPICVErrorCount */ - uint32_t decsuccess; /* DecryptSuccessCount */ - uint32_t tkipicverr; /* TKIPICVErrorCount */ - uint32_t wepexcluded; /* dot11WEPExcludedCount */ - - uint32_t txchanrej; /* Tx frames suppressed due to channel rejection */ - uint32_t psmwds; /* Count PSM watchdogs */ - uint32_t phywatchdog; /* Count Phy watchdogs (triggered by ucode) */ - - /* MBSS counters, AP only */ - uint32_t prq_entries_handled; /* PRQ entries read in */ - uint32_t prq_undirected_entries; /* which were bcast bss & ssid */ - uint32_t prq_bad_entries; /* which could not be translated to info */ - uint32_t atim_suppress_count; /* TX suppressions on ATIM fifo */ - uint32_t bcn_template_not_ready; /* Template marked in use on send bcn ... */ - uint32_t bcn_template_not_ready_done; /* ...but "DMA done" interrupt rcvd */ - uint32_t late_tbtt_dpc; /* TBTT DPC did not happen in time */ - - /* per-rate receive stat counters */ - uint32_t rx1mbps; /* packets rx at 1Mbps */ - uint32_t rx2mbps; /* packets rx at 2Mbps */ - uint32_t rx5mbps5; /* packets rx at 5.5Mbps */ - uint32_t rx6mbps; /* packets rx at 6Mbps */ - uint32_t rx9mbps; /* packets rx at 9Mbps */ - uint32_t rx11mbps; /* packets rx at 11Mbps */ - uint32_t rx12mbps; /* packets rx at 12Mbps */ - uint32_t rx18mbps; /* packets rx at 18Mbps */ - uint32_t rx24mbps; /* packets rx at 24Mbps */ - uint32_t rx36mbps; /* packets rx at 36Mbps */ - uint32_t rx48mbps; /* packets rx at 48Mbps */ - uint32_t rx54mbps; /* packets rx at 54Mbps */ - uint32_t rx108mbps; /* packets rx at 108mbps */ - uint32_t rx162mbps; /* packets rx at 162mbps */ - uint32_t rx216mbps; /* packets rx at 216 mbps */ - uint32_t rx270mbps; /* packets rx at 270 mbps */ - uint32_t rx324mbps; /* packets rx at 324 mbps */ - uint32_t rx378mbps; /* packets rx at 378 mbps */ - uint32_t rx432mbps; /* packets rx at 432 mbps */ - uint32_t rx486mbps; /* packets rx at 486 mbps */ - uint32_t rx540mbps; /* packets rx at 540 mbps */ - - /* pkteng rx frame stats */ - uint32_t pktengrxducast; /* unicast frames rxed by the pkteng code */ - uint32_t pktengrxdmcast; /* multicast frames rxed by the pkteng code */ - - uint32_t rfdisable; /* count of radio disables */ - uint32_t bphy_rxcrsglitch; /* PHY count of bphy glitches */ - uint32_t bphy_badplcp; - - uint32_t txexptime; /* Tx frames suppressed due to timer expiration */ - - uint32_t txmpdu_sgi; /* count for sgi transmit */ - uint32_t rxmpdu_sgi; /* count for sgi received */ - uint32_t txmpdu_stbc; /* count for stbc transmit */ - uint32_t rxmpdu_stbc; /* count for stbc received */ - - uint32_t rxundec_mcst; /* dot11WEPUndecryptableCount */ - - /* WPA2 counters (see rxundec for DecryptFailureCount) */ - uint32_t tkipmicfaill_mcst; /* TKIPLocalMICFailures */ - uint32_t tkipcntrmsr_mcst; /* TKIPCounterMeasuresInvoked */ - uint32_t tkipreplay_mcst; /* TKIPReplays */ - uint32_t ccmpfmterr_mcst; /* CCMPFormatErrors */ - uint32_t ccmpreplay_mcst; /* CCMPReplays */ - uint32_t ccmpundec_mcst; /* CCMPDecryptErrors */ - uint32_t fourwayfail_mcst; /* FourWayHandshakeFailures */ - uint32_t wepundec_mcst; /* dot11WEPUndecryptableCount */ - uint32_t wepicverr_mcst; /* dot11WEPICVErrorCount */ - uint32_t decsuccess_mcst; /* DecryptSuccessCount */ - uint32_t tkipicverr_mcst; /* TKIPICVErrorCount */ - uint32_t wepexcluded_mcst; /* dot11WEPExcludedCount */ - - uint32_t dma_hang; /* count for dma hang */ - uint32_t reinit; /* count for reinit */ - - uint32_t pstatxucast; /* count of ucast frames xmitted on all psta assoc */ - uint32_t pstatxnoassoc; /* count of txnoassoc frames xmitted on all psta assoc */ - uint32_t pstarxucast; /* count of ucast frames received on all psta assoc */ - uint32_t pstarxbcmc; /* count of bcmc frames received on all psta */ - uint32_t pstatxbcmc; /* count of bcmc frames transmitted on all psta */ - - uint32_t cso_passthrough; /* hw cso required but passthrough */ - uint32_t cso_normal; /* hw cso hdr for normal process */ - uint32_t chained; /* number of frames chained */ - uint32_t chainedsz1; /* number of chain size 1 frames */ - uint32_t unchained; /* number of frames not chained */ - uint32_t maxchainsz; /* max chain size so far */ - uint32_t currchainsz; /* current chain size */ - - uint32_t rxdrop20s; /* drop secondary cnt */ +typedef struct +{ + uint16_t version; /* see definition of WL_CNT_T_VERSION */ + uint16_t length; /* length of entire structure */ + + /* transmit stat counters */ + uint32_t txframe; /* tx data frames */ + uint32_t txbyte; /* tx data bytes */ + uint32_t txretrans; /* tx mac retransmits */ + uint32_t txerror; /* tx data errors (derived: sum of others) */ + uint32_t txctl; /* tx management frames */ + uint32_t txprshort; /* tx short preamble frames */ + uint32_t txserr; /* tx status errors */ + uint32_t txnobuf; /* tx out of buffers errors */ + uint32_t txnoassoc; /* tx discard because we're not associated */ + uint32_t txrunt; /* tx runt frames */ + uint32_t txchit; /* tx header cache hit (fastpath) */ + uint32_t txcmiss; /* tx header cache miss (slowpath) */ + + /* transmit chip error counters */ + uint32_t txuflo; /* tx fifo underflows */ + uint32_t txphyerr; /* tx phy errors (indicated in tx status) */ + uint32_t txphycrs; /* PR8861/8963 counter */ + + /* receive stat counters */ + uint32_t rxframe; /* rx data frames */ + uint32_t rxbyte; /* rx data bytes */ + uint32_t rxerror; /* rx data errors (derived: sum of others) */ + uint32_t rxctl; /* rx management frames */ + uint32_t rxnobuf; /* rx out of buffers errors */ + uint32_t rxnondata; /* rx non data frames in the data channel errors */ + uint32_t rxbadds; /* rx bad DS errors */ + uint32_t rxbadcm; /* rx bad control or management frames */ + uint32_t rxfragerr; /* rx fragmentation errors */ + uint32_t rxrunt; /* rx runt frames */ + uint32_t rxgiant; /* rx giant frames */ + uint32_t rxnoscb; /* rx no scb error */ + uint32_t rxbadproto; /* rx invalid frames */ + uint32_t rxbadsrcmac; /* rx frames with Invalid Src Mac */ + uint32_t rxbadda; /* rx frames tossed for invalid da */ + uint32_t rxfilter; /* rx frames filtered out */ + + /* receive chip error counters */ + uint32_t rxoflo; /* rx fifo overflow errors */ + uint32_t rxuflo[NFIFO]; /* rx dma descriptor underflow errors */ + + uint32_t d11cnt_txrts_off; /* d11cnt txrts value when reset d11cnt */ + uint32_t d11cnt_rxcrc_off; /* d11cnt rxcrc value when reset d11cnt */ + uint32_t d11cnt_txnocts_off; /* d11cnt txnocts value when reset d11cnt */ + + /* misc counters */ + uint32_t dmade; /* tx/rx dma descriptor errors */ + uint32_t dmada; /* tx/rx dma data errors */ + uint32_t dmape; /* tx/rx dma descriptor protocol errors */ + uint32_t reset; /* reset count */ + uint32_t tbtt; /* cnts the TBTT int's */ + uint32_t txdmawar; /* # occurrences of PR15420 workaround */ + uint32_t pkt_callback_reg_fail; /* callbacks register failure */ + + /* MAC counters: 32-bit version of d11.h's macstat_t */ + uint32_t txallfrm; /* total number of frames sent, incl. Data, ACK, RTS, CTS, + * Control Management (includes retransmissions) + */ + uint32_t txrtsfrm; /* number of RTS sent out by the MAC */ + uint32_t txctsfrm; /* number of CTS sent out by the MAC */ + uint32_t txackfrm; /* number of ACK frames sent out */ + uint32_t txdnlfrm; /* Not used */ + uint32_t txbcnfrm; /* beacons transmitted */ + uint32_t txfunfl[8]; /* per-fifo tx underflows */ + uint32_t txtplunfl; /* Template underflows (mac was too slow to transmit ACK/CTS + * or BCN) + */ + uint32_t txphyerror; /* Transmit phy error, type of error is reported in tx-status for + * driver enqueued frames + */ + uint32_t rxfrmtoolong; /* Received frame longer than legal limit (2346 bytes) */ + uint32_t rxfrmtooshrt; /* Received frame did not contain enough bytes for its frame type */ + uint32_t rxinvmachdr; /* Either the protocol version != 0 or frame type not + * data/control/management + */ + uint32_t rxbadfcs; /* number of frames for which the CRC check failed in the MAC */ + uint32_t rxbadplcp; /* parity check of the PLCP header failed */ + uint32_t rxcrsglitch; /* PHY was able to correlate the preamble but not the header */ + uint32_t rxstrt; /* Number of received frames with a good PLCP + * (i.e. passing parity check) + */ + uint32_t rxdfrmucastmbss; /* Number of received DATA frames with good FCS and matching RA */ + uint32_t rxmfrmucastmbss; /* number of received mgmt frames with good FCS and matching RA */ + uint32_t rxcfrmucast; /* number of received CNTRL frames with good FCS and matching RA */ + uint32_t rxrtsucast; /* number of unicast RTS addressed to the MAC (good FCS) */ + uint32_t rxctsucast; /* number of unicast CTS addressed to the MAC (good FCS) */ + uint32_t rxackucast; /* number of ucast ACKS received (good FCS) */ + uint32_t rxdfrmocast; /* number of received DATA frames (good FCS and not matching RA) */ + uint32_t rxmfrmocast; /* number of received MGMT frames (good FCS and not matching RA) */ + uint32_t rxcfrmocast; /* number of received CNTRL frame (good FCS and not matching RA) */ + uint32_t rxrtsocast; /* number of received RTS not addressed to the MAC */ + uint32_t rxctsocast; /* number of received CTS not addressed to the MAC */ + uint32_t rxdfrmmcast; /* number of RX Data multicast frames received by the MAC */ + uint32_t rxmfrmmcast; /* number of RX Management multicast frames received by the MAC */ + uint32_t rxcfrmmcast; /* number of RX Control multicast frames received by the MAC + * (unlikely to see these) + */ + uint32_t rxbeaconmbss; /* beacons received from member of BSS */ + uint32_t rxdfrmucastobss; /* number of unicast frames addressed to the MAC from + * other BSS (WDS FRAME) + */ + uint32_t rxbeaconobss; /* beacons received from other BSS */ + uint32_t rxrsptmout; /* Number of response timeouts for transmitted frames + * expecting a response + */ + uint32_t bcntxcancl; /* transmit beacons canceled due to receipt of beacon (IBSS) */ + uint32_t rxf0ovfl; /* Number of receive fifo 0 overflows */ + uint32_t rxf1ovfl; /* Number of receive fifo 1 overflows (obsolete) */ + uint32_t rxf2ovfl; /* Number of receive fifo 2 overflows (obsolete) */ + uint32_t txsfovfl; /* Number of transmit status fifo overflows (obsolete) */ + uint32_t pmqovfl; /* Number of PMQ overflows */ + uint32_t rxcgprqfrm; /* Number of received Probe requests that made it into + * the PRQ fifo + */ + uint32_t rxcgprsqovfl; /* Rx Probe Request Que overflow in the AP */ + uint32_t txcgprsfail; /* Tx Probe Response Fail. AP sent probe response but did + * not get ACK + */ + uint32_t txcgprssuc; /* Tx Probe Response Success (ACK was received) */ + uint32_t prs_timeout; /* Number of probe requests that were dropped from the PRQ + * fifo because a probe response could not be sent out within + * the time limit defined in M_PRS_MAXTIME + */ + uint32_t rxnack; /* obsolete */ + uint32_t frmscons; /* obsolete */ + uint32_t txnack; /* obsolete */ + uint32_t txglitch_nack; /* obsolete */ + uint32_t txburst; /* obsolete */ + + /* 802.11 MIB counters, pp. 614 of 802.11 reaff doc. */ + uint32_t txfrag; /* dot11TransmittedFragmentCount */ + uint32_t txmulti; /* dot11MulticastTransmittedFrameCount */ + uint32_t txfail; /* dot11FailedCount */ + uint32_t txretry; /* dot11RetryCount */ + uint32_t txretrie; /* dot11MultipleRetryCount */ + uint32_t rxdup; /* dot11FrameduplicateCount */ + uint32_t txrts; /* dot11RTSSuccessCount */ + uint32_t txnocts; /* dot11RTSFailureCount */ + uint32_t txnoack; /* dot11ACKFailureCount */ + uint32_t rxfrag; /* dot11ReceivedFragmentCount */ + uint32_t rxmulti; /* dot11MulticastReceivedFrameCount */ + uint32_t rxcrc; /* dot11FCSErrorCount */ + uint32_t txfrmsnt; /* dot11TransmittedFrameCount (bogus MIB?) */ + uint32_t rxundec; /* dot11WEPUndecryptableCount */ + + /* WPA2 counters (see rxundec for DecryptFailureCount) */ + uint32_t tkipmicfaill; /* TKIPLocalMICFailures */ + uint32_t tkipcntrmsr; /* TKIPCounterMeasuresInvoked */ + uint32_t tkipreplay; /* TKIPReplays */ + uint32_t ccmpfmterr; /* CCMPFormatErrors */ + uint32_t ccmpreplay; /* CCMPReplays */ + uint32_t ccmpundec; /* CCMPDecryptErrors */ + uint32_t fourwayfail; /* FourWayHandshakeFailures */ + uint32_t wepundec; /* dot11WEPUndecryptableCount */ + uint32_t wepicverr; /* dot11WEPICVErrorCount */ + uint32_t decsuccess; /* DecryptSuccessCount */ + uint32_t tkipicverr; /* TKIPICVErrorCount */ + uint32_t wepexcluded; /* dot11WEPExcludedCount */ + + uint32_t txchanrej; /* Tx frames suppressed due to channel rejection */ + uint32_t psmwds; /* Count PSM watchdogs */ + uint32_t phywatchdog; /* Count Phy watchdogs (triggered by ucode) */ + + /* MBSS counters, AP only */ + uint32_t prq_entries_handled; /* PRQ entries read in */ + uint32_t prq_undirected_entries; /* which were bcast bss & ssid */ + uint32_t prq_bad_entries; /* which could not be translated to info */ + uint32_t atim_suppress_count; /* TX suppressions on ATIM fifo */ + uint32_t bcn_template_not_ready; /* Template marked in use on send bcn ... */ + uint32_t bcn_template_not_ready_done; /* ...but "DMA done" interrupt rcvd */ + uint32_t late_tbtt_dpc; /* TBTT DPC did not happen in time */ + + /* per-rate receive stat counters */ + uint32_t rx1mbps; /* packets rx at 1Mbps */ + uint32_t rx2mbps; /* packets rx at 2Mbps */ + uint32_t rx5mbps5; /* packets rx at 5.5Mbps */ + uint32_t rx6mbps; /* packets rx at 6Mbps */ + uint32_t rx9mbps; /* packets rx at 9Mbps */ + uint32_t rx11mbps; /* packets rx at 11Mbps */ + uint32_t rx12mbps; /* packets rx at 12Mbps */ + uint32_t rx18mbps; /* packets rx at 18Mbps */ + uint32_t rx24mbps; /* packets rx at 24Mbps */ + uint32_t rx36mbps; /* packets rx at 36Mbps */ + uint32_t rx48mbps; /* packets rx at 48Mbps */ + uint32_t rx54mbps; /* packets rx at 54Mbps */ + uint32_t rx108mbps; /* packets rx at 108mbps */ + uint32_t rx162mbps; /* packets rx at 162mbps */ + uint32_t rx216mbps; /* packets rx at 216 mbps */ + uint32_t rx270mbps; /* packets rx at 270 mbps */ + uint32_t rx324mbps; /* packets rx at 324 mbps */ + uint32_t rx378mbps; /* packets rx at 378 mbps */ + uint32_t rx432mbps; /* packets rx at 432 mbps */ + uint32_t rx486mbps; /* packets rx at 486 mbps */ + uint32_t rx540mbps; /* packets rx at 540 mbps */ + + /* pkteng rx frame stats */ + uint32_t pktengrxducast; /* unicast frames rxed by the pkteng code */ + uint32_t pktengrxdmcast; /* multicast frames rxed by the pkteng code */ + + uint32_t rfdisable; /* count of radio disables */ + uint32_t bphy_rxcrsglitch; /* PHY count of bphy glitches */ + + uint32_t txexptime; /* Tx frames suppressed due to timer expiration */ + + uint32_t txmpdu_sgi; /* count for sgi transmit */ + uint32_t rxmpdu_sgi; /* count for sgi received */ + uint32_t txmpdu_stbc; /* count for stbc transmit */ + uint32_t rxmpdu_stbc; /* count for stbc received */ + + uint32_t rxundec_mcst; /* dot11WEPUndecryptableCount */ + + /* WPA2 counters (see rxundec for DecryptFailureCount) */ + uint32_t tkipmicfaill_mcst; /* TKIPLocalMICFailures */ + uint32_t tkipcntrmsr_mcst; /* TKIPCounterMeasuresInvoked */ + uint32_t tkipreplay_mcst; /* TKIPReplays */ + uint32_t ccmpfmterr_mcst; /* CCMPFormatErrors */ + uint32_t ccmpreplay_mcst; /* CCMPReplays */ + uint32_t ccmpundec_mcst; /* CCMPDecryptErrors */ + uint32_t fourwayfail_mcst; /* FourWayHandshakeFailures */ + uint32_t wepundec_mcst; /* dot11WEPUndecryptableCount */ + uint32_t wepicverr_mcst; /* dot11WEPICVErrorCount */ + uint32_t decsuccess_mcst; /* DecryptSuccessCount */ + uint32_t tkipicverr_mcst; /* TKIPICVErrorCount */ + uint32_t wepexcluded_mcst; /* dot11WEPExcludedCount */ + + uint32_t dma_hang; /* count for stbc received */ +} wl_cnt_ver_seven_t; + +typedef struct +{ + uint16_t version; /* see definition of WL_CNT_T_VERSION */ + uint16_t length; /* length of entire structure */ + + /* transmit stat counters */ + uint32_t txframe; /* tx data frames */ + uint32_t txbyte; /* tx data bytes */ + uint32_t txretrans; /* tx mac retransmits */ + uint32_t txerror; /* tx data errors (derived: sum of others) */ + uint32_t txctl; /* tx management frames */ + uint32_t txprshort; /* tx short preamble frames */ + uint32_t txserr; /* tx status errors */ + uint32_t txnobuf; /* tx out of buffers errors */ + uint32_t txnoassoc; /* tx discard because we're not associated */ + uint32_t txrunt; /* tx runt frames */ + uint32_t txchit; /* tx header cache hit (fastpath) */ + uint32_t txcmiss; /* tx header cache miss (slowpath) */ + + /* transmit chip error counters */ + uint32_t txuflo; /* tx fifo underflows */ + uint32_t txphyerr; /* tx phy errors (indicated in tx status) */ + uint32_t txphycrs; /* PR8861/8963 counter */ + + /* receive stat counters */ + uint32_t rxframe; /* rx data frames */ + uint32_t rxbyte; /* rx data bytes */ + uint32_t rxerror; /* rx data errors (derived: sum of others) */ + uint32_t rxctl; /* rx management frames */ + uint32_t rxnobuf; /* rx out of buffers errors */ + uint32_t rxnondata; /* rx non data frames in the data channel errors */ + uint32_t rxbadds; /* rx bad DS errors */ + uint32_t rxbadcm; /* rx bad control or management frames */ + uint32_t rxfragerr; /* rx fragmentation errors */ + uint32_t rxrunt; /* rx runt frames */ + uint32_t rxgiant; /* rx giant frames */ + uint32_t rxnoscb; /* rx no scb error */ + uint32_t rxbadproto; /* rx invalid frames */ + uint32_t rxbadsrcmac; /* rx frames with Invalid Src Mac */ + uint32_t rxbadda; /* rx frames tossed for invalid da */ + uint32_t rxfilter; /* rx frames filtered out */ + + /* receive chip error counters */ + uint32_t rxoflo; /* rx fifo overflow errors */ + uint32_t rxuflo[NFIFO]; /* rx dma descriptor underflow errors */ + + uint32_t d11cnt_txrts_off; /* d11cnt txrts value when reset d11cnt */ + uint32_t d11cnt_rxcrc_off; /* d11cnt rxcrc value when reset d11cnt */ + uint32_t d11cnt_txnocts_off; /* d11cnt txnocts value when reset d11cnt */ + + /* misc counters */ + uint32_t dmade; /* tx/rx dma descriptor errors */ + uint32_t dmada; /* tx/rx dma data errors */ + uint32_t dmape; /* tx/rx dma descriptor protocol errors */ + uint32_t reset; /* reset count */ + uint32_t tbtt; /* cnts the TBTT int's */ + uint32_t txdmawar; /* # occurrences of PR15420 workaround */ + uint32_t pkt_callback_reg_fail; /* callbacks register failure */ + + /* MAC counters: 32-bit version of d11.h's macstat_t */ + uint32_t txallfrm; /* total number of frames sent, incl. Data, ACK, RTS, CTS, + * Control Management (includes retransmissions) + */ + uint32_t txrtsfrm; /* number of RTS sent out by the MAC */ + uint32_t txctsfrm; /* number of CTS sent out by the MAC */ + uint32_t txackfrm; /* number of ACK frames sent out */ + uint32_t txdnlfrm; /* Not used */ + uint32_t txbcnfrm; /* beacons transmitted */ + uint32_t txfunfl[6]; /* per-fifo tx underflows */ + uint32_t rxtoolate; /* receive too late */ + uint32_t txfbw; /* transmit at fallback bw (dynamic bw) */ + uint32_t txtplunfl; /* Template underflows (mac was too slow to transmit ACK/CTS + * or BCN) + */ + uint32_t txphyerror; /* Transmit phy error, type of error is reported in tx-status for + * driver enqueued frames + */ + uint32_t rxfrmtoolong; /* Received frame longer than legal limit (2346 bytes) */ + uint32_t rxfrmtooshrt; /* Received frame did not contain enough bytes for its frame type */ + uint32_t rxinvmachdr; /* Either the protocol version != 0 or frame type not + * data/control/management + */ + uint32_t rxbadfcs; /* number of frames for which the CRC check failed in the MAC */ + uint32_t rxbadplcp; /* parity check of the PLCP header failed */ + uint32_t rxcrsglitch; /* PHY was able to correlate the preamble but not the header */ + uint32_t rxstrt; /* Number of received frames with a good PLCP + * (i.e. passing parity check) + */ + uint32_t rxdfrmucastmbss; /* Number of received DATA frames with good FCS and matching RA */ + uint32_t rxmfrmucastmbss; /* number of received mgmt frames with good FCS and matching RA */ + uint32_t rxcfrmucast; /* number of received CNTRL frames with good FCS and matching RA */ + uint32_t rxrtsucast; /* number of unicast RTS addressed to the MAC (good FCS) */ + uint32_t rxctsucast; /* number of unicast CTS addressed to the MAC (good FCS) */ + uint32_t rxackucast; /* number of ucast ACKS received (good FCS) */ + uint32_t rxdfrmocast; /* number of received DATA frames (good FCS and not matching RA) */ + uint32_t rxmfrmocast; /* number of received MGMT frames (good FCS and not matching RA) */ + uint32_t rxcfrmocast; /* number of received CNTRL frame (good FCS and not matching RA) */ + uint32_t rxrtsocast; /* number of received RTS not addressed to the MAC */ + uint32_t rxctsocast; /* number of received CTS not addressed to the MAC */ + uint32_t rxdfrmmcast; /* number of RX Data multicast frames received by the MAC */ + uint32_t rxmfrmmcast; /* number of RX Management multicast frames received by the MAC */ + uint32_t rxcfrmmcast; /* number of RX Control multicast frames received by the MAC + * (unlikely to see these) + */ + uint32_t rxbeaconmbss; /* beacons received from member of BSS */ + uint32_t rxdfrmucastobss; /* number of unicast frames addressed to the MAC from + * other BSS (WDS FRAME) + */ + uint32_t rxbeaconobss; /* beacons received from other BSS */ + uint32_t rxrsptmout; /* Number of response timeouts for transmitted frames + * expecting a response + */ + uint32_t bcntxcancl; /* transmit beacons canceled due to receipt of beacon (IBSS) */ + uint32_t rxf0ovfl; /* Number of receive fifo 0 overflows */ + uint32_t rxf1ovfl; /* Number of receive fifo 1 overflows (obsolete) */ + uint32_t rxf2ovfl; /* Number of receive fifo 2 overflows (obsolete) */ + uint32_t txsfovfl; /* Number of transmit status fifo overflows (obsolete) */ + uint32_t pmqovfl; /* Number of PMQ overflows */ + uint32_t rxcgprqfrm; /* Number of received Probe requests that made it into + * the PRQ fifo + */ + uint32_t rxcgprsqovfl; /* Rx Probe Request Que overflow in the AP */ + uint32_t txcgprsfail; /* Tx Probe Response Fail. AP sent probe response but did + * not get ACK + */ + uint32_t txcgprssuc; /* Tx Probe Response Success (ACK was received) */ + uint32_t prs_timeout; /* Number of probe requests that were dropped from the PRQ + * fifo because a probe response could not be sent out within + * the time limit defined in M_PRS_MAXTIME + */ + uint32_t rxnack; /* obsolete */ + uint32_t frmscons; /* obsolete */ + uint32_t txnack; /* obsolete */ + uint32_t rxback; /* blockack rxcnt */ + uint32_t txback; /* blockack txcnt */ + + /* 802.11 MIB counters, pp. 614 of 802.11 reaff doc. */ + uint32_t txfrag; /* dot11TransmittedFragmentCount */ + uint32_t txmulti; /* dot11MulticastTransmittedFrameCount */ + uint32_t txfail; /* dot11FailedCount */ + uint32_t txretry; /* dot11RetryCount */ + uint32_t txretrie; /* dot11MultipleRetryCount */ + uint32_t rxdup; /* dot11FrameduplicateCount */ + uint32_t txrts; /* dot11RTSSuccessCount */ + uint32_t txnocts; /* dot11RTSFailureCount */ + uint32_t txnoack; /* dot11ACKFailureCount */ + uint32_t rxfrag; /* dot11ReceivedFragmentCount */ + uint32_t rxmulti; /* dot11MulticastReceivedFrameCount */ + uint32_t rxcrc; /* dot11FCSErrorCount */ + uint32_t txfrmsnt; /* dot11TransmittedFrameCount (bogus MIB?) */ + uint32_t rxundec; /* dot11WEPUndecryptableCount */ + + /* WPA2 counters (see rxundec for DecryptFailureCount) */ + uint32_t tkipmicfaill; /* TKIPLocalMICFailures */ + uint32_t tkipcntrmsr; /* TKIPCounterMeasuresInvoked */ + uint32_t tkipreplay; /* TKIPReplays */ + uint32_t ccmpfmterr; /* CCMPFormatErrors */ + uint32_t ccmpreplay; /* CCMPReplays */ + uint32_t ccmpundec; /* CCMPDecryptErrors */ + uint32_t fourwayfail; /* FourWayHandshakeFailures */ + uint32_t wepundec; /* dot11WEPUndecryptableCount */ + uint32_t wepicverr; /* dot11WEPICVErrorCount */ + uint32_t decsuccess; /* DecryptSuccessCount */ + uint32_t tkipicverr; /* TKIPICVErrorCount */ + uint32_t wepexcluded; /* dot11WEPExcludedCount */ + + uint32_t txchanrej; /* Tx frames suppressed due to channel rejection */ + uint32_t psmwds; /* Count PSM watchdogs */ + uint32_t phywatchdog; /* Count Phy watchdogs (triggered by ucode) */ + + /* MBSS counters, AP only */ + uint32_t prq_entries_handled; /* PRQ entries read in */ + uint32_t prq_undirected_entries; /* which were bcast bss & ssid */ + uint32_t prq_bad_entries; /* which could not be translated to info */ + uint32_t atim_suppress_count; /* TX suppressions on ATIM fifo */ + uint32_t bcn_template_not_ready; /* Template marked in use on send bcn ... */ + uint32_t bcn_template_not_ready_done; /* ...but "DMA done" interrupt rcvd */ + uint32_t late_tbtt_dpc; /* TBTT DPC did not happen in time */ + + /* per-rate receive stat counters */ + uint32_t rx1mbps; /* packets rx at 1Mbps */ + uint32_t rx2mbps; /* packets rx at 2Mbps */ + uint32_t rx5mbps5; /* packets rx at 5.5Mbps */ + uint32_t rx6mbps; /* packets rx at 6Mbps */ + uint32_t rx9mbps; /* packets rx at 9Mbps */ + uint32_t rx11mbps; /* packets rx at 11Mbps */ + uint32_t rx12mbps; /* packets rx at 12Mbps */ + uint32_t rx18mbps; /* packets rx at 18Mbps */ + uint32_t rx24mbps; /* packets rx at 24Mbps */ + uint32_t rx36mbps; /* packets rx at 36Mbps */ + uint32_t rx48mbps; /* packets rx at 48Mbps */ + uint32_t rx54mbps; /* packets rx at 54Mbps */ + uint32_t rx108mbps; /* packets rx at 108mbps */ + uint32_t rx162mbps; /* packets rx at 162mbps */ + uint32_t rx216mbps; /* packets rx at 216 mbps */ + uint32_t rx270mbps; /* packets rx at 270 mbps */ + uint32_t rx324mbps; /* packets rx at 324 mbps */ + uint32_t rx378mbps; /* packets rx at 378 mbps */ + uint32_t rx432mbps; /* packets rx at 432 mbps */ + uint32_t rx486mbps; /* packets rx at 486 mbps */ + uint32_t rx540mbps; /* packets rx at 540 mbps */ + + /* pkteng rx frame stats */ + uint32_t pktengrxducast; /* unicast frames rxed by the pkteng code */ + uint32_t pktengrxdmcast; /* multicast frames rxed by the pkteng code */ + + uint32_t rfdisable; /* count of radio disables */ + uint32_t bphy_rxcrsglitch; /* PHY count of bphy glitches */ + uint32_t bphy_badplcp; + + uint32_t txexptime; /* Tx frames suppressed due to timer expiration */ + + uint32_t txmpdu_sgi; /* count for sgi transmit */ + uint32_t rxmpdu_sgi; /* count for sgi received */ + uint32_t txmpdu_stbc; /* count for stbc transmit */ + uint32_t rxmpdu_stbc; /* count for stbc received */ + + uint32_t rxundec_mcst; /* dot11WEPUndecryptableCount */ + + /* WPA2 counters (see rxundec for DecryptFailureCount) */ + uint32_t tkipmicfaill_mcst; /* TKIPLocalMICFailures */ + uint32_t tkipcntrmsr_mcst; /* TKIPCounterMeasuresInvoked */ + uint32_t tkipreplay_mcst; /* TKIPReplays */ + uint32_t ccmpfmterr_mcst; /* CCMPFormatErrors */ + uint32_t ccmpreplay_mcst; /* CCMPReplays */ + uint32_t ccmpundec_mcst; /* CCMPDecryptErrors */ + uint32_t fourwayfail_mcst; /* FourWayHandshakeFailures */ + uint32_t wepundec_mcst; /* dot11WEPUndecryptableCount */ + uint32_t wepicverr_mcst; /* dot11WEPICVErrorCount */ + uint32_t decsuccess_mcst; /* DecryptSuccessCount */ + uint32_t tkipicverr_mcst; /* TKIPICVErrorCount */ + uint32_t wepexcluded_mcst; /* dot11WEPExcludedCount */ + + uint32_t dma_hang; /* count for dma hang */ + uint32_t reinit; /* count for reinit */ + + uint32_t pstatxucast; /* count of ucast frames xmitted on all psta assoc */ + uint32_t pstatxnoassoc; /* count of txnoassoc frames xmitted on all psta assoc */ + uint32_t pstarxucast; /* count of ucast frames received on all psta assoc */ + uint32_t pstarxbcmc; /* count of bcmc frames received on all psta */ + uint32_t pstatxbcmc; /* count of bcmc frames transmitted on all psta */ + + uint32_t cso_passthrough; /* hw cso required but passthrough */ + uint32_t cso_normal; /* hw cso hdr for normal process */ + uint32_t chained; /* number of frames chained */ + uint32_t chainedsz1; /* number of chain size 1 frames */ + uint32_t unchained; /* number of frames not chained */ + uint32_t maxchainsz; /* max chain size so far */ + uint32_t currchainsz; /* current chain size */ + + uint32_t rxdrop20s; /* drop secondary cnt */ } wl_cnt_ver_eight_t; typedef struct { - uint16_t version; - uint16_t length; - uint32_t rxampdu_sgi; - uint32_t rxampdu_stbc; - uint32_t rxmpdu_sgi; - uint32_t rxmpdu_stbc; - uint32_t rxmcs0_40M; - uint32_t rxmcs1_40M; - uint32_t rxmcs2_40M; - uint32_t rxmcs3_40M; - uint32_t rxmcs4_40M; - uint32_t rxmcs5_40M; - uint32_t rxmcs6_40M; - uint32_t rxmcs7_40M; - uint32_t rxmcs32_40M; - uint32_t txfrmsnt_20Mlo; - uint32_t txfrmsnt_20Mup; - uint32_t txfrmsnt_40M; - uint32_t rx_20ul; + uint16_t version; + uint16_t length; + uint32_t rxampdu_sgi; + uint32_t rxampdu_stbc; + uint32_t rxmpdu_sgi; + uint32_t rxmpdu_stbc; + uint32_t rxmcs0_40M; + uint32_t rxmcs1_40M; + uint32_t rxmcs2_40M; + uint32_t rxmcs3_40M; + uint32_t rxmcs4_40M; + uint32_t rxmcs5_40M; + uint32_t rxmcs6_40M; + uint32_t rxmcs7_40M; + uint32_t rxmcs32_40M; + uint32_t txfrmsnt_20Mlo; + uint32_t txfrmsnt_20Mup; + uint32_t txfrmsnt_40M; + uint32_t rx_20ul; } wl_cnt_ext_t; #define WL_RXDIV_STATS_T_VERSION 1 typedef struct { - uint16_t version; - uint16_t length; - uint32_t rxant[4]; + uint16_t version; + uint16_t length; + uint32_t rxant[4]; } wl_rxdiv_stats_t; #define WL_DELTA_STATS_T_VERSION 1 typedef struct { - uint16_t version; - uint16_t length; - uint32_t txframe; - uint32_t txbyte; - uint32_t txretrans; - uint32_t txfail; - uint32_t rxframe; - uint32_t rxbyte; - uint32_t rx1mbps; - uint32_t rx2mbps; - uint32_t rx5mbps5; - uint32_t rx6mbps; - uint32_t rx9mbps; - uint32_t rx11mbps; - uint32_t rx12mbps; - uint32_t rx18mbps; - uint32_t rx24mbps; - uint32_t rx36mbps; - uint32_t rx48mbps; - uint32_t rx54mbps; - uint32_t rx108mbps; - uint32_t rx162mbps; - uint32_t rx216mbps; - uint32_t rx270mbps; - uint32_t rx324mbps; - uint32_t rx378mbps; - uint32_t rx432mbps; - uint32_t rx486mbps; - uint32_t rx540mbps; + uint16_t version; + uint16_t length; + uint32_t txframe; + uint32_t txbyte; + uint32_t txretrans; + uint32_t txfail; + uint32_t rxframe; + uint32_t rxbyte; + uint32_t rx1mbps; + uint32_t rx2mbps; + uint32_t rx5mbps5; + uint32_t rx6mbps; + uint32_t rx9mbps; + uint32_t rx11mbps; + uint32_t rx12mbps; + uint32_t rx18mbps; + uint32_t rx24mbps; + uint32_t rx36mbps; + uint32_t rx48mbps; + uint32_t rx54mbps; + uint32_t rx108mbps; + uint32_t rx162mbps; + uint32_t rx216mbps; + uint32_t rx270mbps; + uint32_t rx324mbps; + uint32_t rx378mbps; + uint32_t rx432mbps; + uint32_t rx486mbps; + uint32_t rx540mbps; } wl_delta_stats_t; #define WL_WME_CNT_VERSION 1 typedef struct { - uint32_t packets; - uint32_t bytes; + uint32_t packets; + uint32_t bytes; } wl_traffic_stats_t; #define AC_COUNT 4 typedef struct { - uint16_t version; - uint16_t length; - wl_traffic_stats_t tx[AC_COUNT]; - wl_traffic_stats_t tx_failed[AC_COUNT]; - wl_traffic_stats_t rx[AC_COUNT]; - wl_traffic_stats_t rx_failed[AC_COUNT]; - wl_traffic_stats_t forward[AC_COUNT]; - wl_traffic_stats_t tx_expired[AC_COUNT]; + uint16_t version; + uint16_t length; + wl_traffic_stats_t tx[AC_COUNT]; + wl_traffic_stats_t tx_failed[AC_COUNT]; + wl_traffic_stats_t rx[AC_COUNT]; + wl_traffic_stats_t rx_failed[AC_COUNT]; + wl_traffic_stats_t forward[AC_COUNT]; + wl_traffic_stats_t tx_expired[AC_COUNT]; } wl_wme_cnt_t; -typedef struct wl_mkeep_alive_pkt { - uint16_t version; /* Version for mkeep_alive */ - uint16_t length; /* length of fixed parameters */ - uint32_t period_msec; /* repeat interval msecs */ - uint16_t len_bytes; /* packet length */ - uint8_t keep_alive_id; /* 0 - 3 for N = 4 */ - uint8_t data[1]; /* Packet data */ +typedef struct wl_mkeep_alive_pkt +{ + uint16_t version; /* Version for mkeep_alive */ + uint16_t length; /* length of fixed parameters */ + uint32_t period_msec; /* repeat interval msecs */ + uint16_t len_bytes; /* packet length */ + uint8_t keep_alive_id; /* 0 - 3 for N = 4 */ + uint8_t data[1]; /* Packet data */ } wl_mkeep_alive_pkt_t; #define WL_MKEEP_ALIVE_VERSION 1 @@ -2204,32 +2210,32 @@ typedef struct wl_mkeep_alive_pkt { struct ampdu_tid_control { - uint8_t tid; - uint8_t enable; + uint8_t tid; + uint8_t enable; }; struct wl_msglevel2 { - uint32_t low; - uint32_t high; + uint32_t low; + uint32_t high; }; struct ampdu_ea_tid { - struct ether_addr ea; - uint8_t tid; + struct ether_addr ea; + uint8_t tid; }; struct ampdu_retry_tid { - uint8_t tid; - uint8_t retry; + uint8_t tid; + uint8_t retry; }; struct ampdu_ba_sizes { - uint8_t ba_tx_wsize; - uint8_t ba_rx_wsize; + uint8_t ba_tx_wsize; + uint8_t ba_rx_wsize; }; #define DPT_DISCOVERY_MANUAL 0x01 @@ -2245,9 +2251,9 @@ struct ampdu_ba_sizes #define DPT_MANUAL_EP_DELETE 3 typedef struct dpt_iovar { - struct ether_addr ea; - uint8_t mode; - uint32_t pad; + struct ether_addr ea; + uint8_t mode; + uint32_t pad; } dpt_iovar_t; #define DPT_STATUS_ACTIVE 0x01 #define DPT_STATUS_AES 0x02 @@ -2255,64 +2261,64 @@ typedef struct dpt_iovar #define DPT_FNAME_LEN 48 typedef struct dpt_status { - uint8_t status; - uint8_t fnlen; - uint8_t name[DPT_FNAME_LEN]; - uint32_t rssi; - sta_info_t sta; + uint8_t status; + uint8_t fnlen; + uint8_t name[DPT_FNAME_LEN]; + uint32_t rssi; + sta_info_t sta; } dpt_status_t; typedef struct dpt_list { - uint32_t num; - dpt_status_t status[1]; + uint32_t num; + dpt_status_t status[1]; } dpt_list_t; typedef struct dpt_fname { - uint8_t len; - uint8_t name[DPT_FNAME_LEN]; + uint8_t len; + uint8_t name[DPT_FNAME_LEN]; } dpt_fname_t; #define BDD_FNAME_LEN 32 typedef struct bdd_fname { - uint8_t len; - uint8_t name[BDD_FNAME_LEN]; + uint8_t len; + uint8_t name[BDD_FNAME_LEN]; } bdd_fname_t; struct ts_list { - int32_t count; - struct tsinfo_arg tsinfo[1]; + int32_t count; + struct tsinfo_arg tsinfo[1]; }; typedef struct tspec_arg { - uint16_t version; - uint16_t length; - uint32_t flag; - struct tsinfo_arg tsinfo; - uint16_t nom_msdu_size; - uint16_t max_msdu_size; - uint32_t min_srv_interval; - uint32_t max_srv_interval; - uint32_t inactivity_interval; - uint32_t suspension_interval; - uint32_t srv_start_time; - uint32_t min_data_rate; - uint32_t mean_data_rate; - uint32_t peak_data_rate; - uint32_t max_burst_size; - uint32_t delay_bound; - uint32_t min_phy_rate; - uint16_t surplus_bw; - uint16_t medium_time; - uint8_t dialog_token; + uint16_t version; + uint16_t length; + uint32_t flag; + struct tsinfo_arg tsinfo; + uint16_t nom_msdu_size; + uint16_t max_msdu_size; + uint32_t min_srv_interval; + uint32_t max_srv_interval; + uint32_t inactivity_interval; + uint32_t suspension_interval; + uint32_t srv_start_time; + uint32_t min_data_rate; + uint32_t mean_data_rate; + uint32_t peak_data_rate; + uint32_t max_burst_size; + uint32_t delay_bound; + uint32_t min_phy_rate; + uint16_t surplus_bw; + uint16_t medium_time; + uint8_t dialog_token; } tspec_arg_t; typedef struct tspec_per_sta_arg { - struct ether_addr ea; - struct tspec_arg ts; + struct ether_addr ea; + struct tspec_arg ts; } tspec_per_sta_arg_t; typedef struct wme_max_bandwidth { - uint32_t ac[AC_COUNT]; + uint32_t ac[AC_COUNT]; } wme_max_bandwidth_t; #define WL_WME_MBW_PARAMS_IO_BYTES (sizeof(wme_max_bandwidth_t)) #define TSPEC_ARG_VERSION 2 @@ -2328,15 +2334,15 @@ typedef struct wme_max_bandwidth #define WL_LIFETIME_MAX 0xFFFF typedef struct wl_lifetime { - uint32_t ac; - uint32_t lifetime; + uint32_t ac; + uint32_t lifetime; } wl_lifetime_t; typedef struct wl_chan_switch { - uint8_t mode; - uint8_t count; - wl_chanspec_t chspec; - uint8_t reg; + uint8_t mode; + uint8_t count; + wl_chanspec_t chspec; + uint8_t reg; } wl_chan_switch_t; #define WLC_ROAM_TRIGGER_DEFAULT 0 @@ -2346,7 +2352,7 @@ typedef struct wl_chan_switch enum { - PFN_LIST_ORDER, PFN_RSSI + PFN_LIST_ORDER, PFN_RSSI }; #define SORT_CRITERIA_BIT 0 @@ -2363,21 +2369,21 @@ enum typedef struct wl_pfn_param { - int32_t version; - int32_t scan_freq; - int32_t lost_network_timeout; - int16_t flags; - int16_t rssi_margin; + int32_t version; + int32_t scan_freq; + int32_t lost_network_timeout; + int16_t flags; + int16_t rssi_margin; } wl_pfn_param_t; typedef struct wl_pfn { - wlc_ssid_t ssid; - int32_t bss_type; - int32_t infra; - int32_t auth; - uint32_t wpa_auth; - int32_t wsec; + wlc_ssid_t ssid; + int32_t bss_type; + int32_t infra; + int32_t auth; + uint32_t wpa_auth; + int32_t wsec; } wl_pfn_t; #define TOE_TX_CSUM_OL 0x00000001 @@ -2388,25 +2394,25 @@ typedef struct wl_pfn struct toe_ol_stats_t { - uint32_t tx_summed; - uint32_t tx_iph_fill; - uint32_t tx_tcp_fill; - uint32_t tx_udp_fill; - uint32_t tx_icmp_fill; - uint32_t rx_iph_good; - uint32_t rx_iph_bad; - uint32_t rx_tcp_good; - uint32_t rx_tcp_bad; - uint32_t rx_udp_good; - uint32_t rx_udp_bad; - uint32_t rx_icmp_good; - uint32_t rx_icmp_bad; - uint32_t tx_tcp_errinj; - uint32_t tx_udp_errinj; - uint32_t tx_icmp_errinj; - uint32_t rx_tcp_errinj; - uint32_t rx_udp_errinj; - uint32_t rx_icmp_errinj; + uint32_t tx_summed; + uint32_t tx_iph_fill; + uint32_t tx_tcp_fill; + uint32_t tx_udp_fill; + uint32_t tx_icmp_fill; + uint32_t rx_iph_good; + uint32_t rx_iph_bad; + uint32_t rx_tcp_good; + uint32_t rx_tcp_bad; + uint32_t rx_udp_good; + uint32_t rx_udp_bad; + uint32_t rx_icmp_good; + uint32_t rx_icmp_bad; + uint32_t tx_tcp_errinj; + uint32_t tx_udp_errinj; + uint32_t tx_icmp_errinj; + uint32_t rx_tcp_errinj; + uint32_t rx_udp_errinj; + uint32_t rx_icmp_errinj; }; #define ARP_OL_AGENT 0x00000001 @@ -2419,52 +2425,52 @@ struct toe_ol_stats_t struct arp_ol_stats_t { - uint32_t host_ip_entries; - uint32_t host_ip_overflow; - uint32_t arp_table_entries; - uint32_t arp_table_overflow; - uint32_t host_request; - uint32_t host_reply; - uint32_t host_service; - uint32_t peer_request; - uint32_t peer_request_drop; - uint32_t peer_reply; - uint32_t peer_reply_drop; - uint32_t peer_service; + uint32_t host_ip_entries; + uint32_t host_ip_overflow; + uint32_t arp_table_entries; + uint32_t arp_table_overflow; + uint32_t host_request; + uint32_t host_reply; + uint32_t host_service; + uint32_t peer_request; + uint32_t peer_request_drop; + uint32_t peer_reply; + uint32_t peer_reply_drop; + uint32_t peer_service; }; typedef struct wl_keep_alive_pkt { - uint32_t period_msec; - uint16_t len_bytes; - uint8_t data[1]; + uint32_t period_msec; + uint16_t len_bytes; + uint8_t data[1]; } wl_keep_alive_pkt_t; #define WL_KEEP_ALIVE_FIXED_LEN offsetof(wl_keep_alive_pkt_t, data) typedef enum wl_pkt_filter_type { - WL_PKT_FILTER_TYPE_PATTERN_MATCH + WL_PKT_FILTER_TYPE_PATTERN_MATCH } wl_pkt_filter_type_t; #define WL_PKT_FILTER_TYPE wl_pkt_filter_type_t typedef struct wl_pkt_filter_pattern { - uint32_t offset; - uint32_t size_bytes; - uint8_t mask_and_pattern[1]; + uint32_t offset; + uint32_t size_bytes; + uint8_t mask_and_pattern[1]; } wl_pkt_filter_pattern_t; typedef struct wl_pkt_filter { - uint32_t id; - uint32_t type; - uint32_t negate_match; - union - { - wl_pkt_filter_pattern_t pattern; - } u; + uint32_t id; + uint32_t type; + uint32_t negate_match; + union + { + wl_pkt_filter_pattern_t pattern; + } u; } wl_pkt_filter_t; #define WL_PKT_FILTER_FIXED_LEN offsetof(wl_pkt_filter_t, u) @@ -2472,37 +2478,37 @@ typedef struct wl_pkt_filter typedef struct wl_pkt_filter_enable { - uint32_t id; - uint32_t enable; + uint32_t id; + uint32_t enable; } wl_pkt_filter_enable_t; typedef struct wl_pkt_filter_list { - uint32_t num; - wl_pkt_filter_t filter[1]; + uint32_t num; + wl_pkt_filter_t filter[1]; } wl_pkt_filter_list_t; #define WL_PKT_FILTER_LIST_FIXED_LEN offsetof(wl_pkt_filter_list_t, filter) typedef struct wl_pkt_filter_stats { - uint32_t num_pkts_matched; - uint32_t num_pkts_forwarded; - uint32_t num_pkts_discarded; + uint32_t num_pkts_matched; + uint32_t num_pkts_forwarded; + uint32_t num_pkts_discarded; } wl_pkt_filter_stats_t; typedef struct wl_seq_cmd_ioctl { - uint32_t cmd; - uint32_t len; + uint32_t cmd; + uint32_t len; } wl_seq_cmd_ioctl_t; #define WL_SEQ_CMD_ALIGN_BYTES 4 #define WL_SEQ_CMDS_GET_IOCTL_FILTER(cmd) \ - (((cmd) == WLC_GET_MAGIC) || \ - ((cmd) == WLC_GET_VERSION) || \ - ((cmd) == WLC_GET_AP) || \ - ((cmd) == WLC_GET_INSTANCE)) + (((cmd) == WLC_GET_MAGIC) || \ + ((cmd) == WLC_GET_VERSION) || \ + ((cmd) == WLC_GET_AP) || \ + ((cmd) == WLC_GET_INSTANCE)) #define WL_PKTENG_PER_TX_START 0x01 #define WL_PKTENG_PER_TX_STOP 0x02 #define WL_PKTENG_PER_RX_START 0x04 @@ -2514,13 +2520,13 @@ typedef struct wl_seq_cmd_ioctl typedef struct wl_pkteng { - uint32_t flags; - uint32_t delay; - uint32_t nframes; - uint32_t length; - uint8_t seqno; - struct ether_addr dest; - struct ether_addr src; + uint32_t flags; + uint32_t delay; + uint32_t nframes; + uint32_t length; + uint8_t seqno; + struct ether_addr dest; + struct ether_addr src; } wl_pkteng_t; #define NUM_80211b_RATES 4 @@ -2530,10 +2536,10 @@ typedef struct wl_pkteng typedef struct wl_pkteng_stats { - uint32_t lostfrmcnt; - int32_t rssi; - int32_t snr; - uint16_t rxpktcnt[NUM_80211_RATES + 1]; + uint32_t lostfrmcnt; + int32_t rssi; + int32_t snr; + uint16_t rxpktcnt[NUM_80211_RATES + 1]; } wl_pkteng_stats_t; #define WL_WOWL_MAGIC (1 << 0) @@ -2547,29 +2553,29 @@ typedef struct wl_pkteng_stats typedef struct { - uint32_t masksize; - uint32_t offset; - uint32_t patternoffset; - uint32_t patternsize; + uint32_t masksize; + uint32_t offset; + uint32_t patternoffset; + uint32_t patternsize; } wl_wowl_pattern_t; typedef struct { - uint32_t count; - wl_wowl_pattern_t pattern[1]; + uint32_t count; + wl_wowl_pattern_t pattern[1]; } wl_wowl_pattern_list_t; typedef struct { - uint8_t pci_wakeind; - uint16_t ucode_wakeind; + uint8_t pci_wakeind; + uint16_t ucode_wakeind; } wl_wowl_wakeind_t; typedef struct wl_txrate_class { - uint8_t init_rate; - uint8_t min_rate; - uint8_t max_rate; + uint8_t init_rate; + uint8_t min_rate; + uint8_t max_rate; } wl_txrate_class_t; #define WLC_OBSS_SCAN_PASSIVE_DWELL_DEFAULT 100 @@ -2596,13 +2602,13 @@ typedef struct wl_txrate_class typedef struct wl_obss_scan_arg { - int16_t passive_dwell; - int16_t active_dwell; - int16_t bss_widthscan_interval; - int16_t passive_total; - int16_t active_total; - int16_t chanwidth_transition_delay; - int16_t activity_threshold; + int16_t passive_dwell; + int16_t active_dwell; + int16_t bss_widthscan_interval; + int16_t passive_total; + int16_t active_total; + int16_t chanwidth_transition_delay; + int16_t activity_threshold; } wl_obss_scan_arg_t; #define WL_OBSS_SCAN_PARAM_LEN sizeof(wl_obss_scan_arg_t) @@ -2614,18 +2620,18 @@ typedef struct wl_obss_scan_arg typedef struct wl_action_obss_coex_req { - uint8_t info; - uint8_t num; - uint8_t ch_list[1]; + uint8_t info; + uint8_t num; + uint8_t ch_list[1]; } wl_action_obss_coex_req_t; #define MAX_RSSI_LEVELS 8 typedef struct wl_rssi_event { - uint32_t rate_limit_msec; - uint8_t num_rssi_levels; - int8_t rssi_levels[MAX_RSSI_LEVELS]; + uint32_t rate_limit_msec; + uint8_t num_rssi_levels; + int8_t rssi_levels[MAX_RSSI_LEVELS]; } wl_rssi_event_t; #define WLFEATURE_DISABLE_11N 0x00000001 @@ -2641,20 +2647,20 @@ typedef struct wl_rssi_event typedef struct sta_prbreq_wps_ie_hdr { - struct ether_addr staAddr; - uint16_t ieLen; + struct ether_addr staAddr; + uint16_t ieLen; } sta_prbreq_wps_ie_hdr_t; typedef struct sta_prbreq_wps_ie_data { - sta_prbreq_wps_ie_hdr_t hdr; - uint8_t ieData[1]; + sta_prbreq_wps_ie_hdr_t hdr; + uint8_t ieData[1]; } sta_prbreq_wps_ie_data_t; typedef struct sta_prbreq_wps_ie_list { - uint32_t totLen; - uint8_t ieDataList[1]; + uint32_t totLen; + uint8_t ieDataList[1]; } sta_prbreq_wps_ie_list_t; /* EDCF related items from 802.11.h */ @@ -2681,10 +2687,11 @@ typedef struct sta_prbreq_wps_ie_list #define EDCF_TXOP_MAX 65535 /* TXOP maximum value */ #define EDCF_TXOP2USEC(txop) ((txop) << 5) -struct edcf_acparam { - uint8_t ACI; - uint8_t ECW; - uint16_t TXOP; /* stored in network order (ls octet first) */ +struct edcf_acparam +{ + uint8_t ACI; + uint8_t ECW; + uint16_t TXOP; /* stored in network order (ls octet first) */ } ; typedef struct edcf_acparam edcf_acparam_t; @@ -2696,139 +2703,139 @@ typedef struct edcf_acparam edcf_acparam_t; */ typedef enum { - WLC_E_NONE = -1, - WLC_E_SET_SSID = 0 /** indicates status of set SSID */, - WLC_E_JOIN = 1, /** differentiates join IBSS from found (WLC_E_START) IBSS */ - WLC_E_START = 2, /** STA founded an IBSS or AP started a BSS */ - WLC_E_AUTH = 3, /** 802.11 AUTH request */ - WLC_E_AUTH_IND = 4, /** 802.11 AUTH indication */ - WLC_E_DEAUTH = 5, /** 802.11 DEAUTH request */ - WLC_E_DEAUTH_IND = 6, /** 802.11 DEAUTH indication */ - WLC_E_ASSOC = 7, /** 802.11 ASSOC request */ - WLC_E_ASSOC_IND = 8, /** 802.11 ASSOC indication */ - WLC_E_REASSOC = 9, /** 802.11 REASSOC request */ - WLC_E_REASSOC_IND = 10, /** 802.11 REASSOC indication */ - WLC_E_DISASSOC = 11, /** 802.11 DISASSOC request */ - WLC_E_DISASSOC_IND = 12, /** 802.11 DISASSOC indication */ - WLC_E_QUIET_START = 13, /** 802.11h Quiet period started */ - WLC_E_QUIET_END = 14, /** 802.11h Quiet period ended */ - WLC_E_BEACON_RX = 15, /** BEACONS received/lost indication */ - WLC_E_LINK = 16, /** generic link indication */ - WLC_E_MIC_ERROR = 17, /** TKIP MIC error occurred */ - WLC_E_NDIS_LINK = 18, /** NDIS style link indication */ - WLC_E_ROAM = 19, /** roam attempt occurred: indicate status & reason */ - WLC_E_TXFAIL = 20, /** change in dot11FailedCount (txfail) */ - WLC_E_PMKID_CACHE = 21, /** WPA2 pmkid cache indication */ - WLC_E_RETROGRADE_TSF = 22, /** current AP's TSF value went backward */ - WLC_E_PRUNE = 23, /** AP was pruned from join list for reason */ - WLC_E_AUTOAUTH = 24, /** report AutoAuth table entry match for join attempt */ - WLC_E_EAPOL_MSG = 25, /** Event encapsulating an EAPOL message */ - WLC_E_SCAN_COMPLETE = 26, /** Scan results are ready or scan was aborted */ - WLC_E_ADDTS_IND = 27, /** indicate to host addts fail/success */ - WLC_E_DELTS_IND = 28, /** indicate to host delts fail/success */ - WLC_E_BCNSENT_IND = 29, /** indicate to host of beacon transmit */ - WLC_E_BCNRX_MSG = 30, /** Send the received beacon up to the host */ - WLC_E_BCNLOST_MSG = 31, /** indicate to host loss of beacon */ - WLC_E_ROAM_PREP = 32, /** before attempting to roam */ - WLC_E_PFN_NET_FOUND = 33, /** PFN network found event */ - WLC_E_PFN_NET_LOST = 34, /** PFN network lost event */ - WLC_E_RESET_COMPLETE = 35, - WLC_E_JOIN_START = 36, - WLC_E_ROAM_START = 37, - WLC_E_ASSOC_START = 38, - WLC_E_IBSS_ASSOC = 39, - WLC_E_RADIO = 40, - WLC_E_PSM_WATCHDOG = 41, /** PSM microcode watchdog fired */ - WLC_E_CCX_ASSOC_START = 42, /** CCX association start */ - WLC_E_CCX_ASSOC_ABORT = 43, /** CCX association abort */ - WLC_E_PROBREQ_MSG = 44, /** probe request received */ - WLC_E_SCAN_CONFIRM_IND = 45, - WLC_E_PSK_SUP = 46, /** WPA Handshake */ - WLC_E_COUNTRY_CODE_CHANGED = 47, - WLC_E_EXCEEDED_MEDIUM_TIME = 48, /** WMMAC excedded medium time */ - WLC_E_ICV_ERROR = 49, /** WEP ICV error occurred */ - WLC_E_UNICAST_DECODE_ERROR = 50, /** Unsupported unicast encrypted frame */ - WLC_E_MULTICAST_DECODE_ERROR = 51, /** Unsupported multicast encrypted frame */ - WLC_E_TRACE = 52, - WLC_E_BTA_HCI_EVENT = 53, /** BT-AMP HCI event */ - WLC_E_IF = 54, /** I/F change (for wlan host notification) */ - WLC_E_P2P_DISC_LISTEN_COMPLETE = 55, /** P2P Discovery listen state expires */ - WLC_E_RSSI = 56, /** indicate RSSI change based on configured levels */ - WLC_E_PFN_SCAN_COMPLETE = 57, /** PFN completed scan of network list */ - WLC_E_EXTLOG_MSG = 58, - WLC_E_ACTION_FRAME = 59, /** Action frame reception */ - WLC_E_ACTION_FRAME_COMPLETE = 60, /** Action frame Tx complete */ - WLC_E_PRE_ASSOC_IND = 61, /** assoc request received */ - WLC_E_PRE_REASSOC_IND = 62, /** re-assoc request received */ - WLC_E_CHANNEL_ADOPTED = 63, /** channel adopted (xxx: obsoleted) */ - WLC_E_AP_STARTED = 64, /** AP started */ - WLC_E_DFS_AP_STOP = 65, /** AP stopped due to DFS */ - WLC_E_DFS_AP_RESUME = 66, /** AP resumed due to DFS */ - WLC_E_WAI_STA_EVENT = 67, /** WAI stations event */ - WLC_E_WAI_MSG = 68, /** event encapsulating an WAI message */ - WLC_E_ESCAN_RESULT = 69, /** escan result event */ - WLC_E_ACTION_FRAME_OFF_CHAN_COMPLETE = 70, /** action frame off channel complete */ /* NOTE - This used to be WLC_E_WAKE_EVENT */ - WLC_E_PROBRESP_MSG = 71, /** probe response received */ - WLC_E_P2P_PROBREQ_MSG = 72, /** P2P Probe request received */ - WLC_E_DCS_REQUEST = 73, - WLC_E_FIFO_CREDIT_MAP = 74, /** credits for D11 FIFOs. [AC0,AC1,AC2,AC3,BC_MC,ATIM] */ - WLC_E_ACTION_FRAME_RX = 75, /** Received action frame event WITH wl_event_rx_frame_data_t header */ - WLC_E_WAKE_EVENT = 76, /** Wake Event timer fired, used for wake WLAN test mode */ - WLC_E_RM_COMPLETE = 77, /** Radio measurement complete */ - WLC_E_HTSFSYNC = 78, /** Synchronize TSF with the host */ - WLC_E_OVERLAY_REQ = 79, /** request an overlay IOCTL/iovar from the host */ - WLC_E_CSA_COMPLETE_IND = 80, - WLC_E_EXCESS_PM_WAKE_EVENT = 81, /** excess PM Wake Event to inform host */ - WLC_E_PFN_SCAN_NONE = 82, /** no PFN networks around */ - WLC_E_PFN_SCAN_ALLGONE = 83, /** last found PFN network gets lost */ - WLC_E_GTK_PLUMBED = 84, - WLC_E_ASSOC_IND_NDIS = 85, /** 802.11 ASSOC indication for NDIS only */ - WLC_E_REASSOC_IND_NDIS = 86, /** 802.11 REASSOC indication for NDIS only */ - WLC_E_ASSOC_REQ_IE = 87, - WLC_E_ASSOC_RESP_IE = 88, - WLC_E_ASSOC_RECREATED = 89, /** association recreated on resume */ - WLC_E_ACTION_FRAME_RX_NDIS = 90, /** rx action frame event for NDIS only */ - WLC_E_AUTH_REQ = 91, /** authentication request received */ - WLC_E_TDLS_PEER_EVENT = 92, /** discovered peer, connected/disconnected peer */ - WLC_E_SPEEDY_RECREATE_FAIL = 93, /** fast assoc recreation failed */ - WLC_E_NATIVE = 94, /** port-specific event and payload (e.g. NDIS) */ - WLC_E_PKTDELAY_IND = 95, /** event for tx pkt delay suddently jump */ - WLC_E_AWDL_AW = 96, /** AWDL AW period starts */ - WLC_E_AWDL_ROLE = 97, /** AWDL Master/Slave/NE master role event */ - WLC_E_AWDL_EVENT = 98, /** Generic AWDL event */ - WLC_E_NIC_AF_TXS = 99, /** NIC AF txstatus */ - WLC_E_NIC_NIC_REPORT = 100, /** NIC period report */ - WLC_E_BEACON_FRAME_RX = 101, - WLC_E_SERVICE_FOUND = 102, /** desired service found */ - WLC_E_GAS_FRAGMENT_RX = 103, /** GAS fragment received */ - WLC_E_GAS_COMPLETE = 104, /** GAS sessions all complete */ - WLC_E_P2PO_ADD_DEVICE = 105, /** New device found by p2p offload */ - WLC_E_P2PO_DEL_DEVICE = 106, /** device has been removed by p2p offload */ - WLC_E_WNM_STA_SLEEP = 107, /** WNM event to notify STA enter sleep mode */ - WLC_E_TXFAIL_THRESH = 108, /** Indication of MAC tx failures (exhaustion of 802.11 retries) exceeding threshold(s) */ - WLC_E_PROXD = 109, /** Proximity Detection event */ - WLC_E_IBSS_COALESCE = 110, /** IBSS Coalescing */ - WLC_E_AWDL_RX_PRB_RESP = 111, /** AWDL RX Probe response */ - WLC_E_AWDL_RX_ACT_FRAME = 112, /** AWDL RX Action Frames */ - WLC_E_AWDL_WOWL_NULLPKT = 113, /** AWDL Wowl nulls */ - WLC_E_AWDL_PHYCAL_STATUS = 114, /** AWDL Phycal status */ - WLC_E_AWDL_OOB_AF_STATUS = 115, /** AWDL OOB AF status */ - WLC_E_AWDL_SCAN_STATUS = 116, /** Interleaved Scan status */ - WLC_E_AWDL_AW_START = 117, /** AWDL AW Start */ - WLC_E_AWDL_AW_END = 118, /** AWDL AW End */ - WLC_E_AWDL_AW_EXT = 119, /** AWDL AW Extensions */ - WLC_E_AWDL_PEER_CACHE_CONTROL = 120, - WLC_E_CSA_START_IND = 121, - WLC_E_CSA_DONE_IND = 122, - WLC_E_CSA_FAILURE_IND = 123, - WLC_E_CCA_CHAN_QUAL = 124, /** CCA based channel quality report */ - WLC_E_BSSID = 125, /** to report change in BSSID while roaming */ - WLC_E_TX_STAT_ERROR = 126, /** tx error indication */ - WLC_E_BCMC_CREDIT_SUPPORT = 127, /** credit check for BCMC supported */ - WLC_E_PSTA_PRIMARY_INTF_IND = 128, /** psta primary interface indication */ - WLC_E_LAST = 129, /** highest val + 1 for range checking */ - - WLC_E_FORCE_32_BIT = 0x7FFFFFFE /** Force enum to be stored in 32 bit variable */ + WLC_E_NONE = -1, + WLC_E_SET_SSID = 0 /** indicates status of set SSID */, + WLC_E_JOIN = 1, /** differentiates join IBSS from found (WLC_E_START) IBSS */ + WLC_E_START = 2, /** STA founded an IBSS or AP started a BSS */ + WLC_E_AUTH = 3, /** 802.11 AUTH request */ + WLC_E_AUTH_IND = 4, /** 802.11 AUTH indication */ + WLC_E_DEAUTH = 5, /** 802.11 DEAUTH request */ + WLC_E_DEAUTH_IND = 6, /** 802.11 DEAUTH indication */ + WLC_E_ASSOC = 7, /** 802.11 ASSOC request */ + WLC_E_ASSOC_IND = 8, /** 802.11 ASSOC indication */ + WLC_E_REASSOC = 9, /** 802.11 REASSOC request */ + WLC_E_REASSOC_IND = 10, /** 802.11 REASSOC indication */ + WLC_E_DISASSOC = 11, /** 802.11 DISASSOC request */ + WLC_E_DISASSOC_IND = 12, /** 802.11 DISASSOC indication */ + WLC_E_QUIET_START = 13, /** 802.11h Quiet period started */ + WLC_E_QUIET_END = 14, /** 802.11h Quiet period ended */ + WLC_E_BEACON_RX = 15, /** BEACONS received/lost indication */ + WLC_E_LINK = 16, /** generic link indication */ + WLC_E_MIC_ERROR = 17, /** TKIP MIC error occurred */ + WLC_E_NDIS_LINK = 18, /** NDIS style link indication */ + WLC_E_ROAM = 19, /** roam attempt occurred: indicate status & reason */ + WLC_E_TXFAIL = 20, /** change in dot11FailedCount (txfail) */ + WLC_E_PMKID_CACHE = 21, /** WPA2 pmkid cache indication */ + WLC_E_RETROGRADE_TSF = 22, /** current AP's TSF value went backward */ + WLC_E_PRUNE = 23, /** AP was pruned from join list for reason */ + WLC_E_AUTOAUTH = 24, /** report AutoAuth table entry match for join attempt */ + WLC_E_EAPOL_MSG = 25, /** Event encapsulating an EAPOL message */ + WLC_E_SCAN_COMPLETE = 26, /** Scan results are ready or scan was aborted */ + WLC_E_ADDTS_IND = 27, /** indicate to host addts fail/success */ + WLC_E_DELTS_IND = 28, /** indicate to host delts fail/success */ + WLC_E_BCNSENT_IND = 29, /** indicate to host of beacon transmit */ + WLC_E_BCNRX_MSG = 30, /** Send the received beacon up to the host */ + WLC_E_BCNLOST_MSG = 31, /** indicate to host loss of beacon */ + WLC_E_ROAM_PREP = 32, /** before attempting to roam */ + WLC_E_PFN_NET_FOUND = 33, /** PFN network found event */ + WLC_E_PFN_NET_LOST = 34, /** PFN network lost event */ + WLC_E_RESET_COMPLETE = 35, + WLC_E_JOIN_START = 36, + WLC_E_ROAM_START = 37, + WLC_E_ASSOC_START = 38, + WLC_E_IBSS_ASSOC = 39, + WLC_E_RADIO = 40, + WLC_E_PSM_WATCHDOG = 41, /** PSM microcode watchdog fired */ + WLC_E_CCX_ASSOC_START = 42, /** CCX association start */ + WLC_E_CCX_ASSOC_ABORT = 43, /** CCX association abort */ + WLC_E_PROBREQ_MSG = 44, /** probe request received */ + WLC_E_SCAN_CONFIRM_IND = 45, + WLC_E_PSK_SUP = 46, /** WPA Handshake */ + WLC_E_COUNTRY_CODE_CHANGED = 47, + WLC_E_EXCEEDED_MEDIUM_TIME = 48, /** WMMAC excedded medium time */ + WLC_E_ICV_ERROR = 49, /** WEP ICV error occurred */ + WLC_E_UNICAST_DECODE_ERROR = 50, /** Unsupported unicast encrypted frame */ + WLC_E_MULTICAST_DECODE_ERROR = 51, /** Unsupported multicast encrypted frame */ + WLC_E_TRACE = 52, + WLC_E_BTA_HCI_EVENT = 53, /** BT-AMP HCI event */ + WLC_E_IF = 54, /** I/F change (for wlan host notification) */ + WLC_E_P2P_DISC_LISTEN_COMPLETE = 55, /** P2P Discovery listen state expires */ + WLC_E_RSSI = 56, /** indicate RSSI change based on configured levels */ + WLC_E_PFN_SCAN_COMPLETE = 57, /** PFN completed scan of network list */ + WLC_E_EXTLOG_MSG = 58, + WLC_E_ACTION_FRAME = 59, /** Action frame reception */ + WLC_E_ACTION_FRAME_COMPLETE = 60, /** Action frame Tx complete */ + WLC_E_PRE_ASSOC_IND = 61, /** assoc request received */ + WLC_E_PRE_REASSOC_IND = 62, /** re-assoc request received */ + WLC_E_CHANNEL_ADOPTED = 63, /** channel adopted (xxx: obsoleted) */ + WLC_E_AP_STARTED = 64, /** AP started */ + WLC_E_DFS_AP_STOP = 65, /** AP stopped due to DFS */ + WLC_E_DFS_AP_RESUME = 66, /** AP resumed due to DFS */ + WLC_E_WAI_STA_EVENT = 67, /** WAI stations event */ + WLC_E_WAI_MSG = 68, /** event encapsulating an WAI message */ + WLC_E_ESCAN_RESULT = 69, /** escan result event */ + WLC_E_ACTION_FRAME_OFF_CHAN_COMPLETE = 70, /** action frame off channel complete */ /* NOTE - This used to be WLC_E_WAKE_EVENT */ + WLC_E_PROBRESP_MSG = 71, /** probe response received */ + WLC_E_P2P_PROBREQ_MSG = 72, /** P2P Probe request received */ + WLC_E_DCS_REQUEST = 73, + WLC_E_FIFO_CREDIT_MAP = 74, /** credits for D11 FIFOs. [AC0,AC1,AC2,AC3,BC_MC,ATIM] */ + WLC_E_ACTION_FRAME_RX = 75, /** Received action frame event WITH wl_event_rx_frame_data_t header */ + WLC_E_WAKE_EVENT = 76, /** Wake Event timer fired, used for wake WLAN test mode */ + WLC_E_RM_COMPLETE = 77, /** Radio measurement complete */ + WLC_E_HTSFSYNC = 78, /** Synchronize TSF with the host */ + WLC_E_OVERLAY_REQ = 79, /** request an overlay IOCTL/iovar from the host */ + WLC_E_CSA_COMPLETE_IND = 80, + WLC_E_EXCESS_PM_WAKE_EVENT = 81, /** excess PM Wake Event to inform host */ + WLC_E_PFN_SCAN_NONE = 82, /** no PFN networks around */ + WLC_E_PFN_SCAN_ALLGONE = 83, /** last found PFN network gets lost */ + WLC_E_GTK_PLUMBED = 84, + WLC_E_ASSOC_IND_NDIS = 85, /** 802.11 ASSOC indication for NDIS only */ + WLC_E_REASSOC_IND_NDIS = 86, /** 802.11 REASSOC indication for NDIS only */ + WLC_E_ASSOC_REQ_IE = 87, + WLC_E_ASSOC_RESP_IE = 88, + WLC_E_ASSOC_RECREATED = 89, /** association recreated on resume */ + WLC_E_ACTION_FRAME_RX_NDIS = 90, /** rx action frame event for NDIS only */ + WLC_E_AUTH_REQ = 91, /** authentication request received */ + WLC_E_TDLS_PEER_EVENT = 92, /** discovered peer, connected/disconnected peer */ + WLC_E_SPEEDY_RECREATE_FAIL = 93, /** fast assoc recreation failed */ + WLC_E_NATIVE = 94, /** port-specific event and payload (e.g. NDIS) */ + WLC_E_PKTDELAY_IND = 95, /** event for tx pkt delay suddently jump */ + WLC_E_AWDL_AW = 96, /** AWDL AW period starts */ + WLC_E_AWDL_ROLE = 97, /** AWDL Master/Slave/NE master role event */ + WLC_E_AWDL_EVENT = 98, /** Generic AWDL event */ + WLC_E_NIC_AF_TXS = 99, /** NIC AF txstatus */ + WLC_E_NIC_NIC_REPORT = 100, /** NIC period report */ + WLC_E_BEACON_FRAME_RX = 101, + WLC_E_SERVICE_FOUND = 102, /** desired service found */ + WLC_E_GAS_FRAGMENT_RX = 103, /** GAS fragment received */ + WLC_E_GAS_COMPLETE = 104, /** GAS sessions all complete */ + WLC_E_P2PO_ADD_DEVICE = 105, /** New device found by p2p offload */ + WLC_E_P2PO_DEL_DEVICE = 106, /** device has been removed by p2p offload */ + WLC_E_WNM_STA_SLEEP = 107, /** WNM event to notify STA enter sleep mode */ + WLC_E_TXFAIL_THRESH = 108, /** Indication of MAC tx failures (exhaustion of 802.11 retries) exceeding threshold(s) */ + WLC_E_PROXD = 109, /** Proximity Detection event */ + WLC_E_IBSS_COALESCE = 110, /** IBSS Coalescing */ + WLC_E_AWDL_RX_PRB_RESP = 111, /** AWDL RX Probe response */ + WLC_E_AWDL_RX_ACT_FRAME = 112, /** AWDL RX Action Frames */ + WLC_E_AWDL_WOWL_NULLPKT = 113, /** AWDL Wowl nulls */ + WLC_E_AWDL_PHYCAL_STATUS = 114, /** AWDL Phycal status */ + WLC_E_AWDL_OOB_AF_STATUS = 115, /** AWDL OOB AF status */ + WLC_E_AWDL_SCAN_STATUS = 116, /** Interleaved Scan status */ + WLC_E_AWDL_AW_START = 117, /** AWDL AW Start */ + WLC_E_AWDL_AW_END = 118, /** AWDL AW End */ + WLC_E_AWDL_AW_EXT = 119, /** AWDL AW Extensions */ + WLC_E_AWDL_PEER_CACHE_CONTROL = 120, + WLC_E_CSA_START_IND = 121, + WLC_E_CSA_DONE_IND = 122, + WLC_E_CSA_FAILURE_IND = 123, + WLC_E_CCA_CHAN_QUAL = 124, /** CCA based channel quality report */ + WLC_E_BSSID = 125, /** to report change in BSSID while roaming */ + WLC_E_TX_STAT_ERROR = 126, /** tx error indication */ + WLC_E_BCMC_CREDIT_SUPPORT = 127, /** credit check for BCMC supported */ + WLC_E_PSTA_PRIMARY_INTF_IND = 128, /** psta primary interface indication */ + WLC_E_LAST = 129, /** highest val + 1 for range checking */ + + WLC_E_FORCE_32_BIT = 0x7FFFFFFE /** Force enum to be stored in 32 bit variable */ } wl_event_num_t; #define BCMF_EVENT_COUNT WLC_E_LAST @@ -2843,68 +2850,68 @@ typedef enum */ typedef enum { - WLC_E_STATUS_SUCCESS = 0, /** operation was successful */ - WLC_E_STATUS_FAIL = 1, /** operation failed */ - WLC_E_STATUS_TIMEOUT = 2, /** operation timed out */ - WLC_E_STATUS_NO_NETWORKS = 3, /** failed due to no matching network found */ - WLC_E_STATUS_ABORT = 4, /** operation was aborted */ - WLC_E_STATUS_NO_ACK = 5, /** protocol failure: packet not ack'd */ - WLC_E_STATUS_UNSOLICITED = 6, /** AUTH or ASSOC packet was unsolicited */ - WLC_E_STATUS_ATTEMPT = 7, /** attempt to assoc to an auto auth configuration */ - WLC_E_STATUS_PARTIAL = 8, /** scan results are incomplete */ - WLC_E_STATUS_NEWSCAN = 9, /** scan aborted by another scan */ - WLC_E_STATUS_NEWASSOC = 10, /** scan aborted due to assoc in progress */ - WLC_E_STATUS_11HQUIET = 11, /** 802.11h quiet period started */ - WLC_E_STATUS_SUPPRESS = 12, /** user disabled scanning (WLC_SET_SCANSUPPRESS) */ - WLC_E_STATUS_NOCHANS = 13, /** no allowable channels to scan */ - WLC_E_STATUS_CCXFASTRM = 14, /** scan aborted due to CCX fast roam */ - WLC_E_STATUS_CS_ABORT = 15, /** abort channel select */ - - /* for WLC_SUP messages */ - WLC_SUP_DISCONNECTED = 0 + WLC_SUP_STATUS_OFFSET, - WLC_SUP_CONNECTING = 1 + WLC_SUP_STATUS_OFFSET, - WLC_SUP_IDREQUIRED = 2 + WLC_SUP_STATUS_OFFSET, - WLC_SUP_AUTHENTICATING = 3 + WLC_SUP_STATUS_OFFSET, - WLC_SUP_AUTHENTICATED = 4 + WLC_SUP_STATUS_OFFSET, - WLC_SUP_KEYXCHANGE = 5 + WLC_SUP_STATUS_OFFSET, - WLC_SUP_KEYED = 6 + WLC_SUP_STATUS_OFFSET, - WLC_SUP_TIMEOUT = 7 + WLC_SUP_STATUS_OFFSET, - WLC_SUP_LAST_BASIC_STATE = 8 + WLC_SUP_STATUS_OFFSET, - /* Extended supplicant authentication states */ - WLC_SUP_KEYXCHANGE_WAIT_M1 = (int) WLC_SUP_AUTHENTICATED + WLC_SUP_STATUS_OFFSET, /** Waiting to receive handshake msg M1 */ - WLC_SUP_KEYXCHANGE_PREP_M2 = (int) WLC_SUP_KEYXCHANGE + WLC_SUP_STATUS_OFFSET, /** Preparing to send handshake msg M2 */ - WLC_SUP_KEYXCHANGE_WAIT_M3 = (int) WLC_SUP_LAST_BASIC_STATE + WLC_SUP_STATUS_OFFSET, /** Waiting to receive handshake msg M3 */ - WLC_SUP_KEYXCHANGE_PREP_M4 = 9 + WLC_SUP_STATUS_OFFSET, /** Preparing to send handshake msg M4 */ - WLC_SUP_KEYXCHANGE_WAIT_G1 = 10 + WLC_SUP_STATUS_OFFSET, /** Waiting to receive handshake msg G1 */ - WLC_SUP_KEYXCHANGE_PREP_G2 = 11 + WLC_SUP_STATUS_OFFSET, /** Preparing to send handshake msg G2 */ - - WLC_DOT11_SC_SUCCESS = 0 + WLC_DOT11_SC_STATUS_OFFSET, /* Successful */ - WLC_DOT11_SC_FAILURE = 1 + WLC_DOT11_SC_STATUS_OFFSET, /* Unspecified failure */ - WLC_DOT11_SC_CAP_MISMATCH = 10 + WLC_DOT11_SC_STATUS_OFFSET, /* Cannot support all requested capabilities in the Capability Information field */ - WLC_DOT11_SC_REASSOC_FAIL = 11 + WLC_DOT11_SC_STATUS_OFFSET, /* Reassociation denied due to inability to confirm that association exists */ - WLC_DOT11_SC_ASSOC_FAIL = 12 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to reason outside the scope of this standard */ - WLC_DOT11_SC_AUTH_MISMATCH = 13 + WLC_DOT11_SC_STATUS_OFFSET, /* Responding station does not support the specified authentication algorithm */ - WLC_DOT11_SC_AUTH_SEQ = 14 + WLC_DOT11_SC_STATUS_OFFSET, /* Received an Authentication frame with authentication transaction sequence number out of expected sequence */ - WLC_DOT11_SC_AUTH_CHALLENGE_FAIL = 15 + WLC_DOT11_SC_STATUS_OFFSET, /* Authentication rejected because of challenge failure */ - WLC_DOT11_SC_AUTH_TIMEOUT = 16 + WLC_DOT11_SC_STATUS_OFFSET, /* Authentication rejected due to timeout waiting for next frame in sequence */ - WLC_DOT11_SC_ASSOC_BUSY_FAIL = 17 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied because AP is unable to handle additional associated stations */ - WLC_DOT11_SC_ASSOC_RATE_MISMATCH = 18 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to requesting station not supporting all of the data rates in the BSSBasicRateSet parameter */ - WLC_DOT11_SC_ASSOC_SHORT_REQUIRED = 19 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to requesting station not supporting the Short Preamble option */ - WLC_DOT11_SC_ASSOC_PBCC_REQUIRED = 20 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to requesting station not supporting the PBCC Modulation option */ - WLC_DOT11_SC_ASSOC_AGILITY_REQUIRED = 21 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to requesting station not supporting the Channel Agility option */ - WLC_DOT11_SC_ASSOC_SPECTRUM_REQUIRED = 22 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied because Spectrum Management capability is required. */ - WLC_DOT11_SC_ASSOC_BAD_POWER_CAP = 23 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied because the info in the Power Cap element is unacceptable. */ - WLC_DOT11_SC_ASSOC_BAD_SUP_CHANNELS = 24 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied because the info in the Supported Channel element is unacceptable */ - WLC_DOT11_SC_ASSOC_SHORTSLOT_REQUIRED = 25 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to requesting station not supporting the Short Slot Time option */ - WLC_DOT11_SC_ASSOC_ERPBCC_REQUIRED = 26 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to requesting station not supporting the ER-PBCC Modulation option */ - WLC_DOT11_SC_ASSOC_DSSOFDM_REQUIRED = 27 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to requesting station not supporting the DSS-OFDM option */ - WLC_DOT11_SC_DECLINED = 37 + WLC_DOT11_SC_STATUS_OFFSET, /* request declined */ - WLC_DOT11_SC_INVALID_PARAMS = 38 + WLC_DOT11_SC_STATUS_OFFSET, /* One or more params have invalid values */ - WLC_DOT11_SC_INVALID_AKMP = 43 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to invalid AKMP */ - WLC_DOT11_SC_INVALID_MDID = 54 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to invalid MDID */ - WLC_DOT11_SC_INVALID_FTIE = 55 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to invalid FTIE */ - - WLC_E_STATUS_FORCE_32_BIT = 0x7FFFFFFE /** Force enum to be stored in 32 bit variable */ + WLC_E_STATUS_SUCCESS = 0, /** operation was successful */ + WLC_E_STATUS_FAIL = 1, /** operation failed */ + WLC_E_STATUS_TIMEOUT = 2, /** operation timed out */ + WLC_E_STATUS_NO_NETWORKS = 3, /** failed due to no matching network found */ + WLC_E_STATUS_ABORT = 4, /** operation was aborted */ + WLC_E_STATUS_NO_ACK = 5, /** protocol failure: packet not ack'd */ + WLC_E_STATUS_UNSOLICITED = 6, /** AUTH or ASSOC packet was unsolicited */ + WLC_E_STATUS_ATTEMPT = 7, /** attempt to assoc to an auto auth configuration */ + WLC_E_STATUS_PARTIAL = 8, /** scan results are incomplete */ + WLC_E_STATUS_NEWSCAN = 9, /** scan aborted by another scan */ + WLC_E_STATUS_NEWASSOC = 10, /** scan aborted due to assoc in progress */ + WLC_E_STATUS_11HQUIET = 11, /** 802.11h quiet period started */ + WLC_E_STATUS_SUPPRESS = 12, /** user disabled scanning (WLC_SET_SCANSUPPRESS) */ + WLC_E_STATUS_NOCHANS = 13, /** no allowable channels to scan */ + WLC_E_STATUS_CCXFASTRM = 14, /** scan aborted due to CCX fast roam */ + WLC_E_STATUS_CS_ABORT = 15, /** abort channel select */ + + /* for WLC_SUP messages */ + WLC_SUP_DISCONNECTED = 0 + WLC_SUP_STATUS_OFFSET, + WLC_SUP_CONNECTING = 1 + WLC_SUP_STATUS_OFFSET, + WLC_SUP_IDREQUIRED = 2 + WLC_SUP_STATUS_OFFSET, + WLC_SUP_AUTHENTICATING = 3 + WLC_SUP_STATUS_OFFSET, + WLC_SUP_AUTHENTICATED = 4 + WLC_SUP_STATUS_OFFSET, + WLC_SUP_KEYXCHANGE = 5 + WLC_SUP_STATUS_OFFSET, + WLC_SUP_KEYED = 6 + WLC_SUP_STATUS_OFFSET, + WLC_SUP_TIMEOUT = 7 + WLC_SUP_STATUS_OFFSET, + WLC_SUP_LAST_BASIC_STATE = 8 + WLC_SUP_STATUS_OFFSET, + /* Extended supplicant authentication states */ + WLC_SUP_KEYXCHANGE_WAIT_M1 = (int) WLC_SUP_AUTHENTICATED + WLC_SUP_STATUS_OFFSET, /** Waiting to receive handshake msg M1 */ + WLC_SUP_KEYXCHANGE_PREP_M2 = (int) WLC_SUP_KEYXCHANGE + WLC_SUP_STATUS_OFFSET, /** Preparing to send handshake msg M2 */ + WLC_SUP_KEYXCHANGE_WAIT_M3 = (int) WLC_SUP_LAST_BASIC_STATE + WLC_SUP_STATUS_OFFSET, /** Waiting to receive handshake msg M3 */ + WLC_SUP_KEYXCHANGE_PREP_M4 = 9 + WLC_SUP_STATUS_OFFSET, /** Preparing to send handshake msg M4 */ + WLC_SUP_KEYXCHANGE_WAIT_G1 = 10 + WLC_SUP_STATUS_OFFSET, /** Waiting to receive handshake msg G1 */ + WLC_SUP_KEYXCHANGE_PREP_G2 = 11 + WLC_SUP_STATUS_OFFSET, /** Preparing to send handshake msg G2 */ + + WLC_DOT11_SC_SUCCESS = 0 + WLC_DOT11_SC_STATUS_OFFSET, /* Successful */ + WLC_DOT11_SC_FAILURE = 1 + WLC_DOT11_SC_STATUS_OFFSET, /* Unspecified failure */ + WLC_DOT11_SC_CAP_MISMATCH = 10 + WLC_DOT11_SC_STATUS_OFFSET, /* Cannot support all requested capabilities in the Capability Information field */ + WLC_DOT11_SC_REASSOC_FAIL = 11 + WLC_DOT11_SC_STATUS_OFFSET, /* Reassociation denied due to inability to confirm that association exists */ + WLC_DOT11_SC_ASSOC_FAIL = 12 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to reason outside the scope of this standard */ + WLC_DOT11_SC_AUTH_MISMATCH = 13 + WLC_DOT11_SC_STATUS_OFFSET, /* Responding station does not support the specified authentication algorithm */ + WLC_DOT11_SC_AUTH_SEQ = 14 + WLC_DOT11_SC_STATUS_OFFSET, /* Received an Authentication frame with authentication transaction sequence number out of expected sequence */ + WLC_DOT11_SC_AUTH_CHALLENGE_FAIL = 15 + WLC_DOT11_SC_STATUS_OFFSET, /* Authentication rejected because of challenge failure */ + WLC_DOT11_SC_AUTH_TIMEOUT = 16 + WLC_DOT11_SC_STATUS_OFFSET, /* Authentication rejected due to timeout waiting for next frame in sequence */ + WLC_DOT11_SC_ASSOC_BUSY_FAIL = 17 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied because AP is unable to handle additional associated stations */ + WLC_DOT11_SC_ASSOC_RATE_MISMATCH = 18 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to requesting station not supporting all of the data rates in the BSSBasicRateSet parameter */ + WLC_DOT11_SC_ASSOC_SHORT_REQUIRED = 19 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to requesting station not supporting the Short Preamble option */ + WLC_DOT11_SC_ASSOC_PBCC_REQUIRED = 20 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to requesting station not supporting the PBCC Modulation option */ + WLC_DOT11_SC_ASSOC_AGILITY_REQUIRED = 21 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to requesting station not supporting the Channel Agility option */ + WLC_DOT11_SC_ASSOC_SPECTRUM_REQUIRED = 22 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied because Spectrum Management capability is required. */ + WLC_DOT11_SC_ASSOC_BAD_POWER_CAP = 23 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied because the info in the Power Cap element is unacceptable. */ + WLC_DOT11_SC_ASSOC_BAD_SUP_CHANNELS = 24 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied because the info in the Supported Channel element is unacceptable */ + WLC_DOT11_SC_ASSOC_SHORTSLOT_REQUIRED = 25 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to requesting station not supporting the Short Slot Time option */ + WLC_DOT11_SC_ASSOC_ERPBCC_REQUIRED = 26 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to requesting station not supporting the ER-PBCC Modulation option */ + WLC_DOT11_SC_ASSOC_DSSOFDM_REQUIRED = 27 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to requesting station not supporting the DSS-OFDM option */ + WLC_DOT11_SC_DECLINED = 37 + WLC_DOT11_SC_STATUS_OFFSET, /* request declined */ + WLC_DOT11_SC_INVALID_PARAMS = 38 + WLC_DOT11_SC_STATUS_OFFSET, /* One or more params have invalid values */ + WLC_DOT11_SC_INVALID_AKMP = 43 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to invalid AKMP */ + WLC_DOT11_SC_INVALID_MDID = 54 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to invalid MDID */ + WLC_DOT11_SC_INVALID_FTIE = 55 + WLC_DOT11_SC_STATUS_OFFSET, /* Association denied due to invalid FTIE */ + + WLC_E_STATUS_FORCE_32_BIT = 0x7FFFFFFE /** Force enum to be stored in 32 bit variable */ } wl_event_status_t; #define WLC_E_PRUNE_REASON_OFFSET (256) @@ -2918,82 +2925,82 @@ typedef enum */ typedef enum { - /* roam reason codes */ - WLC_E_REASON_INITIAL_ASSOC = 0, /** initial assoc */ - WLC_E_REASON_LOW_RSSI = 1, /** roamed due to low RSSI */ - WLC_E_REASON_DEAUTH = 2, /** roamed due to DEAUTH indication */ - WLC_E_REASON_DISASSOC = 3, /** roamed due to DISASSOC indication */ - WLC_E_REASON_BCNS_LOST = 4, /** roamed due to lost beacons */ - WLC_E_REASON_FAST_ROAM_FAILED = 5, /** roamed due to fast roam failure */ - WLC_E_REASON_DIRECTED_ROAM = 6, /** roamed due to request by AP */ - WLC_E_REASON_TSPEC_REJECTED = 7, /** roamed due to TSPEC rejection */ - WLC_E_REASON_BETTER_AP = 8, /** roamed due to finding better AP */ - - /* prune reason codes */ - WLC_E_PRUNE_ENCR_MISMATCH = 1 + WLC_E_PRUNE_REASON_OFFSET, /** encryption mismatch */ - WLC_E_PRUNE_BCAST_BSSID = 2 + WLC_E_PRUNE_REASON_OFFSET, /** AP uses a broadcast BSSID */ - WLC_E_PRUNE_MAC_DENY = 3 + WLC_E_PRUNE_REASON_OFFSET, /** STA's MAC addr is in AP's MAC deny list */ - WLC_E_PRUNE_MAC_NA = 4 + WLC_E_PRUNE_REASON_OFFSET, /** STA's MAC addr is not in AP's MAC allow list */ - WLC_E_PRUNE_REG_PASSV = 5 + WLC_E_PRUNE_REASON_OFFSET, /** AP not allowed due to regulatory restriction */ - WLC_E_PRUNE_SPCT_MGMT = 6 + WLC_E_PRUNE_REASON_OFFSET, /** AP does not support STA locale spectrum mgmt */ - WLC_E_PRUNE_RADAR = 7 + WLC_E_PRUNE_REASON_OFFSET, /** AP is on a radar channel of STA locale */ - WLC_E_RSN_MISMATCH = 8 + WLC_E_PRUNE_REASON_OFFSET, /** STA does not support AP's RSN */ - WLC_E_PRUNE_NO_COMMON_RATES = 9 + WLC_E_PRUNE_REASON_OFFSET, /** No rates in common with AP */ - WLC_E_PRUNE_BASIC_RATES = 10 + WLC_E_PRUNE_REASON_OFFSET, /** STA does not support all basic rates of BSS */ - WLC_E_PRUNE_CCXFAST_PREVAP = 11 + WLC_E_PRUNE_REASON_OFFSET, /** CCX FAST ROAM: prune previous AP */ - WLC_E_PRUNE_CIPHER_NA = 12 + WLC_E_PRUNE_REASON_OFFSET, /** BSS's cipher not supported */ - WLC_E_PRUNE_KNOWN_STA = 13 + WLC_E_PRUNE_REASON_OFFSET, /** AP is already known to us as a STA */ - WLC_E_PRUNE_CCXFAST_DROAM = 14 + WLC_E_PRUNE_REASON_OFFSET, /** CCX FAST ROAM: prune unqualified AP */ - WLC_E_PRUNE_WDS_PEER = 15 + WLC_E_PRUNE_REASON_OFFSET, /** AP is already known to us as a WDS peer */ - WLC_E_PRUNE_QBSS_LOAD = 16 + WLC_E_PRUNE_REASON_OFFSET, /** QBSS LOAD - AAC is too low */ - WLC_E_PRUNE_HOME_AP = 17 + WLC_E_PRUNE_REASON_OFFSET, /** prune home AP */ - WLC_E_PRUNE_AP_BLOCKED = 18 + WLC_E_PRUNE_REASON_OFFSET, /** prune blocked AP */ - WLC_E_PRUNE_NO_DIAG_SUPPORT = 19 + WLC_E_PRUNE_REASON_OFFSET, /** prune due to diagnostic mode not supported */ - - /* WPA failure reason codes carried in the WLC_E_PSK_SUP event */ - WLC_E_SUP_OTHER = 0 + WLC_E_SUP_REASON_OFFSET, /** Other reason */ - WLC_E_SUP_DECRYPT_KEY_DATA = 1 + WLC_E_SUP_REASON_OFFSET, /** Decryption of key data failed */ - WLC_E_SUP_BAD_UCAST_WEP128 = 2 + WLC_E_SUP_REASON_OFFSET, /** Illegal use of ucast WEP128 */ - WLC_E_SUP_BAD_UCAST_WEP40 = 3 + WLC_E_SUP_REASON_OFFSET, /** Illegal use of ucast WEP40 */ - WLC_E_SUP_UNSUP_KEY_LEN = 4 + WLC_E_SUP_REASON_OFFSET, /** Unsupported key length */ - WLC_E_SUP_PW_KEY_CIPHER = 5 + WLC_E_SUP_REASON_OFFSET, /** Unicast cipher mismatch in pairwise key */ - WLC_E_SUP_MSG3_TOO_MANY_IE = 6 + WLC_E_SUP_REASON_OFFSET, /** WPA IE contains > 1 RSN IE in key msg 3 */ - WLC_E_SUP_MSG3_IE_MISMATCH = 7 + WLC_E_SUP_REASON_OFFSET, /** WPA IE mismatch in key message 3 */ - WLC_E_SUP_NO_INSTALL_FLAG = 8 + WLC_E_SUP_REASON_OFFSET, /** INSTALL flag unset in 4-way msg */ - WLC_E_SUP_MSG3_NO_GTK = 9 + WLC_E_SUP_REASON_OFFSET, /** encapsulated GTK missing from msg 3 */ - WLC_E_SUP_GRP_KEY_CIPHER = 10 + WLC_E_SUP_REASON_OFFSET, /** Multicast cipher mismatch in group key */ - WLC_E_SUP_GRP_MSG1_NO_GTK = 11 + WLC_E_SUP_REASON_OFFSET, /** encapsulated GTK missing from group msg 1 */ - WLC_E_SUP_GTK_DECRYPT_FAIL = 12 + WLC_E_SUP_REASON_OFFSET, /** GTK decrypt failure */ - WLC_E_SUP_SEND_FAIL = 13 + WLC_E_SUP_REASON_OFFSET, /** message send failure */ - WLC_E_SUP_DEAUTH = 14 + WLC_E_SUP_REASON_OFFSET, /** received FC_DEAUTH */ - WLC_E_SUP_WPA_PSK_TMO = 15 + WLC_E_SUP_REASON_OFFSET, /** WPA PSK 4-way handshake timeout */ - - DOT11_RC_RESERVED = 0 + WLC_E_DOT11_RC_REASON_OFFSET, /* d11 RC reserved */ - DOT11_RC_UNSPECIFIED = 1 + WLC_E_DOT11_RC_REASON_OFFSET, /* Unspecified reason */ - DOT11_RC_AUTH_INVAL = 2 + WLC_E_DOT11_RC_REASON_OFFSET, /* Previous authentication no longer valid */ - DOT11_RC_DEAUTH_LEAVING = 3 + WLC_E_DOT11_RC_REASON_OFFSET, /* Deauthenticated because sending station is leaving (or has left) IBSS or ESS */ - DOT11_RC_INACTIVITY = 4 + WLC_E_DOT11_RC_REASON_OFFSET, /* Disassociated due to inactivity */ - DOT11_RC_BUSY = 5 + WLC_E_DOT11_RC_REASON_OFFSET, /* Disassociated because AP is unable to handle all currently associated stations */ - DOT11_RC_INVAL_CLASS_2 = 6 + WLC_E_DOT11_RC_REASON_OFFSET, /* Class 2 frame received from nonauthenticated station */ - DOT11_RC_INVAL_CLASS_3 = 7 + WLC_E_DOT11_RC_REASON_OFFSET, /* Class 3 frame received from nonassociated station */ - DOT11_RC_DISASSOC_LEAVING = 8 + WLC_E_DOT11_RC_REASON_OFFSET, /* Disassociated because sending station is leaving (or has left) BSS */ - DOT11_RC_NOT_AUTH = 9 + WLC_E_DOT11_RC_REASON_OFFSET, /* Station requesting (re)association is not * authenticated with responding station */ - DOT11_RC_BAD_PC = 10 + WLC_E_DOT11_RC_REASON_OFFSET, /* Unacceptable power capability element */ - DOT11_RC_BAD_CHANNELS = 11 + WLC_E_DOT11_RC_REASON_OFFSET, /* Unacceptable supported channels element */ - /* 12 is unused */ - /* XXX 13-23 are WPA/802.11i reason codes defined in proto/wpa.h */ - /* 32-39 are QSTA specific reasons added in 11e */ - DOT11_RC_UNSPECIFIED_QOS = 32 + WLC_E_DOT11_RC_REASON_OFFSET, /* unspecified QoS-related reason */ - DOT11_RC_INSUFFCIENT_BW = 33 + WLC_E_DOT11_RC_REASON_OFFSET, /* QAP lacks sufficient bandwidth */ - DOT11_RC_EXCESSIVE_FRAMES = 34 + WLC_E_DOT11_RC_REASON_OFFSET, /* excessive number of frames need ack */ - DOT11_RC_TX_OUTSIDE_TXOP = 35 + WLC_E_DOT11_RC_REASON_OFFSET, /* transmitting outside the limits of txop */ - DOT11_RC_LEAVING_QBSS = 36 + WLC_E_DOT11_RC_REASON_OFFSET, /* QSTA is leaving the QBSS (or restting) */ - DOT11_RC_BAD_MECHANISM = 37 + WLC_E_DOT11_RC_REASON_OFFSET, /* does not want to use the mechanism */ - DOT11_RC_SETUP_NEEDED = 38 + WLC_E_DOT11_RC_REASON_OFFSET, /* mechanism needs a setup */ - DOT11_RC_TIMEOUT = 39 + WLC_E_DOT11_RC_REASON_OFFSET, /* timeout */ - DOT11_RC_MAX = 23 + WLC_E_DOT11_RC_REASON_OFFSET, /* Reason codes > 23 are reserved */ - - WLC_E_REASON_FORCE_32_BIT = 0x7FFFFFFE /** Force enum to be stored in 32 bit variable */ + /* roam reason codes */ + WLC_E_REASON_INITIAL_ASSOC = 0, /** initial assoc */ + WLC_E_REASON_LOW_RSSI = 1, /** roamed due to low RSSI */ + WLC_E_REASON_DEAUTH = 2, /** roamed due to DEAUTH indication */ + WLC_E_REASON_DISASSOC = 3, /** roamed due to DISASSOC indication */ + WLC_E_REASON_BCNS_LOST = 4, /** roamed due to lost beacons */ + WLC_E_REASON_FAST_ROAM_FAILED = 5, /** roamed due to fast roam failure */ + WLC_E_REASON_DIRECTED_ROAM = 6, /** roamed due to request by AP */ + WLC_E_REASON_TSPEC_REJECTED = 7, /** roamed due to TSPEC rejection */ + WLC_E_REASON_BETTER_AP = 8, /** roamed due to finding better AP */ + + /* prune reason codes */ + WLC_E_PRUNE_ENCR_MISMATCH = 1 + WLC_E_PRUNE_REASON_OFFSET, /** encryption mismatch */ + WLC_E_PRUNE_BCAST_BSSID = 2 + WLC_E_PRUNE_REASON_OFFSET, /** AP uses a broadcast BSSID */ + WLC_E_PRUNE_MAC_DENY = 3 + WLC_E_PRUNE_REASON_OFFSET, /** STA's MAC addr is in AP's MAC deny list */ + WLC_E_PRUNE_MAC_NA = 4 + WLC_E_PRUNE_REASON_OFFSET, /** STA's MAC addr is not in AP's MAC allow list */ + WLC_E_PRUNE_REG_PASSV = 5 + WLC_E_PRUNE_REASON_OFFSET, /** AP not allowed due to regulatory restriction */ + WLC_E_PRUNE_SPCT_MGMT = 6 + WLC_E_PRUNE_REASON_OFFSET, /** AP does not support STA locale spectrum mgmt */ + WLC_E_PRUNE_RADAR = 7 + WLC_E_PRUNE_REASON_OFFSET, /** AP is on a radar channel of STA locale */ + WLC_E_RSN_MISMATCH = 8 + WLC_E_PRUNE_REASON_OFFSET, /** STA does not support AP's RSN */ + WLC_E_PRUNE_NO_COMMON_RATES = 9 + WLC_E_PRUNE_REASON_OFFSET, /** No rates in common with AP */ + WLC_E_PRUNE_BASIC_RATES = 10 + WLC_E_PRUNE_REASON_OFFSET, /** STA does not support all basic rates of BSS */ + WLC_E_PRUNE_CCXFAST_PREVAP = 11 + WLC_E_PRUNE_REASON_OFFSET, /** CCX FAST ROAM: prune previous AP */ + WLC_E_PRUNE_CIPHER_NA = 12 + WLC_E_PRUNE_REASON_OFFSET, /** BSS's cipher not supported */ + WLC_E_PRUNE_KNOWN_STA = 13 + WLC_E_PRUNE_REASON_OFFSET, /** AP is already known to us as a STA */ + WLC_E_PRUNE_CCXFAST_DROAM = 14 + WLC_E_PRUNE_REASON_OFFSET, /** CCX FAST ROAM: prune unqualified AP */ + WLC_E_PRUNE_WDS_PEER = 15 + WLC_E_PRUNE_REASON_OFFSET, /** AP is already known to us as a WDS peer */ + WLC_E_PRUNE_QBSS_LOAD = 16 + WLC_E_PRUNE_REASON_OFFSET, /** QBSS LOAD - AAC is too low */ + WLC_E_PRUNE_HOME_AP = 17 + WLC_E_PRUNE_REASON_OFFSET, /** prune home AP */ + WLC_E_PRUNE_AP_BLOCKED = 18 + WLC_E_PRUNE_REASON_OFFSET, /** prune blocked AP */ + WLC_E_PRUNE_NO_DIAG_SUPPORT = 19 + WLC_E_PRUNE_REASON_OFFSET, /** prune due to diagnostic mode not supported */ + + /* WPA failure reason codes carried in the WLC_E_PSK_SUP event */ + WLC_E_SUP_OTHER = 0 + WLC_E_SUP_REASON_OFFSET, /** Other reason */ + WLC_E_SUP_DECRYPT_KEY_DATA = 1 + WLC_E_SUP_REASON_OFFSET, /** Decryption of key data failed */ + WLC_E_SUP_BAD_UCAST_WEP128 = 2 + WLC_E_SUP_REASON_OFFSET, /** Illegal use of ucast WEP128 */ + WLC_E_SUP_BAD_UCAST_WEP40 = 3 + WLC_E_SUP_REASON_OFFSET, /** Illegal use of ucast WEP40 */ + WLC_E_SUP_UNSUP_KEY_LEN = 4 + WLC_E_SUP_REASON_OFFSET, /** Unsupported key length */ + WLC_E_SUP_PW_KEY_CIPHER = 5 + WLC_E_SUP_REASON_OFFSET, /** Unicast cipher mismatch in pairwise key */ + WLC_E_SUP_MSG3_TOO_MANY_IE = 6 + WLC_E_SUP_REASON_OFFSET, /** WPA IE contains > 1 RSN IE in key msg 3 */ + WLC_E_SUP_MSG3_IE_MISMATCH = 7 + WLC_E_SUP_REASON_OFFSET, /** WPA IE mismatch in key message 3 */ + WLC_E_SUP_NO_INSTALL_FLAG = 8 + WLC_E_SUP_REASON_OFFSET, /** INSTALL flag unset in 4-way msg */ + WLC_E_SUP_MSG3_NO_GTK = 9 + WLC_E_SUP_REASON_OFFSET, /** encapsulated GTK missing from msg 3 */ + WLC_E_SUP_GRP_KEY_CIPHER = 10 + WLC_E_SUP_REASON_OFFSET, /** Multicast cipher mismatch in group key */ + WLC_E_SUP_GRP_MSG1_NO_GTK = 11 + WLC_E_SUP_REASON_OFFSET, /** encapsulated GTK missing from group msg 1 */ + WLC_E_SUP_GTK_DECRYPT_FAIL = 12 + WLC_E_SUP_REASON_OFFSET, /** GTK decrypt failure */ + WLC_E_SUP_SEND_FAIL = 13 + WLC_E_SUP_REASON_OFFSET, /** message send failure */ + WLC_E_SUP_DEAUTH = 14 + WLC_E_SUP_REASON_OFFSET, /** received FC_DEAUTH */ + WLC_E_SUP_WPA_PSK_TMO = 15 + WLC_E_SUP_REASON_OFFSET, /** WPA PSK 4-way handshake timeout */ + + DOT11_RC_RESERVED = 0 + WLC_E_DOT11_RC_REASON_OFFSET, /* d11 RC reserved */ + DOT11_RC_UNSPECIFIED = 1 + WLC_E_DOT11_RC_REASON_OFFSET, /* Unspecified reason */ + DOT11_RC_AUTH_INVAL = 2 + WLC_E_DOT11_RC_REASON_OFFSET, /* Previous authentication no longer valid */ + DOT11_RC_DEAUTH_LEAVING = 3 + WLC_E_DOT11_RC_REASON_OFFSET, /* Deauthenticated because sending station is leaving (or has left) IBSS or ESS */ + DOT11_RC_INACTIVITY = 4 + WLC_E_DOT11_RC_REASON_OFFSET, /* Disassociated due to inactivity */ + DOT11_RC_BUSY = 5 + WLC_E_DOT11_RC_REASON_OFFSET, /* Disassociated because AP is unable to handle all currently associated stations */ + DOT11_RC_INVAL_CLASS_2 = 6 + WLC_E_DOT11_RC_REASON_OFFSET, /* Class 2 frame received from nonauthenticated station */ + DOT11_RC_INVAL_CLASS_3 = 7 + WLC_E_DOT11_RC_REASON_OFFSET, /* Class 3 frame received from nonassociated station */ + DOT11_RC_DISASSOC_LEAVING = 8 + WLC_E_DOT11_RC_REASON_OFFSET, /* Disassociated because sending station is leaving (or has left) BSS */ + DOT11_RC_NOT_AUTH = 9 + WLC_E_DOT11_RC_REASON_OFFSET, /* Station requesting (re)association is not * authenticated with responding station */ + DOT11_RC_BAD_PC = 10 + WLC_E_DOT11_RC_REASON_OFFSET, /* Unacceptable power capability element */ + DOT11_RC_BAD_CHANNELS = 11 + WLC_E_DOT11_RC_REASON_OFFSET, /* Unacceptable supported channels element */ + /* 12 is unused */ + /* XXX 13-23 are WPA/802.11i reason codes defined in proto/wpa.h */ + /* 32-39 are QSTA specific reasons added in 11e */ + DOT11_RC_UNSPECIFIED_QOS = 32 + WLC_E_DOT11_RC_REASON_OFFSET, /* unspecified QoS-related reason */ + DOT11_RC_INSUFFCIENT_BW = 33 + WLC_E_DOT11_RC_REASON_OFFSET, /* QAP lacks sufficient bandwidth */ + DOT11_RC_EXCESSIVE_FRAMES = 34 + WLC_E_DOT11_RC_REASON_OFFSET, /* excessive number of frames need ack */ + DOT11_RC_TX_OUTSIDE_TXOP = 35 + WLC_E_DOT11_RC_REASON_OFFSET, /* transmitting outside the limits of txop */ + DOT11_RC_LEAVING_QBSS = 36 + WLC_E_DOT11_RC_REASON_OFFSET, /* QSTA is leaving the QBSS (or restting) */ + DOT11_RC_BAD_MECHANISM = 37 + WLC_E_DOT11_RC_REASON_OFFSET, /* does not want to use the mechanism */ + DOT11_RC_SETUP_NEEDED = 38 + WLC_E_DOT11_RC_REASON_OFFSET, /* mechanism needs a setup */ + DOT11_RC_TIMEOUT = 39 + WLC_E_DOT11_RC_REASON_OFFSET, /* timeout */ + DOT11_RC_MAX = 23 + WLC_E_DOT11_RC_REASON_OFFSET, /* Reason codes > 23 are reserved */ + + WLC_E_REASON_FORCE_32_BIT = 0x7FFFFFFE /** Force enum to be stored in 32 bit variable */ } wl_event_reason_t; #endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_IOCTL_H */ diff --git a/drivers/wireless/ieee80211/bcmf_netdev.c b/drivers/wireless/ieee80211/bcmf_netdev.c index fafae13bb2..0d7e38c935 100644 --- a/drivers/wireless/ieee80211/bcmf_netdev.c +++ b/drivers/wireless/ieee80211/bcmf_netdev.c @@ -755,9 +755,10 @@ static int bcmf_ifdown(FAR struct net_driver_s *dev) static void bcmf_txavail_work(FAR void *arg) { - // wlinfo("Entry\n"); FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)arg; + // wlinfo("Entry\n"); + /* Lock the network and serialize driver operations if necessary. * NOTE: Serialization is only required in the case where the driver work * is performed on an LP worker thread and where more than one LP worker @@ -991,23 +992,23 @@ static int bcmf_ioctl(FAR struct net_driver_s *dev, int cmd, switch (cmd) { case SIOCSIWSCAN: - ret = bcmf_wl_start_scan(priv, (struct ifreq*)arg); + ret = bcmf_wl_start_scan(priv, (struct ifreq *)arg); break; case SIOCGIWSCAN: - ret = bcmf_wl_get_scan_results(priv, (struct ifreq*)arg); + ret = bcmf_wl_get_scan_results(priv, (struct ifreq *)arg); break; case SIOCSIFHWADDR: /* Set device MAC address */ - ret = bcmf_wl_set_mac_address(priv, (struct ifreq*)arg); + ret = bcmf_wl_set_mac_address(priv, (struct ifreq *)arg); break; case SIOCSIWAUTH: - ret = bcmf_wl_set_auth_param(priv, (struct iwreq*)arg); + ret = bcmf_wl_set_auth_param(priv, (struct iwreq *)arg); break; case SIOCSIWENCODEEXT: - ret = bcmf_wl_set_encode_ext(priv, (struct iwreq*)arg); + ret = bcmf_wl_set_encode_ext(priv, (struct iwreq *)arg); break; case SIOCSIWFREQ: /* Set channel/frequency (Hz) */ @@ -1021,7 +1022,7 @@ static int bcmf_ioctl(FAR struct net_driver_s *dev, int cmd, break; case SIOCSIWMODE: /* Set operation mode */ - ret = bcmf_wl_set_mode(priv, (struct iwreq*)arg); + ret = bcmf_wl_set_mode(priv, (struct iwreq *)arg); break; case SIOCGIWMODE: /* Get operation mode */ @@ -1040,7 +1041,7 @@ static int bcmf_ioctl(FAR struct net_driver_s *dev, int cmd, break; case SIOCSIWESSID: /* Set ESSID (network name) */ - ret = bcmf_wl_set_ssid(priv, (struct iwreq*)arg); + ret = bcmf_wl_set_ssid(priv, (struct iwreq *)arg); break; case SIOCGIWESSID: /* Get ESSID */ diff --git a/drivers/wireless/ieee80211/bcmf_sdio.c b/drivers/wireless/ieee80211/bcmf_sdio.c index 4d6324090a..7433903795 100644 --- a/drivers/wireless/ieee80211/bcmf_sdio.c +++ b/drivers/wireless/ieee80211/bcmf_sdio.c @@ -114,7 +114,8 @@ static int bcmf_sdio_find_block_size(unsigned int size); FAR struct bcmf_dev_s *g_sdio_priv; /* Buffer pool for SDIO bus interface - This pool is shared between all driver devices */ + * This pool is shared between all driver devices + */ static struct bcmf_sdio_frame g_pktframes[BCMF_PKT_POOL_SIZE]; @@ -126,11 +127,12 @@ static struct bcmf_sdio_frame g_pktframes[BCMF_PKT_POOL_SIZE]; int bcmf_oob_irq(int irq, FAR void *context, FAR void *arg) { - FAR struct bcmf_sdio_dev_s *sbus = (struct bcmf_sdio_dev_s*)arg; + FAR struct bcmf_sdio_dev_s *sbus = (struct bcmf_sdio_dev_s *)arg; if (sbus->ready) { /* Signal bmcf thread */ + sbus->irq_pending = true; sem_post(&sbus->thread_signal); @@ -360,7 +362,7 @@ int bcmf_bus_setup_interrupts(FAR struct bcmf_sdio_dev_s *sbus) /* Configure gpio interrupt pin */ - bcmf_board_setup_oob_irq(sbus->minor, bcmf_oob_irq, (void*)sbus); + bcmf_board_setup_oob_irq(sbus->minor, bcmf_oob_irq, (void *)sbus); /* Enable function 2 interrupt */ @@ -455,16 +457,18 @@ int bcmf_sdio_find_block_size(unsigned int size) { int ret = 0; int size_copy = size; - while (size_copy) { - size_copy >>= 1; - ret++; - } + while (size_copy) + { + size_copy >>= 1; + ret++; + } if (size & (size-1)) { - return 1<tx_queue); sq_init(&sbus->rx_queue); sq_init(&sbus->free_queue); @@ -599,6 +604,7 @@ int bcmf_bus_sdio_initialize(FAR struct bcmf_dev_s *priv, { goto exit_free_bus; } + if ((ret = sem_setprotocol(&sbus->thread_signal, SEM_PRIO_NONE)) != OK) { goto exit_free_bus; @@ -708,7 +714,7 @@ int bcmf_chipinitialize(FAR struct bcmf_sdio_dev_s *sbus) #ifdef CONFIG_IEEE80211_BROADCOM_BCM43362 case SDIO_DEVICE_ID_BROADCOM_43362: wlinfo("bcm43362 chip detected\n"); - sbus->chip = (struct bcmf_sdio_chip*)&bcmf_43362_config_sdio; + sbus->chip = (struct bcmf_sdio_chip *)&bcmf_43362_config_sdio; break; #endif default: @@ -720,8 +726,8 @@ int bcmf_chipinitialize(FAR struct bcmf_sdio_dev_s *sbus) void bcmf_sdio_waitdog_timeout(int argc, wdparm_t arg1, ...) { - FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s*)arg1; - FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s*)priv->bus; + FAR struct bcmf_dev_s *priv = (FAR struct bcmf_dev_s *)arg1; + FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s *)priv->bus; /* Notify bcmf thread */ @@ -733,7 +739,7 @@ int bcmf_sdio_thread(int argc, char **argv) { int ret; FAR struct bcmf_dev_s *priv = g_sdio_priv; - FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s*)priv->bus; + FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s *)priv->bus; wlinfo("Enter\n"); @@ -788,7 +794,8 @@ int bcmf_sdio_thread(int argc, char **argv) do { ret = bcmf_sdpcm_readframe(priv); - } while (ret == OK); + } + while (ret == OK); if (ret == -ENODATA) { @@ -803,7 +810,8 @@ int bcmf_sdio_thread(int argc, char **argv) do { ret = bcmf_sdpcm_sendframe(priv); - } while (ret == OK); + } + while (ret == OK); /* Check if RX frames are available */ @@ -825,10 +833,10 @@ int bcmf_sdio_thread(int argc, char **argv) return 0; } -struct bcmf_sdio_frame* bcmf_sdio_allocate_frame(FAR struct bcmf_dev_s *priv, +struct bcmf_sdio_frame *bcmf_sdio_allocate_frame(FAR struct bcmf_dev_s *priv, bool block, bool tx) { - FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s*)priv->bus; + FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s *)priv->bus; struct bcmf_sdio_frame *sframe; dq_entry_t *entry = NULL; @@ -879,7 +887,7 @@ void bcmf_sdio_free_frame(FAR struct bcmf_dev_s *priv, struct bcmf_sdio_frame *sframe) { // wlinfo("free %p\n", sframe); - FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s*)priv->bus; + FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s *)priv->bus; if (sem_wait(&sbus->queue_mutex)) { @@ -893,4 +901,4 @@ void bcmf_sdio_free_frame(FAR struct bcmf_dev_s *priv, sbus->tx_queue_count -= 1; } sem_post(&sbus->queue_mutex); -} \ No newline at end of file +} diff --git a/drivers/wireless/ieee80211/bcmf_sdio.h b/drivers/wireless/ieee80211/bcmf_sdio.h index d21365a1c4..692b1a9251 100644 --- a/drivers/wireless/ieee80211/bcmf_sdio.h +++ b/drivers/wireless/ieee80211/bcmf_sdio.h @@ -106,12 +106,13 @@ struct bcmf_sdio_dev_s /* Structure used to manage SDIO frames */ -struct bcmf_sdio_frame { - struct bcmf_frame_s header; - bool tx; - dq_entry_t list_entry; - uint8_t data[HEADER_SIZE + MAX_NET_DEV_MTU + - CONFIG_NET_GUARDSIZE]; +struct bcmf_sdio_frame +{ + struct bcmf_frame_s header; + bool tx; + dq_entry_t list_entry; + uint8_t data[HEADER_SIZE + MAX_NET_DEV_MTU + + CONFIG_NET_GUARDSIZE]; }; /**************************************************************************** @@ -137,7 +138,7 @@ int bcmf_read_reg(FAR struct bcmf_sdio_dev_s *sbus, uint8_t function, int bcmf_write_reg(FAR struct bcmf_sdio_dev_s *sbus, uint8_t function, uint32_t address, uint8_t reg); -struct bcmf_sdio_frame* bcmf_sdio_allocate_frame(FAR struct bcmf_dev_s *priv, +struct bcmf_sdio_frame *bcmf_sdio_allocate_frame(FAR struct bcmf_dev_s *priv, bool block, bool tx); void bcmf_sdio_free_frame(FAR struct bcmf_dev_s *priv, diff --git a/drivers/wireless/ieee80211/bcmf_sdio_core.h b/drivers/wireless/ieee80211/bcmf_sdio_core.h index eb4f4a9803..6131b1be3a 100644 --- a/drivers/wireless/ieee80211/bcmf_sdio_core.h +++ b/drivers/wireless/ieee80211/bcmf_sdio_core.h @@ -1,4 +1,4 @@ -/* +/**************************************************************************** * Copyright (c) 2011 Broadcom Corporation * * Permission to use, copy, modify, and/or distribute this software for any @@ -12,7 +12,8 @@ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION * OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF OR IN * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - */ + * + ****************************************************************************/ #ifndef __DRIVERS_WIRELESS_IEEE80211_BCMF_SDIO_CORE_H #define __DRIVERS_WIRELESS_IEEE80211_BCMF_SDIO_CORE_H @@ -26,6 +27,7 @@ #endif /* SDIO device ID */ + #define SDIO_DEVICE_ID_BROADCOM_43143 43143 #define SDIO_DEVICE_ID_BROADCOM_43241 0x4324 #define SDIO_DEVICE_ID_BROADCOM_4329 0x4329 @@ -34,10 +36,10 @@ #define SDIO_DEVICE_ID_BROADCOM_4335_4339 0x4335 #define SDIO_DEVICE_ID_BROADCOM_43362 43362 -/* - * Core reg address translation. +/* Core reg address translation. * Both macro's returns a 32 bits byte address on the backplane bus. */ + #define CORE_CC_REG(base, field) \ (base + offsetof(struct chipcregs, field)) #define CORE_BUS_REG(base, field) \ @@ -68,152 +70,157 @@ #define SMB_USE_OOB (1 << 2) /* Use OOB Wakeup */ #define SMB_DEV_INT (1 << 3) /* Miscellaneous Interrupt */ -enum { - CHIPCOMMON_CORE_ID = 0, - DOT11MAC_CORE_ID, - SDIOD_CORE_ID, - WLAN_ARMCM3_CORE_ID, - SOCSRAM_CORE_ID, - MAX_CORE_ID +enum +{ + CHIPCOMMON_CORE_ID = 0, + DOT11MAC_CORE_ID, + SDIOD_CORE_ID, + WLAN_ARMCM3_CORE_ID, + SOCSRAM_CORE_ID, + MAX_CORE_ID }; -struct chip_core_info { - uint16_t id; - uint16_t rev; - uint32_t base; - uint32_t wrapbase; - uint32_t caps; - uint32_t cib; +struct chip_core_info +{ + uint16_t id; + uint16_t rev; + uint32_t base; + uint32_t wrapbase; + uint32_t caps; + uint32_t cib; }; -struct sbconfig { - uint8_t PAD[0xf00]; - uint32_t PAD[2]; - uint32_t sbipsflag; /* initiator port ocp slave flag */ - uint32_t PAD[3]; - uint32_t sbtpsflag; /* target port ocp slave flag */ - uint32_t PAD[11]; - uint32_t sbtmerrloga; /* (sonics >= 2.3) */ - uint32_t PAD; - uint32_t sbtmerrlog; /* (sonics >= 2.3) */ - uint32_t PAD[3]; - uint32_t sbadmatch3; /* address match3 */ - uint32_t PAD; - uint32_t sbadmatch2; /* address match2 */ - uint32_t PAD; - uint32_t sbadmatch1; /* address match1 */ - uint32_t PAD[7]; - uint32_t sbimstate; /* initiator agent state */ - uint32_t sbintvec; /* interrupt mask */ - uint32_t sbtmstatelow; /* target state */ - uint32_t sbtmstatehigh; /* target state */ - uint32_t sbbwa0; /* bandwidth allocation table0 */ - uint32_t PAD; - uint32_t sbimconfiglow; /* initiator configuration */ - uint32_t sbimconfighigh; /* initiator configuration */ - uint32_t sbadmatch0; /* address match0 */ - uint32_t PAD; - uint32_t sbtmconfiglow; /* target configuration */ - uint32_t sbtmconfighigh; /* target configuration */ - uint32_t sbbconfig; /* broadcast configuration */ - uint32_t PAD; - uint32_t sbbstate; /* broadcast state */ - uint32_t PAD[3]; - uint32_t sbactcnfg; /* activate configuration */ - uint32_t PAD[3]; - uint32_t sbflagst; /* current sbflags */ - uint32_t PAD[3]; - uint32_t sbidlow; /* identification */ - uint32_t sbidhigh; /* identification */ +struct sbconfig +{ + uint8_t PAD[0xf00]; + uint32_t PAD[2]; + uint32_t sbipsflag; /* initiator port ocp slave flag */ + uint32_t PAD[3]; + uint32_t sbtpsflag; /* target port ocp slave flag */ + uint32_t PAD[11]; + uint32_t sbtmerrloga; /* (sonics >= 2.3) */ + uint32_t PAD; + uint32_t sbtmerrlog; /* (sonics >= 2.3) */ + uint32_t PAD[3]; + uint32_t sbadmatch3; /* address match3 */ + uint32_t PAD; + uint32_t sbadmatch2; /* address match2 */ + uint32_t PAD; + uint32_t sbadmatch1; /* address match1 */ + uint32_t PAD[7]; + uint32_t sbimstate; /* initiator agent state */ + uint32_t sbintvec; /* interrupt mask */ + uint32_t sbtmstatelow; /* target state */ + uint32_t sbtmstatehigh; /* target state */ + uint32_t sbbwa0; /* bandwidth allocation table0 */ + uint32_t PAD; + uint32_t sbimconfiglow; /* initiator configuration */ + uint32_t sbimconfighigh; /* initiator configuration */ + uint32_t sbadmatch0; /* address match0 */ + uint32_t PAD; + uint32_t sbtmconfiglow; /* target configuration */ + uint32_t sbtmconfighigh; /* target configuration */ + uint32_t sbbconfig; /* broadcast configuration */ + uint32_t PAD; + uint32_t sbbstate; /* broadcast state */ + uint32_t PAD[3]; + uint32_t sbactcnfg; /* activate configuration */ + uint32_t PAD[3]; + uint32_t sbflagst; /* current sbflags */ + uint32_t PAD[3]; + uint32_t sbidlow; /* identification */ + uint32_t sbidhigh; /* identification */ }; /* sdio core registers */ -struct sdpcmd_regs { - uint32_t corecontrol; /* 0x00, rev8 */ - uint32_t corestatus; /* rev8 */ - uint32_t PAD[1]; - uint32_t biststatus; /* rev8 */ - - /* PCMCIA access */ - uint16_t pcmciamesportaladdr; /* 0x010, rev8 */ - uint16_t PAD[1]; - uint16_t pcmciamesportalmask; /* rev8 */ - uint16_t PAD[1]; - uint16_t pcmciawrframebc; /* rev8 */ - uint16_t PAD[1]; - uint16_t pcmciaunderflowtimer; /* rev8 */ - uint16_t PAD[1]; - - /* interrupt */ - uint32_t intstatus; /* 0x020, rev8 */ - uint32_t hostintmask; /* rev8 */ - uint32_t intmask; /* rev8 */ - uint32_t sbintstatus; /* rev8 */ - uint32_t sbintmask; /* rev8 */ - uint32_t funcintmask; /* rev4 */ - uint32_t PAD[2]; - uint32_t tosbmailbox; /* 0x040, rev8 */ - uint32_t tohostmailbox; /* rev8 */ - uint32_t tosbmailboxdata; /* rev8 */ - uint32_t tohostmailboxdata; /* rev8 */ - - /* synchronized access to registers in SDIO clock domain */ - uint32_t sdioaccess; /* 0x050, rev8 */ - uint32_t PAD[3]; - - /* PCMCIA frame control */ - uint8_t pcmciaframectrl; /* 0x060, rev8 */ - uint8_t PAD[3]; - uint8_t pcmciawatermark; /* rev8 */ - uint8_t PAD[155]; - - /* interrupt batching control */ - uint32_t intrcvlazy; /* 0x100, rev8 */ - uint32_t PAD[3]; - - /* counters */ - uint32_t cmd52rd; /* 0x110, rev8 */ - uint32_t cmd52wr; /* rev8 */ - uint32_t cmd53rd; /* rev8 */ - uint32_t cmd53wr; /* rev8 */ - uint32_t abort; /* rev8 */ - uint32_t datacrcerror; /* rev8 */ - uint32_t rdoutofsync; /* rev8 */ - uint32_t wroutofsync; /* rev8 */ - uint32_t writebusy; /* rev8 */ - uint32_t readwait; /* rev8 */ - uint32_t readterm; /* rev8 */ - uint32_t writeterm; /* rev8 */ - uint32_t PAD[40]; - uint32_t clockctlstatus; /* rev8 */ - uint32_t PAD[7]; - - uint32_t PAD[128]; /* DMA engines */ - - /* SDIO/PCMCIA CIS region */ - char cis[512]; /* 0x400-0x5ff, rev6 */ - - /* PCMCIA function control registers */ - char pcmciafcr[256]; /* 0x600-6ff, rev6 */ - uint16_t PAD[55]; - - /* PCMCIA backplane access */ - uint16_t backplanecsr; /* 0x76E, rev6 */ - uint16_t backplaneaddr0; /* rev6 */ - uint16_t backplaneaddr1; /* rev6 */ - uint16_t backplaneaddr2; /* rev6 */ - uint16_t backplaneaddr3; /* rev6 */ - uint16_t backplanedata0; /* rev6 */ - uint16_t backplanedata1; /* rev6 */ - uint16_t backplanedata2; /* rev6 */ - uint16_t backplanedata3; /* rev6 */ - uint16_t PAD[31]; - - /* sprom "size" & "blank" info */ - uint16_t spromstatus; /* 0x7BE, rev2 */ - uint32_t PAD[464]; - - uint16_t PAD[0x80]; + +struct sdpcmd_regs +{ + uint32_t corecontrol; /* 0x00, rev8 */ + uint32_t corestatus; /* rev8 */ + uint32_t PAD[1]; + uint32_t biststatus; /* rev8 */ + + /* PCMCIA access */ + uint16_t pcmciamesportaladdr; /* 0x010, rev8 */ + uint16_t PAD[1]; + uint16_t pcmciamesportalmask; /* rev8 */ + uint16_t PAD[1]; + uint16_t pcmciawrframebc; /* rev8 */ + uint16_t PAD[1]; + uint16_t pcmciaunderflowtimer; /* rev8 */ + uint16_t PAD[1]; + + /* interrupt */ + uint32_t intstatus; /* 0x020, rev8 */ + uint32_t hostintmask; /* rev8 */ + uint32_t intmask; /* rev8 */ + uint32_t sbintstatus; /* rev8 */ + uint32_t sbintmask; /* rev8 */ + uint32_t funcintmask; /* rev4 */ + uint32_t PAD[2]; + uint32_t tosbmailbox; /* 0x040, rev8 */ + uint32_t tohostmailbox; /* rev8 */ + uint32_t tosbmailboxdata; /* rev8 */ + uint32_t tohostmailboxdata; /* rev8 */ + + /* synchronized access to registers in SDIO clock domain */ + uint32_t sdioaccess; /* 0x050, rev8 */ + uint32_t PAD[3]; + + /* PCMCIA frame control */ + uint8_t pcmciaframectrl; /* 0x060, rev8 */ + uint8_t PAD[3]; + uint8_t pcmciawatermark; /* rev8 */ + uint8_t PAD[155]; + + /* interrupt batching control */ + uint32_t intrcvlazy; /* 0x100, rev8 */ + uint32_t PAD[3]; + + /* counters */ + uint32_t cmd52rd; /* 0x110, rev8 */ + uint32_t cmd52wr; /* rev8 */ + uint32_t cmd53rd; /* rev8 */ + uint32_t cmd53wr; /* rev8 */ + uint32_t abort; /* rev8 */ + uint32_t datacrcerror; /* rev8 */ + uint32_t rdoutofsync; /* rev8 */ + uint32_t wroutofsync; /* rev8 */ + uint32_t writebusy; /* rev8 */ + uint32_t readwait; /* rev8 */ + uint32_t readterm; /* rev8 */ + uint32_t writeterm; /* rev8 */ + uint32_t PAD[40]; + uint32_t clockctlstatus; /* rev8 */ + uint32_t PAD[7]; + + uint32_t PAD[128]; /* DMA engines */ + + /* SDIO/PCMCIA CIS region */ + char cis[512]; /* 0x400-0x5ff, rev6 */ + + /* PCMCIA function control registers */ + char pcmciafcr[256]; /* 0x600-6ff, rev6 */ + uint16_t PAD[55]; + + /* PCMCIA backplane access */ + uint16_t backplanecsr; /* 0x76E, rev6 */ + uint16_t backplaneaddr0; /* rev6 */ + uint16_t backplaneaddr1; /* rev6 */ + uint16_t backplaneaddr2; /* rev6 */ + uint16_t backplaneaddr3; /* rev6 */ + uint16_t backplanedata0; /* rev6 */ + uint16_t backplanedata1; /* rev6 */ + uint16_t backplanedata2; /* rev6 */ + uint16_t backplanedata3; /* rev6 */ + uint16_t PAD[31]; + + /* sprom "size" & "blank" info */ + uint16_t spromstatus; /* 0x7BE, rev2 */ + uint32_t PAD[464]; + + uint16_t PAD[0x80]; }; #endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_SDIO_CORE_H */ diff --git a/drivers/wireless/ieee80211/bcmf_sdio_regs.h b/drivers/wireless/ieee80211/bcmf_sdio_regs.h index c92898af53..6959968524 100644 --- a/drivers/wireless/ieee80211/bcmf_sdio_regs.h +++ b/drivers/wireless/ieee80211/bcmf_sdio_regs.h @@ -1,4 +1,4 @@ -/* +/**************************************************************************** * Copyright (c) 2010 Broadcom Corporation * * Permission to use, copy, modify, and/or distribute this software for any @@ -12,7 +12,8 @@ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION * OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF OR IN * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. - */ + * + ****************************************************************************/ #ifndef __DRIVERS_WIRELESS_IEEE80211_BCMF_SDIO_REGS_H #define __DRIVERS_WIRELESS_IEEE80211_BCMF_SDIO_REGS_H @@ -24,28 +25,35 @@ #define SDIOD_FBR_SIZE 0x100 /* io_en */ + #define SDIO_FUNC_ENABLE_1 0x02 #define SDIO_FUNC_ENABLE_2 0x04 /* io_rdys */ + #define SDIO_FUNC_READY_1 0x02 #define SDIO_FUNC_READY_2 0x04 /* intr_status */ + #define INTR_STATUS_FUNC1 0x2 #define INTR_STATUS_FUNC2 0x4 /* Maximum number of I/O funcs */ + #define SDIOD_MAX_IOFUNCS 7 /* mask of register map */ + #define REG_F0_REG_MASK 0x7FF #define REG_F1_MISC_MASK 0x1FFFF /* as of sdiod rev 0, supports 3 functions */ + #define SBSDIO_NUM_FUNCTION 3 /* function 0 vendor specific CCCR registers */ + #define SDIO_CCCR_BRCM_CARDCAP 0xf0 #define SDIO_CCCR_BRCM_CARDCAP_CMD14_SUPPORT 0x02 #define SDIO_CCCR_BRCM_CARDCAP_CMD14_EXT 0x04 @@ -61,74 +69,140 @@ /* function 1 miscellaneous registers */ /* sprom command and status */ + #define SBSDIO_SPROM_CS 0x10000 + /* sprom info register */ + #define SBSDIO_SPROM_INFO 0x10001 + /* sprom indirect access data byte 0 */ + #define SBSDIO_SPROM_DATA_LOW 0x10002 + /* sprom indirect access data byte 1 */ + #define SBSDIO_SPROM_DATA_HIGH 0x10003 + /* sprom indirect access addr byte 0 */ + #define SBSDIO_SPROM_ADDR_LOW 0x10004 + /* sprom indirect access addr byte 0 */ + #define SBSDIO_SPROM_ADDR_HIGH 0x10005 + /* xtal_pu (gpio) output */ + #define SBSDIO_CHIP_CTRL_DATA 0x10006 + /* xtal_pu (gpio) enable */ + #define SBSDIO_CHIP_CTRL_EN 0x10007 + /* rev < 7, watermark for sdio device */ + #define SBSDIO_WATERMARK 0x10008 + /* control busy signal generation */ + #define SBSDIO_DEVICE_CTL 0x10009 + /* SB Address Window Low (b15) */ + #define SBSDIO_FUNC1_SBADDRLOW 0x1000A + /* SB Address Window Mid (b23:b16) */ + #define SBSDIO_FUNC1_SBADDRMID 0x1000B -/* SB Address Window High (b31:b24) */ + +/* SB Address Window High (b31:b24) */ + #define SBSDIO_FUNC1_SBADDRHIGH 0x1000C + /* Frame Control (frame term/abort) */ + #define SBSDIO_FUNC1_FRAMECTRL 0x1000D + /* Read Frame Terminate */ + #define SFC_RF_TERM (1 << 0) + /* Write Frame Terminate */ + #define SFC_WF_TERM (1 << 1) + /* CRC error for write out of sync */ + #define SFC_CRC4WOOS (1 << 2) + /* Abort all in-progress frames */ + #define SFC_ABORTALL (1 << 3) + /* ChipClockCSR (ALP/HT ctl/status) */ + #define SBSDIO_FUNC1_CHIPCLKCSR 0x1000E + /* Force ALP request to backplane */ + #define SBSDIO_FORCE_ALP 0x01 + /* Force HT request to backplane */ + #define SBSDIO_FORCE_HT 0x02 + /* Force ILP request to backplane */ + #define SBSDIO_FORCE_ILP 0x04 + /* Make ALP ready (power up xtal) */ + #define SBSDIO_ALP_AVAIL_REQ 0x08 + /* Make HT ready (power up PLL) */ + #define SBSDIO_HT_AVAIL_REQ 0x10 + /* Squelch clock requests from HW */ + #define SBSDIO_FORCE_HW_CLKREQ_OFF 0x20 + /* Status: ALP is ready */ + #define SBSDIO_ALP_AVAIL 0x40 + /* Status: HT is ready */ + #define SBSDIO_HT_AVAIL 0x80 /* SdioPullUp (on cmd, d0-d2) */ + #define SBSDIO_FUNC1_SDIOPULLUP 0x1000F + /* Write Frame Byte Count Low */ + #define SBSDIO_FUNC1_WFRAMEBCLO 0x10019 + /* Write Frame Byte Count High */ + #define SBSDIO_FUNC1_WFRAMEBCHI 0x1001A + /* Read Frame Byte Count Low */ + #define SBSDIO_FUNC1_RFRAMEBCLO 0x1001B + /* Read Frame Byte Count High */ + #define SBSDIO_FUNC1_RFRAMEBCHI 0x1001C + /* MesBusyCtl (rev 11) */ + #define SBSDIO_FUNC1_MESBUSYCTRL 0x1001D + /* Sdio Core Rev 12 */ + #define SBSDIO_FUNC1_WAKEUPCTRL 0x1001E #define SBSDIO_FUNC1_WCTRL_ALPWAIT_MASK 0x1 #define SBSDIO_FUNC1_WCTRL_ALPWAIT_SHIFT 0 @@ -155,9 +229,12 @@ /* function 1 OCP space */ /* sb offset addr is <= 15 bits, 32k */ + #define SBSDIO_SB_OFT_ADDR_MASK 0x07FFF #define SBSDIO_SB_OFT_ADDR_LIMIT 0x08000 + /* with b15, maps to 32-bit SB access */ + #define SBSDIO_SB_ACCESS_2_4B_FLAG 0x08000 /* valid bits in SBSDIO_FUNC1_SBADDRxxx regs */ diff --git a/drivers/wireless/ieee80211/bcmf_sdpcm.c b/drivers/wireless/ieee80211/bcmf_sdpcm.c index 065dafb61b..f3346325b9 100644 --- a/drivers/wireless/ieee80211/bcmf_sdpcm.c +++ b/drivers/wireless/ieee80211/bcmf_sdpcm.c @@ -152,7 +152,7 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv) uint16_t len, checksum; struct bcmf_sdpcm_header *header; struct bcmf_sdio_frame *sframe; - FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s*)priv->bus; + FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s *)priv->bus; /* Request free frame buffer */ @@ -164,11 +164,11 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv) return -EAGAIN; } - header = (struct bcmf_sdpcm_header*)sframe->data; + header = (struct bcmf_sdpcm_header *)sframe->data; /* Read header */ - ret = bcmf_transfer_bytes(sbus, false, 2, 0, (uint8_t*)header, 4); + ret = bcmf_transfer_bytes(sbus, false, 2, 0, (uint8_t *)header, 4); if (ret != OK) { wlinfo("failread size\n"); @@ -203,7 +203,7 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv) /* Read remaining frame data */ - ret = bcmf_transfer_bytes(sbus, false, 2, 0, (uint8_t*)header+4, len - 4); + ret = bcmf_transfer_bytes(sbus, false, 2, 0, (uint8_t *)header + 4, len - 4); if (ret != OK) { ret = -EIO; @@ -211,7 +211,7 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv) } // wlinfo("Receive frame %p %d\n", sframe, len); - // bcmf_hexdump((uint8_t*)header, header->size, (unsigned int)header); + // bcmf_hexdump((uint8_t *)header, header->size, (unsigned int)header); /* Process and validate header */ @@ -289,7 +289,7 @@ int bcmf_sdpcm_sendframe(FAR struct bcmf_dev_s *priv) dq_entry_t *entry; struct bcmf_sdio_frame *sframe; struct bcmf_sdpcm_header *header; - FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s*)priv->bus; + FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s *)priv->bus; if (sbus->tx_queue.tail == NULL) { @@ -313,7 +313,7 @@ int bcmf_sdpcm_sendframe(FAR struct bcmf_dev_s *priv) entry = sbus->tx_queue.tail; sframe = container_of(entry, struct bcmf_sdio_frame, list_entry); - header = (struct bcmf_sdpcm_header*)sframe->header.base; + header = (struct bcmf_sdpcm_header *)sframe->header.base; /* Set frame sequence id */ @@ -361,9 +361,9 @@ exit_abort: int bcmf_sdpcm_queue_frame(FAR struct bcmf_dev_s *priv, struct bcmf_frame_s *frame, bool control) { - FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s*)priv->bus; - struct bcmf_sdio_frame *sframe = (struct bcmf_sdio_frame*)frame; - struct bcmf_sdpcm_header *header = (struct bcmf_sdpcm_header*)sframe->data; + FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s *)priv->bus; + struct bcmf_sdio_frame *sframe = (struct bcmf_sdio_frame *)frame; + struct bcmf_sdpcm_header *header = (struct bcmf_sdpcm_header *)sframe->data; /* Prepare sw header */ @@ -399,9 +399,9 @@ int bcmf_sdpcm_queue_frame(FAR struct bcmf_dev_s *priv, return OK; } -struct bcmf_frame_s* bcmf_sdpcm_alloc_frame(FAR struct bcmf_dev_s *priv, - unsigned int len, bool block, - bool control) +struct bcmf_frame_s *bcmf_sdpcm_alloc_frame(FAR struct bcmf_dev_s *priv, + unsigned int len, bool block, + bool control) { struct bcmf_sdio_frame *sframe; unsigned int header_len = sizeof(struct bcmf_sdpcm_header); @@ -436,14 +436,14 @@ struct bcmf_frame_s* bcmf_sdpcm_alloc_frame(FAR struct bcmf_dev_s *priv, void bcmf_sdpcm_free_frame(FAR struct bcmf_dev_s *priv, struct bcmf_frame_s *frame) { - return bcmf_sdio_free_frame(priv, (struct bcmf_sdio_frame*)frame); + return bcmf_sdio_free_frame(priv, (struct bcmf_sdio_frame *)frame); } -struct bcmf_frame_s* bcmf_sdpcm_get_rx_frame(FAR struct bcmf_dev_s *priv) +struct bcmf_frame_s *bcmf_sdpcm_get_rx_frame(FAR struct bcmf_dev_s *priv) { dq_entry_t *entry; struct bcmf_sdio_frame *sframe; - FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s*)priv->bus; + FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s *)priv->bus; if (sem_wait(&sbus->queue_mutex)) { @@ -461,4 +461,4 @@ struct bcmf_frame_s* bcmf_sdpcm_get_rx_frame(FAR struct bcmf_dev_s *priv) sframe = container_of(entry, struct bcmf_sdio_frame, list_entry); return &sframe->header; -} \ No newline at end of file +} diff --git a/drivers/wireless/ieee80211/bcmf_sdpcm.h b/drivers/wireless/ieee80211/bcmf_sdpcm.h index f1091fd519..6144489e40 100644 --- a/drivers/wireless/ieee80211/bcmf_sdpcm.h +++ b/drivers/wireless/ieee80211/bcmf_sdpcm.h @@ -55,9 +55,10 @@ int bcmf_sdpcm_queue_frame(FAR struct bcmf_dev_s *priv, void bcmf_sdpcm_free_frame(FAR struct bcmf_dev_s *priv, struct bcmf_frame_s *frame); -struct bcmf_frame_s* bcmf_sdpcm_alloc_frame(FAR struct bcmf_dev_s *priv, - unsigned int len, bool block, bool control); +struct bcmf_frame_s *bcmf_sdpcm_alloc_frame(FAR struct bcmf_dev_s *priv, + unsigned int len, bool block, + bool control); -struct bcmf_frame_s* bcmf_sdpcm_get_rx_frame(FAR struct bcmf_dev_s *priv); +struct bcmf_frame_s *bcmf_sdpcm_get_rx_frame(FAR struct bcmf_dev_s *priv); -#endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_SDPCM_H */ \ No newline at end of file +#endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_SDPCM_H */ diff --git a/drivers/wireless/ieee80211/bcmf_utils.c b/drivers/wireless/ieee80211/bcmf_utils.c index c82908f6ab..16c42d27ac 100644 --- a/drivers/wireless/ieee80211/bcmf_utils.c +++ b/drivers/wireless/ieee80211/bcmf_utils.c @@ -68,7 +68,7 @@ void bcmf_hexdump(uint8_t *data, unsigned int len, unsigned long offset) char char_line[20]; char hex_line[64]; - for(i = 0; i < len; i++) + for (i = 0; i < len; i++) { if (char_count >= LINE_LEN) { @@ -107,9 +107,9 @@ int bcmf_sem_wait(sem_t *sem, unsigned int timeout_ms) (void)clock_gettime(CLOCK_REALTIME, &abstime); - timeout_sec = timeout_ms/1000; + timeout_sec = timeout_ms / 1000; abstime.tv_sec += timeout_sec; - abstime.tv_nsec += 1000 * 1000* (timeout_ms % 1000); + abstime.tv_nsec += 1000 * 1000 * (timeout_ms % 1000); if (abstime.tv_nsec >= 1000 * 1000 * 1000) { @@ -144,7 +144,7 @@ void bcmf_dqueue_push(dq_queue_t *queue, dq_entry_t *entry) queue->head = entry; } -dq_entry_t* bcmf_dqueue_pop_tail(dq_queue_t *queue) +dq_entry_t *bcmf_dqueue_pop_tail(dq_queue_t *queue) { dq_entry_t *entry = queue->tail; @@ -164,4 +164,4 @@ dq_entry_t* bcmf_dqueue_pop_tail(dq_queue_t *queue) } return entry; -} \ No newline at end of file +} diff --git a/drivers/wireless/ieee80211/bcmf_utils.h b/drivers/wireless/ieee80211/bcmf_utils.h index e79c44bdcf..32fd4ca562 100644 --- a/drivers/wireless/ieee80211/bcmf_utils.h +++ b/drivers/wireless/ieee80211/bcmf_utils.h @@ -45,7 +45,7 @@ #include #define container_of(ptr, type, member) \ - (type *)( (uint8_t *)(ptr) - offsetof(type,member) ) + (type *)((uint8_t *)(ptr) - offsetof(type, member)) /**************************************************************************** * Public Function Prototypes @@ -55,19 +55,19 @@ void bcmf_hexdump(uint8_t *data, unsigned int len, unsigned long offset); int bcmf_sem_wait(sem_t *sem, unsigned int timeout_ms); -dq_entry_t* bcmf_dqueue_pop_tail(dq_queue_t *queue); +dq_entry_t *bcmf_dqueue_pop_tail(dq_queue_t *queue); void bcmf_dqueue_push(dq_queue_t *queue, dq_entry_t *entry); static inline uint16_t bcmf_getle16(uint16_t *val) { - uint8_t *valb = (uint8_t*)val; + uint8_t *valb = (uint8_t *)val; return (uint16_t)valb[0] << 8 | (uint16_t)valb[1]; } static inline uint16_t bcmf_getle32(uint32_t *val) { - uint16_t *valw = (uint16_t*)val; - return (uint32_t)bcmf_getle16(valw)<<16 | bcmf_getle16(valw+1); + uint16_t *valw = (uint16_t *)val; + return (uint32_t)bcmf_getle16(valw) << 16 | bcmf_getle16(valw + 1); } #endif /* __DRIVERS_WIRELESS_IEEE80211_BCMF_UTILS_H */ \ No newline at end of file diff --git a/drivers/wireless/ieee80211/mmc_sdio.c b/drivers/wireless/ieee80211/mmc_sdio.c index 1848c3f72f..88d97612e9 100644 --- a/drivers/wireless/ieee80211/mmc_sdio.c +++ b/drivers/wireless/ieee80211/mmc_sdio.c @@ -7,43 +7,48 @@ #define SDIO_CMD53_TIMEOUT_MS 100 #define SDIO_IDLE_DELAY_MS 50 -struct __attribute__((packed)) sdio_cmd52 { - uint32_t write_data : 8; - uint32_t reserved_8 : 1; - uint32_t register_address : 17; - uint32_t reserved_26 : 1; - uint32_t raw_flag : 1; - uint32_t function_number : 3; - uint32_t rw_flag : 1; +struct __attribute__((packed)) sdio_cmd52 +{ + uint32_t write_data : 8; + uint32_t reserved_8 : 1; + uint32_t register_address : 17; + uint32_t reserved_26 : 1; + uint32_t raw_flag : 1; + uint32_t function_number : 3; + uint32_t rw_flag : 1; }; -struct __attribute__((packed)) sdio_cmd53 { - uint32_t byte_block_count : 9; - uint32_t register_address : 17; - uint32_t op_code : 1; - uint32_t block_mode : 1; - uint32_t function_number : 3; - uint32_t rw_flag : 1; +struct __attribute__((packed)) sdio_cmd53 +{ + uint32_t byte_block_count : 9; + uint32_t register_address : 17; + uint32_t op_code : 1; + uint32_t block_mode : 1; + uint32_t function_number : 3; + uint32_t rw_flag : 1; }; -struct __attribute__((packed)) sdio_resp_R5 { - uint32_t data : 8; - struct { - uint32_t out_of_range : 1; - uint32_t function_number : 1; - uint32_t rfu : 1; - uint32_t error : 1; - uint32_t io_current_state : 2; - uint32_t illegal_command : 1; - uint32_t com_crc_error : 1; - } flags; - uint32_t reserved_16 : 16; +struct __attribute__((packed)) sdio_resp_R5 +{ + uint32_t data : 8; + struct + { + uint32_t out_of_range : 1; + uint32_t function_number : 1; + uint32_t rfu : 1; + uint32_t error : 1; + uint32_t io_current_state : 2; + uint32_t illegal_command : 1; + uint32_t com_crc_error : 1; + } flags; + uint32_t reserved_16 : 16; }; -union sdio_cmd5x { - uint32_t value; - struct sdio_cmd52 cmd52; - struct sdio_cmd53 cmd53; +union sdio_cmd5x +{ + uint32_t value; + struct sdio_cmd52 cmd52; + struct sdio_cmd53 cmd53; }; int sdio_sendcmdpoll(FAR struct sdio_dev_s *dev, uint32_t cmd, uint32_t arg) @@ -70,7 +75,7 @@ int sdio_sendcmdpoll(FAR struct sdio_dev_s *dev, uint32_t cmd, uint32_t arg) int sdio_io_rw_direct(FAR struct sdio_dev_s *dev, bool write, uint8_t function, uint32_t address, - uint8_t inb, uint8_t* outb) + uint8_t inb, uint8_t *outb) { union sdio_cmd5x arg; struct sdio_resp_R5 resp; @@ -96,7 +101,7 @@ int sdio_io_rw_direct(FAR struct sdio_dev_s *dev, bool write, /* Send CMD52 command */ sdio_sendcmdpoll(dev, SDIO_ACMD52, arg.value); - ret = SDIO_RECVR5(dev, SDIO_ACMD52, (uint32_t*)&resp); + ret = SDIO_RECVR5(dev, SDIO_ACMD52, (uint32_t *)&resp); if (ret != OK) { @@ -110,6 +115,7 @@ int sdio_io_rw_direct(FAR struct sdio_dev_s *dev, bool write, { return -EIO; } + if (resp.flags.function_number || resp.flags.out_of_range) { return -EINVAL; @@ -170,7 +176,7 @@ int sdio_io_rw_extended(FAR struct sdio_dev_s *dev, bool write, { // wlinfo("prep write %d %d\n", blocklen, nblocks); sdio_sendcmdpoll(dev, SDIO_ACMD53, (uint32_t)arg.value); - ret = SDIO_RECVR5(dev, SDIO_ACMD53, (uint32_t*)&resp); + ret = SDIO_RECVR5(dev, SDIO_ACMD53, (uint32_t *)&resp); SDIO_DMASENDSETUP(dev, buf, blocklen * nblocks); wkupevent = SDIO_EVENTWAIT(dev, SDIO_CMD53_TIMEOUT_MS); @@ -182,7 +188,7 @@ int sdio_io_rw_extended(FAR struct sdio_dev_s *dev, bool write, SDIO_SENDCMD(dev, SDIO_ACMD53, (uint32_t)arg.value); wkupevent = SDIO_EVENTWAIT(dev, SDIO_CMD53_TIMEOUT_MS); - ret = SDIO_RECVR5(dev, SDIO_ACMD53, (uint32_t*)&resp); + ret = SDIO_RECVR5(dev, SDIO_ACMD53, (uint32_t *)&resp); } if (ret != OK) @@ -198,11 +204,13 @@ int sdio_io_rw_extended(FAR struct sdio_dev_s *dev, bool write, wlerr("timeout\n"); return -ETIMEDOUT; } + if (resp.flags.error || (wkupevent & SDIOWAIT_ERROR)) { wlerr("error 1\n"); return -EIO; } + if (resp.flags.function_number || resp.flags.out_of_range) { wlerr("error 2\n"); @@ -233,7 +241,7 @@ int sdio_set_wide_bus(struct sdio_dev_s *dev) ret = sdio_io_rw_direct(dev, true, 0, SDIO_CCCR_BUS_IF, value, NULL); if (ret != OK) { - return ret; + return ret; } SDIO_WIDEBUS(dev, true); -- GitLab From b0e880b04c336b3c3d7b4da7dfa477fb9c295b97 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 3 May 2017 18:26:24 -0600 Subject: [PATCH 697/990] Revert "STM32 I2C: More backward tests of CONFIG_I2C_POLLED. Needs to be reviewed." This reverts commit 1e054a2d3b1e3fb7be4348d88e35db3773e836b9. --- arch/arm/src/stm32/stm32_i2c.c | 4 ++-- arch/arm/src/stm32/stm32f30xxx_i2c.c | 4 ++-- arch/arm/src/stm32f0/stm32f0_i2c.c | 4 ++-- arch/arm/src/stm32f7/stm32_i2c.c | 4 ++-- arch/arm/src/stm32l4/stm32l4_i2c.c | 4 ++-- 5 files changed, 10 insertions(+), 10 deletions(-) diff --git a/arch/arm/src/stm32/stm32_i2c.c b/arch/arm/src/stm32/stm32_i2c.c index 6a08e14143..5f3e1c2c5c 100644 --- a/arch/arm/src/stm32/stm32_i2c.c +++ b/arch/arm/src/stm32/stm32_i2c.c @@ -1272,7 +1272,7 @@ static int stm32_i2c_isr_process(struct stm32_i2c_priv_s *priv) * device. */ -#ifndef CONFIG_I2C_POLLED +#ifdef CONFIG_I2C_POLLED irqstate_t flags = enter_critical_section(); #endif /* Receive a byte */ @@ -1287,7 +1287,7 @@ static int stm32_i2c_isr_process(struct stm32_i2c_priv_s *priv) stm32_i2c_modifyreg(priv, STM32_I2C_CR1_OFFSET, I2C_CR1_ACK, 0); } -#ifndef CONFIG_I2C_POLLED +#ifdef CONFIG_I2C_POLLED leave_critical_section(flags); #endif } diff --git a/arch/arm/src/stm32/stm32f30xxx_i2c.c b/arch/arm/src/stm32/stm32f30xxx_i2c.c index 9d616b7489..539305194d 100644 --- a/arch/arm/src/stm32/stm32f30xxx_i2c.c +++ b/arch/arm/src/stm32/stm32f30xxx_i2c.c @@ -1332,7 +1332,7 @@ static int stm32_i2c_isr_process(struct stm32_i2c_priv_s *priv) * device. */ -#ifndef CONFIG_I2C_POLLED +#ifdef CONFIG_I2C_POLLED irqstate_t flags = enter_critical_section(); #endif /* Receive a byte */ @@ -1347,7 +1347,7 @@ static int stm32_i2c_isr_process(struct stm32_i2c_priv_s *priv) /* autoend? */ } -#ifndef CONFIG_I2C_POLLED +#ifdef CONFIG_I2C_POLLED leave_critical_section(flags); #endif } diff --git a/arch/arm/src/stm32f0/stm32f0_i2c.c b/arch/arm/src/stm32f0/stm32f0_i2c.c index b8f7ede7d6..c782754fc3 100644 --- a/arch/arm/src/stm32f0/stm32f0_i2c.c +++ b/arch/arm/src/stm32f0/stm32f0_i2c.c @@ -1306,7 +1306,7 @@ static int stm32f0_i2c_isr_process(struct stm32f0_i2c_priv_s *priv) * device. */ -#ifndef CONFIG_I2C_POLLED +#ifdef CONFIG_I2C_POLLED irqstate_t flags = enter_critical_section(); #endif /* Receive a byte */ @@ -1321,7 +1321,7 @@ static int stm32f0_i2c_isr_process(struct stm32f0_i2c_priv_s *priv) /* autoend? */ } -#ifndef CONFIG_I2C_POLLED +#ifdef CONFIG_I2C_POLLED leave_critical_section(flags); #endif } diff --git a/arch/arm/src/stm32f7/stm32_i2c.c b/arch/arm/src/stm32f7/stm32_i2c.c index d85023e6c5..be3122ea4e 100644 --- a/arch/arm/src/stm32f7/stm32_i2c.c +++ b/arch/arm/src/stm32f7/stm32_i2c.c @@ -1776,7 +1776,7 @@ static int stm32_i2c_isr_process(struct stm32_i2c_priv_s *priv) * sequence. Otherwise, additional bytes may be received. */ -#ifndef CONFIG_I2C_POLLED +#ifdef CONFIG_I2C_POLLED irqstate_t state = enter_critical_section(); #endif /* Receive a byte */ @@ -1793,7 +1793,7 @@ static int stm32_i2c_isr_process(struct stm32_i2c_priv_s *priv) priv->dcnt--; -#ifndef CONFIG_I2C_POLLED +#ifdef CONFIG_I2C_POLLED leave_critical_section(state); #endif } diff --git a/arch/arm/src/stm32l4/stm32l4_i2c.c b/arch/arm/src/stm32l4/stm32l4_i2c.c index 956dd8c788..58c2fa780f 100644 --- a/arch/arm/src/stm32l4/stm32l4_i2c.c +++ b/arch/arm/src/stm32l4/stm32l4_i2c.c @@ -1384,7 +1384,7 @@ static int stm32l4_i2c_isr_process(struct stm32l4_i2c_priv_s *priv) * device. */ -#ifndef CONFIG_I2C_POLLED +#ifdef CONFIG_I2C_POLLED irqstate_t flags = enter_critical_section(); #endif /* Receive a byte */ @@ -1399,7 +1399,7 @@ static int stm32l4_i2c_isr_process(struct stm32l4_i2c_priv_s *priv) /* autoend? */ } -#ifndef CONFIG_I2C_POLLED +#ifdef CONFIG_I2C_POLLED leave_critical_section(flags); #endif } -- GitLab From 88be413a0584541772e3a9306a28a7aa99a15ea4 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 3 May 2017 18:30:40 -0600 Subject: [PATCH 698/990] Remove dangling whitespace at the end of lines. --- drivers/wireless/ieee80211/Make.defs | 2 +- drivers/wireless/ieee80211/bcmf_bdc.c | 2 +- drivers/wireless/ieee80211/bcmf_cdc.c | 2 +- drivers/wireless/ieee80211/bcmf_core.c | 3 ++- drivers/wireless/ieee80211/bcmf_driver.c | 3 +-- drivers/wireless/ieee80211/bcmf_netdev.c | 2 +- drivers/wireless/ieee80211/bcmf_sdio.c | 22 +++++++++++----------- drivers/wireless/ieee80211/bcmf_sdpcm.c | 2 +- drivers/wireless/ieee80211/mmc_sdio.c | 4 ++-- 9 files changed, 21 insertions(+), 21 deletions(-) diff --git a/drivers/wireless/ieee80211/Make.defs b/drivers/wireless/ieee80211/Make.defs index 0df7f9ef8b..a648f70a93 100644 --- a/drivers/wireless/ieee80211/Make.defs +++ b/drivers/wireless/ieee80211/Make.defs @@ -47,7 +47,7 @@ ifeq ($(CONFIG_IEEE80211_BROADCOM_FULLMAC),y) CSRCS += bcmf_utils.c CSRCS += bcmf_netdev.c -ifeq ($(CONFIG_IEEE80211_BROADCOM_FULLMAC_SDIO),y) +ifeq ($(CONFIG_IEEE80211_BROADCOM_FULLMAC_SDIO),y) CSRCS += mmc_sdio.c CSRCS += bcmf_sdio.c CSRCS += bcmf_core.c diff --git a/drivers/wireless/ieee80211/bcmf_bdc.c b/drivers/wireless/ieee80211/bcmf_bdc.c index a2a31a3f3f..509106fdc1 100644 --- a/drivers/wireless/ieee80211/bcmf_bdc.c +++ b/drivers/wireless/ieee80211/bcmf_bdc.c @@ -115,7 +115,7 @@ struct bcmf_frame_s *bcmf_bdc_allocate_frame(FAR struct bcmf_dev_s *priv, frame->data += sizeof(struct bcmf_bdc_header); - return frame; + return frame; } int bcmf_bdc_process_event_frame(FAR struct bcmf_dev_s *priv, diff --git a/drivers/wireless/ieee80211/bcmf_cdc.c b/drivers/wireless/ieee80211/bcmf_cdc.c index 06efd9ec5c..ca1f00c01f 100644 --- a/drivers/wireless/ieee80211/bcmf_cdc.c +++ b/drivers/wireless/ieee80211/bcmf_cdc.c @@ -130,7 +130,7 @@ struct bcmf_frame_s *bcmf_cdc_allocate_frame(FAR struct bcmf_dev_s *priv, frame = priv->bus->allocate_frame(priv, sizeof(struct bcmf_cdc_header) + data_len + name_len, true, true); - + if (!frame) { return NULL; diff --git a/drivers/wireless/ieee80211/bcmf_core.c b/drivers/wireless/ieee80211/bcmf_core.c index 64606b7a71..eba356264e 100644 --- a/drivers/wireless/ieee80211/bcmf_core.c +++ b/drivers/wireless/ieee80211/bcmf_core.c @@ -339,8 +339,9 @@ void bcmf_core_disable(FAR struct bcmf_sdio_dev_s *sbus, unsigned int core) wlerr("Invalid core id %d\n", core); return; } + uint32_t base = sbus->chip->core_base[core]; - + /* Check if core is already in reset state */ bcmf_read_sbregb(sbus, base + BCMA_RESET_CTL, &value); diff --git a/drivers/wireless/ieee80211/bcmf_driver.c b/drivers/wireless/ieee80211/bcmf_driver.c index 8e62c6049a..4666d8da9f 100644 --- a/drivers/wireless/ieee80211/bcmf_driver.c +++ b/drivers/wireless/ieee80211/bcmf_driver.c @@ -201,7 +201,7 @@ int bcmf_wl_set_mac_address(FAR struct bcmf_dev_s *priv, struct ifreq *req) memcpy(priv->bc_dev.d_mac.ether.ether_addr_octet, req->ifr_hwaddr.sa_data, ETHER_ADDR_LEN); - + return OK; } @@ -912,4 +912,3 @@ int bcmf_wl_set_ssid(FAR struct bcmf_dev_s *priv, struct iwreq *iwr) } return OK; } - \ No newline at end of file diff --git a/drivers/wireless/ieee80211/bcmf_netdev.c b/drivers/wireless/ieee80211/bcmf_netdev.c index 0d7e38c935..02527fe60c 100644 --- a/drivers/wireless/ieee80211/bcmf_netdev.c +++ b/drivers/wireless/ieee80211/bcmf_netdev.c @@ -210,7 +210,7 @@ static int bcmf_transmit(FAR struct bcmf_dev_s *priv, frame->len = priv->bc_dev.d_len + (unsigned int)(frame->data - frame->base); - + ret = bcmf_bdc_transmit_frame(priv, frame); if (ret) diff --git a/drivers/wireless/ieee80211/bcmf_sdio.c b/drivers/wireless/ieee80211/bcmf_sdio.c index 7433903795..dcef6fc66e 100644 --- a/drivers/wireless/ieee80211/bcmf_sdio.c +++ b/drivers/wireless/ieee80211/bcmf_sdio.c @@ -159,7 +159,7 @@ int bcmf_sdio_bus_sleep(FAR struct bcmf_sdio_dev_s *sbus, bool sleep) else { /* Request HT Avail */ - + ret = bcmf_write_reg(sbus, 1, SBSDIO_FUNC1_CHIPCLKCSR, SBSDIO_HT_AVAIL_REQ | SBSDIO_FORCE_HT); if (ret != OK) @@ -167,27 +167,27 @@ int bcmf_sdio_bus_sleep(FAR struct bcmf_sdio_dev_s *sbus, bool sleep) wlerr("HT Avail request failed %d\n", ret); return ret; } - + /* Wait for High Troughput clock */ - + loops = 20; while (--loops > 0) { up_mdelay(1); ret = bcmf_read_reg(sbus, 1, SBSDIO_FUNC1_CHIPCLKCSR, &value); - + if (ret != OK) { return ret; } - + if (value & SBSDIO_HT_AVAIL) { /* High Throughput clock is ready */ break; } } - + if (loops <= 0) { wlerr("HT clock not ready\n"); @@ -196,7 +196,7 @@ int bcmf_sdio_bus_sleep(FAR struct bcmf_sdio_dev_s *sbus, bool sleep) sbus->sleeping = false; } - + return OK; } @@ -597,7 +597,7 @@ int bcmf_bus_sdio_initialize(FAR struct bcmf_dev_s *priv, { bcmf_dqueue_push(&sbus->free_queue, &g_pktframes[ret].list_entry); } - + /* Init thread semaphore */ if ((ret = sem_init(&sbus->thread_signal, 0, 0)) != OK) @@ -740,13 +740,13 @@ int bcmf_sdio_thread(int argc, char **argv) int ret; FAR struct bcmf_dev_s *priv = g_sdio_priv; FAR struct bcmf_sdio_dev_s *sbus = (FAR struct bcmf_sdio_dev_s *)priv->bus; - + wlinfo("Enter\n"); /* FIXME wait for the chip to be ready to receive commands */ up_mdelay(50); - + while (sbus->ready) { /* Wait for event (device interrupt, user request or waitdog timer) */ @@ -796,7 +796,7 @@ int bcmf_sdio_thread(int argc, char **argv) ret = bcmf_sdpcm_readframe(priv); } while (ret == OK); - + if (ret == -ENODATA) { /* All frames processed */ diff --git a/drivers/wireless/ieee80211/bcmf_sdpcm.c b/drivers/wireless/ieee80211/bcmf_sdpcm.c index f3346325b9..21691bd957 100644 --- a/drivers/wireless/ieee80211/bcmf_sdpcm.c +++ b/drivers/wireless/ieee80211/bcmf_sdpcm.c @@ -223,7 +223,7 @@ int bcmf_sdpcm_readframe(FAR struct bcmf_dev_s *priv) goto exit_free_frame; } - /* Update frame structure */ + /* Update frame structure */ sframe->header.len = header->size; sframe->header.data += header->data_offset; diff --git a/drivers/wireless/ieee80211/mmc_sdio.c b/drivers/wireless/ieee80211/mmc_sdio.c index 88d97612e9..377dcc3e53 100644 --- a/drivers/wireless/ieee80211/mmc_sdio.c +++ b/drivers/wireless/ieee80211/mmc_sdio.c @@ -243,7 +243,7 @@ int sdio_set_wide_bus(struct sdio_dev_s *dev) { return ret; } - + SDIO_WIDEBUS(dev, true); return OK; } @@ -343,7 +343,7 @@ int sdio_enable_function(FAR struct sdio_dev_s *dev, uint8_t function) { return ret; } - + ret = sdio_io_rw_direct(dev, true, 0, SDIO_CCCR_IOEN, value | (1 << function), NULL); if (ret != OK) -- GitLab From c67c4a75ba7110fe896d1bf52ec231e7efa7d4d6 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Thu, 4 May 2017 08:56:32 +0300 Subject: [PATCH 699/990] STM32L4: stm32l4_i2c: change wrong macro to CONFIG_I2C_POLLED --- arch/arm/src/stm32l4/stm32l4_i2c.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/arch/arm/src/stm32l4/stm32l4_i2c.c b/arch/arm/src/stm32l4/stm32l4_i2c.c index 9be4419de4..fb9b7f6acb 100644 --- a/arch/arm/src/stm32l4/stm32l4_i2c.c +++ b/arch/arm/src/stm32l4/stm32l4_i2c.c @@ -1532,7 +1532,7 @@ static int stm32l4_i2c_isr_process(struct stm32l4_i2c_priv_s *priv) * ************************************************************************************/ -#ifdef CONFIG_STM32L4_I2C2 +#ifndef CONFIG_I2C_POLLED static int stm32l4_i2c_isr(int irq, void *context, FAR void *arg) { struct stm32l4_i2c_priv_s *priv = (struct stm32l4_i2c_priv_s *priv)arg; -- GitLab From dd1b9dfa81c30e0011f3e7419a9227c96dedc316 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Tue, 2 May 2017 15:14:45 +0300 Subject: [PATCH 700/990] STM32L4: modularize Kconfig to support different product lines/families This is modeled after STM32F7. Idea is to declare each chip in Kconfig but allow for flash size override. Commit adds many STM32L4_HAVE_XXX feature test macros. --- arch/arm/src/stm32l4/Kconfig | 555 ++++++++++++++++++++++--- arch/arm/src/stm32l4/stm32l4x6xx_rcc.c | 9 +- configs/nucleo-l496zg/nsh/defconfig | 27 +- 3 files changed, 513 insertions(+), 78 deletions(-) diff --git a/arch/arm/src/stm32l4/Kconfig b/arch/arm/src/stm32l4/Kconfig index 28be165f44..74b3f9ae70 100644 --- a/arch/arm/src/stm32l4/Kconfig +++ b/arch/arm/src/stm32l4/Kconfig @@ -12,57 +12,218 @@ choice default ARCH_CHIP_STM32L476RG depends on ARCH_CHIP_STM32L4 +config ARCH_CHIP_STM32L432KB + bool "STM32L432KB" + select STM32L4_STM32L432XX + select STM32L4_FLASH_CONFIG_B + select STM32L4_IO_CONFIG_K + ---help--- + STM32 L4 Cortex M4, 128 Kb FLASH, 64 Kb SRAM + +config ARCH_CHIP_STM32L432KC + bool "STM32L432KC" + select STM32L4_STM32L432XX + select STM32L4_FLASH_CONFIG_C + select STM32L4_IO_CONFIG_K + ---help--- + STM32 L4 Cortex M4, 256 Kb FLASH, 64 Kb SRAM + +config ARCH_CHIP_STM32L442KC + bool "STM32L442KC" + select STM32L4_STM32L442XX + select STM32L4_FLASH_CONFIG_C + select STM32L4_IO_CONFIG_K + ---help--- + STM32 L4 Cortex M4, AES, 256 Kb FLASH, 64 Kb SRAM + +config ARCH_CHIP_STM32L451CC + bool "STM32L451CC" + select STM32L4_STM32L451XX + select STM32L4_FLASH_CONFIG_C + select STM32L4_IO_CONFIG_C + ---help--- + STM32 L4 Cortex M4, 256 Kb FLASH, 128+32 Kb SRAM + +config ARCH_CHIP_STM32L451CE + bool "STM32L451CE" + select STM32L4_STM32L451XX + select STM32L4_FLASH_CONFIG_E + select STM32L4_IO_CONFIG_C + ---help--- + STM32 L4 Cortex M4, 512 Kb FLASH, 128+32 Kb SRAM + +config ARCH_CHIP_STM32L451RC + bool "STM32L451RC" + select STM32L4_STM32L451XX + select STM32L4_FLASH_CONFIG_C + select STM32L4_IO_CONFIG_R + ---help--- + STM32 L4 Cortex M4, 256 Kb FLASH, 128+32 Kb SRAM + +config ARCH_CHIP_STM32L451RE + bool "STM32L451RE" + select STM32L4_STM32L451XX + select STM32L4_FLASH_CONFIG_E + select STM32L4_IO_CONFIG_R + ---help--- + STM32 L4 Cortex M4, 512 Kb FLASH, 128+32 Kb SRAM + +config ARCH_CHIP_STM32L451VC + bool "STM32L451VC" + select STM32L4_STM32L451XX + select STM32L4_FLASH_CONFIG_C + select STM32L4_IO_CONFIG_V + ---help--- + STM32 L4 Cortex M4, 256 Kb FLASH, 128+32 Kb SRAM + +config ARCH_CHIP_STM32L451VE + bool "STM32L451VE" + select STM32L4_STM32L451XX + select STM32L4_FLASH_CONFIG_E + select STM32L4_IO_CONFIG_V + ---help--- + STM32 L4 Cortex M4, 512 Kb FLASH, 128+32 Kb SRAM + +config ARCH_CHIP_STM32L452CC + bool "STM32L452CC" + select STM32L4_STM32L452XX + select STM32L4_FLASH_CONFIG_C + select STM32L4_IO_CONFIG_C + ---help--- + STM32 L4 Cortex M4, 256 Kb FLASH, 128+32 Kb SRAM + +config ARCH_CHIP_STM32L452CE + bool "STM32L452CE" + select STM32L4_STM32L452XX + select STM32L4_FLASH_CONFIG_E + select STM32L4_IO_CONFIG_C + ---help--- + STM32 L4 Cortex M4, 512 Kb FLASH, 128+32 Kb SRAM + +config ARCH_CHIP_STM32L452RC + bool "STM32L452RC" + select STM32L4_STM32L452XX + select STM32L4_FLASH_CONFIG_C + select STM32L4_IO_CONFIG_R + ---help--- + STM32 L4 Cortex M4, 256 Kb FLASH, 128+32 Kb SRAM + +config ARCH_CHIP_STM32L452RE + bool "STM32L452RE" + select STM32L4_STM32L452XX + select STM32L4_FLASH_CONFIG_E + select STM32L4_IO_CONFIG_R + ---help--- + STM32 L4 Cortex M4, 512 Kb FLASH, 128+32 Kb SRAM + +config ARCH_CHIP_STM32L452VC + bool "STM32L452VC" + select STM32L4_STM32L452XX + select STM32L4_FLASH_CONFIG_C + select STM32L4_IO_CONFIG_V + ---help--- + STM32 L4 Cortex M4, 256 Kb FLASH, 128+32 Kb SRAM + +config ARCH_CHIP_STM32L452VE + bool "STM32L452VE" + select STM32L4_STM32L452XX + select STM32L4_FLASH_CONFIG_E + select STM32L4_IO_CONFIG_V + ---help--- + STM32 L4 Cortex M4, 512 Kb FLASH, 128+32 Kb SRAM + +config ARCH_CHIP_STM32L462CE + bool "STM32L462CE" + select STM32L4_STM32L462XX + select STM32L4_FLASH_CONFIG_E + select STM32L4_IO_CONFIG_C + ---help--- + STM32 L4 Cortex M4, USB FS, AES, 512 Kb FLASH, 128+32 Kb SRAM + +config ARCH_CHIP_STM32L462RE + bool "STM32L462RE" + select STM32L4_STM32L462XX + select STM32L4_FLASH_CONFIG_E + select STM32L4_IO_CONFIG_R + ---help--- + STM32 L4 Cortex M4, USB FS, AES, 512 Kb FLASH, 128+32 Kb SRAM + +config ARCH_CHIP_STM32L462VE + bool "STM32L462VE" + select STM32L4_STM32L462XX + select STM32L4_FLASH_CONFIG_E + select STM32L4_IO_CONFIG_V + ---help--- + STM32 L4 Cortex M4, USB FS, AES, 512 Kb FLASH, 128+32 Kb SRAM + config ARCH_CHIP_STM32L476RG bool "STM32L476RG" select STM32L4_STM32L476XX - select STM32L4_FLASH_1024KB + select STM32L4_FLASH_CONFIG_G + select STM32L4_IO_CONFIG_R ---help--- STM32 L4 Cortex M4, 1024Kb FLASH, 96+32 Kb SRAM config ARCH_CHIP_STM32L476RE bool "STM32L476RE" select STM32L4_STM32L476XX - select STM32L4_FLASH_512KB + select STM32L4_FLASH_CONFIG_E + select STM32L4_IO_CONFIG_R ---help--- STM32 L4 Cortex M4, 512Kb FLASH, 96+32 Kb SRAM -config ARCH_CHIP_STM32L486 +config ARCH_CHIP_STM32L486 # REVISIT: expand for each chip bool "STM32L486xx" select STM32L4_STM32L486XX - select STM32L4_HAVE_AES + select STM32L4_FLASH_CONFIG_G ---help--- STM32 L4 Cortex M4, AES, 1024Kb FLASH, 96+32 Kb SRAM config ARCH_CHIP_STM32L496ZE bool "STM32L496ZE" select STM32L4_STM32L496XX - select STM32L4_FLASH_512KB + select STM32L4_FLASH_CONFIG_E + select STM32L4_IO_CONFIG_Z ---help--- STM32 L4 Cortex M4, 512Kb FLASH, 320 Kb SRAM config ARCH_CHIP_STM32L496ZG bool "STM32L496ZG" select STM32L4_STM32L496XX - select STM32L4_FLASH_1024KB + select STM32L4_FLASH_CONFIG_G + select STM32L4_IO_CONFIG_Z ---help--- STM32 L4 Cortex M4, 1024Kb FLASH, 320 Kb SRAM -config ARCH_CHIP_STM32L4A6 +config ARCH_CHIP_STM32L4A6 # REVISIT: expand for each chip bool "STM32L4A6xx" - select STM32L4_STM32L496XX # Close enough to L496 - select STM32L4_FLASH_1024KB - select STM32L4_HAVE_AES - select STM32L4_HAVE_HASH + select STM32L4_STM32L4A6XX + select STM32L4_FLASH_CONFIG_G ---help--- STM32 L4 Cortex M4, AES, HASH, 1024Kb FLASH, 320 Kb SRAM endchoice # STM32 L4 Chip Selection -# Chip families +# Chip product lines + +config STM32L4_STM32L4X1 + # Note: This is _not_ for L471xx as in RM0392 + bool + default n + select STM32L4_STM32L4X3 + +config STM32L4_STM32L4X2 + bool + default n + select STM32L4_STM32L4X3 config STM32L4_STM32L4X3 bool default n + select ARCH_HAVE_FPU + select ARCH_HAVE_DPFPU # REVISIT + select ARMV7M_HAVE_ITCM + select ARMV7M_HAVE_DTCM select STM32L4_HAVE_USART1 select STM32L4_HAVE_USART2 select STM32L4_HAVE_USART3 if !(STM32L4_L432XX || STM32L4_L442XX) @@ -78,64 +239,259 @@ config STM32L4_STM32L4X5 select STM32L4_HAVE_USART1 select STM32L4_HAVE_USART2 select STM32L4_HAVE_USART3 + select STM32L4_HAVE_UART4 + select STM32L4_HAVE_UART5 + select STM32L4_HAVE_ADC2 + select STM32L4_HAVE_ADC3 + select STM32L4_HAVE_DAC2 + select STM32L4_HAVE_FSMC + select STM32L4_HAVE_TIM3 + select STM32L4_HAVE_TIM4 + select STM32L4_HAVE_TIM5 + select STM32L4_HAVE_TIM7 + select STM32L4_HAVE_TIM8 + select STM32L4_HAVE_TIM17 select STM32L4_HAVE_LPTIM1 select STM32L4_HAVE_LPTIM2 select STM32L4_HAVE_COMP select STM32L4_HAVE_SAI1 select STM32L4_HAVE_SAI2 + select STM32L4_HAVE_SDMMC1 + select STM32L4_HAVE_OTGFS + select STM32L4_HAVE_DFSDM1 config STM32L4_STM32L4X6 bool default n + select ARCH_HAVE_FPU + select ARCH_HAVE_DPFPU # REVISIT + select ARMV7M_HAVE_ITCM + select ARMV7M_HAVE_DTCM select STM32L4_HAVE_USART1 select STM32L4_HAVE_USART2 select STM32L4_HAVE_USART3 select STM32L4_HAVE_UART4 select STM32L4_HAVE_UART5 + select STM32L4_HAVE_ADC2 + select STM32L4_HAVE_ADC3 + select STM32L4_HAVE_DAC2 + select STM32L4_HAVE_FSMC + select STM32L4_HAVE_TIM3 + select STM32L4_HAVE_TIM4 + select STM32L4_HAVE_TIM5 + select STM32L4_HAVE_TIM7 + select STM32L4_HAVE_TIM8 + select STM32L4_HAVE_TIM17 select STM32L4_HAVE_LPTIM1 select STM32L4_HAVE_LPTIM2 select STM32L4_HAVE_COMP select STM32L4_HAVE_SAI1 select STM32L4_HAVE_SAI2 + select STM32L4_HAVE_SDMMC1 + select STM32L4_HAVE_OTGFS + select STM32L4_HAVE_LCD + +# Chip subfamilies: + +config STM32L4_STM32L431XX + bool + default n + select STM32L4_STM32L4X1 + select STM32L4_HAVE_TIM7 + select STM32L4_HAVE_SDMMC1 if (STM32L4_IO_CONFIG_V || STM32L4_IO_CONFIG_R) + +config STM32L4_STM32L432XX + bool + default n + select STM32L4_STM32L4X2 + select STM32L4_HAVE_TIM7 + +config STM32L4_STM32L433XX + bool + default n + select STM32L4_STM32L4X3 + select STM32L4_HAVE_TIM7 + +config STM32L4_STM32L442XX + bool + default n + select STM32L4_STM32L4X2 + select STM32L4_HAVE_TIM7 + select STM32L4_HAVE_AES + +config STM32L4_STM32L443XX + bool + default n + select STM32L4_STM32L4X3 + select STM32L4_HAVE_TIM7 + select STM32L4_HAVE_SDMMC1 + select STM32L4_HAVE_AES + +config STM32L4_STM32L451XX + bool + default n + select STM32L4_STM32L4X1 + select STM32L4_HAVE_UART4 + select STM32L4_HAVE_TIM3 + select STM32L4_HAVE_I2C4 + select STM32L4_HAVE_SDMMC1 if !STM32L4_IO_CONFIG_C + select STM32L4_HAVE_DFSDM1 + +config STM32L4_STM32L452XX + bool + default n + select STM32L4_STM32L4X2 + select STM32L4_HAVE_UART4 + select STM32L4_HAVE_TIM3 + select STM32L4_HAVE_I2C4 + select STM32L4_HAVE_SDMMC1 + select STM32L4_HAVE_DFSDM1 + +config STM32L4_STM32L462XX + bool + default n + select STM32L4_STM32L4X2 + select STM32L4_HAVE_UART4 + select STM32L4_HAVE_TIM3 + select STM32L4_HAVE_I2C4 + select STM32L4_HAVE_SDMMC1 + select STM32L4_HAVE_DFSDM1 + select STM32L4_HAVE_AES + +config STM32L4_STM32L471XX + bool + default n + # TODO config STM32L4_STM32L476XX bool default n select STM32L4_STM32L4X6 - select ARCH_HAVE_FPU config STM32L4_STM32L486XX bool default n select STM32L4_STM32L4X6 - select ARCH_HAVE_FPU - select STM32L4_FLASH_1024KB + select STM32L4_HAVE_AES config STM32L4_STM32L496XX bool default n select STM32L4_STM32L4X6 - select ARCH_HAVE_FPU select STM32L4_HAVE_I2C4 select STM32L4_HAVE_CAN2 select STM32L4_HAVE_DCMI select STM32L4_HAVE_DMA2D + select STM32L4_HAVE_DFSDM1 + +config STM32L4_STM32L4A6XX + bool + default n + select STM32L4_STM32L496XX + select STM32L4_HAVE_AES + select STM32L4_HAVE_HASH choice - prompt "Embedded FLASH size" - default STM32L4_FLASH_1024KB + prompt "Override Flash Size Designator" + depends on ARCH_CHIP_STM32L4 + default STM32L4_FLASH_OVERRIDE_DEFAULT + ---help--- + STM32L4 series parts numbering (sans the package type) ends with a letter + that designates the FLASH size. + + Designator Size in KiB + B 128 + C 256 + E 512 + G 1024 + + This configuration option defaults to using the configuration based on that designator + or the default smaller size if there is no last character designator is present in the + STM32 Chip Selection. -config STM32L4_FLASH_256KB - bool "256 KB" + Examples: + If the STM32L476VE is chosen, the Flash configuration would be 'E', if a variant of + the part with a 1024 KiB Flash is released in the future one could simply select + the 'G' designator here. + + If an STM32L4xxx Series parts is chosen the default Flash configuration will be set + herein and can be changed. + +config STM32L4_FLASH_OVERRIDE_DEFAULT + bool "Default" + +config STM32L4_FLASH_OVERRIDE_B + bool "B 128 KB" + +config STM32L4_FLASH_OVERRIDE_C + bool "C 256 KB" + +config STM32L4_FLASH_OVERRIDE_E + bool "E 512 KB" + +config STM32L4_FLASH_OVERRIDE_G + bool "G 1024 KB" + +endchoice # "Override Flash Size Designator" + +# Flash configurations + +config STM32L4_FLASH_CONFIG_B + bool + default n + depends on STM32L4_STM32L4X1 || STM32L4_STM32L4X3 + +config STM32L4_FLASH_CONFIG_C + bool + default n depends on !STM32L4_STM32L496XX -config STM32L4_FLASH_512KB - bool "512 KB" +config STM32L4_FLASH_CONFIG_E + bool + default n -config STM32L4_FLASH_1024KB - bool "1024 KB" +config STM32L4_FLASH_CONFIG_G + bool + default n + depends on STM32L4_STM32L4X5 || STM32L4_STM32L4X6 + +# Pin/package configurations + +config STM32L4_IO_CONFIG_K + bool + default n -endchoice # Embedded FLASH size +config STM32L4_IO_CONFIG_C + bool + default n + +config STM32L4_IO_CONFIG_R + bool + default n + +config STM32L4_IO_CONFIG_J + bool + default n + +config STM32L4_IO_CONFIG_M + bool + default n + +config STM32L4_IO_CONFIG_V + bool + default n + +config STM32L4_IO_CONFIG_Q + bool + default n + +config STM32L4_IO_CONFIG_Z + bool + default n + +config STM32L4_IO_CONFIG_A + bool + default n comment "STM32L4 SRAM2 Options" @@ -172,6 +528,14 @@ menu "STM32L4 Peripheral Support" # These "hidden" settings determine is a peripheral option is available for the # selection MCU +config STM32L4_HAVE_ADC2 + bool + default n + +config STM32L4_HAVE_ADC3 + bool + default n + config STM32L4_HAVE_AES bool default n @@ -184,14 +548,26 @@ config STM32L4_HAVE_COMP bool default n +config STM32L4_HAVE_DAC2 + bool + default n + config STM32L4_HAVE_DCMI bool default n +config STM32L4_HAVE_DFSDM1 + bool + default n + config STM32L4_HAVE_DMA2D bool default n +config STM32L4_HAVE_FSMC + bool + default n + config STM32L4_HAVE_HASH bool default n @@ -200,6 +576,10 @@ config STM32L4_HAVE_I2C4 bool default n +config STM32L4_HAVE_LCD + bool + default n + config STM32L4_HAVE_LTDC bool default n @@ -212,6 +592,10 @@ config STM32L4_HAVE_LPTIM2 bool default n +config STM32L4_HAVE_OTGFS + bool + default n + config STM32L4_HAVE_SAI1 bool default n @@ -220,6 +604,34 @@ config STM32L4_HAVE_SAI2 bool default n +config STM32L4_HAVE_SDMMC1 + bool + default n + +config STM32L4_HAVE_TIM3 + bool + default n + +config STM32L4_HAVE_TIM4 + bool + default n + +config STM32L4_HAVE_TIM5 + bool + default n + +config STM32L4_HAVE_TIM7 + bool + default n + +config STM32L4_HAVE_TIM8 + bool + default n + +config STM32L4_HAVE_TIM17 + bool + default n + # These "hidden" settings are the OR of individual peripheral selections # indicating that the general capability is required. @@ -289,6 +701,7 @@ config STM32L4_OTGFS bool "OTG FS" default n select USBHOST_HAVE_ASYNCH if USBHOST + depends on STM32L4_HAVE_OTGFS config STM32L4_ADC1 bool "ADC1" @@ -299,11 +712,13 @@ config STM32L4_ADC2 bool "ADC2" default n select STM32L4_ADC + depends on STM32L4_HAVE_ADC2 config STM32L4_ADC3 bool "ADC3" default n select STM32L4_ADC + depends on STM32L4_HAVE_ADC3 config STM32L4_AES bool "AES" @@ -330,43 +745,12 @@ config STM32L4_RNG default n select ARCH_HAVE_RNG -config STM32L4_SAI1_A - bool "SAI1 Block A" - default n - select AUDIO - select I2S - select SCHED_WORKQUEUE - select STM32L4_SAI - -config STM32L4_SAI1_B - bool "SAI1 Block B" - default n - select AUDIO - select I2S - select SCHED_WORKQUEUE - select STM32L4_SAI - -config STM32L4_SAI2_A - bool "SAI2 Block A" - default n - select AUDIO - select I2S - select SCHED_WORKQUEUE - select STM32L4_SAI - -config STM32L4_SAI2_B - bool "SAI2 Block B" - default n - select AUDIO - select I2S - select SCHED_WORKQUEUE - select STM32L4_SAI - comment "AHB3 Peripherals" -config STM32L4_FMC - bool "FMC" +config STM32L4_FSMC + bool "FSMC" default n + depends on STM32L4_HAVE_FSMC config STM32L4_QSPI bool "QuadSPI" @@ -526,14 +910,17 @@ config STM32L4_TIM2 config STM32L4_TIM3 bool "TIM3" default n + depends on STM32L4_HAVE_TIM3 config STM32L4_TIM4 bool "TIM4" default n + depends on STM32L4_HAVE_TIM4 config STM32L4_TIM5 bool "TIM5" default n + depends on STM32L4_HAVE_TIM5 config STM32L4_TIM6 bool "TIM6" @@ -542,14 +929,17 @@ config STM32L4_TIM6 config STM32L4_TIM7 bool "TIM7" default n + depends on STM32L4_HAVE_TIM7 config STM32L4_LCD bool "LCD" default n + depends on STM32L4_HAVE_LCD config STM32L4_SPI2 bool "SPI2" default n + depends on !(STM32L4_L432XX || STM32L4_L442XX) select SPI select STM32L4_SPI @@ -607,6 +997,7 @@ config STM32L4_I2C1 config STM32L4_I2C2 bool "I2C2" default n + depends on !(STM32L4_L432XX || STM32L4_L442XX) select STM32L4_I2C config STM32L4_I2C3 @@ -642,6 +1033,7 @@ config STM32L4_DAC2 bool "DAC2" default n select STM32L4_DAC + depends on STM32L4_HAVE_DAC2 config STM32L4_OPAMP bool "OPAMP" @@ -684,6 +1076,7 @@ config STM32L4_SDMMC1 bool "SDMMC1" default n select ARCH_HAVE_SDIO + depends on STM32L4_HAVE_SDMMC1 config STM32L4_TIM1 bool "TIM1" @@ -698,6 +1091,7 @@ config STM32L4_SPI1 config STM32L4_TIM8 bool "TIM8" default n + depends on STM32L4_HAVE_TIM8 config STM32L4_USART1 bool "USART1" @@ -717,6 +1111,7 @@ config STM32L4_TIM16 config STM32L4_TIM17 bool "TIM17" default n + depends on STM32L4_HAVE_TIM17 config STM32L4_COMP bool "COMP" @@ -728,14 +1123,51 @@ config STM32L4_SAI1 default n depends on STM32L4_HAVE_SAI1 +config STM32L4_SAI1_A + bool "SAI1 Block A" + default n + select AUDIO + select I2S + select SCHED_WORKQUEUE + select STM32L4_SAI + depends on STM32L4_SAI1 + +config STM32L4_SAI1_B + bool "SAI1 Block B" + default n + select AUDIO + select I2S + select SCHED_WORKQUEUE + select STM32L4_SAI + depends on STM32L4_SAI1 + config STM32L4_SAI2 bool "SAI2" default n depends on STM32L4_HAVE_SAI2 -config STM32L4_DFSDM - bool "DFSDM" +config STM32L4_SAI2_A + bool "SAI2 Block A" default n + select AUDIO + select I2S + select SCHED_WORKQUEUE + select STM32L4_SAI + depends on STM32L4_SAI2 + +config STM32L4_SAI2_B + bool "SAI2 Block B" + default n + select AUDIO + select I2S + select SCHED_WORKQUEUE + select STM32L4_SAI + depends on STM32L4_SAI2 + +config STM32L4_DFSDM1 + bool "DFSDM1" + default n + depends on STM32L4_HAVE_DFSDM1 comment "Other Peripherals" @@ -809,6 +1241,7 @@ config STM32L4_SAI1PLL config STM32L4_SAI2PLL bool "SAI2PLL" default n + depends on STM32L4_HAVE_SAI2 ---help--- The STM32L476 has a separate PLL for the SAI2 block. Set this true and provide configuration parameters in diff --git a/arch/arm/src/stm32l4/stm32l4x6xx_rcc.c b/arch/arm/src/stm32l4/stm32l4x6xx_rcc.c index 08344fa0ba..3b17417740 100644 --- a/arch/arm/src/stm32l4/stm32l4x6xx_rcc.c +++ b/arch/arm/src/stm32l4/stm32l4x6xx_rcc.c @@ -277,7 +277,7 @@ static inline void rcc_enableahb3(void) #ifdef CONFIG_STM32L4_FSMC /* Flexible static memory controller module clock enable */ - regval |= RCC_AHB3ENR_FMCEN; + regval |= RCC_AHB3ENR_FSMCEN; #endif @@ -563,7 +563,7 @@ static inline void rcc_enableapb2(void) regval |= RCC_APB2ENR_SAI2EN; #endif -#ifdef CONFIG_STM32L4_DFSDM +#ifdef CONFIG_STM32L4_DFSDM1 /* DFSDM clock enable */ regval |= RCC_APB2ENR_DFSDMEN; @@ -814,7 +814,6 @@ static void stm32l4_stdclockconfig(void) regval = getreg32(STM32L4_RCC_PLLSAI2CFG); - /* Enable the SAI2 PLL */ /* Set the PLL dividers and multipliers to configure the SAI2 PLL */ regval = (STM32L4_PLLSAI2CFG_PLLN | STM32L4_PLLSAI2CFG_PLLP | @@ -829,7 +828,7 @@ static void stm32l4_stdclockconfig(void) putreg32(regval, STM32L4_RCC_PLLSAI2CFG); - /* Enable the SAI1 PLL */ + /* Enable the SAI2 PLL */ regval = getreg32(STM32L4_RCC_CR); regval |= RCC_CR_PLLSAI2ON; @@ -842,7 +841,7 @@ static void stm32l4_stdclockconfig(void) } #endif - /* Enable FLASH prefetch, instruction cache, data cache, and 5 wait states */ + /* Enable FLASH prefetch, instruction cache, data cache, and 4 wait states */ #ifdef CONFIG_STM32L4_FLASH_PREFETCH regval = (FLASH_ACR_LATENCY_4 | FLASH_ACR_ICEN | FLASH_ACR_DCEN | FLASH_ACR_PRFTEN); diff --git a/configs/nucleo-l496zg/nsh/defconfig b/configs/nucleo-l496zg/nsh/defconfig index 3808958bd4..4bc74debaf 100644 --- a/configs/nucleo-l496zg/nsh/defconfig +++ b/configs/nucleo-l496zg/nsh/defconfig @@ -166,7 +166,7 @@ CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y # CONFIG_ARMV7M_LAZYFPU is not set CONFIG_ARCH_HAVE_FPU=y -CONFIG_ARCH_HAVE_DPFPU=y +# CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_FPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set CONFIG_ARM_HAVE_MPU_UNIFIED=y @@ -178,15 +178,13 @@ CONFIG_ARM_HAVE_MPU_UNIFIED=y # # CONFIG_ARMV7M_HAVE_ICACHE is not set # CONFIG_ARMV7M_HAVE_DCACHE is not set -CONFIG_ARMV7M_HAVE_ITCM=y -CONFIG_ARMV7M_HAVE_DTCM=y -# CONFIG_ARMV7M_ITCM is not set -# CONFIG_ARMV7M_DTCM is not set +# CONFIG_ARMV7M_HAVE_ITCM is not set +# CONFIG_ARMV7M_HAVE_DTCM is not set # CONFIG_ARMV7M_TOOLCHAIN_IARL is not set # CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set # CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set -CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL=y -# CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL is not set +# CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL is not set +CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL=y CONFIG_ARMV7M_HAVE_STACKCHECK=y CONFIG_ARMV7M_STACKCHECK=y # CONFIG_ARMV7M_ITMSYSLOG is not set @@ -281,6 +279,7 @@ CONFIG_STM32L4_HAVE_DAC2=y CONFIG_STM32L4_HAVE_DCMI=y CONFIG_STM32L4_HAVE_DFSDM1=y CONFIG_STM32L4_HAVE_DMA2D=y +CONFIG_STM32L4_HAVE_FSMC=y # CONFIG_STM32L4_HAVE_HASH is not set CONFIG_STM32L4_HAVE_I2C4=y CONFIG_STM32L4_HAVE_LCD=y @@ -292,7 +291,11 @@ CONFIG_STM32L4_HAVE_SAI1=y CONFIG_STM32L4_HAVE_SAI2=y CONFIG_STM32L4_HAVE_SDMMC1=y CONFIG_STM32L4_HAVE_TIM3=y +CONFIG_STM32L4_HAVE_TIM4=y +CONFIG_STM32L4_HAVE_TIM5=y CONFIG_STM32L4_HAVE_TIM7=y +CONFIG_STM32L4_HAVE_TIM8=y +CONFIG_STM32L4_HAVE_TIM17=y CONFIG_STM32L4_ADC=y # CONFIG_STM32L4_CAN is not set # CONFIG_STM32L4_DAC is not set @@ -321,15 +324,11 @@ CONFIG_STM32L4_ADC1=y # CONFIG_STM32L4_DCMI is not set # CONFIG_STM32L4_DMA2D is not set CONFIG_STM32L4_RNG=y -# CONFIG_STM32L4_SAI1_A is not set -# CONFIG_STM32L4_SAI1_B is not set -# CONFIG_STM32L4_SAI2_A is not set -# CONFIG_STM32L4_SAI2_B is not set # # AHB3 Peripherals # -# CONFIG_STM32L4_FMC is not set +CONFIG_STM32L4_FSMC=y # CONFIG_STM32L4_QSPI is not set # @@ -402,6 +401,9 @@ CONFIG_STM32L4_SAI1PLL=y # CONFIG_STM32L4_ONESHOT is not set # CONFIG_STM32L4_FREERUN is not set # CONFIG_STM32L4_TIM3_CAP is not set +# CONFIG_STM32L4_TIM4_CAP is not set +# CONFIG_STM32L4_TIM5_CAP is not set +# CONFIG_STM32L4_TIM8_CAP is not set # # ADC Configuration @@ -698,6 +700,7 @@ CONFIG_ANALOG=y # CONFIG_ADC is not set # CONFIG_COMP is not set # CONFIG_DAC is not set +# CONFIG_OPAMP is not set # CONFIG_AUDIO_DEVICES is not set # CONFIG_VIDEO_DEVICES is not set # CONFIG_BCH is not set -- GitLab From ae22eb224a1474538f5264a79d3f4ff0c36e713d Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Tue, 2 May 2017 15:20:11 +0300 Subject: [PATCH 701/990] STM32L4: changes needed for STM32L452 and Nucleo-L452RE board GPIO and UART seem similar across STMicro product matrix, so renamed files accordingly. RCC is cloned just in case, while conflicting differences there seem to be very minor. --- arch/arm/include/stm32l4/chip.h | 77 +- arch/arm/include/stm32l4/irq.h | 5 +- arch/arm/include/stm32l4/stm32l4x3xx_irq.h | 185 ++++ .../{stm32l4x6xx_gpio.h => stm32l4_gpio.h} | 8 +- arch/arm/src/stm32l4/chip/stm32l4_memorymap.h | 27 +- arch/arm/src/stm32l4/chip/stm32l4_pinmap.h | 5 +- .../{stm32l4x6xx_uart.h => stm32l4_uart.h} | 18 +- arch/arm/src/stm32l4/chip/stm32l4x3xx_dma.h | 461 ++++++++++ .../arm/src/stm32l4/chip/stm32l4x3xx_pinmap.h | 559 +++++++++++ arch/arm/src/stm32l4/chip/stm32l4x3xx_rcc.h | 789 ++++++++++++++++ arch/arm/src/stm32l4/chip/stm32l4x6xx_rcc.h | 5 +- arch/arm/src/stm32l4/stm32l4_dma.c | 25 +- arch/arm/src/stm32l4/stm32l4_dma.h | 5 +- arch/arm/src/stm32l4/stm32l4_gpio.h | 5 +- arch/arm/src/stm32l4/stm32l4_rcc.c | 5 +- arch/arm/src/stm32l4/stm32l4_rcc.h | 5 +- arch/arm/src/stm32l4/stm32l4_serial.c | 1 + arch/arm/src/stm32l4/stm32l4_uart.h | 5 +- arch/arm/src/stm32l4/stm32l4x3xx_rcc.c | 864 ++++++++++++++++++ 19 files changed, 2992 insertions(+), 62 deletions(-) create mode 100644 arch/arm/include/stm32l4/stm32l4x3xx_irq.h rename arch/arm/src/stm32l4/chip/{stm32l4x6xx_gpio.h => stm32l4_gpio.h} (98%) rename arch/arm/src/stm32l4/chip/{stm32l4x6xx_uart.h => stm32l4_uart.h} (97%) create mode 100644 arch/arm/src/stm32l4/chip/stm32l4x3xx_dma.h create mode 100644 arch/arm/src/stm32l4/chip/stm32l4x3xx_pinmap.h create mode 100644 arch/arm/src/stm32l4/chip/stm32l4x3xx_rcc.h create mode 100644 arch/arm/src/stm32l4/stm32l4x3xx_rcc.c diff --git a/arch/arm/include/stm32l4/chip.h b/arch/arm/include/stm32l4/chip.h index 7cd275e280..589d88f675 100644 --- a/arch/arm/include/stm32l4/chip.h +++ b/arch/arm/include/stm32l4/chip.h @@ -68,7 +68,7 @@ * Parts STM32L4x6xE have 512Kb of FLASH * Parts STM32L4x6xG have 1024Kb of FLASH * - * The correct FLASH size must be set with a CONFIG_STM32L4_FLASH_*KB + * The correct FLASH size must be set with a CONFIG_STM32L4_FLASH_CONFIG_* * selection. */ @@ -78,10 +78,18 @@ #elif defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX) # define STM32L4_SRAM1_SIZE (96*1024) /* 96Kb SRAM1 on AHB bus Matrix */ # define STM32L4_SRAM2_SIZE (32*1024) /* 32Kb SRAM2 on AHB bus Matrix */ +#elif defined(CONFIG_STM32L4_STM32L451XX) || defined(CONFIG_STM32L4_STM32L452XX) || \ + defined(CONFIG_STM32L4_STM32L462XX) +# define STM32L4_SRAM1_SIZE (128*1024) /* 128Kb SRAM1 on AHB bus Matrix */ +# define STM32L4_SRAM2_SIZE (32*1024) /* 32Kb SRAM2 on AHB bus Matrix */ +#elif defined(CONFIG_STM32L4_STM32L432XX) +# define STM32L4_SRAM1_SIZE (48*1024) /* 48Kb SRAM1 on AHB bus Matrix */ +# define STM32L4_SRAM2_SIZE (16*1024) /* 16Kb SRAM2 on AHB bus Matrix */ #else # error "Unsupported STM32L4 chip" #endif +#if defined(CONFIG_STM32L4_STM32L4X6) # define STM32L4_NFSMC 1 /* Have FSMC memory controller */ # define STM32L4_NATIM 2 /* Two advanced timers TIM1 and 8 */ # define STM32L4_NGTIM32 2 /* 32-bit general timers TIM2 and 5 with DMA */ @@ -100,6 +108,7 @@ # define STM32L4_NI2C 3 /* I2C1-3 */ #endif # define STM32L4_NUSBOTGFS 1 /* USB OTG FS */ +# define STM32L4_NUSBFS 0 /* No USB FS */ #if defined(CONFIG_STM32L4_STM32L496XX) # define STM32L4_NCAN 2 /* CAN1-2 */ #else @@ -118,6 +127,72 @@ # define STM32L4_NCRC 1 /* CRC */ # define STM32L4_NCOMP 2 /* Comparators */ # define STM32L4_NOPAMP 2 /* Operational Amplifiers */ +#endif /* CONFIG_STM32L4_STM32L4X6 */ + +#if defined(CONFIG_STM32L4_STM32L451XX) || defined(CONFIG_STM32L4_STM32L452XX) || \ + defined(CONFIG_STM32L4_STM32L462XX) +# define STM32L4_NFSMC 0 /* No FSMC memory controller */ +# define STM32L4_NATIM 1 /* One advanced timer TIM1 */ +# define STM32L4_NGTIM32 1 /* 32-bit general timer TIM2 with DMA */ +# define STM32L4_NGTIM16 3 /* 16-bit general timers TIM3, TIM15-16 with DMA */ +# define STM32L4_NGTIMNDMA 0 /* No 16-bit general timers without DMA */ +# define STM32L4_NBTIM 1 /* One basic timer, TIM6 */ +# define STM32L4_NLPTIM 2 /* Two low-power timers, LPTIM1-2 */ +# define STM32L4_NRNG 1 /* Random number generator (RNG) */ +# define STM32L4_NUART 1 /* UART 4 */ +# define STM32L4_NUSART 3 /* USART 1-3 */ +# define STM32L4_NLPUART 1 /* LPUART 1 */ +# define STM32L4_NSPI 3 /* SPI1-3 */ +# define STM32L4_NI2C 4 /* I2C1-4 */ +# define STM32L4_NUSBOTGFS 0 /* No USB OTG FS */ +#if defined(CONFIG_STM32L4_STM32L451XX) +# define STM32L4_NUSBFS 0 /* No USB FS */ +#else +# define STM32L4_NUSBFS 1 /* USB FS */ +#endif +# define STM32L4_NCAN 1 /* CAN1 */ +# define STM32L4_NSAI 1 /* SAI1 */ +#if defined(CONFIG_STM32L4_HAVE_SDMMC1) +# define STM32L4_NSDMMC 1 /* SDMMC interface */ +#else +# define STM32L4_NSDMMC 0 /* No SDMMC interface */ +#endif +# define STM32L4_NDMA 2 /* DMA1-2 */ +# define STM32L4_NPORTS 8 /* 8 GPIO ports, GPIOA-H */ +# define STM32L4_NADC 1 /* 12-bit ADC1, 16 channels (10 in CE,CV) */ +# define STM32L4_NDAC 1 /* 12-bit DAC1 */ +# define STM32L4_NCRC 1 /* CRC */ +# define STM32L4_NCOMP 2 /* Comparators */ +# define STM32L4_NOPAMP 1 /* Operational Amplifiers */ +#endif /* CONFIG_STM32L4_STM32L451XX */ + +#if defined(CONFIG_STM32L4_STM32L432XX) +# define STM32L4_NFSMC 0 /* No FSMC memory controller */ +# define STM32L4_NATIM 1 /* One advanced timer TIM1 */ +# define STM32L4_NGTIM32 1 /* 32-bit general timer TIM2 with DMA */ +# define STM32L4_NGTIM16 2 /* 16-bit general timers TIM15-16 with DMA */ +# define STM32L4_NGTIMNDMA 0 /* No 16-bit general timers without DMA */ +# define STM32L4_NBTIM 2 /* Two basic timers, TIM6-7 */ +# define STM32L4_NLPTIM 2 /* Two low-power timers, LPTIM1-2 */ +# define STM32L4_NRNG 1 /* Random number generator (RNG) */ +# define STM32L4_NUART 0 /* No UART */ +# define STM32L4_NUSART 2 /* USART 1-2 */ +# define STM32L4_NLPUART 1 /* LPUART 1 */ +# define STM32L4_NSPI 2 /* SPI1, SPI3 */ +# define STM32L4_NI2C 2 /* I2C1, I2C3 */ +# define STM32L4_NUSBOTGFS 0 /* No USB OTG FS */ +# define STM32L4_NUSBFS 1 /* USB FS */ +# define STM32L4_NCAN 1 /* CAN1 */ +# define STM32L4_NSAI 1 /* SAI1 */ +# define STM32L4_NSDMMC 0 /* No SDMMC interface */ +# define STM32L4_NDMA 2 /* DMA1-2 */ +# define STM32L4_NPORTS 8 /* 8 GPIO ports, GPIOA-H */ +# define STM32L4_NADC 1 /* 12-bit ADC1, 10 channels */ +# define STM32L4_NDAC 2 /* 12-bit DAC1-2 */ +# define STM32L4_NCRC 1 /* CRC */ +# define STM32L4_NCOMP 2 /* Comparators */ +# define STM32L4_NOPAMP 1 /* Operational Amplifiers */ +#endif /* CONFIG_STM32L4_STM32L432XX */ /* NVIC priority levels *************************************************************/ /* 16 Programmable interrupt levels */ diff --git a/arch/arm/include/stm32l4/irq.h b/arch/arm/include/stm32l4/irq.h index abb543bc72..480b7d693a 100644 --- a/arch/arm/include/stm32l4/irq.h +++ b/arch/arm/include/stm32l4/irq.h @@ -76,9 +76,10 @@ #define STM32L4_IRQ_FIRST (16) /* Vector number of the first external interrupt */ -#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX) || \ - defined(CONFIG_STM32L4_STM32L496XX) +#if defined(CONFIG_STM32L4_STM32L4X6) # include +#elif defined(CONFIG_STM32L4_STM32L4X3) +# include #else # error "Unsupported STM32 L4 chip" #endif diff --git a/arch/arm/include/stm32l4/stm32l4x3xx_irq.h b/arch/arm/include/stm32l4/stm32l4x3xx_irq.h new file mode 100644 index 0000000000..e3c3c8cf17 --- /dev/null +++ b/arch/arm/include/stm32l4/stm32l4x3xx_irq.h @@ -0,0 +1,185 @@ +/**************************************************************************************************** + * arch/arm/include/stm32l4/stm32l4x3xx_irq.h + * + * Copyright (C) 2015 Sebastien Lorquet. All rights reserved. + * Authors: Sebastien Lorquet + * 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. + * + ****************************************************************************************************/ + +/* This file should never be included directed but, rather, only indirectly through arch/irq.h */ + +#ifndef __ARCH_ARM_INCLUDE_STM32L4_STM32L4X3XX_IRQ_H +#define __ARCH_ARM_INCLUDE_STM32L4_STM32L4X3XX_IRQ_H + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include + +/**************************************************************************************************** + * Pre-processor Definitions + ****************************************************************************************************/ + +/* IRQ numbers. The IRQ number corresponds vector number and hence map directly to bits in the + * NVIC. This does, however, waste several words of memory in the IRQ to handle mapping tables. + * + * Processor Exceptions (vectors 0-15). These common definitions can be found in the file + * nuttx/arch/arm/include/stm32f7/irq.h which includes this file + * + * External interrupts (vectors >= 16) + */ + +#define STM32L4_IRQ_WWDG (STM32L4_IRQ_FIRST+0) /* 0: Window Watchdog interrupt */ +#define STM32L4_IRQ_PVD (STM32L4_IRQ_FIRST+1) /* 1: PVD through EXTI Line detection interrupt */ +#define STM32L4_IRQ_TAMPER (STM32L4_IRQ_FIRST+2) /* 2: Tamper and time stamp interrupts */ +#define STM32L4_IRQ_TIMESTAMP (STM32L4_IRQ_FIRST+2) /* 2: Tamper and time stamp interrupts */ +#define STM32L4_IRQ_RTC_WKUP (STM32L4_IRQ_FIRST+3) /* 3: RTC global interrupt */ +#define STM32L4_IRQ_FLASH (STM32L4_IRQ_FIRST+4) /* 4: Flash global interrupt */ +#define STM32L4_IRQ_RCC (STM32L4_IRQ_FIRST+5) /* 5: RCC global interrupt */ +#define STM32L4_IRQ_EXTI0 (STM32L4_IRQ_FIRST+6) /* 6: EXTI Line 0 interrupt */ +#define STM32L4_IRQ_EXTI1 (STM32L4_IRQ_FIRST+7) /* 7: EXTI Line 1 interrupt */ +#define STM32L4_IRQ_EXTI2 (STM32L4_IRQ_FIRST+8) /* 8: EXTI Line 2 interrupt */ +#define STM32L4_IRQ_EXTI3 (STM32L4_IRQ_FIRST+9) /* 9: EXTI Line 3 interrupt */ +#define STM32L4_IRQ_EXTI4 (STM32L4_IRQ_FIRST+10) /* 10: EXTI Line 4 interrupt */ +#define STM32L4_IRQ_DMA1CH1 (STM32L4_IRQ_FIRST+11) /* 12: DMA1 Channel 1 global interrupt */ +#define STM32L4_IRQ_DMA1CH2 (STM32L4_IRQ_FIRST+12) /* 13: DMA1 Channel 2 global interrupt */ +#define STM32L4_IRQ_DMA1CH3 (STM32L4_IRQ_FIRST+13) /* 14: DMA1 Channel 3 global interrupt */ +#define STM32L4_IRQ_DMA1CH4 (STM32L4_IRQ_FIRST+14) /* 15: DMA1 Channel 4 global interrupt */ +#define STM32L4_IRQ_DMA1CH5 (STM32L4_IRQ_FIRST+15) /* 16: DMA1 Channel 5 global interrupt */ +#define STM32L4_IRQ_DMA1CH6 (STM32L4_IRQ_FIRST+16) /* 17: DMA1 Channel 6 global interrupt */ +#define STM32L4_IRQ_DMA1CH7 (STM32L4_IRQ_FIRST+17) /* 17: DMA1 Channel 7 global interrupt */ +#define STM32L4_IRQ_ADC1 (STM32L4_IRQ_FIRST+18) /* 18: ADC1 global interrupt */ +#define STM32L4_IRQ_CAN1TX (STM32L4_IRQ_FIRST+19) /* 19: CAN1 TX interrupts */ +#define STM32L4_IRQ_CAN1RX0 (STM32L4_IRQ_FIRST+20) /* 20: CAN1 RX0 interrupts */ +#define STM32L4_IRQ_CAN1RX1 (STM32L4_IRQ_FIRST+21) /* 21: CAN1 RX1 interrupt */ +#define STM32L4_IRQ_CAN1SCE (STM32L4_IRQ_FIRST+22) /* 22: CAN1 SCE interrupt */ +#define STM32L4_IRQ_EXTI95 (STM32L4_IRQ_FIRST+23) /* 23: EXTI Line[9:5] interrupts */ +#define STM32L4_IRQ_TIM1BRK (STM32L4_IRQ_FIRST+24) /* 24: TIM1 Break interrupt */ +#define STM32L4_IRQ_TIM15 (STM32L4_IRQ_FIRST+24) /* 24: TIM15 global interrupt */ +#define STM32L4_IRQ_TIM1UP (STM32L4_IRQ_FIRST+25) /* 25: TIM1 Update interrupt */ +#define STM32L4_IRQ_TIM16 (STM32L4_IRQ_FIRST+25) /* 25: TIM16 global interrupt */ +#define STM32L4_IRQ_TIM1TRGCOM (STM32L4_IRQ_FIRST+26) /* 26: TIM1 Trigger and Commutation interrupts */ +#define STM32L4_IRQ_TIM1CC (STM32L4_IRQ_FIRST+27) /* 27: TIM1 Capture Compare interrupt */ +#define STM32L4_IRQ_TIM2 (STM32L4_IRQ_FIRST+28) /* 28: TIM2 global interrupt */ +#define STM32L4_IRQ_TIM3 (STM32L4_IRQ_FIRST+29) /* 29: TIM3 global interrupt */ +/* Reserved */ /* 30: TIM4 global interrupt */ +#define STM32L4_IRQ_I2C1EV (STM32L4_IRQ_FIRST+31) /* 31: I2C1 event interrupt */ +#define STM32L4_IRQ_I2C1ER (STM32L4_IRQ_FIRST+32) /* 32: I2C1 error interrupt */ +#define STM32L4_IRQ_I2C2EV (STM32L4_IRQ_FIRST+33) /* 33: I2C2 event interrupt */ +#define STM32L4_IRQ_I2C2ER (STM32L4_IRQ_FIRST+34) /* 34: I2C2 error interrupt */ +#define STM32L4_IRQ_SPI1 (STM32L4_IRQ_FIRST+35) /* 35: SPI1 global interrupt */ +#define STM32L4_IRQ_SPI2 (STM32L4_IRQ_FIRST+36) /* 36: SPI2 global interrupt */ +#define STM32L4_IRQ_USART1 (STM32L4_IRQ_FIRST+37) /* 37: USART1 global interrupt */ +#define STM32L4_IRQ_USART2 (STM32L4_IRQ_FIRST+38) /* 38: USART2 global interrupt */ +#define STM32L4_IRQ_USART3 (STM32L4_IRQ_FIRST+39) /* 39: USART3 global interrupt */ +#define STM32L4_IRQ_EXTI1510 (STM32L4_IRQ_FIRST+40) /* 40: EXTI Line[15:10] interrupts */ +#define STM32L4_IRQ_RTCALRM (STM32L4_IRQ_FIRST+41) /* 41: RTC alarm through EXTI line interrupt */ +/* Reserved */ /* 42-48: reserved */ +#define STM32L4_IRQ_SDMMC1 (STM32L4_IRQ_FIRST+49) /* 49: SDMMC1 global interrupt */ +/* Reserved */ /* 50: TIM5 global interrupt */ +#define STM32L4_IRQ_SPI3 (STM32L4_IRQ_FIRST+51) /* 51: SPI3 global interrupt */ +#define STM32L4_IRQ_UART4 (STM32L4_IRQ_FIRST+52) /* 52: UART4 global interrupt */ +/* Reserved */ /* 53: UART5 global interrupt */ +#define STM32L4_IRQ_TIM6 (STM32L4_IRQ_FIRST+54) /* 54: TIM6 global interrupt */ +#define STM32L4_IRQ_DAC (STM32L4_IRQ_FIRST+54) /* 54: DAC1 underrun error interrupts */ +#define STM32L4_IRQ_TIM7 (STM32L4_IRQ_FIRST+55) /* 55: TIM7 global interrupt */ +#define STM32L4_IRQ_DMA2CH1 (STM32L4_IRQ_FIRST+56) /* 56: DMA2 Channel 1 global interrupt */ +#define STM32L4_IRQ_DMA2CH2 (STM32L4_IRQ_FIRST+57) /* 57: DMA2 Channel 2 global interrupt */ +#define STM32L4_IRQ_DMA2CH3 (STM32L4_IRQ_FIRST+58) /* 58: DMA2 Channel 3 global interrupt */ +#define STM32L4_IRQ_DMA2CH4 (STM32L4_IRQ_FIRST+59) /* 59: DMA2 Channel 4 global interrupt */ +#define STM32L4_IRQ_DMA2CH5 (STM32L4_IRQ_FIRST+60) /* 60: DMA2 Channel 5 global interrupt */ +#define STM32L4_IRQ_DFSDM0 (STM32L4_IRQ_FIRST+61) /* 61: DFSDM0 global interrupt */ +#define STM32L4_IRQ_DFSDM1 (STM32L4_IRQ_FIRST+62) /* 62: DFSDM1 global interrupt*/ +/* Reserved */ /* 63: DFSDM2 global interrupt */ +#define STM32L4_IRQ_COMP (STM32L4_IRQ_FIRST+64) /* 64: COMP1/COMP2 interrupts */ +#define STM32L4_IRQ_LPTIM1 (STM32L4_IRQ_FIRST+65) /* 65: LPTIM1 global interrupt */ +#define STM32L4_IRQ_LPTIM2 (STM32L4_IRQ_FIRST+66) /* 66: LPTIM2 global interrupt */ +#define STM32L4_IRQ_USB_FS (STM32L4_IRQ_FIRST+67) /* 67: USB event interrupt through EXTI line 17 */ +#define STM32L4_IRQ_DMA2CH6 (STM32L4_IRQ_FIRST+68) /* 68: DMA2 Channel 6 global interrupt */ +#define STM32L4_IRQ_DMA2CH7 (STM32L4_IRQ_FIRST+69) /* 69: DMA2 Channel 7 global interrupt */ +#define STM32L4_IRQ_LPUART1 (STM32L4_IRQ_FIRST+70) /* 70: Low power UART 1 global interrupt */ +#define STM32L4_IRQ_QUADSPI (STM32L4_IRQ_FIRST+71) /* 71: QUADSPI global interrupt */ +#define STM32L4_IRQ_I2C3EV (STM32L4_IRQ_FIRST+72) /* 72: I2C3 event interrupt */ +#define STM32L4_IRQ_I2C3ER (STM32L4_IRQ_FIRST+73) /* 73: I2C3 error interrupt */ +#define STM32L4_IRQ_SAI1 (STM32L4_IRQ_FIRST+74) /* 74: SAI1 global interrupt */ +/* Reserved */ /* 75: SAI2 global interrupt */ +#define STM32L4_IRQ_SWPMI1 (STM32L4_IRQ_FIRST+76) /* 76: SWPMI1 global interrupt */ +#define STM32L4_IRQ_TSC (STM32L4_IRQ_FIRST+77) /* 77: TSC global interrupt */ +#define STM32L4_IRQ_LCD (STM32L4_IRQ_FIRST+78) /* 78: LCD global interrupt */ +#define STM32L4_IRQ_AES (STM32L4_IRQ_FIRST+79) /* 79: AES crypto global interrupt */ +#define STM32L4_IRQ_RNG (STM32L4_IRQ_FIRST+80) /* 80: RNG global interrupt */ +#define STM32L4_IRQ_FPU (STM32L4_IRQ_FIRST+81) /* 81: FPU global interrupt */ +#define STM32L4_IRQ_CRS (STM32L4_IRQ_FIRST+82) /* 82: CRS global interrupt */ +#define STM32L4_IRQ_I2C4EV (STM32L4_IRQ_FIRST+83) /* 83: I2C4 event interrupt */ +#define STM32L4_IRQ_I2C4ER (STM32L4_IRQ_FIRST+84) /* 84: I2C4 error interrupt */ + +#if defined(CONFIG_STM32L4_STM32L4X3) +# define NR_INTERRUPTS 85 +#else +# error "Unsupported STM32L4 chip" +#endif + +#define NR_VECTORS (STM32L4_IRQ_FIRST+NR_INTERRUPTS) + +/* EXTI interrupts (Do not use IRQ numbers) */ + +#define NR_IRQS NR_VECTORS + +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + +/**************************************************************************************************** + * Public Data + ****************************************************************************************************/ + +#ifndef __ASSEMBLY__ +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/**************************************************************************************************** + * Public Functions + ****************************************************************************************************/ + +#undef EXTERN +#ifdef __cplusplus +} +#endif +#endif + +#endif /* __ARCH_ARM_INCLUDE_STM32L4_STM32L4X3XX_IRQ_H */ diff --git a/arch/arm/src/stm32l4/chip/stm32l4x6xx_gpio.h b/arch/arm/src/stm32l4/chip/stm32l4_gpio.h similarity index 98% rename from arch/arm/src/stm32l4/chip/stm32l4x6xx_gpio.h rename to arch/arm/src/stm32l4/chip/stm32l4_gpio.h index f4f32e7f92..08e0e9e519 100644 --- a/arch/arm/src/stm32l4/chip/stm32l4x6xx_gpio.h +++ b/arch/arm/src/stm32l4/chip/stm32l4_gpio.h @@ -1,5 +1,5 @@ /************************************************************************************ - * arch/arm/src/stm32l4/chip/stm32l4x6xx_gpio.h + * arch/arm/src/stm32l4/chip/stm32l4_gpio.h * * Copyright (C) 2016, Sebastien Lorquet. All rights reserved. * Author: Sebastien Lorquet @@ -33,8 +33,8 @@ * ************************************************************************************/ -#ifndef __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X6XX_GPIO_H -#define __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X6XX_GPIO_H +#ifndef __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4_GPIO_H +#define __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4_GPIO_H /************************************************************************************ * Included Files @@ -371,5 +371,5 @@ #define GPIO_AFRH15_SHIFT (28) #define GPIO_AFRH15_MASK (15 << GPIO_AFRH15_SHIFT) -#endif /* __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X6XX_GPIO_H */ +#endif /* __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4_GPIO_H */ diff --git a/arch/arm/src/stm32l4/chip/stm32l4_memorymap.h b/arch/arm/src/stm32l4/chip/stm32l4_memorymap.h index 33a9b5bd56..cbd89cc429 100644 --- a/arch/arm/src/stm32l4/chip/stm32l4_memorymap.h +++ b/arch/arm/src/stm32l4/chip/stm32l4_memorymap.h @@ -40,7 +40,7 @@ * Pre-processor Definitions ************************************************************************************/ -/* STM32F40XXX Address Blocks *******************************************************/ +/* STM32L4XXX Address Blocks ********************************************************/ #define STM32L4_CODE_BASE 0x00000000 /* 0x00000000-0x1fffffff: 512Mb code block */ #define STM32L4_SRAM_BASE 0x20000000 /* 0x20000000-0x3fffffff: 512Mb sram block (96k or 256k) */ @@ -50,7 +50,7 @@ # define STM32L4_FSMC_BANK2 0x70000000 /* 0x70000000-0x7fffffff: 256Mb NAND FLASH */ #define STM32L4_FSMC_BASE34 0x80000000 /* 0x80000000-0x8fffffff: 512Mb FSMC bank3 / QSPI block */ # define STM32L4_FSMC_BANK3 0x80000000 /* 0x80000000-0x8fffffff: 256Mb NAND FLASH */ -# define STM32L4_QSPI_BANK 0x90000000 /* 0x90000000-0x9fffffff: 256Mb QUADSPI*/ +# define STM32L4_QSPI_BANK 0x90000000 /* 0x90000000-0x9fffffff: 256Mb QUADSPI */ #define STM32L4_FSMC_BASE 0xa0000000 /* 0xa0000000-0xbfffffff: FSMC register block */ #define STM32L4_QSPI_BASE 0xa0001000 /* 0xa0000000-0xbfffffff: QSPI register block */ /* 0xc0000000-0xdfffffff: 512Mb (not used) */ @@ -68,10 +68,13 @@ /* 0x08100000-0x0fffffff: Reserved */ #define STM32L4_SRAM2_BASE 0x10000000 /* 0x10000000-0x1000ffff: 32Kb or 64Kb SRAM2 */ /* 0x10010000-0x1ffeffff: Reserved */ -#define STM32L4_SYSMEM_BASE 0x1fff0000 /* 0x1fff0000-0x1fff7a0f: System memory */ - /* 0x1fff7a10-0x1fff7fff: Reserved */ -#define STM32L4_OPTION_BASE 0x1fffc000 /* 0x1fffc000-0x1fffc007: Option bytes */ - /* 0x1fffc008-0x1fffffff: Reserved */ +#define STM32L4_SYSMEM_BASE 0x1fff0000 /* 0x1fff0000-0x1fff6fff: System memory */ +#define STM32L4_OTP_BASE 0x1fff7000 /* 0x1fff7000-0x1fff73ff: OTP memory */ + /* 0x1fff7400-0x1fff77ff: Reserved */ +#define STM32L4_OPTION_BASE 0x1fff7800 /* 0x1fff7800-0x1fff780f: Option bytes */ + /* 0x1fff7810-0x1ffff7ff: Reserved */ +#define STM32L4_OPTION2_BASE 0x1ffff800 /* 0x1ffff800-0x1ffff80f: Option bytes 2 */ + /* 0x1ffff810-0x1fffffff: Reserved */ /* System Memory Addresses **********************************************************/ @@ -84,9 +87,13 @@ #define STM32L4_SYSMEM_PACKAGE 0x1fff7500 /* This bitfield indicates the package * type. * 0: LQFP64 + * 1: WLCSP64 * 2: LQFP100 * 3: UFBGA132 * 4: LQFP144, WLCSP81 or WLCSP72 + * 10: WLCSP49 + * 11: UFBGA64 + * 12: UFBGA100 * 16: UFBGA169 * 17: WLCSP100 */ @@ -124,8 +131,14 @@ #define STM32L4_OPAMP_BASE 0x40007800 #define STM32L4_DAC_BASE 0x40007400 #define STM32L4_PWR_BASE 0x40007000 -#define STM32L4_CAN2_BASE 0x40006800 +#if defined(CONFIG_STM32L4_STM32L4X2) +# define STM32L4_USB_SRAM_BASE 0x40006c00 +# define STM32L4_USB_FS_BASE 0x40006800 +#else +# define STM32L4_CAN2_BASE 0x40006800 +#endif #define STM32L4_CAN1_BASE 0x40006400 +#define STM32L4_CRS_BASE 0x40006000 #define STM32L4_I2C3_BASE 0x40005c00 #define STM32L4_I2C2_BASE 0x40005800 #define STM32L4_I2C1_BASE 0x40005400 diff --git a/arch/arm/src/stm32l4/chip/stm32l4_pinmap.h b/arch/arm/src/stm32l4/chip/stm32l4_pinmap.h index 28257e1738..85140db034 100644 --- a/arch/arm/src/stm32l4/chip/stm32l4_pinmap.h +++ b/arch/arm/src/stm32l4/chip/stm32l4_pinmap.h @@ -43,9 +43,10 @@ #include #include "chip.h" -#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX) || \ - defined(CONFIG_STM32L4_STM32L496XX) +#if defined(CONFIG_STM32L4_STM32L4X6) # include "chip/stm32l4x6xx_pinmap.h" +#elif defined(CONFIG_STM32L4_STM32L4X3) +# include "chip/stm32l4x3xx_pinmap.h" #else # error "Unsupported STM32 L4 pin map" #endif diff --git a/arch/arm/src/stm32l4/chip/stm32l4x6xx_uart.h b/arch/arm/src/stm32l4/chip/stm32l4_uart.h similarity index 97% rename from arch/arm/src/stm32l4/chip/stm32l4x6xx_uart.h rename to arch/arm/src/stm32l4/chip/stm32l4_uart.h index 7e1855061d..c7605ab8ad 100644 --- a/arch/arm/src/stm32l4/chip/stm32l4x6xx_uart.h +++ b/arch/arm/src/stm32l4/chip/stm32l4_uart.h @@ -1,5 +1,5 @@ /************************************************************************************ - * arch/arm/src/stm32l4/chip/stm32l4x6xx_uart.h + * arch/arm/src/stm32l4/chip/stm32l4_uart.h * * Copyright (C) 2009, 2011-2014 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -33,8 +33,8 @@ * ************************************************************************************/ -#ifndef __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X6XX_UART_H -#define __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X6XX_UART_H +#ifndef __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4_UART_H +#define __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4_UART_H /************************************************************************************ * Included Files @@ -57,7 +57,7 @@ #define STM32L4_USART_GTPR_OFFSET 0x0010 /* Guard time and prescaler register */ #define STM32L4_USART_RTOR_OFFSET 0x0014 /* Receiver timeout register */ #define STM32L4_USART_RQR_OFFSET 0x0018 /* Request register */ -#define STM32L4_USART_ISR_OFFSET 0x001c /* Interrupot and status register */ +#define STM32L4_USART_ISR_OFFSET 0x001c /* Interrupt and status register */ #define STM32L4_USART_ICR_OFFSET 0x0020 /* Interrupt flag clear register */ #define STM32L4_USART_RDR_OFFSET 0x0024 /* Receive Data register */ #define STM32L4_USART_TDR_OFFSET 0x0028 /* Transmit Data register */ @@ -139,7 +139,7 @@ /* Control register 1 */ #define USART_CR1_UE (1 << 0) /* Bit 0: USART Enable */ -#define USART_CR1_UESM (1 << 1) /* Bit 1: USART Enable in Stop mode*/ +#define USART_CR1_UESM (1 << 1) /* Bit 1: USART Enable in Stop mode */ #define USART_CR1_RE (1 << 2) /* Bit 2: Receiver Enable */ #define USART_CR1_TE (1 << 3) /* Bit 3: Transmitter Enable */ #define USART_CR1_IDLEIE (1 << 4) /* Bit 4: IDLE Interrupt Enable */ @@ -150,7 +150,7 @@ #define USART_CR1_PS (1 << 9) /* Bit 9: Parity Selection */ #define USART_CR1_PCE (1 << 10) /* Bit 10: Parity Control Enable */ #define USART_CR1_WAKE (1 << 11) /* Bit 11: Wakeup method */ -#define USART_CR1_M0 (1 << 12) /* Bit 12: word length */ +#define USART_CR1_M0 (1 << 12) /* Bit 12: Word length */ #define USART_CR1_MME (1 << 13) /* Bit 13: Mute mode enable */ #define USART_CR1_CMIE (1 << 14) /* Bit 14: Character match interrupt enable */ #define USART_CR1_OVER8 (1 << 15) /* Bit 15: Oversampling mode */ @@ -163,7 +163,7 @@ #define USART_CR1_RTOIE (1 << 26) /* Bit 26: Receiver timeout interrupt enable */ #define USART_CR1_EOBIE (1 << 27) /* Bit 27: End of block interrupt enable */ -#define USART_CR1_M1 (1 << 28) /* Bit 12: word length */ +#define USART_CR1_M1 (1 << 28) /* Bit 28: Word length */ #define USART_CR1_ALLINTS (USART_CR1_IDLEIE|USART_CR1_RXNEIE| \ USART_CR1_TCIE|USART_CR1_TXEIE|USART_CR1_PEIE|USART_CR1_CMIE| \ @@ -171,7 +171,7 @@ /* Control register 2 */ -#define USART_CR2_ADDM7 (1 << 4) /* Bit 4: */ +#define USART_CR2_ADDM7 (1 << 4) /* Bit 4: 7-bit/4-bit Address Detection */ #define USART_CR2_LBDL (1 << 5) /* Bit 5: LIN Break Detection Length */ #define USART_CR2_LBDIE (1 << 6) /* Bit 6: LIN Break Detection Interrupt Enable */ #define USART_CR2_LBCL (1 << 8) /* Bit 8: Last Bit Clock pulse */ @@ -314,5 +314,5 @@ * Public Functions ************************************************************************************/ -#endif /* __ARCH_ARM_STC_STM32L4_CHIP_STM32L4X6XX_UART_H */ +#endif /* __ARCH_ARM_STC_STM32L4_CHIP_STM32L4_UART_H */ diff --git a/arch/arm/src/stm32l4/chip/stm32l4x3xx_dma.h b/arch/arm/src/stm32l4/chip/stm32l4x3xx_dma.h new file mode 100644 index 0000000000..166562c9c5 --- /dev/null +++ b/arch/arm/src/stm32l4/chip/stm32l4x3xx_dma.h @@ -0,0 +1,461 @@ +/************************************************************************************ + * arch/arm/src/stm32l4/chip/stm32l4x3xx_dma.h + * + * Copyright (C) 2009, 2011-2013 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X3XX_DMA_H +#define __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X3XX_DMA_H + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* 14 Channels Total: 7 DMA1 Channels(1-7) and 7 DMA2 channels (1-7) */ + +#define DMA1 0 +#define DMA2 1 +#define DMA3 2 +#define DMA4 3 +#define DMA5 4 +#define DMA6 5 +#define DMA7 6 + +/* Register Offsets *****************************************************************/ + +#define STM32L4_DMA_ISR_OFFSET 0x0000 /* DMA interrupt status register */ +#define STM32L4_DMA_IFCR_OFFSET 0x0004 /* DMA interrupt flag clear register */ + +#define STM32L4_DMACHAN_OFFSET(n) (0x0014*(n)) +#define STM32L4_DMACHAN1_OFFSET 0x0000 +#define STM32L4_DMACHAN2_OFFSET 0x0014 +#define STM32L4_DMACHAN3_OFFSET 0x0028 +#define STM32L4_DMACHAN4_OFFSET 0x003c +#define STM32L4_DMACHAN5_OFFSET 0x0050 +#define STM32L4_DMACHAN6_OFFSET 0x0064 +#define STM32L4_DMACHAN7_OFFSET 0x0078 + +#define STM32L4_DMACHAN_CCR_OFFSET 0x0008 /* DMA channel configuration register */ +#define STM32L4_DMACHAN_CNDTR_OFFSET 0x000c /* DMA channel number of data register */ +#define STM32L4_DMACHAN_CPAR_OFFSET 0x0010 /* DMA channel peripheral address register */ +#define STM32L4_DMACHAN_CMAR_OFFSET 0x0014 /* DMA channel memory address register */ + +#define STM32L4_DMA_CCR_OFFSET(n) (STM32L4_DMACHAN_CCR_OFFSET+STM32L4_DMACHAN_OFFSET(n)) +#define STM32L4_DMA_CNDTR_OFFSET(n) (STM32L4_DMACHAN_CNDTR_OFFSET+STM32L4_DMACHAN_OFFSET(n)) +#define STM32L4_DMA_CPAR_OFFSET(n) (STM32L4_DMACHAN_CPAR_OFFSET+STM32L4_DMACHAN_OFFSET(n)) +#define STM32L4_DMA_CMAR_OFFSET(n) (STM32L4_DMACHAN_CMAR_OFFSET+STM32L4_DMACHAN_OFFSET(n)) + +#define STM32L4_DMA_CCR1_OFFSET 0x0008 /* DMA channel 1 configuration register */ +#define STM32L4_DMA_CCR2_OFFSET 0x001c /* DMA channel 2 configuration register */ +#define STM32L4_DMA_CCR3_OFFSET 0x0030 /* DMA channel 3 configuration register */ +#define STM32L4_DMA_CCR4_OFFSET 0x0044 /* DMA channel 4 configuration register */ +#define STM32L4_DMA_CCR5_OFFSET 0x0058 /* DMA channel 5 configuration register */ +#define STM32L4_DMA_CCR6_OFFSET 0x006c /* DMA channel 6 configuration register */ +#define STM32L4_DMA_CCR7_OFFSET 0x0080 /* DMA channel 7 configuration register */ + +#define STM32L4_DMA_CNDTR1_OFFSET 0x000c /* DMA channel 1 number of data register */ +#define STM32L4_DMA_CNDTR2_OFFSET 0x0020 /* DMA channel 2 number of data register */ +#define STM32L4_DMA_CNDTR3_OFFSET 0x0034 /* DMA channel 3 number of data register */ +#define STM32L4_DMA_CNDTR4_OFFSET 0x0048 /* DMA channel 4 number of data register */ +#define STM32L4_DMA_CNDTR5_OFFSET 0x005c /* DMA channel 5 number of data register */ +#define STM32L4_DMA_CNDTR6_OFFSET 0x0070 /* DMA channel 6 number of data register */ +#define STM32L4_DMA_CNDTR7_OFFSET 0x0084 /* DMA channel 7 number of data register */ + +#define STM32L4_DMA_CPAR1_OFFSET 0x0010 /* DMA channel 1 peripheral address register */ +#define STM32L4_DMA_CPAR2_OFFSET 0x0024 /* DMA channel 2 peripheral address register */ +#define STM32L4_DMA_CPAR3_OFFSET 0x0038 /* DMA channel 3 peripheral address register */ +#define STM32L4_DMA_CPAR4_OFFSET 0x004c /* DMA channel 4 peripheral address register */ +#define STM32L4_DMA_CPAR5_OFFSET 0x0060 /* DMA channel 5 peripheral address register */ +#define STM32L4_DMA_CPAR6_OFFSET 0x0074 /* DMA channel 6 peripheral address register */ +#define STM32L4_DMA_CPAR7_OFFSET 0x0088 /* DMA channel 7 peripheral address register */ + +#define STM32L4_DMA_CMAR1_OFFSET 0x0014 /* DMA channel 1 memory address register */ +#define STM32L4_DMA_CMAR2_OFFSET 0x0028 /* DMA channel 2 memory address register */ +#define STM32L4_DMA_CMAR3_OFFSET 0x003c /* DMA channel 3 memory address register */ +#define STM32L4_DMA_CMAR4_OFFSET 0x0050 /* DMA channel 4 memory address register */ +#define STM32L4_DMA_CMAR5_OFFSET 0x0064 /* DMA channel 5 memory address register */ +#define STM32L4_DMA_CMAR6_OFFSET 0x0078 /* DMA channel 6 memory address register */ +#define STM32L4_DMA_CMAR7_OFFSET 0x008c /* DMA channel 7 memory address register */ + +#define STM32L4_DMA_CSELR_OFFSET 0x00a8 /* DMA channel selection register */ + +/* Register Addresses ***************************************************************/ + +#define STM32L4_DMA1_ISRC (STM32L4_DMA1_BASE+STM32L4_DMA_ISR_OFFSET) +#define STM32L4_DMA1_IFCR (STM32L4_DMA1_BASE+STM32L4_DMA_IFCR_OFFSET) + +#define STM32L4_DMA1_CCR(n) (STM32L4_DMA1_BASE+STM32L4_DMA_CCR_OFFSET(n)) +#define STM32L4_DMA1_CCR1 (STM32L4_DMA1_BASE+STM32L4_DMA_CCR1_OFFSET) +#define STM32L4_DMA1_CCR2 (STM32L4_DMA1_BASE+STM32L4_DMA_CCR2_OFFSET) +#define STM32L4_DMA1_CCR3 (STM32L4_DMA1_BASE+STM32L4_DMA_CCR3_OFFSET) +#define STM32L4_DMA1_CCR4 (STM32L4_DMA1_BASE+STM32L4_DMA_CCR4_OFFSET) +#define STM32L4_DMA1_CCR5 (STM32L4_DMA1_BASE+STM32L4_DMA_CCR5_OFFSET) +#define STM32L4_DMA1_CCR6 (STM32L4_DMA1_BASE+STM32L4_DMA_CCR6_OFFSET) +#define STM32L4_DMA1_CCR7 (STM32L4_DMA1_BASE+STM32L4_DMA_CCR7_OFFSET) + +#define STM32L4_DMA1_CNDTR(n) (STM32L4_DMA1_BASE+STM32L4_DMA_CNDTR_OFFSET(n)) +#define STM32L4_DMA1_CNDTR1 (STM32L4_DMA1_BASE+STM32L4_DMA_CNDTR1_OFFSET) +#define STM32L4_DMA1_CNDTR2 (STM32L4_DMA1_BASE+STM32L4_DMA_CNDTR2_OFFSET) +#define STM32L4_DMA1_CNDTR3 (STM32L4_DMA1_BASE+STM32L4_DMA_CNDTR3_OFFSET) +#define STM32L4_DMA1_CNDTR4 (STM32L4_DMA1_BASE+STM32L4_DMA_CNDTR4_OFFSET) +#define STM32L4_DMA1_CNDTR5 (STM32L4_DMA1_BASE+STM32L4_DMA_CNDTR5_OFFSET) +#define STM32L4_DMA1_CNDTR6 (STM32L4_DMA1_BASE+STM32L4_DMA_CNDTR6_OFFSET) +#define STM32L4_DMA1_CNDTR7 (STM32L4_DMA1_BASE+STM32L4_DMA_CNDTR7_OFFSET) + +#define STM32L4_DMA1_CPAR(n) (STM32L4_DMA1_BASE+STM32L4_DMA_CPAR_OFFSET(n)) +#define STM32L4_DMA1_CPAR1 (STM32L4_DMA1_BASE+STM32L4_DMA_CPAR1_OFFSET) +#define STM32L4_DMA1_CPAR2 (STM32L4_DMA1_BASE+STM32L4_DMA_CPAR2_OFFSET) +#define STM32L4_DMA1_CPAR3 (STM32L4_DMA1_BASE+STM32L4_DMA_CPAR3_OFFSET) +#define STM32L4_DMA1_CPAR4 (STM32L4_DMA1_BASE+STM32L4_DMA_CPAR4_OFFSET) +#define STM32L4_DMA1_CPAR5 (STM32L4_DMA1_BASE+STM32L4_DMA_CPAR5_OFFSET) +#define STM32L4_DMA1_CPAR6 (STM32L4_DMA1_BASE+STM32L4_DMA_CPAR6_OFFSET) +#define STM32L4_DMA1_CPAR7 (STM32L4_DMA1_BASE+STM32L4_DMA_CPAR7_OFFSET) + +#define STM32L4_DMA1_CMAR(n) (STM32L4_DMA1_BASE+STM32L4_DMA_CMAR_OFFSET(n)) +#define STM32L4_DMA1_CMAR1 (STM32L4_DMA1_BASE+STM32L4_DMA_CMAR1_OFFSET) +#define STM32L4_DMA1_CMAR2 (STM32L4_DMA1_BASE+STM32L4_DMA_CMAR2_OFFSET) +#define STM32L4_DMA1_CMAR3 (STM32L4_DMA1_BASE+STM32L4_DMA_CMAR3_OFFSET) +#define STM32L4_DMA1_CMAR4 (STM32L4_DMA1_BASE+STM32L4_DMA_CMAR4_OFFSET) +#define STM32L4_DMA1_CMAR5 (STM32L4_DMA1_BASE+STM32L4_DMA_CMAR5_OFFSET) +#define STM32L4_DMA1_CMAR6 (STM32L4_DMA1_BASE+STM32L4_DMA_CMAR6_OFFSET) +#define STM32L4_DMA1_CMAR7 (STM32L4_DMA1_BASE+STM32L4_DMA_CMAR7_OFFSET) + +#define STM32L4_DMA2_ISRC (STM32L4_DMA2_BASE+STM32L4_DMA_ISR_OFFSET) +#define STM32L4_DMA2_IFCR (STM32L4_DMA2_BASE+STM32L4_DMA_IFCR_OFFSET) + +#define STM32L4_DMA2_CCR(n) (STM32L4_DMA2_BASE+STM32L4_DMA_CCR_OFFSET(n)) +#define STM32L4_DMA2_CCR1 (STM32L4_DMA2_BASE+STM32L4_DMA_CCR1_OFFSET) +#define STM32L4_DMA2_CCR2 (STM32L4_DMA2_BASE+STM32L4_DMA_CCR2_OFFSET) +#define STM32L4_DMA2_CCR3 (STM32L4_DMA2_BASE+STM32L4_DMA_CCR3_OFFSET) +#define STM32L4_DMA2_CCR4 (STM32L4_DMA2_BASE+STM32L4_DMA_CCR4_OFFSET) +#define STM32L4_DMA2_CCR5 (STM32L4_DMA2_BASE+STM32L4_DMA_CCR5_OFFSET) +#define STM32L4_DMA2_CCR6 (STM32L4_DMA2_BASE+STM32L4_DMA_CCR6_OFFSET) +#define STM32L4_DMA2_CCR7 (STM32L4_DMA2_BASE+STM32L4_DMA_CCR7_OFFSET) + +#define STM32L4_DMA2_CNDTR(n) (STM32L4_DMA2_BASE+STM32L4_DMA_CNDTR_OFFSET(n)) +#define STM32L4_DMA2_CNDTR1 (STM32L4_DMA2_BASE+STM32L4_DMA_CNDTR1_OFFSET) +#define STM32L4_DMA2_CNDTR2 (STM32L4_DMA2_BASE+STM32L4_DMA_CNDTR2_OFFSET) +#define STM32L4_DMA2_CNDTR3 (STM32L4_DMA2_BASE+STM32L4_DMA_CNDTR3_OFFSET) +#define STM32L4_DMA2_CNDTR4 (STM32L4_DMA2_BASE+STM32L4_DMA_CNDTR4_OFFSET) +#define STM32L4_DMA2_CNDTR5 (STM32L4_DMA2_BASE+STM32L4_DMA_CNDTR5_OFFSET) +#define STM32L4_DMA2_CNDTR6 (STM32L4_DMA2_BASE+STM32L4_DMA_CNDTR6_OFFSET) +#define STM32L4_DMA2_CNDTR7 (STM32L4_DMA2_BASE+STM32L4_DMA_CNDTR7_OFFSET) + +#define STM32L4_DMA2_CPAR(n) (STM32L4_DMA2_BASE+STM32L4_DMA_CPAR_OFFSET(n)) +#define STM32L4_DMA2_CPAR1 (STM32L4_DMA2_BASE+STM32L4_DMA_CPAR1_OFFSET) +#define STM32L4_DMA2_CPAR2 (STM32L4_DMA2_BASE+STM32L4_DMA_CPAR2_OFFSET) +#define STM32L4_DMA2_CPAR3 (STM32L4_DMA2_BASE+STM32L4_DMA_CPAR3_OFFSET) +#define STM32L4_DMA2_CPAR4 (STM32L4_DMA2_BASE+STM32L4_DMA_CPAR4_OFFSET) +#define STM32L4_DMA2_CPAR5 (STM32L4_DMA2_BASE+STM32L4_DMA_CPAR5_OFFSET) +#define STM32L4_DMA2_CPAR6 (STM32L4_DMA2_BASE+STM32L4_DMA_CPAR6_OFFSET) +#define STM32L4_DMA2_CPAR7 (STM32L4_DMA2_BASE+STM32L4_DMA_CPAR7_OFFSET) + +#define STM32L4_DMA2_CMAR(n) (STM32L4_DMA2_BASE+STM32L4_DMA_CMAR_OFFSET(n)) +#define STM32L4_DMA2_CMAR1 (STM32L4_DMA2_BASE+STM32L4_DMA_CMAR1_OFFSET) +#define STM32L4_DMA2_CMAR2 (STM32L4_DMA2_BASE+STM32L4_DMA_CMAR2_OFFSET) +#define STM32L4_DMA2_CMAR3 (STM32L4_DMA2_BASE+STM32L4_DMA_CMAR3_OFFSET) +#define STM32L4_DMA2_CMAR4 (STM32L4_DMA2_BASE+STM32L4_DMA_CMAR4_OFFSET) +#define STM32L4_DMA2_CMAR5 (STM32L4_DMA2_BASE+STM32L4_DMA_CMAR5_OFFSET) +#define STM32L4_DMA2_CMAR6 (STM32L4_DMA2_BASE+STM32L4_DMA_CMAR6_OFFSET) +#define STM32L4_DMA2_CMAR7 (STM32L4_DMA2_BASE+STM32L4_DMA_CMAR7_OFFSET) + +/* Register Bitfield Definitions ****************************************************/ + +#define DMA_CHAN_SHIFT(n) ((n) << 2) +#define DMA_CHAN_MASK 0x0f +#define DMA_CHAN_GIF_BIT (1 << 0) /* Bit 0: Channel Global interrupt flag */ +#define DMA_CHAN_TCIF_BIT (1 << 1) /* Bit 1: Channel Transfer Complete flag */ +#define DMA_CHAN_HTIF_BIT (1 << 2) /* Bit 2: Channel Half Transfer flag */ +#define DMA_CHAN_TEIF_BIT (1 << 3) /* Bit 3: Channel Transfer Error flag */ + +/* DMA interrupt status register */ + +#define DMA_ISR_CHAN_SHIFT(n) DMA_CHAN_SHIFT(n) +#define DMA_ISR_CHAN_MASK(n) (DMA_CHAN_MASK << DMA_ISR_CHAN_SHIFT(n)) +#define DMA_ISR_CHAN1_SHIFT (0) /* Bits 3-0: DMA Channel 1 interrupt status */ +#define DMA_ISR_CHAN1_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN1_SHIFT) +#define DMA_ISR_CHAN2_SHIFT (4) /* Bits 7-4: DMA Channel 2 interrupt status */ +#define DMA_ISR_CHAN2_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN2_SHIFT) +#define DMA_ISR_CHAN3_SHIFT (8) /* Bits 11-8: DMA Channel 3 interrupt status */ +#define DMA_ISR_CHAN3_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN3_SHIFT) +#define DMA_ISR_CHAN4_SHIFT (12) /* Bits 15-12: DMA Channel 4 interrupt status */ +#define DMA_ISR_CHAN4_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN4_SHIFT) +#define DMA_ISR_CHAN5_SHIFT (16) /* Bits 19-16: DMA Channel 5 interrupt status */ +#define DMA_ISR_CHAN5_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN5_SHIFT) +#define DMA_ISR_CHAN6_SHIFT (20) /* Bits 23-20: DMA Channel 6 interrupt status */ +#define DMA_ISR_CHAN6_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN6_SHIFT) +#define DMA_ISR_CHAN7_SHIFT (24) /* Bits 27-24: DMA Channel 7 interrupt status */ +#define DMA_ISR_CHAN7_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN7_SHIFT) + +#define DMA_ISR_GIF(n) (DMA_CHAN_GIF_BIT << DMA_ISR_CHAN_SHIFT(n)) +#define DMA_ISR_TCIF(n) (DMA_CHAN_TCIF_BIT << DMA_ISR_CHAN_SHIFT(n)) +#define DMA_ISR_HTIF(n) (DMA_CHAN_HTIF_BIT << DMA_ISR_CHAN_SHIFT(n)) +#define DMA_ISR_TEIF(n) (DMA_CHAN_TEIF_BIT << DMA_ISR_CHAN_SHIFT(n)) + +/* DMA interrupt flag clear register */ + +#define DMA_IFCR_CHAN_SHIFT(n) DMA_CHAN_SHIFT(n) +#define DMA_IFCR_CHAN_MASK(n) (DMA_CHAN_MASK << DMA_IFCR_CHAN_SHIFT(n)) +#define DMA_IFCR_CHAN1_SHIFT (0) /* Bits 3-0: DMA Channel 1 interrupt flag clear */ +#define DMA_IFCR_CHAN1_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN1_SHIFT) +#define DMA_IFCR_CHAN2_SHIFT (4) /* Bits 7-4: DMA Channel 2 interrupt flag clear */ +#define DMA_IFCR_CHAN2_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN2_SHIFT) +#define DMA_IFCR_CHAN3_SHIFT (8) /* Bits 11-8: DMA Channel 3 interrupt flag clear */ +#define DMA_IFCR_CHAN3_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN3_SHIFT) +#define DMA_IFCR_CHAN4_SHIFT (12) /* Bits 15-12: DMA Channel 4 interrupt flag clear */ +#define DMA_IFCR_CHAN4_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN4_SHIFT) +#define DMA_IFCR_CHAN5_SHIFT (16) /* Bits 19-16: DMA Channel 5 interrupt flag clear */ +#define DMA_IFCR_CHAN5_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN5_SHIFT) +#define DMA_IFCR_CHAN6_SHIFT (20) /* Bits 23-20: DMA Channel 6 interrupt flag clear */ +#define DMA_IFCR_CHAN6_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN6_SHIFT) +#define DMA_IFCR_CHAN7_SHIFT (24) /* Bits 27-24: DMA Channel 7 interrupt flag clear */ +#define DMA_IFCR_CHAN7_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN7_SHIFT) +#define DMA_IFCR_ALLCHANNELS (0x0fffffff) + +#define DMA_IFCR_CGIF(n) (DMA_CHAN_GIF_BIT << DMA_IFCR_CHAN_SHIFT(n)) +#define DMA_IFCR_CTCIF(n) (DMA_CHAN_TCIF_BIT << DMA_IFCR_CHAN_SHIFT(n)) +#define DMA_IFCR_CHTIF(n) (DMA_CHAN_HTIF_BIT << DMA_IFCR_CHAN_SHIFT(n)) +#define DMA_IFCR_CTEIF(n) (DMA_CHAN_TEIF_BIT << DMA_IFCR_CHAN_SHIFT(n)) + +/* DMA channel configuration register */ + +#define DMA_CCR_EN (1 << 0) /* Bit 0: Channel enable */ +#define DMA_CCR_TCIE (1 << 1) /* Bit 1: Transfer complete interrupt enable */ +#define DMA_CCR_HTIE (1 << 2) /* Bit 2: Half Transfer interrupt enable */ +#define DMA_CCR_TEIE (1 << 3) /* Bit 3: Transfer error interrupt enable */ +#define DMA_CCR_DIR (1 << 4) /* Bit 4: Data transfer direction */ +#define DMA_CCR_CIRC (1 << 5) /* Bit 5: Circular mode */ +#define DMA_CCR_PINC (1 << 6) /* Bit 6: Peripheral increment mode */ +#define DMA_CCR_MINC (1 << 7) /* Bit 7: Memory increment mode */ +#define DMA_CCR_PSIZE_SHIFT (8) /* Bits 8-9: Peripheral size */ +#define DMA_CCR_PSIZE_MASK (3 << DMA_CCR_PSIZE_SHIFT) +# define DMA_CCR_PSIZE_8BITS (0 << DMA_CCR_PSIZE_SHIFT) /* 00: 8-bits */ +# define DMA_CCR_PSIZE_16BITS (1 << DMA_CCR_PSIZE_SHIFT) /* 01: 16-bits */ +# define DMA_CCR_PSIZE_32BITS (2 << DMA_CCR_PSIZE_SHIFT) /* 10: 32-bits */ +#define DMA_CCR_MSIZE_SHIFT (10) /* Bits 10-11: Memory size */ +#define DMA_CCR_MSIZE_MASK (3 << DMA_CCR_MSIZE_SHIFT) +# define DMA_CCR_MSIZE_8BITS (0 << DMA_CCR_MSIZE_SHIFT) /* 00: 8-bits */ +# define DMA_CCR_MSIZE_16BITS (1 << DMA_CCR_MSIZE_SHIFT) /* 01: 16-bits */ +# define DMA_CCR_MSIZE_32BITS (2 << DMA_CCR_MSIZE_SHIFT) /* 10: 32-bits */ +#define DMA_CCR_PL_SHIFT (12) /* Bits 12-13: Channel Priority level */ +#define DMA_CCR_PL_MASK (3 << DMA_CCR_PL_SHIFT) +# define DMA_CCR_PRILO (0 << DMA_CCR_PL_SHIFT) /* 00: Low */ +# define DMA_CCR_PRIMED (1 << DMA_CCR_PL_SHIFT) /* 01: Medium */ +# define DMA_CCR_PRIHI (2 << DMA_CCR_PL_SHIFT) /* 10: High */ +# define DMA_CCR_PRIVERYHI (3 << DMA_CCR_PL_SHIFT) /* 11: Very high */ +#define DMA_CCR_MEM2MEM (1 << 14) /* Bit 14: Memory to memory mode */ + +#define DMA_CCR_ALLINTS (DMA_CCR_TEIE|DMA_CCR_HTIE|DMA_CCR_TCIE) + +/* DMA channel number of data register */ + +#define DMA_CNDTR_NDT_SHIFT (0) /* Bits 15-0: Number of data to Transfer */ +#define DMA_CNDTR_NDT_MASK (0xffff << DMA_CNDTR_NDT_SHIFT) + +/* DMA Channel mapping. Each DMA channel has a mapping to one of several + * possible sources/sinks of data. The requests from peripherals assigned to a + * channel are multiplexed together before entering the DMA block. This means + * that only one request on a given channel can be enabled at once. + * + * Alternative DMA channel selections are provided with a numeric suffix like _1, + * _2, etc. Drivers, however, will use the pin selection without the numeric suffix. + * Additional definitions are required in the board.h file. + */ + +#define STM32L4_DMA1_CHAN1 (0) +#define STM32L4_DMA1_CHAN2 (1) +#define STM32L4_DMA1_CHAN3 (2) +#define STM32L4_DMA1_CHAN4 (3) +#define STM32L4_DMA1_CHAN5 (4) +#define STM32L4_DMA1_CHAN6 (5) +#define STM32L4_DMA1_CHAN7 (6) + +#define STM32L4_DMA2_CHAN1 (7) +#define STM32L4_DMA2_CHAN2 (8) +#define STM32L4_DMA2_CHAN3 (9) +#define STM32L4_DMA2_CHAN4 (10) +#define STM32L4_DMA2_CHAN5 (11) +#define STM32L4_DMA2_CHAN6 (12) +#define STM32L4_DMA2_CHAN7 (13) + +/* DMA Channel settings include a channel and an alternative function. + * Channel is in bits 0..7 + * Request number is in bits 8..15 + */ + +#define DMACHAN_SETTING(chan, req) ((((req) & 0xff) << 8) | ((chan) & 0xff)) +#define DMACHAN_SETTING_CHANNEL_MASK 0x00FF +#define DMACHAN_SETTING_CHANNEL_SHIFT (0) +#define DMACHAN_SETTING_FUNCTION_MASK 0xFF00 +#define DMACHAN_SETTING_FUNCTION_SHIFT (8) + +/* ADC */ + +#define DMACHAN_ADC1_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN1, 0) +#define DMACHAN_ADC1_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN3, 0) + +/* AES */ + +#define DMACHAN_AES_IN_1 DMACHAN_SETTING(STM32L4_DMA2_CHAN1, 6) +#define DMACHAN_AES_IN_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN5, 6) +#define DMACHAN_AES_OUT_1 DMACHAN_SETTING(STM32L4_DMA2_CHAN2, 6) +#define DMACHAN_AES_OUT_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN3, 6) + +/* DAC */ + +#define DMACHAN_DAC1_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN3, 6) +#define DMACHAN_DAC1_2 DMACHAN_SETTING(STM32L4_DMA1_CHAN4, 5) +#define DMACHAN_DAC1_3 DMACHAN_SETTING(STM32L4_DMA2_CHAN4, 3) + +/* DCMI */ + +#define DMACHAN_DCMI_1 DMACHAN_SETTING(STM32L4_DMA2_CHAN5, 4) +#define DMACHAN_DCMI_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN6, 0) + +/* DFSDM */ + +#define DMACHAN_DFSDM1_FLT0 DMACHAN_SETTING(STM32L4_DMA1_CHAN5, 0) +#define DMACHAN_DFSDM1_FLT1 DMACHAN_SETTING(STM32L4_DMA1_CHAN6, 0) + +/* I2C */ + +#define DMACHAN_I2C1_RX_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN7, 3) +#define DMACHAN_I2C1_RX_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN6, 5) +#define DMACHAN_I2C1_TX_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN6, 3) +#define DMACHAN_I2C1_TX_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN7, 5) + +#define DMACHAN_I2C2_RX DMACHAN_SETTING(STM32L4_DMA1_CHAN5, 3) +#define DMACHAN_I2C2_TX DMACHAN_SETTING(STM32L4_DMA1_CHAN4, 3) + +#define DMACHAN_I2C3_RX DMACHAN_SETTING(STM32L4_DMA1_CHAN3, 2) +#define DMACHAN_I2C3_TX DMACHAN_SETTING(STM32L4_DMA1_CHAN2, 3) + +#define DMACHAN_I2C4_RX DMACHAN_SETTING(STM32L4_DMA2_CHAN1, 0) +#define DMACHAN_I2C4_TX DMACHAN_SETTING(STM32L4_DMA2_CHAN2, 0) + +/* QUADSPI */ + +#define DMACHAN_QUADSPI_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN5, 5) +#define DMACHAN_QUADSPI_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN7, 3) + +/* SAI */ + +#define DMACHAN_SAI1_A_1 DMACHAN_SETTING(STM32L4_DMA2_CHAN1, 1) +#define DMACHAN_SAI1_A_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN6, 1) +#define DMACHAN_SAI1_B_1 DMACHAN_SETTING(STM32L4_DMA2_CHAN2, 1) +#define DMACHAN_SAI1_B_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN7, 1) + +#define DMACHAN_SAI2_A_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN6, 1) +#define DMACHAN_SAI2_A_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN3, 1) +#define DMACHAN_SAI2_B_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN7, 1) +#define DMACHAN_SAI2_B_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN4, 1) + +/* SDMMC */ + +#define DMACHAN_SDMMC_1 DMACHAN_SETTING(STM32L4_DMA2_CHAN4, 7) +#define DMACHAN_SDMMC_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN5, 7) + +/* SPI */ + +#define DMACHAN_SPI1_RX_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN2, 1) +#define DMACHAN_SPI1_RX_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN3, 4) +#define DMACHAN_SPI1_TX_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN3, 1) +#define DMACHAN_SPI1_TX_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN4, 4) + +#define DMACHAN_SPI2_RX DMACHAN_SETTING(STM32L4_DMA1_CHAN4, 1) +#define DMACHAN_SPI2_TX DMACHAN_SETTING(STM32L4_DMA1_CHAN5, 1) + +#define DMACHAN_SPI3_RX DMACHAN_SETTING(STM32L4_DMA2_CHAN1, 3) +#define DMACHAN_SPI3_TX DMACHAN_SETTING(STM32L4_DMA2_CHAN2, 3) + +/* SWPMI */ + +#define DMACHAN_SWPMI_RX DMACHAN_SETTING(STM32L4_DMA2_CHAN1, 4) +#define DMACHAN_SWPMI_TX DMACHAN_SETTING(STM32L4_DMA2_CHAN2, 4) + +/* TIM */ + +#define DMACHAN_TIM1_CH1 DMACHAN_SETTING(STM32L4_DMA1_CHAN2, 7) +#define DMACHAN_TIM1_CH2 DMACHAN_SETTING(STM32L4_DMA1_CHAN3, 7) +#define DMACHAN_TIM1_CH3 DMACHAN_SETTING(STM32L4_DMA1_CHAN7, 7) +#define DMACHAN_TIM1_CH4 DMACHAN_SETTING(STM32L4_DMA1_CHAN4, 7) +#define DMACHAN_TIM1_COM DMACHAN_SETTING(STM32L4_DMA1_CHAN4, 7) +#define DMACHAN_TIM1_TRIG DMACHAN_SETTING(STM32L4_DMA1_CHAN4, 7) +#define DMACHAN_TIM1_UP DMACHAN_SETTING(STM32L4_DMA1_CHAN6, 7) + +#define DMACHAN_TIM2_CH1 DMACHAN_SETTING(STM32L4_DMA1_CHAN5, 4) +#define DMACHAN_TIM2_CH2 DMACHAN_SETTING(STM32L4_DMA1_CHAN7, 4) +#define DMACHAN_TIM2_CH3 DMACHAN_SETTING(STM32L4_DMA1_CHAN1, 4) +#define DMACHAN_TIM2_CH4 DMACHAN_SETTING(STM32L4_DMA1_CHAN7, 4) +#define DMACHAN_TIM2_UP DMACHAN_SETTING(STM32L4_DMA1_CHAN2, 4) + +#define DMACHAN_TIM3_CH1 DMACHAN_SETTING(STM32L4_DMA1_CHAN6, 5) +#define DMACHAN_TIM3_CH3 DMACHAN_SETTING(STM32L4_DMA1_CHAN2, 5) +#define DMACHAN_TIM3_CH4 DMACHAN_SETTING(STM32L4_DMA1_CHAN3, 5) +#define DMACHAN_TIM3_TRIG DMACHAN_SETTING(STM32L4_DMA1_CHAN6, 5) +#define DMACHAN_TIM3_UP DMACHAN_SETTING(STM32L4_DMA1_CHAN3, 5) + +#define DMACHAN_TIM6_UP_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN3, 6) +#define DMACHAN_TIM6_UP_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN4, 3) + +#define DMACHAN_TIM7_UP_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN4, 5) +#define DMACHAN_TIM7_UP_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN5, 3) + +#define DMACHAN_TIM15_CH1 DMACHAN_SETTING(STM32L4_DMA1_CHAN5, 7) +#define DMACHAN_TIM15_COM DMACHAN_SETTING(STM32L4_DMA1_CHAN5, 7) +#define DMACHAN_TIM15_TRIG DMACHAN_SETTING(STM32L4_DMA1_CHAN5, 7) +#define DMACHAN_TIM15_UP DMACHAN_SETTING(STM32L4_DMA1_CHAN5, 7) + +#define DMACHAN_TIM16_CH1_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN3, 4) +#define DMACHAN_TIM16_CH1_2 DMACHAN_SETTING(STM32L4_DMA1_CHAN6, 4) +#define DMACHAN_TIM16_UP_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN3, 4) +#define DMACHAN_TIM16_UP_2 DMACHAN_SETTING(STM32L4_DMA1_CHAN6, 4) + +/* UART */ + +#define DMACHAN_USART1_RX_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN5, 2) +#define DMACHAN_USART1_RX_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN7, 2) +#define DMACHAN_USART1_TX_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN4, 2) +#define DMACHAN_USART1_TX_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN6, 2) + +#define DMACHAN_USART2_RX DMACHAN_SETTING(STM32L4_DMA1_CHAN6, 2) +#define DMACHAN_USART2_TX DMACHAN_SETTING(STM32L4_DMA1_CHAN7, 2) + +#define DMACHAN_USART3_RX DMACHAN_SETTING(STM32L4_DMA1_CHAN3, 1) +#define DMACHAN_USART3_TX DMACHAN_SETTING(STM32L4_DMA1_CHAN2, 2) + +#define DMACHAN_UART4_RX DMACHAN_SETTING(STM32L4_DMA2_CHAN5, 2) +#define DMACHAN_UART4_TX DMACHAN_SETTING(STM32L4_DMA2_CHAN3, 2) + +#define DMACHAN_LPUART_RX DMACHAN_SETTING(STM32L4_DMA2_CHAN7, 4) +#define DMACHAN_LPUART_TX DMACHAN_SETTING(STM32L4_DMA2_CHAN6, 4) + +#endif /* __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X3XX_DMA_H */ diff --git a/arch/arm/src/stm32l4/chip/stm32l4x3xx_pinmap.h b/arch/arm/src/stm32l4/chip/stm32l4x3xx_pinmap.h new file mode 100644 index 0000000000..5820f2a009 --- /dev/null +++ b/arch/arm/src/stm32l4/chip/stm32l4x3xx_pinmap.h @@ -0,0 +1,559 @@ +/************************************************************************************ + * arch/arm/src/stm32l4/chip/stm32l4x3xx_pinmap.h + * + * Copyright (C) 2015-2016 Sebastien Lorquet. All rights reserved. + * Authors: Sebastien Lorquet + * 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 __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X3XX_PINMAP_H +#define __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X3XX_PINMAP_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include "stm32l4_gpio.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Alternate Pin Functions. All members of the STM32L4xxx family share the same + * pin multiplexing (although they may differ in the pins physically available). + * + * Alternative pin selections are provided with a numeric suffix like _1, _2, etc. + * Drivers, however, will use the pin selection without the numeric suffix. + * Additional definitions are required in the board.h file. For example, if + * CAN1_RX connects vis PA11 on some board, then the following definitions should + * appear inthe board.h header file for that board: + * + * #define GPIO_CAN1_RX GPIO_CAN1_RX_1 + * + * The driver will then automatically configre PA11 as the CAN1 RX pin. + */ + +/* WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!! + * Additional effort is required to select specific GPIO options such as frequency, + * open-drain/push-pull, and pull-up/down! Just the basics are defined for most + * pins in this file. + */ + +/* ADC */ + +#define GPIO_ADC1_IN1 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN0) +#define GPIO_ADC1_IN2 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN1) +#define GPIO_ADC1_IN3 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN2) +#define GPIO_ADC1_IN4 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN3) +#define GPIO_ADC1_IN5 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN0) +#define GPIO_ADC1_IN6 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN1) +#define GPIO_ADC1_IN7 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN2) +#define GPIO_ADC1_IN8 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN3) +#define GPIO_ADC1_IN9 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN4) +#define GPIO_ADC1_IN10 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN5) +#define GPIO_ADC1_IN11 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN6) +#define GPIO_ADC1_IN12 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN7) +#define GPIO_ADC1_IN13 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN4) +#define GPIO_ADC1_IN14 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN5) +#define GPIO_ADC1_IN15 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN0) +#define GPIO_ADC1_IN16 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN1) + +/* CAN */ + +#define GPIO_CAN1_RX_1 (GPIO_ALT|GPIO_AF9 |GPIO_PORTA|GPIO_PIN11) +#define GPIO_CAN1_RX_2 (GPIO_ALT|GPIO_AF3 |GPIO_PORTB|GPIO_PIN5) +#define GPIO_CAN1_RX_3 (GPIO_ALT|GPIO_AF9 |GPIO_PORTB|GPIO_PIN8) +#define GPIO_CAN1_RX_4 (GPIO_ALT|GPIO_AF10 |GPIO_PORTB|GPIO_PIN12) +#define GPIO_CAN1_RX_5 (GPIO_ALT|GPIO_AF9 |GPIO_PORTD|GPIO_PIN0) +#define GPIO_CAN1_TX_1 (GPIO_ALT|GPIO_AF9 |GPIO_PORTA|GPIO_PIN12) +#define GPIO_CAN1_TX_2 (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN6) +#define GPIO_CAN1_TX_3 (GPIO_ALT|GPIO_AF9 |GPIO_PORTB|GPIO_PIN9) +#define GPIO_CAN1_TX_4 (GPIO_ALT|GPIO_AF10 |GPIO_PORTB|GPIO_PIN13) +#define GPIO_CAN1_TX_5 (GPIO_ALT|GPIO_AF9 |GPIO_PORTD|GPIO_PIN1) + +/* Clocks outputs */ + +#define GPIO_MCO (GPIO_ALT|GPIO_AF0 |GPIO_PORTA|GPIO_PIN8) + +/* Comparators */ + +#define GPIO_COMP1_INM_1 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN0) +#define GPIO_COMP1_INM_2 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN1) +#define GPIO_COMP1_INM_3 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN4) +#define GPIO_COMP1_INP_1 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN1) +#define GPIO_COMP1_INP_2 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN2) +#define GPIO_COMP1_INP_3 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN5) +#define GPIO_COMP1_OUT_1 (GPIO_ALT|GPIO_AF6|GPIO_PORTA|GPIO_PIN6) +#define GPIO_COMP1_OUT_2 (GPIO_ALT|GPIO_AF6|GPIO_PORTA|GPIO_PIN11) +#define GPIO_COMP1_OUT_3 (GPIO_ALT|GPIO_AF12|GPIO_PORTA|GPIO_PIN0) +#define GPIO_COMP1_OUT_4 (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN0) +#define GPIO_COMP1_OUT_5 (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN10) + +#define GPIO_COMP2_INM_1 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN2) +#define GPIO_COMP2_INM_2 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN3) +#define GPIO_COMP2_INM_3 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN7) +#define GPIO_COMP2_INP_1 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN3) +#define GPIO_COMP2_INP_2 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN4) +#define GPIO_COMP2_INP_3 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN6) +#define GPIO_COMP2_OUT_1 (GPIO_ALT|GPIO_AF12|GPIO_PORTA|GPIO_PIN2) +#define GPIO_COMP2_OUT_2 (GPIO_ALT|GPIO_AF12|GPIO_PORTA|GPIO_PIN7) +#define GPIO_COMP2_OUT_3 (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN5) +#define GPIO_COMP2_OUT_4 (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN11) + +/* DAC */ + +#define GPIO_DAC1_OUT (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN4) + +/* Digital Filter for Sigma-Delta Modulators (DFSDM) */ + +#define GPIO_DFSDM_DATIN0_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTB|GPIO_PIN1) +#define GPIO_DFSDM_DATIN0_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTD|GPIO_PIN3) +#define GPIO_DFSDM_DATIN1_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTB|GPIO_PIN12) +#define GPIO_DFSDM_DATIN1_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTD|GPIO_PIN6) +#define GPIO_DFSDM_DATIN2_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTB|GPIO_PIN14) +#define GPIO_DFSDM_DATIN2_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTE|GPIO_PIN7) +#define GPIO_DFSDM_DATIN3_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTC|GPIO_PIN7) +#define GPIO_DFSDM_DATIN3_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTE|GPIO_PIN4) + +#define GPIO_DFSDM_CKIN0_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTB|GPIO_PIN2) +#define GPIO_DFSDM_CKIN0_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTD|GPIO_PIN4) +#define GPIO_DFSDM_CKIN1_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTB|GPIO_PIN13) +#define GPIO_DFSDM_CKIN1_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTD|GPIO_PIN7) +#define GPIO_DFSDM_CKIN2_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTB|GPIO_PIN15) +#define GPIO_DFSDM_CKIN2_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTE|GPIO_PIN8) +#define GPIO_DFSDM_CKIN3_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTC|GPIO_PIN6) +#define GPIO_DFSDM_CKIN3_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTE|GPIO_PIN5) + +#define GPIO_DFSDM_CKOUT_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTA|GPIO_PIN5) +#define GPIO_DFSDM_CKOUT_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTC|GPIO_PIN2) +#define GPIO_DFSDM_CKOUT_3 (GPIO_ALT|GPIO_AF6 |GPIO_PORTE|GPIO_PIN9) + +/* I2C */ + +#define GPIO_I2C1_SDA_1 (GPIO_ALT|GPIO_AF4 |GPIO_PORTB|GPIO_PIN7) +#define GPIO_I2C1_SDA_2 (GPIO_ALT|GPIO_AF4 |GPIO_PORTB|GPIO_PIN9) +#define GPIO_I2C1_SCL_1 (GPIO_ALT|GPIO_AF4 |GPIO_PORTB|GPIO_PIN6) +#define GPIO_I2C1_SCL_2 (GPIO_ALT|GPIO_AF4 |GPIO_PORTB|GPIO_PIN8) +#define GPIO_I2C1_SMBA_1 (GPIO_ALT|GPIO_AF4 |GPIO_PORTA|GPIO_PIN1) +#define GPIO_I2C1_SMBA_2 (GPIO_ALT|GPIO_AF4 |GPIO_PORTA|GPIO_PIN14) +#define GPIO_I2C1_SMBA_3 (GPIO_ALT|GPIO_AF4 |GPIO_PORTB|GPIO_PIN5) + +#define GPIO_I2C2_SDA_1 (GPIO_ALT|GPIO_AF4 |GPIO_PORTB|GPIO_PIN11) +#define GPIO_I2C2_SDA_2 (GPIO_ALT|GPIO_AF4 |GPIO_PORTB|GPIO_PIN14) +#define GPIO_I2C2_SCL_1 (GPIO_ALT|GPIO_AF4 |GPIO_PORTB|GPIO_PIN10) +#define GPIO_I2C2_SCL_2 (GPIO_ALT|GPIO_AF4 |GPIO_PORTB|GPIO_PIN13) +#define GPIO_I2C2_SMBA_1 (GPIO_ALT|GPIO_AF4 |GPIO_PORTB|GPIO_PIN12) + +#define GPIO_I2C3_SDA_1 (GPIO_ALT|GPIO_AF4 |GPIO_PORTB|GPIO_PIN4) +#define GPIO_I2C3_SDA_2 (GPIO_ALT|GPIO_AF4 |GPIO_PORTC|GPIO_PIN1) +#define GPIO_I2C3_SCL_1 (GPIO_ALT|GPIO_AF4 |GPIO_PORTA|GPIO_PIN7) +#define GPIO_I2C3_SCL_2 (GPIO_ALT|GPIO_AF4 |GPIO_PORTC|GPIO_PIN0) +#define GPIO_I2C3_SMBA_1 (GPIO_ALT|GPIO_AF4 |GPIO_PORTB|GPIO_PIN2) + +#define GPIO_I2C4_SDA_1 (GPIO_ALT|GPIO_AF5 |GPIO_PORTB|GPIO_PIN7) +#define GPIO_I2C4_SDA_2 (GPIO_ALT|GPIO_AF3 |GPIO_PORTB|GPIO_PIN11) +#define GPIO_I2C4_SDA_3 (GPIO_ALT|GPIO_AF2 |GPIO_PORTC|GPIO_PIN1) +#define GPIO_I2C4_SDA_4 (GPIO_ALT|GPIO_AF4 |GPIO_PORTD|GPIO_PIN13) +#define GPIO_I2C4_SCL_1 (GPIO_ALT|GPIO_AF5 |GPIO_PORTB|GPIO_PIN6) +#define GPIO_I2C4_SCL_2 (GPIO_ALT|GPIO_AF3 |GPIO_PORTB|GPIO_PIN10) +#define GPIO_I2C4_SCL_3 (GPIO_ALT|GPIO_AF2 |GPIO_PORTC|GPIO_PIN0) +#define GPIO_I2C4_SCL_4 (GPIO_ALT|GPIO_AF4 |GPIO_PORTD|GPIO_PIN12) +#define GPIO_I2C4_SMBA_1 (GPIO_ALT|GPIO_AF5 |GPIO_PORTA|GPIO_PIN14) +#define GPIO_I2C4_SMBA_2 (GPIO_ALT|GPIO_AF4 |GPIO_PORTD|GPIO_PIN11) + +/* JTAG */ + +#define GPIO_JTCK_SWCLK (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN14) +#define GPIO_JTDI (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN15) +#define GPIO_JTDO (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN3) +#define GPIO_JTMS_SWDAT (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN13) +#define GPIO_JTRST (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN4) + +/* QUADSPI */ + +#define GPIO_QSPI_NCS_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN11) +#define GPIO_QSPI_NCS_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTE|GPIO_PIN11) +#define GPIO_QSPI_CLK_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN10) +#define GPIO_QSPI_CLK_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTE|GPIO_PIN10) +#define GPIO_QSPI_BK1_IO0_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN1) +#define GPIO_QSPI_BK1_IO0_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTE|GPIO_PIN12) +#define GPIO_QSPI_BK1_IO1_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN0) +#define GPIO_QSPI_BK1_IO1_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTE|GPIO_PIN13) +#define GPIO_QSPI_BK1_IO2_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTA|GPIO_PIN7) +#define GPIO_QSPI_BK1_IO2_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTE|GPIO_PIN14) +#define GPIO_QSPI_BK1_IO3_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTA|GPIO_PIN6) +#define GPIO_QSPI_BK1_IO3_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTE|GPIO_PIN15) + +/* RTC */ + +#define GPIO_RTC_OUT (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN2) +#define GPIO_RTC_REFIN (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN15) + +/* SAI */ + +#define GPIO_SAI1_EXTCLK (GPIO_ALT|GPIO_AF13|GPIO_PORTA|GPIO_PIN0) + +#define GPIO_SAI1_FS_A_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN9) +#define GPIO_SAI1_FS_A_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN4) +#define GPIO_SAI1_SCK_A_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN10) +#define GPIO_SAI1_SCK_A_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN5) +#define GPIO_SAI1_SD_A_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTC|GPIO_PIN3) +#define GPIO_SAI1_SD_A_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTD|GPIO_PIN6) +#define GPIO_SAI1_SD_A_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN6) +#define GPIO_SAI1_MCLK_A_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN8) +#define GPIO_SAI1_MCLK_A_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN2) + +#define GPIO_SAI1_FS_B_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTA|GPIO_PIN4) +#define GPIO_SAI1_FS_B_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN6) +#define GPIO_SAI1_FS_B_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN9) +#define GPIO_SAI1_SCK_B_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN3) +#define GPIO_SAI1_SCK_B_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN8) +#define GPIO_SAI1_SD_B_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN5) +#define GPIO_SAI1_SD_B_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN3) +#define GPIO_SAI1_SD_B_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN7) +#define GPIO_SAI1_MCLK_B_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN4) +#define GPIO_SAI1_MCLK_B_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN10) + +/* SDIO */ + +#define GPIO_SDMMC1_CK (GPIO_ALT|GPIO_AF12|GPIO_PORTC|GPIO_PIN12) +#define GPIO_SDMMC1_CMD (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN2) +#define GPIO_SDMMC1_D0 (GPIO_ALT|GPIO_AF12|GPIO_PORTC|GPIO_PIN8) +#define GPIO_SDMMC1_D1 (GPIO_ALT|GPIO_AF12|GPIO_PORTC|GPIO_PIN9) +#define GPIO_SDMMC1_D2 (GPIO_ALT|GPIO_AF12|GPIO_PORTC|GPIO_PIN10) +#define GPIO_SDMMC1_D3 (GPIO_ALT|GPIO_AF12|GPIO_PORTC|GPIO_PIN11) +#define GPIO_SDMMC1_D4 (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN8) +#define GPIO_SDMMC1_D5 (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN9) +#define GPIO_SDMMC1_D6 (GPIO_ALT|GPIO_AF12|GPIO_PORTC|GPIO_PIN6) +#define GPIO_SDMMC1_D7 (GPIO_ALT|GPIO_AF12|GPIO_PORTC|GPIO_PIN7) + +/* Single Wire Protocol Interface */ + +#define GPIO_SWPMI1_IO (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN12) +#define GPIO_SWPMI1_TX (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN13) +#define GPIO_SWPMI1_RX (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN14) +#define GPIO_SWPMI1_SUSPEND (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN15) + +/* SPI */ + +#define GPIO_SPI1_NSS_1 (GPIO_ALT|GPIO_AF5 |GPIO_PORTA|GPIO_PIN4) +#define GPIO_SPI1_NSS_2 (GPIO_ALT|GPIO_AF5 |GPIO_PORTA|GPIO_PIN15) +#define GPIO_SPI1_NSS_3 (GPIO_ALT|GPIO_AF5 |GPIO_PORTB|GPIO_PIN0) +#define GPIO_SPI1_NSS_4 (GPIO_ALT|GPIO_AF5 |GPIO_PORTE|GPIO_PIN12) +#define GPIO_SPI1_SCK_1 (GPIO_ALT|GPIO_AF5 |GPIO_PORTA|GPIO_PIN1) +#define GPIO_SPI1_SCK_2 (GPIO_ALT|GPIO_AF5 |GPIO_PORTA|GPIO_PIN5) +#define GPIO_SPI1_SCK_3 (GPIO_ALT|GPIO_AF5 |GPIO_PORTB|GPIO_PIN3) +#define GPIO_SPI1_SCK_4 (GPIO_ALT|GPIO_AF5 |GPIO_PORTE|GPIO_PIN13) +#define GPIO_SPI1_MOSI_1 (GPIO_ALT|GPIO_AF5 |GPIO_PORTA|GPIO_PIN7) +#define GPIO_SPI1_MOSI_2 (GPIO_ALT|GPIO_AF5 |GPIO_PORTA|GPIO_PIN12) +#define GPIO_SPI1_MOSI_3 (GPIO_ALT|GPIO_AF5 |GPIO_PORTB|GPIO_PIN5) +#define GPIO_SPI1_MOSI_4 (GPIO_ALT|GPIO_AF5 |GPIO_PORTE|GPIO_PIN15) +#define GPIO_SPI1_MISO_1 (GPIO_ALT|GPIO_AF5 |GPIO_PORTA|GPIO_PIN6) +#define GPIO_SPI1_MISO_2 (GPIO_ALT|GPIO_AF5 |GPIO_PORTA|GPIO_PIN11) +#define GPIO_SPI1_MISO_3 (GPIO_ALT|GPIO_AF5 |GPIO_PORTB|GPIO_PIN4) +#define GPIO_SPI1_MISO_4 (GPIO_ALT|GPIO_AF5 |GPIO_PORTE|GPIO_PIN14) + +#define GPIO_SPI2_NSS_1 (GPIO_ALT|GPIO_AF5 |GPIO_PORTB|GPIO_PIN9) +#define GPIO_SPI2_NSS_2 (GPIO_ALT|GPIO_AF5 |GPIO_PORTB|GPIO_PIN12) +#define GPIO_SPI2_NSS_3 (GPIO_ALT|GPIO_AF5 |GPIO_PORTD|GPIO_PIN0) +#define GPIO_SPI2_SCK_1 (GPIO_ALT|GPIO_AF5 |GPIO_PORTB|GPIO_PIN10) +#define GPIO_SPI2_SCK_2 (GPIO_ALT|GPIO_AF5 |GPIO_PORTB|GPIO_PIN13) +#define GPIO_SPI2_SCK_3 (GPIO_ALT|GPIO_AF5 |GPIO_PORTD|GPIO_PIN1) +#define GPIO_SPI2_MOSI_1 (GPIO_ALT|GPIO_AF5 |GPIO_PORTB|GPIO_PIN15) +#define GPIO_SPI2_MOSI_2 (GPIO_ALT|GPIO_AF5 |GPIO_PORTC|GPIO_PIN3) +#define GPIO_SPI2_MOSI_3 (GPIO_ALT|GPIO_AF5 |GPIO_PORTD|GPIO_PIN4) +#define GPIO_SPI2_MISO_1 (GPIO_ALT|GPIO_AF5 |GPIO_PORTB|GPIO_PIN14) +#define GPIO_SPI2_MISO_2 (GPIO_ALT|GPIO_AF5 |GPIO_PORTC|GPIO_PIN2) +#define GPIO_SPI2_MISO_3 (GPIO_ALT|GPIO_AF5 |GPIO_PORTD|GPIO_PIN3) + +#define GPIO_SPI3_NSS_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTA|GPIO_PIN4) +#define GPIO_SPI3_NSS_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTA|GPIO_PIN15) +#define GPIO_SPI3_SCK_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTB|GPIO_PIN3) +#define GPIO_SPI3_SCK_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTC|GPIO_PIN10) +#define GPIO_SPI3_MOSI_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTB|GPIO_PIN5) +#define GPIO_SPI3_MOSI_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTC|GPIO_PIN12) +#define GPIO_SPI3_MISO_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTB|GPIO_PIN4) +#define GPIO_SPI3_MISO_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTC|GPIO_PIN11) + +/* Timers */ + +#define GPIO_TIM1_CH1IN_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN8) +#define GPIO_TIM1_CH1IN_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN9) +#define GPIO_TIM1_CH1OUT_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN8) +#define GPIO_TIM1_CH1OUT_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN9) +#define GPIO_TIM1_CH2IN_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN9) +#define GPIO_TIM1_CH2IN_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN11) +#define GPIO_TIM1_CH2OUT_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN9) +#define GPIO_TIM1_CH2OUT_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN11) +#define GPIO_TIM1_CH3IN_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN10) +#define GPIO_TIM1_CH3IN_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN13) +#define GPIO_TIM1_CH3OUT_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN10) +#define GPIO_TIM1_CH3OUT_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN13) +#define GPIO_TIM1_CH4IN_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN11) +#define GPIO_TIM1_CH4IN_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN14) +#define GPIO_TIM1_CH4OUT_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN11) +#define GPIO_TIM1_CH4OUT_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN14) +#define GPIO_TIM1_CH1N_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN7) +#define GPIO_TIM1_CH1N_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN13) +#define GPIO_TIM1_CH1N_3 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN8) +#define GPIO_TIM1_CH2N_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN0) +#define GPIO_TIM1_CH2N_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN14) +#define GPIO_TIM1_CH2N_3 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN10) +#define GPIO_TIM1_CH3N_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN1) +#define GPIO_TIM1_CH3N_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN15) +#define GPIO_TIM1_CH3N_3 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN12) +#define GPIO_TIM1_BKIN_1 (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN6) +#define GPIO_TIM1_BKIN_2 (GPIO_ALT|GPIO_AF1 |GPIO_PORTB|GPIO_PIN12) +#define GPIO_TIM1_BKIN_3 (GPIO_ALT|GPIO_AF1 |GPIO_PORTE|GPIO_PIN15) +#define GPIO_TIM1_BKIN_COMP1 (GPIO_ALT|GPIO_AF3 |GPIO_PORTE|GPIO_PIN15) +#define GPIO_TIM1_BKIN_COMP2_1 (GPIO_ALT|GPIO_AF12|GPIO_PORTA|GPIO_PIN6) +#define GPIO_TIM1_BKIN_COMP2_2 (GPIO_ALT|GPIO_AF3 |GPIO_PORTB|GPIO_PIN12) +#define GPIO_TIM1_BKIN2 (GPIO_ALT|GPIO_AF2 |GPIO_PORTA|GPIO_PIN11) +#define GPIO_TIM1_BKIN2_COMP1 (GPIO_ALT|GPIO_AF12|GPIO_PORTA|GPIO_PIN11) +#define GPIO_TIM1_BKIN2_COMP2 (GPIO_ALT|GPIO_AF3 |GPIO_PORTE|GPIO_PIN14) +#define GPIO_TIM1_ETR_1 (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN12) +#define GPIO_TIM1_ETR_2 (GPIO_ALT|GPIO_AF1 |GPIO_PORTE|GPIO_PIN7) + +#define GPIO_TIM2_CH1IN_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN0) +#define GPIO_TIM2_CH1IN_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN5) +#define GPIO_TIM2_CH1IN_3 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN15) +#define GPIO_TIM2_CH1OUT_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN0) +#define GPIO_TIM2_CH1OUT_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN5) +#define GPIO_TIM2_CH1OUT_3 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN15) +#define GPIO_TIM2_CH2IN_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN1) +#define GPIO_TIM2_CH2IN_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN3) +#define GPIO_TIM2_CH2OUT_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN1) +#define GPIO_TIM2_CH2OUT_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN3) +#define GPIO_TIM2_CH3IN_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN2) +#define GPIO_TIM2_CH3IN_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN10) +#define GPIO_TIM2_CH3OUT_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN2) +#define GPIO_TIM2_CH3OUT_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN10) +#define GPIO_TIM2_CH4IN_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN3) +#define GPIO_TIM2_CH4IN_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN11) +#define GPIO_TIM2_CH4OUT_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN3) +#define GPIO_TIM2_CH4OUT_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN11) +#define GPIO_TIM2_BKIN (GPIO_ALT|GPIO_AF2 |GPIO_PORTE|GPIO_PIN14) +#define GPIO_TIM2_ETR_1 (GPIO_ALT|GPIO_AF14|GPIO_PORTA|GPIO_PIN0) +#define GPIO_TIM2_ETR_2 (GPIO_ALT|GPIO_AF2 |GPIO_PORTA|GPIO_PIN5) +#define GPIO_TIM2_ETR_3 (GPIO_ALT|GPIO_AF2 |GPIO_PORTA|GPIO_PIN15) + +#define GPIO_TIM3_CH1IN_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN6) +#define GPIO_TIM3_CH1IN_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN4) +#define GPIO_TIM3_CH1IN_3 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN6) +#define GPIO_TIM3_CH1IN_4 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN3) +#define GPIO_TIM3_CH1OUT_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN6) +#define GPIO_TIM3_CH1OUT_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN4) +#define GPIO_TIM3_CH1OUT_3 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN6) +#define GPIO_TIM3_CH1OUT_4 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN3) +#define GPIO_TIM3_CH2IN_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN7) +#define GPIO_TIM3_CH2IN_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN5) +#define GPIO_TIM3_CH2IN_3 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN7) +#define GPIO_TIM3_CH2IN_4 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN4) +#define GPIO_TIM3_CH2OUT_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN7) +#define GPIO_TIM3_CH2OUT_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN5) +#define GPIO_TIM3_CH2OUT_3 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN7) +#define GPIO_TIM3_CH2OUT_4 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN4) +#define GPIO_TIM3_CH3IN_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN0) +#define GPIO_TIM3_CH3IN_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN8) +#define GPIO_TIM3_CH3IN_3 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN5) +#define GPIO_TIM3_CH3OUT_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN0) +#define GPIO_TIM3_CH3OUT_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8) +#define GPIO_TIM3_CH3OUT_3 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN5) +#define GPIO_TIM3_CH4IN_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN1) +#define GPIO_TIM3_CH4IN_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN9) +#define GPIO_TIM3_CH4IN_3 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN6) +#define GPIO_TIM3_CH4OUT_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN1) +#define GPIO_TIM3_CH4OUT_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN9) +#define GPIO_TIM3_CH4OUT_3 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN6) +#define GPIO_TIM3_ETR_1 (GPIO_ALT|GPIO_AF2 |GPIO_PORTD|GPIO_PIN2) +#define GPIO_TIM3_ETR_2 (GPIO_ALT|GPIO_AF2 |GPIO_PORTE|GPIO_PIN2) + +#define GPIO_TIM15_CH1IN_1 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN2) +#define GPIO_TIM15_CH1IN_2 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN14) +#define GPIO_TIM15_CH1OUT_1 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN2) +#define GPIO_TIM15_CH1OUT_2 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN14) +#define GPIO_TIM15_CH2IN_1 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN3) +#define GPIO_TIM15_CH2IN_2 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN15) +#define GPIO_TIM15_CH2OUT_1 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN3) +#define GPIO_TIM15_CH2OUT_2 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN15) +#define GPIO_TIM15_CH1N_1 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN1) +#define GPIO_TIM15_CH1N_2 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN13) +#define GPIO_TIM15_BKIN_1 (GPIO_ALT|GPIO_AF14|GPIO_PORTA|GPIO_PIN9) +#define GPIO_TIM15_BKIN_2 (GPIO_ALT|GPIO_AF14|GPIO_PORTB|GPIO_PIN12) + +#define GPIO_TIM16_CH1IN_1 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN6) +#define GPIO_TIM16_CH1IN_2 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN8) +#define GPIO_TIM16_CH1IN_3 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN0) +#define GPIO_TIM16_CH1OUT_1 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN6) +#define GPIO_TIM16_CH1OUT_2 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN8) +#define GPIO_TIM16_CH1OUT_3 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN0) +#define GPIO_TIM16_CH1N (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN6) +#define GPIO_TIM16_BKIN (GPIO_ALT|GPIO_AF14|GPIO_PORTB|GPIO_PIN5) + +#define GPIO_LPTIM1_IN1_1 (GPIO_ALT|GPIO_AF1 |GPIO_PORTB|GPIO_PIN5) +#define GPIO_LPTIM1_IN1_2 (GPIO_ALT|GPIO_AF1 |GPIO_PORTC|GPIO_PIN0) +#define GPIO_LPTIM1_IN2_1 (GPIO_ALT|GPIO_AF1 |GPIO_PORTB|GPIO_PIN7) +#define GPIO_LPTIM1_IN2_2 (GPIO_ALT|GPIO_AF1 |GPIO_PORTC|GPIO_PIN2) +#define GPIO_LPTIM1_OUT_1 (GPIO_ALT|GPIO_AF1 |GPIO_PORTB|GPIO_PIN2) +#define GPIO_LPTIM1_OUT_2 (GPIO_ALT|GPIO_AF1 |GPIO_PORTC|GPIO_PIN1) +#define GPIO_LPTIM1_ETR_1 (GPIO_ALT|GPIO_AF1 |GPIO_PORTB|GPIO_PIN6) +#define GPIO_LPTIM1_ETR_2 (GPIO_ALT|GPIO_AF1 |GPIO_PORTC|GPIO_PIN3) + +#define GPIO_LPTIM2_IN1_1 (GPIO_ALT|GPIO_AF14|GPIO_PORTB|GPIO_PIN1) +#define GPIO_LPTIM2_IN1_2 (GPIO_ALT|GPIO_AF14|GPIO_PORTC|GPIO_PIN0) +#define GPIO_LPTIM2_IN1_3 (GPIO_ALT|GPIO_AF14|GPIO_PORTD|GPIO_PIN12) +#define GPIO_LPTIM2_OUT_1 (GPIO_ALT|GPIO_AF14|GPIO_PORTA|GPIO_PIN4) +#define GPIO_LPTIM2_OUT_2 (GPIO_ALT|GPIO_AF14|GPIO_PORTA|GPIO_PIN8) +#define GPIO_LPTIM2_OUT_3 (GPIO_ALT|GPIO_AF14|GPIO_PORTD|GPIO_PIN13) +#define GPIO_LPTIM2_ETR_1 (GPIO_ALT|GPIO_AF14|GPIO_PORTA|GPIO_PIN5) +#define GPIO_LPTIM2_ETR_2 (GPIO_ALT|GPIO_AF14|GPIO_PORTC|GPIO_PIN3) +#define GPIO_LPTIM2_ETR_3 (GPIO_ALT|GPIO_AF14|GPIO_PORTD|GPIO_PIN11) + +/* Touch Screen Controller */ + +#define GPIO_TSC_SYNC (GPIO_ALT|GPIO_AF9 |GPIO_PORTD|GPIO_PIN2) + +#define GPIO_TSC_G1_IO1 (GPIO_ALT|GPIO_AF9 |GPIO_PORTB|GPIO_PIN12) +#define GPIO_TSC_G1_IO2 (GPIO_ALT|GPIO_AF9 |GPIO_PORTB|GPIO_PIN13) +#define GPIO_TSC_G1_IO3 (GPIO_ALT|GPIO_AF9 |GPIO_PORTB|GPIO_PIN14) +#define GPIO_TSC_G1_IO4 (GPIO_ALT|GPIO_AF9 |GPIO_PORTB|GPIO_PIN15) + +#define GPIO_TSC_G2_IO1 (GPIO_ALT|GPIO_AF9 |GPIO_PORTB|GPIO_PIN4) +#define GPIO_TSC_G2_IO2 (GPIO_ALT|GPIO_AF9 |GPIO_PORTB|GPIO_PIN5) +#define GPIO_TSC_G2_IO3 (GPIO_ALT|GPIO_AF9 |GPIO_PORTB|GPIO_PIN6) +#define GPIO_TSC_G2_IO4 (GPIO_ALT|GPIO_AF9 |GPIO_PORTB|GPIO_PIN7) + +#define GPIO_TSC_G3_IO1 (GPIO_ALT|GPIO_AF9 |GPIO_PORTA|GPIO_PIN15) +#define GPIO_TSC_G3_IO2 (GPIO_ALT|GPIO_AF9 |GPIO_PORTC|GPIO_PIN10) +#define GPIO_TSC_G3_IO3 (GPIO_ALT|GPIO_AF9 |GPIO_PORTC|GPIO_PIN11) +#define GPIO_TSC_G3_IO4 (GPIO_ALT|GPIO_AF9 |GPIO_PORTC|GPIO_PIN12) + +#define GPIO_TSC_G4_IO1 (GPIO_ALT|GPIO_AF9 |GPIO_PORTC|GPIO_PIN6) +#define GPIO_TSC_G4_IO2 (GPIO_ALT|GPIO_AF9 |GPIO_PORTC|GPIO_PIN7) +#define GPIO_TSC_G4_IO3 (GPIO_ALT|GPIO_AF9 |GPIO_PORTC|GPIO_PIN8) +#define GPIO_TSC_G4_IO4 (GPIO_ALT|GPIO_AF9 |GPIO_PORTC|GPIO_PIN9) + +#define GPIO_TSC_G5_IO1 (GPIO_ALT|GPIO_AF9 |GPIO_PORTE|GPIO_PIN10) +#define GPIO_TSC_G5_IO2 (GPIO_ALT|GPIO_AF9 |GPIO_PORTE|GPIO_PIN11) +#define GPIO_TSC_G5_IO3 (GPIO_ALT|GPIO_AF9 |GPIO_PORTE|GPIO_PIN12) +#define GPIO_TSC_G5_IO4 (GPIO_ALT|GPIO_AF9 |GPIO_PORTE|GPIO_PIN13) + +#define GPIO_TSC_G6_IO1 (GPIO_ALT|GPIO_AF9 |GPIO_PORTD|GPIO_PIN10) +#define GPIO_TSC_G6_IO2 (GPIO_ALT|GPIO_AF9 |GPIO_PORTD|GPIO_PIN11) +#define GPIO_TSC_G6_IO3 (GPIO_ALT|GPIO_AF9 |GPIO_PORTD|GPIO_PIN12) +#define GPIO_TSC_G6_IO4 (GPIO_ALT|GPIO_AF9 |GPIO_PORTD|GPIO_PIN13) + +#define GPIO_TSC_G7_IO1 (GPIO_ALT|GPIO_AF9 |GPIO_PORTE|GPIO_PIN2) +#define GPIO_TSC_G7_IO2 (GPIO_ALT|GPIO_AF9 |GPIO_PORTE|GPIO_PIN3) +#define GPIO_TSC_G7_IO3 (GPIO_ALT|GPIO_AF9 |GPIO_PORTE|GPIO_PIN4) +#define GPIO_TSC_G7_IO4 (GPIO_ALT|GPIO_AF9 |GPIO_PORTE|GPIO_PIN5) + +/* IR interface (with timers 16 and 17) */ + +#define GPIO_IR_OUT_1 (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN13) +#define GPIO_IR_OUT_2 (GPIO_ALT|GPIO_AF1 |GPIO_PORTB|GPIO_PIN9) + +/* Trace */ + +#define GPIO_TRACECK (GPIO_ALT|GPIO_AF0 |GPIO_PORTE|GPIO_PIN2) +#define GPIO_TRACED0 (GPIO_ALT|GPIO_AF0 |GPIO_PORTE|GPIO_PIN3) +#define GPIO_TRACED1 (GPIO_ALT|GPIO_AF0 |GPIO_PORTE|GPIO_PIN4) +#define GPIO_TRACED2 (GPIO_ALT|GPIO_AF0 |GPIO_PORTE|GPIO_PIN5) +#define GPIO_TRACED3 (GPIO_ALT|GPIO_AF0 |GPIO_PORTE|GPIO_PIN6) + +/* UARTs/USARTs */ + +#define GPIO_USART1_TX_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN9) +#define GPIO_USART1_TX_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTB|GPIO_PIN6) +#define GPIO_USART1_RX_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN10) +#define GPIO_USART1_RX_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTB|GPIO_PIN7) +#define GPIO_USART1_CK_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN8) +#define GPIO_USART1_CK_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTB|GPIO_PIN5) +#define GPIO_USART1_CTS_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN11) +#define GPIO_USART1_CTS_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTB|GPIO_PIN4) +#define GPIO_USART1_RTS_DE_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN12) +#define GPIO_USART1_RTS_DE_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTB|GPIO_PIN3) + +#define GPIO_USART2_TX_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN2) +#define GPIO_USART2_TX_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN5) +#define GPIO_USART2_RX_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN3) +#define GPIO_USART2_RX_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN6) +#define GPIO_USART2_CK_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN4) +#define GPIO_USART2_CK_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN7) +#define GPIO_USART2_CTS_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN0) +#define GPIO_USART2_CTS_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN3) +#define GPIO_USART2_RTS_DE_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN1) +#define GPIO_USART2_RTS_DE_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN4) + +#define GPIO_USART3_TX_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTB|GPIO_PIN10) +#define GPIO_USART3_TX_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTC|GPIO_PIN4) +#define GPIO_USART3_TX_3 (GPIO_ALT|GPIO_AF7 |GPIO_PORTC|GPIO_PIN10) +#define GPIO_USART3_TX_4 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN8) +#define GPIO_USART3_RX_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTB|GPIO_PIN11) +#define GPIO_USART3_RX_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTC|GPIO_PIN5) +#define GPIO_USART3_RX_3 (GPIO_ALT|GPIO_AF7 |GPIO_PORTC|GPIO_PIN11) +#define GPIO_USART3_RX_4 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN9) +#define GPIO_USART3_CK_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTB|GPIO_PIN0) +#define GPIO_USART3_CK_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTB|GPIO_PIN12) +#define GPIO_USART3_CK_3 (GPIO_ALT|GPIO_AF7 |GPIO_PORTC|GPIO_PIN12) +#define GPIO_USART3_CK_4 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN10) +#define GPIO_USART3_CTS_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN6) +#define GPIO_USART3_CTS_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTB|GPIO_PIN13) +#define GPIO_USART3_CTS_3 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN11) +#define GPIO_USART3_RTS_DE_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTB|GPIO_PIN1) +#define GPIO_USART3_RTS_DE_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTB|GPIO_PIN14) +#define GPIO_USART3_RTS_DE_3 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN2) +#define GPIO_USART3_RTS_DE_4 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN12) + +#define GPIO_UART4_TX_1 (GPIO_ALT|GPIO_AF8 |GPIO_PORTA|GPIO_PIN0) +#define GPIO_UART4_TX_2 (GPIO_ALT|GPIO_AF8 |GPIO_PORTC|GPIO_PIN10) +#define GPIO_UART4_RX_1 (GPIO_ALT|GPIO_AF8 |GPIO_PORTA|GPIO_PIN1) +#define GPIO_UART4_RX_2 (GPIO_ALT|GPIO_AF8 |GPIO_PORTC|GPIO_PIN11) +#define GPIO_UART4_CTS (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN7) +#define GPIO_UART4_RTS_DE (GPIO_ALT|GPIO_AF8 |GPIO_PORTA|GPIO_PIN15) + +#define GPIO_UART5_TX (GPIO_ALT|GPIO_AF8 |GPIO_PORTC|GPIO_PIN12) +#define GPIO_UART5_RX (GPIO_ALT|GPIO_AF8 |GPIO_PORTD|GPIO_PIN2) +#define GPIO_UART5_CTS (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN5) +#define GPIO_UART5_RTS_DE (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN4) + +#define GPIO_LPUART1_TX_1 (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN11) +#define GPIO_LPUART1_TX_2 (GPIO_ALT|GPIO_AF8 |GPIO_PORTC|GPIO_PIN1) +#define GPIO_LPUART1_RX_1 (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN10) +#define GPIO_LPUART1_RX_2 (GPIO_ALT|GPIO_AF8 |GPIO_PORTC|GPIO_PIN0) +#define GPIO_LPUART1_CTS_1 (GPIO_ALT|GPIO_AF8 |GPIO_PORTA|GPIO_PIN6) +#define GPIO_LPUART1_CTS_2 (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN13) +#define GPIO_LPUART1_RTS_DE_1 (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN1) +#define GPIO_LPUART1_RTS_DE_2 (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN12) + +#endif /* __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X3XX_PINMAP_H */ diff --git a/arch/arm/src/stm32l4/chip/stm32l4x3xx_rcc.h b/arch/arm/src/stm32l4/chip/stm32l4x3xx_rcc.h new file mode 100644 index 0000000000..7aa7edfd6c --- /dev/null +++ b/arch/arm/src/stm32l4/chip/stm32l4x3xx_rcc.h @@ -0,0 +1,789 @@ +/**************************************************************************************************** + * arch/arm/src/stm32l4/chip/stm32l4x3xx_rcc.h + * + * Copyright (C) 2014-2015 Gregory Nutt. All rights reserved. + * Copyright (C) 2016 Sebastien Lorquet. All rights reserved. + * Author: Gregory Nutt + * Author: Sebastien Lorquet + * Author: 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 __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X3XX_RCC_H +#define __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X3XX_RCC_H + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include + +#if defined(CONFIG_STM32L4_STM32L4X3) + +/**************************************************************************************************** + * Pre-processor Definitions + ****************************************************************************************************/ + +/* Register Offsets *********************************************************************************/ + +#define STM32L4_RCC_CR_OFFSET 0x0000 /* Clock control register */ +#define STM32L4_RCC_ICSCR_OFFSET 0x0004 /* Internal clock sources calibration register */ +#define STM32L4_RCC_CFGR_OFFSET 0x0008 /* Clock configuration register */ +#define STM32L4_RCC_PLLCFG_OFFSET 0x000c /* PLL configuration register */ +#define STM32L4_RCC_PLLSAI1CFG_OFFSET 0x0010 /* PLLSAI1 configuration register */ +#define STM32L4_RCC_PLLSAI2CFG_OFFSET 0x0014 /* PLLSAI2 configuration register */ +#define STM32L4_RCC_CIER_OFFSET 0x0018 /* Clock interrupt enable register */ +#define STM32L4_RCC_CIFR_OFFSET 0x001c /* Clock interrupt flag register */ +#define STM32L4_RCC_CICR_OFFSET 0x0020 /* Clock interrupt clear register */ +#define STM32L4_RCC_AHB1RSTR_OFFSET 0x0028 /* AHB1 peripheral reset register */ +#define STM32L4_RCC_AHB2RSTR_OFFSET 0x002c /* AHB2 peripheral reset register */ +#define STM32L4_RCC_AHB3RSTR_OFFSET 0x0030 /* AHB3 peripheral reset register */ +#define STM32L4_RCC_APB1RSTR1_OFFSET 0x0038 /* APB1 Peripheral reset register 1 */ +#define STM32L4_RCC_APB1RSTR2_OFFSET 0x003c /* APB1 Peripheral reset register 2 */ +#define STM32L4_RCC_APB2RSTR_OFFSET 0x0040 /* APB2 Peripheral reset register */ +#define STM32L4_RCC_AHB1ENR_OFFSET 0x0048 /* AHB1 Peripheral Clock enable register */ +#define STM32L4_RCC_AHB2ENR_OFFSET 0x004c /* AHB2 Peripheral Clock enable register */ +#define STM32L4_RCC_AHB3ENR_OFFSET 0x0050 /* AHB3 Peripheral Clock enable register */ +#define STM32L4_RCC_APB1ENR1_OFFSET 0x0058 /* APB1 Peripheral Clock enable register 1 */ +#define STM32L4_RCC_APB1ENR2_OFFSET 0x005c /* APB1 Peripheral Clock enable register 2 */ +#define STM32L4_RCC_APB2ENR_OFFSET 0x0060 /* APB2 Peripheral Clock enable register */ +#define STM32L4_RCC_AHB1SMENR_OFFSET 0x0068 /* RCC AHB1 low power mode peripheral clock enable register */ +#define STM32L4_RCC_AHB2SMENR_OFFSET 0x006c /* RCC AHB2 low power mode peripheral clock enable register */ +#define STM32L4_RCC_AHB3SMENR_OFFSET 0x0070 /* RCC AHB3 low power mode peripheral clock enable register */ +#define STM32L4_RCC_APB1SMENR1_OFFSET 0x0078 /* RCC APB1 low power mode peripheral clock enable register 1 */ +#define STM32L4_RCC_APB1SMENR2_OFFSET 0x007c /* RCC APB1 low power mode peripheral clock enable register 2 */ +#define STM32L4_RCC_APB2SMENR_OFFSET 0x0080 /* RCC APB2 low power mode peripheral clock enable register */ +#define STM32L4_RCC_CCIPR_OFFSET 0x0088 /* Peripherals independent clock configuration register 1 */ +#define STM32L4_RCC_BDCR_OFFSET 0x0090 /* Backup domain control register */ +#define STM32L4_RCC_CSR_OFFSET 0x0094 /* Control/status register */ +#define STM32L4_RCC_CRRCR_OFFSET 0x0098 /* Clock recovery RC register */ + +/* Register Addresses *******************************************************************************/ + +#define STM32L4_RCC_CR (STM32L4_RCC_BASE+STM32L4_RCC_CR_OFFSET) +#define STM32L4_RCC_ICSCR (STM32L4_RCC_BASE+STM32L4_RCC_ICSCR_OFFSET) +#define STM32L4_RCC_CFGR (STM32L4_RCC_BASE+STM32L4_RCC_CFGR_OFFSET) +#define STM32L4_RCC_PLLCFG (STM32L4_RCC_BASE+STM32L4_RCC_PLLCFG_OFFSET) +#define STM32L4_RCC_PLLSAI1CFG (STM32L4_RCC_BASE+STM32L4_RCC_PLLSAI1CFG_OFFSET) +#define STM32L4_RCC_PLLSAI2CFG (STM32L4_RCC_BASE+STM32L4_RCC_PLLSAI2CFG_OFFSET) +#define STM32L4_RCC_CIER (STM32L4_RCC_BASE+STM32L4_RCC_CIER_OFFSET) +#define STM32L4_RCC_CIFR (STM32L4_RCC_BASE+STM32L4_RCC_CIFR_OFFSET) +#define STM32L4_RCC_CICR (STM32L4_RCC_BASE+STM32L4_RCC_CICR_OFFSET) +#define STM32L4_RCC_AHB1RSTR (STM32L4_RCC_BASE+STM32L4_RCC_AHB1RSTR_OFFSET) +#define STM32L4_RCC_AHB2RSTR (STM32L4_RCC_BASE+STM32L4_RCC_AHB2RSTR_OFFSET) +#define STM32L4_RCC_AHB3RSTR (STM32L4_RCC_BASE+STM32L4_RCC_AHB3RSTR_OFFSET) +#define STM32L4_RCC_APB1RSTR1 (STM32L4_RCC_BASE+STM32L4_RCC_APB1RSTR1_OFFSET) +#define STM32L4_RCC_APB1RSTR2 (STM32L4_RCC_BASE+STM32L4_RCC_APB1RSTR2_OFFSET) +#define STM32L4_RCC_APB2RSTR (STM32L4_RCC_BASE+STM32L4_RCC_APB2RSTR_OFFSET) +#define STM32L4_RCC_AHB1ENR (STM32L4_RCC_BASE+STM32L4_RCC_AHB1ENR_OFFSET) +#define STM32L4_RCC_AHB2ENR (STM32L4_RCC_BASE+STM32L4_RCC_AHB2ENR_OFFSET) +#define STM32L4_RCC_AHB3ENR (STM32L4_RCC_BASE+STM32L4_RCC_AHB3ENR_OFFSET) +#define STM32L4_RCC_APB1ENR1 (STM32L4_RCC_BASE+STM32L4_RCC_APB1ENR1_OFFSET) +#define STM32L4_RCC_APB1ENR2 (STM32L4_RCC_BASE+STM32L4_RCC_APB1ENR2_OFFSET) +#define STM32L4_RCC_APB2ENR (STM32L4_RCC_BASE+STM32L4_RCC_APB2ENR_OFFSET) +#define STM32L4_RCC_AHB1SMENR (STM32L4_RCC_BASE+STM32L4_RCC_AHB1SMENR_OFFSET) +#define STM32L4_RCC_AHB2SMENR (STM32L4_RCC_BASE+STM32L4_RCC_AHB2SMENR) +#define STM32L4_RCC_AHB3SMENR (STM32L4_RCC_BASE+STM32L4_RCC_AHB3SMENR_OFFSET) +#define STM32L4_RCC_APB1SMENR1 (STM32L4_RCC_BASE+STM32L4_RCC_APB1SMENR1_OFFSET) +#define STM32L4_RCC_APB1SMENR2 (STM32L4_RCC_BASE+STM32L4_RCC_APB1SMENR2_OFFSET) +#define STM32L4_RCC_APB2SMENR (STM32L4_RCC_BASE+STM32L4_RCC_APB2SMENR_OFFSET) +#define STM32L4_RCC_CCIPR (STM32L4_RCC_BASE+STM32L4_RCC_CCIPR_OFFSET) +#define STM32L4_RCC_BDCR (STM32L4_RCC_BASE+STM32L4_RCC_BDCR_OFFSET) +#define STM32L4_RCC_CSR (STM32L4_RCC_BASE+STM32L4_RCC_CSR_OFFSET) +#define STM32L4_RCC_CRRCR (STM32L4_RCC_BASE+STM32L4_RCC_CRRCR_OFFSET) + +/* Register Bitfield Definitions ********************************************************************/ + +/* Clock control register */ + +#define RCC_CR_MSION (1 << 0) /* Bit 0: Internal Multi Speed clock enable */ +#define RCC_CR_MSIRDY (1 << 1) /* Bit 1: Internal Multi Speed clock ready flag */ +#define RCC_CR_MSIPLLEN (1 << 2) /* Bit 2: MSI clock PLL enable */ +#define RCC_CR_MSIRGSEL (1 << 3) /* Bit 2: MSI clock range selection */ +#define RCC_CR_MSIRANGE_SHIFT (4) /* Bits 7-4: MSI clock range */ +#define RCC_CR_MSIRANGE_MASK (0x0f << RCC_CR_MSIRANGE_SHIFT) +# define RCC_CR_MSIRANGE_100K (0 << RCC_CR_MSIRANGE_SHIFT) /* 0000: around 100 kHz */ +# define RCC_CR_MSIRANGE_200K (1 << RCC_CR_MSIRANGE_SHIFT) /* 0001: around 200 kHz */ +# define RCC_CR_MSIRANGE_400K (2 << RCC_CR_MSIRANGE_SHIFT) /* 0010: around 400 kHz */ +# define RCC_CR_MSIRANGE_800K (3 << RCC_CR_MSIRANGE_SHIFT) /* 0011: around 800 kHz */ +# define RCC_CR_MSIRANGE_1M (4 << RCC_CR_MSIRANGE_SHIFT) /* 0100: around 1 MHz */ +# define RCC_CR_MSIRANGE_2M (5 << RCC_CR_MSIRANGE_SHIFT) /* 0101: around 2 MHz */ +# define RCC_CR_MSIRANGE_4M (6 << RCC_CR_MSIRANGE_SHIFT) /* 0110: around 4 MHz */ +# define RCC_CR_MSIRANGE_8M (7 << RCC_CR_MSIRANGE_SHIFT) /* 0111: around 8 MHz */ +# define RCC_CR_MSIRANGE_16M (8 << RCC_CR_MSIRANGE_SHIFT) /* 1000: around 16 MHz */ +# define RCC_CR_MSIRANGE_24M (9 << RCC_CR_MSIRANGE_SHIFT) /* 1001: around 24 MHz */ +# define RCC_CR_MSIRANGE_32M (10 << RCC_CR_MSIRANGE_SHIFT) /* 1010: around 32 MHz */ +# define RCC_CR_MSIRANGE_48M (11 << RCC_CR_MSIRANGE_SHIFT) /* 1011: around 48 MHz */ + +#define RCC_CR_HSION (1 << 8) /* Bit 8: Internal High Speed clock enable */ +#define RCC_CR_HSIKERON (1 << 9) /* Bit 9: HSI16 always enable for peripheral kernels */ +#define RCC_CR_HSIRDY (1 << 10) /* Bit 10: Internal High Speed clock ready flag */ +#define RCC_CR_HSIASFS (1 << 11) /* Bit 11: HSI automatic start from stop */ + +#define RCC_CR_HSEON (1 << 16) /* Bit 16: External High Speed clock enable */ +#define RCC_CR_HSERDY (1 << 17) /* Bit 17: External High Speed clock ready flag */ +#define RCC_CR_HSEBYP (1 << 18) /* Bit 18: External High Speed clock Bypass */ +#define RCC_CR_CSSON (1 << 19) /* Bit 19: Clock Security System enable */ +#define RCC_CR_PLLON (1 << 24) /* Bit 24: PLL enable */ +#define RCC_CR_PLLRDY (1 << 25) /* Bit 25: PLL clock ready flag */ +#define RCC_CR_PLLSAI1ON (1 << 26) /* Bit 26: PLLSAI1 enable */ +#define RCC_CR_PLLSAI1RDY (1 << 27) /* Bit 27: PLLSAI1 clock ready flag */ +#define RCC_CR_PLLSAI2ON (1 << 28) /* Bit 28: PLLSAI2 enable */ +#define RCC_CR_PLLSAI2RDY (1 << 29) /* Bit 29: PLLSAI2 clock ready flag */ + +/* Internal Clock Sources Calibration */ + +#define RCC_CR_HSITRIM_SHIFT (24) /* Bits 28-24: Internal High Speed clock trimming */ +#define RCC_CR_HSITRIM_MASK (0x1f << RCC_CR_HSITRIM_SHIFT) +#define RCC_CR_HSICAL_SHIFT (16) /* Bits 23-16: Internal High Speed clock Calibration */ +#define RCC_CR_HSICAL_MASK (0xff << RCC_CR_HSICAL_SHIFT) +#define RCC_CR_MSITRIM_SHIFT (8) /* Bits 15-8: Internal Multi Speed clock trimming */ +#define RCC_CR_MSITRIM_MASK (0xff << RCC_CR_MSITRIM_SHIFT) +#define RCC_CR_MSICAL_SHIFT (0) /* Bits 7-0: Internal Multi Speed clock Calibration */ +#define RCC_CR_MSICAL_MASK (0xff << RCC_CR_MSICAL_SHIFT) + +/* Clock configuration register */ + +#define RCC_CFGR_SW_SHIFT (0) /* Bits 0-1: System clock Switch */ +#define RCC_CFGR_SW_MASK (3 << RCC_CFGR_SW_SHIFT) +# define RCC_CFGR_SW_MSI (0 << RCC_CFGR_SW_SHIFT) /* 00: HSI selected as system clock */ +# define RCC_CFGR_SW_HSI (1 << RCC_CFGR_SW_SHIFT) /* 00: HSI selected as system clock */ +# define RCC_CFGR_SW_HSE (2 << RCC_CFGR_SW_SHIFT) /* 01: HSE selected as system clock */ +# define RCC_CFGR_SW_PLL (3 << RCC_CFGR_SW_SHIFT) /* 10: PLL selected as system clock */ + +#define RCC_CFGR_SWS_SHIFT (2) /* Bits 2-3: System Clock Switch Status */ +#define RCC_CFGR_SWS_MASK (3 << RCC_CFGR_SWS_SHIFT) +# define RCC_CFGR_SWS_MSI (0 << RCC_CFGR_SWS_SHIFT) /* 00: HSI oscillator used as system clock */ +# define RCC_CFGR_SWS_HSI (1 << RCC_CFGR_SWS_SHIFT) /* 00: HSI oscillator used as system clock */ +# define RCC_CFGR_SWS_HSE (2 << RCC_CFGR_SWS_SHIFT) /* 01: HSE oscillator used as system clock */ +# define RCC_CFGR_SWS_PLL (3 << RCC_CFGR_SWS_SHIFT) /* 10: PLL used as system clock */ + +#define RCC_CFGR_HPRE_SHIFT (4) /* Bits 4-7: AHB prescaler */ +#define RCC_CFGR_HPRE_MASK (0x0f << RCC_CFGR_HPRE_SHIFT) +# define RCC_CFGR_HPRE_SYSCLK (0 << RCC_CFGR_HPRE_SHIFT) /* 0xxx: SYSCLK not divided */ +# define RCC_CFGR_HPRE_SYSCLKd2 (8 << RCC_CFGR_HPRE_SHIFT) /* 1000: SYSCLK divided by 2 */ +# define RCC_CFGR_HPRE_SYSCLKd4 (9 << RCC_CFGR_HPRE_SHIFT) /* 1001: SYSCLK divided by 4 */ +# define RCC_CFGR_HPRE_SYSCLKd8 (10 << RCC_CFGR_HPRE_SHIFT) /* 1010: SYSCLK divided by 8 */ +# define RCC_CFGR_HPRE_SYSCLKd16 (11 << RCC_CFGR_HPRE_SHIFT) /* 1011: SYSCLK divided by 16 */ +# define RCC_CFGR_HPRE_SYSCLKd64 (12 << RCC_CFGR_HPRE_SHIFT) /* 1100: SYSCLK divided by 64 */ +# define RCC_CFGR_HPRE_SYSCLKd128 (13 << RCC_CFGR_HPRE_SHIFT) /* 1101: SYSCLK divided by 128 */ +# define RCC_CFGR_HPRE_SYSCLKd256 (14 << RCC_CFGR_HPRE_SHIFT) /* 1110: SYSCLK divided by 256 */ +# define RCC_CFGR_HPRE_SYSCLKd512 (15 << RCC_CFGR_HPRE_SHIFT) /* 1111: SYSCLK divided by 512 */ + +#define RCC_CFGR_PPRE1_SHIFT (8) /* Bits 8-10: APB Low speed prescaler (APB1) */ +#define RCC_CFGR_PPRE1_MASK (7 << RCC_CFGR_PPRE1_SHIFT) +# define RCC_CFGR_PPRE1_HCLK (0 << RCC_CFGR_PPRE1_SHIFT) /* 0xx: HCLK not divided */ +# define RCC_CFGR_PPRE1_HCLKd2 (4 << RCC_CFGR_PPRE1_SHIFT) /* 100: HCLK divided by 2 */ +# define RCC_CFGR_PPRE1_HCLKd4 (5 << RCC_CFGR_PPRE1_SHIFT) /* 101: HCLK divided by 4 */ +# define RCC_CFGR_PPRE1_HCLKd8 (6 << RCC_CFGR_PPRE1_SHIFT) /* 110: HCLK divided by 8 */ +# define RCC_CFGR_PPRE1_HCLKd16 (7 << RCC_CFGR_PPRE1_SHIFT) /* 111: HCLK divided by 16 */ + +#define RCC_CFGR_PPRE2_SHIFT (11) /* Bits 11-13: APB High speed prescaler (APB2) */ +#define RCC_CFGR_PPRE2_MASK (7 << RCC_CFGR_PPRE2_SHIFT) +# define RCC_CFGR_PPRE2_HCLK (0 << RCC_CFGR_PPRE2_SHIFT) /* 0xx: HCLK not divided */ +# define RCC_CFGR_PPRE2_HCLKd2 (4 << RCC_CFGR_PPRE2_SHIFT) /* 100: HCLK divided by 2 */ +# define RCC_CFGR_PPRE2_HCLKd4 (5 << RCC_CFGR_PPRE2_SHIFT) /* 101: HCLK divided by 4 */ +# define RCC_CFGR_PPRE2_HCLKd8 (6 << RCC_CFGR_PPRE2_SHIFT) /* 110: HCLK divided by 8 */ +# define RCC_CFGR_PPRE2_HCLKd16 (7 << RCC_CFGR_PPRE2_SHIFT) /* 111: HCLK divided by 16 */ + +#define RCC_CFGR_STOPWUCK (1 << 15) /* Bit 15: Wakeup from Stop and CSS backup clock selection */ +# define RCC_CFGR_STOPWUCK_MSI (0 << 15) /* 0: MSI */ +# define RCC_CFGR_STOPWUCK_HSI (1 << 15) /* 0: HSI */ + +#define RCC_CFGR_MCO_SHIFT (24) /* Bits 24-26: Microcontroller Clock Output */ +#define RCC_CFGR_MCO_MASK (7 << RCC_CFGR_MCO_SHIFT) +# define RCC_CFGR_MCO_NONE (0 << RCC_CFGR_MCO_SHIFT) /* 000: Disabled */ +# define RCC_CFGR_MCO_SYSCLK (1 << RCC_CFGR_MCO_SHIFT) /* 001: SYSCLK system clock selected */ +# define RCC_CFGR_MCO_MSI (2 << RCC_CFGR_MCO_SHIFT) /* 010: MSI clock selected */ +# define RCC_CFGR_MCO_HSI (3 << RCC_CFGR_MCO_SHIFT) /* 011: HSI clock selected */ +# define RCC_CFGR_MCO_HSE (4 << RCC_CFGR_MCO_SHIFT) /* 100: HSE clock selected */ +# define RCC_CFGR_MCO_PLL (5 << RCC_CFGR_MCO_SHIFT) /* 101: Main PLL selected */ +# define RCC_CFGR_MCO_LSI (6 << RCC_CFGR_MCO_SHIFT) /* 110: LSI clock selected */ +# define RCC_CFGR_MCO_LSE (7 << RCC_CFGR_MCO_SHIFT) /* 111: LSE clock selected */ + +#define RCC_CFGR_MCOPRE_SHIFT (28) /* Bits 28-30: MCO prescaler */ +#define RCC_CFGR_MCOPRE_MASK (7 << RCC_CFGR_MCOPRE_SHIFT) +# define RCC_CFGR_MCOPRE_NONE (0 << RCC_CFGR_MCOPRE_SHIFT) /* 000: no division */ +# define RCC_CFGR_MCOPRE_DIV2 (1 << RCC_CFGR_MCOPRE_SHIFT) /* 001: division by 2 */ +# define RCC_CFGR_MCOPRE_DIV4 (2 << RCC_CFGR_MCOPRE_SHIFT) /* 010: division by 4 */ +# define RCC_CFGR_MCOPRE_DIV8 (3 << RCC_CFGR_MCOPRE_SHIFT) /* 011: division by 8 */ +# define RCC_CFGR_MCOPRE_DIV16 (4 << RCC_CFGR_MCOPRE_SHIFT) /* 100: division by 16 */ + +/* PLL configuration register */ + +#define RCC_PLLCFG_PLLSRC_SHIFT (0) /* Bit 0-1: Main PLL(PLL) and audio PLLs (PLLSAIx) + * entry clock source */ +#define RCC_PLLCFG_PLLSRC_MASK (3 << RCC_PLLCFG_PLLSRC_SHIFT) +# define RCC_PLLCFG_PLLSRC_NONE (0 << RCC_PLLCFG_PLLSRC_SHIFT) /* 000: No clock sent to PLLs */ +# define RCC_PLLCFG_PLLSRC_MSI (1 << RCC_PLLCFG_PLLSRC_SHIFT) /* 001: MSI selected as PLL source */ +# define RCC_PLLCFG_PLLSRC_HSI (2 << RCC_PLLCFG_PLLSRC_SHIFT) /* 001: HSI selected as PLL source */ +# define RCC_PLLCFG_PLLSRC_HSE (3 << RCC_PLLCFG_PLLSRC_SHIFT) /* 001: HSE selected as PLL source */ + +#define RCC_PLLCFG_PLLM_SHIFT (4) /* Bits 4-6: Main PLL (PLL) input clock divider */ +#define RCC_PLLCFG_PLLM_MASK (0x07 << RCC_PLLCFG_PLLM_SHIFT) +# define RCC_PLLCFG_PLLM(n) ((n-1) << RCC_PLLCFG_PLLM_SHIFT) /* m = 1..8 */ + +#define RCC_PLLCFG_PLLN_SHIFT (8) /* Bits 6-14: Main PLL (PLL) VCO multiplier */ +#define RCC_PLLCFG_PLLN_MASK (0x7f << RCC_PLLCFG_PLLN_SHIFT) +# define RCC_PLLCFG_PLLN(n) ((n) << RCC_PLLCFG_PLLN_SHIFT) /* n = 8..86 */ + +#define RCC_PLLCFG_PLLPEN (1 << 16) /* Bit 16: Main PLL PLLSAI3CLK output enable */ + +#define RCC_PLLCFG_PLLP (1 << 17) /* Bit 17: Main PLL div factor for PLLSAI3CLK */ +# define RCC_PLLCFG_PLLP_7 0 /* 0: PLLP = 7 */ +# define RCC_PLLCFG_PLLP_17 RCC_PLLCFG_PLLP /* 1: PLLP = 17 */ + +#define RCC_PLLCFG_PLLQEN (1 << 20) /* Bit 20: Main PLL PLL48M1CLK output enable */ + +#define RCC_PLLCFG_PLLQ_SHIFT (21) +#define RCC_PLLCFG_PLLQ_MASK (3 << RCC_PLLCFG_PLLQ_SHIFT) +# define RCC_PLLCFG_PLLQ(n) ((((n)>>1)-1)<< RCC_PLLCFG_PLLQ_SHIFT) /* n=2,4,6,8 */ +# define RCC_PLLCFG_PLLQ_2 (0 << RCC_PLLCFG_PLLQ_SHIFT) /* 00: PLLQ = 2 */ +# define RCC_PLLCFG_PLLQ_4 (1 << RCC_PLLCFG_PLLQ_SHIFT) /* 01: PLLQ = 4 */ +# define RCC_PLLCFG_PLLQ_6 (2 << RCC_PLLCFG_PLLQ_SHIFT) /* 10: PLLQ = 6 */ +# define RCC_PLLCFG_PLLQ_8 (3 << RCC_PLLCFG_PLLQ_SHIFT) /* 11: PLLQ = 8 */ + +#define RCC_PLLCFG_PLLREN (1 << 24) /* Bit 24: Main PLL PLLCLK output enable */ + +#define RCC_PLLCFG_PLLR_SHIFT (25) +#define RCC_PLLCFG_PLLR_MASK (3 << RCC_PLLCFG_PLLR_SHIFT) +# define RCC_PLLCFG_PLLR(n) ((((n)>>1)-1)<< RCC_PLLCFG_PLLR_SHIFT) /* n=2,4,6,8 */ +# define RCC_PLLCFG_PLLR_2 (0 << RCC_PLLCFG_PLLR_SHIFT) /* 00: PLLR = 2 */ +# define RCC_PLLCFG_PLLR_4 (1 << RCC_PLLCFG_PLLR_SHIFT) /* 01: PLLR = 4 */ +# define RCC_PLLCFG_PLLR_6 (2 << RCC_PLLCFG_PLLR_SHIFT) /* 10: PLLR = 6 */ +# define RCC_PLLCFG_PLLR_8 (3 << RCC_PLLCFG_PLLR_SHIFT) /* 11: PLLR = 8 */ + +#define RCC_PLLCFG_RESET (0x00001000) /* PLLCFG reset value */ + +/* PLLSAI1 Configuration register */ + +#define RCC_PLLSAI1CFG_PLLN_SHIFT (8) /* Bits 6-14: SAI1 PLL (PLLSAI1) VCO multiplier */ +#define RCC_PLLSAI1CFG_PLLN_MASK (0x7f << RCC_PLLSAI1CFG_PLLN_SHIFT) +# define RCC_PLLSAI1CFG_PLLN(n) ((n) << RCC_PLLSAI1CFG_PLLN_SHIFT) /* n = 8..86 */ + +#define RCC_PLLSAI1CFG_PLLPEN (1 << 16) /* Bit 16: SAI1 PLL PLLSAI1CLK output enable */ + +#define RCC_PLLSAI1CFG_PLLP (1 << 17) /* Bit 17: Main PLL div factor for PLLSAI1CLK */ +# define RCC_PLLSAI1CFG_PLLP_7 0 /* 0: PLLP = 7 */ +# define RCC_PLLSAI1CFG_PLLP_17 RCC_PLLSAI1CFG_PLLP /* 1: PLLP = 17 */ + +#define RCC_PLLSAI1CFG_PLLQEN (1 << 20) /* Bit 20: Main PLL PLL48M2CLK output enable */ + +#define RCC_PLLSAI1CFG_PLLQ_SHIFT (21) +#define RCC_PLLSAI1CFG_PLLQ_MASK (3 << RCC_PLLSAI1CFG_PLLQ_SHIFT) +# define RCC_PLLSAI1CFG_PLLQ(n) ((((n)>>1)-1)<< RCC_PLLSAI1CFG_PLLQ_SHIFT) /* n=2,4,6,8 */ +# define RCC_PLLSAI1CFG_PLLQ_2 (0 << RCC_PLLSAI1CFG_PLLQ_SHIFT) /* 00: PLLQ = 2 */ +# define RCC_PLLSAI1CFG_PLLQ_4 (1 << RCC_PLLSAI1CFG_PLLQ_SHIFT) /* 01: PLLQ = 4 */ +# define RCC_PLLSAI1CFG_PLLQ_6 (2 << RCC_PLLSAI1CFG_PLLQ_SHIFT) /* 10: PLLQ = 6 */ +# define RCC_PLLSAI1CFG_PLLQ_8 (3 << RCC_PLLSAI1CFG_PLLQ_SHIFT) /* 11: PLLQ = 8 */ + +#define RCC_PLLSAI1CFG_PLLREN (1 << 24) /* Bit 24: SAI1 PLL PLLADC1CLK output enable */ + +#define RCC_PLLSAI1CFG_PLLR_SHIFT (25) +#define RCC_PLLSAI1CFG_PLLR_MASK (3 << RCC_PLLSAI1CFG_PLLR_SHIFT) +# define RCC_PLLSAI1CFG_PLLR(n) ((((n)>>1)-1)<< RCC_PLLSAI1CFG_PLLR_SHIFT) /* n=2,4,6,8 */ +# define RCC_PLLSAI1CFG_PLLR_2 (0 << RCC_PLLSAI1CFG_PLLR_SHIFT) /* 00: PLLR = 2 */ +# define RCC_PLLSAI1CFG_PLLR_4 (1 << RCC_PLLSAI1CFG_PLLR_SHIFT) /* 01: PLLR = 4 */ +# define RCC_PLLSAI1CFG_PLLR_6 (2 << RCC_PLLSAI1CFG_PLLR_SHIFT) /* 10: PLLR = 6 */ +# define RCC_PLLSAI1CFG_PLLR_8 (3 << RCC_PLLSAI1CFG_PLLR_SHIFT) /* 11: PLLR = 8 */ + +/* PLLSAI2 Configuration register */ + +#define RCC_PLLSAI2CFG_PLLN_SHIFT (8) /* Bits 6-14: SAI2 PLL (PLLSAI2) VCO multiplier */ +#define RCC_PLLSAI2CFG_PLLN_MASK (0x7f << RCC_PLLSAI2CFG_PLLN_SHIFT) +# define RCC_PLLSAI2CFG_PLLN(n) ((n) << RCC_PLLSAI2CFG_PLLN_SHIFT) /* n = 8..86 */ + +#define RCC_PLLSAI2CFG_PLLPEN (1 << 16) /* Bit 16: SAI1 PLL PLLSAI2CLK output enable */ + +#define RCC_PLLSAI2CFG_PLLP (1 << 17) /* Bit 17: Main PLL div factor for PLLSAI2CLK */ +# define RCC_PLLSAI2CFG_PLLP_7 0 /* 0: PLLP = 7 */ +# define RCC_PLLSAI2CFG_PLLP_17 RCC_PLLSAI2CFG_PLLP /* 1: PLLP = 17 */ + +#define RCC_PLLSAI2CFG_PLLREN (1 << 24) /* Bit 24: SAI2 PLL PLLADC2CLK output enable */ + +#define RCC_PLLSAI2CFG_PLLR_SHIFT (25) +#define RCC_PLLSAI2CFG_PLLR_MASK (3 << RCC_PLLSAI2CFG_PLLR_SHIFT) +# define RCC_PLLSAI2CFG_PLLR(n) ((((n)>>1)-1)<< RCC_PLLSAI2CFG_PLLR_SHIFT) /* n=2,4,6,8 */ +# define RCC_PLLSAI2CFG_PLLR_2 (0 << RCC_PLLSAI2CFG_PLLR_SHIFT) /* 00: PLLR = 2 */ +# define RCC_PLLSAI2CFG_PLLR_4 (1 << RCC_PLLSAI2CFG_PLLR_SHIFT) /* 01: PLLR = 4 */ +# define RCC_PLLSAI2CFG_PLLR_6 (2 << RCC_PLLSAI2CFG_PLLR_SHIFT) /* 10: PLLR = 6 */ +# define RCC_PLLSAI2CFG_PLLR_8 (3 << RCC_PLLSAI2CFG_PLLR_SHIFT) /* 11: PLLR = 8 */ + +/* Clock interrupt enable register */ + +#define RCC_CIR_LSIRDYIE (1 << 0) /* Bit 0: LSI Ready Interrupt Enable */ +#define RCC_CIR_LSERDYIE (1 << 1) /* Bit 1: LSE Ready Interrupt Enable */ +#define RCC_CIR_MSIRDYIE (1 << 2) /* Bit 2: MSI Ready Interrupt Enable */ +#define RCC_CIR_HSIRDYIE (1 << 3) /* Bit 3: HSI Ready Interrupt Enable */ +#define RCC_CIR_HSERDYIE (1 << 4) /* Bit 4: HSE Ready Interrupt Enable */ +#define RCC_CIR_PLLRDYIE (1 << 5) /* Bit 5: PLL Ready Interrupt Enable */ +#define RCC_CIR_PLLSAI1RDYIE (1 << 6) /* Bit 6: PLLSAI1 Ready Interrupt enable */ +#define RCC_CIR_PLLSAI2RDYIE (1 << 7) /* Bit 7: PLLSAI2 Ready Interrupt enable */ +#define RCC_CIR_LSECSSIE (1 << 9) /* Bit 9: LSE Clock Security System Interrupt Enable */ +#define RCC_CIR_HSI48RDYIE (1 << 10) /* Bit 10: HSI48 Ready Interrupt Enable */ + +/* Clock interrupt flag register */ + +#define RCC_CIR_LSIRDYIF (1 << 0) /* Bit 0: LSI Ready Interrupt Flag */ +#define RCC_CIR_LSERDYIF (1 << 1) /* Bit 1: LSE Ready Interrupt Flag */ +#define RCC_CIR_MSIRDYIF (1 << 2) /* Bit 2: MSI Ready Interrupt Flag */ +#define RCC_CIR_HSIRDYIF (1 << 3) /* Bit 3: HSI Ready Interrupt Flag */ +#define RCC_CIR_HSERDYIF (1 << 4) /* Bit 4: HSE Ready Interrupt Flag */ +#define RCC_CIR_PLLRDYIF (1 << 5) /* Bit 5: PLL Ready Interrupt Flag */ +#define RCC_CIR_PLLSAI1RDYIF (1 << 6) /* Bit 6: PLLSAI1 Ready Interrupt Flag */ +#define RCC_CIR_PLLSAI2RDYIF (1 << 7) /* Bit 7: PLLSAI2 Ready Interrupt Flag */ +#define RCC_CIR_CSSF (1 << 8) /* Bit 8: Clock Security System Interrupt Flag */ +#define RCC_CIR_LSECSSIF (1 << 9) /* Bit 9: LSE Clock Security System Interrupt Flag */ +#define RCC_CIR_HSI48RDYIF (1 << 10) /* Bit 10: HSI48 Ready Interrupt Flag */ + +/* Clock interrupt clear register */ + +#define RCC_CIR_LSIRDYIC (1 << 0) /* Bit 0: LSI Ready Interrupt Clear */ +#define RCC_CIR_LSERDYIC (1 << 1) /* Bit 1: LSE Ready Interrupt Clear */ +#define RCC_CIR_MSIRDYIC (1 << 2) /* Bit 2: MSI Ready Interrupt Clear */ +#define RCC_CIR_HSIRDYIC (1 << 3) /* Bit 3: HSI Ready Interrupt Clear */ +#define RCC_CIR_HSERDYIC (1 << 4) /* Bit 4: HSE Ready Interrupt Clear */ +#define RCC_CIR_PLLRDYIC (1 << 5) /* Bit 5: PLL Ready Interrupt Clear */ +#define RCC_CIR_PLLSAI1RDYIC (1 << 6) /* Bit 6: PLLSAI1 Ready Interrupt Clear */ +#define RCC_CIR_PLLSAI2RDYIC (1 << 7) /* Bit 7: PLLSAI2 Ready Interrupt Clear */ +#define RCC_CIR_CSSC (1 << 8) /* Bit 8: Clock Security System Interrupt Clear */ +#define RCC_CIR_LSECSSIC (1 << 9) /* Bit 9: LSE Clock Security System Interrupt Clear */ +#define RCC_CIR_HSI48RDYIC (1 << 10) /* Bit 10: HSI48 Oscillator Ready Interrupt Clear */ + +/* AHB1 peripheral reset register */ + +#define RCC_AHB1RSTR_DMA1RST (1 << 0) /* Bit 0: DMA1 reset */ +#define RCC_AHB1RSTR_DMA2RST (1 << 1) /* Bit 1: DMA2 reset */ +#define RCC_AHB1RSTR_FLASHRST (1 << 8) /* Bit 8: Flash memory interface reset */ +#define RCC_AHB1RSTR_CRCRST (1 << 12) /* Bit 12: CRC reset */ +#define RCC_AHB1RSTR_TSCRST (1 << 16) /* Bit 16: Touch Sensing Controller reset */ +#define RCC_AHB1RSTR_DMA2DRST (1 << 17) /* Bit 17: DMA2D reset */ + +/* AHB2 peripheral reset register */ + +#define RCC_AHB1ENR_GPIOEN(port) (1 << (port)) +#define RCC_AHB2RSTR_GPIOARST (1 << 0) /* Bit 0: IO port A reset */ +#define RCC_AHB2RSTR_GPIOBRST (1 << 1) /* Bit 1: IO port B reset */ +#define RCC_AHB2RSTR_GPIOCRST (1 << 2) /* Bit 2: IO port C reset */ +#define RCC_AHB2RSTR_GPIODRST (1 << 3) /* Bit 3: IO port D reset */ +#define RCC_AHB2RSTR_GPIOERST (1 << 4) /* Bit 4: IO port E reset */ +#define RCC_AHB2RSTR_GPIOHRST (1 << 7) /* Bit 7: IO port H reset */ +#define RCC_AHB2RSTR_ADCRST (1 << 13) /* Bit 13: ADC interface reset (common to all ADCs) */ +#define RCC_AHB2RSTR_DCMIRST (1 << 14) /* Bit 14: DCMI interface reset */ +#define RCC_AHB2RSTR_AESRST (1 << 16) /* Bit 16: AES Cryptographic module reset */ +#define RCC_AHB2RSTR_HASHRST (1 << 17) /* Bit 17: HASH module reset */ +#define RCC_AHB2RSTR_RNGRST (1 << 18) /* Bit 18: Random number generator module reset */ + +/* AHB3 peripheral reset register */ + +#define RCC_AHB3RSTR_FSMCRST (1 << 0) /* Bit 0: Flexible static memory controller module reset */ +#define RCC_AHB3RSTR_QSPIRST (1 << 8) /* Bit 8: Quad SPI module reset */ + +/* APB1 Peripheral reset register 1 */ + +#define RCC_APB1RSTR1_TIM2RST (1 << 0) /* Bit 0: TIM2 reset */ +#define RCC_APB1RSTR1_TIM3RST (1 << 1) /* Bit 1: TIM3 reset */ +#define RCC_APB1RSTR1_TIM4RST (1 << 2) /* Bit 2: TIM4 reset */ +#define RCC_APB1RSTR1_TIM5RST (1 << 3) /* Bit 3: TIM5 reset */ +#define RCC_APB1RSTR1_TIM6RST (1 << 4) /* Bit 4: TIM6 reset */ +#define RCC_APB1RSTR1_TIM7RST (1 << 5) /* Bit 5: TIM7 reset */ +#define RCC_APB1RSTR1_LCDRST (1 << 9) /* Bit 9: LCD controller reset */ +#define RCC_APB1RSTR1_SPI2RST (1 << 14) /* Bit 14: SPI2 reset */ +#define RCC_APB1RSTR1_SPI3RST (1 << 15) /* Bit 15: SPI3 reset */ +#define RCC_APB1RSTR1_USART2RST (1 << 17) /* Bit 17: USART2 reset */ +#define RCC_APB1RSTR1_USART3RST (1 << 18) /* Bit 18: USART3 reset */ +#define RCC_APB1RSTR1_UART4RST (1 << 19) /* Bit 19: USART4 reset */ +#define RCC_APB1RSTR1_UART5RST (1 << 20) /* Bit 20: USART5 reset */ +#define RCC_APB1RSTR1_I2C1RST (1 << 21) /* Bit 21: I2C1 reset */ +#define RCC_APB1RSTR1_I2C2RST (1 << 22) /* Bit 22: I2C2 reset */ +#define RCC_APB1RSTR1_I2C3RST (1 << 23) /* Bit 23: I2C3 reset */ +#define RCC_APB1RSTR1_CRSRST (1 << 24) /* Bit 24: CRS reset */ +#define RCC_APB1RSTR1_CAN1RST (1 << 25) /* Bit 25: CAN1 reset */ +#define RCC_APB1RSTR1_USBFSRST (1 << 26) /* Bit 26: USB FS reset */ +#define RCC_APB1RSTR1_PWRRST (1 << 28) /* Bit 28: Power interface reset */ +#define RCC_APB1RSTR1_DAC1RST (1 << 29) /* Bit 29: DAC1 reset */ +#define RCC_APB1RSTR1_OPAMPRST (1 << 30) /* Bit 30: OPAMP reset */ +#define RCC_APB1RSTR1_LPTIM1RST (1 << 31) /* Bit 31: Low-power Timer 1 reset */ + +/* APB1 Peripheral reset register 2 */ + +#define RCC_APB1RSTR2_LPUART1RST (1 << 0) /* Bit 0: Low-power UART 1 reset */ +#define RCC_APB1RSTR2_I2C4RST (1 << 1) /* Bit 1: I2C4 reset */ +#define RCC_APB1RSTR2_SWPMI1RST (1 << 2) /* Bit 2: Single Wire Protocol reset */ +#define RCC_APB1RSTR2_LPTIM2RST (1 << 5) /* Bit 5: Low-power Timer 2 reset */ + +/* APB2 Peripheral reset register */ + +#define RCC_APB2RSTR_SYSCFGRST (1 << 0) /* Bit 0: System configuration controller reset */ +#define RCC_APB2RSTR_SDMMCRST (1 << 10) /* Bit 10: SDMMC reset */ +#define RCC_APB2RSTR_TIM1RST (1 << 11) /* Bit 11: TIM1 reset */ +#define RCC_APB2RSTR_SPI1RST (1 << 12) /* Bit 12: SPI1 reset */ +#define RCC_APB2RSTR_TIM8RST (1 << 13) /* Bit 13: TIM8 reset */ +#define RCC_APB2RSTR_USART1RST (1 << 14) /* Bit 14: USART1 reset */ +#define RCC_APB2RSTR_TIM15RST (1 << 16) /* Bit 16: TIM15 reset */ +#define RCC_APB2RSTR_TIM16RST (1 << 17) /* Bit 17: TIM16 reset */ +#define RCC_APB2RSTR_TIM17RST (1 << 18) /* Bit 18: TIM17 reset */ +#define RCC_APB2RSTR_SAI1RST (1 << 21) /* Bit 21: SAI1 reset */ +#define RCC_APB2RSTR_SAI2RST (1 << 22) /* Bit 22: SAI2 reset */ +#define RCC_APB2RSTR_DFSDMRST (1 << 24) /* Bit 24: DFSDM reset */ + +/* AHB1 Peripheral Clock enable register */ + +#define RCC_AHB1ENR_DMA1EN (1 << 0) /* Bit 0: DMA1 enable */ +#define RCC_AHB1ENR_DMA2EN (1 << 1) /* Bit 1: DMA2 enable */ +#define RCC_AHB1ENR_FLASHEN (1 << 8) /* Bit 8: Flash memory interface enable */ +#define RCC_AHB1ENR_CRCEN (1 << 12) /* Bit 12: CRC enable */ +#define RCC_AHB1ENR_TSCEN (1 << 16) /* Bit 16: Touch Sensing Controller enable */ +#define RCC_AHB1ENR_DMA2DEN (1 << 17) /* Bit 17: DMA2D enable */ + +/* AHB2 Peripheral Clock enable register */ + +#define RCC_AHB2ENR_GPIOAEN (1 << 0) /* Bit 0: IO port A enable */ +#define RCC_AHB2ENR_GPIOBEN (1 << 1) /* Bit 1: IO port B enable */ +#define RCC_AHB2ENR_GPIOCEN (1 << 2) /* Bit 2: IO port C enable */ +#define RCC_AHB2ENR_GPIODEN (1 << 3) /* Bit 3: IO port D enable */ +#define RCC_AHB2ENR_GPIOEEN (1 << 4) /* Bit 4: IO port E enable */ +#define RCC_AHB2ENR_GPIOHEN (1 << 7) /* Bit 7: IO port H enable */ +#define RCC_AHB2ENR_ADCEN (1 << 13) /* Bit 13: ADC interface enable (common to all ADCs) */ +#define RCC_AHB2ENR_DCMIEN (1 << 14) /* Bit 14: DCMI interface enable */ +#define RCC_AHB2ENR_AESEN (1 << 16) /* Bit 16: AES Cryptographic module enable */ +#define RCC_AHB2ENR_HASHEN (1 << 17) /* Bit 17: HASH module enable */ +#define RCC_AHB2ENR_RNGEN (1 << 18) /* Bit 18: Random number generator module enable */ + +/* AHB3 Peripheral Clock enable register */ + +#define RCC_AHB3ENR_FSMCEN (1 << 0) /* Bit 0: Flexible static memory controller module enable */ +#define RCC_AHB3ENR_QSPIEN (1 << 8) /* Bit 8: Quad SPI module enable */ + +/* APB1 Peripheral Clock enable register 1 */ + +#define RCC_APB1ENR1_TIM2EN (1 << 0) /* Bit 0: TIM2 enable */ +#define RCC_APB1ENR1_TIM3EN (1 << 1) /* Bit 1: TIM3 enable */ +#define RCC_APB1ENR1_TIM4EN (1 << 2) /* Bit 2: TIM4 enable */ +#define RCC_APB1ENR1_TIM5EN (1 << 3) /* Bit 3: TIM5 enable */ +#define RCC_APB1ENR1_TIM6EN (1 << 4) /* Bit 4: TIM6 enable */ +#define RCC_APB1ENR1_TIM7EN (1 << 5) /* Bit 5: TIM7 enable */ +#define RCC_APB1ENR1_LCDEN (1 << 9) /* Bit 9: LCD controller enable */ +#define RCC_APB1ENR1_RTCAPBEN (1 << 10) /* Bit 10: RTC APB clock enable */ +#define RCC_APB1ENR1_WWDGEN (1 << 11) /* Bit 11: Windowed Watchdog enable */ +#define RCC_APB1ENR1_SPI2EN (1 << 14) /* Bit 14: SPI2 enable */ +#define RCC_APB1ENR1_SPI3EN (1 << 15) /* Bit 15: SPI3 enable */ +#define RCC_APB1ENR1_USART2EN (1 << 17) /* Bit 17: USART2 enable */ +#define RCC_APB1ENR1_USART3EN (1 << 18) /* Bit 18: USART3 enable */ +#define RCC_APB1ENR1_UART4EN (1 << 19) /* Bit 19: USART4 enable */ +#define RCC_APB1ENR1_UART5EN (1 << 20) /* Bit 20: USART5 enable */ +#define RCC_APB1ENR1_I2C1EN (1 << 21) /* Bit 21: I2C1 enable */ +#define RCC_APB1ENR1_I2C2EN (1 << 22) /* Bit 22: I2C2 enable */ +#define RCC_APB1ENR1_I2C3EN (1 << 23) /* Bit 23: I2C3 enable */ +#define RCC_APB1ENR1_CRSEN (1 << 24) /* Bit 24: CRSEN enable */ +#define RCC_APB1ENR1_CAN1EN (1 << 25) /* Bit 25: CAN1 enable */ +#define RCC_APB1ENR1_USBFSEN (1 << 26) /* Bit 26: USB FS enable */ +#define RCC_APB1ENR1_PWREN (1 << 28) /* Bit 28: Power interface enable */ +#define RCC_APB1ENR1_DAC1EN (1 << 29) /* Bit 29: DAC1 enable */ +#define RCC_APB1ENR1_OPAMPEN (1 << 30) /* Bit 30: OPAMP enable */ +#define RCC_APB1ENR1_LPTIM1EN (1 << 31) /* Bit 31: Low-power Timer 1 enable */ + +/* APB1 Peripheral Clock enable register 2 */ + +#define RCC_APB1ENR2_LPUART1EN (1 << 0) /* Bit 0: Low-power UART 1 enable */ +#define RCC_APB1ENR2_I2C4EN (1 << 1) /* Bit 1: I2C4 enable */ +#define RCC_APB1ENR2_SWPMI1EN (1 << 2) /* Bit 2: Single Wire Protocol enable */ +#define RCC_APB1ENR2_LPTIM2EN (1 << 5) /* Bit 5: Low-power Timer 2 enable */ + +/* APB2 Peripheral Clock enable register */ + +#define RCC_APB2ENR_SYSCFGEN (1 << 0) /* Bit 0: System configuration controller enable */ +#define RCC_APB2ENR_FWEN (1 << 7) /* Bit 7: Firewall enable */ +#define RCC_APB2ENR_SDMMCEN (1 << 10) /* Bit 10: SDMMC enable */ +#define RCC_APB2ENR_TIM1EN (1 << 11) /* Bit 11: TIM1 enable */ +#define RCC_APB2ENR_SPI1EN (1 << 12) /* Bit 12: SPI1 enable */ +#define RCC_APB2ENR_TIM8EN (1 << 13) /* Bit 13: TIM8 enable */ +#define RCC_APB2ENR_USART1EN (1 << 14) /* Bit 14: USART1 enable */ +#define RCC_APB2ENR_TIM15EN (1 << 16) /* Bit 16: TIM15 enable */ +#define RCC_APB2ENR_TIM16EN (1 << 17) /* Bit 17: TIM16 enable */ +#define RCC_APB2ENR_TIM17EN (1 << 18) /* Bit 18: TIM17 enable */ +#define RCC_APB2ENR_SAI1EN (1 << 21) /* Bit 21: SAI1 enable */ +#define RCC_APB2ENR_SAI2EN (1 << 22) /* Bit 22: SAI2 enable */ +#define RCC_APB2ENR_DFSDMEN (1 << 24) /* Bit 24: DFSDM enable */ + +/* RCC AHB1 low power mode peripheral clock enable register */ + +#define RCC_AHB1SMENR_DMA1LPSMEN (1 << 0) /* Bit 0: DMA1 enable during Sleep mode */ +#define RCC_AHB1SMENR_DMA2LPSMEN (1 << 1) /* Bit 1: DMA2 enable during Sleep mode */ +#define RCC_AHB1SMENR_FLASHLPSMEN (1 << 8) /* Bit 8: Flash memory interface enable during Sleep mode */ +#define RCC_AHB1SMENR_SRAM1SMEN (1 << 9) /* Bit 9: SRAM1 enable during Sleep mode */ +#define RCC_AHB1SMENR_CRCLPSMEN (1 << 12) /* Bit 12: CRC enable during Sleep mode */ +#define RCC_AHB1SMENR_TSCLPSMEN (1 << 16) /* Bit 16: Touch Sensing Controller enable during Sleep mode */ +#define RCC_AHB1SMENR_DMA2DSMEN (1 << 17) /* Bit 17: DMA2D enable during Sleep mode */ + +/* RCC AHB2 low power mode peripheral clock enable register */ + +#define RCC_AHB2SMENR_GPIOASMEN (1 << 0) /* Bit 0: IO port A enable during Sleep mode */ +#define RCC_AHB2SMENR_GPIOBSMEN (1 << 1) /* Bit 1: IO port B enable during Sleep mode */ +#define RCC_AHB2SMENR_GPIOCSMEN (1 << 2) /* Bit 2: IO port C enable during Sleep mode */ +#define RCC_AHB2SMENR_GPIODSMEN (1 << 3) /* Bit 3: IO port D enable during Sleep mode */ +#define RCC_AHB2SMENR_GPIOESMEN (1 << 4) /* Bit 4: IO port E enable during Sleep mode */ +#define RCC_AHB2SMENR_GPIOHSMEN (1 << 7) /* Bit 7: IO port H enable during Sleep mode */ +#define RCC_AHB2SMENR_SRAM2SMEN (1 << 9) /* Bit 9: SRAM2 enable during Sleep mode */ +#define RCC_AHB2SMENR_ADCSMEN (1 << 13) /* Bit 13: ADC interface enable during Sleep mode (common to all ADCs) */ +#define RCC_AHB2SMENR_DCMISMEN (1 << 14) /* Bit 14: DCMI interface enable during Sleep mode */ +#define RCC_AHB2SMENR_AESSMEN (1 << 16) /* Bit 16: AES Cryptographic module enable during Sleep mode */ +#define RCC_AHB2SMENR_HASHSMEN (1 << 17) /* Bit 17: HASH module enable during Sleep mode */ +#define RCC_AHB2SMENR_RNGSMEN (1 << 18) /* Bit 18: Random number generator module enable during Sleep mode */ + +/* RCC AHB3 low power mode peripheral clock enable register */ + +#define RCC_AHB3SMENR_FSMCSMEN (1 << 0) /* Bit 0: Flexible static memory controller module enable during Sleep mode */ +#define RCC_AHB3SMENR_QSPISMEN (1 << 8) /* Bit 8: Quad SPI module enable during Sleep mode */ + +/* RCC APB1 low power mode peripheral clock enable register 1 */ + +#define RCC_APB1SMENR1_TIM2SMEN (1 << 0) /* Bit 0: TIM2 enable during Sleep mode */ +#define RCC_APB1SMENR1_TIM3SMEN (1 << 1) /* Bit 1: TIM3 enable during Sleep mode */ +#define RCC_APB1SMENR1_TIM4SMEN (1 << 2) /* Bit 2: TIM4 enable during Sleep mode */ +#define RCC_APB1SMENR1_TIM5SMEN (1 << 3) /* Bit 3: TIM5 enable during Sleep mode */ +#define RCC_APB1SMENR1_TIM6SMEN (1 << 4) /* Bit 4: TIM6 enable during Sleep mode */ +#define RCC_APB1SMENR1_TIM7SMEN (1 << 5) /* Bit 5: TIM7 enable during Sleep mode */ +#define RCC_APB1SMENR1_LCDSMEN (1 << 9) /* Bit 9: LCD controller enable during Sleep mode */ +#define RCC_APB1SMENR1_RTCAPBSMEN (1 << 10) /* Bit 10: RTC APB clock enable during Sleep mode */ +#define RCC_APB1SMENR1_WWDGSMEN (1 << 11) /* Bit 11: Windowed Watchdog enable during Sleep mode */ +#define RCC_APB1SMENR1_SPI2SMEN (1 << 14) /* Bit 14: SPI2 enable during Sleep mode */ +#define RCC_APB1SMENR1_SPI3SMEN (1 << 15) /* Bit 15: SPI3 enable during Sleep mode */ +#define RCC_APB1SMENR1_USART2SMEN (1 << 17) /* Bit 17: USART2 enable during Sleep mode */ +#define RCC_APB1SMENR1_USART3SMEN (1 << 18) /* Bit 18: USART3 enable during Sleep mode */ +#define RCC_APB1SMENR1_UART4SMEN (1 << 19) /* Bit 19: USART4 enable during Sleep mode */ +#define RCC_APB1SMENR1_UART5SMEN (1 << 20) /* Bit 20: USART5 enable during Sleep mode */ +#define RCC_APB1SMENR1_I2C1SMEN (1 << 21) /* Bit 21: I2C1 enable during Sleep mode */ +#define RCC_APB1SMENR1_I2C2SMEN (1 << 22) /* Bit 22: I2C2 enable during Sleep mode */ +#define RCC_APB1SMENR1_I2C3SMEN (1 << 23) /* Bit 23: I2C3 enable during Sleep mode */ +#define RCC_APB1SMENR1_CRSSMEN (1 << 24) /* Bit 24: CRS enable during Sleep mode */ +#define RCC_APB1SMENR1_CAN1SMEN (1 << 25) /* Bit 25: CAN1 enable during Sleep mode */ +#define RCC_APB1SMENR1_USBFSSMEN (1 << 26) /* Bit 26: USB FS enable during Sleep mode */ +#define RCC_APB1SMENR1_PWRSMEN (1 << 28) /* Bit 28: Power interface enable during Sleep mode */ +#define RCC_APB1SMENR1_DAC1SMEN (1 << 29) /* Bit 29: DAC1 enable during Sleep mode */ +#define RCC_APB1SMENR1_OPAMPSMEN (1 << 30) /* Bit 30: OPAMP enable during Sleep mode */ +#define RCC_APB1SMENR1_LPTIM1SMEN (1 << 31) /* Bit 31: Low-power Timer 1 enable during Sleep mode */ + +/* RCC APB1 low power modeperipheral clock enable register 2 */ + +#define RCC_APB1SMENR2_LPUART1SMEN (1 << 0) /* Bit 0: Low-power UART 1 enable during Sleep mode */ +#define RCC_APB1SMENR2_I2C4SMEN (1 << 1) /* Bit 1: I2C4 enable during Sleep mode */ +#define RCC_APB1SMENR2_SWPMI1SMEN (1 << 2) /* Bit 2: Single Wire Protocol enable during Sleep mode */ +#define RCC_APB1SMENR2_LPTIM2SMEN (1 << 5) /* Bit 5: Low-power Timer 2 enable during Sleep mode */ + +/* RCC APB2 low power mode peripheral clock enable register */ + +#define RCC_APB2SMENR_SYSCFGSMEN (1 << 0) /* Bit 0: System configuration controller enable during Sleep mode */ +#define RCC_APB2SMENR_SDMMCSMEN (1 << 10) /* Bit 10: SDMMC enable during Sleep mode */ +#define RCC_APB2SMENR_TIM1SMEN (1 << 11) /* Bit 11: TIM1 enable during Sleep mode */ +#define RCC_APB2SMENR_SPI1SMEN (1 << 12) /* Bit 12: SPI1 enable during Sleep mode */ +#define RCC_APB2SMENR_TIM8SMEN (1 << 13) /* Bit 13: TIM8 enable during Sleep mode */ +#define RCC_APB2SMENR_USART1SMEN (1 << 14) /* Bit 14: USART1 enable during Sleep mode */ +#define RCC_APB2SMENR_TIM15SMEN (1 << 16) /* Bit 16: TIM15 enable during Sleep mode */ +#define RCC_APB2SMENR_TIM16SMEN (1 << 17) /* Bit 17: TIM16 enable during Sleep mode */ +#define RCC_APB2SMENR_TIM17SMEN (1 << 18) /* Bit 18: TIM17 enable during Sleep mode */ +#define RCC_APB2SMENR_SAI1SMEN (1 << 21) /* Bit 21: SAI1 enable during Sleep mode */ +#define RCC_APB2SMENR_SAI2SMEN (1 << 22) /* Bit 22: SAI2 enable during Sleep mode */ +#define RCC_APB2SMENR_DFSDMSMEN (1 << 24) /* Bit 24: DFSDM enable during Sleep mode */ + +/* Peripheral Independent Clock Configuration register */ + +#define RCC_CCIPR_USART1SEL_SHIFT (0) +#define RCC_CCIPR_USART1SEL_MASK (3 << RCC_CCIPR_USART1SEL_SHIFT) +# define RCC_CCIPR_USART1SEL_PCLK (0 << RCC_CCIPR_USART1SEL_SHIFT) +# define RCC_CCIPR_USART1SEL_SYSCLK (1 << RCC_CCIPR_USART1SEL_SHIFT) +# define RCC_CCIPR_USART1SEL_HSI (2 << RCC_CCIPR_USART1SEL_SHIFT) +# define RCC_CCIPR_USART1SEL_LSE (3 << RCC_CCIPR_USART1SEL_SHIFT) + +#define RCC_CCIPR_USART2SEL_SHIFT (2) +#define RCC_CCIPR_USART2SEL_MASK (3 << RCC_CCIPR_USART2SEL_SHIFT) +# define RCC_CCIPR_USART2SEL_PCLK (0 << RCC_CCIPR_USART2SEL_SHIFT) +# define RCC_CCIPR_USART2SEL_SYSCLK (1 << RCC_CCIPR_USART2SEL_SHIFT) +# define RCC_CCIPR_USART2SEL_HSI (2 << RCC_CCIPR_USART2SEL_SHIFT) +# define RCC_CCIPR_USART2SEL_LSE (3 << RCC_CCIPR_USART2SEL_SHIFT) + +#define RCC_CCIPR_USART3SEL_SHIFT (4) +#define RCC_CCIPR_USART3SEL_MASK (3 << RCC_CCIPR_USART3SEL_SHIFT) +# define RCC_CCIPR_USART3SEL_PCLK (0 << RCC_CCIPR_USART3SEL_SHIFT) +# define RCC_CCIPR_USART3SEL_SYSCLK (1 << RCC_CCIPR_USART3SEL_SHIFT) +# define RCC_CCIPR_USART3SEL_HSI (2 << RCC_CCIPR_USART3SEL_SHIFT) +# define RCC_CCIPR_USART3SEL_LSE (3 << RCC_CCIPR_USART3SEL_SHIFT) + +#define RCC_CCIPR_UART4SEL_SHIFT (6) +#define RCC_CCIPR_UART4SEL_MASK (3 << RCC_CCIPR_UART4SEL_SHIFT) +# define RCC_CCIPR_UART4SEL_PCLK (0 << RCC_CCIPR_UART4SEL_SHIFT) +# define RCC_CCIPR_UART4SEL_SYSCLK (1 << RCC_CCIPR_UART4SEL_SHIFT) +# define RCC_CCIPR_UART4SEL_HSI (2 << RCC_CCIPR_UART4SEL_SHIFT) +# define RCC_CCIPR_UART4SEL_LSE (3 << RCC_CCIPR_UART4SEL_SHIFT) + +#define RCC_CCIPR_UART5SEL_SHIFT (8) +#define RCC_CCIPR_UART5SEL_MASK (3 << RCC_CCIPR_UART5SEL_SHIFT) +# define RCC_CCIPR_UART5SEL_PCLK (0 << RCC_CCIPR_UART5SEL_SHIFT) +# define RCC_CCIPR_UART5SEL_SYSCLK (1 << RCC_CCIPR_UART5SEL_SHIFT) +# define RCC_CCIPR_UART5SEL_HSI (2 << RCC_CCIPR_UART5SEL_SHIFT) +# define RCC_CCIPR_UART5SEL_LSE (3 << RCC_CCIPR_UART5SEL_SHIFT) + +#define RCC_CCIPR_LPUART1SEL_SHIFT (10) +#define RCC_CCIPR_LPUART1SEL_MASK (3 << RCC_CCIPR_LPUART1SEL_SHIFT) +# define RCC_CCIPR_LPUART1SEL_PCLK (0 << RCC_CCIPR_LPUART1SEL_SHIFT) +# define RCC_CCIPR_LPUART1SEL_SYSCLK (1 << RCC_CCIPR_LPUART1SEL_SHIFT) +# define RCC_CCIPR_LPUART1SEL_HSI (2 << RCC_CCIPR_LPUART1SEL_SHIFT) +# define RCC_CCIPR_LPUART1SEL_LSE (3 << RCC_CCIPR_LPUART1SEL_SHIFT) + +#define RCC_CCIPR_I2C1SEL_SHIFT (12) +#define RCC_CCIPR_I2C1SEL_MASK (3 << RCC_CCIPR_I2C1SEL_SHIFT) +# define RCC_CCIPR_I2C1SEL_PCLK (0 << RCC_CCIPR_I2C1SEL_SHIFT) +# define RCC_CCIPR_I2C1SEL_SYSCLK (1 << RCC_CCIPR_I2C1SEL_SHIFT) +# define RCC_CCIPR_I2C1SEL_HSI (2 << RCC_CCIPR_I2C1SEL_SHIFT) + +#define RCC_CCIPR_I2C2SEL_SHIFT (14) +#define RCC_CCIPR_I2C2SEL_MASK (3 << RCC_CCIPR_I2C2SEL_SHIFT) +# define RCC_CCIPR_I2C2SEL_PCLK (0 << RCC_CCIPR_I2C2SEL_SHIFT) +# define RCC_CCIPR_I2C2SEL_SYSCLK (1 << RCC_CCIPR_I2C2SEL_SHIFT) +# define RCC_CCIPR_I2C2SEL_HSI (2 << RCC_CCIPR_I2C2SEL_SHIFT) + +#define RCC_CCIPR_I2C3SEL_SHIFT (16) +#define RCC_CCIPR_I2C3SEL_MASK (3 << RCC_CCIPR_I2C3SEL_SHIFT) +# define RCC_CCIPR_I2C3SEL_PCLK (0 << RCC_CCIPR_I2C3SEL_SHIFT) +# define RCC_CCIPR_I2C3SEL_SYSCLK (1 << RCC_CCIPR_I2C3SEL_SHIFT) +# define RCC_CCIPR_I2C3SEL_HSI (2 << RCC_CCIPR_I2C3SEL_SHIFT) + +#define RCC_CCIPR_LPTIM1SEL_SHIFT (18) +#define RCC_CCIPR_LPTIM1SEL_MASK (3 << RCC_CCIPR_LPTIM1SEL_SHIFT) +# define RCC_CCIPR_LPTIM1SEL_PCLK (0 << RCC_CCIPR_LPTIM1SEL_SHIFT) +# define RCC_CCIPR_LPTIM1SEL_LSI (1 << RCC_CCIPR_LPTIM1SEL_SHIFT) +# define RCC_CCIPR_LPTIM1SEL_HSI (2 << RCC_CCIPR_LPTIM1SEL_SHIFT) +# define RCC_CCIPR_LPTIM1SEL_LSE (3 << RCC_CCIPR_LPTIM1SEL_SHIFT) + +#define RCC_CCIPR_LPTIM2SEL_SHIFT (20) +#define RCC_CCIPR_LPTIM2SEL_MASK (3 << RCC_CCIPR_LPTIM2SEL_SHIFT) +# define RCC_CCIPR_LPTIM2SEL_PCLK (0 << RCC_CCIPR_LPTIM2SEL_SHIFT) +# define RCC_CCIPR_LPTIM2SEL_LSI (1 << RCC_CCIPR_LPTIM2SEL_SHIFT) +# define RCC_CCIPR_LPTIM2SEL_HSI (2 << RCC_CCIPR_LPTIM2SEL_SHIFT) +# define RCC_CCIPR_LPTIM2SEL_LSE (3 << RCC_CCIPR_LPTIM2SEL_SHIFT) + +#define RCC_CCIPR_SAI1SEL_SHIFT (22) +#define RCC_CCIPR_SAI1SEL_MASK (3 << RCC_CCIPR_SAI1SEL_SHIFT) +# define RCC_CCIPR_SAI1SEL_PLLSAI1 (0 << RCC_CCIPR_SAI1SEL_SHIFT) +# define RCC_CCIPR_SAI1SEL_PLLSAI2 (1 << RCC_CCIPR_SAI1SEL_SHIFT) +# define RCC_CCIPR_SAI1SEL_PLLMAIN (2 << RCC_CCIPR_SAI1SEL_SHIFT) +# define RCC_CCIPR_SAI1SEL_EXTCLK (3 << RCC_CCIPR_SAI1SEL_SHIFT) + +#define RCC_CCIPR_SAI2SEL_SHIFT (24) +#define RCC_CCIPR_SAI2SEL_MASK (3 << RCC_CCIPR_SAI2SEL_SHIFT) +# define RCC_CCIPR_SAI2SEL_PLLSAI1 (0 << RCC_CCIPR_SAI2SEL_SHIFT) +# define RCC_CCIPR_SAI2SEL_PLLSAI2 (1 << RCC_CCIPR_SAI2SEL_SHIFT) +# define RCC_CCIPR_SAI2SEL_PLLMAIN (2 << RCC_CCIPR_SAI2SEL_SHIFT) +# define RCC_CCIPR_SAI2SEL_EXTCLK (3 << RCC_CCIPR_SAI2SEL_SHIFT) + +#define RCC_CCIPR_CLK48SEL_SHIFT (26) +#define RCC_CCIPR_CLK48SEL_MASK (3 << RCC_CCIPR_CLK48SEL_SHIFT) +# define RCC_CCIPR_CLK48SEL_NONE (0 << RCC_CCIPR_CLK48SEL_SHIFT) +# define RCC_CCIPR_CLK48SEL_PLLSAI1 (1 << RCC_CCIPR_CLK48SEL_SHIFT) +# define RCC_CCIPR_CLK48SEL_PLLMAIN (2 << RCC_CCIPR_CLK48SEL_SHIFT) +# define RCC_CCIPR_CLK48SEL_MSI (3 << RCC_CCIPR_CLK48SEL_SHIFT) + +#define RCC_CCIPR_ADCSEL_SHIFT (28) +#define RCC_CCIPR_ADCSEL_MASK (3 << RCC_CCIPR_ADCSEL_SHIFT) +# define RCC_CCIPR_ADCSEL_NONE (0 << RCC_CCIPR_ADCSEL_SHIFT) +# define RCC_CCIPR_ADCSEL_PLLSAI1 (1 << RCC_CCIPR_ADCSEL_SHIFT) +# define RCC_CCIPR_ADCSEL_PLLSAI2 (2 << RCC_CCIPR_ADCSEL_SHIFT) +# define RCC_CCIPR_ADCSEL_SYSCLK (3 << RCC_CCIPR_ADCSEL_SHIFT) + +#define RCC_CCIPR_SWPMI1SEL (1 << 30) +# define RCC_CCIPR_SWPMI1SEL_PCLK 0 +# define RCC_CCIPR_SWPMI1SEL_HSI RCC_CCIPR_SWPMI1SEL + +#define RCC_CCIPR_DFSDMSEL (1 << 31) +# define RCC_CCIPR_DFSDMSEL_PCLK 0 +# define RCC_CCIPR_DFSDMSEL_SYSCLK RCC_CCIPR_DFSDMSEL + +/* Backup domain control register */ + +#define RCC_BDCR_LSEON (1 << 0) /* Bit 0: External Low Speed oscillator enable */ +#define RCC_BDCR_LSERDY (1 << 1) /* Bit 1: External Low Speed oscillator Ready */ +#define RCC_BDCR_LSEBYP (1 << 2) /* Bit 2: External Low Speed oscillator Bypass */ + +#define RCC_BDCR_LSEDRV_SHIFT (3) /* Bits 3-4: LSE oscillator drive capability */ +#define RCC_BDCR_LSEDRV_MASK (3 << RCC_BDCR_LSEDRV_SHIFT) +# define RCC_BDCR_LSEDRV_LOWER (0 << RCC_BDCR_LSEDRV_SHIFT) /* 00: Lower driving capability */ +# define RCC_BDCR_LSEDRV_MIDLOW (1 << RCC_BDCR_LSEDRV_SHIFT) /* 01: Medium Low driving capability */ +# define RCC_BDCR_LSEDRV_MIDHI (2 << RCC_BDCR_LSEDRV_SHIFT) /* 10: Medium High driving capability*/ +# define RCC_BDCR_LSEDRV_HIGER (3 << RCC_BDCR_LSEDRV_SHIFT) /* 11: Higher driving capability */ + +#define RCC_BDCR_LSECSSON (1 << 5) /* Bit 5: CSS on LSE enable */ +#define RCC_BDCR_LSECSSD (1 << 6) /* Bit 6: CSS on LSE failure Detection */ + +#define RCC_BDCR_RTCSEL_SHIFT (8) /* Bits 9:8: RTC clock source selection */ +#define RCC_BDCR_RTCSEL_MASK (3 << RCC_BDCR_RTCSEL_SHIFT) +# define RCC_BDCR_RTCSEL_NOCLK (0 << RCC_BDCR_RTCSEL_SHIFT) /* 00: No clock */ +# define RCC_BDCR_RTCSEL_LSE (1 << RCC_BDCR_RTCSEL_SHIFT) /* 01: LSE oscillator clock used as RTC clock */ +# define RCC_BDCR_RTCSEL_LSI (2 << RCC_BDCR_RTCSEL_SHIFT) /* 10: LSI oscillator clock used as RTC clock */ +# define RCC_BDCR_RTCSEL_HSE (3 << RCC_BDCR_RTCSEL_SHIFT) /* 11: HSE oscillator clock divided by 32 used as RTC clock */ + +#define RCC_BDCR_RTCEN (1 << 15) /* Bit 15: RTC clock enable */ +#define RCC_BDCR_BDRST (1 << 16) /* Bit 16: Backup domain software reset */ +#define RCC_BDCR_LSCOEN (1 << 24) /* Bit 24: Low speed clock output enable */ +#define RCC_BDCR_LSCOSEL (1 << 25) /* Bit 25: Low speed clock output selection */ +# define RCC_BCDR_LSCOSEL_LSI 0 /* LSI selected */ +# define RCC_BDCR_LSCOSEL_LSE RCC_BDCR_LSCOSEL /* LSE selected */ + +/* Control/status register */ + +#define RCC_CSR_LSION (1 << 0) /* Bit 0: Internal Low Speed oscillator enable */ +#define RCC_CSR_LSIRDY (1 << 1) /* Bit 1: Internal Low Speed oscillator Ready */ + +#define RCC_CSR_MSISRANGE_SHIFT 8 +# define RCC_CSR_MSISRANGE_MASK (0x0F << RCC_CSR_MSISRANGE_SHIFT) /* MSI range after Standby mode */ +# define RCC_CSR_MSISRANGE_1M (4 << RCC_CSR_MSISRANGE_SHIFT) /* 0100: around 1 MHz */ +# define RCC_CSR_MSISRANGE_2M (5 << RCC_CSR_MSISRANGE_SHIFT) /* 0101: around 2 MHz */ +# define RCC_CSR_MSISRANGE_4M (6 << RCC_CSR_MSISRANGE_SHIFT) /* 0110: around 4 MHz */ +# define RCC_CSR_MSISRANGE_8M (7 << RCC_CSR_MSISRANGE_SHIFT) /* 0111: around 8 MHz */ + +#define RCC_CSR_RMVF (1 << 23) /* Bit 23: Remove reset flag */ +#define RCC_CSR_FWRSTF (1 << 24) /* Bit 24: Firewall reset flag */ +#define RCC_CSR_OBLRSTF (1 << 25) /* Bit 25: Option byte loader reset flag */ +#define RCC_CSR_PINRSTF (1 << 26) /* Bit 26: PIN reset flag */ +#define RCC_CSR_BORRSTF (1 << 27) /* Bit 27: BOR reset flag */ +#define RCC_CSR_SFTRSTF (1 << 28) /* Bit 28: Software Reset flag */ +#define RCC_CSR_IWDGRSTF (1 << 29) /* Bit 29: Independent Watchdog reset flag */ +#define RCC_CSR_WWDGRSTF (1 << 30) /* Bit 30: Window watchdog reset flag */ +#define RCC_CSR_LPWRRSTF (1 << 31) /* Bit 31: Low-Power reset flag */ + +/* Clock recovery RC register */ + +#define RCC_CRRCR_HSI48CAL_SHIFT 7 +# define RCC_CRRCR_HSI48CAL_MASK (0x01ff << RCC_CRRCR_HSI48CAL_SHIFT) /* HSI48 clock calibration */ + +#define RCC_CRRCR_HSI48ON (1 << 0) /* Bit 0: HSI48 clock enable */ +#define RCC_CRRCR_HSI48RDY (1 << 1) /* Bit 1: HSI48 clock ready flag */ + +#endif /* CONFIG_STM32L4_STM32L4X3 */ +#endif /* __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X3XX_RCC_H */ diff --git a/arch/arm/src/stm32l4/chip/stm32l4x6xx_rcc.h b/arch/arm/src/stm32l4/chip/stm32l4x6xx_rcc.h index d180033ad2..6d55cfea9a 100644 --- a/arch/arm/src/stm32l4/chip/stm32l4x6xx_rcc.h +++ b/arch/arm/src/stm32l4/chip/stm32l4x6xx_rcc.h @@ -44,8 +44,7 @@ #include -#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX) || \ - defined(CONFIG_STM32L4_STM32L496XX) +#if defined(CONFIG_STM32L4_STM32L4X6) /**************************************************************************************************** * Pre-processor Definitions @@ -807,5 +806,5 @@ # define RCC_CCIPR2_I2C4SEL_SYSCLK (1 << RCC_CCIPR2_I2C4SEL_SHIFT) # define RCC_CCIPR2_I2C4SEL_HSI (2 << RCC_CCIPR2_I2C4SEL_SHIFT) -#endif /* CONFIG_STM32L4_STM32L476XX || CONFIG_STM32L4_STM32L486XX || CONFIG_STM32L4_STM32L496XX */ +#endif /* CONFIG_STM32L4_STM32L4X6 */ #endif /* __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X6XX_RCC_H */ diff --git a/arch/arm/src/stm32l4/stm32l4_dma.c b/arch/arm/src/stm32l4/stm32l4_dma.c index d2fd26546e..fbde7e04e6 100644 --- a/arch/arm/src/stm32l4/stm32l4_dma.c +++ b/arch/arm/src/stm32l4/stm32l4_dma.c @@ -41,34 +41,15 @@ #include "chip.h" -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Types - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - /* This file is only a thin shell that includes the correct DMA implementation * for the selected STM32 family. The correct file cannot be selected by * the make system because it needs the intelligence that only exists in * chip.h that can associate an STM32 part number with an STM32 family. + * + * TODO: do we need separate implementation for STM32L4X3? */ -#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX) || \ - defined(CONFIG_STM32L4_STM32L496XX) +#if defined(CONFIG_STM32L4_STM32L4X6) || defined(CONFIG_STM32L4_STM32L4X3) #include "stm32l4x6xx_dma.c" #else # error "Unsupported STM32L4 chip" diff --git a/arch/arm/src/stm32l4/stm32l4_dma.h b/arch/arm/src/stm32l4/stm32l4_dma.h index 89196cb381..c12013782d 100644 --- a/arch/arm/src/stm32l4/stm32l4_dma.h +++ b/arch/arm/src/stm32l4/stm32l4_dma.h @@ -49,9 +49,10 @@ /* Include the correct DMA register definitions for this STM32 family */ -#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX) || \ - defined(CONFIG_STM32L4_STM32L496XX) +#if defined(CONFIG_STM32L4_STM32L4X6) # include "chip/stm32l4x6xx_dma.h" +#elif defined(CONFIG_STM32L4_STM32L4X3) +# include "chip/stm32l4x3xx_dma.h" #else # error "Unsupported STM32L4 chip" #endif diff --git a/arch/arm/src/stm32l4/stm32l4_gpio.h b/arch/arm/src/stm32l4/stm32l4_gpio.h index 57076a83ed..e0fac1e273 100644 --- a/arch/arm/src/stm32l4/stm32l4_gpio.h +++ b/arch/arm/src/stm32l4/stm32l4_gpio.h @@ -54,9 +54,8 @@ #include "chip.h" -#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX) || \ - defined(CONFIG_STM32L4_STM32L496XX) -# include "chip/stm32l4x6xx_gpio.h" +#if defined(CONFIG_STM32L4_STM32L4X6) || defined(CONFIG_STM32L4_STM32L4X3) +# include "chip/stm32l4_gpio.h" #else # error "Unsupported STM32L4 chip" #endif diff --git a/arch/arm/src/stm32l4/stm32l4_rcc.c b/arch/arm/src/stm32l4/stm32l4_rcc.c index 6d7a240d89..ffe1c4d2dc 100644 --- a/arch/arm/src/stm32l4/stm32l4_rcc.c +++ b/arch/arm/src/stm32l4/stm32l4_rcc.c @@ -78,9 +78,10 @@ /* Include chip-specific clocking initialization logic */ -#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX) || \ - defined(CONFIG_STM32L4_STM32L496XX) +#if defined(CONFIG_STM32L4_STM32L4X6) # include "stm32l4x6xx_rcc.c" +#elif defined(CONFIG_STM32L4_STM32L4X3) +# include "stm32l4x3xx_rcc.c" #else # error "Unsupported STM32L4 chip" #endif diff --git a/arch/arm/src/stm32l4/stm32l4_rcc.h b/arch/arm/src/stm32l4/stm32l4_rcc.h index 6c77771ec6..8e3f84adc8 100644 --- a/arch/arm/src/stm32l4/stm32l4_rcc.h +++ b/arch/arm/src/stm32l4/stm32l4_rcc.h @@ -45,9 +45,10 @@ #include "up_arch.h" #include "chip.h" -#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX) || \ - defined(CONFIG_STM32L4_STM32L496XX) +#if defined(CONFIG_STM32L4_STM32L4X6) # include "chip/stm32l4x6xx_rcc.h" +#elif defined(CONFIG_STM32L4_STM32L4X3) +# include "chip/stm32l4x3xx_rcc.h" #else # error "Unsupported STM32L4 chip" #endif diff --git a/arch/arm/src/stm32l4/stm32l4_serial.c b/arch/arm/src/stm32l4/stm32l4_serial.c index 187a8f8f9b..955fb548e1 100644 --- a/arch/arm/src/stm32l4/stm32l4_serial.c +++ b/arch/arm/src/stm32l4/stm32l4_serial.c @@ -61,6 +61,7 @@ #include #include "chip.h" +#include "stm32l4_gpio.h" #include "stm32l4_uart.h" #include "stm32l4_dma.h" #include "stm32l4_rcc.h" diff --git a/arch/arm/src/stm32l4/stm32l4_uart.h b/arch/arm/src/stm32l4/stm32l4_uart.h index d6922269fb..286ba8eeb8 100644 --- a/arch/arm/src/stm32l4/stm32l4_uart.h +++ b/arch/arm/src/stm32l4/stm32l4_uart.h @@ -44,9 +44,8 @@ #include "chip.h" -#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX) || \ - defined(CONFIG_STM32L4_STM32L496XX) -# include "chip/stm32l4x6xx_uart.h" +#if defined(CONFIG_STM32L4_STM32L4X6) || defined(CONFIG_STM32L4_STM32L4X3) +# include "chip/stm32l4_uart.h" #else # error "Unsupported STM32L4 chip" #endif diff --git a/arch/arm/src/stm32l4/stm32l4x3xx_rcc.c b/arch/arm/src/stm32l4/stm32l4x3xx_rcc.c new file mode 100644 index 0000000000..855481df09 --- /dev/null +++ b/arch/arm/src/stm32l4/stm32l4x3xx_rcc.c @@ -0,0 +1,864 @@ +/**************************************************************************** + * arch/arm/src/stm32l4/stm32l4x3xx_rcc.c + * + * Copyright (C) 2011-2012, 2014-2015 Gregory Nutt. All rights reserved. + * Copyright (C) 2016 Sebastien Lorquet. All rights reserved. + * Authors: Gregory Nutt + * Sebastien Lorquet + * 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 "stm32l4_pwr.h" +#include "stm32l4_flash.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Allow up to 100 milliseconds for the high speed clock to become ready. + * that is a very long delay, but if the clock does not become ready we are + * hosed anyway. Normally this is very fast, but I have seen at least one + * board that required this long, long timeout for the HSE to be ready. + */ + +#define HSERDY_TIMEOUT (100 * CONFIG_BOARD_LOOPSPERMSEC) + +/* Same for HSI and MSI */ + +#define HSIRDY_TIMEOUT HSERDY_TIMEOUT +#define MSIRDY_TIMEOUT HSERDY_TIMEOUT + +/* HSE divisor to yield ~1MHz RTC clock */ + +#define HSE_DIVISOR (STM32L4_HSE_FREQUENCY + 500000) / 1000000 + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: rcc_reset + * + * Description: + * Reset the RCC clock configuration to the default reset state + * + ****************************************************************************/ + +static inline void rcc_reset(void) +{ + uint32_t regval; + + /* Enable the Internal High Speed clock (HSI) */ + + regval = getreg32(STM32L4_RCC_CR); + regval |= RCC_CR_HSION; + putreg32(regval, STM32L4_RCC_CR); + + /* Reset CFGR register */ + + putreg32(0x00000000, STM32L4_RCC_CFGR); + + /* Reset HSION, HSEON, CSSON and PLLON bits */ + + regval = getreg32(STM32L4_RCC_CR); + regval &= ~(RCC_CR_HSION | RCC_CR_HSEON | RCC_CR_CSSON | RCC_CR_PLLON); + putreg32(regval, STM32L4_RCC_CR); + + /* Reset PLLCFGR register to reset default */ + + putreg32(RCC_PLLCFG_RESET, STM32L4_RCC_PLLCFG); + + /* Reset HSEBYP bit */ + + regval = getreg32(STM32L4_RCC_CR); + regval &= ~RCC_CR_HSEBYP; + putreg32(regval, STM32L4_RCC_CR); + + /* Disable all interrupts */ + + putreg32(0x00000000, STM32L4_RCC_CIER); +} + +/**************************************************************************** + * Name: rcc_enableahb1 + * + * Description: + * Enable selected AHB1 peripherals + * + ****************************************************************************/ + +static inline void rcc_enableahb1(void) +{ + uint32_t regval; + + /* Set the appropriate bits in the AHB1ENR register to enabled the + * selected AHB1 peripherals. + */ + + regval = getreg32(STM32L4_RCC_AHB1ENR); + +#ifdef CONFIG_STM32L4_DMA1 + /* DMA 1 clock enable */ + + regval |= RCC_AHB1ENR_DMA1EN; +#endif + +#ifdef CONFIG_STM32L4_DMA2 + /* DMA 2 clock enable */ + + regval |= RCC_AHB1ENR_DMA2EN; +#endif + +#ifdef CONFIG_STM32L4_CRC + /* CRC clock enable */ + + regval |= RCC_AHB1ENR_CRCEN; +#endif + +#ifdef CONFIG_STM32L4_TSC + /* TSC clock enable */ + + regval |= RCC_AHB1ENR_TSCEN; +#endif + + putreg32(regval, STM32L4_RCC_AHB1ENR); /* Enable peripherals */ +} + +/**************************************************************************** + * Name: rcc_enableahb2 + * + * Description: + * Enable selected AHB2 peripherals + * + ****************************************************************************/ + +static inline void rcc_enableahb2(void) +{ + uint32_t regval; + + /* Set the appropriate bits in the AHB2ENR register to enable the + * selected AHB2 peripherals. + */ + + regval = getreg32(STM32L4_RCC_AHB2ENR); + + /* Enable GPIOA, GPIOB, .... GPIOH */ + +#if STM32L4_NPORTS > 0 + regval |= (RCC_AHB2ENR_GPIOAEN +#if STM32L4_NPORTS > 1 + | RCC_AHB2ENR_GPIOBEN +#endif +#if STM32L4_NPORTS > 2 + | RCC_AHB2ENR_GPIOCEN +#endif +#if STM32L4_NPORTS > 3 + | RCC_AHB2ENR_GPIODEN +#endif +#if STM32L4_NPORTS > 4 + | RCC_AHB2ENR_GPIOEEN +#endif +/* These chips have no GPIOF, GPIOG or GPIOI */ +#if STM32L4_NPORTS > 7 + | RCC_AHB2ENR_GPIOHEN +#endif + ); +#endif + +#if defined(CONFIG_STM32L4_ADC1) || defined(CONFIG_STM32L4_ADC2) || defined(CONFIG_STM32L4_ADC3) + /* ADC clock enable */ + + regval |= RCC_AHB2ENR_ADCEN; +#endif + +#ifdef CONFIG_STM32L4_AES + /* Cryptographic modules clock enable */ + + regval |= RCC_AHB2ENR_AESEN; +#endif + +#ifdef CONFIG_STM32L4_RNG + /* Random number generator clock enable */ + + regval |= RCC_AHB2ENR_RNGEN; +#endif + + putreg32(regval, STM32L4_RCC_AHB2ENR); /* Enable peripherals */ +} + +/**************************************************************************** + * Name: rcc_enableahb3 + * + * Description: + * Enable selected AHB3 peripherals + * + ****************************************************************************/ + +static inline void rcc_enableahb3(void) +{ + uint32_t regval; + + /* Set the appropriate bits in the AHB3ENR register to enabled the + * selected AHB3 peripherals. + */ + + regval = getreg32(STM32L4_RCC_AHB3ENR); + +#ifdef CONFIG_STM32L4_QSPI + /* QuadSPI module clock enable */ + + regval |= RCC_AHB3ENR_QSPIEN; +#endif + + putreg32(regval, STM32L4_RCC_AHB3ENR); /* Enable peripherals */ +} + +/**************************************************************************** + * Name: rcc_enableapb1 + * + * Description: + * Enable selected APB1 peripherals + * + ****************************************************************************/ + +static inline void rcc_enableapb1(void) +{ + uint32_t regval; + + /* Set the appropriate bits in the APB1ENR register to enabled the + * selected APB1 peripherals. + */ + + regval = getreg32(STM32L4_RCC_APB1ENR1); + +#ifdef CONFIG_STM32L4_TIM2 + /* TIM2 clock enable */ + + regval |= RCC_APB1ENR1_TIM2EN; +#endif + +#ifdef CONFIG_STM32L4_TIM3 + /* TIM3 clock enable */ + + regval |= RCC_APB1ENR1_TIM3EN; +#endif + +#ifdef CONFIG_STM32L4_TIM6 + /* TIM6 clock enable */ + + regval |= RCC_APB1ENR1_TIM6EN; +#endif + +#ifdef CONFIG_STM32L4_TIM7 + /* TIM7 clock enable */ + + regval |= RCC_APB1ENR1_TIM7EN; +#endif + +#ifdef CONFIG_STM32L4_LCD + /* LCD clock enable */ + + regval |= RCC_APB1ENR1_LCDEN; +#endif + +#ifdef CONFIG_STM32L4_SPI2 + /* SPI2 clock enable */ + + regval |= RCC_APB1ENR1_SPI2EN; +#endif + +#ifdef CONFIG_STM32L4_SPI3 + /* SPI3 clock enable */ + + regval |= RCC_APB1ENR1_SPI3EN; +#endif + +#ifdef CONFIG_STM32L4_USART2 + /* USART 2 clock enable */ + + regval |= RCC_APB1ENR1_USART2EN; +#endif + +#ifdef CONFIG_STM32L4_USART3 + /* USART3 clock enable */ + + regval |= RCC_APB1ENR1_USART3EN; +#endif + +#ifdef CONFIG_STM32L4_UART4 + /* UART4 clock enable */ + + regval |= RCC_APB1ENR1_UART4EN; +#endif + +#ifdef CONFIG_STM32L4_I2C1 + /* I2C1 clock enable */ + + regval |= RCC_APB1ENR1_I2C1EN; +#endif + +#ifdef CONFIG_STM32L4_I2C2 + /* I2C2 clock enable */ + + regval |= RCC_APB1ENR1_I2C2EN; +#endif + +#ifdef CONFIG_STM32L4_I2C3 + /* I2C3 clock enable */ + + regval |= RCC_APB1ENR1_I2C3EN; +#endif + +#ifdef CONFIG_STM32L4_CAN1 + /* CAN 1 clock enable */ + + regval |= RCC_APB1ENR1_CAN1EN; +#endif + +#ifdef CONFIG_STM32L4_USBFS + /* USB FS clock enable */ + + regval |= RCC_APB1ENR1_USBFSEN; +#endif + + /* Power interface clock enable. The PWR block is always enabled so that + * we can set the internal voltage regulator as required. + */ + + regval |= RCC_APB1ENR1_PWREN; + +#if defined (CONFIG_STM32L4_DAC1) || defined(CONFIG_STM32L4_DAC2) + /* DAC interface clock enable */ + + regval |= RCC_APB1ENR1_DACEN; +#endif + +#ifdef CONFIG_STM32L4_OPAMP + /* OPAMP clock enable */ + + regval |= RCC_APB1ENR1_OPAMPEN; +#endif + +#ifdef CONFIG_STM32L4_LPTIM1 + /* Low power timer 1 clock enable */ + + regval |= RCC_APB1ENR1_LPTIM1EN; +#endif + + putreg32(regval, STM32L4_RCC_APB1ENR1); /* Enable peripherals */ + + /* Second APB1 register */ + + regval = getreg32(STM32L4_RCC_APB1ENR2); + +#ifdef CONFIG_STM32L4_LPUART1 + /* Low power uart clock enable */ + + regval |= RCC_APB1ENR2_LPUART1EN; +#endif + +#ifdef CONFIG_STM32L4_I2C4 + /* I2C4 clock enable */ + + regval |= RCC_APB1ENR2_I2C4EN; +#endif + +#ifdef CONFIG_STM32L4_SWPMI + /* Single-wire protocol master clock enable */ + + regval |= RCC_APB1ENR2_SWPMI1EN; +#endif + +#ifdef CONFIG_STM32L4_LPTIM2 + /* Low power timer 2 clock enable */ + + regval |= RCC_APB1ENR2_LPTIM2EN; +#endif + + putreg32(regval, STM32L4_RCC_APB1ENR2); /* Enable peripherals */ +} + +/**************************************************************************** + * Name: rcc_enableapb2 + * + * Description: + * Enable selected APB2 peripherals + * + ****************************************************************************/ + +static inline void rcc_enableapb2(void) +{ + uint32_t regval; + + /* Set the appropriate bits in the APB2ENR register to enabled the + * selected APB2 peripherals. + */ + + regval = getreg32(STM32L4_RCC_APB2ENR); + +#ifdef CONFIG_STM32L4_SYSCFG + /* System configuration controller clock enable */ + + regval |= RCC_APB2ENR_SYSCFGEN; +#endif + +#ifdef CONFIG_STM32L4_FIREWALL + /* Firewall clock enable */ + + regval |= RCC_APB2ENR_FWEN; +#endif + +#ifdef CONFIG_STM32L4_SDMMC + /* SDMMC clock enable */ + + regval |= RCC_APB2ENR_SDMMCEN; +#endif + +#ifdef CONFIG_STM32L4_TIM1 + /* TIM1 clock enable */ + + regval |= RCC_APB2ENR_TIM1EN; +#endif + +#ifdef CONFIG_STM32L4_SPI1 + /* SPI1 clock enable */ + + regval |= RCC_APB2ENR_SPI1EN; +#endif + +#ifdef CONFIG_STM32L4_USART1 + /* USART1 clock enable */ + + regval |= RCC_APB2ENR_USART1EN; +#endif + +#ifdef CONFIG_STM32L4_TIM15 + /* TIM15 clock enable */ + + regval |= RCC_APB2ENR_TIM15EN; +#endif + +#ifdef CONFIG_STM32L4_TIM16 + /* TIM16 clock enable */ + + regval |= RCC_APB2ENR_TIM16EN; +#endif + +#ifdef CONFIG_STM32L4_SAI1 + /* SAI1 clock enable */ + + regval |= RCC_APB2ENR_SAI1EN; +#endif + +#ifdef CONFIG_STM32L4_DFSDM1 + /* DFSDM clock enable */ + + regval |= RCC_APB2ENR_DFSDMEN; +#endif + + putreg32(regval, STM32L4_RCC_APB2ENR); /* Enable peripherals */ +} + +/**************************************************************************** + * Name: stm32l4_stdclockconfig + * + * Description: + * Called to change to new clock based on settings in board.h + * + * NOTE: This logic would need to be extended if you need to select low- + * power clocking modes! + ****************************************************************************/ + +#ifndef CONFIG_ARCH_BOARD_STM32L4_CUSTOM_CLOCKCONFIG +static void stm32l4_stdclockconfig(void) +{ + uint32_t regval; + volatile int32_t timeout; + +#ifdef STM32L4_BOARD_USEHSI + /* Enable Internal High-Speed Clock (HSI) */ + + regval = getreg32(STM32L4_RCC_CR); + regval |= RCC_CR_HSION; /* Enable HSI */ + putreg32(regval, STM32L4_RCC_CR); + + /* Wait until the HSI is ready (or until a timeout elapsed) */ + + for (timeout = HSIRDY_TIMEOUT; timeout > 0; timeout--) + { + /* Check if the HSIRDY flag is the set in the CR */ + + if ((getreg32(STM32L4_RCC_CR) & RCC_CR_HSIRDY) != 0) + { + /* If so, then break-out with timeout > 0 */ + + break; + } + } + +#elif defined(STM32L4_BOARD_USEMSI) + /* Enable Internal Multi-Speed Clock (MSI) */ + + /* Wait until the MSI is either off or ready (or until a timeout elapsed) */ + + for (timeout = MSIRDY_TIMEOUT; timeout > 0; timeout--) + { + if ((regval = getreg32(STM32L4_RCC_CR)), (regval & RCC_CR_MSIRDY) || ~(regval & RCC_CR_MSION)) + { + /* If so, then break-out with timeout > 0 */ + + break; + } + } + + /* setting MSIRANGE */ + + regval = getreg32(STM32L4_RCC_CR); + regval |= (STM32L4_BOARD_MSIRANGE | RCC_CR_MSION); /* Enable MSI and frequency */ + putreg32(regval, STM32L4_RCC_CR); + + /* Wait until the MSI is ready (or until a timeout elapsed) */ + + for (timeout = MSIRDY_TIMEOUT; timeout > 0; timeout--) + { + /* Check if the MSIRDY flag is the set in the CR */ + + if ((getreg32(STM32L4_RCC_CR) & RCC_CR_MSIRDY) != 0) + { + /* If so, then break-out with timeout > 0 */ + + break; + } + } + +#elif defined(STM32L4_BOARD_USEHSE) + /* Enable External High-Speed Clock (HSE) */ + + regval = getreg32(STM32L4_RCC_CR); + regval |= RCC_CR_HSEON; /* Enable HSE */ + putreg32(regval, STM32L4_RCC_CR); + + /* Wait until the HSE is ready (or until a timeout elapsed) */ + + for (timeout = HSERDY_TIMEOUT; timeout > 0; timeout--) + { + /* Check if the HSERDY flag is the set in the CR */ + + if ((getreg32(STM32L4_RCC_CR) & RCC_CR_HSERDY) != 0) + { + /* If so, then break-out with timeout > 0 */ + + break; + } + } +#else + +# error stm32l4_stdclockconfig(), must have one of STM32L4_BOARD_USEHSI, STM32L4_BOARD_USEMSI, STM32L4_BOARD_USEHSE defined + +#endif + + /* Check for a timeout. If this timeout occurs, then we are hosed. We + * have no real back-up plan, although the following logic makes it look + * as though we do. + */ + + if (timeout > 0) + { +#warning todo: regulator voltage according to clock freq +#if 0 + /* Ensure Power control is enabled before modifying it. */ + + regval = getreg32(STM32L4_RCC_APB1ENR); + regval |= RCC_APB1ENR_PWREN; + putreg32(regval, STM32L4_RCC_APB1ENR); + + /* Select regulator voltage output Scale 1 mode to support system + * frequencies up to 168 MHz. + */ + + regval = getreg32(STM32L4_PWR_CR); + regval &= ~PWR_CR_VOS_MASK; + regval |= PWR_CR_VOS_SCALE_1; + putreg32(regval, STM32L4_PWR_CR); +#endif + + /* Set the HCLK source/divider */ + + regval = getreg32(STM32L4_RCC_CFGR); + regval &= ~RCC_CFGR_HPRE_MASK; + regval |= STM32L4_RCC_CFGR_HPRE; + putreg32(regval, STM32L4_RCC_CFGR); + + /* Set the PCLK2 divider */ + + regval = getreg32(STM32L4_RCC_CFGR); + regval &= ~RCC_CFGR_PPRE2_MASK; + regval |= STM32L4_RCC_CFGR_PPRE2; + putreg32(regval, STM32L4_RCC_CFGR); + + /* Set the PCLK1 divider */ + + regval = getreg32(STM32L4_RCC_CFGR); + regval &= ~RCC_CFGR_PPRE1_MASK; + regval |= STM32L4_RCC_CFGR_PPRE1; + putreg32(regval, STM32L4_RCC_CFGR); + +#ifdef CONFIG_RTC_HSECLOCK + /* Set the RTC clock divisor */ + + regval = getreg32(STM32L4_RCC_CFGR); + regval &= ~RCC_CFGR_RTCPRE_MASK; + regval |= RCC_CFGR_RTCPRE(HSE_DIVISOR); + putreg32(regval, STM32L4_RCC_CFGR); +#endif + + /* Set the PLL source and main divider */ + + regval = getreg32(STM32L4_RCC_PLLCFG); + + /* Configure Main PLL */ + + /* Set the PLL dividers and multipliers to configure the main PLL */ + + regval = (STM32L4_PLLCFG_PLLM | STM32L4_PLLCFG_PLLN | STM32L4_PLLCFG_PLLP + | STM32L4_PLLCFG_PLLQ | STM32L4_PLLCFG_PLLR); + +#ifdef STM32L4_PLLCFG_PLLP_ENABLED + regval |= RCC_PLLCFG_PLLPEN; +#endif +#ifdef STM32L4_PLLCFG_PLLQ_ENABLED + regval |= RCC_PLLCFG_PLLQEN; +#endif +#ifdef STM32L4_PLLCFG_PLLR_ENABLED + regval |= RCC_PLLCFG_PLLREN; +#endif + + /* XXX The choice of clock source to PLL (all three) is independent + * of the sys clock source choice, review the STM32L4_BOARD_USEHSI + * name; probably split it into two, one for PLL source and one + * for sys clock source. + */ + +#ifdef STM32L4_BOARD_USEHSI + regval |= RCC_PLLCFG_PLLSRC_HSI; +#elif defined(STM32L4_BOARD_USEMSI) + regval |= RCC_PLLCFG_PLLSRC_MSI; +#else /* if STM32L4_BOARD_USEHSE */ + regval |= RCC_PLLCFG_PLLSRC_HSE; +#endif + + putreg32(regval, STM32L4_RCC_PLLCFG); + + /* Enable the main PLL */ + + regval = getreg32(STM32L4_RCC_CR); + regval |= RCC_CR_PLLON; + putreg32(regval, STM32L4_RCC_CR); + + /* Wait until the PLL is ready */ + + while ((getreg32(STM32L4_RCC_CR) & RCC_CR_PLLRDY) == 0) + { + } + +#ifdef CONFIG_STM32L4_SAI1PLL + /* Configure SAI1 PLL */ + + regval = getreg32(STM32L4_RCC_PLLSAI1CFG); + + /* Set the PLL dividers and multipliers to configure the SAI1 PLL */ + + regval = (STM32L4_PLLSAI1CFG_PLLN | STM32L4_PLLSAI1CFG_PLLP + | STM32L4_PLLSAI1CFG_PLLQ | STM32L4_PLLSAI1CFG_PLLR); + +#ifdef STM32L4_PLLSAI1CFG_PLLP_ENABLED + regval |= RCC_PLLSAI1CFG_PLLPEN; +#endif +#ifdef STM32L4_PLLSAI1CFG_PLLQ_ENABLED + regval |= RCC_PLLSAI1CFG_PLLQEN; +#endif +#ifdef STM32L4_PLLSAI1CFG_PLLR_ENABLED + regval |= RCC_PLLSAI1CFG_PLLREN; +#endif + + putreg32(regval, STM32L4_RCC_PLLSAI1CFG); + + /* Enable the SAI1 PLL */ + + regval = getreg32(STM32L4_RCC_CR); + regval |= RCC_CR_PLLSAI1ON; + putreg32(regval, STM32L4_RCC_CR); + + /* Wait until the PLL is ready */ + + while ((getreg32(STM32L4_RCC_CR) & RCC_CR_PLLSAI1RDY) == 0) + { + } +#endif + +#ifdef CONFIG_STM32L4_SAI2PLL + /* Configure SAI2 PLL */ + + regval = getreg32(STM32L4_RCC_PLLSAI2CFG); + + /* Set the PLL dividers and multipliers to configure the SAI2 PLL */ + + regval = (STM32L4_PLLSAI2CFG_PLLN | STM32L4_PLLSAI2CFG_PLLP | + STM32L4_PLLSAI2CFG_PLLR); + +#ifdef STM32L4_PLLSAI2CFG_PLLP_ENABLED + regval |= RCC_PLLSAI2CFG_PLLPEN; +#endif +#ifdef STM32L4_PLLSAI2CFG_PLLR_ENABLED + regval |= RCC_PLLSAI2CFG_PLLREN; +#endif + + putreg32(regval, STM32L4_RCC_PLLSAI2CFG); + + /* Enable the SAI2 PLL */ + + regval = getreg32(STM32L4_RCC_CR); + regval |= RCC_CR_PLLSAI2ON; + putreg32(regval, STM32L4_RCC_CR); + + /* Wait until the PLL is ready */ + + while ((getreg32(STM32L4_RCC_CR) & RCC_CR_PLLSAI2RDY) == 0) + { + } +#endif + + /* Enable FLASH prefetch, instruction cache, data cache, and 4 wait states */ + +#ifdef CONFIG_STM32L4_FLASH_PREFETCH + regval = (FLASH_ACR_LATENCY_4 | FLASH_ACR_ICEN | FLASH_ACR_DCEN | FLASH_ACR_PRFTEN); +#else + regval = (FLASH_ACR_LATENCY_4 | FLASH_ACR_ICEN | FLASH_ACR_DCEN); +#endif + putreg32(regval, STM32L4_FLASH_ACR); + + /* Select the main PLL as system clock source */ + + regval = getreg32(STM32L4_RCC_CFGR); + regval &= ~RCC_CFGR_SW_MASK; + regval |= RCC_CFGR_SW_PLL; + putreg32(regval, STM32L4_RCC_CFGR); + + /* Wait until the PLL source is used as the system clock source */ + + while ((getreg32(STM32L4_RCC_CFGR) & RCC_CFGR_SWS_MASK) != RCC_CFGR_SWS_PLL) + { + } + +#if defined(CONFIG_STM32L4_IWDG) || defined(CONFIG_RTC_LSICLOCK) + /* Low speed internal clock source LSI */ + + stm32l4_rcc_enablelsi(); +#endif + +#if defined(STM32L4_USE_LSE) + /* Low speed external clock source LSE + * + * TODO: There is another case where the LSE needs to + * be enabled: if the MCO1 pin selects LSE as source. + * XXX and other cases, like automatic trimming of MSI for USB use + */ + + /* ensure Power control is enabled since it is indirectly required + * to alter the LSE parameters. + */ + stm32l4_pwr_enableclk(true); + + /* XXX other LSE settings must be made before turning on the oscillator + * and we need to ensure it is first off before doing so. + */ + + /* Turn on the LSE oscillator + * XXX this will almost surely get moved since we also want to use + * this for automatically trimming MSI, etc. + */ + + stm32l4_rcc_enablelse(); + +# if defined(STM32L4_BOARD_USEMSI) + /* Now that LSE is up, auto trim the MSI */ + + regval = getreg32(STM32L4_RCC_CR); + regval |= RCC_CR_MSIPLLEN; + putreg32(regval, STM32L4_RCC_CR); +# endif +#endif + +#if defined(STM32L4_USE_CLK48) + /* XXX sanity if sdmmc1 or usb or rng, then we need to set the clk48 source + * and then we can also do away with STM32L4_USE_CLK48, and give better + * warning messages + * + * XXX sanity if our STM32L4_CLK48_SEL is YYY then we need to have already + * enabled ZZZ + */ + + regval = getreg32(STM32L4_RCC_CCIPR); + regval &= RCC_CCIPR_CLK48SEL_MASK; + regval |= STM32L4_CLK48_SEL; + putreg32(regval, STM32L4_RCC_CCIPR); +#endif + } +} +#endif + +/**************************************************************************** + * Name: rcc_enableperipherals + ****************************************************************************/ + +static inline void rcc_enableperipherals(void) +{ + rcc_enableahb1(); + rcc_enableahb2(); + rcc_enableahb3(); + rcc_enableapb1(); + rcc_enableapb2(); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ -- GitLab From 80c2d384bb511baf595785479ac17d66ac9b6b00 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Tue, 2 May 2017 15:21:06 +0300 Subject: [PATCH 702/990] STM32L4: flash: update override config macros and add FLASH_CONFIG_B --- arch/arm/src/stm32l4/stm32l4_flash.h | 80 +++++++++++++++++++--------- 1 file changed, 55 insertions(+), 25 deletions(-) diff --git a/arch/arm/src/stm32l4/stm32l4_flash.h b/arch/arm/src/stm32l4/stm32l4_flash.h index 96bd6135d9..c29a8d35a5 100644 --- a/arch/arm/src/stm32l4/stm32l4_flash.h +++ b/arch/arm/src/stm32l4/stm32l4_flash.h @@ -41,42 +41,72 @@ * Pre-processor Definitions ************************************************************************************/ +/* Flash size is known from the chip selection: + * + * When CONFIG_STM32L4_FLASH_OVERRIDE_DEFAULT is set the + * CONFIG_STM32L4_FLASH_CONFIG_x selects the default FLASH size based on the chip + * part number. This value can be overridden with CONFIG_STM32L4_FLASH_OVERRIDE_x + * + * Parts STM32L4xxE have 512Kb of FLASH + * Parts STM32L4xxG have 1024Kb of FLASH + * + * N.B. Only Single bank mode is supported + */ + #define _K(x) ((x)*1024) -#if !defined(CONFIG_STM32L4_FLASH_CONFIG_DEFAULT) && \ +#if !defined(CONFIG_STM32L4_FLASH_OVERRIDE_DEFAULT) && \ + !defined(CONFIG_STM32L4_FLASH_OVERRIDE_B) && \ + !defined(CONFIG_STM32L4_FLASH_OVERRIDE_C) && \ + !defined(CONFIG_STM32L4_FLASH_OVERRIDE_E) && \ + !defined(CONFIG_STM32L4_FLASH_OVERRIDE_G) && \ + !defined(CONFIG_STM32L4_FLASH_CONFIG_B) && \ !defined(CONFIG_STM32L4_FLASH_CONFIG_C) && \ !defined(CONFIG_STM32L4_FLASH_CONFIG_E) && \ !defined(CONFIG_STM32L4_FLASH_CONFIG_G) -# define CONFIG_STM32L4_FLASH_CONFIG_DEFAULT +# define CONFIG_STM32L4_FLASH_OVERRIDE_E +# warning "Flash size not defined defaulting to 512KiB (E)" #endif -#if defined(CONFIG_STM32L4_FLASH_CONFIG_DEFAULT) -# define STM32L4_FLASH_NPAGES 512 -# define STM32L4_FLASH_PAGESIZE 2048 -#endif /* CONFIG_STM32L4_FLASH_CONFIG_DEFAULT */ - -/* Override of the Flash Has been Chosen */ - -#if !defined(CONFIG_STM32L4_FLASH_CONFIG_DEFAULT) - -/* Define the Valid Configuration the F1 and F3 */ - -# if defined(CONFIG_STM32L4_FLASH_CONFIG_C) /* 256 kB */ -# define STM32L4_FLASH_NPAGES 128 -# define STM32L4_FLASH_PAGESIZE 2048 -# elif defined(CONFIG_STM32L4_FLASH_CONFIG_E) /* 512 kB */ -# define STM32L4_FLASH_NPAGES 256 -# define STM32L4_FLASH_PAGESIZE 2048 -# elif defined(CONFIG_STM32L4_FLASH_CONFIG_G) /* 1 MB */ -# define STM32L4_FLASH_NPAGES 512 -# define STM32L4_FLASH_PAGESIZE 2048 -# else +/* Override of the Flash has been chosen */ + +#if !defined(CONFIG_STM32L4_FLASH_OVERRIDE_DEFAULT) +# undef CONFIG_STM32L4_FLASH_CONFIG_B +# undef CONFIG_STM32L4_FLASH_CONFIG_C +# undef CONFIG_STM32L4_FLASH_CONFIG_E +# undef CONFIG_STM32L4_FLASH_CONFIG_G +# if defined(CONFIG_STM32L4_FLASH_OVERRIDE_B) +# define CONFIG_STM32L4_FLASH_CONFIG_B +# elif defined(CONFIG_STM32L4_FLASH_OVERRIDE_C) +# define CONFIG_STM32L4_FLASH_CONFIG_C +# elif defined(CONFIG_STM32L4_FLASH_OVERRIDE_E) +# define CONFIG_STM32L4_FLASH_CONFIG_E +# elif defined(CONFIG_STM32L4_FLASH_OVERRIDE_G) +# define CONFIG_STM32L4_FLASH_CONFIG_G # endif #endif +/* Define the valid configuration */ + +#if defined(CONFIG_STM32L4_FLASH_CONFIG_B) /* 128 kB */ +# define STM32L4_FLASH_NPAGES 64 +# define STM32L4_FLASH_PAGESIZE 2048 +#elif defined(CONFIG_STM32L4_FLASH_CONFIG_C) /* 256 kB */ +# define STM32L4_FLASH_NPAGES 128 +# define STM32L4_FLASH_PAGESIZE 2048 +#elif defined(CONFIG_STM32L4_FLASH_CONFIG_E) /* 512 kB */ +# define STM32L4_FLASH_NPAGES 256 +# define STM32L4_FLASH_PAGESIZE 2048 +#elif defined(CONFIG_STM32L4_FLASH_CONFIG_G) /* 1 MB */ +# define STM32L4_FLASH_NPAGES 512 +# define STM32L4_FLASH_PAGESIZE 2048 +#else +# error "unknown flash configuration!" +#endif + #ifdef STM32L4_FLASH_PAGESIZE # define STM32L4_FLASH_SIZE (STM32L4_FLASH_NPAGES * STM32L4_FLASH_PAGESIZE) -#endif /* def STM32L4_FLASH_PAGESIZE */ +#endif /* Register Offsets *****************************************************************/ @@ -128,7 +158,7 @@ # define FLASH_ACR_LATENCY_3 (3 << FLASH_ACR_LATENCY_SHIFT) /* 011: Three wait states <=64 <=26 */ # define FLASH_ACR_LATENCY_4 (4 << FLASH_ACR_LATENCY_SHIFT) /* 100: Four wait states <=80 <=26 */ -#define FLASH_ACR_PRFTEN (1 << 8) /* Bit 8: Pprefetch enable */ +#define FLASH_ACR_PRFTEN (1 << 8) /* Bit 8: Prefetch enable */ #define FLASH_ACR_ICEN (1 << 9) /* Bit 9: Instruction cache enable */ #define FLASH_ACR_DCEN (1 << 10) /* Bit 10: Data cache enable */ #define FLASH_ACR_ICRST (1 << 11) /* Bit 11: Instruction cache reset */ -- GitLab From 0ce7815efe39376f7fa06b4e0b8baf602e055427 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Thu, 4 May 2017 14:45:37 +0300 Subject: [PATCH 703/990] configs: add nucleo-l452re board files --- configs/Kconfig | 13 + configs/nucleo-l452re/Kconfig | 8 + configs/nucleo-l452re/README.txt | 271 ++++ configs/nucleo-l452re/include/board.h | 272 ++++ configs/nucleo-l452re/include/nucleo-l452re.h | 510 +++++++ configs/nucleo-l452re/nsh/Make.defs | 112 ++ configs/nucleo-l452re/nsh/defconfig | 1258 +++++++++++++++++ configs/nucleo-l452re/scripts/l452re-flash.ld | 119 ++ configs/nucleo-l452re/src/.gitignore | 2 + configs/nucleo-l452re/src/Makefile | 56 + configs/nucleo-l452re/src/nucleo-l452re.h | 149 ++ configs/nucleo-l452re/src/stm32_appinit.c | 87 ++ configs/nucleo-l452re/src/stm32_autoleds.c | 96 ++ configs/nucleo-l452re/src/stm32_boot.c | 94 ++ configs/nucleo-l452re/src/stm32_bringup.c | 117 ++ configs/nucleo-l452re/src/stm32_buttons.c | 128 ++ configs/nucleo-l452re/src/stm32_spi.c | 223 +++ configs/nucleo-l452re/src/stm32_userleds.c | 217 +++ 18 files changed, 3732 insertions(+) create mode 100644 configs/nucleo-l452re/Kconfig create mode 100644 configs/nucleo-l452re/README.txt create mode 100644 configs/nucleo-l452re/include/board.h create mode 100644 configs/nucleo-l452re/include/nucleo-l452re.h create mode 100644 configs/nucleo-l452re/nsh/Make.defs create mode 100644 configs/nucleo-l452re/nsh/defconfig create mode 100644 configs/nucleo-l452re/scripts/l452re-flash.ld create mode 100644 configs/nucleo-l452re/src/.gitignore create mode 100644 configs/nucleo-l452re/src/Makefile create mode 100644 configs/nucleo-l452re/src/nucleo-l452re.h create mode 100644 configs/nucleo-l452re/src/stm32_appinit.c create mode 100644 configs/nucleo-l452re/src/stm32_autoleds.c create mode 100644 configs/nucleo-l452re/src/stm32_boot.c create mode 100644 configs/nucleo-l452re/src/stm32_bringup.c create mode 100644 configs/nucleo-l452re/src/stm32_buttons.c create mode 100644 configs/nucleo-l452re/src/stm32_spi.c create mode 100644 configs/nucleo-l452re/src/stm32_userleds.c diff --git a/configs/Kconfig b/configs/Kconfig index 6daffc80e0..d61c7ef879 100644 --- a/configs/Kconfig +++ b/configs/Kconfig @@ -810,6 +810,15 @@ config ARCH_BOARD_NUCLEO_F411RE This is a minimal configuration that supports low-level test of the Nucleo F411RE in the NuttX source tree. +config ARCH_BOARD_NUCLEO_L452RE + bool "STM32L452 Nucleo L452RE" + depends on ARCH_CHIP_STM32L452RE + select ARCH_HAVE_LEDS + select ARCH_HAVE_BUTTONS + select ARCH_HAVE_IRQBUTTONS + ---help--- + STMicro Nucleo L452RE board based on the STMicro STM32L452RET6 MCU. + config ARCH_BOARD_NUCLEO_L476RG bool "STM32L476 Nucleo L476RG" depends on ARCH_CHIP_STM32L476RG @@ -1557,6 +1566,7 @@ config ARCH_BOARD default "nucleo-f303re" if ARCH_BOARD_NUCLEO_F303RE default "nucleo-f334r8" if ARCH_BOARD_NUCLEO_F334R8 default "nucleo-f4x1re" if ARCH_BOARD_NUCLEO_F401RE || ARCH_BOARD_NUCLEO_F411RE + default "nucleo-l452re" if ARCH_BOARD_NUCLEO_L452RE default "nucleo-l476rg" if ARCH_BOARD_NUCLEO_L476RG default "nucleo-l496zg" if ARCH_BOARD_NUCLEO_L496ZG default "qemu-i486" if ARCH_BOARD_QEMU_I486 @@ -1876,6 +1886,9 @@ endif if ARCH_BOARD_NUCLEO_F401RE || ARCH_BOARD_NUCLEO_F411RE source "configs/nucleo-f4x1re/Kconfig" endif +if ARCH_BOARD_NUCLEO_L452RE +source "configs/nucleo-l452re/Kconfig" +endif if ARCH_BOARD_NUCLEO_L476RG source "configs/nucleo-l476rg/Kconfig" endif diff --git a/configs/nucleo-l452re/Kconfig b/configs/nucleo-l452re/Kconfig new file mode 100644 index 0000000000..e0e29ca22c --- /dev/null +++ b/configs/nucleo-l452re/Kconfig @@ -0,0 +1,8 @@ +# +# For a description of the syntax of this configuration file, +# see the file kconfig-language.txt in the NuttX tools repository. +# + +if ARCH_BOARD_NUCLEO_L452RE + +endif diff --git a/configs/nucleo-l452re/README.txt b/configs/nucleo-l452re/README.txt new file mode 100644 index 0000000000..386c1ad8f7 --- /dev/null +++ b/configs/nucleo-l452re/README.txt @@ -0,0 +1,271 @@ +Nucleo-L452RE README +==================== + + This README file discusses the port of NuttX to the STMicro Nucleo-L452RE + board. That board features the STM32L452RET6 MCU with 512KiB of FLASH + and 160KiB of SRAM. + +Contents +======== + + - Status + - Nucleo-64 Boards + - LEDs + - Buttons + - Serial Console + - Configurations + +Status +====== + 2017-05-04: The board now boots and the basic NSH configurations works + without problem. + +Nucleo-64 Boards +================ + + The Nucleo-L452RE is a member of the Nucleo-64 board family. The Nucleo-64 + is a standard board for use with several STM32 parts in the LQFP64 package. + Variants including: + + Order code Targeted STM32 + ------------- -------------- + NUCLEO-F030R8 STM32F030R8T6 + NUCLEO-F070RB STM32F070RBT6 + NUCLEO-F072RB STM32F072RBT6 + NUCLEO-F091RC STM32F091RCT6 + NUCLEO-F103RB STM32F103RBT6 + NUCLEO-F302R8 STM32F302R8T6 + NUCLEO-F303RE STM32F303RET6 + NUCLEO-F334R8 STM32F334R8T6 + NUCLEO-F401RE STM32F401RET6 + NUCLEO-F410RB STM32F410RBT6 + NUCLEO-F411RE STM32F411RET6 + NUCLEO-F446RE STM32F446RET6 + NUCLEO-L053R8 STM32L053R8T6 + NUCLEO-L073RZ STM32L073RZT6 + NUCLEO-L152RE STM32L152RET6 + NUCLEO-L452RE STM32L452RET6 + NUCLEO-L476RG STM32L476RGT6 + +LEDs +==== + + The Nucleo-64 board has one user controlable LED, User LD2. This green + LED is a user LED connected to Arduino signal D13 corresponding to STM32 + I/O PA5 (PB13 on other some other Nucleo-64 boards). + + - When the I/O is HIGH value, the LED is on + - When the I/O is LOW, the LED is off + + These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is + defined. In that case, the usage by the board port is defined in + include/board.h and src/stm32_autoleds.c. The LEDs are used to encode + OS-related events as follows when the red LED (PE24) is available: + + SYMBOL Meaning LD2 + ------------------- ----------------------- ----------- + LED_STARTED NuttX has been started OFF + LED_HEAPALLOCATE Heap has been allocated OFF + LED_IRQSENABLED Interrupts enabled OFF + LED_STACKCREATED Idle stack created ON + LED_INIRQ In an interrupt No change + LED_SIGNAL In a signal handler No change + LED_ASSERTION An assertion failed No change + LED_PANIC The system has crashed Blinking + LED_IDLE MCU is is sleep mode Not used + + Thus if LD2, NuttX has successfully booted and is, apparently, running + normally. If LD2 is flashing at approximately 2Hz, then a fatal error + has been detected and the system has halted. + +Buttons +======= + + B1 USER: the user button is connected to the I/O PC13 (pin 2) of the STM32 + microcontroller. + +Serial Console +============== + + USART1 + ------ + Pins and Connectors: + + RXD: PA10 D3 CN9 pin 3, CN10 pin 33 + PB7 CN7 pin 21 + TXD: PA9 D8 CN5 pin 1, CN10 pin 21 + PB6 D10 CN5 pin 3, CN10 pin 17 + + NOTE: You may need to edit the include/board.h to select different USART1 + pin selections. + + TTL to RS-232 converter connection: + + Nucleo CN10 STM32F072RB + ----------- ------------ + Pin 21 PA9 USART1_TX *Warning you make need to reverse RX/TX on + Pin 33 PA10 USART1_RX some RS-232 converters + Pin 20 GND + Pin 8 U5V + + To configure USART1 as the console: + + CONFIG_STM32_USART1=y + CONFIG_USART1_SERIALDRIVER=y + CONFIG_USART1_SERIAL_CONSOLE=y + CONFIG_USART1_RXBUFSIZE=256 + CONFIG_USART1_TXBUFSIZE=256 + CONFIG_USART1_BAUD=115200 + CONFIG_USART1_BITS=8 + CONFIG_USART1_PARITY=0 + CONFIG_USART1_2STOP=0 + + USART2 + ------ + Pins and Connectors: + + RXD: PA3 To be provided + PA15 + PD6 + TXD: PA2 + PA14 + PD5 + + See "Virtual COM Port" and "RS-232 Shield" below. + + USART3 + ------ + Pins and Connectors: + + RXD: PB11 To be provided + PC5 + PC11 + D9 + TXD: PB10 + PC4 + PC10 + D8 + + USART3 + ------ + Pins and Connectors: + + RXD: PA1 To be provided + PC11 + TXD: PA0 + PC10 + + Virtual COM Port + ---------------- + Yet another option is to use UART2 and the USB virtual COM port. This + option may be more convenient for long term development, but is painful + to use during board bring-up. + + Solder Bridges. This configuration requires: + + - SB62 and SB63 Open: PA2 and PA3 on STM32 MCU are disconnected to D1 + and D0 (pin 7 and pin 8) on Arduino connector CN9 and ST Morpho + connector CN10. + + - SB13 and SB14 Closed: PA2 and PA3 on STM32F103C8T6 (ST-LINK MCU) are + connected to PA3 and PA2 on STM32 MCU to have USART communication + between them. Thus SB61, SB62 and SB63 should be OFF. + + Configuring USART2 is the same as given above. + + 115200 8N1 BAUD should be configure to interface with the Virtual COM + port. + + Default + ------- + As shipped, SB62 and SB63 are open and SB13 and SB14 closed, so the + virtual COM port is enabled. + + RS-232 Shield + ------------- + Supports a single RS-232 connected via + + Nucleo STM32F4x1RE Shield + --------- --------------- -------- + CN9 Pin 1 PA3 USART2_RXD RXD + CN9 Pin 2 PA2 USART2_TXD TXD + + Support for this shield is enabled by selecting USART2 and configuring + SB13, 14, 62, and 63 as described above under "Virtual COM Port" + +Configurations +============== + + Information Common to All Configurations + ---------------------------------------- + Each configuration is maintained in a sub-directory and can be + selected as follow: + + cd tools + ./configure.sh nucleo-l452re/ + cd - + + Before building, make sure the PATH environment variable includes the + correct path to the directory than holds your toolchain binaries. + + And then build NuttX by simply typing the following. At the conclusion of + the make, the nuttx binary will reside in an ELF file called, simply, nuttx. + + make oldconfig + make + + The that is provided above as an argument to the tools/configure.sh + must be is one of the following. + + NOTES: + + 1. These configurations use the mconf-based configuration tool. To + change any of these configurations using that tool, you should: + + a. Build and install the kconfig-mconf tool. See nuttx/README.txt + see additional README.txt files in the NuttX tools repository. + + b. Execute 'make menuconfig' in nuttx/ in order to start the + reconfiguration process. + + 2. Unless stated otherwise, all configurations generate console + output on USART2, as described above under "Serial Console". The + elevant configuration settings are listed below: + + CONFIG_STM32_USART2=y + CONFIG_STM32_USART2_SERIALDRIVER=y + CONFIG_STM32_USART=y + + CONFIG_USART2_SERIALDRIVER=y + CONFIG_USART2_SERIAL_CONSOLE=y + + CONFIG_USART2_RXBUFSIZE=256 + CONFIG_USART2_TXBUFSIZE=256 + CONFIG_USART2_BAUD=115200 + CONFIG_USART2_BITS=8 + CONFIG_USART2_PARITY=0 + CONFIG_USART2_2STOP=0 + + 3. All of these configurations are set up to build under Linux using the + "GNU Tools for ARM Embedded Processors" that is maintained by ARM + (unless stated otherwise in the description of the configuration). + + https://launchpad.net/gcc-arm-embedded + + That toolchain selection can easily be reconfigured using + 'make menuconfig'. Here are the relevant current settings: + + Build Setup: + CONFIG_HOST_LINUX=y : Linux environment + + System Type -> Toolchain: + CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL=y : GNU ARM EABI toolchain + + Configuration sub-directories + ----------------------------- + + nsh: + + Configures the NuttShell (nsh) located at examples/nsh. This + configuration is focused on low level, command-line driver testing. + diff --git a/configs/nucleo-l452re/include/board.h b/configs/nucleo-l452re/include/board.h new file mode 100644 index 0000000000..30e452dca7 --- /dev/null +++ b/configs/nucleo-l452re/include/board.h @@ -0,0 +1,272 @@ +/************************************************************************************ + * configs/nucleo-l452re/include/board.h + * + * Copyright (C) 2016 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. + * + ************************************************************************************/ + +#ifndef __CONFIGS_NUCLEO_L452RE_INCLUDE_BOARD_H +#define __CONFIGS_NUCLEO_L452RE_INCLUDE_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#ifndef __ASSEMBLY__ +# include +#endif + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ + +#if defined(CONFIG_ARCH_CHIP_STM32L452RE) +# include +#endif + +/* DMA Channel/Stream Selections ****************************************************/ +/* Stream selections are arbitrary for now but might become important in the future + * is we set aside more DMA channels/streams. + */ + +/* Values defined in arch/arm/src/stm32l4/chip/stm32l4x3xx_dma.h */ + +#define DMACHAN_SDMMC DMACHAN_SDMMC_1 /* 2 choices */ + +#define DMACHAN_SPI1_RX DMACHAN_SPI1_RX_1 /* 2 choices */ +#define DMACHAN_SPI1_TX DMACHAN_SPI1_TX_1 /* 2 choices */ + +/* UART RX DMA configurations */ + +#define DMACHAN_USART1_RX DMACHAN_USART1_RX_2 + +/* Alternate function pin selections ************************************************/ + +/* USART1: + * RXD: PA10 CN9 pin 3, CN10 pin 33 + * PB7 CN7 pin 21 + * TXD: PA9 CN5 pin 1, CN10 pin 21 + * PB6 CN5 pin 3, CN10 pin 17 + */ + +#if 1 +# define GPIO_USART1_RX GPIO_USART1_RX_1 /* PA10 */ +# define GPIO_USART1_TX GPIO_USART1_TX_1 /* PA9 */ +#else +# define GPIO_USART1_RX GPIO_USART1_RX_2 /* PB7 */ +# define GPIO_USART1_TX GPIO_USART1_TX_2 /* PB6 */ +#endif + +/* USART2: Connected to STLink Debug via PA2, PA3 + * RXD: PA3 CN9 pin 1 (See SB13, 14, 62, 63). CN10 pin 37 + * PD6 + * TXD: PA2 CN9 pin 2 (See SB13, 14, 62, 63). CN10 pin 35 + * PD5 + */ + +#define GPIO_USART2_RX GPIO_USART2_RX_1 /* PA3 */ +#define GPIO_USART2_TX GPIO_USART2_TX_1 /* PA2 */ +#define GPIO_USART2_RTS GPIO_USART2_RTS_2 +#define GPIO_USART2_CTS GPIO_USART2_CTS_2 + +#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PC11 */ +#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PC10 */ + +#define GPIO_UART4_RX GPIO_UART4_RX_1 /* PA1 */ +#define GPIO_UART4_TX GPIO_UART4_TX_1 /* PA0 */ + +/* I2C + * + * The optional _GPIO configurations allow the I2C driver to manually + * reset the bus to clear stuck slaves. They match the pin configuration, + * but are normally-high GPIOs. + */ + +#define GPIO_I2C1_SCL \ + (GPIO_I2C1_SCL_2 | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET) +#define GPIO_I2C1_SDA \ + (GPIO_I2C1_SDA_2 | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET) +#define GPIO_I2C1_SCL_GPIO \ + (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | \ + GPIO_PORTB | GPIO_PIN8) +#define GPIO_I2C1_SDA_GPIO \ + (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | \ + GPIO_PORTB | GPIO_PIN9) + +#define GPIO_I2C2_SCL \ + (GPIO_I2C2_SCL_1 | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET) +#define GPIO_I2C2_SDA \ + (GPIO_I2C2_SDA_1 | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET) +#define GPIO_I2C2_SCL_GPIO \ + (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | \ + GPIO_PORTB | GPIO_PIN10) +#define GPIO_I2C2_SDA_GPIO \ + (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | \ + GPIO_PORTB | GPIO_PIN11) + +/* SPI */ + +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 +#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1 + +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1 +#define GPIO_SPI2_SCK GPIO_SPI2_SCK_2 + +/* LEDs + * + * The Nucleo L452RE board provides a single user LED, LD2. LD2 + * is the green LED connected to Arduino signal D13 corresponding to MCU I/O + * PA5 (pin 21) or PB13 (pin 34) depending on the STM32 target. + * + * - When the I/O is HIGH value, the LED is on. + * - When the I/O is LOW, the LED is off. + */ + +/* LED index values for use with board_userled() */ + +#define BOARD_LD2 0 +#define BOARD_NLEDS 1 + +/* LED bits for use with board_userled_all() */ + +#define BOARD_LD2_BIT (1 << BOARD_LD2) + +/* These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is + * defined. In that case, the usage by the board port is defined in + * include/board.h and src/stm32_autoleds.c. The LEDs are used to encode + * OS-related events as follows when the red LED (PE24) is available: + * + * SYMBOL Meaning LD2 + * ------------------- ----------------------- ----------- + * LED_STARTED NuttX has been started OFF + * LED_HEAPALLOCATE Heap has been allocated OFF + * LED_IRQSENABLED Interrupts enabled OFF + * LED_STACKCREATED Idle stack created ON + * LED_INIRQ In an interrupt No change + * LED_SIGNAL In a signal handler No change + * LED_ASSERTION An assertion failed No change + * LED_PANIC The system has crashed Blinking + * LED_IDLE MCU is is sleep mode Not used + * + * Thus if LD2, NuttX has successfully booted and is, apparently, running + * normally. If LD2 is flashing at approximately 2Hz, then a fatal error + * has been detected and the system has halted. + */ + +#define LED_STARTED 0 +#define LED_HEAPALLOCATE 0 +#define LED_IRQSENABLED 0 +#define LED_STACKCREATED 1 +#define LED_INIRQ 1 +#define LED_SIGNAL 2 +#define LED_ASSERTION 2 +#define LED_PANIC 1 + +/* Buttons + * + * B1 USER: the user button is connected to the I/O PC13 (pin 2) of the STM32 + * microcontroller. + */ + +#define BUTTON_USER 0 +#define NUM_BUTTONS 1 + +#define BUTTON_USER_BIT (1 << BUTTON_USER) + +/* Quadrature encoder + * Default is to use timer 5 (32-bit) and encoder on PA0/PA1 + */ + +#define GPIO_TIM2_CH1IN GPIO_TIM2_CH1IN_1 +#define GPIO_TIM2_CH2IN GPIO_TIM2_CH2IN_1 + +#define GPIO_TIM3_CH1IN GPIO_TIM3_CH1IN_3 +#define GPIO_TIM3_CH2IN GPIO_TIM3_CH2IN_3 + +#define GPIO_TIM5_CH1IN GPIO_TIM5_CH1IN_1 +#define GPIO_TIM5_CH2IN GPIO_TIM5_CH2IN_1 + +/* PWM output for full bridge, uses config 1, because port E is N/A on QFP64 + * CH1 | 1(A8) 2(E9) + * CH2 | 1(A9) 2(E11) + * CHN1 | 1(A7) 2(B13) 3(E8) + * CHN2 | 1(B0) 2(B14) 3(E10) + */ + +#define GPIO_TIM1_CH1OUT GPIO_TIM1_CH1OUT_1 +#define GPIO_TIM1_CH1NOUT GPIO_TIM1_CH1N_1 +#define GPIO_TIM1_CH2OUT GPIO_TIM1_CH2OUT_1 +#define GPIO_TIM1_CH2NOUT GPIO_TIM1_CH2N_1 + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ +/************************************************************************************ + * Name: stm32l4_boardinitialize + * + * Description: + * All STM32L4 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +void stm32l4_boardinitialize(void); + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __CONFIGS_NUCLEO_L452RE_INCLUDE_BOARD_H */ diff --git a/configs/nucleo-l452re/include/nucleo-l452re.h b/configs/nucleo-l452re/include/nucleo-l452re.h new file mode 100644 index 0000000000..0074a64d9b --- /dev/null +++ b/configs/nucleo-l452re/include/nucleo-l452re.h @@ -0,0 +1,510 @@ +/************************************************************************************ + * configs/nucleo-l452re/include/nucleo-l452re.h + * + * Copyright (C) 2016 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. + * + ************************************************************************************/ + +#ifndef __CONFIGS_NUCLEO_L452RE_INCLUDE_NUCLEO_L452RE_H +#define __CONFIGS_NUCLEO_L452RE_INCLUDE_NUCLEO_L452RE_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#ifndef __ASSEMBLY__ +# include +#endif + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +#if 1 +# define HSI_CLOCK_CONFIG /* HSI-16 clock configuration */ +#elif 0 +/* Make sure you installed one! */ + +# define HSE_CLOCK_CONFIG /* HSE with 8 MHz xtal */ +#else +# define MSI_CLOCK_CONFIG /* MSI @ 4 MHz autotrimmed via LSE */ +#endif + +/* Clocking *************************************************************************/ + +#if defined(HSI_CLOCK_CONFIG) +/* The NUCLEOL452RE supports both HSE and LSE crystals (X2 and X3). However, as + * shipped, the X3 crystal is not populated. Therefore the Nucleo-L452RE + * will need to run off the 16MHz HSI clock, or the 32khz-synced MSI. + * + * System Clock source : PLL (HSI) + * SYSCLK(Hz) : 80000000 Determined by PLL configuration + * HCLK(Hz) : 80000000 (STM32L4_RCC_CFGR_HPRE) (Max 80 MHz) + * AHB Prescaler : 1 (STM32L4_RCC_CFGR_HPRE) (Max 80 MHz) + * APB1 Prescaler : 1 (STM32L4_RCC_CFGR_PPRE1) (Max 80 MHz) + * APB2 Prescaler : 1 (STM32L4_RCC_CFGR_PPRE2) (Max 80 MHz) + * HSI Frequency(Hz) : 16000000 (nominal) + * PLLM : 1 (STM32L4_PLLCFG_PLLM) + * PLLN : 10 (STM32L4_PLLCFG_PLLN) + * PLLP : 0 (STM32L4_PLLCFG_PLLP) + * PLLQ : 0 (STM32L4_PLLCFG_PLLQ) + * PLLR : 2 (STM32L4_PLLCFG_PLLR) + * PLLSAI1N : 12 + * PLLSAI1Q : 4 + * Flash Latency(WS) : 4 + * Prefetch Buffer : OFF + * 48MHz for USB OTG FS, : Doable if required using PLLSAI1 or MSI + * SDIO and RNG clock + */ + +/* HSI - 16 MHz RC factory-trimmed + * LSI - 32 KHz RC + * MSI - variable up to 48 MHz, synchronized to LSE + * HSE - not installed + * LSE - 32.768 kHz installed + */ + +#define STM32L4_HSI_FREQUENCY 16000000ul +#define STM32L4_LSI_FREQUENCY 32000 +#define STM32L4_LSE_FREQUENCY 32768 + +#define STM32L4_BOARD_USEHSI 1 + +/* XXX sysclk mux = pllclk */ + +/* XXX pll source mux = hsi */ + +/* REVISIT: Trimming of the HSI and MSI is not yet supported. */ + +/* Main PLL Configuration. + * + * Formulae: + * + * VCO input frequency = PLL input clock frequency / PLLM, 1 <= PLLM <= 8 + * VCO output frequency = VCO input frequency × PLLN, 8 <= PLLN <= 86, frequency range 64 to 344 MHz + * PLL output P (SAI3) clock frequency = VCO frequency / PLLP, PLLP = 7, or 17, or 0 to disable + * PLL output Q (48M1) clock frequency = VCO frequency / PLLQ, PLLQ = 2, 4, 6, or 8, or 0 to disable + * PLL output R (CLK) clock frequency = VCO frequency / PLLR, PLLR = 2, 4, 6, or 8, or 0 to disable + * + * PLL output P is used for SAI + * PLL output Q is used for OTG FS, SDMMC, RNG + * PLL output R is used for SYSCLK + * PLLP = 0 (not used) + * PLLQ = 0 (not used) + * PLLR = 2 + * PLLN = 10 + * PLLM = 1 + * + * We will configure like this + * + * PLL source is HSI + * + * PLL_REF = STM32L4_HSI_FREQUENCY / PLLM + * = 16,000,000 / 1 + * = 16,000,000 + * + * PLL_VCO = PLL_REF * PLLN + * = 16,000,000 * 10 + * = 160,000,000 + * + * PLL_CLK = PLL_VCO / PLLR + * = 160,000,000 / 2 = 80,000,000 + * PLL_48M1 = disabled + * PLL_SAI3 = disabled + * + * ---------------------------------------- + * + * PLLSAI1 Configuration + * + * The clock input and M divider are identical to the main PLL. + * However the multiplier and postscalers are independent. + * The PLLSAI1 is configured only if CONFIG_STM32L4_SAI1PLL is defined + * + * SAI1VCO input frequency = PLL input clock frequency + * SAI1VCO output frequency = SAI1VCO input frequency × PLLSAI1N, 8 <= PLLSAI1N <= 86, frequency range 64 to 344 MHz + * SAI1PLL output P (SAI1) clock frequency = SAI1VCO frequency / PLLSAI1P, PLLP = 7, or 17, or 0 to disable + * SAI1PLL output Q (48M2) clock frequency = SAI1VCO frequency / PLLSAI1Q, PLLQ = 2, 4, 6, or 8, or 0 to disable + * SAI1PLL output R (ADC1) clock frequency = SAI1VCO frequency / PLLSAI1R, PLLR = 2, 4, 6, or 8, or 0 to disable + * + * We will configure like this + * + * PLLSAI1 disabled + * + * ---------------------------------------- + * + * PLLSAI2 Configuration + * + * The clock input and M divider are identical to the main PLL. + * However the multiplier and postscalers are independent. + * The PLLSAI2 is configured only if CONFIG_STM32L4_SAI2PLL is defined + * + * SAI2VCO input frequency = PLL input clock frequency + * SAI2VCO output frequency = SAI2VCO input frequency × PLLSAI2N, 8 <= PLLSAI1N <= 86, frequency range 64 to 344 MHz + * SAI2PLL output P (SAI2) clock frequency = SAI2VCO frequency / PLLSAI2P, PLLP = 7, or 17, or 0 to disable + * SAI2PLL output R (ADC2) clock frequency = SAI2VCO frequency / PLLSAI2R, PLLR = 2, 4, 6, or 8, or 0 to disable + * + * We will configure like this + * + * PLLSAI2 disabled + * + * ---------------------------------------- + * + * TODO: The STM32L is a low power peripheral and all these clocks should be configurable at runtime. + * + * ---------------------------------------- + * + * TODO These clock sources can be configured in Kconfig (this is not a board feature) + * USART1 + * USART2 + * USART3 + * UART4 + * UART5 + * LPUART1 + * I2C1 + * I2C2 + * I2C3 + * LPTIM1 + * LPTIM2 + * SAI1 + * SAI2 + * CLK48 + * ADC + * SWPMI + * DFSDM + */ + +/* prescaler common to all PLL inputs; will be 1 (XXX source is implicitly + as per comment above HSI) */ + +#define STM32L4_PLLCFG_PLLM RCC_PLLCFG_PLLM(1) + +/* 'main' PLL config; we use this to generate our system clock via the R + * output. We set it up as 16 MHz / 1 * 10 / 2 = 80 MHz + * + * XXX NOTE: currently the main PLL is implicitly turned on and is implicitly + * the system clock; this should be configurable since not all applications may + * want things done this way. + */ + +#define STM32L4_PLLCFG_PLLN RCC_PLLCFG_PLLN(10) +#define STM32L4_PLLCFG_PLLP 0 +#undef STM32L4_PLLCFG_PLLP_ENABLED +#define STM32L4_PLLCFG_PLLQ RCC_PLLCFG_PLLQ_2 +#define STM32L4_PLLCFG_PLLQ_ENABLED +#define STM32L4_PLLCFG_PLLR RCC_PLLCFG_PLLR(2) +#define STM32L4_PLLCFG_PLLR_ENABLED + +/* 'SAIPLL1' is used to generate the 48 MHz clock, since we can't + * do that with the main PLL's N value. We set N = 12, and enable + * the Q output (ultimately for CLK48) with /4. So, + * 16 MHz / 1 * 12 / 4 = 48 MHz + * + * XXX NOTE: currently the SAIPLL /must/ be explicitly selected in the + * menuconfig, or else all this is a moot point, and the various 48 MHz + * peripherals will not work (RNG at present). I would suggest removing + * that option from Kconfig altogether, and simply making it an option + * that is selected via a #define here, like all these other params. + */ + +#define STM32L4_PLLSAI1CFG_PLLN RCC_PLLSAI1CFG_PLLN(12) +#define STM32L4_PLLSAI1CFG_PLLP 0 +#undef STM32L4_PLLSAI1CFG_PLLP_ENABLED +#define STM32L4_PLLSAI1CFG_PLLQ RCC_PLLSAI1CFG_PLLQ_4 +#define STM32L4_PLLSAI1CFG_PLLQ_ENABLED +#define STM32L4_PLLSAI1CFG_PLLR 0 +#undef STM32L4_PLLSAI1CFG_PLLR_ENABLED + +/* 'SAIPLL2' is not used in this application */ + +#define STM32L4_PLLSAI2CFG_PLLN RCC_PLLSAI2CFG_PLLN(8) +#define STM32L4_PLLSAI2CFG_PLLP 0 +#undef STM32L4_PLLSAI2CFG_PLLP_ENABLED +#define STM32L4_PLLSAI2CFG_PLLR 0 +#undef STM32L4_PLLSAI2CFG_PLLR_ENABLED + +#define STM32L4_SYSCLK_FREQUENCY 80000000ul + +/* CLK48 will come from PLLSAI1 (implicitly Q) */ + +#define STM32L4_USE_CLK48 +#define STM32L4_CLK48_SEL RCC_CCIPR_CLK48SEL_PLLSAI1 + +/* enable the LSE oscillator, used automatically trim the MSI, and for RTC */ + +#define STM32L4_USE_LSE 1 + +/* AHB clock (HCLK) is SYSCLK (80MHz) */ + +#define STM32L4_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */ +#define STM32L4_HCLK_FREQUENCY STM32L4_SYSCLK_FREQUENCY +#define STM32L4_BOARD_HCLK STM32L4_HCLK_FREQUENCY /* Same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/1 (80MHz) */ + +#define STM32L4_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLK /* PCLK1 = HCLK / 1 */ +#define STM32L4_PCLK1_FREQUENCY (STM32L4_HCLK_FREQUENCY/1) + +/* Timers driven from APB1 will be twice PCLK1 */ +/* REVISIT : this can be configured */ + +#define STM32L4_APB1_TIM2_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM3_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM4_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM5_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM6_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM7_CLKIN (2*STM32L4_PCLK1_FREQUENCY) + +/* APB2 clock (PCLK2) is HCLK (80MHz) */ + +#define STM32L4_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK /* PCLK2 = HCLK / 1 */ +#define STM32L4_PCLK2_FREQUENCY (STM32L4_HCLK_FREQUENCY/1) + +/* Timers driven from APB2 will be twice PCLK2 */ +/* REVISIT : this can be configured */ + +#define STM32L4_APB2_TIM1_CLKIN (2*STM32L4_PCLK2_FREQUENCY) +#define STM32L4_APB2_TIM8_CLKIN (2*STM32L4_PCLK2_FREQUENCY) + +/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx + * otherwise frequency is 2xAPBx. + * Note: TIM1,8 are on APB2, others on APB1 + */ +/* REVISIT : this can be configured */ + +/* TODO SDMMC */ + +#elif defined(HSE_CLOCK_CONFIG) + +/* Use the HSE */ + +#define STM32L4_BOARD_USEHSE 1 + +/* XXX sysclk mux = pllclk */ + +/* XXX pll source mux = hse */ + +/* Prescaler common to all PLL inputs */ + +#define STM32L4_PLLCFG_PLLM RCC_PLLCFG_PLLM(1) + +/* 'main' PLL config; we use this to generate our system clock */ + +#define STM32L4_PLLCFG_PLLN RCC_PLLCFG_PLLN(20) +#define STM32L4_PLLCFG_PLLP 0 +#undef STM32L4_PLLCFG_PLLP_ENABLED +#define STM32L4_PLLCFG_PLLQ 0 +#undef STM32L4_PLLCFG_PLLQ_ENABLED +#define STM32L4_PLLCFG_PLLR RCC_PLLCFG_PLLR_2 +#define STM32L4_PLLCFG_PLLR_ENABLED + +/* 'SAIPLL1' is used to generate the 48 MHz clock */ + +#define STM32L4_PLLSAI1CFG_PLLN RCC_PLLSAI1CFG_PLLN(12) +#define STM32L4_PLLSAI1CFG_PLLP 0 +#undef STM32L4_PLLSAI1CFG_PLLP_ENABLED +#define STM32L4_PLLSAI1CFG_PLLQ RCC_PLLSAI1CFG_PLLQ_2 +#define STM32L4_PLLSAI1CFG_PLLQ_ENABLED +#define STM32L4_PLLSAI1CFG_PLLR 0 +#undef STM32L4_PLLSAI1CFG_PLLR_ENABLED + +/* 'SAIPLL2' is not used in this application */ + +#define STM32L4_PLLSAI2CFG_PLLN RCC_PLLSAI2CFG_PLLN(8) +#define STM32L4_PLLSAI2CFG_PLLP 0 +#undef STM32L4_PLLSAI2CFG_PLLP_ENABLED +#define STM32L4_PLLSAI2CFG_PLLR 0 +#undef STM32L4_PLLSAI2CFG_PLLR_ENABLED + +#define STM32L4_SYSCLK_FREQUENCY 80000000ul + +/* Enable CLK48; get it from PLLSAI1 */ + +#define STM32L4_USE_CLK48 +#define STM32L4_CLK48_SEL RCC_CCIPR_CLK48SEL_PLLSAI1 + +/* Enable LSE (for the RTC) */ + +#define STM32L4_USE_LSE 1 + +/* Configure the HCLK divisor (for the AHB bus, core, memory, and DMA */ + +#define STM32L4_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */ +#define STM32L4_HCLK_FREQUENCY STM32L4_SYSCLK_FREQUENCY +#define STM32L4_BOARD_HCLK STM32L4_HCLK_FREQUENCY /* Same as above, to satisfy compiler */ + +/* Configure the APB1 prescaler */ + +#define STM32L4_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLK /* PCLK1 = HCLK / 1 */ +#define STM32L4_PCLK1_FREQUENCY (STM32L4_HCLK_FREQUENCY/1) + +#define STM32L4_APB1_TIM2_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM3_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM4_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM5_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM6_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM7_CLKIN (2*STM32L4_PCLK1_FREQUENCY) + +/* Configure the APB2 prescaler */ + +#define STM32L4_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK /* PCLK2 = HCLK / 1 */ +#define STM32L4_PCLK2_FREQUENCY (STM32L4_HCLK_FREQUENCY/1) + +#define STM32L4_APB2_TIM1_CLKIN (2*STM32L4_PCLK2_FREQUENCY) +#define STM32L4_APB2_TIM8_CLKIN (2*STM32L4_PCLK2_FREQUENCY) + +#elif defined(MSI_CLOCK_CONFIG) + +/* Use the MSI; frequ = 4 MHz; autotrim from LSE */ + +#define STM32L4_BOARD_USEMSI 1 +#define STM32L4_BOARD_MSIRANGE RCC_CR_MSIRANGE_4M + +/* XXX sysclk mux = pllclk */ + +/* XXX pll source mux = msi */ + +/* prescaler common to all PLL inputs */ + +#define STM32L4_PLLCFG_PLLM RCC_PLLCFG_PLLM(1) + +/* 'main' PLL config; we use this to generate our system clock */ + +#define STM32L4_PLLCFG_PLLN RCC_PLLCFG_PLLN(40) +#define STM32L4_PLLCFG_PLLP 0 +#undef STM32L4_PLLCFG_PLLP_ENABLED +#define STM32L4_PLLCFG_PLLQ 0 +#undef STM32L4_PLLCFG_PLLQ_ENABLED +#define STM32L4_PLLCFG_PLLR RCC_PLLCFG_PLLR_2 +#define STM32L4_PLLCFG_PLLR_ENABLED + +/* 'SAIPLL1' is used to generate the 48 MHz clock */ + +#define STM32L4_PLLSAI1CFG_PLLN RCC_PLLSAI1CFG_PLLN(24) +#define STM32L4_PLLSAI1CFG_PLLP 0 +#undef STM32L4_PLLSAI1CFG_PLLP_ENABLED +#define STM32L4_PLLSAI1CFG_PLLQ RCC_PLLSAI1CFG_PLLQ_2 +#define STM32L4_PLLSAI1CFG_PLLQ_ENABLED +#define STM32L4_PLLSAI1CFG_PLLR 0 +#undef STM32L4_PLLSAI1CFG_PLLR_ENABLED + +/* 'SAIPLL2' is not used in this application */ + +#define STM32L4_PLLSAI2CFG_PLLN RCC_PLLSAI2CFG_PLLN(8) +#define STM32L4_PLLSAI2CFG_PLLP 0 +#undef STM32L4_PLLSAI2CFG_PLLP_ENABLED +#define STM32L4_PLLSAI2CFG_PLLR 0 +#undef STM32L4_PLLSAI2CFG_PLLR_ENABLED + +#define STM32L4_SYSCLK_FREQUENCY 80000000ul + +/* Enable CLK48; get it from PLLSAI1 */ + +#define STM32L4_USE_CLK48 +#define STM32L4_CLK48_SEL RCC_CCIPR_CLK48SEL_PLLSAI1 + +/* Enable LSE (for the RTC) */ + +#define STM32L4_USE_LSE 1 + +/* Configure the HCLK divisor (for the AHB bus, core, memory, and DMA */ + +#define STM32L4_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */ +#define STM32L4_HCLK_FREQUENCY STM32L4_SYSCLK_FREQUENCY +#define STM32L4_BOARD_HCLK STM32L4_HCLK_FREQUENCY /* Same as above, to satisfy compiler */ + +/* Configure the APB1 prescaler */ + +#define STM32L4_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLK /* PCLK1 = HCLK / 1 */ +#define STM32L4_PCLK1_FREQUENCY (STM32L4_HCLK_FREQUENCY/1) + +#define STM32L4_APB1_TIM2_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM3_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM4_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM5_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM6_CLKIN (2*STM32L4_PCLK1_FREQUENCY) +#define STM32L4_APB1_TIM7_CLKIN (2*STM32L4_PCLK1_FREQUENCY) + +/* Configure the APB2 prescaler */ + +#define STM32L4_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK /* PCLK2 = HCLK / 1 */ +#define STM32L4_PCLK2_FREQUENCY (STM32L4_HCLK_FREQUENCY/1) + +#define STM32L4_APB2_TIM1_CLKIN (2*STM32L4_PCLK2_FREQUENCY) +#define STM32L4_APB2_TIM8_CLKIN (2*STM32L4_PCLK2_FREQUENCY) + +#endif + +/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx + * otherwise frequency is 2xAPBx. + * Note: TIM1,8,15,16,17 are on APB2, others on APB1 + */ + +#define BOARD_TIM1_FREQUENCY STM32L4_HCLK_FREQUENCY +#define BOARD_TIM2_FREQUENCY (STM32L4_HCLK_FREQUENCY / 2) +#define BOARD_TIM3_FREQUENCY (STM32L4_HCLK_FREQUENCY / 2) +#define BOARD_TIM4_FREQUENCY (STM32L4_HCLK_FREQUENCY / 2) +#define BOARD_TIM5_FREQUENCY (STM32L4_HCLK_FREQUENCY / 2) +#define BOARD_TIM6_FREQUENCY (STM32L4_HCLK_FREQUENCY / 2) +#define BOARD_TIM7_FREQUENCY (STM32L4_HCLK_FREQUENCY / 2) +#define BOARD_TIM8_FREQUENCY STM32L4_HCLK_FREQUENCY +#define BOARD_TIM15_FREQUENCY STM32L4_HCLK_FREQUENCY +#define BOARD_TIM16_FREQUENCY STM32L4_HCLK_FREQUENCY +#define BOARD_TIM17_FREQUENCY STM32L4_HCLK_FREQUENCY +#define BOARD_LPTIM1_FREQUENCY (STM32L4_HCLK_FREQUENCY / 2) +#define BOARD_LPTIM2_FREQUENCY (STM32L4_HCLK_FREQUENCY / 2) + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __CONFIGS_NUCLEO_L452RE_INCLUDE_NUCLEO_L452RE_H */ diff --git a/configs/nucleo-l452re/nsh/Make.defs b/configs/nucleo-l452re/nsh/Make.defs new file mode 100644 index 0000000000..39adcf7611 --- /dev/null +++ b/configs/nucleo-l452re/nsh/Make.defs @@ -0,0 +1,112 @@ +############################################################################ +# configs/nucleo-l452re/nsh/Make.defs +# +# Copyright (C) 2014 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. +# +############################################################################ + +include ${TOPDIR}/.config +include ${TOPDIR}/tools/Config.mk +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs + +LDSCRIPT = l452re-flash.ld + +ifeq ($(WINTOOL),y) + # Windows-native toolchains + DIRLINK = $(TOPDIR)/tools/copydir.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh + ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" + ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" +else + # Linux/Cygwin-native toolchain + MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT) + ARCHINCLUDES = -I. -isystem $(TOPDIR)/include + ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) +endif + +CC = $(CROSSDEV)gcc +CXX = $(CROSSDEV)g++ +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(ARCROSSDEV)ar rcs +NM = $(ARCROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump + +ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} +ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} + +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + ARCHOPTIMIZATION = -g +endif + +ifneq ($(CONFIG_DEBUG_NOOPT),y) + ARCHOPTIMIZATION += $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer +endif + +ARCHCFLAGS = -fno-builtin +ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fcheck-new -fno-rtti +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow -Wundef +ARCHWARNINGSXX = -Wall -Wshadow -Wundef +ARCHDEFINES = +ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 + +CFLAGS = $(ARCHCFLAGS) $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) +CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +NXFLATLDFLAGS1 = -r -d -warn-common +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections +LDNXFLATFLAGS = -e main -s 2048 + +ASMEXT = .S +OBJEXT = .o +LIBEXT = .a +EXEEXT = + +ifneq ($(CROSSDEV),arm-nuttx-elf-) + LDFLAGS += -nostartfiles -nodefaultlibs +endif +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + LDFLAGS += -g +endif + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -Wundef -g -pipe +HOSTLDFLAGS = + diff --git a/configs/nucleo-l452re/nsh/defconfig b/configs/nucleo-l452re/nsh/defconfig new file mode 100644 index 0000000000..5030287da0 --- /dev/null +++ b/configs/nucleo-l452re/nsh/defconfig @@ -0,0 +1,1258 @@ +# +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# + +# +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set +# CONFIG_DEFAULT_SMALL is not set +CONFIG_HOST_LINUX=y +# CONFIG_HOST_OSX is not set +# CONFIG_HOST_WINDOWS is not set +# CONFIG_HOST_OTHER is not set + +# +# Build Configuration +# +CONFIG_APPS_DIR="../apps" +CONFIG_BUILD_FLAT=y +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +# CONFIG_INTELHEX_BINARY is not set +# CONFIG_MOTOROLA_SREC is not set +CONFIG_RAW_BINARY=y +# CONFIG_UBOOT_UIMAGE is not set + +# +# Customize Header Files +# +# CONFIG_ARCH_STDINT_H is not set +# CONFIG_ARCH_STDBOOL_H is not set +# CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_FLOAT_H is not set +# CONFIG_ARCH_STDARG_H is not set +# CONFIG_ARCH_DEBUG_H is not set + +# +# Debug Options +# +CONFIG_DEBUG_ALERT=y +CONFIG_DEBUG_FEATURES=y + +# +# Debug SYSLOG Output Controls +# +CONFIG_DEBUG_ERROR=y +CONFIG_DEBUG_WARN=y +CONFIG_DEBUG_INFO=y +CONFIG_DEBUG_ASSERTIONS=y + +# +# Subsystem Debug Options +# +# CONFIG_DEBUG_BINFMT is not set +# CONFIG_DEBUG_FS is not set +# CONFIG_DEBUG_GRAPHICS is not set +# CONFIG_DEBUG_LIB is not set +# CONFIG_DEBUG_MM is not set +# CONFIG_DEBUG_SCHED is not set + +# +# OS Function Debug Options +# +# CONFIG_DEBUG_DMA is not set +# CONFIG_DEBUG_IRQ is not set + +# +# Driver Debug Options +# +# CONFIG_DEBUG_LEDS is not set +# CONFIG_DEBUG_ANALOG is not set +# CONFIG_DEBUG_GPIO is not set +# CONFIG_DEBUG_I2C is not set +# CONFIG_DEBUG_RTC is not set +# CONFIG_DEBUG_SPI is not set +# CONFIG_DEBUG_TIMER is not set +CONFIG_ARCH_HAVE_STACKCHECK=y +CONFIG_STACK_COLORATION=y +CONFIG_ARCH_HAVE_HEAPCHECK=y +# CONFIG_HEAP_COLORATION is not set +CONFIG_DEBUG_SYMBOLS=y +CONFIG_ARCH_HAVE_CUSTOMOPT=y +CONFIG_DEBUG_NOOPT=y +# CONFIG_DEBUG_CUSTOMOPT is not set +# CONFIG_DEBUG_FULLOPT is not set + +# +# System Type +# +CONFIG_ARCH_ARM=y +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_MISOC is not set +# CONFIG_ARCH_RENESAS is not set +# CONFIG_ARCH_RISCV is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_XTENSA is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="arm" + +# +# ARM Options +# +# CONFIG_ARCH_CHIP_A1X is not set +# CONFIG_ARCH_CHIP_C5471 is not set +# CONFIG_ARCH_CHIP_DM320 is not set +# CONFIG_ARCH_CHIP_EFM32 is not set +# CONFIG_ARCH_CHIP_IMX1 is not set +# CONFIG_ARCH_CHIP_IMX6 is not set +# CONFIG_ARCH_CHIP_KINETIS is not set +# CONFIG_ARCH_CHIP_KL is not set +# CONFIG_ARCH_CHIP_LM is not set +# CONFIG_ARCH_CHIP_TIVA is not set +# CONFIG_ARCH_CHIP_LPC11XX is not set +# CONFIG_ARCH_CHIP_LPC17XX is not set +# CONFIG_ARCH_CHIP_LPC214X is not set +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_NUC1XX is not set +# CONFIG_ARCH_CHIP_SAMA5 is not set +# CONFIG_ARCH_CHIP_SAMD is not set +# CONFIG_ARCH_CHIP_SAML is not set +# CONFIG_ARCH_CHIP_SAM34 is not set +# CONFIG_ARCH_CHIP_SAMV7 is not set +# CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set +# CONFIG_ARCH_CHIP_STM32F7 is not set +CONFIG_ARCH_CHIP_STM32L4=y +# CONFIG_ARCH_CHIP_STR71X is not set +# CONFIG_ARCH_CHIP_TMS570 is not set +# CONFIG_ARCH_CHIP_XMC4 is not set +# CONFIG_ARCH_ARM7TDMI is not set +# CONFIG_ARCH_ARM926EJS is not set +# CONFIG_ARCH_ARM920T is not set +# CONFIG_ARCH_CORTEXM0 is not set +# CONFIG_ARCH_CORTEXM23 is not set +# CONFIG_ARCH_CORTEXM3 is not set +# CONFIG_ARCH_CORTEXM33 is not set +CONFIG_ARCH_CORTEXM4=y +# CONFIG_ARCH_CORTEXM7 is not set +# CONFIG_ARCH_CORTEXA5 is not set +# CONFIG_ARCH_CORTEXA8 is not set +# CONFIG_ARCH_CORTEXA9 is not set +# CONFIG_ARCH_CORTEXR4 is not set +# CONFIG_ARCH_CORTEXR4F is not set +# CONFIG_ARCH_CORTEXR5 is not set +# CONFIG_ARCH_CORTEX5F is not set +# CONFIG_ARCH_CORTEXR7 is not set +# CONFIG_ARCH_CORTEXR7F is not set +CONFIG_ARCH_FAMILY="armv7-m" +CONFIG_ARCH_CHIP="stm32l4" +# CONFIG_ARM_TOOLCHAIN_IAR is not set +CONFIG_ARM_TOOLCHAIN_GNU=y +# CONFIG_ARMV7M_USEBASEPRI is not set +CONFIG_ARCH_HAVE_CMNVECTOR=y +CONFIG_ARMV7M_CMNVECTOR=y +# CONFIG_ARMV7M_LAZYFPU is not set +CONFIG_ARCH_HAVE_FPU=y +# CONFIG_ARCH_HAVE_DPFPU is not set +# CONFIG_ARCH_FPU is not set +# CONFIG_ARCH_HAVE_TRUSTZONE is not set +CONFIG_ARM_HAVE_MPU_UNIFIED=y +# CONFIG_ARM_MPU is not set +# CONFIG_DEBUG_HARDFAULT is not set + +# +# ARMV7M Configuration Options +# +# CONFIG_ARMV7M_HAVE_ICACHE is not set +# CONFIG_ARMV7M_HAVE_DCACHE is not set +# CONFIG_ARMV7M_HAVE_ITCM is not set +# CONFIG_ARMV7M_HAVE_DTCM is not set +# CONFIG_ARMV7M_TOOLCHAIN_IARL is not set +# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set +# CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set +# CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL is not set +CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL=y +CONFIG_ARMV7M_HAVE_STACKCHECK=y +CONFIG_ARMV7M_STACKCHECK=y +# CONFIG_ARMV7M_ITMSYSLOG is not set +CONFIG_SERIAL_TERMIOS=y +# CONFIG_USART2_RS485 is not set +# CONFIG_USART2_RXDMA is not set +# CONFIG_SERIAL_DISABLE_REORDERING is not set + +# +# STM32L4 Configuration Options +# +# CONFIG_ARCH_CHIP_STM32L432KB is not set +# CONFIG_ARCH_CHIP_STM32L432KC is not set +# CONFIG_ARCH_CHIP_STM32L442KC is not set +# CONFIG_ARCH_CHIP_STM32L451CC is not set +# CONFIG_ARCH_CHIP_STM32L451CE is not set +# CONFIG_ARCH_CHIP_STM32L451RC is not set +# CONFIG_ARCH_CHIP_STM32L451RE is not set +# CONFIG_ARCH_CHIP_STM32L451VC is not set +# CONFIG_ARCH_CHIP_STM32L451VE is not set +# CONFIG_ARCH_CHIP_STM32L452CC is not set +# CONFIG_ARCH_CHIP_STM32L452CE is not set +# CONFIG_ARCH_CHIP_STM32L452RC is not set +CONFIG_ARCH_CHIP_STM32L452RE=y +# CONFIG_ARCH_CHIP_STM32L452VC is not set +# CONFIG_ARCH_CHIP_STM32L452VE is not set +# CONFIG_ARCH_CHIP_STM32L462CE is not set +# CONFIG_ARCH_CHIP_STM32L462RE is not set +# CONFIG_ARCH_CHIP_STM32L462VE is not set +# CONFIG_ARCH_CHIP_STM32L476RG is not set +# CONFIG_ARCH_CHIP_STM32L476RE is not set +# CONFIG_ARCH_CHIP_STM32L486 is not set +# CONFIG_ARCH_CHIP_STM32L496ZE is not set +# CONFIG_ARCH_CHIP_STM32L496ZG is not set +# CONFIG_ARCH_CHIP_STM32L4A6 is not set +# CONFIG_STM32L4_STM32L4X1 is not set +CONFIG_STM32L4_STM32L4X2=y +CONFIG_STM32L4_STM32L4X3=y +# CONFIG_STM32L4_STM32L4X5 is not set +# CONFIG_STM32L4_STM32L4X6 is not set +# CONFIG_STM32L4_STM32L431XX is not set +# CONFIG_STM32L4_STM32L432XX is not set +# CONFIG_STM32L4_STM32L433XX is not set +# CONFIG_STM32L4_STM32L442XX is not set +# CONFIG_STM32L4_STM32L443XX is not set +# CONFIG_STM32L4_STM32L451XX is not set +CONFIG_STM32L4_STM32L452XX=y +# CONFIG_STM32L4_STM32L462XX is not set +# CONFIG_STM32L4_STM32L471XX is not set +# CONFIG_STM32L4_STM32L476XX is not set +# CONFIG_STM32L4_STM32L486XX is not set +# CONFIG_STM32L4_STM32L496XX is not set +# CONFIG_STM32L4_STM32L4A6XX is not set +CONFIG_STM32L4_FLASH_OVERRIDE_DEFAULT=y +# CONFIG_STM32L4_FLASH_OVERRIDE_B is not set +# CONFIG_STM32L4_FLASH_OVERRIDE_C is not set +# CONFIG_STM32L4_FLASH_OVERRIDE_E is not set +# CONFIG_STM32L4_FLASH_OVERRIDE_G is not set +# CONFIG_STM32L4_FLASH_CONFIG_B is not set +# CONFIG_STM32L4_FLASH_CONFIG_C is not set +CONFIG_STM32L4_FLASH_CONFIG_E=y +# CONFIG_STM32L4_IO_CONFIG_K is not set +# CONFIG_STM32L4_IO_CONFIG_C is not set +CONFIG_STM32L4_IO_CONFIG_R=y +# CONFIG_STM32L4_IO_CONFIG_J is not set +# CONFIG_STM32L4_IO_CONFIG_M is not set +# CONFIG_STM32L4_IO_CONFIG_V is not set +# CONFIG_STM32L4_IO_CONFIG_Q is not set +# CONFIG_STM32L4_IO_CONFIG_Z is not set +# CONFIG_STM32L4_IO_CONFIG_A is not set + +# +# STM32L4 SRAM2 Options +# +CONFIG_STM32L4_SRAM2_HEAP=y +CONFIG_STM32L4_SRAM2_INIT=y + +# +# STM32L4 Peripherals +# + +# +# STM32L4 Peripheral Support +# +# CONFIG_STM32L4_HAVE_ADC2 is not set +# CONFIG_STM32L4_HAVE_ADC3 is not set +# CONFIG_STM32L4_HAVE_AES is not set +# CONFIG_STM32L4_HAVE_CAN2 is not set +CONFIG_STM32L4_HAVE_COMP=y +# CONFIG_STM32L4_HAVE_DAC2 is not set +# CONFIG_STM32L4_HAVE_DCMI is not set +CONFIG_STM32L4_HAVE_DFSDM1=y +# CONFIG_STM32L4_HAVE_DMA2D is not set +# CONFIG_STM32L4_HAVE_FSMC is not set +# CONFIG_STM32L4_HAVE_HASH is not set +CONFIG_STM32L4_HAVE_I2C4=y +# CONFIG_STM32L4_HAVE_LCD is not set +# CONFIG_STM32L4_HAVE_LTDC is not set +CONFIG_STM32L4_HAVE_LPTIM1=y +CONFIG_STM32L4_HAVE_LPTIM2=y +# CONFIG_STM32L4_HAVE_OTGFS is not set +CONFIG_STM32L4_HAVE_SAI1=y +# CONFIG_STM32L4_HAVE_SAI2 is not set +CONFIG_STM32L4_HAVE_SDMMC1=y +CONFIG_STM32L4_HAVE_TIM3=y +# CONFIG_STM32L4_HAVE_TIM4 is not set +# CONFIG_STM32L4_HAVE_TIM5 is not set +# CONFIG_STM32L4_HAVE_TIM7 is not set +# CONFIG_STM32L4_HAVE_TIM8 is not set +# CONFIG_STM32L4_HAVE_TIM17 is not set +# CONFIG_STM32L4_ADC is not set +# CONFIG_STM32L4_CAN is not set +# CONFIG_STM32L4_DAC is not set +CONFIG_STM32L4_DMA=y +CONFIG_STM32L4_I2C=y +# CONFIG_STM32L4_SAI is not set +CONFIG_STM32L4_SPI=y +CONFIG_STM32L4_USART=y +# CONFIG_STM32L4_LPTIM is not set + +# +# AHB1 Peripherals +# +CONFIG_STM32L4_DMA1=y +CONFIG_STM32L4_DMA2=y +# CONFIG_STM32L4_CRC is not set +# CONFIG_STM32L4_TSC is not set + +# +# AHB2 Peripherals +# +# CONFIG_STM32L4_ADC1 is not set +CONFIG_STM32L4_RNG=y + +# +# AHB3 Peripherals +# +# CONFIG_STM32L4_QSPI is not set + +# +# APB1 Peripherals +# +CONFIG_STM32L4_PWR=y +# CONFIG_STM32L4_TIM2 is not set +# CONFIG_STM32L4_TIM3 is not set +# CONFIG_STM32L4_TIM6 is not set +# CONFIG_STM32L4_SPI2 is not set +# CONFIG_STM32L4_SPI3 is not set +# CONFIG_STM32L4_USART1 is not set +CONFIG_STM32L4_USART2=y +# CONFIG_STM32L4_USART3 is not set +# CONFIG_STM32L4_UART4 is not set +CONFIG_STM32L4_I2C1=y +# CONFIG_STM32L4_I2C2 is not set +# CONFIG_STM32L4_I2C3 is not set +# CONFIG_STM32L4_I2C4 is not set +# CONFIG_STM32L4_CAN1 is not set +# CONFIG_STM32L4_DAC1 is not set +# CONFIG_STM32L4_OPAMP is not set +# CONFIG_STM32L4_LPTIM1 is not set +# CONFIG_STM32L4_LPUART1 is not set +# CONFIG_STM32L4_SWPMI is not set +# CONFIG_STM32L4_LPTIM2 is not set + +# +# APB2 Peripherals +# +CONFIG_STM32L4_SYSCFG=y +CONFIG_STM32L4_FIREWALL=y +# CONFIG_STM32L4_SDMMC1 is not set +# CONFIG_STM32L4_TIM1 is not set +CONFIG_STM32L4_SPI1=y +# CONFIG_STM32L4_TIM15 is not set +# CONFIG_STM32L4_TIM16 is not set +# CONFIG_STM32L4_COMP is not set +# CONFIG_STM32L4_SAI1 is not set +# CONFIG_STM32L4_DFSDM1 is not set + +# +# Other Peripherals +# +# CONFIG_STM32L4_BKPSRAM is not set +# CONFIG_STM32L4_IWDG is not set +# CONFIG_STM32L4_WWDG is not set +CONFIG_STM32L4_FLASH_PREFETCH=y +CONFIG_STM32L4_DISABLE_IDLE_SLEEP_DURING_DEBUG=y +# CONFIG_ARCH_BOARD_STM32L4_CUSTOM_CLOCKCONFIG is not set +CONFIG_STM32L4_RTC_LSECLOCK=y +# CONFIG_STM32L4_RTC_LSICLOCK is not set +# CONFIG_STM32L4_RTC_HSECLOCK is not set +CONFIG_STM32L4_SAI1PLL=y + +# +# Timer Configuration +# +# CONFIG_STM32L4_ONESHOT is not set +# CONFIG_STM32L4_FREERUN is not set +# CONFIG_STM32L4_TIM3_CAP is not set +CONFIG_STM32L4_HAVE_USART1=y +CONFIG_STM32L4_HAVE_USART2=y +CONFIG_STM32L4_HAVE_USART3=y +CONFIG_STM32L4_HAVE_UART4=y +# CONFIG_STM32L4_HAVE_UART5 is not set + +# +# U[S]ART Configuration +# +# CONFIG_STM32L4_FLOWCONTROL_BROKEN is not set +# CONFIG_STM32L4_USART_BREAKS is not set + +# +# SPI Configuration +# +# CONFIG_STM32L4_SPI_INTERRUPTS is not set +# CONFIG_STM32L4_SPI_DMA is not set + +# +# I2C Configuration +# +# CONFIG_STM32L4_I2C_DYNTIMEO is not set +CONFIG_STM32L4_I2CTIMEOSEC=0 +CONFIG_STM32L4_I2CTIMEOMS=500 +CONFIG_STM32L4_I2CTIMEOTICKS=500 +# CONFIG_STM32L4_I2C_DUTY16_9 is not set + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_VECNOTIRQ is not set +CONFIG_ARCH_DMA=y +CONFIG_ARCH_HAVE_IRQPRIO=y +# CONFIG_ARCH_L2CACHE is not set +# CONFIG_ARCH_HAVE_COHERENT_DCACHE is not set +# CONFIG_ARCH_HAVE_ADDRENV is not set +# CONFIG_ARCH_NEED_ADDRENV_MAPPING is not set +# CONFIG_ARCH_HAVE_MULTICPU is not set +CONFIG_ARCH_HAVE_VFORK=y +# CONFIG_ARCH_HAVE_MMU is not set +CONFIG_ARCH_HAVE_MPU=y +# CONFIG_ARCH_NAND_HWECC is not set +# CONFIG_ARCH_HAVE_EXTCLK is not set +# CONFIG_ARCH_HAVE_POWEROFF is not set +CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set +# CONFIG_ARCH_USE_MPU is not set +# CONFIG_ARCH_IRQPRIO is not set +CONFIG_ARCH_STACKDUMP=y +# CONFIG_ENDIAN_BIG is not set +# CONFIG_ARCH_IDLE_CUSTOM is not set +# CONFIG_ARCH_HAVE_RAMFUNCS is not set +CONFIG_ARCH_HAVE_RAMVECTORS=y +# CONFIG_ARCH_RAMVECTORS is not set +# CONFIG_ARCH_MINIMAL_VECTORTABLE is not set + +# +# Board Settings +# +CONFIG_BOARD_LOOPSPERMSEC=8499 +# CONFIG_ARCH_CALIBRATION is not set + +# +# Interrupt options +# +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y +CONFIG_ARCH_INTERRUPTSTACK=2048 +CONFIG_ARCH_HAVE_HIPRI_INTERRUPT=y +# CONFIG_ARCH_HIPRI_INTERRUPT is not set + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Boot Memory Configuration +# +CONFIG_RAM_START=0x20000000 +CONFIG_RAM_SIZE=131072 +# CONFIG_ARCH_HAVE_SDRAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_NUCLEO_L452RE=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="nucleo-l452re" + +# +# Common Board Options +# +CONFIG_ARCH_HAVE_LEDS=y +CONFIG_ARCH_LEDS=y +CONFIG_ARCH_HAVE_BUTTONS=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_HAVE_IRQBUTTONS=y +CONFIG_ARCH_IRQBUTTONS=y + +# +# Board-Specific Options +# +# CONFIG_BOARD_CRASHDUMP is not set +CONFIG_LIB_BOARDCTL=y +# CONFIG_BOARDCTL_RESET is not set +# CONFIG_BOARDCTL_UNIQUEID is not set +# CONFIG_BOARDCTL_TSCTEST is not set +# CONFIG_BOARDCTL_GRAPHICS is not set +# CONFIG_BOARDCTL_IOCTL is not set + +# +# RTOS Features +# +CONFIG_DISABLE_OS_API=y +# CONFIG_DISABLE_POSIX_TIMERS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_DISABLE_SIGNALS is not set +# CONFIG_DISABLE_MQUEUE is not set +# CONFIG_DISABLE_ENVIRON is not set + +# +# Clocks and Timers +# +CONFIG_ARCH_HAVE_TICKLESS=y +# CONFIG_SCHED_TICKLESS is not set +CONFIG_USEC_PER_TICK=10000 +# CONFIG_SYSTEM_TIME64 is not set +# CONFIG_CLOCK_MONOTONIC is not set +# CONFIG_ARCH_HAVE_TIMEKEEPING is not set +# CONFIG_JULIAN_TIME is not set +CONFIG_START_YEAR=2017 +CONFIG_START_MONTH=1 +CONFIG_START_DAY=1 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=8 +CONFIG_WDOG_INTRESERVE=1 +CONFIG_PREALLOC_TIMERS=4 + +# +# Tasks and Scheduling +# +# CONFIG_SPINLOCK is not set +# CONFIG_INIT_NONE is not set +CONFIG_INIT_ENTRYPOINT=y +# CONFIG_INIT_FILEPATH is not set +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_RR_INTERVAL=200 +# CONFIG_SCHED_SPORADIC is not set +CONFIG_TASK_NAME_SIZE=0 +CONFIG_MAX_TASKS=16 +# CONFIG_SCHED_HAVE_PARENT is not set +CONFIG_SCHED_WAITPID=y + +# +# Pthread Options +# +# CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set +CONFIG_NPTHREAD_KEYS=4 +# CONFIG_PTHREAD_CLEANUP is not set +# CONFIG_CANCELLATION_POINTS is not set + +# +# Performance Monitoring +# +# CONFIG_SCHED_CPULOAD is not set +# CONFIG_SCHED_INSTRUMENTATION is not set + +# +# Files and I/O +# +CONFIG_DEV_CONSOLE=y +# CONFIG_FDCLONE_DISABLE is not set +# CONFIG_FDCLONE_STDIO is not set +CONFIG_SDCLONE_DISABLE=y +CONFIG_NFILE_DESCRIPTORS=8 +CONFIG_NFILE_STREAMS=8 +CONFIG_NAME_MAX=32 +# CONFIG_PRIORITY_INHERITANCE is not set + +# +# RTOS hooks +# +# CONFIG_BOARD_INITIALIZE is not set +# CONFIG_SCHED_STARTHOOK is not set +# CONFIG_SCHED_ATEXIT is not set +# CONFIG_SCHED_ONEXIT is not set + +# +# Signal Numbers +# +CONFIG_SIG_SIGUSR1=1 +CONFIG_SIG_SIGUSR2=2 +CONFIG_SIG_SIGALARM=3 +CONFIG_SIG_SIGCONDTIMEDOUT=16 + +# +# POSIX Message Queue Options +# +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_MQ_MAXMSGSIZE=32 +# CONFIG_MODULE is not set + +# +# Work queue support +# +# CONFIG_SCHED_WORKQUEUE is not set +# CONFIG_SCHED_HPWORK is not set +# CONFIG_SCHED_LPWORK is not set + +# +# Stack and heap information +# +CONFIG_IDLETHREAD_STACKSIZE=1024 +CONFIG_USERMAIN_STACKSIZE=2048 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=2048 +# CONFIG_LIB_SYSCALL is not set + +# +# Device Drivers +# +CONFIG_DISABLE_POLL=y +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +CONFIG_ARCH_HAVE_RNG=y +CONFIG_DEV_RANDOM=y +# CONFIG_DEV_URANDOM is not set +# CONFIG_DEV_LOOP is not set + +# +# Buffering +# + +# +# Common I/O Buffer Support +# +# CONFIG_DRIVERS_IOB is not set +# CONFIG_DRVR_WRITEBUFFER is not set +# CONFIG_DRVR_READAHEAD is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_ARCH_HAVE_PWM_PULSECOUNT is not set +# CONFIG_ARCH_HAVE_PWM_MULTICHAN is not set +# CONFIG_PWM is not set +CONFIG_ARCH_HAVE_I2CRESET=y +CONFIG_I2C=y +# CONFIG_I2C_SLAVE is not set +# CONFIG_I2C_POLLED is not set +CONFIG_I2C_RESET=y +# CONFIG_I2C_TRACE is not set +CONFIG_I2C_DRIVER=y +# CONFIG_ARCH_HAVE_SPI_CRCGENERATION is not set +# CONFIG_ARCH_HAVE_SPI_CS_CONTROL is not set +CONFIG_ARCH_HAVE_SPI_BITORDER=y +CONFIG_SPI=y +# CONFIG_SPI_SLAVE is not set +CONFIG_SPI_EXCHANGE=y +# CONFIG_SPI_CMDDATA is not set +# CONFIG_SPI_CALLBACK is not set +# CONFIG_SPI_HWFEATURES is not set +# CONFIG_SPI_BITORDER is not set +# CONFIG_SPI_CS_DELAY_CONTROL is not set +# CONFIG_SPI_DRIVER is not set +# CONFIG_SPI_BITBANG is not set +# CONFIG_I2S is not set + +# +# Timer Driver Support +# +# CONFIG_TIMER is not set +# CONFIG_ONESHOT is not set +CONFIG_RTC=y +CONFIG_RTC_DATETIME=y +CONFIG_RTC_ALARM=y +CONFIG_RTC_NALARMS=2 +CONFIG_RTC_DRIVER=y +CONFIG_RTC_IOCTL=y +# CONFIG_RTC_EXTERNAL is not set +# CONFIG_WATCHDOG is not set +# CONFIG_TIMERS_CS2100CP is not set +CONFIG_ANALOG=y +# CONFIG_ADC is not set +# CONFIG_COMP is not set +# CONFIG_DAC is not set +# CONFIG_OPAMP is not set +# CONFIG_AUDIO_DEVICES is not set +# CONFIG_VIDEO_DEVICES is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set + +# +# IO Expander/GPIO Support +# +# CONFIG_IOEXPANDER is not set +# CONFIG_DEV_GPIO is not set + +# +# LCD Driver Support +# +# CONFIG_LCD is not set +# CONFIG_SLCD is not set + +# +# LED Support +# +# CONFIG_USERLED is not set +# CONFIG_RGBLED is not set +# CONFIG_PCA9635PW is not set +# CONFIG_NCP5623C is not set +# CONFIG_MMCSD is not set +# CONFIG_MODEM is not set +# CONFIG_MTD is not set +# CONFIG_EEPROM is not set +# CONFIG_PIPES is not set +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +CONFIG_SERIAL=y +# CONFIG_DEV_LOWCONSOLE is not set +# CONFIG_SERIAL_REMOVABLE is not set +CONFIG_SERIAL_CONSOLE=y +# CONFIG_16550_UART is not set +# CONFIG_UART_SERIALDRIVER is not set +# CONFIG_UART0_SERIALDRIVER is not set +# CONFIG_UART1_SERIALDRIVER is not set +# CONFIG_UART2_SERIALDRIVER is not set +# CONFIG_UART3_SERIALDRIVER is not set +# CONFIG_UART4_SERIALDRIVER is not set +# CONFIG_UART5_SERIALDRIVER is not set +# CONFIG_UART6_SERIALDRIVER is not set +# CONFIG_UART7_SERIALDRIVER is not set +# CONFIG_UART8_SERIALDRIVER is not set +# CONFIG_SCI0_SERIALDRIVER is not set +# CONFIG_SCI1_SERIALDRIVER is not set +# CONFIG_USART0_SERIALDRIVER is not set +# CONFIG_USART1_SERIALDRIVER is not set +CONFIG_USART2_SERIALDRIVER=y +# CONFIG_USART3_SERIALDRIVER is not set +# CONFIG_USART4_SERIALDRIVER is not set +# CONFIG_USART5_SERIALDRIVER is not set +# CONFIG_USART6_SERIALDRIVER is not set +# CONFIG_USART7_SERIALDRIVER is not set +# CONFIG_USART8_SERIALDRIVER is not set +# CONFIG_OTHER_UART_SERIALDRIVER is not set +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +# CONFIG_SERIAL_IFLOWCONTROL is not set +# CONFIG_SERIAL_OFLOWCONTROL is not set +# CONFIG_SERIAL_DMA is not set +# CONFIG_SERIAL_TIOCSERGSTRUCT is not set +CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y +CONFIG_USART2_SERIAL_CONSOLE=y +# CONFIG_OTHER_SERIAL_CONSOLE is not set +# CONFIG_NO_SERIAL_CONSOLE is not set + +# +# USART2 Configuration +# +CONFIG_USART2_RXBUFSIZE=128 +CONFIG_USART2_TXBUFSIZE=128 +CONFIG_USART2_BAUD=115200 +CONFIG_USART2_BITS=8 +CONFIG_USART2_PARITY=0 +CONFIG_USART2_2STOP=0 +# CONFIG_USART2_IFLOWCONTROL is not set +# CONFIG_USART2_OFLOWCONTROL is not set +# CONFIG_USART2_DMA is not set +# CONFIG_PSEUDOTERM is not set +# CONFIG_USBDEV is not set +# CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set +# CONFIG_HAVE_USBTRACE is not set +# CONFIG_DRIVERS_WIRELESS is not set +# CONFIG_DRIVERS_CONTACTLESS is not set + +# +# System Logging +# +# CONFIG_ARCH_SYSLOG is not set +# CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_INTBUFFER is not set +# CONFIG_SYSLOG_TIMESTAMP is not set +CONFIG_SYSLOG_SERIAL_CONSOLE=y +# CONFIG_SYSLOG_CHAR is not set +CONFIG_SYSLOG_CONSOLE=y +# CONFIG_SYSLOG_NONE is not set +# CONFIG_SYSLOG_FILE is not set +# CONFIG_SYSLOG_CHARDEV is not set + +# +# Networking Support +# +# CONFIG_ARCH_HAVE_NET is not set +# CONFIG_ARCH_HAVE_PHY is not set +# CONFIG_NET is not set + +# +# Crypto API +# +# CONFIG_CRYPTO is not set + +# +# File Systems +# + +# +# File system configuration +# +# CONFIG_DISABLE_MOUNTPOINT is not set +# CONFIG_FS_AUTOMOUNTER is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_PSEUDOFS_SOFTLINKS is not set +CONFIG_FS_READABLE=y +# CONFIG_FS_WRITABLE is not set +# CONFIG_FS_NAMED_SEMAPHORES is not set +CONFIG_FS_MQUEUE_MPATH="/var/mqueue" +# CONFIG_FS_RAMMAP is not set +# CONFIG_FS_FAT is not set +# CONFIG_FS_NXFFS is not set +# CONFIG_FS_ROMFS is not set +# CONFIG_FS_TMPFS is not set +# CONFIG_FS_SMARTFS is not set +# CONFIG_FS_BINFS is not set +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_REGISTER=y + +# +# Exclude individual procfs entries +# +# CONFIG_FS_PROCFS_EXCLUDE_PROCESS is not set +# CONFIG_FS_PROCFS_EXCLUDE_UPTIME is not set +# CONFIG_FS_PROCFS_EXCLUDE_MOUNTS is not set +# CONFIG_FS_UNIONFS is not set + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=2 +# CONFIG_ARCH_HAVE_HEAP2 is not set +# CONFIG_GRAN is not set + +# +# Audio Support +# +# CONFIG_AUDIO is not set + +# +# Wireless Support +# + +# +# Binary Loader +# +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_BINFMT_EXEPATH is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +CONFIG_BUILTIN=y +# CONFIG_PIC is not set +# CONFIG_SYMTAB_ORDEREDBYNAME is not set + +# +# Library Routines +# + +# +# Standard C Library Options +# + +# +# Standard C I/O +# +# CONFIG_STDIO_DISABLE_BUFFERING is not set +CONFIG_STDIO_BUFFER_SIZE=64 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +# CONFIG_NOPRINTF_FIELDWIDTH is not set +# CONFIG_LIBC_FLOATINGPOINT is not set +CONFIG_LIBC_LONG_LONG=y +# CONFIG_LIBC_SCANSET is not set +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_MEMCPY_VIK is not set +# CONFIG_LIBM is not set + +# +# Architecture-Specific Support +# +CONFIG_ARCH_LOWPUTC=y +# CONFIG_ARCH_ROMGETC is not set +# CONFIG_LIBC_ARCH_MEMCPY is not set +# CONFIG_LIBC_ARCH_MEMCMP is not set +# CONFIG_LIBC_ARCH_MEMMOVE is not set +# CONFIG_LIBC_ARCH_MEMSET is not set +# CONFIG_LIBC_ARCH_STRCHR is not set +# CONFIG_LIBC_ARCH_STRCMP is not set +# CONFIG_LIBC_ARCH_STRCPY is not set +# CONFIG_LIBC_ARCH_STRNCPY is not set +# CONFIG_LIBC_ARCH_STRLEN is not set +# CONFIG_LIBC_ARCH_STRNLEN is not set +# CONFIG_LIBC_ARCH_ELF is not set +# CONFIG_ARMV7M_MEMCPY is not set + +# +# stdlib Options +# +CONFIG_LIB_RAND_ORDER=1 +CONFIG_LIB_HOMEDIR="/" + +# +# Program Execution Options +# +# CONFIG_LIBC_EXECFUNCS is not set +CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024 +CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=2048 + +# +# errno Decode Support +# +# CONFIG_LIBC_STRERROR is not set +# CONFIG_LIBC_PERROR_STDOUT is not set + +# +# memcpy/memset Options +# +# CONFIG_MEMSET_OPTSPEED is not set +# CONFIG_LIBC_DLLFCN is not set +# CONFIG_LIBC_MODLIB is not set +# CONFIG_LIBC_WCHAR is not set +# CONFIG_LIBC_LOCALE is not set + +# +# Time/Time Zone Support +# +# CONFIG_LIBC_LOCALTIME is not set +# CONFIG_TIME_EXTENDED is not set +CONFIG_ARCH_HAVE_TLS=y + +# +# Thread Local Storage (TLS) +# +# CONFIG_TLS is not set + +# +# Network-Related Options +# +# CONFIG_LIBC_IPv4_ADDRCONV is not set +# CONFIG_LIBC_IPv6_ADDRCONV is not set +# CONFIG_LIBC_NETDB is not set + +# +# NETDB Support +# +# CONFIG_NETDB_HOSTFILE is not set +# CONFIG_LIBC_IOCTL_VARIADIC is not set +CONFIG_LIB_SENDFILE_BUFSIZE=512 + +# +# Non-standard Library Support +# +# CONFIG_LIB_CRC64_FAST is not set +# CONFIG_LIB_KBDCODEC is not set +# CONFIG_LIB_SLCDCODEC is not set +# CONFIG_LIB_HEX2BIN is not set + +# +# Basic CXX Support +# +# CONFIG_C99_BOOL8 is not set +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +# CONFIG_CXX_NEWLONG is not set + +# +# LLVM C++ Library (libcxx) +# +# CONFIG_LIBCXX is not set + +# +# uClibc++ Standard C++ Library +# +# CONFIG_UCLIBCXX is not set + +# +# Application Configuration +# + +# +# Built-In Applications +# +CONFIG_BUILTIN_PROXY_STACKSIZE=1024 + +# +# CAN Utilities +# + +# +# Examples +# +CONFIG_EXAMPLES_ALARM=y +CONFIG_EXAMPLES_ALARM_PRIORITY=100 +CONFIG_EXAMPLES_ALARM_STACKSIZE=2048 +CONFIG_EXAMPLES_ALARM_DEVPATH="/dev/rtc0" +CONFIG_EXAMPLES_ALARM_SIGNO=1 +# CONFIG_EXAMPLES_BUTTONS is not set +# CONFIG_EXAMPLES_CCTYPE is not set +# CONFIG_EXAMPLES_CHAT is not set +# CONFIG_EXAMPLES_CONFIGDATA is not set +# CONFIG_EXAMPLES_CXXTEST is not set +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HELLOXX is not set +# CONFIG_EXAMPLES_HIDKBD is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_JSON is not set +# CONFIG_EXAMPLES_KEYPADTEST is not set +# CONFIG_EXAMPLES_MEDIA is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MODBUS is not set +# CONFIG_EXAMPLES_MOUNT is not set +CONFIG_EXAMPLES_NSH=y +CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXLINES is not set +# CONFIG_EXAMPLES_NXTERM is not set +# CONFIG_EXAMPLES_NXTEXT is not set +CONFIG_EXAMPLES_OSTEST=y +CONFIG_EXAMPLES_OSTEST_LOOPS=1 +CONFIG_EXAMPLES_OSTEST_STACKSIZE=8192 +CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=8 +CONFIG_EXAMPLES_OSTEST_RR_RANGE=10000 +CONFIG_EXAMPLES_OSTEST_RR_RUNS=10 +CONFIG_EXAMPLES_OSTEST_WAITRESULT=y +# CONFIG_EXAMPLES_PCA9635 is not set +# CONFIG_EXAMPLES_POSIXSPAWN is not set +# CONFIG_EXAMPLES_PPPD is not set +CONFIG_EXAMPLES_RANDOM=y +CONFIG_EXAMPLES_MAXSAMPLES=64 +CONFIG_EXAMPLES_NSAMPLES=8 +# CONFIG_EXAMPLES_RFID_READUID is not set +# CONFIG_EXAMPLES_RGBLED is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERIALBLASTER is not set +# CONFIG_EXAMPLES_SERIALRX is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_SLCD is not set +# CONFIG_EXAMPLES_SMART is not set +# CONFIG_EXAMPLES_SMART_TEST is not set +# CONFIG_EXAMPLES_SMP is not set +# CONFIG_EXAMPLES_STAT is not set +# CONFIG_EXAMPLES_TCPECHO is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_USBSERIAL is not set +# CONFIG_EXAMPLES_WATCHDOG is not set +# CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set + +# +# File System Utilities +# +# CONFIG_FSUTILS_INIFILE is not set +# CONFIG_FSUTILS_PASSWD is not set + +# +# GPS Utilities +# +# CONFIG_GPSUTILS_MINMEA_LIB is not set + +# +# Graphics Support +# +# CONFIG_TIFF is not set +# CONFIG_GRAPHICS_TRAVELER is not set + +# +# Interpreters +# +# CONFIG_INTERPRETERS_BAS is not set +# CONFIG_INTERPRETERS_FICL is not set +# CONFIG_INTERPRETERS_MICROPYTHON is not set +# CONFIG_INTERPRETERS_MINIBASIC is not set +# CONFIG_INTERPRETERS_PCODE is not set + +# +# FreeModBus +# +# CONFIG_MODBUS is not set + +# +# Network Utilities +# +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_ESP8266 is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_JSON is not set +# CONFIG_NETUTILS_SMTP is not set + +# +# NSH Library +# +CONFIG_NSH_LIBRARY=y +# CONFIG_NSH_MOTD is not set + +# +# Command Line Configuration +# +CONFIG_NSH_READLINE=y +# CONFIG_NSH_CLE is not set +CONFIG_NSH_LINELEN=64 +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_CMDPARMS is not set +CONFIG_NSH_MAXARGUMENTS=6 +# CONFIG_NSH_ARGCAT is not set +CONFIG_NSH_NESTDEPTH=3 +# CONFIG_NSH_DISABLEBG is not set +CONFIG_NSH_BUILTIN_APPS=y + +# +# Disable Individual commands +# +# CONFIG_NSH_DISABLE_ADDROUTE is not set +# CONFIG_NSH_DISABLE_BASENAME is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_CMP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_DD is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_DELROUTE is not set +# CONFIG_NSH_DISABLE_DIRNAME is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_HEXDUMP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +CONFIG_NSH_DISABLE_IFUPDOWN=y +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOSETUP is not set +CONFIG_NSH_DISABLE_LOSMART=y +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MB is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKRD is not set +# CONFIG_NSH_DISABLE_MH is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_MW is not set +CONFIG_NSH_DISABLE_PRINTF=y +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set +# CONFIG_NSH_DISABLE_PUT is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SH is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNAME is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +# CONFIG_NSH_DISABLE_WGET is not set +# CONFIG_NSH_DISABLE_XD is not set +CONFIG_NSH_MMCSDMINOR=0 + +# +# Configure Command Options +# +# CONFIG_NSH_CMDOPT_DF_H is not set +# CONFIG_NSH_CMDOPT_DD_STATS is not set +CONFIG_NSH_CODECS_BUFSIZE=128 +CONFIG_NSH_CMDOPT_HEXDUMP=y +CONFIG_NSH_PROC_MOUNTPOINT="/proc" +CONFIG_NSH_FILEIOSIZE=512 + +# +# Scripting Support +# +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_LOOPS is not set + +# +# Console Configuration +# +CONFIG_NSH_CONSOLE=y +# CONFIG_NSH_ALTCONDEV is not set +CONFIG_NSH_ARCHINIT=y +# CONFIG_NSH_LOGIN is not set +# CONFIG_NSH_CONSOLE_LOGIN is not set + +# +# NxWidgets/NxWM +# + +# +# Platform-specific Support +# +# CONFIG_PLATFORM_CONFIGDATA is not set + +# +# System Libraries and NSH Add-Ons +# +# CONFIG_SYSTEM_CLE is not set +# CONFIG_SYSTEM_CUTERM is not set +# CONFIG_SYSTEM_FREE is not set +# CONFIG_SYSTEM_HEX2BIN is not set +# CONFIG_SYSTEM_HEXED is not set +CONFIG_SYSTEM_I2CTOOL=y +CONFIG_I2CTOOL_MINBUS=0 +CONFIG_I2CTOOL_MAXBUS=3 +CONFIG_I2CTOOL_MINADDR=0x03 +CONFIG_I2CTOOL_MAXADDR=0x77 +CONFIG_I2CTOOL_MAXREGADDR=0xff +CONFIG_I2CTOOL_DEFFREQ=400000 +# CONFIG_SYSTEM_INSTALL is not set +# CONFIG_SYSTEM_RAMTEST is not set +CONFIG_READLINE_HAVE_EXTMATCH=y +CONFIG_SYSTEM_READLINE=y +CONFIG_READLINE_ECHO=y +CONFIG_READLINE_TABCOMPLETION=y +CONFIG_READLINE_MAX_BUILTINS=64 +CONFIG_READLINE_MAX_EXTCMDS=64 +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_READLINE_CMD_HISTORY_LINELEN=80 +CONFIG_READLINE_CMD_HISTORY_LEN=16 +CONFIG_SYSTEM_STACKMONITOR=y +CONFIG_SYSTEM_STACKMONITOR_STACKSIZE=2048 +CONFIG_SYSTEM_STACKMONITOR_PRIORITY=50 +CONFIG_SYSTEM_STACKMONITOR_INTERVAL=2 +# CONFIG_SYSTEM_SUDOKU is not set +# CONFIG_SYSTEM_SYSTEM is not set +CONFIG_SYSTEM_TEE=y +CONFIG_SYSTEM_TEE_STACKSIZE=1536 +CONFIG_SYSTEM_TEE_PRIORITY=100 +# CONFIG_SYSTEM_UBLOXMODEM is not set +# CONFIG_SYSTEM_VI is not set +# CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# diff --git a/configs/nucleo-l452re/scripts/l452re-flash.ld b/configs/nucleo-l452re/scripts/l452re-flash.ld new file mode 100644 index 0000000000..362a34d600 --- /dev/null +++ b/configs/nucleo-l452re/scripts/l452re-flash.ld @@ -0,0 +1,119 @@ +/**************************************************************************** + * configs/nucleo-l452re/scripts/l452re-flash.ld + * + * Copyright (C) 2014 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Sebastien Lorquet + * + * 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. + * + ****************************************************************************/ + +/* The STM32L452RE has 512Kb of FLASH beginning at address 0x0800:0000 and + * 160Kb of SRAM beginning at address 0x2000:0000. When booting from FLASH, + * FLASH memory is aliased to address 0x0000:0000 where the code expects to + * begin execution by jumping to the entry point in the 0x0800:0000 address + * range. + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x08000000, LENGTH = 512K + sram (rwx) : ORIGIN = 0x20000000, LENGTH = 160K +} + +OUTPUT_ARCH(arm) +ENTRY(_stext) +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + } > flash + + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + /* The STM32L452RE has 160Kb of SRAM beginning at the following address */ + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/configs/nucleo-l452re/src/.gitignore b/configs/nucleo-l452re/src/.gitignore new file mode 100644 index 0000000000..726d936e1e --- /dev/null +++ b/configs/nucleo-l452re/src/.gitignore @@ -0,0 +1,2 @@ +/.depend +/Make.dep diff --git a/configs/nucleo-l452re/src/Makefile b/configs/nucleo-l452re/src/Makefile new file mode 100644 index 0000000000..4cd0f2e7c4 --- /dev/null +++ b/configs/nucleo-l452re/src/Makefile @@ -0,0 +1,56 @@ +############################################################################ +# configs/nucleo-l452re/src/Makefile +# +# Copyright (C) 2017 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# Alan Carvalho de Assis +# +# 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. +# +############################################################################ + +-include $(TOPDIR)/Make.defs + +ASRCS = +CSRCS = stm32_boot.c stm32_bringup.c stm32_spi.c + +ifeq ($(CONFIG_ARCH_LEDS),y) +CSRCS += stm32_autoleds.c +else +CSRCS += stm32_userleds.c +endif + +ifeq ($(CONFIG_ARCH_BUTTONS),y) +CSRCS += stm32_buttons.c +endif + +ifeq ($(CONFIG_LIB_BOARDCTL),y) +CSRCS += stm32_appinit.c +endif + +include $(TOPDIR)/configs/Board.mk diff --git a/configs/nucleo-l452re/src/nucleo-l452re.h b/configs/nucleo-l452re/src/nucleo-l452re.h new file mode 100644 index 0000000000..4ab3436861 --- /dev/null +++ b/configs/nucleo-l452re/src/nucleo-l452re.h @@ -0,0 +1,149 @@ +/**************************************************************************** + * configs/nucleo-l452re/src/nucleo-l452re.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Alan Carvalho de Assis + * + * 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 __CONFIGS_NUCLEO_L452RE_SRC_NUCLEO_L452RE_H +#define __CONFIGS_NUCLEO_L452RE_SRC_NUCLEO_L452RE_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +#include "stm32l4_gpio.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +#define HAVE_PROC 1 +#define HAVE_RTC_DRIVER 1 +#define HAVE_MMCSD 1 + +#if !defined(CONFIG_FS_PROCFS) +# undef HAVE_PROC +#endif + +#if defined(HAVE_PROC) && defined(CONFIG_DISABLE_MOUNTPOINT) +# warning Mountpoints disabled. No procfs support +# undef HAVE_PROC +#endif + +/* Check if we can support the RTC driver */ + +#if !defined(CONFIG_RTC) || !defined(CONFIG_RTC_DRIVER) +# undef HAVE_RTC_DRIVER +#endif + +#if !defined(CONFIG_STM32L4_SDIO) || !defined(CONFIG_MMCSD) || \ + !defined(CONFIG_MMCSD_SDIO) +# undef HAVE_MMCSD +#endif + +/* How many SPI modules does this chip support? */ + +#if STM32L4_NSPI < 1 +# undef CONFIG_STM32L4_SPI1 +# undef CONFIG_STM32L4_SPI2 +# undef CONFIG_STM32L4_SPI3 +#elif STM32L4_NSPI < 2 +# undef CONFIG_STM32L4_SPI2 +# undef CONFIG_STM32L4_SPI3 +#elif STM32L4_NSPI < 3 +# undef CONFIG_STM32L4_SPI3 +#endif + +/* Nucleo-L452RE GPIOs ******************************************************/ +/* LED. User LD2: the green LED is a user LED connected to Arduino signal + * D13 corresponding to MCU I/O PA5 (pin 21) or PB13 (pin 34) depending on + * the STM32 target. + * + * - When the I/O is HIGH value, the LED is on. + * - When the I/O is LOW, the LED is off. + */ + +#define GPIO_LD2 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_2MHz | \ + GPIO_OUTPUT_CLEAR | GPIO_PORTA | GPIO_PIN5) + + +/* Button definitions *******************************************************/ +/* B1 USER: the user button is connected to the I/O PC13 (pin 2) of the STM32 + * microcontroller. + */ + +#define MIN_IRQBUTTON BUTTON_USER +#define MAX_IRQBUTTON BUTTON_USER +#define NUM_IRQBUTTONS 1 + +#define GPIO_BTN_USER (GPIO_INPUT | GPIO_FLOAT | GPIO_EXTI | \ + GPIO_PORTC | GPIO_PIN13) + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/**************************************************************************** + * Public data + ****************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_bringup + * + * Description: + * Perform architecture-specific initialization + * + * CONFIG_BOARD_INITIALIZE=y : + * Called from board_initialize(). + * + * CONFIG_BOARD_INITIALIZE=n && CONFIG_LIB_BOARDCTL=y : + * Called from the NSH library + * + ****************************************************************************/ + +int stm32_bringup(void); + +#endif /* __ASSEMBLY__ */ +#endif /* __CONFIGS_NUCLEO_L452RE_SRC_NUCLEO_L452RE_H */ diff --git a/configs/nucleo-l452re/src/stm32_appinit.c b/configs/nucleo-l452re/src/stm32_appinit.c new file mode 100644 index 0000000000..26b1b4f4c5 --- /dev/null +++ b/configs/nucleo-l452re/src/stm32_appinit.c @@ -0,0 +1,87 @@ +/**************************************************************************** + * config/nucleo-l452re/src/stm32_appinit.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Alan Carvalho de Assis + * + * 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 "nucleo-l452re.h" + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; the meaning of the argument is a contract + * between the board-specific initalization logic and the the + * matching application logic. The value cold be such things as a + * mode enumeration value, a set of DIP switch switch settings, a + * pointer to configuration data read from a file or serial FLASH, + * or whatever you would like to do with it. Every implementation + * should accept zero/NULL as a default configuration. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ + +int board_app_initialize(uintptr_t arg) +{ + /* Did we already initialize via board_initialize()? */ + +#ifndef CONFIG_BOARD_INITIALIZE + return stm32_bringup(); +#else + return OK; +#endif +} diff --git a/configs/nucleo-l452re/src/stm32_autoleds.c b/configs/nucleo-l452re/src/stm32_autoleds.c new file mode 100644 index 0000000000..197478aeaa --- /dev/null +++ b/configs/nucleo-l452re/src/stm32_autoleds.c @@ -0,0 +1,96 @@ +/**************************************************************************** + * configs/nucleo-l452re/src/stm32_autoleds.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "up_arch.h" +#include "up_internal.h" +#include "stm32l4_gpio.h" +#include "nucleo-l452re.h" + +#ifdef CONFIG_ARCH_LEDS + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_autoled_initialize + ****************************************************************************/ + +void board_autoled_initialize(void) +{ + /* Configure LD2 GPIO for output */ + + stm32l4_configgpio(GPIO_LD2); +} + +/**************************************************************************** + * Name: board_autoled_on + ****************************************************************************/ + +void board_autoled_on(int led) +{ + if (led == 1) + { + stm32l4_gpiowrite(GPIO_LD2, true); + } +} + +/**************************************************************************** + * Name: board_autoled_off + ****************************************************************************/ + +void board_autoled_off(int led) +{ + if (led == 1) + { + stm32l4_gpiowrite(GPIO_LD2, false); + } +} + +#endif /* CONFIG_ARCH_LEDS */ diff --git a/configs/nucleo-l452re/src/stm32_boot.c b/configs/nucleo-l452re/src/stm32_boot.c new file mode 100644 index 0000000000..9e7c287303 --- /dev/null +++ b/configs/nucleo-l452re/src/stm32_boot.c @@ -0,0 +1,94 @@ +/************************************************************************************ + * configs/nucleo-l452re/src/stm32_boot.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Alan Carvalho de Assis + * + * 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 "up_arch.h" +#include "nucleo-l452re.h" + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32l4_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the intitialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +void stm32l4_boardinitialize(void) +{ +#ifdef CONFIG_ARCH_LEDS + /* Configure on-board LEDs if LED support has been selected. */ + + board_autoled_initialize(); +#endif +} + +/**************************************************************************** + * Name: board_initialize + * + * Description: + * If CONFIG_BOARD_INITIALIZE is selected, then an additional + * initialization call will be performed in the boot-up sequence to a + * function called board_initialize(). board_initialize() will be + * called immediately after up_initialize() is called and just before the + * initial application is started. This additional initialization phase + * may be used, for example, to initialize board-specific device drivers. + * + ****************************************************************************/ + +#ifdef CONFIG_BOARD_INITIALIZE +void board_initialize(void) +{ + /* Perform board-specific initialization here if so configured */ + + (void)stm32_bringup(); +} +#endif diff --git a/configs/nucleo-l452re/src/stm32_bringup.c b/configs/nucleo-l452re/src/stm32_bringup.c new file mode 100644 index 0000000000..b50fe95827 --- /dev/null +++ b/configs/nucleo-l452re/src/stm32_bringup.c @@ -0,0 +1,117 @@ +/**************************************************************************** + * config/nucleo-l452re/src/stm32_bringup.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include + +#include "stm32l4_i2c.h" +#include "nucleo-l452re.h" + +/**************************************************************************** + * Pre-processor Defintiionis + ****************************************************************************/ + +#undef HAVE_I2C_DRIVER +#if defined(CONFIG_STM32L4_I2C1) && defined(CONFIG_I2C_DRIVER) +# define HAVE_I2C_DRIVER 1 +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_bringup + * + * Description: + * Perform architecture-specific initialization + * + * CONFIG_BOARD_INITIALIZE=y : + * Called from board_initialize(). + * + * CONFIG_BOARD_INITIALIZE=n && CONFIG_LIB_BOARDCTL=y : + * Called from the NSH library + * + ****************************************************************************/ + +int stm32_bringup(void) +{ +#ifdef HAVE_I2C_DRIVER + FAR struct i2c_master_s *i2c; +#endif + int ret; + +#ifdef CONFIG_FS_PROCFS + /* Mount the procfs file system */ + + ret = mount(NULL, "/proc", "procfs", 0, NULL); + if (ret < 0) + { + ferr("ERROR: Failed to mount procfs at /proc: %d\n", ret); + } +#endif + +#ifdef HAVE_I2C_DRIVER + /* Get the I2C lower half instance */ + + i2c = stm32l4_i2cbus_initialize(1); + if (i2c == NULL) + { + i2cerr("ERROR: Initialize I2C1: %d\n", ret); + } + else + { + /* Register the I2C character driver */ + + ret = i2c_register(i2c, 1); + if (ret < 0) + { + i2cerr("ERROR: Failed to register I2C1 device: %d\n", ret); + } + } +#endif + + UNUSED(ret); + return OK; +} diff --git a/configs/nucleo-l452re/src/stm32_buttons.c b/configs/nucleo-l452re/src/stm32_buttons.c new file mode 100644 index 0000000000..1d48c1f4a6 --- /dev/null +++ b/configs/nucleo-l452re/src/stm32_buttons.c @@ -0,0 +1,128 @@ +/**************************************************************************** + * configs/nucleo-l452re/src/stm32_buttons.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include +#include +#include + +#include "stm32l4_gpio.h" +#include "nucleo-l452re.h" + +#ifdef CONFIG_ARCH_BUTTONS + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_button_initialize + * + * Description: + * board_button_initialize() must be called to initialize button resources. + * After that, board_buttons() may be called to collect the current state + * of all buttons or board_button_irq() may be called to register button + * interrupt handlers. + * + ****************************************************************************/ + +void board_button_initialize(void) +{ + /* Configure the single button as an input. NOTE that EXTI interrupts are + * also configured for the pin. + */ + + stm32l4_configgpio(GPIO_BTN_USER); +} + +/**************************************************************************** + * Name: board_buttons + ****************************************************************************/ + +uint32_t board_buttons(void) +{ + /* Check that state of each USER button. A LOW value means that the key is + * pressed. + */ + + bool released = stm32l4_gpioread(GPIO_BTN_USER); + return !released; +} + +/************************************************************************************ + * Button support. + * + * Description: + * board_button_initialize() must be called to initialize button resources. After + * that, board_buttons() may be called to collect the current state of all + * buttons or board_button_irq() may be called to register button interrupt + * handlers. + * + * After board_button_initialize() has been called, board_buttons() may be called to + * collect the state of all buttons. board_buttons() returns an 32-bit bit set + * with each bit associated with a button. See the BUTTON_*_BIT + * definitions in board.h for the meaning of each bit. + * + * board_button_irq() may be called to register an interrupt handler that will + * be called when a button is depressed or released. The ID value is a + * button enumeration value that uniquely identifies a button resource. See the + * BUTTON_* definitions in board.h for the meaning of enumeration + * value. + * + ************************************************************************************/ + +#ifdef CONFIG_ARCH_IRQBUTTONS +int board_button_irq(int id, xcpt_t irqhandler, FAR void *arg) +{ + int ret = -EINVAL; + + if (id == BUTTON_USER) + { + ret = stm32l4_gpiosetevent(GPIO_BTN_USER, true, true, true, irqhandler, arg); + } + + return ret; +} +#endif +#endif /* CONFIG_ARCH_BUTTONS */ diff --git a/configs/nucleo-l452re/src/stm32_spi.c b/configs/nucleo-l452re/src/stm32_spi.c new file mode 100644 index 0000000000..02f17ca607 --- /dev/null +++ b/configs/nucleo-l452re/src/stm32_spi.c @@ -0,0 +1,223 @@ +/**************************************************************************** + * configs/nucleo-l452re/src/stm32_spi.c + * + * Copyright (C) 2014 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. + * + ****************************************************************************/ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include + +#include "nucleo-l452re.h" + +#if defined(CONFIG_STM32L4_SPI1) || defined(CONFIG_STM32L4_SPI2) || defined(CONFIG_STM32L4_SPI3) + +/************************************************************************************ + * Public Data + ************************************************************************************/ +/* Global driver instances */ + +#ifdef CONFIG_STM32L4_SPI1 +struct spi_dev_s *g_spi1; +#endif +#ifdef CONFIG_STM32L4_SPI2 +struct spi_dev_s *g_spi2; +#endif + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32l4_spiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins. + * + ************************************************************************************/ + +void weak_function stm32l4_spiinitialize(void) +{ +#ifdef CONFIG_STM32L4_SPI1 + /* Configure SPI-based devices */ + + g_spi1 = stm32l4_spibus_initialize(1); + if (!g_spi1) + { + spierr("ERROR: FAILED to initialize SPI port 1\n"); + } + +#ifdef HAVE_MMCSD + stm32l4_configgpio(GPIO_SPI_CS_SD_CARD); +#endif +#endif + +#ifdef CONFIG_STM32L4_SPI2 + /* Configure SPI-based devices */ + + g_spi2 = stm32l4_spibus_initialize(2); + if (!g_spi2) + { + spierr("ERROR: FAILED to initialize SPI port 1\n"); + } +#endif +} + +/**************************************************************************** + * Name: stm32l4_spi1/2/3select and stm32l4_spi1/2/3status + * + * Description: + * The external functions, stm32l4_spi1/2/3select and stm32l4_spi1/2/3status must be + * provided by board-specific logic. They are implementations of the select + * and status methods of the SPI interface defined by struct spi_ops_s (see + * include/nuttx/spi/spi.h). All other methods (including up_spiinitialize()) + * are provided by common STM32 logic. To use this common SPI logic on your + * board: + * + * 1. Provide logic in stm32l4_boardinitialize() to configure SPI chip select + * pins. + * 2. Provide stm32l4_spi1/2/3select() and stm32l4_spi1/2/3status() functions in your + * board-specific logic. These functions will perform chip selection and + * status operations using GPIOs in the way your board is configured. + * 3. Add a calls to up_spiinitialize() in your low level application + * initialization logic + * 4. The handle returned by up_spiinitialize() may then be used to bind the + * SPI driver to higher level logic (e.g., calling + * mmcsd_spislotinitialize(), for example, will bind the SPI driver to + * the SPI MMC/SD driver). + * + ****************************************************************************/ + +#ifdef CONFIG_STM32L4_SPI1 +void stm32l4_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) +{ + spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); + +#ifdef HAVE_MMCSD + if (devid == SPIDEV_MMCSD(0)) + { + stm32l4_gpiowrite(GPIO_SPI_CS_SD_CARD, !selected); + } +#endif +} + +uint8_t stm32l4_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) +{ + return 0; +} +#endif + +#ifdef CONFIG_STM32L4_SPI2 +void stm32l4_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) +{ + spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); +} + +uint8_t stm32l4_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) +{ + return 0; +} +#endif + +#ifdef CONFIG_STM32L4_SPI3 +void stm32l4_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) + + spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); +} + +uint8_t stm32l4_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) +{ + return 0; +} +#endif + +/**************************************************************************** + * Name: stm32l4_spi1cmddata + * + * Description: + * Set or clear the SH1101A A0 or SD1306 D/C n bit to select data (true) + * or command (false). This function must be provided by platform-specific + * logic. This is an implementation of the cmddata method of the SPI + * interface defined by struct spi_ops_s (see include/nuttx/spi/spi.h). + * + * Input Parameters: + * + * spi - SPI device that controls the bus the device that requires the CMD/ + * DATA selection. + * devid - If there are multiple devices on the bus, this selects which one + * to select cmd or data. NOTE: This design restricts, for example, + * one one SPI display per SPI bus. + * cmd - true: select command; false: select data + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_SPI_CMDDATA +#ifdef CONFIG_STM32L4_SPI1 +int stm32l4_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) +{ + return OK; +} +#endif + +#ifdef CONFIG_STM32L4_SPI2 +int stm32l4_spi2cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) +{ + return OK; +} +#endif + +#ifdef CONFIG_STM32L4_SPI3 +int stm32l4_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd) +{ + return OK; +} +#endif +#endif /* CONFIG_SPI_CMDDATA */ + +#endif /* CONFIG_STM32L4_SPI1 || CONFIG_STM32L4_SPI2 || CONFIG_STM32L4_SPI3 */ diff --git a/configs/nucleo-l452re/src/stm32_userleds.c b/configs/nucleo-l452re/src/stm32_userleds.c new file mode 100644 index 0000000000..77ba277c34 --- /dev/null +++ b/configs/nucleo-l452re/src/stm32_userleds.c @@ -0,0 +1,217 @@ +/**************************************************************************** + * configs/nucleo-l452re/src/stm32_userleds.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "up_arch.h" +#include "up_internal.h" +#include "stm32l4_gpio.h" +#include "nucleo-l452re.h" + +#ifndef CONFIG_ARCH_LEDS + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* LED Power Management */ + +#ifdef CONFIG_PM +static void led_pm_notify(struct pm_callback_s *cb, int domain, + enum pm_state_e pmstate); +static int led_pm_prepare(struct pm_callback_s *cb, int domain, + enum pm_state_e pmstate); +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +#ifdef CONFIG_PM +static struct pm_callback_s g_ledscb = +{ + .notify = led_pm_notify, + .prepare = led_pm_prepare, +}; +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: led_pm_notify + * + * Description: + * Notify the driver of new power state. This callback is called after + * all drivers have had the opportunity to prepare for the new power state. + * + ****************************************************************************/ + +#ifdef CONFIG_PM +static void led_pm_notify(struct pm_callback_s *cb, int domain, + enum pm_state_e pmstate) +{ + switch (pmstate) + { + case(PM_NORMAL): + { + /* Restore normal LEDs operation */ + + } + break; + + case(PM_IDLE): + { + /* Entering IDLE mode - Turn leds off */ + + } + break; + + case(PM_STANDBY): + { + /* Entering STANDBY mode - Logic for PM_STANDBY goes here */ + + } + break; + + case(PM_SLEEP): + { + /* Entering SLEEP mode - Logic for PM_SLEEP goes here */ + + } + break; + + default: + { + /* Should not get here */ + + } + break; + } +} +#endif + +/**************************************************************************** + * Name: led_pm_prepare + * + * Description: + * Request the driver to prepare for a new power state. This is a warning + * that the system is about to enter into a new power state. The driver + * should begin whatever operations that may be required to enter power + * state. The driver may abort the state change mode by returning a + * non-zero value from the callback function. + * + ****************************************************************************/ + +#ifdef CONFIG_PM +static int led_pm_prepare(struct pm_callback_s *cb, int domain, + enum pm_state_e pmstate) +{ + /* No preparation to change power modes is required by the LEDs driver. + * We always accept the state change by returning OK. + */ + + return OK; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_userled_initialize + ****************************************************************************/ + +void board_userled_initialize(void) +{ + /* Configure LD2 GPIO for output */ + + stm32l4_configgpio(GPIO_LD2); +} + +/**************************************************************************** + * Name: board_userled + ****************************************************************************/ + +void board_userled(int led, bool ledon) +{ + if (led == 1) + { + stm32l4_gpiowrite(GPIO_LD2, ldeon); + } +} + +/**************************************************************************** + * Name: board_userled_all + ****************************************************************************/ + +void board_userled_all(uint8_t ledset) +{ + if (led == 1) + { + stm32l4_gpiowrite(GPIO_LD2, (ledset & BOARD_LD2_BIT) != 0); + } +} + +/**************************************************************************** + * Name: stm32l4_led_pminitialize + ****************************************************************************/ + +#ifdef CONFIG_PM +void stm32l4_led_pminitialize(void) +{ + /* Register to receive power management callbacks */ + + int ret = pm_register(&g_ledscb); + DEBUGASSERT(ret == OK); + UNUSED(ret); +} +#endif /* CONFIG_PM */ + +#endif /* !CONFIG_ARCH_LEDS */ -- GitLab From afc46cb7ba5ab262aabe29932d8e173dac55580f Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Thu, 4 May 2017 06:50:08 -0600 Subject: [PATCH 704/990] fixedmath: add square root and b32_t conversion operators --- include/fixedmath.h | 43 ++++++++++-- libc/fixedmath/Make.defs | 1 + libc/fixedmath/lib_ubsqrt.c | 136 ++++++++++++++++++++++++++++++++++++ 3 files changed, 173 insertions(+), 7 deletions(-) create mode 100644 libc/fixedmath/lib_ubsqrt.c diff --git a/include/fixedmath.h b/include/fixedmath.h index 665179c427..bd8383672e 100644 --- a/include/fixedmath.h +++ b/include/fixedmath.h @@ -1,7 +1,7 @@ /**************************************************************************** * include/fixedmath.h * - * Copyright (C) 2008 Gregory Nutt. All rights reserved. + * Copyright (C) 2008, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -40,6 +40,7 @@ * Included Files ****************************************************************************/ +#include #include /**************************************************************************** @@ -124,7 +125,7 @@ #define ub8toi(a) ((a) >> 8) /* Conversion to unsigned integer */ #define itob8(i) (((b8_t)(i)) << 8) /* Conversion from integer */ #define uitoub8(i) (((ub8_t)(i)) << 8) /* Conversion from unsigned integer */ -#define b8tof(b) (((float)b)/256.0) /* Conversion to float */ +#define b8tof(b) (((float)(b))/256.0) /* Conversion to float */ #define ftob8(f) (b8_t)(((f)*256.0)) /* Conversion from float */ #define b8trunc(a) ((a) & 0xff00) /* Truncate to integer b8 */ #define b8round(a) (((a)+0x0080) & 0xff00) /* Round to integer b8 */ @@ -138,13 +139,13 @@ #define b8addi(a,i) ((a)+itob8(i)) /* Add integer from b16 */ #define b8subb8(a,b) ((a)-(b)) /* Subtraction */ #define b8subi(a,i) ((a)-itob8(i)) /* Subtract integer from b8 */ -#define b8mulb8(a,b) b16tob8((b16_t)(a)*(b16_t)(b) /* Muliplication */ -#define ub8mulub8(a,b) ub16toub8((ub16_t)(a)*(ub16_t)(b) /* Muliplication */ +#define b8mulb8(a,b) (b16tob8((b16_t)(a)*(b16_t)(b)) /* Muliplication */ +#define ub8mulub8(a,b) (ub16toub8((ub16_t)(a)*(ub16_t)(b)) /* Muliplication */ #define b8muli(a,i) ((a)*(i)) /* Simple multiplication by integer */ #define b8sqr(a) b8mulb8(a,a) /* Square */ #define ub8sqr(a) ub8mulub8(a,a) /* Square */ -#define b8divb8(a,b) b8tob16(a)/(b16_t)(b) /* Division */ -#define ub8divub8(a,b) ub8toub16(a)/(ub16_t)(b) /* Division */ +#define b8divb8(a,b) (b8tob16(a)/(b16_t)(b)) /* Division */ +#define ub8divub8(a,b) (ub8toub16(a)/(ub16_t)(b)) /* Division */ #define b8divi(a,i) ((a)/(i)) /* Simple division by integer */ #define b8idiv(i,j) (((i)<<8)/j) /* Division of integer, b8 result */ @@ -156,7 +157,7 @@ #define ub16toi(a) ((a) >> 16) /* Conversion to unsgined integer */ #define itob16(i) (((b16_t)(i)) << 16) /* Conversion from integer */ #define uitoub16(i) (((ub16_t)(i)) << 16) /* Conversion from unsigned integer */ -#define b16tof(b) (((float)b)/65536.0) /* Conversion to float */ +#define b16tof(b) (((float)(b))/65536.0) /* Conversion to float */ #define ftob16(f) (b16_t)(((f)*65536.0)) /* Conversion from float */ #define b16trunc(a) ((a) & 0xffff0000) /* Truncate to integer */ #define b16round(a) (((a)+0x00008000) & 0xffff0000) @@ -189,6 +190,27 @@ # define b16divb16(a,b) (b16_t)(b16tob32(a)/(b32_t)(b)) # define ub16divub16(a,b) (ub16_t)(ub16toub32(a)/(ub32_t)(b)) + +/* Square root operators */ + +# define ub16sqrtub16(a) ub32sqrtub16(ub16toub32(a)) +#else +# define ub16sqrtub16(a) ub8toub16(ub16sqrtub8(a)) +#endif + +/* 64-bit values with 32 bits of precision ********************************/ + +#ifdef CONFIG_HAVE_LONG_LONG +/* Conversions */ + +#define b32toi(a) ((a) >> 32) /* Conversion to integer */ +#define itob32(i) (((b32_t)(i)) << 32) /* Conversion from integer */ +#define uitoub32(i) (((ub32_t)(i)) << 32) /* Conversion from unsigned integer */ +#define b32tod(b) (((double)(b))/((long long)1 << 32)) /* Conversion to double */ +#define dtob32(f) (b32_t)(((f)*(double)((long long)1 << 32))) /* Conversion from double */ +#define b32trunc(a) ((a) & 0xffffffff00000000) /* Truncate to integer */ +#define b32round(a) (((a)+0x0000000080000000) & 0xffffffff00000000) +#define b32frac(a) ((a) & 0x00000000ffffffff) /* Take fractional part */ #endif /**************************************************************************** @@ -240,6 +262,13 @@ b16_t b16sin(b16_t rad); b16_t b16cos(b16_t rad); b16_t b16atan2(b16_t y, b16_t x); +/* Square root operators */ + +#ifdef CONFIG_HAVE_LONG_LONG +ub16_t ub32sqrtub16(ub32_t a); +#endif +ub8_t ub16sqrtub8(ub16_t a); + #undef EXTERN #if defined(__cplusplus) } diff --git a/libc/fixedmath/Make.defs b/libc/fixedmath/Make.defs index e4534184c9..2c77345343 100644 --- a/libc/fixedmath/Make.defs +++ b/libc/fixedmath/Make.defs @@ -36,6 +36,7 @@ # Add the fixed precision math C files to the build CSRCS += lib_fixedmath.c lib_b16sin.c lib_b16cos.c lib_b16atan2.c +CSRCS += lib_ubsqrt.c # Add the fixed precision math directory to the build diff --git a/libc/fixedmath/lib_ubsqrt.c b/libc/fixedmath/lib_ubsqrt.c new file mode 100644 index 0000000000..9e1b26a5af --- /dev/null +++ b/libc/fixedmath/lib_ubsqrt.c @@ -0,0 +1,136 @@ +/**************************************************************************** + * libc/fixedmath/lib_ubsqrt.c + * + * Copyright (C) 2014,2017 Jussi Kivilinna + * + * 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 + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +#ifdef CONFIG_HAVE_LONG_LONG + +/**************************************************************************** + * Name: ub32sqrtub16 + * + * Description: + * ub32sqrtub16 calculates square root for 'a' + * + ****************************************************************************/ + +ub16_t ub32sqrtub16(ub32_t a) +{ + uint64_t n = a; + uint64_t xk = n; + + /* Direct conversion of ub32_t to uint64_t is same operation as multiplying + * 'a' by 2^32, therefore n = a * 2^32. + */ + + if (xk == UINT64_MAX) + { + /* Avoid 'xk + n / xk' overflow on first iteration. */ + + xk = 1ULL << 63; + } + + do + { + uint64_t xk1 = (xk + n / xk) >> 1; + + if (xk1 >= xk) + { + break; + } + + xk = xk1; + } + while (1); + + /* 'xk' now holds 'sqrt(n)' => 'sqrt(a * 2^32)' => 'sqrt(a) * 2^16', thus + * 'xk' holds square root of 'a' in ub16_t format. + */ + + return (ub16_t)xk; +} + +#endif + +/**************************************************************************** + * Name: ub16sqrtub8 + * + * Description: + * ub16sqrtub8 calculates square root for 'a' + * + ****************************************************************************/ + +ub8_t ub16sqrtub8(ub16_t a) +{ + uint32_t n = a; + uint32_t xk = n; + + /* Direct conversion of ub16_t to uint32_t is same operation as multiplying + * 'a' by 2^16, therefore n = a * 2^16. + */ + + if (xk == UINT32_MAX) + { + /* Avoid 'xk + n / xk' overflow on first iteration. */ + + xk = 1U << 31; + } + + do + { + uint32_t xk1 = (xk + n / xk) >> 1; + + if (xk1 >= xk) + { + break; + } + + xk = xk1; + } + while (1); + + /* 'xk' now holds 'sqrt(n)' => 'sqrt(a * 2^16)' => 'sqrt(a) * 2^8', thus + * 'xk' holds square root of 'a' in ub8_t format. + */ + + return (ub8_t)xk; +} -- GitLab From acf0d17e5a2ef4807d2f8e0ebd63b1221ed660bc Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Thu, 4 May 2017 06:51:44 -0600 Subject: [PATCH 705/990] Fix STM32F7 I2C interrupt handler --- arch/arm/src/stm32f7/stm32_i2c.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/arch/arm/src/stm32f7/stm32_i2c.c b/arch/arm/src/stm32f7/stm32_i2c.c index be3122ea4e..38c1f08268 100644 --- a/arch/arm/src/stm32f7/stm32_i2c.c +++ b/arch/arm/src/stm32f7/stm32_i2c.c @@ -2141,7 +2141,7 @@ static int stm32_i2c_isr(int irq, void *context, FAR void *arg) struct stm32_i2c_priv_s *priv = (struct stm32_i2c_priv_s *)arg; DEBUGASSERT(priv != NULL); - return stm32_i2c_isr_process(&stm32_i2c1_priv); + return stm32_i2c_isr_process(priv); } #endif @@ -2189,7 +2189,7 @@ static int stm32_i2c_init(FAR struct stm32_i2c_priv_s *priv) * - Provide means to set peripheral clock source via RCC_CFGR3_I2CxSW * - Set to HSI by default, make Kconfig option */ - + /* Force a frequency update */ priv->frequency = 0; -- GitLab From 7035723aebd23c10aa9783b31f19909aa90131ae Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Thu, 4 May 2017 07:09:19 -0600 Subject: [PATCH 706/990] STM32F7 serial: Allow configuring Rx DMA buffer size --- arch/arm/src/stm32f7/Kconfig | 12 ++++++++++++ arch/arm/src/stm32f7/stm32_serial.c | 25 ++++++++++++++++++++----- 2 files changed, 32 insertions(+), 5 deletions(-) diff --git a/arch/arm/src/stm32f7/Kconfig b/arch/arm/src/stm32f7/Kconfig index 95e931abc2..123277ba13 100644 --- a/arch/arm/src/stm32f7/Kconfig +++ b/arch/arm/src/stm32f7/Kconfig @@ -1614,6 +1614,18 @@ config UART8_RXDMA ---help--- In high data rate usage, Rx DMA may eliminate Rx overrun errors +config STM32F7_SERIAL_RXDMA_BUFFER_SIZE + int "Rx DMA buffer size" + default 32 + depends on USART1_RXDMA || USART2_RXDMA || USART3_RXDMA || UART4_RXDMA || UART5_RXDMA || USART6_RXDMA || UART7_RXDMA || UART8_RXDMA + ---help--- + The DMA buffer size when using RX DMA to emulate a FIFO. + + When streaming data, the generic serial layer will be called + every time the FIFO receives half this number of bytes. + + Value given here will be rounded up to next multiple of 32 bytes. + config SERIAL_DISABLE_REORDERING bool "Disable reordering of ttySx devices." depends on STM32F7_USART1 || STM32F7_USART2 || STM32F7_USART3 || STM32F7_UART4 || STM32F7_UART5 || STM32F7_USART6 || STM32F7_UART7 || STM32F7_UART8 diff --git a/arch/arm/src/stm32f7/stm32_serial.c b/arch/arm/src/stm32f7/stm32_serial.c index 5c2b8b74bc..ce6e7db9a7 100644 --- a/arch/arm/src/stm32f7/stm32_serial.c +++ b/arch/arm/src/stm32f7/stm32_serial.c @@ -159,15 +159,30 @@ /* The DMA buffer size when using RX DMA to emulate a FIFO. * - * When streaming data, the generic serial layer will be called - * every time the FIFO receives half this number of bytes. + * When streaming data, the generic serial layer will be called every time + * the FIFO receives half this number of bytes. * - * This buffer size should be an even multiple of the Cortex-M7 - * D-Cache line size so that it can be individually invalidated. + * This buffer size should be an even multiple of the Cortex-M7 D-Cache line + * size, ARMV7M_DCACHE_LINESIZE, so that it can be individually invalidated. + * + * Should there be a Cortex-M7 without a D-Cache, ARMV7M_DCACHE_LINESIZE + * would be zero! */ +# if !defined(ARMV7M_DCACHE_LINESIZE) || ARMV7M_DCACHE_LINESIZE == 0 +# undef ARMV7M_DCACHE_LINESIZE +# define ARMV7M_DCACHE_LINESIZE 32 +# endif + +# if !defined(CONFIG_STM32F7_SERIAL_RXDMA_BUFFER_SIZE) || \ + (CONFIG_STM32F7_SERIAL_RXDMA_BUFFER_SIZE < ARMV7M_DCACHE_LINESIZE) +# undef CONFIG_STM32F7_SERIAL_RXDMA_BUFFER_SIZE +# define CONFIG_STM32F7_SERIAL_RXDMA_BUFFER_SIZE ARMV7M_DCACHE_LINESIZE +# endif + # define RXDMA_BUFFER_MASK (ARMV7M_DCACHE_LINESIZE - 1) -# define RXDMA_BUFFER_SIZE ((32 + RXDMA_BUFFER_MASK) & ~RXDMA_BUFFER_MASK) +# define RXDMA_BUFFER_SIZE ((CONFIG_STM32F7_SERIAL_RXDMA_BUFFER_SIZE \ + + RXDMA_BUFFER_MASK) & ~RXDMA_BUFFER_MASK) /* DMA priority */ -- GitLab From 969c1ab6144e4f2e4cf56ea5d5799d8ad6c0cf83 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 4 May 2017 08:20:59 -0600 Subject: [PATCH 707/990] 6loWPAN: Replace some Rime address naming with more consistent short/exended address terminology --- configs/sim/sixlowpan/defconfig | 2 +- include/nuttx/net/ieee802154.h | 39 ++++++++++++++++++------ include/nuttx/net/netdev.h | 2 +- include/nuttx/net/sixlowpan.h | 2 +- net/netdev/netdev_ioctl.c | 6 ++-- net/procfs/netdev_statistics.c | 4 +-- net/sixlowpan/Kconfig | 2 +- net/sixlowpan/sixlowpan_framelist.c | 8 ++--- net/sixlowpan/sixlowpan_framer.c | 10 +++--- net/sixlowpan/sixlowpan_globals.c | 2 +- net/sixlowpan/sixlowpan_hc06.c | 14 ++++----- net/sixlowpan/sixlowpan_hc1.c | 2 +- net/sixlowpan/sixlowpan_input.c | 2 +- net/sixlowpan/sixlowpan_internal.h | 22 ++++++------- net/sixlowpan/sixlowpan_send.c | 4 +-- net/sixlowpan/sixlowpan_tcpsend.c | 4 +-- net/sixlowpan/sixlowpan_udpsend.c | 2 +- net/sixlowpan/sixlowpan_utils.c | 20 ++++++------ wireless/ieee802154/mac802154_loopback.c | 6 ++-- 19 files changed, 87 insertions(+), 66 deletions(-) diff --git a/configs/sim/sixlowpan/defconfig b/configs/sim/sixlowpan/defconfig index 5c64eb13e6..f46639d003 100644 --- a/configs/sim/sixlowpan/defconfig +++ b/configs/sim/sixlowpan/defconfig @@ -548,7 +548,7 @@ CONFIG_NET_6LOWPAN_MAXADDRCONTEXT=1 CONFIG_NET_6LOWPAN_MAXADDRCONTEXT_PREFIX_0_0=0xaa CONFIG_NET_6LOWPAN_MAXADDRCONTEXT_PREFIX_0_1=0xaa # CONFIG_NET_6LOWPAN_MAXADDRCONTEXT_PREINIT_1 is not set -# CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED is not set +# CONFIG_NET_6LOWPAN_EXTENDEDADDR is not set CONFIG_NET_6LOWPAN_MAXAGE=20 CONFIG_NET_6LOWPAN_MAX_MACTRANSMITS=4 CONFIG_NET_6LOWPAN_MTU=1294 diff --git a/include/nuttx/net/ieee802154.h b/include/nuttx/net/ieee802154.h index 6132d3d02b..9d9260f61b 100644 --- a/include/nuttx/net/ieee802154.h +++ b/include/nuttx/net/ieee802154.h @@ -58,15 +58,18 @@ * Pre-processor Definitions ****************************************************************************/ -/* By default, a 2-byte Rime address is used for the IEEE802.15.4 MAC - * device's link layer address. If CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED - * is selected, then an 8-byte Rime address will be used. +/* By default, a 2-byte short address is used for the IEEE802.15.4 MAC + * device's link layer address. If CONFIG_NET_6LOWPAN_EXTENDEDADDR + * is selected, then an 8-byte extended address will be used. */ -#ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED -# define NET_6LOWPAN_RIMEADDR_SIZE 8 +#define NET_6LOWPAN_SADDRSIZE 2 +#define NET_6LOWPAN_EADDRSIZE 8 + +#ifdef CONFIG_NET_6LOWPAN_EXTENDEDADDR +# define NET_6LOWPAN_ADDRSIZE NET_6LOWPAN_EADDRSIZE #else -# define NET_6LOWPAN_RIMEADDR_SIZE 2 +# define NET_6LOWPAN_ADDRSIZE NET_6LOWPAN_SADDRSIZE #endif /* Frame format definitions *************************************************/ @@ -123,11 +126,29 @@ * Public Types ****************************************************************************/ -/* Rime address representation */ +/* IEEE 802.15.4 address representations */ + +struct sixlowpan_saddr_s +{ + uint8_t u8[NET_6LOWPAN_SADDRSIZE]; +}; + +struct sixlowpan_eaddr_s +{ + uint8_t u8[NET_6LOWPAN_EADDRSIZE]; +}; + +union sixlowpan_anyaddr_u +{ + struct sixlowpan_saddr_s saddr; + struct sixlowpan_eaddr_s eaddr; +}; + +/* Represents the configured address size */ -struct rimeaddr_s +struct sixlowpan_addr_s { - uint8_t u8[NET_6LOWPAN_RIMEADDR_SIZE]; + uint8_t u8[NET_6LOWPAN_ADDRSIZE]; }; /**************************************************************************** diff --git a/include/nuttx/net/netdev.h b/include/nuttx/net/netdev.h index 7f8e4041f4..fe2743f5e9 100644 --- a/include/nuttx/net/netdev.h +++ b/include/nuttx/net/netdev.h @@ -224,7 +224,7 @@ struct net_driver_s #ifdef CONFIG_NET_6LOWPAN /* The address assigned to an IEEE 802.15.4 radio. */ - struct rimeaddr_s ieee802154; /* IEEE 802.15.4 Radio address */ + struct sixlowpan_addr_s ieee802154; /* IEEE 802.15.4 Radio address */ #endif } d_mac; #endif diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index 507f08eb51..94061a365e 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -420,7 +420,7 @@ struct ieee802154_driver_s /* The source MAC address of the fragments being merged */ - struct rimeaddr_s i_fragsrc; + struct sixlowpan_addr_s i_fragsrc; /* That time at which reassembly was started. If the elapsed time * exceeds CONFIG_NET_6LOWPAN_MAXAGE, then the reassembly will diff --git a/net/netdev/netdev_ioctl.c b/net/netdev/netdev_ioctl.c index 9eb099dddb..81bfe9a0b3 100644 --- a/net/netdev/netdev_ioctl.c +++ b/net/netdev/netdev_ioctl.c @@ -790,7 +790,7 @@ static int netdev_ifr_ioctl(FAR struct socket *psock, int cmd, { req->ifr_hwaddr.sa_family = AF_INETX; memcpy(req->ifr_hwaddr.sa_data, - dev->d_mac.ieee802154.u8, NET_6LOWPAN_RIMEADDR_SIZE); + dev->d_mac.ieee802154.u8, NET_6LOWPAN_ADDRSIZE); } else #endif @@ -828,7 +828,7 @@ static int netdev_ifr_ioctl(FAR struct socket *psock, int cmd, #endif { memcpy(dev->d_mac.ieee802154.u8, - req->ifr_hwaddr.sa_data, NET_6LOWPAN_RIMEADDR_SIZE); + req->ifr_hwaddr.sa_data, NET_6LOWPAN_ADDRSIZE); ret = OK; } else @@ -1023,7 +1023,7 @@ static int netdev_arp_ioctl(FAR struct socket *psock, int cmd, case SIOCSARP: /* Set an ARP mapping */ { if (req != NULL && - req->arp_pa.sa_family == AF_INET && + req->arp_pa.sa_family == AF_INET && req->arp_ha.sa_family == ARPHRD_ETHER) { FAR struct sockaddr_in *addr = diff --git a/net/procfs/netdev_statistics.c b/net/procfs/netdev_statistics.c index 5383adfc6a..109f4cdca2 100644 --- a/net/procfs/netdev_statistics.c +++ b/net/procfs/netdev_statistics.c @@ -151,7 +151,7 @@ static int netprocfs_linklayer(FAR struct netprocfs_file_s *netfile) #ifdef CONFIG_NET_6LOWPAN case NET_LL_IEEE802154: { -#ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED +#ifdef CONFIG_NET_6LOWPAN_EXTENDEDADDR len += snprintf(&netfile->line[len], NET_LINELEN - len, "%s\tLink encap:6loWPAN HWaddr " "%02x:%02x:%02x:%02x:%02x:%02x:%02x:%02x", @@ -213,7 +213,7 @@ static int netprocfs_linklayer(FAR struct netprocfs_file_s *netfile) dev->d_ifname, ether_ntoa(&dev->d_mac.ether), status); #elif defined(CONFIG_NET_6LOWPAN) -#ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED +#ifdef CONFIG_NET_6LOWPAN_EXTENDEDADDR len += snprintf(&netfile->line[len], NET_LINELEN - len, "%s\tLink encap:6loWPAN HWaddr " "%02x:%02x:%02x:%02x:%02x:%02x:%02x:%02x at %s\n", diff --git a/net/sixlowpan/Kconfig b/net/sixlowpan/Kconfig index 021571fbd0..4b1c4df409 100644 --- a/net/sixlowpan/Kconfig +++ b/net/sixlowpan/Kconfig @@ -133,7 +133,7 @@ config NET_6LOWPAN_MAXADDRCONTEXT_PREFIX_2_1 endif # NET_6LOWPAN_MAXADDRCONTEXT_PREINIT_0 endif # NET_6LOWPAN_COMPRESSION_HC06 -config NET_6LOWPAN_RIMEADDR_EXTENDED +config NET_6LOWPAN_EXTENDEDADDR bool "Extended Rime address" default n ---help--- diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c index fb03af457f..013f7cbb7e 100644 --- a/net/sixlowpan/sixlowpan_framelist.c +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -209,13 +209,13 @@ static void sixlowpan_compress_ipv6hdr(FAR const struct ipv6_hdr_s *ipv6hdr, int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, FAR const struct ipv6_hdr_s *destip, FAR const void *buf, size_t buflen, - FAR const struct rimeaddr_s *destmac) + FAR const struct sixlowpan_addr_s *destmac) { struct ieee802154_frame_meta_s meta; FAR struct iob_s *iob; FAR uint8_t *fptr; int framer_hdrlen; - struct rimeaddr_s bcastmac; + struct sixlowpan_addr_s bcastmac; uint16_t pktlen; uint16_t paysize; uint16_t dest_panid; @@ -234,7 +234,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, /* Reset rime buffer, packet buffer metatadata */ memset(g_pktattrs, 0, PACKETBUF_NUM_ATTRS * sizeof(uint16_t)); - memset(g_pktaddrs, 0, PACKETBUF_NUM_ADDRS * sizeof(struct rimeaddr_s)); + memset(g_pktaddrs, 0, PACKETBUF_NUM_ADDRS * sizeof(struct sixlowpan_addr_s)); g_pktattrs[PACKETBUF_ATTR_MAX_MAC_TRANSMISSIONS] = CONFIG_NET_6LOWPAN_MAX_MACTRANSMITS; @@ -263,7 +263,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, if (destmac == NULL) { - memset(&bcastmac, 0, sizeof(struct rimeaddr_s)); + memset(&bcastmac, 0, sizeof(struct sixlowpan_addr_s)); destmac = &bcastmac; } diff --git a/net/sixlowpan/sixlowpan_framer.c b/net/sixlowpan/sixlowpan_framer.c index 47afecf6af..e8b68eede4 100644 --- a/net/sixlowpan/sixlowpan_framer.c +++ b/net/sixlowpan/sixlowpan_framer.c @@ -83,7 +83,7 @@ static bool sixlowpan_addrnull(FAR uint8_t *addr) { - int i = NET_6LOWPAN_RIMEADDR_SIZE; + int i = NET_6LOWPAN_ADDRSIZE; while (i-- > 0) { @@ -179,12 +179,12 @@ int sixlowpan_meta_data(uint16_t dest_panid, { /* Copy the destination address */ - rimeaddr_copy((struct rimeaddr_s *)&meta->dest_addr, + rimeaddr_copy((struct sixlowpan_addr_s *)&meta->dest_addr, g_pktaddrs[PACKETBUF_ADDR_RECEIVER].u8); /* Use short destination address mode if so configured */ -#ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED +#ifdef CONFIG_NET_6LOWPAN_EXTENDEDADDR meta->fcf.dest_addr_mode = FRAME802154_LONGADDRMODE; #else meta->fcf.dest_addr_mode = FRAME802154_SHORTADDRMODE; @@ -193,12 +193,12 @@ int sixlowpan_meta_data(uint16_t dest_panid, /* Set the source address to the node address assigned to the device */ - rimeaddr_copy((struct rimeaddr_s *)&meta->src_addr, + rimeaddr_copy((struct sixlowpan_addr_s *)&meta->src_addr, &ieee->i_dev.d_mac.ieee802154); /* Use short soruce address mode if so configured */ -#ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED +#ifdef CONFIG_NET_6LOWPAN_EXTENDEDADDR meta->fcf.src_addr_mode = FRAME802154_LONGADDRMODE; #else meta->fcf.src_addr_mode = FRAME802154_SHORTADDRMODE; diff --git a/net/sixlowpan/sixlowpan_globals.c b/net/sixlowpan/sixlowpan_globals.c index aac17f7eb9..646e2fec21 100644 --- a/net/sixlowpan/sixlowpan_globals.c +++ b/net/sixlowpan/sixlowpan_globals.c @@ -70,6 +70,6 @@ uint8_t g_frame_hdrlen; /* Packet buffer metadata: Attributes and addresses */ uint16_t g_pktattrs[PACKETBUF_NUM_ATTRS]; -struct rimeaddr_s g_pktaddrs[PACKETBUF_NUM_ADDRS]; +struct sixlowpan_addr_s g_pktaddrs[PACKETBUF_NUM_ADDRS]; #endif /* CONFIG_NET_6LOWPAN */ diff --git a/net/sixlowpan/sixlowpan_hc06.c b/net/sixlowpan/sixlowpan_hc06.c index a2ceb53cb6..751daf4dc8 100644 --- a/net/sixlowpan/sixlowpan_hc06.c +++ b/net/sixlowpan/sixlowpan_hc06.c @@ -233,7 +233,7 @@ static FAR struct sixlowpan_addrcontext_s * ****************************************************************************/ static uint8_t compress_addr_64(FAR const net_ipv6addr_t ipaddr, - FAR const struct rimeaddr_s *macaddr, + FAR const struct sixlowpan_addr_s *macaddr, uint8_t bitpos) { ninfo("ipaddr=%p macaddr=%p bitpos=%u g_hc06ptr=%p\n", @@ -275,7 +275,7 @@ static uint8_t compress_addr_64(FAR const net_ipv6addr_t ipaddr, ****************************************************************************/ static void uncompress_addr(FAR net_ipv6addr_t ipaddr, uint8_t const prefix[], - uint8_t prefpost, FAR struct rimeaddr_s *macaddr) + uint8_t prefpost, FAR struct sixlowpan_addr_s *macaddr) { uint8_t prefcount = prefpost >> 4; uint8_t postcount = prefpost & 0x0f; @@ -446,7 +446,7 @@ void sixlowpan_hc06_initialize(void) void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, FAR const struct ipv6_hdr_s *ipv6, - FAR const struct rimeaddr_s *destmac, + FAR const struct sixlowpan_addr_s *destmac, FAR uint8_t *fptr) { FAR uint8_t *iphc = fptr + g_frame_hdrlen; @@ -987,14 +987,14 @@ void sixlowpan_uncompresshdr_hc06(uint16_t iplen, FAR struct iob_s *iob, uncompress_addr(ipv6->srcipaddr, tmp != 0 ? addrcontext->prefix : NULL, g_unc_ctxconf[tmp], - (FAR struct rimeaddr_s *)&g_pktaddrs[PACKETBUF_ADDR_SENDER]); + (FAR struct sixlowpan_addr_s *)&g_pktaddrs[PACKETBUF_ADDR_SENDER]); } else { /* No compression and link local */ uncompress_addr(ipv6->srcipaddr, g_llprefix, g_unc_llconf[tmp], - (FAR struct rimeaddr_s *)&g_pktaddrs[PACKETBUF_ADDR_SENDER]); + (FAR struct sixlowpan_addr_s *)&g_pktaddrs[PACKETBUF_ADDR_SENDER]); } /* Destination address */ @@ -1053,14 +1053,14 @@ void sixlowpan_uncompresshdr_hc06(uint16_t iplen, FAR struct iob_s *iob, } uncompress_addr(ipv6->destipaddr, addrcontext->prefix, g_unc_ctxconf[tmp], - (FAR struct rimeaddr_s *)&g_pktaddrs[PACKETBUF_ADDR_RECEIVER]); + (FAR struct sixlowpan_addr_s *)&g_pktaddrs[PACKETBUF_ADDR_RECEIVER]); } else { /* Not address context based => link local M = 0, DAC = 0 - same as SAC */ uncompress_addr(ipv6->destipaddr, g_llprefix, g_unc_llconf[tmp], - (FAR struct rimeaddr_s *)&g_pktaddrs[PACKETBUF_ADDR_RECEIVER]); + (FAR struct sixlowpan_addr_s *)&g_pktaddrs[PACKETBUF_ADDR_RECEIVER]); } } diff --git a/net/sixlowpan/sixlowpan_hc1.c b/net/sixlowpan/sixlowpan_hc1.c index 3696c4a34f..5b8829745e 100644 --- a/net/sixlowpan/sixlowpan_hc1.c +++ b/net/sixlowpan/sixlowpan_hc1.c @@ -120,7 +120,7 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, FAR const struct ipv6_hdr_s *ipv6, - FAR const struct rimeaddr_s *destmac, + FAR const struct sixlowpan_addr_s *destmac, FAR uint8_t *fptr) { FAR uint8_t *hc1 = fptr + g_frame_hdrlen; diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index 0c573913d9..dc45b3fdd0 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -740,7 +740,7 @@ int sixlowpan_input(FAR struct ieee802154_driver_s *ieee, { FAR struct ipv6_hdr_s *ipv6hdr; FAR uint8_t *buffer; - struct rimeaddr_s destmac; + struct sixlowpan_addr_s destmac; size_t hdrlen; size_t buflen; diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index 8eecb3b49b..0a9cf07424 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -75,12 +75,12 @@ /* Copy a Rime address */ #define rimeaddr_copy(dest,src) \ - memcpy(dest, src, NET_6LOWPAN_RIMEADDR_SIZE) + memcpy(dest, src, NET_6LOWPAN_ADDRSIZE) /* Compare two Rime addresses */ #define rimeaddr_cmp(addr1,addr2) \ - (memcmp(addr1, addr2, NET_6LOWPAN_RIMEADDR_SIZE) == 0) + (memcmp(addr1, addr2, NET_6LOWPAN_ADDRSIZE) == 0) /* Pointers in the Rime buffer */ @@ -222,7 +222,7 @@ extern uint8_t g_frame_hdrlen; /* Packet buffer metadata: Attributes and addresses */ extern uint16_t g_pktattrs[PACKETBUF_NUM_ATTRS]; -extern struct rimeaddr_s g_pktaddrs[PACKETBUF_NUM_ADDRS]; +extern struct sixlowpan_addr_s g_pktaddrs[PACKETBUF_NUM_ADDRS]; /**************************************************************************** * Public Types @@ -236,7 +236,7 @@ struct net_driver_s; /* Forward reference */ struct ieee802154_driver_s; /* Forward reference */ struct devif_callback_s; /* Forward reference */ struct ipv6_hdr_s; /* Forward reference */ -struct rimeaddr_s; /* Forward reference */ +struct sixlowpan_addr_s; /* Forward reference */ struct iob_s; /* Forward reference */ /**************************************************************************** @@ -275,7 +275,7 @@ struct iob_s; /* Forward reference */ int sixlowpan_send(FAR struct net_driver_s *dev, FAR struct devif_callback_s **list, FAR const struct ipv6_hdr_s *ipv6hdr, FAR const void *buf, - size_t buflen, FAR const struct rimeaddr_s *raddr, + size_t buflen, FAR const struct sixlowpan_addr_s *raddr, uint16_t timeout); /**************************************************************************** @@ -381,7 +381,7 @@ int sixlowpan_frame_submit(FAR struct ieee802154_driver_s *ieee, int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, FAR const struct ipv6_hdr_s *ipv6hdr, FAR const void *buf, size_t buflen, - FAR const struct rimeaddr_s *destmac); + FAR const struct sixlowpan_addr_s *destmac); /**************************************************************************** * Name: sixlowpan_hc06_initialize @@ -437,7 +437,7 @@ void sixlowpan_hc06_initialize(void); #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, FAR const struct ipv6_hdr_s *ipv6, - FAR const struct rimeaddr_s *destmac, + FAR const struct sixlowpan_addr_s *destmac, FAR uint8_t *fptr); #endif @@ -498,7 +498,7 @@ void sixlowpan_uncompresshdr_hc06(uint16_t iplen, FAR struct iob_s *iob, #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC1 void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, FAR const struct ipv6_hdr_s *ipv6, - FAR const struct rimeaddr_s *destmac, + FAR const struct sixlowpan_addr_s *destmac, FAR uint8_t *fptr); #endif @@ -557,12 +557,12 @@ int sixlowpan_uncompresshdr_hc1(uint16_t iplen, FAR struct iob_s *iob, #define sixlowpan_islinklocal(ipaddr) ((ipaddr)[0] == NTOHS(0xfe80)) -void sixlowpan_ipfromrime(FAR const struct rimeaddr_s *rime, +void sixlowpan_ipfromrime(FAR const struct sixlowpan_addr_s *rime, net_ipv6addr_t ipaddr); void sixlowpan_rimefromip(const net_ipv6addr_t ipaddr, - FAR struct rimeaddr_s *rime); + FAR struct sixlowpan_addr_s *rime); bool sixlowpan_ismacbased(const net_ipv6addr_t ipaddr, - FAR const struct rimeaddr_s *rime); + FAR const struct sixlowpan_addr_s *rime); /**************************************************************************** * Name: sixlowpan_src_panid diff --git a/net/sixlowpan/sixlowpan_send.c b/net/sixlowpan/sixlowpan_send.c index 64b7088735..e742acfe7d 100644 --- a/net/sixlowpan/sixlowpan_send.c +++ b/net/sixlowpan/sixlowpan_send.c @@ -83,7 +83,7 @@ struct sixlowpan_send_s uint16_t s_timeout; /* Send timeout in deciseconds */ systime_t s_time; /* Last send time for determining timeout */ FAR const struct ipv6_hdr_s *s_ipv6hdr; /* IPv6 header, followed by UDP or TCP header. */ - FAR const struct rimeaddr_s *s_destmac; /* Destination MAC address */ + FAR const struct sixlowpan_addr_s *s_destmac; /* Destination MAC address */ FAR const void *s_buf; /* Data to send */ size_t s_len; /* Length of data in buf */ }; @@ -274,7 +274,7 @@ end_wait: int sixlowpan_send(FAR struct net_driver_s *dev, FAR struct devif_callback_s **list, FAR const struct ipv6_hdr_s *ipv6hdr, FAR const void *buf, - size_t len, FAR const struct rimeaddr_s *destmac, + size_t len, FAR const struct sixlowpan_addr_s *destmac, uint16_t timeout) { struct sixlowpan_send_s sinfo; diff --git a/net/sixlowpan/sixlowpan_tcpsend.c b/net/sixlowpan/sixlowpan_tcpsend.c index 2bb6c49130..9091c04016 100644 --- a/net/sixlowpan/sixlowpan_tcpsend.c +++ b/net/sixlowpan/sixlowpan_tcpsend.c @@ -164,7 +164,7 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, FAR struct tcp_conn_s *conn; FAR struct net_driver_s *dev; struct ipv6tcp_hdr_s ipv6tcp; - struct rimeaddr_s destmac; + struct sixlowpan_addr_s destmac; uint16_t timeout; uint16_t iplen; int ret; @@ -409,7 +409,7 @@ void sixlowpan_tcp_send(FAR struct net_driver_s *dev) } else { - struct rimeaddr_s destmac; + struct sixlowpan_addr_s destmac; FAR uint8_t *buf; uint16_t hdrlen; uint16_t buflen; diff --git a/net/sixlowpan/sixlowpan_udpsend.c b/net/sixlowpan/sixlowpan_udpsend.c index a29197eec7..2ab4286d8f 100644 --- a/net/sixlowpan/sixlowpan_udpsend.c +++ b/net/sixlowpan/sixlowpan_udpsend.c @@ -162,7 +162,7 @@ ssize_t psock_6lowpan_udp_sendto(FAR struct socket *psock, FAR struct udp_conn_s *conn; FAR struct net_driver_s *dev; struct ipv6udp_hdr_s ipv6udp; - struct rimeaddr_s destmac; + struct sixlowpan_addr_s destmac; uint16_t iplen; uint16_t timeout; int ret; diff --git a/net/sixlowpan/sixlowpan_utils.c b/net/sixlowpan/sixlowpan_utils.c index 7e1a6ac2ee..072a1b26d6 100644 --- a/net/sixlowpan/sixlowpan_utils.c +++ b/net/sixlowpan/sixlowpan_utils.c @@ -80,7 +80,7 @@ * ****************************************************************************/ -void sixlowpan_ipfromrime(FAR const struct rimeaddr_s *rime, +void sixlowpan_ipfromrime(FAR const struct sixlowpan_addr_s *rime, net_ipv6addr_t ipaddr) { /* We consider only links with IEEE EUI-64 identifier or IEEE 48-bit MAC @@ -90,13 +90,13 @@ void sixlowpan_ipfromrime(FAR const struct rimeaddr_s *rime, memset(ipaddr, 0, sizeof(net_ipv6addr_t)); ipaddr[0] = HTONS(0xfe80); -#ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED - memcpy(&ipaddr[4], rime, NET_6LOWPAN_RIMEADDR_SIZE); +#ifdef CONFIG_NET_6LOWPAN_EXTENDEDADDR + memcpy(&ipaddr[4], rime, NET_6LOWPAN_ADDRSIZE); ipaddr[4] ^= HTONS(0x0200); #else ipaddr[5] = HTONS(0x00ff); ipaddr[6] = HTONS(0xfe00); - memcpy(&ipaddr[7], rime, NET_6LOWPAN_RIMEADDR_SIZE); + memcpy(&ipaddr[7], rime, NET_6LOWPAN_ADDRSIZE); ipaddr[7] ^= HTONS(0x0200); #endif } @@ -115,16 +115,16 @@ void sixlowpan_ipfromrime(FAR const struct rimeaddr_s *rime, ****************************************************************************/ void sixlowpan_rimefromip(const net_ipv6addr_t ipaddr, - FAR struct rimeaddr_s *rime) + FAR struct sixlowpan_addr_s *rime) { /* REVISIT: See notes about 2 byte addresses in sixlowpan_ipfromrime() */ DEBUGASSERT(ipaddr[0] == HTONS(0xfe80)); -#ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED - memcpy(rime, &ipaddr[4], NET_6LOWPAN_RIMEADDR_SIZE); +#ifdef CONFIG_NET_6LOWPAN_EXTENDEDADDR + memcpy(rime, &ipaddr[4], NET_6LOWPAN_ADDRSIZE); #else - memcpy(rime, &ipaddr[7], NET_6LOWPAN_RIMEADDR_SIZE); + memcpy(rime, &ipaddr[7], NET_6LOWPAN_ADDRSIZE); #endif rime->u8[0] ^= 0x02; } @@ -143,11 +143,11 @@ void sixlowpan_rimefromip(const net_ipv6addr_t ipaddr, ****************************************************************************/ bool sixlowpan_ismacbased(const net_ipv6addr_t ipaddr, - FAR const struct rimeaddr_s *rime) + FAR const struct sixlowpan_addr_s *rime) { FAR const uint8_t *rimeptr = rime->u8; -#ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED +#ifdef CONFIG_NET_6LOWPAN_EXTENDEDADDR return (ipaddr[4] == htons((GETINT16(rimeptr, 0) ^ 0x0200)) && ipaddr[5] == GETINT16(rimeptr, 2) && ipaddr[6] == GETINT16(rimeptr, 4) && diff --git a/wireless/ieee802154/mac802154_loopback.c b/wireless/ieee802154/mac802154_loopback.c index c4cb8de153..51780af2c4 100644 --- a/wireless/ieee802154/mac802154_loopback.c +++ b/wireless/ieee802154/mac802154_loopback.c @@ -350,7 +350,7 @@ static int lo_ifup(FAR struct net_driver_s *dev) dev->d_ipv6addr[3], dev->d_ipv6addr[4], dev->d_ipv6addr[5], dev->d_ipv6addr[6], dev->d_ipv6addr[7]); -#ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED +#ifdef CONFIG_NET_6LOWPAN_EXTENDEDADDR ninfo(" Node: %02x:%02x:%02x:%02x:%02x:%02x:%02x:%02x PANID=%04x\n", dev->d_mac.ieee802154.u8[0], dev->d_mac.ieee802154.u8[1], dev->d_mac.ieee802154.u8[2], dev->d_mac.ieee802154.u8[3], @@ -507,7 +507,7 @@ static int lo_txavail(FAR struct net_driver_s *dev) #if defined(CONFIG_NET_IGMP) || defined(CONFIG_NET_ICMPv6) static int lo_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) { -#ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED +#ifdef CONFIG_NET_6LOWPAN_EXTENDEDADDR ninfo("MAC: %02x:%02x:%02x:%02x:%02x:%02x:%02x:%02x\n", mac[0], mac[1], mac[2], mac[3], mac[4], mac[5], mac[6], mac[7]); #else @@ -542,7 +542,7 @@ static int lo_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) #ifdef CONFIG_NET_IGMP static int lo_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) { -#ifdef CONFIG_NET_6LOWPAN_RIMEADDR_EXTENDED +#ifdef CONFIG_NET_6LOWPAN_EXTENDEDADDR ninfo("MAC: %02x:%02x:%02x:%02x:%02x:%02x:%02x:%02x\n", mac[0], mac[1], mac[2], mac[3], mac[4], mac[5], mac[6], mac[7]); #else -- GitLab From 2675d3028b97baa2cea279fd9a94c5bb4de0b7de Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 4 May 2017 08:24:18 -0600 Subject: [PATCH 708/990] Remove some dangling whitespace at the end of lines. --- net/netdev/netdev_ioctl.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/net/netdev/netdev_ioctl.c b/net/netdev/netdev_ioctl.c index 23f81c5276..8bb44c82fc 100644 --- a/net/netdev/netdev_ioctl.c +++ b/net/netdev/netdev_ioctl.c @@ -709,7 +709,7 @@ static int netdev_ifr_ioctl(FAR struct socket *psock, int cmd, { req->ifr_hwaddr.sa_family = AF_INETX; memcpy(req->ifr_hwaddr.sa_data, - dev->d_mac.ieee802154.u8, NET_6LOWPAN_RIMEADDR_SIZE); + dev->d_mac.ieee802154.u8, NET_6LOWPAN_RIMEADDR_SIZE); } else #endif @@ -942,7 +942,7 @@ static int netdev_arp_ioctl(FAR struct socket *psock, int cmd, case SIOCSARP: /* Set an ARP mapping */ { if (req != NULL && - req->arp_pa.sa_family == AF_INET && + req->arp_pa.sa_family == AF_INET && req->arp_ha.sa_family == ARPHRD_ETHER) { FAR struct sockaddr_in *addr = -- GitLab From 6f6e61769ac14817ed98d5514cb536366255d0e1 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 4 May 2017 09:05:41 -0600 Subject: [PATCH 709/990] 6loWPAN: Remove final references to Rime from code. --- include/nuttx/net/sixlowpan.h | 160 ++++++++++++++-------------- net/sixlowpan/Kconfig | 6 +- net/sixlowpan/README.txt | 32 +++--- net/sixlowpan/sixlowpan_framelist.c | 16 +-- net/sixlowpan/sixlowpan_framer.c | 16 +-- net/sixlowpan/sixlowpan_hc06.c | 6 +- net/sixlowpan/sixlowpan_hc1.c | 54 +++++----- net/sixlowpan/sixlowpan_input.c | 38 +++---- net/sixlowpan/sixlowpan_internal.h | 50 ++++----- net/sixlowpan/sixlowpan_tcpsend.c | 12 +-- net/sixlowpan/sixlowpan_udpsend.c | 6 +- net/sixlowpan/sixlowpan_utils.c | 52 ++++----- 12 files changed, 219 insertions(+), 229 deletions(-) diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index 94061a365e..91869dd41f 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -82,132 +82,132 @@ * bytes for all subsequent headers. */ -#define RIME_FRAG_DISPATCH_SIZE 0 /* 16 bit */ -#define RIME_FRAG_TAG 2 /* 16 bit */ -#define RIME_FRAG_OFFSET 4 /* 8 bit */ +#define SIXLOWPAN_FRAG_DISPATCH_SIZE 0 /* 16 bit */ +#define SIXLOWPAN_FRAG_TAG 2 /* 16 bit */ +#define SIXLOWPAN_FRAG_OFFSET 4 /* 8 bit */ -/* Define the Rime buffer as a byte array */ +/* Define the frame buffer as a byte array */ -#define RIME_HC1_DISPATCH 0 /* 8 bit */ -#define RIME_HC1_ENCODING 1 /* 8 bit */ -#define RIME_HC1_TTL 2 /* 8 bit */ +#define SIXLOWPAN_HC1_DISPATCH 0 /* 8 bit */ +#define SIXLOWPAN_HC1_ENCODING 1 /* 8 bit */ +#define SIXLOWPAN_HC1_TTL 2 /* 8 bit */ -#define RIME_HC1_HC_UDP_DISPATCH 0 /* 8 bit */ -#define RIME_HC1_HC_UDP_HC1_ENCODING 1 /* 8 bit */ -#define RIME_HC1_HC_UDP_UDP_ENCODING 2 /* 8 bit */ -#define RIME_HC1_HC_UDP_TTL 3 /* 8 bit */ -#define RIME_HC1_HC_UDP_PORTS 4 /* 8 bit */ -#define RIME_HC1_HC_UDP_CHKSUM 5 /* 16 bit */ +#define SIXLOWPAN_HC1_HC_UDP_DISPATCH 0 /* 8 bit */ +#define SIXLOWPAN_HC1_HC_UDP_HC1_ENCODING 1 /* 8 bit */ +#define SIXLOWPAN_HC1_HC_UDP_UDP_ENCODING 2 /* 8 bit */ +#define SIXLOWPAN_HC1_HC_UDP_TTL 3 /* 8 bit */ +#define SIXLOWPAN_HC1_HC_UDP_PORTS 4 /* 8 bit */ +#define SIXLOWPAN_HC1_HC_UDP_CHKSUM 5 /* 16 bit */ /* Min and Max compressible UDP ports - HC06 */ -#define SIXLOWPAN_UDP_4_BIT_PORT_MIN 0xf0b0 -#define SIXLOWPAN_UDP_4_BIT_PORT_MAX 0xf0bf /* f0b0 + 15 */ -#define SIXLOWPAN_UDP_8_BIT_PORT_MIN 0xf000 -#define SIXLOWPAN_UDP_8_BIT_PORT_MAX 0xf0ff /* f000 + 255 */ +#define SIXLOWPAN_UDP_4_BIT_PORT_MIN 0xf0b0 +#define SIXLOWPAN_UDP_4_BIT_PORT_MAX 0xf0bf /* f0b0 + 15 */ +#define SIXLOWPAN_UDP_8_BIT_PORT_MIN 0xf000 +#define SIXLOWPAN_UDP_8_BIT_PORT_MAX 0xf0ff /* f000 + 255 */ /* 6lowpan dispatches */ -#define SIXLOWPAN_DISPATCH_NALP 0x00 /* 00xxxxxx Not a LoWPAN packet */ -#define SIXLOWPAN_DISPATCH_NALP_MASK 0xc0 /* 11000000 */ +#define SIXLOWPAN_DISPATCH_NALP 0x00 /* 00xxxxxx Not a LoWPAN packet */ +#define SIXLOWPAN_DISPATCH_NALP_MASK 0xc0 /* 11000000 */ -#define SIXLOWPAN_DISPATCH_IPV6 0x41 /* 01000001 Uncompressed IPv6 addresses */ -#define SIXLOWPAN_DISPATCH_HC1 0x42 /* 01000010 HC1 Compressed IPv6 header */ -#define SIXLOWPAN_DISPATCH_BC0 0x50 /* 01010000 BC0 Broadcast header */ -#define SIXLOWPAN_DISPATCH_ESC 0x7f /* 01111111 Additional Dispatch octet follows */ +#define SIXLOWPAN_DISPATCH_IPV6 0x41 /* 01000001 Uncompressed IPv6 addresses */ +#define SIXLOWPAN_DISPATCH_HC1 0x42 /* 01000010 HC1 Compressed IPv6 header */ +#define SIXLOWPAN_DISPATCH_BC0 0x50 /* 01010000 BC0 Broadcast header */ +#define SIXLOWPAN_DISPATCH_ESC 0x7f /* 01111111 Additional Dispatch octet follows */ -#define SIXLOWPAN_DISPATCH_IPHC 0x60 /* 011xxxxx IP Header Compression (IPHC)*/ -#define SIXLOWPAN_DISPATCH_IPHC_MASK 0xe0 /* 11100000 */ +#define SIXLOWPAN_DISPATCH_IPHC 0x60 /* 011xxxxx IP Header Compression (IPHC)*/ +#define SIXLOWPAN_DISPATCH_IPHC_MASK 0xe0 /* 11100000 */ -#define SIXLOWPAN_DISPATCH_MESH 0x80 /* 10xxxxxx Mesh routing header */ -#define SIXLOWPAN_DISPATCH_MESH_MASK 0xc0 /* 11000000 */ +#define SIXLOWPAN_DISPATCH_MESH 0x80 /* 10xxxxxx Mesh routing header */ +#define SIXLOWPAN_DISPATCH_MESH_MASK 0xc0 /* 11000000 */ -#define SIXLOWPAN_DISPATCH_FRAG1 0xc0 /* 11000xxx Fragmentation header (ï¬rst) */ -#define SIXLOWPAN_DISPATCH_FRAGN 0xe0 /* 11100xxx Fragmentation header (subsequent) */ -#define SIXLOWPAN_DISPATCH_FRAG_MASK 0xf8 /* 11111000 */ +#define SIXLOWPAN_DISPATCH_FRAG1 0xc0 /* 11000xxx Fragmentation header (ï¬rst) */ +#define SIXLOWPAN_DISPATCH_FRAGN 0xe0 /* 11100xxx Fragmentation header (subsequent) */ +#define SIXLOWPAN_DISPATCH_FRAG_MASK 0xf8 /* 11111000 */ /* HC1 encoding */ -#define SIXLOWPAN_HC1_NH_UDP 0x02 -#define SIXLOWPAN_HC1_NH_TCP 0x06 -#define SIXLOWPAN_HC1_NH_ICMP6 0x04 +#define SIXLOWPAN_HC1_NH_UDP 0x02 +#define SIXLOWPAN_HC1_NH_TCP 0x06 +#define SIXLOWPAN_HC1_NH_ICMP6 0x04 /* HC_UDP encoding (works together with HC1) */ -#define SIXLOWPAN_HC_UDP_ALL_C 0xe0 +#define SIXLOWPAN_HC_UDP_ALL_C 0xe0 /* IPHC encoding * * Values of fields within the IPHC encoding first byte * (Using MS-to-LS bit numbering of the draft RFC) */ - /* Bits 0-2: 011 */ -#define SIXLOWPAN_IPHC_TC_MASK 0x18 /* Bits 3-4: Traffic Class, Flow Label */ -# define SIXLOWPAN_IPHC_TC_00 0x00 /* ECN+DSCP+4-bit Pad+Flow Label (4 bytes) */ -# define SIXLOWPAN_IPHC_TC_01 0x08 /* ECN+2-bit Pad+ Flow Label (3 bytes), DSCP is elided. */ -# define SIXLOWPAN_IPHC_TC_10 0x10 /* ECN+DSCP (1 byte), Flow Label is elided */ -# define SIXLOWPAN_IPHC_TC_11 0x11 /* Traffic Class and Flow Label are elided */ -#define SIXLOWPAN_IPHC_NH 0x04 /* Bit 5: Next Header Compressed */ -#define SIXLOWPAN_IPHC_HLIM_MASK 0x03 /* Bits 6-7: Hop Limit */ -# define SIXLOWPAN_IPHC_HLIM_INLINE 0x00 /* Carried in-line */ -# define SIXLOWPAN_IPHC_HLIM_1 0x01 /* Compressed hop limit of 1 */ -# define SIXLOWPAN_IPHC_HLIM_64 0x02 /* Compressed hop limit of 64 */ -# define SIXLOWPAN_IPHC_HLIM_255 0x03 /* Compressed hop limit of 255 */ + /* Bits 0-2: 011 */ +#define SIXLOWPAN_IPHC_TC_MASK 0x18 /* Bits 3-4: Traffic Class, Flow Label */ +# define SIXLOWPAN_IPHC_TC_00 0x00 /* ECN+DSCP+4-bit Pad+Flow Label (4 bytes) */ +# define SIXLOWPAN_IPHC_TC_01 0x08 /* ECN+2-bit Pad+ Flow Label (3 bytes), DSCP is elided. */ +# define SIXLOWPAN_IPHC_TC_10 0x10 /* ECN+DSCP (1 byte), Flow Label is elided */ +# define SIXLOWPAN_IPHC_TC_11 0x11 /* Traffic Class and Flow Label are elided */ +#define SIXLOWPAN_IPHC_NH 0x04 /* Bit 5: Next Header Compressed */ +#define SIXLOWPAN_IPHC_HLIM_MASK 0x03 /* Bits 6-7: Hop Limit */ +# define SIXLOWPAN_IPHC_HLIM_INLINE 0x00 /* Carried in-line */ +# define SIXLOWPAN_IPHC_HLIM_1 0x01 /* Compressed hop limit of 1 */ +# define SIXLOWPAN_IPHC_HLIM_64 0x02 /* Compressed hop limit of 64 */ +# define SIXLOWPAN_IPHC_HLIM_255 0x03 /* Compressed hop limit of 255 */ /* Values of fields within the IPHC encoding second byte */ -#define SIXLOWPAN_IPHC_CID 0x80 /* Bit 8: Context identifier extension */ -#define SIXLOWPAN_IPHC_SAC 0x40 /* Bit 9: Source address compression */ -#define SIXLOWPAN_IPHC_SAM_MASK 0x30 /* Bits 10-11: Source address mode */ -# define SIXLOWPAN_IPHC_SAM_128 0x00 /* 128-bits */ -# define SIXLOWPAN_IPHC_SAM_64 0x10 /* 64-bits */ -# define SIXLOWPAN_IPHC_SAM_16 0x20 /* 16-bits */ -# define SIXLOWPAN_IPHC_SAM_0 0x30 /* 0-bits */ -#define SIXLOWPAN_IPHC_M 0x08 /* Bit 12: Multicast compression */ -#define SIXLOWPAN_IPHC_DAC 0x04 /* Bit 13: Destination address compression */ -#define SIXLOWPAN_IPHC_DAM_MASK 0x03 /* Bits 14-15: Destination address mode */ -# define SIXLOWPAN_IPHC_DAM_128 0x00 /* 128-bits */ -# define SIXLOWPAN_IPHC_DAM_64 0x01 /* 64-bits */ -# define SIXLOWPAN_IPHC_DAM_16 0x02 /* 16-bits */ -# define SIXLOWPAN_IPHC_DAM_0 0x03 /* 0-bits */ - -#define SIXLOWPAN_IPHC_SAM_BIT 4 -#define SIXLOWPAN_IPHC_DAM_BIT 0 +#define SIXLOWPAN_IPHC_CID 0x80 /* Bit 8: Context identifier extension */ +#define SIXLOWPAN_IPHC_SAC 0x40 /* Bit 9: Source address compression */ +#define SIXLOWPAN_IPHC_SAM_MASK 0x30 /* Bits 10-11: Source address mode */ +# define SIXLOWPAN_IPHC_SAM_128 0x00 /* 128-bits */ +# define SIXLOWPAN_IPHC_SAM_64 0x10 /* 64-bits */ +# define SIXLOWPAN_IPHC_SAM_16 0x20 /* 16-bits */ +# define SIXLOWPAN_IPHC_SAM_0 0x30 /* 0-bits */ +#define SIXLOWPAN_IPHC_M 0x08 /* Bit 12: Multicast compression */ +#define SIXLOWPAN_IPHC_DAC 0x04 /* Bit 13: Destination address compression */ +#define SIXLOWPAN_IPHC_DAM_MASK 0x03 /* Bits 14-15: Destination address mode */ +# define SIXLOWPAN_IPHC_DAM_128 0x00 /* 128-bits */ +# define SIXLOWPAN_IPHC_DAM_64 0x01 /* 64-bits */ +# define SIXLOWPAN_IPHC_DAM_16 0x02 /* 16-bits */ +# define SIXLOWPAN_IPHC_DAM_0 0x03 /* 0-bits */ + +#define SIXLOWPAN_IPHC_SAM_BIT 4 +#define SIXLOWPAN_IPHC_DAM_BIT 0 /* Link local context number */ -#define SIXLOWPAN_IPHC_ADDR_CONTEXT_LL 0 +#define SIXLOWPAN_IPHC_ADDR_CONTEXT_LL 0 /* 16-bit multicast addresses compression */ -#define SIXLOWPAN_IPHC_MCAST_RANGE 0xa0 +#define SIXLOWPAN_IPHC_MCAST_RANGE 0xa0 /* NHC_EXT_HDR */ -#define SIXLOWPAN_NHC_MASK 0xf0 -#define SIXLOWPAN_NHC_EXT_HDR 0xe0 +#define SIXLOWPAN_NHC_MASK 0xf0 +#define SIXLOWPAN_NHC_EXT_HDR 0xe0 /* LOWPAN_UDP encoding (works together with IPHC) */ -#define SIXLOWPAN_NHC_UDP_MASK 0xf8 -#define SIXLOWPAN_NHC_UDP_ID 0xf0 -#define SIXLOWPAN_NHC_UDP_CHECKSUMC 0x04 -#define SIXLOWPAN_NHC_UDP_CHECKSUMI 0x00 +#define SIXLOWPAN_NHC_UDP_MASK 0xf8 +#define SIXLOWPAN_NHC_UDP_ID 0xf0 +#define SIXLOWPAN_NHC_UDP_CHECKSUMC 0x04 +#define SIXLOWPAN_NHC_UDP_CHECKSUMI 0x00 /* Values for port compression, _with checksum_ ie bit 5 set to 0 */ -#define SIXLOWPAN_NHC_UDP_CS_P_00 0xf0 /* All inline */ -#define SIXLOWPAN_NHC_UDP_CS_P_01 0xf1 /* Source 16bit inline, dest = 0xf0 + 8 bit inline */ -#define SIXLOWPAN_NHC_UDP_CS_P_10 0xf2 /* Source = 0xf0 + 8bit inline, dest = 16 bit inline */ -#define SIXLOWPAN_NHC_UDP_CS_P_11 0xf3 /* Source & dest = 0xf0b + 4bit inline */ +#define SIXLOWPAN_NHC_UDP_CS_P_00 0xf0 /* All inline */ +#define SIXLOWPAN_NHC_UDP_CS_P_01 0xf1 /* Source 16bit inline, dest = 0xf0 + 8 bit inline */ +#define SIXLOWPAN_NHC_UDP_CS_P_10 0xf2 /* Source = 0xf0 + 8bit inline, dest = 16 bit inline */ +#define SIXLOWPAN_NHC_UDP_CS_P_11 0xf3 /* Source & dest = 0xf0b + 4bit inline */ /* The 6lowpan "headers" length */ -#define SIXLOWPAN_IPV6_HDR_LEN 1 /* One byte */ -#define SIXLOWPAN_HC1_HDR_LEN 3 -#define SIXLOWPAN_HC1_HC_UDP_HDR_LEN 7 -#define SIXLOWPAN_FRAG1_HDR_LEN 4 -#define SIXLOWPAN_FRAGN_HDR_LEN 5 +#define SIXLOWPAN_IPV6_HDR_LEN 1 /* One byte */ +#define SIXLOWPAN_HC1_HDR_LEN 3 +#define SIXLOWPAN_HC1_HC_UDP_HDR_LEN 7 +#define SIXLOWPAN_FRAG1_HDR_LEN 4 +#define SIXLOWPAN_FRAGN_HDR_LEN 5 /* Address compressibility test macros **************************************/ diff --git a/net/sixlowpan/Kconfig b/net/sixlowpan/Kconfig index 4b1c4df409..d7c709c311 100644 --- a/net/sixlowpan/Kconfig +++ b/net/sixlowpan/Kconfig @@ -134,12 +134,12 @@ endif # NET_6LOWPAN_MAXADDRCONTEXT_PREINIT_0 endif # NET_6LOWPAN_COMPRESSION_HC06 config NET_6LOWPAN_EXTENDEDADDR - bool "Extended Rime address" + bool "Extended IEEE 802.15.4 address" default n ---help--- - By default, a 2-byte Rime address is used for the IEEE802.15.4 MAC + By default, a 2-byte short address is used for the IEEE802.15.4 MAC device's link layer address. If this option is selected, then an - 8-byte Rime address will be used. + 8-byte extended address will be used. config NET_6LOWPAN_MAXAGE int "Packet reassembly timeout" diff --git a/net/sixlowpan/README.txt b/net/sixlowpan/README.txt index 5b6b4e298d..9eb848144e 100644 --- a/net/sixlowpan/README.txt +++ b/net/sixlowpan/README.txt @@ -10,12 +10,12 @@ Optimal 6loWPAN Configuration 128 112 96 80 64 48 32 16 ---- ---- ---- ---- ---- ---- ---- ---- - AAAA xxxx xxxx xxxx xxxx 00ff fe00 MMMM 2-byte Rime address IEEE 48-bit MAC - AAAA 0000 0000 0000 NNNN NNNN NNNN NNNN 8-byte Rime address IEEE EUI-64 + AAAA xxxx xxxx xxxx xxxx 00ff fe00 MMMM 2-byte short address IEEE 48-bit MAC + AAAA 0000 0000 0000 NNNN NNNN NNNN NNNN 8-byte extended address IEEE EUI-64 - Where MMM is the 2-byte rime address XORed 0x0200. For example, the MAC + Where MMM is the 2-byte short address XORed 0x0200. For example, the MAC address of 0xabcd would be 0xa9cd. And NNNN NNNN NNNN NNNN is the 8-byte - rime address address XOR 02000 0000 0000 0000. + extended address address XOR 02000 0000 0000 0000. For link-local address, AAAA is 0xfe80 @@ -23,8 +23,8 @@ Optimal 6loWPAN Configuration 128 112 96 80 64 48 32 16 ---- ---- ---- ---- ---- ---- ---- ---- - fe80 0000 0000 0000 0000 00ff fe00 MMMM 2-byte Rime address IEEE 48-bit MAC - fe80 0000 0000 0000 NNNN NNNN NNNN NNNN 8-byte Rime address IEEE EUI-64 + fe80 0000 0000 0000 0000 00ff fe00 MMMM 2-byte short address IEEE 48-bit MAC + fe80 0000 0000 0000 NNNN NNNN NNNN NNNN 8-byte extended address IEEE EUI-64 4. Compressable port numbers in the rangs 0xf0b0-0xf0bf @@ -52,11 +52,11 @@ this is a HC1 compressed first frame of a packet 41 88 2a cefa 3412 cdab ### 9-byte MAC header c50e 000b ### 4-byte FRAG1 header 42 ### SIXLOWPAN_DISPATCH_HC1 - fb ### RIME_HC1_HC_UDP_HC1_ENCODING - e0 ### RIME_HC1_HC_UDP_UDP_ENCODING - 00 ### RIME_HC1_HC_UDP_TTL - 10 ### RIME_HC1_HC_UDP_PORTS - 0000 ### RIME_HC1_HC_UDP_CHKSUM + fb ### SIXLOWPAN_HC1_HC_UDP_HC1_ENCODING + e0 ### SIXLOWPAN_HC1_HC_UDP_UDP_ENCODING + 00 ### SIXLOWPAN_HC1_HC_UDP_TTL + 10 ### SIXLOWPAN_HC1_HC_UDP_PORTS + 0000 ### SIXLOWPAN_HC1_HC_UDP_CHKSUM 104 byte Payload follows: 4f4e452064617920 48656e6e792d7065 6e6e792077617320 7069636b696e6720 @@ -69,11 +69,11 @@ This is the second frame of the same transfer: 41 88 2b cefa 3412 cdab ### 9-byte MAC header e50e 000b 0d ### 5 byte FRAGN header 42 ### SIXLOWPAN_DISPATCH_HC1 - fb ### RIME_HC1_HC_UDP_HC1_ENCODING - e0 ### RIME_HC1_HC_UDP_UDP_ENCODING - 00 ### RIME_HC1_HC_UDP_TTL - 10 ### RIME_HC1_HC_UDP_PORTS - 0000 ### RIME_HC1_HC_UDP_CHKSUM + fb ### SIXLOWPAN_HC1_HC_UDP_HC1_ENCODING + e0 ### SIXLOWPAN_HC1_HC_UDP_UDP_ENCODING + 00 ### SIXLOWPAN_HC1_HC_UDP_TTL + 10 ### SIXLOWPAN_HC1_HC_UDP_PORTS + 0000 ### SIXLOWPAN_HC1_HC_UDP_CHKSUM 104 byte Payload follows: 476f6f646e657373 2067726163696f75 73206d6521272073 6169642048656e6e diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c index 013f7cbb7e..005473c4e0 100644 --- a/net/sixlowpan/sixlowpan_framelist.c +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -231,7 +231,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, g_uncomp_hdrlen = 0; g_frame_hdrlen = 0; - /* Reset rime buffer, packet buffer metatadata */ + /* Reset address buffer and packet buffer metatadata */ memset(g_pktattrs, 0, PACKETBUF_NUM_ATTRS * sizeof(uint16_t)); memset(g_pktaddrs, 0, PACKETBUF_NUM_ADDRS * sizeof(struct sixlowpan_addr_s)); @@ -286,9 +286,9 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, /* Set the source and destination address */ - rimeaddr_copy(&g_pktaddrs[PACKETBUF_ADDR_SENDER], + sixlowpan_addrcopy(&g_pktaddrs[PACKETBUF_ADDR_SENDER], &ieee->i_dev.d_mac.ieee802154); - rimeaddr_copy(&g_pktaddrs[PACKETBUF_ADDR_RECEIVER], destmac); + sixlowpan_addrcopy(&g_pktaddrs[PACKETBUF_ADDR_RECEIVER], destmac); /* Get the destination PAN ID. * @@ -400,9 +400,9 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, */ pktlen = buflen + g_uncomp_hdrlen; - PUTINT16(fragptr, RIME_FRAG_DISPATCH_SIZE, + PUTINT16(fragptr, SIXLOWPAN_FRAG_DISPATCH_SIZE, ((SIXLOWPAN_DISPATCH_FRAG1 << 8) | pktlen)); - PUTINT16(fragptr, RIME_FRAG_TAG, ieee->i_dgramtag); + PUTINT16(fragptr, SIXLOWPAN_FRAG_TAG, ieee->i_dgramtag); g_frame_hdrlen += SIXLOWPAN_FRAG1_HDR_LEN; @@ -469,10 +469,10 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, /* Setup up the FRAGN header after the frame header. */ - PUTINT16(fragptr, RIME_FRAG_DISPATCH_SIZE, + PUTINT16(fragptr, SIXLOWPAN_FRAG_DISPATCH_SIZE, ((SIXLOWPAN_DISPATCH_FRAGN << 8) | pktlen)); - PUTINT16(fragptr, RIME_FRAG_TAG, ieee->i_dgramtag); - fragptr[RIME_FRAG_OFFSET] = outlen >> 3; + PUTINT16(fragptr, SIXLOWPAN_FRAG_TAG, ieee->i_dgramtag); + fragptr[SIXLOWPAN_FRAG_OFFSET] = outlen >> 3; fragn_hdrlen += SIXLOWPAN_FRAGN_HDR_LEN; diff --git a/net/sixlowpan/sixlowpan_framer.c b/net/sixlowpan/sixlowpan_framer.c index e8b68eede4..49b1548498 100644 --- a/net/sixlowpan/sixlowpan_framer.c +++ b/net/sixlowpan/sixlowpan_framer.c @@ -70,8 +70,8 @@ * Name: sixlowpan_addrnull * * Description: - * If the output address is NULL in the Rime buf, then it is broadcast - * on the 802.15.4 network. + * If the output address is NULL in the MAC header buf, then it is + * broadcast on the 802.15.4 network. * * Input parameters: * addrmode - The address mode @@ -138,8 +138,8 @@ int sixlowpan_meta_data(uint16_t dest_panid, meta->fcf.frame_type = FRAME802154_DATAFRAME; meta->fcf.frame_pending = g_pktattrs[PACKETBUF_ATTR_PENDING]; - /* If the output address is NULL in the Rime buf, then it is broadcast - * on the 802.15.4 network. + /* If the output address is NULL in the MAC header buf, then it is + * broadcast on the 802.15.4 network. */ rcvrnull = sixlowpan_addrnull(g_pktaddrs[PACKETBUF_ADDR_RECEIVER].u8); @@ -163,8 +163,8 @@ int sixlowpan_meta_data(uint16_t dest_panid, meta->src_pid = src_panid; meta->dest_pid = dest_panid; - /* If the output address is NULL in the Rime buf, then it is broadcast - * on the 802.15.4 network. + /* If the output address is NULL in the MAC header buf, then it is + * broadcast on the 802.15.4 network. */ if (rcvrnull) @@ -179,7 +179,7 @@ int sixlowpan_meta_data(uint16_t dest_panid, { /* Copy the destination address */ - rimeaddr_copy((struct sixlowpan_addr_s *)&meta->dest_addr, + sixlowpan_addrcopy((struct sixlowpan_addr_s *)&meta->dest_addr, g_pktaddrs[PACKETBUF_ADDR_RECEIVER].u8); /* Use short destination address mode if so configured */ @@ -193,7 +193,7 @@ int sixlowpan_meta_data(uint16_t dest_panid, /* Set the source address to the node address assigned to the device */ - rimeaddr_copy((struct sixlowpan_addr_s *)&meta->src_addr, + sixlowpan_addrcopy((struct sixlowpan_addr_s *)&meta->src_addr, &ieee->i_dev.d_mac.ieee802154); /* Use short soruce address mode if so configured */ diff --git a/net/sixlowpan/sixlowpan_hc06.c b/net/sixlowpan/sixlowpan_hc06.c index 751daf4dc8..2a262f5b53 100644 --- a/net/sixlowpan/sixlowpan_hc06.c +++ b/net/sixlowpan/sixlowpan_hc06.c @@ -316,7 +316,7 @@ static void uncompress_addr(FAR net_ipv6addr_t ipaddr, uint8_t const prefix[], { /* No IID based configuration if no prefix and no data => unspec */ - sixlowpan_ipfromrime(macaddr, ipaddr); + sixlowpan_ipfromaddr(macaddr, ipaddr); } ninfo("Uncompressing %d + %d => %04x:%04x:%04x:%04x:%04x:%04x:%04x:%04x\n", @@ -828,8 +828,8 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, * sixlowpan_buf * * This function is called by the input function when the dispatch is HC06. - * We process the packet in the rime buffer, uncompress the header fields, - * and copy the result in the sixlowpan buffer. At the end of the + * We process the frame in the IOB buffer, uncompress the header fields, + * and copy the result into the driver packet buffer. At the end of the * decompression, g_frame_hdrlen and g_uncompressed_hdrlen are set to the * appropriate values * diff --git a/net/sixlowpan/sixlowpan_hc1.c b/net/sixlowpan/sixlowpan_hc1.c index 5b8829745e..d0e5b13d99 100644 --- a/net/sixlowpan/sixlowpan_hc1.c +++ b/net/sixlowpan/sixlowpan_hc1.c @@ -137,12 +137,12 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, { /* IPV6 DISPATCH * Something cannot be compressed, use IPV6 DISPATCH, compress - * nothing, copy IPv6 header in rime buffer + * nothing, copy IPv6 header into the frame buffer */ /* IPv6 dispatch header (1 byte) */ - hc1[RIME_HC1_DISPATCH] = SIXLOWPAN_DISPATCH_IPV6; + hc1[SIXLOWPAN_HC1_DISPATCH] = SIXLOWPAN_DISPATCH_IPV6; g_frame_hdrlen += SIXLOWPAN_IPV6_HDR_LEN; memcpy(fptr + g_frame_hdrlen, ipv6, IPv6_HDRLEN); @@ -156,15 +156,15 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, * header is UDP, we compress UDP header using HC2 */ - hc1[RIME_HC1_DISPATCH] = SIXLOWPAN_DISPATCH_HC1; + hc1[SIXLOWPAN_HC1_DISPATCH] = SIXLOWPAN_DISPATCH_HC1; g_uncomp_hdrlen += IPv6_HDRLEN; switch (ipv6->proto) { case IP_PROTO_ICMP6: /* HC1 encoding and ttl */ - hc1[RIME_HC1_ENCODING] = 0xfc; - hc1[RIME_HC1_TTL] = ipv6->ttl; + hc1[SIXLOWPAN_HC1_ENCODING] = 0xfc; + hc1[SIXLOWPAN_HC1_TTL] = ipv6->ttl; g_frame_hdrlen += SIXLOWPAN_HC1_HDR_LEN; break; @@ -172,8 +172,8 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, case IP_PROTO_TCP: /* HC1 encoding and ttl */ - hc1[RIME_HC1_ENCODING] = 0xfe; - hc1[RIME_HC1_TTL] = ipv6->ttl; + hc1[SIXLOWPAN_HC1_ENCODING] = 0xfe; + hc1[SIXLOWPAN_HC1_TTL] = ipv6->ttl; g_frame_hdrlen += SIXLOWPAN_HC1_HDR_LEN; break; #endif /* CONFIG_NET_TCP */ @@ -201,17 +201,17 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, /* HC1 encoding */ - hcudp[RIME_HC1_HC_UDP_HC1_ENCODING] = 0xfb; + hcudp[SIXLOWPAN_HC1_HC_UDP_HC1_ENCODING] = 0xfb; /* HC_UDP encoding, ttl, src and dest ports, checksum */ - hcudp[RIME_HC1_HC_UDP_UDP_ENCODING] = 0xe0; - hcudp[RIME_HC1_HC_UDP_TTL] = ipv6->ttl; - hcudp[RIME_HC1_HC_UDP_PORTS] = + hcudp[SIXLOWPAN_HC1_HC_UDP_UDP_ENCODING] = 0xe0; + hcudp[SIXLOWPAN_HC1_HC_UDP_TTL] = ipv6->ttl; + hcudp[SIXLOWPAN_HC1_HC_UDP_PORTS] = (uint8_t)((ntohs(udp->srcport) - CONFIG_NET_6LOWPAN_MINPORT) << 4) + (uint8_t)((ntohs(udp->destport) - CONFIG_NET_6LOWPAN_MINPORT)); - memcpy(&hcudp[RIME_HC1_HC_UDP_CHKSUM], &udp->udpchksum, 2); + memcpy(&hcudp[SIXLOWPAN_HC1_HC_UDP_CHKSUM], &udp->udpchksum, 2); g_frame_hdrlen += SIXLOWPAN_HC1_HC_UDP_HDR_LEN; g_uncomp_hdrlen += UDP_HDRLEN; @@ -220,8 +220,8 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, { /* HC1 encoding and ttl */ - hc1[RIME_HC1_ENCODING] = 0xfa; - hc1[RIME_HC1_TTL] = ipv6->ttl; + hc1[SIXLOWPAN_HC1_ENCODING] = 0xfa; + hc1[SIXLOWPAN_HC1_TTL] = ipv6->ttl; g_frame_hdrlen += SIXLOWPAN_HC1_HDR_LEN; } } @@ -238,8 +238,8 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, * Uncompress HC1 (and HC_UDP) headers and put them in sixlowpan_buf * * This function is called by the input function when the dispatch is - * HC1. It processes the packet in the rime buffer, uncompresses the - * header fields, and copies the result in the sixlowpan buffer. At the + * HC1. It processes the frame in the IOB buffer, uncompresses the + * header fields, and copies the result in the packet buffer. At the * end of the decompression, g_frame_hdrlen and uncompressed_hdr_len * are set to the appropriate values * @@ -275,26 +275,26 @@ int sixlowpan_uncompresshdr_hc1(uint16_t iplen, FAR struct iob_s *iob, * addresses. */ - sixlowpan_ipfromrime(&g_pktaddrs[PACKETBUF_ADDR_SENDER], + sixlowpan_ipfromaddr(&g_pktaddrs[PACKETBUF_ADDR_SENDER], ipv6->srcipaddr); - sixlowpan_ipfromrime(&g_pktaddrs[PACKETBUF_ADDR_RECEIVER], + sixlowpan_ipfromaddr(&g_pktaddrs[PACKETBUF_ADDR_RECEIVER], ipv6->destipaddr); g_uncomp_hdrlen += IPv6_HDRLEN; /* len[], proto, and ttl depend on the encoding */ - switch (hc1[RIME_HC1_ENCODING] & 0x06) + switch (hc1[SIXLOWPAN_HC1_ENCODING] & 0x06) { case SIXLOWPAN_HC1_NH_ICMP6: ipv6->proto = IP_PROTO_ICMP6; - ipv6->ttl = hc1[RIME_HC1_TTL]; + ipv6->ttl = hc1[SIXLOWPAN_HC1_TTL]; g_frame_hdrlen += SIXLOWPAN_HC1_HDR_LEN; break; #if CONFIG_NET_TCP case SIXLOWPAN_HC1_NH_TCP: ipv6->proto = IP_PROTO_TCP; - ipv6->ttl = hc1[RIME_HC1_TTL]; + ipv6->ttl = hc1[SIXLOWPAN_HC1_TTL]; g_frame_hdrlen += SIXLOWPAN_HC1_HDR_LEN; break; #endif /* CONFIG_NET_TCP */ @@ -306,11 +306,11 @@ int sixlowpan_uncompresshdr_hc1(uint16_t iplen, FAR struct iob_s *iob, FAR uint8_t *hcudp = fptr + g_frame_hdrlen; ipv6->proto = IP_PROTO_UDP; - if ((hcudp[RIME_HC1_HC_UDP_HC1_ENCODING] & 0x01) != 0) + if ((hcudp[SIXLOWPAN_HC1_HC_UDP_HC1_ENCODING] & 0x01) != 0) { /* UDP header is compressed with HC_UDP */ - if (hcudp[RIME_HC1_HC_UDP_UDP_ENCODING] != + if (hcudp[SIXLOWPAN_HC1_HC_UDP_UDP_ENCODING] != SIXLOWPAN_HC_UDP_ALL_C) { nwarn("WARNING: sixlowpan (uncompress_hdr), packet not supported"); @@ -319,16 +319,16 @@ int sixlowpan_uncompresshdr_hc1(uint16_t iplen, FAR struct iob_s *iob, /* IP TTL */ - ipv6->ttl = hcudp[RIME_HC1_HC_UDP_TTL]; + ipv6->ttl = hcudp[SIXLOWPAN_HC1_HC_UDP_TTL]; /* UDP ports, len, checksum */ udp->srcport = - htons(CONFIG_NET_6LOWPAN_MINPORT + (hcudp[RIME_HC1_HC_UDP_PORTS] >> 4)); + htons(CONFIG_NET_6LOWPAN_MINPORT + (hcudp[SIXLOWPAN_HC1_HC_UDP_PORTS] >> 4)); udp->destport = - htons(CONFIG_NET_6LOWPAN_MINPORT + (hcudp[RIME_HC1_HC_UDP_PORTS] & 0x0F)); + htons(CONFIG_NET_6LOWPAN_MINPORT + (hcudp[SIXLOWPAN_HC1_HC_UDP_PORTS] & 0x0F)); - memcpy(&udp->udpchksum, &hcudp[RIME_HC1_HC_UDP_CHKSUM], 2); + memcpy(&udp->udpchksum, &hcudp[SIXLOWPAN_HC1_HC_UDP_CHKSUM], 2); g_uncomp_hdrlen += UDP_HDRLEN; g_frame_hdrlen += SIXLOWPAN_HC1_HC_UDP_HDR_LEN; diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index dc45b3fdd0..7a2621cfba 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -291,7 +291,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, */ fragptr = fptr + hdrsize; - switch ((GETINT16(fragptr, RIME_FRAG_DISPATCH_SIZE) & 0xf800) >> 8) + switch ((GETINT16(fragptr, SIXLOWPAN_FRAG_DISPATCH_SIZE) & 0xf800) >> 8) { /* First fragment of new reassembly */ @@ -299,8 +299,8 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, { /* Set up for the reassembly */ - fragsize = GETINT16(fragptr, RIME_FRAG_DISPATCH_SIZE) & 0x07ff; - fragtag = GETINT16(fragptr, RIME_FRAG_TAG); + fragsize = GETINT16(fragptr, SIXLOWPAN_FRAG_DISPATCH_SIZE) & 0x07ff; + fragtag = GETINT16(fragptr, SIXLOWPAN_FRAG_TAG); g_frame_hdrlen += SIXLOWPAN_FRAG1_HDR_LEN; ninfo("FRAG1: fragsize=%d fragtag=%d fragoffset=%d\n", @@ -317,9 +317,9 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, { /* Set offset, tag, size. Offset is in units of 8 bytes. */ - fragoffset = fragptr[RIME_FRAG_OFFSET]; - fragtag = GETINT16(fragptr, RIME_FRAG_TAG); - fragsize = GETINT16(fragptr, RIME_FRAG_DISPATCH_SIZE) & 0x07ff; + fragoffset = fragptr[SIXLOWPAN_FRAG_OFFSET]; + fragtag = GETINT16(fragptr, SIXLOWPAN_FRAG_TAG); + fragsize = GETINT16(fragptr, SIXLOWPAN_FRAG_DISPATCH_SIZE) & 0x07ff; g_frame_hdrlen += SIXLOWPAN_FRAGN_HDR_LEN; ninfo("FRAGN: fragsize=%d fragtag=%d fragoffset=%d\n", @@ -402,7 +402,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, /* Verify that this fragment is part of that reassembly sequence */ else if (fragsize != ieee->i_pktlen || ieee->i_reasstag != fragtag || - !rimeaddr_cmp(&ieee->i_fragsrc, &g_pktaddrs[PACKETBUF_ADDR_SENDER])) + !sixlowpan_addrcmp(&ieee->i_fragsrc, &g_pktaddrs[PACKETBUF_ADDR_SENDER])) { /* The packet is a fragment that does not belong to the packet * being reassembled or the packet is not a fragment. @@ -454,7 +454,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, ninfo("Starting reassembly: i_pktlen %u, i_reasstag %d\n", ieee->i_pktlen, ieee->i_reasstag); - rimeaddr_copy(&ieee->i_fragsrc, &g_pktaddrs[PACKETBUF_ADDR_SENDER]); + sixlowpan_addrcopy(&ieee->i_fragsrc, &g_pktaddrs[PACKETBUF_ADDR_SENDER]); } #endif /* CONFIG_NET_6LOWPAN_FRAG */ @@ -463,7 +463,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, hc1 = fptr + g_frame_hdrlen; #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 - if ((hc1[RIME_HC1_DISPATCH] & SIXLOWPAN_DISPATCH_IPHC_MASK) == SIXLOWPAN_DISPATCH_IPHC) + if ((hc1[SIXLOWPAN_HC1_DISPATCH] & SIXLOWPAN_DISPATCH_IPHC_MASK) == SIXLOWPAN_DISPATCH_IPHC) { ninfo("IPHC Dispatch\n"); sixlowpan_uncompresshdr_hc06(fragsize, iob, fptr, bptr); @@ -472,7 +472,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, #endif /* CONFIG_NET_6LOWPAN_COMPRESSION_HC06 */ #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC1 - if (hc1[RIME_HC1_DISPATCH] == SIXLOWPAN_DISPATCH_HC1) + if (hc1[SIXLOWPAN_HC1_DISPATCH] == SIXLOWPAN_DISPATCH_HC1) { ninfo("HC1 Dispatch\n"); sixlowpan_uncompresshdr_hc1(fragsize, iob, fptr, bptr); @@ -480,7 +480,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, else #endif /* CONFIG_NET_6LOWPAN_COMPRESSION_HC1 */ - if (hc1[RIME_HC1_DISPATCH] == SIXLOWPAN_DISPATCH_IPV6) + if (hc1[SIXLOWPAN_HC1_DISPATCH] == SIXLOWPAN_DISPATCH_IPV6) { ninfo("IPv6 Dispatch\n"); sixlowpan_uncompress_ipv6hdr(fptr, bptr); @@ -489,7 +489,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, { /* Unknown or unsupported header */ - nwarn("WARNING: Unknown dispatch: %u\n", hc1[RIME_HC1_DISPATCH]); + nwarn("WARNING: Unknown dispatch: %u\n", hc1[SIXLOWPAN_HC1_DISPATCH]); return OK; } @@ -519,10 +519,10 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, #endif /* CONFIG_NET_6LOWPAN_FRAG */ - /* Copy "payload" from the rime buffer to the IEEE802.15.4 MAC driver's - * d_buf. If this frame is a first fragment or not part of a fragmented - * packet, we have already copied the compressed headers, g_uncomp_hdrlen - * and g_frame_hdrlen are non-zerio, fragoffset is. + /* Copy "payload" from the frame buffer to the IEEE802.15.4 MAC driver's + * packet buffer, d_buf. If this frame is a first fragment or not part of + * a fragmented packet, we have already copied the compressed headers, + * g_uncomp_hdrlen and g_frame_hdrlen are non-zerio, fragoffset is. */ paysize = iob->io_len - g_frame_hdrlen; @@ -751,12 +751,12 @@ int sixlowpan_input(FAR struct ieee802154_driver_s *ieee, ipv6hdr = IPv6BUF(&ieee->i_dev); - /* Get the Rime MAC address of the destination. This - * assumes an encoding of the MAC address in the IPv6 + /* Get the IEEE 802.15.4 MAC address of the destination. + * This assumes an encoding of the MAC address in the IPv6 * address. */ - sixlowpan_rimefromip(ipv6hdr->destipaddr, &destmac); + sixlowpan_addrfromip(ipv6hdr->destipaddr, &destmac); /* The data payload should follow the IPv6 header plus * the protocol header. diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index 0a9cf07424..aefe48b11b 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -71,19 +71,17 @@ * Pre-processor Definitions ****************************************************************************/ -/* Rime addres macros */ -/* Copy a Rime address */ +/* IEEE 802.15.4 addres macros */ +/* Copy a an IEEE 802.15.4 address */ -#define rimeaddr_copy(dest,src) \ +#define sixlowpan_addrcopy(dest,src) \ memcpy(dest, src, NET_6LOWPAN_ADDRSIZE) -/* Compare two Rime addresses */ +/* Compare two IEEE 802.15.4 addresses */ -#define rimeaddr_cmp(addr1,addr2) \ +#define sixlowpan_addrcmp(addr1,addr2) \ (memcmp(addr1, addr2, NET_6LOWPAN_ADDRSIZE) == 0) -/* Pointers in the Rime buffer */ - /* Packet buffer Definitions */ #define PACKETBUF_ATTR_PACKET_TYPE_DATA 0 @@ -198,14 +196,6 @@ struct ipv6icmp_hdr_s * during that processing */ -/* A pointer to the rime buffer. - * - * We initialize it to the beginning of the rime buffer, then access - * different fields by updating the offset ieee->g_frame_hdrlen. - */ - -extern FAR uint8_t *g_rimeptr; - /* g_uncomp_hdrlen is the length of the headers before compression (if HC2 * is used this includes the UDP header in addition to the IP header). */ @@ -449,8 +439,8 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, * sixlowpan_buf * * This function is called by the input function when the dispatch is HC06. - * We process the packet in the rime buffer, uncompress the header fields, - * and copy the result in the sixlowpan buffer. At the end of the + * We process the frame in the IOB buffer, uncompress the header fields, + * and copy the result into the driver packet buffer. At the end of the * decompression, g_frame_hdrlen and g_uncompressed_hdrlen are set to the * appropriate values * @@ -509,8 +499,8 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, * Uncompress HC1 (and HC_UDP) headers and put them in sixlowpan_buf * * This function is called by the input function when the dispatch is - * HC1. It processes the packet in the rime buffer, uncompresses the - * header fields, and copies the result in the sixlowpan buffer. At the + * HC1. It processes the frame in the IOB buffer, uncompresses the + * header fields, and copies the result in the packet buffer. At the * end of the decompression, g_frame_hdrlen and uncompressed_hdr_len * are set to the appropriate values * @@ -535,34 +525,34 @@ int sixlowpan_uncompresshdr_hc1(uint16_t iplen, FAR struct iob_s *iob, #endif /**************************************************************************** - * Name: sixlowpan_islinklocal, sixlowpan_ipfromrime, sixlowpan_rimefromip, + * Name: sixlowpan_islinklocal, sixlowpan_ipfromaddr, sixlowpan_addrfromip, * and sixlowpan_ismacbased * * Description: - * sixlowpan_ipfromrime: Create a link local IPv6 address from a rime - * address. + * sixlowpan_ipfromaddr: Create a link local IPv6 address from an IEEE + * 802.15.4 address. * - * sixlowpan_rimefromip: Extract the rime address from a link local IPv6 - * address. + * sixlowpan_addrfromip: Extract the IEEE 802.15.14 address from a link + * local IPv6 address. * * sixlowpan_islinklocal and sixlowpan_ismacbased will return true for * address created in this fashion. * * 128 112 96 80 64 48 32 16 * ---- ---- ---- ---- ---- ---- ---- ---- - * fe80 0000 0000 0000 xxxx 0000 0000 0000 2-byte Rime address (VALID?) - * fe80 0000 0000 0000 xxxx xxxx xxxx xxxx 8-byte Rime address + * fe80 0000 0000 0000 xxxx 0000 0000 0000 2-byte short address (VALID?) + * fe80 0000 0000 0000 xxxx xxxx xxxx xxxx 8-byte extended address * ****************************************************************************/ #define sixlowpan_islinklocal(ipaddr) ((ipaddr)[0] == NTOHS(0xfe80)) -void sixlowpan_ipfromrime(FAR const struct sixlowpan_addr_s *rime, +void sixlowpan_ipfromaddr(FAR const struct sixlowpan_addr_s *addr, net_ipv6addr_t ipaddr); -void sixlowpan_rimefromip(const net_ipv6addr_t ipaddr, - FAR struct sixlowpan_addr_s *rime); +void sixlowpan_addrfromip(const net_ipv6addr_t ipaddr, + FAR struct sixlowpan_addr_s *addr); bool sixlowpan_ismacbased(const net_ipv6addr_t ipaddr, - FAR const struct sixlowpan_addr_s *rime); + FAR const struct sixlowpan_addr_s *addr); /**************************************************************************** * Name: sixlowpan_src_panid diff --git a/net/sixlowpan/sixlowpan_tcpsend.c b/net/sixlowpan/sixlowpan_tcpsend.c index 9091c04016..5e5d07bdfb 100644 --- a/net/sixlowpan/sixlowpan_tcpsend.c +++ b/net/sixlowpan/sixlowpan_tcpsend.c @@ -317,11 +317,11 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_SEND); - /* Get the Rime MAC address of the destination This assumes an encoding - * of the MAC address in the IPv6 address. + /* Get the IEEE 802.15.4 MAC address of the destination. This assumes + * an encoding of the MAC address in the IPv6 address. */ - sixlowpan_rimefromip(conn->u.ipv6.raddr, &destmac); + sixlowpan_addrfromip(conn->u.ipv6.raddr, &destmac); /* If routable, then call sixlowpan_send() to format and send the 6loWPAN * packet. @@ -414,11 +414,11 @@ void sixlowpan_tcp_send(FAR struct net_driver_s *dev) uint16_t hdrlen; uint16_t buflen; - /* Get the Rime MAC address of the destination. This assumes an - * encoding of the MAC address in the IPv6 address. + /* Get the IEEE 802.15.4 MAC address of the destination. This + * assumes an encoding of the MAC address in the IPv6 address. */ - sixlowpan_rimefromip(ipv6hdr->ipv6.destipaddr, &destmac); + sixlowpan_addrfromip(ipv6hdr->ipv6.destipaddr, &destmac); /* Get the IPv6 + TCP combined header length. The size of the TCP * header is encoded in the top 4 bits of the tcpoffset field (in diff --git a/net/sixlowpan/sixlowpan_udpsend.c b/net/sixlowpan/sixlowpan_udpsend.c index 2ab4286d8f..bbc39ef758 100644 --- a/net/sixlowpan/sixlowpan_udpsend.c +++ b/net/sixlowpan/sixlowpan_udpsend.c @@ -292,11 +292,11 @@ ssize_t psock_6lowpan_udp_sendto(FAR struct socket *psock, psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_SEND); - /* Get the Rime MAC address of the destination This assumes an encoding - * of the MAC address in the IPv6 address. + /* Get the IEEE 802.15.4 MAC address of the destination This assumes an + * encoding of the MAC address in the IPv6 address. */ - sixlowpan_rimefromip(to6->sin6_addr.in6_u.u6_addr16, &destmac); + sixlowpan_addrfromip(to6->sin6_addr.in6_u.u6_addr16, &destmac); /* If routable, then call sixlowpan_send() to format and send the 6loWPAN * packet. diff --git a/net/sixlowpan/sixlowpan_utils.c b/net/sixlowpan/sixlowpan_utils.c index 072a1b26d6..e194786e3b 100644 --- a/net/sixlowpan/sixlowpan_utils.c +++ b/net/sixlowpan/sixlowpan_utils.c @@ -68,19 +68,19 @@ ****************************************************************************/ /**************************************************************************** - * Name: sixlowpan_ipfromrime + * Name: sixlowpan_ipfromaddr * * Description: - * Create a link local IPv6 address from a rime address: + * Create a link local IPv6 address from an IEEE 802.15.4 address: * * 128 112 96 80 64 48 32 16 * ---- ---- ---- ---- ---- ---- ---- ---- - * fe80 0000 0000 0000 0000 00ff fe00 xxxx 2-byte Rime address IEEE 48-bit MAC - * fe80 0000 0000 0000 xxxx xxxx xxxx xxxx 8-byte Rime address IEEE EUI-64 + * fe80 0000 0000 0000 0000 00ff fe00 xxxx 2-byte address IEEE 48-bit MAC + * fe80 0000 0000 0000 xxxx xxxx xxxx xxxx 8-byte address IEEE EUI-64 * ****************************************************************************/ -void sixlowpan_ipfromrime(FAR const struct sixlowpan_addr_s *rime, +void sixlowpan_ipfromaddr(FAR const struct sixlowpan_addr_s *addr, net_ipv6addr_t ipaddr) { /* We consider only links with IEEE EUI-64 identifier or IEEE 48-bit MAC @@ -91,42 +91,42 @@ void sixlowpan_ipfromrime(FAR const struct sixlowpan_addr_s *rime, ipaddr[0] = HTONS(0xfe80); #ifdef CONFIG_NET_6LOWPAN_EXTENDEDADDR - memcpy(&ipaddr[4], rime, NET_6LOWPAN_ADDRSIZE); + memcpy(&ipaddr[4], addr, NET_6LOWPAN_ADDRSIZE); ipaddr[4] ^= HTONS(0x0200); #else ipaddr[5] = HTONS(0x00ff); ipaddr[6] = HTONS(0xfe00); - memcpy(&ipaddr[7], rime, NET_6LOWPAN_ADDRSIZE); + memcpy(&ipaddr[7], addr, NET_6LOWPAN_ADDRSIZE); ipaddr[7] ^= HTONS(0x0200); #endif } /**************************************************************************** - * Name: sixlowpan_rimefromip + * Name: sixlowpan_addrfromip * * Description: - * Extract the rime address from a link local IPv6 address: + * Extract the IEEE 802.15.4 address from a link local IPv6 address: * * 128 112 96 80 64 48 32 16 * ---- ---- ---- ---- ---- ---- ---- ---- - * fe80 0000 0000 0000 0000 00ff fe00 xxxx 2-byte Rime address IEEE 48-bit MAC - * fe80 0000 0000 0000 xxxx xxxx xxxx xxxx 8-byte Rime address IEEE EUI-64 + * fe80 0000 0000 0000 0000 00ff fe00 xxxx 2-byte short address IEEE 48-bit MAC + * fe80 0000 0000 0000 xxxx xxxx xxxx xxxx 8-byte extended address IEEE EUI-64 * ****************************************************************************/ -void sixlowpan_rimefromip(const net_ipv6addr_t ipaddr, - FAR struct sixlowpan_addr_s *rime) +void sixlowpan_addrfromip(const net_ipv6addr_t ipaddr, + FAR struct sixlowpan_addr_s *addr) { - /* REVISIT: See notes about 2 byte addresses in sixlowpan_ipfromrime() */ + /* REVISIT: See notes about 2 byte addresses in sixlowpan_ipfromaddr() */ DEBUGASSERT(ipaddr[0] == HTONS(0xfe80)); #ifdef CONFIG_NET_6LOWPAN_EXTENDEDADDR - memcpy(rime, &ipaddr[4], NET_6LOWPAN_ADDRSIZE); + memcpy(addr, &ipaddr[4], NET_6LOWPAN_ADDRSIZE); #else - memcpy(rime, &ipaddr[7], NET_6LOWPAN_ADDRSIZE); + memcpy(addr, &ipaddr[7], NET_6LOWPAN_ADDRSIZE); #endif - rime->u8[0] ^= 0x02; + addr->u8[0] ^= 0x02; } /**************************************************************************** @@ -137,24 +137,24 @@ void sixlowpan_rimefromip(const net_ipv6addr_t ipaddr, * * 128 112 96 80 64 48 32 16 * ---- ---- ---- ---- ---- ---- ---- ---- - * fe80 0000 0000 0000 0000 00ff fe00 xxxx 2-byte Rime address IEEE 48-bit MAC - * fe80 0000 0000 0000 xxxx xxxx xxxx xxxx 8-byte Rime address IEEE EUI-64 + * fe80 0000 0000 0000 0000 00ff fe00 xxxx 2-byte short address IEEE 48-bit MAC + * fe80 0000 0000 0000 xxxx xxxx xxxx xxxx 8-byte extended address IEEE EUI-64 * ****************************************************************************/ bool sixlowpan_ismacbased(const net_ipv6addr_t ipaddr, - FAR const struct sixlowpan_addr_s *rime) + FAR const struct sixlowpan_addr_s *addr) { - FAR const uint8_t *rimeptr = rime->u8; + FAR const uint8_t *byteptr = addr->u8; #ifdef CONFIG_NET_6LOWPAN_EXTENDEDADDR - return (ipaddr[4] == htons((GETINT16(rimeptr, 0) ^ 0x0200)) && - ipaddr[5] == GETINT16(rimeptr, 2) && - ipaddr[6] == GETINT16(rimeptr, 4) && - ipaddr[7] == GETINT16(rimeptr, 6)); + return (ipaddr[4] == htons((GETINT16(byteptr, 0) ^ 0x0200)) && + ipaddr[5] == GETINT16(byteptr, 2) && + ipaddr[6] == GETINT16(byteptr, 4) && + ipaddr[7] == GETINT16(byteptr, 6)); #else return (ipaddr[5] == HTONS(0x00ff) && ipaddr[6] == HTONS(0xfe00) && - ipaddr[7] == htons((GETINT16(rimeptr, 0) ^ 0x0200))); + ipaddr[7] == htons((GETINT16(byteptr, 0) ^ 0x0200))); #endif } -- GitLab From 1cf891bbe1c30496fe2c930ce0df257947f136e2 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 4 May 2017 11:33:22 -0600 Subject: [PATCH 710/990] Another baby step in removing MAC knowledge from 6loWPAN. --- include/nuttx/net/ieee802154.h | 44 ---------- include/nuttx/net/netdev.h | 4 +- include/nuttx/net/sixlowpan.h | 13 ++- net/sixlowpan/sixlowpan_framelist.c | 29 +++++-- net/sixlowpan/sixlowpan_framer.c | 101 +++++++++++++++++------ net/sixlowpan/sixlowpan_globals.c | 15 +++- net/sixlowpan/sixlowpan_hc06.c | 26 +++--- net/sixlowpan/sixlowpan_hc1.c | 8 -- net/sixlowpan/sixlowpan_input.c | 27 ++++-- net/sixlowpan/sixlowpan_internal.h | 53 +++++++++--- wireless/ieee802154/mac802154_loopback.c | 2 +- wireless/ieee802154/mac802154_netdev.c | 2 +- 12 files changed, 205 insertions(+), 119 deletions(-) diff --git a/include/nuttx/net/ieee802154.h b/include/nuttx/net/ieee802154.h index 9d9260f61b..b677195715 100644 --- a/include/nuttx/net/ieee802154.h +++ b/include/nuttx/net/ieee802154.h @@ -72,50 +72,6 @@ # define NET_6LOWPAN_ADDRSIZE NET_6LOWPAN_SADDRSIZE #endif -/* Frame format definitions *************************************************/ -/* These are some definitions of element values used in the FCF. See the - * IEEE802.15.4 spec for details. - */ - -#define FRAME802154_FRAMETYPE_SHIFT (0) /* Bits 0-2: Frame type */ -#define FRAME802154_FRAMETYPE_MASK (7 << FRAME802154_FRAMETYPE_SHIFT) -#define FRAME802154_SECENABLED_SHIFT (3) /* Bit 3: Security enabled */ -#define FRAME802154_FRAMEPENDING_SHIFT (4) /* Bit 4: Frame pending */ -#define FRAME802154_ACKREQUEST_SHIFT (5) /* Bit 5: ACK request */ -#define FRAME802154_PANIDCOMP_SHIFT (6) /* Bit 6: PANID compression */ - /* Bits 7-9: Reserved */ -#define FRAME802154_DSTADDR_SHIFT (2) /* Bits 10-11: Dest address mode */ -#define FRAME802154_DSTADDR_MASK (3 << FRAME802154_DSTADDR_SHIFT) -#define FRAME802154_VERSION_SHIFT (4) /* Bit 12-13: Frame version */ -#define FRAME802154_VERSION_MASK (3 << FRAME802154_VERSION_SHIFT) -#define FRAME802154_SRCADDR_SHIFT (6) /* Bits 14-15: Source address mode */ -#define FRAME802154_SRCADDR_MASK (3 << FRAME802154_SRCADDR_SHIFT) - -/* Unshifted values for use in struct frame802154_fcf_s */ - -#define FRAME802154_BEACONFRAME (0) -#define FRAME802154_DATAFRAME (1) -#define FRAME802154_ACKFRAME (2) -#define FRAME802154_CMDFRAME (3) - -#define FRAME802154_BEACONREQ (7) - -#define FRAME802154_IEEERESERVED (0) -#define FRAME802154_NOADDR (0) /* Only valid for ACK or Beacon frames */ -#define FRAME802154_SHORTADDRMODE (2) -#define FRAME802154_LONGADDRMODE (3) - -#define FRAME802154_NOBEACONS 0x0f - -#define FRAME802154_BROADCASTADDR 0xffff -#define FRAME802154_BROADCASTPANDID 0xffff - -#define FRAME802154_IEEE802154_2003 (0) -#define FRAME802154_IEEE802154_2006 (1) - -#define FRAME802154_SECURITY_LEVEL_NONE (0) -#define FRAME802154_SECURITY_LEVEL_128 (3) - /* This maximum size of an IEEE802.15.4 frame. Certain, non-standard * devices may exceed this value, however. */ diff --git a/include/nuttx/net/netdev.h b/include/nuttx/net/netdev.h index fe2743f5e9..0b65d2afd3 100644 --- a/include/nuttx/net/netdev.h +++ b/include/nuttx/net/netdev.h @@ -437,9 +437,11 @@ int ipv6_input(FAR struct net_driver_s *dev); #ifdef CONFIG_NET_6LOWPAN struct ieee802154_driver_s; /* See sixlowpan.h */ +struct eee802154_data_ind_s; /* See sixlowpan.h */ struct iob_s; /* See iob.h */ int sixlowpan_input(FAR struct ieee802154_driver_s *ieee, - FAR struct iob_s *framelist); + FAR struct iob_s *framelist, + FAR const struct eee802154_data_ind_s *ind); #endif /**************************************************************************** diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index 91869dd41f..48370a79e5 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -342,6 +342,7 @@ */ struct ieee802154_frame_meta_s; /* Forward reference */ +struct eee802154_data_ind_s; /* Forward reference */ struct iob_s; /* Forward reference */ struct ieee802154_driver_s @@ -420,7 +421,7 @@ struct ieee802154_driver_s /* The source MAC address of the fragments being merged */ - struct sixlowpan_addr_s i_fragsrc; + union sixlowpan_anyaddr_u i_fragsrc; /* That time at which reassembly was started. If the elapsed time * exceeds CONFIG_NET_6LOWPAN_MAXAGE, then the reassembly will @@ -525,7 +526,12 @@ struct ieee802154_driver_s * * Input Parameters: * ieee - The IEEE802.15.4 MAC network driver interface. - * framelist - The head of an incoming list of frames. + * framelist - The head of an incoming list of frames. Normally this + * would be a single frame. A list may be provided if + * appropriate, however. + * ind - Meta data characterizing the received packet. If there are + * multilple frames in the list, this meta data must apply to + * all of the frames! * * Returned Value: * Ok is returned on success; Othewise a negated errno value is returned. @@ -533,7 +539,8 @@ struct ieee802154_driver_s ****************************************************************************/ int sixlowpan_input(FAR struct ieee802154_driver_s *ieee, - FAR struct iob_s *framelist); + FAR struct iob_s *framelist, + FAR const struct eee802154_data_ind_s *ind); #endif /* CONFIG_NET_6LOWPAN */ #endif /* __INCLUDE_NUTTX_NET_SIXLOWPAN_H */ diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c index 005473c4e0..46e2bd750d 100644 --- a/net/sixlowpan/sixlowpan_framelist.c +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -234,7 +234,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, /* Reset address buffer and packet buffer metatadata */ memset(g_pktattrs, 0, PACKETBUF_NUM_ATTRS * sizeof(uint16_t)); - memset(g_pktaddrs, 0, PACKETBUF_NUM_ADDRS * sizeof(struct sixlowpan_addr_s)); + memset(&g_packet_meta, 0, sizeof(struct packet_metadata_s)); g_pktattrs[PACKETBUF_ATTR_MAX_MAC_TRANSMISSIONS] = CONFIG_NET_6LOWPAN_MAX_MACTRANSMITS; @@ -284,11 +284,30 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, ninfo("Sending packet length %d\n", buflen); - /* Set the source and destination address */ + /* Set the source and destination address. The source MAC address + * is a fixed size, determined by a configuration setting. The + * destination MAC address many be either short or extended. + */ + +#ifdef CONFIG_NET_6LOWPAN_EXTENDEDADDR + g_packet_meta.sextended = TRUE; + sixlowpan_eaddrcopy(g_packet_meta.source.eaddr.u8, + &ieee->i_dev.d_mac.ieee802154); +#else + sixlowpan_saddrcopy(g_packet_meta.source.saddr.u8, + &ieee->i_dev.d_mac.ieee802154); +#endif - sixlowpan_addrcopy(&g_pktaddrs[PACKETBUF_ADDR_SENDER], - &ieee->i_dev.d_mac.ieee802154); - sixlowpan_addrcopy(&g_pktaddrs[PACKETBUF_ADDR_RECEIVER], destmac); + /* REVISIT: Destination MAC address could be of different size than + * the source MAC address. + */ + +#ifdef CONFIG_NET_6LOWPAN_EXTENDEDADDR + g_packet_meta.dextended = TRUE; + sixlowpan_addrcopy(g_packet_meta.dest.eaddr.u8, destmac); +#else + sixlowpan_addrcopy(g_packet_meta.dest.saddr.u8, destmac); +#endif /* Get the destination PAN ID. * diff --git a/net/sixlowpan/sixlowpan_framer.c b/net/sixlowpan/sixlowpan_framer.c index 49b1548498..db2ac6dfce 100644 --- a/net/sixlowpan/sixlowpan_framer.c +++ b/net/sixlowpan/sixlowpan_framer.c @@ -67,27 +67,26 @@ ****************************************************************************/ /**************************************************************************** - * Name: sixlowpan_addrnull + * Name: sixlowpan_anyaddrnull * * Description: - * If the output address is NULL in the MAC header buf, then it is + * If the destination address is all zero in the MAC header buf, then it is * broadcast on the 802.15.4 network. * * Input parameters: - * addrmode - The address mode + * addr - The address to check + * addrlen - The length of the address in bytes * * Returned Value: - * The address length associated with the address mode. + * True if the address is all zero. * ****************************************************************************/ -static bool sixlowpan_addrnull(FAR uint8_t *addr) +static bool sixlowpan_anyaddrnull(FAR uint8_t *addr, uint8_t addrlen) { - int i = NET_6LOWPAN_ADDRSIZE; - - while (i-- > 0) + while (addrlen-- > 0) { - if (addr[i] != 0x00) + if (addr[addrlen] != 0x00) { return false; } @@ -96,6 +95,46 @@ static bool sixlowpan_addrnull(FAR uint8_t *addr) return true; } +/**************************************************************************** + * Name: sixlowpan_saddrnull + * + * Description: + * If the destination address is all zero in the MAC header buf, then it is + * broadcast on the 802.15.4 network. + * + * Input parameters: + * eaddr - The short address to check + * + * Returned Value: + * The address length associated with the address mode. + * + ****************************************************************************/ + +static inline bool sixlowpan_saddrnull(FAR uint8_t *saddr) +{ + return sixlowpan_anyaddrnull(saddr, NET_6LOWPAN_SADDRSIZE); +} + +/**************************************************************************** + * Name: sixlowpan_eaddrnull + * + * Description: + * If the destination address is all zero in the MAC header buf, then it is + * broadcast on the 802.15.4 network. + * + * Input parameters: + * eaddr - The extended address to check + * + * Returned Value: + * The address length associated with the address mode. + * + ****************************************************************************/ + +static inline bool sixlowpan_eaddrnull(FAR uint8_t *eaddr) +{ + return sixlowpan_anyaddrnull(eaddr, NET_6LOWPAN_EADDRSIZE); +} + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -142,7 +181,15 @@ int sixlowpan_meta_data(uint16_t dest_panid, * broadcast on the 802.15.4 network. */ - rcvrnull = sixlowpan_addrnull(g_pktaddrs[PACKETBUF_ADDR_RECEIVER].u8); + if (g_packet_meta.dextended != 0) + { + rcvrnull = sixlowpan_eaddrnull(g_packet_meta.dest.eaddr.u8); + } + else + { + rcvrnull = sixlowpan_saddrnull(g_packet_meta.dest.saddr.u8); + } + if (rcvrnull) { meta->fcf.ack_required = g_pktattrs[PACKETBUF_ATTR_MAC_ACK]; @@ -175,26 +222,30 @@ int sixlowpan_meta_data(uint16_t dest_panid, meta->dest_addr[0] = 0xff; meta->dest_addr[1] = 0xff; } + else if (g_packet_meta.dextended != 0) + { + meta->fcf.dest_addr_mode = FRAME802154_LONGADDRMODE; + sixlowpan_eaddrcopy((struct sixlowpan_addr_s *)&meta->dest_addr, + g_packet_meta.dest.eaddr.u8); + } else { - /* Copy the destination address */ - - sixlowpan_addrcopy((struct sixlowpan_addr_s *)&meta->dest_addr, - g_pktaddrs[PACKETBUF_ADDR_RECEIVER].u8); - - /* Use short destination address mode if so configured */ + meta->fcf.dest_addr_mode = FRAME802154_SHORTADDRMODE; + sixlowpan_saddrcopy((struct sixlowpan_addr_s *)&meta->dest_addr, + g_packet_meta.dest.saddr.u8); + } #ifdef CONFIG_NET_6LOWPAN_EXTENDEDADDR - meta->fcf.dest_addr_mode = FRAME802154_LONGADDRMODE; + DEBUGASSERT(g_packet_meta.sextended != 0); + meta->fcf.src_addr_mode = FRAME802154_LONGADDRMODE; + sixlowpan_eaddrcopy((struct sixlowpan_addr_s *)&meta->src_addr, + g_packet_meta.source.eaddr.u8); #else - meta->fcf.dest_addr_mode = FRAME802154_SHORTADDRMODE; + DEBUGASSERT(g_packet_meta.sextended == 0); + meta->fcf.src_addr_mode = FRAME802154_SHORTADDRMODE; + sixlowpan_saddrcopy((struct sixlowpan_addr_s *)&meta->src_addr, + g_packet_meta.source.saddr.u8); #endif - } - - /* Set the source address to the node address assigned to the device */ - - sixlowpan_addrcopy((struct sixlowpan_addr_s *)&meta->src_addr, - &ieee->i_dev.d_mac.ieee802154); /* Use short soruce address mode if so configured */ @@ -203,7 +254,7 @@ int sixlowpan_meta_data(uint16_t dest_panid, #else meta->fcf.src_addr_mode = FRAME802154_SHORTADDRMODE; #endif -#endif +#endif /* 0 */ #warning Missing logic return -ENOSYS; diff --git a/net/sixlowpan/sixlowpan_globals.c b/net/sixlowpan/sixlowpan_globals.c index 646e2fec21..c1f4f9ef50 100644 --- a/net/sixlowpan/sixlowpan_globals.c +++ b/net/sixlowpan/sixlowpan_globals.c @@ -67,9 +67,22 @@ uint8_t g_uncomp_hdrlen; uint8_t g_frame_hdrlen; +/* In order to provide a customizable IEEE 802.15.4 MAC header, a structure + * of meta data is passed to the MAC network driver, struct + * ieee802154_frame_meta_s. Many of the settings in this meta data are + * fixed, deterimined by the 6loWPAN configuration. Other settings depend + * on the protocol used in the current packet or on chacteristics of the + * destination node. + * + * The following structure is used to summarize those per-packet + * customizations and, along, with the fixed configuratin settings, + * determines the full form of that meta data. + */ + /* Packet buffer metadata: Attributes and addresses */ uint16_t g_pktattrs[PACKETBUF_NUM_ATTRS]; -struct sixlowpan_addr_s g_pktaddrs[PACKETBUF_NUM_ADDRS]; + +struct packet_metadata_s g_packet_meta; #endif /* CONFIG_NET_6LOWPAN */ diff --git a/net/sixlowpan/sixlowpan_hc06.c b/net/sixlowpan/sixlowpan_hc06.c index 2a262f5b53..0413e834c9 100644 --- a/net/sixlowpan/sixlowpan_hc06.c +++ b/net/sixlowpan/sixlowpan_hc06.c @@ -275,7 +275,7 @@ static uint8_t compress_addr_64(FAR const net_ipv6addr_t ipaddr, ****************************************************************************/ static void uncompress_addr(FAR net_ipv6addr_t ipaddr, uint8_t const prefix[], - uint8_t prefpost, FAR struct sixlowpan_addr_s *macaddr) + uint8_t prefpost) { uint8_t prefcount = prefpost >> 4; uint8_t postcount = prefpost & 0x0f; @@ -316,7 +316,7 @@ static void uncompress_addr(FAR net_ipv6addr_t ipaddr, uint8_t const prefix[], { /* No IID based configuration if no prefix and no data => unspec */ - sixlowpan_ipfromaddr(macaddr, ipaddr); + nwarn("WARNING: No IID based configuration\n") } ninfo("Uncompressing %d + %d => %04x:%04x:%04x:%04x:%04x:%04x:%04x:%04x\n", @@ -983,18 +983,22 @@ void sixlowpan_uncompresshdr_hc06(uint16_t iplen, FAR struct iob_s *iob, } } - /* If tmp == 0 we do not have a Address context and therefore no prefix */ + /* If tmp == 0 we do not have a address context and therefore no prefix */ + /* REVISIT: Source address may not be the same size as the destination + * address. + */ uncompress_addr(ipv6->srcipaddr, - tmp != 0 ? addrcontext->prefix : NULL, g_unc_ctxconf[tmp], - (FAR struct sixlowpan_addr_s *)&g_pktaddrs[PACKETBUF_ADDR_SENDER]); + tmp != 0 ? addrcontext->prefix : NULL, g_unc_ctxconf[tmp]); } else { /* No compression and link local */ + /* REVISIT: Source address may not be the same size as the destination + * address. + */ - uncompress_addr(ipv6->srcipaddr, g_llprefix, g_unc_llconf[tmp], - (FAR struct sixlowpan_addr_s *)&g_pktaddrs[PACKETBUF_ADDR_SENDER]); + uncompress_addr(ipv6->srcipaddr, g_llprefix, g_unc_llconf[tmp]); } /* Destination address */ @@ -1029,7 +1033,7 @@ void sixlowpan_uncompresshdr_hc06(uint16_t iplen, FAR struct iob_s *iob, g_hc06ptr++; } - uncompress_addr(ipv6->destipaddr, prefix, g_unc_mxconf[tmp], NULL); + uncompress_addr(ipv6->destipaddr, prefix, g_unc_mxconf[tmp]); } } else @@ -1052,15 +1056,13 @@ void sixlowpan_uncompresshdr_hc06(uint16_t iplen, FAR struct iob_s *iob, return; } - uncompress_addr(ipv6->destipaddr, addrcontext->prefix, g_unc_ctxconf[tmp], - (FAR struct sixlowpan_addr_s *)&g_pktaddrs[PACKETBUF_ADDR_RECEIVER]); + uncompress_addr(ipv6->destipaddr, addrcontext->prefix, g_unc_ctxconf[tmp]); } else { /* Not address context based => link local M = 0, DAC = 0 - same as SAC */ - uncompress_addr(ipv6->destipaddr, g_llprefix, g_unc_llconf[tmp], - (FAR struct sixlowpan_addr_s *)&g_pktaddrs[PACKETBUF_ADDR_RECEIVER]); + uncompress_addr(ipv6->destipaddr, g_llprefix, g_unc_llconf[tmp]); } } diff --git a/net/sixlowpan/sixlowpan_hc1.c b/net/sixlowpan/sixlowpan_hc1.c index d0e5b13d99..88d7f72412 100644 --- a/net/sixlowpan/sixlowpan_hc1.c +++ b/net/sixlowpan/sixlowpan_hc1.c @@ -271,14 +271,6 @@ int sixlowpan_uncompresshdr_hc1(uint16_t iplen, FAR struct iob_s *iob, ipv6->tcf = 0; /* Bits 0-3: traffic class (LS), 4-bits: flow label (MS) */ ipv6->flow = 0; /* 16-bit flow label (LS) */ - /* Use stateless auto-configuration to set source and destination IP - * addresses. - */ - - sixlowpan_ipfromaddr(&g_pktaddrs[PACKETBUF_ADDR_SENDER], - ipv6->srcipaddr); - sixlowpan_ipfromaddr(&g_pktaddrs[PACKETBUF_ADDR_RECEIVER], - ipv6->destipaddr); g_uncomp_hdrlen += IPv6_HDRLEN; /* len[], proto, and ttl depend on the encoding */ diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index 7a2621cfba..58ee8af571 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -401,8 +401,8 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, /* Verify that this fragment is part of that reassembly sequence */ - else if (fragsize != ieee->i_pktlen || ieee->i_reasstag != fragtag || - !sixlowpan_addrcmp(&ieee->i_fragsrc, &g_pktaddrs[PACKETBUF_ADDR_SENDER])) + else if (fragsize != ieee->i_pktlen || ieee->i_reasstag != fragtag /* || + !sixlowpan_addrcmp(&ieee->i_fragsrc, &ind->???) */) { /* The packet is a fragment that does not belong to the packet * being reassembled or the packet is not a fragment. @@ -454,7 +454,15 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, ninfo("Starting reassembly: i_pktlen %u, i_reasstag %d\n", ieee->i_pktlen, ieee->i_reasstag); - sixlowpan_addrcopy(&ieee->i_fragsrc, &g_pktaddrs[PACKETBUF_ADDR_SENDER]); + /* Extract the source address from the 'ind' meta data. NOTE that the + * size of the source address may be different that our local, destination + * address. + */ + +#warning Missing logic +#if 0 + sixlowpan_addrcopy(&ieee->i_fragsrc, ind->???]); +#endif } #endif /* CONFIG_NET_6LOWPAN_FRAG */ @@ -496,7 +504,6 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, #ifdef CONFIG_NET_6LOWPAN_FRAG /* Is this the first fragment is a sequence? */ - if (isfirstfrag) { /* Yes.. Remember the offset from the beginning of d_buf where we @@ -517,6 +524,8 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, g_uncomp_hdrlen = ieee->i_boffset; } + + #endif /* CONFIG_NET_6LOWPAN_FRAG */ /* Copy "payload" from the frame buffer to the IEEE802.15.4 MAC driver's @@ -686,7 +695,12 @@ static int sixlowpan_dispatch(FAR struct ieee802154_driver_s *ieee) * * Input Parameters: * ieee - The IEEE802.15.4 MAC network driver interface. - * framelist - The head of an incoming list of frames. + * framelist - The head of an incoming list of frames. Normally this + * would be a single frame. A list may be provided if + * appropriate, however. + * ind - Meta data characterizing the received packet. If there are + * multilple frames in the list, this meta data must apply to + * all of the frames! * * Returned Value: * Ok is returned on success; Othewise a negated errno value is returned. @@ -694,7 +708,8 @@ static int sixlowpan_dispatch(FAR struct ieee802154_driver_s *ieee) ****************************************************************************/ int sixlowpan_input(FAR struct ieee802154_driver_s *ieee, - FAR struct iob_s *framelist) + FAR struct iob_s *framelist, + FAR const struct eee802154_data_ind_s *ind) { int ret = -EINVAL; diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index aefe48b11b..1720ddcdf4 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -74,13 +74,31 @@ /* IEEE 802.15.4 addres macros */ /* Copy a an IEEE 802.15.4 address */ +#define sixlowpan_anyaddrcopy(dest,src,len) \ + memcpy(dest, src, len) + +#define sixlowpan_saddrcopy(dest,src) \ + sixlowpan_anyaddrcopy(dest,src,NET_6LOWPAN_SADDRSIZE) + +#define sixlowpan_aeddrcopy(dest,src) \ + sixlowpan_anyaddrcopy(dest,src,NET_6LOWPAN_EADDRSIZE) + #define sixlowpan_addrcopy(dest,src) \ - memcpy(dest, src, NET_6LOWPAN_ADDRSIZE) + sixlowpan_anyaddrcopy(dest,src,NET_6LOWPAN_ADDRSIZE) /* Compare two IEEE 802.15.4 addresses */ +#define sixlowpan_anyaddrcmp(addr1,addr2,len) \ + (memcmp(addr1, addr2, len) == 0) + +#define sixlowpan_saddrcmp(addr1,addr2) \ + sixlowpan_anyaddrcmp(addr1,addr2,NET_6LOWPAN_SADDRSIZE) + +#define sixlowpan_eaddrcmp(addr1,addr2) \ + sixlowpan_anyaddrcmp(addr1,addr2,NET_6LOWPAN_EADDRSIZE) + #define sixlowpan_addrcmp(addr1,addr2) \ - (memcmp(addr1, addr2, NET_6LOWPAN_ADDRSIZE) == 0) + sixlowpan_anyaddrcmp(addr1,addr2,NET_6LOWPAN_ADDRSIZE) /* Packet buffer Definitions */ @@ -127,15 +145,6 @@ #define PACKETBUF_NUM_ATTRS 23 -/* Addresses (indices into g_pktaddrs) */ - -#define PACKETBUF_ADDR_SENDER 0 -#define PACKETBUF_ADDR_RECEIVER 1 -#define PACKETBUF_ADDR_ESENDER 2 -#define PACKETBUF_ADDR_ERECEIVER 3 - -#define PACKETBUF_NUM_ADDRS 4 - /* General helper macros ****************************************************/ #define GETINT16(ptr,index) \ @@ -185,6 +194,26 @@ struct ipv6icmp_hdr_s struct icmpv6_iphdr_s icmp; }; +/* In order to provide a customizable IEEE 802.15.4 MAC header, a structure + * of meta data is passed to the MAC network driver, struct + * ieee802154_frame_meta_s. Many of the settings in this meta data are + * fixed, deterimined by the 6loWPAN configuration. Other settings depend + * on the protocol used in the current packet or on chacteristics of the + * destination node. + * + * The following structure is used to summarize those per-packet + * customizations and, along, with the fixed configuratin settings, + * determines the full form of that meta data. + */ + +struct packet_metadata_s +{ + uint8_t sextended : 1; /* Extended source address */ + uint8_t dextended : 1; /* Extended destination address */ + union sixlowpan_anyaddr_u source; /* Source IEEE 802.15.4 address */ + union sixlowpan_anyaddr_u dest; /* Destination IEEE 802.15.4 address */ +}; + /**************************************************************************** * Public Data ****************************************************************************/ @@ -212,7 +241,7 @@ extern uint8_t g_frame_hdrlen; /* Packet buffer metadata: Attributes and addresses */ extern uint16_t g_pktattrs[PACKETBUF_NUM_ATTRS]; -extern struct sixlowpan_addr_s g_pktaddrs[PACKETBUF_NUM_ADDRS]; +extern struct packet_metadata_s g_packet_meta; /**************************************************************************** * Public Types diff --git a/wireless/ieee802154/mac802154_loopback.c b/wireless/ieee802154/mac802154_loopback.c index 51780af2c4..8b0abaf5b5 100644 --- a/wireless/ieee802154/mac802154_loopback.c +++ b/wireless/ieee802154/mac802154_loopback.c @@ -211,7 +211,7 @@ static int lo_loopback(FAR struct net_driver_s *dev) ninfo("Send frame %p to the network: Offset=%u Length=%u\n", iob, iob->io_offset, iob->io_len); - ret = sixlowpan_input(&priv->lo_ieee, iob); + ret = sixlowpan_input(&priv->lo_ieee, iob, NULL); /* Increment statistics */ diff --git a/wireless/ieee802154/mac802154_netdev.c b/wireless/ieee802154/mac802154_netdev.c index b81ad465bc..bf4c9013cb 100644 --- a/wireless/ieee802154/mac802154_netdev.c +++ b/wireless/ieee802154/mac802154_netdev.c @@ -718,7 +718,7 @@ static void macnet_receive(FAR struct macnet_driver_s *priv) /* Transfer the frame to the network logic */ - sixlowpan_input(&priv->md_dev, iob); + sixlowpan_input(&priv->md_dev, iob, NULL); } /**************************************************************************** -- GitLab From 920c0a2e50884ce11753d6a33849f5b58dac90eb Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 4 May 2017 12:06:28 -0600 Subject: [PATCH 711/990] One more baby step in removing MAC knowledge from 6loWPAN. --- net/sixlowpan/Kconfig | 1 + net/sixlowpan/sixlowpan_framelist.c | 11 +++--- net/sixlowpan/sixlowpan_framer.c | 4 +-- net/sixlowpan/sixlowpan_globals.c | 4 --- net/sixlowpan/sixlowpan_internal.h | 54 ++++++----------------------- 5 files changed, 17 insertions(+), 57 deletions(-) diff --git a/net/sixlowpan/Kconfig b/net/sixlowpan/Kconfig index d7c709c311..674eff01f6 100644 --- a/net/sixlowpan/Kconfig +++ b/net/sixlowpan/Kconfig @@ -151,6 +151,7 @@ config NET_6LOWPAN_MAXAGE config NET_6LOWPAN_MAX_MACTRANSMITS int "Max MAC transmissions" default 4 + range 1 255 ---help--- CONFIG_NET_6LOWPAN_MAX_MACTRANSMITS specifies how many times the MAC layer should resend packets if no link-layer ACK wasreceived. This diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c index 46e2bd750d..048944d674 100644 --- a/net/sixlowpan/sixlowpan_framelist.c +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -231,13 +231,10 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, g_uncomp_hdrlen = 0; g_frame_hdrlen = 0; - /* Reset address buffer and packet buffer metatadata */ + /* Reset frame meta data */ - memset(g_pktattrs, 0, PACKETBUF_NUM_ATTRS * sizeof(uint16_t)); memset(&g_packet_meta, 0, sizeof(struct packet_metadata_s)); - - g_pktattrs[PACKETBUF_ATTR_MAX_MAC_TRANSMISSIONS] = - CONFIG_NET_6LOWPAN_MAX_MACTRANSMITS; + g_packet_meta.xmits = CONFIG_NET_6LOWPAN_MAX_MACTRANSMITS; /* Set stream mode for all TCP packets, except FIN packets. */ @@ -249,11 +246,11 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, if ((tcp->flags & TCP_FIN) == 0 && (tcp->flags & TCP_CTL) != TCP_ACK) { - g_pktattrs[PACKETBUF_ATTR_PACKET_TYPE] = PACKETBUF_ATTR_PACKET_TYPE_STREAM; + g_packet_meta.type = FRAME_ATTR_TYPE_STREAM; } else if ((tcp->flags & TCP_FIN) == TCP_FIN) { - g_pktattrs[PACKETBUF_ATTR_PACKET_TYPE] = PACKETBUF_ATTR_PACKET_TYPE_STREAM_END; + g_packet_meta.type = FRAME_ATTR_TYPE_STREAM_END; } } diff --git a/net/sixlowpan/sixlowpan_framer.c b/net/sixlowpan/sixlowpan_framer.c index db2ac6dfce..f5c5c25966 100644 --- a/net/sixlowpan/sixlowpan_framer.c +++ b/net/sixlowpan/sixlowpan_framer.c @@ -175,7 +175,7 @@ int sixlowpan_meta_data(uint16_t dest_panid, /* Build the FCF (Only non-zero elements need to be initialized). */ meta->fcf.frame_type = FRAME802154_DATAFRAME; - meta->fcf.frame_pending = g_pktattrs[PACKETBUF_ATTR_PENDING]; + meta->fcf.frame_pending = g_packet_meta.pending; /* If the output address is NULL in the MAC header buf, then it is * broadcast on the 802.15.4 network. @@ -192,7 +192,7 @@ int sixlowpan_meta_data(uint16_t dest_panid, if (rcvrnull) { - meta->fcf.ack_required = g_pktattrs[PACKETBUF_ATTR_MAC_ACK]; + meta->fcf.ack_required = g_packet_meta.macack; } /* Insert IEEE 802.15.4 (2003) version bit. */ diff --git a/net/sixlowpan/sixlowpan_globals.c b/net/sixlowpan/sixlowpan_globals.c index c1f4f9ef50..7c5740df9e 100644 --- a/net/sixlowpan/sixlowpan_globals.c +++ b/net/sixlowpan/sixlowpan_globals.c @@ -79,10 +79,6 @@ uint8_t g_frame_hdrlen; * determines the full form of that meta data. */ -/* Packet buffer metadata: Attributes and addresses */ - -uint16_t g_pktattrs[PACKETBUF_NUM_ATTRS]; - struct packet_metadata_s g_packet_meta; #endif /* CONFIG_NET_6LOWPAN */ diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index 1720ddcdf4..7e3f45332a 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -100,50 +100,13 @@ #define sixlowpan_addrcmp(addr1,addr2) \ sixlowpan_anyaddrcmp(addr1,addr2,NET_6LOWPAN_ADDRSIZE) -/* Packet buffer Definitions */ +/* Frame meta data definitions */ -#define PACKETBUF_ATTR_PACKET_TYPE_DATA 0 -#define PACKETBUF_ATTR_PACKET_TYPE_ACK 1 -#define PACKETBUF_ATTR_PACKET_TYPE_STREAM 2 -#define PACKETBUF_ATTR_PACKET_TYPE_STREAM_END 3 -#define PACKETBUF_ATTR_PACKET_TYPE_TIMESTAMP 4 - -/* Packet buffer attributes (indices into g_pktattrs) */ - -#define PACKETBUF_ATTR_NONE 0 - -/* Scope 0 attributes: used only on the local node. */ - -#define PACKETBUF_ATTR_CHANNEL 1 -#define PACKETBUF_ATTR_NETWORK_ID 2 -#define PACKETBUF_ATTR_LINK_QUALITY 3 -#define PACKETBUF_ATTR_RSSI 4 -#define PACKETBUF_ATTR_TIMESTAMP 5 -#define PACKETBUF_ATTR_RADIO_TXPOWER 6 -#define PACKETBUF_ATTR_LISTEN_TIME 7 -#define PACKETBUF_ATTR_TRANSMIT_TIME 8 -#define PACKETBUF_ATTR_MAX_MAC_TRANSMISSIONS 9 -#define PACKETBUF_ATTR_MAC_ACK 10 - -/* Scope 1 attributes: used between two neighbors only. */ - -#define PACKETBUF_ATTR_RELIABLE 11 -#define PACKETBUF_ATTR_PACKET_ID 12 -#define PACKETBUF_ATTR_PACKET_TYPE 13 -#define PACKETBUF_ATTR_REXMIT 14 -#define PACKETBUF_ATTR_MAX_REXMIT 15 -#define PACKETBUF_ATTR_NUM_REXMIT 16 -#define PACKETBUF_ATTR_PENDING 17 - -/* Scope 2 attributes: used between end-to-end nodes. */ - -#define PACKETBUF_ATTR_HOPS 18 -#define PACKETBUF_ATTR_TTL 19 -#define PACKETBUF_ATTR_EPACKET_ID 20 -#define PACKETBUF_ATTR_EPACKET_TYPE 21 -#define PACKETBUF_ATTR_ERELIABLE 22 - -#define PACKETBUF_NUM_ATTRS 23 +#define FRAME_ATTR_TYPE_DATA 0 +#define FRAME_ATTR_TYPE_ACK 1 +#define FRAME_ATTR_TYPE_STREAM 2 +#define FRAME_ATTR_TYPE_STREAM_END 3 +#define FRAME_ATTR_TYPE_TIMESTAMP 4 /* General helper macros ****************************************************/ @@ -208,8 +171,12 @@ struct ipv6icmp_hdr_s struct packet_metadata_s { + uint8_t type : 3; /* See FRAME_ATTR_TYPE_* definitons */ + uint8_t pending : 1; /* Pending attribute */ + uint8_t macack : 1; /* MAC ACK */ uint8_t sextended : 1; /* Extended source address */ uint8_t dextended : 1; /* Extended destination address */ + uint8_t xmits; /* Max MAC transmisstion */ union sixlowpan_anyaddr_u source; /* Source IEEE 802.15.4 address */ union sixlowpan_anyaddr_u dest; /* Destination IEEE 802.15.4 address */ }; @@ -240,7 +207,6 @@ extern uint8_t g_frame_hdrlen; /* Packet buffer metadata: Attributes and addresses */ -extern uint16_t g_pktattrs[PACKETBUF_NUM_ATTRS]; extern struct packet_metadata_s g_packet_meta; /**************************************************************************** -- GitLab From d385f461306a5977523e8a7447127d0bd55050d3 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 4 May 2017 13:19:11 -0600 Subject: [PATCH 712/990] 6loWPAN: The last vestiges of MAC header generate stripped out. --- .../wireless/ieee802154/ieee802154_mac.h | 2 +- net/sixlowpan/sixlowpan_framelist.c | 55 +++++++-- net/sixlowpan/sixlowpan_framer.c | 114 ++++++++---------- net/sixlowpan/sixlowpan_internal.h | 25 ++-- 4 files changed, 109 insertions(+), 87 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index f91fbbceae..93bd2ca76f 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -524,7 +524,7 @@ struct ieee802154_frame_meta_s uint8_t msdu_handle; /* Handle assoc. with MSDU */ /* Number of bytes contained in the MAC Service Data Unit (MSDU) - * to be transmitted by the MAC sublayer enitity + * to be transmitted by the MAC sublayer entity * Note: This could be a uint8_t but if anyone ever wants to use * non-standard frame lengths, they may want a length larger than * a uint8_t. diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c index 048944d674..9d5756ed8b 100644 --- a/net/sixlowpan/sixlowpan_framelist.c +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -218,7 +218,6 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, struct sixlowpan_addr_s bcastmac; uint16_t pktlen; uint16_t paysize; - uint16_t dest_panid; #ifdef CONFIG_NET_6LOWPAN_FRAG uint16_t outlen = 0; #endif @@ -238,6 +237,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, /* Set stream mode for all TCP packets, except FIN packets. */ +#if 0 /* Currently the frame type is always data */ if (destip->proto == IP_PROTO_TCP) { FAR const struct tcp_hdr_s *tcp = @@ -253,6 +253,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, g_packet_meta.type = FRAME_ATTR_TYPE_STREAM_END; } } +#endif /* The destination address will be tagged to each outbound packet. If the * argument destmac is NULL, we are sending a broadcast packet. @@ -312,14 +313,14 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, * PAN IDs are the same. */ - dest_panid = 0xffff; - (void)sixlowpan_src_panid(ieee, &dest_panid); + g_packet_meta.dpanid = 0xffff; + (void)sixlowpan_src_panid(ieee, &g_packet_meta.dpanid); /* Based on the collected attributes and addresses, construct the MAC meta * data structure that we need to interface with the IEEE802.15.4 MAC. */ - ret = sixlowpan_meta_data(dest_panid, &meta); + ret = sixlowpan_meta_data(ieee, &meta, 0); if (ret < 0) { nerr("ERROR: sixlowpan_meta_data() failed: %d\n", ret); @@ -528,14 +529,42 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, } /* Submit all of the fragments to the MAC. We send all frames back- - * to-back like this to eliminate any possible condition where some + * to-back like this to minimize any possible condition where some * frame which is not a fragment from this sequence from intervening. */ - ret = sixlowpan_frame_submit(ieee, &meta, qhead); - if (ret < 0) + paysize = 0; + for (iob = qhead; iob != NULL; iob = qhead) { - nerr("ERROR: sixlowpan_frame_submit() failed: %d\n", ret); + uint16_t newsize; + + /* Remove the IOB from the list */ + + qhead = iob->io_flink; + iob->io_flink = NULL; + + /* Re-construct the MAC meta data structure using the correct + * payload size for this frame (if it is different than the + * payload size of the previous frame). + */ + + newsize = iob->io_len - iob->io_offset; + if (newsize != paysize) + { + ret = sixlowpan_meta_data(ieee, &meta, newsize); + if (ret < 0) + { + nerr("ERROR: sixlowpan_meta_data() failed: %d\n", ret); + } + + paysize = newsize; + } + + ret = sixlowpan_frame_submit(ieee, &meta, iob); + if (ret < 0) + { + nerr("ERROR: sixlowpan_frame_submit() failed: %d\n", ret); + } } /* Update the datagram TAG value */ @@ -565,6 +594,16 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, sixlowpan_dumpbuffer("Outgoing frame", (FAR const uint8_t *)iob->io_data, iob->io_len); + /* Re-construct the MAC meta data structure using the correct payload + * size for this frame. + */ + + ret = sixlowpan_meta_data(ieee, &meta, iob->io_len - iob->io_offset); + if (ret < 0) + { + nerr("ERROR: sixlowpan_meta_data() failed: %d\n", ret); + } + /* Submit the frame to the MAC */ ret = sixlowpan_frame_submit(ieee, &meta, iob); diff --git a/net/sixlowpan/sixlowpan_framer.c b/net/sixlowpan/sixlowpan_framer.c index f5c5c25966..b750156d36 100644 --- a/net/sixlowpan/sixlowpan_framer.c +++ b/net/sixlowpan/sixlowpan_framer.c @@ -147,9 +147,9 @@ static inline bool sixlowpan_eaddrnull(FAR uint8_t *eaddr) * data structure that we need to interface with the IEEE802.15.4 MAC. * * Input Parameters: - * dest_panid - PAN ID of the destination. May be 0xffff if the destination - * is not associated. - * meta - Location to return the corresponding meta data. + * ieee - IEEE 802.15.4 MAC driver state reference. + * meta - Location to return the corresponding meta data. + * paylen - The size of the data payload to be sent. * * Returned Value: * Ok is returned on success; Othewise a negated errno value is returned. @@ -159,105 +159,97 @@ static inline bool sixlowpan_eaddrnull(FAR uint8_t *eaddr) * ****************************************************************************/ -int sixlowpan_meta_data(uint16_t dest_panid, - FAR struct ieee802154_frame_meta_s *meta) +int sixlowpan_meta_data(FAR struct ieee802154_driver_s *ieee, + FAR struct ieee802154_frame_meta_s *meta, + uint16_t paylen) { -#if 0 /* To be provided */ - /* Set up the frame parameters */ - - uint16_t src_panid; bool rcvrnull; - /* Initialize all prameters to all zero */ + /* Initialize all settings to all zero */ memset(meta, 0, sizeof(struct ieee802154_frame_meta_s)); - /* Build the FCF (Only non-zero elements need to be initialized). */ + /* Source address mode */ - meta->fcf.frame_type = FRAME802154_DATAFRAME; - meta->fcf.frame_pending = g_packet_meta.pending; + meta->src_addr_mode = g_packet_meta.sextended != 0? + IEEE802154_ADDRMODE_EXTENDED : + IEEE802154_ADDRMODE_SHORT; - /* If the output address is NULL in the MAC header buf, then it is - * broadcast on the 802.15.4 network. - */ + /* Check for a broadcast destination address (all zero) */ if (g_packet_meta.dextended != 0) { + /* Extended destination address mode */ + rcvrnull = sixlowpan_eaddrnull(g_packet_meta.dest.eaddr.u8); } else { + /* Short destination address mode */ + rcvrnull = sixlowpan_saddrnull(g_packet_meta.dest.saddr.u8); } if (rcvrnull) { - meta->fcf.ack_required = g_packet_meta.macack; + meta->msdu_flags.ack_tx = TRUE; } - /* Insert IEEE 802.15.4 (2003) version bit. */ - - meta->fcf.frame_version = FRAME802154_IEEE802154_2003; + /* Destination address */ - /* Complete the addressing fields. */ - /* Get the source PAN ID from the IEEE802.15.4 radio driver */ - - src_panid = 0xffff; - (void)sixlowpan_src_panid(ieee, &src_panid); - - /* Set the source and destination PAN ID. */ - - meta->src_pid = src_panid; - meta->dest_pid = dest_panid; - - /* If the output address is NULL in the MAC header buf, then it is - * broadcast on the 802.15.4 network. + /* If the output address is NULL, then it is broadcast on the 802.15.4 + * network. */ if (rcvrnull) { /* Broadcast requires short address mode. */ - meta->fcf.dest_addr_mode = FRAME802154_SHORTADDRMODE; - meta->dest_addr[0] = 0xff; - meta->dest_addr[1] = 0xff; + meta->dest_addr.mode = IEEE802154_ADDRMODE_SHORT; + meta->dest_addr.saddr = 0; } else if (g_packet_meta.dextended != 0) { - meta->fcf.dest_addr_mode = FRAME802154_LONGADDRMODE; - sixlowpan_eaddrcopy((struct sixlowpan_addr_s *)&meta->dest_addr, - g_packet_meta.dest.eaddr.u8); + /* Extended destination address mode */ + + meta->dest_addr.mode = IEEE802154_ADDRMODE_EXTENDED; + sixlowpan_eaddrcopy(&meta->dest_addr.eaddr, g_packet_meta.dest.eaddr.u8); } else { - meta->fcf.dest_addr_mode = FRAME802154_SHORTADDRMODE; - sixlowpan_saddrcopy((struct sixlowpan_addr_s *)&meta->dest_addr, - g_packet_meta.dest.saddr.u8); + /* Short destination address mode */ + + meta->dest_addr.mode = IEEE802154_ADDRMODE_SHORT; + sixlowpan_saddrcopy(&meta->dest_addr.saddr, g_packet_meta.dest.saddr.u8); } -#ifdef CONFIG_NET_6LOWPAN_EXTENDEDADDR - DEBUGASSERT(g_packet_meta.sextended != 0); - meta->fcf.src_addr_mode = FRAME802154_LONGADDRMODE; - sixlowpan_eaddrcopy((struct sixlowpan_addr_s *)&meta->src_addr, - g_packet_meta.source.eaddr.u8); -#else - DEBUGASSERT(g_packet_meta.sextended == 0); - meta->fcf.src_addr_mode = FRAME802154_SHORTADDRMODE; - sixlowpan_saddrcopy((struct sixlowpan_addr_s *)&meta->src_addr, - g_packet_meta.source.saddr.u8); -#endif + meta->dest_addr.panid = g_packet_meta.dpanid; + + /* Handle associated with MSDU. Will increment once per packet, not + * necesarily per frame: The MSDU handler will be used for each fragment + * of a disassembled packet. + */ + + meta->msdu_handle = ieee->i_msdu_handle++; - /* Use short soruce address mode if so configured */ + /* Number of bytes contained in the MAC Service Data Unit (MSDU) */ -#ifdef CONFIG_NET_6LOWPAN_EXTENDEDADDR - meta->fcf.src_addr_mode = FRAME802154_LONGADDRMODE; -#else - meta->fcf.src_addr_mode = FRAME802154_SHORTADDRMODE; + meta->msdu_length = paylen; + + /* MSDU flags that may be non-zero */ + + +#ifdef CONFIG_IEEE802154_SECURITY +# warning CONFIG_IEEE802154_SECURITY not yet supported" #endif -#endif /* 0 */ + +#ifdef CONFIG_IEEE802154_UWB +# warning CONFIG_IEEE802154_UWB not yet supported" +#endif + + /* Ranging left zero */ -#warning Missing logic - return -ENOSYS; + return OK; } /**************************************************************************** diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index 7e3f45332a..1e38d46b65 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -80,7 +80,7 @@ #define sixlowpan_saddrcopy(dest,src) \ sixlowpan_anyaddrcopy(dest,src,NET_6LOWPAN_SADDRSIZE) -#define sixlowpan_aeddrcopy(dest,src) \ +#define sixlowpan_eaddrcopy(dest,src) \ sixlowpan_anyaddrcopy(dest,src,NET_6LOWPAN_EADDRSIZE) #define sixlowpan_addrcopy(dest,src) \ @@ -100,14 +100,6 @@ #define sixlowpan_addrcmp(addr1,addr2) \ sixlowpan_anyaddrcmp(addr1,addr2,NET_6LOWPAN_ADDRSIZE) -/* Frame meta data definitions */ - -#define FRAME_ATTR_TYPE_DATA 0 -#define FRAME_ATTR_TYPE_ACK 1 -#define FRAME_ATTR_TYPE_STREAM 2 -#define FRAME_ATTR_TYPE_STREAM_END 3 -#define FRAME_ATTR_TYPE_TIMESTAMP 4 - /* General helper macros ****************************************************/ #define GETINT16(ptr,index) \ @@ -171,12 +163,10 @@ struct ipv6icmp_hdr_s struct packet_metadata_s { - uint8_t type : 3; /* See FRAME_ATTR_TYPE_* definitons */ - uint8_t pending : 1; /* Pending attribute */ - uint8_t macack : 1; /* MAC ACK */ uint8_t sextended : 1; /* Extended source address */ uint8_t dextended : 1; /* Extended destination address */ uint8_t xmits; /* Max MAC transmisstion */ + uint16_t dpanid; /* Destination PAN ID */ union sixlowpan_anyaddr_u source; /* Source IEEE 802.15.4 address */ union sixlowpan_anyaddr_u dest; /* Destination IEEE 802.15.4 address */ }; @@ -271,9 +261,9 @@ int sixlowpan_send(FAR struct net_driver_s *dev, * data structure that we need to interface with the IEEE802.15.4 MAC. * * Input Parameters: - * dest_panid - PAN ID of the destination. May be 0xffff if the destination - * is not associated. - * meta - Location to return the corresponding meta data. + * ieee - IEEE 802.15.4 MAC driver state reference. + * meta - Location to return the corresponding meta data. + * paylen - The size of the data payload to be sent. * * Returned Value: * Ok is returned on success; Othewise a negated errno value is returned. @@ -283,8 +273,9 @@ int sixlowpan_send(FAR struct net_driver_s *dev, * ****************************************************************************/ -int sixlowpan_meta_data(uint16_t dest_panid, - FAR struct ieee802154_frame_meta_s *meta); +int sixlowpan_meta_data(FAR struct ieee802154_driver_s *ieee, + FAR struct ieee802154_frame_meta_s *meta, + uint16_t paylen); /**************************************************************************** * Name: sixlowpan_frame_hdrlen -- GitLab From 128936d9a6f709fb055a3b17e660372b7a77cd50 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 4 May 2017 17:16:45 -0600 Subject: [PATCH 713/990] 6loWPAN: Design simplications; also remove unused utility function. --- net/sixlowpan/sixlowpan_framelist.c | 35 +++++++--------------------- net/sixlowpan/sixlowpan_hc06.c | 2 +- net/sixlowpan/sixlowpan_internal.h | 8 +------ net/sixlowpan/sixlowpan_utils.c | 36 ----------------------------- 4 files changed, 10 insertions(+), 71 deletions(-) diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c index 9d5756ed8b..9b522a5d71 100644 --- a/net/sixlowpan/sixlowpan_framelist.c +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -317,7 +317,8 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, (void)sixlowpan_src_panid(ieee, &g_packet_meta.dpanid); /* Based on the collected attributes and addresses, construct the MAC meta - * data structure that we need to interface with the IEEE802.15.4 MAC. + * data structure that we need to interface with the IEEE802.15.4 MAC (we + * will update the MSDU payload size when the IOB has been setup). */ ret = sixlowpan_meta_data(ieee, &meta, 0); @@ -533,32 +534,18 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, * frame which is not a fragment from this sequence from intervening. */ - paysize = 0; for (iob = qhead; iob != NULL; iob = qhead) { - uint16_t newsize; - /* Remove the IOB from the list */ qhead = iob->io_flink; iob->io_flink = NULL; - /* Re-construct the MAC meta data structure using the correct - * payload size for this frame (if it is different than the - * payload size of the previous frame). - */ + /* Update the MSDU length in the metadata */ - newsize = iob->io_len - iob->io_offset; - if (newsize != paysize) - { - ret = sixlowpan_meta_data(ieee, &meta, newsize); - if (ret < 0) - { - nerr("ERROR: sixlowpan_meta_data() failed: %d\n", ret); - } + meta.msdu_length = iob->io_len - iob->io_offset; - paysize = newsize; - } + /* And submit the frame to the MAC */ ret = sixlowpan_frame_submit(ieee, &meta, iob); if (ret < 0) @@ -594,17 +581,11 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, sixlowpan_dumpbuffer("Outgoing frame", (FAR const uint8_t *)iob->io_data, iob->io_len); - /* Re-construct the MAC meta data structure using the correct payload - * size for this frame. - */ + /* Update the MSDU length in the metadata */ - ret = sixlowpan_meta_data(ieee, &meta, iob->io_len - iob->io_offset); - if (ret < 0) - { - nerr("ERROR: sixlowpan_meta_data() failed: %d\n", ret); - } + meta.msdu_length = iob->io_len - iob->io_offset; - /* Submit the frame to the MAC */ + /* And submit the frame to the MAC */ ret = sixlowpan_frame_submit(ieee, &meta, iob); if (ret < 0) diff --git a/net/sixlowpan/sixlowpan_hc06.c b/net/sixlowpan/sixlowpan_hc06.c index 0413e834c9..8ee28332bc 100644 --- a/net/sixlowpan/sixlowpan_hc06.c +++ b/net/sixlowpan/sixlowpan_hc06.c @@ -316,7 +316,7 @@ static void uncompress_addr(FAR net_ipv6addr_t ipaddr, uint8_t const prefix[], { /* No IID based configuration if no prefix and no data => unspec */ - nwarn("WARNING: No IID based configuration\n") + nwarn("WARNING: No IID based configuration\n"); } ninfo("Uncompressing %d + %d => %04x:%04x:%04x:%04x:%04x:%04x:%04x:%04x\n", diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index 1e38d46b65..276a497652 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -511,13 +511,9 @@ int sixlowpan_uncompresshdr_hc1(uint16_t iplen, FAR struct iob_s *iob, #endif /**************************************************************************** - * Name: sixlowpan_islinklocal, sixlowpan_ipfromaddr, sixlowpan_addrfromip, - * and sixlowpan_ismacbased + * Name: sixlowpan_islinklocal, sixlowpan_addrfromip, and sixlowpan_ismacbased * * Description: - * sixlowpan_ipfromaddr: Create a link local IPv6 address from an IEEE - * 802.15.4 address. - * * sixlowpan_addrfromip: Extract the IEEE 802.15.14 address from a link * local IPv6 address. * @@ -533,8 +529,6 @@ int sixlowpan_uncompresshdr_hc1(uint16_t iplen, FAR struct iob_s *iob, #define sixlowpan_islinklocal(ipaddr) ((ipaddr)[0] == NTOHS(0xfe80)) -void sixlowpan_ipfromaddr(FAR const struct sixlowpan_addr_s *addr, - net_ipv6addr_t ipaddr); void sixlowpan_addrfromip(const net_ipv6addr_t ipaddr, FAR struct sixlowpan_addr_s *addr); bool sixlowpan_ismacbased(const net_ipv6addr_t ipaddr, diff --git a/net/sixlowpan/sixlowpan_utils.c b/net/sixlowpan/sixlowpan_utils.c index e194786e3b..687a0bd7e4 100644 --- a/net/sixlowpan/sixlowpan_utils.c +++ b/net/sixlowpan/sixlowpan_utils.c @@ -67,40 +67,6 @@ * Public Functions ****************************************************************************/ -/**************************************************************************** - * Name: sixlowpan_ipfromaddr - * - * Description: - * Create a link local IPv6 address from an IEEE 802.15.4 address: - * - * 128 112 96 80 64 48 32 16 - * ---- ---- ---- ---- ---- ---- ---- ---- - * fe80 0000 0000 0000 0000 00ff fe00 xxxx 2-byte address IEEE 48-bit MAC - * fe80 0000 0000 0000 xxxx xxxx xxxx xxxx 8-byte address IEEE EUI-64 - * - ****************************************************************************/ - -void sixlowpan_ipfromaddr(FAR const struct sixlowpan_addr_s *addr, - net_ipv6addr_t ipaddr) -{ - /* We consider only links with IEEE EUI-64 identifier or IEEE 48-bit MAC - * addresses. - */ - - memset(ipaddr, 0, sizeof(net_ipv6addr_t)); - ipaddr[0] = HTONS(0xfe80); - -#ifdef CONFIG_NET_6LOWPAN_EXTENDEDADDR - memcpy(&ipaddr[4], addr, NET_6LOWPAN_ADDRSIZE); - ipaddr[4] ^= HTONS(0x0200); -#else - ipaddr[5] = HTONS(0x00ff); - ipaddr[6] = HTONS(0xfe00); - memcpy(&ipaddr[7], addr, NET_6LOWPAN_ADDRSIZE); - ipaddr[7] ^= HTONS(0x0200); -#endif -} - /**************************************************************************** * Name: sixlowpan_addrfromip * @@ -117,8 +83,6 @@ void sixlowpan_ipfromaddr(FAR const struct sixlowpan_addr_s *addr, void sixlowpan_addrfromip(const net_ipv6addr_t ipaddr, FAR struct sixlowpan_addr_s *addr) { - /* REVISIT: See notes about 2 byte addresses in sixlowpan_ipfromaddr() */ - DEBUGASSERT(ipaddr[0] == HTONS(0xfe80)); #ifdef CONFIG_NET_6LOWPAN_EXTENDEDADDR -- GitLab From 14fc1b2d390b0fca6b2cde837467994a0bee08b8 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 4 May 2017 19:17:38 -0600 Subject: [PATCH 714/990] 6loWPAN: Local MAC address is fixed by the configuration. The remote address be with short or extended. --- include/nuttx/net/ieee802154.h | 6 +++ include/nuttx/net/sixlowpan.h | 2 +- net/sixlowpan/sixlowpan_framelist.c | 37 +++++++------- net/sixlowpan/sixlowpan_hc06.c | 45 +++++++++++------ net/sixlowpan/sixlowpan_hc1.c | 2 +- net/sixlowpan/sixlowpan_input.c | 12 ++--- net/sixlowpan/sixlowpan_internal.h | 35 +++++++++---- net/sixlowpan/sixlowpan_send.c | 4 +- net/sixlowpan/sixlowpan_tcpsend.c | 4 +- net/sixlowpan/sixlowpan_udpsend.c | 2 +- net/sixlowpan/sixlowpan_utils.c | 77 ++++++++++++++++++++++------- 11 files changed, 151 insertions(+), 75 deletions(-) diff --git a/include/nuttx/net/ieee802154.h b/include/nuttx/net/ieee802154.h index b677195715..736141a351 100644 --- a/include/nuttx/net/ieee802154.h +++ b/include/nuttx/net/ieee802154.h @@ -100,6 +100,12 @@ union sixlowpan_anyaddr_u struct sixlowpan_eaddr_s eaddr; }; +struct sixlowpan_tagaddr_s +{ + bool extended; + union sixlowpan_anyaddr_u u; +}; + /* Represents the configured address size */ struct sixlowpan_addr_s diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index 48370a79e5..591687bb1d 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -228,7 +228,7 @@ #define SIXLOWPAN_IS_IID_16BIT_COMPRESSABLE(a) \ ((((a)[4]) == 0x0000) && (((a)[5]) == HTONS(0x00ff)) && \ - (((a)[6]) == 0xfe00)) + (((a)[6]) == HTONS(0xfe00))) /* Check whether the 9-bit group-id of the compressed multicast address is * known. It is true if the 9-bit group is the all nodes or all routers diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c index 9b522a5d71..6f41a59210 100644 --- a/net/sixlowpan/sixlowpan_framelist.c +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -209,13 +209,13 @@ static void sixlowpan_compress_ipv6hdr(FAR const struct ipv6_hdr_s *ipv6hdr, int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, FAR const struct ipv6_hdr_s *destip, FAR const void *buf, size_t buflen, - FAR const struct sixlowpan_addr_s *destmac) + FAR const struct sixlowpan_tagaddr_s *destmac) { struct ieee802154_frame_meta_s meta; FAR struct iob_s *iob; FAR uint8_t *fptr; int framer_hdrlen; - struct sixlowpan_addr_s bcastmac; + struct sixlowpan_tagaddr_s bcastmac; uint16_t pktlen; uint16_t paysize; #ifdef CONFIG_NET_6LOWPAN_FRAG @@ -261,7 +261,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, if (destmac == NULL) { - memset(&bcastmac, 0, sizeof(struct sixlowpan_addr_s)); + memset(&bcastmac, 0, sizeof(struct sixlowpan_tagaddr_s)); destmac = &bcastmac; } @@ -296,16 +296,15 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, &ieee->i_dev.d_mac.ieee802154); #endif - /* REVISIT: Destination MAC address could be of different size than - * the source MAC address. - */ - -#ifdef CONFIG_NET_6LOWPAN_EXTENDEDADDR - g_packet_meta.dextended = TRUE; - sixlowpan_addrcopy(g_packet_meta.dest.eaddr.u8, destmac); -#else - sixlowpan_addrcopy(g_packet_meta.dest.saddr.u8, destmac); -#endif + if (destmac->extended) + { + g_packet_meta.dextended = TRUE; + sixlowpan_eaddrcopy(g_packet_meta.dest.eaddr.u8, destmac->u.eaddr.u8); + } + else + { + sixlowpan_saddrcopy(g_packet_meta.dest.saddr.u8, destmac->u.saddr.u8); + } /* Get the destination PAN ID. * @@ -418,9 +417,9 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, */ pktlen = buflen + g_uncomp_hdrlen; - PUTINT16(fragptr, SIXLOWPAN_FRAG_DISPATCH_SIZE, - ((SIXLOWPAN_DISPATCH_FRAG1 << 8) | pktlen)); - PUTINT16(fragptr, SIXLOWPAN_FRAG_TAG, ieee->i_dgramtag); + PUTHOST16(fragptr, SIXLOWPAN_FRAG_DISPATCH_SIZE, + ((SIXLOWPAN_DISPATCH_FRAG1 << 8) | pktlen)); + PUTHOST16(fragptr, SIXLOWPAN_FRAG_TAG, ieee->i_dgramtag); g_frame_hdrlen += SIXLOWPAN_FRAG1_HDR_LEN; @@ -487,9 +486,9 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, /* Setup up the FRAGN header after the frame header. */ - PUTINT16(fragptr, SIXLOWPAN_FRAG_DISPATCH_SIZE, - ((SIXLOWPAN_DISPATCH_FRAGN << 8) | pktlen)); - PUTINT16(fragptr, SIXLOWPAN_FRAG_TAG, ieee->i_dgramtag); + PUTHOST16(fragptr, SIXLOWPAN_FRAG_DISPATCH_SIZE, + ((SIXLOWPAN_DISPATCH_FRAGN << 8) | pktlen)); + PUTHOST16(fragptr, SIXLOWPAN_FRAG_TAG, ieee->i_dgramtag); fragptr[SIXLOWPAN_FRAG_OFFSET] = outlen >> 3; fragn_hdrlen += SIXLOWPAN_FRAGN_HDR_LEN; diff --git a/net/sixlowpan/sixlowpan_hc06.c b/net/sixlowpan/sixlowpan_hc06.c index 8ee28332bc..18d3ccf696 100644 --- a/net/sixlowpan/sixlowpan_hc06.c +++ b/net/sixlowpan/sixlowpan_hc06.c @@ -220,7 +220,7 @@ static FAR struct sixlowpan_addrcontext_s * } /**************************************************************************** - * Name: compress_addr_64 + * Name: compress_tagaddr and compress_laddr * * Description: * Uncompress addresses based on a prefix and a postfix with zeroes in @@ -232,12 +232,12 @@ static FAR struct sixlowpan_addrcontext_s * * ****************************************************************************/ -static uint8_t compress_addr_64(FAR const net_ipv6addr_t ipaddr, - FAR const struct sixlowpan_addr_s *macaddr, +static uint8_t compress_tagaddr(FAR const net_ipv6addr_t ipaddr, + FAR const struct sixlowpan_tagaddr_s *macaddr, uint8_t bitpos) { - ninfo("ipaddr=%p macaddr=%p bitpos=%u g_hc06ptr=%p\n", - ipaddr, macaddr, bitpos, g_hc06ptr); + ninfo("ipaddr=%p macaddr=%p extended=%u bitpos=%u g_hc06ptr=%p\n", + ipaddr, macaddr, macaddr->extended, bitpos, g_hc06ptr); if (sixlowpan_ismacbased(ipaddr, macaddr)) { @@ -261,6 +261,23 @@ static uint8_t compress_addr_64(FAR const net_ipv6addr_t ipaddr, } } +static uint8_t compress_laddr(FAR const net_ipv6addr_t ipaddr, + FAR const struct sixlowpan_addr_s *macaddr, + uint8_t bitpos) +{ + struct sixlowpan_tagaddr_s tagaddr; + +#ifdef CONFIG_NET_6LOWPAN_EXTENDEDADDR + tagaddr.extended = true; + sixlowpan_eaddrcopy(tagaddr.u.eaddr.u8, macaddr->u8); +#else + tagaddr.extended = false; + sixlowpan_saddrcopy(tagaddr.u.saddr.u8, macaddr->u8); +#endif + + return compress_tagaddr(ipaddr, &tagaddr, bitpos); +} + /**************************************************************************** * Name: uncompress_addr * @@ -446,7 +463,7 @@ void sixlowpan_hc06_initialize(void) void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, FAR const struct ipv6_hdr_s *ipv6, - FAR const struct sixlowpan_addr_s *destmac, + FAR const struct sixlowpan_tagaddr_s *destmac, FAR uint8_t *fptr) { FAR uint8_t *iphc = fptr + g_frame_hdrlen; @@ -614,9 +631,9 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, /* Compression compare with this nodes address (source) */ - iphc1 |= compress_addr_64(ipv6->srcipaddr, - &ieee->i_dev.d_mac.ieee802154, - SIXLOWPAN_IPHC_SAM_BIT); + iphc1 |= compress_laddr(ipv6->srcipaddr, + &ieee->i_dev.d_mac.ieee802154, + SIXLOWPAN_IPHC_SAM_BIT); } /* No address context found for this address */ @@ -625,9 +642,9 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, ipv6->destipaddr[1] == 0 && ipv6->destipaddr[2] == 0 && ipv6->destipaddr[3] == 0) { - iphc1 |= compress_addr_64(ipv6->srcipaddr, - &ieee->i_dev.d_mac.ieee802154, - SIXLOWPAN_IPHC_SAM_BIT); + iphc1 |= compress_laddr(ipv6->srcipaddr, + &ieee->i_dev.d_mac.ieee802154, + SIXLOWPAN_IPHC_SAM_BIT); } else { @@ -701,7 +718,7 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, /* Compession compare with link adress (destination) */ - iphc1 |= compress_addr_64(ipv6->destipaddr, destmac, + iphc1 |= compress_tagaddr(ipv6->destipaddr, destmac, SIXLOWPAN_IPHC_DAM_BIT); /* No address context found for this address */ @@ -710,7 +727,7 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, ipv6->destipaddr[1] == 0 && ipv6->destipaddr[2] == 0 && ipv6->destipaddr[3] == 0) { - iphc1 |= compress_addr_64(ipv6->destipaddr, destmac, + iphc1 |= compress_tagaddr(ipv6->destipaddr, destmac, SIXLOWPAN_IPHC_DAM_BIT); } else diff --git a/net/sixlowpan/sixlowpan_hc1.c b/net/sixlowpan/sixlowpan_hc1.c index 88d7f72412..0168cb653b 100644 --- a/net/sixlowpan/sixlowpan_hc1.c +++ b/net/sixlowpan/sixlowpan_hc1.c @@ -120,7 +120,7 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, FAR const struct ipv6_hdr_s *ipv6, - FAR const struct sixlowpan_addr_s *destmac, + FAR const struct sixlowpan_tagaddr_s *destmac, FAR uint8_t *fptr) { FAR uint8_t *hc1 = fptr + g_frame_hdrlen; diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index 58ee8af571..3c203d07a1 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -291,7 +291,7 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, */ fragptr = fptr + hdrsize; - switch ((GETINT16(fragptr, SIXLOWPAN_FRAG_DISPATCH_SIZE) & 0xf800) >> 8) + switch ((GETHOST16(fragptr, SIXLOWPAN_FRAG_DISPATCH_SIZE) & 0xf800) >> 8) { /* First fragment of new reassembly */ @@ -299,8 +299,8 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, { /* Set up for the reassembly */ - fragsize = GETINT16(fragptr, SIXLOWPAN_FRAG_DISPATCH_SIZE) & 0x07ff; - fragtag = GETINT16(fragptr, SIXLOWPAN_FRAG_TAG); + fragsize = GETHOST16(fragptr, SIXLOWPAN_FRAG_DISPATCH_SIZE) & 0x07ff; + fragtag = GETHOST16(fragptr, SIXLOWPAN_FRAG_TAG); g_frame_hdrlen += SIXLOWPAN_FRAG1_HDR_LEN; ninfo("FRAG1: fragsize=%d fragtag=%d fragoffset=%d\n", @@ -318,8 +318,8 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, /* Set offset, tag, size. Offset is in units of 8 bytes. */ fragoffset = fragptr[SIXLOWPAN_FRAG_OFFSET]; - fragtag = GETINT16(fragptr, SIXLOWPAN_FRAG_TAG); - fragsize = GETINT16(fragptr, SIXLOWPAN_FRAG_DISPATCH_SIZE) & 0x07ff; + fragtag = GETHOST16(fragptr, SIXLOWPAN_FRAG_TAG); + fragsize = GETHOST16(fragptr, SIXLOWPAN_FRAG_DISPATCH_SIZE) & 0x07ff; g_frame_hdrlen += SIXLOWPAN_FRAGN_HDR_LEN; ninfo("FRAGN: fragsize=%d fragtag=%d fragoffset=%d\n", @@ -755,7 +755,7 @@ int sixlowpan_input(FAR struct ieee802154_driver_s *ieee, { FAR struct ipv6_hdr_s *ipv6hdr; FAR uint8_t *buffer; - struct sixlowpan_addr_s destmac; + struct sixlowpan_tagaddr_s destmac; size_t hdrlen; size_t buflen; diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index 276a497652..c48b89929f 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -102,9 +102,19 @@ /* General helper macros ****************************************************/ -#define GETINT16(ptr,index) \ +/* GET 16-bit data: source in network order, result in host order */ + +#define GETHOST16(ptr,index) \ ((((uint16_t)((ptr)[index])) << 8) | ((uint16_t)(((ptr)[(index) + 1])))) -#define PUTINT16(ptr,index,value) \ + +/* GET 16-bit data: source in network order, result in network order */ + +#define GETNET16(ptr,index) \ + ((((uint16_t)((ptr)[(index) + 1])) << 8) | ((uint16_t)(((ptr)[index])))) + +/* PUT 16-bit data: source in host order, result in newtwork order */ + +#define PUTHOST16(ptr,index,value) \ do \ { \ (ptr)[index] = ((uint16_t)(value) >> 8) & 0xff; \ @@ -211,7 +221,7 @@ struct net_driver_s; /* Forward reference */ struct ieee802154_driver_s; /* Forward reference */ struct devif_callback_s; /* Forward reference */ struct ipv6_hdr_s; /* Forward reference */ -struct sixlowpan_addr_s; /* Forward reference */ +struct sixlowpan_addr_s; /* Forward reference */ struct iob_s; /* Forward reference */ /**************************************************************************** @@ -232,7 +242,7 @@ struct iob_s; /* Forward reference */ * list - Head of callback list for send interrupt * ipv6hdr - IPv6 plus TCP or UDP headers. * buf - Data to send - * buflen - Length of data to send + * len - Length of data to send * raddr - The MAC address of the destination * timeout - Send timeout in deciseconds * @@ -250,7 +260,7 @@ struct iob_s; /* Forward reference */ int sixlowpan_send(FAR struct net_driver_s *dev, FAR struct devif_callback_s **list, FAR const struct ipv6_hdr_s *ipv6hdr, FAR const void *buf, - size_t buflen, FAR const struct sixlowpan_addr_s *raddr, + size_t len, FAR const struct sixlowpan_tagaddr_s *destmac, uint16_t timeout); /**************************************************************************** @@ -357,7 +367,7 @@ int sixlowpan_frame_submit(FAR struct ieee802154_driver_s *ieee, int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, FAR const struct ipv6_hdr_s *ipv6hdr, FAR const void *buf, size_t buflen, - FAR const struct sixlowpan_addr_s *destmac); + FAR const struct sixlowpan_tagaddr_s *destmac); /**************************************************************************** * Name: sixlowpan_hc06_initialize @@ -413,7 +423,7 @@ void sixlowpan_hc06_initialize(void); #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC06 void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, FAR const struct ipv6_hdr_s *ipv6, - FAR const struct sixlowpan_addr_s *destmac, + FAR const struct sixlowpan_tagaddr_s *destmac, FAR uint8_t *fptr); #endif @@ -474,7 +484,7 @@ void sixlowpan_uncompresshdr_hc06(uint16_t iplen, FAR struct iob_s *iob, #ifdef CONFIG_NET_6LOWPAN_COMPRESSION_HC1 void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, FAR const struct ipv6_hdr_s *ipv6, - FAR const struct sixlowpan_addr_s *destmac, + FAR const struct sixlowpan_tagaddr_s *destmac, FAR uint8_t *fptr); #endif @@ -529,10 +539,15 @@ int sixlowpan_uncompresshdr_hc1(uint16_t iplen, FAR struct iob_s *iob, #define sixlowpan_islinklocal(ipaddr) ((ipaddr)[0] == NTOHS(0xfe80)) +void sixlowpan_saddrfromip(const net_ipv6addr_t ipaddr, + FAR struct sixlowpan_saddr_s *saddr); +void sixlowpan_eaddrfromip(const net_ipv6addr_t ipaddr, + FAR struct sixlowpan_eaddr_s *eaddr); void sixlowpan_addrfromip(const net_ipv6addr_t ipaddr, - FAR struct sixlowpan_addr_s *addr); + FAR struct sixlowpan_tagaddr_s *addr); + bool sixlowpan_ismacbased(const net_ipv6addr_t ipaddr, - FAR const struct sixlowpan_addr_s *addr); + FAR const struct sixlowpan_tagaddr_s *addr); /**************************************************************************** * Name: sixlowpan_src_panid diff --git a/net/sixlowpan/sixlowpan_send.c b/net/sixlowpan/sixlowpan_send.c index e742acfe7d..db8337834c 100644 --- a/net/sixlowpan/sixlowpan_send.c +++ b/net/sixlowpan/sixlowpan_send.c @@ -83,7 +83,7 @@ struct sixlowpan_send_s uint16_t s_timeout; /* Send timeout in deciseconds */ systime_t s_time; /* Last send time for determining timeout */ FAR const struct ipv6_hdr_s *s_ipv6hdr; /* IPv6 header, followed by UDP or TCP header. */ - FAR const struct sixlowpan_addr_s *s_destmac; /* Destination MAC address */ + FAR const struct sixlowpan_tagaddr_s *s_destmac; /* Destination MAC address */ FAR const void *s_buf; /* Data to send */ size_t s_len; /* Length of data in buf */ }; @@ -274,7 +274,7 @@ end_wait: int sixlowpan_send(FAR struct net_driver_s *dev, FAR struct devif_callback_s **list, FAR const struct ipv6_hdr_s *ipv6hdr, FAR const void *buf, - size_t len, FAR const struct sixlowpan_addr_s *destmac, + size_t len, FAR const struct sixlowpan_tagaddr_s *destmac, uint16_t timeout) { struct sixlowpan_send_s sinfo; diff --git a/net/sixlowpan/sixlowpan_tcpsend.c b/net/sixlowpan/sixlowpan_tcpsend.c index 5e5d07bdfb..5ae5de0b81 100644 --- a/net/sixlowpan/sixlowpan_tcpsend.c +++ b/net/sixlowpan/sixlowpan_tcpsend.c @@ -164,7 +164,7 @@ ssize_t psock_6lowpan_tcp_send(FAR struct socket *psock, FAR const void *buf, FAR struct tcp_conn_s *conn; FAR struct net_driver_s *dev; struct ipv6tcp_hdr_s ipv6tcp; - struct sixlowpan_addr_s destmac; + struct sixlowpan_tagaddr_s destmac; uint16_t timeout; uint16_t iplen; int ret; @@ -409,7 +409,7 @@ void sixlowpan_tcp_send(FAR struct net_driver_s *dev) } else { - struct sixlowpan_addr_s destmac; + struct sixlowpan_tagaddr_s destmac; FAR uint8_t *buf; uint16_t hdrlen; uint16_t buflen; diff --git a/net/sixlowpan/sixlowpan_udpsend.c b/net/sixlowpan/sixlowpan_udpsend.c index bbc39ef758..7036589e09 100644 --- a/net/sixlowpan/sixlowpan_udpsend.c +++ b/net/sixlowpan/sixlowpan_udpsend.c @@ -162,7 +162,7 @@ ssize_t psock_6lowpan_udp_sendto(FAR struct socket *psock, FAR struct udp_conn_s *conn; FAR struct net_driver_s *dev; struct ipv6udp_hdr_s ipv6udp; - struct sixlowpan_addr_s destmac; + struct sixlowpan_tagaddr_s destmac; uint16_t iplen; uint16_t timeout; int ret; diff --git a/net/sixlowpan/sixlowpan_utils.c b/net/sixlowpan/sixlowpan_utils.c index 687a0bd7e4..05b60e3d38 100644 --- a/net/sixlowpan/sixlowpan_utils.c +++ b/net/sixlowpan/sixlowpan_utils.c @@ -80,17 +80,39 @@ * ****************************************************************************/ +void sixlowpan_saddrfromip(const net_ipv6addr_t ipaddr, + FAR struct sixlowpan_saddr_s *saddr) +{ + DEBUGASSERT(ipaddr[0] == HTONS(0xfe80)); + + memcpy(saddr, &ipaddr[7], NET_6LOWPAN_SADDRSIZE); + saddr->u8[0] ^= 0x02; +} + +void sixlowpan_eaddrfromip(const net_ipv6addr_t ipaddr, + FAR struct sixlowpan_eaddr_s *eaddr) +{ + DEBUGASSERT(ipaddr[0] == HTONS(0xfe80)); + + memcpy(eaddr, &ipaddr[4], NET_6LOWPAN_EADDRSIZE); + eaddr->u8[0] ^= 0x02; +} + void sixlowpan_addrfromip(const net_ipv6addr_t ipaddr, - FAR struct sixlowpan_addr_s *addr) + FAR struct sixlowpan_tagaddr_s *addr) { DEBUGASSERT(ipaddr[0] == HTONS(0xfe80)); -#ifdef CONFIG_NET_6LOWPAN_EXTENDEDADDR - memcpy(addr, &ipaddr[4], NET_6LOWPAN_ADDRSIZE); -#else - memcpy(addr, &ipaddr[7], NET_6LOWPAN_ADDRSIZE); -#endif - addr->u8[0] ^= 0x02; + if (SIXLOWPAN_IS_IID_16BIT_COMPRESSABLE(ipaddr)) + { + memset(addr, 0, sizeof(struct sixlowpan_tagaddr_s)); + sixlowpan_saddrfromip(ipaddr, &addr->u.saddr); + } + else + { + sixlowpan_eaddrfromip(ipaddr, &addr->u.eaddr); + addr->extended = true; + } } /**************************************************************************** @@ -106,20 +128,37 @@ void sixlowpan_addrfromip(const net_ipv6addr_t ipaddr, * ****************************************************************************/ -bool sixlowpan_ismacbased(const net_ipv6addr_t ipaddr, - FAR const struct sixlowpan_addr_s *addr) +bool sixlowpan_issaddrbased(const net_ipv6addr_t ipaddr, + FAR const struct sixlowpan_saddr_s *saddr) { - FAR const uint8_t *byteptr = addr->u8; - -#ifdef CONFIG_NET_6LOWPAN_EXTENDEDADDR - return (ipaddr[4] == htons((GETINT16(byteptr, 0) ^ 0x0200)) && - ipaddr[5] == GETINT16(byteptr, 2) && - ipaddr[6] == GETINT16(byteptr, 4) && - ipaddr[7] == GETINT16(byteptr, 6)); -#else + FAR const uint8_t *byteptr = saddr->u8; + return (ipaddr[5] == HTONS(0x00ff) && ipaddr[6] == HTONS(0xfe00) && - ipaddr[7] == htons((GETINT16(byteptr, 0) ^ 0x0200))); -#endif + ipaddr[7] == (GETNET16(byteptr, 0) ^ HTONS(0x0200))); +} + +bool sixlowpan_iseaddrbased(const net_ipv6addr_t ipaddr, + FAR const struct sixlowpan_eaddr_s *eaddr) +{ + FAR const uint8_t *byteptr = eaddr->u8; + + return (ipaddr[4] == (GETNET16(byteptr, 0) ^ HTONS(0x0200)) && + ipaddr[5] == GETNET16(byteptr, 2) && + ipaddr[6] == GETNET16(byteptr, 4) && + ipaddr[7] == GETNET16(byteptr, 6)); +} + +bool sixlowpan_ismacbased(const net_ipv6addr_t ipaddr, + FAR const struct sixlowpan_tagaddr_s *addr) +{ + if (addr->extended) + { + return sixlowpan_iseaddrbased(ipaddr, &addr->u.eaddr); + } + else + { + return sixlowpan_issaddrbased(ipaddr, &addr->u.saddr); + } } /**************************************************************************** -- GitLab From 075a8b913cb9c682f5039e7cfde0bb930ddb0c08 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Fri, 5 May 2017 10:10:37 +0300 Subject: [PATCH 715/990] STM32L4: separate SYSCFG into product line specific files for clarity --- arch/arm/src/stm32l4/chip/stm32l4_syscfg.h | 163 ++------------- .../arm/src/stm32l4/chip/stm32l4x3xx_syscfg.h | 182 +++++++++++++++++ .../arm/src/stm32l4/chip/stm32l4x6xx_syscfg.h | 191 ++++++++++++++++++ 3 files changed, 386 insertions(+), 150 deletions(-) create mode 100644 arch/arm/src/stm32l4/chip/stm32l4x3xx_syscfg.h create mode 100644 arch/arm/src/stm32l4/chip/stm32l4x6xx_syscfg.h diff --git a/arch/arm/src/stm32l4/chip/stm32l4_syscfg.h b/arch/arm/src/stm32l4/chip/stm32l4_syscfg.h index 2cbffbc7f1..c68c992296 100644 --- a/arch/arm/src/stm32l4/chip/stm32l4_syscfg.h +++ b/arch/arm/src/stm32l4/chip/stm32l4_syscfg.h @@ -1,8 +1,8 @@ -/**************************************************************************************************** +/************************************************************************************ * arch/arm/src/stm32l4/chip/stm32l4_syscfg.h * - * Copyright (C) 2014-2015 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Copyright (C) 2015 Sebastien Lorquet. All rights reserved. + * Author: Sebastien Lorquet * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -31,162 +31,25 @@ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * - ****************************************************************************************************/ + ************************************************************************************/ #ifndef __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4_SYSCFG_H #define __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4_SYSCFG_H -/**************************************************************************************************** +/************************************************************************************ * Included Files - ****************************************************************************************************/ + ************************************************************************************/ #include #include "chip.h" -#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX) || \ - defined(CONFIG_STM32L4_STM32L496XX) +#if defined(CONFIG_STM32L4_STM32L4X6) +# include "chip/stm32l4x6xx_syscfg.h" +#elif defined(CONFIG_STM32L4_STM32L4X3) +# include "chip/stm32l4x3xx_syscfg.h" +#else +# error "Unsupported STM32 L4 chip" +#endif -/**************************************************************************************************** - * Pre-processor Definitions - ****************************************************************************************************/ - -/* Register Offsets *********************************************************************************/ - -#define STM32L4_SYSCFG_MEMRMP_OFFSET 0x0000 /* SYSCFG memory remap register */ -#define STM32L4_SYSCFG_CFGR1_OFFSET 0x0004 /* SYSCFG configuration register 1 */ -#define STM32L4_SYSCFG_EXTICR_OFFSET(p) (0x0008 + ((p) & 0x000c)) /* Registers are displaced by 4! */ -#define STM32L4_SYSCFG_EXTICR1_OFFSET 0x0008 /* SYSCFG external interrupt configuration register 1 */ -#define STM32L4_SYSCFG_EXTICR2_OFFSET 0x000c /* SYSCFG external interrupt configuration register 2 */ -#define STM32L4_SYSCFG_EXTICR3_OFFSET 0x0010 /* SYSCFG external interrupt configuration register 3 */ -#define STM32L4_SYSCFG_EXTICR4_OFFSET 0x0014 /* SYSCFG external interrupt configuration register 4 */ -#define STM32L4_SYSCFG_SCSR_OFFSET 0x0018 /* SYSCFG SRAM2 control and status register */ -#define STM32L4_SYSCFG_CFGR2_OFFSET 0x001c /* SYSCFG configuration register 2 */ -#define STM32L4_SYSCFG_SWPR_OFFSET 0x0020 /* SYSCFG SRAM2 write protection register */ -#define STM32L4_SYSCFG_SKR_OFFSET 0x0024 /* SYSCFG SRAM2 key register */ -#define STM32L4_SYSCFG_SWPR2_OFFSET 0x0028 /* SYSCFG SRAM2 write protection register 2 */ - -/* Register Addresses *******************************************************************************/ - -#define STM32L4_SYSCFG_MEMRMP (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_MEMRMP_OFFSET) -#define STM32L4_SYSCFG_CFGR1 (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_CFGR1_OFFSET) -#define STM32L4_SYSCFG_EXTICR(p) (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_EXTICR_OFFSET(p)) -#define STM32L4_SYSCFG_EXTICR1 (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_EXTICR1_OFFSET) -#define STM32L4_SYSCFG_EXTICR2 (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_EXTICR2_OFFSET) -#define STM32L4_SYSCFG_EXTICR3 (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_EXTICR3_OFFSET) -#define STM32L4_SYSCFG_EXTICR4 (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_EXTICR4_OFFSET) -#define STM32L4_SYSCFG_SCSR (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_SCSR_OFFSET) -#define STM32L4_SYSCFG_CFGR2 (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_CFGR2_OFFSET) -#define STM32L4_SYSCFG_SWPR (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_SWPR_OFFSET) -#define STM32L4_SYSCFG_SKR (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_SKR_OFFSET) - -/* Register Bitfield Definitions ********************************************************************/ - -/* SYSCFG memory remap register */ - -#define SYSCFG_MEMRMP_SHIFT (0) /* Bits 2:0 MEM_MODE: Memory mapping selection */ -#define SYSCFG_MEMRMP_MASK (7 << SYSCFG_MEMRMP_SHIFT) -# define SYSCFG_MEMRMP_FLASH (0 << SYSCFG_MEMRMP_SHIFT) /* 000: Main Flash memory mapped at 0x0000 0000 */ -# define SYSCFG_MEMRMP_SYSTEM (1 << SYSCFG_MEMRMP_SHIFT) /* 001: System Flash memory mapped at 0x0000 0000 */ -# define SYSCFG_MEMRMP_FMC (2 << SYSCFG_MEMRMP_SHIFT) /* 010: FSMC Bank1 (NOR/PSRAM 1 and 2) mapped at 0x0000 0000 */ -# define SYSCFG_MEMRMP_SRAM (3 << SYSCFG_MEMRMP_SHIFT) /* 011: SRAM1 (112kB) mapped at 0x0000 0000 */ -# define SYSCFG_MEMRMP_QSPI (6 << SYSCFG_MEMRMP_SHIFT) /* 110: QUADSPI mapped at 0x0000 0000 */ -#define SYSCFG_FBMODE (1 << 8) /* Bit 8: Flash Bank mode selection */ - -/* SYSCFG configuration register 1 */ - -#define SYSCFG_CFGR1_FWDIS (1 << 0) /* Bit 0: Firewall disable */ -#define SYSCFG_CFGR1_BOOSTEN (1 << 8) /* Bit 8: I/O analog switch voltage booster enable (use when vdd is low) */ -#define SYSCFG_CFGR1_I2C_PB6_FMP (1 << 16) /* Bit 16: Fast-mode Plus (Fm+) driving capability activation on PB6 */ -#define SYSCFG_CFGR1_I2C_PB7_FMP (1 << 17) /* Bit 17: Fast-mode Plus (Fm+) driving capability activation on PB7 */ -#define SYSCFG_CFGR1_I2C_PB8_FMP (1 << 18) /* Bit 18: Fast-mode Plus (Fm+) driving capability activation on PB8 */ -#define SYSCFG_CFGR1_I2C_PB9_FMP (1 << 19) /* Bit 19: Fast-mode Plus (Fm+) driving capability activation on PB9 */ -#define SYSCFG_CFGR1_I2C1_FMP (1 << 20) /* Bit 20: I2C1 Fast-mode Plus (Fm+) driving capability activation */ -#define SYSCFG_CFGR1_I2C2_FMP (1 << 21) /* Bit 21: I2C2 Fast-mode Plus (Fm+) driving capability activation */ -#define SYSCFG_CFGR1_I2C3_FMP (1 << 22) /* Bit 22: I2C3 Fast-mode Plus (Fm+) driving capability activation */ -#define SYSCFG_CFGR1_I2C4_FMP (1 << 23) /* Bit 23: I2C4 Fast-mode Plus (Fm+) driving capability activation */ -#define SYSCFG_CFGR1_FPU_IE0 (1 << 26) /* Bit 26: FPU Invalid operation interrupt enable */ -#define SYSCFG_CFGR1_FPU_IE1 (1 << 27) /* Bit 27: FPU Divide-by-zero interrupt enable */ -#define SYSCFG_CFGR1_FPU_IE2 (1 << 28) /* Bit 28: FPU Underflow interrupt enable */ -#define SYSCFG_CFGR1_FPU_IE3 (1 << 29) /* Bit 29: FPU Overflow interrupt enable */ -#define SYSCFG_CFGR1_FPU_IE4 (1 << 30) /* Bit 30: FPU Input denormal interrupt enable */ -#define SYSCFG_CFGR1_FPU_IE5 (1 << 31) /* Bit 31: FPU Inexact interrupt enable */ - -/* SYSCFG external interrupt configuration register 1-4 */ - -#define SYSCFG_EXTICR_PORTA (0) /* 0000: PA[x] pin */ -#define SYSCFG_EXTICR_PORTB (1) /* 0001: PB[x] pin */ -#define SYSCFG_EXTICR_PORTC (2) /* 0010: PC[x] pin */ -#define SYSCFG_EXTICR_PORTD (3) /* 0011: PD[x] pin */ -#define SYSCFG_EXTICR_PORTE (4) /* 0100: PE[x] pin */ -#define SYSCFG_EXTICR_PORTF (5) /* 0101: PF[C] pin */ -#define SYSCFG_EXTICR_PORTG (6) /* 0110: PG[x] pin */ -#define SYSCFG_EXTICR_PORTH (7) /* 0111: PH[x] pin (only on STM32L496xx/4A6xx) */ -#define SYSCFG_EXTICR_PORTI (8) /* 1000: PI[x] pin (only on STM32L496xx/4A6xx) */ - -#define SYSCFG_EXTICR_PORT_MASK (15) -#define SYSCFG_EXTICR_EXTI_SHIFT(g) (((g) & 3) << 2) -#define SYSCFG_EXTICR_EXTI_MASK(g) (SYSCFG_EXTICR_PORT_MASK << (SYSCFG_EXTICR_EXTI_SHIFT(g))) - -#define SYSCFG_EXTICR1_EXTI0_SHIFT (0) /* Bits 0-2: EXTI 0 configuration */ -#define SYSCFG_EXTICR1_EXTI0_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI0_SHIFT) -#define SYSCFG_EXTICR1_EXTI1_SHIFT (4) /* Bits 4-6: EXTI 1 configuration */ -#define SYSCFG_EXTICR1_EXTI1_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI1_SHIFT) -#define SYSCFG_EXTICR1_EXTI2_SHIFT (8) /* Bits 8-10: EXTI 2 configuration */ -#define SYSCFG_EXTICR1_EXTI2_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI2_SHIFT) -#define SYSCFG_EXTICR1_EXTI3_SHIFT (12) /* Bits 12-14: EXTI 3 configuration */ -#define SYSCFG_EXTICR1_EXTI3_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI3_SHIFT) - -#define SYSCFG_EXTICR2_EXTI4_SHIFT (0) /* Bits 0-2: EXTI 4 configuration */ -#define SYSCFG_EXTICR2_EXTI4_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI4_SHIFT) -#define SYSCFG_EXTICR2_EXTI5_SHIFT (4) /* Bits 4-6: EXTI 5 configuration */ -#define SYSCFG_EXTICR2_EXTI5_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI5_SHIFT) -#define SYSCFG_EXTICR2_EXTI6_SHIFT (8) /* Bits 8-10: EXTI 6 configuration */ -#define SYSCFG_EXTICR2_EXTI6_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI6_SHIFT) -#define SYSCFG_EXTICR2_EXTI7_SHIFT (12) /* Bits 12-14: EXTI 7 configuration */ -#define SYSCFG_EXTICR2_EXTI7_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI7_SHIFT) - -#define SYSCFG_EXTICR3_EXTI8_SHIFT (0) /* Bits 0-2: EXTI 8 configuration */ -#define SYSCFG_EXTICR3_EXTI8_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI8_SHIFT) -#define SYSCFG_EXTICR3_EXTI9_SHIFT (4) /* Bits 4-6: EXTI 9 configuration */ -#define SYSCFG_EXTICR3_EXTI9_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI9_SHIFT) -#define SYSCFG_EXTICR3_EXTI10_SHIFT (8) /* Bits 8-10: EXTI 10 configuration */ -#define SYSCFG_EXTICR3_EXTI10_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI10_SHIFT) -#define SYSCFG_EXTICR3_EXTI11_SHIFT (12) /* Bits 12-14: EXTI 11 configuration */ -#define SYSCFG_EXTICR3_EXTI11_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI11_SHIFT) - -#define SYSCFG_EXTICR4_EXTI12_SHIFT (0) /* Bits 0-2: EXTI 12 configuration */ -#define SYSCFG_EXTICR4_EXTI12_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI12_SHIFT) -#define SYSCFG_EXTICR4_EXTI13_SHIFT (4) /* Bits 4-6: EXTI 13 configuration */ -#define SYSCFG_EXTICR4_EXTI13_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI13_SHIFT) -#define SYSCFG_EXTICR4_EXTI14_SHIFT (8) /* Bits 8-10: EXTI 14 configuration */ -#define SYSCFG_EXTICR4_EXTI14_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI14_SHIFT) -#define SYSCFG_EXTICR4_EXTI15_SHIFT (12) /* Bits 12-14: EXTI 15 configuration */ -#define SYSCFG_EXTICR4_EXTI15_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI15_SHIFT) - -/* SYSCFG SRAM2 control and status register */ - -#define SYSCFG_SCSR_SRAM2ER (1 << 0) /* Bit 0: SRAM2 Erase */ -#define SYSCFG_SCSR_SRAM2BSY (1 << 1) /* Bit 1: SRAM2 busy in erase operation */ - -/* SYSCFG configuration register 2 */ - -#define SYSCFG_CFGR2_CLL (1 << 0) /* Bit 0: Cortex-M4 LOCKUP (Hardfault) output enable (TIMx break enable, see refman) */ -#define SYSCFG_CFGR2_SPL (1 << 1) /* Bit 1: SRAM2 parity lock enable (same) */ -#define SYSCFG_CFGR2_PVDL (1 << 2) /* Bit 2: PVD lock enable (same) */ -#define SYSCFG_CFGR2_ECCL (1 << 3) /* Bit 3: ECC lock enable (same) */ -#define SYSCFG_CFGR2_SPF (1 << 8) /* Bit 8: SRAM2 parity error flag */ - -/* SYSCFG SRAM2 write protection register */ -/* There is one bit per SRAM2 page (0 to 31) */ - -/* SYSCFG SRAM2 key register */ - -#define SYSCFG_SKR_SHIFT 0 -#define SYSCFG_SKR_MASK (0xFF << SYSCFG_SKR_SHIFT) - -/* SYSCFG SRAM2 write protection register 2 (only on STM32L496xx/4A6xx) */ -/* There is one bit per SRAM2 page (32 to 63) */ - -#endif /* CONFIG_STM32L4_STM32L476XX || CONFIG_STM32L4_STM32L486XX || CONFIG_STM32L4_STM32L496XX */ #endif /* __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4_SYSCFG_H */ diff --git a/arch/arm/src/stm32l4/chip/stm32l4x3xx_syscfg.h b/arch/arm/src/stm32l4/chip/stm32l4x3xx_syscfg.h new file mode 100644 index 0000000000..446ce1811a --- /dev/null +++ b/arch/arm/src/stm32l4/chip/stm32l4x3xx_syscfg.h @@ -0,0 +1,182 @@ +/**************************************************************************************************** + * arch/arm/src/stm32l4/chip/stm32l4x3xx_syscfg.h + * + * Copyright (C) 2014-2015 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. + * + ****************************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X3XX_SYSCFG_H +#define __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X3XX_SYSCFG_H + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include "chip.h" + +#if defined(CONFIG_STM32L4_STM32L4X3) + +/**************************************************************************************************** + * Pre-processor Definitions + ****************************************************************************************************/ + +/* Register Offsets *********************************************************************************/ + +#define STM32L4_SYSCFG_MEMRMP_OFFSET 0x0000 /* SYSCFG memory remap register */ +#define STM32L4_SYSCFG_CFGR1_OFFSET 0x0004 /* SYSCFG configuration register 1 */ +#define STM32L4_SYSCFG_EXTICR_OFFSET(p) (0x0008 + ((p) & 0x000c)) /* Registers are displaced by 4! */ +#define STM32L4_SYSCFG_EXTICR1_OFFSET 0x0008 /* SYSCFG external interrupt configuration register 1 */ +#define STM32L4_SYSCFG_EXTICR2_OFFSET 0x000c /* SYSCFG external interrupt configuration register 2 */ +#define STM32L4_SYSCFG_EXTICR3_OFFSET 0x0010 /* SYSCFG external interrupt configuration register 3 */ +#define STM32L4_SYSCFG_EXTICR4_OFFSET 0x0014 /* SYSCFG external interrupt configuration register 4 */ +#define STM32L4_SYSCFG_SCSR_OFFSET 0x0018 /* SYSCFG SRAM2 control and status register */ +#define STM32L4_SYSCFG_CFGR2_OFFSET 0x001c /* SYSCFG configuration register 2 */ +#define STM32L4_SYSCFG_SWPR_OFFSET 0x0020 /* SYSCFG SRAM2 write protection register */ +#define STM32L4_SYSCFG_SKR_OFFSET 0x0024 /* SYSCFG SRAM2 key register */ + +/* Register Addresses *******************************************************************************/ + +#define STM32L4_SYSCFG_MEMRMP (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_MEMRMP_OFFSET) +#define STM32L4_SYSCFG_CFGR1 (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_CFGR1_OFFSET) +#define STM32L4_SYSCFG_EXTICR(p) (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_EXTICR_OFFSET(p)) +#define STM32L4_SYSCFG_EXTICR1 (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_EXTICR1_OFFSET) +#define STM32L4_SYSCFG_EXTICR2 (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_EXTICR2_OFFSET) +#define STM32L4_SYSCFG_EXTICR3 (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_EXTICR3_OFFSET) +#define STM32L4_SYSCFG_EXTICR4 (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_EXTICR4_OFFSET) +#define STM32L4_SYSCFG_SCSR (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_SCSR_OFFSET) +#define STM32L4_SYSCFG_CFGR2 (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_CFGR2_OFFSET) +#define STM32L4_SYSCFG_SWPR (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_SWPR_OFFSET) +#define STM32L4_SYSCFG_SKR (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_SKR_OFFSET) + +/* Register Bitfield Definitions ********************************************************************/ + +/* SYSCFG memory remap register */ + +#define SYSCFG_MEMRMP_SHIFT (0) /* Bits 2:0 MEM_MODE: Memory mapping selection */ +#define SYSCFG_MEMRMP_MASK (7 << SYSCFG_MEMRMP_SHIFT) +# define SYSCFG_MEMRMP_FLASH (0 << SYSCFG_MEMRMP_SHIFT) /* 000: Main Flash memory mapped at 0x0000 0000 */ +# define SYSCFG_MEMRMP_SYSTEM (1 << SYSCFG_MEMRMP_SHIFT) /* 001: System Flash memory mapped at 0x0000 0000 */ +# define SYSCFG_MEMRMP_SRAM (3 << SYSCFG_MEMRMP_SHIFT) /* 011: SRAM1 (112kB) mapped at 0x0000 0000 */ +# define SYSCFG_MEMRMP_QSPI (6 << SYSCFG_MEMRMP_SHIFT) /* 110: QUADSPI mapped at 0x0000 0000 */ + +/* SYSCFG configuration register 1 */ + +#define SYSCFG_CFGR1_FWDIS (1 << 0) /* Bit 0: Firewall disable */ +#define SYSCFG_CFGR1_BOOSTEN (1 << 8) /* Bit 8: I/O analog switch voltage booster enable (use when vdd is low) */ +#define SYSCFG_CFGR1_I2C_PB6_FMP (1 << 16) /* Bit 16: Fast-mode Plus (Fm+) driving capability activation on PB6 */ +#define SYSCFG_CFGR1_I2C_PB7_FMP (1 << 17) /* Bit 17: Fast-mode Plus (Fm+) driving capability activation on PB7 */ +#define SYSCFG_CFGR1_I2C_PB8_FMP (1 << 18) /* Bit 18: Fast-mode Plus (Fm+) driving capability activation on PB8 */ +#define SYSCFG_CFGR1_I2C_PB9_FMP (1 << 19) /* Bit 19: Fast-mode Plus (Fm+) driving capability activation on PB9 */ +#define SYSCFG_CFGR1_I2C1_FMP (1 << 20) /* Bit 20: I2C1 Fast-mode Plus (Fm+) driving capability activation */ +#define SYSCFG_CFGR1_I2C2_FMP (1 << 21) /* Bit 21: I2C2 Fast-mode Plus (Fm+) driving capability activation */ +#define SYSCFG_CFGR1_I2C3_FMP (1 << 22) /* Bit 22: I2C3 Fast-mode Plus (Fm+) driving capability activation */ +#define SYSCFG_CFGR1_I2C4_FMP (1 << 23) /* Bit 23: I2C4 Fast-mode Plus (Fm+) driving capability activation */ +#define SYSCFG_CFGR1_FPU_IE0 (1 << 26) /* Bit 26: FPU Invalid operation interrupt enable */ +#define SYSCFG_CFGR1_FPU_IE1 (1 << 27) /* Bit 27: FPU Divide-by-zero interrupt enable */ +#define SYSCFG_CFGR1_FPU_IE2 (1 << 28) /* Bit 28: FPU Underflow interrupt enable */ +#define SYSCFG_CFGR1_FPU_IE3 (1 << 29) /* Bit 29: FPU Overflow interrupt enable */ +#define SYSCFG_CFGR1_FPU_IE4 (1 << 30) /* Bit 30: FPU Input denormal interrupt enable */ +#define SYSCFG_CFGR1_FPU_IE5 (1 << 31) /* Bit 31: FPU Inexact interrupt enable */ + +/* SYSCFG external interrupt configuration register 1-4 */ + +#define SYSCFG_EXTICR_PORTA (0) /* 0000: PA[x] pin */ +#define SYSCFG_EXTICR_PORTB (1) /* 0001: PB[x] pin */ +#define SYSCFG_EXTICR_PORTC (2) /* 0010: PC[x] pin */ +#define SYSCFG_EXTICR_PORTD (3) /* 0011: PD[x] pin */ +#define SYSCFG_EXTICR_PORTE (4) /* 0100: PE[x] pin */ +/* No PORTF or PORTG on these chips */ +#define SYSCFG_EXTICR_PORTH (7) /* 0111: PH[x] pin */ + +#define SYSCFG_EXTICR_PORT_MASK (7) +#define SYSCFG_EXTICR_EXTI_SHIFT(g) (((g) & 3) << 2) +#define SYSCFG_EXTICR_EXTI_MASK(g) (SYSCFG_EXTICR_PORT_MASK << (SYSCFG_EXTICR_EXTI_SHIFT(g))) + +#define SYSCFG_EXTICR1_EXTI0_SHIFT (0) /* Bits 0-2: EXTI 0 configuration */ +#define SYSCFG_EXTICR1_EXTI0_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI0_SHIFT) +#define SYSCFG_EXTICR1_EXTI1_SHIFT (4) /* Bits 4-6: EXTI 1 configuration */ +#define SYSCFG_EXTICR1_EXTI1_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI1_SHIFT) +#define SYSCFG_EXTICR1_EXTI2_SHIFT (8) /* Bits 8-10: EXTI 2 configuration */ +#define SYSCFG_EXTICR1_EXTI2_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI2_SHIFT) +#define SYSCFG_EXTICR1_EXTI3_SHIFT (12) /* Bits 12-14: EXTI 3 configuration */ +#define SYSCFG_EXTICR1_EXTI3_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI3_SHIFT) + +#define SYSCFG_EXTICR2_EXTI4_SHIFT (0) /* Bits 0-2: EXTI 4 configuration */ +#define SYSCFG_EXTICR2_EXTI4_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI4_SHIFT) +#define SYSCFG_EXTICR2_EXTI5_SHIFT (4) /* Bits 4-6: EXTI 5 configuration */ +#define SYSCFG_EXTICR2_EXTI5_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI5_SHIFT) +#define SYSCFG_EXTICR2_EXTI6_SHIFT (8) /* Bits 8-10: EXTI 6 configuration */ +#define SYSCFG_EXTICR2_EXTI6_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI6_SHIFT) +#define SYSCFG_EXTICR2_EXTI7_SHIFT (12) /* Bits 12-14: EXTI 7 configuration */ +#define SYSCFG_EXTICR2_EXTI7_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI7_SHIFT) + +#define SYSCFG_EXTICR3_EXTI8_SHIFT (0) /* Bits 0-2: EXTI 8 configuration */ +#define SYSCFG_EXTICR3_EXTI8_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI8_SHIFT) +#define SYSCFG_EXTICR3_EXTI9_SHIFT (4) /* Bits 4-6: EXTI 9 configuration */ +#define SYSCFG_EXTICR3_EXTI9_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI9_SHIFT) +#define SYSCFG_EXTICR3_EXTI10_SHIFT (8) /* Bits 8-10: EXTI 10 configuration */ +#define SYSCFG_EXTICR3_EXTI10_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI10_SHIFT) +#define SYSCFG_EXTICR3_EXTI11_SHIFT (12) /* Bits 12-14: EXTI 11 configuration */ +#define SYSCFG_EXTICR3_EXTI11_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI11_SHIFT) + +#define SYSCFG_EXTICR4_EXTI12_SHIFT (0) /* Bits 0-2: EXTI 12 configuration */ +#define SYSCFG_EXTICR4_EXTI12_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI12_SHIFT) +#define SYSCFG_EXTICR4_EXTI13_SHIFT (4) /* Bits 4-6: EXTI 13 configuration */ +#define SYSCFG_EXTICR4_EXTI13_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI13_SHIFT) +#define SYSCFG_EXTICR4_EXTI14_SHIFT (8) /* Bits 8-10: EXTI 14 configuration */ +#define SYSCFG_EXTICR4_EXTI14_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI14_SHIFT) +#define SYSCFG_EXTICR4_EXTI15_SHIFT (12) /* Bits 12-14: EXTI 15 configuration */ +#define SYSCFG_EXTICR4_EXTI15_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI15_SHIFT) + +/* SYSCFG SRAM2 control and status register */ + +#define SYSCFG_SCSR_SRAM2ER (1 << 0) /* Bit 0: SRAM2 Erase */ +#define SYSCFG_SCSR_SRAM2BSY (1 << 1) /* Bit 1: SRAM2 busy in erase operation */ + +/* SYSCFG configuration register 2 */ + +#define SYSCFG_CFGR2_CLL (1 << 0) /* Bit 0: Cortex-M4 LOCKUP (Hardfault) output enable (TIMx break enable, see refman) */ +#define SYSCFG_CFGR2_SPL (1 << 1) /* Bit 1: SRAM2 parity lock enable (same) */ +#define SYSCFG_CFGR2_PVDL (1 << 2) /* Bit 2: PVD lock enable (same) */ +#define SYSCFG_CFGR2_ECCL (1 << 3) /* Bit 3: ECC lock enable (same) */ +#define SYSCFG_CFGR2_SPF (1 << 8) /* Bit 8: SRAM2 parity error flag */ + +/* SYSCFG SRAM2 write protection register */ +/* There is one bit per SRAM2 page (0 to 31) */ + +/* SYSCFG SRAM2 key register */ + +#define SYSCFG_SKR_SHIFT 0 +#define SYSCFG_SKR_MASK (0xFF << SYSCFG_SKR_SHIFT) + +#endif /* CONFIG_STM32L4_STM32L4X3 */ +#endif /* __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X3XX_SYSCFG_H */ diff --git a/arch/arm/src/stm32l4/chip/stm32l4x6xx_syscfg.h b/arch/arm/src/stm32l4/chip/stm32l4x6xx_syscfg.h new file mode 100644 index 0000000000..e7446cfb29 --- /dev/null +++ b/arch/arm/src/stm32l4/chip/stm32l4x6xx_syscfg.h @@ -0,0 +1,191 @@ +/**************************************************************************************************** + * arch/arm/src/stm32l4/chip/stm32l4x6xx_syscfg.h + * + * Copyright (C) 2014-2015 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. + * + ****************************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X6XX_SYSCFG_H +#define __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X6XX_SYSCFG_H + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include "chip.h" + +#if defined(CONFIG_STM32L4_STM32L4X6) + +/**************************************************************************************************** + * Pre-processor Definitions + ****************************************************************************************************/ + +/* Register Offsets *********************************************************************************/ + +#define STM32L4_SYSCFG_MEMRMP_OFFSET 0x0000 /* SYSCFG memory remap register */ +#define STM32L4_SYSCFG_CFGR1_OFFSET 0x0004 /* SYSCFG configuration register 1 */ +#define STM32L4_SYSCFG_EXTICR_OFFSET(p) (0x0008 + ((p) & 0x000c)) /* Registers are displaced by 4! */ +#define STM32L4_SYSCFG_EXTICR1_OFFSET 0x0008 /* SYSCFG external interrupt configuration register 1 */ +#define STM32L4_SYSCFG_EXTICR2_OFFSET 0x000c /* SYSCFG external interrupt configuration register 2 */ +#define STM32L4_SYSCFG_EXTICR3_OFFSET 0x0010 /* SYSCFG external interrupt configuration register 3 */ +#define STM32L4_SYSCFG_EXTICR4_OFFSET 0x0014 /* SYSCFG external interrupt configuration register 4 */ +#define STM32L4_SYSCFG_SCSR_OFFSET 0x0018 /* SYSCFG SRAM2 control and status register */ +#define STM32L4_SYSCFG_CFGR2_OFFSET 0x001c /* SYSCFG configuration register 2 */ +#define STM32L4_SYSCFG_SWPR_OFFSET 0x0020 /* SYSCFG SRAM2 write protection register */ +#define STM32L4_SYSCFG_SKR_OFFSET 0x0024 /* SYSCFG SRAM2 key register */ +#define STM32L4_SYSCFG_SWPR2_OFFSET 0x0028 /* SYSCFG SRAM2 write protection register 2 */ + +/* Register Addresses *******************************************************************************/ + +#define STM32L4_SYSCFG_MEMRMP (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_MEMRMP_OFFSET) +#define STM32L4_SYSCFG_CFGR1 (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_CFGR1_OFFSET) +#define STM32L4_SYSCFG_EXTICR(p) (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_EXTICR_OFFSET(p)) +#define STM32L4_SYSCFG_EXTICR1 (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_EXTICR1_OFFSET) +#define STM32L4_SYSCFG_EXTICR2 (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_EXTICR2_OFFSET) +#define STM32L4_SYSCFG_EXTICR3 (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_EXTICR3_OFFSET) +#define STM32L4_SYSCFG_EXTICR4 (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_EXTICR4_OFFSET) +#define STM32L4_SYSCFG_SCSR (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_SCSR_OFFSET) +#define STM32L4_SYSCFG_CFGR2 (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_CFGR2_OFFSET) +#define STM32L4_SYSCFG_SWPR (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_SWPR_OFFSET) +#define STM32L4_SYSCFG_SKR (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_SKR_OFFSET) +#define STM32L4_SYSCFG_SWPR2 (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_SWPR2_OFFSET) + +/* Register Bitfield Definitions ********************************************************************/ + +/* SYSCFG memory remap register */ + +#define SYSCFG_MEMRMP_SHIFT (0) /* Bits 2:0 MEM_MODE: Memory mapping selection */ +#define SYSCFG_MEMRMP_MASK (7 << SYSCFG_MEMRMP_SHIFT) +# define SYSCFG_MEMRMP_FLASH (0 << SYSCFG_MEMRMP_SHIFT) /* 000: Main Flash memory mapped at 0x0000 0000 */ +# define SYSCFG_MEMRMP_SYSTEM (1 << SYSCFG_MEMRMP_SHIFT) /* 001: System Flash memory mapped at 0x0000 0000 */ +# define SYSCFG_MEMRMP_FMC (2 << SYSCFG_MEMRMP_SHIFT) /* 010: FSMC Bank1 (NOR/PSRAM 1 and 2) mapped at 0x0000 0000 */ +# define SYSCFG_MEMRMP_SRAM (3 << SYSCFG_MEMRMP_SHIFT) /* 011: SRAM1 (112kB) mapped at 0x0000 0000 */ +# define SYSCFG_MEMRMP_QSPI (6 << SYSCFG_MEMRMP_SHIFT) /* 110: QUADSPI mapped at 0x0000 0000 */ +#define SYSCFG_FBMODE (1 << 8) /* Bit 8: Flash Bank mode selection */ + +/* SYSCFG configuration register 1 */ + +#define SYSCFG_CFGR1_FWDIS (1 << 0) /* Bit 0: Firewall disable */ +#define SYSCFG_CFGR1_BOOSTEN (1 << 8) /* Bit 8: I/O analog switch voltage booster enable (use when vdd is low) */ +#define SYSCFG_CFGR1_I2C_PB6_FMP (1 << 16) /* Bit 16: Fast-mode Plus (Fm+) driving capability activation on PB6 */ +#define SYSCFG_CFGR1_I2C_PB7_FMP (1 << 17) /* Bit 17: Fast-mode Plus (Fm+) driving capability activation on PB7 */ +#define SYSCFG_CFGR1_I2C_PB8_FMP (1 << 18) /* Bit 18: Fast-mode Plus (Fm+) driving capability activation on PB8 */ +#define SYSCFG_CFGR1_I2C_PB9_FMP (1 << 19) /* Bit 19: Fast-mode Plus (Fm+) driving capability activation on PB9 */ +#define SYSCFG_CFGR1_I2C1_FMP (1 << 20) /* Bit 20: I2C1 Fast-mode Plus (Fm+) driving capability activation */ +#define SYSCFG_CFGR1_I2C2_FMP (1 << 21) /* Bit 21: I2C2 Fast-mode Plus (Fm+) driving capability activation */ +#define SYSCFG_CFGR1_I2C3_FMP (1 << 22) /* Bit 22: I2C3 Fast-mode Plus (Fm+) driving capability activation */ +#define SYSCFG_CFGR1_I2C4_FMP (1 << 23) /* Bit 23: I2C4 Fast-mode Plus (Fm+) driving capability activation */ +#define SYSCFG_CFGR1_FPU_IE0 (1 << 26) /* Bit 26: FPU Invalid operation interrupt enable */ +#define SYSCFG_CFGR1_FPU_IE1 (1 << 27) /* Bit 27: FPU Divide-by-zero interrupt enable */ +#define SYSCFG_CFGR1_FPU_IE2 (1 << 28) /* Bit 28: FPU Underflow interrupt enable */ +#define SYSCFG_CFGR1_FPU_IE3 (1 << 29) /* Bit 29: FPU Overflow interrupt enable */ +#define SYSCFG_CFGR1_FPU_IE4 (1 << 30) /* Bit 30: FPU Input denormal interrupt enable */ +#define SYSCFG_CFGR1_FPU_IE5 (1 << 31) /* Bit 31: FPU Inexact interrupt enable */ + +/* SYSCFG external interrupt configuration register 1-4 */ + +#define SYSCFG_EXTICR_PORTA (0) /* 0000: PA[x] pin */ +#define SYSCFG_EXTICR_PORTB (1) /* 0001: PB[x] pin */ +#define SYSCFG_EXTICR_PORTC (2) /* 0010: PC[x] pin */ +#define SYSCFG_EXTICR_PORTD (3) /* 0011: PD[x] pin */ +#define SYSCFG_EXTICR_PORTE (4) /* 0100: PE[x] pin */ +#define SYSCFG_EXTICR_PORTF (5) /* 0101: PF[C] pin */ +#define SYSCFG_EXTICR_PORTG (6) /* 0110: PG[x] pin */ +#define SYSCFG_EXTICR_PORTH (7) /* 0111: PH[x] pin (only on STM32L496xx/4A6xx) */ +#define SYSCFG_EXTICR_PORTI (8) /* 1000: PI[x] pin (only on STM32L496xx/4A6xx) */ + +#define SYSCFG_EXTICR_PORT_MASK (15) +#define SYSCFG_EXTICR_EXTI_SHIFT(g) (((g) & 3) << 2) +#define SYSCFG_EXTICR_EXTI_MASK(g) (SYSCFG_EXTICR_PORT_MASK << (SYSCFG_EXTICR_EXTI_SHIFT(g))) + +#define SYSCFG_EXTICR1_EXTI0_SHIFT (0) /* Bits 0-2: EXTI 0 configuration */ +#define SYSCFG_EXTICR1_EXTI0_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI0_SHIFT) +#define SYSCFG_EXTICR1_EXTI1_SHIFT (4) /* Bits 4-6: EXTI 1 configuration */ +#define SYSCFG_EXTICR1_EXTI1_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI1_SHIFT) +#define SYSCFG_EXTICR1_EXTI2_SHIFT (8) /* Bits 8-10: EXTI 2 configuration */ +#define SYSCFG_EXTICR1_EXTI2_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI2_SHIFT) +#define SYSCFG_EXTICR1_EXTI3_SHIFT (12) /* Bits 12-14: EXTI 3 configuration */ +#define SYSCFG_EXTICR1_EXTI3_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI3_SHIFT) + +#define SYSCFG_EXTICR2_EXTI4_SHIFT (0) /* Bits 0-2: EXTI 4 configuration */ +#define SYSCFG_EXTICR2_EXTI4_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI4_SHIFT) +#define SYSCFG_EXTICR2_EXTI5_SHIFT (4) /* Bits 4-6: EXTI 5 configuration */ +#define SYSCFG_EXTICR2_EXTI5_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI5_SHIFT) +#define SYSCFG_EXTICR2_EXTI6_SHIFT (8) /* Bits 8-10: EXTI 6 configuration */ +#define SYSCFG_EXTICR2_EXTI6_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI6_SHIFT) +#define SYSCFG_EXTICR2_EXTI7_SHIFT (12) /* Bits 12-14: EXTI 7 configuration */ +#define SYSCFG_EXTICR2_EXTI7_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI7_SHIFT) + +#define SYSCFG_EXTICR3_EXTI8_SHIFT (0) /* Bits 0-2: EXTI 8 configuration */ +#define SYSCFG_EXTICR3_EXTI8_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI8_SHIFT) +#define SYSCFG_EXTICR3_EXTI9_SHIFT (4) /* Bits 4-6: EXTI 9 configuration */ +#define SYSCFG_EXTICR3_EXTI9_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI9_SHIFT) +#define SYSCFG_EXTICR3_EXTI10_SHIFT (8) /* Bits 8-10: EXTI 10 configuration */ +#define SYSCFG_EXTICR3_EXTI10_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI10_SHIFT) +#define SYSCFG_EXTICR3_EXTI11_SHIFT (12) /* Bits 12-14: EXTI 11 configuration */ +#define SYSCFG_EXTICR3_EXTI11_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI11_SHIFT) + +#define SYSCFG_EXTICR4_EXTI12_SHIFT (0) /* Bits 0-2: EXTI 12 configuration */ +#define SYSCFG_EXTICR4_EXTI12_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI12_SHIFT) +#define SYSCFG_EXTICR4_EXTI13_SHIFT (4) /* Bits 4-6: EXTI 13 configuration */ +#define SYSCFG_EXTICR4_EXTI13_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI13_SHIFT) +#define SYSCFG_EXTICR4_EXTI14_SHIFT (8) /* Bits 8-10: EXTI 14 configuration */ +#define SYSCFG_EXTICR4_EXTI14_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI14_SHIFT) +#define SYSCFG_EXTICR4_EXTI15_SHIFT (12) /* Bits 12-14: EXTI 15 configuration */ +#define SYSCFG_EXTICR4_EXTI15_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI15_SHIFT) + +/* SYSCFG SRAM2 control and status register */ + +#define SYSCFG_SCSR_SRAM2ER (1 << 0) /* Bit 0: SRAM2 Erase */ +#define SYSCFG_SCSR_SRAM2BSY (1 << 1) /* Bit 1: SRAM2 busy in erase operation */ + +/* SYSCFG configuration register 2 */ + +#define SYSCFG_CFGR2_CLL (1 << 0) /* Bit 0: Cortex-M4 LOCKUP (Hardfault) output enable (TIMx break enable, see refman) */ +#define SYSCFG_CFGR2_SPL (1 << 1) /* Bit 1: SRAM2 parity lock enable (same) */ +#define SYSCFG_CFGR2_PVDL (1 << 2) /* Bit 2: PVD lock enable (same) */ +#define SYSCFG_CFGR2_ECCL (1 << 3) /* Bit 3: ECC lock enable (same) */ +#define SYSCFG_CFGR2_SPF (1 << 8) /* Bit 8: SRAM2 parity error flag */ + +/* SYSCFG SRAM2 write protection register */ +/* There is one bit per SRAM2 page (0 to 31) */ + +/* SYSCFG SRAM2 key register */ + +#define SYSCFG_SKR_SHIFT 0 +#define SYSCFG_SKR_MASK (0xFF << SYSCFG_SKR_SHIFT) + +/* SYSCFG SRAM2 write protection register 2 (only on STM32L496xx/4A6xx) */ +/* There is one bit per SRAM2 page (32 to 63) */ + +#endif /* CONFIG_STM32L4_STM32L4X6 */ +#endif /* __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X6XX_SYSCFG_H */ -- GitLab From a5e972422406ebc6f96ed9fd8ce3c4e31f119f79 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Fri, 5 May 2017 10:15:09 +0300 Subject: [PATCH 716/990] STM32L4: firewall for stm32l4x3xx Not tested for any product family, but now it at least compiles. L496 devices can have one bit wider Volatile Data Segment. --- arch/arm/src/stm32l4/Make.defs | 4 + .../src/stm32l4/chip/stm32l4x3xx_firewall.h | 103 ++++++++++++++++++ .../src/stm32l4/chip/stm32l4x6xx_firewall.h | 8 ++ arch/arm/src/stm32l4/stm32l4_firewall.c | 4 + arch/arm/src/stm32l4/stm32l4_firewall.h | 11 +- 5 files changed, 125 insertions(+), 5 deletions(-) create mode 100644 arch/arm/src/stm32l4/chip/stm32l4x3xx_firewall.h diff --git a/arch/arm/src/stm32l4/Make.defs b/arch/arm/src/stm32l4/Make.defs index 49ee972539..417d7c170d 100644 --- a/arch/arm/src/stm32l4/Make.defs +++ b/arch/arm/src/stm32l4/Make.defs @@ -212,3 +212,7 @@ ifeq ($(CONFIG_STM32L4_CAN),y) CHIP_CSRCS += stm32l4_can.c endif +ifeq ($(CONFIG_STM32L4_FIREWALL),y) +CHIP_CSRCS += stm32l4_firewall.c +endif + diff --git a/arch/arm/src/stm32l4/chip/stm32l4x3xx_firewall.h b/arch/arm/src/stm32l4/chip/stm32l4x3xx_firewall.h new file mode 100644 index 0000000000..4e78b60102 --- /dev/null +++ b/arch/arm/src/stm32l4/chip/stm32l4x3xx_firewall.h @@ -0,0 +1,103 @@ +/************************************************************************************ + * arch/arm/src/stm32l4/chip/stm32l4x3xx_firewall.h + * + * Copyright (C) 2016 Sebastien Lorquet. All rights reserved. + * Author: Sebastien Lorquet + * + * 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 __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X3XX_FIREWALL_H +#define __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X3XX_FIREWALL_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include + +#include "chip.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Register Offsets *****************************************************************/ + +#define STM32L4_FIREWALL_CSSA_OFFSET 0x0000 +#define STM32L4_FIREWALL_CSL_OFFSET 0x0004 +#define STM32L4_FIREWALL_NVDSSA_OFFSET 0x0008 +#define STM32L4_FIREWALL_NVDSL_OFFSET 0x000C +#define STM32L4_FIREWALL_VDSSA_OFFSET 0x0010 +#define STM32L4_FIREWALL_VDSL_OFFSET 0x0014 +#define STM32L4_FIREWALL_CR_OFFSET 0x0020 + +/* Register Addresses ***************************************************************/ + +#define STM32L4_FIREWALL_CSSA (STM32L4_FIREWALL_BASE+STM32L4_FIREWALL_CSSA_OFFSET) +#define STM32L4_FIREWALL_CSL (STM32L4_FIREWALL_BASE+STM32L4_FIREWALL_CSL_OFFSET) +#define STM32L4_FIREWALL_NVDSSA (STM32L4_FIREWALL_BASE+STM32L4_FIREWALL_NVDSSA_OFFSET) +#define STM32L4_FIREWALL_NVDSL (STM32L4_FIREWALL_BASE+STM32L4_FIREWALL_NVDSL_OFFSET) +#define STM32L4_FIREWALL_VDSSA (STM32L4_FIREWALL_BASE+STM32L4_FIREWALL_VDSSA_OFFSET) +#define STM32L4_FIREWALL_VDSL (STM32L4_FIREWALL_BASE+STM32L4_FIREWALL_VDSL_OFFSET) +#define STM32L4_FIREWALL_CR (STM32L4_FIREWALL_BASE+STM32L4_FIREWALL_CR_OFFSET) + +/* Register Bitfield Definitions ****************************************************/ + +/* Code Segment Start Address */ +#define FIREWALL_CSSADD_SHIFT 8 +#define FIREWALL_CSSADD_MASK (0xFFFF << FIREWALL_CSSADD_SHIFT) + +/* Code Segment Length */ +#define FIREWALL_CSSLENG_SHIFT 8 +#define FIREWALL_CSSLENG_MASK (0x3FFF << FIREWALL_CSSLENG_SHIFT) + +/* Non-volatile Data Segment Start Address */ +#define FIREWALL_NVDSADD_SHIFT 8 +#define FIREWALL_NVDSADD_MASK (0xFFFF << FIREWALL_NVDSADD_SHIFT) + +/* Non-volatile Data Segment Length */ +#define FIREWALL_NVDSLENG_SHIFT 8 +#define FIREWALL_NVDSLENG_MASK (0x3FFF << FIREWALL_NVDSLENG_SHIFT) + +/* Volatile Data Segment Start Address */ +#define FIREWALL_VDSADD_SHIFT 6 +#define FIREWALL_VDSADD_MASK (0x07FF << FIREWALL_VDSADD_SHIFT) + +/* Volatile Data Segment Length */ +#define FIREWALL_VDSLENG_SHIFT 6 +#define FIREWALL_VDSLENG_MASK (0x07FF << FIREWALL_VDSLENG_SHIFT) + +/* Configuration Register */ +#define FIREWALL_CR_FPA (1 << 0) /* Bit 0: Firewall prearm */ +#define FIREWALL_CR_VDS (1 << 1) /* Bit 1: Volatile data shared */ +#define FIREWALL_CR_VDE (1 << 2) /* Bit 2: Volatile data execution */ + +#endif /* __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X3XX_FIREWALL_H */ diff --git a/arch/arm/src/stm32l4/chip/stm32l4x6xx_firewall.h b/arch/arm/src/stm32l4/chip/stm32l4x6xx_firewall.h index e1531de5d0..55826d73f7 100644 --- a/arch/arm/src/stm32l4/chip/stm32l4x6xx_firewall.h +++ b/arch/arm/src/stm32l4/chip/stm32l4x6xx_firewall.h @@ -89,11 +89,19 @@ /* Volatile Data Segment Start Address */ #define FIREWALL_VDSADD_SHIFT 6 +#if defined(CONFIG_STM32L4_STM32L496XX) +#define FIREWALL_VDSADD_MASK (0x0FFF << FIREWALL_VDSADD_SHIFT) +#else #define FIREWALL_VDSADD_MASK (0x07FF << FIREWALL_VDSADD_SHIFT) +#endif /* Volatile Data Segment Length */ #define FIREWALL_VDSLENG_SHIFT 6 +#if defined(CONFIG_STM32L4_STM32L496XX) +#define FIREWALL_VDSLENG_MASK (0x0FFF << FIREWALL_VDSLENG_SHIFT) +#else #define FIREWALL_VDSLENG_MASK (0x07FF << FIREWALL_VDSLENG_SHIFT) +#endif /* Configuration Register */ #define FIREWALL_CR_FPA (1 << 0) /* Bit 0: Firewall prearm */ diff --git a/arch/arm/src/stm32l4/stm32l4_firewall.c b/arch/arm/src/stm32l4/stm32l4_firewall.c index 46cc3ff62d..27f948e43f 100644 --- a/arch/arm/src/stm32l4/stm32l4_firewall.c +++ b/arch/arm/src/stm32l4/stm32l4_firewall.c @@ -38,6 +38,10 @@ ****************************************************************************/ #include +#include + +#include "up_arch.h" +#include "chip/stm32l4_syscfg.h" #include "stm32l4_firewall.h" diff --git a/arch/arm/src/stm32l4/stm32l4_firewall.h b/arch/arm/src/stm32l4/stm32l4_firewall.h index ec667fe5a7..7b4a4dd0c4 100644 --- a/arch/arm/src/stm32l4/stm32l4_firewall.h +++ b/arch/arm/src/stm32l4/stm32l4_firewall.h @@ -47,9 +47,10 @@ /* Include the correct firewall register definitions for this STM32L4 family */ -#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX) || \ - defined(CONFIG_STM32L4_STM32L496XX) +#if defined(CONFIG_STM32L4_STM32L4X6) # include "chip/stm32l4x6xx_firewall.h" +#elif defined(CONFIG_STM32L4_STM32L4X3) +# include "chip/stm32l4x3xx_firewall.h" #else # error "Unsupported STM32L4 chip" #endif @@ -60,11 +61,11 @@ struct stm32l4_firewall_t { - uintptr_t *codestart; + uintptr_t codestart; size_t codelen; - uintptr_t *nvdatastart; + uintptr_t nvdatastart; size_t nvdatalen; - uintptr_t *datastart; + uintptr_t datastart; size_t datalen; uint8_t datashared:1; uint8_t dataexec :1; -- GitLab From 71accfc57b71a4c2a8516b486f20752a1329383a Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Fri, 5 May 2017 11:03:49 +0300 Subject: [PATCH 717/990] STM32L4: add more chips to Kconfig (This also removes DPFPU/DTCM/ITCM features again, fixing a recent git history hickup.) --- arch/arm/src/stm32l4/Kconfig | 71 +++++++++++++++++++++++++++++++++--- 1 file changed, 65 insertions(+), 6 deletions(-) diff --git a/arch/arm/src/stm32l4/Kconfig b/arch/arm/src/stm32l4/Kconfig index 74b3f9ae70..76d2dae613 100644 --- a/arch/arm/src/stm32l4/Kconfig +++ b/arch/arm/src/stm32l4/Kconfig @@ -36,6 +36,70 @@ config ARCH_CHIP_STM32L442KC ---help--- STM32 L4 Cortex M4, AES, 256 Kb FLASH, 64 Kb SRAM +config ARCH_CHIP_STM32L433CB + bool "STM32L433CB" + select STM32L4_STM32L433XX + select STM32L4_FLASH_CONFIG_B + select STM32L4_IO_CONFIG_C + ---help--- + STM32 L4 Cortex M4, 128 Kb FLASH, 64 Kb SRAM + +config ARCH_CHIP_STM32L433CC + bool "STM32L433CC" + select STM32L4_STM32L433XX + select STM32L4_FLASH_CONFIG_C + select STM32L4_IO_CONFIG_C + ---help--- + STM32 L4 Cortex M4, 256 Kb FLASH, 64 Kb SRAM + +config ARCH_CHIP_STM32L433RB + bool "STM32L433RB" + select STM32L4_STM32L433XX + select STM32L4_FLASH_CONFIG_B + select STM32L4_IO_CONFIG_R + ---help--- + STM32 L4 Cortex M4, 128 Kb FLASH, 64 Kb SRAM + +config ARCH_CHIP_STM32L433RC + bool "STM32L433RC" + select STM32L4_STM32L433XX + select STM32L4_FLASH_CONFIG_C + select STM32L4_IO_CONFIG_R + ---help--- + STM32 L4 Cortex M4, 256 Kb FLASH, 64 Kb SRAM + +config ARCH_CHIP_STM32L433VC + bool "STM32L433VC" + select STM32L4_STM32L433XX + select STM32L4_FLASH_CONFIG_C + select STM32L4_IO_CONFIG_V + ---help--- + STM32 L4 Cortex M4, 256 Kb FLASH, 64 Kb SRAM + +config ARCH_CHIP_STM32L443CC + bool "STM32L443CC" + select STM32L4_STM32L443XX + select STM32L4_FLASH_CONFIG_C + select STM32L4_IO_CONFIG_C + ---help--- + STM32 L4 Cortex M4, AES, 256 Kb FLASH, 64 Kb SRAM + +config ARCH_CHIP_STM32L443RC + bool "STM32L443RC" + select STM32L4_STM32L443XX + select STM32L4_FLASH_CONFIG_C + select STM32L4_IO_CONFIG_R + ---help--- + STM32 L4 Cortex M4, AES, 256 Kb FLASH, 64 Kb SRAM + +config ARCH_CHIP_STM32L443VC + bool "STM32L443VC" + select STM32L4_STM32L443XX + select STM32L4_FLASH_CONFIG_C + select STM32L4_IO_CONFIG_V + ---help--- + STM32 L4 Cortex M4, AES, 256 Kb FLASH, 64 Kb SRAM + config ARCH_CHIP_STM32L451CC bool "STM32L451CC" select STM32L4_STM32L451XX @@ -221,9 +285,6 @@ config STM32L4_STM32L4X3 bool default n select ARCH_HAVE_FPU - select ARCH_HAVE_DPFPU # REVISIT - select ARMV7M_HAVE_ITCM - select ARMV7M_HAVE_DTCM select STM32L4_HAVE_USART1 select STM32L4_HAVE_USART2 select STM32L4_HAVE_USART3 if !(STM32L4_L432XX || STM32L4_L442XX) @@ -236,6 +297,7 @@ config STM32L4_STM32L4X3 config STM32L4_STM32L4X5 bool default n + select ARCH_HAVE_FPU select STM32L4_HAVE_USART1 select STM32L4_HAVE_USART2 select STM32L4_HAVE_USART3 @@ -264,9 +326,6 @@ config STM32L4_STM32L4X6 bool default n select ARCH_HAVE_FPU - select ARCH_HAVE_DPFPU # REVISIT - select ARMV7M_HAVE_ITCM - select ARMV7M_HAVE_DTCM select STM32L4_HAVE_USART1 select STM32L4_HAVE_USART2 select STM32L4_HAVE_USART3 -- GitLab From a7b452bc5bce39112c275f4faa8956b79a149ac6 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Fri, 5 May 2017 15:32:07 +0300 Subject: [PATCH 718/990] configs/nucleo-l496zg: Kconfig was copied from nucleo-144 Removed as most options have not been tested. --- configs/nucleo-l496zg/Kconfig | 219 +--------------------------------- 1 file changed, 2 insertions(+), 217 deletions(-) diff --git a/configs/nucleo-l496zg/Kconfig b/configs/nucleo-l496zg/Kconfig index af61775c0b..713c28241c 100644 --- a/configs/nucleo-l496zg/Kconfig +++ b/configs/nucleo-l496zg/Kconfig @@ -3,221 +3,6 @@ # see the file kconfig-language.txt in the NuttX tools repository. # -if ARCH_BOARD_NUCLEO_144 +if ARCH_BOARD_NUCLEO_L496ZG -choice - prompt "Select Console wiring." - default NUCLEO_ARDUINO - ---help--- - Select where you will connect the console. - - Virtual COM Port: - - Advantage: Use the ST-Link as a console. No Extra wiring - neded. - - Disdvantage: Not the best choice for initial bring up. - - ARDUINO Connector: - - Advantage: You have a shield so it is - easy. - - Disdvantage: You loose the use of the - other functions on PC6, PC7 - - STM32F7 - ARDUIONO FUNCTION GPIO - -- ----- --------- ---- - DO RX USART6_RX PG9 - D1 TX USART6_TX PG14 - -- ----- --------- --- - - OR - - Morpho Connector: - - STM32F7 - MORPHO FUNCTION GPIO - -------- --------- ----- - CN12-64 USART8_RX PE0 - CN11-61 USART8_TX PE1 - -------- --------- ----- - -config NUCLEO_CONSOLE_ARDUINO - bool "ARDUINO Connector" - select STM32F7_USART6 - select USART6_SERIALDRIVER - select USART6_SERIAL_CONSOLE - -config NUCLEO_CONSOLE_VIRTUAL - bool "Virtual Comport" - select STM32F7_USART3 - select USART3_SERIALDRIVER - select USART3_SERIAL_CONSOLE - -config NUCLEO_CONSOLE_MORPHO - bool "Morpho Connector" - select STM32F7_UART8 - select UART8_SERIALDRIVER - select UART8_SERIAL_CONSOLE - -config NUCLEO_CONSOLE_NONE - bool "No Console" - -endchoice # "Select Console wiring" - -config NUCLEO_SPI_TEST - bool "Enable SPI test" - default n - ---help--- - Enable Spi test - initalize and configure SPI to send - NUCLEO_SPI_TEST_MESSAGE text. The text is sent on the - selected SPI Buses with the configured parameters. - Note the CS lines will not be asserted. - -if NUCLEO_SPI_TEST - -config NUCLEO_SPI_TEST_MESSAGE - string "Text to Send on SPI Bus(es)" - default "Hello World" - depends on NUCLEO_SPI_TEST - ---help--- - Text to sent on SPI bus(es) - -config NUCLEO_SPI1_TEST - bool "Test SPI bus 1" - default n - depends on NUCLEO_SPI_TEST - ---help--- - Enable Spi test - on SPI BUS 1 - -if NUCLEO_SPI1_TEST - -config NUCLEO_SPI1_TEST_FREQ - int "SPI 1 Clock Freq in Hz" - default 1000000 - depends on NUCLEO_SPI1_TEST - ---help--- - Sets SPI 1 Clock Freq - -config NUCLEO_SPI1_TEST_BITS - int "SPI 1 number of bits" - default 8 - depends on NUCLEO_SPI1_TEST - ---help--- - Sets SPI 1 bit length - -choice - prompt "SPI BUS 1 Clock Mode" - default NUCLEO_SPI1_TEST_MODE3 - ---help--- - Sets SPI 1 clock mode - -config NUCLEO_SPI1_TEST_MODE0 - bool "CPOL=0 CHPHA=0" - -config NUCLEO_SPI1_TEST_MODE1 - bool "CPOL=0 CHPHA=1" - -config NUCLEO_SPI1_TEST_MODE2 - bool "CPOL=1 CHPHA=0" - -config NUCLEO_SPI1_TEST_MODE3 - bool "CPOL=1 CHPHA=1" - -endchoice # "SPI BUS 1 Clock Mode" - -endif # NUCLEO_SPI1_TEST - -config NUCLEO_SPI2_TEST - bool "Test SPI bus 2" - default n - depends on NUCLEO_SPI_TEST - ---help--- - Enable Spi test - on SPI BUS 2 - -if NUCLEO_SPI2_TEST - -config NUCLEO_SPI2_TEST_FREQ - int "SPI 2 Clock Freq in Hz" - default 12000000 - depends on NUCLEO_SPI2_TEST - ---help--- - Sets SPI 2 Clock Freq - -config NUCLEO_SPI2_TEST_BITS - int "SPI 2 number of bits" - default 8 - depends on NUCLEO_SPI2_TEST - ---help--- - Sets SPI 2 bit length - -choice - prompt "SPI BUS 2 Clock Mode" - default NUCLEO_SPI2_TEST_MODE3 - ---help--- - Sets SPI 2 clock mode - -config NUCLEO_SPI2_TEST_MODE0 - bool "CPOL=0 CHPHA=0" - -config NUCLEO_SPI2_TEST_MODE1 - bool "CPOL=0 CHPHA=1" - -config NUCLEO_SPI2_TEST_MODE2 - bool "CPOL=1 CHPHA=0" - -config NUCLEO_SPI2_TEST_MODE3 - bool "CPOL=1 CHPHA=1" - -endchoice # "SPI BUS 2 Clock Mode" - -endif # NUCLEO_SPI2_TEST - -config NUCLEO_SPI3_TEST - bool "Test SPI bus 3" - default n - depends on NUCLEO_SPI_TEST - ---help--- - Enable Spi test - on SPI BUS 3 - -if NUCLEO_SPI3_TEST - -config NUCLEO_SPI3_TEST_FREQ - int "SPI 3 Clock Freq in Hz" - default 40000000 - depends on NUCLEO_SPI3_TEST - ---help--- - Sets SPI 3 Clock Freq - -config NUCLEO_SPI3_TEST_BITS - int "SPI 3 number of bits" - default 8 - depends on NUCLEO_SPI3_TEST - ---help--- - Sets SPI 3 bit length - -choice - prompt "SPI BUS 3 Clock Mode" - default NUCLEO_SPI3_TEST_MODE3 - ---help--- - Sets SPI 3 clock mode - -config NUCLEO_SPI3_TEST_MODE0 - bool "CPOL=0 CHPHA=0" - -config NUCLEO_SPI3_TEST_MODE1 - bool "CPOL=0 CHPHA=1" - -config NUCLEO_SPI3_TEST_MODE2 - bool "CPOL=1 CHPHA=0" - -config NUCLEO_SPI3_TEST_MODE3 - bool "CPOL=1 CHPHA=1" - -endchoice # "SPI BUS 3 Clock Mode" - -endif # NUCLEO_SPI3_TEST -endif # NUCLEO_SPI_TEST -endif # ARCH_BOARD_NUCLEO_144 +endif # ARCH_BOARD_NUCLEO_L496ZG -- GitLab From 2ecaf33bb690aec30f1b9c54cdfac7cbc4fb3bf8 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 5 May 2017 06:48:53 -0600 Subject: [PATCH 719/990] nucleo-144: Default for choice in Kconfig was not one of the possible choices. --- configs/nucleo-144/Kconfig | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/configs/nucleo-144/Kconfig b/configs/nucleo-144/Kconfig index 96427a9a5e..a6ac8ffbed 100644 --- a/configs/nucleo-144/Kconfig +++ b/configs/nucleo-144/Kconfig @@ -7,7 +7,7 @@ if ARCH_BOARD_NUCLEO_144 choice prompt "Select Console wiring." - default NUCLEO_ARDUINO + default NUCLEO_CONSOLE_ARDUINO ---help--- Select where you will connect the console. -- GitLab From 2171523f50c5d3ebb2d2ad8372bb0816afafbcd9 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Fri, 5 May 2017 07:12:52 -0600 Subject: [PATCH 720/990] Kinetis:Add TPM to K66 chip --- arch/arm/include/kinetis/chip.h | 5 +- arch/arm/src/kinetis/Kconfig | 32 +++- arch/arm/src/kinetis/chip/kinetis_kx6tpm.h | 211 +++++++++++++++++++++ arch/arm/src/kinetis/kinetis_tpm.h | 58 ++++++ 4 files changed, 303 insertions(+), 3 deletions(-) create mode 100644 arch/arm/src/kinetis/chip/kinetis_kx6tpm.h create mode 100644 arch/arm/src/kinetis/kinetis_tpm.h diff --git a/arch/arm/include/kinetis/chip.h b/arch/arm/include/kinetis/chip.h index 5c6cc76a08..cc50674e97 100644 --- a/arch/arm/include/kinetis/chip.h +++ b/arch/arm/include/kinetis/chip.h @@ -1438,8 +1438,9 @@ # define KINETIS_NDAC6 4 /* Four 6-bit DAC */ # define KINETIS_NDAC12 2 /* Two 12-bit DAC */ # define KINETIS_NVREF 1 /* Voltage reference */ -# define KINETIS_NTIMERS8 2 /* ? Two 8 channel timers */ -# define KINETIS_NTIMERS2 2 /* ? Two 2 channel timers */ +# define KINETIS_NTIMERS8 2 /* Two 8 channel FTM timers */ +# define KINETIS_NTIMERS2 2 /* Two 2 channel FTM timers */ +# define KINETIS_NTPMTIMERS2 2 /* Two 2 channel TPM timers */ # define KINETIS_NRTC 1 /* Real time clock */ # define KINETIS_NRNG 1 /* Random number generator */ # define KINETIS_NMMCAU 1 /* Hardware encryption */ diff --git a/arch/arm/src/kinetis/Kconfig b/arch/arm/src/kinetis/Kconfig index 271921a9ef..9920e3ce35 100644 --- a/arch/arm/src/kinetis/Kconfig +++ b/arch/arm/src/kinetis/Kconfig @@ -268,15 +268,23 @@ config ARCH_FAMILY_K60 config ARCH_FAMILY_K64 bool default n + select KINETIS_HAVE_FTM3 select KINETIS_HAVE_UART5 config ARCH_FAMILY_K66 bool default n + select KINETIS_HAVE_FTM3 select KINETIS_HAVE_LPUART0 + select KINETIS_HAVE_TPM1 + select KINETIS_HAVE_TPM2 menu "Kinetis Peripheral Support" +config KINETIS_HAVE_FTM3 + bool + default n + config KINETIS_HAVE_I2C1 bool default n @@ -297,6 +305,14 @@ config KINETIS_HAVE_SPI2 bool default n +config KINETIS_HAVE_TPM1 + bool + default n + +config KINETIS_HAVE_TPM2 + bool + default n + config KINETIS_TRACE bool "Trace" default n @@ -531,10 +547,24 @@ config KINETIS_FTM2 config KINETIS_FTM3 bool "FTM3" default n - depends on ARCH_FAMILY_K64 || ARCH_FAMILY_K66 + depends on KINETIS_HAVE_FTM3 ---help--- Support FlexTimer 3 +config KINETIS_TPM1 + bool "TPM1" + default n + depends on KINETIS_HAVE_TPM1 + ---help--- + Support TPM module 1 + +config KINETIS_TPM2 + bool "TPM2" + default n + depends on KINETIS_HAVE_TPM2 + ---help--- + Support TPM module 2 + config KINETIS_LPTIMER bool "Low power timer (LPTIMER)" default n diff --git a/arch/arm/src/kinetis/chip/kinetis_kx6tpm.h b/arch/arm/src/kinetis/chip/kinetis_kx6tpm.h new file mode 100644 index 0000000000..2dd103c656 --- /dev/null +++ b/arch/arm/src/kinetis/chip/kinetis_kx6tpm.h @@ -0,0 +1,211 @@ +/**************************************************************************** + * arch/arm/src/kinetis/chip/kinetis_kx6tpm.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * David Sidrane + * + * 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 __ARCH_ARM_SRC_KINETIS_CHIP_KINETIS_KX6TPM_H +#define __ARCH_ARM_SRC_KINETIS_CHIP_KINETIS_KX6TPM_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include "chip.h" + +/**************************************************************************** + * Pre-processor Declarations + ****************************************************************************/ + +#define KINETIS_TPM_SC_OFFSET 0x0000 /* Status and Control offset*/ +#define KINETIS_TPM_CNT_OFFSET 0x0004 /* Counter offset */ +#define KINETIS_TPM_MOD_OFFSET 0x0008 /* Modulo offset */ +#define KINETIS_TPM_C0SC_OFFSET 0x000C /* Channel 0 Status and Control offset */ +#define KINETIS_TPM_C0V_OFFSET 0x0010 /* Channel 0 Value offset */ +#define KINETIS_TPM_C1SC_OFFSET 0x0014 /* Channel 1 Status and Control offset */ +#define KINETIS_TPM_C1V_OFFSET 0x0018 /* Channel 1 Value offset */ +#define KINETIS_TPM_STATUS_OFFSET 0x0050 /* Capture and Compare Status offset */ +#define KINETIS_TPM_COMBINE_OFFSET 0x0064 /* Combine Channel Register offset */ +#define KINETIS_TPM_POL_OFFSET 0x0070 /* Channel Polarity offset */ +#define KINETIS_TPM_FILTER_OFFSET 0x0078 /* Filter Control offset */ +#define KINETIS_TPM_QDCTRL_OFFSET 0x0080 /* Quadrature Decoder Control and Status offset */ +#define KINETIS_TPM_CONF_OFFSET 0x0084 /* Configuration offset */ + +#define KINETIS_TPM1_SC (KINETIS_TPM1_BASE + KINETIS_TPM_SC_OFFSET) /* TPM1 Status and Control */ +#define KINETIS_TPM1_CNT (KINETIS_TPM1_BASE + KINETIS_TPM_CNT_OFFSET) /* TPM1 Counter */ +#define KINETIS_TPM1_MOD (KINETIS_TPM1_BASE + KINETIS_TPM_MOD_OFFSET) /* TPM1 Modulo */ +#define KINETIS_TPM1_C0SC (KINETIS_TPM1_BASE + KINETIS_TPM_C0SC_OFFSET) /* TPM1 Channel 0 Status and Control */ +#define KINETIS_TPM1_C0V (KINETIS_TPM1_BASE + KINETIS_TPM_C0V_OFFSET) /* TPM1 Channel 0 Value */ +#define KINETIS_TPM1_C1SC (KINETIS_TPM1_BASE + KINETIS_TPM_C1SC_OFFSET) /* TPM1 Channel 1 Status and Control */ +#define KINETIS_TPM1_C1V (KINETIS_TPM1_BASE + KINETIS_TPM_C1V_OFFSET) /* TPM1 Channel 1 Value */ +#define KINETIS_TPM1_C2SC (KINETIS_TPM1_BASE + KINETIS_TPM_C2SC_OFFSET) /* TPM1 Channel 2 Status and Control */ +#define KINETIS_TPM1_C2V (KINETIS_TPM1_BASE + KINETIS_TPM_C2V_OFFSET) /* TPM1 Channel 2 Value */ +#define KINETIS_TPM1_STATUS (KINETIS_TPM1_BASE + KINETIS_TPM_STATUS_OFFSET) /* TPM1 Capture and Compare Status */ +#define KINETIS_TPM1_COMBINE (KINETIS_TPM1_BASE + KINETIS_TPM_COMBINE_OFFSET) /* TPM1 Combine Channel Register offset */ +#define KINETIS_TPM1_POL (KINETIS_TPM1_BASE + KINETIS_TPM_POL_OFFSET) /* TPM1 Channel Polarity offset */ +#define KINETIS_TPM1_FILTER (KINETIS_TPM1_BASE + KINETIS_TPM_FILTER_OFFSET) /* TPM1 Filter Control offset */ +#define KINETIS_TPM1_QDCTRL (KINETIS_TPM1_BASE + KINETIS_TPM_QDCTRL_OFFSET) /* TPM1 Quadrature Decoder Control and Status offset */ +#define KINETIS_TPM1_CONF (KINETIS_TPM1_BASE + KINETIS_TPM_CONF_OFFSET) /* TPM1 Configuration */ + +#define KINETIS_TPM2_SC (KINETIS_TPM2_BASE + KINETIS_TPM_SC_OFFSET) /* TPM2 Status and Control */ +#define KINETIS_TPM2_CNT (KINETIS_TPM2_BASE + KINETIS_TPM_CNT_OFFSET) /* TPM2 Counter */ +#define KINETIS_TPM2_MOD (KINETIS_TPM2_BASE + KINETIS_TPM_MOD_OFFSET) /* TPM2 Modulo */ +#define KINETIS_TPM2_C0SC (KINETIS_TPM2_BASE + KINETIS_TPM_C0SC_OFFSET) /* TPM2 Channel 0 Status and Control */ +#define KINETIS_TPM2_C0V (KINETIS_TPM2_BASE + KINETIS_TPM_C0V_OFFSET) /* TPM2 Channel 0 Value */ +#define KINETIS_TPM2_C1SC (KINETIS_TPM2_BASE + KINETIS_TPM_C1SC_OFFSET) /* TPM2 Channel 1 Status and Control */ +#define KINETIS_TPM2_C1V (KINETIS_TPM2_BASE + KINETIS_TPM_C1V_OFFSET) /* TPM2 Channel 1 Value */ +#define KINETIS_TPM2_C2SC (KINETIS_TPM2_BASE + KINETIS_TPM_C2SC_OFFSET) /* TPM2 Channel 2 Status and Control */ +#define KINETIS_TPM2_C2V (KINETIS_TPM2_BASE + KINETIS_TPM_C2V_OFFSET) /* TPM2 Channel 2 Value */ +#define KINETIS_TPM2_STATUS (KINETIS_TPM2_BASE + KINETIS_TPM_STATUS_OFFSET) /* TPM2 Capture and Compare Status */ +#define KINETIS_TPM2_COMBINE (KINETIS_TPM2_BASE + KINETIS_TPM_COMBINE_OFFSET) /* TPM2 Combine Channel Register offset */ +#define KINETIS_TPM2_POL (KINETIS_TPM2_BASE + KINETIS_TPM_POL_OFFSET) /* TPM2 Channel Polarity offset */ +#define KINETIS_TPM2_FILTER (KINETIS_TPM2_BASE + KINETIS_TPM_FILTER_OFFSET) /* TPM2 Filter Control offset */ +#define KINETIS_TPM2_QDCTRL (KINETIS_TPM2_BASE + KINETIS_TPM_QDCTRL_OFFSET) /* TPM2 Quadrature Decoder Control and Status offset */ +#define KINETIS_TPM2_CONF (KINETIS_TPM2_BASE + KINETIS_TPM_CONF_OFFSET) /* TPM2 Configuration */ + +#define TPM_SC_PS_SHIFT 0 /* Bits 0-2: Prescale Factor Selection */ +#define TPM_SC_PS_MASK (7 << TPM_SC_PS_SHIFT) +# define TPM_SC_PS_DIV1 (0 << TPM_SC_PS_SHIFT) /* Divide Clock by 1 */ +# define TPM_SC_PS_DIV2 (1 << TPM_SC_PS_SHIFT) /* Divide Clock by 2 */ +# define TPM_SC_PS_DIV4 (2 << TPM_SC_PS_SHIFT) /* Divide Clock by 4 */ +# define TPM_SC_PS_DIV8 (3 << TPM_SC_PS_SHIFT) /* Divide Clock by 8 */ +# define TPM_SC_PS_DIV16 (4 << TPM_SC_PS_SHIFT) /* Divide Clock by 16 */ +# define TPM_SC_PS_DIV32 (5 << TPM_SC_PS_SHIFT) /* Divide Clock by 32 */ +# define TPM_SC_PS_DIV64 (6 << TPM_SC_PS_SHIFT) /* Divide Clock by 64 */ +# define TPM_SC_PS_DIV128 (7 << TPM_SC_PS_SHIFT) /* Divide Clock by 128 */ + +#define TPM_SC_CMOD_SHIFT 3 /* Bits 3-4: Clock Mode Selection */ +#define TPM_SC_CMOD_MASK (3 << TPM_SC_CMOD_SHIFT) +# define TPM_SC_CMOD_DIS (0 << TPM_SC_CMOD_SHIFT) /* TPM counter is disabled */ +# define TPM_SC_CMOD_LPTPM_CLK (1 << TPM_SC_CMOD_SHIFT) /* TPM increments on every counter clock */ +# define TPM_SC_CMOD_LPTPM_EXTCLK (2 << TPM_SC_CMOD_SHIFT) /* TPM increments on rising edge of EXTCLK */ + +#define TPM_SC_CPWMS (1 << 5) /* Bit 5: Center-aligned PWM Select */ +#define TPM_SC_TOIE (1 << 6) /* Bit 6: Timer Overflow Interrupt Enable */ +#define TPM_SC_TOF (1 << 7) /* Bit 7: Timer Overflow Flag*/ +#define TPM_SC_DMA (1 << 8) /* Bit 8: DMA Enable*/ + /* Bits 9-31: Reserved */ + +#define TPM_CNT_SHIFT 0 /* Bits 0-15: Counter value */ +#define TPM_CNT_MASK (0xffff << TPM_COUNT_SHIFT) /* Any write clears Count */ + /* Bits 16-31: Reserved */ + +#define TPM_MOD_SHIFT 0 /* Bits 0-15: Mod value */ +#define TPM_MOD_MASK (0xffff << TPM_MOD_SHIFT) /* This field must be written with single 16 or 32-bit access */ + /* Bits 16-31: Reserved */ + +#define TPM_CnSC_DMA (1 << 0) /* Bit 0: Enables DMA transfers for the channel */ + /* Bit 1: Reserved*/ +#define TPM_CnSC_ELSA (1 << 2) /* Bit 2: Edge or Level Select */ +#define TPM_CnSC_ELSB (1 << 3) /* Bit 3: Edge or Level Select */ +#define TPM_CnSC_MSA (1 << 4) /* Bit 4: Channel Mode Select */ +#define TPM_CnSC_MSB (1 << 5) /* Bit 5: Channel Mode Select */ +#define TPM_CnSC_CHIE (1 << 6) /* Bit 6: Channel Interrupt Enable */ +#define TPM_CnSC_CHF (1 << 7) /* Bit 7: Channel Flag */ + /* Bits 8-31: Reserved */ + +#define TPM_VAL_SHIFT 0 /* Bits 0-15: Channel value */ +#define TPM_VAL_MASK (0xffff << TPM_VAL_SHIFT) /* Captured TPM counter value of the input modes or + * the match value for the output modes. This field + * must be written with single 16 or 32-bit access.*/ + /* Bits 16-31: Reserved */ + +#define TPM_STATUS_CH0F (1 << 0) /* Bit 0: Channel 0 Flag */ +#define TPM_STATUS_CH1F (1 << 1) /* Bit 1: Channel 1 Flag */ + /* Bits 2-7: Reserved */ +#define TPM_STATUS_TOF (1 << 8) /* Bit 8: Timer Overflow Flag */ + /* Bits 9-31: Reserved */ + +#define TPM_COMBINE_COMBINE0 (1 << 0) /* Bit 0: Combine Channels 0 and 1 */ +#define TPM_COMBINE_COMSWAP0 (1 << 1) /* Bit 1: Combine Channel 0 and 1 Swap */ + /* Bits 2-7: Reserved */ + /* Bits 8-31: Reserved */ + +#define TPM_POL_POL0 (1 << 0) /* Bit 0: Channel 0 Polarity */ +#define TPM_POL_POL1 (1 << 1) /* Bit 1: Channel 1 Polarity */ + /* Bits 2-31: Reserved */ + +#define TPM_FILTER_CH0FVAL_SHIFT 0 /* Bits 0-3: Channel 0 Filter Value */ +#define TPM_FILTER_CH0FVAL_MASK (0xf << TPM_FILTER_CH0FVAL_SHIFT) +#define TPM_FILTER_CH1FVAL_SHIFT 4 /* Bits 4-7: Channel 1 Filter Value */ +#define TPM_FILTER_CH1FVAL_MASK (0xf << TPM_FILTER_CH1FVAL_SHIFT) + +#define TPM_QDCTRL_QDCTRL (1 << 0) /* Bit 0: Enables the quadrature decoder mode */ +#define TPM_QDCTRL_TOFDIR (1 << 1) /* Bit 1: Indicates if the TOF bit was set (Read Only) */ +#define TPM_QDCTRL_QUADIR (1 << 2) /* Bit 2: Counter Direction in Quadrature Decode Mode (Read Only) */ +#define TPM_QDCTRL_QUADMODE (1 << 3) /* Bit 3: Quadrature Decoder Mode */ + /* Bits 4-31: Reserved */ + +#define TPM_CONF_DOZEEN (1 << 5) /* Bit 5: Doze Enable */ +#define TPM_CONF_DBGMODE_SHIFT 6 /* Bits 6-7: Debug Mode */ +#define TPM_CONF_DBGMODE_MASK (3 << TPM_CONF_DBGMODE_SHIFT) +# define TPM_CONF_DBGMODE_PAUSE (0 << TPM_CONF_DBGMODE_SHIFT) /* TPM counter will pause during DEBUG mode */ +# define TPM_CONF_DBGMODE_CONT (3 << TPM_CONF_DBGMODE_SHIFT) /* TPM counter continue working in DEBUG mode */ +#define TPM_CONF_GTBSYNC (1 << 8) /* Bit 8: Global Time Base Synchronization */ +#define TPM_CONF_GTBEEN (1 << 9) /* Bit 9: Global Time Base Enable */ + /* Bits 10-15: Reserved */ +#define TPM_CONF_CSOT (1 << 16) /* Bit 16: Counter Start On Trigger */ +#define TPM_CONF_CSOO (1 << 17) /* Bit 17: Counter Stop On Overflow */ +#define TPM_CONF_CROT (1 << 18) /* Bit 18: Counter Reload On Trigger */ +#define TPM_CONF_CPOT (1 << 19) /* Bit 19: Counter Pause On Trigger */ + /* Bits 20-21: Reserved */ +#define TPM_CONF_TRGPOL (1 << 22) /* Bit 22: Trigger Polarity */ +#define TPM_CONF_TRGSRC (1 << 23) /* Bit 23: Trigger Source */ + +#define TPM_CONF_TRGSEL_SHIFT 24 /* Bits 24-27: Trigger Select */ +#define TPM_CONF_TRGSEL_MASK (0xf << TPM_CONF_TRGSEL_SHIFT) + /* Internal TPM_CONF_TRGSRC set */ +# define TPM_CONF_TRGSEL_INTC0 (0 << TPM_CONF_TRGSEL_SHIFT) /* Internal Channel 0 pin input capture */ +# define TPM_CONF_TRGSEL_INTC1 (2 << TPM_CONF_TRGSEL_SHIFT) /* Internal Channel 1 pin input capture */ +# define TPM_CONF_TRGSEL_INTC01 (3 << TPM_CONF_TRGSEL_SHIFT) /* Internal Channel 0 or 1 pin input capture */ + +# define TPM_CONF_TRGSEL_EXTRG_IN (0 << TPM_CONF_TRGSEL_SHIFT) /* External trigger pin input */ +# define TPM_CONF_TRGSEL_CMP0 (1 << TPM_CONF_TRGSEL_SHIFT) /* CPM0 output */ +# define TPM_CONF_TRGSEL_CMP1 (2 << TPM_CONF_TRGSEL_SHIFT) /* CPM1 output */ +# define TPM_CONF_TRGSEL_CMP2 (3 << TPM_CONF_TRGSEL_SHIFT) /* CPM2 output */ +# define TPM_CONF_TRGSEL_PIT0 (4 << TPM_CONF_TRGSEL_SHIFT) /* PIT trigger 0 */ +# define TPM_CONF_TRGSEL_PIT1 (5 << TPM_CONF_TRGSEL_SHIFT) /* PIT trigger 1 */ +# define TPM_CONF_TRGSEL_PIT2 (6 << TPM_CONF_TRGSEL_SHIFT) /* PIT trigger 2 */ +# define TPM_CONF_TRGSEL_PIT3 (7 << TPM_CONF_TRGSEL_SHIFT) /* PIT trigger 3 */ +# define TPM_CONF_TRGSEL_FTM0 (8 << TPM_CONF_TRGSEL_SHIFT) /* FTM0 initialization trigger and channel triggers */ +# define TPM_CONF_TRGSEL_FTM1 (9 << TPM_CONF_TRGSEL_SHIFT) /* FTM1 initialization trigger and channel triggers */ +# define TPM_CONF_TRGSEL_FTM2 (10 << TPM_CONF_TRGSEL_SHIFT) /* FTM2 initialization trigger and channel triggers */ +# define TPM_CONF_TRGSEL_FTM3 (11 << TPM_CONF_TRGSEL_SHIFT) /* FTM3 initialization trigger and channel triggers */ +# define TPM_CONF_TRGSEL_RTC_ALRM (12 << TPM_CONF_TRGSEL_SHIFT) /* RTC Alarm */ +# define TPM_CONF_TRGSEL_RTC_SECS (13 << TPM_CONF_TRGSEL_SHIFT) /* RTC Seconds */ +# define TPM_CONF_TRGSEL_LPTMR (14 << TPM_CONF_TRGSEL_SHIFT) /* LPTMR trigger */ +# define TPM_CONF_TRGSEL_SW (15 << TPM_CONF_TRGSEL_SHIFT) /* Software Trigger */ + +#endif /* __ARCH_ARM_SRC_KINETIS_CHIP_KINETIS_KX6TPM_H */ diff --git a/arch/arm/src/kinetis/kinetis_tpm.h b/arch/arm/src/kinetis/kinetis_tpm.h new file mode 100644 index 0000000000..03fe3b1362 --- /dev/null +++ b/arch/arm/src/kinetis/kinetis_tpm.h @@ -0,0 +1,58 @@ +/**************************************************************************** + * arch/arm/src/kinetis/kinetis_tpm.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * David Sidrane + * + * 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 __ARCH_ARM_SRC_KINETIS_KINETIS_TPM_H +#define __ARCH_ARM_SRC_KINETIS_KINETIS_TPM_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include "chip.h" + +/* This file is just a wrapper around tmp header files for the Kinetis family + * selected by the logic in chip.h. + */ + +#if defined(KINETIS_K66) +# include "chip/kinetis_kx6tpm.h" +#else +# error "No TMP definitions for this Kinetis part" +#endif + +#endif /* __ARCH_ARM_SRC_KINETIS_KINETIS_TPM_H */ -- GitLab From f73e2aab8d8c956c10522dab068c1a9f6a998e73 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Fri, 5 May 2017 07:14:00 -0600 Subject: [PATCH 721/990] Kinetis:Fixed CLKSRC Bit Names --- arch/arm/src/kinetis/chip/kinetis_sim.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/arch/arm/src/kinetis/chip/kinetis_sim.h b/arch/arm/src/kinetis/chip/kinetis_sim.h index 3e6cb6a6ef..a1ffe6721e 100644 --- a/arch/arm/src/kinetis/chip/kinetis_sim.h +++ b/arch/arm/src/kinetis/chip/kinetis_sim.h @@ -328,7 +328,7 @@ divided by the PLLFLLCLK fractional divider as configured by SIM_CLKDIV3[PLLFLLFRAC, PLLFLLDIV] */ # define SIM_SOPT2_TPMSRC_OCSERCLK (2 << SIM_SOPT2_TPMSRC_SHIFT) /* OSCERCLK clock */ -# define SIM_SOPT2_TPMSRC_EXTBYP (3 << SIM_SOPT2_TPMSRC_SHIFT) /* MCGIRCLK clock */ +# define SIM_SOPT2_TPMSRC_MCGIRCLK (3 << SIM_SOPT2_TPMSRC_SHIFT) /* MCGIRCLK clock */ # endif # if defined(KINETIS_SIM_HAS_SOPT2_I2SSRC) # define SIM_SOPT2_I2SSRC_SHIFT (24) /* Bits 24-25: I2S master clock source select */ @@ -348,7 +348,7 @@ divided by the PLLFLLCLK fractional divider as configured by SIM_CLKDIV3[PLLFLLFRAC, PLLFLLDIV] */ # define SIM_SOPT2_LPUARTSRC_OCSERCLK (2 << SIM_SOPT2_LPUARTSRC_SHIFT) /* OSCERCLK clock */ -# define SIM_SOPT2_LPUARTSRC_EXTBYP (3 << SIM_SOPT2_LPUARTSRC_SHIFT) /* MCGIRCLK clock */ +# define SIM_SOPT2_LPUARTSRC_MCGIRCLK (3 << SIM_SOPT2_LPUARTSRC_SHIFT) /* MCGIRCLK clock */ # endif # if defined(KINETIS_SIM_HAS_SOPT2_SDHCSRC) # define SIM_SOPT2_SDHCSRC_SHIFT (28) /* Bits 28-29: SDHC clock source select */ -- GitLab From 29ef635e895e6fb8829acfef0924b54fabd4c94f Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Fri, 5 May 2017 07:16:11 -0600 Subject: [PATCH 722/990] Kinetis:Add OSC_DIV to the kinetis_osc header --- arch/arm/src/kinetis/chip/kinetis_osc.h | 13 ++++++++++++- 1 file changed, 12 insertions(+), 1 deletion(-) diff --git a/arch/arm/src/kinetis/chip/kinetis_osc.h b/arch/arm/src/kinetis/chip/kinetis_osc.h index 69a7b8a30c..e61f0a8c1c 100644 --- a/arch/arm/src/kinetis/chip/kinetis_osc.h +++ b/arch/arm/src/kinetis/chip/kinetis_osc.h @@ -1,7 +1,7 @@ /******************************************************************************************** * arch/arm/src/kinetis/chip/kinetis_osc.h * - * Copyright (C) 2011, 2016 Gregory Nutt. All rights reserved. + * Copyright (C) 2011, 2016-2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -51,10 +51,12 @@ /* Register Offsets *************************************************************************/ #define KINETIS_OSC_CR_OFFSET 0x0000 /* OSC Control Register */ +#define KINETIS_OSC_DIV_OFFSET 0x0002 /* OSC CLock divider register */ /* Register Addresses ***********************************************************************/ #define KINETIS_OSC_CR (KINETIS_OSC_BASE+KINETIS_OSC_CR_OFFSET) +#define KINETIS_OSC_DIV (KINETIS_OSC_BASE+KINETIS_OSC_DIV_OFFSET) /* Register Bit Definitions *****************************************************************/ @@ -69,6 +71,15 @@ #define OSC_CR_SC8P (1 << 1) /* Bit 1: Oscillator 8 pF Capacitor Load Configure */ #define OSC_CR_SC16P (1 << 0) /* Bit 0: Oscillator 16 pF Capacitor Load Configure */ +/* OSC Control Register (8-bit) */ + /* Bits 0-5: Reserved */ +#define OSC_DIV_ERPS_SHIFT 6 /* Bits 6-7: ERCLK prescaler */ +#define OSC_DIV_ERPS_MASK (3 << OSC_DIV_ERPS_SHIFT) +# define OSC_DIV_ERPS_DIV1 (0 << OSC_DIV_ERPS_SHIFT) /* The divisor ratio is 1 */ +# define OSC_DIV_ERPS_DIV2 (1 << OSC_DIV_ERPS_SHIFT) /* The divisor ratio is 2 */ +# define OSC_DIV_ERPS_DIV3 (2 << OSC_DIV_ERPS_SHIFT) /* The divisor ratio is 4 */ +# define OSC_DIV_ERPS_DIV8 (3 << OSC_DIV_ERPS_SHIFT) /* The divisor ratio is 8 */ + /******************************************************************************************** * Public Types ********************************************************************************************/ -- GitLab From b6a8db1b392961b0e5c4a5a4e307fdd70786bca6 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Fri, 5 May 2017 07:18:39 -0600 Subject: [PATCH 723/990] Kinetis: Use optional BOARD_OSC_CR and BOARD_OSC_DIV in clock configuration --- arch/arm/src/kinetis/kinetis_clockconfig.c | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/arch/arm/src/kinetis/kinetis_clockconfig.c b/arch/arm/src/kinetis/kinetis_clockconfig.c index b954f33be2..28218fcd86 100644 --- a/arch/arm/src/kinetis/kinetis_clockconfig.c +++ b/arch/arm/src/kinetis/kinetis_clockconfig.c @@ -49,6 +49,7 @@ #include "chip/kinetis_pmc.h" #include "chip/kinetis_llwu.h" #include "chip/kinetis_pinmux.h" +#include "chip/kinetis_osc.h" #include @@ -199,6 +200,18 @@ void kinetis_pllconfig(void) #endif uint8_t regval8; +#if defined(BOARD_OSC_CR) + /* Use complete BOARD_OSC_CR settings */ + + putreg8(BOARD_OSC_CR, KINETIS_OSC_CR); +#endif + +#if defined(BOARD_OSC_DIV) + /* Use complete BOARD_OSC_DIV settings */ + + putreg8(BOARD_OSC_DIV, KINETIS_OSC_DIV); +#endif + #if defined(BOARD_MCG_C2) /* Use complete BOARD_MCG_C2 settings */ -- GitLab From f29981e473292ad6bab5cd62064d673da55e842e Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Fri, 5 May 2017 07:33:15 -0600 Subject: [PATCH 724/990] kinetis:Added HW flow control and termios --- arch/arm/src/kinetis/Kconfig | 57 ++++ arch/arm/src/kinetis/kinetis.h | 6 +- arch/arm/src/kinetis/kinetis_lowputc.c | 169 +++++++++- arch/arm/src/kinetis/kinetis_lpserial.c | 360 +++++++++++++++++++++- arch/arm/src/kinetis/kinetis_serial.c | 390 +++++++++++++++++++++++- 5 files changed, 948 insertions(+), 34 deletions(-) diff --git a/arch/arm/src/kinetis/Kconfig b/arch/arm/src/kinetis/Kconfig index 9920e3ce35..646e7254fa 100644 --- a/arch/arm/src/kinetis/Kconfig +++ b/arch/arm/src/kinetis/Kconfig @@ -239,6 +239,10 @@ config KINETIS_HAVE_LPUART1 # will automatically be selected and will represent the 'OR' of the # instances selected. +config KINETIS_SERIALDRIVER + bool + default n + config KINETIS_LPUART bool default n @@ -330,6 +334,8 @@ config KINETIS_UART0 default n select UART0_SERIALDRIVER select KINETIS_UART + select KINETIS_SERIALDRIVER + select ARCH_HAVE_SERIAL_TERMIOS ---help--- Support UART0 @@ -338,6 +344,8 @@ config KINETIS_UART1 default n select UART1_SERIALDRIVER select KINETIS_UART + select KINETIS_SERIALDRIVER + select ARCH_HAVE_SERIAL_TERMIOS ---help--- Support UART1 @@ -346,6 +354,8 @@ config KINETIS_UART2 default n select UART2_SERIALDRIVER select KINETIS_UART + select KINETIS_SERIALDRIVER + select ARCH_HAVE_SERIAL_TERMIOS ---help--- Support UART2 @@ -354,6 +364,8 @@ config KINETIS_UART3 default n select UART3_SERIALDRIVER select KINETIS_UART + select KINETIS_SERIALDRIVER + select ARCH_HAVE_SERIAL_TERMIOS ---help--- Support UART3 @@ -362,6 +374,8 @@ config KINETIS_UART4 default n select UART4_SERIALDRIVER select KINETIS_UART + select KINETIS_SERIALDRIVER + select ARCH_HAVE_SERIAL_TERMIOS ---help--- Support UART4 @@ -371,6 +385,8 @@ config KINETIS_UART5 depends on KINETIS_HAVE_UART5 select UART5_SERIALDRIVER select KINETIS_UART + select KINETIS_SERIALDRIVER + select ARCH_HAVE_SERIAL_TERMIOS ---help--- Support UART5 @@ -380,6 +396,8 @@ config KINETIS_LPUART0 depends on KINETIS_HAVE_LPUART0 select OTHER_UART_SERIALDRIVER select KINETIS_LPUART + select KINETIS_SERIALDRIVER + select ARCH_HAVE_SERIAL_TERMIOS ---help--- Support the low power UART0 @@ -389,6 +407,8 @@ config KINETIS_LPUART1 depends on KINETIS_HAVE_LPUART1 select OTHER_UART_SERIALDRIVER select KINETIS_LPUART + select KINETIS_SERIALDRIVER + select ARCH_HAVE_SERIAL_TERMIOS ---help--- Support the low power UART1 @@ -933,6 +953,43 @@ endmenu # Kinetis SDHC Configuration # menu "Kinetis UART Configuration" +if KINETIS_SERIALDRIVER || OTHER_SERIALDRIVER + +comment "Serial Driver Configuration" + +config KINETIS_UART_BREAKS + bool "Add TIOxSBRK to support sending Breaks" + depends on KINETIS_UART || KINETIS_LPUART + default n + ---help--- + Add TIOCxBRK routines to send a line break per the Kinetis manual, the + break will be a pulse based on the value M. This is not a BSD compatible + break. + +config KINETIS_UART_EXTEDED_BREAK + bool "Selects a longer transmitted break character length" + depends on KINETIS_UART_BREAKS + default n + ---help--- + Sets BRK13 to send a longer transmitted break character. + +config KINETIS_SERIALBRK_BSDCOMPAT + bool "BSD compatible break the break asserted until released" + depends on (KINETIS_UART || KINETIS_LPUART) && KINETIS_UART_BREAKS + default n + ---help--- + Enable using a BSD compatible break: TIOCSBRK will start the break + and TIOCCBRK will end the break. + +config KINETIS_UART_SINGLEWIRE + bool "Single Wire Support" + default n + depends on KINETIS_UART || KINETIS_LPUART + ---help--- + Enable single wire UART and LPUART support. The option enables support + for the TIOCSSINGLEWIRE ioctl in the Kineteis serial drivers. + +endif # KINETIS_SERIALDRIVER || OTHER_SERIALDRIVER config KINETIS_UARTFIFOS bool "Enable UART0 FIFO" diff --git a/arch/arm/src/kinetis/kinetis.h b/arch/arm/src/kinetis/kinetis.h index 3f171e223b..89ab791741 100644 --- a/arch/arm/src/kinetis/kinetis.h +++ b/arch/arm/src/kinetis/kinetis.h @@ -468,7 +468,8 @@ void kinetis_lpuartreset(uintptr_t uart_base); #ifdef HAVE_UART_DEVICE void kinetis_uartconfigure(uintptr_t uart_base, uint32_t baud, uint32_t clock, unsigned int parity, unsigned int nbits, - unsigned int stop2); + unsigned int stop2, + bool iflow, bool oflow); #endif /**************************************************************************** @@ -482,7 +483,8 @@ void kinetis_uartconfigure(uintptr_t uart_base, uint32_t baud, uint32_t clock, #ifdef HAVE_LPUART_DEVICE void kinetis_lpuartconfigure(uintptr_t uart_base, uint32_t baud, uint32_t clock, unsigned int parity, unsigned int nbits, - unsigned int stop2); + unsigned int stop2, + bool iflow, bool oflow); #endif /************************************************************************************ diff --git a/arch/arm/src/kinetis/kinetis_lowputc.c b/arch/arm/src/kinetis/kinetis_lowputc.c index 31bb32f697..bfc56dd069 100644 --- a/arch/arm/src/kinetis/kinetis_lowputc.c +++ b/arch/arm/src/kinetis/kinetis_lowputc.c @@ -41,6 +41,7 @@ #include #include +#include #include #include @@ -59,6 +60,58 @@ * Pre-processor Definitions ****************************************************************************/ +/* Default hardware flow control */ + +#if !defined(CONFIG_UART0_IFLOWCONTROL) +# define CONFIG_UART0_IFLOWCONTROL 0 +#endif +#if !defined(CONFIG_UART0_OFLOWCONTROL) +# define CONFIG_UART0_OFLOWCONTROL 0 +#endif +#if !defined(CONFIG_UART1_IFLOWCONTROL) +# define CONFIG_UART1_IFLOWCONTROL 0 +#endif +#if !defined(CONFIG_UART1_OFLOWCONTROL) +# define CONFIG_UART1_OFLOWCONTROL 0 +#endif +#if !defined(CONFIG_UART2_IFLOWCONTROL) +# define CONFIG_UART2_IFLOWCONTROL 0 +#endif +#if !defined(CONFIG_UART2_OFLOWCONTROL) +# define CONFIG_UART2_OFLOWCONTROL 0 +#endif +#if !defined(CONFIG_UART3_IFLOWCONTROL) +# define CONFIG_UART3_IFLOWCONTROL 0 +#endif +#if !defined(CONFIG_UART3_OFLOWCONTROL) +# define CONFIG_UART3_OFLOWCONTROL 0 +#endif +#if !defined(CONFIG_UART4_IFLOWCONTROL) +# define CONFIG_UART4_IFLOWCONTROL 0 +#endif +#if !defined(CONFIG_UART4_OFLOWCONTROL) +# define CONFIG_UART4_OFLOWCONTROL 0 +#endif +#if !defined(CONFIG_UART5_IFLOWCONTROL) +# define CONFIG_UART5_IFLOWCONTROL 0 +#endif +#if !defined(CONFIG_UART5_OFLOWCONTROL) +# define CONFIG_UART5_OFLOWCONTROL 0 +#endif + +#if !defined(CONFIG_LPUART0_IFLOWCONTROL) +# define CONFIG_LPUART0_IFLOWCONTROL 0 +#endif +#if !defined(CONFIG_LPUART0_OFLOWCONTROL) +# define CONFIG_LPUART0_OFLOWCONTROL 0 +#endif +#if !defined(CONFIG_LPUART1_IFLOWCONTROL) +# define CONFIG_LPUART1_IFLOWCONTROL 0 +#endif +#if !defined(CONFIG_LPUART1_OFLOWCONTROL) +# define CONFIG_LPUART1_OFLOWCONTROL 0 +#endif + /* Select UART parameters for the selected console */ #if defined(HAVE_UART_CONSOLE) @@ -69,6 +122,8 @@ # define CONSOLE_BITS CONFIG_UART0_BITS # define CONSOLE_2STOP CONFIG_UART0_2STOP # define CONSOLE_PARITY CONFIG_UART0_PARITY +# define CONSOLE_IFLOW CONFIG_UART0_IFLOWCONTROL +# define CONSOLE_OFLOW CONFIG_UART0_OFLOWCONTROL # elif defined(CONFIG_UART1_SERIAL_CONSOLE) # define CONSOLE_BASE KINETIS_UART1_BASE # define CONSOLE_FREQ BOARD_CORECLK_FREQ @@ -76,6 +131,8 @@ # define CONSOLE_BITS CONFIG_UART1_BITS # define CONSOLE_2STOP CONFIG_UART1_2STOP # define CONSOLE_PARITY CONFIG_UART1_PARITY +# define CONSOLE_IFLOW CONFIG_UART1_IFLOWCONTROL +# define CONSOLE_OFLOW CONFIG_UART1_OFLOWCONTROL # elif defined(CONFIG_UART2_SERIAL_CONSOLE) # define CONSOLE_BASE KINETIS_UART2_BASE # define CONSOLE_FREQ BOARD_BUS_FREQ @@ -83,6 +140,8 @@ # define CONSOLE_BITS CONFIG_UART2_BITS # define CONSOLE_2STOP CONFIG_UART2_2STOP # define CONSOLE_PARITY CONFIG_UART2_PARITY +# define CONSOLE_IFLOW CONFIG_UART2_IFLOWCONTROL +# define CONSOLE_OFLOW CONFIG_UART2_OFLOWCONTROL # elif defined(CONFIG_UART3_SERIAL_CONSOLE) # define CONSOLE_BASE KINETIS_UART3_BASE # define CONSOLE_FREQ BOARD_BUS_FREQ @@ -90,6 +149,8 @@ # define CONSOLE_BITS CONFIG_UART3_BITS # define CONSOLE_2STOP CONFIG_UART3_2STOP # define CONSOLE_PARITY CONFIG_UART3_PARITY +# define CONSOLE_IFLOW CONFIG_UART3_IFLOWCONTROL +# define CONSOLE_OFLOW CONFIG_UART3_OFLOWCONTROL # elif defined(CONFIG_UART4_SERIAL_CONSOLE) # define CONSOLE_BASE KINETIS_UART4_BASE # define CONSOLE_FREQ BOARD_BUS_FREQ @@ -97,6 +158,8 @@ # define CONSOLE_BITS CONFIG_UART4_BITS # define CONSOLE_2STOP CONFIG_UART4_2STOP # define CONSOLE_PARITY CONFIG_UART4_PARITY +# define CONSOLE_IFLOW CONFIG_UART4_IFLOWCONTROL +# define CONSOLE_OFLOW CONFIG_UART4_OFLOWCONTROL # elif defined(CONFIG_UART5_SERIAL_CONSOLE) # define CONSOLE_BASE KINETIS_UART5_BASE # define CONSOLE_FREQ BOARD_BUS_FREQ @@ -104,6 +167,8 @@ # define CONSOLE_BITS CONFIG_UART5_BITS # define CONSOLE_2STOP CONFIG_UART5_2STOP # define CONSOLE_PARITY CONFIG_UART5_PARITY +# define CONSOLE_IFLOW CONFIG_UART5_IFLOWCONTROL +# define CONSOLE_OFLOW CONFIG_UART5_OFLOWCONTROL # elif defined(HAVE_UART_CONSOLE) # error "No CONFIG_UARTn_SERIAL_CONSOLE Setting" # endif @@ -115,6 +180,8 @@ # define CONSOLE_PARITY CONFIG_LPUART0_PARITY # define CONSOLE_BITS CONFIG_LPUART0_BITS # define CONSOLE_2STOP CONFIG_LPUART0_2STOP +# define CONSOLE_IFLOW CONFIG_LPUART0_IFLOWCONTROL +# define CONSOLE_OFLOW CONFIG_LPUART0_OFLOWCONTROL # elif defined(CONFIG_LPUART1_SERIAL_CONSOLE) # define CONSOLE_BASE KINETIS_LPUART1_BASE # define CONSOLE_FREQ BOARD_LPUART1_FREQ @@ -122,6 +189,8 @@ # define CONSOLE_PARITY CONFIG_LPUART1_PARITY # define CONSOLE_BITS CONFIG_LPUART1_BITS # define CONSOLE_2STOP CONFIG_LPUART1_2STOP +# define CONSOLE_IFLOW CONFIG_LPUART1_IFLOWCONTROL +# define CONSOLE_OFLOW CONFIG_LPUART1_OFLOWCONTROL # else # error "No LPUART console is selected" # endif @@ -271,26 +340,62 @@ void kinetis_lowsetup(void) # ifdef CONFIG_KINETIS_UART0 kinetis_pinconfig(PIN_UART0_TX); kinetis_pinconfig(PIN_UART0_RX); +# if CONFIG_UART0_IFLOWCONTROL == 1 + kinetis_pinconfig(PIN_UART0_RTS); +# endif +# if CONFIG_UART0_OFLOWCONTROL == 1 + kinetis_pinconfig(PIN_UART0_CTS); +# endif # endif # ifdef CONFIG_KINETIS_UART1 kinetis_pinconfig(PIN_UART1_TX); kinetis_pinconfig(PIN_UART1_RX); +# if CONFIG_UART1_IFLOWCONTROL == 1 + kinetis_pinconfig(PIN_UART1_RTS); +# endif +# if CONFIG_UART1_OFLOWCONTROL == 1 + kinetis_pinconfig(PIN_UART1_CTS); +# endif # endif # ifdef CONFIG_KINETIS_UART2 kinetis_pinconfig(PIN_UART2_TX); kinetis_pinconfig(PIN_UART2_RX); +# if CONFIG_UART2_IFLOWCONTROL == 1 + kinetis_pinconfig(PIN_UART2_RTS); +# endif +# if CONFIG_UART2_OFLOWCONTROL == 1 + kinetis_pinconfig(PIN_UART2_CTS); +# endif # endif # ifdef CONFIG_KINETIS_UART3 kinetis_pinconfig(PIN_UART3_TX); kinetis_pinconfig(PIN_UART3_RX); +# if CONFIG_UART3_IFLOWCONTROL == 1 + kinetis_pinconfig(PIN_UART3_RTS); +# endif +# if CONFIG_UART3_OFLOWCONTROL == 1 + kinetis_pinconfig(PIN_UART3_CTS); +# endif # endif # ifdef CONFIG_KINETIS_UART4 kinetis_pinconfig(PIN_UART4_TX); kinetis_pinconfig(PIN_UART4_RX); +# if CONFIG_UART4_IFLOWCONTROL == 1 + kinetis_pinconfig(PIN_UART4_RTS); +# endif +# if CONFIG_UART4_OFLOWCONTROL == 1 + kinetis_pinconfig(PIN_UART4_CTS); +# endif # endif # ifdef CONFIG_KINETIS_UART5 kinetis_pinconfig(PIN_UART5_TX); kinetis_pinconfig(PIN_UART5_RX); +# if CONFIG_UART5_IFLOWCONTROL == 1 + kinetis_pinconfig(PIN_UART5_RTS); +# endif +# if CONFIG_UART5_OFLOWCONTROL == 1 + kinetis_pinconfig(PIN_UART5_CTS); +# endif # endif /* Configure the console (only) now. Other UARTs will be configured @@ -300,7 +405,8 @@ void kinetis_lowsetup(void) # if defined(HAVE_UART_CONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG) kinetis_uartconfigure(CONSOLE_BASE, CONSOLE_BAUD, CONSOLE_FREQ, \ - CONSOLE_PARITY, CONSOLE_BITS, CONSOLE_2STOP); + CONSOLE_PARITY, CONSOLE_BITS, CONSOLE_2STOP, \ + CONSOLE_IFLOW, CONSOLE_OFLOW); # endif #endif /* HAVE_UART_DEVICE */ @@ -327,17 +433,30 @@ void kinetis_lowsetup(void) # ifdef CONFIG_KINETIS_LPUART0 kinetis_pinconfig(PIN_LPUART0_TX); kinetis_pinconfig(PIN_LPUART0_RX); +# if CONFIG_LPUART0_IFLOWCONTROL == 1 + kinetis_pinconfig(PIN_LPUART0_RTS); +# endif +# if CONFIG_LPUART0_OFLOWCONTROL == 1 + kinetis_pinconfig(PIN_LOUART0_CTS); +# endif # endif # ifdef CONFIG_KINETIS_LPUART1 kinetis_pinconfig(PIN_LPUART1_TX); kinetis_pinconfig(PIN_LPUART1_RX); +# if CONFIG_LPUART1_IFLOWCONTROL == 1 + kinetis_pinconfig(PIN_LPUART1_RTS); +# endif +# if CONFIG_LPUART1_OFLOWCONTROL == 1 + kinetis_pinconfig(PIN_LOUART1_CTS); +# endif # endif # if defined(HAVE_LPUART_CONSOLE) && !defined(CONFIG_SUPPRESS_LPUART_CONFIG) kinetis_lpuartconfigure(CONSOLE_BASE, CONSOLE_BAUD, CONSOLE_FREQ, \ - CONSOLE_PARITY, CONSOLE_BITS, CONSOLE_2STOP); + CONSOLE_PARITY, CONSOLE_BITS, CONSOLE_2STOP, \ + CONSOLE_IFLOW, CONSOLE_OFLOW); # endif #endif /* HAVE_LPUART_DEVICE */ } @@ -395,7 +514,8 @@ void kinetis_lpuartreset(uintptr_t uart_base) #ifdef HAVE_UART_DEVICE void kinetis_uartconfigure(uintptr_t uart_base, uint32_t baud, uint32_t clock, unsigned int parity, - unsigned int nbits, unsigned int stop2) + unsigned int nbits, unsigned int stop2, + bool iflow, bool oflow) { uint32_t sbr; uint32_t brfa; @@ -542,6 +662,27 @@ void kinetis_uartconfigure(uintptr_t uart_base, uint32_t baud, putreg8(0, uart_base+KINETIS_UART_PFIFO_OFFSET); #endif + /* Hardware flow control */ + + regval = getreg8(uart_base+KINETIS_UART_MODEM_OFFSET); + regval &= ~(UART_MODEM_TXCTSE | UART_MODEM_RXRTSE); + +#ifdef CONFIG_SERIAL_IFLOWCONTROL + if (iflow) + { + regval |= UART_MODEM_RXRTSE; + } +#endif + +#ifdef CONFIG_SERIAL_OFLOWCONTROL + if (oflow) + { + regval |= UART_MODEM_TXCTSE; + } +#endif + + putreg8(regval, uart_base+KINETIS_UART_MODEM_OFFSET); + /* Now we can (re-)enable the transmitter and receiver */ regval = getreg8(uart_base+KINETIS_UART_C2_OFFSET); @@ -561,7 +702,8 @@ void kinetis_uartconfigure(uintptr_t uart_base, uint32_t baud, #ifdef HAVE_LPUART_DEVICE void kinetis_lpuartconfigure(uintptr_t uart_base, uint32_t baud, uint32_t clock, unsigned int parity, - unsigned int nbits, unsigned int stop2) + unsigned int nbits, unsigned int stop2, + bool iflow, bool oflow) { uint32_t sbrreg; uint32_t osrreg; @@ -711,6 +853,25 @@ void kinetis_lpuartconfigure(uintptr_t uart_base, uint32_t baud, DEBUGASSERT(nbits == 8); } + /* Hardware flow control */ + + regval = getreg32(uart_base+KINETIS_LPUART_MODIR_OFFSET); + regval &= ~(UART_MODEM_TXCTSE | UART_MODEM_RXRTSE); + +#ifdef CONFIG_SERIAL_IFLOWCONTROL + if (iflow) + { + regval |= LPUART_MODIR_RXRTSE; + } +#endif + #ifdef CONFIG_SERIAL_OFLOWCONTROL + if (oflow) + { + regval |= LPUART_MODIR_TXCTSE; + } +#endif + putreg32(regval, uart_base+KINETIS_LPUART_MODIR_OFFSET); + /* Now we can (re-)enable the transmitter and receiver */ regval |= (LPUART_CTRL_RE | LPUART_CTRL_TE); diff --git a/arch/arm/src/kinetis/kinetis_lpserial.c b/arch/arm/src/kinetis/kinetis_lpserial.c index 2980f18b8d..5a70582d41 100644 --- a/arch/arm/src/kinetis/kinetis_lpserial.c +++ b/arch/arm/src/kinetis/kinetis_lpserial.c @@ -53,6 +53,11 @@ #include #include +#ifdef CONFIG_SERIAL_TERMIOS +# include +#endif + +#include #include #include "up_arch.h" @@ -61,6 +66,7 @@ #include "kinetis_config.h" #include "chip.h" #include "chip/kinetis_lpuart.h" +#include "chip/kinetis_pinmux.h" #include "kinetis.h" /**************************************************************************** @@ -153,6 +159,18 @@ struct kinetis_dev_s uint8_t parity; /* 0=none, 1=odd, 2=even */ uint8_t bits; /* Number of bits (8 or 9) */ uint8_t stop2; /* Use 2 stop bits */ +#ifdef CONFIG_SERIAL_IFLOWCONTROL + bool iflow; /* input flow control (RTS) enabled */ +#endif +#ifdef CONFIG_SERIAL_OFLOWCONTROL + bool oflow; /* output flow control (CTS) enabled */ +#endif +#ifdef CONFIG_SERIAL_IFLOWCONTROL + uint32_t rts_gpio; /* UART RTS GPIO pin configuration */ +#endif +#ifdef CONFIG_SERIAL_OFLOWCONTROL + uint32_t cts_gpio; /* UART CTS GPIO pin configuration */ +#endif }; /**************************************************************************** @@ -168,6 +186,10 @@ static int kinetis_ioctl(struct file *filep, int cmd, unsigned long arg); static int kinetis_receive(struct uart_dev_s *dev, uint32_t *status); static void kinetis_rxint(struct uart_dev_s *dev, bool enable); static bool kinetis_rxavailable(struct uart_dev_s *dev); +#ifdef CONFIG_SERIAL_IFLOWCONTROL +static bool kinetis_rxflowcontrol(struct uart_dev_s *dev, unsigned int nbuffered, + bool upper); +#endif static void kinetis_send(struct uart_dev_s *dev, int ch); static void kinetis_txint(struct uart_dev_s *dev, bool enable); static bool kinetis_txready(struct uart_dev_s *dev); @@ -187,7 +209,7 @@ static const struct uart_ops_s g_lpuart_ops = .rxint = kinetis_rxint, .rxavailable = kinetis_rxavailable, #ifdef CONFIG_SERIAL_IFLOWCONTROL - .rxflowcontrol = NULL, + .rxflowcontrol = kinetis_rxflowcontrol, #endif .send = kinetis_send, .txint = kinetis_txint, @@ -219,6 +241,14 @@ static struct kinetis_dev_s g_lpuart0priv = .parity = CONFIG_LPUART0_PARITY, .bits = CONFIG_LPUART0_BITS, .stop2 = CONFIG_LPUART0_2STOP, +#if defined(CONFIG_SERIAL_OFLOWCONTROL) && defined(CONFIG_LPUART0_OFLOWCONTROL) + .oflow = true, + .cts_gpio = PIN_LPUART0_CTS, +#endif +#if defined(CONFIG_SERIAL_IFLOWCONTROL) && defined(CONFIG_LPUART0_IFLOWCONTROL) + .iflow = true, + .rts_gpio = PIN_LPUART0_RTS, +#endif }; static uart_dev_t g_lpuart0port = @@ -251,6 +281,14 @@ static struct kinetis_dev_s g_lpuart1priv = .parity = CONFIG_LPUART1_PARITY, .bits = CONFIG_LPUART1_BITS, .stop2 = CONFIG_LPUART1_2STOP, +#if defined(CONFIG_SERIAL_OFLOWCONTROL) && defined(CONFIG_LPUART1_OFLOWCONTROL) + .oflow = true, + .cts_gpio = PIN_LPUART1_CTS, +#endif +#if defined(CONFIG_SERIAL_IFLOWCONTROL) && defined(CONFIG_LPUART1_IFLOWCONTROL) + .iflow = true, + .rts_gpio = PIN_LPUART1_RTS, +#endif }; static uart_dev_t g_lpuart1port = @@ -360,11 +398,22 @@ static int kinetis_setup(struct uart_dev_s *dev) { #ifndef CONFIG_SUPPRESS_LPUART_CONFIG struct kinetis_dev_s *priv = (struct kinetis_dev_s *)dev->priv; +#ifdef CONFIG_SERIAL_IFLOWCONTROL + bool iflow = priv->iflow; +#else + bool iflow = false; +#endif +#ifdef CONFIG_SERIAL_OFLOWCONTROL + bool oflow = priv->oflow; +#else + bool oflow = false; +#endif /* Configure the LPUART as an RS-232 UART */ kinetis_lpuartconfigure(priv->uartbase, priv->baud, priv->clock, - priv->parity, priv->bits, priv->stop2); + priv->parity, priv->bits, priv->stop2, + iflow, oflow); #endif /* Make sure that all interrupts are disabled */ @@ -564,23 +613,234 @@ static int kinetis_interrupt(int irq, void *context, void *arg) static int kinetis_ioctl(struct file *filep, int cmd, unsigned long arg) { -#if 0 /* Reserved for future growth */ - struct inode *inode; - struct uart_dev_s *dev; - struct kinetis_dev_s *priv; - int ret = OK; +#if defined(CONFIG_SERIAL_TERMIOS) || defined(CONFIG_SERIAL_TIOCSERGSTRUCT) || \ + defined(CONFIG_KINETIS_SERIALBRK_BSDCOMPAT) + struct inode *inode = filep->f_inode; + struct uart_dev_s *dev = inode->i_private; + uint8_t regval; +#endif +#if defined(CONFIG_SERIAL_TERMIOS) || defined(CONFIG_KINETIS_SERIALBRK_BSDCOMPAT) + struct kinetis_dev_s *priv = (struct kinetis_dev_s *)dev->priv; + bool iflow = false; + bool oflow = false; +#endif + int ret = OK; - DEBUGASSERT(filep, filep->f_inode); +#if defined(CONFIG_SERIAL_TERMIOS) || defined(CONFIG_SERIAL_TIOCSERGSTRUCT) || \ + defined(CONFIG_KINETIS_SERIALBRK_BSDCOMPAT) + DEBUGASSERT(filep != NULL && filep->f_inode != NULL); inode = filep->f_inode; dev = inode->i_private; - - DEBUGASSERT(dev, dev->priv); - priv = (struct kinetis_dev_s *)dev->priv; + DEBUGASSERT(dev != NULL && dev->priv != NULL); +#endif switch (cmd) { - case xxx: /* Add commands here */ +#ifdef CONFIG_SERIAL_TIOCSERGSTRUCT + case TIOCSERGSTRUCT: + { + struct kinetis_dev_s *user = (struct kinetis_dev_s *)arg; + if (!user) + { + ret = -EINVAL; + } + else + { + memcpy(user, dev, sizeof(struct kinetis_dev_s)); + } + } break; +#endif + +#ifdef CONFIG_KINETIS_UART_SINGLEWIRE + case TIOCSSINGLEWIRE: + { + /* Change to single-wire operation. the RXD pin is disconnected from + * the UART and the UART implements a half-duplex serial connection. + * The UART uses the TXD pin for both receiving and transmitting + */ + + regval = kinetis_serialin(priv, KINETIS_LPUART_CTRL_OFFSET); + + if (arg == SER_SINGLEWIRE_ENABLED) + { + regval |= (LPUART_CTRL_LOOPS | LPUART_CTRL_RSRC); + } + else + { + regval &= ~(LPUART_CTRL_LOOPS | LPUART_CTRL_RSRC); + } + kinetis_serialout(priv, KINETIS_LPUART_CTRL_OFFSET, regval); + } + break; +#endif + +#ifdef CONFIG_SERIAL_TERMIOS + case TCGETS: + { + struct termios *termiosp = (struct termios *)arg; + + if (!termiosp) + { + ret = -EINVAL; + break; + } + + cfsetispeed(termiosp, priv->baud); + + /* Note: CSIZE only supports 5-8 bits. The driver only support 8/9 bit + * modes and therefore is no way to report 9-bit mode, we always claim + * 8 bit mode. + */ + + termiosp->c_cflag = + ((priv->parity != 0) ? PARENB : 0) | + ((priv->parity == 1) ? PARODD : 0) | + ((priv->stop2) ? CSTOPB : 0) | +# ifdef CONFIG_SERIAL_OFLOWCONTROL + ((priv->oflow) ? CCTS_OFLOW : 0) | +# endif +# ifdef CONFIG_SERIAL_IFLOWCONTROL + ((priv->iflow) ? CRTS_IFLOW : 0) | +# endif + CS8; + + /* TODO: CCTS_IFLOW, CCTS_OFLOW */ + } + break; + + case TCSETS: + { + struct termios *termiosp = (struct termios *)arg; + + if (!termiosp) + { + ret = -EINVAL; + break; + } + + /* Perform some sanity checks before accepting any changes */ + + if (((termiosp->c_cflag & CSIZE) != CS8) +# ifdef CONFIG_SERIAL_IFLOWCONTROL + || ((termiosp->c_cflag & CCTS_OFLOW) && (priv->cts_gpio == 0)) +# endif +# ifdef CONFIG_SERIAL_IFLOWCONTROL + || ((termiosp->c_cflag & CRTS_IFLOW) && (priv->rts_gpio == 0)) +# endif + ) + { + ret = -EINVAL; + break; + } + + if (termiosp->c_cflag & PARENB) + { + priv->parity = (termiosp->c_cflag & PARODD) ? 1 : 2; + } + else + { + priv->parity = 0; + } + + priv->stop2 = (termiosp->c_cflag & CSTOPB) != 0; +# ifdef CONFIG_SERIAL_OFLOWCONTROL + priv->oflow = (termiosp->c_cflag & CCTS_OFLOW) != 0; + oflow = priv->oflow; +# endif +# ifdef CONFIG_SERIAL_IFLOWCONTROL + priv->iflow = (termiosp->c_cflag & CRTS_IFLOW) != 0; + iflow = priv->iflow; +# endif + + /* Note that since there is no way to request 9-bit mode + * and no way to support 5/6/7-bit modes, we ignore them + * all here. + */ + + /* Note that only cfgetispeed is used because we have knowledge + * that only one speed is supported. + */ + + priv->baud = cfgetispeed(termiosp); + + /* Effect the changes immediately - note that we do not implement + * TCSADRAIN / TCSAFLUSH + */ + + kinetis_uartconfigure(priv->uartbase, priv->baud, priv->clock, + priv->parity, priv->bits, priv->stop2, + iflow, oflow); + } + break; +#endif /* CONFIG_SERIAL_TERMIOS */ + +#ifdef CONFIG_KINETIS_UART_BREAKS + case TIOCSBRK: + { + irqstate_t flags; + + flags = enter_critical_section(); + + /* Send a longer break signal */ + + regval = kinetis_serialin(priv, KINETIS_LPUART_STAT_OFFSET); + regval &= ~LPUART_STAT_BRK13; +# ifdef CONFIG_KINETIS_UART_EXTEDED_BREAK + regval |= LPUART_STAT_BRK13; +# endif + kinetis_serialout(priv, LPUART_STAT_BRK13, regval); + + /* Send a break signal */ + + regval = kinetis_serialin(priv, KINETIS_LPUART_CTRL_OFFSET); + regval |= LPUART_CTRL_SBK; + kinetis_serialout(priv, KINETIS_LPUART_CTRL_OFFSET, regval); + +# ifdef CONFIG_KINETIS_SERIALBRK_BSDCOMPAT + /* BSD compatibility: Turn break on, and leave it on */ + + kinetis_txint(dev, false); +# else + /* Send a single break character + * Toggling SBK sends one break character. Per the manual + * Toggling implies clearing the SBK field before the break + * character has finished transmitting. + */ + + regval &= ~LPUART_CTRL_SBK; + kinetis_serialout(priv, KINETIS_LPUART_CTRL_OFFSET, regval); +#endif + + leave_critical_section(flags); + } + break; + + case TIOCCBRK: + { + irqstate_t flags; + + flags = enter_critical_section(); + + /* Configure TX back to UART + * If non BSD compatible: This code has no effect, the SBRK + * was already cleared. + * but for BSD compatibility: Turn break off + */ + + regval = kinetis_serialin(priv, KINETIS_LPUART_CTRL_OFFSET); + regval &= ~LPUART_CTRL_SBK; + kinetis_serialout(priv, KINETIS_LPUART_CTRL_OFFSET, regval); + +# ifdef CONFIG_KINETIS_SERIALBRK_BSDCOMPAT + /* Enable further tx activity */ + + kinetis_txint(dev, true); +# endif + leave_critical_section(flags); + } + break; +#endif /* CONFIG_KINETIS_UART_BREAKS */ default: ret = -ENOTTY; @@ -588,9 +848,6 @@ static int kinetis_ioctl(struct file *filep, int cmd, unsigned long arg) } return ret; -#else - return -ENOTTY; -#endif } /**************************************************************************** @@ -696,6 +953,79 @@ static bool kinetis_rxavailable(struct uart_dev_s *dev) return (kinetis_serialin(priv, KINETIS_LPUART_STAT_OFFSET) & LPUART_STAT_RDRF) != 0; } +/**************************************************************************** + * Name: kinetis_rxflowcontrol + * + * Description: + * Called when Rx buffer is full (or exceeds configured watermark levels + * if CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS is defined). + * Return true if UART activated RX flow control to block more incoming + * data + * + * Input parameters: + * dev - UART device instance + * nbuffered - the number of characters currently buffered + * (if CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS is + * not defined the value will be 0 for an empty buffer or the + * defined buffer size for a full buffer) + * upper - true indicates the upper watermark was crossed where + * false indicates the lower watermark has been crossed + * + * Returned Value: + * true if RX flow control activated. + * + ****************************************************************************/ + +#ifdef CONFIG_SERIAL_IFLOWCONTROL +static bool kinetis_rxflowcontrol(struct uart_dev_s *dev, + unsigned int nbuffered, bool upper) +{ +#if defined(CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS) + struct kinetis_dev_s *priv = (struct kinetis_dev_s *)dev->priv; + uint16_t ie; + + if (priv->iflow) + { + /* Is the RX buffer full? */ + + if (upper) + { + /* Disable Rx interrupt to prevent more data being from + * peripheral. When hardware RTS is enabled, this will + * prevent more data from coming in. + * + * This function is only called when UART recv buffer is full, + * that is: "dev->recv.head + 1 == dev->recv.tail". + * + * Logic in "uart_read" will automatically toggle Rx interrupts + * when buffer is read empty and thus we do not have to re- + * enable Rx interrupts. + */ + + ie = priv->ie; + ie &= ~LPUART_CTRL_RX_INTS; + kinetis_restoreuartint(priv, ie); + return true; + } + + /* No.. The RX buffer is empty */ + + else + { + /* We might leave Rx interrupt disabled if full recv buffer was + * read empty. Enable Rx interrupt to make sure that more input is + * received. + */ + + kinetis_rxint(dev, true); + } + } +#endif + + return false; +} +#endif + /**************************************************************************** * Name: kinetis_send * diff --git a/arch/arm/src/kinetis/kinetis_serial.c b/arch/arm/src/kinetis/kinetis_serial.c index 79f0030b78..b7c6aeebc7 100644 --- a/arch/arm/src/kinetis/kinetis_serial.c +++ b/arch/arm/src/kinetis/kinetis_serial.c @@ -53,6 +53,11 @@ #include #include +#ifdef CONFIG_SERIAL_TERMIOS +# include +#endif + +#include #include #include "up_arch.h" @@ -61,6 +66,7 @@ #include "kinetis_config.h" #include "chip.h" #include "chip/kinetis_uart.h" +#include "chip/kinetis_pinmux.h" #include "kinetis.h" /**************************************************************************** @@ -242,6 +248,18 @@ struct up_dev_s uint8_t parity; /* 0=none, 1=odd, 2=even */ uint8_t bits; /* Number of bits (8 or 9) */ uint8_t stop2; /* Use 2 stop bits */ +#ifdef CONFIG_SERIAL_IFLOWCONTROL + bool iflow; /* input flow control (RTS) enabled */ +#endif +#ifdef CONFIG_SERIAL_OFLOWCONTROL + bool oflow; /* output flow control (CTS) enabled */ +#endif +#ifdef CONFIG_SERIAL_IFLOWCONTROL + uint32_t rts_gpio; /* UART RTS GPIO pin configuration */ +#endif +#ifdef CONFIG_SERIAL_OFLOWCONTROL + uint32_t cts_gpio; /* UART CTS GPIO pin configuration */ +#endif }; /**************************************************************************** @@ -260,6 +278,10 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg); static int up_receive(struct uart_dev_s *dev, uint32_t *status); static void up_rxint(struct uart_dev_s *dev, bool enable); static bool up_rxavailable(struct uart_dev_s *dev); +#ifdef CONFIG_SERIAL_IFLOWCONTROL +static bool up_rxflowcontrol(struct uart_dev_s *dev, unsigned int nbuffered, + bool upper); +#endif static void up_send(struct uart_dev_s *dev, int ch); static void up_txint(struct uart_dev_s *dev, bool enable); static bool up_txready(struct uart_dev_s *dev); @@ -282,7 +304,7 @@ static const struct uart_ops_s g_uart_ops = .rxint = up_rxint, .rxavailable = up_rxavailable, #ifdef CONFIG_SERIAL_IFLOWCONTROL - .rxflowcontrol = NULL, + .rxflowcontrol = up_rxflowcontrol, #endif .send = up_send, .txint = up_txint, @@ -337,6 +359,14 @@ static struct up_dev_s g_uart0priv = .parity = CONFIG_UART0_PARITY, .bits = CONFIG_UART0_BITS, .stop2 = CONFIG_UART0_2STOP, +#if defined(CONFIG_SERIAL_OFLOWCONTROL) && defined(CONFIG_UART0_OFLOWCONTROL) + .oflow = true, + .cts_gpio = PIN_UART0_CTS, +#endif +#if defined(CONFIG_SERIAL_IFLOWCONTROL) && defined(CONFIG_UART0_IFLOWCONTROL) + .iflow = true, + .rts_gpio = PIN_UART0_RTS, +#endif }; static uart_dev_t g_uart0port = @@ -372,6 +402,14 @@ static struct up_dev_s g_uart1priv = .parity = CONFIG_UART1_PARITY, .bits = CONFIG_UART1_BITS, .stop2 = CONFIG_UART1_2STOP, +#if defined(CONFIG_SERIAL_OFLOWCONTROL) && defined(CONFIG_UART1_OFLOWCONTROL) + .oflow = true, + .cts_gpio = PIN_UART1_CTS, +#endif +#if defined(CONFIG_SERIAL_IFLOWCONTROL) && defined(CONFIG_UART1_IFLOWCONTROL) + .iflow = true, + .rts_gpio = PIN_UART1_RTS, +#endif }; static uart_dev_t g_uart1port = @@ -407,6 +445,14 @@ static struct up_dev_s g_uart2priv = .parity = CONFIG_UART2_PARITY, .bits = CONFIG_UART2_BITS, .stop2 = CONFIG_UART2_2STOP, +#if defined(CONFIG_SERIAL_OFLOWCONTROL) && defined(CONFIG_UART2_OFLOWCONTROL) + .oflow = true, + .cts_gpio = PIN_UART2_CTS, +#endif +#if defined(CONFIG_SERIAL_IFLOWCONTROL) && defined(CONFIG_UART2_IFLOWCONTROL) + .iflow = true, + .rts_gpio = PIN_UART2_RTS, +#endif }; static uart_dev_t g_uart2port = @@ -442,6 +488,14 @@ static struct up_dev_s g_uart3priv = .parity = CONFIG_UART3_PARITY, .bits = CONFIG_UART3_BITS, .stop2 = CONFIG_UART3_2STOP, +#if defined(CONFIG_SERIAL_OFLOWCONTROL) && defined(CONFIG_UART3_OFLOWCONTROL) + .oflow = true, + .cts_gpio = PIN_UART3_CTS, +#endif +#if defined(CONFIG_SERIAL_IFLOWCONTROL) && defined(CONFIG_UART3_IFLOWCONTROL) + .iflow = true, + .rts_gpio = PIN_UART3_RTS, +#endif }; static uart_dev_t g_uart3port = @@ -477,6 +531,14 @@ static struct up_dev_s g_uart4priv = .parity = CONFIG_UART4_PARITY, .bits = CONFIG_UART4_BITS, .stop2 = CONFIG_UART4_2STOP, +#if defined(CONFIG_SERIAL_OFLOWCONTROL) && defined(CONFIG_UART4_OFLOWCONTROL) + .oflow = true, + .cts_gpio = PIN_UART4_CTS, +#endif +#if defined(CONFIG_SERIAL_IFLOWCONTROL) && defined(CONFIG_UART4_IFLOWCONTROL) + .iflow = true, + .rts_gpio = PIN_UART4_RTS, +#endif }; static uart_dev_t g_uart4port = @@ -512,6 +574,14 @@ static struct up_dev_s g_uart5priv = .parity = CONFIG_UART5_PARITY, .bits = CONFIG_UART5_BITS, .stop2 = CONFIG_UART5_2STOP, +#if defined(CONFIG_SERIAL_OFLOWCONTROL) && defined(CONFIG_UART5_OFLOWCONTROL) + .oflow = true, + .cts_gpio = PIN_UART5_CTS, +#endif +#if defined(CONFIG_SERIAL_IFLOWCONTROL) && defined(CONFIG_UART5_IFLOWCONTROL) + .iflow = true, + .rts_gpio = PIN_UART5_RTS, +#endif }; static uart_dev_t g_uart5port = @@ -621,11 +691,23 @@ static int up_setup(struct uart_dev_s *dev) { #ifndef CONFIG_SUPPRESS_UART_CONFIG struct up_dev_s *priv = (struct up_dev_s *)dev->priv; +#ifdef CONFIG_SERIAL_IFLOWCONTROL + bool iflow = priv->iflow; +#else + bool iflow = false; +#endif +#ifdef CONFIG_SERIAL_OFLOWCONTROL + bool oflow = priv->oflow; +#else + bool oflow = false; +#endif + /* Configure the UART as an RS-232 UART */ kinetis_uartconfigure(priv->uartbase, priv->baud, priv->clock, - priv->parity, priv->bits, priv->stop2); + priv->parity, priv->bits, priv->stop2, + iflow, oflow); #endif /* Make sure that all interrupts are disabled */ @@ -891,23 +973,235 @@ static int up_interrupts(int irq, void *context, FAR void *arg) static int up_ioctl(struct file *filep, int cmd, unsigned long arg) { -#if 0 /* Reserved for future growth */ +#if defined(CONFIG_SERIAL_TERMIOS) || defined(CONFIG_SERIAL_TIOCSERGSTRUCT) || \ + defined(CONFIG_KINETIS_SERIALBRK_BSDCOMPAT) struct inode *inode; struct uart_dev_s *dev; - struct up_dev_s *priv; - int ret = OK; + uint8_t regval; +#endif +#if defined(CONFIG_SERIAL_TERMIOS) || defined(CONFIG_KINETIS_SERIALBRK_BSDCOMPAT) + struct up_dev_s *priv = (struct up_dev_s *)dev->priv; + bool iflow = false; + bool oflow = false; +#endif + int ret = OK; - DEBUGASSERT(filep, filep->f_inode); +#if defined(CONFIG_SERIAL_TERMIOS) || defined(CONFIG_SERIAL_TIOCSERGSTRUCT) || \ + defined(CONFIG_KINETIS_SERIALBRK_BSDCOMPAT) + DEBUGASSERT(filep != NULL && filep->f_inode != NULL); inode = filep->f_inode; dev = inode->i_private; - - DEBUGASSERT(dev, dev->priv); - priv = (struct up_dev_s *)dev->priv; + DEBUGASSERT(dev != NULL && dev->priv != NULL); +#endif switch (cmd) { - case xxx: /* Add commands here */ +#ifdef CONFIG_SERIAL_TIOCSERGSTRUCT + case TIOCSERGSTRUCT: + { + struct up_dev_s *user = (struct up_dev_s *)arg; + if (!user) + { + ret = -EINVAL; + } + else + { + memcpy(user, dev, sizeof(struct up_dev_s)); + } + } + break; +#endif + +#ifdef CONFIG_KINETIS_UART_SINGLEWIRE + case TIOCSSINGLEWIRE: + { + /* Change to single-wire operation. the RXD pin is disconnected from + * the UART and the UART implements a half-duplex serial connection. + * The UART uses the TXD pin for both receiving and transmitting + */ + + regval = up_serialin(priv, KINETIS_UART_C1_OFFSET); + + if (arg == SER_SINGLEWIRE_ENABLED) + { + regval |= (UART_C1_LOOPS | UART_C1_RSRC); + } + else + { + regval &= ~(UART_C1_LOOPS | UART_C1_RSRC); + } + + up_serialout(priv, KINETIS_UART_C1_OFFSET, regval); + } + break; +#endif + +#ifdef CONFIG_SERIAL_TERMIOS + case TCGETS: + { + struct termios *termiosp = (struct termios *)arg; + + if (!termiosp) + { + ret = -EINVAL; + break; + } + + cfsetispeed(termiosp, priv->baud); + + /* Note: CSIZE only supports 5-8 bits. The driver only support 8/9 bit + * modes and therefore is no way to report 9-bit mode, we always claim + * 8 bit mode. + */ + + termiosp->c_cflag = + ((priv->parity != 0) ? PARENB : 0) | + ((priv->parity == 1) ? PARODD : 0) | + ((priv->stop2) ? CSTOPB : 0) | +# ifdef CONFIG_SERIAL_OFLOWCONTROL + ((priv->oflow) ? CCTS_OFLOW : 0) | +# endif +# ifdef CONFIG_SERIAL_IFLOWCONTROL + ((priv->iflow) ? CRTS_IFLOW : 0) | +# endif + CS8; + + /* TODO: CCTS_IFLOW, CCTS_OFLOW */ + } + break; + + case TCSETS: + { + struct termios *termiosp = (struct termios *)arg; + + if (!termiosp) + { + ret = -EINVAL; + break; + } + + /* Perform some sanity checks before accepting any changes */ + + if (((termiosp->c_cflag & CSIZE) != CS8) +# ifdef CONFIG_SERIAL_IFLOWCONTROL + || ((termiosp->c_cflag & CCTS_OFLOW) && (priv->cts_gpio == 0)) +# endif +# ifdef CONFIG_SERIAL_IFLOWCONTROL + || ((termiosp->c_cflag & CRTS_IFLOW) && (priv->rts_gpio == 0)) +# endif + ) + { + ret = -EINVAL; + break; + } + + if (termiosp->c_cflag & PARENB) + { + priv->parity = (termiosp->c_cflag & PARODD) ? 1 : 2; + } + else + { + priv->parity = 0; + } + + priv->stop2 = (termiosp->c_cflag & CSTOPB) != 0; +# ifdef CONFIG_SERIAL_OFLOWCONTROL + priv->oflow = (termiosp->c_cflag & CCTS_OFLOW) != 0; + oflow = priv->oflow; +# endif +# ifdef CONFIG_SERIAL_IFLOWCONTROL + priv->iflow = (termiosp->c_cflag & CRTS_IFLOW) != 0; + iflow = priv->iflow; +# endif + + /* Note that since there is no way to request 9-bit mode + * and no way to support 5/6/7-bit modes, we ignore them + * all here. + */ + + /* Note that only cfgetispeed is used because we have knowledge + * that only one speed is supported. + */ + + priv->baud = cfgetispeed(termiosp); + + /* Effect the changes immediately - note that we do not implement + * TCSADRAIN / TCSAFLUSH + */ + + kinetis_uartconfigure(priv->uartbase, priv->baud, priv->clock, + priv->parity, priv->bits, priv->stop2, + iflow, oflow); + } break; +#endif /* CONFIG_SERIAL_TERMIOS */ + +#ifdef CONFIG_KINETIS_UART_BREAKS + case TIOCSBRK: + { + irqstate_t flags; + + flags = enter_critical_section(); + + /* Send a longer break signal */ + + regval = up_serialin(priv, KINETIS_UART_S2_OFFSET); + regval &= ~UART_S2_BRK13; +# ifdef CONFIG_KINETIS_UART_EXTEDED_BREAK + regval |= UART_S2_BRK13; +# endif + up_serialout(priv, KINETIS_UART_S2_OFFSET, regval); + + /* Send a break signal */ + + regval = up_serialin(priv, KINETIS_UART_C2_OFFSET); + regval |= UART_C2_SBK; + up_serialout(priv, KINETIS_UART_C2_OFFSET, regval); + +# ifdef CONFIG_KINETIS_SERIALBRK_BSDCOMPAT + /* BSD compatibility: Turn break on, and leave it on */ + + up_txint(dev, false); +# else + /* Send a single break character + * Toggling SBK sends one break character. Per the manual + * Toggling implies clearing the SBK field before the break + * character has finished transmitting. + */ + + regval &= ~(UART_C2_SBK); + up_serialout(priv, KINETIS_UART_C2_OFFSET, regval); +#endif + + leave_critical_section(flags); + } + break; + + case TIOCCBRK: + { + irqstate_t flags; + + flags = enter_critical_section(); + + /* Configure TX back to UART + * If non BSD compatible: This code has no effect, the SBRK + * was already cleared. + * but for BSD compatibility: Turn break off + */ + + regval = up_serialin(priv, KINETIS_UART_C2_OFFSET); + regval &= ~UART_C2_SBK; + up_serialout(priv, KINETIS_UART_C2_OFFSET, regval); + +# ifdef CONFIG_KINETIS_SERIALBRK_BSDCOMPAT + /* Enable further tx activity */ + + up_txint(dev, true); +# endif + leave_critical_section(flags); + } + break; +#endif /* CONFIG_KINETIS_UART_BREAKS */ default: ret = -ENOTTY; @@ -915,9 +1209,6 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg) } return ret; -#else - return -ENOTTY; -#endif } /**************************************************************************** @@ -1030,6 +1321,79 @@ static bool up_rxavailable(struct uart_dev_s *dev) #endif } +/**************************************************************************** + * Name: up_rxflowcontrol + * + * Description: + * Called when Rx buffer is full (or exceeds configured watermark levels + * if CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS is defined). + * Return true if UART activated RX flow control to block more incoming + * data + * + * Input parameters: + * dev - UART device instance + * nbuffered - the number of characters currently buffered + * (if CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS is + * not defined the value will be 0 for an empty buffer or the + * defined buffer size for a full buffer) + * upper - true indicates the upper watermark was crossed where + * false indicates the lower watermark has been crossed + * + * Returned Value: + * true if RX flow control activated. + * + ****************************************************************************/ + +#ifdef CONFIG_SERIAL_IFLOWCONTROL +static bool up_rxflowcontrol(struct uart_dev_s *dev, + unsigned int nbuffered, bool upper) +{ +#if defined(CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS) + struct up_dev_s *priv = (struct up_dev_s *)dev->priv; + uint16_t ie; + + if (priv->iflow) + { + /* Is the RX buffer full? */ + + if (upper) + { + /* Disable Rx interrupt to prevent more data being from + * peripheral. When hardware RTS is enabled, this will + * prevent more data from coming in. + * + * This function is only called when UART recv buffer is full, + * that is: "dev->recv.head + 1 == dev->recv.tail". + * + * Logic in "uart_read" will automatically toggle Rx interrupts + * when buffer is read empty and thus we do not have to re- + * enable Rx interrupts. + */ + + ie = priv->ie; + ie &= ~UART_C2_RIE; + up_restoreuartint(priv, ie); + return true; + } + + /* No.. The RX buffer is empty */ + + else + { + /* We might leave Rx interrupt disabled if full recv buffer was + * read empty. Enable Rx interrupt to make sure that more input is + * received. + */ + + up_rxint(dev, true); + } + } +#endif + + return false; +} +#endif + /**************************************************************************** * Name: up_send * -- GitLab From 2c57c3f83ba1eacc49fc8ca587bc733d62789999 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Wed, 3 May 2017 21:49:59 -0400 Subject: [PATCH 725/990] wireless/ieee802154: Changes rxenable at radio layer --- drivers/wireless/ieee802154/mrf24j40.c | 37 ++++++++++++------- .../wireless/ieee802154/ieee802154_radio.h | 2 +- 2 files changed, 24 insertions(+), 15 deletions(-) diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c index c703933acc..9fb75cf03a 100644 --- a/drivers/wireless/ieee802154/mrf24j40.c +++ b/drivers/wireless/ieee802154/mrf24j40.c @@ -224,7 +224,7 @@ static int mrf24j40_bind(FAR struct ieee802154_radio_s *radio, FAR struct ieee802154_radiocb_s *radiocb); static int mrf24j40_ioctl(FAR struct ieee802154_radio_s *radio, int cmd, unsigned long arg); -static int mrf24j40_rxenable(FAR struct ieee802154_radio_s *radio); +static int mrf24j40_rxenable(FAR struct ieee802154_radio_s *radio bool enable); static int mrf24j40_txnotify_csma(FAR struct ieee802154_radio_s *radio); static int mrf24j40_txnotify_gts(FAR struct ieee802154_radio_s *radio); @@ -1336,8 +1336,6 @@ static int mrf24j40_csma_setup(FAR struct mrf24j40_radio_s *dev, uint8_t reg; int ret; - mrf24j40_pacontrol(dev, MRF24J40_PA_AUTO); - /* Enable tx int */ reg = mrf24j40_getreg(dev->spi, MRF24J40_INTCON); @@ -1534,22 +1532,31 @@ static void mrf24j40_irqwork_txgts(FAR struct mrf24j40_radio_s *dev, * Name: mrf24j40_rxenable * * Description: - * Enable reception of a packet. The interrupt will signal the rx semaphore. + * Enable/Disable receiver. * ****************************************************************************/ -static int mrf24j40_rxenable(FAR struct ieee802154_radio_s *radio) +static int mrf24j40_rxenable(FAR struct ieee802154_radio_s *radio, bool enable) { FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)radio; uint8_t reg; - mrf24j40_pacontrol(dev, MRF24J40_PA_AUTO); + if (enable) + { + /* Enable rx int */ - /* Enable rx int */ + reg = mrf24j40_getreg(dev->spi, MRF24J40_INTCON); + reg &= ~MRF24J40_INTCON_RXIE; + mrf24j40_setreg(dev->spi, MRF24J40_INTCON, reg); + } + else + { + /* Disable rx int */ - reg = mrf24j40_getreg(dev->spi, MRF24J40_INTCON); - reg &= ~MRF24J40_INTCON_RXIE; - mrf24j40_setreg(dev->spi, MRF24J40_INTCON, reg); + reg = mrf24j40_getreg(dev->spi, MRF24J40_INTCON); + reg |= MRF24J40_INTCON_RXIE; + mrf24j40_setreg(dev->spi, MRF24J40_INTCON, reg); + } return OK; } @@ -1570,15 +1577,13 @@ static void mrf24j40_irqwork_rx(FAR struct mrf24j40_radio_s *dev) uint32_t index; uint8_t reg; - /* wlinfo("!\n"); */ - /* Disable rx int */ reg = mrf24j40_getreg(dev->spi, MRF24J40_INTCON); reg |= MRF24J40_INTCON_RXIE; mrf24j40_setreg(dev->spi, MRF24J40_INTCON, reg); - /* Disable packet reception */ + /* Disable packet reception. See pg. 109 of datasheet */ mrf24j40_setreg(dev->spi, MRF24J40_BBREG1, MRF24J40_BBREG1_RXDECINV); @@ -1597,7 +1602,6 @@ static void mrf24j40_irqwork_rx(FAR struct mrf24j40_radio_s *dev) addr = MRF24J40_RXBUF_BASE; iob->io_len= mrf24j40_getreg(dev->spi, addr++); - /* wlinfo("len %3d\n", dev->radio.rxbuf->len); */ /* TODO: This needs to be changed. It is inefficient to do the SPI read byte * by byte */ @@ -1633,6 +1637,11 @@ static void mrf24j40_irqwork_rx(FAR struct mrf24j40_radio_s *dev) mrf24j40_setreg(dev->spi, MRF24J40_BBREG1, 0); + /* Enable rx int */ + + reg = mrf24j40_getreg(dev->spi, MRF24J40_INTCON); + reg &= ~MRF24J40_INTCON_RXIE; + mrf24j40_setreg(dev->spi, MRF24J40_INTCON, reg); } /**************************************************************************** diff --git a/include/nuttx/wireless/ieee802154/ieee802154_radio.h b/include/nuttx/wireless/ieee802154/ieee802154_radio.h index 9a80658664..50da135567 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_radio.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_radio.h @@ -215,7 +215,7 @@ struct ieee802154_radioops_s FAR struct ieee802154_radiocb_s *radiocb); CODE int (*ioctl)(FAR struct ieee802154_radio_s *radio, int cmd, unsigned long arg); - CODE int (*rxenable)(FAR struct ieee802154_radio_s *radio); + CODE int (*rxenable)(FAR struct ieee802154_radio_s *radio, bool enable); CODE int (*txnotify_csma)(FAR struct ieee802154_radio_s *radio); CODE int (*txnotify_gts)(FAR struct ieee802154_radio_s *radio); }; -- GitLab From abc15c84292d470b00df4a271a559492d2f14b93 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Wed, 3 May 2017 21:52:43 -0400 Subject: [PATCH 726/990] wireless/ieee802154: Finishes promiscuous mode IOCTL --- .../wireless/ieee802154/ieee802154_mac.h | 5 ++- wireless/ieee802154/mac802154.c | 34 +++++++++++++++---- 2 files changed, 32 insertions(+), 7 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index 87efa3662c..9ab06ada2f 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -227,7 +227,10 @@ enum ieee802154_status_e IEEE802154_STATUS_TRANSACTION_OVERFLOW, IEEE802154_STATUS_TX_ACTIVE, IEEE802154_STATUS_UNAVAILABLE_KEY, - IEEE802154_STATUS_UNSUPPORTED_ATTRIBUTE + IEEE802154_STATUS_UNSUPPORTED_ATTRIBUTE, + IEEE802154_STATUS_FAILED /* This value is not outlined in the standard. It is + * a catch-all for any failures that are not outlined + * in the standard */ }; /* IEEE 802.15.4 PHY/MAC PIB attributes IDs */ diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index 2b373a51da..be79dad029 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -1493,17 +1493,39 @@ int mac802154_req_set(MACHANDLE mac, FAR struct ieee802154_set_req_s *req) { case IEEE802154_PIB_MAC_EXTENDED_ADDR: { - /* Set the attribute in the structure to the new value */ + /* Update the radio's extended address */ - memcpy(&priv->addr.eaddr[0], &req->attr_value.eaddr[0], 8); + memcpy(&radio_arg.eaddr[0], &priv->addr.eaddr[0], 8); + ret = priv->radio->ops->ioctl(priv->radio, PHY802154IOC_SET_EADDR, + (unsigned long)&radio_arg); + if (ret < 0) + { + return -IEEE802154_STATUS_FAILED; + } + /* Set the attribute in the table */ - /* The radio device needs to be updated as well */ + memcpy(&priv->addr.eaddr[0], &req->attr_value.eaddr[0], 8); + + ret = IEEE802154_STATUS_SUCCESS; + } + break; + case IEEE802154_PIB_MAC_PROMISCUOUS_MODE: + { + /* Try and enable/disable promiscuous mode at the radio */ - memcpy(&radio_arg.eaddr[0], &priv->addr.eaddr[0], 8); - ret = priv->radio->ops->ioctl(priv->radio, PHY802154IOC_SET_EADDR, + radio_arg.promisc = priv->promisc_mode; + ret = priv->radio->ops->ioctl(priv->radio, PHY802154IOC_SET_PROMISC, (unsigned long)&radio_arg); - + if (ret < 0) + { + return -IEEE802154_STATUS_FAILED; + } + + /* Set the attribute in the table */ + + priv->promisc_mode = req->attr_value.promics_mode; + ret = IEEE802154_STATUS_SUCCESS; } break; -- GitLab From dd40014279f2976f205f65e1eb7e64cae43f460a Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Fri, 5 May 2017 11:15:28 -0400 Subject: [PATCH 727/990] wireless/ieee802154: Removes radio IOCTL. Starts bringing radio and MAC closer with well-defined interface. --- configs/clicker2-stm32/src/stm32_mrf24j40.c | 14 - drivers/wireless/ieee802154/at86rf23x.c | 97 ---- drivers/wireless/ieee802154/mrf24j40.c | 314 +++++------ include/nuttx/fs/ioctl.h | 7 - .../wireless/ieee802154/ieee802154_mac.h | 105 +++- .../wireless/ieee802154/ieee802154_radio.h | 165 +----- include/sys/ioctl.h | 5 - net/netdev/netdev_ioctl.c | 18 +- net/sixlowpan/sixlowpan_utils.c | 13 +- wireless/ieee802154/Kconfig | 8 - wireless/ieee802154/Make.defs | 2 - wireless/ieee802154/mac802154.c | 114 ++-- wireless/ieee802154/mac802154.h | 3 +- wireless/ieee802154/mac802154_loopback.c | 27 - wireless/ieee802154/mac802154_netdev.c | 14 - wireless/ieee802154/radio802154_device.c | 512 ------------------ wireless/ieee802154/radio802154_ioctl.c | 487 ----------------- wireless/ieee802154/radio802154_ioctl.h | 255 --------- 18 files changed, 270 insertions(+), 1890 deletions(-) delete mode 100644 wireless/ieee802154/radio802154_device.c delete mode 100644 wireless/ieee802154/radio802154_ioctl.c delete mode 100644 wireless/ieee802154/radio802154_ioctl.h diff --git a/configs/clicker2-stm32/src/stm32_mrf24j40.c b/configs/clicker2-stm32/src/stm32_mrf24j40.c index 18751e27dc..c92b93239b 100644 --- a/configs/clicker2-stm32/src/stm32_mrf24j40.c +++ b/configs/clicker2-stm32/src/stm32_mrf24j40.c @@ -47,7 +47,6 @@ #include #include -#include #include #include @@ -84,8 +83,6 @@ # endif #endif -#define RADIO_DEVNAME "/dev/mrf24j40" - /**************************************************************************** * Private Types ****************************************************************************/ @@ -287,18 +284,7 @@ static int stm32_mrf24j40_devsetup(FAR struct stm32_priv_s *priv) return ret; } #endif -#elif defined(CONFIG_IEEE802154_DEV) - /* Register a character driver to access the IEEE 802.15.4 radio from - * user-space - */ - ret = radio802154dev_register(radio, RADIO_DEVNAME); - if (ret < 0) - { - wlerr("ERROR: Failed to register the radio device %s: %d\n", - RADIO_DEVNAME, ret); - return ret; - } #endif /* CONFIG_IEEE802154_MAC */ return OK; diff --git a/drivers/wireless/ieee802154/at86rf23x.c b/drivers/wireless/ieee802154/at86rf23x.c index 24a4d5ca39..90d99351ba 100644 --- a/drivers/wireless/ieee802154/at86rf23x.c +++ b/drivers/wireless/ieee802154/at86rf23x.c @@ -148,7 +148,6 @@ static void at86rf23x_irqwork_tx(FAR struct at86rf23x_dev_s *dev); static void at86rf23x_irqworker(FAR void *arg); static int at86rf23x_interrupt(int irq, FAR void *context, FAR void *arg); -/* IOCTL helpers */ static int at86rf23x_setchannel(FAR struct ieee802154_radio_s *ieee, uint8_t chan); @@ -187,8 +186,6 @@ static int at86rf23x_energydetect(FAR struct ieee802154_radio_s *ieee, /* Driver operations */ -static int at86rf23x_ioctl(FAR struct ieee802154_radio_s *ieee, int cmd, - unsigned long arg); static int at86rf23x_rxenable(FAR struct ieee802154_radio_s *ieee, bool state, FAR struct ieee802154_packet_s *packet); static int at86rf23x_transmit(FAR struct ieee802154_radio_s *ieee, @@ -1147,100 +1144,6 @@ static int at86rf23x_energydetect(FAR struct ieee802154_radio_s *ieee, return ERROR; } -/**************************************************************************** - * Name: at86rf23x_ioctl - * - * Description: - * Control operations for the radio. - * - ****************************************************************************/ - -static int at86rf23x_ioctl(FAR struct ieee802154_radio_s *ieee, int cmd, - unsigned long arg) -{ - FAR struct at86rf23x_dev_s *dev = - (FAR struct at86rf23x_dev_s *)ieee; - FAR union ieee802154_radioarg_u *u; = - (FAR union ieee802154_radioarg_u *)((uintptr_t)arg) - - switch (cmd) - { - case PHY802154IOC_SET_CHAN: - ret = at86rf23x_setchannel(ieee, u.channel); - break; - - case PHY802154IOC_GET_CHAN: - ret = at86rf23x_getchannel(ieee, &u.channel); - break; - - case PHY802154IOC_SET_PANID: - ret = at86rf23x_setpanid(ieee, u.panid); - break; - - case PHY802154IOC_GET_PANID: - ret = at86rf23x_getpanid(ieee, &u.panid); - break; - - case PHY802154IOC_SET_SADDR: - ret = at86rf23x_setsaddr(ieee, u.saddr); - break; - - case PHY802154IOC_GET_SADDR: - ret = at86rf23x_getsaddr(ieee, &u.saddr); - break; - - case PHY802154IOC_SET_EADDR: - ret = at86rf23x_seteaddr(ieee, u.eaddr); - break; - - case PHY802154IOC_GET_EADDR: - ret = at86rf23x_geteaddr(ieee, u.eaddr); - break; - - case PHY802154IOC_SET_PROMISC: - ret = at86rf23x_setpromisc(ieee, u.promisc); - break; - - case PHY802154IOC_GET_PROMISC: - ret = at86rf23x_getpromisc(ieee, &u.promisc); - break; - - case PHY802154IOC_SET_DEVMODE: - ret = at86rf23x_setdevmode(ieee, u.devmode); - break; - - case PHY802154IOC_GET_DEVMODE: - ret = at86rf23x_getdevmode(ieee, &u.devmode); - break; - - case PHY802154IOC_SET_TXPWR: - ret = at86rf23x_settxpower(ieee, u.txpwr); - break; - - case PHY802154IOC_GET_TXPWR: - ret = at86rf23x_gettxpower(ieee, &u.txpwr); - break; - - case PHY802154IOC_SET_CCA: - ret = at86rf23x_setcca(ieee, &u.cca); - break; - - case PHY802154IOC_GET_CCA: - ret = at86rf23x_getcca(ieee, &u.cca); - break; - - case PHY802154IOC_ENERGYDETECT: - ret = at86rf23x_energydetect(ieee, &u.energy); - break; - - case 1000: - return at86rf23x_regdump(dev); - - default: - return -ENOTTY; - } -} - /**************************************************************************** * Name: at86rf23x_initialize * diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c index 9fb75cf03a..366471cd9c 100644 --- a/drivers/wireless/ieee802154/mrf24j40.c +++ b/drivers/wireless/ieee802154/mrf24j40.c @@ -2,6 +2,7 @@ * drivers/wireless/ieee802154/mrf24j40.c * * Copyright (C) 2015-2016 Sebastien Lorquet. All rights reserved. + * Copyright (C) 2017 Verge Inc. All rights reserved. * Author: Sebastien Lorquet * Author: Anthony Merlino * @@ -90,6 +91,10 @@ #define MRF24J40_RXMODE_PROMISC 1 #define MRF24J40_RXMODE_NOCRC 2 +#define MRF24J40_MODE_DEVICE 0 +#define MRF24J40_MODE_COORD 1 +#define MRF24J40_MODE_PANCOORD 2 + /* Definitions for PA control on high power modules */ #define MRF24J40_PA_AUTO 1 @@ -125,9 +130,8 @@ struct mrf24j40_radio_s struct work_s pollwork; /* For deferring poll work to the work queue */ sem_t exclsem; /* Exclusive access to this struct */ - uint16_t panid; /* PAN identifier, FFFF = not set */ - uint16_t saddr; /* short address, FFFF = not set */ - uint8_t eaddr[8]; /* extended address, FFFFFFFFFFFFFFFF = not set */ + struct ieee802154_addr_s addr; + uint8_t channel; /* 11 to 26 for the 2.4 GHz band */ uint8_t devmode; /* device mode: device, coord, pancoord */ uint8_t paenabled; /* enable usage of PA */ @@ -181,7 +185,6 @@ static int mrf24j40_gts_setup(FAR struct mrf24j40_radio_s *dev, uint8_t gts, static int mrf24j40_setup_fifo(FAR struct mrf24j40_radio_s *dev, FAR struct iob_s *frame, uint32_t fifo_addr); -/* IOCTL helpers */ static int mrf24j40_setchannel(FAR struct mrf24j40_radio_s *radio, uint8_t chan); @@ -196,7 +199,7 @@ static int mrf24j40_setsaddr(FAR struct mrf24j40_radio_s *radio, static int mrf24j40_getsaddr(FAR struct mrf24j40_radio_s *radio, FAR uint16_t *saddr); static int mrf24j40_seteaddr(FAR struct mrf24j40_radio_s *radio, - FAR uint8_t *eaddr); + FAR const uint8_t *eaddr); static int mrf24j40_geteaddr(FAR struct mrf24j40_radio_s *radio, FAR uint8_t *eaddr); static int mrf24j40_setpromisc(FAR struct mrf24j40_radio_s *radio, @@ -222,11 +225,14 @@ static int mrf24j40_energydetect(FAR struct mrf24j40_radio_s *radio, static int mrf24j40_bind(FAR struct ieee802154_radio_s *radio, FAR struct ieee802154_radiocb_s *radiocb); -static int mrf24j40_ioctl(FAR struct ieee802154_radio_s *radio, int cmd, - unsigned long arg); -static int mrf24j40_rxenable(FAR struct ieee802154_radio_s *radio bool enable); static int mrf24j40_txnotify_csma(FAR struct ieee802154_radio_s *radio); static int mrf24j40_txnotify_gts(FAR struct ieee802154_radio_s *radio); +static int mrf24j40_get_attr(FAR struct ieee802154_radio_s *radio, + enum ieee802154_pib_attr_e pib_attr, + FAR union ieee802154_attr_val_u *attr_value); +static int mrf24j40_set_attr(FAR struct ieee802154_radio_s *radio, + enum ieee802154_pib_attr_e pib_attr, + FAR const union ieee802154_attr_val_u *attr_value); /**************************************************************************** * Private Data @@ -242,14 +248,14 @@ static int mrf24j40_txnotify_gts(FAR struct ieee802154_radio_s *radio); static const struct ieee802154_radioops_s mrf24j40_devops = { mrf24j40_bind, - mrf24j40_ioctl, - mrf24j40_rxenable, mrf24j40_txnotify_csma, mrf24j40_txnotify_gts, + mrf24j40_get_attr, + mrf24j40_set_attr }; /**************************************************************************** - * Private Functions + * Radio Interface Functions ****************************************************************************/ static int mrf24j40_bind(FAR struct ieee802154_radio_s *radio, @@ -299,6 +305,103 @@ static int mrf24j40_txnotify_csma(FAR struct ieee802154_radio_s *radio) return OK; } +/**************************************************************************** + * Function: mrf24j40_txnotify_gts + * + * Description: + * Driver callback invoked when new TX data is available. This is a + * stimulus perform an out-of-cycle poll and, thereby, reduce the TX + * latency. + * + * Parameters: + * radio - Reference to the radio driver state structure + * + * Returned Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +static int mrf24j40_txnotify_gts(FAR struct ieee802154_radio_s *radio) +{ + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)radio; + + /* Is our single work structure available? It may not be if there are + * pending interrupt actions and we will have to ignore the Tx + * availability action. + */ + + if (work_available(&dev->pollwork)) + { + /* Schedule to serialize the poll on the worker thread. */ + + work_queue(HPWORK, &dev->pollwork, mrf24j40_dopoll_gts, dev, 0); + } + + return OK; +} + +static int mrf24j40_get_attr(FAR struct ieee802154_radio_s *radio, + enum ieee802154_pib_attr_e pib_attr, + FAR union ieee802154_attr_val_u *attr_value) +{ + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)radio; + int ret; + + switch (pib_attr) + { + case IEEE802154_PIB_MAC_EXTENDED_ADDR: + { + memcpy(&attr_value->mac.eaddr[0], &dev->addr.eaddr[0], 8); + ret = IEEE802154_STATUS_SUCCESS; + } + break; + default: + ret = IEEE802154_STATUS_UNSUPPORTED_ATTRIBUTE; + } + return ret; +} + +static int mrf24j40_set_attr(FAR struct ieee802154_radio_s *radio, + enum ieee802154_pib_attr_e pib_attr, + FAR const union ieee802154_attr_val_u *attr_value) +{ + FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)radio; + int ret; + + switch (pib_attr) + { + case IEEE802154_PIB_MAC_EXTENDED_ADDR: + { + mrf24j40_seteaddr(dev, &attr_value->mac.eaddr[0]); + ret = IEEE802154_STATUS_SUCCESS; + } + break; + case IEEE802154_PIB_MAC_PROMISCUOUS_MODE: + { + if (attr_value->mac.promisc_mode) + { + mrf24j40_setrxmode(dev, MRF24J40_RXMODE_PROMISC); + } + else + { + mrf24j40_setrxmode(dev, MRF24J40_RXMODE_NORMAL); + } + + ret = IEEE802154_STATUS_SUCCESS; + } + break; + default: + ret = IEEE802154_STATUS_UNSUPPORTED_ATTRIBUTE; + } + return ret; +} + +/**************************************************************************** + * Internal Functions + ****************************************************************************/ + /**************************************************************************** * Function: mrf24j40_dopoll_csma * @@ -353,43 +456,6 @@ static void mrf24j40_dopoll_csma(FAR void *arg) sem_post(&dev->exclsem); } -/**************************************************************************** - * Function: mrf24j40_txnotify_gts - * - * Description: - * Driver callback invoked when new TX data is available. This is a - * stimulus perform an out-of-cycle poll and, thereby, reduce the TX - * latency. - * - * Parameters: - * radio - Reference to the radio driver state structure - * - * Returned Value: - * None - * - * Assumptions: - * - ****************************************************************************/ - -static int mrf24j40_txnotify_gts(FAR struct ieee802154_radio_s *radio) -{ - FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)radio; - - /* Is our single work structure available? It may not be if there are - * pending interrupt actions and we will have to ignore the Tx - * availability action. - */ - - if (work_available(&dev->pollwork)) - { - /* Schedule to serialize the poll on the worker thread. */ - - work_queue(HPWORK, &dev->pollwork, mrf24j40_dopoll_gts, dev, 0); - } - - return OK; -} - /**************************************************************************** * Function: mrf24j40_dopoll_gts * @@ -772,7 +838,7 @@ static int mrf24j40_setpanid(FAR struct mrf24j40_radio_s *dev, mrf24j40_setreg(dev->spi, MRF24J40_PANIDH, (uint8_t)(panid>>8)); mrf24j40_setreg(dev->spi, MRF24J40_PANIDL, (uint8_t)(panid&0xFF)); - dev->panid = panid; + dev->addr.panid = panid; wlinfo("%04X\n", (unsigned)panid); return OK; @@ -789,7 +855,7 @@ static int mrf24j40_setpanid(FAR struct mrf24j40_radio_s *dev, static int mrf24j40_getpanid(FAR struct mrf24j40_radio_s *dev, FAR uint16_t *panid) { - *panid = dev->panid; + *panid = dev->addr.panid; return OK; } @@ -810,7 +876,7 @@ static int mrf24j40_setsaddr(FAR struct mrf24j40_radio_s *dev, mrf24j40_setreg(dev->spi, MRF24J40_SADRH, (uint8_t)(saddr>>8)); mrf24j40_setreg(dev->spi, MRF24J40_SADRL, (uint8_t)(saddr&0xFF)); - dev->saddr = saddr; + dev->addr.saddr = saddr; wlinfo("%04X\n", (unsigned)saddr); return OK; } @@ -826,7 +892,7 @@ static int mrf24j40_setsaddr(FAR struct mrf24j40_radio_s *dev, static int mrf24j40_getsaddr(FAR struct mrf24j40_radio_s *dev, FAR uint16_t *saddr) { - *saddr = dev->saddr; + *saddr = dev->addr.saddr; return OK; } @@ -841,14 +907,14 @@ static int mrf24j40_getsaddr(FAR struct mrf24j40_radio_s *dev, ****************************************************************************/ static int mrf24j40_seteaddr(FAR struct mrf24j40_radio_s *dev, - FAR uint8_t *eaddr) + FAR const uint8_t *eaddr) { int i; for (i = 0; i < 8; i++) { mrf24j40_setreg(dev->spi, MRF24J40_EADR0 + i, eaddr[i]); - dev->eaddr[i] = eaddr[i]; + dev->addr.eaddr[i] = eaddr[i]; } return OK; @@ -865,39 +931,7 @@ static int mrf24j40_seteaddr(FAR struct mrf24j40_radio_s *dev, static int mrf24j40_geteaddr(FAR struct mrf24j40_radio_s *dev, FAR uint8_t *eaddr) { - memcpy(eaddr, dev->eaddr, 8); - - return OK; -} - -/**************************************************************************** - * Name: mrf24j40_setpromisc - * - * Description: - * Set the device into promiscuous mode, e.g do not filter any incoming - * frame. - * - ****************************************************************************/ - -static int mrf24j40_setpromisc(FAR struct mrf24j40_radio_s *dev, - bool promisc) -{ - return mrf24j40_setrxmode(dev, promisc ? MRF24J40_RXMODE_PROMISC : - MRF24J40_RXMODE_NORMAL); -} - -/**************************************************************************** - * Name: mrf24j40_getpromisc - * - * Description: - * Get the device receive mode. - * - ****************************************************************************/ - -static int mrf24j40_getpromisc(FAR struct mrf24j40_radio_s *dev, - FAR bool *promisc) -{ - *promisc = (dev->rxmode == MRF24J40_RXMODE_PROMISC); + memcpy(eaddr, dev->addr.eaddr, 8); return OK; } @@ -927,17 +961,17 @@ static int mrf24j40_setdevmode(FAR struct mrf24j40_radio_s *dev, reg = mrf24j40_getreg(dev->spi, MRF24J40_RXMCR); - if (mode == IEEE802154_MODE_PANCOORD) + if (mode == MRF24J40_MODE_PANCOORD) { reg |= MRF24J40_RXMCR_PANCOORD; reg &= ~MRF24J40_RXMCR_COORD; } - else if (mode == IEEE802154_MODE_COORD) + else if (mode == MRF24J40_MODE_COORD) { reg |= MRF24J40_RXMCR_COORD; reg &= ~MRF24J40_RXMCR_PANCOORD; } - else if (mode == IEEE802154_MODE_DEVICE) + else if (mode == MRF24J40_MODE_DEVICE) { reg &= ~MRF24J40_RXMCR_PANCOORD; reg &= ~MRF24J40_RXMCR_COORD; @@ -1175,106 +1209,6 @@ static int mrf24j40_regdump(FAR struct mrf24j40_radio_s *dev) return 0; } -/**************************************************************************** - * Name: mrf24j40_ioctl - * - * Description: - * Misc/unofficial device controls. - * - ****************************************************************************/ - -static int mrf24j40_ioctl(FAR struct ieee802154_radio_s *radio, int cmd, - unsigned long arg) -{ - FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)radio; - FAR union ieee802154_radioarg_u *u = - (FAR union ieee802154_radioarg_u *)((uintptr_t)arg); - int ret; - - switch(cmd) - { - case PHY802154IOC_SET_CHAN: - ret = mrf24j40_setchannel(dev, u->channel); - break; - - case PHY802154IOC_GET_CHAN: - ret = mrf24j40_getchannel(dev, &u->channel); - break; - - case PHY802154IOC_SET_PANID: - ret = mrf24j40_setpanid(dev, u->panid); - break; - - case PHY802154IOC_GET_PANID: - ret = mrf24j40_getpanid(dev, &u->panid); - break; - - case PHY802154IOC_SET_SADDR: - ret = mrf24j40_setsaddr(dev, u->saddr); - break; - - case PHY802154IOC_GET_SADDR: - ret = mrf24j40_getsaddr(dev, &u->saddr); - break; - - case PHY802154IOC_SET_EADDR: - ret = mrf24j40_seteaddr(dev, u->eaddr); - break; - - case PHY802154IOC_GET_EADDR: - ret = mrf24j40_geteaddr(dev, u->eaddr); - break; - - case PHY802154IOC_SET_PROMISC: - ret = mrf24j40_setpromisc(dev, u->promisc); - break; - - case PHY802154IOC_GET_PROMISC: - ret = mrf24j40_getpromisc(dev, &u->promisc); - break; - - case PHY802154IOC_SET_DEVMODE: - ret = mrf24j40_setdevmode(dev, u->devmode); - break; - - case PHY802154IOC_GET_DEVMODE: - ret = mrf24j40_getdevmode(dev, &u->devmode); - break; - - case PHY802154IOC_SET_TXPWR: - ret = mrf24j40_settxpower(dev, u->txpwr); - break; - - case PHY802154IOC_GET_TXPWR: - ret = mrf24j40_gettxpower(dev, &u->txpwr); - break; - - case PHY802154IOC_SET_CCA: - ret = mrf24j40_setcca(dev, &u->cca); - break; - - case PHY802154IOC_GET_CCA: - ret = mrf24j40_getcca(dev, &u->cca); - break; - - case PHY802154IOC_ENERGYDETECT: - ret = mrf24j40_energydetect(dev, &u->energy); - break; - - case 1000: - return mrf24j40_regdump(dev); - - case 1001: dev->paenabled = (uint8_t)arg; - wlinfo("PA %sabled\n", arg ? "en" : "dis"); - return OK; - - default: - return -ENOTTY; - } - - return ret; -} - /**************************************************************************** * Name: mrf24j40_energydetect * diff --git a/include/nuttx/fs/ioctl.h b/include/nuttx/fs/ioctl.h index 9b0df767dc..2d18dc217e 100644 --- a/include/nuttx/fs/ioctl.h +++ b/include/nuttx/fs/ioctl.h @@ -89,7 +89,6 @@ #define _CLIOCBASE (0x2400) /* Contactless modules ioctl commands */ #define _USBCBASE (0x2500) /* USB-C controller ioctl commands */ #define _MAC802154BASE (0x2600) /* 802.15.4 MAC ioctl commands */ -#define _PHY802154BASE (0x2700) /* 802.15.4 Radio ioctl commands */ /* boardctl() commands share the same number space */ @@ -429,12 +428,6 @@ #define _MAC802154IOCVALID(c) (_IOC_TYPE(c)==_MAC802154BASE) #define _MAC802154IOC(nr) _IOC(_MAC802154BASE,nr) -/* 802.15.4 Radio driver ioctl definitions **********************************/ -/* (see nuttx/ieee802154/wireless/ieee802154_radio.h */ - -#define _PHY802154IOCVALID(c) (_IOC_TYPE(c)==_PHY802154BASE) -#define _PHY802154IOC(nr) _IOC(_PHY802154BASE,nr) - /* boardctl() command definitions *******************************************/ #define _BOARDIOCVALID(c) (_IOC_TYPE(c)==_BOARDBASE) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index 9ab06ada2f..407b6f6be7 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -55,8 +55,6 @@ # include #endif -#include - #include /**************************************************************************** @@ -331,6 +329,8 @@ enum ieee802154_pib_attr_e IEEE802154_PIB_MAC_PANCOORD_SHORT_ADDR, }; +#define IEEE802154_EADDR_LEN 8 + /* IEEE 802.15.4 Device address * The addresses in ieee802154 have several formats: * No address : [none] @@ -351,9 +351,10 @@ struct ieee802154_addr_s enum ieee802154_addr_mode_e mode; - uint16_t panid; /* PAN identifier, can be IEEE802154_PAN_UNSPEC */ - uint16_t saddr; /* short address */ - uint8_t eaddr[8]; /* extended address */ + uint16_t panid; /* PAN identifier, can be + * IEEE802154_PAN_UNSPEC */ + uint16_t saddr; /* short address */ + uint8_t eaddr[IEEE802154_EADDR_LEN]; /* extended address */ }; #define IEEE802154_ADDRSTRLEN 22 /* (2*2+1+8*2, PPPP/EEEEEEEEEEEEEEEE) */ @@ -454,15 +455,54 @@ struct ieee802154_pend_addr_s struct ieee802154_addr_s addr[7]; /* Array of at most 7 addresses */ }; +#ifdef CONFIG_IEEE802154_RANGING +#define IEEE802154_TXDESC_FIELDS \ + uint8_t handle; \ + uint32_t timestamp; \ + uint8_t status; +#else +#define IEEE802154_TXDESC_FIELDS \ + uint8_t handle; \ + uint32_t timestamp; \ + uint8_t status; + bool rng_rcvd; \ + uint32_t rng_counter_start; \ + uint32_t rng_counter_stop; \ + uint32_t rng_tracking_interval; \ + uint32_t rng_offset;\ + uint8_t rng_fom; +#endif + +struct ieee802154_txdesc_s +{ + IEEE802154_TXDESC_FIELDS + + /* TODO: Add slotting information for GTS transactions */ +}; + +struct ieee802154_rxdesc_s +{ + uint8_t lqi; + uint8_t rssi; +}; + +struct ieee802154_cca_s +{ + uint8_t use_ed : 1; /* CCA using ED */ + uint8_t use_cs : 1; /* CCA using carrier sense */ + uint8_t edth; /* Energy detection threshold for CCA */ + uint8_t csth; /* Carrier sense threshold for CCA */ +}; + /* Primitive Support Types ***************************************************/ -union ieee802154_attr_val_u +union ieee802154_macattr_u { - uint8_t eaddr[8]; + uint8_t eaddr[IEEE802154_EADDR_LEN]; uint16_t saddr; - uint16_t pan_id; + uint16_t panid; - uint8_t coord_eaddr[8]; + uint8_t coord_eaddr[IEEE802154_EADDR_LEN]; uint16_t coord_saddr; bool is_assoc; @@ -503,6 +543,25 @@ union ieee802154_attr_val_u uint8_t dsn; }; +union ieee802154_phyattr_u +{ + uint8_t channel; + int32_t txpwr + /* TODO: Fill this out as we implement supported get/set commands */ +}; + +union ieee802154_secattr_u +{ + /* TODO: Fill this out as we implement supported get/set commands */ +}; + +union ieee802154_attr_val_u +{ + union ieee802154_macattr_u mac; + union ieee802154_phyattr_u phy; + union ieee802154_secattr_u sec; +}; + struct ieee802154_gts_info_s { uint8_t length : 4; /* Number of SF slots for GTS */ @@ -884,20 +943,6 @@ struct ieee802154_commstatus_ind_s #endif }; -/***************************************************************************** - * Primitive: MLME-GET.request - * - * Description: - * Requests information about a given PIB attribute. - * - *****************************************************************************/ - -struct ieee802154_get_req_s -{ - enum ieee802154_pib_attr_e pib_attr; - FAR union ieee802154_attr_val_u *attr_value; -}; - /***************************************************************************** * Primitive: MLME-GTS.request * @@ -1092,6 +1137,20 @@ struct ieee802154_scan_conf_s #warning Figure out how to handle missing primitive semantics. See standard. }; +/***************************************************************************** + * Primitive: MLME-GET.request + * + * Description: + * Requests information about a given PIB attribute. + * + *****************************************************************************/ + +struct ieee802154_get_req_s +{ + enum ieee802154_pib_attr_e pib_attr; + union ieee802154_attr_val_u attr_value; +}; + /***************************************************************************** * Primitive: MLME-SET.request * diff --git a/include/nuttx/wireless/ieee802154/ieee802154_radio.h b/include/nuttx/wireless/ieee802154/ieee802154_radio.h index 50da135567..bfadc11023 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_radio.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_radio.h @@ -48,150 +48,18 @@ #include #include -#ifdef CONFIG_NET_6LOWPAN -# include -#endif - -#include +#include /**************************************************************************** * Pre-Processor Definitions ****************************************************************************/ -/* Configuration ************************************************************/ - -/* IEEE 802.15.4 Radio Interface **********************************************/ - -/* This layer only knows radio frames. There are no 802.15.4 specific bits - * at this layer. */ - -/* Device modes */ - -#define IEEE802154_MODE_DEVICE 0x00 -#define IEEE802154_MODE_COORD 0x01 /* avail in mrf24j40, but why? */ -#define IEEE802154_MODE_PANCOORD 0x02 - -/* IEEE 802.15.4 Radio Character Driver IOCTL ********************************/ - -#define PHY802154IOC_SET_CHAN _PHY802154IOC(0x0001) -#define PHY802154IOC_GET_CHAN _PHY802154IOC(0x0002) - -#define PHY802154IOC_SET_PANID _PHY802154IOC(0x0003) -#define PHY802154IOC_GET_PANID _PHY802154IOC(0x0004) - -#define PHY802154IOC_SET_SADDR _PHY802154IOC(0x0005) -#define PHY802154IOC_GET_SADDR _PHY802154IOC(0x0006) - -#define PHY802154IOC_SET_EADDR _PHY802154IOC(0x0007) -#define PHY802154IOC_GET_EADDR _PHY802154IOC(0x0008) - -#define PHY802154IOC_SET_PROMISC _PHY802154IOC(0x0009) -#define PHY802154IOC_GET_PROMISC _PHY802154IOC(0x000A) - -#define PHY802154IOC_SET_DEVMODE _PHY802154IOC(0x000B) -#define PHY802154IOC_GET_DEVMODE _PHY802154IOC(0x000C) - -#define PHY802154IOC_SET_TXPWR _PHY802154IOC(0x000D) -#define PHY802154IOC_GET_TXPWR _PHY802154IOC(0x000E) - -#define PHY802154IOC_SET_CCA _PHY802154IOC(0x000F) -#define PHY802154IOC_GET_CCA _PHY802154IOC(0x0010) - -#define PHY802154IOC_ENERGYDETECT _PHY802154IOC(0x0011) - -#define EADDR_SIZE 8 /* Extended address size */ - /**************************************************************************** * Public Types ****************************************************************************/ -/* Structures used with IEEE802.15.4 radio interface operations *************/ - -struct ieee802154_cca_s -{ - uint8_t use_ed : 1; /* CCA using ED */ - uint8_t use_cs : 1; /* CCA using carrier sense */ - uint8_t edth; /* Energy detection threshold for CCA */ - uint8_t csth; /* Carrier sense threshold for CCA */ -}; - -struct ieee802154_packet_s -{ - uint8_t len; - uint8_t data[127]; - uint8_t lqi; - uint8_t rssi; -}; - -/* IOCTL command data argument **********************************************/ - -/* A pointer to this structure is passed as the argument of each IOCTL - * command. - */ - -union ieee802154_radioarg_u -{ - uint8_t channel; /* PHY802154IOC_GET/SET_CHAN */ - uint16_t panid; /* PHY802154IOC_GET/SET_PANID */ - uint16_t saddr; /* PHY802154IOC_GET/SET_SADDR */ - uint8_t eaddr[EADDR_SIZE]; /* PHY802154IOC_GET/SET_EADDR */ - bool promisc; /* PHY802154IOC_GET/SET_EADDR */ - uint8_t devmode; /* PHY802154IOC_GET/SET_DEVMODE */ - int32_t txpwr; /* PHY802154IOC_GET/SET_TXPWR */ - bool energy; /* PHY802154IOC_ENERGYDETECT */ - struct ieee802154_cca_s cca; /* PHY802154IOC_GET/SET_CCA */ -}; - -#ifdef CONFIG_NET_6LOWPAN -/* For the case of network IOCTLs, the network IOCTL to the MAC network - * driver will include a device name like "wpan0" as the destination of - * the IOCTL command. The MAC layer will forward only the payload union - * to the radio IOCTL method. - */ - -struct ieee802154_netradio_s -{ - char ifr_name[IFNAMSIZ]; /* Interface name, e.g. "wpan0" */ - union ieee802154_radioarg_u u; /* Data payload */ -}; -#endif - /* IEEE802.15.4 Radio Interface Operations **********************************/ -/* This is a work-around to allow the MAC upper layer have a struct with - * identical members but with a different name. */ - -#ifdef CONFIG_IEEE802154_RANGING -#define IEEE802154_TXDESC_FIELDS \ - uint8_t handle; \ - uint32_t timestamp; \ - uint8_t status; -#else -#define IEEE802154_TXDESC_FIELDS \ - uint8_t handle; \ - uint32_t timestamp; \ - uint8_t status; - bool rng_rcvd; \ - uint32_t rng_counter_start; \ - uint32_t rng_counter_stop; \ - uint32_t rng_tracking_interval; \ - uint32_t rng_offset;\ - uint8_t rng_fom; -#endif - -struct ieee802154_txdesc_s -{ - IEEE802154_TXDESC_FIELDS - - /* TODO: Add slotting information for GTS transactions */ -}; - -struct ieee802154_rxdesc_s -{ - uint8_t lqi; - uint8_t rssi; -}; - struct ieee802154_radiocb_s { CODE int (*poll_csma) (FAR const struct ieee802154_radiocb_s *radiocb, @@ -213,11 +81,14 @@ struct ieee802154_radioops_s { CODE int (*bind) (FAR struct ieee802154_radio_s *radio, FAR struct ieee802154_radiocb_s *radiocb); - CODE int (*ioctl)(FAR struct ieee802154_radio_s *radio, int cmd, - unsigned long arg); - CODE int (*rxenable)(FAR struct ieee802154_radio_s *radio, bool enable); CODE int (*txnotify_csma)(FAR struct ieee802154_radio_s *radio); CODE int (*txnotify_gts)(FAR struct ieee802154_radio_s *radio); + CODE int (*get_attr) (FAR struct ieee802154_radio_s *radio, + enum ieee802154_pib_attr_e pib_attr, + FAR union ieee802154_attr_val_u *attr_value); + CODE int (*set_attr) (FAR struct ieee802154_radio_s *radio, + enum ieee802154_pib_attr_e pib_attr, + FAR const union ieee802154_attr_val_u *attr_value); }; struct ieee802154_radio_s @@ -237,28 +108,6 @@ extern "C" * Public Function Prototypes ****************************************************************************/ -/**************************************************************************** - * Name: radio802154dev_register - * - * Description: - * Register a character driver to access the IEEE 802.15.4 radio from - * user-space - * - * Input Parameters: - * radio - Pointer to the radio struct to be registerd. - * devname - The name of the IEEE 802.15.4 radio to be registered. - * - * Returned Values: - * Zero (OK) is returned on success. Otherwise a negated errno value is - * returned to indicate the nature of the failure. - * - ****************************************************************************/ - -#ifdef CONFIG_IEEE802154_DEV -int radio802154dev_register(FAR struct ieee802154_radio_s *radio, - FAR char *devname); -#endif - #undef EXTERN #ifdef __cplusplus } diff --git a/include/sys/ioctl.h b/include/sys/ioctl.h index e993a8d6b9..76abe7f01f 100644 --- a/include/sys/ioctl.h +++ b/include/sys/ioctl.h @@ -65,11 +65,6 @@ #endif #ifdef CONFIG_WIRELESS_IEEE802154 -#ifdef CONFIG_IEEE802154_DEV -/* Include ieee802.15.4 radio IOCTL definitions */ - -# include -#endif #ifdef CONFIG_IEEE802154_MAC /* Include ieee802.15.4 MAC IOCTL definitions */ diff --git a/net/netdev/netdev_ioctl.c b/net/netdev/netdev_ioctl.c index 81bfe9a0b3..dae8064645 100644 --- a/net/netdev/netdev_ioctl.c +++ b/net/netdev/netdev_ioctl.c @@ -74,7 +74,6 @@ #if defined(CONFIG_NETDEV_IOCTL) && defined(CONFIG_NET_6LOWPAN) # include -# include #endif #include "arp/arp.h" @@ -353,22 +352,7 @@ static int netdev_iee802154_ioctl(FAR struct socket *psock, int cmd, if (arg != 0ul) { - /* Verify that this is either a valid IEEE802.15.4 radio IOCTL command - * or a valid IEEE802.15.4 MAC IOCTL command. - */ - - if (_PHY802154IOCVALID(cmd)) - { - /* Get the IEEE802.15.4 network device to receive the radio IOCTL - * commdand - */ - - FAR struct ieee802154_netradio_s *radio = - (FAR struct ieee802154_netradio_s *)((uintptr_t)arg); - - ifname = radio->ifr_name; - } - else if (_MAC802154IOCVALID(cmd)) + if (_MAC802154IOCVALID(cmd)) { /* Get the IEEE802.15.4 MAC device to receive the radio IOCTL * commdand diff --git a/net/sixlowpan/sixlowpan_utils.c b/net/sixlowpan/sixlowpan_utils.c index 05b60e3d38..d392f0ef47 100644 --- a/net/sixlowpan/sixlowpan_utils.c +++ b/net/sixlowpan/sixlowpan_utils.c @@ -57,7 +57,6 @@ #include #include -#include #include "sixlowpan/sixlowpan_internal.h" @@ -165,7 +164,7 @@ bool sixlowpan_ismacbased(const net_ipv6addr_t ipaddr, * Name: sixlowpan_src_panid * * Description: - * Get the source PAN ID from the IEEE802.15.4 radio. + * Get the source PAN ID from the IEEE802.15.4 MAC layer. * * Input parameters: * ieee - A reference IEEE802.15.4 MAC network device structure. @@ -181,18 +180,20 @@ int sixlowpan_src_panid(FAR struct ieee802154_driver_s *ieee, FAR uint16_t *panid) { FAR struct net_driver_s *dev = &ieee->i_dev; - struct ieee802154_netradio_s arg; + struct ieee802154_netmac_s arg; int ret; memcpy(arg.ifr_name, ieee->i_dev.d_ifname, IFNAMSIZ); - ret = dev->d_ioctl(dev, PHY802154IOC_GET_PANID, (unsigned long)((uintptr_t)&arg)); + arg.u.getreq.pib_attr = IEEE802154_PIB_MAC_PAN_ID; + ret = dev->d_ioctl(dev, MAC802154IOC_MLME_GET_REQUEST, + (unsigned long)((uintptr_t)&arg)); if (ret < 0) { - wlerr("ERROR: PHY802154IOC_GET_PANID failed: %d\n", ret); + wlerr("ERROR: MAC802154IOC_MLME_GET_REQUEST failed: %d\n", ret); return ret; } - *panid = arg.u.panid; + *panid = arg.u.getreq.attr_value->panid; return OK; } diff --git a/wireless/ieee802154/Kconfig b/wireless/ieee802154/Kconfig index c1f7f828fa..aa3f16219c 100644 --- a/wireless/ieee802154/Kconfig +++ b/wireless/ieee802154/Kconfig @@ -60,14 +60,6 @@ config IEEE802154_NTXDESC endif # IEEE802154_MAC -config IEEE802154_DEV - bool "Debug character driver for ieee802.15.4 radio interfaces" - default n - depends on WIRELESS_IEEE802154 - ---help--- - Enables a device driver to expose ieee802.15.4 radio controls - to user space as IOCTLs. - config IEEE802154_NETDEV bool "IEEE802154 6loWPAN Network Device" default n diff --git a/wireless/ieee802154/Make.defs b/wireless/ieee802154/Make.defs index a2ec823d3b..da84b153a7 100644 --- a/wireless/ieee802154/Make.defs +++ b/wireless/ieee802154/Make.defs @@ -37,8 +37,6 @@ ifeq ($(CONFIG_WIRELESS_IEEE802154),y) # Include IEEE 802.15.4 support -CSRCS = radio802154_ioctl.c - # Include wireless devices build support ifeq ($(CONFIG_IEEE802154_MAC),y) diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index be79dad029..0f548841c2 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -2,7 +2,9 @@ * wireless/ieee802154/mac802154.c * * Copyright (C) 2016 Sebastien Lorquet. All rights reserved. + * Copyright (C) 2017 Verge Inc. All rights reserved. * Author: Sebastien Lorquet + * Author: Anthony Merlino * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -51,6 +53,7 @@ #include #include +#include #include "mac802154.h" @@ -445,14 +448,15 @@ static int mac802154_defaultmib(FAR struct ieee802154_privmac_s *priv) priv->coord_addr.mode = IEEE802154_ADDRMODE_NONE; priv->coord_addr.saddr = IEEE802154_SADDR_UNSPEC; - memcpy(&priv->coord_addr.eaddr[0], IEEE802154_EADDR_UNSPEC, 8); + memcpy(&priv->coord_addr.eaddr[0], IEEE802154_EADDR_UNSPEC, + IEEE802154_EADDR_LEN); /* Reset the device's address */ priv->addr.mode = IEEE802154_ADDRMODE_NONE; priv->addr.panid = IEEE802154_PAN_UNSPEC; priv->addr.saddr = IEEE802154_SADDR_UNSPEC; - memcpy(&priv->addr.eaddr[0], IEEE802154_EADDR_UNSPEC, 8); + memcpy(&priv->addr.eaddr[0], IEEE802154_EADDR_UNSPEC, IEEE802154_EADDR_LEN); /* These attributes are effected and determined based on the PHY. Need to @@ -875,85 +879,78 @@ int mac802154_ioctl(MACHANDLE mac, int cmd, unsigned long arg) { case MAC802154IOC_MLME_ASSOC_REQUEST: { - mac802154_req_associate(mac, &macarg->assocreq); + ret = mac802154_req_associate(mac, &macarg->assocreq); } break; case MAC802154IOC_MLME_ASSOC_RESPONSE: { - mac802154_resp_associate(mac, &macarg->assocresp); + ret = mac802154_resp_associate(mac, &macarg->assocresp); } break; case MAC802154IOC_MLME_DISASSOC_REQUEST: { - mac802154_req_disassociate(mac, &macarg->disassocreq); + ret = mac802154_req_disassociate(mac, &macarg->disassocreq); } break; case MAC802154IOC_MLME_GET_REQUEST: { - mac802154_req_get(mac, macarg->getreq.pib_attr, - macarg->getreq.attr_value); + ret = mac802154_req_get(mac, macarg->getreq.pib_attr, + &macarg->getreq.attr_value); } break; case MAC802154IOC_MLME_GTS_REQUEST: { - mac802154_req_gts(mac, &macarg->gtsreq); + ret = mac802154_req_gts(mac, &macarg->gtsreq); } break; case MAC802154IOC_MLME_ORPHAN_RESPONSE: { - mac802154_resp_orphan(mac, &macarg->orphanresp); + ret = mac802154_resp_orphan(mac, &macarg->orphanresp); } break; case MAC802154IOC_MLME_RESET_REQUEST: { - mac802154_req_reset(mac, macarg->resetreq.rst_pibattr); + ret = mac802154_req_reset(mac, macarg->resetreq.rst_pibattr); } break; case MAC802154IOC_MLME_RXENABLE_REQUEST: { - mac802154_req_rxenable(mac, &macarg->rxenabreq); + ret = mac802154_req_rxenable(mac, &macarg->rxenabreq); } break; case MAC802154IOC_MLME_SCAN_REQUEST: { - mac802154_req_scan(mac, &macarg->scanreq); + ret = mac802154_req_scan(mac, &macarg->scanreq); } break; case MAC802154IOC_MLME_SET_REQUEST: { - mac802154_req_set(mac, &macarg->setreq); + ret = mac802154_req_set(mac, macarg->setreq.pib_attr, + &macarg->setreq.attr_value); } break; case MAC802154IOC_MLME_START_REQUEST: { - mac802154_req_start(mac, &macarg->startreq); + ret = mac802154_req_start(mac, &macarg->startreq); } break; case MAC802154IOC_MLME_SYNC_REQUEST: { - mac802154_req_sync(mac, &macarg->syncreq); + ret = mac802154_req_sync(mac, &macarg->syncreq); } break; case MAC802154IOC_MLME_POLL_REQUEST: { - mac802154_req_poll(mac, &macarg->pollreq); + ret = mac802154_req_poll(mac, &macarg->pollreq); } break; + default: + wlerr("ERROR: Unrecognized cmd: %d\n", cmd); + ret = -ENOTTY; + break; } } - - /* No, other IOCTLs must be aimed at the IEEE802.15.4 radio layer */ - - else - { - DEBUGASSERT(priv->radio != NULL && - priv->radio->ops != NULL && - priv->radio->ops->ioctl != NULL); - - ret = priv->radio->ops->ioctl(priv->radio, cmd, arg); - } - - return ret; + return ret; } /**************************************************************************** @@ -1109,8 +1106,10 @@ int mac802154_req_data(MACHANDLE mac, } else if (meta->dest_addr.mode == IEEE802154_ADDRMODE_EXTENDED) { - memcpy(&frame->io_data[mhr_len], &meta->dest_addr.eaddr, 8); - mhr_len += 8; + memcpy(&frame->io_data[mhr_len], &meta->dest_addr.eaddr, + IEEE802154_EADDR_LEN); + + mhr_len += IEEE802154_EADDR_LEN; } } @@ -1166,8 +1165,10 @@ int mac802154_req_data(MACHANDLE mac, } else if (meta->src_addr_mode == IEEE802154_ADDRMODE_EXTENDED) { - memcpy(&frame->io_data[mhr_len], &priv->addr.eaddr, 8); - mhr_len += 8; + memcpy(&frame->io_data[mhr_len], &priv->addr.eaddr, + IEEE802154_EADDR_LEN); + + mhr_len += IEEE802154_EADDR_LEN; } } @@ -1482,60 +1483,39 @@ int mac802154_req_get(MACHANDLE mac, enum ieee802154_pib_attr_e pib_attr, * ****************************************************************************/ -int mac802154_req_set(MACHANDLE mac, FAR struct ieee802154_set_req_s *req) +int mac802154_req_set(MACHANDLE mac, enum ieee802154_pib_attr_e pib_attr, + FAR const union ieee802154_attr_val_u *attr_value) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; - union ieee802154_radioarg_u radio_arg; int ret; - switch (req->pib_attr) + switch (pib_attr) { case IEEE802154_PIB_MAC_EXTENDED_ADDR: { - /* Update the radio's extended address */ + /* Set the MAC copy of the address in the table */ - memcpy(&radio_arg.eaddr[0], &priv->addr.eaddr[0], 8); - ret = priv->radio->ops->ioctl(priv->radio, PHY802154IOC_SET_EADDR, - (unsigned long)&radio_arg); - if (ret < 0) - { - return -IEEE802154_STATUS_FAILED; - } + memcpy(&priv->addr.eaddr[0], &attr_value->mac.eaddr[0], + IEEE802154_EADDR_LEN); - /* Set the attribute in the table */ + /* Tell the radio about the attribute */ - memcpy(&priv->addr.eaddr[0], &req->attr_value.eaddr[0], 8); + priv->radio->ops->set_attr(priv->radio, pib_attr, attr_value); ret = IEEE802154_STATUS_SUCCESS; } break; - case IEEE802154_PIB_MAC_PROMISCUOUS_MODE: - { - /* Try and enable/disable promiscuous mode at the radio */ - - radio_arg.promisc = priv->promisc_mode; - ret = priv->radio->ops->ioctl(priv->radio, PHY802154IOC_SET_PROMISC, - (unsigned long)&radio_arg); - if (ret < 0) - { - return -IEEE802154_STATUS_FAILED; - } - - /* Set the attribute in the table */ - - priv->promisc_mode = req->attr_value.promics_mode; - - ret = IEEE802154_STATUS_SUCCESS; - } - break; default: { - ret = -IEEE802154_STATUS_UNSUPPORTED_ATTRIBUTE; + /* The attribute may be handled soley in the radio driver, so pass + * it along. + */ + + ret = priv->radio->ops->set_attr(priv->radio, pib_attr, attr_value); } break; } - return ret; } diff --git a/wireless/ieee802154/mac802154.h b/wireless/ieee802154/mac802154.h index 883d0180ee..b98fa0d360 100644 --- a/wireless/ieee802154/mac802154.h +++ b/wireless/ieee802154/mac802154.h @@ -269,7 +269,8 @@ int mac802154_req_get(MACHANDLE mac, enum ieee802154_pib_attr_e pib_attr, * ****************************************************************************/ -int mac802154_req_set(MACHANDLE mac, FAR struct ieee802154_set_req_s *req); +int mac802154_req_set(MACHANDLE mac, enum ieee802154_pib_attr_e pib_attr, + FAR const union ieee802154_attr_val_u *attr_value); /**************************************************************************** * Name: mac802154_req_start diff --git a/wireless/ieee802154/mac802154_loopback.c b/wireless/ieee802154/mac802154_loopback.c index 8b0abaf5b5..44cb4f0762 100644 --- a/wireless/ieee802154/mac802154_loopback.c +++ b/wireless/ieee802154/mac802154_loopback.c @@ -54,7 +54,6 @@ #include #include #include -#include #include #include "mac802154.h" @@ -594,32 +593,6 @@ static int lo_ioctl(FAR struct net_driver_s *dev, int cmd, else #endif - if (_PHY802154IOCVALID(cmd)) - { - FAR struct ieee802154_netradio_s *netradio = - (FAR struct ieee802154_netradio_s *)arg; - - /* Pick out radio settings of interest. There is, of course, no - * radio in this loopback. - */ - - switch (cmd) - { - case PHY802154IOC_SET_PANID: - priv->lo_panid = netradio->u.panid; - ret = OK; - break; - - case PHY802154IOC_GET_PANID: - netradio->u.panid = priv->lo_panid; - ret = OK; - break; - - default: - break; - } - } - return ret; } #endif diff --git a/wireless/ieee802154/mac802154_netdev.c b/wireless/ieee802154/mac802154_netdev.c index bf4c9013cb..7016cf7199 100644 --- a/wireless/ieee802154/mac802154_netdev.c +++ b/wireless/ieee802154/mac802154_netdev.c @@ -1381,20 +1381,6 @@ static int macnet_ioctl(FAR struct net_driver_s *dev, int cmd, } } - /* No, check for IOCTLs aimed at the IEEE802.15.4 radio layer */ - - else if (_PHY802154IOCVALID(cmd)) - { - FAR struct ieee802154_netradio_s *netradio = - (FAR struct ieee802154_netradio_s *)arg; - - if (netradio != NULL) - { - unsigned long radioarg = (unsigned int)((uintptr_t)&netradio->u); - ret = priv->md_mac.macops.ioctl(priv->md_mac, cmd, radioarg); - } - } - /* Okay, we have no idea what this command is.. just give to the * IEEE802.15.4 MAC layer without modification. */ diff --git a/wireless/ieee802154/radio802154_device.c b/wireless/ieee802154/radio802154_device.c deleted file mode 100644 index 2c48e107d0..0000000000 --- a/wireless/ieee802154/radio802154_device.c +++ /dev/null @@ -1,512 +0,0 @@ -/**************************************************************************** - * wireless/ieee802154/radio802154_device.c - * - * Copyright (C) 2014-2015 Gregory Nutt. All rights reserved. - * Copyright (C) 2014-2015 Sebastien Lorquet. All rights reserved. - * Author: Sebastien Lorquet - * Author: Anthony Merlino - * - * 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 "radio802154_ioctl.h" - -/**************************************************************************** - * Private Types - ****************************************************************************/ - -struct radio802154_devwrapper_s -{ - FAR struct ieee802154_radio_s *child; - sem_t devsem; /* Device access serialization semaphore */ - bool opened; /* This device can only be opened once */ -}; - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -static void radio802154dev_semtake(FAR struct radio802154_devwrapper_s *dev); -static int radio802154dev_open(FAR struct file *filep); -static int radio802154dev_close(FAR struct file *filep); -static ssize_t radio802154dev_read(FAR struct file *filep, FAR char *buffer, - size_t len); -static ssize_t radio802154dev_write(FAR struct file *filep, - FAR const char *buffer, size_t len); -static int radio802154dev_ioctl(FAR struct file *filep, int cmd, - unsigned long arg); - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -static const struct file_operations radio802154dev_fops = -{ - radio802154dev_open , /* open */ - radio802154dev_close, /* close */ - radio802154dev_read , /* read */ - radio802154dev_write, /* write */ - NULL, /* seek */ - radio802154dev_ioctl /* ioctl */ -#ifndef CONFIG_DISABLE_POLL - , NULL /* poll */ -#endif -#ifndef CONFIG_DISABLE_PSEUDOFS_OPERATIONS - , NULL /* unlink */ -#endif -}; - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: radio802154dev_semtake - * - * Description: - * Acquire the semaphore used for access serialization. - * - ****************************************************************************/ - -static void radio802154dev_semtake(FAR struct radio802154_devwrapper_s *dev) -{ - /* Take the semaphore (perhaps waiting) */ - - while (sem_wait(&dev->devsem) != 0) - { - /* The only case that an error should occur here is if - * the wait was awakened by a signal. - */ - - DEBUGASSERT(errno == EINTR); - } -} - -/**************************************************************************** - * Name: radio802154dev_semgive - * - * Description: - * Release the semaphore used for access serialization. - * - ****************************************************************************/ - -static inline void radio802154dev_semgive(FAR struct radio802154_devwrapper_s *dev) -{ - sem_post(&dev->devsem); -} - -/**************************************************************************** - * Name: radio802154dev_open - * - * Description: - * Open the 802.15.4 radio character device. - * - ****************************************************************************/ - -static int radio802154dev_open(FAR struct file *filep) -{ - FAR struct inode *inode; - FAR struct radio802154_devwrapper_s *dev; - - DEBUGASSERT(filep != NULL && filep->f_inode != NULL); - inode = filep->f_inode; - dev = inode->i_private; - DEBUGASSERT(dev != NULL); - - /* Get exclusive access to the driver data structures */ - - radio802154dev_semtake(dev); - - if (dev->opened) - { - /* Already opened */ - - return -EMFILE; - } - else - { - /* Enable interrupts (only rx for now)*/ - - //mrf24j40_setreg(dev->spi, MRF24J40_INTCON, ~(MRF24J40_INTCON_RXIE) ); - //dev->lower->enable(dev->lower, TRUE); - - dev->opened = true; - } - - radio802154dev_semgive(dev); - return OK; -} - -/**************************************************************************** - * Name: radio802154dev_close - * - * Description: - * Close the 802.15.4 radio character device. - * - ****************************************************************************/ - -static int radio802154dev_close(FAR struct file *filep) -{ - FAR struct inode *inode; - FAR struct radio802154_devwrapper_s *dev; - int ret = OK; - - DEBUGASSERT(filep != NULL && filep->f_inode != NULL); - inode = filep->f_inode; - dev = inode->i_private; - DEBUGASSERT(dev != NULL); - - /* Get exclusive access to the driver data structures */ - - radio802154dev_semtake(dev); - - if (!dev->opened) - { - /* Driver has not been opened */ - - ret = -EIO; - } - else - { - /* Disable interrupts */ - - //mrf24j40_setreg(dev->spi, MRF24J40_INTCON, 0xFF ); - //dev->lower->enable(dev->lower, FALSE); - - dev->opened = false; - } - - radio802154dev_semgive(dev); - return ret; -} - -/**************************************************************************** - * Name: radio802154dev_read - * - * Description: - * Return the last received packet. - * TODO: Return a packet from the receive queue. The buffer must be a pointer to a - * struct ieee802154_packet_s structure, with a correct length. - * - ****************************************************************************/ - -static ssize_t radio802154dev_read(FAR struct file *filep, FAR char *buffer, size_t len) -{ - FAR struct inode *inode; - FAR struct radio802154_devwrapper_s *dev; - FAR struct ieee802154_packet_s *buf; - int ret = OK; - - DEBUGASSERT(filep != NULL && filep->f_inode != NULL); - inode = filep->f_inode; - dev = inode->i_private; - DEBUGASSERT(dev != NULL && buffer != NULL); - buf = (FAR struct ieee802154_packet_s*)buffer; - - /* Get exclusive access to the driver data structures */ - - if (len < sizeof(struct ieee802154_packet_s)) - { - ret = -EINVAL; - goto done; - } - -#warning Receive needs to be redone! -#if 0 - ret = dev->child->ops->rxenable(dev->child, 1, buf); - if (ret < 0) - { - goto done; - } - - /* if no packet is received, this will produce -EAGAIN - * The user is responsible for sleeping until sth arrives - */ - -#if 0 - ret = sem_trywait(&dev->child->rxsem); -#else - ret = sem_wait(&dev->child->rxsem); -#endif - if (ret < 0) - { - ret = -errno; - goto done; - } - - /* Disable read until we have process the current read */ - - dev->child->ops->rxenable(dev->child, 0, NULL); - ret = buf->len; - -#endif - -done: - return ret; -} - -/**************************************************************************** - * Name: radio802154dev_write - * - * Description: - * Send a packet immediately. - * TODO: Put a packet in the send queue. The packet will be sent as soon - * as possible. The buffer must point to a struct radio802154_packet_s - * with the correct length. - * - ****************************************************************************/ - -static ssize_t radio802154dev_write(FAR struct file *filep, - FAR const char *buffer, size_t len) -{ - FAR struct inode *inode; - FAR struct radio802154_devwrapper_s *dev; - FAR struct ieee802154_packet_s *packet; - FAR struct timespec timeout; - int ret = OK; - - DEBUGASSERT(filep != NULL && filep->f_inode != NULL); - inode = filep->f_inode; - dev = inode->i_private; - DEBUGASSERT(dev != NULL); - - /* Get exclusive access to the driver data structures */ - - /* TODO: Make this an option or have a new method of doing timeout from - * ioctrl. - */ - - timeout.tv_sec = 1; - timeout.tv_nsec = 0; - - /* Sanity checks */ - - if (len < sizeof(struct ieee802154_packet_s)) - { - ret = -EINVAL; - //goto done; - - /* TODO Double check I like having assert here. It is a bigger problem - * if buffers are to small. - */ - - DEBUGASSERT(0); - } - - packet = (FAR struct ieee802154_packet_s*) buffer; - if (packet->len > 125) /* Max len 125, 2 FCS bytes auto added by mrf */ - { - ret = -EPERM; - //goto done; - DEBUGASSERT(0); - } - - /* Copy packet to normal device TX fifo. - * Beacons and GTS transmission will be handled via IOCTLs - */ - -#warning Fix this when transmit interface is complete -#if 0 - ret = dev->child->ops->transmit(dev->child, packet); - if (ret != packet->len) - { - ret = -EPERM; - goto done; - } - - if (sem_timedwait(&dev->child->txsem, &timeout)) - { - wlerr("Radio Device timedout on Tx\n"); - } -#endif - -done: - - /* Okay, tx interrupt received. check transmission status to decide success. */ - - return ret; -} - -/**************************************************************************** - * Name: radio802154dev_ioctl - * - * Description: - * Control the MRF24J40 device. This is where the real operations happen. - * - ****************************************************************************/ - -static int radio802154dev_ioctl(FAR struct file *filep, int cmd, - unsigned long arg) -{ - FAR struct inode *inode; - FAR struct radio802154_devwrapper_s *dev; - FAR struct ieee802154_radio_s *child; - int ret = OK; - - DEBUGASSERT(filep != NULL && filep->f_inode != NULL); - inode = filep->f_inode; - dev = inode->i_private; - DEBUGASSERT(dev != NULL && dev->child != NULL); - child = dev->child; - - /* Get exclusive access to the driver data structures */ - - switch (cmd) - { - case PHY802154IOC_SET_CHAN: - ret = radio802154_setchannel(child, (uint8_t)arg); - break; - - case PHY802154IOC_GET_CHAN: - ret = radio802154_getchannel(child, (FAR uint8_t*)arg); - break; - - case PHY802154IOC_SET_PANID: - ret = radio802154_setpanid(child, (uint16_t)arg); - break; - - case PHY802154IOC_GET_PANID: - ret = radio802154_getpanid(child, (FAR uint16_t*)arg); - break; - - case PHY802154IOC_SET_SADDR: - ret = radio802154_setsaddr(child, (uint16_t)arg); - break; - - case PHY802154IOC_GET_SADDR: - ret = radio802154_getsaddr(child, (FAR uint16_t*)arg); - break; - - case PHY802154IOC_SET_EADDR: - ret = radio802154_seteaddr(child, (FAR uint8_t*)arg); - break; - - case PHY802154IOC_GET_EADDR: - ret = radio802154_geteaddr(child, (FAR uint8_t*)arg); - break; - - case PHY802154IOC_SET_PROMISC: - ret = radio802154_setpromisc(child, (bool)arg); - break; - - case PHY802154IOC_GET_PROMISC: - ret = radio802154_getpromisc(child, (FAR bool*)arg); - break; - - case PHY802154IOC_SET_DEVMODE: - ret = radio802154_setdevmode(child, (uint8_t)arg); - break; - - case PHY802154IOC_GET_DEVMODE: - ret = radio802154_getdevmode(child, (FAR uint8_t*)arg); - break; - - case PHY802154IOC_SET_TXPWR: - ret = radio802154_settxpower(child, (int32_t)arg); - break; - - case PHY802154IOC_GET_TXPWR: - ret = radio802154_gettxpower(child, (FAR int32_t*)arg); - break; - - case PHY802154IOC_SET_CCA: - ret = radio802154_setcca(child, (FAR struct ieee802154_cca_s*)arg); - break; - - case PHY802154IOC_GET_CCA: - ret = radio802154_getcca(child, (FAR struct ieee802154_cca_s*)arg); - break; - - case PHY802154IOC_ENERGYDETECT: - ret = radio802154_energydetect(child, (FAR uint8_t*)arg); - break; - - default: - ret = child->ops->ioctl(child, cmd,arg); - break; - } - - return ret; -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: radio802154dev_register - * - * Description: - * Register a character driver to access the IEEE 802.15.4 radio from - * user-space - * - * Input Parameters: - * radio - Pointer to the radio struct to be registerd. - * devname - The name of the IEEE 802.15.4 radio to be registered. - * - * Returned Values: - * Zero (OK) is returned on success. Otherwise a negated errno value is - * returned to indicate the nature of the failure. - * - ****************************************************************************/ - -int radio802154dev_register(FAR struct ieee802154_radio_s *radio, - FAR char *devname) -{ - FAR struct radio802154_devwrapper_s *dev; - - dev = kmm_zalloc(sizeof(struct radio802154_devwrapper_s)); - if (dev == NULL) - { - return -ENOMEM; - } - - dev->child = radio; - - sem_init(&dev->devsem, 0, 1); /* Allow the device to be opened once before blocking */ - - return register_driver(devname, &radio802154dev_fops, 0666, dev); -} diff --git a/wireless/ieee802154/radio802154_ioctl.c b/wireless/ieee802154/radio802154_ioctl.c deleted file mode 100644 index d86366c987..0000000000 --- a/wireless/ieee802154/radio802154_ioctl.c +++ /dev/null @@ -1,487 +0,0 @@ -/**************************************************************************** - * wireless/ieee802154/radio802154_ioctl.c - * - * 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include - -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -#define RADIO_IOCTL(r,c,a) \ - (r)->ops->ioctl((r),(c),(unsigned long)((uintptr_t)(a))) - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: radio802154_setchannel - * - * Description: - * Define the current radio channel the device is operating on. - * In the 2.4 GHz, there are 16 channels, each 2 MHz wide, 5 MHz spacing: - * Chan MHz Chan MHz Chan MHz Chan MHz - * 11 2405 15 2425 19 2445 23 2465 - * 12 2410 16 2430 20 2450 24 2470 - * 13 2415 17 2435 21 2455 25 2475 - * 14 2420 18 2440 22 2460 26 2480 - * - ****************************************************************************/ - -int radio802154_setchannel(FAR struct ieee802154_radio_s *radio, - uint8_t chan) -{ - union ieee802154_radioarg_u arg; - int ret; - - arg.channel = chan; - - ret = RADIO_IOCTL(radio, PHY802154IOC_SET_CHAN, &arg); - if (ret < 0) - { - wlerr("ERROR: PHY802154IOC_SET_CHAN failed: %d\n", ret); - } - - return ret; -} - -/**************************************************************************** - * Name: radio802154_getchannel - * - * Description: - * Define the current radio channel the device is operating on. - * - ****************************************************************************/ - -int radio802154_getchannel(FAR struct ieee802154_radio_s *radio, - FAR uint8_t *chan) -{ - union ieee802154_radioarg_u arg; - int ret; - - ret = RADIO_IOCTL(radio, PHY802154IOC_GET_CHAN, &arg); - if (ret < 0) - { - wlerr("ERROR: PHY802154IOC_GET_CHAN failed: %d\n", ret); - } - - *chan = arg.channel; - return ret; -} - -/**************************************************************************** - * Name: radio802154_setpanid - * - * Description: - * Define the PAN ID the device is operating on. - * - ****************************************************************************/ - -int radio802154_setpanid(FAR struct ieee802154_radio_s *radio, - uint16_t panid) -{ - union ieee802154_radioarg_u arg; - int ret; - - arg.panid = panid; - - ret = RADIO_IOCTL(radio, PHY802154IOC_SET_PANID, &arg); - if (ret < 0) - { - wlerr("ERROR: PHY802154IOC_SET_PANID failed: %d\n", ret); - } - - return ret; -} - -/**************************************************************************** - * Name: radio802154_getpanid - * - * Description: - * Define the current PAN ID the device is operating on. - * - ****************************************************************************/ - -int radio802154_getpanid(FAR struct ieee802154_radio_s *radio, - FAR uint16_t *panid) -{ - union ieee802154_radioarg_u arg; - int ret; - - ret = RADIO_IOCTL(radio, PHY802154IOC_GET_PANID, &arg); - if (ret < 0) - { - wlerr("ERROR: PHY802154IOC_GET_PANID failed: %d\n", ret); - } - - *panid = arg.panid; - return ret; -} - -/**************************************************************************** - * Name: radio802154_setsaddr - * - * Description: - * Define the device short address. The following addresses are special: - * FFFEh : Broadcast - * FFFFh : Unspecified - * - ****************************************************************************/ - -int radio802154_setsaddr(FAR struct ieee802154_radio_s *radio, - uint16_t saddr) -{ - union ieee802154_radioarg_u arg; - int ret; - - arg.saddr = saddr; - - ret = RADIO_IOCTL(radio, PHY802154IOC_SET_SADDR, &arg); - if (ret < 0) - { - wlerr("ERROR: PHY802154IOC_SET_SADDR failed: %d\n", ret); - } - - return ret; -} - -/**************************************************************************** - * Name: radio802154_getsaddr - * - * Description: - * Define the current short address the device is using. - * - ****************************************************************************/ - -int radio802154_getsaddr(FAR struct ieee802154_radio_s *radio, - FAR uint16_t *saddr) -{ - union ieee802154_radioarg_u arg; - int ret; - - ret = RADIO_IOCTL(radio, PHY802154IOC_GET_SADDR, &arg); - if (ret < 0) - { - wlerr("ERROR: PHY802154IOC_GET_SADDR failed: %d\n", ret); - } - - *saddr = arg.saddr; - return ret; -} - -/**************************************************************************** - * Name: radio802154_seteaddr - * - * Description: - * Define the device extended address. The following addresses are special: - * FFFFFFFFFFFFFFFFh : Unspecified - * - ****************************************************************************/ - -int radio802154_seteaddr(FAR struct ieee802154_radio_s *radio, - FAR uint8_t *eaddr) -{ - union ieee802154_radioarg_u arg; - int ret; - - memcpy(arg.eaddr, eaddr, EADDR_SIZE); /* REVISIT */ - - ret = RADIO_IOCTL(radio, PHY802154IOC_SET_EADDR, &arg); - if (ret < 0) - { - wlerr("ERROR: PHY802154IOC_SET_EADDR failed: %d\n", ret); - } - - return ret; -} - -/**************************************************************************** - * Name: radio802154_geteaddr - * - * Description: - * Define the current extended address the device is using. - * - ****************************************************************************/ - -int radio802154_geteaddr(FAR struct ieee802154_radio_s *radio, - FAR uint8_t *eaddr) -{ - union ieee802154_radioarg_u arg; - int ret; - - ret = RADIO_IOCTL(radio, PHY802154IOC_GET_EADDR, &arg); - if (ret < 0) - { - wlerr("ERROR: PHY802154IOC_GET_EADDR failed: %d\n", ret); - } - - memcpy(eaddr, arg.eaddr, EADDR_SIZE); /* REVISIT */ - return ret; -} - -/**************************************************************************** - * Name: radio802154_setpromisc - * - * Description: - * Set the device into promiscuous mode, e.g do not filter any incoming - * frame. - * - ****************************************************************************/ - -int radio802154_setpromisc(FAR struct ieee802154_radio_s *radio, - bool promisc) -{ - union ieee802154_radioarg_u arg; - int ret; - - arg.promisc = promisc; - - ret = RADIO_IOCTL(radio, PHY802154IOC_SET_PROMISC, &arg); - if (ret < 0) - { - wlerr("ERROR: PHY802154IOC_SET_PROMISC failed: %d\n", ret); - } - - return ret; -} - -/**************************************************************************** - * Name: radio802154_getpromisc - * - * Description: - * Get the device receive mode. - * - ****************************************************************************/ - -int radio802154_getpromisc(FAR struct ieee802154_radio_s *radio, - FAR bool *promisc) -{ - union ieee802154_radioarg_u arg; - int ret; - - ret = RADIO_IOCTL(radio, PHY802154IOC_GET_PROMISC, &arg); - if (ret < 0) - { - wlerr("ERROR: PHY802154IOC_GET_PROMISC failed: %d\n", ret); - } - - *promisc = arg.promisc; - return ret; -} - -/**************************************************************************** - * Name: radio802154_setdevmode - * - * Description: - * Define the device behaviour: normal end device or coordinator - * - ****************************************************************************/ - -int radio802154_setdevmode(FAR struct ieee802154_radio_s *radio, - uint8_t mode) -{ - union ieee802154_radioarg_u arg; - int ret; - - arg.devmode = mode; - - ret = RADIO_IOCTL(radio, PHY802154IOC_SET_DEVMODE, &arg); - if (ret < 0) - { - wlerr("ERROR: PHY802154IOC_SET_DEVMODE failed: %d\n", ret); - } - - return ret; -} - -/**************************************************************************** - * Name: radio802154_setdevmode - * - * Description: - * Return the current device mode - * - ****************************************************************************/ - -int radio802154_getdevmode(FAR struct ieee802154_radio_s *radio, - FAR uint8_t *mode) -{ - union ieee802154_radioarg_u arg; - int ret; - - ret = RADIO_IOCTL(radio, PHY802154IOC_GET_DEVMODE, &arg); - if (ret < 0) - { - wlerr("ERROR: PHY802154IOC_GET_DEVMODE failed: %d\n", ret); - } - - *mode = arg.devmode; - return ret; -} - -/**************************************************************************** - * Name: radio802154_settxpower - * - * Description: - * Define the transmit power. Value is passed in mBm, it is rounded to - * the nearest value. Some MRF modules have a power amplifier, this routine - * does not care about this. We only change the CHIP output power. - * - ****************************************************************************/ - -int radio802154_settxpower(FAR struct ieee802154_radio_s *radio, - int32_t txpwr) -{ - union ieee802154_radioarg_u arg; - int ret; - - arg.txpwr = txpwr; - - ret = RADIO_IOCTL(radio, PHY802154IOC_SET_TXPWR, &arg); - if (ret < 0) - { - wlerr("ERROR: PHY802154IOC_SET_TXPWR failed: %d\n", ret); - } - - return ret; -} - -/**************************************************************************** - * Name: radio802154_gettxpower - * - * Description: - * Return the actual transmit power, in mBm. - * - ****************************************************************************/ - -int radio802154_gettxpower(FAR struct ieee802154_radio_s *radio, - FAR int32_t *txpwr) -{ - union ieee802154_radioarg_u arg; - int ret; - - ret = RADIO_IOCTL(radio, PHY802154IOC_GET_TXPWR, &arg); - if (ret < 0) - { - wlerr("ERROR: PHY802154IOC_GET_TXPWR failed: %d\n", ret); - } - - *txpwr = arg.txpwr; - return ret; -} - -/**************************************************************************** - * Name: radio802154_setcca - * - * Description: - * Define the Clear Channel Assessement method. - * - ****************************************************************************/ - -int radio802154_setcca(FAR struct ieee802154_radio_s *radio, - FAR struct ieee802154_cca_s *cca) -{ - union ieee802154_radioarg_u arg; - int ret; - - memcpy(&arg.cca, cca, sizeof(struct ieee802154_cca_s)); - - ret = RADIO_IOCTL(radio, PHY802154IOC_SET_CCA, &arg); - if (ret < 0) - { - wlerr("ERROR: PHY802154IOC_SET_CCA failed: %d\n", ret); - } - - return ret; -} - -/**************************************************************************** - * Name: radio802154_getcca - * - * Description: - * Return the Clear Channel Assessement method. - * - ****************************************************************************/ - -int radio802154_getcca(FAR struct ieee802154_radio_s *radio, - FAR struct ieee802154_cca_s *cca) -{ - union ieee802154_radioarg_u arg; - int ret; - - ret = RADIO_IOCTL(radio, PHY802154IOC_GET_CCA, &arg); - if (ret < 0) - { - wlerr("ERROR: PHY802154IOC_GET_CCA failed: %d\n", ret); - } - - memcpy(cca, &arg.cca, sizeof(struct ieee802154_cca_s)); - return ret; -} - -/**************************************************************************** - * Name: radio802154_energydetect - * - * Description: - * Measure the RSSI level for the current channel. - * - ****************************************************************************/ - -int radio802154_energydetect(FAR struct ieee802154_radio_s *radio, - FAR uint8_t *energy) - -{ - union ieee802154_radioarg_u arg; - int ret; - - ret = RADIO_IOCTL(radio, PHY802154IOC_ENERGYDETECT, &arg); - if (ret < 0) - { - wlerr("ERROR: PHY802154IOC_ENERGYDETECT failed: %d\n", ret); - } - - *energy = arg.energy; - return ret; -} diff --git a/wireless/ieee802154/radio802154_ioctl.h b/wireless/ieee802154/radio802154_ioctl.h deleted file mode 100644 index d09ad57103..0000000000 --- a/wireless/ieee802154/radio802154_ioctl.h +++ /dev/null @@ -1,255 +0,0 @@ -/**************************************************************************** - * wireless/ieee802154/radio802154_ioctl.h - * - * 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. - * - ****************************************************************************/ - -#ifndef __WIRELESS_IEEE802154_RADIO802154_IOCTL_H -#define __WIRELESS_IEEE802154_RADIO802154_IOCTL_H 1 - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include - -#include - -#include "radio802154_ioctl.h" - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: radio802154_setchannel - * - * Description: - * Define the current radio channel the device is operating on. - * In the 2.4 GHz, there are 16 channels, each 2 MHz wide, 5 MHz spacing: - * Chan MHz Chan MHz Chan MHz Chan MHz - * 11 2405 15 2425 19 2445 23 2465 - * 12 2410 16 2430 20 2450 24 2470 - * 13 2415 17 2435 21 2455 25 2475 - * 14 2420 18 2440 22 2460 26 2480 - * - ****************************************************************************/ - -int radio802154_setchannel(FAR struct ieee802154_radio_s *radio, - uint8_t chan); - -/**************************************************************************** - * Name: radio802154_getchannel - * - * Description: - * Define the current radio channel the device is operating on. - * - ****************************************************************************/ - -int radio802154_getchannel(FAR struct ieee802154_radio_s *radio, - FAR uint8_t *chan); - -/**************************************************************************** - * Name: radio802154_setpanid - * - * Description: - * Define the PAN ID the device is operating on. - * - ****************************************************************************/ - -int radio802154_setpanid(FAR struct ieee802154_radio_s *radio, - uint16_t panid); - -/**************************************************************************** - * Name: radio802154_getpanid - * - * Description: - * Define the current PAN ID the device is operating on. - * - ****************************************************************************/ - -int radio802154_getpanid(FAR struct ieee802154_radio_s *radio, - FAR uint16_t *panid); - -/**************************************************************************** - * Name: radio802154_setsaddr - * - * Description: - * Define the device short address. The following addresses are special: - * FFFEh : Broadcast - * FFFFh : Unspecified - * - ****************************************************************************/ - -int radio802154_setsaddr(FAR struct ieee802154_radio_s *radio, - uint16_t saddr); - -/**************************************************************************** - * Name: radio802154_getsaddr - * - * Description: - * Define the current short address the device is using. - * - ****************************************************************************/ - -int radio802154_getsaddr(FAR struct ieee802154_radio_s *radio, - FAR uint16_t *saddr); - -/**************************************************************************** - * Name: radio802154_seteaddr - * - * Description: - * Define the device extended address. The following addresses are special: - * FFFFFFFFFFFFFFFFh : Unspecified - * - ****************************************************************************/ - -int radio802154_seteaddr(FAR struct ieee802154_radio_s *radio, - FAR uint8_t *eaddr); - -/**************************************************************************** - * Name: radio802154_geteaddr - * - * Description: - * Define the current extended address the device is using. - * - ****************************************************************************/ - -int radio802154_geteaddr(FAR struct ieee802154_radio_s *radio, - FAR uint8_t *eaddr); - -/**************************************************************************** - * Name: radio802154_setpromisc - * - * Description: - * Set the device into promiscuous mode, e.g do not filter any incoming - * frame. - * - ****************************************************************************/ - -int radio802154_setpromisc(FAR struct ieee802154_radio_s *radio, - bool promisc); - -/**************************************************************************** - * Name: radio802154_getpromisc - * - * Description: - * Get the device receive mode. - * - ****************************************************************************/ - -int radio802154_getpromisc(FAR struct ieee802154_radio_s *radio, - FAR bool *promisc); - -/**************************************************************************** - * Name: radio802154_setdevmode - * - * Description: - * Define the device behaviour: normal end device or coordinator - * - ****************************************************************************/ - -int radio802154_setdevmode(FAR struct ieee802154_radio_s *radio, - uint8_t mode); - -/**************************************************************************** - * Name: radio802154_setdevmode - * - * Description: - * Return the current device mode - * - ****************************************************************************/ - -int radio802154_getdevmode(FAR struct ieee802154_radio_s *radio, - FAR uint8_t *mode); - -/**************************************************************************** - * Name: radio802154_settxpower - * - * Description: - * Define the transmit power. Value is passed in mBm, it is rounded to - * the nearest value. Some MRF modules have a power amplifier, this routine - * does not care about this. We only change the CHIP output power. - * - ****************************************************************************/ - -int radio802154_settxpower(FAR struct ieee802154_radio_s *radio, - int32_t txpwr); - -/**************************************************************************** - * Name: radio802154_gettxpower - * - * Description: - * Return the actual transmit power, in mBm. - * - ****************************************************************************/ - -int radio802154_gettxpower(FAR struct ieee802154_radio_s *radio, - FAR int32_t *txpwr); - -/**************************************************************************** - * Name: radio802154_setcca - * - * Description: - * Define the Clear Channel Assessement method. - * - ****************************************************************************/ - -int radio802154_setcca(FAR struct ieee802154_radio_s *radio, - FAR struct ieee802154_cca_s *cca); - -/**************************************************************************** - * Name: radio802154_getcca - * - * Description: - * Return the Clear Channel Assessement method. - * - ****************************************************************************/ - -int radio802154_getcca(FAR struct ieee802154_radio_s *radio, - FAR struct ieee802154_cca_s *cca); - -/**************************************************************************** - * Name: radio802154_energydetect - * - * Description: - * Measure the RSSI level for the current channel. - * - ****************************************************************************/ - -int radio802154_energydetect(FAR struct ieee802154_radio_s *radio, - FAR uint8_t *energy); - -#endif /* __WIRELESS_IEEE802154_RADIO802154_IOCTL_H */ -- GitLab From 0e49db76263713974946c67cfbf7473dd179aee5 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 5 May 2017 09:35:22 -0600 Subject: [PATCH 728/990] Add a blank line. --- arch/arm/src/kinetis/kinetis_lpserial.c | 1 + 1 file changed, 1 insertion(+) diff --git a/arch/arm/src/kinetis/kinetis_lpserial.c b/arch/arm/src/kinetis/kinetis_lpserial.c index 5a70582d41..117dd3de4a 100644 --- a/arch/arm/src/kinetis/kinetis_lpserial.c +++ b/arch/arm/src/kinetis/kinetis_lpserial.c @@ -670,6 +670,7 @@ static int kinetis_ioctl(struct file *filep, int cmd, unsigned long arg) { regval &= ~(LPUART_CTRL_LOOPS | LPUART_CTRL_RSRC); } + kinetis_serialout(priv, KINETIS_LPUART_CTRL_OFFSET, regval); } break; -- GitLab From 95bacb6a34b526aa44c08706b156a776b1cbe340 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 5 May 2017 10:00:18 -0600 Subject: [PATCH 729/990] 6loWPAN: Some fixed to get a clean compile after last big changes to the radio IOCTLs. --- include/nuttx/fs/ioctl.h | 4 ++-- net/sixlowpan/sixlowpan_internal.h | 9 ++++++++- net/sixlowpan/sixlowpan_utils.c | 3 ++- wireless/ieee802154/mac802154_loopback.c | 12 ++++++------ 4 files changed, 18 insertions(+), 10 deletions(-) diff --git a/include/nuttx/fs/ioctl.h b/include/nuttx/fs/ioctl.h index 2d18dc217e..cfcc4507d6 100644 --- a/include/nuttx/fs/ioctl.h +++ b/include/nuttx/fs/ioctl.h @@ -425,8 +425,8 @@ /* 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) +#define _MAC802154IOCVALID(c) (_IOC_TYPE(c)==_MAC802154BASE) +#define _MAC802154IOC(nr) _IOC(_MAC802154BASE,nr) /* boardctl() command definitions *******************************************/ diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index c48b89929f..cf71100db1 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -134,7 +134,9 @@ * Public Types ****************************************************************************/ -/* IPv^ TCP/UDP Definitions *************************************************/ +/* IPv6 TCP/UDP/ICMPv6 Definitions ******************************************/ + +#ifdef CONFIG_NET_TCP /* IPv6 + TCP header. Cast compatible based on IPv6 protocol field. */ struct ipv6tcp_hdr_s @@ -142,7 +144,9 @@ struct ipv6tcp_hdr_s struct ipv6_hdr_s ipv6; struct tcp_hdr_s tcp; }; +#endif +#ifdef CONFIG_NET_UDP /* IPv6 + UDP header */ struct ipv6udp_hdr_s @@ -150,7 +154,9 @@ struct ipv6udp_hdr_s struct ipv6_hdr_s ipv6; struct udp_hdr_s udp; }; +#endif +#ifdef CONFIG_NET_ICMPv6 /* IPv6 + ICMPv6 header */ struct ipv6icmp_hdr_s @@ -158,6 +164,7 @@ struct ipv6icmp_hdr_s struct ipv6_hdr_s ipv6; struct icmpv6_iphdr_s icmp; }; +#endif /* In order to provide a customizable IEEE 802.15.4 MAC header, a structure * of meta data is passed to the MAC network driver, struct diff --git a/net/sixlowpan/sixlowpan_utils.c b/net/sixlowpan/sixlowpan_utils.c index d392f0ef47..a1d7892a3e 100644 --- a/net/sixlowpan/sixlowpan_utils.c +++ b/net/sixlowpan/sixlowpan_utils.c @@ -57,6 +57,7 @@ #include #include +#include #include "sixlowpan/sixlowpan_internal.h" @@ -193,7 +194,7 @@ int sixlowpan_src_panid(FAR struct ieee802154_driver_s *ieee, return ret; } - *panid = arg.u.getreq.attr_value->panid; + *panid = arg.u.getreq.attr_value.mac.panid; return OK; } diff --git a/wireless/ieee802154/mac802154_loopback.c b/wireless/ieee802154/mac802154_loopback.c index 44cb4f0762..f30953a386 100644 --- a/wireless/ieee802154/mac802154_loopback.c +++ b/wireless/ieee802154/mac802154_loopback.c @@ -577,10 +577,9 @@ static int lo_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) static int lo_ioctl(FAR struct net_driver_s *dev, int cmd, unsigned long arg) { +#if 0 FAR struct lo_driver_s *priv = (FAR struct lo_driver_s *)dev->d_private; - int ret = -ENOTTY; -#if 0 /* Check for IOCTLs aimed at the IEEE802.15.4 MAC layer */ if (_MAC802154IOCVALID(cmd)) @@ -588,12 +587,13 @@ static int lo_ioctl(FAR struct net_driver_s *dev, int cmd, FAR struct ieee802154_netmac_s *netmac = (FAR struct ieee802154_netmac_s *)arg; } - - /* No, check for IOCTLs aimed at the IEEE802.15.4 radio layer */ - else #endif - return ret; + { + /* Not a valid IEEE 802.15.4 MAC IOCTL command */ + + return -ENOTTY; + } } #endif -- GitLab From b98ba3b6fe6ea0c42df7a31110d835a0f4972c91 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Fri, 5 May 2017 12:07:26 -0400 Subject: [PATCH 730/990] wireless/ieee802154: Fixes ieee802154_data_ind_s --- .../wireless/ieee802154/ieee802154_mac.h | 31 ++++++++++++++++--- 1 file changed, 26 insertions(+), 5 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index 407b6f6be7..d4046bccb2 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -652,13 +652,34 @@ struct ieee802154_data_conf_s struct ieee802154_data_ind_s { - uint8_t msdu_handle; /* Handle assoc. with MSDU */ + struct ieee802154_addr_s src; /* Source addressing information */ + struct ieee802154_addr_s dest; /* Destination addressing infromation */ + uint8_t lqi; /* Link Quality Index */ + uint8_t dsn; /* Data Sequence Number */ + uint32_t timestamp; /* Time of received frame */ + +#ifdef CONFIG_IEEE802154_SECURITY + /* Security information if enabled */ + + struct ieee802154_security_s security; +#endif /* CONFIG_IEEE802154_SECURITY */ + +#ifdef CONFIG_IEEE802154_UWB + /* The UWB Pulse Repetition Frequency to be used for the transmission */ + + enum ieee802154_uwbprf_e uwb_prf; + + /* The UWB preamble symbol repititions + * Should be one of: + * 0, 16, 64, 1024, 4096 + */ - /* The time, in symbols, at which the data were transmitted */ + uint16_t uwb_presym_rep; - uint32_t timestamp; + /* The UWB Data Rate to be used for the transmission */ - enum ieee802154_status_e status; /* The status of the MSDU transmission */ + enum ieee802154_uwb_datarate_e data_rate; +#endif /* CONFIG_IEEE802154_UWB */ #ifdef CONFIG_IEEE802154_RANGING bool rng_rcvd; /* Ranging indicated by MSDU */ @@ -690,7 +711,7 @@ struct ieee802154_data_ind_s /* The Figure of Merit (FoM) characterizing the ranging measurement */ uint8_t rng_fom; -#endif +#endif /* CONFIG_IEEE802154_RANGING */ }; /***************************************************************************** -- GitLab From b87fac776f0a8b515a5b1cdbaed0a082f16b1b6f Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Fri, 5 May 2017 12:44:29 -0400 Subject: [PATCH 731/990] wireless/ieee802154: Removes msdu_length from meta-data since it is intrinsically in the IOB --- include/nuttx/wireless/ieee802154/ieee802154_ioctl.h | 1 + include/nuttx/wireless/ieee802154/ieee802154_mac.h | 9 --------- wireless/ieee802154/mac802154.c | 2 +- wireless/ieee802154/mac802154_device.c | 4 ++-- 4 files changed, 4 insertions(+), 12 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_ioctl.h b/include/nuttx/wireless/ieee802154/ieee802154_ioctl.h index cd5550057c..6171d0e3a3 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_ioctl.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_ioctl.h @@ -78,6 +78,7 @@ struct mac802154dev_txframe_s { struct ieee802154_frame_meta_s meta; FAR uint8_t *payload; + uint16_t length; }; #endif /* CONFIG_WIRELESS_IEEE802154 */ diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index d4046bccb2..8f8e0c22d5 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -585,15 +585,6 @@ struct ieee802154_frame_meta_s uint8_t msdu_handle; /* Handle assoc. with MSDU */ - /* Number of bytes contained in the MAC Service Data Unit (MSDU) - * to be transmitted by the MAC sublayer entity - * Note: This could be a uint8_t but if anyone ever wants to use - * non-standard frame lengths, they may want a length larger than - * a uint8_t. - */ - - uint16_t msdu_length; - struct { uint8_t ack_tx : 1; /* Acknowledge TX? */ diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index 0f548841c2..23ed9db872 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -1078,7 +1078,7 @@ int mac802154_req_data(MACHANDLE mac, * sublayer will set the Frame Version to one. [1] pg. 118. */ - if (meta->msdu_length > IEEE802154_MAX_SAFE_MAC_PAYLOAD_SIZE) + if ((frame->io_len - frame->io_offset) > IEEE802154_MAX_SAFE_MAC_PAYLOAD_SIZE) { *frame_ctrl |= IEEE802154_FRAMECTRL_VERSION; } diff --git a/wireless/ieee802154/mac802154_device.c b/wireless/ieee802154/mac802154_device.c index d78e7acfdc..6ea212ae53 100644 --- a/wireless/ieee802154/mac802154_device.c +++ b/wireless/ieee802154/mac802154_device.c @@ -449,9 +449,9 @@ static ssize_t mac802154dev_write(FAR struct file *filep, iob->io_offset = ret; iob->io_len = iob->io_offset; - memcpy(&iob->io_data[iob->io_offset], tx->payload, tx->meta.msdu_length); + memcpy(&iob->io_data[iob->io_offset], tx->payload, tx->length); - iob->io_len += tx->meta.msdu_length; + iob->io_len += tx->length; /* If this is a blocking operation, we need to setup a wait struct so we * can unblock when the packet transmission has finished. If this is a -- GitLab From 0eb7ec046ed31b2831cd9958c8557f0845836db4 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 5 May 2017 11:36:16 -0600 Subject: [PATCH 732/990] 6loWPAN: Use information in struct ieee802154_data_ind_s when reassembling a packet --- include/nuttx/net/netdev.h | 8 +-- include/nuttx/net/sixlowpan.h | 6 +- net/sixlowpan/sixlowpan_input.c | 76 +++++++++++++++++++++--- wireless/ieee802154/mac802154_loopback.c | 5 +- 4 files changed, 78 insertions(+), 17 deletions(-) diff --git a/include/nuttx/net/netdev.h b/include/nuttx/net/netdev.h index 0b65d2afd3..782c2e3399 100644 --- a/include/nuttx/net/netdev.h +++ b/include/nuttx/net/netdev.h @@ -436,12 +436,12 @@ int ipv6_input(FAR struct net_driver_s *dev); #endif #ifdef CONFIG_NET_6LOWPAN -struct ieee802154_driver_s; /* See sixlowpan.h */ -struct eee802154_data_ind_s; /* See sixlowpan.h */ -struct iob_s; /* See iob.h */ +struct ieee802154_driver_s; /* See sixlowpan.h */ +struct ieee802154_data_ind_s; /* See ieee8021454_mac.h */ +struct iob_s; /* See iob.h */ int sixlowpan_input(FAR struct ieee802154_driver_s *ieee, FAR struct iob_s *framelist, - FAR const struct eee802154_data_ind_s *ind); + FAR const struct ieee802154_data_ind_s *ind); #endif /**************************************************************************** diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index 591687bb1d..a99f0e5e67 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -342,7 +342,7 @@ */ struct ieee802154_frame_meta_s; /* Forward reference */ -struct eee802154_data_ind_s; /* Forward reference */ +struct ieee802154_data_ind_s; /* Forward reference */ struct iob_s; /* Forward reference */ struct ieee802154_driver_s @@ -421,7 +421,7 @@ struct ieee802154_driver_s /* The source MAC address of the fragments being merged */ - union sixlowpan_anyaddr_u i_fragsrc; + struct sixlowpan_tagaddr_s i_fragsrc; /* That time at which reassembly was started. If the elapsed time * exceeds CONFIG_NET_6LOWPAN_MAXAGE, then the reassembly will @@ -540,7 +540,7 @@ struct ieee802154_driver_s int sixlowpan_input(FAR struct ieee802154_driver_s *ieee, FAR struct iob_s *framelist, - FAR const struct eee802154_data_ind_s *ind); + FAR const struct ieee802154_data_ind_s *ind); #endif /* CONFIG_NET_6LOWPAN */ #endif /* __INCLUDE_NUTTX_NET_SIXLOWPAN_H */ diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index 3c203d07a1..9739ab7f61 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -61,6 +61,7 @@ #include "nuttx/net/netdev.h" #include "nuttx/net/ip.h" #include "nuttx/net/sixlowpan.h" +#include "nuttx/wireless/ieee802154/ieee802154_mac.h" #ifdef CONFIG_NET_PKT # include "pkt/pkt.h" @@ -129,6 +130,55 @@ static uint8_t g_bitbucket[UNCOMP_MAXHDR]; * Private Functions ****************************************************************************/ +/**************************************************************************** + * Name: sixlowpan_compare_fragsrc + * + * Description: + * Check if the fragment that we just received is from the same source as + * the previosly received fragements. + * + * Input Parameters: + * ieee - IEEE 802.15.4 MAC driver state reference + * ind - Characteristics of the newly received frame + * + * Returned Value: + * true if the sources are the same. + * + ****************************************************************************/ + +static bool sixlowpan_compare_fragsrc(FAR struct ieee802154_driver_s *ieee, + FAR const struct ieee802154_data_ind_s *ind) +{ + /* Check for an extended source address */ + + if (ind->src.mode == IEEE802154_ADDRMODE_EXTENDED) + { + /* Was the first source address also extended? */ + + if (ieee->i_fragsrc.extended) + { + /* Yes.. perform the extended address comparison */ + + return sixlowpan_eaddrcmp(ieee->i_fragsrc.u.eaddr.u8, ind->src.eaddr); + } + } + else + { + /* Short source address. Was the first source address also short? */ + + if (!ieee->i_fragsrc.extended) + { + /* Yes.. perform the extended short comparison */ + + return sixlowpan_saddrcmp(ieee->i_fragsrc.u.saddr.u8, &ind->src.saddr); + } + } + + /* Address are different size and, hence, cannot match */ + + return false; +} + /**************************************************************************** * Name: sixlowpan_compress_ipv6hdr * @@ -235,6 +285,7 @@ static void sixlowpan_uncompress_ipv6hdr(FAR uint8_t *fptr, FAR uint8_t *bptr) * * Input Parameters: * ieee - The IEEE802.15.4 MAC network driver interface. + * ind - Meta data characterizing the received frame. * iob - The IOB containing the frame. * * Returned Value: @@ -246,6 +297,7 @@ static void sixlowpan_uncompress_ipv6hdr(FAR uint8_t *fptr, FAR uint8_t *bptr) ****************************************************************************/ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, + FAR const struct ieee802154_data_ind_s *ind, FAR struct iob_s *iob) { FAR uint8_t *fptr; /* Convenience pointer to beginning of the frame */ @@ -401,8 +453,8 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, /* Verify that this fragment is part of that reassembly sequence */ - else if (fragsize != ieee->i_pktlen || ieee->i_reasstag != fragtag /* || - !sixlowpan_addrcmp(&ieee->i_fragsrc, &ind->???) */) + else if (fragsize != ieee->i_pktlen || ieee->i_reasstag != fragtag || + !sixlowpan_compare_fragsrc(ieee, ind)) { /* The packet is a fragment that does not belong to the packet * being reassembled or the packet is not a fragment. @@ -459,10 +511,16 @@ static int sixlowpan_frame_process(FAR struct ieee802154_driver_s *ieee, * address. */ -#warning Missing logic -#if 0 - sixlowpan_addrcopy(&ieee->i_fragsrc, ind->???]); -#endif + if (ind->src.mode == IEEE802154_ADDRMODE_EXTENDED) + { + ieee->i_fragsrc.extended = true; + sixlowpan_eaddrcopy(ieee->i_fragsrc.u.eaddr.u8, ind->src.eaddr); + } + else + { + memset(&ieee->i_fragsrc, 0, sizeof(struct sixlowpan_tagaddr_s)); + sixlowpan_saddrcopy(ieee->i_fragsrc.u.saddr.u8, &ind->src.saddr); + } } #endif /* CONFIG_NET_6LOWPAN_FRAG */ @@ -698,7 +756,7 @@ static int sixlowpan_dispatch(FAR struct ieee802154_driver_s *ieee) * framelist - The head of an incoming list of frames. Normally this * would be a single frame. A list may be provided if * appropriate, however. - * ind - Meta data characterizing the received packet. If there are + * ind - Meta data characterizing the received frame. If there are * multilple frames in the list, this meta data must apply to * all of the frames! * @@ -709,7 +767,7 @@ static int sixlowpan_dispatch(FAR struct ieee802154_driver_s *ieee) int sixlowpan_input(FAR struct ieee802154_driver_s *ieee, FAR struct iob_s *framelist, - FAR const struct eee802154_data_ind_s *ind) + FAR const struct ieee802154_data_ind_s *ind) { int ret = -EINVAL; @@ -730,7 +788,7 @@ int sixlowpan_input(FAR struct ieee802154_driver_s *ieee, /* Process the frame, decompressing it into the packet buffer */ - ret = sixlowpan_frame_process(ieee, iob); + ret = sixlowpan_frame_process(ieee, ind, iob); /* Free the IOB the held the consumed frame */ diff --git a/wireless/ieee802154/mac802154_loopback.c b/wireless/ieee802154/mac802154_loopback.c index f30953a386..47940329c7 100644 --- a/wireless/ieee802154/mac802154_loopback.c +++ b/wireless/ieee802154/mac802154_loopback.c @@ -176,9 +176,12 @@ static int lo_req_data(FAR struct ieee802154_driver_s *netdev, static int lo_loopback(FAR struct net_driver_s *dev) { FAR struct lo_driver_s *priv = (FAR struct lo_driver_s *)dev->d_private; + struct ieee802154_data_ind_s ind; FAR struct iob_s *iob; int ret; + memset(&ind, 0, sizeof(struct ieee802154_data_ind_s)); + /* Loop while there framelist to be sent, i.e., while the freme list is not * emtpy. Sending, of course, just means relaying back through the network * for this driver. @@ -210,7 +213,7 @@ static int lo_loopback(FAR struct net_driver_s *dev) ninfo("Send frame %p to the network: Offset=%u Length=%u\n", iob, iob->io_offset, iob->io_len); - ret = sixlowpan_input(&priv->lo_ieee, iob, NULL); + ret = sixlowpan_input(&priv->lo_ieee, iob, &ind); /* Increment statistics */ -- GitLab From 3fcdc28a59a640bfe0482a381933694a40b271ac Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 5 May 2017 12:50:34 -0600 Subject: [PATCH 733/990] ieee 802.15.4: Add a pool-based memory allocator for RX frame meta-data. --- .../wireless/ieee802154/ieee802154_mac.h | 3 + wireless/ieee802154/Kconfig | 29 ++ wireless/ieee802154/Make.defs | 2 + wireless/ieee802154/mac802154.c | 65 ++++ wireless/ieee802154/mac802154.h | 2 + wireless/ieee802154/mac802154_indalloc.c | 367 ++++++++++++++++++ 6 files changed, 468 insertions(+) create mode 100644 wireless/ieee802154/mac802154_indalloc.c diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index d4046bccb2..bc3dfd3bce 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -652,10 +652,13 @@ struct ieee802154_data_conf_s struct ieee802154_data_ind_s { + FAR struct ieee802154_data_ind_s *flink; + struct ieee802154_addr_s src; /* Source addressing information */ struct ieee802154_addr_s dest; /* Destination addressing infromation */ uint8_t lqi; /* Link Quality Index */ uint8_t dsn; /* Data Sequence Number */ + uint8_t pool; /* Memory pool (Needed for deallocation) */ uint32_t timestamp; /* Time of received frame */ #ifdef CONFIG_IEEE802154_SECURITY diff --git a/wireless/ieee802154/Kconfig b/wireless/ieee802154/Kconfig index aa3f16219c..77f194d6ef 100644 --- a/wireless/ieee802154/Kconfig +++ b/wireless/ieee802154/Kconfig @@ -60,6 +60,35 @@ config IEEE802154_NTXDESC endif # IEEE802154_MAC +config IEEE802154_IND_PREALLOC + int "Number of pre-allocated meta-data structures" + default 20 + ---help--- + This specifies the total number of preallocated meta data structures + must be allocated with each incoming packet. These may be allocated + from either from tasking logic or from interrupt level logic. + +config IEEE802154_IND_IRQRESERVE + int "Rserved pre-allocated meta-data structures" + default 10 + ---help--- + If meta-data structures can be allocated from interrupt handlers, + then this specifies the number of pre-allocatd meta-data structures + that are reserved for for use only by interrupt handlers. This may + be zero to reserve no meta-data structures for interrupt handlers. + In that case, the allocation will fail if tasking logic has + allocated them all. + + Interrupt logic will first attempt to allocate fromt the general, + pre-allocated structure pool that will contain up to (size + CONFIG_IEEE802154_IND_PREALLOC - CONFIG_IEEE802154_IND_IRQRESERVE) + entries. If that fails, then it will try to take a structure from + the reserve (size CONFIG_IEEE802154_IND_IRQRESERVE). + + Non-interrupt logic will also first attempt to allocate fromt the + general, pre-allocated structure pool. If that fails, it will + dynamically allocate the meta data structure with an additional cost in performance. + config IEEE802154_NETDEV bool "IEEE802154 6loWPAN Network Device" default n diff --git a/wireless/ieee802154/Make.defs b/wireless/ieee802154/Make.defs index da84b153a7..73354b2609 100644 --- a/wireless/ieee802154/Make.defs +++ b/wireless/ieee802154/Make.defs @@ -37,6 +37,8 @@ ifeq ($(CONFIG_WIRELESS_IEEE802154),y) # Include IEEE 802.15.4 support +CSRCS += mac802154_indalloc.c + # Include wireless devices build support ifeq ($(CONFIG_IEEE802154_MAC),y) diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index 0f548841c2..46073765b6 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -1605,3 +1605,68 @@ int mac802154_resp_orphan(MACHANDLE mac, (FAR struct ieee802154_privmac_s *)mac; return -ENOTTY; } + +/**************************************************************************** + * Name: ieee802154_indpool_initialize + * + * Description: + * This function initializes the meta-data allocator. This function must + * be called early in the initialization sequence before any radios + * begin operation. + * + * Inputs: + * None + * + * Return Value: + * None + * + ****************************************************************************/ + +void ieee802154_indpool_initialize(void); + +/**************************************************************************** + * Name: ieee802154_ind_allocate + * + * Description: + * The ieee802154_ind_allocate function will get a free meta-data + * structure for use by the IEEE 802.15.4 MAC. + * + * Interrupt handling logic will first attempt to allocate from the + * g_indfree list. If that list is empty, it will attempt to allocate + * from its reserve, g_indfree_irq. If that list is empty, then the + * allocation fails (NULL is returned). + * + * Non-interrupt handler logic will attempt to allocate from g_indfree + * list. If that the list is empty, then the meta-data structure will be + * allocated from the dynamic memory pool. + * + * Inputs: + * None + * + * Return Value: + * A reference to the allocated msg structure. All user fields in this + * structure have been zeroed. On a failure to allocate, NULL is + * returned. + * + ****************************************************************************/ + +FAR struct ieee802154_data_ind_s *ieee802154_ind_allocate(void); + +/**************************************************************************** + * Name: ieee802154_ind_free + * + * Description: + * The ieee802154_ind_free function will return a meta-data structure to + * the free pool of messages if it was a pre-allocated meta-data + * structure. If the meta-data structure was allocated dynamically it will + * be deallocated. + * + * Inputs: + * ind - meta-data structure to free + * + * Return Value: + * None + * + ****************************************************************************/ + +void ieee802154_ind_free(FAR struct ieee802154_data_ind_s *ind); diff --git a/wireless/ieee802154/mac802154.h b/wireless/ieee802154/mac802154.h index b98fa0d360..152046b61f 100644 --- a/wireless/ieee802154/mac802154.h +++ b/wireless/ieee802154/mac802154.h @@ -58,6 +58,8 @@ * Public Function Prototypes ****************************************************************************/ +struct iob_s; /* Forward reference */ + /**************************************************************************** * Name: mac802154_bind * diff --git a/wireless/ieee802154/mac802154_indalloc.c b/wireless/ieee802154/mac802154_indalloc.c new file mode 100644 index 0000000000..84ec3b131a --- /dev/null +++ b/wireless/ieee802154/mac802154_indalloc.c @@ -0,0 +1,367 @@ +/**************************************************************************** + * wireless/ieee802154_indalloc.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include +#include + +#include "mac802154.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#if !defined(CONFIG_IEEE802154_IND_PREALLOC) || CONFIG_IEEE802154_IND_PREALLOC < 0 +# undef CONFIG_IEEE802154_IND_PREALLOC +# define CONFIG_IEEE802154_IND_PREALLOC 20 +#endif + +#if !defined(CONFIG_IEEE802154_IND_IRQRESERVE) || CONFIG_IEEE802154_IND_IRQRESERVE < 0 +# undef CONFIG_IEEE802154_IND_IRQRESERVE +# define CONFIG_IEEE802154_IND_IRQRESERVE 10 +#endif + +#if CONFIG_IEEE802154_IND_IRQRESERVE > CONFIG_IEEE802154_IND_PREALLOC +# undef CONFIG_IEEE802154_IND_IRQRESERVE +# define CONFIG_IEEE802154_IND_IRQRESERVE CONFIG_IEEE802154_IND_PREALLOC +#endif + +/* Memory Pools */ + +#define POOL_IND_GENERAL 0 +#define POOL_IND_IRQ 1 +#define POOL_IND_DYNAMIC 2 + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +#if CONFIG_IEEE802154_IND_PREALLOC > 0 +#if CONFIG_IEEE802154_IND_PREALLOC > CONFIG_IEEE802154_IND_IRQRESERVE +/* The g_indfree is a list of meta-data structures that are available for + * general use. The number of messages in this list is a system configuration + * item. + */ + +static struct ieee802154_data_ind_s *g_indfree; +#endif + +#if CONFIG_IEEE802154_IND_IRQRESERVE > 0 +/* The g_indfree_irq is a list of meta-data structures that are reserved for + * use by only by interrupt handlers. + */ + +static struct ieee802154_data_ind_s *g_indfree_irq; +#endif + +/* Pool of pre-allocated meta-data stuctures */ + +static struct ieee802154_data_ind_s g_indpool[CONFIG_IEEE802154_IND_PREALLOC]; +#endif /* CONFIG_IEEE802154_IND_PREALLOC > 0 */ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: ieee802154_indpool_initialize + * + * Description: + * This function initializes the meta-data allocator. This function must + * be called early in the initialization sequence before any radios + * begin operation. + * + * Inputs: + * None + * + * Return Value: + * None + * + ****************************************************************************/ + +void ieee802154_indpool_initialize(void) +{ +#if CONFIG_IEEE802154_IND_PREALLOC > 0 + FAR struct ieee802154_data_ind_s *pool = g_indpool; + int remaining = CONFIG_IEEE802154_IND_PREALLOC; + +#if CONFIG_IEEE802154_IND_PREALLOC > CONFIG_IEEE802154_IND_IRQRESERVE + /* Initialize g_indfree, thelist of meta-data structures that are available + * for general use. + */ + + g_indfree = NULL; + while (remaining > CONFIG_IEEE802154_IND_IRQRESERVE) + { + FAR struct ieee802154_data_ind_s *ind = pool; + + /* Add the next meta data structure from the pool to the list of + * general structures. + */ + + ind->flink = g_indfree; + g_indfree = ind; + + /* Set up for the next structure from the pool */ + + pool++; + remaining--; + } +#endif + +#if CONFIG_IEEE802154_IND_IRQRESERVE > 0 + /* Initialize g_indfree_irq is a list of meta-data structures reserved for + * use by only by interrupt handlers. + */ + + g_indfree_irq = NULL; + while (remaining > 0) + { + FAR struct ieee802154_data_ind_s *ind = pool; + + /* Add the next meta data structure from the pool to the list of + * general structures. + */ + + ind->flink = g_indfree_irq; + g_indfree_irq = ind; + + /* Set up for the next structure from the pool */ + + pool++; + remaining--; + } +#endif +#endif /* CONFIG_IEEE802154_IND_PREALLOC > 0 */ +} + +/**************************************************************************** + * Name: ieee802154_ind_allocate + * + * Description: + * The ieee802154_ind_allocate function will get a free meta-data + * structure for use by the IEEE 802.15.4 MAC. + * + * Interrupt handling logic will first attempt to allocate from the + * g_indfree list. If that list is empty, it will attempt to allocate + * from its reserve, g_indfree_irq. If that list is empty, then the + * allocation fails (NULL is returned). + * + * Non-interrupt handler logic will attempt to allocate from g_indfree + * list. If that the list is empty, then the meta-data structure will be + * allocated from the dynamic memory pool. + * + * Inputs: + * None + * + * Return Value: + * A reference to the allocated msg structure. All user fields in this + * structure have been zeroed. On a failure to allocate, NULL is + * returned. + * + ****************************************************************************/ + +FAR struct ieee802154_data_ind_s *ieee802154_ind_allocate(void) +{ +#if CONFIG_IEEE802154_IND_PREALLOC > 0 + FAR struct ieee802154_data_ind_s *ind; + irqstate_t flags; + uint8_t pool; + + /* If we were called from an interrupt handler, then try to get the meta- + * data structure from generally available list of messages. If this fails, + * then try the list of messages reserved for interrupt handlers + */ + + flags = enter_critical_section(); /* Always necessary in SMP mode */ + if (up_interrupt_context()) + { +#if CONFIG_IEEE802154_IND_PREALLOC > CONFIG_IEEE802154_IND_IRQRESERVE + /* Try the general free list */ + + if (g_indfree != NULL) + { + ind = g_indfree; + g_indfree = ind->flink; + + leave_critical_section(flags); + pool = POOL_IND_GENERAL; + } + else +#endif +#if CONFIG_IEEE802154_IND_IRQRESERVE > 0 + /* Try the list list reserved for interrupt handlers */ + + if (g_indfree_irq != NULL) + { + ind = g_indfree_irq; + g_indfree_irq = ind->flink; + + leave_critical_section(flags); + pool = POOL_IND_IRQ; + } + else +#endif + { + leave_critical_section(flags); + return NULL; + } + } + + /* We were not called from an interrupt handler. */ + + else + { +#if CONFIG_IEEE802154_IND_PREALLOC > CONFIG_IEEE802154_IND_IRQRESERVE + /* Try the general free list */ + + if (g_indfree != NULL) + { + ind = g_indfree; + g_indfree = ind->flink; + + leave_critical_section(flags); + pool = POOL_IND_GENERAL; + } + else +#endif + { + /* If we cannot a meta-data structure from the free list, then we + * will have to allocate one from the kernal memory pool. + */ + + leave_critical_section(flags); + ind = (FAR struct ieee802154_data_ind_s *) + kmm_malloc((sizeof (struct ieee802154_data_ind_s))); + + /* Check if we allocated the meta-data structure */ + + if (ind != NULL) + { + /* Yes... remember that this meta-data structure was dynamically allocated */ + + pool = POOL_IND_DYNAMIC; + } + } + } + + /* We have successfully allocated memory from some source. + * Zero and tag the alloated meta-data structure. + */ + + memset(ind, 0, sizeof(struct ieee802154_data_ind_s)); + ind->pool = pool; + return ind; +#else + return NULL; +#endif +} + +/**************************************************************************** + * Name: ieee802154_ind_free + * + * Description: + * The ieee802154_ind_free function will return a meta-data structure to + * the free pool of messages if it was a pre-allocated meta-data + * structure. If the meta-data structure was allocated dynamically it will + * be deallocated. + * + * Inputs: + * ind - meta-data structure to free + * + * Return Value: + * None + * + ****************************************************************************/ + +void ieee802154_ind_free(FAR struct ieee802154_data_ind_s *ind) +{ +#if CONFIG_IEEE802154_IND_PREALLOC > 0 + irqstate_t flags; + +#if CONFIG_IEEE802154_IND_PREALLOC > CONFIG_IEEE802154_IND_IRQRESERVE + /* If this is a generally available pre-allocated meta-data structure, + * then just put it back in the free list. + */ + + if (ind->pool == POOL_IND_GENERAL) + { + /* Make sure we avoid concurrent access to the free + * list from interrupt handlers. + */ + + flags = enter_critical_section(); + ind->flink = g_indfree; + g_indfree = ind; + leave_critical_section(flags); + } + else +#endif + +#if CONFIG_IEEE802154_IND_IRQRESERVE > 0 + /* If this is a meta-data structure pre-allocated for interrupts, + * then put it back in the correct free list. + */ + + if (ind->pool == POOL_IND_IRQ) + { + /* Make sure we avoid concurrent access to the free + * list from interrupt handlers. + */ + + flags = enter_critical_section(); + ind->flink = g_indfree_irq; + g_indfree_irq = ind; + leave_critical_section(flags); + } + else +#endif + + { + /* Otherwise, deallocate it. */ + + DEBUGASSERT(ind->pool == POOL_IND_DYNAMIC); + sched_kfree(ind); + } +#endif +} -- GitLab From a1a68216a9d38b087462e468f984582f89f3d8dc Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 5 May 2017 14:43:44 -0600 Subject: [PATCH 734/990] Trivial changes to spacing --- wireless/ieee802154/mac802154_indalloc.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/wireless/ieee802154/mac802154_indalloc.c b/wireless/ieee802154/mac802154_indalloc.c index 84ec3b131a..86d8dcd0ef 100644 --- a/wireless/ieee802154/mac802154_indalloc.c +++ b/wireless/ieee802154/mac802154_indalloc.c @@ -163,8 +163,8 @@ void ieee802154_indpool_initialize(void) * general structures. */ - ind->flink = g_indfree_irq; - g_indfree_irq = ind; + ind->flink = g_indfree_irq; + g_indfree_irq = ind; /* Set up for the next structure from the pool */ -- GitLab From 1cd3b3f590bf821e8f93e14f5c5318ebce16f982 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 5 May 2017 14:47:11 -0600 Subject: [PATCH 735/990] Fix errors introduced into Kinetis serial when I unsuccessfully tried to correct coding standard violations. Folks, things will be better for everyone if you just follow that standard. --- arch/arm/src/kinetis/kinetis_lpserial.c | 10 +++++++--- arch/arm/src/kinetis/kinetis_serial.c | 6 +++++- 2 files changed, 12 insertions(+), 4 deletions(-) diff --git a/arch/arm/src/kinetis/kinetis_lpserial.c b/arch/arm/src/kinetis/kinetis_lpserial.c index 117dd3de4a..515f1f370e 100644 --- a/arch/arm/src/kinetis/kinetis_lpserial.c +++ b/arch/arm/src/kinetis/kinetis_lpserial.c @@ -615,12 +615,12 @@ static int kinetis_ioctl(struct file *filep, int cmd, unsigned long arg) { #if defined(CONFIG_SERIAL_TERMIOS) || defined(CONFIG_SERIAL_TIOCSERGSTRUCT) || \ defined(CONFIG_KINETIS_SERIALBRK_BSDCOMPAT) - struct inode *inode = filep->f_inode; - struct uart_dev_s *dev = inode->i_private; + struct inode *inode; + struct uart_dev_s *dev; uint8_t regval; #endif #if defined(CONFIG_SERIAL_TERMIOS) || defined(CONFIG_KINETIS_SERIALBRK_BSDCOMPAT) - struct kinetis_dev_s *priv = (struct kinetis_dev_s *)dev->priv; + struct kinetis_dev_s *priv; bool iflow = false; bool oflow = false; #endif @@ -634,6 +634,10 @@ static int kinetis_ioctl(struct file *filep, int cmd, unsigned long arg) DEBUGASSERT(dev != NULL && dev->priv != NULL); #endif +#if defined(CONFIG_SERIAL_TERMIOS) || defined(CONFIG_KINETIS_SERIALBRK_BSDCOMPAT) + priv = (struct kinetis_dev_s *)dev->priv; +#endif + switch (cmd) { #ifdef CONFIG_SERIAL_TIOCSERGSTRUCT diff --git a/arch/arm/src/kinetis/kinetis_serial.c b/arch/arm/src/kinetis/kinetis_serial.c index b7c6aeebc7..0f2a4b2ee4 100644 --- a/arch/arm/src/kinetis/kinetis_serial.c +++ b/arch/arm/src/kinetis/kinetis_serial.c @@ -980,7 +980,7 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg) uint8_t regval; #endif #if defined(CONFIG_SERIAL_TERMIOS) || defined(CONFIG_KINETIS_SERIALBRK_BSDCOMPAT) - struct up_dev_s *priv = (struct up_dev_s *)dev->priv; + struct up_dev_s *priv; bool iflow = false; bool oflow = false; #endif @@ -994,6 +994,10 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg) DEBUGASSERT(dev != NULL && dev->priv != NULL); #endif +#if defined(CONFIG_SERIAL_TERMIOS) || defined(CONFIG_KINETIS_SERIALBRK_BSDCOMPAT) + priv = (struct up_dev_s *)dev->priv; +#endif + switch (cmd) { #ifdef CONFIG_SERIAL_TIOCSERGSTRUCT -- GitLab From 979e671cf0e403540a2c20093417894d77db5a9d Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Fri, 5 May 2017 15:02:55 -1000 Subject: [PATCH 736/990] kinetis:k20 Pin mux configure all I2C signals as Open Drain The output structure of the GPIO for I2C needs to be open drain. When left at the default, one can observe on a scope the slave contending with the push-pull during the ACK --- arch/arm/src/kinetis/chip/kinetis_k20pinmux.h | 21 ++++++++++--------- 1 file changed, 11 insertions(+), 10 deletions(-) diff --git a/arch/arm/src/kinetis/chip/kinetis_k20pinmux.h b/arch/arm/src/kinetis/chip/kinetis_k20pinmux.h index ca708acfdf..d77ea96270 100644 --- a/arch/arm/src/kinetis/chip/kinetis_k20pinmux.h +++ b/arch/arm/src/kinetis/chip/kinetis_k20pinmux.h @@ -1,8 +1,9 @@ /******************************************************************************************** * arch/arm/src/kinetis/chip/kinetis_k20pinmux.h * - * Copyright (C) 2015-2016 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Copyright (C) 2015-2017 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * David Sidrane * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -159,14 +160,14 @@ # define PIN_FTM2_QD_PHA (PIN_ALT6 | PIN_PORTB | PIN18) # define PIN_FTM2_QD_PHB (PIN_ALT6 | PIN_PORTB | PIN19) -# define PIN_I2C0_SCL_1 (PIN_ALT2 | PIN_PORTB | PIN0) -# define PIN_I2C0_SCL_2 (PIN_ALT2 | PIN_PORTB | PIN2) -# define PIN_I2C0_SDA_1 (PIN_ALT2 | PIN_PORTB | PIN1) -# define PIN_I2C0_SDA_2 (PIN_ALT2 | PIN_PORTB | PIN3) -# define PIN_I2C1_SCL_1 (PIN_ALT2 | PIN_PORTC | PIN10) -# define PIN_I2C1_SCL_2 (PIN_ALT6 | PIN_PORTE | PIN1) -# define PIN_I2C1_SDA_1 (PIN_ALT2 | PIN_PORTC | PIN11) -# define PIN_I2C1_SDA_2 (PIN_ALT6 | PIN_PORTE | PIN0) +# define PIN_I2C0_SCL_1 (PIN_ALT2_OPENDRAIN | PIN_PORTB | PIN0) +# define PIN_I2C0_SCL_2 (PIN_ALT2_OPENDRAIN | PIN_PORTB | PIN2) +# define PIN_I2C0_SDA_1 (PIN_ALT2_OPENDRAIN | PIN_PORTB | PIN1) +# define PIN_I2C0_SDA_2 (PIN_ALT2_OPENDRAIN | PIN_PORTB | PIN3) +# define PIN_I2C1_SCL_1 (PIN_ALT2_OPENDRAIN | PIN_PORTC | PIN10) +# define PIN_I2C1_SCL_2 (PIN_ALT6_OPENDRAIN | PIN_PORTE | PIN1) +# define PIN_I2C1_SDA_1 (PIN_ALT2_OPENDRAIN | PIN_PORTC | PIN11) +# define PIN_I2C1_SDA_2 (PIN_ALT6_OPENDRAIN | PIN_PORTE | PIN0) # define PIN_I2S0_MCLK_1 (PIN_ALT4 | PIN_PORTC | PIN8) # define PIN_I2S0_MCLK_2 (PIN_ALT6 | PIN_PORTC | PIN6) -- GitLab From 1d9d13c426d9463fb7c14d66329bb8d08e05789b Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Fri, 5 May 2017 15:02:55 -1000 Subject: [PATCH 737/990] kinetis:k40 Pin mux configure all I2C signals as Open Drain The output structure of the GPIO for I2C needs to be open drain. When left at the default, one can observe on a scope the slave contending with the push-pull during the ACK --- arch/arm/src/kinetis/chip/kinetis_k40pinmux.h | 21 ++++++++++--------- 1 file changed, 11 insertions(+), 10 deletions(-) diff --git a/arch/arm/src/kinetis/chip/kinetis_k40pinmux.h b/arch/arm/src/kinetis/chip/kinetis_k40pinmux.h index 7083b0caf7..c7570edaf9 100644 --- a/arch/arm/src/kinetis/chip/kinetis_k40pinmux.h +++ b/arch/arm/src/kinetis/chip/kinetis_k40pinmux.h @@ -1,8 +1,9 @@ /******************************************************************************************** * arch/arm/src/kinetis/chip/kinetis_k40pinmux.h * - * Copyright (C) 2011, 2016 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Copyright (C) 2011, 2016-2017 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * David Sidrane * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -160,7 +161,7 @@ #define PIN_ADC0_SE8 (PIN_ANALOG | PIN_PORTB | PIN0) #define PIN_ADC1_SE8 (PIN_ANALOG | PIN_PORTB | PIN0) #define PIN_TSI0_CH0 (PIN_ANALOG | PIN_PORTB | PIN0) -#define PIN_I2C0_SCL_1 (PIN_ALT2 | PIN_PORTB | PIN0) +#define PIN_I2C0_SCL_1 (PIN_ALT2_OPENDRAIN | PIN_PORTB | PIN0) #define PIN_FTM1_CH0_3 (PIN_ALT3 | PIN_PORTB | PIN0) #define PIN_FTM1_QD_PHA_3 (PIN_ALT6 | PIN_PORTB | PIN0) #define PIN_LCD_P0F (PIN_ALT7 | PIN_PORTB | PIN0) @@ -168,21 +169,21 @@ #define PIN_ADC0_SE9 (PIN_ANALOG | PIN_PORTB | PIN1) #define PIN_ADC1_SE9 (PIN_ANALOG | PIN_PORTB | PIN1) #define PIN_TSI0_CH6 (PIN_ANALOG | PIN_PORTB | PIN1) -#define PIN_I2C0_SDA_1 (PIN_ALT2 | PIN_PORTB | PIN1) +#define PIN_I2C0_SDA_1 (PIN_ALT2_OPENDRAIN | PIN_PORTB | PIN1) #define PIN_FTM1_CH1_3 (PIN_ALT3 | PIN_PORTB | PIN1) #define PIN_FTM1_QD_PHB (PIN_ALT6 | PIN_PORTB | PIN1) #define PIN_LCD_P1F (PIN_ALT7 | PIN_PORTB | PIN1) #define PIN_LCD_P2 (PIN_ANALOG | PIN_PORTB | PIN2) #define PIN_ADC0_SE12 (PIN_ANALOG | PIN_PORTB | PIN2) #define PIN_TSI0_CH7 (PIN_ANALOG | PIN_PORTB | PIN2) -#define PIN_I2C0_SCL_2 (PIN_ALT2 | PIN_PORTB | PIN2) +#define PIN_I2C0_SCL_2 (PIN_ALT2_OPENDRAIN| PIN_PORTB | PIN2) #define PIN_UART0_RTS_3 (PIN_ALT3 | PIN_PORTB | PIN2) #define PIN_FTM0_FLT3 (PIN_ALT6 | PIN_PORTB | PIN2) #define PIN_LCD_P2F (PIN_ALT7 | PIN_PORTB | PIN2) #define PIN_LCD_P3 (PIN_ANALOG | PIN_PORTB | PIN3) #define PIN_ADC0_SE13 (PIN_ANALOG | PIN_PORTB | PIN3) #define PIN_TSI0_CH8 (PIN_ANALOG | PIN_PORTB | PIN3) -#define PIN_I2C0_SDA_2 (PIN_ALT2 | PIN_PORTB | PIN3) +#define PIN_I2C0_SDA_2 (PIN_ALT2_OPENDRAIN | PIN_PORTB | PIN3) #define PIN_UART0_CTS_3 (PIN_ALT3 | PIN_PORTB | PIN3) #define PIN_FTM0_FLT0_1 (PIN_ALT6 | PIN_PORTB | PIN3) #define PIN_LCD_P3F (PIN_ALT7 | PIN_PORTB | PIN3) @@ -325,12 +326,12 @@ #define PIN_LCD_P30 (PIN_ANALOG | PIN_PORTC | PIN10) #define PIN_ADC1_SE6B (PIN_ANALOG | PIN_PORTC | PIN10) #define PIN_CMP0_IN4 (PIN_ANALOG | PIN_PORTC | PIN10) -#define PIN_I2C1_SCL_1 (PIN_ALT2 | PIN_PORTC | PIN10) +#define PIN_I2C1_SCL_1 (PIN_ALT2_OPENDRAIN | PIN_PORTC | PIN10) #define PIN_I2S0_RX_FS_2 (PIN_ALT4 | PIN_PORTC | PIN10) #define PIN_LCD_P30F (PIN_ALT7 | PIN_PORTC | PIN10) #define PIN_LCD_P31 (PIN_ANALOG | PIN_PORTC | PIN11) #define PIN_ADC1_SE7B (PIN_ANALOG | PIN_PORTC | PIN11) -#define PIN_I2C1_SDA_1 (PIN_ALT2 | PIN_PORTC | PIN11) +#define PIN_I2C1_SDA_1 (PIN_ALT2_OPENDRAIN | PIN_PORTC | PIN11) #define PIN_I2S0_RXD_2 (PIN_ALT4 | PIN_PORTC | PIN11) #define PIN_LCD_P31F (PIN_ALT7 | PIN_PORTC | PIN11) #define PIN_LCD_P32 (PIN_ANALOG | PIN_PORTC | PIN12) @@ -427,13 +428,13 @@ #define PIN_UART1_TX_2 (PIN_ALT3 | PIN_PORTE | PIN0) #define PIN_SDHC0_D1 (PIN_ALT4 | PIN_PORTE | PIN0) #define PIN_FB_AD27 (PIN_ALT5 | PIN_PORTE | PIN0) -#define PIN_I2C1_SDA_2 (PIN_ALT6 | PIN_PORTE | PIN0) +#define PIN_I2C1_SDA_2 (PIN_ALT6_OPENDRAIN | PIN_PORTE | PIN0) #define PIN_ADC1_SE5A (PIN_ANALOG | PIN_PORTE | PIN1) #define PIN_SPI1_SOUT_2 (PIN_ALT2 | PIN_PORTE | PIN1) #define PIN_UART1_RX_2 (PIN_ALT3 | PIN_PORTE | PIN1) #define PIN_SDHC0_D0 (PIN_ALT4 | PIN_PORTE | PIN1) #define PIN_FB_AD26 (PIN_ALT5 | PIN_PORTE | PIN1) -#define PIN_I2C1_SCL_2 (PIN_ALT6 | PIN_PORTE | PIN1) +#define PIN_I2C1_SCL_2 (PIN_ALT6_OPENDRAIN | PIN_PORTE | PIN1) #define PIN_ADC1_SE6A (PIN_ANALOG | PIN_PORTE | PIN2) #define PIN_SPI1_SCK_2 (PIN_ALT2 | PIN_PORTE | PIN2) #define PIN_UART1_CTS_2 (PIN_ALT3 | PIN_PORTE | PIN2) -- GitLab From af1f48c1c55f6ece27522f1082b554c6a246b9cc Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Fri, 5 May 2017 15:02:56 -1000 Subject: [PATCH 738/990] kinetis:k60 Pin mux configure all I2C signals as Open Drain The output structure of the GPIO for I2C needs to be open drain. When left at the default, one can observe on a scope the slave contending with the push-pull during the ACK --- arch/arm/src/kinetis/chip/kinetis_k60pinmux.h | 25 ++++++++++--------- 1 file changed, 13 insertions(+), 12 deletions(-) diff --git a/arch/arm/src/kinetis/chip/kinetis_k60pinmux.h b/arch/arm/src/kinetis/chip/kinetis_k60pinmux.h index 888a595584..b1ca87746f 100644 --- a/arch/arm/src/kinetis/chip/kinetis_k60pinmux.h +++ b/arch/arm/src/kinetis/chip/kinetis_k60pinmux.h @@ -1,8 +1,9 @@ /******************************************************************************************** * arch/arm/src/kinetis/chip/kinetis_k60pinset.h * - * Copyright (C) 2011, 2016 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Copyright (C) 2011, 2016-2017 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * David Sidrane * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -172,7 +173,7 @@ #define PIN_ADC0_SE8 (PIN_ANALOG | PIN_PORTB | PIN0) #define PIN_ADC1_SE8 (PIN_ANALOG | PIN_PORTB | PIN0) #define PIN_TSI0_CH0 (PIN_ANALOG | PIN_PORTB | PIN0) -#define PIN_I2C0_SCL_1 (PIN_ALT2 | PIN_PORTB | PIN0) +#define PIN_I2C0_SCL_1 (PIN_ALT2_OPENDRAIN | PIN_PORTB | PIN0) #define PIN_FTM1_CH0_3 (PIN_ALT3 | PIN_PORTB | PIN0) #ifdef CONFIG_KINETIS_ENET_MDIOPULLUP # define PIN_RMII0_MDIO (PIN_ALT4_PULLUP | PIN_PORTB | PIN0) @@ -184,20 +185,20 @@ #define PIN_ADC0_SE9 (PIN_ANALOG | PIN_PORTB | PIN1) #define PIN_ADC1_SE9 (PIN_ANALOG | PIN_PORTB | PIN1) #define PIN_TSI0_CH6 (PIN_ANALOG | PIN_PORTB | PIN1) -#define PIN_I2C0_SDA_1 (PIN_ALT2 | PIN_PORTB | PIN1) +#define PIN_I2C0_SDA_1 (PIN_ALT2_OPENDRAIN | PIN_PORTB | PIN1) #define PIN_FTM1_CH1_3 (PIN_ALT3 | PIN_PORTB | PIN1) #define PIN_RMII0_MDC (PIN_ALT4 | PIN_PORTB | PIN1) #define PIN_MII0_MDC (PIN_ALT4 | PIN_PORTB | PIN1) #define PIN_FTM1_QD_PHB_3 (PIN_ALT6 | PIN_PORTB | PIN1) #define PIN_ADC0_SE12 (PIN_ANALOG | PIN_PORTB | PIN2) #define PIN_TSI0_CH7 (PIN_ANALOG | PIN_PORTB | PIN2) -#define PIN_I2C0_SCL_2 (PIN_ALT2 | PIN_PORTB | PIN2) +#define PIN_I2C0_SCL_2 (PIN_ALT2_OPENDRAIN | PIN_PORTB | PIN2) #define PIN_UART0_RTS_3 (PIN_ALT3 | PIN_PORTB | PIN2) #define PIN_ENET0_1588_TMR0_1 (PIN_ALT4 | PIN_PORTB | PIN2) #define PIN_FTM0_FLT3 (PIN_ALT6 | PIN_PORTB | PIN2) #define PIN_ADC0_SE13 (PIN_ANALOG | PIN_PORTB | PIN3) #define PIN_TSI0_CH8 (PIN_ANALOG | PIN_PORTB | PIN3) -#define PIN_I2C0_SDA_2 (PIN_ALT2 | PIN_PORTB | PIN3) +#define PIN_I2C0_SDA_2 (PIN_ALT2_OPENDRAIN | PIN_PORTB | PIN3) #define PIN_UART0_CTS_3 (PIN_ALT3 | PIN_PORTB | PIN3) #define PIN_ENET0_1588_TMR1_1 (PIN_ALT4 | PIN_PORTB | PIN3) #define PIN_FTM0_FLT0_2 (PIN_ALT6 | PIN_PORTB | PIN3) @@ -313,11 +314,11 @@ #define PIN_FTM2_FLT0_2 (PIN_ALT6 | PIN_PORTC | PIN9) #define PIN_ADC1_SE6B (PIN_ANALOG | PIN_PORTC | PIN10) #define PIN_CMP0_IN4 (PIN_ANALOG | PIN_PORTC | PIN10) -#define PIN_I2C1_SCL_1 (PIN_ALT2 | PIN_PORTC | PIN10) +#define PIN_I2C1_SCL_1 (PIN_ALT2_OPENDRAIN | PIN_PORTC | PIN10) #define PIN_I2S0_RX_FS_2 (PIN_ALT4 | PIN_PORTC | PIN10) #define PIN_FB_AD5 (PIN_ALT5 | PIN_PORTC | PIN10) #define PIN_ADC1_SE7B (PIN_ANALOG | PIN_PORTC | PIN11) -#define PIN_I2C1_SDA_1 (PIN_ALT2 | PIN_PORTC | PIN11) +#define PIN_I2C1_SDA_1 (PIN_ALT2_OPENDRAIN | PIN_PORTC | PIN11) #define PIN_I2S0_RXD_2 (PIN_ALT4 | PIN_PORTC | PIN11) #define PIN_FB_RW (PIN_ALT5 | PIN_PORTC | PIN11) #define PIN_UART4_RTS_1 (PIN_ALT3 | PIN_PORTC | PIN12) @@ -387,10 +388,10 @@ #define PIN_UART0_TX_4 (PIN_ALT3 | PIN_PORTD | PIN7) #define PIN_FTM0_CH7_2 (PIN_ALT4 | PIN_PORTD | PIN7) #define PIN_FTM0_FLT1_2 (PIN_ALT6 | PIN_PORTD | PIN7) -#define PIN_I2C0_SCL_3 (PIN_ALT2 | PIN_PORTD | PIN8) +#define PIN_I2C0_SCL_3 (PIN_ALT2_OPENDRAIN | PIN_PORTD | PIN8) #define PIN_UART5_RX_1 (PIN_ALT3 | PIN_PORTD | PIN8) #define PIN_FB_A16 (PIN_ALT6 | PIN_PORTD | PIN8) -#define PIN_I2C0_SDA_3 (PIN_ALT2 | PIN_PORTD | PIN9) +#define PIN_I2C0_SDA_3 (PIN_ALT2_OPENDRAIN | PIN_PORTD | PIN9) #define PIN_UART5_TX_1 (PIN_ALT3 | PIN_PORTD | PIN9) #define PIN_FB_A17 (PIN_ALT6 | PIN_PORTD | PIN9) #define PIN_UART5_RTS_1 (PIN_ALT3 | PIN_PORTD | PIN10) @@ -416,12 +417,12 @@ #define PIN_SPI1_PCS1_2 (PIN_ALT2 | PIN_PORTE | PIN0) #define PIN_UART1_TX_2 (PIN_ALT3 | PIN_PORTE | PIN0) #define PIN_SDHC0_D1 (PIN_ALT4 | PIN_PORTE | PIN0) -#define PIN_I2C1_SDA_2 (PIN_ALT6 | PIN_PORTE | PIN0) +#define PIN_I2C1_SDA_2 (PIN_ALT6_OPENDRAIN | PIN_PORTE | PIN0) #define PIN_ADC1_SE5A (PIN_ANALOG | PIN_PORTE | PIN1) #define PIN_SPI1_SOUT_2 (PIN_ALT2 | PIN_PORTE | PIN1) #define PIN_UART1_RX_2 (PIN_ALT3 | PIN_PORTE | PIN1) #define PIN_SDHC0_D0 (PIN_ALT4 | PIN_PORTE | PIN1) -#define PIN_I2C1_SCL_2 (PIN_ALT6 | PIN_PORTE | PIN1) +#define PIN_I2C1_SCL_2 (PIN_ALT6_OPENDRAIN | PIN_PORTE | PIN1) #define PIN_ADC1_SE6A (PIN_ANALOG | PIN_PORTE | PIN2) #define PIN_SPI1_SCK_2 (PIN_ALT2 | PIN_PORTE | PIN2) #define PIN_UART1_CTS_2 (PIN_ALT3 | PIN_PORTE | PIN2) -- GitLab From ce98cedb17f0852eb93a08afb23447ef137848ff Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Fri, 5 May 2017 15:02:56 -1000 Subject: [PATCH 739/990] kinetis:k64 Pin mux configure all I2C signals as Open Drain The output structure of the GPIO for I2C needs to be open drain. When left at the default, one can observe on a scope the slave contending with the push-pull during the ACK --- arch/arm/src/kinetis/chip/kinetis_k64pinmux.h | 45 ++++++++++--------- 1 file changed, 23 insertions(+), 22 deletions(-) diff --git a/arch/arm/src/kinetis/chip/kinetis_k64pinmux.h b/arch/arm/src/kinetis/chip/kinetis_k64pinmux.h index 3479099bf6..d9894b3ff7 100644 --- a/arch/arm/src/kinetis/chip/kinetis_k64pinmux.h +++ b/arch/arm/src/kinetis/chip/kinetis_k64pinmux.h @@ -1,8 +1,9 @@ /******************************************************************************************** * arch/arm/src/kinetis/chip/kinetis_k64pinmux.h * - * Copyright (C) 2016 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Copyright (C) 2016-2017 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * David Sidrane * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -305,26 +306,26 @@ /* I2C */ -#define PIN_I2C0_SCL_1 (PIN_ALT2 | PIN_PORTB | PIN0) -#define PIN_I2C0_SCL_2 (PIN_ALT2 | PIN_PORTB | PIN2) -#define PIN_I2C0_SCL_3 (PIN_ALT2 | PIN_PORTD | PIN8) -#define PIN_I2C0_SCL_4 (PIN_ALT5 | PIN_PORTE | PIN24) -#define PIN_I2C0_SCL_5 (PIN_ALT7 | PIN_PORTD | PIN2) -#define PIN_I2C0_SDA_1 (PIN_ALT2 | PIN_PORTB | PIN1) -#define PIN_I2C0_SDA_2 (PIN_ALT2 | PIN_PORTB | PIN3) -#define PIN_I2C0_SDA_3 (PIN_ALT2 | PIN_PORTD | PIN9) -#define PIN_I2C0_SDA_4 (PIN_ALT5 | PIN_PORTE | PIN25) -#define PIN_I2C0_SDA_5 (PIN_ALT7 | PIN_PORTD | PIN3) - -#define PIN_I2C1_SCL_1 (PIN_ALT2 | PIN_PORTC | PIN10) -#define PIN_I2C1_SCL_2 (PIN_ALT6 | PIN_PORTE | PIN1) -#define PIN_I2C1_SDA_1 (PIN_ALT2 | PIN_PORTC | PIN11) -#define PIN_I2C1_SDA_2 (PIN_ALT6 | PIN_PORTE | PIN0) - -#define PIN_I2C2_SCL_1 (PIN_ALT5 | PIN_PORTA | PIN12) -#define PIN_I2C2_SCL_2 (PIN_ALT5 | PIN_PORTA | PIN14) -#define PIN_I2C2_SDA_1 (PIN_ALT5 | PIN_PORTA | PIN11) -#define PIN_I2C2_SDA_2 (PIN_ALT5 | PIN_PORTA | PIN13) +#define PIN_I2C0_SCL_1 (PIN_ALT2_OPENDRAIN | PIN_PORTB | PIN0) +#define PIN_I2C0_SCL_2 (PIN_ALT2_OPENDRAIN | PIN_PORTB | PIN2) +#define PIN_I2C0_SCL_3 (PIN_ALT2_OPENDRAIN | PIN_PORTD | PIN8) +#define PIN_I2C0_SCL_4 (PIN_ALT5_OPENDRAIN | PIN_PORTE | PIN24) +#define PIN_I2C0_SCL_5 (PIN_ALT7_OPENDRAIN | PIN_PORTD | PIN2) +#define PIN_I2C0_SDA_1 (PIN_ALT2_OPENDRAIN | PIN_PORTB | PIN1) +#define PIN_I2C0_SDA_2 (PIN_ALT2_OPENDRAIN | PIN_PORTB | PIN3) +#define PIN_I2C0_SDA_3 (PIN_ALT2_OPENDRAIN | PIN_PORTD | PIN9) +#define PIN_I2C0_SDA_4 (PIN_ALT5_OPENDRAIN | PIN_PORTE | PIN25) +#define PIN_I2C0_SDA_5 (PIN_ALT7_OPENDRAIN | PIN_PORTD | PIN3) + +#define PIN_I2C1_SCL_1 (PIN_ALT2_OPENDRAIN | PIN_PORTC | PIN10) +#define PIN_I2C1_SCL_2 (PIN_ALT6_OPENDRAIN | PIN_PORTE | PIN1) +#define PIN_I2C1_SDA_1 (PIN_ALT2_OPENDRAIN | PIN_PORTC | PIN11) +#define PIN_I2C1_SDA_2 (PIN_ALT6_OPENDRAIN | PIN_PORTE | PIN0) + +#define PIN_I2C2_SCL_1 (PIN_ALT5_OPENDRAIN | PIN_PORTA | PIN12) +#define PIN_I2C2_SCL_2 (PIN_ALT5_OPENDRAIN | PIN_PORTA | PIN14) +#define PIN_I2C2_SDA_1 (PIN_ALT5_OPENDRAIN | PIN_PORTA | PIN11) +#define PIN_I2C2_SDA_2 (PIN_ALT5_OPENDRAIN | PIN_PORTA | PIN13) /* I2S */ -- GitLab From 97260321f2ef52407b6d5e6dc274a9e5945177da Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Fri, 5 May 2017 15:02:57 -1000 Subject: [PATCH 740/990] kinetis:k66 Pin mux configure all I2C signals as Open Drain The output structure of the GPIO for I2C needs to be open drain. When left at the default, one can observe on a scope the slave contending with the push-pull during the ACK --- arch/arm/src/kinetis/chip/kinetis_k66pinmux.h | 50 +++++++++---------- 1 file changed, 25 insertions(+), 25 deletions(-) diff --git a/arch/arm/src/kinetis/chip/kinetis_k66pinmux.h b/arch/arm/src/kinetis/chip/kinetis_k66pinmux.h index b549f5c76d..ad15c5ac02 100644 --- a/arch/arm/src/kinetis/chip/kinetis_k66pinmux.h +++ b/arch/arm/src/kinetis/chip/kinetis_k66pinmux.h @@ -317,31 +317,31 @@ /* I2C */ -#define PIN_I2C0_SCL_1 (PIN_ALT2 | PIN_PORTB | PIN0) -#define PIN_I2C0_SCL_2 (PIN_ALT2 | PIN_PORTB | PIN2) -#define PIN_I2C0_SCL_3 (PIN_ALT2 | PIN_PORTD | PIN8) -#define PIN_I2C0_SCL_4 (PIN_ALT5 | PIN_PORTE | PIN24) -#define PIN_I2C0_SCL_5 (PIN_ALT7 | PIN_PORTD | PIN2) -#define PIN_I2C0_SDA_1 (PIN_ALT2 | PIN_PORTB | PIN1) -#define PIN_I2C0_SDA_2 (PIN_ALT2 | PIN_PORTB | PIN3) -#define PIN_I2C0_SDA_3 (PIN_ALT2 | PIN_PORTD | PIN9) -#define PIN_I2C0_SDA_4 (PIN_ALT5 | PIN_PORTE | PIN25) -#define PIN_I2C0_SDA_5 (PIN_ALT7 | PIN_PORTD | PIN3) - -#define PIN_I2C1_SCL_1 (PIN_ALT2 | PIN_PORTC | PIN10) -#define PIN_I2C1_SCL_2 (PIN_ALT6 | PIN_PORTE | PIN1) -#define PIN_I2C1_SDA_1 (PIN_ALT2 | PIN_PORTC | PIN11) -#define PIN_I2C1_SDA_2 (PIN_ALT6 | PIN_PORTE | PIN0) - -#define PIN_I2C2_SCL_1 (PIN_ALT5 | PIN_PORTA | PIN12) -#define PIN_I2C2_SCL_2 (PIN_ALT5 | PIN_PORTA | PIN14) -#define PIN_I2C2_SDA_1 (PIN_ALT5 | PIN_PORTA | PIN11) -#define PIN_I2C2_SDA_2 (PIN_ALT5 | PIN_PORTA | PIN13) - -#define PIN_I2C3_SCL_1 (PIN_ALT2 | PIN_PORTE | PIN11) -#define PIN_I2C3_SCL_2 (PIN_ALT4 | PIN_PORTA | PIN2) -#define PIN_I2C3_SDA_1 (PIN_ALT2 | PIN_PORTE | PIN10) -#define PIN_I2C3_SDA_2 (PIN_ALT4 | PIN_PORTA | PIN1) +#define PIN_I2C0_SCL_1 (PIN_ALT2_OPENDRAIN | PIN_PORTB | PIN0) +#define PIN_I2C0_SCL_2 (PIN_ALT2_OPENDRAIN | PIN_PORTB | PIN2) +#define PIN_I2C0_SCL_3 (PIN_ALT2_OPENDRAIN | PIN_PORTD | PIN8) +#define PIN_I2C0_SCL_4 (PIN_ALT5_OPENDRAIN | PIN_PORTE | PIN24) +#define PIN_I2C0_SCL_5 (PIN_ALT7_OPENDRAIN | PIN_PORTD | PIN2) +#define PIN_I2C0_SDA_1 (PIN_ALT2_OPENDRAIN | PIN_PORTB | PIN1) +#define PIN_I2C0_SDA_2 (PIN_ALT2_OPENDRAIN | PIN_PORTB | PIN3) +#define PIN_I2C0_SDA_3 (PIN_ALT2_OPENDRAIN | PIN_PORTD | PIN9) +#define PIN_I2C0_SDA_4 (PIN_ALT5_OPENDRAIN | PIN_PORTE | PIN25) +#define PIN_I2C0_SDA_5 (PIN_ALT7_OPENDRAIN | PIN_PORTD | PIN3) + +#define PIN_I2C1_SCL_1 (PIN_ALT2_OPENDRAIN | PIN_PORTC | PIN10) +#define PIN_I2C1_SCL_2 (PIN_ALT6_OPENDRAIN | PIN_PORTE | PIN1) +#define PIN_I2C1_SDA_1 (PIN_ALT2_OPENDRAIN | PIN_PORTC | PIN11) +#define PIN_I2C1_SDA_2 (PIN_ALT6_OPENDRAIN | PIN_PORTE | PIN0) + +#define PIN_I2C2_SCL_1 (PIN_ALT5_OPENDRAIN | PIN_PORTA | PIN12) +#define PIN_I2C2_SCL_2 (PIN_ALT5_OPENDRAIN | PIN_PORTA | PIN14) +#define PIN_I2C2_SDA_1 (PIN_ALT5_OPENDRAIN | PIN_PORTA | PIN11) +#define PIN_I2C2_SDA_2 (PIN_ALT5_OPENDRAIN | PIN_PORTA | PIN13) + +#define PIN_I2C3_SCL_1 (PIN_ALT2_OPENDRAIN | PIN_PORTE | PIN11) +#define PIN_I2C3_SCL_2 (PIN_ALT4_OPENDRAIN | PIN_PORTA | PIN2) +#define PIN_I2C3_SDA_1 (PIN_ALT2_OPENDRAIN | PIN_PORTE | PIN10) +#define PIN_I2C3_SDA_2 (PIN_ALT4_OPENDRAIN | PIN_PORTA | PIN1) /* I2S */ -- GitLab From e072069e2d674e94fdcdd172eb19a9e93bdc61c2 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 6 May 2017 06:48:06 -0600 Subject: [PATCH 741/990] 6loWPAN: Remove usage of the now non-existent msdu_length field. --- net/sixlowpan/sixlowpan_framelist.c | 10 +--------- net/sixlowpan/sixlowpan_framer.c | 15 ++++----------- 2 files changed, 5 insertions(+), 20 deletions(-) diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c index 6f41a59210..3f208bb388 100644 --- a/net/sixlowpan/sixlowpan_framelist.c +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -535,15 +535,11 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, for (iob = qhead; iob != NULL; iob = qhead) { - /* Remove the IOB from the list */ + /* Remove the IOB containing the frame from the list */ qhead = iob->io_flink; iob->io_flink = NULL; - /* Update the MSDU length in the metadata */ - - meta.msdu_length = iob->io_len - iob->io_offset; - /* And submit the frame to the MAC */ ret = sixlowpan_frame_submit(ieee, &meta, iob); @@ -580,10 +576,6 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, sixlowpan_dumpbuffer("Outgoing frame", (FAR const uint8_t *)iob->io_data, iob->io_len); - /* Update the MSDU length in the metadata */ - - meta.msdu_length = iob->io_len - iob->io_offset; - /* And submit the frame to the MAC */ ret = sixlowpan_frame_submit(ieee, &meta, iob); diff --git a/net/sixlowpan/sixlowpan_framer.c b/net/sixlowpan/sixlowpan_framer.c index b750156d36..9de555134d 100644 --- a/net/sixlowpan/sixlowpan_framer.c +++ b/net/sixlowpan/sixlowpan_framer.c @@ -226,25 +226,18 @@ int sixlowpan_meta_data(FAR struct ieee802154_driver_s *ieee, meta->dest_addr.panid = g_packet_meta.dpanid; /* Handle associated with MSDU. Will increment once per packet, not - * necesarily per frame: The MSDU handler will be used for each fragment - * of a disassembled packet. + * necesarily per frame: The same MSDU handle will be used for each + * fragment of a disassembled packet. */ meta->msdu_handle = ieee->i_msdu_handle++; - /* Number of bytes contained in the MAC Service Data Unit (MSDU) */ - - meta->msdu_length = paylen; - - /* MSDU flags that may be non-zero */ - - #ifdef CONFIG_IEEE802154_SECURITY -# warning CONFIG_IEEE802154_SECURITY not yet supported" +# warning CONFIG_IEEE802154_SECURITY not yet supported #endif #ifdef CONFIG_IEEE802154_UWB -# warning CONFIG_IEEE802154_UWB not yet supported" +# warning CONFIG_IEEE802154_UWB not yet supported #endif /* Ranging left zero */ -- GitLab From 1490599b69ed7f99ee61c27f907d8b3e76b263fd Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Fri, 5 May 2017 17:12:26 -0400 Subject: [PATCH 742/990] wireless/ieee802154: Reworks data_ind allocation to include IOB allocation/deallocation. Hides private data. --- drivers/wireless/ieee802154/mrf24j40.c | 36 +++--- .../wireless/ieee802154/ieee802154_mac.h | 10 +- .../wireless/ieee802154/ieee802154_radio.h | 3 +- wireless/ieee802154/Kconfig | 4 +- wireless/ieee802154/mac802154.c | 105 +++--------------- wireless/ieee802154/mac802154.h | 65 +++++++++++ wireless/ieee802154/mac802154_indalloc.c | 86 ++++++++++---- 7 files changed, 172 insertions(+), 137 deletions(-) diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c index 366471cd9c..14c9782777 100644 --- a/drivers/wireless/ieee802154/mrf24j40.c +++ b/drivers/wireless/ieee802154/mrf24j40.c @@ -1505,8 +1505,7 @@ static int mrf24j40_rxenable(FAR struct ieee802154_radio_s *radio, bool enable) static void mrf24j40_irqwork_rx(FAR struct mrf24j40_radio_s *dev) { - FAR struct iob_s *iob; - struct ieee802154_rxdesc_s rxdesc; + FAR struct ieee802154_data_ind_s *ind; uint32_t addr; uint32_t index; uint8_t reg; @@ -1521,46 +1520,43 @@ static void mrf24j40_irqwork_rx(FAR struct mrf24j40_radio_s *dev) mrf24j40_setreg(dev->spi, MRF24J40_BBREG1, MRF24J40_BBREG1_RXDECINV); - /* Allocate an IOB to put the packet in */ + /* Allocate a data_ind to put the frame in */ - iob = iob_alloc(true); - DEBUGASSERT(iob != NULL); - - iob->io_flink = NULL; - iob->io_len = 0; - iob->io_offset = 0; - iob->io_pktlen = 0; + ind = ieee802154_ind_allocate(); + if (ind == NULL) + { + wlerr("ERROR: Unable to allocate data_ind. Discarding frame"); + goto done; + } /* Read packet */ addr = MRF24J40_RXBUF_BASE; - iob->io_len= mrf24j40_getreg(dev->spi, addr++); + ind->frame->io_len= mrf24j40_getreg(dev->spi, addr++); /* TODO: This needs to be changed. It is inefficient to do the SPI read byte * by byte */ - for (index = 0; index < iob->io_len; index++) + for (index = 0; index < ind->frame->io_len; index++) { - iob->io_data[index] = mrf24j40_getreg(dev->spi, addr++); + ind->frame->io_data[index] = mrf24j40_getreg(dev->spi, addr++); } - /* Copy meta-data into RX descriptor */ - - rxdesc.lqi = mrf24j40_getreg(dev->spi, addr++); - rxdesc.rssi = mrf24j40_getreg(dev->spi, addr++); + ind->lqi = mrf24j40_getreg(dev->spi, addr++); + ind->rssi = mrf24j40_getreg(dev->spi, addr++); /* Reduce len by 2, we only receive frames with correct crc, no check * required. */ - iob->io_len -= 2; + ind->frame->io_len -= 2; /* Callback the receiver in the next highest layer */ - dev->radiocb->rxframe(dev->radiocb, - (FAR const struct ieee802154_rxdesc_s *)&rxdesc, iob); + dev->radiocb->rxframe(dev->radiocb, ind); +done: /* Enable reception of next packet by flushing the fifo. * This is an MRF24J40 errata (no. 1). */ diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index b4583c2e3c..fc9818212e 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -480,12 +480,6 @@ struct ieee802154_txdesc_s /* TODO: Add slotting information for GTS transactions */ }; -struct ieee802154_rxdesc_s -{ - uint8_t lqi; - uint8_t rssi; -}; - struct ieee802154_cca_s { uint8_t use_ed : 1; /* CCA using ED */ @@ -645,11 +639,13 @@ struct ieee802154_data_ind_s { FAR struct ieee802154_data_ind_s *flink; + FAR struct iob_s *frame; + struct ieee802154_addr_s src; /* Source addressing information */ struct ieee802154_addr_s dest; /* Destination addressing infromation */ uint8_t lqi; /* Link Quality Index */ + uint8_t rssi; /* Non-standard field */ uint8_t dsn; /* Data Sequence Number */ - uint8_t pool; /* Memory pool (Needed for deallocation) */ uint32_t timestamp; /* Time of received frame */ #ifdef CONFIG_IEEE802154_SECURITY diff --git a/include/nuttx/wireless/ieee802154/ieee802154_radio.h b/include/nuttx/wireless/ieee802154/ieee802154_radio.h index bfadc11023..fcbc7ec1b7 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_radio.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_radio.h @@ -71,8 +71,7 @@ struct ieee802154_radiocb_s CODE void (*txdone) (FAR const struct ieee802154_radiocb_s *radiocb, FAR const struct ieee802154_txdesc_s *tx_desc); CODE void (*rxframe) (FAR const struct ieee802154_radiocb_s *radiocb, - FAR const struct ieee802154_rxdesc_s *rx_desc, - FAR struct iob_s *frame); + FAR struct ieee802154_data_ind_s *ind); }; struct ieee802154_radio_s; /* Forward reference */ diff --git a/wireless/ieee802154/Kconfig b/wireless/ieee802154/Kconfig index 77f194d6ef..ff64c06d84 100644 --- a/wireless/ieee802154/Kconfig +++ b/wireless/ieee802154/Kconfig @@ -79,13 +79,13 @@ config IEEE802154_IND_IRQRESERVE In that case, the allocation will fail if tasking logic has allocated them all. - Interrupt logic will first attempt to allocate fromt the general, + Interrupt logic will first attempt to allocate from the general, pre-allocated structure pool that will contain up to (size CONFIG_IEEE802154_IND_PREALLOC - CONFIG_IEEE802154_IND_IRQRESERVE) entries. If that fails, then it will try to take a structure from the reserve (size CONFIG_IEEE802154_IND_IRQRESERVE). - Non-interrupt logic will also first attempt to allocate fromt the + Non-interrupt logic will also first attempt to allocate from the general, pre-allocated structure pool. If that fails, it will dynamically allocate the meta data structure with an additional cost in performance. diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index f954fd9046..127eae9d4f 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -84,11 +84,11 @@ * Private Types ****************************************************************************/ -struct mac802154_trans_s +struct mac802154_txframe_s { /* Supports a singly linked list */ - FAR struct mac802154_trans_s *flink; + FAR struct mac802154_txframe_s *flink; FAR struct iob_s *frame; uint8_t msdu_handle; sem_t sem; @@ -132,8 +132,8 @@ struct ieee802154_privmac_s * during the CAP of the Coordinator's superframe. */ - FAR struct mac802154_trans_s *csma_head; - FAR struct mac802154_trans_s *csma_tail; + FAR struct mac802154_txframe_s *csma_head; + FAR struct mac802154_txframe_s *csma_tail; /* Support a singly linked list of transactions that will be sent indirectly. * This list should only be used by a MAC acting as a coordinator. These @@ -143,15 +143,15 @@ struct ieee802154_privmac_s * beacon frame. */ - FAR struct mac802154_trans_s *indirect_head; - FAR struct mac802154_trans_s *indirect_tail; + FAR struct mac802154_txframe_s *indirect_head; + FAR struct mac802154_txframe_s *indirect_tail; uint8_t txdesc_count; struct ieee802154_txdesc_s txdesc[CONFIG_IEEE802154_NTXDESC]; /* Support a singly linked list of frames received */ - FAR struct iob_s *rxframes_head; - FAR struct iob_s *rxframes_tail; + FAR struct ieee802154_data_ind_s *rxframes_head; + FAR struct ieee802154_data_ind_s *rxframes_tail; /* MAC PIB attributes, grouped to save memory */ @@ -297,8 +297,7 @@ static void mac802154_txdone(FAR const struct ieee802154_radiocb_s *radiocb, FAR const struct ieee802154_txdesc_s *tx_desc); static void mac802154_rxframe(FAR const struct ieee802154_radiocb_s *radiocb, - FAR const struct ieee802154_rxdesc_s *rx_desc, - FAR struct iob_s *frame); + FAR struct ieee802154_data_ind_s *ind); /**************************************************************************** * Private Data @@ -345,7 +344,7 @@ static inline int mac802154_takesem(sem_t *sem) ****************************************************************************/ static void mac802154_push_csma(FAR struct ieee802154_privmac_s *priv, - FAR struct mac802154_trans_s *trans) + FAR struct mac802154_txframe_s *trans) { /* Ensure the transactions forward link is NULL */ @@ -380,10 +379,10 @@ static void mac802154_push_csma(FAR struct ieee802154_privmac_s *priv, * ****************************************************************************/ -static FAR struct mac802154_trans_s * +static FAR struct mac802154_txframe_s * mac802154_pop_csma(FAR struct ieee802154_privmac_s *priv) { - FAR struct mac802154_trans_s *trans; + FAR struct mac802154_txframe_s *trans; if (priv->csma_head == NULL) { @@ -510,7 +509,7 @@ static int mac802154_poll_csma(FAR const struct ieee802154_radiocb_s *radiocb, FAR struct mac802154_radiocb_s *cb = (FAR struct mac802154_radiocb_s *)radiocb; FAR struct ieee802154_privmac_s *priv; - FAR struct mac802154_trans_s *trans; + FAR struct mac802154_txframe_s *trans; DEBUGASSERT(cb != NULL && cb->priv != NULL); priv = cb->priv; @@ -564,7 +563,7 @@ static int mac802154_poll_gts(FAR const struct ieee802154_radiocb_s *radiocb, FAR struct mac802154_radiocb_s *cb = (FAR struct mac802154_radiocb_s *)radiocb; FAR struct ieee802154_privmac_s *priv; - FAR struct mac802154_trans_s *trans; + FAR struct mac802154_txframe_s *trans; int ret = 0; DEBUGASSERT(cb != NULL && cb->priv != NULL); @@ -691,13 +690,11 @@ static void mac802154_txdone_worker(FAR void *arg) ****************************************************************************/ static void mac802154_rxframe(FAR const struct ieee802154_radiocb_s *radiocb, - FAR const struct ieee802154_rxdesc_s *rx_desc, - FAR struct iob_s *frame) + FAR struct ieee802154_data_ind_s *ind) { FAR struct mac802154_radiocb_s *cb = (FAR struct mac802154_radiocb_s *)radiocb; FAR struct ieee802154_privmac_s *priv; - FAR struct ieee802154_rxdesc_s *desc; DEBUGASSERT(cb != NULL && cb->priv != NULL); priv = cb->priv; @@ -708,12 +705,10 @@ static void mac802154_rxframe(FAR const struct ieee802154_radiocb_s *radiocb, while (mac802154_takesem(&priv->exclsem) != 0); - /* TODO: Copy the frame descriptor to some type of list */ - /* Push the iob onto the tail of the frame list for processing */ - priv->rxframes_tail->io_flink = frame; - priv->rxframes_tail = frame; + priv->rxframes_tail->flink = ind; + priv->rxframes_tail = ind; mac802154_givesem(&priv->exclsem); @@ -1050,7 +1045,7 @@ int mac802154_req_data(MACHANDLE mac, { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; - FAR struct mac802154_trans_s trans; + FAR struct mac802154_txframe_s trans; uint16_t *frame_ctrl; uint8_t mhr_len = 3; /* Start assuming frame control and seq. num */ int ret; @@ -1606,67 +1601,3 @@ int mac802154_resp_orphan(MACHANDLE mac, return -ENOTTY; } -/**************************************************************************** - * Name: ieee802154_indpool_initialize - * - * Description: - * This function initializes the meta-data allocator. This function must - * be called early in the initialization sequence before any radios - * begin operation. - * - * Inputs: - * None - * - * Return Value: - * None - * - ****************************************************************************/ - -void ieee802154_indpool_initialize(void); - -/**************************************************************************** - * Name: ieee802154_ind_allocate - * - * Description: - * The ieee802154_ind_allocate function will get a free meta-data - * structure for use by the IEEE 802.15.4 MAC. - * - * Interrupt handling logic will first attempt to allocate from the - * g_indfree list. If that list is empty, it will attempt to allocate - * from its reserve, g_indfree_irq. If that list is empty, then the - * allocation fails (NULL is returned). - * - * Non-interrupt handler logic will attempt to allocate from g_indfree - * list. If that the list is empty, then the meta-data structure will be - * allocated from the dynamic memory pool. - * - * Inputs: - * None - * - * Return Value: - * A reference to the allocated msg structure. All user fields in this - * structure have been zeroed. On a failure to allocate, NULL is - * returned. - * - ****************************************************************************/ - -FAR struct ieee802154_data_ind_s *ieee802154_ind_allocate(void); - -/**************************************************************************** - * Name: ieee802154_ind_free - * - * Description: - * The ieee802154_ind_free function will return a meta-data structure to - * the free pool of messages if it was a pre-allocated meta-data - * structure. If the meta-data structure was allocated dynamically it will - * be deallocated. - * - * Inputs: - * ind - meta-data structure to free - * - * Return Value: - * None - * - ****************************************************************************/ - -void ieee802154_ind_free(FAR struct ieee802154_data_ind_s *ind); diff --git a/wireless/ieee802154/mac802154.h b/wireless/ieee802154/mac802154.h index 152046b61f..45f9c3a729 100644 --- a/wireless/ieee802154/mac802154.h +++ b/wireless/ieee802154/mac802154.h @@ -336,6 +336,71 @@ int mac802154_resp_associate(MACHANDLE mac, int mac802154_resp_orphan(MACHANDLE mac, FAR struct ieee802154_orphan_resp_s *resp); +/**************************************************************************** + * Name: ieee802154_indpool_initialize + * + * Description: + * This function initializes the meta-data allocator. This function must + * be called early in the initialization sequence before any radios + * begin operation. + * + * Inputs: + * None + * + * Return Value: + * None + * + ****************************************************************************/ + +void ieee802154_indpool_initialize(void); + +/**************************************************************************** + * Name: ieee802154_ind_allocate + * + * Description: + * The ieee802154_ind_allocate function will get a free meta-data + * structure for use by the IEEE 802.15.4 MAC. + * + * Interrupt handling logic will first attempt to allocate from the + * g_indfree list. If that list is empty, it will attempt to allocate + * from its reserve, g_indfree_irq. If that list is empty, then the + * allocation fails (NULL is returned). + * + * Non-interrupt handler logic will attempt to allocate from g_indfree + * list. If that the list is empty, then the meta-data structure will be + * allocated from the dynamic memory pool. + * + * Inputs: + * None + * + * Return Value: + * A reference to the allocated msg structure. All user fields in this + * structure have been zeroed. On a failure to allocate, NULL is + * returned. + * + ****************************************************************************/ + +FAR struct ieee802154_data_ind_s *ieee802154_ind_allocate(void); + +/**************************************************************************** + * Name: ieee802154_ind_free + * + * Description: + * The ieee802154_ind_free function will return a meta-data structure to + * the free pool of messages if it was a pre-allocated meta-data + * structure. If the meta-data structure was allocated dynamically it will + * be deallocated. + * + * Inputs: + * ind - meta-data structure to free + * + * Return Value: + * None + * + ****************************************************************************/ + +void ieee802154_ind_free(FAR struct ieee802154_data_ind_s *ind); + #undef EXTERN #ifdef __cplusplus } diff --git a/wireless/ieee802154/mac802154_indalloc.c b/wireless/ieee802154/mac802154_indalloc.c index 86d8dcd0ef..5e05c5c09e 100644 --- a/wireless/ieee802154/mac802154_indalloc.c +++ b/wireless/ieee802154/mac802154_indalloc.c @@ -43,6 +43,9 @@ #include #include + +#include + #include #include "mac802154.h" @@ -72,6 +75,21 @@ #define POOL_IND_IRQ 1 #define POOL_IND_DYNAMIC 2 +/**************************************************************************** + * Private Data Types + ****************************************************************************/ + +/* Private data type that extends the ieee802154_data_ind_s struct */ + +struct ieee802154_priv_ind_s +{ + /* Must be first member so we can cast to/from */ + + struct ieee802154_data_ind_s pub; + FAR struct ieee802154_priv_ind_s *flink; + uint8_t pool; +}; + /**************************************************************************** * Private Data ****************************************************************************/ @@ -83,7 +101,7 @@ * item. */ -static struct ieee802154_data_ind_s *g_indfree; +static struct ieee802154_priv_ind_s *g_indfree; #endif #if CONFIG_IEEE802154_IND_IRQRESERVE > 0 @@ -91,12 +109,12 @@ static struct ieee802154_data_ind_s *g_indfree; * use by only by interrupt handlers. */ -static struct ieee802154_data_ind_s *g_indfree_irq; +static struct ieee802154_priv_ind_s *g_indfree_irq; #endif /* Pool of pre-allocated meta-data stuctures */ -static struct ieee802154_data_ind_s g_indpool[CONFIG_IEEE802154_IND_PREALLOC]; +static struct ieee802154_priv_ind_s g_indpool[CONFIG_IEEE802154_IND_PREALLOC]; #endif /* CONFIG_IEEE802154_IND_PREALLOC > 0 */ /**************************************************************************** @@ -122,7 +140,7 @@ static struct ieee802154_data_ind_s g_indpool[CONFIG_IEEE802154_IND_PREALLOC]; void ieee802154_indpool_initialize(void) { #if CONFIG_IEEE802154_IND_PREALLOC > 0 - FAR struct ieee802154_data_ind_s *pool = g_indpool; + FAR struct ieee802154_priv_ind_s *pool = g_indpool; int remaining = CONFIG_IEEE802154_IND_PREALLOC; #if CONFIG_IEEE802154_IND_PREALLOC > CONFIG_IEEE802154_IND_IRQRESERVE @@ -133,7 +151,7 @@ void ieee802154_indpool_initialize(void) g_indfree = NULL; while (remaining > CONFIG_IEEE802154_IND_IRQRESERVE) { - FAR struct ieee802154_data_ind_s *ind = pool; + FAR struct ieee802154_priv_ind_s *ind = pool; /* Add the next meta data structure from the pool to the list of * general structures. @@ -157,7 +175,7 @@ void ieee802154_indpool_initialize(void) g_indfree_irq = NULL; while (remaining > 0) { - FAR struct ieee802154_data_ind_s *ind = pool; + FAR struct ieee802154_priv_ind_s *ind = pool; /* Add the next meta data structure from the pool to the list of * general structures. @@ -204,7 +222,7 @@ void ieee802154_indpool_initialize(void) FAR struct ieee802154_data_ind_s *ieee802154_ind_allocate(void) { #if CONFIG_IEEE802154_IND_PREALLOC > 0 - FAR struct ieee802154_data_ind_s *ind; + FAR struct ieee802154_priv_ind_s *ind; irqstate_t flags; uint8_t pool; @@ -271,8 +289,8 @@ FAR struct ieee802154_data_ind_s *ieee802154_ind_allocate(void) */ leave_critical_section(flags); - ind = (FAR struct ieee802154_data_ind_s *) - kmm_malloc((sizeof (struct ieee802154_data_ind_s))); + ind = (FAR struct ieee802154_priv_ind_s *) + kmm_malloc((sizeof (struct ieee802154_priv_ind_s))); /* Check if we allocated the meta-data structure */ @@ -289,9 +307,27 @@ FAR struct ieee802154_data_ind_s *ieee802154_ind_allocate(void) * Zero and tag the alloated meta-data structure. */ - memset(ind, 0, sizeof(struct ieee802154_data_ind_s)); ind->pool = pool; - return ind; + memset(&ind->pub, 0, sizeof(struct ieee802154_data_ind_s)); + + /* Allocate the IOB for the frame */ + + ind->pub.frame = iob_alloc(true); + if (ind->pub.frame == NULL) + { + /* Deallocate the ind */ + + ieee802154_ind_free(&ind->pub); + + return NULL; + } + + ind->pub.frame->io_flink = NULL; + ind->pub.frame->io_len = 0; + ind->pub.frame->io_offset = 0; + ind->pub.frame->io_pktlen = 0; + + return &ind->pub; #else return NULL; #endif @@ -318,21 +354,33 @@ void ieee802154_ind_free(FAR struct ieee802154_data_ind_s *ind) { #if CONFIG_IEEE802154_IND_PREALLOC > 0 irqstate_t flags; + FAR struct ieee802154_priv_ind_s *priv = + (FAR struct ieee802154_priv_ind_s *)ind; + + /* Check if the IOB is not NULL. The only time it should be NULL is if we + * allocated the data_ind, but the IOB allocation failed so we now have to + * free the data_ind but not the IOB. This really should happen rarely if at all. + */ + + if (ind->frame != NULL) + { + iob_free(ind->frame); + } #if CONFIG_IEEE802154_IND_PREALLOC > CONFIG_IEEE802154_IND_IRQRESERVE /* If this is a generally available pre-allocated meta-data structure, * then just put it back in the free list. */ - if (ind->pool == POOL_IND_GENERAL) + if (priv->pool == POOL_IND_GENERAL) { /* Make sure we avoid concurrent access to the free * list from interrupt handlers. */ flags = enter_critical_section(); - ind->flink = g_indfree; - g_indfree = ind; + priv->flink = g_indfree; + g_indfree = priv; leave_critical_section(flags); } else @@ -343,15 +391,15 @@ void ieee802154_ind_free(FAR struct ieee802154_data_ind_s *ind) * then put it back in the correct free list. */ - if (ind->pool == POOL_IND_IRQ) + if (priv->pool == POOL_IND_IRQ) { /* Make sure we avoid concurrent access to the free * list from interrupt handlers. */ flags = enter_critical_section(); - ind->flink = g_indfree_irq; - g_indfree_irq = ind; + priv->flink = g_indfree_irq; + g_indfree_irq = priv; leave_critical_section(flags); } else @@ -360,8 +408,8 @@ void ieee802154_ind_free(FAR struct ieee802154_data_ind_s *ind) { /* Otherwise, deallocate it. */ - DEBUGASSERT(ind->pool == POOL_IND_DYNAMIC); - sched_kfree(ind); + DEBUGASSERT(priv->pool == POOL_IND_DYNAMIC); + sched_kfree(priv); } #endif } -- GitLab From a19a44ad3d12bc6b99fb006a09c043a363aaee78 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Sat, 6 May 2017 10:20:10 -0400 Subject: [PATCH 743/990] wireless/ieee802154: Completes Rx data flow through MAC layer to callback --- .../wireless/ieee802154/ieee802154_mac.h | 2 +- wireless/ieee802154/mac802154.c | 227 +++++++++++++++++- 2 files changed, 221 insertions(+), 8 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index fc9818212e..0d10b53216 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -1322,7 +1322,7 @@ union ieee802154_mlme_notify_u union ieee802154_mcps_notify_u { struct ieee802154_data_conf_s dataconf; - struct ieee802154_data_ind_s dataind; + struct ieee802154_data_ind_s *dataind; }; /* A pointer to this structure is passed as the argument of each IOCTL diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index 127eae9d4f..cc6e4415b7 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -150,8 +150,8 @@ struct ieee802154_privmac_s struct ieee802154_txdesc_s txdesc[CONFIG_IEEE802154_NTXDESC]; /* Support a singly linked list of frames received */ - FAR struct ieee802154_data_ind_s *rxframes_head; - FAR struct ieee802154_data_ind_s *rxframes_tail; + FAR struct ieee802154_data_ind_s *dataind_head; + FAR struct ieee802154_data_ind_s *dataind_tail; /* MAC PIB attributes, grouped to save memory */ @@ -392,6 +392,7 @@ static FAR struct mac802154_txframe_s * /* Get the transaction from the head of the list */ trans = priv->csma_head; + trans->flink = NULL; /* Move the head pointer to the next transaction */ @@ -407,6 +408,79 @@ static FAR struct mac802154_txframe_s * return trans; } +/**************************************************************************** + * Name: mac802154_push_rxframe + * + * Description: + * Push a data indication onto the list to be processed + * + ****************************************************************************/ + +static void mac802154_push_dataind(FAR struct ieee802154_privmac_s *priv, + FAR struct ieee802154_data_ind_s *ind) +{ + /* Ensure the forward link is NULL */ + + ind->flink = NULL; + + /* If the tail is not empty, make the frame pointed to by the tail, + * point to the new data indication */ + + if (priv->dataind_tail != NULL) + { + priv->dataind_tail->flink = ind; + } + + /* Point the tail at the new frame */ + + priv->dataind_tail = ind; + + /* If the head is NULL, we need to point it at the data indication since there + * is only one indication in the list at this point */ + + if (priv->dataind_head == NULL) + { + priv->dataind_head = ind; + } +} + +/**************************************************************************** + * Name: mac802154_pop_dataind + * + * Description: + * Pop a data indication from the list + * + ****************************************************************************/ + +static FAR struct ieee802154_data_ind_s * + mac802154_pop_dataind(FAR struct ieee802154_privmac_s *priv) +{ + FAR struct ieee802154_data_ind_s *ind; + + if (priv->dataind_head == NULL) + { + return NULL; + } + + /* Get the data indication from the head of the list */ + + ind = priv->dataind_head; + ind->flink = NULL; + + /* Move the head pointer to the next data indication */ + + priv->dataind_head = ind->flink; + + /* If the head is now NULL, the list is empty, so clear the tail too */ + + if (priv->dataind_head == NULL) + { + priv->dataind_tail = NULL; + } + + return ind; +} + /**************************************************************************** * Name: mac802154_defaultmib * @@ -707,8 +781,7 @@ static void mac802154_rxframe(FAR const struct ieee802154_radiocb_s *radiocb, /* Push the iob onto the tail of the frame list for processing */ - priv->rxframes_tail->flink = ind; - priv->rxframes_tail = ind; + mac802154_push_dataind(priv, ind); mac802154_givesem(&priv->exclsem); @@ -736,10 +809,150 @@ static void mac802154_rxframe_worker(FAR void *arg) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)arg; + FAR struct ieee802154_data_ind_s *ind; + union ieee802154_mcps_notify_u mcps_notify; + FAR struct iob_s *frame; + uint16_t *frame_ctrl; + bool panid_comp; - /* The radio layer is responsible for handling all ACKs and retries. If for - * some reason an ACK gets here, just throw it out. - */ + while(1) + { + /* Get exclusive access to the driver structure. We don't care about any + * signals so if we see one, just go back to trying to get access again. + */ + + while (mac802154_takesem(&priv->exclsem) != 0); + + /* Push the iob onto the tail of the frame list for processing */ + + ind = mac802154_pop_dataind(priv); + + if (ind == NULL) + { + mac802154_givesem(&priv->exclsem); + break; + } + + /* Once we pop off the indication, we don't need to keep the mac locked */ + + mac802154_givesem(&priv->exclsem); + + /* Get a local copy of the frame to make it easier to access */ + + frame = iob->frame; + + /* Set a local pointer to the frame control then move the offset past + * the frame control field + */ + + frame_ctrl = (uint16_t *)&frame->io_data[frame->io_offset]; + frame->io_offset += 2; + + /* We use the data_ind_s as a container for the frame information even if + * this isn't a data frame + */ + + ind->src.mode = (frame_ctrl & IEEE802154_FRAMECTRL_SADDR) >> + IEEE802154_FRAMECTRL_SHIFT_SADDR; + + ind->dest.mode = (frame_ctrl & IEEE802154_FRAMECTRL_DADDR) >> + IEEE802154_FRAMECTRL_SHIFT_DADDR; + + panid_comp = (frame_ctrl & IEEE802154_FRAMECTRL_PANIDCOMP) >> + IEEE802154_FRAMECTRL_SHIFT_PANIDCOMP; + + ind->dsn = iob->frame->io_data[frame->io_offset++]; + + /* If the destination address is included */ + + if (ind->dest.mode != IEEE802154_ADDRMODE_NONE) + { + /* Get the destination PAN ID */ + + ind->dest.panid = frame->io_data[frame->io_offset]; + frame->io_offset += 2; + + if (ind->dest.mode == IEEE802154_ADDRMODE_SHORT) + { + ind->dest.saddr = frame->io_data[frame->io_offset]; + frame->io_offset += 2; + } + else if (ind->dest.mode == IEEE802154_ADDRMODE_EXTENDED) + { + memcpy(&ind->dest.eaddr[0], frame->io_data[frame->io_offset], + IEEE802154_EADDR_LEN); + frame->io_offset += 8; + } + } + + if (ind->src.mode != IEEE802154_ADDRMODE_NONE) + { + /* If the source address is included, and the PAN ID compression field + * is set, get the PAN ID from the header. + */ + + if (!panid_comp) + { + ind->src.panid = frame->io_data[frame->io_offset]; + frame->io_offset += 2; + } + + /* If the source address is included, and the PAN ID compression field + * is set, the source PAN ID is the same as the destination PAN ID + */ + + else + { + ind->src.panid = ind->dest.panid; + } + + if (ind->src.mode == IEEE802154_ADDRMODE_SHORT) + { + ind->src.saddr = frame->io_data[frame->io_offset]; + frame->io_offset += 2; + } + else if (ind->src.mode == IEEE802154_ADDRMODE_EXTENDED) + { + memcpy(&ind->src.eaddr[0], frame->io_data[frame->io_offset], + IEEE802154_EADDR_LEN); + frame->io_offset += 8; + } + } + + if (frame_ctrl & IEEE802154_FRAMECTRL_FTYPE == IEEE802154_FRAME_DATA) + { + /* If there is a registered MCPS callback receiver registered, send + * the frame, otherwise, throw it out. + */ + + if (priv->cb->mcps_notify != NULL) + { + mcps_notify.dataind = ind; + priv->cb->mcps_notify(priv->cb, IEEE802154_NOTIFY_IND_DATA, + mcps_notify); + } + else + { + /* Free the data indication struct from the pool */ + + ieee802154_ind_free(ind); + } + } + else if (frame_ctrl & IEEE802154_FRAMECTRL_FTYPE == IEEE802154_FRAME_COMMAND) + { + + } + else if (frame_ctrl & IEEE802154_FRAMECTRL_FTYPE == IEEE802154_FRAME_BEACON) + { + + } + else + { + /* The radio layer is responsible for handling all ACKs and retries. If for + * some reason an ACK gets here, just throw it out. + */ + } + } } /**************************************************************************** -- GitLab From 5d6da5f4bb3296c42fd0ebdc34639a8b756bff88 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Sat, 6 May 2017 04:52:48 -1000 Subject: [PATCH 744/990] kinetis:Add ARCH_HAVE_I2CRESET --- arch/arm/Kconfig | 1 + 1 file changed, 1 insertion(+) diff --git a/arch/arm/Kconfig b/arch/arm/Kconfig index c71fc98773..c8964e3c81 100644 --- a/arch/arm/Kconfig +++ b/arch/arm/Kconfig @@ -76,6 +76,7 @@ config ARCH_CHIP_KINETIS select ARCH_HAVE_FPU select ARCH_HAVE_RAMFUNCS select ARCH_HAVE_CMNVECTOR + select ARCH_HAVE_I2CRESET ---help--- Freescale Kinetis Architectures (ARM Cortex-M4) -- GitLab From b62ef579c8f3b96b3939d6879dd4669089055f32 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Sat, 6 May 2017 05:16:21 -1000 Subject: [PATCH 745/990] stm32: serial Allow configuring Rx DMA buffer size --- arch/arm/src/stm32/Kconfig | 13 +++++++++++++ arch/arm/src/stm32/stm32_serial.c | 8 ++++++-- 2 files changed, 19 insertions(+), 2 deletions(-) diff --git a/arch/arm/src/stm32/Kconfig b/arch/arm/src/stm32/Kconfig index e36b54673e..a74bfafc59 100644 --- a/arch/arm/src/stm32/Kconfig +++ b/arch/arm/src/stm32/Kconfig @@ -6165,6 +6165,19 @@ if STM32_SERIALDRIVER comment "Serial Driver Configuration" +config STM32_SERIAL_RXDMA_BUFFER_SIZE + int "Rx DMA buffer size" + default 32 + range 32 4096 + depends on USART1_RXDMA || USART2_RXDMA || USART3_RXDMA || UART4_RXDMA || UART5_RXDMA || USART6_RXDMA || UART7_RXDMA || UART8_RXDMA + ---help--- + The DMA buffer size when using RX DMA to emulate a FIFO. + + When streaming data, the generic serial layer will be called + every time the FIFO receives half or this number of bytes. + + Value given here will be rounded up to next multiple of 4 bytes. + config SERIAL_DISABLE_REORDERING bool "Disable reordering of ttySx devices." depends on STM32_USART1 || STM32_USART2 || STM32_USART3 || STM32_UART4 || STM32_UART5 || STM32_USART6 || STM32_UART7 || STM32_UART8 diff --git a/arch/arm/src/stm32/stm32_serial.c b/arch/arm/src/stm32/stm32_serial.c index 6b6161f0ce..04dcde479e 100644 --- a/arch/arm/src/stm32/stm32_serial.c +++ b/arch/arm/src/stm32/stm32_serial.c @@ -182,8 +182,12 @@ * When streaming data, the generic serial layer will be called * every time the FIFO receives half this number of bytes. */ - -# define RXDMA_BUFFER_SIZE 32 +# if !defined(CONFIG_STM32_SERIAL_RXDMA_BUFFER_SIZE) +# define CONFIG_STM32_SERIAL_RXDMA_BUFFER_SIZE 32 +# endif +# define RXDMA_MUTIPLE 4 +# define RXDMA_BUFFER_SIZE ((CONFIG_STM32_SERIAL_RXDMA_BUFFER_SIZE \ + + RXDMA_MUTIPLE) & ~RXDMA_MUTIPLE) /* DMA priority */ -- GitLab From 606255374820059331aa35a128d5ef4ed539335d Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 6 May 2017 09:38:26 -0600 Subject: [PATCH 746/990] Refresh a configuration --- configs/photon/wlan/defconfig | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/configs/photon/wlan/defconfig b/configs/photon/wlan/defconfig index a616dd914f..5f6b7e3ec7 100644 --- a/configs/photon/wlan/defconfig +++ b/configs/photon/wlan/defconfig @@ -16,7 +16,7 @@ CONFIG_HOST_LINUX=y # # Build Configuration # -CONFIG_APPS_DIR="../apps" +# CONFIG_APPS_DIR="../apps" CONFIG_BUILD_FLAT=y # CONFIG_BUILD_2PASS is not set @@ -1595,4 +1595,3 @@ CONFIG_WIRELESS_WAPI=y CONFIG_WIRELESS_WAPI_CMDTOOL=y CONFIG_WIRELESS_WAPI_STACKSIZE=2048 CONFIG_WIRELESS_WAPI_PRIORITY=100 -CONFIG_WIRELESS_WEXT=y -- GitLab From 5e81391d791d9e0d77941ab87c8a3b165df74052 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 6 May 2017 11:25:39 -0600 Subject: [PATCH 747/990] Update a configuration. --- configs/photon/wlan/defconfig | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/configs/photon/wlan/defconfig b/configs/photon/wlan/defconfig index 5f6b7e3ec7..1892e56c10 100644 --- a/configs/photon/wlan/defconfig +++ b/configs/photon/wlan/defconfig @@ -1552,6 +1552,16 @@ CONFIG_NSH_DRIPADDR=0xc0a80001 CONFIG_NSH_NETMASK=0xffffff00 # CONFIG_NSH_DNS is not set # CONFIG_NSH_NOMAC is not set + +# +# WAPI Configuration +# +CONFIG_NSH_WAPI_STAMODE=2 +CONFIG_NSH_WAPI_AUTHWPA=0x00000004 +CONFIG_NSH_WAPI_CIPHERMODE=0x00000008 +CONFIG_NSH_WAPI_ALG=3 +CONFIG_NSH_WAPI_SSID="myApSSID" +CONFIG_NSH_WAPI_PASSPHRASE="mySSIDpassphrase" CONFIG_NSH_MAX_ROUNDTRIP=20 # CONFIG_NSH_LOGIN is not set # CONFIG_NSH_CONSOLE_LOGIN is not set -- GitLab From c3180720849c9b3338632e8fc95b402b6a1287e8 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 6 May 2017 14:24:06 -0600 Subject: [PATCH 748/990] 6loWPAN: Minor cleanup and re-verification of all compression modes after so menay recent changes. --- net/sixlowpan/sixlowpan_hc06.c | 65 ++++++++++++++++++------------ net/sixlowpan/sixlowpan_hc1.c | 2 +- net/sixlowpan/sixlowpan_internal.h | 37 +++++++++++++---- net/sixlowpan/sixlowpan_utils.c | 18 +++++++-- 4 files changed, 83 insertions(+), 39 deletions(-) diff --git a/net/sixlowpan/sixlowpan_hc06.c b/net/sixlowpan/sixlowpan_hc06.c index 18d3ccf696..4de177e0a8 100644 --- a/net/sixlowpan/sixlowpan_hc06.c +++ b/net/sixlowpan/sixlowpan_hc06.c @@ -220,7 +220,7 @@ static FAR struct sixlowpan_addrcontext_s * } /**************************************************************************** - * Name: compress_tagaddr and compress_laddr + * Name: comporess_ipaddr, compress_tagaddr, and compress_laddr * * Description: * Uncompress addresses based on a prefix and a postfix with zeroes in @@ -230,20 +230,16 @@ static FAR struct sixlowpan_addrcontext_s * * prefpost takes a byte where the first nibble specify prefix count * and the second postfix count (NOTE: 15/0xf => 16 bytes copy). * + * compress_tagaddr() accepts a remote, variable length, taged MAC address; + * compress_laddr() accepts a local, fixed length MAC address. + * compress_ipaddr() is simply the common logic that does not depend on + * the size of the MAC address. + * ****************************************************************************/ -static uint8_t compress_tagaddr(FAR const net_ipv6addr_t ipaddr, - FAR const struct sixlowpan_tagaddr_s *macaddr, - uint8_t bitpos) +static uint8_t compress_ipaddr(FAR const net_ipv6addr_t ipaddr, uint8_t bitpos) { - ninfo("ipaddr=%p macaddr=%p extended=%u bitpos=%u g_hc06ptr=%p\n", - ipaddr, macaddr, macaddr->extended, bitpos, g_hc06ptr); - - if (sixlowpan_ismacbased(ipaddr, macaddr)) - { - return 3 << bitpos; /* 0-bits */ - } - else if (SIXLOWPAN_IS_IID_16BIT_COMPRESSABLE(ipaddr)) + if (SIXLOWPAN_IS_IID_16BIT_COMPRESSABLE(ipaddr)) { /* Compress IID to 16 bits: xxxx:xxxx:xxxx:xxxx:0000:00ff:fe00:XXXX */ @@ -261,21 +257,38 @@ static uint8_t compress_tagaddr(FAR const net_ipv6addr_t ipaddr, } } -static uint8_t compress_laddr(FAR const net_ipv6addr_t ipaddr, - FAR const struct sixlowpan_addr_s *macaddr, +static uint8_t compress_tagaddr(FAR const net_ipv6addr_t ipaddr, + FAR const struct sixlowpan_tagaddr_s *macaddr, uint8_t bitpos) { - struct sixlowpan_tagaddr_s tagaddr; + ninfo("ipaddr=%p macaddr=%p extended=%u bitpos=%u g_hc06ptr=%p\n", + ipaddr, macaddr, macaddr->extended, bitpos, g_hc06ptr); -#ifdef CONFIG_NET_6LOWPAN_EXTENDEDADDR - tagaddr.extended = true; - sixlowpan_eaddrcopy(tagaddr.u.eaddr.u8, macaddr->u8); -#else - tagaddr.extended = false; - sixlowpan_saddrcopy(tagaddr.u.saddr.u8, macaddr->u8); -#endif + if (sixlowpan_ismacbased(ipaddr, macaddr)) + { + return 3 << bitpos; /* 0-bits */ + } + else + { + return compress_ipaddr(ipaddr, bitpos); + } +} + +static uint8_t compress_laddr(FAR const net_ipv6addr_t ipaddr, + FAR const struct sixlowpan_addr_s *macaddr, + uint8_t bitpos) +{ + ninfo("ipaddr=%p macaddr=%p bitpos=%u g_hc06ptr=%p\n", + ipaddr, macaddr, bitpos, g_hc06ptr); - return compress_tagaddr(ipaddr, &tagaddr, bitpos); + if (sixlowpan_isaddrbased(ipaddr, macaddr)) + { + return 3 << bitpos; /* 0-bits */ + } + else + { + return compress_ipaddr(ipaddr, bitpos); + } } /**************************************************************************** @@ -642,9 +655,9 @@ void sixlowpan_compresshdr_hc06(FAR struct ieee802154_driver_s *ieee, ipv6->destipaddr[1] == 0 && ipv6->destipaddr[2] == 0 && ipv6->destipaddr[3] == 0) { - iphc1 |= compress_laddr(ipv6->srcipaddr, - &ieee->i_dev.d_mac.ieee802154, - SIXLOWPAN_IPHC_SAM_BIT); + iphc1 |= compress_laddr(ipv6->srcipaddr, + &ieee->i_dev.d_mac.ieee802154, + SIXLOWPAN_IPHC_SAM_BIT); } else { diff --git a/net/sixlowpan/sixlowpan_hc1.c b/net/sixlowpan/sixlowpan_hc1.c index 0168cb653b..c6b2f4a137 100644 --- a/net/sixlowpan/sixlowpan_hc1.c +++ b/net/sixlowpan/sixlowpan_hc1.c @@ -129,7 +129,7 @@ void sixlowpan_compresshdr_hc1(FAR struct ieee802154_driver_s *ieee, if (ipv6->vtc != 0x60 || ipv6->tcf != 0 || ipv6->flow != 0 || !sixlowpan_islinklocal(ipv6->srcipaddr) || - !sixlowpan_ismacbased(ipv6->srcipaddr, &ieee->i_dev.d_mac.ieee802154) || + !sixlowpan_isaddrbased(ipv6->srcipaddr, &ieee->i_dev.d_mac.ieee802154) || !sixlowpan_islinklocal(ipv6->destipaddr) || !sixlowpan_ismacbased(ipv6->destipaddr, destmac) || (ipv6->proto != IP_PROTO_ICMP6 && ipv6->proto != IP_PROTO_UDP && diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index cf71100db1..ade3ae1809 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -528,19 +528,27 @@ int sixlowpan_uncompresshdr_hc1(uint16_t iplen, FAR struct iob_s *iob, #endif /**************************************************************************** - * Name: sixlowpan_islinklocal, sixlowpan_addrfromip, and sixlowpan_ismacbased + * Name: sixlowpan_islinklocal, sixlowpan_addrfromip, and + * sixlowpan_ismacbased * * Description: - * sixlowpan_addrfromip: Extract the IEEE 802.15.14 address from a link - * local IPv6 address. - * - * sixlowpan_islinklocal and sixlowpan_ismacbased will return true for - * address created in this fashion. + * sixlowpan_addrfromip(): Extract the IEEE 802.15.14 address from a MAC + * based IPv6 address. sixlowpan_addrfromip() is intended to handle a + * tagged address or any size; sixlowpan_saddrfromip() and + * sixlowpan_eaddrfromip() specifically handle short and extended + * addresses. + * + * sixlowpan_islinklocal() and sixlowpan_ismacbased() will return true for + * address created in this fashion. sixlowpan_addrfromip() is intended to + * handle a tagged address or any size; sixlowpan_issaddrbased() and + * sixlowpan_iseaddrbased() specifically handle short and extended + * addresses. Local addresses are of a fixed but configurable size and + * sixlowpan_isaddrbased() is for use with such local addresses. * * 128 112 96 80 64 48 32 16 * ---- ---- ---- ---- ---- ---- ---- ---- - * fe80 0000 0000 0000 xxxx 0000 0000 0000 2-byte short address (VALID?) - * fe80 0000 0000 0000 xxxx xxxx xxxx xxxx 8-byte extended address + * fe80 0000 0000 0000 0000 00ff fe00 xxxx 2-byte short address IEEE 48-bit MAC + * fe80 0000 0000 0000 xxxx xxxx xxxx xxxx 8-byte extended address IEEE EUI-64 * ****************************************************************************/ @@ -553,6 +561,19 @@ void sixlowpan_eaddrfromip(const net_ipv6addr_t ipaddr, void sixlowpan_addrfromip(const net_ipv6addr_t ipaddr, FAR struct sixlowpan_tagaddr_s *addr); +bool sixlowpan_issaddrbased(const net_ipv6addr_t ipaddr, + FAR const struct sixlowpan_saddr_s *saddr); +bool sixlowpan_iseaddrbased(const net_ipv6addr_t ipaddr, + FAR const struct sixlowpan_eaddr_s *eaddr); + +#ifdef CONFIG_NET_6LOWPAN_EXTENDEDADDR +# define sixlowpan_isaddrbased(ipaddr,addr) \ + sixlowpan_iseaddrbased(ipaddr,(FAR struct sixlowpan_eaddr_s *)addr) +#else +# define sixlowpan_isaddrbased(ipaddr,addr) \ + sixlowpan_issaddrbased(ipaddr,(FAR struct sixlowpan_saddr_s *)addr) +#endif + bool sixlowpan_ismacbased(const net_ipv6addr_t ipaddr, FAR const struct sixlowpan_tagaddr_s *addr); diff --git a/net/sixlowpan/sixlowpan_utils.c b/net/sixlowpan/sixlowpan_utils.c index a1d7892a3e..d04ce878c7 100644 --- a/net/sixlowpan/sixlowpan_utils.c +++ b/net/sixlowpan/sixlowpan_utils.c @@ -71,12 +71,16 @@ * Name: sixlowpan_addrfromip * * Description: - * Extract the IEEE 802.15.4 address from a link local IPv6 address: + * sixlowpan_addrfromip(): Extract the IEEE 802.15.14 address from a MAC + * based IPv6 address. sixlowpan_addrfromip() is intended to handle a + * tagged address or and size; sixlowpan_saddrfromip() and + * sixlowpan_eaddrfromip() specifically handler short and extended + * addresses. * * 128 112 96 80 64 48 32 16 * ---- ---- ---- ---- ---- ---- ---- ---- - * fe80 0000 0000 0000 0000 00ff fe00 xxxx 2-byte short address IEEE 48-bit MAC - * fe80 0000 0000 0000 xxxx xxxx xxxx xxxx 8-byte extended address IEEE EUI-64 + * xxxx 0000 0000 0000 0000 00ff fe00 xxxx 2-byte short address IEEE 48-bit MAC + * xxxx 0000 0000 0000 xxxx xxxx xxxx xxxx 8-byte extended address IEEE EUI-64 * ****************************************************************************/ @@ -119,7 +123,13 @@ void sixlowpan_addrfromip(const net_ipv6addr_t ipaddr, * Name: sixlowpan_ismacbased * * Description: - * Check if the MAC address is encoded in the IP address: + * sixlowpan_ismacbased() will return true for IP addresses formed from + * IEEE802.15.4 MAC addresses. sixlowpan_addrfromip() is intended to + * handle a tagged address or any size; sixlowpan_issaddrbased() and + * sixlowpan_iseaddrbased() specifically handle short and extended + * addresses. Local addresses are of a fixed but configurable size and + * sixlowpan_isaddrbased() is for use with such local addresses. + * * * 128 112 96 80 64 48 32 16 * ---- ---- ---- ---- ---- ---- ---- ---- -- GitLab From e4b71a06bba813396144c3af8639d3d965c650f0 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 6 May 2017 15:18:39 -0600 Subject: [PATCH 749/990] Update the C coding standard. --- Documentation/NuttXCCodingStandard.html | 20 +++++++++++++++++--- 1 file changed, 17 insertions(+), 3 deletions(-) diff --git a/Documentation/NuttXCCodingStandard.html b/Documentation/NuttXCCodingStandard.html index f867fb3782..7d65a766a2 100644 --- a/Documentation/NuttXCCodingStandard.html +++ b/Documentation/NuttXCCodingStandard.html @@ -12,7 +12,7 @@

      NuttX C Coding Standard

      -

      Last Updated: April 18, 2017

      +

      Last Updated: May 6, 2017

      @@ -405,8 +405,11 @@

      Line Spacing A single blank line should precede and follow each comment. - The only exception is for the file header block comment that begins on line one; + The only exceptions are (1) for the file header block comment that begins on line one; there is no preceding blank line in that case. + And (2) for conditional compilation. + Conditional compilation should include the conditional logic and all comments associated with the conditional logic. + In this case, the blank line appears before the conditional, not after it.

      @@ -416,6 +419,12 @@ a = b; /* set b equal to c */ b = c; + + /* Do the impossible */ + +#ifdef CONFIG_THE_IMPOSSIBLE + the_impossible(); +#endif
      @@ -430,6 +439,11 @@ b = c; +#ifdef CONFIG_THE_IMPOSSIBLE + /* Do the impossible */ + + the_impossible(); +#endif
      @@ -1611,7 +1625,7 @@ enum xyz_state_e
    • Lowercase Exceptions. - There are3 a few lower case values in NuttX macro names. Such as a lower-case p for a period or decimal point (such as VOLTAGE_3p3V). + There are a few lower case values in NuttX macro names. Such as a lower-case p for a period or decimal point (such as VOLTAGE_3p3V). I have also used lower-case v for a version number (such as CONFIG_NET_IPv6). However, these are exceptions to the rule rather than illustrating a rule.
    • -- GitLab From 47793aa8f8d47abe741ae3b4c27df144d1bf5744 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 7 May 2017 08:47:48 -0600 Subject: [PATCH 750/990] Update ieee802.15.4 network driver so that it compiles cleanly. --- .../wireless/ieee802154/ieee802154_mac.h | 12 +- wireless/ieee802154/mac802154_netdev.c | 557 +++--------------- 2 files changed, 93 insertions(+), 476 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index 0d10b53216..ff9e270621 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -1405,13 +1405,13 @@ enum ieee802154_macnotify_e struct ieee802154_maccb_s { - CODE void (*mlme_notify) (FAR const struct ieee802154_maccb_s *maccb, - enum ieee802154_macnotify_e notif, - FAR const union ieee802154_mlme_notify_u *arg); + CODE void (*mlme_notify)(FAR const struct ieee802154_maccb_s *maccb, + enum ieee802154_macnotify_e notif, + FAR const union ieee802154_mlme_notify_u *arg); - CODE void (*mcps_notify) (FAR const struct ieee802154_maccb_s *maccb, - enum ieee802154_macnotify_e notif, - FAR const union ieee802154_mcps_notify_u *arg); + CODE void (*mcps_notify)(FAR const struct ieee802154_maccb_s *maccb, + enum ieee802154_macnotify_e notif, + FAR const union ieee802154_mcps_notify_u *arg); }; #ifdef __cplusplus diff --git a/wireless/ieee802154/mac802154_netdev.c b/wireless/ieee802154/mac802154_netdev.c index 7016cf7199..d1cd9c97a9 100644 --- a/wireless/ieee802154/mac802154_netdev.c +++ b/wireless/ieee802154/mac802154_netdev.c @@ -51,14 +51,14 @@ #include #include +#include #include #include -#include +#include #include #include #include -#include -#include +#include #include "mac802154.h" @@ -79,11 +79,11 @@ /* Use the selected work queue */ # if defined(CONFIG_IEEE802154_NETDEV_HPWORK) -# define ETHWORK HPWORK +# define WPANWORK HPWORK # elif defined(CONFIG_IEEE802154_NETDEV_LPWORK) -# define ETHWORK LPWORK +# define WPANWORK LPWORK # else -# error Neither CONFIG_IEEE802154_NETDEV_HPWORK nor CONFIG_IEEE802154_NETDEV_LPWORK defined +# error Neither CONFIG_IEEE802154_NETDEV_HPWORK nor CONFIG_IEEE802154_NETDEV_LPWORK defined # endif #endif @@ -97,15 +97,7 @@ /* TX poll delay = 1 seconds. CLK_TCK is the number of clock ticks per second */ -#define skeleton_WDDELAY (1*CLK_TCK) - -/* TX timeout = 1 minute */ - -#define skeleton_TXTIMEOUT (60*CLK_TCK) - -/* This is a helper pointer for accessing the contents of the Ethernet header */ - -#define BUF ((struct eth_hdr_s *)priv->md_dev.d_buf) +#define TXPOLL_WDDELAY (1*CLK_TCK) /**************************************************************************** * Private Types @@ -137,8 +129,6 @@ struct macnet_driver_s MACHANDLE md_mac; /* Contained MAC interface */ bool md_bifup; /* true:ifup false:ifdown */ WDOG_ID md_txpoll; /* TX poll timer */ - WDOG_ID md_txtimeout; /* TX timeout timer */ - struct work_s md_irqwork; /* Defer interupt work to the work queue */ struct work_s md_pollwork; /* Defer poll work to the work queue */ }; @@ -148,36 +138,27 @@ struct macnet_driver_s /* IEE802.15.4 MAC callback functions ***************************************/ -static void macnet_mlme_notify(FAR struct ieee802154_maccb_s *maccb, +static void macnet_mlme_notify(FAR const struct ieee802154_maccb_s *maccb, enum ieee802154_macnotify_e notif, - FAR union ieee802154_mlme_notify_u *arg); - -static void macnet_mcps_notify(FAR struct ieee802154_maccb_s *maccb, + FAR const union ieee802154_mlme_notify_u *arg); +static void macnet_mcps_notify(FAR const struct ieee802154_maccb_s *maccb, enum ieee802154_macnotify_e notif, - FAR union ieee802154_mcps_notify_u *arg); + FAR const union ieee802154_mcps_notify_u *arg); /* Asynchronous confirmations to requests */ static void macnet_conf_data(FAR struct macnet_driver_s *priv, - FAR struct ieee802154_data_conf_s *conf); -static void macnet_conf_purge(FAR struct macnet_driver_s *priv, - FAR struct ieee802154_purge_conf_s *conf); + FAR const struct ieee802154_data_conf_s *conf); static void macnet_conf_associate(FAR struct macnet_driver_s *priv, FAR struct ieee802154_assoc_conf_s *conf); static void macnet_conf_disassociate(FAR struct macnet_driver_s *priv, FAR struct ieee802154_disassoc_conf_s *conf); -static void macnet_conf_get(FAR struct macnet_driver_s *priv, - FAR struct ieee802154_get_conf_s *conf); static void macnet_conf_gts(FAR struct macnet_driver_s *priv, FAR struct ieee802154_gts_conf_s *conf); -static void macnet_conf_reset(FAR struct macnet_driver_s *priv, - FAR struct ieee802154_reset_conf_s *conf); static void macnet_conf_rxenable(FAR struct macnet_driver_s *priv, FAR struct ieee802154_rxenable_conf_s *conf); static void macnet_conf_scan(FAR struct macnet_driver_s *priv, FAR struct ieee802154_scan_conf_s *conf); -static void macnet_conf_set(FAR struct macnet_driver_s *priv, - FAR struct ieee802154_set_conf_s *conf); static void macnet_conf_start(FAR struct macnet_driver_s *priv, FAR struct ieee802154_start_conf_s *conf); static void macnet_conf_poll(FAR struct macnet_driver_s *priv, @@ -205,24 +186,9 @@ static void macnet_ind_syncloss(FAR struct macnet_driver_s *priv, /* Network interface support ************************************************/ /* Common TX logic */ -static int macnet_transmit(FAR struct macnet_driver_s *priv); -static int macnet_txpoll(FAR struct net_driver_s *dev); - -/* Frame transfer */ - -static void macnet_receive(FAR struct macnet_driver_s *priv); -static void macnet_txdone(FAR struct macnet_driver_s *priv); - -static void macnet_transfer_work(FAR void *arg); -static int macnet_transfer(int irq, FAR void *context, FAR void *arg); - -/* Watchdog timer expirations */ - -static void macnet_txtimeout_work(FAR void *arg); -static void macnet_txtimeout_expiry(int argc, wdparm_t arg, ...); - -static void macnet_poll_work(FAR void *arg); -static void macnet_poll_expiry(int argc, wdparm_t arg, ...); +static int macnet_txpoll_callback(FAR struct net_driver_s *dev); +static void macnet_txpoll_work(FAR void *arg); +static void macnet_txpoll_expiry(int argc, wdparm_t arg, ...); /* NuttX callback functions */ @@ -264,12 +230,12 @@ static int macnet_req_data(FAR struct ieee802154_driver_s *netdev, * ****************************************************************************/ -static void macnet_mlme_notify(FAR struct ieee802154_maccb_s *maccb, +static void macnet_mlme_notify(FAR const struct ieee802154_maccb_s *maccb, enum ieee802154_macnotify_e notif, - FAR union ieee802154_mlme_notify_u *arg) + FAR const union ieee802154_mlme_notify_u *arg) { - FAR struct macdev_callback_s *cb = - (FAR struct macdev_callback_s *)maccb; + FAR struct macnet_callback_s *cb = + (FAR struct macnet_callback_s *)maccb; FAR struct macnet_driver_s *priv; DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); @@ -290,13 +256,13 @@ static void macnet_mlme_notify(FAR struct ieee802154_maccb_s *maccb, * ****************************************************************************/ -static void macnet_mcps_notify(FAR struct ieee802154_maccb_s *maccb, +static void macnet_mcps_notify(FAR const struct ieee802154_maccb_s *maccb, enum ieee802154_macnotify_e notif, - FAR union ieee802154_mcps_notify_u *arg) + FAR const union ieee802154_mcps_notify_u *arg) { - FAR struct macdev_callback_s *cb = - (FAR struct macdev_callback_s *)maccb; - FAR struct macdev_driver_s *priv; + FAR struct macnet_callback_s *cb = + (FAR struct macnet_callback_s *)maccb; + FAR struct macnet_driver_s *priv; DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); priv = cb->mc_priv; @@ -309,15 +275,9 @@ static void macnet_mcps_notify(FAR struct ieee802154_maccb_s *maccb, } break; - case IEEE802154_NOTIFY_CONF_PURGE: - { - macnet_conf_purge(priv, &arg->purgeconf); - } - break; - case IEEE802154_NOTIFY_IND_DATA: { - macnet_ind_data(priv, &arg->dataind); + macnet_ind_data(priv, arg->dataind); } break; @@ -335,21 +295,7 @@ static void macnet_mcps_notify(FAR struct ieee802154_maccb_s *maccb, ****************************************************************************/ static void macnet_conf_data(FAR struct macnet_driver_s *priv, - FAR struct ieee802154_data_conf_s *conf) -{ - -} - -/**************************************************************************** - * Name: macnet_conf_purge - * - * Description: - * Data frame was purged - * - ****************************************************************************/ - -static void macnet_conf_purge(FAR struct macnet_driver_s *priv, - FAR struct ieee802154_purge_conf_s *conf) + FAR const struct ieee802154_data_conf_s *conf) { } @@ -382,20 +328,6 @@ static void macnet_conf_disassociate(FAR struct macnet_driver_s *priv, } -/**************************************************************************** - * Name: macnet_conf_get - * - * Description: - * PIB data returned - * - ****************************************************************************/ - -static void macnet_conf_get(FAR struct macnet_driver_s *priv, - FAR struct ieee802154_get_conf_s *conf) -{ - -} - /**************************************************************************** * Name: macnet_conf_gts * @@ -410,20 +342,6 @@ static void macnet_conf_gts(FAR struct macnet_driver_s *priv, } -/**************************************************************************** - * Name: macnet_conf_reset - * - * Description: - * MAC reset completed - * - ****************************************************************************/ - -static void macnet_conf_reset(FAR struct macnet_driver_s *priv, - FAR struct ieee802154_reset_conf_s *conf) -{ - -} - /**************************************************************************** * Name: macnet_conf_rxenable * @@ -450,19 +368,6 @@ static void macnet_conf_scan(FAR struct macnet_driver_s *priv, } -/**************************************************************************** - * Name: macnet_conf_set - * - * Description: - * - ****************************************************************************/ - -static void macnet_conf_set(FAR struct macnet_driver_s *priv, - FAR struct ieee802154_set_conf_s *conf) -{ - -} - /**************************************************************************** * Name: macnet_conf_start * @@ -500,7 +405,23 @@ static void macnet_conf_poll(FAR struct macnet_driver_s *priv, static void macnet_ind_data(FAR struct macnet_driver_s *priv, FAR struct ieee802154_data_ind_s *ind) { + FAR struct iob_s *iob; + + /* Extract the IOB containing the frame from the struct ieee802154_data_ind_s */ + + DEBUGASSERT(priv != NULL && ind != NULL && ind->frame != NULL); + iob = ind->frame; + ind->frame = NULL; + + /* Transfer the frame to the network logic */ + + sixlowpan_input(&priv->md_dev, iob, ind); + /* sixlowpan_input() will free the IOB, but we must free the struct + * ieee802154_data_ind_s container here. + */ + + ieee802154_ind_free(ind); } /**************************************************************************** @@ -600,52 +521,7 @@ static void macnet_ind_syncloss(FAR struct macnet_driver_s *priv, } /**************************************************************************** - * Name: macnet_transmit - * - * Description: - * This function is called from the lower MAC layer when thre radio device - * is ready to accept another outgoing frame. It removes one of the - * previously queued fram IOBs and provides that to the MAC layer. - * - * Parameters: - * priv - Reference to the driver state structure - * - * Returned Value: - * OK on success; a negated errno on failure - * - * Assumptions: - * May or may not be called from an interrupt handler. - * - ****************************************************************************/ - -static int macnet_transmit(FAR struct macnet_driver_s *priv) -{ - /* Cancel the TX timeout watchdog - * - * REVISIT: Is there not a race condition here? Might the TX timeout - * already be queued?. - */ - - wd_cancel(priv->md_txtimeout); - - /* Increment statistics */ - - NETDEV_TXPACKETS(priv->md_dev); - - /* Provide the pre-formatted packet to the radio device (via the lower MAC - * layer). - */ -#warning Missing logic - - /* Setup the TX timeout watchdog (perhaps restarting the timer) */ - - (void)wd_start(priv->md_txtimeout, skeleton_TXTIMEOUT, - macnet_txtimeout_expiry, 1, (wdparm_t)priv); - return OK; -} - -/**************************************************************************** - * Name: macnet_txpoll + * Name: macnet_txpoll_callback * * Description: * The transmitter is available, check if the network has any outgoing @@ -667,7 +543,7 @@ static int macnet_transmit(FAR struct macnet_driver_s *priv) * ****************************************************************************/ -static int macnet_txpoll(FAR struct net_driver_s *dev) +static int macnet_txpoll_callback(FAR struct net_driver_s *dev) { /* If zero is returned, the polling will continue until all connections have * been examined. @@ -677,265 +553,7 @@ static int macnet_txpoll(FAR struct net_driver_s *dev) } /**************************************************************************** - * Name: macnet_receive - * - * Description: - * An interrupt was received indicating the availability of a new RX packet - * - * Parameters: - * priv - Reference to the driver state structure - * - * Returned Value: - * None - * - * Assumptions: - * The network is locked. - * - ****************************************************************************/ - -static void macnet_receive(FAR struct macnet_driver_s *priv) -{ - FAR struct iob_s *iob; - FAR struct iob_s *fptr; - - /* Allocate an IOB to hold the frame */ - - net_lock(); - iob = iob_alloc(false); -#warning Allocated by radio layer, right? - if (iob == NULL) - { - nerr("ERROR: Failed to allocate an IOB\n") - return; - } - - /* Copy the frame data into the IOB. - * REVISIT: Can a copy be avoided? - */ - - fptr = iob->io_data; -#warning Missing logic - - /* Transfer the frame to the network logic */ - - sixlowpan_input(&priv->md_dev, iob, NULL); -} - -/**************************************************************************** - * Name: macnet_txdone - * - * Description: - * An interrupt was received indicating that the last TX packet(s) is done - * - * Parameters: - * priv - Reference to the driver state structure - * - * Returned Value: - * None - * - * Assumptions: - * The network is locked. - * - ****************************************************************************/ - -static void macnet_txdone(FAR struct macnet_driver_s *priv) -{ - int delay; - - /* Check for errors and update statistics */ - - NETDEV_TXDONE(priv->md_dev); - - /* Check if there are pending transmissions */ - - /* If no further transmissions are pending, then cancel the TX timeout and - * disable further Tx interrupts. - */ - - wd_cancel(priv->md_txtimeout); - - /* And disable further TX interrupts. */ - - /* In any event, poll the network for new TX data */ - - (void)devif_poll(&priv->md_dev, macnet_txpoll); -} - -/**************************************************************************** - * Name: macnet_transfer_work - * - * Description: - * Perform interrupt related work from the worker thread - * - * Parameters: - * arg - The argument passed when work_queue() was called. - * - * Returned Value: - * OK on success - * - * Assumptions: - * The network is locked. - * - ****************************************************************************/ - -static void macnet_transfer_work(FAR void *arg) -{ - FAR struct macnet_driver_s *priv = (FAR struct macnet_driver_s *)arg; - - /* Lock the network and serialize driver operations if necessary. - * NOTE: Serialization is only required in the case where the driver work - * is performed on an LP worker thread and where more than one LP worker - * thread has been configured. - */ - - net_lock(); - - /* Process pending Ethernet interrupts */ - - /* Get and clear interrupt status bits */ - - /* Handle interrupts according to status bit settings */ - - /* Check if we received an incoming packet, if so, call macnet_receive() */ - - macnet_receive(priv); - - /* Check if a packet transmission just completed. If so, call macnet_txdone. - * This may disable further Tx interrupts if there are no pending - * transmissions. - */ - - macnet_txdone(priv); - net_unlock(); - - /* Re-enable Ethernet interrupts */ - - up_enable_irq(CONFIG_IEEE802154_NETDEV_IRQ); -} - -/**************************************************************************** - * Name: macnet_transfer - * - * Description: - * Hardware interrupt handler - * - * Parameters: - * irq - Number of the IRQ that generated the interrupt - * context - Interrupt register state save info (architecture-specific) - * - * Returned Value: - * OK on success - * - * Assumptions: - * - ****************************************************************************/ - -static int macnet_transfer(int irq, FAR void *context, FAR void *arg) -{ - FAR struct macnet_driver_s *priv = (FAR struct macnet_driver_s *)arg; - - /* Disable further Ethernet interrupts. Because Ethernet interrupts are - * also disabled if the TX timeout event occurs, there can be no race - * condition here. - */ - - up_disable_irq(CONFIG_IEEE802154_NETDEV_IRQ); - - /* TODO: Determine if a TX transfer just completed */ - - { - /* If a TX transfer just completed, then cancel the TX timeout so - * there will be no race condition between any subsequent timeout - * expiration and the deferred interrupt processing. - */ - - wd_cancel(priv->md_txtimeout); - } - - /* Schedule to perform the interrupt processing on the worker thread. */ - - work_queue(ETHWORK, &priv->md_irqwork, macnet_transfer_work, priv, 0); - return OK; -} - -/**************************************************************************** - * Name: macnet_txtimeout_work - * - * Description: - * Perform TX timeout related work from the worker thread - * - * Parameters: - * arg - The argument passed when work_queue() as called. - * - * Returned Value: - * OK on success - * - * Assumptions: - * The network is locked. - * - ****************************************************************************/ - -static void macnet_txtimeout_work(FAR void *arg) -{ - FAR struct macnet_driver_s *priv = (FAR struct macnet_driver_s *)arg; - - /* Lock the network and serialize driver operations if necessary. - * NOTE: Serialization is only required in the case where the driver work - * is performed on an LP worker thread and where more than one LP worker - * thread has been configured. - */ - - net_lock(); - - /* Increment statistics and dump debug info */ - - NETDEV_TXTIMEOUTS(priv->md_dev); - - /* Then reset the hardware */ - - /* Then poll the network for new XMIT data */ - - (void)devif_poll(&priv->md_dev, macnet_txpoll); - net_unlock(); -} - -/**************************************************************************** - * Name: macnet_txtimeout_expiry - * - * Description: - * Our TX watchdog timed out. Called from the timer interrupt handler. - * The last TX never completed. Reset the hardware and start again. - * - * Parameters: - * argc - The number of available arguments - * arg - The first argument - * - * Returned Value: - * None - * - * Assumptions: - * Global interrupts are disabled by the watchdog logic. - * - ****************************************************************************/ - -static void macnet_txtimeout_expiry(int argc, wdparm_t arg, ...) -{ - FAR struct macnet_driver_s *priv = (FAR struct macnet_driver_s *)arg; - - /* Disable further Ethernet interrupts. This will prevent some race - * conditions with interrupt work. There is still a potential race - * condition with interrupt work that is already queued and in progress. - */ - - up_disable_irq(CONFIG_IEEE802154_NETDEV_IRQ); - - /* Schedule to perform the TX timeout processing on the worker thread. */ - - work_queue(ETHWORK, &priv->md_irqwork, macnet_txtimeout_work, priv, 0); -} - -/**************************************************************************** - * Name: macnet_poll_process + * Name: macnet_txpoll_process * * Description: * Perform the periodic poll. This may be called either from watchdog @@ -951,12 +569,12 @@ static void macnet_txtimeout_expiry(int argc, wdparm_t arg, ...) * ****************************************************************************/ -static inline void macnet_poll_process(FAR struct macnet_driver_s *priv) +static inline void macnet_txpoll_process(FAR struct macnet_driver_s *priv) { } /**************************************************************************** - * Name: macnet_poll_work + * Name: macnet_txpoll_work * * Description: * Perform periodic polling from the worker thread @@ -972,7 +590,7 @@ static inline void macnet_poll_process(FAR struct macnet_driver_s *priv) * ****************************************************************************/ -static void macnet_poll_work(FAR void *arg) +static void macnet_txpoll_work(FAR void *arg) { FAR struct macnet_driver_s *priv = (FAR struct macnet_driver_s *)arg; @@ -995,17 +613,17 @@ static void macnet_poll_work(FAR void *arg) * progress, we will missing TCP time state updates? */ - (void)devif_timer(&priv->md_dev, macnet_txpoll); + (void)devif_timer(&priv->md_dev.i_dev, macnet_txpoll_callback); /* Setup the watchdog poll timer again */ - (void)wd_start(priv->md_txpoll, skeleton_WDDELAY, macnet_poll_expiry, 1, + (void)wd_start(priv->md_txpoll, TXPOLL_WDDELAY, macnet_txpoll_expiry, 1, (wdparm_t)priv); net_unlock(); } /**************************************************************************** - * Name: macnet_poll_expiry + * Name: macnet_txpoll_expiry * * Description: * Periodic timer handler. Called from the timer interrupt handler. @@ -1022,21 +640,21 @@ static void macnet_poll_work(FAR void *arg) * ****************************************************************************/ -static void macnet_poll_expiry(int argc, wdparm_t arg, ...) +static void macnet_txpoll_expiry(int argc, wdparm_t arg, ...) { FAR struct macnet_driver_s *priv = (FAR struct macnet_driver_s *)arg; /* Schedule to perform the interrupt processing on the worker thread. */ - work_queue(ETHWORK, &priv->md_pollwork, macnet_poll_work, priv, 0); + work_queue(WPANWORK, &priv->md_pollwork, macnet_txpoll_work, priv, 0); } /**************************************************************************** * Name: macnet_ifup * * Description: - * NuttX Callback: Bring up the Ethernet interface when an IP address is - * provided + * NuttX Callback: Bring up the IEEE 802.15.4 interface when an IP address + * is provided * * Parameters: * dev - Reference to the NuttX driver state structure @@ -1064,9 +682,10 @@ static int macnet_ifup(FAR struct net_driver_s *dev) dev->d_ipv6addr[6], dev->d_ipv6addr[7]); #endif - /* Initialize PHYs, the Ethernet interface, and setup up Ethernet interrupts */ + /* Initialize PHYs, the IEEE 802.15.4 interface, and setup up IEEE 802.15.4 interrupts */ +#warning Missing logic - /* Instantiate the MAC address from priv->md_dev.d_mac.ether_addr_octet */ + /* Instantiate the MAC address from priv->md_dev.i_dev.d_mac.ether_addr_octet */ #ifdef CONFIG_NET_ICMPv6 /* Set up IPv6 multicast address filtering */ @@ -1076,13 +695,12 @@ static int macnet_ifup(FAR struct net_driver_s *dev) /* Set and activate a timer process */ - (void)wd_start(priv->md_txpoll, skeleton_WDDELAY, macnet_poll_expiry, 1, + (void)wd_start(priv->md_txpoll, TXPOLL_WDDELAY, macnet_txpoll_expiry, 1, (wdparm_t)priv); - /* Enable the Ethernet interrupt */ + /* Enable the IEEE 802.15.4 radio */ priv->md_bifup = true; - up_enable_irq(CONFIG_IEEE802154_NETDEV_IRQ); return OK; } @@ -1107,15 +725,13 @@ static int macnet_ifdown(FAR struct net_driver_s *dev) FAR struct macnet_driver_s *priv = (FAR struct macnet_driver_s *)dev->d_private; irqstate_t flags; - /* Disable the Ethernet interrupt */ + /* Disable interruption */ flags = enter_critical_section(); - up_disable_irq(CONFIG_IEEE802154_NETDEV_IRQ); /* Cancel the TX poll timer and TX timeout timers */ wd_cancel(priv->md_txpoll); - wd_cancel(priv->md_txtimeout); /* Put the EMAC in its reset, non-operational state. This should be * a known configuration that will guarantee the macnet_ifup() always @@ -1166,7 +782,7 @@ static void macnet_txavail_work(FAR void *arg) /* If so, then poll the network for new XMIT data */ - (void)devif_poll(&priv->md_dev, macnet_txpoll); + (void)devif_poll(&priv->md_dev.i_dev, macnet_txpoll_callback); } net_unlock(); @@ -1204,7 +820,7 @@ static int macnet_txavail(FAR struct net_driver_s *dev) { /* Schedule to serialize the poll on the worker thread. */ - work_queue(ETHWORK, &priv->md_pollwork, macnet_txavail_work, priv, 0); + work_queue(WPANWORK, &priv->md_pollwork, macnet_txavail_work, priv, 0); } return OK; @@ -1293,10 +909,10 @@ static void macnet_ipv6multicast(FAR struct macnet_driver_s *priv) /* For ICMPv6, we need to add the IPv6 multicast address * - * For IPv6 multicast addresses, the Ethernet MAC is derived by + * For IPv6 multicast addresses, the IEEE 802.15.4 MAC is derived by * the four low-order octets OR'ed with the MAC 33:33:00:00:00:00, * so for example the IPv6 address FF02:DEAD:BEEF::1:3 would map - * to the Ethernet MAC address 33:33:00:01:00:03. + * to the IEEE 802.15.4 MAC address 33:33:00:01:00:03. * * NOTES: This appears correct for the ICMPv6 Router Solicitation * Message, but the ICMPv6 Neighbor Solicitation message seems to @@ -1321,7 +937,7 @@ static void macnet_ipv6multicast(FAR struct macnet_driver_s *priv) (void)macnet_addmac(dev, mac); #ifdef CONFIG_NET_ICMPv6_AUTOCONF - /* Add the IPv6 all link-local nodes Ethernet address. This is the + /* Add the IPv6 all link-local nodes IEEE 802.15.4 address. This is the * address that we expect to receive ICMPv6 Router Advertisement * packets. */ @@ -1331,7 +947,7 @@ static void macnet_ipv6multicast(FAR struct macnet_driver_s *priv) #endif /* CONFIG_NET_ICMPv6_AUTOCONF */ #ifdef CONFIG_NET_ICMPv6_ROUTER - /* Add the IPv6 all link-local routers Ethernet address. This is the + /* Add the IPv6 all link-local routers IEEE 802.15.4 address. This is the * address that we expect to receive ICMPv6 Router Solicitation * packets. */ @@ -1377,7 +993,8 @@ static int macnet_ioctl(FAR struct net_driver_s *dev, int cmd, if (netmac != NULL) { unsigned long macarg = (unsigned int)((uintptr_t)&netmac->u); - ret = priv->md_mac.macops.ioctl(priv->md_mac, cmd, macarg); + ret = mac802154_ioctl(priv->md_mac, cmd, macarg); + } } @@ -1387,8 +1004,10 @@ static int macnet_ioctl(FAR struct net_driver_s *dev, int cmd, else { - ret = priv->md_mac.macops.ioctl(priv->md_mac, cmd, arg); + ret = mac802154_ioctl(priv->md_mac, cmd, arg); } + + return ret; } #endif @@ -1413,7 +1032,7 @@ static int macnet_get_mhrlen(FAR struct ieee802154_driver_s *netdev, { FAR struct macnet_driver_s *priv; - DEBUGASSERT(netdev != NULL && netdev->i_dev.d_private != NULL && iob != NULL); + DEBUGASSERT(netdev != NULL && netdev->i_dev.d_private != NULL && meta != NULL); priv = (FAR struct macnet_driver_s *)netdev->i_dev.d_private; return mac802154_get_mhrlen(priv->md_mac, meta); @@ -1441,20 +1060,21 @@ static int macnet_req_data(FAR struct ieee802154_driver_s *netdev, FAR struct iob_s *framelist) { FAR struct macnet_driver_s *priv; - struct ieee802154_data_req_s req; FAR struct iob_s *iob; int ret; - DEBUGASSERT(netdev != NULL && netdev->i_dev.d_private != NULL && iob != NULL); + DEBUGASSERT(netdev != NULL && netdev->i_dev.d_private != NULL); priv = (FAR struct macnet_driver_s *)netdev->i_dev.d_private; + DEBUGASSERT(meta != NULL && framelist != NULL); + /* Add the incoming list of frames to the MAC's outgoing queue */ for (iob = framelist; iob != NULL; iob = framelist) { /* Increment statistics */ - NETDEV_RXPACKETS(&priv->lo_ieee.i_dev); + NETDEV_TXPACKETS(&priv->md_dev.i_dev); /* Remove the IOB from the queue */ @@ -1463,15 +1083,13 @@ static int macnet_req_data(FAR struct ieee802154_driver_s *netdev, /* Transfer the frame to the MAC */ - req.meta = mets; - req.frame = iob; - ret = mac802154_req_data(priv->md_mac, req); + ret = mac802154_req_data(priv->md_mac, meta, iob); if (ret < 0) { wlerr("ERROR: mac802154_req_data failed: %d\n", ret); iob_free(iob); - for (iob = framelist; ; iob != NULL; iob = framelist) + for (iob = framelist; iob != NULL; iob = framelist) { /* Remove the IOB from the queue and free */ @@ -1533,7 +1151,7 @@ int mac802154netdev_register(MACHANDLE mac) */ pktbuf = (FAR uint8_t *)kmm_malloc(CONFIG_NET_6LOWPAN_MTU + CONFIG_NET_GUARDSIZE); - if (pktbuf == NULL + if (pktbuf == NULL) { nerr("ERROR: Failed to allocate the packet buffer\n"); kmm_free(priv); @@ -1542,7 +1160,7 @@ int mac802154netdev_register(MACHANDLE mac) /* Initialize the driver structure */ - ieee = &priv->lo_ieee; + ieee = &priv->md_dev; dev = &ieee->i_dev; dev->d_buf = pktbuf; /* Single packet buffer */ dev->d_ifup = macnet_ifup; /* I/F up (new IP address) callback */ @@ -1561,9 +1179,8 @@ int mac802154netdev_register(MACHANDLE mac) priv->md_mac = mac; /* Save the MAC interface instance */ priv->md_txpoll = wd_create(); /* Create periodic poll timer */ - priv->md_txtimeout = wd_create(); /* Create TX timeout timer */ - DEBUGASSERT(priv->md_txpoll != NULL && priv->md_txtimeout != NULL); + DEBUGASSERT(priv->md_txpoll != NULL); /* Initialize the Network frame-related callbacks */ @@ -1575,22 +1192,22 @@ int mac802154netdev_register(MACHANDLE mac) priv->md_cb.mc_priv = priv; maccb = &priv->md_cb.mc_cb; - maccb->mlme_notify = macdev_mlme_notify; - maccb->mcps_notify = macdev_mcps_notify; + maccb->mlme_notify = macnet_mlme_notify; + maccb->mcps_notify = macnet_mcps_notify; /* Bind the callback structure */ ret = mac802154_bind(mac, maccb); - if (ret < 0 + if (ret < 0) { nerr("ERROR: Failed to bind the MAC callbacks: %d\n", ret); /* Release wdog timers */ wd_delete(priv->md_txpoll); - wd_delete(priv->md_txtimeout); /* Free memory and return the error */ + kmm_free(pktbuf); kmm_free(priv); return ret; @@ -1602,7 +1219,7 @@ int mac802154netdev_register(MACHANDLE mac) /* Register the device with the OS so that socket IOCTLs can be performed */ - (void)netdev_register(&priv->md_dev, NET_LL_IEEE802154); + (void)netdev_register(&priv->md_dev.i_dev, NET_LL_IEEE802154); return OK; } -- GitLab From d785893a65b3fa8435629bea6c554438412339b5 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 7 May 2017 16:58:49 -0600 Subject: [PATCH 751/990] Update some comments. --- net/sixlowpan/sixlowpan_framer.c | 44 ++++++++++---------------- wireless/ieee802154/mac802154_netdev.c | 9 ------ 2 files changed, 17 insertions(+), 36 deletions(-) diff --git a/net/sixlowpan/sixlowpan_framer.c b/net/sixlowpan/sixlowpan_framer.c index 9de555134d..454d06c407 100644 --- a/net/sixlowpan/sixlowpan_framer.c +++ b/net/sixlowpan/sixlowpan_framer.c @@ -4,18 +4,6 @@ * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * - * Derives from Contiki: - * - * Copyright (c) 2008, Swedish Institute of Computer Science. - * All rights reserved. - * Authors: Adam Dunkels - * Nicolas Tsiftes - * Niclas Finne - * Mathilde Durvy - * Julien Abeille - * Joakim Eriksson - * Joel Hoglund - * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: @@ -23,23 +11,25 @@ * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in the - * documentation and/or other materials provided with the distribution. - * 3. Neither the name of the Institute nor the names of its contributors - * may be used to endorse or promote products derived from this software + * 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 INSTITUTE 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 INSTITUTE 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. + * 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. * ****************************************************************************/ diff --git a/wireless/ieee802154/mac802154_netdev.c b/wireless/ieee802154/mac802154_netdev.c index d1cd9c97a9..2c53009507 100644 --- a/wireless/ieee802154/mac802154_netdev.c +++ b/wireless/ieee802154/mac802154_netdev.c @@ -604,15 +604,6 @@ static void macnet_txpoll_work(FAR void *arg) /* Perform the poll */ - /* Check if there is room in the send another TX packet. We cannot perform - * the TX poll if he are unable to accept another packet for transmission. - */ - - /* If so, update TCP timing states and poll the network for new XMIT data. - * Hmmm.. might be bug here. Does this mean if there is a transmit in - * progress, we will missing TCP time state updates? - */ - (void)devif_timer(&priv->md_dev.i_dev, macnet_txpoll_callback); /* Setup the watchdog poll timer again */ -- GitLab From b8ef079951f23d2ea5d02cde2032b0c1dc8706da Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Mon, 8 May 2017 03:43:36 +0000 Subject: [PATCH 752/990] stm32:stm32_serial Forgot the -1 on mask --- arch/arm/src/stm32/stm32_serial.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/arch/arm/src/stm32/stm32_serial.c b/arch/arm/src/stm32/stm32_serial.c index 04dcde479e..200c76c43b 100644 --- a/arch/arm/src/stm32/stm32_serial.c +++ b/arch/arm/src/stm32/stm32_serial.c @@ -187,7 +187,7 @@ # endif # define RXDMA_MUTIPLE 4 # define RXDMA_BUFFER_SIZE ((CONFIG_STM32_SERIAL_RXDMA_BUFFER_SIZE \ - + RXDMA_MUTIPLE) & ~RXDMA_MUTIPLE) + + RXDMA_MUTIPLE) & ~(RXDMA_MUTIPLE-1)) /* DMA priority */ -- GitLab From b0b0c7ac490fe7a694931e5d43096ab391b0abe1 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 8 May 2017 08:34:21 -0600 Subject: [PATCH 753/990] IEEE 802.15.4 network driver. Remove support for multicast address filtering; doesn't work that way on an IEEE 802.15.4 network --- wireless/ieee802154/mac802154_netdev.c | 97 +++----------------------- 1 file changed, 9 insertions(+), 88 deletions(-) diff --git a/wireless/ieee802154/mac802154_netdev.c b/wireless/ieee802154/mac802154_netdev.c index 2c53009507..f510cf7f5d 100644 --- a/wireless/ieee802154/mac802154_netdev.c +++ b/wireless/ieee802154/mac802154_netdev.c @@ -205,9 +205,6 @@ static int macnet_addmac(FAR struct net_driver_s *dev, static int macnet_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac); #endif -#ifdef CONFIG_NET_ICMPv6 -static void macnet_ipv6multicast(FAR struct macnet_driver_s *priv); -#endif #endif #ifdef CONFIG_NETDEV_IOCTL static int macnet_ioctl(FAR struct net_driver_s *dev, int cmd, @@ -676,13 +673,7 @@ static int macnet_ifup(FAR struct net_driver_s *dev) /* Initialize PHYs, the IEEE 802.15.4 interface, and setup up IEEE 802.15.4 interrupts */ #warning Missing logic - /* Instantiate the MAC address from priv->md_dev.i_dev.d_mac.ether_addr_octet */ - -#ifdef CONFIG_NET_ICMPv6 - /* Set up IPv6 multicast address filtering */ - - macnet_ipv6multicast(priv); -#endif + /* Setup up address filtering */ /* Set and activate a timer process */ @@ -840,9 +831,11 @@ static int macnet_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) { FAR struct macnet_driver_s *priv = (FAR struct macnet_driver_s *)dev->d_private; - /* Add the MAC address to the hardware multicast routing table */ + /* Add the MAC address to the hardware multicast routing table. Not used + * with IEEE 802.15.4 radios. + */ - return OK; + return -ENOSYS; } #endif @@ -869,85 +862,13 @@ static int macnet_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac) { FAR struct macnet_driver_s *priv = (FAR struct macnet_driver_s *)dev->d_private; - /* Add the MAC address to the hardware multicast routing table */ - - return OK; -} -#endif - -/**************************************************************************** - * Name: macnet_ipv6multicast - * - * Description: - * Configure the IPv6 multicast MAC address. - * - * Parameters: - * priv - A reference to the private driver state structure - * - * Returned Value: - * OK on success; Negated errno on failure. - * - * Assumptions: - * - ****************************************************************************/ - -#ifdef CONFIG_NET_ICMPv6 -static void macnet_ipv6multicast(FAR struct macnet_driver_s *priv) -{ - FAR struct net_driver_s *dev; - uint16_t tmp16; - uint8_t mac[6]; - - /* For ICMPv6, we need to add the IPv6 multicast address - * - * For IPv6 multicast addresses, the IEEE 802.15.4 MAC is derived by - * the four low-order octets OR'ed with the MAC 33:33:00:00:00:00, - * so for example the IPv6 address FF02:DEAD:BEEF::1:3 would map - * to the IEEE 802.15.4 MAC address 33:33:00:01:00:03. - * - * NOTES: This appears correct for the ICMPv6 Router Solicitation - * Message, but the ICMPv6 Neighbor Solicitation message seems to - * use 33:33:ff:01:00:03. + /* Remove the MAC address from the hardware multicast routing table Not used + * with IEEE 802.15.4 radios. */ - mac[0] = 0x33; - mac[1] = 0x33; - - dev = &priv->dev; - tmp16 = dev->d_ipv6addr[6]; - mac[2] = 0xff; - mac[3] = tmp16 >> 8; - - tmp16 = dev->d_ipv6addr[7]; - mac[4] = tmp16 & 0xff; - mac[5] = tmp16 >> 8; - - ninfo("IPv6 Multicast: %02x:%02x:%02x:%02x:%02x:%02x\n", - mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]); - - (void)macnet_addmac(dev, mac); - -#ifdef CONFIG_NET_ICMPv6_AUTOCONF - /* Add the IPv6 all link-local nodes IEEE 802.15.4 address. This is the - * address that we expect to receive ICMPv6 Router Advertisement - * packets. - */ - - (void)macnet_addmac(dev, g_ipv6_ethallnodes.ether_addr_octet); - -#endif /* CONFIG_NET_ICMPv6_AUTOCONF */ - -#ifdef CONFIG_NET_ICMPv6_ROUTER - /* Add the IPv6 all link-local routers IEEE 802.15.4 address. This is the - * address that we expect to receive ICMPv6 Router Solicitation - * packets. - */ - - (void)macnet_addmac(dev, g_ipv6_ethallrouters.ether_addr_octet); - -#endif /* CONFIG_NET_ICMPv6_ROUTER */ + return -ENOSYS; } -#endif /* CONFIG_NET_ICMPv6 */ +#endif /**************************************************************************** * Name: macnet_ioctl -- GitLab From 546e7acb99ab2495866d1b0ad0e705a2b0c1ef49 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Mon, 8 May 2017 15:54:03 +0000 Subject: [PATCH 754/990] stm32:Serial DMA buffer round off not up --- arch/arm/src/stm32/stm32_serial.c | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/arch/arm/src/stm32/stm32_serial.c b/arch/arm/src/stm32/stm32_serial.c index 200c76c43b..6425cd2d91 100644 --- a/arch/arm/src/stm32/stm32_serial.c +++ b/arch/arm/src/stm32/stm32_serial.c @@ -186,8 +186,10 @@ # define CONFIG_STM32_SERIAL_RXDMA_BUFFER_SIZE 32 # endif # define RXDMA_MUTIPLE 4 +# define RXDMA_MUTIPLE_MASK (RXDMA_MUTIPLE -1) # define RXDMA_BUFFER_SIZE ((CONFIG_STM32_SERIAL_RXDMA_BUFFER_SIZE \ - + RXDMA_MUTIPLE) & ~(RXDMA_MUTIPLE-1)) + + RXDMA_MUTIPLE_MASK) \ + & ~RXDMA_MUTIPLE_MASK)) /* DMA priority */ -- GitLab From 18eaf52e352930f48b81461ffa9f1bcde5e87b69 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 8 May 2017 10:56:35 -0600 Subject: [PATCH 755/990] 6loWPAN: packet meta data does not need to be a global variable --- net/sixlowpan/sixlowpan_framelist.c | 27 ++++++++++++++------------- net/sixlowpan/sixlowpan_framer.c | 28 +++++++++++++++------------- net/sixlowpan/sixlowpan_globals.c | 14 -------------- net/sixlowpan/sixlowpan_internal.h | 12 +++++------- 4 files changed, 34 insertions(+), 47 deletions(-) diff --git a/net/sixlowpan/sixlowpan_framelist.c b/net/sixlowpan/sixlowpan_framelist.c index 3f208bb388..697bec1a81 100644 --- a/net/sixlowpan/sixlowpan_framelist.c +++ b/net/sixlowpan/sixlowpan_framelist.c @@ -211,6 +211,7 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, FAR const void *buf, size_t buflen, FAR const struct sixlowpan_tagaddr_s *destmac) { + struct packet_metadata_s pktmeta; struct ieee802154_frame_meta_s meta; FAR struct iob_s *iob; FAR uint8_t *fptr; @@ -232,8 +233,8 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, /* Reset frame meta data */ - memset(&g_packet_meta, 0, sizeof(struct packet_metadata_s)); - g_packet_meta.xmits = CONFIG_NET_6LOWPAN_MAX_MACTRANSMITS; + memset(&pktmeta, 0, sizeof(struct packet_metadata_s)); + pktmeta.xmits = CONFIG_NET_6LOWPAN_MAX_MACTRANSMITS; /* Set stream mode for all TCP packets, except FIN packets. */ @@ -246,11 +247,11 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, if ((tcp->flags & TCP_FIN) == 0 && (tcp->flags & TCP_CTL) != TCP_ACK) { - g_packet_meta.type = FRAME_ATTR_TYPE_STREAM; + pktmeta.type = FRAME_ATTR_TYPE_STREAM; } else if ((tcp->flags & TCP_FIN) == TCP_FIN) { - g_packet_meta.type = FRAME_ATTR_TYPE_STREAM_END; + pktmeta.type = FRAME_ATTR_TYPE_STREAM_END; } } #endif @@ -288,22 +289,22 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, */ #ifdef CONFIG_NET_6LOWPAN_EXTENDEDADDR - g_packet_meta.sextended = TRUE; - sixlowpan_eaddrcopy(g_packet_meta.source.eaddr.u8, + pktmeta.sextended = TRUE; + sixlowpan_eaddrcopy(pktmeta.source.eaddr.u8, &ieee->i_dev.d_mac.ieee802154); #else - sixlowpan_saddrcopy(g_packet_meta.source.saddr.u8, + sixlowpan_saddrcopy(pktmeta.source.saddr.u8, &ieee->i_dev.d_mac.ieee802154); #endif if (destmac->extended) { - g_packet_meta.dextended = TRUE; - sixlowpan_eaddrcopy(g_packet_meta.dest.eaddr.u8, destmac->u.eaddr.u8); + pktmeta.dextended = TRUE; + sixlowpan_eaddrcopy(pktmeta.dest.eaddr.u8, destmac->u.eaddr.u8); } else { - sixlowpan_saddrcopy(g_packet_meta.dest.saddr.u8, destmac->u.saddr.u8); + sixlowpan_saddrcopy(pktmeta.dest.saddr.u8, destmac->u.saddr.u8); } /* Get the destination PAN ID. @@ -312,15 +313,15 @@ int sixlowpan_queue_frames(FAR struct ieee802154_driver_s *ieee, * PAN IDs are the same. */ - g_packet_meta.dpanid = 0xffff; - (void)sixlowpan_src_panid(ieee, &g_packet_meta.dpanid); + pktmeta.dpanid = 0xffff; + (void)sixlowpan_src_panid(ieee, &pktmeta.dpanid); /* Based on the collected attributes and addresses, construct the MAC meta * data structure that we need to interface with the IEEE802.15.4 MAC (we * will update the MSDU payload size when the IOB has been setup). */ - ret = sixlowpan_meta_data(ieee, &meta, 0); + ret = sixlowpan_meta_data(ieee, &pktmeta, &meta, 0); if (ret < 0) { nerr("ERROR: sixlowpan_meta_data() failed: %d\n", ret); diff --git a/net/sixlowpan/sixlowpan_framer.c b/net/sixlowpan/sixlowpan_framer.c index 454d06c407..d52a5cd30c 100644 --- a/net/sixlowpan/sixlowpan_framer.c +++ b/net/sixlowpan/sixlowpan_framer.c @@ -100,7 +100,7 @@ static bool sixlowpan_anyaddrnull(FAR uint8_t *addr, uint8_t addrlen) * ****************************************************************************/ -static inline bool sixlowpan_saddrnull(FAR uint8_t *saddr) +static inline bool sixlowpan_saddrnull(FAR const uint8_t *saddr) { return sixlowpan_anyaddrnull(saddr, NET_6LOWPAN_SADDRSIZE); } @@ -120,7 +120,7 @@ static inline bool sixlowpan_saddrnull(FAR uint8_t *saddr) * ****************************************************************************/ -static inline bool sixlowpan_eaddrnull(FAR uint8_t *eaddr) +static inline bool sixlowpan_eaddrnull(FAR const uint8_t *eaddr) { return sixlowpan_anyaddrnull(eaddr, NET_6LOWPAN_EADDRSIZE); } @@ -137,9 +137,10 @@ static inline bool sixlowpan_eaddrnull(FAR uint8_t *eaddr) * data structure that we need to interface with the IEEE802.15.4 MAC. * * Input Parameters: - * ieee - IEEE 802.15.4 MAC driver state reference. - * meta - Location to return the corresponding meta data. - * paylen - The size of the data payload to be sent. + * ieee - IEEE 802.15.4 MAC driver state reference. + * pktmeta - Meta-data specific to the current outgoing frame + * meta - Location to return the corresponding meta data. + * paylen - The size of the data payload to be sent. * * Returned Value: * Ok is returned on success; Othewise a negated errno value is returned. @@ -150,6 +151,7 @@ static inline bool sixlowpan_eaddrnull(FAR uint8_t *eaddr) ****************************************************************************/ int sixlowpan_meta_data(FAR struct ieee802154_driver_s *ieee, + FAR const struct packet_metadata_s *pktmeta, FAR struct ieee802154_frame_meta_s *meta, uint16_t paylen) { @@ -161,23 +163,23 @@ int sixlowpan_meta_data(FAR struct ieee802154_driver_s *ieee, /* Source address mode */ - meta->src_addr_mode = g_packet_meta.sextended != 0? + meta->src_addr_mode = pktmeta->sextended != 0? IEEE802154_ADDRMODE_EXTENDED : IEEE802154_ADDRMODE_SHORT; /* Check for a broadcast destination address (all zero) */ - if (g_packet_meta.dextended != 0) + if (pktmeta->dextended != 0) { /* Extended destination address mode */ - rcvrnull = sixlowpan_eaddrnull(g_packet_meta.dest.eaddr.u8); + rcvrnull = sixlowpan_eaddrnull(pktmeta->dest.eaddr.u8); } else { /* Short destination address mode */ - rcvrnull = sixlowpan_saddrnull(g_packet_meta.dest.saddr.u8); + rcvrnull = sixlowpan_saddrnull(pktmeta->dest.saddr.u8); } if (rcvrnull) @@ -198,22 +200,22 @@ int sixlowpan_meta_data(FAR struct ieee802154_driver_s *ieee, meta->dest_addr.mode = IEEE802154_ADDRMODE_SHORT; meta->dest_addr.saddr = 0; } - else if (g_packet_meta.dextended != 0) + else if (pktmeta->dextended != 0) { /* Extended destination address mode */ meta->dest_addr.mode = IEEE802154_ADDRMODE_EXTENDED; - sixlowpan_eaddrcopy(&meta->dest_addr.eaddr, g_packet_meta.dest.eaddr.u8); + sixlowpan_eaddrcopy(&meta->dest_addr.eaddr, pktmeta->dest.eaddr.u8); } else { /* Short destination address mode */ meta->dest_addr.mode = IEEE802154_ADDRMODE_SHORT; - sixlowpan_saddrcopy(&meta->dest_addr.saddr, g_packet_meta.dest.saddr.u8); + sixlowpan_saddrcopy(&meta->dest_addr.saddr, pktmeta->dest.saddr.u8); } - meta->dest_addr.panid = g_packet_meta.dpanid; + meta->dest_addr.panid = pktmeta->dpanid; /* Handle associated with MSDU. Will increment once per packet, not * necesarily per frame: The same MSDU handle will be used for each diff --git a/net/sixlowpan/sixlowpan_globals.c b/net/sixlowpan/sixlowpan_globals.c index 7c5740df9e..6d52082df1 100644 --- a/net/sixlowpan/sixlowpan_globals.c +++ b/net/sixlowpan/sixlowpan_globals.c @@ -67,18 +67,4 @@ uint8_t g_uncomp_hdrlen; uint8_t g_frame_hdrlen; -/* In order to provide a customizable IEEE 802.15.4 MAC header, a structure - * of meta data is passed to the MAC network driver, struct - * ieee802154_frame_meta_s. Many of the settings in this meta data are - * fixed, deterimined by the 6loWPAN configuration. Other settings depend - * on the protocol used in the current packet or on chacteristics of the - * destination node. - * - * The following structure is used to summarize those per-packet - * customizations and, along, with the fixed configuratin settings, - * determines the full form of that meta data. - */ - -struct packet_metadata_s g_packet_meta; - #endif /* CONFIG_NET_6LOWPAN */ diff --git a/net/sixlowpan/sixlowpan_internal.h b/net/sixlowpan/sixlowpan_internal.h index ade3ae1809..a4dd9b21d0 100644 --- a/net/sixlowpan/sixlowpan_internal.h +++ b/net/sixlowpan/sixlowpan_internal.h @@ -212,10 +212,6 @@ extern uint8_t g_uncomp_hdrlen; extern uint8_t g_frame_hdrlen; -/* Packet buffer metadata: Attributes and addresses */ - -extern struct packet_metadata_s g_packet_meta; - /**************************************************************************** * Public Types ****************************************************************************/ @@ -278,9 +274,10 @@ int sixlowpan_send(FAR struct net_driver_s *dev, * data structure that we need to interface with the IEEE802.15.4 MAC. * * Input Parameters: - * ieee - IEEE 802.15.4 MAC driver state reference. - * meta - Location to return the corresponding meta data. - * paylen - The size of the data payload to be sent. + * ieee - IEEE 802.15.4 MAC driver state reference. + * pktmeta - Meta-data specific to the current outgoing frame + * meta - Location to return the corresponding meta data. + * paylen - The size of the data payload to be sent. * * Returned Value: * Ok is returned on success; Othewise a negated errno value is returned. @@ -291,6 +288,7 @@ int sixlowpan_send(FAR struct net_driver_s *dev, ****************************************************************************/ int sixlowpan_meta_data(FAR struct ieee802154_driver_s *ieee, + FAR const struct packet_metadata_s *pktmeta, FAR struct ieee802154_frame_meta_s *meta, uint16_t paylen); -- GitLab From aa11d637a88c640b8e970475f8535e1a248fe970 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 8 May 2017 12:33:15 -0600 Subject: [PATCH 756/990] STM32 TIM: Add method to get timer width. Freerun timer: Use timer width to get the correct clock rollover point. --- arch/arm/src/stm32/stm32_freerun.c | 6 ++-- arch/arm/src/stm32/stm32_freerun.h | 1 + arch/arm/src/stm32/stm32_tim.c | 57 ++++++++++++++++++++++++------ arch/arm/src/stm32/stm32_tim.h | 2 ++ 4 files changed, 54 insertions(+), 12 deletions(-) diff --git a/arch/arm/src/stm32/stm32_freerun.c b/arch/arm/src/stm32/stm32_freerun.c index 673b0412d7..f631aa0aa5 100644 --- a/arch/arm/src/stm32/stm32_freerun.c +++ b/arch/arm/src/stm32/stm32_freerun.c @@ -137,6 +137,7 @@ int stm32_freerun_initialize(struct stm32_freerun_s *freerun, int chan, */ freerun->chan = chan; + freerun->width = STM32_TIM_GETWIDTH(freerun->tch); freerun->running = false; #ifdef CONFIG_CLOCK_TIMEKEEPING @@ -153,7 +154,7 @@ int stm32_freerun_initialize(struct stm32_freerun_s *freerun, int chan, /* Set timer period */ - STM32_TIM_SETPERIOD(freerun->tch, UINT32_MAX); + STM32_TIM_SETPERIOD(freerun->tch, (uint32_t)((1ull << freerun->width) - 1)); /* Start the counter */ @@ -248,7 +249,8 @@ int stm32_freerun_counter(struct stm32_freerun_s *freerun, * usecs = (ticks * USEC_PER_SEC) / frequency; */ - usec = ((((uint64_t)overflow << 32) + (uint64_t)counter) * USEC_PER_SEC) / + usec = ((((uint64_t)overflow << freerun->width) + + (uint64_t)counter) * USEC_PER_SEC) / freerun->frequency; /* And return the value of the timer */ diff --git a/arch/arm/src/stm32/stm32_freerun.h b/arch/arm/src/stm32/stm32_freerun.h index bc7609666c..b263367d16 100644 --- a/arch/arm/src/stm32/stm32_freerun.h +++ b/arch/arm/src/stm32/stm32_freerun.h @@ -63,6 +63,7 @@ struct stm32_freerun_s { uint8_t chan; /* The timer/counter in use */ + uint8_t width; /* Width of timer (16- or 32-bits) */ bool running; /* True: the timer is running */ FAR struct stm32_tim_dev_s *tch; /* Handle returned by stm32_tim_init() */ uint32_t frequency; diff --git a/arch/arm/src/stm32/stm32_tim.c b/arch/arm/src/stm32/stm32_tim.c index 5590992827..d4a4ed2559 100644 --- a/arch/arm/src/stm32/stm32_tim.c +++ b/arch/arm/src/stm32/stm32_tim.c @@ -334,22 +334,23 @@ static void stm32_tim_gpioconfig(uint32_t cfg, stm32_tim_channel_t mode); /* Timer methods */ -static int stm32_tim_setmode(FAR struct stm32_tim_dev_s *dev, stm32_tim_mode_t mode); -static int stm32_tim_setclock(FAR struct stm32_tim_dev_s *dev, uint32_t freq); +static int stm32_tim_setmode(FAR struct stm32_tim_dev_s *dev, stm32_tim_mode_t mode); +static int stm32_tim_setclock(FAR struct stm32_tim_dev_s *dev, uint32_t freq); static void stm32_tim_setperiod(FAR struct stm32_tim_dev_s *dev, uint32_t period); static uint32_t stm32_tim_getcounter(FAR struct stm32_tim_dev_s *dev); -static int stm32_tim_setchannel(FAR struct stm32_tim_dev_s *dev, uint8_t channel, - stm32_tim_channel_t mode); -static int stm32_tim_setcompare(FAR struct stm32_tim_dev_s *dev, uint8_t channel, - uint32_t compare); -static int stm32_tim_getcapture(FAR struct stm32_tim_dev_s *dev, uint8_t channel); -static int stm32_tim_setisr(FAR struct stm32_tim_dev_s *dev, xcpt_t handler, - void *arg, int source); +static int stm32_tim_getwidth(FAR struct stm32_tim_dev_s *dev); +static int stm32_tim_setchannel(FAR struct stm32_tim_dev_s *dev, uint8_t channel, + stm32_tim_channel_t mode); +static int stm32_tim_setcompare(FAR struct stm32_tim_dev_s *dev, uint8_t channel, + uint32_t compare); +static int stm32_tim_getcapture(FAR struct stm32_tim_dev_s *dev, uint8_t channel); +static int stm32_tim_setisr(FAR struct stm32_tim_dev_s *dev, xcpt_t handler, + void *arg, int source); static void stm32_tim_enableint(FAR struct stm32_tim_dev_s *dev, int source); static void stm32_tim_disableint(FAR struct stm32_tim_dev_s *dev, int source); static void stm32_tim_ackint(FAR struct stm32_tim_dev_s *dev, int source); -static int stm32_tim_checkint(FAR struct stm32_tim_dev_s *dev, int source); +static int stm32_tim_checkint(FAR struct stm32_tim_dev_s *dev, int source); /************************************************************************************ * Private Data @@ -361,6 +362,7 @@ static const struct stm32_tim_ops_s stm32_tim_ops = .setclock = stm32_tim_setclock, .setperiod = stm32_tim_setperiod, .getcounter = stm32_tim_getcounter, + .getwidth = stm32_tim_getwidth, .setchannel = stm32_tim_setchannel, .setcompare = stm32_tim_setcompare, .getcapture = stm32_tim_getcapture, @@ -904,6 +906,41 @@ static uint32_t stm32_tim_getcounter(FAR struct stm32_tim_dev_s *dev) return stm32_getreg32(dev, STM32_BTIM_CNT_OFFSET); } +/************************************************************************************ + * Name: stm32_tim_getwidth + ************************************************************************************/ + +static int stm32_tim_getwidth(FAR struct stm32_tim_dev_s *dev) +{ + /* Only TIM2 and TIM5 timers may be 32-bits in width + * + * Reference Table 2 of en.DM00042534.pdf + */ + + switch (((struct stm32_tim_priv_s *)dev)->base) + { + /* TIM2 is 32-bits on all except F10x, L0x, and L1x lines */ + +#if defined(CONFIG_STM32_TIM2) && !defined(STM32_STM32F10XX) && \ + !defined(STM32_STM32L15XX) + case STM32_TIM2_BASE: + return 32; +#endif + + /* TIM5 is 32-bits on all except F10x lines */ + +#if defined(CONFIG_STM32_TIM5) && !defined(STM32_STM32F10XX) + case STM32_TIM5_BASE: + return 32; +#endif + + /* All others are 16-bit times */ + + default: + return 16; + } +} + /************************************************************************************ * Name: stm32_tim_setchannel ************************************************************************************/ diff --git a/arch/arm/src/stm32/stm32_tim.h b/arch/arm/src/stm32/stm32_tim.h index 921baebc6c..5b9422f3ee 100644 --- a/arch/arm/src/stm32/stm32_tim.h +++ b/arch/arm/src/stm32/stm32_tim.h @@ -61,6 +61,7 @@ #define STM32_TIM_SETCLOCK(d,freq) ((d)->ops->setclock(d,freq)) #define STM32_TIM_SETPERIOD(d,period) ((d)->ops->setperiod(d,period)) #define STM32_TIM_GETCOUNTER(d) ((d)->ops->getcounter(d)) +#define STM32_TIM_GETWIDTH(d) ((d)->ops->getwidth(d)) #define STM32_TIM_SETCHANNEL(d,ch,mode) ((d)->ops->setchannel(d,ch,mode)) #define STM32_TIM_SETCOMPARE(d,ch,comp) ((d)->ops->setcompare(d,ch,comp)) #define STM32_TIM_GETCAPTURE(d,ch) ((d)->ops->getcapture(d,ch)) @@ -166,6 +167,7 @@ struct stm32_tim_ops_s /* General and Advanced Timers Adds */ + int (*getwidth)(FAR struct stm32_tim_dev_s *dev); int (*setchannel)(FAR struct stm32_tim_dev_s *dev, uint8_t channel, stm32_tim_channel_t mode); int (*setcompare)(FAR struct stm32_tim_dev_s *dev, uint8_t channel, -- GitLab From 13f1ba03d5e118cfae03c60361dac88e712e4051 Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Mon, 8 May 2017 13:14:21 -0600 Subject: [PATCH 757/990] Photon: Add README file --- Documentation/README.html | 2 + README.txt | 2 + configs/photon/README.txt | 125 ++++++++++++++++++++++++++++++++++++++ 3 files changed, 129 insertions(+) create mode 100644 configs/photon/README.txt diff --git a/Documentation/README.html b/Documentation/README.html index 727b2f3684..726f4aa3cf 100644 --- a/Documentation/README.html +++ b/Documentation/README.html @@ -208,6 +208,8 @@ nuttx/ | | `- README.txt | |- pic32mz-starterkit/ | | `- README.txt + | |- photon/ + | | `- README.txt | |- qemu-i486/ | | `- README.txt | |- sabre-6quad/ diff --git a/README.txt b/README.txt index f06800339f..334b501e51 100644 --- a/README.txt +++ b/README.txt @@ -1580,6 +1580,8 @@ nuttx/ | | `- README.txt | |- pic32mz-starterkit/ | | `- README.txt + | |- photon/ + | | `- README.txt | |- qemu-i486/ | | `- README.txt | |- sabre-6quad/ diff --git a/configs/photon/README.txt b/configs/photon/README.txt new file mode 100644 index 0000000000..779226e632 --- /dev/null +++ b/configs/photon/README.txt @@ -0,0 +1,125 @@ +README +====== + + This README discusses issues unique to NuttX configurations for the + Particle.io Photon board featuring the STM32F205RG MCU. + The STM32F205RG is a 120 MHz Cortex-M3 operation with 1Mbit Flash + memory and 128kbytes. The board includes a Broadcom BCM43362 WiFi. + +Contents +======== + + - Selecting the Photon board on NuttX + - Configuring NuttX to use your Wireless Router (aka Access Point) + - Flashing NuttX in the Photon board + - Serial console configuration + +Selecting the Photon board on NuttX +=================================== + + NOTICE: We will not discuss about toolchains and environment configuration + here, please take a look at STM32F4Discory board README or other STM32 board + because it should work for Photon board as well. + + Let us to consider that you cloned the nuttx and apps repositories, then + follow these steps: + + 1) Clear your build system before to start: + + $ make apps_distclean + $ make distclean + + 2) Enter inside nuttx/tools and configure to use the Photon board: + + $ cd nuttx + $ cd tools + $ ./configure.sh photon/wlan + + Now please return to root of nuttx/ directory: + + $ cd .. + +Configuring NuttX to use your Wireless Router (aka Access Point) +================================================================ + + Since you are already in the root of nuttx/ repository, execute + make menuconfig to define your Wireless Router and your password: + + $ make menuconfig + + Browser the menus this way: + + Application Configuration ---> + NSH Library ---> + Networking Configuration ---> + WAPI Configuration ---> + (myApSSID) SSID + (mySSIDpassphrase) Passprhase + + Replace the SSID from myApSSID with your wireless router name and + the Passprhase with your WiFi password. + + Exit and save your configuration. + + Finally just compile NuttX: + + $ make + +Flashing NuttX in the Photon board +================================== + + Connect the Photon board in your computer using a MicroUSB cable. Press and + hold both board's buttons (SETUP and RESET), then release the RESET button, + the board will start blinking in the Purple color, waiting until it starts + blinking in Yellow color. Now you can release the SETUP button as well. + + 1) You can verify if DFU mode in your board is working, using this command: + + $ sudo dfu-util -l + dfu-util 0.8 + + Copyright 2005-2009 Weston Schmidt, Harald Welte and OpenMoko Inc. + Copyright 2010-2014 Tormod Volden and Stefan Schmidt + This program is Free Software and has ABSOLUTELY NO WARRANTY + Please report bugs to dfu-util@lists.gnumonks.org + + Found DFU: [2b04:d006] ver=0200, devnum=15, cfg=1, intf=0, alt=1, name="@DCT Flash /0x00000000/01*016Kg", serial="00000000010C" + Found DFU: [2b04:d006] ver=0200, devnum=15, cfg=1, intf=0, alt=0, name="@Internal Flash /0x08000000/03*016Ka,01*016Kg,01*064Kg,07*128Kg", serial="00000000010C" + + 2) Flash the nuttx.bin inside the Internal Flash: + + $ sudo dfu-util -d 2b04:d006 -a 0 -s 0x08020000 -D nuttx.bin + + dfu-util 0.8 + + Copyright 2005-2009 Weston Schmidt, Harald Welte and OpenMoko Inc. + Copyright 2010-2014 Tormod Volden and Stefan Schmidt + This program is Free Software and has ABSOLUTELY NO WARRANTY + Please report bugs to dfu-util@lists.gnumonks.org + + dfu-util: Invalid DFU suffix signature + dfu-util: A valid DFU suffix will be required in a future dfu-util release!!! + Opening DFU capable USB device... + ID 2b04:d006 + Run-time device DFU version 011a + Claiming USB DFU Interface... + Setting Alternate Setting #0 ... + Determining device status: state = dfuIDLE, status = 0 + dfuIDLE, continuing + DFU mode device DFU version 011a + Device returned transfer size 4096 + DfuSe interface name: "Internal Flash " + Downloading to address = 0x08020000, size = 331348 + Download [=========================] 100% 331348 bytes + Download done. + File downloaded successfully + + +Serial console configuration +============================ + + Connect a USB/Serial 3.3V dongle to GND, TX and RX pins of Photon board. + Then use some serial console client (minicom, picocom, teraterm, etc) confi- + gured to 115200 8n1 without software or hardware flow control. + + Reset the board and you should see NuttX starting in the serial. -- GitLab From 2ea6bb4dc13cca3ed61920ce9731f71caac4fd1a Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Mon, 8 May 2017 16:20:35 -0400 Subject: [PATCH 758/990] wireless/ieee802154: Moves ind allocator from mac802154.h to ieee802154_mac.h --- .../wireless/ieee802154/ieee802154_mac.h | 66 +++++++++++++++++++ wireless/ieee802154/mac802154.h | 64 ------------------ 2 files changed, 66 insertions(+), 64 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index ff9e270621..8352883acc 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -1492,6 +1492,72 @@ int mac802154dev_register(MACHANDLE mac, int minor); int mac802154netdev_register(MACHANDLE mac); +/**************************************************************************** + * Name: ieee802154_indpool_initialize + * + * Description: + * This function initializes the meta-data allocator. This function must + * be called early in the initialization sequence before any radios + * begin operation. + * + * Inputs: + * None + * + * Return Value: + * None + * + ****************************************************************************/ + +void ieee802154_indpool_initialize(void); + +/**************************************************************************** + * Name: ieee802154_ind_allocate + * + * Description: + * The ieee802154_ind_allocate function will get a free meta-data + * structure for use by the IEEE 802.15.4 MAC. + * + * Interrupt handling logic will first attempt to allocate from the + * g_indfree list. If that list is empty, it will attempt to allocate + * from its reserve, g_indfree_irq. If that list is empty, then the + * allocation fails (NULL is returned). + * + * Non-interrupt handler logic will attempt to allocate from g_indfree + * list. If that the list is empty, then the meta-data structure will be + * allocated from the dynamic memory pool. + * + * Inputs: + * None + * + * Return Value: + * A reference to the allocated msg structure. All user fields in this + * structure have been zeroed. On a failure to allocate, NULL is + * returned. + * + ****************************************************************************/ + +FAR struct ieee802154_data_ind_s *ieee802154_ind_allocate(void); + +/**************************************************************************** + * Name: ieee802154_ind_free + * + * Description: + * The ieee802154_ind_free function will return a meta-data structure to + * the free pool of messages if it was a pre-allocated meta-data + * structure. If the meta-data structure was allocated dynamically it will + * be deallocated. + * + * Inputs: + * ind - meta-data structure to free + * + * Return Value: + * None + * + ****************************************************************************/ + +void ieee802154_ind_free(FAR struct ieee802154_data_ind_s *ind); + + #undef EXTERN #ifdef __cplusplus } diff --git a/wireless/ieee802154/mac802154.h b/wireless/ieee802154/mac802154.h index 45f9c3a729..66fa5495ca 100644 --- a/wireless/ieee802154/mac802154.h +++ b/wireless/ieee802154/mac802154.h @@ -336,70 +336,6 @@ int mac802154_resp_associate(MACHANDLE mac, int mac802154_resp_orphan(MACHANDLE mac, FAR struct ieee802154_orphan_resp_s *resp); -/**************************************************************************** - * Name: ieee802154_indpool_initialize - * - * Description: - * This function initializes the meta-data allocator. This function must - * be called early in the initialization sequence before any radios - * begin operation. - * - * Inputs: - * None - * - * Return Value: - * None - * - ****************************************************************************/ - -void ieee802154_indpool_initialize(void); - -/**************************************************************************** - * Name: ieee802154_ind_allocate - * - * Description: - * The ieee802154_ind_allocate function will get a free meta-data - * structure for use by the IEEE 802.15.4 MAC. - * - * Interrupt handling logic will first attempt to allocate from the - * g_indfree list. If that list is empty, it will attempt to allocate - * from its reserve, g_indfree_irq. If that list is empty, then the - * allocation fails (NULL is returned). - * - * Non-interrupt handler logic will attempt to allocate from g_indfree - * list. If that the list is empty, then the meta-data structure will be - * allocated from the dynamic memory pool. - * - * Inputs: - * None - * - * Return Value: - * A reference to the allocated msg structure. All user fields in this - * structure have been zeroed. On a failure to allocate, NULL is - * returned. - * - ****************************************************************************/ - -FAR struct ieee802154_data_ind_s *ieee802154_ind_allocate(void); - -/**************************************************************************** - * Name: ieee802154_ind_free - * - * Description: - * The ieee802154_ind_free function will return a meta-data structure to - * the free pool of messages if it was a pre-allocated meta-data - * structure. If the meta-data structure was allocated dynamically it will - * be deallocated. - * - * Inputs: - * ind - meta-data structure to free - * - * Return Value: - * None - * - ****************************************************************************/ - -void ieee802154_ind_free(FAR struct ieee802154_data_ind_s *ind); #undef EXTERN #ifdef __cplusplus -- GitLab From 2da6f71e84e86b2948e1f8d97f840654887a1a7c Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Mon, 8 May 2017 16:21:29 -0400 Subject: [PATCH 759/990] wireless/ieee802154: Finishes MAC processing of received data frame --- wireless/ieee802154/mac802154.c | 34 ++++++++++++++++++++------------- 1 file changed, 21 insertions(+), 13 deletions(-) diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index cc6e4415b7..1da758082c 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -409,7 +409,7 @@ static FAR struct mac802154_txframe_s * } /**************************************************************************** - * Name: mac802154_push_rxframe + * Name: mac802154_push_dataind * * Description: * Push a data indication onto the list to be processed @@ -814,6 +814,7 @@ static void mac802154_rxframe_worker(FAR void *arg) FAR struct iob_s *frame; uint16_t *frame_ctrl; bool panid_comp; + uint8_t ftype; while(1) { @@ -839,7 +840,7 @@ static void mac802154_rxframe_worker(FAR void *arg) /* Get a local copy of the frame to make it easier to access */ - frame = iob->frame; + frame = ind->frame; /* Set a local pointer to the frame control then move the offset past * the frame control field @@ -852,16 +853,16 @@ static void mac802154_rxframe_worker(FAR void *arg) * this isn't a data frame */ - ind->src.mode = (frame_ctrl & IEEE802154_FRAMECTRL_SADDR) >> + ind->src.mode = (*frame_ctrl & IEEE802154_FRAMECTRL_SADDR) >> IEEE802154_FRAMECTRL_SHIFT_SADDR; - ind->dest.mode = (frame_ctrl & IEEE802154_FRAMECTRL_DADDR) >> + ind->dest.mode = (*frame_ctrl & IEEE802154_FRAMECTRL_DADDR) >> IEEE802154_FRAMECTRL_SHIFT_DADDR; - panid_comp = (frame_ctrl & IEEE802154_FRAMECTRL_PANIDCOMP) >> + panid_comp = (*frame_ctrl & IEEE802154_FRAMECTRL_PANIDCOMP) >> IEEE802154_FRAMECTRL_SHIFT_PANIDCOMP; - ind->dsn = iob->frame->io_data[frame->io_offset++]; + ind->dsn = frame->io_data[frame->io_offset++]; /* If the destination address is included */ @@ -879,7 +880,7 @@ static void mac802154_rxframe_worker(FAR void *arg) } else if (ind->dest.mode == IEEE802154_ADDRMODE_EXTENDED) { - memcpy(&ind->dest.eaddr[0], frame->io_data[frame->io_offset], + memcpy(&ind->dest.eaddr[0], &frame->io_data[frame->io_offset], IEEE802154_EADDR_LEN); frame->io_offset += 8; } @@ -913,13 +914,16 @@ static void mac802154_rxframe_worker(FAR void *arg) } else if (ind->src.mode == IEEE802154_ADDRMODE_EXTENDED) { - memcpy(&ind->src.eaddr[0], frame->io_data[frame->io_offset], + memcpy(&ind->src.eaddr[0], &frame->io_data[frame->io_offset], IEEE802154_EADDR_LEN); frame->io_offset += 8; } } + + ftype = (*frame_ctrl & IEEE802154_FRAMECTRL_FTYPE) >> + IEEE802154_FRAMECTRL_SHIFT_FTYPE; - if (frame_ctrl & IEEE802154_FRAMECTRL_FTYPE == IEEE802154_FRAME_DATA) + if (ftype == IEEE802154_FRAME_DATA) { /* If there is a registered MCPS callback receiver registered, send * the frame, otherwise, throw it out. @@ -929,7 +933,7 @@ static void mac802154_rxframe_worker(FAR void *arg) { mcps_notify.dataind = ind; priv->cb->mcps_notify(priv->cb, IEEE802154_NOTIFY_IND_DATA, - mcps_notify); + &mcps_notify); } else { @@ -938,11 +942,11 @@ static void mac802154_rxframe_worker(FAR void *arg) ieee802154_ind_free(ind); } } - else if (frame_ctrl & IEEE802154_FRAMECTRL_FTYPE == IEEE802154_FRAME_COMMAND) + else if (ftype == IEEE802154_FRAME_COMMAND) { } - else if (frame_ctrl & IEEE802154_FRAMECTRL_FTYPE == IEEE802154_FRAME_BEACON) + else if (ftype == IEEE802154_FRAME_BEACON) { } @@ -1023,6 +1027,10 @@ MACHANDLE mac802154_create(FAR struct ieee802154_radio_s *radiodev) radiodev->ops->bind(radiodev, &mac->radiocb.cb); + /* Initialize our data indication pool */ + + ieee802154_indpool_initialize(); + return (MACHANDLE)mac; } @@ -1360,7 +1368,7 @@ int mac802154_req_data(MACHANDLE mac, */ if ((meta->dest_addr.mode == IEEE802154_ADDRMODE_NONE) || - (*frame_ctrl & IEEE802154_FRAMECTRL_PANIDCOMP)) + (!(*frame_ctrl & IEEE802154_FRAMECTRL_PANIDCOMP))) { memcpy(&frame->io_data[mhr_len], &priv->addr.panid, 2); mhr_len += 2; -- GitLab From bbb85332fd766b60b31658da29e6abb1c67853f6 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Mon, 8 May 2017 16:22:02 -0400 Subject: [PATCH 760/990] wireless/ieee802154: Finishes MAC char driver read functionality --- .../wireless/ieee802154/ieee802154_ioctl.h | 7 + wireless/ieee802154/mac802154_device.c | 234 +++++++++++++++++- 2 files changed, 232 insertions(+), 9 deletions(-) diff --git a/include/nuttx/wireless/ieee802154/ieee802154_ioctl.h b/include/nuttx/wireless/ieee802154/ieee802154_ioctl.h index 6171d0e3a3..5f14f2e2c6 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_ioctl.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_ioctl.h @@ -81,5 +81,12 @@ struct mac802154dev_txframe_s uint16_t length; }; +struct mac802154dev_rxframe_s +{ + struct ieee802154_data_ind_s meta; + uint8_t payload[IEEE802154_MAX_MAC_PAYLOAD_SIZE]; + uint16_t length; +}; + #endif /* CONFIG_WIRELESS_IEEE802154 */ #endif /* __INCLUDE_NUTTX_WIRELESS_IEEE802154_IEEE802154_IOCTL_H */ diff --git a/wireless/ieee802154/mac802154_device.c b/wireless/ieee802154/mac802154_device.c index 6ea212ae53..a4eb93b656 100644 --- a/wireless/ieee802154/mac802154_device.c +++ b/wireless/ieee802154/mac802154_device.c @@ -108,6 +108,9 @@ struct mac802154_chardevice_s struct mac802154dev_callback_s md_cb; /* Callback information */ sem_t md_exclsem; /* Exclusive device access */ + bool readpending; /* Is there a read using the semaphore? */ + sem_t readsem; /* Signaling semaphore for waiting read */ + /* The following is a singly linked list of open references to the * MAC device. */ @@ -115,6 +118,11 @@ struct mac802154_chardevice_s FAR struct mac802154dev_open_s *md_open; FAR struct mac802154dev_dwait_s *md_dwait; + /* Hold a list of transactions as a "readahead" buffer */ + + FAR struct ieee802154_data_ind_s *dataind_head; + FAR struct ieee802154_data_ind_s *dataind_tail; + #ifndef CONFIG_DISABLE_SIGNALS /* MCPS Service notification information */ @@ -137,6 +145,12 @@ struct mac802154_chardevice_s static inline int mac802154dev_takesem(sem_t *sem); #define mac802154dev_givesem(s) sem_post(s); +static void mac802154dev_push_dataind(FAR struct mac802154_chardevice_s *dev, + FAR struct ieee802154_data_ind_s *ind); +static FAR struct ieee802154_data_ind_s * + mac802154dev_pop_dataind(FAR struct mac802154_chardevice_s *dev); + + static void mac802154dev_mlme_notify(FAR const struct ieee802154_maccb_s *maccb, enum ieee802154_macnotify_e notif, FAR const union ieee802154_mlme_notify_u *arg); @@ -158,6 +172,8 @@ static int mac802154dev_ioctl(FAR struct file *filep, int cmd, static void mac802154dev_conf_data(FAR struct mac802154_chardevice_s *dev, FAR const struct ieee802154_data_conf_s *conf); +static void mac802154dev_ind_data(FAR struct mac802154_chardevice_s *dev, + FAR struct ieee802154_data_ind_s *ind); /**************************************************************************** * Private Data @@ -207,6 +223,79 @@ static inline int mac802154dev_takesem(sem_t *sem) return OK; } +/**************************************************************************** + * Name: mac802154dev_push_dataind + * + * Description: + * Push a data indication onto the list to be processed + * + ****************************************************************************/ + +static void mac802154dev_push_dataind(FAR struct mac802154_chardevice_s *dev, + FAR struct ieee802154_data_ind_s *ind) +{ + /* Ensure the forward link is NULL */ + + ind->flink = NULL; + + /* If the tail is not empty, make the frame pointed to by the tail, + * point to the new data indication */ + + if (dev->dataind_tail != NULL) + { + dev->dataind_tail->flink = ind; + } + + /* Point the tail at the new frame */ + + dev->dataind_tail = ind; + + /* If the head is NULL, we need to point it at the data indication since there + * is only one indication in the list at this point */ + + if (dev->dataind_head == NULL) + { + dev->dataind_head = ind; + } +} + +/**************************************************************************** + * Name: mac802154dev_pop_dataind + * + * Description: + * Pop a data indication from the list + * + ****************************************************************************/ + +static FAR struct ieee802154_data_ind_s * + mac802154dev_pop_dataind(FAR struct mac802154_chardevice_s *dev) +{ + FAR struct ieee802154_data_ind_s *ind; + + if (dev->dataind_head == NULL) + { + return NULL; + } + + /* Get the data indication from the head of the list */ + + ind = dev->dataind_head; + ind->flink = NULL; + + /* Move the head pointer to the next data indication */ + + dev->dataind_head = ind->flink; + + /* If the head is now NULL, the list is empty, so clear the tail too */ + + if (dev->dataind_head == NULL) + { + dev->dataind_tail = NULL; + } + + return ind; +} + /**************************************************************************** * Name: mac802154dev_open * @@ -368,6 +457,8 @@ static ssize_t mac802154dev_read(FAR struct file *filep, FAR char *buffer, { FAR struct inode *inode; FAR struct mac802154_chardevice_s *dev; + FAR struct mac802154dev_rxframe_s *rx; + FAR struct ieee802154_data_ind_s *ind; int ret; DEBUGASSERT(filep && filep->f_inode); @@ -375,20 +466,94 @@ static ssize_t mac802154dev_read(FAR struct file *filep, FAR char *buffer, DEBUGASSERT(inode->i_private); dev = (FAR struct mac802154_chardevice_s *)inode->i_private; - /* Get exclusive access to the driver structure */ + /* Check to make sure the buffer is the right size for the struct */ - ret = mac802154dev_takesem(&dev->md_exclsem); - if (ret < 0) + if (len != sizeof(struct mac802154dev_rxframe_s)) { - wlerr("ERROR: mac802154dev_takesem failed: %d\n", ret); - return ret; + wlerr("ERROR: buffer isn't a mac802154dev_rxframe_s: %lu\n", + (unsigned long)len); + return -EINVAL; } - /* TODO: Add code to read a packet and return it */ - ret = -ENOTSUP; + DEBUGASSERT(buffer != NULL); + rx = (FAR struct mac802154dev_rxframe_s *)buffer; - mac802154dev_givesem(&dev->md_exclsem); - return ret; + while (1) + { + /* Get exclusive access to the driver structure */ + + ret = mac802154dev_takesem(&dev->md_exclsem); + if (ret < 0) + { + wlerr("ERROR: mac802154dev_takesem failed: %d\n", ret); + return ret; + } + + /* Try popping a data indication off the list */ + + ind = mac802154dev_pop_dataind(dev); + + /* If the indication is not null, we can exit the loop and copy the data */ + + if (ind != NULL) + { + mac802154dev_givesem(&dev->md_exclsem); + break; + } + + /* If this is a non-blocking call, or if there is another read operation + * already pending, don't block. This driver returns EAGAIN even when + * configured as non-blocking if another read operation is already pending + * This situation should be rare. It will only occur when there are 2 calls + * to read from separate threads and there was no data in the rx list. + */ + + if ((filep->f_oflags & O_NONBLOCK) || dev->readpending) + { + mac802154dev_givesem(&dev->md_exclsem); + return -EAGAIN; + } + + dev->readpending = true; + mac802154dev_givesem(&dev->md_exclsem); + + /* Wait to be signaled when a frame is added to the list */ + + if (sem_wait(&dev->readsem) < 0) + { + DEBUGASSERT(errno == EINTR); + /* Need to get exclusive access again to change the pending bool */ + + ret = mac802154dev_takesem(&dev->md_exclsem); + dev->readpending = false; + mac802154dev_givesem(&dev->md_exclsem); + return -EINTR; + } + + /* Let the loop wrap back around, we will then pop a indication and this + * time, it should have a data indication + */ + } + + rx->length = (ind->frame->io_len - ind->frame->io_offset); + + /* Copy the data from the IOB to the user supplied struct */ + + memcpy(&rx->payload[0], &ind->frame->io_data[ind->frame->io_offset], + rx->length); + + memcpy(&rx->meta, ind, sizeof(struct ieee802154_data_ind_s)); + + /* Zero out the forward link and IOB reference */ + + rx->meta.flink = NULL; + rx->meta.frame = NULL; + + /* Deallocate the data indication */ + + ieee802154_ind_free(ind); + + return OK; } /**************************************************************************** @@ -649,6 +814,11 @@ static void mac802154dev_mcps_notify(FAR const struct ieee802154_maccb_s *maccb, mac802154dev_conf_data(dev, &arg->dataconf); } break; + case IEEE802154_NOTIFY_IND_DATA: + { + mac802154dev_ind_data(dev, arg->dataind); + } + break; default: break; } @@ -717,6 +887,48 @@ static void mac802154dev_conf_data(FAR struct mac802154_chardevice_s *dev, #endif } +static void mac802154dev_ind_data(FAR struct mac802154_chardevice_s *dev, + FAR struct ieee802154_data_ind_s *ind) +{ + /* Get exclusive access to the driver structure. We don't care about any + * signals so if we see one, just go back to trying to get access again */ + + while (mac802154dev_takesem(&dev->md_exclsem) != 0); + + /* Push the indication onto the list */ + + mac802154dev_push_dataind(dev, ind); + + /* Check if there is a read waiting for data */ + + if (dev->readpending) + { + /* Wake the thread waiting for the data transmission */ + + dev->readpending = false; + sem_post(&dev->readsem); + } + + /* Release the driver */ + + mac802154dev_givesem(&dev->md_exclsem); + +#ifndef CONFIG_DISABLE_SIGNALS + /* Send a signal to the registered application */ + +#ifdef CONFIG_CAN_PASS_STRUCTS + /* Copy the status as the signal data to be optionally used by app */ + + union sigval value; + value.sival_int = IEEE802154_STATUS_SUCCESS; + (void)sigqueue(dev->md_mcps_pid, dev->md_mcps_notify.mn_signo, value); +#else + (void)sigqueue(dev->md_mcps_pid, dev->md_mcps_notify.mn_signo, + value.sival_ptr); +#endif +#endif +} + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -758,6 +970,10 @@ int mac802154dev_register(MACHANDLE mac, int minor) dev->md_mac = mac; sem_init(&dev->md_exclsem, 0, 1); /* Allow the device to be opened once * before blocking */ + + sem_init(&dev->readsem, 0, 0); + sem_setprotocol(&dev->readsem, SEM_PRIO_NONE); + dev->readpending = false; /* Initialize the MAC callbacks */ -- GitLab From 3fa8e32e3664145a33cd695454dff54778166ae7 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Mon, 8 May 2017 16:23:09 -0400 Subject: [PATCH 761/990] wireless/ieee802154: MRF24J40: Finishes receive functionality, supports promicuous mode, and rxonidle attributes --- drivers/wireless/ieee802154/mrf24j40.c | 59 +++++++++++-------- .../wireless/ieee802154/ieee802154_mac.h | 2 +- 2 files changed, 37 insertions(+), 24 deletions(-) diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c index 14c9782777..8283278d3c 100644 --- a/drivers/wireless/ieee802154/mrf24j40.c +++ b/drivers/wireless/ieee802154/mrf24j40.c @@ -121,6 +121,10 @@ struct mrf24j40_radio_s struct ieee802154_radio_s radio; /* The public device instance */ FAR struct ieee802154_radiocb_s *radiocb; /* Registered callbacks */ + /* MAC Attributes */ + + bool rxonidle : 1; + /* Low-level MCU-specific support */ FAR const struct mrf24j40_lower_s *lower; @@ -186,40 +190,41 @@ static int mrf24j40_setup_fifo(FAR struct mrf24j40_radio_s *dev, FAR struct iob_s *frame, uint32_t fifo_addr); -static int mrf24j40_setchannel(FAR struct mrf24j40_radio_s *radio, +static int mrf24j40_setchannel(FAR struct mrf24j40_radio_s *dev, uint8_t chan); -static int mrf24j40_getchannel(FAR struct mrf24j40_radio_s *radio, +static int mrf24j40_getchannel(FAR struct mrf24j40_radio_s *dev, FAR uint8_t *chan); -static int mrf24j40_setpanid(FAR struct mrf24j40_radio_s *radio, +static int mrf24j40_setpanid(FAR struct mrf24j40_radio_s *dev, uint16_t panid); -static int mrf24j40_getpanid(FAR struct mrf24j40_radio_s *radio, +static int mrf24j40_getpanid(FAR struct mrf24j40_radio_s *dev, FAR uint16_t *panid); -static int mrf24j40_setsaddr(FAR struct mrf24j40_radio_s *radio, +static int mrf24j40_setsaddr(FAR struct mrf24j40_radio_s *dev, uint16_t saddr); -static int mrf24j40_getsaddr(FAR struct mrf24j40_radio_s *radio, +static int mrf24j40_getsaddr(FAR struct mrf24j40_radio_s *dev, FAR uint16_t *saddr); -static int mrf24j40_seteaddr(FAR struct mrf24j40_radio_s *radio, +static int mrf24j40_seteaddr(FAR struct mrf24j40_radio_s *dev, FAR const uint8_t *eaddr); -static int mrf24j40_geteaddr(FAR struct mrf24j40_radio_s *radio, +static int mrf24j40_geteaddr(FAR struct mrf24j40_radio_s *dev, FAR uint8_t *eaddr); -static int mrf24j40_setpromisc(FAR struct mrf24j40_radio_s *radio, +static int mrf24j40_setpromisc(FAR struct mrf24j40_radio_s *dev, bool promisc); -static int mrf24j40_getpromisc(FAR struct mrf24j40_radio_s *radio, +static int mrf24j40_getpromisc(FAR struct mrf24j40_radio_s *dev, FAR bool *promisc); -static int mrf24j40_setdevmode(FAR struct mrf24j40_radio_s *radio, +static int mrf24j40_setdevmode(FAR struct mrf24j40_radio_s *dev, uint8_t mode); -static int mrf24j40_getdevmode(FAR struct mrf24j40_radio_s *radio, +static int mrf24j40_getdevmode(FAR struct mrf24j40_radio_s *dev, FAR uint8_t *mode); -static int mrf24j40_settxpower(FAR struct mrf24j40_radio_s *radio, +static int mrf24j40_settxpower(FAR struct mrf24j40_radio_s *dev, int32_t txpwr); -static int mrf24j40_gettxpower(FAR struct mrf24j40_radio_s *radio, +static int mrf24j40_gettxpower(FAR struct mrf24j40_radio_s *dev, FAR int32_t *txpwr); -static int mrf24j40_setcca(FAR struct mrf24j40_radio_s *radio, +static int mrf24j40_setcca(FAR struct mrf24j40_radio_s *dev, FAR struct ieee802154_cca_s *cca); -static int mrf24j40_getcca(FAR struct mrf24j40_radio_s *radio, +static int mrf24j40_getcca(FAR struct mrf24j40_radio_s *dev, FAR struct ieee802154_cca_s *cca); -static int mrf24j40_energydetect(FAR struct mrf24j40_radio_s *radio, +static int mrf24j40_energydetect(FAR struct mrf24j40_radio_s *dev, FAR uint8_t *energy); +static int mrf24j40_rxenable(FAR struct mrf24j40_radio_s *dev, bool enable); /* Driver operations */ @@ -392,6 +397,12 @@ static int mrf24j40_set_attr(FAR struct ieee802154_radio_s *radio, ret = IEEE802154_STATUS_SUCCESS; } break; + case IEEE802154_PIB_MAC_RX_ON_WHEN_IDLE: + { + dev->rxonidle = attr_value->mac.rxonidle; + mrf24j40_rxenable(dev, dev->rxonidle); + } + break; default: ret = IEEE802154_STATUS_UNSUPPORTED_ATTRIBUTE; } @@ -1470,9 +1481,8 @@ static void mrf24j40_irqwork_txgts(FAR struct mrf24j40_radio_s *dev, * ****************************************************************************/ -static int mrf24j40_rxenable(FAR struct ieee802154_radio_s *radio, bool enable) +static int mrf24j40_rxenable(FAR struct mrf24j40_radio_s *dev, bool enable) { - FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)radio; uint8_t reg; if (enable) @@ -1567,11 +1577,14 @@ done: mrf24j40_setreg(dev->spi, MRF24J40_BBREG1, 0); - /* Enable rx int */ + /* Only enable RX interrupt if we are to be listening when IDLE */ - reg = mrf24j40_getreg(dev->spi, MRF24J40_INTCON); - reg &= ~MRF24J40_INTCON_RXIE; - mrf24j40_setreg(dev->spi, MRF24J40_INTCON, reg); + if (dev->rxonidle) + { + reg = mrf24j40_getreg(dev->spi, MRF24J40_INTCON); + reg &= ~MRF24J40_INTCON_RXIE; + mrf24j40_setreg(dev->spi, MRF24J40_INTCON, reg); + } } /**************************************************************************** diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index 8352883acc..2c6a846af7 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -507,7 +507,7 @@ union ieee802154_macattr_u bool promisc_mode; bool rng_support; bool resp_wait_time; - bool rx_when_idle; + bool rxonidle; bool sec_enabled; bool timestamp_support; -- GitLab From 014b69e120c1e6aabd4785b1aff1a8e1e32ca8aa Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Mon, 8 May 2017 22:56:05 +0000 Subject: [PATCH 762/990] removed stray paren. --- arch/arm/src/stm32/stm32_serial.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/arch/arm/src/stm32/stm32_serial.c b/arch/arm/src/stm32/stm32_serial.c index 6425cd2d91..77c07ea68e 100644 --- a/arch/arm/src/stm32/stm32_serial.c +++ b/arch/arm/src/stm32/stm32_serial.c @@ -189,7 +189,7 @@ # define RXDMA_MUTIPLE_MASK (RXDMA_MUTIPLE -1) # define RXDMA_BUFFER_SIZE ((CONFIG_STM32_SERIAL_RXDMA_BUFFER_SIZE \ + RXDMA_MUTIPLE_MASK) \ - & ~RXDMA_MUTIPLE_MASK)) + & ~RXDMA_MUTIPLE_MASK) /* DMA priority */ -- GitLab From b2bb795520ed0424ef1e217d865983b49b518ef9 Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Tue, 9 May 2017 09:00:37 +0200 Subject: [PATCH 763/990] Final fixes to get the nucleo-l432kc config build. execution not tested yet --- configs/Kconfig | 13 +++++++++++++ configs/nucleo-l432kc/src/stm32_spi.c | 1 + 2 files changed, 14 insertions(+) diff --git a/configs/Kconfig b/configs/Kconfig index d61c7ef879..a2763f7c00 100644 --- a/configs/Kconfig +++ b/configs/Kconfig @@ -810,6 +810,15 @@ config ARCH_BOARD_NUCLEO_F411RE This is a minimal configuration that supports low-level test of the Nucleo F411RE in the NuttX source tree. +config ARCH_BOARD_NUCLEO_L432KC + bool "STM32L432 Nucleo-32 L432KC" + depends on ARCH_CHIP_STM32L432KC + select ARCH_HAVE_LEDS + select ARCH_HAVE_BUTTONS + select ARCH_HAVE_IRQBUTTONS + ---help--- + STMicro Nucleo-32 L432KC board based on the STMicro STM32L432KCU6 MCU. + config ARCH_BOARD_NUCLEO_L452RE bool "STM32L452 Nucleo L452RE" depends on ARCH_CHIP_STM32L452RE @@ -1566,6 +1575,7 @@ config ARCH_BOARD default "nucleo-f303re" if ARCH_BOARD_NUCLEO_F303RE default "nucleo-f334r8" if ARCH_BOARD_NUCLEO_F334R8 default "nucleo-f4x1re" if ARCH_BOARD_NUCLEO_F401RE || ARCH_BOARD_NUCLEO_F411RE + default "nucleo-l432kc" if ARCH_BOARD_NUCLEO_L432KC default "nucleo-l452re" if ARCH_BOARD_NUCLEO_L452RE default "nucleo-l476rg" if ARCH_BOARD_NUCLEO_L476RG default "nucleo-l496zg" if ARCH_BOARD_NUCLEO_L496ZG @@ -1886,6 +1896,9 @@ endif if ARCH_BOARD_NUCLEO_F401RE || ARCH_BOARD_NUCLEO_F411RE source "configs/nucleo-f4x1re/Kconfig" endif +if ARCH_BOARD_NUCLEO_L432KC +source "configs/nucleo-l432kc/Kconfig" +endif if ARCH_BOARD_NUCLEO_L452RE source "configs/nucleo-l452re/Kconfig" endif diff --git a/configs/nucleo-l432kc/src/stm32_spi.c b/configs/nucleo-l432kc/src/stm32_spi.c index 04f307c40c..731030f7ed 100644 --- a/configs/nucleo-l432kc/src/stm32_spi.c +++ b/configs/nucleo-l432kc/src/stm32_spi.c @@ -90,6 +90,7 @@ void stm32l4_spiinitialize(void) #endif _info("SPI1 initialized\n"); +#endif #ifdef CONFIG_STM32L4_SPI2 /* Configure SPI-based devices */ -- GitLab From 14831a18c6b5a241d091c381de2f303598b1943f Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Tue, 9 May 2017 10:01:26 +0200 Subject: [PATCH 764/990] cleanup all external peripherals --- configs/nucleo-l432kc/Kconfig | 13 -- configs/nucleo-l432kc/README.txt | 18 +- configs/nucleo-l432kc/scripts/l432kc.ld | 11 +- configs/nucleo-l432kc/src/nucleo-l432kc.h | 201 --------------------- configs/nucleo-l432kc/src/stm32_adc.c | 5 - configs/nucleo-l432kc/src/stm32_appinit.c | 15 +- configs/nucleo-l432kc/src/stm32_userleds.c | 2 +- 7 files changed, 9 insertions(+), 256 deletions(-) diff --git a/configs/nucleo-l432kc/Kconfig b/configs/nucleo-l432kc/Kconfig index 6c35982a4c..3ddc1813fe 100644 --- a/configs/nucleo-l432kc/Kconfig +++ b/configs/nucleo-l432kc/Kconfig @@ -5,17 +5,4 @@ if ARCH_BOARD_NUCLEO_L432KC -config NUCLEO_L432KC_AJOY_MINBUTTONS - bool "Minimal Joystick Buttons" - default n if !STM32_USART1 - default y if STM32_USART1 - depends on AJOYSTICK - ---help--- - The Itead Joystick shield supports analog X/Y position and up to 5 - buttons. Some of these buttons may conflict with other resources - (Button F, for example, conflicts with the default USART1 pin usage). - Selecting this option will return the number of buttons to the - minimal set: SELECT (joystick down), FIRE (BUTTON B), and JUMP - (BUTTON A). - endif # ARCH_BOARD_NUCLEO_L432KC diff --git a/configs/nucleo-l432kc/README.txt b/configs/nucleo-l432kc/README.txt index 0c642daa1b..dbe575f5c7 100644 --- a/configs/nucleo-l432kc/README.txt +++ b/configs/nucleo-l432kc/README.txt @@ -6,7 +6,7 @@ Nucleoi-l432kc board from ST Micro. See http://www.st.com/nucleo-l432kc -NucleoF476RG: +NucleoL432KC: Microprocessor: 32-bit ARM Cortex M4 at 80MHz STM32L432KCU6 Memory: 256 KB Flash and 64 KB SRAM @@ -315,22 +315,6 @@ mbed Hardware ======== - GPIO - ---- - SERIAL_TX=PA_2 USER_BUTTON=PC_13 - SERIAL_RX=PA_3 LED1 =PA_5 - - A0=PA_0 USART2RX D0=PA_3 D8 =PA_9 - A1=PA_1 USART2TX D1=PA_2 D9 =PC_7 - A2=PA_4 D2=PA_10 WIFI_CS=D10=PB_6 SPI_CS - A3=PB_0 WIFI_INT=D3=PB_3 D11=PA_7 SPI_MOSI - A4=PC_1 SDCS=D4=PB_5 D12=PA_6 SPI_MISO - A5=PC_0 WIFI_EN=D5=PB_4 LED1=D13=PA_5 SPI_SCK - LED2=D6=PB_10 I2C1_SDA=D14=PB_9 Probe - D7=PA_8 I2C1_SCL=D15=PB_8 Probe - - From: https://mbed.org/platforms/ST-Nucleo-F401RE/ - Buttons ------- B1 USER: the user button is connected to the I/O PC13 (pin 2) of the STM32 diff --git a/configs/nucleo-l432kc/scripts/l432kc.ld b/configs/nucleo-l432kc/scripts/l432kc.ld index bfac18b41f..9fb057cc10 100644 --- a/configs/nucleo-l432kc/scripts/l432kc.ld +++ b/configs/nucleo-l432kc/scripts/l432kc.ld @@ -3,6 +3,7 @@ * * Copyright (C) 2014 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Copyright (C) 2017 Sebastien Lorquet. All rights reserved. * Sebastien Lorquet * * Redistribution and use in source and binary forms, with or without @@ -34,8 +35,8 @@ * ****************************************************************************/ -/* The STM32F411RE has 512Kb of FLASH beginning at address 0x0800:0000 and - * 128Kb of SRAM beginning at address 0x2000:0000. When booting from FLASH, +/* The STM32L432KC has 256Kb of FLASH beginning at address 0x0800:0000 and + * 64Kb of SRAM beginning at address 0x2000:0000. When booting from FLASH, * FLASH memory is aliased to address 0x0000:0000 where the code expects to * begin execution by jumping to the entry point in the 0x0800:0000 address * range. @@ -43,8 +44,8 @@ MEMORY { - flash (rx) : ORIGIN = 0x08000000, LENGTH = 512K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K + flash (rx) : ORIGIN = 0x08000000, LENGTH = 256K + sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K } OUTPUT_ARCH(arm) @@ -85,7 +86,7 @@ SECTIONS _eronly = ABSOLUTE(.); - /* The STM32L432KC has 96Kb of SRAM beginning at the following address */ + /* The STM32L432KC has 64Kb of SRAM beginning at the following address */ .data : { _sdata = ABSOLUTE(.); diff --git a/configs/nucleo-l432kc/src/nucleo-l432kc.h b/configs/nucleo-l432kc/src/nucleo-l432kc.h index cbf549251e..7b6b2194d6 100644 --- a/configs/nucleo-l432kc/src/nucleo-l432kc.h +++ b/configs/nucleo-l432kc/src/nucleo-l432kc.h @@ -101,192 +101,6 @@ #define GPIO_BTN_USER \ (GPIO_INPUT |GPIO_FLOAT |GPIO_EXTI | GPIO_PORTC | GPIO_PIN13) -/* The shield uses the following pins: - * - * +5V - * GND - * SERIAL_TX=PA_2 USER_BUTTON=PC_13 - * SERIAL_RX=PA_3 LD2=PA_5 - * - * Analog Digital - * A0=PA_0 USART2RX D0=PA_3 D8 =PA_9 - * A1=PA_1 USART2TX D1=PA_2 D9 =PC_7 - * A2=PA_4 D2=PA_10 WIFI_CS=D10=PB_6 SPI_CS - * A3=PB_0 WIFI_INT=D3=PB_3 D11=PA_7 SPI_MOSI - * A4=PC_1 SD_CS=D4=PB_5 D12=PA_6 SPI_MISO - * A5=PC_0 WIFI_EN=D5=PB_4 LD2=D13=PA_5 SPI_SCK - * LED2=D6=PB_10 I2C1_SDA=D14=PB_9 WIFI Probe - * D7=PA_8 I2C1_SCL=D15=PB_8 WIFI Probe - * - * mostly from: https://mbed.org/platforms/ST-Nucleo-F401RE/ - * - */ - -#ifdef CONFIG_WL_CC3000 -# define GPIO_WIFI_INT (GPIO_PORTB | GPIO_PIN3 | GPIO_INPUT | \ - GPIO_PULLUP | GPIO_EXTI) -# define GPIO_WIFI_EN (GPIO_PORTB | GPIO_PIN4 | GPIO_OUTPUT_CLEAR | \ - GPIO_OUTPUT | GPIO_PULLUP | GPIO_SPEED_50MHz) -# define GPIO_WIFI_CS (GPIO_PORTB | GPIO_PIN6 | GPIO_OUTPUT_SET | \ - GPIO_OUTPUT | GPIO_PULLUP | GPIO_SPEED_50MHz) -# define GPIO_D14 (GPIO_PORTB | GPIO_PIN9 | GPIO_OUTPUT_CLEAR | \ - GPIO_OUTPUT | GPIO_PULLUP | GPIO_SPEED_50MHz) -# define GPIO_D15 (GPIO_PORTB | GPIO_PIN8 | GPIO_OUTPUT_CLEAR | \ - GPIO_OUTPUT | GPIO_PULLUP | GPIO_SPEED_50MHz) -# define GPIO_D0 (GPIO_PORTA | GPIO_PIN3 | GPIO_INPUT | \ - GPIO_PULLUP) -# define GPIO_D1 (GPIO_PORTA | GPIO_PIN2 | GPIO_OUTPUT_CLEAR | \ - GPIO_PULLUP) -# define GPIO_D2 (GPIO_PORTA | GPIO_PIN10 | GPIO_OUTPUT_CLEAR | \ - GPIO_OUTPUT | GPIO_PULLUP | GPIO_SPEED_50MHz) -# define GPIO_A0 (GPIO_PORTA | GPIO_PIN0 | GPIO_OUTPUT_SET | \ - GPIO_OUTPUT | GPIO_PULLUP | GPIO_SPEED_50MHz) -# define GPIO_A1 (GPIO_PORTA | GPIO_PIN1 | GPIO_OUTPUT_SET | \ - GPIO_OUTPUT | GPIO_PULLUP | GPIO_SPEED_50MHz) -# define GPIO_A2 (GPIO_PORTA | GPIO_PIN4 | GPIO_INPUT | \ - GPIO_PULLUP) -# define GPIO_A3 (GPIO_PORTB | GPIO_PIN0 | GPIO_INPUT | \ - GPIO_PULLUP) -#endif - -/* SPI1 off */ - -#define GPIO_SPI1_MOSI_OFF (GPIO_INPUT | GPIO_PULLDOWN | \ - GPIO_PORTA | GPIO_PIN7) -#define GPIO_SPI1_MISO_OFF (GPIO_INPUT | GPIO_PULLDOWN | \ - GPIO_PORTA | GPIO_PIN6) -#define GPIO_SPI1_SCK_OFF (GPIO_INPUT | GPIO_PULLDOWN | \ - GPIO_PORTA | GPIO_PIN5) - -/* SPI1 chip selects off */ - -#ifdef CONFIG_WL_CC3000 -# define GPIO_SPI_CS_WIFI_OFF \ - (GPIO_INPUT | GPIO_PULLDOWN | GPIO_SPEED_2MHz | \ - GPIO_PORTB | GPIO_PIN6) -#endif - -#ifdef HAVE_MMCSD -# define GPIO_SPI_CS_SD_CARD_OFF \ - (GPIO_INPUT | GPIO_PULLDOWN | GPIO_SPEED_2MHz | \ - GPIO_PORTB | GPIO_PIN5) -#endif - -/* SPI chip selects */ - -#ifdef CONFIG_WL_CC3000 -# define GPIO_SPI_CS_WIFI \ - (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_2MHz | \ - GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN6) -#endif - -#ifdef HAVE_MMCSD -# define GPIO_SPI_CS_SD_CARD \ - (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_2MHz | \ - GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN5) -#endif - -/* Devices on the onboard bus. - * - * Note that these are unshifted addresses. - */ - -#define NUCLEO_I2C_OBDEV_LED 0x55 -#define NUCLEO_I2C_OBDEV_HMC5883 0x1e - -/* User GPIOs - * - * GPIO0-1 are for probing WIFI status - */ - -#ifdef CONFIG_WL_CC3000 -# define GPIO_GPIO0_INPUT \ - (GPIO_INPUT | GPIO_PULLUP | GPIO_PORTB | GPIO_PIN8) -# define GPIO_GPIO1_INPUT \ - (GPIO_INPUT | GPIO_PULLUP | GPIO_PORTB | GPIO_PIN9) -# define GPIO_GPIO0_OUTPUT \ - (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_2MHz | \ - GPIO_OUTPUT_CLEAR | GPIO_PORTB | GPIO_PIN8) -# define GPIO_GPIO1_OUTPUT \ - (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_2MHz | \ - GPIO_OUTPUT_CLEAR | GPIO_PORTB | GPIO_PIN9) -#endif - -/* Itead Joystick Shield - * - * See http://imall.iteadstudio.com/im120417014.html for more information - * about this joystick. - * - * --------- ----------------- --------------------------------- - * ARDUINO ITEAD NUCLEO-F4x1 - * PIN NAME SIGNAL SIGNAL - * --------- ----------------- --------------------------------- - * D3 Button E Output PB3 - * D4 Button D Output PB5 - * D5 Button C Output PB4 - * D6 Button B Output PB10 - * D7 Button A Output PA8 - * D8 Button F Output PA9 - * D9 Button G Output PC7 - * A0 Joystick Y Output PA0 ADC1_0 - * A1 Joystick X Output PA1 ADC1_1 - * --------- ----------------- --------------------------------- - * - * All buttons are pulled on the shield. A sensed low value indicates - * when the button is pressed. - * - * NOTE: Button F cannot be used with the default USART1 configuration - * because PA9 is configured for USART1_RX by default. Use select - * different USART1 pins in the board.h file or select a different - * USART or select CONFIG_NUCLEO_L432KC_AJOY_MINBUTTONS which will - * eliminate all but buttons A, B, and C. - */ - -#define ADC_XOUPUT 1 /* X output is on ADC channel 1 */ -#define ADC_YOUPUT 0 /* Y output is on ADC channel 0 */ - -#define GPIO_BUTTON_A \ - (GPIO_INPUT | GPIO_PULLUP |GPIO_EXTI | GPIO_PORTA | GPIO_PIN8) -#define GPIO_BUTTON_B \ - (GPIO_INPUT | GPIO_PULLUP |GPIO_EXTI | GPIO_PORTB | GPIO_PIN10) -#define GPIO_BUTTON_C \ - (GPIO_INPUT | GPIO_PULLUP |GPIO_EXTI | GPIO_PORTB | GPIO_PIN4) -#define GPIO_BUTTON_D \ - (GPIO_INPUT | GPIO_PULLUP |GPIO_EXTI | GPIO_PORTB | GPIO_PIN5) -#define GPIO_BUTTON_E \ - (GPIO_INPUT | GPIO_PULLUP |GPIO_EXTI | GPIO_PORTB | GPIO_PIN3) -#define GPIO_BUTTON_F \ - (GPIO_INPUT | GPIO_PULLUP |GPIO_EXTI | GPIO_PORTA | GPIO_PIN9) -#define GPIO_BUTTON_G \ - (GPIO_INPUT | GPIO_PULLUP |GPIO_EXTI | GPIO_PORTC | GPIO_PIN7) - -/* Itead Joystick Signal interpretation: - * - * --------- ----------------------- --------------------------- - * BUTTON TYPE NUTTX ALIAS - * --------- ----------------------- --------------------------- - * Button A Large button A JUMP/BUTTON 3 - * Button B Large button B FIRE/BUTTON 2 - * Button C Joystick select button SELECT/BUTTON 1 - * Button D Tiny Button D BUTTON 6 - * Button E Tiny Button E BUTTON 7 - * Button F Large Button F BUTTON 4 - * Button G Large Button G BUTTON 5 - * --------- ----------------------- --------------------------- - */ - -#define GPIO_BUTTON_1 GPIO_BUTTON_C -#define GPIO_BUTTON_2 GPIO_BUTTON_B -#define GPIO_BUTTON_3 GPIO_BUTTON_A -#define GPIO_BUTTON_4 GPIO_BUTTON_F -#define GPIO_BUTTON_5 GPIO_BUTTON_G -#define GPIO_BUTTON_6 GPIO_BUTTON_D -#define GPIO_BUTTON_7 GPIO_BUTTON_E - -#define GPIO_SELECT GPIO_BUTTON_1 -#define GPIO_FIRE GPIO_BUTTON_2 -#define GPIO_JUMP GPIO_BUTTON_3 - /************************************************************************************ * Public Data ************************************************************************************/ @@ -299,9 +113,6 @@ extern struct spi_dev_s *g_spi1; #ifdef CONFIG_STM32L4_SPI2 extern struct spi_dev_s *g_spi2; #endif -#ifdef HAVE_MMCSD -extern struct sdio_dev_s *g_sdio; -#endif /************************************************************************************ * Public Functions @@ -351,18 +162,6 @@ int stm32l4_pwm_setup(void); int stm32l4_adc_setup(void); #endif -/**************************************************************************** - * Name: board_ajoy_initialize - * - * Description: - * Initialize and register the button joystick driver - * - ****************************************************************************/ - -#ifdef CONFIG_AJOYSTICK -int board_ajoy_initialize(void); -#endif - /**************************************************************************** * Name: board_timer_driver_initialize * diff --git a/configs/nucleo-l432kc/src/stm32_adc.c b/configs/nucleo-l432kc/src/stm32_adc.c index ddff398463..775d83190b 100644 --- a/configs/nucleo-l432kc/src/stm32_adc.c +++ b/configs/nucleo-l432kc/src/stm32_adc.c @@ -71,9 +71,7 @@ ************************************************************************************/ /* Identifying number of each ADC channel. */ -#ifdef CONFIG_AJOYSTICK #ifdef CONFIG_ADC_DMA -/* The Itead analog joystick gets inputs on ADC_IN0 and ADC_IN1 */ static const uint8_t g_adc1_chanlist[ADC1_NCHANNELS] = {0, 1}; @@ -84,8 +82,6 @@ static const uint32_t g_adc1_pinlist[ADC1_NCHANNELS] = {GPIO_ADC1_IN0, GPIO_ADC #else /* Without DMA, only a single channel can be supported */ -/* The Itead analog joystick gets input on ADC_IN0 */ - static const uint8_t g_adc1_chanlist[ADC1_NCHANNELS] = {0}; /* Configurations of pins used byte each ADC channels */ @@ -93,7 +89,6 @@ static const uint8_t g_adc1_chanlist[ADC1_NCHANNELS] = {0}; static const uint32_t g_adc1_pinlist[ADC1_NCHANNELS] = {GPIO_ADC1_IN0}; #endif /* CONFIG_ADC_DMA */ -#endif /* CONFIG_AJOYSTICK */ /************************************************************************************ * Private Functions diff --git a/configs/nucleo-l432kc/src/stm32_appinit.c b/configs/nucleo-l432kc/src/stm32_appinit.c index c486838650..649147101d 100644 --- a/configs/nucleo-l432kc/src/stm32_appinit.c +++ b/configs/nucleo-l432kc/src/stm32_appinit.c @@ -76,7 +76,7 @@ * ****************************************************************************/ -#ifdef CONFIG_WL_CC3000 +#ifdef CONFIG_NET void up_netinitialize(void) { } @@ -210,19 +210,6 @@ int board_app_initialize(uintptr_t arg) } #endif -#ifdef CONFIG_AJOYSTICK - /* Initialize and register the joystick driver */ - - ret = board_ajoy_initialize(); - if (ret != OK) - { - syslog(LOG_ERR, - "ERROR: Failed to register the joystick driver: %d\n", - ret); - return ret; - } -#endif - #ifdef CONFIG_TIMER /* Initialize and register the timer driver */ diff --git a/configs/nucleo-l432kc/src/stm32_userleds.c b/configs/nucleo-l432kc/src/stm32_userleds.c index 1ed437ced7..e6fa28f986 100644 --- a/configs/nucleo-l432kc/src/stm32_userleds.c +++ b/configs/nucleo-l432kc/src/stm32_userleds.c @@ -183,7 +183,7 @@ void board_userled(int led, bool ledon) { if (led == 1) { - stm32_gpiowrite(GPIO_LD2, ldeon); + stm32_gpiowrite(GPIO_LD2, ledon); } } -- GitLab From c1cf1269c70e425f2042632cb0c6e837988ea504 Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Tue, 9 May 2017 10:58:04 +0200 Subject: [PATCH 765/990] Adapt stm32l43x pin definitions --- .../arm/src/stm32l4/chip/stm32l4x3xx_pinmap.h | 36 ++++++++----------- 1 file changed, 14 insertions(+), 22 deletions(-) diff --git a/arch/arm/src/stm32l4/chip/stm32l4x3xx_pinmap.h b/arch/arm/src/stm32l4/chip/stm32l4x3xx_pinmap.h index 5820f2a009..39a5c84590 100644 --- a/arch/arm/src/stm32l4/chip/stm32l4x3xx_pinmap.h +++ b/arch/arm/src/stm32l4/chip/stm32l4x3xx_pinmap.h @@ -507,7 +507,8 @@ #define GPIO_USART2_TX_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN2) #define GPIO_USART2_TX_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN5) #define GPIO_USART2_RX_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN3) -#define GPIO_USART2_RX_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN6) +#define GPIO_USART2_RX_2 (GPIO_ALT|GPIO_AF3 |GPIO_PORTA|GPIO_PIN15) +#define GPIO_USART2_RX_3 (GPIO_ALT|GPIO_AF3 |GPIO_PORTD|GPIO_PIN6) #define GPIO_USART2_CK_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN4) #define GPIO_USART2_CK_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN7) #define GPIO_USART2_CTS_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN0) @@ -530,27 +531,18 @@ #define GPIO_USART3_CTS_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN6) #define GPIO_USART3_CTS_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTB|GPIO_PIN13) #define GPIO_USART3_CTS_3 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN11) -#define GPIO_USART3_RTS_DE_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTB|GPIO_PIN1) -#define GPIO_USART3_RTS_DE_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTB|GPIO_PIN14) -#define GPIO_USART3_RTS_DE_3 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN2) -#define GPIO_USART3_RTS_DE_4 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN12) - -#define GPIO_UART4_TX_1 (GPIO_ALT|GPIO_AF8 |GPIO_PORTA|GPIO_PIN0) -#define GPIO_UART4_TX_2 (GPIO_ALT|GPIO_AF8 |GPIO_PORTC|GPIO_PIN10) -#define GPIO_UART4_RX_1 (GPIO_ALT|GPIO_AF8 |GPIO_PORTA|GPIO_PIN1) -#define GPIO_UART4_RX_2 (GPIO_ALT|GPIO_AF8 |GPIO_PORTC|GPIO_PIN11) -#define GPIO_UART4_CTS (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN7) -#define GPIO_UART4_RTS_DE (GPIO_ALT|GPIO_AF8 |GPIO_PORTA|GPIO_PIN15) - -#define GPIO_UART5_TX (GPIO_ALT|GPIO_AF8 |GPIO_PORTC|GPIO_PIN12) -#define GPIO_UART5_RX (GPIO_ALT|GPIO_AF8 |GPIO_PORTD|GPIO_PIN2) -#define GPIO_UART5_CTS (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN5) -#define GPIO_UART5_RTS_DE (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN4) - -#define GPIO_LPUART1_TX_1 (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN11) -#define GPIO_LPUART1_TX_2 (GPIO_ALT|GPIO_AF8 |GPIO_PORTC|GPIO_PIN1) -#define GPIO_LPUART1_RX_1 (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN10) -#define GPIO_LPUART1_RX_2 (GPIO_ALT|GPIO_AF8 |GPIO_PORTC|GPIO_PIN0) +#define GPIO_USART3_RTS_DE_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN15) +#define GPIO_USART3_RTS_DE_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTB|GPIO_PIN1) +#define GPIO_USART3_RTS_DE_3 (GPIO_ALT|GPIO_AF7 |GPIO_PORTB|GPIO_PIN14) +#define GPIO_USART3_RTS_DE_4 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN2) +#define GPIO_USART3_RTS_DE_5 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN12) + +#define GPIO_LPUART1_TX_1 (GPIO_ALT|GPIO_AF8 |GPIO_PORTA|GPIO_PIN2) +#define GPIO_LPUART1_TX_2 (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN11) +#define GPIO_LPUART1_TX_3 (GPIO_ALT|GPIO_AF8 |GPIO_PORTC|GPIO_PIN0) +#define GPIO_LPUART1_RX_1 (GPIO_ALT|GPIO_AF8 |GPIO_PORTA|GPIO_PIN3) +#define GPIO_LPUART1_RX_2 (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN10) +#define GPIO_LPUART1_RX_3 (GPIO_ALT|GPIO_AF8 |GPIO_PORTC|GPIO_PIN1) #define GPIO_LPUART1_CTS_1 (GPIO_ALT|GPIO_AF8 |GPIO_PORTA|GPIO_PIN6) #define GPIO_LPUART1_CTS_2 (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN13) #define GPIO_LPUART1_RTS_DE_1 (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN1) -- GitLab From 565c9520774595e37354b1a9a7c7f6b5256374c8 Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Tue, 9 May 2017 11:00:42 +0200 Subject: [PATCH 766/990] Update defconfig, fix nucleo-32 uart pinout --- configs/nucleo-l432kc/include/board.h | 12 +- configs/nucleo-l432kc/nsh/defconfig | 161 +++++++++++++++++++------- 2 files changed, 119 insertions(+), 54 deletions(-) diff --git a/configs/nucleo-l432kc/include/board.h b/configs/nucleo-l432kc/include/board.h index 7109f47a1a..2d0c152e6f 100644 --- a/configs/nucleo-l432kc/include/board.h +++ b/configs/nucleo-l432kc/include/board.h @@ -90,21 +90,13 @@ # define GPIO_USART1_TX GPIO_USART1_TX_2 /* PB6 */ #endif -/* USART2: Connected to STLInk Debug via PA2, PA3 - * RXD: PA3 CN9 pin 1 (See SB13, 14, 62, 63). CN10 pin 37 - * PD6 - * TXD: PA2 CN9 pin 2 (See SB13, 14, 62, 63). CN10 pin 35 - * PD5 - */ +/* USART2: Connected to STLInk Debug via PA2(TX), PA15(RX) */ -#define GPIO_USART2_RX GPIO_USART2_RX_1 /* PA3 */ +#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PA15 */ #define GPIO_USART2_TX GPIO_USART2_TX_1 /* PA2 */ #define GPIO_USART2_RTS GPIO_USART2_RTS_2 #define GPIO_USART2_CTS GPIO_USART2_CTS_2 -#define GPIO_UART4_RX GPIO_UART4_RX_1 /* PA1 */ -#define GPIO_UART4_TX GPIO_UART4_TX_1 /* PA0 */ - /* I2C * * The optional _GPIO configurations allow the I2C driver to manually diff --git a/configs/nucleo-l432kc/nsh/defconfig b/configs/nucleo-l432kc/nsh/defconfig index f78446519f..1f261b0c1d 100644 --- a/configs/nucleo-l432kc/nsh/defconfig +++ b/configs/nucleo-l432kc/nsh/defconfig @@ -16,7 +16,7 @@ CONFIG_HOST_LINUX=y # # Build Configuration # -# CONFIG_APPS_DIR="../apps" +CONFIG_APPS_DIR="../apps" CONFIG_BUILD_FLAT=y # CONFIG_BUILD_2PASS is not set @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set CONFIG_ARCH_CHIP_STM32L4=y # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -129,7 +132,7 @@ CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y # CONFIG_ARMV7M_LAZYFPU is not set CONFIG_ARCH_HAVE_FPU=y -CONFIG_ARCH_HAVE_DPFPU=y +# CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_FPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set CONFIG_ARM_HAVE_MPU_UNIFIED=y @@ -140,10 +143,8 @@ CONFIG_ARM_HAVE_MPU_UNIFIED=y # # CONFIG_ARMV7M_HAVE_ICACHE is not set # CONFIG_ARMV7M_HAVE_DCACHE is not set -CONFIG_ARMV7M_HAVE_ITCM=y -CONFIG_ARMV7M_HAVE_DTCM=y -# CONFIG_ARMV7M_ITCM is not set -# CONFIG_ARMV7M_DTCM is not set +# CONFIG_ARMV7M_HAVE_ITCM is not set +# CONFIG_ARMV7M_HAVE_DTCM is not set # CONFIG_ARMV7M_TOOLCHAIN_IARL is not set # CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set # CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set @@ -160,16 +161,73 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # # STM32L4 Configuration Options # -CONFIG_ARCH_CHIP_STM32L476RG=y +# CONFIG_ARCH_CHIP_STM32L432KB is not set +CONFIG_ARCH_CHIP_STM32L432KC=y +# CONFIG_ARCH_CHIP_STM32L442KC is not set +# CONFIG_ARCH_CHIP_STM32L433CB is not set +# CONFIG_ARCH_CHIP_STM32L433CC is not set +# CONFIG_ARCH_CHIP_STM32L433RB is not set +# CONFIG_ARCH_CHIP_STM32L433RC is not set +# CONFIG_ARCH_CHIP_STM32L433VC is not set +# CONFIG_ARCH_CHIP_STM32L443CC is not set +# CONFIG_ARCH_CHIP_STM32L443RC is not set +# CONFIG_ARCH_CHIP_STM32L443VC is not set +# CONFIG_ARCH_CHIP_STM32L451CC is not set +# CONFIG_ARCH_CHIP_STM32L451CE is not set +# CONFIG_ARCH_CHIP_STM32L451RC is not set +# CONFIG_ARCH_CHIP_STM32L451RE is not set +# CONFIG_ARCH_CHIP_STM32L451VC is not set +# CONFIG_ARCH_CHIP_STM32L451VE is not set +# CONFIG_ARCH_CHIP_STM32L452CC is not set +# CONFIG_ARCH_CHIP_STM32L452CE is not set +# CONFIG_ARCH_CHIP_STM32L452RC is not set +# CONFIG_ARCH_CHIP_STM32L452RE is not set +# CONFIG_ARCH_CHIP_STM32L452VC is not set +# CONFIG_ARCH_CHIP_STM32L452VE is not set +# CONFIG_ARCH_CHIP_STM32L462CE is not set +# CONFIG_ARCH_CHIP_STM32L462RE is not set +# CONFIG_ARCH_CHIP_STM32L462VE is not set +# CONFIG_ARCH_CHIP_STM32L476RG is not set # CONFIG_ARCH_CHIP_STM32L476RE is not set # CONFIG_ARCH_CHIP_STM32L486 is not set -# CONFIG_STM32L4_STM32L4X3 is not set -CONFIG_STM32L4_STM32L4X6=y -CONFIG_STM32L4_STM32L476XX=y +# CONFIG_ARCH_CHIP_STM32L496ZE is not set +# CONFIG_ARCH_CHIP_STM32L496ZG is not set +# CONFIG_ARCH_CHIP_STM32L4A6 is not set +# CONFIG_STM32L4_STM32L4X1 is not set +CONFIG_STM32L4_STM32L4X2=y +CONFIG_STM32L4_STM32L4X3=y +# CONFIG_STM32L4_STM32L4X5 is not set +# CONFIG_STM32L4_STM32L4X6 is not set +# CONFIG_STM32L4_STM32L431XX is not set +CONFIG_STM32L4_STM32L432XX=y +# CONFIG_STM32L4_STM32L433XX is not set +# CONFIG_STM32L4_STM32L442XX is not set +# CONFIG_STM32L4_STM32L443XX is not set +# CONFIG_STM32L4_STM32L451XX is not set +# CONFIG_STM32L4_STM32L452XX is not set +# CONFIG_STM32L4_STM32L462XX is not set +# CONFIG_STM32L4_STM32L471XX is not set +# CONFIG_STM32L4_STM32L476XX is not set # CONFIG_STM32L4_STM32L486XX is not set -# CONFIG_STM32L4_FLASH_256KB is not set -# CONFIG_STM32L4_FLASH_512KB is not set -CONFIG_STM32L4_FLASH_1024KB=y +# CONFIG_STM32L4_STM32L496XX is not set +# CONFIG_STM32L4_STM32L4A6XX is not set +CONFIG_STM32L4_FLASH_OVERRIDE_DEFAULT=y +# CONFIG_STM32L4_FLASH_OVERRIDE_B is not set +# CONFIG_STM32L4_FLASH_OVERRIDE_C is not set +# CONFIG_STM32L4_FLASH_OVERRIDE_E is not set +# CONFIG_STM32L4_FLASH_OVERRIDE_G is not set +# CONFIG_STM32L4_FLASH_CONFIG_B is not set +CONFIG_STM32L4_FLASH_CONFIG_C=y +# CONFIG_STM32L4_FLASH_CONFIG_E is not set +CONFIG_STM32L4_IO_CONFIG_K=y +# CONFIG_STM32L4_IO_CONFIG_C is not set +# CONFIG_STM32L4_IO_CONFIG_R is not set +# CONFIG_STM32L4_IO_CONFIG_J is not set +# CONFIG_STM32L4_IO_CONFIG_M is not set +# CONFIG_STM32L4_IO_CONFIG_V is not set +# CONFIG_STM32L4_IO_CONFIG_Q is not set +# CONFIG_STM32L4_IO_CONFIG_Z is not set +# CONFIG_STM32L4_IO_CONFIG_A is not set # # STM32L4 SRAM2 Options @@ -184,12 +242,32 @@ CONFIG_STM32L4_SRAM2_INIT=y # # STM32L4 Peripheral Support # +# CONFIG_STM32L4_HAVE_ADC2 is not set +# CONFIG_STM32L4_HAVE_ADC3 is not set +# CONFIG_STM32L4_HAVE_AES is not set +# CONFIG_STM32L4_HAVE_CAN2 is not set +CONFIG_STM32L4_HAVE_COMP=y +# CONFIG_STM32L4_HAVE_DAC2 is not set +# CONFIG_STM32L4_HAVE_DCMI is not set +# CONFIG_STM32L4_HAVE_DFSDM1 is not set +# CONFIG_STM32L4_HAVE_DMA2D is not set +# CONFIG_STM32L4_HAVE_FSMC is not set +# CONFIG_STM32L4_HAVE_HASH is not set +# CONFIG_STM32L4_HAVE_I2C4 is not set +# CONFIG_STM32L4_HAVE_LCD is not set # CONFIG_STM32L4_HAVE_LTDC is not set CONFIG_STM32L4_HAVE_LPTIM1=y CONFIG_STM32L4_HAVE_LPTIM2=y -CONFIG_STM32L4_HAVE_COMP=y +# CONFIG_STM32L4_HAVE_OTGFS is not set CONFIG_STM32L4_HAVE_SAI1=y -CONFIG_STM32L4_HAVE_SAI2=y +# CONFIG_STM32L4_HAVE_SAI2 is not set +# CONFIG_STM32L4_HAVE_SDMMC1 is not set +# CONFIG_STM32L4_HAVE_TIM3 is not set +# CONFIG_STM32L4_HAVE_TIM4 is not set +# CONFIG_STM32L4_HAVE_TIM5 is not set +CONFIG_STM32L4_HAVE_TIM7=y +# CONFIG_STM32L4_HAVE_TIM8 is not set +# CONFIG_STM32L4_HAVE_TIM17 is not set # CONFIG_STM32L4_ADC is not set # CONFIG_STM32L4_CAN is not set # CONFIG_STM32L4_DAC is not set @@ -211,21 +289,12 @@ CONFIG_STM32L4_DMA2=y # # AHB2 Peripherals # -# CONFIG_STM32L4_OTGFS is not set # CONFIG_STM32L4_ADC1 is not set -# CONFIG_STM32L4_ADC2 is not set -# CONFIG_STM32L4_ADC3 is not set -# CONFIG_STM32L4_AES is not set CONFIG_STM32L4_RNG=y -# CONFIG_STM32L4_SAI1_A is not set -# CONFIG_STM32L4_SAI1_B is not set -# CONFIG_STM32L4_SAI2_A is not set -# CONFIG_STM32L4_SAI2_B is not set # # AHB3 Peripherals # -# CONFIG_STM32L4_FMC is not set # CONFIG_STM32L4_QSPI is not set # @@ -233,25 +302,18 @@ CONFIG_STM32L4_RNG=y # CONFIG_STM32L4_PWR=y # CONFIG_STM32L4_TIM2 is not set -# CONFIG_STM32L4_TIM3 is not set -# CONFIG_STM32L4_TIM4 is not set -# CONFIG_STM32L4_TIM5 is not set # CONFIG_STM32L4_TIM6 is not set # CONFIG_STM32L4_TIM7 is not set -# CONFIG_STM32L4_LCD is not set # CONFIG_STM32L4_SPI2 is not set # CONFIG_STM32L4_SPI3 is not set # CONFIG_STM32L4_USART1 is not set CONFIG_STM32L4_USART2=y # CONFIG_STM32L4_USART3 is not set -# CONFIG_STM32L4_UART4 is not set -# CONFIG_STM32L4_UART5 is not set # CONFIG_STM32L4_I2C1 is not set # CONFIG_STM32L4_I2C2 is not set # CONFIG_STM32L4_I2C3 is not set # CONFIG_STM32L4_CAN1 is not set # CONFIG_STM32L4_DAC1 is not set -# CONFIG_STM32L4_DAC2 is not set # CONFIG_STM32L4_OPAMP is not set # CONFIG_STM32L4_LPTIM1 is not set # CONFIG_STM32L4_LPUART1 is not set @@ -263,17 +325,12 @@ CONFIG_STM32L4_USART2=y # CONFIG_STM32L4_SYSCFG=y CONFIG_STM32L4_FIREWALL=y -# CONFIG_STM32L4_SDMMC1 is not set # CONFIG_STM32L4_TIM1 is not set # CONFIG_STM32L4_SPI1 is not set -# CONFIG_STM32L4_TIM8 is not set # CONFIG_STM32L4_TIM15 is not set # CONFIG_STM32L4_TIM16 is not set -# CONFIG_STM32L4_TIM17 is not set # CONFIG_STM32L4_COMP is not set # CONFIG_STM32L4_SAI1 is not set -# CONFIG_STM32L4_SAI2 is not set -# CONFIG_STM32L4_DFSDM is not set # # Other Peripherals @@ -288,7 +345,6 @@ CONFIG_STM32L4_RTC_LSECLOCK=y # CONFIG_STM32L4_RTC_LSICLOCK is not set # CONFIG_STM32L4_RTC_HSECLOCK is not set CONFIG_STM32L4_SAI1PLL=y -# CONFIG_STM32L4_SAI2PLL is not set # # Timer Configuration @@ -298,8 +354,8 @@ CONFIG_STM32L4_SAI1PLL=y CONFIG_STM32L4_HAVE_USART1=y CONFIG_STM32L4_HAVE_USART2=y CONFIG_STM32L4_HAVE_USART3=y -CONFIG_STM32L4_HAVE_UART4=y -CONFIG_STM32L4_HAVE_UART5=y +# CONFIG_STM32L4_HAVE_UART4 is not set +# CONFIG_STM32L4_HAVE_UART5 is not set # # U[S]ART Configuration @@ -326,6 +382,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -369,11 +426,12 @@ CONFIG_RAM_SIZE=98304 # # Board Selection # -CONFIG_ARCH_BOARD_NUCLEO_L476RG=y +CONFIG_ARCH_BOARD_NUCLEO_L432KC=y +# CONFIG_ARCH_BOARD_NUCLEO_L476RG is not set # CONFIG_ARCH_BOARD_STM32L476VG_DISCO is not set # CONFIG_ARCH_BOARD_STM32L476_MDK is not set # CONFIG_ARCH_BOARD_CUSTOM is not set -CONFIG_ARCH_BOARD="nucleo-l476rg" +CONFIG_ARCH_BOARD="nucleo-l432kc" # # Common Board Options @@ -443,6 +501,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -518,6 +578,11 @@ CONFIG_DEV_RANDOM=y # # Buffering # + +# +# Common I/O Buffer Support +# +# CONFIG_DRIVERS_IOB is not set # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -640,6 +705,7 @@ CONFIG_USART2_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -716,6 +782,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -863,6 +930,7 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # # CAN Utilities # +# CONFIG_CANUTILS_CANDUMP is not set # # Examples @@ -891,14 +959,13 @@ CONFIG_EXAMPLES_ALARM_SIGNO=1 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set -# CONFIG_EXAMPLES_NX is not set # CONFIG_EXAMPLES_NXFFS is not set # CONFIG_EXAMPLES_NXHELLO is not set # CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NX is not set # CONFIG_EXAMPLES_NXLINES is not set # CONFIG_EXAMPLES_NXTERM is not set # CONFIG_EXAMPLES_NXTEXT is not set @@ -933,6 +1000,7 @@ CONFIG_EXAMPLES_NSAMPLES=8 # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -954,6 +1022,7 @@ CONFIG_EXAMPLES_NSAMPLES=8 # Interpreters # # CONFIG_INTERPRETERS_FICL is not set +# CONFIG_INTERPRETERS_LUA is not set # CONFIG_INTERPRETERS_MICROPYTHON is not set # CONFIG_INTERPRETERS_MINIBASIC is not set # CONFIG_INTERPRETERS_PCODE is not set @@ -1100,3 +1169,7 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# -- GitLab From 8c0a70e25ca8b32a11682bd2b83890b350867b52 Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Tue, 9 May 2017 11:09:02 +0200 Subject: [PATCH 767/990] Typo --- configs/nucleo-l432kc/README.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/configs/nucleo-l432kc/README.txt b/configs/nucleo-l432kc/README.txt index dbe575f5c7..33ebc530cd 100644 --- a/configs/nucleo-l432kc/README.txt +++ b/configs/nucleo-l432kc/README.txt @@ -2,7 +2,7 @@ README ====== This README discusses issues unique to NuttX configurations for the ST -Nucleoi-l432kc board from ST Micro. See +Nucleo-l432kc board from ST Micro. See http://www.st.com/nucleo-l432kc -- GitLab From ce4c18afe41a0b30769f88d0754a63b7983e2e1a Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Tue, 9 May 2017 11:15:08 +0200 Subject: [PATCH 768/990] More unbuilt stm32 -> stm32l4 changes --- configs/nucleo-l432kc/src/stm32_userleds.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/configs/nucleo-l432kc/src/stm32_userleds.c b/configs/nucleo-l432kc/src/stm32_userleds.c index e6fa28f986..0ff3ce66c8 100644 --- a/configs/nucleo-l432kc/src/stm32_userleds.c +++ b/configs/nucleo-l432kc/src/stm32_userleds.c @@ -172,7 +172,7 @@ void board_userled_initialize(void) { /* Configure LD2 GPIO for output */ - stm32_configgpio(GPIO_LD2); + stm32l4_configgpio(GPIO_LD2); } /**************************************************************************** @@ -183,7 +183,7 @@ void board_userled(int led, bool ledon) { if (led == 1) { - stm32_gpiowrite(GPIO_LD2, ledon); + stm32l4_gpiowrite(GPIO_LD2, ledon); } } @@ -195,7 +195,7 @@ void board_userled_all(uint8_t ledset) { if (led == 1) { - stm32_gpiowrite(GPIO_LD2, (ledset & BOARD_LD2_BIT) != 0); + stm32l4_gpiowrite(GPIO_LD2, (ledset & BOARD_LD2_BIT) != 0); } } -- GitLab From 5204f19e4f96581a30f233121395fa6ffb50686c Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Tue, 9 May 2017 11:32:16 +0200 Subject: [PATCH 769/990] fix typo found by Juha during review --- arch/arm/src/stm32l4/chip/stm32l4x3xx_pinmap.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/arch/arm/src/stm32l4/chip/stm32l4x3xx_pinmap.h b/arch/arm/src/stm32l4/chip/stm32l4x3xx_pinmap.h index 39a5c84590..c0f9e5c57e 100644 --- a/arch/arm/src/stm32l4/chip/stm32l4x3xx_pinmap.h +++ b/arch/arm/src/stm32l4/chip/stm32l4x3xx_pinmap.h @@ -508,7 +508,7 @@ #define GPIO_USART2_TX_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN5) #define GPIO_USART2_RX_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN3) #define GPIO_USART2_RX_2 (GPIO_ALT|GPIO_AF3 |GPIO_PORTA|GPIO_PIN15) -#define GPIO_USART2_RX_3 (GPIO_ALT|GPIO_AF3 |GPIO_PORTD|GPIO_PIN6) +#define GPIO_USART2_RX_3 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN6) #define GPIO_USART2_CK_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN4) #define GPIO_USART2_CK_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN7) #define GPIO_USART2_CTS_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN0) -- GitLab From d591d3ac4e681dbe0147aadcdc8dc32e7262b517 Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Tue, 9 May 2017 11:38:14 +0200 Subject: [PATCH 770/990] Restore settings for UARTs 4 and 5 --- arch/arm/src/stm32l4/chip/stm32l4x3xx_pinmap.h | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/arch/arm/src/stm32l4/chip/stm32l4x3xx_pinmap.h b/arch/arm/src/stm32l4/chip/stm32l4x3xx_pinmap.h index c0f9e5c57e..bf92bcf54b 100644 --- a/arch/arm/src/stm32l4/chip/stm32l4x3xx_pinmap.h +++ b/arch/arm/src/stm32l4/chip/stm32l4x3xx_pinmap.h @@ -537,6 +537,18 @@ #define GPIO_USART3_RTS_DE_4 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN2) #define GPIO_USART3_RTS_DE_5 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN12) +#define GPIO_UART4_TX_1 (GPIO_ALT|GPIO_AF8 |GPIO_PORTA|GPIO_PIN0) +#define GPIO_UART4_TX_2 (GPIO_ALT|GPIO_AF8 |GPIO_PORTC|GPIO_PIN10) +#define GPIO_UART4_RX_1 (GPIO_ALT|GPIO_AF8 |GPIO_PORTA|GPIO_PIN1) +#define GPIO_UART4_RX_2 (GPIO_ALT|GPIO_AF8 |GPIO_PORTC|GPIO_PIN11) +#define GPIO_UART4_CTS (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN7) +#define GPIO_UART4_RTS_DE (GPIO_ALT|GPIO_AF8 |GPIO_PORTA|GPIO_PIN15) + +#define GPIO_UART5_TX (GPIO_ALT|GPIO_AF8 |GPIO_PORTC|GPIO_PIN12) +#define GPIO_UART5_RX (GPIO_ALT|GPIO_AF8 |GPIO_PORTD|GPIO_PIN2) +#define GPIO_UART5_CTS (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN5) +#define GPIO_UART5_RTS_DE (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN4) + #define GPIO_LPUART1_TX_1 (GPIO_ALT|GPIO_AF8 |GPIO_PORTA|GPIO_PIN2) #define GPIO_LPUART1_TX_2 (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN11) #define GPIO_LPUART1_TX_3 (GPIO_ALT|GPIO_AF8 |GPIO_PORTC|GPIO_PIN0) -- GitLab From ce1ad33289a6cc6ac048dd48bf1464be1f1e0b72 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Tue, 9 May 2017 14:13:51 +0300 Subject: [PATCH 771/990] STM32L4: add dbgmcu header files --- .../arm/src/stm32l4/chip/stm32l4x3xx_dbgmcu.h | 108 ++++++++++++++++ .../arm/src/stm32l4/chip/stm32l4x6xx_dbgmcu.h | 119 ++++++++++++++++++ arch/arm/src/stm32l4/stm32l4_dbgmcu.h | 56 +++++++++ 3 files changed, 283 insertions(+) create mode 100644 arch/arm/src/stm32l4/chip/stm32l4x3xx_dbgmcu.h create mode 100644 arch/arm/src/stm32l4/chip/stm32l4x6xx_dbgmcu.h diff --git a/arch/arm/src/stm32l4/chip/stm32l4x3xx_dbgmcu.h b/arch/arm/src/stm32l4/chip/stm32l4x3xx_dbgmcu.h new file mode 100644 index 0000000000..aaf9c780da --- /dev/null +++ b/arch/arm/src/stm32l4/chip/stm32l4x3xx_dbgmcu.h @@ -0,0 +1,108 @@ +/**************************************************************************** + * arch/arm/src/stm32l4/chip/stm32l4x3xx_dbgmcu.h + * + * Copyright (C) 2016 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * David Sidrane + * 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 __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X6XX_DBGMCU_H +#define __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X6XX_DBGMCU_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include "chip.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Register Addresses *******************************************************/ + +#define STM32_DBGMCU_IDCODE 0xe0042000 /* MCU identifier */ +#define STM32_DBGMCU_CR 0xe0042004 /* MCU debug */ +#define STM32_DBGMCU_APB1_FZ 0xe0042008 /* Debug MCU APB1 freeze register */ +#define STM32_DBGMCU_APB1_FZ2 0xe004200c /* Debug MCU APB1 freeze register 2 */ +#define STM32_DBGMCU_APB2_FZ 0xe0042010 /* Debug MCU APB2 freeze register */ + +/* Register Bitfield Definitions ********************************************/ + +/* MCU identifier */ + +#define DBGMCU_IDCODE_DEVID_SHIFT (0) /* Bits 11-0: Device Identifier */ +#define DBGMCU_IDCODE_DEVID_MASK (0x0fff << DBGMCU_IDCODE_DEVID_SHIFT) +#define DBGMCU_IDCODE_REVID_SHIFT (16) /* Bits 31-16: Revision Identifier */ +#define DBGMCU_IDCODE_REVID_MASK (0xffff << DBGMCU_IDCODE_REVID_SHIFT) + +/* MCU debug */ + +#define DBGMCU_CR_SLEEP (1 << 0) /* Bit 0: Debug Sleep Mode */ +#define DBGMCU_CR_STOP (1 << 1) /* Bit 1: Debug Stop Mode */ +#define DBGMCU_CR_STANDBY (1 << 2) /* Bit 2: Debug Standby mode */ +#define DBGMCU_CR_TRACEIOEN (1 << 5) /* Bit 5: Trace enabled */ + +#define DBGMCU_CR_TRACEMODE_SHIFT (6) /* Bits 7-6: Trace mode pin assignment */ +#define DBGMCU_CR_TRACEMODE_MASK (3 << DBGMCU_CR_TRACEMODE_SHIFT) +#define DBGMCU_CR_ASYNCH (0 << DBGMCU_CR_TRACEMODE_SHIFT) /* Asynchronous Mode */ +#define DBGMCU_CR_SYNCH1 (1 << DBGMCU_CR_TRACEMODE_SHIFT) /* Synchronous Mode, TRACEDATA size=1 */ +#define DBGMCU_CR_SYNCH2 (2 << DBGMCU_CR_TRACEMODE_SHIFT) /* Synchronous Mode, TRACEDATA size=2 */ +#define DBGMCU_CR_SYNCH4 (3 << DBGMCU_CR_TRACEMODE_SHIFT) /* Synchronous Mode, TRACEDATA size=4 */ + +/* Debug MCU APB1 freeze register */ + +#define DBGMCU_APB1_TIM2STOP (1 << 0) /* Bit 0: TIM2 stopped when core is halted */ +#define DBGMCU_APB1_TIM6STOP (1 << 4) /* Bit 4: TIM6 stopped when core is halted */ +#define DBGMCU_APB1_TIM7STOP (1 << 5) /* Bit 5: TIM7 stopped when core is halted */ +#define DBGMCU_APB1_RTCSTOP (1 << 10) /* Bit 10: RTC stopped when Core is halted */ +#define DBGMCU_APB1_WWDGSTOP (1 << 11) /* Bit 11: Window Watchdog stopped when core is halted */ +#define DBGMCU_APB1_IWDGSTOP (1 << 12) /* Bit 12: Independent Watchdog stopped when core is halted */ +#define DBGMCU_APB1_I2C1STOP (1 << 21) /* Bit 21: I2C1 SMBUS timeout mode stopped when Core is halted */ +#define DBGMCU_APB1_I2C2STOP (1 << 22) /* Bit 22: I2C2 SMBUS timeout mode stopped when Core is halted */ +#define DBGMCU_APB1_I2C3STOP (1 << 23) /* Bit 23: I2C3 SMBUS timeout mode stopped when Core is halted */ +#define DBGMCU_APB1_CAN1STOP (1 << 25) /* Bit 25: CAN1 stopped when core is halted */ +#define DBGMCU_APB1_LPTIM1STOP (1 << 31) /* Bit 31: LPTIM1 stopper when core is halted */ + +/* Debug MCU APB1 freeze register 2 */ + +#define DBGMCU_APB1_FZ2_LPTIM2STOP (1 << 5) /* Bit 5: LPTIM2 stopper when core is halted */ + +/* Debug MCU APB2 freeze register */ + +#define DBGMCU_APB2_TIM1STOP (1 << 11) /* Bit 11: TIM1 stopped when core is halted */ +#define DBGMCU_APB2_TIM15STOP (1 << 16) /* Bit 16: TIM15 stopped when core is halted */ +#define DBGMCU_APB2_TIM16STOP (1 << 17) /* Bit 17: TIM16 stopped when core is halted */ + +#endif /* __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X3XXDBGMCU_H */ diff --git a/arch/arm/src/stm32l4/chip/stm32l4x6xx_dbgmcu.h b/arch/arm/src/stm32l4/chip/stm32l4x6xx_dbgmcu.h new file mode 100644 index 0000000000..09438cda7b --- /dev/null +++ b/arch/arm/src/stm32l4/chip/stm32l4x6xx_dbgmcu.h @@ -0,0 +1,119 @@ +/**************************************************************************** + * arch/arm/src/stm32l4/chip/stm32l4x6xx_dbgmcu.h + * + * Copyright (C) 2016 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * David Sidrane + * 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 __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X6XX_DBGMCU_H +#define __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X6XX_DBGMCU_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include "chip.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Register Addresses *******************************************************/ + +#define STM32_DBGMCU_IDCODE 0xe0042000 /* MCU identifier */ +#define STM32_DBGMCU_CR 0xe0042004 /* MCU debug */ +#define STM32_DBGMCU_APB1_FZ 0xe0042008 /* Debug MCU APB1 freeze register */ +#define STM32_DBGMCU_APB1_FZ2 0xe004200c /* Debug MCU APB1 freeze register 2 */ +#define STM32_DBGMCU_APB2_FZ 0xe0042010 /* Debug MCU APB2 freeze register */ + +/* Register Bitfield Definitions ********************************************/ + +/* MCU identifier */ + +#define DBGMCU_IDCODE_DEVID_SHIFT (0) /* Bits 11-0: Device Identifier */ +#define DBGMCU_IDCODE_DEVID_MASK (0x0fff << DBGMCU_IDCODE_DEVID_SHIFT) +#define DBGMCU_IDCODE_REVID_SHIFT (16) /* Bits 31-16: Revision Identifier */ +#define DBGMCU_IDCODE_REVID_MASK (0xffff << DBGMCU_IDCODE_REVID_SHIFT) + +/* MCU debug */ + +#define DBGMCU_CR_SLEEP (1 << 0) /* Bit 0: Debug Sleep Mode */ +#define DBGMCU_CR_STOP (1 << 1) /* Bit 1: Debug Stop Mode */ +#define DBGMCU_CR_STANDBY (1 << 2) /* Bit 2: Debug Standby mode */ +#define DBGMCU_CR_TRACEIOEN (1 << 5) /* Bit 5: Trace enabled */ + +#define DBGMCU_CR_TRACEMODE_SHIFT (6) /* Bits 7-6: Trace mode pin assignment */ +#define DBGMCU_CR_TRACEMODE_MASK (3 << DBGMCU_CR_TRACEMODE_SHIFT) +#define DBGMCU_CR_ASYNCH (0 << DBGMCU_CR_TRACEMODE_SHIFT) /* Asynchronous Mode */ +#define DBGMCU_CR_SYNCH1 (1 << DBGMCU_CR_TRACEMODE_SHIFT) /* Synchronous Mode, TRACEDATA size=1 */ +#define DBGMCU_CR_SYNCH2 (2 << DBGMCU_CR_TRACEMODE_SHIFT) /* Synchronous Mode, TRACEDATA size=2 */ +#define DBGMCU_CR_SYNCH4 (3 << DBGMCU_CR_TRACEMODE_SHIFT) /* Synchronous Mode, TRACEDATA size=4 */ + +/* Debug MCU APB1 freeze register */ + +#define DBGMCU_APB1_TIM2STOP (1 << 0) /* Bit 0: TIM2 stopped when core is halted */ +#define DBGMCU_APB1_TIM3STOP (1 << 1) /* Bit 1: TIM3 stopped when core is halted */ +#define DBGMCU_APB1_TIM4STOP (1 << 2) /* Bit 2: TIM4 stopped when core is halted */ +#define DBGMCU_APB1_TIM5STOP (1 << 3) /* Bit 3: TIM5 stopped when core is halted */ +#define DBGMCU_APB1_TIM6STOP (1 << 4) /* Bit 4: TIM6 stopped when core is halted */ +#define DBGMCU_APB1_TIM7STOP (1 << 5) /* Bit 5: TIM7 stopped when core is halted */ +#define DBGMCU_APB1_RTCSTOP (1 << 10) /* Bit 10: RTC stopped when Core is halted */ +#define DBGMCU_APB1_WWDGSTOP (1 << 11) /* Bit 11: Window Watchdog stopped when core is halted */ +#define DBGMCU_APB1_IWDGSTOP (1 << 12) /* Bit 12: Independent Watchdog stopped when core is halted */ +#define DBGMCU_APB1_I2C1STOP (1 << 21) /* Bit 21: I2C1 SMBUS timeout mode stopped when Core is halted */ +#define DBGMCU_APB1_I2C2STOP (1 << 22) /* Bit 22: I2C2 SMBUS timeout mode stopped when Core is halted */ +#define DBGMCU_APB1_I2C3STOP (1 << 23) /* Bit 23: I2C3 SMBUS timeout mode stopped when Core is halted */ +#define DBGMCU_APB1_CAN1STOP (1 << 25) /* Bit 25: CAN1 stopped when core is halted */ +#if defined(CONFIG_STM32L4_STM32L496XX) +# define DBGMCU_APB1_CAN2STOP (1 << 26) /* Bit 26: CAN2 stopped when core is halted */ +#endif +#define DBGMCU_APB1_LPTIM1STOP (1 << 31) /* Bit 31: LPTIM1 stopper when core is halted */ + +/* Debug MCU APB1 freeze register 2 */ + +#if defined(CONFIG_STM32L4_STM32L496XX) +# define DBGMCU_APB1_FZ2_I2C4STOP (1 << 1) /* Bit 1: I2C4 SMBUS timeout mode stopped when Core is halted */ +#endif +#define DBGMCU_APB1_FZ2_LPTIM2STOP (1 << 5) /* Bit 5: LPTIM2 stopper when core is halted */ + +/* Debug MCU APB2 freeze register */ + +#define DBGMCU_APB2_TIM1STOP (1 << 11) /* Bit 11: TIM1 stopped when core is halted */ +#define DBGMCU_APB2_TIM8STOP (1 << 13) /* Bit 13: TIM8 stopped when core is halted */ +#define DBGMCU_APB2_TIM15STOP (1 << 16) /* Bit 16: TIM15 stopped when core is halted */ +#define DBGMCU_APB2_TIM16STOP (1 << 17) /* Bit 17: TIM16 stopped when core is halted */ +#define DBGMCU_APB2_TIM17STOP (1 << 18) /* Bit 18: TIM17 stopped when core is halted */ + +#endif /* __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X6XXDBGMCU_H */ diff --git a/arch/arm/src/stm32l4/stm32l4_dbgmcu.h b/arch/arm/src/stm32l4/stm32l4_dbgmcu.h index e69de29bb2..ee753c0c0e 100644 --- a/arch/arm/src/stm32l4/stm32l4_dbgmcu.h +++ b/arch/arm/src/stm32l4/stm32l4_dbgmcu.h @@ -0,0 +1,56 @@ +/**************************************************************************** + * arch/arm/src/stm32l4/stm32l4_dbgmcu.h + * + * Copyright (C) 2016 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * 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 __ARCH_ARM_SRC_STM32L4_STM32L4_DBGMCU_H +#define __ARCH_ARM_SRC_STM32L4_STM32L4_DBGMCU_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include "chip.h" + +#if defined(CONFIG_STM32L4_STM32L4X6) +# include "chip/stm32l4x6xx_dbgmcu.h" +#elif defined(CONFIG_STM32L4_STM32L4X3) +# include "chip/stm32l4x3xx_dbgmcu.h" +#else +# error "Unsupported STM32L4 chip" +#endif + +#endif /* __ARCH_ARM_SRC_STM32L4_STM32L4_DBGMCU_H */ -- GitLab From 2043e1a114f09f211d39d49f42d5aab6e586cf1a Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 9 May 2017 07:34:59 -0600 Subject: [PATCH 772/990] IOBs: Move from driver/iob to a better location in mm/iob --- arch/arm/src/common/up_initialize.c | 4 ++-- arch/avr/src/common/up_initialize.c | 4 ++-- arch/hc/src/common/up_initialize.c | 4 ++-- arch/mips/src/common/up_initialize.c | 4 ++-- arch/misoc/src/lm32/lm32_initialize.c | 4 ++-- arch/renesas/src/common/up_initialize.c | 4 ++-- arch/risc-v/src/common/up_initialize.c | 4 ++-- arch/sim/src/up_initialize.c | 4 ++-- arch/x86/src/common/up_initialize.c | 4 ++-- arch/xtensa/src/common/xtensa_initialize.c | 4 ++-- arch/z16/src/common/up_initialize.c | 4 ++-- arch/z80/src/common/up_initialize.c | 4 ++-- configs/bambino-200e/netnsh/defconfig | 2 +- configs/c5471evm/httpd/defconfig | 2 +- configs/c5471evm/nettest/defconfig | 2 +- configs/c5471evm/nsh/defconfig | 2 +- configs/clicker2-stm32/knsh/defconfig | 2 +- configs/cloudctrl/nsh/defconfig | 2 +- configs/dk-tm4c129x/ipv6/defconfig | 2 +- configs/dk-tm4c129x/nsh/defconfig | 2 +- configs/eagle100/httpd/defconfig | 2 +- configs/eagle100/nettest/defconfig | 2 +- configs/eagle100/nsh/defconfig | 2 +- configs/eagle100/thttpd/defconfig | 2 +- configs/ekk-lm3s9b96/nsh/defconfig | 2 +- configs/ez80f910200zco/dhcpd/defconfig | 2 +- configs/ez80f910200zco/httpd/defconfig | 2 +- configs/ez80f910200zco/nettest/defconfig | 2 +- configs/ez80f910200zco/nsh/defconfig | 2 +- configs/ez80f910200zco/poll/defconfig | 2 +- configs/fire-stm32v2/nsh/defconfig | 2 +- configs/freedom-k64f/netnsh/defconfig | 2 +- configs/freedom-k66f/netnsh/defconfig | 2 +- configs/lincoln60/netnsh/defconfig | 2 +- configs/lincoln60/thttpd-binfs/defconfig | 2 +- configs/lm3s6432-s2e/nsh/defconfig | 2 +- configs/lm3s6965-ek/discover/defconfig | 2 +- configs/lm3s6965-ek/nsh/defconfig | 2 +- configs/lm3s6965-ek/tcpecho/defconfig | 2 +- configs/lm3s8962-ek/nsh/defconfig | 2 +- configs/lpcxpresso-lpc1768/dhcpd/defconfig | 2 +- configs/lpcxpresso-lpc1768/nsh/defconfig | 2 +- configs/lpcxpresso-lpc1768/thttpd/defconfig | 2 +- configs/misoc/hello/defconfig | 2 +- configs/moxa/nsh/defconfig | 2 +- configs/ntosd-dm320/nettest/defconfig | 2 +- configs/ntosd-dm320/nsh/defconfig | 2 +- configs/ntosd-dm320/poll/defconfig | 2 +- configs/ntosd-dm320/thttpd/defconfig | 2 +- configs/ntosd-dm320/udp/defconfig | 2 +- configs/ntosd-dm320/webserver/defconfig | 2 +- configs/nucleo-f091rc/nsh/defconfig | 2 +- configs/nucleo-l452re/nsh/defconfig | 2 +- configs/nucleo-l496zg/nsh/defconfig | 2 +- configs/olimex-lpc1766stk/ftpc/defconfig | 2 +- configs/olimex-lpc1766stk/hidmouse/defconfig | 2 +- configs/olimex-lpc1766stk/nettest/defconfig | 2 +- configs/olimex-lpc1766stk/nsh/defconfig | 2 +- configs/olimex-lpc1766stk/slip-httpd/defconfig | 2 +- configs/olimex-lpc1766stk/thttpd-binfs/defconfig | 2 +- configs/olimex-lpc1766stk/thttpd-nxflat/defconfig | 2 +- configs/olimex-lpc1766stk/zmodem/defconfig | 2 +- configs/olimex-stm32-e407/discover/defconfig | 2 +- configs/olimex-stm32-e407/netnsh/defconfig | 2 +- configs/olimex-stm32-e407/telnetd/defconfig | 2 +- configs/olimex-stm32-e407/webserver/defconfig | 2 +- configs/olimex-stm32-p107/nsh/defconfig | 2 +- configs/olimex-stm32-p207/nsh/defconfig | 2 +- configs/olimex-strp711/nettest/defconfig | 2 +- configs/photon/wlan/defconfig | 10 +++++++++- configs/pic32mx-starterkit/nsh2/defconfig | 2 +- configs/pic32mx7mmb/nsh/defconfig | 2 +- configs/sam4e-ek/nsh/defconfig | 2 +- configs/sam4e-ek/nxwm/defconfig | 2 +- configs/sam4e-ek/usbnsh/defconfig | 2 +- configs/sama5d3-xplained/bridge/defconfig | 2 +- configs/sama5d4-ek/bridge/defconfig | 2 +- configs/sama5d4-ek/ipv6/defconfig | 2 +- configs/sama5d4-ek/nsh/defconfig | 2 +- configs/sama5d4-ek/nxwm/defconfig | 2 +- configs/same70-xplained/netnsh/defconfig | 2 +- configs/samv71-xult/netnsh/defconfig | 2 +- configs/samv71-xult/vnc/defconfig | 2 +- configs/samv71-xult/vnxwm/defconfig | 2 +- configs/shenzhou/nsh/defconfig | 2 +- configs/shenzhou/nxwm/defconfig | 2 +- configs/shenzhou/thttpd/defconfig | 2 +- configs/sim/nettest/defconfig | 2 +- configs/sim/sixlowpan/defconfig | 2 +- configs/sim/udgram/defconfig | 2 +- configs/sim/ustream/defconfig | 2 +- configs/stm3220g-eval/dhcpd/defconfig | 2 +- configs/stm3220g-eval/nettest/defconfig | 2 +- configs/stm3220g-eval/nsh/defconfig | 2 +- configs/stm3220g-eval/nsh2/defconfig | 2 +- configs/stm3220g-eval/nxwm/defconfig | 2 +- configs/stm3220g-eval/telnetd/defconfig | 2 +- configs/stm3240g-eval/dhcpd/defconfig | 2 +- configs/stm3240g-eval/discover/defconfig | 2 +- configs/stm3240g-eval/nettest/defconfig | 2 +- configs/stm3240g-eval/nsh/defconfig | 2 +- configs/stm3240g-eval/nsh2/defconfig | 2 +- configs/stm3240g-eval/nxterm/defconfig | 2 +- configs/stm3240g-eval/nxwm/defconfig | 2 +- configs/stm3240g-eval/telnetd/defconfig | 2 +- configs/stm3240g-eval/webserver/defconfig | 2 +- configs/stm3240g-eval/xmlrpc/defconfig | 2 +- configs/stm32butterfly2/nshnet/defconfig | 2 +- configs/stm32f4discovery/ipv6/defconfig | 2 +- configs/stm32f4discovery/netnsh/defconfig | 2 +- configs/tm4c1294-launchpad/ipv6/defconfig | 2 +- configs/tm4c1294-launchpad/nsh/defconfig | 2 +- configs/twr-k64f120m/netnsh/defconfig | 2 +- configs/u-blox-c027/nsh/defconfig | 2 +- configs/viewtool-stm32f107/netnsh/defconfig | 2 +- configs/zkit-arm-1769/hello/defconfig | 2 +- configs/zkit-arm-1769/nsh/defconfig | 2 +- configs/zkit-arm-1769/nxhello/defconfig | 2 +- configs/zkit-arm-1769/thttpd/defconfig | 2 +- drivers/Kconfig | 2 -- drivers/Makefile | 1 - drivers/README.txt | 4 ---- drivers/wireless/ieee802154/mrf24j40.c | 2 +- include/nuttx/{drivers => mm}/iob.h | 12 ++++++------ include/nuttx/net/sixlowpan.h | 2 +- mm/Kconfig | 2 +- mm/Makefile | 1 + mm/README.txt | 12 ++++++++++++ {drivers => mm}/iob/Kconfig | 8 ++++---- {drivers => mm}/iob/Make.defs | 6 +++--- {drivers => mm}/iob/iob.h | 15 ++++++++------- {drivers => mm}/iob/iob_add_queue.c | 4 ++-- {drivers => mm}/iob/iob_alloc.c | 4 ++-- {drivers => mm}/iob/iob_alloc_qentry.c | 4 ++-- {drivers => mm}/iob/iob_clone.c | 4 ++-- {drivers => mm}/iob/iob_concat.c | 4 ++-- {drivers => mm}/iob/iob_contig.c | 4 ++-- {drivers => mm}/iob/iob_copyin.c | 4 ++-- {drivers => mm}/iob/iob_copyout.c | 4 ++-- {drivers => mm}/iob/iob_dump.c | 4 ++-- {drivers => mm}/iob/iob_free.c | 4 ++-- {drivers => mm}/iob/iob_free_chain.c | 4 ++-- {drivers => mm}/iob/iob_free_qentry.c | 4 ++-- {drivers => mm}/iob/iob_free_queue.c | 4 ++-- {drivers => mm}/iob/iob_initialize.c | 4 ++-- {drivers => mm}/iob/iob_pack.c | 4 ++-- {drivers => mm}/iob/iob_peek_queue.c | 4 ++-- {drivers => mm}/iob/iob_remove_queue.c | 4 ++-- {drivers => mm}/iob/iob_test.c | 2 +- {drivers => mm}/iob/iob_trimhead.c | 4 ++-- {drivers => mm}/iob/iob_trimhead_queue.c | 4 ++-- {drivers => mm}/iob/iob_trimtail.c | 4 ++-- net/devif/Make.defs | 2 +- net/devif/devif.h | 2 +- net/devif/devif_iobsend.c | 6 +++--- net/sixlowpan/sixlowpan_framer.c | 2 +- net/socket/recvfrom.c | 2 +- net/tcp/Kconfig | 4 ++-- net/tcp/tcp.h | 2 +- net/tcp/tcp_callback.c | 2 +- net/tcp/tcp_send_buffered.c | 2 +- net/tcp/tcp_wrbuffer.c | 2 +- net/tcp/tcp_wrbuffer_dump.c | 2 +- net/udp/Kconfig | 2 +- net/udp/udp.h | 2 +- wireless/ieee802154/Kconfig | 2 +- wireless/ieee802154/mac802154.c | 2 +- wireless/ieee802154/mac802154_device.c | 2 +- wireless/ieee802154/mac802154_indalloc.c | 2 +- wireless/ieee802154/mac802154_netdev.c | 2 +- 170 files changed, 238 insertions(+), 223 deletions(-) rename include/nuttx/{drivers => mm}/iob.h (98%) rename {drivers => mm}/iob/Kconfig (96%) rename {drivers => mm}/iob/Make.defs (96%) rename {drivers => mm}/iob/iob.h (96%) rename {drivers => mm}/iob/iob_add_queue.c (98%) rename {drivers => mm}/iob/iob_alloc.c (99%) rename {drivers => mm}/iob/iob_alloc_qentry.c (99%) rename {drivers => mm}/iob/iob_clone.c (98%) rename {drivers => mm}/iob/iob_concat.c (97%) rename {drivers => mm}/iob/iob_contig.c (98%) rename {drivers => mm}/iob/iob_copyin.c (99%) rename {drivers => mm}/iob/iob_copyout.c (98%) rename {drivers => mm}/iob/iob_dump.c (98%) rename {drivers => mm}/iob/iob_free.c (98%) rename {drivers => mm}/iob/iob_free_chain.c (97%) rename {drivers => mm}/iob/iob_free_qentry.c (98%) rename {drivers => mm}/iob/iob_free_queue.c (98%) rename {drivers => mm}/iob/iob_initialize.c (98%) rename {drivers => mm}/iob/iob_pack.c (98%) rename {drivers => mm}/iob/iob_peek_queue.c (98%) rename {drivers => mm}/iob/iob_remove_queue.c (98%) rename {drivers => mm}/iob/iob_test.c (99%) rename {drivers => mm}/iob/iob_trimhead.c (98%) rename {drivers => mm}/iob/iob_trimhead_queue.c (98%) rename {drivers => mm}/iob/iob_trimtail.c (98%) diff --git a/arch/arm/src/common/up_initialize.c b/arch/arm/src/common/up_initialize.c index ecf6400d33..4b6cfe00df 100644 --- a/arch/arm/src/common/up_initialize.c +++ b/arch/arm/src/common/up_initialize.c @@ -44,7 +44,7 @@ #include #include #include -#include +#include #include #include #include @@ -191,7 +191,7 @@ void up_initialize(void) arm_timer_initialize(); #endif -#ifdef CONFIG_DRIVERS_IOB +#ifdef CONFIG_MM_IOB /* Initialize IO buffering */ iob_initialize(); diff --git a/arch/avr/src/common/up_initialize.c b/arch/avr/src/common/up_initialize.c index 738f9b27d6..ee9e471fba 100644 --- a/arch/avr/src/common/up_initialize.c +++ b/arch/avr/src/common/up_initialize.c @@ -43,7 +43,7 @@ #include #include -#include +#include #include #include #include @@ -232,7 +232,7 @@ void up_initialize(void) avr_timer_initialize(); #endif -#ifdef CONFIG_DRIVERS_IOB +#ifdef CONFIG_MM_IOB /* Initialize IO buffering */ iob_initialize(); diff --git a/arch/hc/src/common/up_initialize.c b/arch/hc/src/common/up_initialize.c index 0484c8ffc3..b976bf1f52 100644 --- a/arch/hc/src/common/up_initialize.c +++ b/arch/hc/src/common/up_initialize.c @@ -44,7 +44,7 @@ #include #include #include -#include +#include #include #include #include @@ -158,7 +158,7 @@ void up_initialize(void) hc_timer_initialize(); #endif -#ifdef CONFIG_DRIVERS_IOB +#ifdef CONFIG_MM_IOB /* Initialize IO buffering */ iob_initialize(); diff --git a/arch/mips/src/common/up_initialize.c b/arch/mips/src/common/up_initialize.c index 7e301be7b0..c99fb50742 100644 --- a/arch/mips/src/common/up_initialize.c +++ b/arch/mips/src/common/up_initialize.c @@ -44,7 +44,7 @@ #include #include #include -#include +#include #include #include #include @@ -160,7 +160,7 @@ void up_initialize(void) mips_timer_initialize(); #endif -#ifdef CONFIG_DRIVERS_IOB +#ifdef CONFIG_MM_IOB /* Initialize IO buffering */ iob_initialize(); diff --git a/arch/misoc/src/lm32/lm32_initialize.c b/arch/misoc/src/lm32/lm32_initialize.c index 8371a9a39f..1c4aeb9eed 100644 --- a/arch/misoc/src/lm32/lm32_initialize.c +++ b/arch/misoc/src/lm32/lm32_initialize.c @@ -44,7 +44,7 @@ #include #include -#include +#include #include #include #include @@ -79,7 +79,7 @@ void up_initialize(void) misoc_timer_initialize(); -#ifdef CONFIG_DRIVERS_IOB +#ifdef CONFIG_MM_IOB /* Initialize IO buffering */ iob_initialize(); diff --git a/arch/renesas/src/common/up_initialize.c b/arch/renesas/src/common/up_initialize.c index ad8756e48e..77dd322ca4 100644 --- a/arch/renesas/src/common/up_initialize.c +++ b/arch/renesas/src/common/up_initialize.c @@ -44,7 +44,7 @@ #include #include #include -#include +#include #include #include #include @@ -149,7 +149,7 @@ void up_initialize(void) renesas_timer_initialize(); #endif -#ifdef CONFIG_DRIVERS_IOB +#ifdef CONFIG_MM_IOB /* Initialize IO buffering */ iob_initialize(); diff --git a/arch/risc-v/src/common/up_initialize.c b/arch/risc-v/src/common/up_initialize.c index f0a86dfd45..acf400f826 100644 --- a/arch/risc-v/src/common/up_initialize.c +++ b/arch/risc-v/src/common/up_initialize.c @@ -43,7 +43,7 @@ #include #include -#include +#include #include @@ -151,7 +151,7 @@ void up_initialize(void) riscv_timer_initialize(); #endif -#ifdef CONFIG_DRIVERS_IOB +#ifdef CONFIG_MM_IOB /* Initialize IO buffering */ iob_initialize(); diff --git a/arch/sim/src/up_initialize.c b/arch/sim/src/up_initialize.c index d618ebac70..f18767ba96 100644 --- a/arch/sim/src/up_initialize.c +++ b/arch/sim/src/up_initialize.c @@ -43,7 +43,7 @@ #include #include -#include +#include #include #include #include @@ -201,7 +201,7 @@ void up_initialize(void) up_pminitialize(); #endif -#ifdef CONFIG_DRIVERS_IOB +#ifdef CONFIG_MM_IOB /* Initialize IO buffering */ iob_initialize(); diff --git a/arch/x86/src/common/up_initialize.c b/arch/x86/src/common/up_initialize.c index f5f6f7a0e0..7c0f3065af 100644 --- a/arch/x86/src/common/up_initialize.c +++ b/arch/x86/src/common/up_initialize.c @@ -44,7 +44,7 @@ #include #include #include -#include +#include #include #include #include @@ -160,7 +160,7 @@ void up_initialize(void) x86_timer_initialize(); #endif -#ifdef CONFIG_DRIVERS_IOB +#ifdef CONFIG_MM_IOB /* Initialize IO buffering */ iob_initialize(); diff --git a/arch/xtensa/src/common/xtensa_initialize.c b/arch/xtensa/src/common/xtensa_initialize.c index f3ad78392a..9be32e3a17 100644 --- a/arch/xtensa/src/common/xtensa_initialize.c +++ b/arch/xtensa/src/common/xtensa_initialize.c @@ -44,7 +44,7 @@ #include #include #include -#include +#include #include #include #include @@ -168,7 +168,7 @@ void up_initialize(void) xtensa_timer_initialize(); #endif -#ifdef CONFIG_DRIVERS_IOB +#ifdef CONFIG_MM_IOB /* Initialize IO buffering */ iob_initialize(); diff --git a/arch/z16/src/common/up_initialize.c b/arch/z16/src/common/up_initialize.c index c04e342ab9..1d936d241e 100644 --- a/arch/z16/src/common/up_initialize.c +++ b/arch/z16/src/common/up_initialize.c @@ -44,7 +44,7 @@ #include #include #include -#include +#include #include #include #include @@ -160,7 +160,7 @@ void up_initialize(void) z16_timer_initialize(); #endif -#ifdef CONFIG_DRIVERS_IOB +#ifdef CONFIG_MM_IOB /* Initialize IO buffering */ iob_initialize(); diff --git a/arch/z80/src/common/up_initialize.c b/arch/z80/src/common/up_initialize.c index bedf28b0b0..53a539326d 100644 --- a/arch/z80/src/common/up_initialize.c +++ b/arch/z80/src/common/up_initialize.c @@ -44,7 +44,7 @@ #include #include #include -#include +#include #include #include #include @@ -157,7 +157,7 @@ void up_initialize(void) (void)up_mmuinit(); #endif -#ifdef CONFIG_DRIVERS_IOB +#ifdef CONFIG_MM_IOB /* Initialize IO buffering */ iob_initialize(); diff --git a/configs/bambino-200e/netnsh/defconfig b/configs/bambino-200e/netnsh/defconfig index 83ae5fe9a8..7b3e53b6cc 100644 --- a/configs/bambino-200e/netnsh/defconfig +++ b/configs/bambino-200e/netnsh/defconfig @@ -488,7 +488,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/c5471evm/httpd/defconfig b/configs/c5471evm/httpd/defconfig index b844eb004a..763da2a5bd 100644 --- a/configs/c5471evm/httpd/defconfig +++ b/configs/c5471evm/httpd/defconfig @@ -370,7 +370,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/c5471evm/nettest/defconfig b/configs/c5471evm/nettest/defconfig index d371baf706..72dc20b6f1 100644 --- a/configs/c5471evm/nettest/defconfig +++ b/configs/c5471evm/nettest/defconfig @@ -358,7 +358,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/c5471evm/nsh/defconfig b/configs/c5471evm/nsh/defconfig index 9c26f594e8..bb9f485700 100644 --- a/configs/c5471evm/nsh/defconfig +++ b/configs/c5471evm/nsh/defconfig @@ -370,7 +370,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/clicker2-stm32/knsh/defconfig b/configs/clicker2-stm32/knsh/defconfig index ed981e5a97..f25787284d 100644 --- a/configs/clicker2-stm32/knsh/defconfig +++ b/configs/clicker2-stm32/knsh/defconfig @@ -758,7 +758,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -# CONFIG_DRIVERS_IOB is not set +# CONFIG_MM_IOB is not set # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set diff --git a/configs/cloudctrl/nsh/defconfig b/configs/cloudctrl/nsh/defconfig index 54f875306e..f14809e3f8 100644 --- a/configs/cloudctrl/nsh/defconfig +++ b/configs/cloudctrl/nsh/defconfig @@ -761,7 +761,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/dk-tm4c129x/ipv6/defconfig b/configs/dk-tm4c129x/ipv6/defconfig index 3eaecb19c5..86189d524b 100644 --- a/configs/dk-tm4c129x/ipv6/defconfig +++ b/configs/dk-tm4c129x/ipv6/defconfig @@ -506,7 +506,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=36 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/dk-tm4c129x/nsh/defconfig b/configs/dk-tm4c129x/nsh/defconfig index 6fb8a008ea..92a8d79c74 100644 --- a/configs/dk-tm4c129x/nsh/defconfig +++ b/configs/dk-tm4c129x/nsh/defconfig @@ -506,7 +506,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=36 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/eagle100/httpd/defconfig b/configs/eagle100/httpd/defconfig index 3af19d1584..d18b5ce513 100644 --- a/configs/eagle100/httpd/defconfig +++ b/configs/eagle100/httpd/defconfig @@ -474,7 +474,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/eagle100/nettest/defconfig b/configs/eagle100/nettest/defconfig index 06adb40d7b..91197d61e3 100644 --- a/configs/eagle100/nettest/defconfig +++ b/configs/eagle100/nettest/defconfig @@ -462,7 +462,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/eagle100/nsh/defconfig b/configs/eagle100/nsh/defconfig index 22bed91050..34b86ded78 100644 --- a/configs/eagle100/nsh/defconfig +++ b/configs/eagle100/nsh/defconfig @@ -485,7 +485,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/eagle100/thttpd/defconfig b/configs/eagle100/thttpd/defconfig index cdd4eecb3f..fc7aef9061 100644 --- a/configs/eagle100/thttpd/defconfig +++ b/configs/eagle100/thttpd/defconfig @@ -453,7 +453,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/ekk-lm3s9b96/nsh/defconfig b/configs/ekk-lm3s9b96/nsh/defconfig index c26cb06d91..a9fb835bb8 100644 --- a/configs/ekk-lm3s9b96/nsh/defconfig +++ b/configs/ekk-lm3s9b96/nsh/defconfig @@ -472,7 +472,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/ez80f910200zco/dhcpd/defconfig b/configs/ez80f910200zco/dhcpd/defconfig index 0b61941b7a..d5168aa4b1 100644 --- a/configs/ez80f910200zco/dhcpd/defconfig +++ b/configs/ez80f910200zco/dhcpd/defconfig @@ -341,7 +341,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=8 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/ez80f910200zco/httpd/defconfig b/configs/ez80f910200zco/httpd/defconfig index 77a0e30b06..b26f794918 100644 --- a/configs/ez80f910200zco/httpd/defconfig +++ b/configs/ez80f910200zco/httpd/defconfig @@ -353,7 +353,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/ez80f910200zco/nettest/defconfig b/configs/ez80f910200zco/nettest/defconfig index 15cbb1da5d..2430277422 100644 --- a/configs/ez80f910200zco/nettest/defconfig +++ b/configs/ez80f910200zco/nettest/defconfig @@ -341,7 +341,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/ez80f910200zco/nsh/defconfig b/configs/ez80f910200zco/nsh/defconfig index 3db4c5cc00..e40d7e64d8 100644 --- a/configs/ez80f910200zco/nsh/defconfig +++ b/configs/ez80f910200zco/nsh/defconfig @@ -353,7 +353,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/ez80f910200zco/poll/defconfig b/configs/ez80f910200zco/poll/defconfig index 53541fe0fb..c48857b889 100644 --- a/configs/ez80f910200zco/poll/defconfig +++ b/configs/ez80f910200zco/poll/defconfig @@ -353,7 +353,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/fire-stm32v2/nsh/defconfig b/configs/fire-stm32v2/nsh/defconfig index a2f7defdf1..1255771f4a 100644 --- a/configs/fire-stm32v2/nsh/defconfig +++ b/configs/fire-stm32v2/nsh/defconfig @@ -770,7 +770,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/freedom-k64f/netnsh/defconfig b/configs/freedom-k64f/netnsh/defconfig index ac209b3a8b..bcac9353a2 100644 --- a/configs/freedom-k64f/netnsh/defconfig +++ b/configs/freedom-k64f/netnsh/defconfig @@ -501,7 +501,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=36 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/freedom-k66f/netnsh/defconfig b/configs/freedom-k66f/netnsh/defconfig index dbb26035ea..71f0cd33b2 100644 --- a/configs/freedom-k66f/netnsh/defconfig +++ b/configs/freedom-k66f/netnsh/defconfig @@ -510,7 +510,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=36 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/lincoln60/netnsh/defconfig b/configs/lincoln60/netnsh/defconfig index ca17f4e7b4..40dfb528ef 100644 --- a/configs/lincoln60/netnsh/defconfig +++ b/configs/lincoln60/netnsh/defconfig @@ -463,7 +463,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=36 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/lincoln60/thttpd-binfs/defconfig b/configs/lincoln60/thttpd-binfs/defconfig index c659979d94..4f4316e9c7 100644 --- a/configs/lincoln60/thttpd-binfs/defconfig +++ b/configs/lincoln60/thttpd-binfs/defconfig @@ -440,7 +440,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/lm3s6432-s2e/nsh/defconfig b/configs/lm3s6432-s2e/nsh/defconfig index 675a7b6c17..fe849d782c 100644 --- a/configs/lm3s6432-s2e/nsh/defconfig +++ b/configs/lm3s6432-s2e/nsh/defconfig @@ -467,7 +467,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/lm3s6965-ek/discover/defconfig b/configs/lm3s6965-ek/discover/defconfig index 838fbeac02..305695abfb 100644 --- a/configs/lm3s6965-ek/discover/defconfig +++ b/configs/lm3s6965-ek/discover/defconfig @@ -477,7 +477,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/lm3s6965-ek/nsh/defconfig b/configs/lm3s6965-ek/nsh/defconfig index 838fbeac02..305695abfb 100644 --- a/configs/lm3s6965-ek/nsh/defconfig +++ b/configs/lm3s6965-ek/nsh/defconfig @@ -477,7 +477,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/lm3s6965-ek/tcpecho/defconfig b/configs/lm3s6965-ek/tcpecho/defconfig index ac6fd9a2bd..ff3212eaae 100644 --- a/configs/lm3s6965-ek/tcpecho/defconfig +++ b/configs/lm3s6965-ek/tcpecho/defconfig @@ -466,7 +466,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/lm3s8962-ek/nsh/defconfig b/configs/lm3s8962-ek/nsh/defconfig index de5e95e743..86971dec84 100644 --- a/configs/lm3s8962-ek/nsh/defconfig +++ b/configs/lm3s8962-ek/nsh/defconfig @@ -489,7 +489,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/lpcxpresso-lpc1768/dhcpd/defconfig b/configs/lpcxpresso-lpc1768/dhcpd/defconfig index d18c05e9e4..6e8638e71d 100644 --- a/configs/lpcxpresso-lpc1768/dhcpd/defconfig +++ b/configs/lpcxpresso-lpc1768/dhcpd/defconfig @@ -430,7 +430,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=8 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/lpcxpresso-lpc1768/nsh/defconfig b/configs/lpcxpresso-lpc1768/nsh/defconfig index 0a2f6da13d..1246035ad3 100644 --- a/configs/lpcxpresso-lpc1768/nsh/defconfig +++ b/configs/lpcxpresso-lpc1768/nsh/defconfig @@ -453,7 +453,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/lpcxpresso-lpc1768/thttpd/defconfig b/configs/lpcxpresso-lpc1768/thttpd/defconfig index ac12426f49..60845d6a63 100644 --- a/configs/lpcxpresso-lpc1768/thttpd/defconfig +++ b/configs/lpcxpresso-lpc1768/thttpd/defconfig @@ -430,7 +430,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/misoc/hello/defconfig b/configs/misoc/hello/defconfig index bb25f3c366..19f64a538d 100644 --- a/configs/misoc/hello/defconfig +++ b/configs/misoc/hello/defconfig @@ -322,7 +322,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/moxa/nsh/defconfig b/configs/moxa/nsh/defconfig index 6a45427b5c..76da9497d6 100644 --- a/configs/moxa/nsh/defconfig +++ b/configs/moxa/nsh/defconfig @@ -358,7 +358,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/ntosd-dm320/nettest/defconfig b/configs/ntosd-dm320/nettest/defconfig index 638279f138..e088110948 100644 --- a/configs/ntosd-dm320/nettest/defconfig +++ b/configs/ntosd-dm320/nettest/defconfig @@ -340,7 +340,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/ntosd-dm320/nsh/defconfig b/configs/ntosd-dm320/nsh/defconfig index 1283565c72..12b46adc25 100644 --- a/configs/ntosd-dm320/nsh/defconfig +++ b/configs/ntosd-dm320/nsh/defconfig @@ -352,7 +352,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/ntosd-dm320/poll/defconfig b/configs/ntosd-dm320/poll/defconfig index 8f179e8ce8..16874144a1 100644 --- a/configs/ntosd-dm320/poll/defconfig +++ b/configs/ntosd-dm320/poll/defconfig @@ -352,7 +352,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/ntosd-dm320/thttpd/defconfig b/configs/ntosd-dm320/thttpd/defconfig index d146c17293..77f922ff67 100644 --- a/configs/ntosd-dm320/thttpd/defconfig +++ b/configs/ntosd-dm320/thttpd/defconfig @@ -340,7 +340,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/ntosd-dm320/udp/defconfig b/configs/ntosd-dm320/udp/defconfig index 24ea1fe49f..1f0c2d5c07 100644 --- a/configs/ntosd-dm320/udp/defconfig +++ b/configs/ntosd-dm320/udp/defconfig @@ -340,7 +340,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=8 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/ntosd-dm320/webserver/defconfig b/configs/ntosd-dm320/webserver/defconfig index 4f1b363d1c..a41eb42fdc 100644 --- a/configs/ntosd-dm320/webserver/defconfig +++ b/configs/ntosd-dm320/webserver/defconfig @@ -352,7 +352,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/nucleo-f091rc/nsh/defconfig b/configs/nucleo-f091rc/nsh/defconfig index 54bf325dca..e3c9cadefb 100644 --- a/configs/nucleo-f091rc/nsh/defconfig +++ b/configs/nucleo-f091rc/nsh/defconfig @@ -571,7 +571,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -# CONFIG_DRIVERS_IOB is not set +# CONFIG_MM_IOB is not set # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set diff --git a/configs/nucleo-l452re/nsh/defconfig b/configs/nucleo-l452re/nsh/defconfig index 5030287da0..c09ddaf382 100644 --- a/configs/nucleo-l452re/nsh/defconfig +++ b/configs/nucleo-l452re/nsh/defconfig @@ -627,7 +627,7 @@ CONFIG_DEV_RANDOM=y # # Common I/O Buffer Support # -# CONFIG_DRIVERS_IOB is not set +# CONFIG_MM_IOB is not set # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set diff --git a/configs/nucleo-l496zg/nsh/defconfig b/configs/nucleo-l496zg/nsh/defconfig index 4bc74debaf..a048b1c048 100644 --- a/configs/nucleo-l496zg/nsh/defconfig +++ b/configs/nucleo-l496zg/nsh/defconfig @@ -652,7 +652,7 @@ CONFIG_DEV_RANDOM=y # # Common I/O Buffer Support # -# CONFIG_DRIVERS_IOB is not set +# CONFIG_MM_IOB is not set # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set diff --git a/configs/olimex-lpc1766stk/ftpc/defconfig b/configs/olimex-lpc1766stk/ftpc/defconfig index ed46ca4e7f..a39d8ceacc 100644 --- a/configs/olimex-lpc1766stk/ftpc/defconfig +++ b/configs/olimex-lpc1766stk/ftpc/defconfig @@ -453,7 +453,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/olimex-lpc1766stk/hidmouse/defconfig b/configs/olimex-lpc1766stk/hidmouse/defconfig index 0dec1bcdc8..da29b55e98 100644 --- a/configs/olimex-lpc1766stk/hidmouse/defconfig +++ b/configs/olimex-lpc1766stk/hidmouse/defconfig @@ -467,7 +467,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/olimex-lpc1766stk/nettest/defconfig b/configs/olimex-lpc1766stk/nettest/defconfig index 15d885ba0e..20e9abafa1 100644 --- a/configs/olimex-lpc1766stk/nettest/defconfig +++ b/configs/olimex-lpc1766stk/nettest/defconfig @@ -431,7 +431,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/olimex-lpc1766stk/nsh/defconfig b/configs/olimex-lpc1766stk/nsh/defconfig index 60f4e87f7c..44a0c97d2e 100644 --- a/configs/olimex-lpc1766stk/nsh/defconfig +++ b/configs/olimex-lpc1766stk/nsh/defconfig @@ -454,7 +454,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/olimex-lpc1766stk/slip-httpd/defconfig b/configs/olimex-lpc1766stk/slip-httpd/defconfig index e9a9fcd7f4..04137cab7a 100644 --- a/configs/olimex-lpc1766stk/slip-httpd/defconfig +++ b/configs/olimex-lpc1766stk/slip-httpd/defconfig @@ -415,7 +415,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/olimex-lpc1766stk/thttpd-binfs/defconfig b/configs/olimex-lpc1766stk/thttpd-binfs/defconfig index ec9ade8e7d..714ed7e341 100644 --- a/configs/olimex-lpc1766stk/thttpd-binfs/defconfig +++ b/configs/olimex-lpc1766stk/thttpd-binfs/defconfig @@ -440,7 +440,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/olimex-lpc1766stk/thttpd-nxflat/defconfig b/configs/olimex-lpc1766stk/thttpd-nxflat/defconfig index 74a3e55d2b..bf1693614c 100644 --- a/configs/olimex-lpc1766stk/thttpd-nxflat/defconfig +++ b/configs/olimex-lpc1766stk/thttpd-nxflat/defconfig @@ -431,7 +431,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/olimex-lpc1766stk/zmodem/defconfig b/configs/olimex-lpc1766stk/zmodem/defconfig index 51526dd8b5..4fdff449c1 100644 --- a/configs/olimex-lpc1766stk/zmodem/defconfig +++ b/configs/olimex-lpc1766stk/zmodem/defconfig @@ -455,7 +455,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/olimex-stm32-e407/discover/defconfig b/configs/olimex-stm32-e407/discover/defconfig index 9a2f223de3..23760ac7b9 100644 --- a/configs/olimex-stm32-e407/discover/defconfig +++ b/configs/olimex-stm32-e407/discover/defconfig @@ -764,7 +764,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/olimex-stm32-e407/netnsh/defconfig b/configs/olimex-stm32-e407/netnsh/defconfig index 1969e3f313..17ffb5f783 100644 --- a/configs/olimex-stm32-e407/netnsh/defconfig +++ b/configs/olimex-stm32-e407/netnsh/defconfig @@ -764,7 +764,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/olimex-stm32-e407/telnetd/defconfig b/configs/olimex-stm32-e407/telnetd/defconfig index 349bf77be8..6ce58a9247 100644 --- a/configs/olimex-stm32-e407/telnetd/defconfig +++ b/configs/olimex-stm32-e407/telnetd/defconfig @@ -764,7 +764,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/olimex-stm32-e407/webserver/defconfig b/configs/olimex-stm32-e407/webserver/defconfig index fa179cb794..c6a7e03b37 100644 --- a/configs/olimex-stm32-e407/webserver/defconfig +++ b/configs/olimex-stm32-e407/webserver/defconfig @@ -764,7 +764,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/olimex-stm32-p107/nsh/defconfig b/configs/olimex-stm32-p107/nsh/defconfig index 78dcb93ed4..d6fdc7e496 100644 --- a/configs/olimex-stm32-p107/nsh/defconfig +++ b/configs/olimex-stm32-p107/nsh/defconfig @@ -731,7 +731,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/olimex-stm32-p207/nsh/defconfig b/configs/olimex-stm32-p207/nsh/defconfig index 55de4e0d37..2f1c5e6149 100644 --- a/configs/olimex-stm32-p207/nsh/defconfig +++ b/configs/olimex-stm32-p207/nsh/defconfig @@ -794,7 +794,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/olimex-strp711/nettest/defconfig b/configs/olimex-strp711/nettest/defconfig index 50d63c8170..4a23d44266 100644 --- a/configs/olimex-strp711/nettest/defconfig +++ b/configs/olimex-strp711/nettest/defconfig @@ -386,7 +386,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/photon/wlan/defconfig b/configs/photon/wlan/defconfig index 1892e56c10..0f5060e846 100644 --- a/configs/photon/wlan/defconfig +++ b/configs/photon/wlan/defconfig @@ -799,7 +799,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 @@ -1601,6 +1601,14 @@ CONFIG_READLINE_ECHO=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set +# CONFIG_WIRELESS_IWPAN is not set CONFIG_WIRELESS_WAPI=y CONFIG_WIRELESS_WAPI_CMDTOOL=y CONFIG_WIRELESS_WAPI_STACKSIZE=2048 diff --git a/configs/pic32mx-starterkit/nsh2/defconfig b/configs/pic32mx-starterkit/nsh2/defconfig index de8c688ac5..78d7f41287 100644 --- a/configs/pic32mx-starterkit/nsh2/defconfig +++ b/configs/pic32mx-starterkit/nsh2/defconfig @@ -483,7 +483,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/pic32mx7mmb/nsh/defconfig b/configs/pic32mx7mmb/nsh/defconfig index c1a7d79a6f..4951d6041e 100644 --- a/configs/pic32mx7mmb/nsh/defconfig +++ b/configs/pic32mx7mmb/nsh/defconfig @@ -492,7 +492,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/sam4e-ek/nsh/defconfig b/configs/sam4e-ek/nsh/defconfig index 1ac7fb3118..7bbdf3723b 100644 --- a/configs/sam4e-ek/nsh/defconfig +++ b/configs/sam4e-ek/nsh/defconfig @@ -521,7 +521,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/sam4e-ek/nxwm/defconfig b/configs/sam4e-ek/nxwm/defconfig index 3ab09117e1..2b86e3a1c8 100644 --- a/configs/sam4e-ek/nxwm/defconfig +++ b/configs/sam4e-ek/nxwm/defconfig @@ -531,7 +531,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/sam4e-ek/usbnsh/defconfig b/configs/sam4e-ek/usbnsh/defconfig index eebe76056b..e8292655ca 100644 --- a/configs/sam4e-ek/usbnsh/defconfig +++ b/configs/sam4e-ek/usbnsh/defconfig @@ -527,7 +527,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/sama5d3-xplained/bridge/defconfig b/configs/sama5d3-xplained/bridge/defconfig index 01e56ae986..bad6c2f17f 100644 --- a/configs/sama5d3-xplained/bridge/defconfig +++ b/configs/sama5d3-xplained/bridge/defconfig @@ -548,7 +548,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -# CONFIG_DRIVERS_IOB is not set +# CONFIG_MM_IOB is not set # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set diff --git a/configs/sama5d4-ek/bridge/defconfig b/configs/sama5d4-ek/bridge/defconfig index ae4d3b8160..565cd8c324 100644 --- a/configs/sama5d4-ek/bridge/defconfig +++ b/configs/sama5d4-ek/bridge/defconfig @@ -566,7 +566,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -# CONFIG_DRIVERS_IOB is not set +# CONFIG_MM_IOB is not set # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set diff --git a/configs/sama5d4-ek/ipv6/defconfig b/configs/sama5d4-ek/ipv6/defconfig index 06791816be..60d4077d20 100644 --- a/configs/sama5d4-ek/ipv6/defconfig +++ b/configs/sama5d4-ek/ipv6/defconfig @@ -667,7 +667,7 @@ CONFIG_DEV_RANDOM=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=36 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/sama5d4-ek/nsh/defconfig b/configs/sama5d4-ek/nsh/defconfig index 4c72b5f9b9..fa51ddcf86 100644 --- a/configs/sama5d4-ek/nsh/defconfig +++ b/configs/sama5d4-ek/nsh/defconfig @@ -667,7 +667,7 @@ CONFIG_DEV_RANDOM=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=36 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/sama5d4-ek/nxwm/defconfig b/configs/sama5d4-ek/nxwm/defconfig index 17907ad732..a47b489608 100644 --- a/configs/sama5d4-ek/nxwm/defconfig +++ b/configs/sama5d4-ek/nxwm/defconfig @@ -641,7 +641,7 @@ CONFIG_DEV_RANDOM=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=36 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/same70-xplained/netnsh/defconfig b/configs/same70-xplained/netnsh/defconfig index 2b3cca401d..45b670fc14 100644 --- a/configs/same70-xplained/netnsh/defconfig +++ b/configs/same70-xplained/netnsh/defconfig @@ -540,7 +540,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/samv71-xult/netnsh/defconfig b/configs/samv71-xult/netnsh/defconfig index ca281528ad..2e59f382ba 100644 --- a/configs/samv71-xult/netnsh/defconfig +++ b/configs/samv71-xult/netnsh/defconfig @@ -543,7 +543,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=36 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/samv71-xult/vnc/defconfig b/configs/samv71-xult/vnc/defconfig index a413da950f..58de7ce621 100644 --- a/configs/samv71-xult/vnc/defconfig +++ b/configs/samv71-xult/vnc/defconfig @@ -542,7 +542,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=72 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/samv71-xult/vnxwm/defconfig b/configs/samv71-xult/vnxwm/defconfig index 4632730355..1a2738b66b 100644 --- a/configs/samv71-xult/vnxwm/defconfig +++ b/configs/samv71-xult/vnxwm/defconfig @@ -545,7 +545,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=72 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/shenzhou/nsh/defconfig b/configs/shenzhou/nsh/defconfig index 6e20d65f44..8bd378dc89 100644 --- a/configs/shenzhou/nsh/defconfig +++ b/configs/shenzhou/nsh/defconfig @@ -751,7 +751,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/shenzhou/nxwm/defconfig b/configs/shenzhou/nxwm/defconfig index 2370d5377a..e64dfed648 100644 --- a/configs/shenzhou/nxwm/defconfig +++ b/configs/shenzhou/nxwm/defconfig @@ -775,7 +775,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/shenzhou/thttpd/defconfig b/configs/shenzhou/thttpd/defconfig index ce40c66cca..cb5aaf0458 100644 --- a/configs/shenzhou/thttpd/defconfig +++ b/configs/shenzhou/thttpd/defconfig @@ -752,7 +752,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/sim/nettest/defconfig b/configs/sim/nettest/defconfig index c1e7c78898..491923f77e 100644 --- a/configs/sim/nettest/defconfig +++ b/configs/sim/nettest/defconfig @@ -283,7 +283,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/sim/sixlowpan/defconfig b/configs/sim/sixlowpan/defconfig index f46639d003..713c8b1f50 100644 --- a/configs/sim/sixlowpan/defconfig +++ b/configs/sim/sixlowpan/defconfig @@ -298,7 +298,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=36 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/sim/udgram/defconfig b/configs/sim/udgram/defconfig index 8586c0b34d..1274550b49 100644 --- a/configs/sim/udgram/defconfig +++ b/configs/sim/udgram/defconfig @@ -292,7 +292,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -# CONFIG_DRIVERS_IOB is not set +# CONFIG_MM_IOB is not set # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set diff --git a/configs/sim/ustream/defconfig b/configs/sim/ustream/defconfig index 034f8b83c1..8721169286 100644 --- a/configs/sim/ustream/defconfig +++ b/configs/sim/ustream/defconfig @@ -292,7 +292,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -# CONFIG_DRIVERS_IOB is not set +# CONFIG_MM_IOB is not set # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set diff --git a/configs/stm3220g-eval/dhcpd/defconfig b/configs/stm3220g-eval/dhcpd/defconfig index c46030d14b..9168df6ad7 100644 --- a/configs/stm3220g-eval/dhcpd/defconfig +++ b/configs/stm3220g-eval/dhcpd/defconfig @@ -746,7 +746,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=8 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/stm3220g-eval/nettest/defconfig b/configs/stm3220g-eval/nettest/defconfig index f69886646f..7067e766aa 100644 --- a/configs/stm3220g-eval/nettest/defconfig +++ b/configs/stm3220g-eval/nettest/defconfig @@ -746,7 +746,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/stm3220g-eval/nsh/defconfig b/configs/stm3220g-eval/nsh/defconfig index 253c075c8d..a37ca34d75 100644 --- a/configs/stm3220g-eval/nsh/defconfig +++ b/configs/stm3220g-eval/nsh/defconfig @@ -771,7 +771,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/stm3220g-eval/nsh2/defconfig b/configs/stm3220g-eval/nsh2/defconfig index c437849e01..c0d61540dc 100644 --- a/configs/stm3220g-eval/nsh2/defconfig +++ b/configs/stm3220g-eval/nsh2/defconfig @@ -772,7 +772,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/stm3220g-eval/nxwm/defconfig b/configs/stm3220g-eval/nxwm/defconfig index 55c3649cb2..68a215312e 100644 --- a/configs/stm3220g-eval/nxwm/defconfig +++ b/configs/stm3220g-eval/nxwm/defconfig @@ -792,7 +792,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/stm3220g-eval/telnetd/defconfig b/configs/stm3220g-eval/telnetd/defconfig index 5a842d7721..e1531299a4 100644 --- a/configs/stm3220g-eval/telnetd/defconfig +++ b/configs/stm3220g-eval/telnetd/defconfig @@ -746,7 +746,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/stm3240g-eval/dhcpd/defconfig b/configs/stm3240g-eval/dhcpd/defconfig index e972d6303c..d14a03b0bf 100644 --- a/configs/stm3240g-eval/dhcpd/defconfig +++ b/configs/stm3240g-eval/dhcpd/defconfig @@ -750,7 +750,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=8 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/stm3240g-eval/discover/defconfig b/configs/stm3240g-eval/discover/defconfig index e104292ed2..e55ee92107 100644 --- a/configs/stm3240g-eval/discover/defconfig +++ b/configs/stm3240g-eval/discover/defconfig @@ -769,7 +769,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/stm3240g-eval/nettest/defconfig b/configs/stm3240g-eval/nettest/defconfig index ac3a56be38..c4f9f51a6c 100644 --- a/configs/stm3240g-eval/nettest/defconfig +++ b/configs/stm3240g-eval/nettest/defconfig @@ -750,7 +750,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/stm3240g-eval/nsh/defconfig b/configs/stm3240g-eval/nsh/defconfig index 4557ee9797..d9f65117d5 100644 --- a/configs/stm3240g-eval/nsh/defconfig +++ b/configs/stm3240g-eval/nsh/defconfig @@ -787,7 +787,7 @@ CONFIG_DEV_RANDOM=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/stm3240g-eval/nsh2/defconfig b/configs/stm3240g-eval/nsh2/defconfig index fc1ab20840..63aa6a234b 100644 --- a/configs/stm3240g-eval/nsh2/defconfig +++ b/configs/stm3240g-eval/nsh2/defconfig @@ -776,7 +776,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/stm3240g-eval/nxterm/defconfig b/configs/stm3240g-eval/nxterm/defconfig index 77847443b9..c68bc68be6 100644 --- a/configs/stm3240g-eval/nxterm/defconfig +++ b/configs/stm3240g-eval/nxterm/defconfig @@ -795,7 +795,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/stm3240g-eval/nxwm/defconfig b/configs/stm3240g-eval/nxwm/defconfig index 5e9f7a1306..980d63b0c5 100644 --- a/configs/stm3240g-eval/nxwm/defconfig +++ b/configs/stm3240g-eval/nxwm/defconfig @@ -796,7 +796,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/stm3240g-eval/telnetd/defconfig b/configs/stm3240g-eval/telnetd/defconfig index 742c3f6e6e..d3ea732595 100644 --- a/configs/stm3240g-eval/telnetd/defconfig +++ b/configs/stm3240g-eval/telnetd/defconfig @@ -750,7 +750,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/stm3240g-eval/webserver/defconfig b/configs/stm3240g-eval/webserver/defconfig index 3dc8fbb926..910033f2d9 100644 --- a/configs/stm3240g-eval/webserver/defconfig +++ b/configs/stm3240g-eval/webserver/defconfig @@ -775,7 +775,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/stm3240g-eval/xmlrpc/defconfig b/configs/stm3240g-eval/xmlrpc/defconfig index 90bd6a6ee4..aa0f34e696 100644 --- a/configs/stm3240g-eval/xmlrpc/defconfig +++ b/configs/stm3240g-eval/xmlrpc/defconfig @@ -764,7 +764,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/stm32butterfly2/nshnet/defconfig b/configs/stm32butterfly2/nshnet/defconfig index fb61f3a9f6..08cc2425c4 100644 --- a/configs/stm32butterfly2/nshnet/defconfig +++ b/configs/stm32butterfly2/nshnet/defconfig @@ -747,7 +747,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/stm32f4discovery/ipv6/defconfig b/configs/stm32f4discovery/ipv6/defconfig index 25d5886bbd..7e027d640c 100644 --- a/configs/stm32f4discovery/ipv6/defconfig +++ b/configs/stm32f4discovery/ipv6/defconfig @@ -795,7 +795,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=36 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/stm32f4discovery/netnsh/defconfig b/configs/stm32f4discovery/netnsh/defconfig index f11c99eb6a..57050f7dae 100644 --- a/configs/stm32f4discovery/netnsh/defconfig +++ b/configs/stm32f4discovery/netnsh/defconfig @@ -795,7 +795,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=36 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/tm4c1294-launchpad/ipv6/defconfig b/configs/tm4c1294-launchpad/ipv6/defconfig index e77c8b7e32..422e5b40be 100644 --- a/configs/tm4c1294-launchpad/ipv6/defconfig +++ b/configs/tm4c1294-launchpad/ipv6/defconfig @@ -494,7 +494,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=36 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/tm4c1294-launchpad/nsh/defconfig b/configs/tm4c1294-launchpad/nsh/defconfig index 7ccb18b26c..7ce75c3e86 100644 --- a/configs/tm4c1294-launchpad/nsh/defconfig +++ b/configs/tm4c1294-launchpad/nsh/defconfig @@ -494,7 +494,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=36 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/twr-k64f120m/netnsh/defconfig b/configs/twr-k64f120m/netnsh/defconfig index 1bd65b87c2..ead54aade6 100644 --- a/configs/twr-k64f120m/netnsh/defconfig +++ b/configs/twr-k64f120m/netnsh/defconfig @@ -509,7 +509,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=36 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/u-blox-c027/nsh/defconfig b/configs/u-blox-c027/nsh/defconfig index da3f3a030c..68b549e9f6 100644 --- a/configs/u-blox-c027/nsh/defconfig +++ b/configs/u-blox-c027/nsh/defconfig @@ -461,7 +461,7 @@ CONFIG_DEV_ZERO=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/viewtool-stm32f107/netnsh/defconfig b/configs/viewtool-stm32f107/netnsh/defconfig index 4b16b79f03..e422e035c8 100644 --- a/configs/viewtool-stm32f107/netnsh/defconfig +++ b/configs/viewtool-stm32f107/netnsh/defconfig @@ -743,7 +743,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/zkit-arm-1769/hello/defconfig b/configs/zkit-arm-1769/hello/defconfig index b8e92733f7..aee6780233 100644 --- a/configs/zkit-arm-1769/hello/defconfig +++ b/configs/zkit-arm-1769/hello/defconfig @@ -431,7 +431,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/zkit-arm-1769/nsh/defconfig b/configs/zkit-arm-1769/nsh/defconfig index 7d896929d8..7f6021ea8e 100644 --- a/configs/zkit-arm-1769/nsh/defconfig +++ b/configs/zkit-arm-1769/nsh/defconfig @@ -454,7 +454,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/zkit-arm-1769/nxhello/defconfig b/configs/zkit-arm-1769/nxhello/defconfig index b0c578902c..372619e563 100644 --- a/configs/zkit-arm-1769/nxhello/defconfig +++ b/configs/zkit-arm-1769/nxhello/defconfig @@ -454,7 +454,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/configs/zkit-arm-1769/thttpd/defconfig b/configs/zkit-arm-1769/thttpd/defconfig index 2846f29834..0866830194 100644 --- a/configs/zkit-arm-1769/thttpd/defconfig +++ b/configs/zkit-arm-1769/thttpd/defconfig @@ -431,7 +431,7 @@ CONFIG_DEV_NULL=y # # Common I/O Buffer Support # -CONFIG_DRIVERS_IOB=y +CONFIG_MM_IOB=y CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_BUFSIZE=196 CONFIG_IOB_NCHAINS=8 diff --git a/drivers/Kconfig b/drivers/Kconfig index fa200e17d4..d7bc265374 100644 --- a/drivers/Kconfig +++ b/drivers/Kconfig @@ -98,8 +98,6 @@ source drivers/loop/Kconfig menu "Buffering" -source "drivers/iob/Kconfig" - config DRVR_WRITEBUFFER bool "Enable write buffer support" default n diff --git a/drivers/Makefile b/drivers/Makefile index 1de5f4d133..5946cc123a 100644 --- a/drivers/Makefile +++ b/drivers/Makefile @@ -54,7 +54,6 @@ include audio$(DELIM)Make.defs include bch$(DELIM)Make.defs include i2c$(DELIM)Make.defs include input$(DELIM)Make.defs -include iob$(DELIM)Make.defs include ioexpander$(DELIM)Make.defs include lcd$(DELIM)Make.defs include leds$(DELIM)Make.defs diff --git a/drivers/README.txt b/drivers/README.txt index ad4e25f642..f9f23af06f 100644 --- a/drivers/README.txt +++ b/drivers/README.txt @@ -74,10 +74,6 @@ eeprom/ interface but instead use the simple character interface provided by the EEPROM drivers. -iob/ - Common driver I/O buffer support. Used primarily by networking and - network-related drivers but available for any usage. - i2c/ I2C drivers and support logic. See include/nuttx/i2c/i2c_master.h diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c index 8283278d3c..e4553a3b8c 100644 --- a/drivers/wireless/ieee802154/mrf24j40.c +++ b/drivers/wireless/ieee802154/mrf24j40.c @@ -57,7 +57,7 @@ #include #include -#include +#include #include #include diff --git a/include/nuttx/drivers/iob.h b/include/nuttx/mm/iob.h similarity index 98% rename from include/nuttx/drivers/iob.h rename to include/nuttx/mm/iob.h index 486c56761b..75e5186c7e 100644 --- a/include/nuttx/drivers/iob.h +++ b/include/nuttx/mm/iob.h @@ -1,5 +1,5 @@ /**************************************************************************** - * include/nuttx/drivers/iob.h + * include/nuttx/mm/iob.h * * Copyright (C) 2014 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -33,8 +33,8 @@ * ****************************************************************************/ -#ifndef _INCLUDE_NUTTX_DRIVERS_IOB_H -#define _INCLUDE_NUTTX_DRIVERS_IOB_H +#ifndef _INCLUDE_NUTTX_MM_IOB_H +#define _INCLUDE_NUTTX_MM_IOB_H /**************************************************************************** * Included Files @@ -45,7 +45,7 @@ #include #include -#ifdef CONFIG_DRIVERS_IOB +#ifdef CONFIG_MM_IOB /**************************************************************************** * Pre-processor Definitions @@ -420,6 +420,6 @@ void iob_dump(FAR const char *msg, FAR struct iob_s *iob, unsigned int len, # define iob_dump(wrb) #endif -#endif /* CONFIG_DRIVERS_IOB */ -#endif /* _INCLUDE_NUTTX_DRIVERS_IOB_H */ +#endif /* CONFIG_MM_IOB */ +#endif /* _INCLUDE_NUTTX_MM_IOB_H */ diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index a99f0e5e67..45395d1c29 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -55,7 +55,7 @@ #include #include -#include +#include #include #include diff --git a/mm/Kconfig b/mm/Kconfig index 8cba9265ea..4c386022c4 100644 --- a/mm/Kconfig +++ b/mm/Kconfig @@ -158,4 +158,4 @@ config MM_SHM Build in support for the shared memory interfaces shmget(), shmat(), shmctl(), and shmdt(). - +source "mm/iob/Kconfig" diff --git a/mm/Makefile b/mm/Makefile index 752a6c0f49..6126ea1c64 100644 --- a/mm/Makefile +++ b/mm/Makefile @@ -61,6 +61,7 @@ include umm_heap/Make.defs include kmm_heap/Make.defs include mm_gran/Make.defs include shm/Make.defs +include iob/Make.defs BINDIR ?= bin diff --git a/mm/README.txt b/mm/README.txt index f33cf49c80..52e6c3cd3a 100644 --- a/mm/README.txt +++ b/mm/README.txt @@ -153,3 +153,15 @@ This directory contains the NuttX memory management logic. This include: The shared memory management logic has its own README file that can be found at nuttx/mm/shm/README.txt. + +5) I/O Buffers + + The iob subdirectory contains a simple allocator of I/O buffers. These + I/O buffers, IOBs, are used extensively for networking but are generally + available for usage by drivers. The I/O buffers have these properties: + + 1. Uses a pool of a fixed number of fixed fixed size buffers. + 2. Free buffers are retained in free list: When a buffer is allocated + it is removed from the free list; when a buffer is freed it is + returned to the free list. + 3. The calling application will wait if there are not free buffers. diff --git a/drivers/iob/Kconfig b/mm/iob/Kconfig similarity index 96% rename from drivers/iob/Kconfig rename to mm/iob/Kconfig index e5368681d5..3d603fde38 100644 --- a/drivers/iob/Kconfig +++ b/mm/iob/Kconfig @@ -3,16 +3,16 @@ # see the file kconfig-language.txt in the NuttX tools repository. # -menu "Common I/O Buffer Support" +menu "Common I/O Buffer Support" -config DRIVERS_IOB +config MM_IOB bool "Enable generic I/O buffer support" default n ---help--- This setting will build the common I/O buffer (IOB) support library. -if DRIVERS_IOB +if MM_IOB config IOB_NBUFFERS int "Number of pre-allocated I/O buffers" @@ -70,5 +70,5 @@ config IOB_DEBUG if you are debugging the I/O buffer logic and do not want to get overloaded with other un-related debug output. -endif # DRIVERS_IOB +endif # MM_IOB endmenu # Common I/O buffer support diff --git a/drivers/iob/Make.defs b/mm/iob/Make.defs similarity index 96% rename from drivers/iob/Make.defs rename to mm/iob/Make.defs index ba74e8e578..7c08edd7fb 100644 --- a/drivers/iob/Make.defs +++ b/mm/iob/Make.defs @@ -1,5 +1,5 @@ ############################################################################ -# drivers/iob/Make.defs +# mm/iob/Make.defs # # Copyright (C) 2014, 2017 Gregory Nutt. All rights reserved. # Author: Gregory Nutt @@ -33,7 +33,7 @@ # ############################################################################ -ifeq ($(CONFIG_DRIVERS_IOB),y) +ifeq ($(CONFIG_MM_IOB),y) # Include IOB source files @@ -51,6 +51,6 @@ endif DEPPATH += --dep-path iob VPATH += :iob -CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)$(DELIM)drivers$(DELIM)iob} +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)$(DELIM)mm$(DELIM)iob} endif diff --git a/drivers/iob/iob.h b/mm/iob/iob.h similarity index 96% rename from drivers/iob/iob.h rename to mm/iob/iob.h index 30f2310272..5f4436980c 100644 --- a/drivers/iob/iob.h +++ b/mm/iob/iob.h @@ -1,5 +1,5 @@ /**************************************************************************** - * drivers/iob/iob.h + * mm/iob/iob.h * * Copyright (C) 2014, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -33,8 +33,8 @@ * ****************************************************************************/ -#ifndef __DRIVERS_IOB_IOB_H -#define __DRIVERS_IOB_IOB_H 1 +#ifndef __MM_IOB_IOB_H +#define __MM_IOB_IOB_H 1 /**************************************************************************** * Included Files @@ -45,9 +45,9 @@ #include #include -#include +#include -#ifdef CONFIG_DRIVERS_IOB +#ifdef CONFIG_MM_IOB /**************************************************************************** * Pre-processor Definitions @@ -146,5 +146,6 @@ FAR struct iob_qentry_s *iob_tryalloc_qentry(void); FAR struct iob_qentry_s *iob_free_qentry(FAR struct iob_qentry_s *iobq); -#endif /* CONFIG_DRIVERS_IOB */ -#endif /* __DRIVERS_IOB_IOB_H */ +#endif /* CONFIG_MM_IOB */ +#endif /* __MM_IOB_IOB_H */ + diff --git a/drivers/iob/iob_add_queue.c b/mm/iob/iob_add_queue.c similarity index 98% rename from drivers/iob/iob_add_queue.c rename to mm/iob/iob_add_queue.c index a2f3376208..d2c40cc6b7 100644 --- a/drivers/iob/iob_add_queue.c +++ b/mm/iob/iob_add_queue.c @@ -1,5 +1,5 @@ /**************************************************************************** - * drivers/iob/iob_add_queue.c + * mm/iob/iob_add_queue.c * * Copyright (C) 2014 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -43,7 +43,7 @@ #include #include -#include +#include #include "iob.h" diff --git a/drivers/iob/iob_alloc.c b/mm/iob/iob_alloc.c similarity index 99% rename from drivers/iob/iob_alloc.c rename to mm/iob/iob_alloc.c index 9fc938d7ed..a1c4d6de97 100644 --- a/drivers/iob/iob_alloc.c +++ b/mm/iob/iob_alloc.c @@ -1,5 +1,5 @@ /**************************************************************************** - * drivers/iob/iob_alloc.c + * mm/iob/iob_alloc.c * * Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -45,7 +45,7 @@ #include #include -#include +#include #include "iob.h" diff --git a/drivers/iob/iob_alloc_qentry.c b/mm/iob/iob_alloc_qentry.c similarity index 99% rename from drivers/iob/iob_alloc_qentry.c rename to mm/iob/iob_alloc_qentry.c index 147f1f8328..a1d4044bc4 100644 --- a/drivers/iob/iob_alloc_qentry.c +++ b/mm/iob/iob_alloc_qentry.c @@ -1,5 +1,5 @@ /**************************************************************************** - * drivers/iob/iob_alloc_qentry.c + * mm/iob/iob_alloc_qentry.c * * Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -45,7 +45,7 @@ #include #include -#include +#include #include "iob.h" diff --git a/drivers/iob/iob_clone.c b/mm/iob/iob_clone.c similarity index 98% rename from drivers/iob/iob_clone.c rename to mm/iob/iob_clone.c index bbd2450280..8b3754b482 100644 --- a/drivers/iob/iob_clone.c +++ b/mm/iob/iob_clone.c @@ -1,5 +1,5 @@ /**************************************************************************** - * drivers/iob/iob_copy.c + * mm/iob/iob_copy.c * * Copyright (C) 2014, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -44,7 +44,7 @@ #include #include -#include +#include #include "iob.h" diff --git a/drivers/iob/iob_concat.c b/mm/iob/iob_concat.c similarity index 97% rename from drivers/iob/iob_concat.c rename to mm/iob/iob_concat.c index 8c9325ee53..4829c3b072 100644 --- a/drivers/iob/iob_concat.c +++ b/mm/iob/iob_concat.c @@ -1,5 +1,5 @@ /**************************************************************************** - * drivers/iob/iob_concat.c + * mm/iob/iob_concat.c * * Copyright (C) 2014 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -41,7 +41,7 @@ #include -#include +#include #include "iob.h" diff --git a/drivers/iob/iob_contig.c b/mm/iob/iob_contig.c similarity index 98% rename from drivers/iob/iob_contig.c rename to mm/iob/iob_contig.c index af2bc40db7..ee71ec05fc 100644 --- a/drivers/iob/iob_contig.c +++ b/mm/iob/iob_contig.c @@ -1,5 +1,5 @@ /**************************************************************************** - * drivers/iob/iob_contig.c + * mm/iob/iob_contig.c * * Copyright (C) 2014 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -44,7 +44,7 @@ #include #include -#include +#include #include "iob.h" diff --git a/drivers/iob/iob_copyin.c b/mm/iob/iob_copyin.c similarity index 99% rename from drivers/iob/iob_copyin.c rename to mm/iob/iob_copyin.c index 8a5732cb94..5c1b8894e3 100644 --- a/drivers/iob/iob_copyin.c +++ b/mm/iob/iob_copyin.c @@ -1,5 +1,5 @@ /**************************************************************************** - * drivers/iob/iob_copyin.c + * mm/iob/iob_copyin.c * * Copyright (C) 2014, 2016-2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -45,7 +45,7 @@ #include #include -#include +#include #include "iob.h" diff --git a/drivers/iob/iob_copyout.c b/mm/iob/iob_copyout.c similarity index 98% rename from drivers/iob/iob_copyout.c rename to mm/iob/iob_copyout.c index 4b8c4e243c..c805a02657 100644 --- a/drivers/iob/iob_copyout.c +++ b/mm/iob/iob_copyout.c @@ -1,5 +1,5 @@ /**************************************************************************** - * drivers/iob/iob_copyout.c + * mm/iob/iob_copyout.c * * Copyright (C) 2014 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -43,7 +43,7 @@ #include #include -#include +#include #include "iob.h" diff --git a/drivers/iob/iob_dump.c b/mm/iob/iob_dump.c similarity index 98% rename from drivers/iob/iob_dump.c rename to mm/iob/iob_dump.c index e2f72edb8d..c84dd4b110 100644 --- a/drivers/iob/iob_dump.c +++ b/mm/iob/iob_dump.c @@ -1,5 +1,5 @@ /**************************************************************************** - * drivers/iob/iob_dump.c + * mm/iob/iob_dump.c * * Copyright (C) 2014 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -42,7 +42,7 @@ #include #include -#include +#include #include "iob.h" diff --git a/drivers/iob/iob_free.c b/mm/iob/iob_free.c similarity index 98% rename from drivers/iob/iob_free.c rename to mm/iob/iob_free.c index d2a67d9758..75a01cf89b 100644 --- a/drivers/iob/iob_free.c +++ b/mm/iob/iob_free.c @@ -1,5 +1,5 @@ /**************************************************************************** - * drivers/iob/iob_free.c + * mm/iob/iob_free.c * * Copyright (C) 2014, 2016-2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -45,7 +45,7 @@ #include #include -#include +#include #include "iob.h" diff --git a/drivers/iob/iob_free_chain.c b/mm/iob/iob_free_chain.c similarity index 97% rename from drivers/iob/iob_free_chain.c rename to mm/iob/iob_free_chain.c index 75c69a3f13..d27a64dc15 100644 --- a/drivers/iob/iob_free_chain.c +++ b/mm/iob/iob_free_chain.c @@ -1,5 +1,5 @@ /**************************************************************************** - * drivers/iob/iob_free_chain.c + * mm/iob/iob_free_chain.c * * Copyright (C) 2014 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -40,7 +40,7 @@ #include #include -#include +#include #include "iob.h" diff --git a/drivers/iob/iob_free_qentry.c b/mm/iob/iob_free_qentry.c similarity index 98% rename from drivers/iob/iob_free_qentry.c rename to mm/iob/iob_free_qentry.c index 402d4e76ac..393f0ee47b 100644 --- a/drivers/iob/iob_free_qentry.c +++ b/mm/iob/iob_free_qentry.c @@ -1,5 +1,5 @@ /**************************************************************************** - * drivers/iob/iob_free_qentry.c + * mm/iob/iob_free_qentry.c * * Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -44,7 +44,7 @@ #include #include -#include +#include #include "iob.h" diff --git a/drivers/iob/iob_free_queue.c b/mm/iob/iob_free_queue.c similarity index 98% rename from drivers/iob/iob_free_queue.c rename to mm/iob/iob_free_queue.c index 953182b5c6..dc436230e8 100644 --- a/drivers/iob/iob_free_queue.c +++ b/mm/iob/iob_free_queue.c @@ -1,5 +1,5 @@ /**************************************************************************** - * drivers/iob/iob_free_queue.c + * mm/iob/iob_free_queue.c * * Copyright (C) 2014 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -41,7 +41,7 @@ #include -#include +#include #include "iob.h" diff --git a/drivers/iob/iob_initialize.c b/mm/iob/iob_initialize.c similarity index 98% rename from drivers/iob/iob_initialize.c rename to mm/iob/iob_initialize.c index 423f90898c..1662fe4772 100644 --- a/drivers/iob/iob_initialize.c +++ b/mm/iob/iob_initialize.c @@ -1,5 +1,5 @@ /**************************************************************************** - * drivers/iob/iob_initialize.c + * mm/iob/iob_initialize.c * * Copyright (C) 2014 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -42,7 +42,7 @@ #include #include -#include +#include #include "iob.h" diff --git a/drivers/iob/iob_pack.c b/mm/iob/iob_pack.c similarity index 98% rename from drivers/iob/iob_pack.c rename to mm/iob/iob_pack.c index 0a2b0f66c5..62799b2238 100644 --- a/drivers/iob/iob_pack.c +++ b/mm/iob/iob_pack.c @@ -1,5 +1,5 @@ /**************************************************************************** - * drivers/iob/iob_pack.c + * mm/iob/iob_pack.c * * Copyright (C) 2014 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -41,7 +41,7 @@ #include -#include +#include #include "iob.h" diff --git a/drivers/iob/iob_peek_queue.c b/mm/iob/iob_peek_queue.c similarity index 98% rename from drivers/iob/iob_peek_queue.c rename to mm/iob/iob_peek_queue.c index 7bc81bfa12..b1151be121 100644 --- a/drivers/iob/iob_peek_queue.c +++ b/mm/iob/iob_peek_queue.c @@ -1,5 +1,5 @@ /**************************************************************************** - * drivers/iob/iob_peek_queue.c + * mm/iob/iob_peek_queue.c * * Copyright (C) 2014 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -41,7 +41,7 @@ #include -#include +#include #include "iob.h" diff --git a/drivers/iob/iob_remove_queue.c b/mm/iob/iob_remove_queue.c similarity index 98% rename from drivers/iob/iob_remove_queue.c rename to mm/iob/iob_remove_queue.c index 4bfbca3056..49e93d765d 100644 --- a/drivers/iob/iob_remove_queue.c +++ b/mm/iob/iob_remove_queue.c @@ -1,5 +1,5 @@ /**************************************************************************** - * drivers/iob/iob_remove_queue.c + * mm/iob/iob_remove_queue.c * * Copyright (C) 2014 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -41,7 +41,7 @@ #include -#include +#include #include "iob.h" diff --git a/drivers/iob/iob_test.c b/mm/iob/iob_test.c similarity index 99% rename from drivers/iob/iob_test.c rename to mm/iob/iob_test.c index ee6b90d886..b3b2ff9a45 100644 --- a/drivers/iob/iob_test.c +++ b/mm/iob/iob_test.c @@ -1,5 +1,5 @@ /**************************************************************************** - * drivers/iob/iob_test.c + * mm/iob/iob_test.c * Unit test driver. This is of historical interest only since it requires * and custom build setup and modifications to the iob source and header * files. diff --git a/drivers/iob/iob_trimhead.c b/mm/iob/iob_trimhead.c similarity index 98% rename from drivers/iob/iob_trimhead.c rename to mm/iob/iob_trimhead.c index 938c040711..0373c5dd8f 100644 --- a/drivers/iob/iob_trimhead.c +++ b/mm/iob/iob_trimhead.c @@ -1,5 +1,5 @@ /**************************************************************************** - * drivers/iob/iob_trimhead.c + * mm/iob/iob_trimhead.c * * Copyright (C) 2014, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -42,7 +42,7 @@ #include #include -#include +#include #include "iob.h" diff --git a/drivers/iob/iob_trimhead_queue.c b/mm/iob/iob_trimhead_queue.c similarity index 98% rename from drivers/iob/iob_trimhead_queue.c rename to mm/iob/iob_trimhead_queue.c index 7ba393366f..2177720da7 100644 --- a/drivers/iob/iob_trimhead_queue.c +++ b/mm/iob/iob_trimhead_queue.c @@ -1,5 +1,5 @@ /**************************************************************************** - * drivers/iob/iob_trimhead_queue.c + * mm/iob/iob_trimhead_queue.c * * Copyright (C) 2014 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -42,7 +42,7 @@ #include #include -#include +#include #include "iob.h" diff --git a/drivers/iob/iob_trimtail.c b/mm/iob/iob_trimtail.c similarity index 98% rename from drivers/iob/iob_trimtail.c rename to mm/iob/iob_trimtail.c index b876de1552..1e2804f4c5 100644 --- a/drivers/iob/iob_trimtail.c +++ b/mm/iob/iob_trimtail.c @@ -1,5 +1,5 @@ /**************************************************************************** - * drivers/iob/iob_trimtail.c + * mm/iob/iob_trimtail.c * * Copyright (C) 2014, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -42,7 +42,7 @@ #include #include -#include +#include #include "iob.h" diff --git a/net/devif/Make.defs b/net/devif/Make.defs index fb16f653ba..f46aa5c26a 100644 --- a/net/devif/Make.defs +++ b/net/devif/Make.defs @@ -50,7 +50,7 @@ endif # I/O buffer chain support required? -ifeq ($(CONFIG_DRIVERS_IOB),y) +ifeq ($(CONFIG_MM_IOB),y) NET_CSRCS += devif_iobsend.c endif diff --git a/net/devif/devif.h b/net/devif/devif.h index baa1644c63..df45f7d8be 100644 --- a/net/devif/devif.h +++ b/net/devif/devif.h @@ -466,7 +466,7 @@ void devif_send(FAR struct net_driver_s *dev, FAR const void *buf, int len); * ****************************************************************************/ -#ifdef CONFIG_DRIVERS_IOB +#ifdef CONFIG_MM_IOB struct iob_s; void devif_iob_send(FAR struct net_driver_s *dev, FAR struct iob_s *buf, unsigned int len, unsigned int offset); diff --git a/net/devif/devif_iobsend.c b/net/devif/devif_iobsend.c index ff4b4e8433..5575a2b60c 100644 --- a/net/devif/devif_iobsend.c +++ b/net/devif/devif_iobsend.c @@ -43,10 +43,10 @@ #include #include -#include +#include #include -#ifdef CONFIG_DRIVERS_IOB +#ifdef CONFIG_MM_IOB /**************************************************************************** * Pre-processor Definitions @@ -113,5 +113,5 @@ void devif_iob_send(FAR struct net_driver_s *dev, FAR struct iob_s *iob, #endif } -#endif /* CONFIG_DRIVERS_IOB */ +#endif /* CONFIG_MM_IOB */ diff --git a/net/sixlowpan/sixlowpan_framer.c b/net/sixlowpan/sixlowpan_framer.c index d52a5cd30c..eef8583dd3 100644 --- a/net/sixlowpan/sixlowpan_framer.c +++ b/net/sixlowpan/sixlowpan_framer.c @@ -72,7 +72,7 @@ * ****************************************************************************/ -static bool sixlowpan_anyaddrnull(FAR uint8_t *addr, uint8_t addrlen) +static bool sixlowpan_anyaddrnull(FAR const uint8_t *addr, uint8_t addrlen) { while (addrlen-- > 0) { diff --git a/net/socket/recvfrom.c b/net/socket/recvfrom.c index 4a3ad32234..ab16ee9c66 100644 --- a/net/socket/recvfrom.c +++ b/net/socket/recvfrom.c @@ -59,7 +59,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/net/tcp/Kconfig b/net/tcp/Kconfig index 00f2519c3c..fac41794dc 100644 --- a/net/tcp/Kconfig +++ b/net/tcp/Kconfig @@ -70,7 +70,7 @@ config NET_MAX_LISTENPORTS config NET_TCP_READAHEAD bool "Enable TCP/IP read-ahead buffering" default y - select DRIVERS_IOB + select MM_IOB ---help--- Read-ahead buffers allows buffering of TCP/IP packets when there is no receive in place to catch the TCP packet. In that case, the packet @@ -91,7 +91,7 @@ endif # NET_TCP_READAHEAD config NET_TCP_WRITE_BUFFERS bool "Enable TCP/IP write buffering" default n - select DRIVERS_IOB + select MM_IOB ---help--- Write buffers allows buffering of ongoing TCP/IP packets, providing for higher performance, streamed output. diff --git a/net/tcp/tcp.h b/net/tcp/tcp.h index 54808a3075..8d25bf6ff0 100644 --- a/net/tcp/tcp.h +++ b/net/tcp/tcp.h @@ -45,7 +45,7 @@ #include #include -#include +#include #include #if defined(CONFIG_NET_TCP) && !defined(CONFIG_NET_TCP_NO_STACK) diff --git a/net/tcp/tcp_callback.c b/net/tcp/tcp_callback.c index 5c467bae29..3a16c86d03 100644 --- a/net/tcp/tcp_callback.c +++ b/net/tcp/tcp_callback.c @@ -45,7 +45,7 @@ #include #include -#include +#include #include #include #include diff --git a/net/tcp/tcp_send_buffered.c b/net/tcp/tcp_send_buffered.c index 4000d694df..f88b9d5f2b 100644 --- a/net/tcp/tcp_send_buffered.c +++ b/net/tcp/tcp_send_buffered.c @@ -64,7 +64,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/net/tcp/tcp_wrbuffer.c b/net/tcp/tcp_wrbuffer.c index a74ee6f3a1..2a4b7c65ca 100644 --- a/net/tcp/tcp_wrbuffer.c +++ b/net/tcp/tcp_wrbuffer.c @@ -55,7 +55,7 @@ #include #include -#include +#include #include "tcp/tcp.h" diff --git a/net/tcp/tcp_wrbuffer_dump.c b/net/tcp/tcp_wrbuffer_dump.c index 7e961278d1..ad92bfb904 100644 --- a/net/tcp/tcp_wrbuffer_dump.c +++ b/net/tcp/tcp_wrbuffer_dump.c @@ -42,7 +42,7 @@ #include #include -#include +#include #include "tcp/tcp.h" diff --git a/net/udp/Kconfig b/net/udp/Kconfig index e8c5d53b2f..a4a16fde08 100644 --- a/net/udp/Kconfig +++ b/net/udp/Kconfig @@ -60,7 +60,7 @@ config NET_RXAVAIL config NET_UDP_READAHEAD bool "Enable UDP/IP read-ahead buffering" default y - select DRIVERS_IOB + select MM_IOB endif # NET_UDP && !NET_UDP_NO_STACK endmenu # UDP Networking diff --git a/net/udp/udp.h b/net/udp/udp.h index 73ac15fbaf..83197afae3 100644 --- a/net/udp/udp.h +++ b/net/udp/udp.h @@ -48,7 +48,7 @@ #include #ifdef CONFIG_NET_UDP_READAHEAD -# include +# include #endif #if defined(CONFIG_NET_UDP) && !defined(CONFIG_NET_UDP_NO_STACK) diff --git a/wireless/ieee802154/Kconfig b/wireless/ieee802154/Kconfig index ff64c06d84..670ea474f3 100644 --- a/wireless/ieee802154/Kconfig +++ b/wireless/ieee802154/Kconfig @@ -6,7 +6,7 @@ config WIRELESS_IEEE802154 bool "IEEE 802.15.4 Wireless Support" default n - select DRIVERS_IOB + select MM_IOB ---help--- Enables support for the IEEE 802.14.5 Wireless library. diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index 1da758082c..738eb47f30 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -50,7 +50,7 @@ #include #include -#include +#include #include #include diff --git a/wireless/ieee802154/mac802154_device.c b/wireless/ieee802154/mac802154_device.c index a4eb93b656..21aae1c50f 100644 --- a/wireless/ieee802154/mac802154_device.c +++ b/wireless/ieee802154/mac802154_device.c @@ -50,7 +50,7 @@ #include #include -#include +#include #include #include diff --git a/wireless/ieee802154/mac802154_indalloc.c b/wireless/ieee802154/mac802154_indalloc.c index 5e05c5c09e..375cda69aa 100644 --- a/wireless/ieee802154/mac802154_indalloc.c +++ b/wireless/ieee802154/mac802154_indalloc.c @@ -44,7 +44,7 @@ #include -#include +#include #include diff --git a/wireless/ieee802154/mac802154_netdev.c b/wireless/ieee802154/mac802154_netdev.c index f510cf7f5d..b09ea4493c 100644 --- a/wireless/ieee802154/mac802154_netdev.c +++ b/wireless/ieee802154/mac802154_netdev.c @@ -54,7 +54,7 @@ #include #include #include -#include +#include #include #include #include -- GitLab From de6bffe713e540061c76a4be278c0d12b1d19adb Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 9 May 2017 11:32:44 -0600 Subject: [PATCH 773/990] Update some README files --- Documentation/README.html | 8 ++++++++ README.txt | 8 ++++++++ mm/iob/Make.defs | 2 +- mm/kmm_heap/Make.defs | 4 +++- 4 files changed, 20 insertions(+), 2 deletions(-) diff --git a/Documentation/README.html b/Documentation/README.html index 726f4aa3cf..02a3042b48 100644 --- a/Documentation/README.html +++ b/Documentation/README.html @@ -164,14 +164,22 @@ nuttx/ | | `- README.txt | |- nucleo-f072rb/ | | `- README.txt + | |- nucleo-f091rc/ + | | `- README.txt | |- nucleo-f303re/ | | `- README.txt | |- nucleo-f334r8/ | | `- README.txt | |- nucleo-f4x1re/ | | `- README.txt + | |- nucleo-l432kc/ + | | `- README.txt + | |- nucleo-l452re/ + | | `- README.txt | |- nucleo-l476rg/ | | `- README.txt + | |- nucleo-l496zg/ + | | `- README.txt | |- nutiny-nuc120/ | | `- README.txt | |- olimex-efm32g880f129-stk/ diff --git a/README.txt b/README.txt index 334b501e51..b6144aca71 100644 --- a/README.txt +++ b/README.txt @@ -1536,14 +1536,22 @@ nuttx/ | | `- README.txt | |- nucleo-f072rb/ | | `- README.txt + | |- nucleo-f091rc/ + | | `- README.txt | |- nucleo-f303re/ | | `- README.txt | |- nucleo-f334r8/ | | `- README.txt | |- nucleo-f4x1re/ | | `- README.txt + | |- nucleo-l432kc/ + | | `- README.txt + | |- nucleo-l452re/ + | | `- README.txt | |- nucleo-l476rg/ | | `- README.txt + | |- nucleo-l496zg/ + | | `- README.txt | |- nutiny-nuc120/ | | `- README.txt | |- olimex-efm32g880f129-stk/ diff --git a/mm/iob/Make.defs b/mm/iob/Make.defs index 7c08edd7fb..bdfd11d7c1 100644 --- a/mm/iob/Make.defs +++ b/mm/iob/Make.defs @@ -53,4 +53,4 @@ DEPPATH += --dep-path iob VPATH += :iob CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)$(DELIM)mm$(DELIM)iob} -endif +endif # CONFIG_MM_IOB diff --git a/mm/kmm_heap/Make.defs b/mm/kmm_heap/Make.defs index 9f7ac447a3..66ac454bde 100644 --- a/mm/kmm_heap/Make.defs +++ b/mm/kmm_heap/Make.defs @@ -36,6 +36,7 @@ # Kernel heap allocator ifeq ($(CONFIG_MM_KERNEL_HEAP),y) + CSRCS += kmm_initialize.c kmm_addregion.c kmm_sem.c CSRCS += kmm_brkaddr.c kmm_calloc.c kmm_extend.c kmm_free.c kmm_mallinfo.c CSRCS += kmm_malloc.c kmm_memalign.c kmm_realloc.c kmm_zalloc.c @@ -52,4 +53,5 @@ endif DEPPATH += --dep-path kmm_heap VPATH += :kmm_heap -endif + +endif # CONFIG_MM_KERNEL_HEAP -- GitLab From 1186cd4e566812138376a3acba46893c88b5071b Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Tue, 9 May 2017 17:19:44 -0400 Subject: [PATCH 774/990] wireless/ieee802154: Fixes missing handle of read/write being able to be interrupted --- wireless/ieee802154/mac802154.c | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index 738eb47f30..54daa38195 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -1482,7 +1482,11 @@ int mac802154_req_data(MACHANDLE mac, priv->radio->ops->txnotify_csma(priv->radio); - sem_wait(&trans.sem); + ret = sem_wait(&trans.sem); + if (ret < 0) + { + return -EINTR; + } } } -- GitLab From 806dcd9a47b2378015271deddacb3fc6e2b58fc1 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Tue, 9 May 2017 17:20:47 -0400 Subject: [PATCH 775/990] wireless/ieee802154: Brings closer to Nuttx coding style --- drivers/wireless/ieee802154/mrf24j40.c | 16 +- .../wireless/ieee802154/ieee802154_mac.h | 41 ++--- .../wireless/ieee802154/ieee802154_radio.h | 4 +- net/sixlowpan/sixlowpan_framer.c | 2 +- net/sixlowpan/sixlowpan_utils.c | 4 +- wireless/ieee802154/mac802154.c | 143 +++++++++--------- wireless/ieee802154/mac802154.h | 4 +- wireless/ieee802154/mac802154_device.c | 1 - 8 files changed, 113 insertions(+), 102 deletions(-) diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c index e4553a3b8c..fe022d5114 100644 --- a/drivers/wireless/ieee802154/mrf24j40.c +++ b/drivers/wireless/ieee802154/mrf24j40.c @@ -234,10 +234,10 @@ static int mrf24j40_txnotify_csma(FAR struct ieee802154_radio_s *radio); static int mrf24j40_txnotify_gts(FAR struct ieee802154_radio_s *radio); static int mrf24j40_get_attr(FAR struct ieee802154_radio_s *radio, enum ieee802154_pib_attr_e pib_attr, - FAR union ieee802154_attr_val_u *attr_value); + FAR union ieee802154_attr_u *attrval); static int mrf24j40_set_attr(FAR struct ieee802154_radio_s *radio, enum ieee802154_pib_attr_e pib_attr, - FAR const union ieee802154_attr_val_u *attr_value); + FAR const union ieee802154_attr_u *attrval); /**************************************************************************** * Private Data @@ -349,7 +349,7 @@ static int mrf24j40_txnotify_gts(FAR struct ieee802154_radio_s *radio) static int mrf24j40_get_attr(FAR struct ieee802154_radio_s *radio, enum ieee802154_pib_attr_e pib_attr, - FAR union ieee802154_attr_val_u *attr_value) + FAR union ieee802154_attr_u *attrval) { FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)radio; int ret; @@ -358,7 +358,7 @@ static int mrf24j40_get_attr(FAR struct ieee802154_radio_s *radio, { case IEEE802154_PIB_MAC_EXTENDED_ADDR: { - memcpy(&attr_value->mac.eaddr[0], &dev->addr.eaddr[0], 8); + memcpy(&attrval->mac.eaddr[0], &dev->addr.eaddr[0], 8); ret = IEEE802154_STATUS_SUCCESS; } break; @@ -370,7 +370,7 @@ static int mrf24j40_get_attr(FAR struct ieee802154_radio_s *radio, static int mrf24j40_set_attr(FAR struct ieee802154_radio_s *radio, enum ieee802154_pib_attr_e pib_attr, - FAR const union ieee802154_attr_val_u *attr_value) + FAR const union ieee802154_attr_u *attrval) { FAR struct mrf24j40_radio_s *dev = (FAR struct mrf24j40_radio_s *)radio; int ret; @@ -379,13 +379,13 @@ static int mrf24j40_set_attr(FAR struct ieee802154_radio_s *radio, { case IEEE802154_PIB_MAC_EXTENDED_ADDR: { - mrf24j40_seteaddr(dev, &attr_value->mac.eaddr[0]); + mrf24j40_seteaddr(dev, &attrval->mac.eaddr[0]); ret = IEEE802154_STATUS_SUCCESS; } break; case IEEE802154_PIB_MAC_PROMISCUOUS_MODE: { - if (attr_value->mac.promisc_mode) + if (attrval->mac.promisc_mode) { mrf24j40_setrxmode(dev, MRF24J40_RXMODE_PROMISC); } @@ -399,7 +399,7 @@ static int mrf24j40_set_attr(FAR struct ieee802154_radio_s *radio, break; case IEEE802154_PIB_MAC_RX_ON_WHEN_IDLE: { - dev->rxonidle = attr_value->mac.rxonidle; + dev->rxonidle = attrval->mac.rxonidle; mrf24j40_rxenable(dev, dev->rxonidle); } break; diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index 2c6a846af7..15963b46e1 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -299,7 +299,7 @@ enum ieee802154_pib_attr_e IEEE802154_PIB_MAC_MIN_BE, IEEE802154_PIB_MAC_LIFS_PERIOD, IEEE802154_PIB_MAC_SIFS_PERIOD, - IEEE802154_PIB_MAC_PAN_ID, + IEEE802154_PIB_MAC_PANID, IEEE802154_PIB_MAC_PROMISCUOUS_MODE, IEEE802154_PIB_MAC_RANGING_SUPPORT, IEEE802154_PIB_MAC_RESPONSE_WAIT_TIME, @@ -329,6 +329,13 @@ enum ieee802154_pib_attr_e IEEE802154_PIB_MAC_PANCOORD_SHORT_ADDR, }; +enum ieee802154_devmode_e +{ + IEEE802154_DEVMODE_ENDPOINT, + IEEE802154_DEVMODE_COORD, + IEEE802154_DEVMODE_PANCOORD +}; + #define IEEE802154_EADDR_LEN 8 /* IEEE 802.15.4 Device address @@ -338,7 +345,7 @@ enum ieee802154_pib_attr_e * Extended address + PAN id : PPPP/LLLLLLLLLLLLLLLL */ -enum ieee802154_addr_mode_e +enum ieee802154_addrmode_e { IEEE802154_ADDRMODE_NONE = 0, IEEE802154_ADDRMODE_SHORT = 2, @@ -349,7 +356,7 @@ struct ieee802154_addr_s { /* Address mode. Short or Extended */ - enum ieee802154_addr_mode_e mode; + enum ieee802154_addrmode_e mode; uint16_t panid; /* PAN identifier, can be * IEEE802154_PAN_UNSPEC */ @@ -549,7 +556,7 @@ union ieee802154_secattr_u /* TODO: Fill this out as we implement supported get/set commands */ }; -union ieee802154_attr_val_u +union ieee802154_attr_u { union ieee802154_macattr_u mac; union ieee802154_phyattr_u phy; @@ -574,7 +581,7 @@ enum ieee802154_scantype_e struct ieee802154_frame_meta_s { - enum ieee802154_addr_mode_e src_addr_mode; /* Source Address Mode */ + enum ieee802154_addrmode_e src_addrmode; /* Source Address Mode */ struct ieee802154_addr_s dest_addr; /* Destination Address */ uint8_t msdu_handle; /* Handle assoc. with MSDU */ @@ -1159,7 +1166,7 @@ struct ieee802154_scan_conf_s struct ieee802154_get_req_s { enum ieee802154_pib_attr_e pib_attr; - union ieee802154_attr_val_u attr_value; + union ieee802154_attr_u attrval; }; /***************************************************************************** @@ -1179,7 +1186,7 @@ struct ieee802154_get_req_s struct ieee802154_set_req_s { enum ieee802154_pib_attr_e pib_attr; - union ieee802154_attr_val_u attr_value; + union ieee802154_attr_u attrval; }; /***************************************************************************** @@ -1195,23 +1202,23 @@ struct ieee802154_set_req_s struct ieee802154_start_req_s { - uint16_t pan_id; - uint8_t ch_num; - uint8_t ch_page; + uint16_t panid; + uint8_t chnum; + uint8_t chpage; - uint32_t start_time : 24; - uint32_t beacon_order : 8; + uint32_t starttime : 24; + uint32_t beaconorder : 8; - uint8_t sf_order; + uint8_t superframeorder; - uint8_t pan_coord : 1; - uint8_t batt_life_ext : 1; - uint8_t coord_realign : 1; + uint8_t pancoord : 1; + uint8_t battlifeext : 1; + uint8_t coordrealign : 1; #ifdef CONFIG_IEEE802154_SECURITY /* Security information if enabled */ - struct ieee802154_security_s coord_realign; + struct ieee802154_security_s coordrealign; struct ieee802154_security_s beacon; #endif }; diff --git a/include/nuttx/wireless/ieee802154/ieee802154_radio.h b/include/nuttx/wireless/ieee802154/ieee802154_radio.h index fcbc7ec1b7..d3fcb5db74 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_radio.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_radio.h @@ -84,10 +84,10 @@ struct ieee802154_radioops_s CODE int (*txnotify_gts)(FAR struct ieee802154_radio_s *radio); CODE int (*get_attr) (FAR struct ieee802154_radio_s *radio, enum ieee802154_pib_attr_e pib_attr, - FAR union ieee802154_attr_val_u *attr_value); + FAR union ieee802154_attr_u *attrval); CODE int (*set_attr) (FAR struct ieee802154_radio_s *radio, enum ieee802154_pib_attr_e pib_attr, - FAR const union ieee802154_attr_val_u *attr_value); + FAR const union ieee802154_attr_u *attrval); }; struct ieee802154_radio_s diff --git a/net/sixlowpan/sixlowpan_framer.c b/net/sixlowpan/sixlowpan_framer.c index eef8583dd3..2d8d54480a 100644 --- a/net/sixlowpan/sixlowpan_framer.c +++ b/net/sixlowpan/sixlowpan_framer.c @@ -163,7 +163,7 @@ int sixlowpan_meta_data(FAR struct ieee802154_driver_s *ieee, /* Source address mode */ - meta->src_addr_mode = pktmeta->sextended != 0? + meta->src_addrmode = pktmeta->sextended != 0? IEEE802154_ADDRMODE_EXTENDED : IEEE802154_ADDRMODE_SHORT; diff --git a/net/sixlowpan/sixlowpan_utils.c b/net/sixlowpan/sixlowpan_utils.c index d04ce878c7..75da3ed556 100644 --- a/net/sixlowpan/sixlowpan_utils.c +++ b/net/sixlowpan/sixlowpan_utils.c @@ -195,7 +195,7 @@ int sixlowpan_src_panid(FAR struct ieee802154_driver_s *ieee, int ret; memcpy(arg.ifr_name, ieee->i_dev.d_ifname, IFNAMSIZ); - arg.u.getreq.pib_attr = IEEE802154_PIB_MAC_PAN_ID; + arg.u.getreq.pib_attr = IEEE802154_PIB_MAC_PANID; ret = dev->d_ioctl(dev, MAC802154IOC_MLME_GET_REQUEST, (unsigned long)((uintptr_t)&arg)); if (ret < 0) @@ -204,7 +204,7 @@ int sixlowpan_src_panid(FAR struct ieee802154_driver_s *ieee, return ret; } - *panid = arg.u.getreq.attr_value.mac.panid; + *panid = arg.u.getreq.attrval.mac.panid; return OK; } diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index 54daa38195..abf2ea2d31 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -161,7 +161,7 @@ struct ieee802154_privmac_s /* Holds all address information (Extended, Short) for Coordinator */ - struct ieee802154_addr_s coord_addr; + struct ieee802154_addr_s coordaddr; /* The maximum number of symbols to wait for an acknowledgement frame to * arrive following a transmitted data frame. [1] pg. 126 @@ -170,7 +170,7 @@ struct ieee802154_privmac_s * sure at the time what the range of reasonable values was. */ - uint32_t ack_wait_dur; + uint32_t ack_waitdur; /* The maximum time to wait either for a frame intended as a response to a * data request frame or for a broadcast frame following a beacon with the @@ -180,59 +180,59 @@ struct ieee802154_privmac_s * sure at the time what the range of reasonable values was. */ - uint32_t max_frame_wait_time; + uint32_t max_frame_waittime; /* The maximum time (in unit periods) that a transaction is stored by a * coordinator and indicated in its beacon. */ - uint16_t trans_persist_time; + uint16_t trans_persisttime; /* Contents of beacon payload */ uint8_t beacon_payload[IEEE802154_MAX_BEACON_PAYLOAD_LEN]; uint8_t beacon_payload_len; /* Length of beacon payload */ - uint8_t batt_life_ext_periods; /* # of backoff periods during which rx is + uint8_t battlifeext_periods; /* # of backoff periods during which rx is * enabled after the IFS following beacon */ uint8_t bsn; /* Seq. num added to tx beacon frame */ uint8_t dsn; /* Seq. num added to tx data or MAC frame */ - uint8_t max_retries; /* Max # of retries alloed after tx failure */ + uint8_t maxretries; /* Max # of retries alloed after tx failure */ /* The maximum time, in multiples of aBaseSuperframeDuration, a device shall * wait for a response command frame to be available following a request * command frame. [1] 128. */ - uint8_t resp_wait_time; + uint8_t resp_waittime; /* The total transmit duration (including PHY header and FCS) specified in * symbols. [1] pg. 129. */ - uint32_t tx_total_dur; + uint32_t tx_totaldur; /* Start of 32-bit bitfield */ - uint32_t is_assoc : 1; /* Are we associated to the PAN */ - uint32_t assoc_permit : 1; /* Are we allowing assoc. as a coord. */ - uint32_t auto_req : 1; /* Automatically send data req. if addr + uint32_t isassoc : 1; /* Are we associated to the PAN */ + uint32_t assocpermit : 1; /* Are we allowing assoc. as a coord. */ + uint32_t autoreq : 1; /* Automatically send data req. if addr * addr is in the beacon frame */ - uint32_t batt_life_ext : 1; /* Is BLE enabled */ - uint32_t gts_permit : 1; /* Is PAN Coord. accepting GTS reqs. */ - uint32_t promisc_mode : 1; /* Is promiscuous mode on? */ - uint32_t rng_support : 1; /* Does MAC sublayer support ranging */ - uint32_t rx_when_idle : 1; /* Recvr. on during idle periods */ + uint32_t battlifeext : 1; /* Is BLE enabled */ + uint32_t gtspermit : 1; /* Is PAN Coord. accepting GTS reqs. */ + uint32_t promisc : 1; /* Is promiscuous mode on? */ + uint32_t rngsupport : 1; /* Does MAC sublayer support ranging */ uint32_t sec_enabled : 1; /* Does MAC sublayer have security en. */ + uint32_t timestamp_support : 1; /* Does MAC layer supports timestamping */ - uint32_t max_csma_backoffs : 3; /* Max num backoffs for CSMA algorithm + uint32_t max_csmabackoffs : 3; /* Max num backoffs for CSMA algorithm * before declaring ch access failure */ - uint32_t beacon_order : 4; /* Freq. that beacon is transmitted */ + uint32_t beaconorder : 4; /* Freq. that beacon is transmitted */ - uint32_t superframe_order : 4; /* Length of active portion of outgoing + uint32_t superframeorder : 4; /* Length of active portion of outgoing * superframe, including the beacon */ /* The offset, measured is symbols, between the symbol boundary at which the @@ -241,27 +241,30 @@ struct ieee802154_privmac_s * the frames [1] pg. 129. */ - uint32_t sync_symb_offset : 12; + uint32_t sync_symboffset : 12; /* End of 32-bit bitfield */ /* Start of 32-bit bitfield */ - uint32_t beacon_tx_time : 24; /* Time of last beacon transmit */ - uint32_t min_be : 4; /* Min value of backoff exponent (BE) */ - uint32_t max_be : 4; /* Max value of backoff exponent (BE) */ + uint32_t beacon_txtime : 24; /* Time of last beacon transmit */ + uint32_t minbe : 4; /* Min value of backoff exponent (BE) */ + uint32_t maxbe : 4; /* Max value of backoff exponent (BE) */ /* End of 32-bit bitfield */ /* Start of 32-bit bitfield */ - uint32_t tx_ctrl_active_dur : 17; /* Duration for which tx is permitted to - * be active */ - uint32_t tx_ctrl_pause_dur : 1; /* Duration after tx before another tx is + uint32_t txctrl_activedur : 17; /* Duration for which tx is permitted to + * be active */ + uint32_t txctrl_pausedur : 1; /* Duration after tx before another tx is * permitted. 0=2000, 1= 10000 */ - uint32_t timestamp_support : 1; /* Does MAC layer supports timestamping */ - uint32_t is_coord : 1; /* Is this device acting as coordinator */ - /* 12-bits remaining */ + + /* What type of device is this node acting as */ + + enum ieee802154_devmode_e devmode : 2; + + /* 11-bits remaining */ /* End of 32-bit bitfield. */ @@ -303,7 +306,7 @@ static void mac802154_rxframe(FAR const struct ieee802154_radiocb_s *radiocb, * Private Data ****************************************************************************/ -/* Map between ieee802154_addr_mode_e enum and actual address length */ +/* Map between ieee802154_addrmode_e enum and actual address length */ static const uint8_t mac802154_addr_length[4] = {0, 0, 2, 8}; @@ -491,37 +494,36 @@ static FAR struct ieee802154_data_ind_s * static int mac802154_defaultmib(FAR struct ieee802154_privmac_s *priv) { - priv->is_assoc = false; /* Not associated with a PAN */ - priv->assoc_permit = false; /* Device (if coord) not accepting association */ - priv->auto_req = true; /* Auto send data req if addr. in beacon */ - priv->batt_life_ext = false; /* BLE disabled */ + priv->isassoc = false; /* Not associated with a PAN */ + priv->assocpermit = false; /* Device (if coord) not accepting association */ + priv->autoreq = true; /* Auto send data req if addr. in beacon */ + priv->battlifeext = false; /* BLE disabled */ priv->beacon_payload_len = 0; /* Beacon payload NULL */ - priv->beacon_order = 15; /* Non-beacon enabled network */ - priv->superframe_order = 15; /* Length of active portion of outgoing SF */ - priv->beacon_tx_time = 0; /* Device never sent a beacon */ + priv->beaconorder = 15; /* Non-beacon enabled network */ + priv->superframeorder = 15; /* Length of active portion of outgoing SF */ + priv->beacon_txtime = 0; /* Device never sent a beacon */ #warning Set BSN and DSN to random values! priv->bsn = 0; priv->dsn = 0; - priv->gts_permit = true; /* PAN Coord accepting GTS requests */ - priv->min_be = 3; /* Min value of backoff exponent (BE) */ - priv->max_be = 5; /* Max value of backoff exponent (BE) */ - priv->max_csma_backoffs = 4; /* Max # of backoffs before failure */ - priv->max_retries = 3; /* Max # of retries allowed after failure */ - priv->promisc_mode = false; /* Device not in promiscuous mode */ - priv->rng_support = false; /* Ranging not yet supported */ - priv->resp_wait_time = 32; /* 32 SF durations */ - priv->rx_when_idle = false; /* Don't receive while idle */ + priv->gtspermit = true; /* PAN Coord accepting GTS requests */ + priv->minbe = 3; /* Min value of backoff exponent (BE) */ + priv->maxbe = 5; /* Max value of backoff exponent (BE) */ + priv->max_csmabackoffs = 4; /* Max # of backoffs before failure */ + priv->maxretries = 3; /* Max # of retries allowed after failure */ + priv->promisc = false; /* Device not in promiscuous mode */ + priv->rngsupport = false; /* Ranging not yet supported */ + priv->resp_waittime = 32; /* 32 SF durations */ priv->sec_enabled = false; /* Security disabled by default */ - priv->tx_total_dur = 0; /* 0 transmit duration */ + priv->tx_totaldur = 0; /* 0 transmit duration */ - priv->trans_persist_time = 0x01F4; + priv->trans_persisttime = 0x01F4; /* Reset the Coordinator address */ - priv->coord_addr.mode = IEEE802154_ADDRMODE_NONE; - priv->coord_addr.saddr = IEEE802154_SADDR_UNSPEC; - memcpy(&priv->coord_addr.eaddr[0], IEEE802154_EADDR_UNSPEC, + priv->coordaddr.mode = IEEE802154_ADDRMODE_NONE; + priv->coordaddr.saddr = IEEE802154_SADDR_UNSPEC; + memcpy(&priv->coordaddr.eaddr[0], IEEE802154_EADDR_UNSPEC, IEEE802154_EADDR_LEN); /* Reset the device's address */ @@ -545,6 +547,7 @@ static int mac802154_defaultmib(FAR struct ieee802154_privmac_s *priv) * macTimestampSupported * macTxControlActiveDuration * macTxControlPauseDuration + * macRxOnWhenIdle */ return OK; @@ -1111,7 +1114,7 @@ int mac802154_ioctl(MACHANDLE mac, int cmd, unsigned long arg) case MAC802154IOC_MLME_GET_REQUEST: { ret = mac802154_req_get(mac, macarg->getreq.pib_attr, - &macarg->getreq.attr_value); + &macarg->getreq.attrval); } break; case MAC802154IOC_MLME_GTS_REQUEST: @@ -1142,7 +1145,7 @@ int mac802154_ioctl(MACHANDLE mac, int cmd, unsigned long arg) case MAC802154IOC_MLME_SET_REQUEST: { ret = mac802154_req_set(mac, macarg->setreq.pib_attr, - &macarg->setreq.attr_value); + &macarg->setreq.attrval); } break; case MAC802154IOC_MLME_START_REQUEST: @@ -1192,14 +1195,15 @@ int mac802154_get_mhrlen(MACHANDLE mac, * to NONE */ if (meta->dest_addr.mode == IEEE802154_ADDRMODE_NONE && - meta->src_addr_mode == IEEE802154_ADDRMODE_NONE) + meta->src_addrmode == IEEE802154_ADDRMODE_NONE) { return -EINVAL; } /* The source address can only be set to NONE if the device is the PAN coord */ - if (meta->src_addr_mode == IEEE802154_ADDRMODE_NONE && !priv->is_coord) + if (meta->src_addrmode == IEEE802154_ADDRMODE_NONE && + priv->devmode != IEEE802154_DEVMODE_PANCOORD) { return -EINVAL; } @@ -1210,14 +1214,14 @@ int mac802154_get_mhrlen(MACHANDLE mac, /* Add the source address length */ - ret += mac802154_addr_length[ meta->src_addr_mode]; + ret += mac802154_addr_length[ meta->src_addrmode]; /* If both destination and source addressing information is present, the MAC * sublayer shall compare the destination and source PAN identifiers. * [1] pg. 41. */ - if (meta->src_addr_mode != IEEE802154_ADDRMODE_NONE && + if (meta->src_addrmode != IEEE802154_ADDRMODE_NONE && meta->dest_addr.mode != IEEE802154_ADDRMODE_NONE) { /* If the PAN identifiers are identical, the PAN ID Compression field @@ -1236,7 +1240,7 @@ int mac802154_get_mhrlen(MACHANDLE mac, * PAN ID if the respective address is included */ - if (meta->src_addr_mode != IEEE802154_ADDRMODE_NONE) + if (meta->src_addrmode != IEEE802154_ADDRMODE_NONE) { ret += 2; /* 2 bytes for source PAN ID */ } @@ -1347,7 +1351,7 @@ int mac802154_req_data(MACHANDLE mac, * [1] pg. 41. */ - if (meta->src_addr_mode != IEEE802154_ADDRMODE_NONE && + if (meta->src_addrmode != IEEE802154_ADDRMODE_NONE && meta->dest_addr.mode != IEEE802154_ADDRMODE_NONE) { /* If the PAN identifiers are identical, the PAN ID Compression field @@ -1361,7 +1365,7 @@ int mac802154_req_data(MACHANDLE mac, } } - if (meta->src_addr_mode != IEEE802154_ADDRMODE_NONE) + if (meta->src_addrmode != IEEE802154_ADDRMODE_NONE) { /* If the destination address is not included, or if PAN ID Compression * is off, we need to include the Source PAN ID. @@ -1374,12 +1378,12 @@ int mac802154_req_data(MACHANDLE mac, mhr_len += 2; } - if (meta->src_addr_mode == IEEE802154_ADDRMODE_SHORT) + if (meta->src_addrmode == IEEE802154_ADDRMODE_SHORT) { memcpy(&frame->io_data[mhr_len], &priv->addr.saddr, 2); mhr_len += 2; } - else if (meta->src_addr_mode == IEEE802154_ADDRMODE_EXTENDED) + else if (meta->src_addrmode == IEEE802154_ADDRMODE_EXTENDED) { memcpy(&frame->io_data[mhr_len], &priv->addr.eaddr, IEEE802154_EADDR_LEN); @@ -1390,7 +1394,7 @@ int mac802154_req_data(MACHANDLE mac, /* Set the source addr mode inside the frame control field */ - *frame_ctrl |= (meta->src_addr_mode << IEEE802154_FRAMECTRL_SHIFT_SADDR); + *frame_ctrl |= (meta->src_addrmode << IEEE802154_FRAMECTRL_SHIFT_SADDR); /* Each time a data or a MAC command frame is generated, the MAC sublayer * shall copy the value of macDSN into the Sequence Number field of the MHR @@ -1458,7 +1462,8 @@ int mac802154_req_data(MACHANDLE mac, * error, since this really shouldn't be happening. */ - if (priv->is_coord && meta->dest_addr.mode != IEEE802154_ADDRMODE_NONE) + if (priv->devmode == IEEE802154_DEVMODE_PANCOORD && + meta->dest_addr.mode != IEEE802154_ADDRMODE_NONE) { /* Link the transaction into the indirect_trans list */ @@ -1681,7 +1686,7 @@ int mac802154_req_scan(MACHANDLE mac, FAR struct ieee802154_scan_req_s *req) ****************************************************************************/ int mac802154_req_get(MACHANDLE mac, enum ieee802154_pib_attr_e pib_attr, - FAR union ieee802154_attr_val_u *attr_value) + FAR union ieee802154_attr_u *attrval) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; @@ -1704,7 +1709,7 @@ int mac802154_req_get(MACHANDLE mac, enum ieee802154_pib_attr_e pib_attr, ****************************************************************************/ int mac802154_req_set(MACHANDLE mac, enum ieee802154_pib_attr_e pib_attr, - FAR const union ieee802154_attr_val_u *attr_value) + FAR const union ieee802154_attr_u *attrval) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; @@ -1716,12 +1721,12 @@ int mac802154_req_set(MACHANDLE mac, enum ieee802154_pib_attr_e pib_attr, { /* Set the MAC copy of the address in the table */ - memcpy(&priv->addr.eaddr[0], &attr_value->mac.eaddr[0], + memcpy(&priv->addr.eaddr[0], &attrval->mac.eaddr[0], IEEE802154_EADDR_LEN); /* Tell the radio about the attribute */ - priv->radio->ops->set_attr(priv->radio, pib_attr, attr_value); + priv->radio->ops->set_attr(priv->radio, pib_attr, attrval); ret = IEEE802154_STATUS_SUCCESS; } @@ -1732,7 +1737,7 @@ int mac802154_req_set(MACHANDLE mac, enum ieee802154_pib_attr_e pib_attr, * it along. */ - ret = priv->radio->ops->set_attr(priv->radio, pib_attr, attr_value); + ret = priv->radio->ops->set_attr(priv->radio, pib_attr, attrval); } break; } diff --git a/wireless/ieee802154/mac802154.h b/wireless/ieee802154/mac802154.h index 66fa5495ca..168bc33cf2 100644 --- a/wireless/ieee802154/mac802154.h +++ b/wireless/ieee802154/mac802154.h @@ -254,7 +254,7 @@ int mac802154_req_scan(MACHANDLE mac, FAR struct ieee802154_scan_req_s *req); ****************************************************************************/ int mac802154_req_get(MACHANDLE mac, enum ieee802154_pib_attr_e pib_attr, - FAR union ieee802154_attr_val_u *attr_value); + FAR union ieee802154_attr_u *attrval); /**************************************************************************** * Name: mac802154_req_set @@ -272,7 +272,7 @@ int mac802154_req_get(MACHANDLE mac, enum ieee802154_pib_attr_e pib_attr, ****************************************************************************/ int mac802154_req_set(MACHANDLE mac, enum ieee802154_pib_attr_e pib_attr, - FAR const union ieee802154_attr_val_u *attr_value); + FAR const union ieee802154_attr_u *attrval); /**************************************************************************** * Name: mac802154_req_start diff --git a/wireless/ieee802154/mac802154_device.c b/wireless/ieee802154/mac802154_device.c index 21aae1c50f..309ca2c99c 100644 --- a/wireless/ieee802154/mac802154_device.c +++ b/wireless/ieee802154/mac802154_device.c @@ -653,7 +653,6 @@ static ssize_t mac802154dev_write(FAR struct file *filep, /* Pass the request to the MAC layer */ ret = mac802154_req_data(dev->md_mac, &tx->meta, iob); - if (ret < 0) { wlerr("ERROR: req_data failed %d\n", ret); -- GitLab From 07c47b0ddee0582f58a9b70b641a8dd748a1498c Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Tue, 9 May 2017 17:22:30 -0400 Subject: [PATCH 776/990] wireless/ieee802154: Starts implementing START.request primitive --- wireless/ieee802154/mac802154.c | 90 ++++++++++++++++++++++++++++++++- 1 file changed, 89 insertions(+), 1 deletion(-) diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index abf2ea2d31..a345d81933 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -1758,7 +1758,95 @@ int mac802154_req_start(MACHANDLE mac, FAR struct ieee802154_start_req_s *req) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; - return -ENOTTY; + int ret; + + /* Get exclusive access to the MAC */ + + ret = mac802154_takesem(&priv->exclsem); + if (ret < 0) + { + wlerr("ERROR: mac802154_takesem failed: %d\n", ret); + return ret; + } + + /* When the CoordRealignment parameter is set to TRUE, the coordinator + * attempts to transmit a coordinator realignment command frame as described + * in 5.1.2.3.2. If the transmission of the coordinator realignment command + * fails due to a channel access failure, the MLME will not make any changes + * to the superframe configuration. (i.e., no PIB attributes will be changed). + * If the coordinator realignment command is successfully transmitted, the + * MLME updates the PIB attributes BeaconOrder, SuperframeOrder, PANId, + * ChannelPage, and ChannelNumber parameters. [1] pg. 106 + */ + + if (req->coordrealign) + { + /* TODO: Finish the realignment functionality */ + + return -ENOTTY; + } + + /* Set the PANID attribute */ + + priv->addr.panid = req->panid; + priv->radio->ops->set_attr(priv->radio, IEEE802154_PIB_MAC_PANID, + (FAR const union ieee802154_attr_u *)&req->panid); + + /* Set the radio attributes */ + priv->radio->ops->set_attr(priv->radio, IEEE802154_PIB_PHY_CURRENT_CHANNEL, + (FAR const union ieee802154_attr_u *)&req->chnum); + + priv->radio->ops->set_attr(priv->radio, IEEE802154_PIB_PHY_CURRENT_PAGE, + (FAR const union ieee802154_attr_u *)&req->chpage); + + /* Set the superframe order */ + + if(req->superframeorder > 15) + { + ret = -EINVAL; + goto errout; + } + + priv->superframeorder = req->superframeorder; + + /* Set the beacon order */ + + if(req->beaconorder > 15) + { + ret = -EINVAL; + goto errout; + } + + priv->beaconorder = req->beaconorder; + + if (req->pancoord) + { + priv->devmode = IEEE802154_DEVMODE_PANCOORD; + } + else + { + priv->devmode = IEEE802154_DEVMODE_COORD; + } + + /* If the BeaconOrder parameter is less than 15, the MLME sets macBattLifeExt to + * the value of the BatteryLifeExtension parameter. If the BeaconOrder parameter + * equals 15, the value of the BatteryLifeExtension parameter is ignored. + * [1] pg. 106 + */ + + if (priv->beaconorder < 15) + { + priv->battlifeext = req->battlifeext; + + /* TODO: Finish starting beacon enabled network */ + return -ENOTTY; + } + + return OK; + +errout: + mac802154_givesem(&priv->exclsem); + return ret; } /**************************************************************************** -- GitLab From 591f35be8717ce023a8f2bb95d433c6ca612a001 Mon Sep 17 00:00:00 2001 From: Stefan Kolb Date: Wed, 10 May 2017 07:56:17 -0600 Subject: [PATCH 777/990] =?UTF-8?q?I=20discovered=20a=20problem=20in=20the?= =?UTF-8?q?=20file=20drivers/serial/serial.c=20concerning=20the=20function?= =?UTF-8?q?=20uart=5Fclose(=E2=80=A6).=20In=20the=20case=20that=20a=20seri?= =?UTF-8?q?al=20device=20is=20opened=20with=20the=20flag=20O=5FNONBLOCK=20?= =?UTF-8?q?the=20function=20uart=5Fclose(=E2=80=A6)=20blocks=20until=20all?= =?UTF-8?q?=20data=20in=20the=20buffer=20is=20transmitted.=20The=20functio?= =?UTF-8?q?n=20close(=E2=80=A6)=20called=20on=20an=20handle=20opened=20wit?= =?UTF-8?q?h=20O=5FNONBLOCK=20should=20not=20block.=20The=20problem=20occu?= =?UTF-8?q?rred=20with=20a=20CDC/ACM=20device.?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Documentation/README.html | 2 +- drivers/serial/serial.c | 27 ++++++++++++++++----------- 2 files changed, 17 insertions(+), 12 deletions(-) diff --git a/Documentation/README.html b/Documentation/README.html index 02a3042b48..fe4dced9ad 100644 --- a/Documentation/README.html +++ b/Documentation/README.html @@ -8,7 +8,7 @@

      NuttX README Files

      -

      Last Updated: April 18, 2017

      +

      Last Updated: May 9, 2017

      diff --git a/drivers/serial/serial.c b/drivers/serial/serial.c index 85fded4e47..775fa3a97a 100644 --- a/drivers/serial/serial.c +++ b/drivers/serial/serial.c @@ -1,7 +1,7 @@ /************************************************************************************ * drivers/serial/serial.c * - * Copyright (C) 2007-2009, 2011-2013, 2016 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009, 2011-2013, 2016-2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -1207,26 +1207,31 @@ static int uart_close(FAR struct file *filep) uart_disablerxint(dev); - /* Now we wait for the transmit buffer to clear */ + /* Prevent blocking if the device is opened with O_NONBLOCK */ - while (dev->xmit.head != dev->xmit.tail) + if ((filep->f_oflags & O_NONBLOCK) == 0) { + /* Now we wait for the transmit buffer to clear */ + + while (dev->xmit.head != dev->xmit.tail) + { #ifndef CONFIG_DISABLE_SIGNALS - usleep(HALF_SECOND_USEC); + usleep(HALF_SECOND_USEC); #else - up_mdelay(HALF_SECOND_MSEC); + up_mdelay(HALF_SECOND_MSEC); #endif - } + } - /* And wait for the TX fifo to drain */ + /* And wait for the TX fifo to drain */ - while (!uart_txempty(dev)) - { + while (!uart_txempty(dev)) + { #ifndef CONFIG_DISABLE_SIGNALS - usleep(HALF_SECOND_USEC); + usleep(HALF_SECOND_USEC); #else - up_mdelay(HALF_SECOND_MSEC); + up_mdelay(HALF_SECOND_MSEC); #endif + } } /* Free the IRQ and disable the UART */ -- GitLab From 4f18b4042975fefc5bb67a924c7ddf17a46049b4 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Wed, 10 May 2017 08:25:39 -0600 Subject: [PATCH 778/990] mtd/config: erase block between block read and write --- arch/arm/src/tiva/tiva_flash.c | 3 +- arch/arm/src/tiva/tiva_flash.h | 59 ++++++++++++++++++++++++++++++++++ drivers/mtd/mtd_config.c | 29 +++++++++++++++-- include/nuttx/mtd/mtd.h | 16 ++------- 4 files changed, 90 insertions(+), 17 deletions(-) create mode 100644 arch/arm/src/tiva/tiva_flash.h diff --git a/arch/arm/src/tiva/tiva_flash.c b/arch/arm/src/tiva/tiva_flash.c index c606b18887..952cf215cd 100644 --- a/arch/arm/src/tiva/tiva_flash.c +++ b/arch/arm/src/tiva/tiva_flash.c @@ -57,6 +57,7 @@ #include "up_arch.h" #include "chip.h" +#include "tiva_flash.h" /**************************************************************************** * Pre-processor Definitions @@ -340,7 +341,7 @@ static int tiva_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg) * ****************************************************************************/ -FAR struct mtd_dev_s *up_flashinitialize(void) +FAR struct mtd_dev_s *tiva_flash_initialize(void) { /* Return the implementation-specific state structure as the MTD device */ diff --git a/arch/arm/src/tiva/tiva_flash.h b/arch/arm/src/tiva/tiva_flash.h new file mode 100644 index 0000000000..3f2b542569 --- /dev/null +++ b/arch/arm/src/tiva/tiva_flash.h @@ -0,0 +1,59 @@ +/************************************************************************************ + * arch/arm/src/tiva/tiva_flash.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_TIVA_TIVA_FLASH_H +#define __ARCH_ARM_SRC_TIVA_TIVA_FLASH_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +struct mtd_dev_s; /* Forward Reference */ + +/**************************************************************************** + * Name: tiva_flash_initialize + * + * Description: + * Create an initialized MTD device instance for internal flash. + * + ****************************************************************************/ + +struct mtd_dev_s *tiva_flash_initialize(void); + +#endif /* __ARCH_ARM_SRC_TIVA_TIVA_FLASH_H */ diff --git a/drivers/mtd/mtd_config.c b/drivers/mtd/mtd_config.c index ca6654b0e6..1502679548 100644 --- a/drivers/mtd/mtd_config.c +++ b/drivers/mtd/mtd_config.c @@ -245,7 +245,7 @@ errout: /**************************************************************************** * Name: mtdconfig_writebytes * - * Writes bytes to the contained MTD device. This will either usee + * Writes bytes to the contained MTD device. This will either use * the byte write function or if that is not available, the bwrite. * ****************************************************************************/ @@ -286,6 +286,17 @@ static int mtdconfig_writebytes(FAR struct mtdconfig_struct_s *dev, int offset, goto errout; } + /* Now erase the block */ + + ret = MTD_ERASE(dev->mtd, block, 1); + if (ret < 0) + { + /* Error erasing the block */ + + ret = -EIO; + goto errout; + } + index = offset - block * dev->blocksize; bytes_this_block = dev->blocksize - index; if (bytes_this_block > writelen) @@ -1035,8 +1046,12 @@ static int mtdconfig_setconfig(FAR struct mtdconfig_struct_s *dev, /* Allocate a temp block buffer */ dev->buffer = (FAR uint8_t *) kmm_malloc(dev->blocksize); + if (dev->buffer == NULL) + { + return -ENOMEM; + } - /* Read and vaidate the signature bytes */ + /* Read and validate the signature bytes */ retry: offset = mtdconfig_findfirstentry(dev, &hdr); @@ -1180,7 +1195,15 @@ retry_find: hdr.len = pdata->len; hdr.flags = MTD_ERASED_FLAGS; - mtdconfig_writebytes(dev, offset, (uint8_t *)&hdr, sizeof(hdr)); + ret = mtdconfig_writebytes(dev, offset, (uint8_t *)&hdr, sizeof(hdr)); + if (ret < 0) + { + /* Cannot write even header! */ + + ret = -EIO; + goto errout; + } + bytes = mtdconfig_writebytes(dev, offset + sizeof(hdr), pdata->configdata, pdata->len); if (bytes != pdata->len) diff --git a/include/nuttx/mtd/mtd.h b/include/nuttx/mtd/mtd.h index d0b8ab3ed7..859411b811 100644 --- a/include/nuttx/mtd/mtd.h +++ b/include/nuttx/mtd/mtd.h @@ -2,7 +2,7 @@ * include/nuttx/mtd/mtd.h * Memory Technology Device (MTD) interface * - * Copyright (C) 2009-2013, 2015 Gregory Nutt. All rights reserved. + * Copyright (C) 2009-2013, 2015, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -99,7 +99,7 @@ #endif #if defined(CONFIG_FS_PROCFS) && !defined(CONFIG_FS_PROCFS_EXCLUDE_MTD) -#define CONFIG_MTD_REGISTRATION 1 +# define CONFIG_MTD_REGISTRATION 1 #endif /**************************************************************************** @@ -548,16 +548,6 @@ struct qspi_dev_s; /* Forward reference */ FAR struct mtd_dev_s *n25qxxx_initialize(FAR struct qspi_dev_s *qspi, bool unprotect); -/**************************************************************************** - * Name: up_flashinitialize - * - * Description: - * Create an initialized MTD device instance for internal flash. - * - ****************************************************************************/ - -FAR struct mtd_dev_s *up_flashinitialize(void); - /**************************************************************************** * Name: filemtd_initialize * @@ -594,7 +584,7 @@ bool filemtd_isfilemtd(FAR struct mtd_dev_s* mtd); * * Description: * Registers MTD device with the procfs file system. This assigns a unique - * MTD number and associates the given device name, then add adds it to + * MTD number and associates the given device name, then adds it to * the list of registered devices. * * In an embedded system, this all is really unnecessary, but is provided -- GitLab From c2096f17d619acd9518acd27da7bb21f96258298 Mon Sep 17 00:00:00 2001 From: Floxx Date: Wed, 10 May 2017 19:56:02 +0200 Subject: [PATCH 779/990] Moved LIS3DSH from the I2C-dependent block to the SPI-block to make Make.defs consistent with the driver (SPI only) and drivers/sensors/Kconfig. --- drivers/sensors/Make.defs | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/drivers/sensors/Make.defs b/drivers/sensors/Make.defs index 7a5d5a0bba..74464abb7d 100644 --- a/drivers/sensors/Make.defs +++ b/drivers/sensors/Make.defs @@ -57,10 +57,6 @@ ifeq ($(CONFIG_LIS2DH),y) CSRCS += lis2dh.c endif -ifeq ($(CONFIG_LIS3DSH),y) - CSRCS += lis3dsh.c -endif - ifeq ($(CONFIG_LIS331DL),y) CSRCS += lis331dl.c endif @@ -126,6 +122,10 @@ ifeq ($(CONFIG_ADXL345_SPI),y) CSRCS += adxl345_spi.c endif +ifeq ($(CONFIG_LIS3DSH),y) + CSRCS += lis3dsh.c +endif + ifeq ($(CONFIG_MAX31855),y) CSRCS += max31855.c endif -- GitLab From 20727d17c3c8bbe6be6b3c1396f0f1507039fef0 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 10 May 2017 14:42:43 -0600 Subject: [PATCH 780/990] SYSLOG: Add option to buffer SYSLOG output to avoid interleaving. --- drivers/syslog/Kconfig | 33 +++ drivers/syslog/Make.defs | 2 +- drivers/syslog/README.txt | 3 + drivers/syslog/ramlog.c | 3 + drivers/syslog/syslog.h | 63 ++++- drivers/syslog/syslog_channel.c | 9 + drivers/syslog/syslog_chardev.c | 24 +- drivers/syslog/syslog_console.c | 9 +- drivers/syslog/syslog_consolechannel.c | 3 + drivers/syslog/syslog_devchannel.c | 3 + drivers/syslog/syslog_device.c | 338 +++++++++++++++++++------ drivers/syslog/syslog_emergstream.c | 2 +- drivers/syslog/syslog_filechannel.c | 3 + drivers/syslog/syslog_stream.c | 76 +++++- drivers/syslog/syslog_write.c | 107 ++++++++ drivers/syslog/vsyslog.c | 4 +- include/nuttx/streams.h | 14 +- include/nuttx/syslog/syslog.h | 10 +- 18 files changed, 581 insertions(+), 125 deletions(-) create mode 100644 drivers/syslog/syslog_write.c diff --git a/drivers/syslog/Kconfig b/drivers/syslog/Kconfig index eb5b455af6..de0d8a137f 100644 --- a/drivers/syslog/Kconfig +++ b/drivers/syslog/Kconfig @@ -11,6 +11,12 @@ config ARCH_SYSLOG bool default n +# Selected if the SYSLOG device supports multi-byte write operations + +config SYSLOG_WRITE + bool + default n + config RAMLOG bool "RAM log device support" default n @@ -76,6 +82,30 @@ config DRIVER_NOTE to read data from the in-memory, scheduler instrumentation "note" buffer. +config SYSLOG_BUFFER + bool "Use buffered output" + default n + depends on SYSLOG_WRITE + ---help--- + Enables an buffering logic that will be used to serialize debug + output from concurrent tasks. This enables allocation of one buffer + per thread, each of size CONFIG_SYSLOG_BUFSIZE. + + The use of SYSLOG buffering is optional. If not enabled, however, + then the output from multiple tasks that attempt to generate SYSLOG + output may be interleaved and difficult to read. + +config SYSLOG_BUFSIZE + int "Output buffer size" + default 32 + range 1 65535 + depends on SYSLOG_BUFFER + ---help--- + If CONFIG_SYSLOG_BUFFER is enabled, then CONFIG_SYSLOG_BUFSIZE + provides the size of the per-thread output buffer. Setting + CONFIG_SYSLOG_BUFSIZE to a value less than one effectly disables + output SYSLOG buffering. + config SYSLOG_INTBUFFER bool "Use interrupt buffer" default n @@ -108,6 +138,7 @@ choice config SYSLOG_CHAR bool "Log to a character device" + select SYSLOG_WRITE ---help--- Enable the generic character device for the SYSLOG. The full path to the SYSLOG device is provided by SYSLOG_DEVPATH. A valid character device (or @@ -126,6 +157,7 @@ config SYSLOG_CONSOLE bool "Log to /dev/console" depends on DEV_CONSOLE select SYSLOG_SERIAL_CONSOLE if SERIAL_CONSOLE + select SYSLOG_WRITE ---help--- Use the system console as a SYSLOG output device. @@ -140,6 +172,7 @@ endchoice config SYSLOG_FILE bool "Sylog file output" default n + select SYSLOG_WRITE ---help--- Build in support to use a file to collect SYSOG output. File SYSLOG channels differ from other SYSLOG channels in that they cannot be diff --git a/drivers/syslog/Make.defs b/drivers/syslog/Make.defs index 2cad218e5a..f363449839 100644 --- a/drivers/syslog/Make.defs +++ b/drivers/syslog/Make.defs @@ -38,7 +38,7 @@ # Include SYSLOG Infrastructure CSRCS += vsyslog.c syslog_stream.c syslog_emergstream.c syslog_channel.c -CSRCS += syslog_putc.c syslog_force.c syslog_flush.c +CSRCS += syslog_putc.c syslog_write.c syslog_force.c syslog_flush.c ifeq ($(CONFIG_SYSLOG_INTBUFFER),y) CSRCS += syslog_intbuffer.c diff --git a/drivers/syslog/README.txt b/drivers/syslog/README.txt index 2764f0e2ad..c0adaaa8da 100644 --- a/drivers/syslog/README.txt +++ b/drivers/syslog/README.txt @@ -129,6 +129,9 @@ SYSLOG Channels { /* I/O redirection methods */ + #ifdef CONFIG_SYSLOG_WRITE + syslog_write_t sc_write; /* Write multiple bytes */ + #endif syslog_putc_t sc_putc; /* Normal buffered output */ syslog_putc_t sc_force; /* Low-level output for interrupt handlers */ syslog_flush_t sc_flush; /* Flush buffered output (on crash) */ diff --git a/drivers/syslog/ramlog.c b/drivers/syslog/ramlog.c index d322710433..f6a09c8a4f 100644 --- a/drivers/syslog/ramlog.c +++ b/drivers/syslog/ramlog.c @@ -127,6 +127,9 @@ static int ramlog_poll(FAR struct file *filep, FAR struct pollfd *fds, #ifdef CONFIG_RAMLOG_SYSLOG static const struct syslog_channel_s g_ramlog_syslog_channel = { +#ifdef CONFIG_SYSLOG_WRITE + syslog_default_write, +#endif ramlog_putc, ramlog_putc, ramlog_flush diff --git a/drivers/syslog/syslog.h b/drivers/syslog/syslog.h index 67aedbb9f1..8a8872bd56 100644 --- a/drivers/syslog/syslog.h +++ b/drivers/syslog/syslog.h @@ -240,19 +240,57 @@ int syslog_flush_intbuffer(FAR const struct syslog_channel_s *channel, * Name: syslog_putc * * Description: - * This is the low-level system logging interface. + * This is the low-level, single character, system logging interface. * * Input Parameters: * ch - The character to add to the SYSLOG (must be positive). * * Returned Value: - * On success, the character is echoed back to the caller. A negated - * errno value is returned on any failure. + * On success, the character is echoed back to the caller. Minus one + * is returned on any failure with the errno set correctly. * ****************************************************************************/ int syslog_putc(int ch); +/**************************************************************************** + * Name: syslog_write + * + * Description: + * This is the low-level, multiple character, system logging interface. + * + * Input Parameters: + * buffer - The buffer containing the data to be output + * buflen - The number of bytes in the buffer + * + * Returned Value: + * On success, the number of characters written is returned. A negated + * errno value is returned on any failure. + * + ****************************************************************************/ + +ssize_t syslog_write(FAR const char *buffer, size_t buflen); + +/**************************************************************************** + * Name: syslog_default_write + * + * Description: + * This provides a default write method for syslog devices that do not + * support multiple byte writes This functions simply loops, outputting + * one cahracter at a time. + * + * Input Parameters: + * buffer - The buffer containing the data to be output + * buflen - The number of bytes in the buffer + * + * Returned Value: + * On success, the number of characters written is returned. A negated + * errno value is returned on any failure. + * + ****************************************************************************/ + +ssize_t syslog_default_write(FAR const char *buffer, size_t buflen); + /**************************************************************************** * Name: syslog_force * @@ -272,6 +310,25 @@ int syslog_putc(int ch); int syslog_force(int ch); +/**************************************************************************** + * Name: syslog_dev_write + * + * Description: + * This is the low-level, multile byte, system logging interface provided + * for the character driver interface. + * + * Input Parameters: + * buffer - The buffer containing the data to be output + * buflen - The number of bytes in the buffer + * + * Returned Value: + * On success, the character is echoed back to the caller. Minus one + * is returned on any failure with the errno set correctly. + * + ****************************************************************************/ + +ssize_t syslog_dev_write(FAR const char *buffer, size_t buflen); + /**************************************************************************** * Name: syslog_dev_putc * diff --git a/drivers/syslog/syslog_channel.c b/drivers/syslog/syslog_channel.c index a36cb6e70f..107bdae0c3 100644 --- a/drivers/syslog/syslog_channel.c +++ b/drivers/syslog/syslog_channel.c @@ -79,6 +79,9 @@ static int syslog_default_flush(void); #if defined(CONFIG_RAMLOG_SYSLOG) const struct syslog_channel_s g_default_channel = { +#ifdef CONFIG_SYSLOG_WRITE + syslog_default_write, +#endif ramlog_putc, ramlog_putc, syslog_default_flush @@ -86,6 +89,9 @@ const struct syslog_channel_s g_default_channel = #elif defined(HAVE_LOWPUTC) const struct syslog_channel_s g_default_channel = { +#ifdef CONFIG_SYSLOG_WRITE + syslog_default_write, +#endif up_putc, up_putc, syslog_default_flush @@ -93,6 +99,9 @@ const struct syslog_channel_s g_default_channel = #else const struct syslog_channel_s g_default_channel = { +#ifdef CONFIG_SYSLOG_WRITE + syslog_default_write, +#endif syslog_default_putc, syslog_default_putc, syslog_default_flush diff --git a/drivers/syslog/syslog_chardev.c b/drivers/syslog/syslog_chardev.c index b852db05a2..0db139ab82 100644 --- a/drivers/syslog/syslog_chardev.c +++ b/drivers/syslog/syslog_chardev.c @@ -56,8 +56,8 @@ * Private Function Prototypes ****************************************************************************/ -static ssize_t syslog_write(FAR struct file *filep, FAR const char *buffer, - size_t buflen); +static ssize_t syslog_chardev_write(FAR struct file *filep, + FAR const char *buffer, size_t buflen); /**************************************************************************** * Private Data @@ -68,7 +68,7 @@ static const struct file_operations syslog_fops = NULL, /* open */ NULL, /* close */ NULL, /* read */ - syslog_write, /* write */ + syslog_chardev_write, /* write */ NULL, /* seek */ NULL /* ioctl */ #ifndef CONFIG_DISABLE_POLL @@ -84,23 +84,13 @@ static const struct file_operations syslog_fops = ****************************************************************************/ /**************************************************************************** - * Name: syslog_write + * Name: syslog_chardev_write ****************************************************************************/ -static ssize_t syslog_write(FAR struct file *filep, FAR const char *buffer, - size_t len) +static ssize_t syslog_chardev_write(FAR struct file *filep, + FAR const char *buffer, size_t len) { - size_t nwritten; - int ret; - - for (nwritten = 0; nwritten < len; nwritten++) - { - int ch = *buffer++; - ret = syslog_putc(ch); - UNUSED(ret); - } - - return len; + return syslog_write(buffer, len); } /**************************************************************************** diff --git a/drivers/syslog/syslog_console.c b/drivers/syslog/syslog_console.c index 04a21d2ec9..b1a9cf2cb6 100644 --- a/drivers/syslog/syslog_console.c +++ b/drivers/syslog/syslog_console.c @@ -106,14 +106,7 @@ static ssize_t syslog_console_read(FAR struct file *filep, FAR char *buffer, static ssize_t syslog_console_write(FAR struct file *filep, FAR const char *buffer, size_t buflen) { - ssize_t ret = buflen; - - for (; buflen; buflen--) - { - syslog_putc(*buffer++); - } - - return ret; + return syslog_write(buffer, len); } /**************************************************************************** diff --git a/drivers/syslog/syslog_consolechannel.c b/drivers/syslog/syslog_consolechannel.c index 8ed6374ff6..1c338b0257 100644 --- a/drivers/syslog/syslog_consolechannel.c +++ b/drivers/syslog/syslog_consolechannel.c @@ -83,6 +83,9 @@ static int syslog_console_force(int ch); static const struct syslog_channel_s g_syslog_console_channel = { +#ifdef CONFIG_SYSLOG_WRITE + syslog_dev_write, +#endif syslog_dev_putc, #ifdef HAVE_LOWPUTC up_putc, diff --git a/drivers/syslog/syslog_devchannel.c b/drivers/syslog/syslog_devchannel.c index e0251efc8e..74805d59bf 100644 --- a/drivers/syslog/syslog_devchannel.c +++ b/drivers/syslog/syslog_devchannel.c @@ -74,6 +74,9 @@ static int syslog_devchan_force(int ch); static const struct syslog_channel_s g_syslog_dev_channel = { +#ifdef CONFIG_SYSLOG_WRITE + syslog_dev_write, +#endif #ifdef CONFIG_SYSLOG_CHAR_CRLF syslog_devchan_putc, #else diff --git a/drivers/syslog/syslog_device.c b/drivers/syslog/syslog_device.c index 862a3d2b5d..1978ec211c 100644 --- a/drivers/syslog/syslog_device.c +++ b/drivers/syslog/syslog_device.c @@ -184,6 +184,114 @@ static inline void syslog_dev_givesem(void) sem_post(&g_syslog_dev.sl_sem); } +/**************************************************************************** + * Name: syslog_dev_outputready + * + * Description: + * Ignore any output: + * + * (1) Before the SYSLOG device has been initialized. This could happen + * from debug output that occurs early in the boot sequence before + * syslog_dev_initialize() is called (SYSLOG_UNINITIALIZED). + * (2) While the device is being initialized. The case could happen if + * debug output is generated while syslog_dev_initialize() executes + * (SYSLOG_INITIALIZING). + * (3) While we are generating SYSLOG output. The case could happen if + * debug output is generated while syslog_dev_putc() executes + * (This case is actually handled inside of syslog_semtake()). + * (4) Any debug output generated from interrupt handlers. A disadvantage + * of using the generic character device for the SYSLOG is that it + * cannot handle debug output generated from interrupt level handlers. + * (5) Any debug output generated from the IDLE loop. The character + * driver interface is blocking and the IDLE thread is not permitted + * to block. + * (6) If an irrecoverable failure occurred during initialization. In + * this case, we won't ever bother to try again (ever). + * + * NOTE: That the third case is different. It applies only to the thread + * that currently holds the sl_sem sempaphore. Other threads should wait. + * that is why that case is handled in syslog_semtake(). + * + * Input Parameters: + * ch - The character to add to the SYSLOG (must be positive). + * + * Returned Value: + * On success, the character is echoed back to the caller. A negated + * errno value is returned on any failure. + * + ****************************************************************************/ + +static int syslog_dev_outputready(void) +{ + int ret; + + /* Cases (4) and (5) */ + + if (up_interrupt_context() || getpid() == 0) + { + return -ENOSYS; + } + + /* We can save checks in the usual case: That after the SYSLOG device + * has been successfully opened. + */ + + if (g_syslog_dev.sl_state != SYSLOG_OPENED) + { + /* Case (1) and (2) */ + + if (g_syslog_dev.sl_state == SYSLOG_UNINITIALIZED || + g_syslog_dev.sl_state == SYSLOG_INITIALIZING) + { + return -EAGAIN; /* Can't access the SYSLOG now... maybe next time? */ + } + + /* Case (6) */ + + if (g_syslog_dev.sl_state == SYSLOG_FAILURE) + { + return -ENXIO; /* There is no SYSLOG device */ + } + + /* syslog_dev_initialize() is called as soon as enough of the operating + * system is in place to support the open operation... but it is + * possible that the SYSLOG device is not yet registered at that time. + * In this case, we know that the system is sufficiently initialized + * to support an attempt to re-open the SYSLOG device. + * + * NOTE that the scheduler is locked. That is because we do not have + * fully initialized semaphore capability until the SYSLOG device is + * successfully initialized + */ + + sched_lock(); + if (g_syslog_dev.sl_state == SYSLOG_REOPEN) + { + /* Try again to initialize the device. We may do this repeatedly + * because the log device might be something that was not ready + * the first time that syslog_dev_initializee() was called (such as a + * USB serial device that has not yet been connected or a file in + * an NFS mounted file system that has not yet been mounted). + */ + + DEBUGASSERT(g_syslog_dev.sl_devpath != NULL); + ret = syslog_dev_initialize(g_syslog_dev.sl_devpath, + (int)g_syslog_dev.sl_oflags, + (int)g_syslog_dev.sl_mode); + if (ret < 0) + { + sched_unlock(); + return ret; + } + } + + sched_unlock(); + DEBUGASSERT(g_syslog_dev.sl_state == SYSLOG_OPENED); + } + + return OK; +} + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -355,119 +463,183 @@ int syslog_dev_uninitialize(void) #endif /* CONFIG_SYSLOG_FILE */ /**************************************************************************** - * Name: syslog_dev_putc + * Name: syslog_dev_write * * Description: - * This is the low-level system logging interface provided for the - * character driver interface. + * This is the low-level, multile byte, system logging interface provided + * for the character driver interface. * * Input Parameters: - * ch - The character to add to the SYSLOG (must be positive). + * buffer - The buffer containing the data to be output + * buflen - The number of bytes in the buffer * * Returned Value: - * On success, the character is echoed back to the caller. A negated - * errno value is returned on any failure. + * On success, the character is echoed back to the caller. Minus one + * is returned on any failure with the errno set correctly. * ****************************************************************************/ -int syslog_dev_putc(int ch) +ssize_t syslog_dev_write(FAR const char *buffer, size_t buflen) { - ssize_t nbytes; - uint8_t uch; + FAR const char *endptr; + ssize_t nwritten; + size_t writelen; int errcode; int ret; - /* Ignore any output: - * - * (1) Before the SYSLOG device has been initialized. This could happen - * from debug output that occurs early in the boot sequence before - * syslog_dev_initialize() is called (SYSLOG_UNINITIALIZED). - * (2) While the device is being initialized. The case could happen if - * debug output is generated while syslog_dev_initialize() executes - * (SYSLOG_INITIALIZING). - * (3) While we are generating SYSLOG output. The case could happen if - * debug output is generated while syslog_dev_putc() executes - * (This case is actually handled inside of syslog_semtake()). - * (4) Any debug output generated from interrupt handlers. A disadvantage - * of using the generic character device for the SYSLOG is that it - * cannot handle debug output generated from interrupt level handlers. - * (5) Any debug output generated from the IDLE loop. The character - * driver interface is blocking and the IDLE thread is not permitted - * to block. - * (6) If an irrecoverable failure occurred during initialization. In - * this case, we won't ever bother to try again (ever). - * - * NOTE: That the third case is different. It applies only to the thread - * that currently holds the sl_sem sempaphore. Other threads should wait. - * that is why that case is handled in syslog_semtake(). - */ - - /* Cases (4) and (5) */ + /* Check if the system is ready to do output operations */ - if (up_interrupt_context() || getpid() == 0) + ret = syslog_dev_outputready(); + if (ret < 0) { - errcode = ENOSYS; + errcode = -ret; goto errout_with_errcode; } - /* We can save checks in the usual case: That after the SYSLOG device - * has been successfully opened. - */ + /* The syslog device is ready for writing */ - if (g_syslog_dev.sl_state != SYSLOG_OPENED) + ret = syslog_dev_takesem(); + if (ret < 0) { - /* Case (1) and (2) */ + /* We probably already hold the semaphore and were probably + * re-entered by the logic kicked off by file_write(). + * We might also have been interrupted by a signal. Either + * way, we are outta here. + */ - if (g_syslog_dev.sl_state == SYSLOG_UNINITIALIZED || - g_syslog_dev.sl_state == SYSLOG_INITIALIZING) - { - errcode = EAGAIN; /* Can't access the SYSLOG now... maybe next time? */ - goto errout_with_errcode; - } + errcode = -ret; + goto errout_with_errcode; + } - /* Case (6) */ + /* Loop until we have output all characters */ - if (g_syslog_dev.sl_state == SYSLOG_FAILURE) + for (endptr = buffer; *endptr != '\n'; endptr++) + { + switch (*endptr) { - errcode = ENXIO; /* There is no SYSLOG device */ - goto errout_with_errcode; + case '\r': + { + /* Write everything up to this point, ignore the carriage + * return. + * + * - buffer points to next byte to output. + * - endptr points to the carriage return. + */ + + writelen = (size_t)((uintptr_t)endptr - (uintptr_t)buffer); + if (writelen > 0) + { + nwritten = file_write(&g_syslog_dev.sl_file, buffer, writelen); + if (nwritten < 0) + { + errcode = -nwritten; + goto errout_with_sem; + } + } + + /* Adjust pointers */ + + writelen++; /* Skip the carriage return */ + buffer += writelen; /* Points past the carriage return */ + } + break; + + case '\n': + { + /* Write everything up to this point, then add a carriage + * return and linefeed; + * + * - buffer points to next byte to output. + * - endptr points to the new line. + */ + + writelen = (size_t)((uintptr_t)endptr - (uintptr_t)buffer); + if (writelen > 0) + { + nwritten = file_write(&g_syslog_dev.sl_file, buffer, writelen); + if (nwritten < 0) + { + errcode = -nwritten; + goto errout_with_sem; + } + } + + nwritten = file_write(&g_syslog_dev.sl_file, g_syscrlf, 2); + if (nwritten < 0) + { + errcode = -nwritten; + goto errout_with_sem; + } + + /* Adjust pointers */ + + writelen++; /* Skip the line feed */ + buffer += writelen; /* Points past the line feed */ + } + break; + + default: + break; } + } - /* syslog_dev_initialize() is called as soon as enough of the operating - * system is in place to support the open operation... but it is - * possible that the SYSLOG device is not yet registered at that time. - * In this case, we know that the system is sufficiently initialized - * to support an attempt to re-open the SYSLOG device. - * - * NOTE that the scheduler is locked. That is because we do not have - * fully initialized semaphore capability until the SYSLOG device is - * successfully initialized - */ + /* Write any data at the end of the buffer. + * + * - buffer points to next byte to output. + * - endptr points to the NULL terminator. + */ - sched_lock(); - if (g_syslog_dev.sl_state == SYSLOG_REOPEN) + writelen = (size_t)((uintptr_t)endptr - (uintptr_t)buffer); + if (writelen > 0) + { + nwritten = file_write(&g_syslog_dev.sl_file, buffer, writelen); + if (nwritten < 0) { - /* Try again to initialize the device. We may do this repeatedly - * because the log device might be something that was not ready - * the first time that syslog_dev_initializee() was called (such as a - * USB serial device that has not yet been connected or a file in - * an NFS mounted file system that has not yet been mounted). - */ - - DEBUGASSERT(g_syslog_dev.sl_devpath != NULL); - ret = syslog_dev_initialize(g_syslog_dev.sl_devpath, - (int)g_syslog_dev.sl_oflags, - (int)g_syslog_dev.sl_mode); - if (ret < 0) - { - sched_unlock(); - errcode = -ret; - goto errout_with_errcode; - } + errcode = -nwritten; + goto errout_with_sem; } + } - sched_unlock(); - DEBUGASSERT(g_syslog_dev.sl_state == SYSLOG_OPENED); + syslog_dev_givesem(); + return buflen; + +errout_with_sem: + syslog_dev_givesem(); +errout_with_errcode: + set_errno(errcode); + return -1; +} + +/**************************************************************************** + * Name: syslog_dev_putc + * + * Description: + * This is the low-level, single character, system logging interface + * provided for the character driver interface. + * + * Input Parameters: + * ch - The character to add to the SYSLOG (must be positive). + * + * Returned Value: + * On success, the character is echoed back to the caller. Minus one + * is returned on any failure with the errno set correctly. + * + ****************************************************************************/ + +int syslog_dev_putc(int ch) +{ + ssize_t nbytes; + uint8_t uch; + int errcode; + int ret; + + /* Check if the system is ready to do output operations */ + + ret = syslog_dev_outputready(); + if (ret < 0) + { + errcode = -ret; + goto errout_with_errcode; } /* Ignore carriage returns */ diff --git a/drivers/syslog/syslog_emergstream.c b/drivers/syslog/syslog_emergstream.c index 2ea230b63c..8347c15a8e 100644 --- a/drivers/syslog/syslog_emergstream.c +++ b/drivers/syslog/syslog_emergstream.c @@ -99,7 +99,7 @@ static void emergstream_putc(FAR struct lib_outstream_s *this, int ch) * * Input parameters: * stream - User allocated, uninitialized instance of struct - * lib_lowoutstream_s to be initialized. + * lib_outstream_s to be initialized. * * Returned Value: * None (User allocated instance initialized). diff --git a/drivers/syslog/syslog_filechannel.c b/drivers/syslog/syslog_filechannel.c index efd5e541b3..1fcef4aa4a 100644 --- a/drivers/syslog/syslog_filechannel.c +++ b/drivers/syslog/syslog_filechannel.c @@ -72,6 +72,9 @@ static int syslog_file_force(int ch); static const struct syslog_channel_s g_syslog_file_channel = { +#ifdef CONFIG_SYSLOG_WRITE + syslog_dev_write, +#endif syslog_dev_putc, syslog_file_force, syslog_dev_flush, diff --git a/drivers/syslog/syslog_stream.c b/drivers/syslog/syslog_stream.c index 8305089b8b..3426b31691 100644 --- a/drivers/syslog/syslog_stream.c +++ b/drivers/syslog/syslog_stream.c @@ -1,7 +1,7 @@ /**************************************************************************** * drivers/syslog/syslog_stream.c * - * Copyright (C) 2012, 2016 Gregory Nutt. All rights reserved. + * Copyright (C) 2012, 2016-2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -59,6 +59,24 @@ static void syslogstream_putc(FAR struct lib_outstream_s *this, int ch) { +#ifdef CONFIG_SYSLOG_BUFFER + FAR struct lib_syslogstream_s *stream = (FAR struct lib_syslogstream_s *)this; + + /* Add the incoming character to the buffer */ + + stream->buf[stream->nbuf] = ch; + stream->nbuf++; + this->nput++; + + /* Is the buffer full? Did we encounter a new line? */ + + if (stream->nbuf >= CONFIG_SYSLOG_BUFSIZE || ch == '\n') + { + /* Yes.. then flush the buffer */ + + (void)this->flush(this); + } +#else int ret; /* Try writing until the write was successful or until an irrecoverable @@ -83,8 +101,45 @@ static void syslogstream_putc(FAR struct lib_outstream_s *this, int ch) * ignored in this context. */ } - while (errno == -EINTR); + while (get_errno() == -EINTR); +#endif +} + +/**************************************************************************** + * Name: syslogstream_flush + ****************************************************************************/ + +#ifdef CONFIG_SYSLOG_BUFFER +static int syslogstream_flush(FAR struct lib_outstream_s *this) +{ + FAR struct lib_syslogstream_s *stream = (FAR struct lib_syslogstream_s *)this; + int ret = OK; + + /* Is there anything buffered? */ + + if (stream->nbuf > 0) + { + /* Yes write the buffered data */ + + do + { + int status = syslog_write(stream->buf, stream->nbuf); + if (status < 0) + { + ret = -get_errno(); + } + else + { + stream->nbuf = 0; + ret = OK; + } + } + while (ret == -EINTR); + } + + return ret; } +#endif /**************************************************************************** * Public Functions @@ -99,16 +154,23 @@ static void syslogstream_putc(FAR struct lib_outstream_s *this, int ch) * * Input parameters: * stream - User allocated, uninitialized instance of struct - * lib_lowoutstream_s to be initialized. + * lib_syslogstream_s to be initialized. * * Returned Value: * None (User allocated instance initialized). * ****************************************************************************/ -void syslogstream(FAR struct lib_outstream_s *stream) +void syslogstream(FAR struct lib_syslogstream_s *stream) { - stream->put = syslogstream_putc; - stream->flush = lib_noflush; - stream->nput = 0; +#ifdef CONFIG_SYSLOG_BUFFER + stream->public.put = syslogstream_putc; + stream->public.flush = syslogstream_flush; + stream->public.nput = 0; + stream->nbuf = 0; +#else + stream->public.put = syslogstream_putc; + stream->public.flush = lib_noflush; + stream->public.nput = 0; +#endif } diff --git a/drivers/syslog/syslog_write.c b/drivers/syslog/syslog_write.c new file mode 100644 index 0000000000..a3100702ca --- /dev/null +++ b/drivers/syslog/syslog_write.c @@ -0,0 +1,107 @@ +/**************************************************************************** + * drivers/syslog/syslog_write.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include "syslog.h" + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: syslog_default_write + * + * Description: + * This provides a default write method for syslog devices that do not + * support multiple byte writes This functions simply loops, outputting + * one cahracter at a time. + * + * Input Parameters: + * buffer - The buffer containing the data to be output + * buflen - The number of bytes in the buffer + * + * Returned Value: + * On success, the number of characters written is returned. A negated + * errno value is returned on any failure. + * + ****************************************************************************/ + +ssize_t syslog_default_write(FAR const char *buffer, size_t buflen) +{ + size_t nwritten; + int ret; + + for (nwritten = 0; nwritten < buflen; nwritten++) + { + int ch = *buffer++; + ret = syslog_putc(ch); + UNUSED(ret); + } + + return buflen; +} + +/**************************************************************************** + * Name: syslog_write + * + * Description: + * This is the low-level, multiple character, system logging interface. + * + * Input Parameters: + * buffer - The buffer containing the data to be output + * buflen - The number of bytes in the buffer + * + * Returned Value: + * On success, the number of characters written is returned. A negated + * errno value is returned on any failure. + * + ****************************************************************************/ + +ssize_t syslog_write(FAR const char *buffer, size_t buflen) +{ +#ifdef CONFIG_SYSLOG_WRITE + return g_syslog_channel->sc_write(buffer, buflen); +#else + return syslog_default_write(buffer, buflen); +#endif +} diff --git a/drivers/syslog/vsyslog.c b/drivers/syslog/vsyslog.c index ba0d3726f8..5d45d83092 100644 --- a/drivers/syslog/vsyslog.c +++ b/drivers/syslog/vsyslog.c @@ -67,7 +67,7 @@ int _vsyslog(int priority, FAR const IPTR char *fmt, FAR va_list *ap) { - struct lib_outstream_s stream; + struct lib_syslogstream_s stream; #ifdef CONFIG_SYSLOG_TIMESTAMP struct timespec ts; int ret = -1; @@ -114,7 +114,7 @@ int _vsyslog(int priority, FAR const IPTR char *fmt, FAR va_list *ap) { /* Use the normal SYSLOG stream */ - syslogstream((FAR struct lib_outstream_s *)&stream); + syslogstream((FAR struct lib_syslogstream_s *)&stream); } #if defined(CONFIG_SYSLOG_TIMESTAMP) diff --git a/include/nuttx/streams.h b/include/nuttx/streams.h index 9d48c6d393..c8eae2d625 100644 --- a/include/nuttx/streams.h +++ b/include/nuttx/streams.h @@ -189,6 +189,18 @@ struct lib_rawsostream_s int fd; }; +/* This is a special stream that does buffered character I/O. NOTE that is + * CONFIG_SYSLOG_BUFFER is not defined, it is the same as struct lib_outstream_s */ + +struct lib_syslogstream_s +{ + struct lib_outstream_s public; +#ifdef CONFIG_SYSLOG_BUFFER + unsigned int nbuf; + char buf[CONFIG_SYSLOG_BUFSIZE]; +#endif +}; + /**************************************************************************** * Public Data ****************************************************************************/ @@ -360,7 +372,7 @@ void lib_nulloutstream(FAR struct lib_outstream_s *nulloutstream); * ****************************************************************************/ -void syslogstream(FAR struct lib_outstream_s *stream); +void syslogstream(FAR struct lib_syslogstream_s *stream); /**************************************************************************** * Name: emergstream diff --git a/include/nuttx/syslog/syslog.h b/include/nuttx/syslog/syslog.h index 01de19736d..bce437d7a7 100644 --- a/include/nuttx/syslog/syslog.h +++ b/include/nuttx/syslog/syslog.h @@ -43,6 +43,8 @@ #include #include + +#include #include /**************************************************************************** @@ -104,6 +106,7 @@ enum syslog_init_e /* This structure provides the interface to a SYSLOG device */ +typedef CODE ssize_t (*syslog_write_t)(FAR const char *buf, size_t buflen); typedef CODE int (*syslog_putc_t)(int ch); typedef CODE int (*syslog_flush_t)(void); @@ -111,8 +114,11 @@ struct syslog_channel_s { /* I/O redirection methods */ - syslog_putc_t sc_putc; /* Normal buffered output */ - syslog_putc_t sc_force; /* Low-level output for interrupt handlers */ +#ifdef CONFIG_SYSLOG_WRITE + syslog_write_t sc_write; /* Write multiple bytes */ +#endif + syslog_putc_t sc_putc; /* Normal buffered output */ + syslog_putc_t sc_force; /* Low-level output for interrupt handlers */ syslog_flush_t sc_flush; /* Flush buffered output (on crash) */ /* Implementation specific logic may follow */ -- GitLab From d8a83f16be1051dd41734f0052b69b4c5cd587c8 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 10 May 2017 16:13:21 -0600 Subject: [PATCH 781/990] Syslog buffering: Various corrections from early debug --- drivers/syslog/syslog_device.c | 84 ++++++++++++------------------- drivers/syslog/syslog_intbuffer.c | 4 +- drivers/syslog/syslog_stream.c | 27 ++++++---- drivers/syslog/vsyslog.c | 10 ++-- 4 files changed, 54 insertions(+), 71 deletions(-) diff --git a/drivers/syslog/syslog_device.c b/drivers/syslog/syslog_device.c index 1978ec211c..748f6908d1 100644 --- a/drivers/syslog/syslog_device.c +++ b/drivers/syslog/syslog_device.c @@ -484,6 +484,7 @@ ssize_t syslog_dev_write(FAR const char *buffer, size_t buflen) FAR const char *endptr; ssize_t nwritten; size_t writelen; + size_t remaining; int errcode; int ret; @@ -513,80 +514,57 @@ ssize_t syslog_dev_write(FAR const char *buffer, size_t buflen) /* Loop until we have output all characters */ - for (endptr = buffer; *endptr != '\n'; endptr++) + for (endptr = buffer, remaining = buflen; + remaining > 0; + endptr++, remaining--) { - switch (*endptr) + /* Special case carriage return and line feed */ + + if (*endptr == '\r' || *endptr == '\n') { - case '\r': + /* Write everything up to this point, ignore the special + * character. + * + * - buffer points to next byte to output. + * - endptr points to the special character. + */ + + writelen = (size_t)((uintptr_t)endptr - (uintptr_t)buffer); + if (writelen > 0) { - /* Write everything up to this point, ignore the carriage - * return. - * - * - buffer points to next byte to output. - * - endptr points to the carriage return. - */ - - writelen = (size_t)((uintptr_t)endptr - (uintptr_t)buffer); - if (writelen > 0) + nwritten = file_write(&g_syslog_dev.sl_file, buffer, writelen); + if (nwritten < 0) { - nwritten = file_write(&g_syslog_dev.sl_file, buffer, writelen); - if (nwritten < 0) - { - errcode = -nwritten; - goto errout_with_sem; - } + errcode = -nwritten; + goto errout_with_sem; } - - /* Adjust pointers */ - - writelen++; /* Skip the carriage return */ - buffer += writelen; /* Points past the carriage return */ } - break; - case '\n': - { - /* Write everything up to this point, then add a carriage - * return and linefeed; - * - * - buffer points to next byte to output. - * - endptr points to the new line. - */ - - writelen = (size_t)((uintptr_t)endptr - (uintptr_t)buffer); - if (writelen > 0) - { - nwritten = file_write(&g_syslog_dev.sl_file, buffer, writelen); - if (nwritten < 0) - { - errcode = -nwritten; - goto errout_with_sem; - } - } + /* Ignore the carriage return, but for the linefeed, output + * both a carriage return and a linefeed. + */ + if (*endptr == '\n') + { nwritten = file_write(&g_syslog_dev.sl_file, g_syscrlf, 2); if (nwritten < 0) { errcode = -nwritten; goto errout_with_sem; } - - /* Adjust pointers */ - - writelen++; /* Skip the line feed */ - buffer += writelen; /* Points past the line feed */ } - break; - default: - break; + /* Adjust pointers */ + + writelen++; /* Skip the special character */ + buffer += writelen; /* Points past the special character */ } } - /* Write any data at the end of the buffer. + /* Write any unterminated data at the end of the buffer. * * - buffer points to next byte to output. - * - endptr points to the NULL terminator. + * - endptr points to the end of the buffer plus 1. */ writelen = (size_t)((uintptr_t)endptr - (uintptr_t)buffer); diff --git a/drivers/syslog/syslog_intbuffer.c b/drivers/syslog/syslog_intbuffer.c index 28be3a74ca..e68ff3fb74 100644 --- a/drivers/syslog/syslog_intbuffer.c +++ b/drivers/syslog/syslog_intbuffer.c @@ -133,7 +133,7 @@ int syslog_remove_intbuffer(void) flags = enter_critical_section(); - /* How much space is left in the inbuffer? */ + /* How much space is left in the intbuffer? */ inndx = (uint32_t)g_syslog_intbuffer.si_inndx; outndx = (uint32_t)g_syslog_intbuffer.si_outndx; @@ -211,7 +211,7 @@ int syslog_add_intbuffer(int ch) flags = enter_critical_section(); - /* How much space is left in the inbuffer? */ + /* How much space is left in the intbuffer? */ inndx = (uint32_t)g_syslog_intbuffer.si_inndx; outndx = (uint32_t)g_syslog_intbuffer.si_outndx; diff --git a/drivers/syslog/syslog_stream.c b/drivers/syslog/syslog_stream.c index 3426b31691..5fb8d19280 100644 --- a/drivers/syslog/syslog_stream.c +++ b/drivers/syslog/syslog_stream.c @@ -62,19 +62,24 @@ static void syslogstream_putc(FAR struct lib_outstream_s *this, int ch) #ifdef CONFIG_SYSLOG_BUFFER FAR struct lib_syslogstream_s *stream = (FAR struct lib_syslogstream_s *)this; - /* Add the incoming character to the buffer */ + /* Discard carriage returns */ - stream->buf[stream->nbuf] = ch; - stream->nbuf++; - this->nput++; + if (ch != '\r') + { + /* Add the incoming character to the buffer */ - /* Is the buffer full? Did we encounter a new line? */ + stream->buf[stream->nbuf] = ch; + stream->nbuf++; + this->nput++; - if (stream->nbuf >= CONFIG_SYSLOG_BUFSIZE || ch == '\n') - { - /* Yes.. then flush the buffer */ + /* Is the buffer full? Did we encounter a new line? */ - (void)this->flush(this); + if (stream->nbuf >= CONFIG_SYSLOG_BUFSIZE || ch == '\n') + { + /* Yes.. then flush the buffer */ + + (void)this->flush(this); + } } #else int ret; @@ -123,8 +128,8 @@ static int syslogstream_flush(FAR struct lib_outstream_s *this) do { - int status = syslog_write(stream->buf, stream->nbuf); - if (status < 0) + ssize_t nbytes = syslog_write(stream->buf, stream->nbuf); + if (nbytes < 0) { ret = -get_errno(); } diff --git a/drivers/syslog/vsyslog.c b/drivers/syslog/vsyslog.c index 5d45d83092..3ffc521181 100644 --- a/drivers/syslog/vsyslog.c +++ b/drivers/syslog/vsyslog.c @@ -108,21 +108,21 @@ int _vsyslog(int priority, FAR const IPTR char *fmt, FAR va_list *ap) { /* Use the SYSLOG emergency stream */ - emergstream((FAR struct lib_outstream_s *)&stream); + emergstream(&stream.public); } else { /* Use the normal SYSLOG stream */ - syslogstream((FAR struct lib_syslogstream_s *)&stream); + syslogstream(&stream); } #if defined(CONFIG_SYSLOG_TIMESTAMP) /* Pre-pend the message with the current time, if available */ - (void)lib_sprintf((FAR struct lib_outstream_s *)&stream, - "[%6d.%06d]", ts.tv_sec, ts.tv_nsec/1000); + (void)lib_sprintf(&stream.public, "[%6d.%06d]", + ts.tv_sec, ts.tv_nsec/1000); #endif - return lib_vsprintf((FAR struct lib_outstream_s *)&stream, fmt, *ap); + return lib_vsprintf(&stream.public, fmt, *ap); } -- GitLab From d3b9f5b37f071b3f909e1735ee85b8047eb70c44 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 10 May 2017 17:36:08 -0600 Subject: [PATCH 782/990] Syslog buffering: Use IOBs to buffer data, not an on-stack buffer --- drivers/serial/serial.c | 3 +- drivers/syslog/Kconfig | 14 +-- drivers/syslog/syslog_stream.c | 158 ++++++++++++++++++++++++--------- drivers/syslog/vsyslog.c | 21 ++++- include/nuttx/sched.h | 2 +- include/nuttx/streams.h | 34 +++++-- mm/iob/iob_alloc.c | 3 +- 7 files changed, 168 insertions(+), 67 deletions(-) diff --git a/drivers/serial/serial.c b/drivers/serial/serial.c index 775fa3a97a..49417a9685 100644 --- a/drivers/serial/serial.c +++ b/drivers/serial/serial.c @@ -51,6 +51,7 @@ #include #include +#include #include #include #include @@ -365,7 +366,7 @@ static ssize_t uart_write(FAR struct file *filep, FAR const char *buffer, * a little differently. */ - if (up_interrupt_context() || getpid() == 0) + if (up_interrupt_context() || sched_idletask()) { #ifdef CONFIG_SERIAL_REMOVABLE /* If the removable device is no longer connected, refuse to write to diff --git a/drivers/syslog/Kconfig b/drivers/syslog/Kconfig index de0d8a137f..60c136e5a7 100644 --- a/drivers/syslog/Kconfig +++ b/drivers/syslog/Kconfig @@ -86,26 +86,16 @@ config SYSLOG_BUFFER bool "Use buffered output" default n depends on SYSLOG_WRITE + select MM_IOB ---help--- Enables an buffering logic that will be used to serialize debug output from concurrent tasks. This enables allocation of one buffer - per thread, each of size CONFIG_SYSLOG_BUFSIZE. + per thread, each of size CONFIG_IOB_BUFSIZE. The use of SYSLOG buffering is optional. If not enabled, however, then the output from multiple tasks that attempt to generate SYSLOG output may be interleaved and difficult to read. -config SYSLOG_BUFSIZE - int "Output buffer size" - default 32 - range 1 65535 - depends on SYSLOG_BUFFER - ---help--- - If CONFIG_SYSLOG_BUFFER is enabled, then CONFIG_SYSLOG_BUFSIZE - provides the size of the per-thread output buffer. Setting - CONFIG_SYSLOG_BUFSIZE to a value less than one effectly disables - output SYSLOG buffering. - config SYSLOG_INTBUFFER bool "Use interrupt buffer" default n diff --git a/drivers/syslog/syslog_stream.c b/drivers/syslog/syslog_stream.c index 5fb8d19280..04bb0726b0 100644 --- a/drivers/syslog/syslog_stream.c +++ b/drivers/syslog/syslog_stream.c @@ -44,8 +44,9 @@ #include #include -#include #include +#include +#include #include "syslog.h" @@ -59,55 +60,67 @@ static void syslogstream_putc(FAR struct lib_outstream_s *this, int ch) { -#ifdef CONFIG_SYSLOG_BUFFER - FAR struct lib_syslogstream_s *stream = (FAR struct lib_syslogstream_s *)this; - /* Discard carriage returns */ if (ch != '\r') { - /* Add the incoming character to the buffer */ +#ifdef CONFIG_SYSLOG_BUFFER + FAR struct lib_syslogstream_s *stream; + FAR struct iob_s *iob; - stream->buf[stream->nbuf] = ch; - stream->nbuf++; - this->nput++; + DEBUGASSERT(this != NULL); + stream = (FAR struct lib_syslogstream_s *)this; + iob = stream->iob; - /* Is the buffer full? Did we encounter a new line? */ + /* Do we have an IO buffer? */ - if (stream->nbuf >= CONFIG_SYSLOG_BUFSIZE || ch == '\n') + if (iob != NULL) { - /* Yes.. then flush the buffer */ + /* Yes.. Add the incoming character to the buffer */ - (void)this->flush(this); - } - } -#else - int ret; + iob->io_data[iob->io_len] = ch; + iob->io_len++; + this->nput++; - /* Try writing until the write was successful or until an irrecoverable - * error occurs. - */ + /* Is the buffer full? Did we encounter a new line? */ - do - { - /* Write the character to the supported logging device. On failure, - * syslog_putc returns EOF with the errno value set; - */ + if (iob->io_len >= CONFIG_IOB_BUFSIZE || ch == '\n') + { + /* Yes.. then flush the buffer */ - ret = syslog_putc(ch); - if (ret != EOF) - { - this->nput++; - return; + (void)this->flush(this); + } } + else +#endif + { + int ret; + + /* Try writing until the write was successful or until an + * irrecoverable error occurs. + */ - /* The special errno value -EINTR means that syslog_putc() was - * awakened by a signal. This is not a real error and must be - * ignored in this context. - */ + do + { + /* Write the character to the supported logging device. On + * failure, syslog_putc returns EOF with the errno value set; + */ + + ret = syslog_putc(ch); + if (ret != EOF) + { + this->nput++; + return; + } + + /* The special errno value -EINTR means that syslog_putc() was + * awakened by a signal. This is not a real error and must be + * ignored in this context. + */ + } + while (get_errno() == -EINTR); + } } - while (get_errno() == -EINTR); -#endif } /**************************************************************************** @@ -117,25 +130,31 @@ static void syslogstream_putc(FAR struct lib_outstream_s *this, int ch) #ifdef CONFIG_SYSLOG_BUFFER static int syslogstream_flush(FAR struct lib_outstream_s *this) { - FAR struct lib_syslogstream_s *stream = (FAR struct lib_syslogstream_s *)this; + FAR struct lib_syslogstream_s *stream; + FAR struct iob_s *iob; int ret = OK; - /* Is there anything buffered? */ + DEBUGASSERT(this != NULL); + stream = (FAR struct lib_syslogstream_s *)this; + iob = stream->iob; + + /* Do we have an IO buffer? Is there anything buffered? */ - if (stream->nbuf > 0) + if (iob != NULL && iob->io_len > 0) { /* Yes write the buffered data */ do { - ssize_t nbytes = syslog_write(stream->buf, stream->nbuf); + ssize_t nbytes = syslog_write((FAR const char *)iob->io_data, + (size_t)iob->io_len); if (nbytes < 0) { ret = -get_errno(); } else { - stream->nbuf = 0; + iob->io_len = 0; ret = OK; } } @@ -151,7 +170,7 @@ static int syslogstream_flush(FAR struct lib_outstream_s *this) ****************************************************************************/ /**************************************************************************** - * Name: syslogstream + * Name: syslogstream_create * * Description: * Initializes a stream for use with the configured syslog interface. @@ -159,23 +178,74 @@ static int syslogstream_flush(FAR struct lib_outstream_s *this) * * Input parameters: * stream - User allocated, uninitialized instance of struct - * lib_syslogstream_s to be initialized. + * lib_lowoutstream_s to be initialized. * * Returned Value: * None (User allocated instance initialized). * ****************************************************************************/ -void syslogstream(FAR struct lib_syslogstream_s *stream) +void syslogstream_create(FAR struct lib_syslogstream_s *stream) { + DEBUGASSERT(stream != NULL); + #ifdef CONFIG_SYSLOG_BUFFER + FAR struct iob_s *iob; + + /* Initialize the common fields */ + stream->public.put = syslogstream_putc; stream->public.flush = syslogstream_flush; stream->public.nput = 0; - stream->nbuf = 0; + + /* Allocate an IOB */ + + iob = iob_alloc(true); + stream->iob = iob; + + if (iob != NULL) + { + /* Initialize the IOB */ + + iob->io_len = 0; + iob->io_offset = 0; + iob->io_pktlen = 0; + } #else stream->public.put = syslogstream_putc; stream->public.flush = lib_noflush; stream->public.nput = 0; #endif } + +/**************************************************************************** + * Name: syslogstream_destroy + * + * Description: + * Free resources held by the syslog stream. + * + * Input parameters: + * stream - User allocated, uninitialized instance of struct + * lib_lowoutstream_s to be initialized. + * + * Returned Value: + * None (Resources freed). + * + ****************************************************************************/ + +#ifdef CONFIG_SYSLOG_BUFFER +void syslogstream_destroy(FAR struct lib_syslogstream_s *stream) +{ + DEBUGASSERT(stream != NULL); + + /* Verify that there is an IOB attached (there should be) */ + + if (stream->iob != NULL) + { + /* Free the IOB */ + + iob_free(stream->iob); + stream->iob = NULL; + } +} +#endif diff --git a/drivers/syslog/vsyslog.c b/drivers/syslog/vsyslog.c index 3ffc521181..cbb8588240 100644 --- a/drivers/syslog/vsyslog.c +++ b/drivers/syslog/vsyslog.c @@ -68,15 +68,17 @@ int _vsyslog(int priority, FAR const IPTR char *fmt, FAR va_list *ap) { struct lib_syslogstream_s stream; + int ret; + #ifdef CONFIG_SYSLOG_TIMESTAMP struct timespec ts; - int ret = -1; /* Get the current time. Since debug output may be generated very early * in the start-up sequence, hardware timer support may not yet be * available. */ + ret = -EAGAIN; if (OSINIT_HW_READY()) { /* Prefer monotonic when enabled, as it can be synchronized to @@ -114,7 +116,7 @@ int _vsyslog(int priority, FAR const IPTR char *fmt, FAR va_list *ap) { /* Use the normal SYSLOG stream */ - syslogstream(&stream); + syslogstream_create(&stream); } #if defined(CONFIG_SYSLOG_TIMESTAMP) @@ -124,5 +126,18 @@ int _vsyslog(int priority, FAR const IPTR char *fmt, FAR va_list *ap) ts.tv_sec, ts.tv_nsec/1000); #endif - return lib_vsprintf(&stream.public, fmt, *ap); + /* Generate the output */ + + ret = lib_vsprintf(&stream.public, fmt, *ap); + +#ifdef CONFIG_SYSLOG_BUFFER + /* Destroy the syslog stream buffer */ + + if (priority != LOG_EMERG) + { + syslogstream_destroy(&stream); + } +#endif + + return ret; } diff --git a/include/nuttx/sched.h b/include/nuttx/sched.h index a6031c3183..a1dbe6c5d6 100644 --- a/include/nuttx/sched.h +++ b/include/nuttx/sched.h @@ -760,7 +760,7 @@ FAR struct tcb_s *sched_self(void); void sched_foreach(sched_foreach_t handler, FAR void *arg); -/* Give a task ID, look up the corresponding TCB */ +/* Given a task ID, look up the corresponding TCB */ FAR struct tcb_s *sched_gettcb(pid_t pid); diff --git a/include/nuttx/streams.h b/include/nuttx/streams.h index c8eae2d625..ccb7054f7f 100644 --- a/include/nuttx/streams.h +++ b/include/nuttx/streams.h @@ -190,14 +190,17 @@ struct lib_rawsostream_s }; /* This is a special stream that does buffered character I/O. NOTE that is - * CONFIG_SYSLOG_BUFFER is not defined, it is the same as struct lib_outstream_s */ + * CONFIG_SYSLOG_BUFFER is not defined, it is the same as struct + * lib_outstream_s + */ + +struct iob_s; /* Forward reference */ struct lib_syslogstream_s { struct lib_outstream_s public; #ifdef CONFIG_SYSLOG_BUFFER - unsigned int nbuf; - char buf[CONFIG_SYSLOG_BUFSIZE]; + FAR struct iob_s *iob; #endif }; @@ -357,7 +360,7 @@ void lib_nullinstream(FAR struct lib_instream_s *nullinstream); void lib_nulloutstream(FAR struct lib_outstream_s *nulloutstream); /**************************************************************************** - * Name: syslogstream + * Name: syslogstream_create * * Description: * Initializes a stream for use with the configured syslog interface. @@ -372,7 +375,28 @@ void lib_nulloutstream(FAR struct lib_outstream_s *nulloutstream); * ****************************************************************************/ -void syslogstream(FAR struct lib_syslogstream_s *stream); +void syslogstream_create(FAR struct lib_syslogstream_s *stream); + +/**************************************************************************** + * Name: syslogstream_destroy + * + * Description: + * Free resources held by the syslog stream. + * + * Input parameters: + * stream - User allocated, uninitialized instance of struct + * lib_lowoutstream_s to be initialized. + * + * Returned Value: + * None (Resources freed). + * + ****************************************************************************/ + +#ifdef CONFIG_SYSLOG_BUFFER +void syslogstream_destroy(FAR struct lib_syslogstream_s *stream); +#else +# define syslogstream_destroy(s) +#endif /**************************************************************************** * Name: emergstream diff --git a/mm/iob/iob_alloc.c b/mm/iob/iob_alloc.c index a1c4d6de97..27de294670 100644 --- a/mm/iob/iob_alloc.c +++ b/mm/iob/iob_alloc.c @@ -45,6 +45,7 @@ #include #include +#include #include #include "iob.h" @@ -172,7 +173,7 @@ FAR struct iob_s *iob_alloc(bool throttled) { /* Were we called from the interrupt level? */ - if (up_interrupt_context()) + if (up_interrupt_context() || sched_idletask()) { /* Yes, then try to allocate an I/O buffer without waiting */ -- GitLab From c74a51f789ccb07d6868bafe54e55b5c6a57499e Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Thu, 11 May 2017 14:35:27 +0300 Subject: [PATCH 783/990] STM32L4: add internal flash write support --- arch/arm/src/stm32l4/Make.defs | 2 +- arch/arm/src/stm32l4/stm32l4_flash.c | 357 +++++++++++++++++++++++++++ arch/arm/src/stm32l4/stm32l4_flash.h | 66 +++-- 3 files changed, 401 insertions(+), 24 deletions(-) create mode 100644 arch/arm/src/stm32l4/stm32l4_flash.c diff --git a/arch/arm/src/stm32l4/Make.defs b/arch/arm/src/stm32l4/Make.defs index 417d7c170d..313e4195e7 100644 --- a/arch/arm/src/stm32l4/Make.defs +++ b/arch/arm/src/stm32l4/Make.defs @@ -103,7 +103,7 @@ CHIP_CSRCS = stm32l4_allocateheap.c stm32l4_exti_gpio.c stm32l4_gpio.c CHIP_CSRCS += stm32l4_idle.c stm32l4_irq.c stm32l4_lowputc.c stm32l4_rcc.c CHIP_CSRCS += stm32l4_serial.c stm32l4_start.c stm32l4_waste.c stm32l4_uid.c CHIP_CSRCS += stm32l4_spi.c stm32l4_i2c.c stm32l4_lse.c stm32l4_pwr.c -CHIP_CSRCS += stm32l4_tim.c +CHIP_CSRCS += stm32l4_tim.c stm32l4_flash.c ifeq ($(CONFIG_TIMER),y) CHIP_CSRCS += stm32l4_tim_lowerhalf.c diff --git a/arch/arm/src/stm32l4/stm32l4_flash.c b/arch/arm/src/stm32l4/stm32l4_flash.c new file mode 100644 index 0000000000..14ac3614d6 --- /dev/null +++ b/arch/arm/src/stm32l4/stm32l4_flash.c @@ -0,0 +1,357 @@ +/************************************************************************************ + * arch/arm/src/stm32l4/stm32l4_flash.c + * + * Copyright (C) 2011 Uros Platise. All rights reserved. + * Copyright (C) 2017 Haltian Ltd. All rights reserved. + * Authors: Uros Platise + * 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. + * + ************************************************************************************/ + +/* Provides standard flash access functions, to be used by the flash mtd driver. + * The interface is defined in the include/nuttx/progmem.h + * + * Notes about this implementation: + * - HSI16 is automatically turned ON by MCU, if not enabled beforehand + * - Only Standard Programming is supported, no Fast Programming. + * - Low Power Modes are not permitted during write/erase + */ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include +#include + +#include +#include +#include + +#include "stm32l4_rcc.h" +#include "stm32l4_waste.h" +#include "stm32l4_flash.h" + +#include "up_arch.h" + + +#if !(defined(CONFIG_STM32L4_STM32L4X3) || defined(CONFIG_STM32L4_STM32L4X6)) +# error "Unrecognized STM32 chip" +#endif + +#if !defined(CONFIG_STM32L4_FLASH_OVERRIDE_DEFAULT) +# warning "Flash Configuration has been overridden - make sure it is correct" +#endif + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +#define FLASH_KEY1 0x45670123 +#define FLASH_KEY2 0xCDEF89AB + +#define OPTBYTES_KEY1 0x08192A3B +#define OPTBYTES_KEY2 0x4C5D6E7F + +#define FLASH_CR_PAGE_ERASE FLASH_CR_PER +#define FLASH_SR_WRITE_PROTECTION_ERROR FLASH_SR_WRPERR + +/* All errors for Standard Programming, not for other operations. */ + +#define FLASH_SR_ALLERRS (FLASH_SR_PGSERR | FLASH_SR_SIZERR | \ + FLASH_SR_PGAERR | FLASH_SR_WRPERR | \ + FLASH_SR_PROGERR) + +/************************************************************************************ + * Private Data + ************************************************************************************/ + +static sem_t g_sem = SEM_INITIALIZER(1); + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +static inline void sem_lock(void) +{ + while (sem_wait(&g_sem) < 0) + { + DEBUGASSERT(errno == EINTR); + } +} + +static inline void sem_unlock(void) +{ + sem_post(&g_sem); +} + +static void flash_unlock(void) +{ + while (getreg32(STM32L4_FLASH_SR) & FLASH_SR_BSY) + { + up_waste(); + } + + if (getreg32(STM32L4_FLASH_CR) & FLASH_CR_LOCK) + { + /* Unlock sequence */ + + putreg32(FLASH_KEY1, STM32L4_FLASH_KEYR); + putreg32(FLASH_KEY2, STM32L4_FLASH_KEYR); + } +} + +static void flash_lock(void) +{ + modifyreg32(STM32L4_FLASH_CR, 0, FLASH_CR_LOCK); +} + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +void stm32l4_flash_unlock(void) +{ + sem_lock(); + flash_unlock(); + sem_unlock(); +} + +void stm32l4_flash_lock(void) +{ + sem_lock(); + flash_lock(); + sem_unlock(); +} + +size_t up_progmem_pagesize(size_t page) +{ + return STM32L4_FLASH_PAGESIZE; +} + +ssize_t up_progmem_getpage(size_t addr) +{ + if (addr >= STM32L4_FLASH_BASE) + { + addr -= STM32L4_FLASH_BASE; + } + + if (addr >= STM32L4_FLASH_SIZE) + { + return -EFAULT; + } + + return addr / STM32L4_FLASH_PAGESIZE; +} + +size_t up_progmem_getaddress(size_t page) +{ + if (page >= STM32L4_FLASH_NPAGES) + { + return SIZE_MAX; + } + + return page * STM32L4_FLASH_PAGESIZE + STM32L4_FLASH_BASE; +} + +size_t up_progmem_npages(void) +{ + return STM32L4_FLASH_NPAGES; +} + +bool up_progmem_isuniform(void) +{ + return true; +} + +ssize_t up_progmem_erasepage(size_t page) +{ + if (page >= STM32L4_FLASH_NPAGES) + { + return -EFAULT; + } + + sem_lock(); + + /* Get flash ready and begin erasing single page. */ + + flash_unlock(); + + modifyreg32(STM32L4_FLASH_CR, 0, FLASH_CR_PAGE_ERASE); + modifyreg32(STM32L4_FLASH_CR, FLASH_CR_PNB_MASK, FLASH_CR_PNB(page)); + modifyreg32(STM32L4_FLASH_CR, 0, FLASH_CR_START); + + while (getreg32(STM32L4_FLASH_SR) & FLASH_SR_BSY) + { + up_waste(); + } + + modifyreg32(STM32L4_FLASH_CR, FLASH_CR_PAGE_ERASE, 0); + + flash_lock(); + sem_unlock(); + + /* Verify */ + + if (up_progmem_ispageerased(page) == 0) + { + return up_progmem_pagesize(page); + } + else + { + return -EIO; + } +} + +ssize_t up_progmem_ispageerased(size_t page) +{ + size_t addr; + size_t count; + size_t bwritten = 0; + + if (page >= STM32L4_FLASH_NPAGES) + { + return -EFAULT; + } + + /* Verify */ + + for (addr = up_progmem_getaddress(page), count = up_progmem_pagesize(page); + count; count--, addr++) + { + if (getreg8(addr) != 0xff) + { + bwritten++; + } + } + + return bwritten; +} + +ssize_t up_progmem_write(size_t addr, const void *buf, size_t count) +{ + uint32_t *word = (uint32_t *)buf; + size_t written = count; + int ret = OK; + + /* STM32L4 requires double-word access and alignment. */ + + if (addr & 7) + { + return -EINVAL; + } + + /* But we can complete single-word writes by writing the + * erase value 0xffffffff as second word ourselves, so + * allow odd number of words here. + */ + + if (count & 3) + { + return -EINVAL; + } + + /* Check for valid address range. */ + + if (addr >= STM32L4_FLASH_BASE) + { + addr -= STM32L4_FLASH_BASE; + } + + if ((addr + count) > STM32L4_FLASH_SIZE) + { + return -EFAULT; + } + + sem_lock(); + + /* Get flash ready and begin flashing. */ + + flash_unlock(); + + modifyreg32(STM32L4_FLASH_CR, 0, FLASH_CR_PG); + + for (addr += STM32L4_FLASH_BASE; count; count -= 8, word += 2, addr += 8) + { + uint32_t second_word; + + /* Write first word. */ + + putreg32(*word, addr); + + /* Write second word and wait to complete. */ + + second_word = (count == 4) ? 0xffffffff : *(word + 1); + putreg32(second_word, (addr + 4)); + + while (getreg32(STM32L4_FLASH_SR) & FLASH_SR_BSY) + { + up_waste(); + } + + /* Verify */ + + if (getreg32(STM32L4_FLASH_SR) & FLASH_SR_WRITE_PROTECTION_ERROR) + { + ret = -EROFS; + goto out; + } + + if (getreg32(addr) != *word || getreg32((addr + 4)) != second_word) + { + ret = -EIO; + goto out; + } + + if (count == 4) + { + break; + } + } + +out: + modifyreg32(STM32L4_FLASH_CR, FLASH_CR_PG, 0); + + /* If there was an error, clear all error flags in status + * register (rc_w1 register so do this by writing the + * error bits). + */ + + if (ret != OK) + { + ferr("flash write error: %d, status: 0x%x\n", ret, getreg32(STM32L4_FLASH_SR)); + modifyreg32(STM32L4_FLASH_SR, 0, FLASH_SR_ALLERRS); + } + + flash_lock(); + sem_unlock(); + return (ret == OK) ? written : ret; +} diff --git a/arch/arm/src/stm32l4/stm32l4_flash.h b/arch/arm/src/stm32l4/stm32l4_flash.h index c29a8d35a5..15745b9377 100644 --- a/arch/arm/src/stm32l4/stm32l4_flash.h +++ b/arch/arm/src/stm32l4/stm32l4_flash.h @@ -1,9 +1,10 @@ /************************************************************************************ - * arch/arm/src/stm32l4/chip/stm32l4_flash.h + * arch/arm/src/stm32l4/stm32l4_flash.h * - * Copyright (C) 2009, 2011, 2015 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * David Sidrane + * Copyright (C) 2009, 2011, 2015, 2017 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * David Sidrane + * Juha Niskanen * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -34,8 +35,8 @@ * ************************************************************************************/ -#ifndef __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4_FLASH_H -#define __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4_FLASH_H +#ifndef __ARCH_ARM_SRC_STM32L4_STM32L4_FLASH_H +#define __ARCH_ARM_SRC_STM32L4_STM32L4_FLASH_H /************************************************************************************ * Pre-processor Definitions @@ -122,10 +123,12 @@ #define STM32L4_FLASH_PCROP1ER_OFFSET 0x0028 #define STM32L4_FLASH_WRP1AR_OFFSET 0x002c #define STM32L4_FLASH_WRP1BR_OFFSET 0x0030 -#define STM32L4_FLASH_PCROP2SR_OFFSET 0x0044 -#define STM32L4_FLASH_PCROP2ER_OFFSET 0x0048 -#define STM32L4_FLASH_WRP2AR_OFFSET 0x004c -#define STM32L4_FLASH_WRP2BR_OFFSET 0x0050 +#if defined(CONFIG_STM32L4_STM32L4X6) +# define STM32L4_FLASH_PCROP2SR_OFFSET 0x0044 +# define STM32L4_FLASH_PCROP2ER_OFFSET 0x0048 +# define STM32L4_FLASH_WRP2AR_OFFSET 0x004c +# define STM32L4_FLASH_WRP2BR_OFFSET 0x0050 +#endif /* Register Addresses ***************************************************************/ @@ -141,10 +144,12 @@ #define STM32L4_FLASH_PCROP1ER (STM32L4_FLASHIF_BASE+STM32L4_FLASH_PCROP1ER_OFFSET) #define STM32L4_FLASH_WRP1AR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_WRP1AR_OFFSET) #define STM32L4_FLASH_WRP1BR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_WRP1BR_OFFSET) -#define STM32L4_FLASH_PCROP2SR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_PCROP2SR_OFFSET) -#define STM32L4_FLASH_PCROP2ER (STM32L4_FLASHIF_BASE+STM32L4_FLASH_PCROP2ER_OFFSET) -#define STM32L4_FLASH_WRP2AR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_WRP2AR_OFFSET) -#define STM32L4_FLASH_WRP2BR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_WRP2BR_OFFSET) +#if defined(CONFIG_STM32L4_STM32L4X6) +# define STM32L4_FLASH_PCROP2SR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_PCROP2SR_OFFSET) +# define STM32L4_FLASH_PCROP2ER (STM32L4_FLASHIF_BASE+STM32L4_FLASH_PCROP2ER_OFFSET) +# define STM32L4_FLASH_WRP2AR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_WRP2AR_OFFSET) +# define STM32L4_FLASH_WRP2BR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_WRP2BR_OFFSET) +#endif /* Register Bitfield Definitions ****************************************************/ /* Flash Access Control Register (ACR) */ @@ -170,6 +175,7 @@ #define FLASH_SR_EOP (1 << 0) /* Bit 0: End of operation */ #define FLASH_SR_OPERR (1 << 1) /* Bit 1: Operation error */ +#define FLASH_SR_PROGERR (1 << 3) /* Bit 3: Programming error */ #define FLASH_SR_WRPERR (1 << 4) /* Bit 4: Write protection error */ #define FLASH_SR_PGAERR (1 << 5) /* Bit 5: Programming alignment error */ #define FLASH_SR_SIZERR (1 << 6) /* Bit 6: Size error */ @@ -179,6 +185,9 @@ #define FLASH_SR_RDERR (1 << 14) /* Bit 14: PCROP read error */ #define FLASH_SR_OPTVERR (1 << 15) /* Bit 15: Option validity error */ #define FLASH_SR_BSY (1 << 16) /* Bit 16: Busy */ +#if defined(CONFIG_STM32L4_STM32L4X3) +# define FLASH_SR_PEMPTY (1 << 17) /* Bit 17: Program empty */ +#endif /* Flash Control Register (CR) */ @@ -190,8 +199,10 @@ #define FLASH_CR_PNB_MASK (0xFF << FLASH_CR_PNB_SHIFT) #define FLASH_CR_PNB(n) ((n) << FLASH_CR_PNB_SHIFT) /* Page n (if BKER=0) or n+256 (if BKER=1), n=0..255 */ -#define FLASH_CR_BKER (1 << 11) /* Bit 11: Page number MSB (Bank selection) */ -#define FLASH_CR_MER2 (1 << 15) /* Bit 15: Mass Erase Bank 2 */ +#if defined(CONFIG_STM32L4_STM32L4X6) +# define FLASH_CR_BKER (1 << 11) /* Bit 11: Page number MSB (Bank selection) */ +# define FLASH_CR_MER2 (1 << 15) /* Bit 15: Mass Erase Bank 2 */ +#endif #define FLASH_CR_START (1 << 16) /* Bit 16: Start Erase */ #define FLASH_CR_OPTSTRT (1 << 17) /* Bit 17: Options modification Start */ #define FLASH_CR_FSTPG (1 << 23) /* Bit 23: Fast programming */ @@ -206,7 +217,9 @@ #define FLASH_ECCR_ADDR_ECC_SHIFT (0) /* Bits 8-15: Read protect */ #define FLASH_ECCR_ADDR_ECC_MASK (0x07ffff << FLASH_ECCR_ADDR_ECC_SHIFT) -#define FLASH_ECCR_BK_ECC (1 << 19) /* Bit 19: ECC fail bank */ +#if defined(CONFIG_STM32L4_STM32L4X6) +# define FLASH_ECCR_BK_ECC (1 << 19) /* Bit 19: ECC fail bank */ +#endif #define FLASH_ECCR_SYSF_ECC (1 << 20) /* Bit 20: System Flash ECC fail */ #define FLASH_ECCR_ECCCIE (1 << 24) /* Bit 24: ECC correction interrupt enable */ #define FLASH_ECCR_ECCC (1 << 30) /* Bit 30: ECC correction */ @@ -221,11 +234,18 @@ #define FLASH_OPTCR_IWDG_STOP (1 << 17) /* Bit 17: Independent watchdog counter freeze in Stop mode */ #define FLASH_OPTCR_IWDG_STDBY (1 << 18) /* Bit 18: Independent watchdog counter freeze in Standby mode*/ #define FLASH_OPTCR_WWDG_SW (1 << 19) /* Bit 19: Window watchdog selection */ -#define FLASH_OPTCR_BFB2 (1 << 20) /* Bit 20: Dual bank boot */ -#define FLASH_OPTCR_DUALBANK (1 << 21) /* Bit 21: Dual bank enable */ +#if defined(CONFIG_STM32L4_STM32L4X6) +# define FLASH_OPTCR_BFB2 (1 << 20) /* Bit 20: Dual bank boot */ +# define FLASH_OPTCR_DUALBANK (1 << 21) /* Bit 21: Dual bank enable */ +#endif #define FLASH_OPTCR_NBOOT1 (1 << 23) /* Bit 23: Boot configuration */ #define FLASH_OPTCR_SRAM2_PE (1 << 24) /* Bit 24: SRAM2 parity check enable */ -#define FLASH_OPTCR_SRAM2_RST (1 << 25) /* Bit 24: SRAM2 Erase when system reset */ +#define FLASH_OPTCR_SRAM2_RST (1 << 25) /* Bit 25: SRAM2 Erase when system reset */ +#if defined(CONFIG_STM32L4_STM32L4X3) || defined(CONFIG_STM32L4_STM32L496XX) +# define FLASH_OPTCR_NSWBOOT0 (1 << 26) /* Bit 26: Software BOOT0 */ +# define FLASH_OPTCR_NBOOT0 (1 << 27) /* Bit 27: nBOOT0 option bit */ +#endif + #define FLASH_OPTCR_BORLEV_SHIFT (8) /* Bits 8-10: BOR reset Level */ #define FLASH_OPTCR_BORLEV_MASK (7 << FLASH_OPTCR_BORLEV_SHIFT) #define FLASH_OPTCR_VBOR0 (0 << FLASH_OPTCR_BORLEV_SHIFT) /* 000: BOR Level 0 (1.7 V) */ @@ -242,7 +262,7 @@ * Public Functions ************************************************************************************/ -void STM32L4_flash_lock(void); -void STM32L4_flash_unlock(void); +void stm32l4_flash_lock(void); +void stm32l4_flash_unlock(void); -#endif /* __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4_FLASH_H */ +#endif /* __ARCH_ARM_SRC_STM32L4_STM32L4_FLASH_H */ -- GitLab From 309105096392099e788c3b3a2be2f26fb789ee08 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 11 May 2017 06:58:39 -0600 Subject: [PATCH 784/990] STM32L4: Review of last PR + Move separate stm32l4_flash.h; move hardware-specific definitions to chip/stm32l4_flash.h --- arch/arm/src/stm32l4/chip/stm32l4_flash.h | 267 ++++++++++++++++++++++ arch/arm/src/stm32l4/stm32l4_flash.c | 1 - arch/arm/src/stm32l4/stm32l4_flash.h | 219 +----------------- 3 files changed, 270 insertions(+), 217 deletions(-) create mode 100644 arch/arm/src/stm32l4/chip/stm32l4_flash.h diff --git a/arch/arm/src/stm32l4/chip/stm32l4_flash.h b/arch/arm/src/stm32l4/chip/stm32l4_flash.h new file mode 100644 index 0000000000..530091f928 --- /dev/null +++ b/arch/arm/src/stm32l4/chip/stm32l4_flash.h @@ -0,0 +1,267 @@ +/************************************************************************************ + * arch/arm/src/stm32l4/chip/stm32l4_flash.h + * + * Copyright (C) 2009, 2011, 2015, 2017 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * David Sidrane + * 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 __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4_FLASH_H +#define __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4_FLASH_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Flash size is known from the chip selection: + * + * When CONFIG_STM32L4_FLASH_OVERRIDE_DEFAULT is set the + * CONFIG_STM32L4_FLASH_CONFIG_x selects the default FLASH size based on the chip + * part number. This value can be overridden with CONFIG_STM32L4_FLASH_OVERRIDE_x + * + * Parts STM32L4xxE have 512Kb of FLASH + * Parts STM32L4xxG have 1024Kb of FLASH + * + * N.B. Only Single bank mode is supported + */ + +#define _K(x) ((x)*1024) + +#if !defined(CONFIG_STM32L4_FLASH_OVERRIDE_DEFAULT) && \ + !defined(CONFIG_STM32L4_FLASH_OVERRIDE_B) && \ + !defined(CONFIG_STM32L4_FLASH_OVERRIDE_C) && \ + !defined(CONFIG_STM32L4_FLASH_OVERRIDE_E) && \ + !defined(CONFIG_STM32L4_FLASH_OVERRIDE_G) && \ + !defined(CONFIG_STM32L4_FLASH_CONFIG_B) && \ + !defined(CONFIG_STM32L4_FLASH_CONFIG_C) && \ + !defined(CONFIG_STM32L4_FLASH_CONFIG_E) && \ + !defined(CONFIG_STM32L4_FLASH_CONFIG_G) +# define CONFIG_STM32L4_FLASH_OVERRIDE_E +# warning "Flash size not defined defaulting to 512KiB (E)" +#endif + +/* Override of the Flash has been chosen */ + +#if !defined(CONFIG_STM32L4_FLASH_OVERRIDE_DEFAULT) +# undef CONFIG_STM32L4_FLASH_CONFIG_B +# undef CONFIG_STM32L4_FLASH_CONFIG_C +# undef CONFIG_STM32L4_FLASH_CONFIG_E +# undef CONFIG_STM32L4_FLASH_CONFIG_G +# if defined(CONFIG_STM32L4_FLASH_OVERRIDE_B) +# define CONFIG_STM32L4_FLASH_CONFIG_B +# elif defined(CONFIG_STM32L4_FLASH_OVERRIDE_C) +# define CONFIG_STM32L4_FLASH_CONFIG_C +# elif defined(CONFIG_STM32L4_FLASH_OVERRIDE_E) +# define CONFIG_STM32L4_FLASH_CONFIG_E +# elif defined(CONFIG_STM32L4_FLASH_OVERRIDE_G) +# define CONFIG_STM32L4_FLASH_CONFIG_G +# endif +#endif + +/* Define the valid configuration */ + +#if defined(CONFIG_STM32L4_FLASH_CONFIG_B) /* 128 kB */ +# define STM32L4_FLASH_NPAGES 64 +# define STM32L4_FLASH_PAGESIZE 2048 +#elif defined(CONFIG_STM32L4_FLASH_CONFIG_C) /* 256 kB */ +# define STM32L4_FLASH_NPAGES 128 +# define STM32L4_FLASH_PAGESIZE 2048 +#elif defined(CONFIG_STM32L4_FLASH_CONFIG_E) /* 512 kB */ +# define STM32L4_FLASH_NPAGES 256 +# define STM32L4_FLASH_PAGESIZE 2048 +#elif defined(CONFIG_STM32L4_FLASH_CONFIG_G) /* 1 MB */ +# define STM32L4_FLASH_NPAGES 512 +# define STM32L4_FLASH_PAGESIZE 2048 +#else +# error "unknown flash configuration!" +#endif + +#ifdef STM32L4_FLASH_PAGESIZE +# define STM32L4_FLASH_SIZE (STM32L4_FLASH_NPAGES * STM32L4_FLASH_PAGESIZE) +#endif + +/* Register Offsets *****************************************************************/ + +#define STM32L4_FLASH_ACR_OFFSET 0x0000 +#define STM32L4_FLASH_PDKEYR_OFFSET 0x0004 +#define STM32L4_FLASH_KEYR_OFFSET 0x0008 +#define STM32L4_FLASH_OPTKEYR_OFFSET 0x000c +#define STM32L4_FLASH_SR_OFFSET 0x0010 +#define STM32L4_FLASH_CR_OFFSET 0x0014 +#define STM32L4_FLASH_ECCR_OFFSET 0x0018 +#define STM32L4_FLASH_OPTR_OFFSET 0x0020 +#define STM32L4_FLASH_PCROP1SR_OFFSET 0x0024 +#define STM32L4_FLASH_PCROP1ER_OFFSET 0x0028 +#define STM32L4_FLASH_WRP1AR_OFFSET 0x002c +#define STM32L4_FLASH_WRP1BR_OFFSET 0x0030 +#if defined(CONFIG_STM32L4_STM32L4X6) +# define STM32L4_FLASH_PCROP2SR_OFFSET 0x0044 +# define STM32L4_FLASH_PCROP2ER_OFFSET 0x0048 +# define STM32L4_FLASH_WRP2AR_OFFSET 0x004c +# define STM32L4_FLASH_WRP2BR_OFFSET 0x0050 +#endif + +/* Register Addresses ***************************************************************/ + +#define STM32L4_FLASH_ACR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_ACR_OFFSET) +#define STM32L4_FLASH_PDKEYR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_PDKEYR_OFFSET) +#define STM32L4_FLASH_KEYR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_KEYR_OFFSET) +#define STM32L4_FLASH_OPTKEYR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_OPTKEYR_OFFSET) +#define STM32L4_FLASH_SR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_SR_OFFSET) +#define STM32L4_FLASH_CR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_CR_OFFSET) +#define STM32L4_FLASH_ECCR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_ECCR_OFFSET) +#define STM32L4_FLASH_OPTR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_OPTR_OFFSET) +#define STM32L4_FLASH_PCROP1SR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_PCROP1SR_OFFSET) +#define STM32L4_FLASH_PCROP1ER (STM32L4_FLASHIF_BASE+STM32L4_FLASH_PCROP1ER_OFFSET) +#define STM32L4_FLASH_WRP1AR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_WRP1AR_OFFSET) +#define STM32L4_FLASH_WRP1BR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_WRP1BR_OFFSET) +#if defined(CONFIG_STM32L4_STM32L4X6) +# define STM32L4_FLASH_PCROP2SR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_PCROP2SR_OFFSET) +# define STM32L4_FLASH_PCROP2ER (STM32L4_FLASHIF_BASE+STM32L4_FLASH_PCROP2ER_OFFSET) +# define STM32L4_FLASH_WRP2AR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_WRP2AR_OFFSET) +# define STM32L4_FLASH_WRP2BR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_WRP2BR_OFFSET) +#endif + +/* Register Bitfield Definitions ****************************************************/ +/* Flash Access Control Register (ACR) */ + +#define FLASH_ACR_LATENCY_SHIFT (0) +#define FLASH_ACR_LATENCY_MASK (7 << FLASH_ACR_LATENCY_SHIFT) +# define FLASH_ACR_LATENCY(n) ((n) << FLASH_ACR_LATENCY_SHIFT) /* n wait states , for Vcore range 1 2 */ +# define FLASH_ACR_LATENCY_0 (0 << FLASH_ACR_LATENCY_SHIFT) /* 000: Zero wait states <=16 <=6 */ +# define FLASH_ACR_LATENCY_1 (1 << FLASH_ACR_LATENCY_SHIFT) /* 001: One wait state <=32 <=12 */ +# define FLASH_ACR_LATENCY_2 (2 << FLASH_ACR_LATENCY_SHIFT) /* 010: Two wait states <=48 <=18 */ +# define FLASH_ACR_LATENCY_3 (3 << FLASH_ACR_LATENCY_SHIFT) /* 011: Three wait states <=64 <=26 */ +# define FLASH_ACR_LATENCY_4 (4 << FLASH_ACR_LATENCY_SHIFT) /* 100: Four wait states <=80 <=26 */ + +#define FLASH_ACR_PRFTEN (1 << 8) /* Bit 8: Prefetch enable */ +#define FLASH_ACR_ICEN (1 << 9) /* Bit 9: Instruction cache enable */ +#define FLASH_ACR_DCEN (1 << 10) /* Bit 10: Data cache enable */ +#define FLASH_ACR_ICRST (1 << 11) /* Bit 11: Instruction cache reset */ +#define FLASH_ACR_DCRST (1 << 12) /* Bit 12: Data cache reset */ +#define FLASH_ACR_RUN_PD (1 << 13) /* Bit 13: Flash mode during Run */ +#define FLASH_ACR_SLEEP_PD (1 << 14) /* Bit 14: Flash mode during Sleep */ + +/* Flash Status Register (SR) */ + +#define FLASH_SR_EOP (1 << 0) /* Bit 0: End of operation */ +#define FLASH_SR_OPERR (1 << 1) /* Bit 1: Operation error */ +#define FLASH_SR_PROGERR (1 << 3) /* Bit 3: Programming error */ +#define FLASH_SR_WRPERR (1 << 4) /* Bit 4: Write protection error */ +#define FLASH_SR_PGAERR (1 << 5) /* Bit 5: Programming alignment error */ +#define FLASH_SR_SIZERR (1 << 6) /* Bit 6: Size error */ +#define FLASH_SR_PGSERR (1 << 7) /* Bit 7: Programming sequence error */ +#define FLASH_SR_MISERR (1 << 8) /* Bit 8: Fast programming data miss error */ +#define FLASH_SR_FASTERR (1 << 9) /* Bit 9: Fast programming error */ +#define FLASH_SR_RDERR (1 << 14) /* Bit 14: PCROP read error */ +#define FLASH_SR_OPTVERR (1 << 15) /* Bit 15: Option validity error */ +#define FLASH_SR_BSY (1 << 16) /* Bit 16: Busy */ +#if defined(CONFIG_STM32L4_STM32L4X3) +# define FLASH_SR_PEMPTY (1 << 17) /* Bit 17: Program empty */ +#endif + +/* Flash Control Register (CR) */ + +#define FLASH_CR_PG (1 << 0) /* Bit 0 : Program Page */ +#define FLASH_CR_PER (1 << 1) /* Bit 1 : Page Erase */ +#define FLASH_CR_MER1 (1 << 2) /* Bit 2 : Mass Erase Bank 1 */ + +#define FLASH_CR_PNB_SHIFT (3) /* Bits 3-10: Page number */ +#define FLASH_CR_PNB_MASK (0xFF << FLASH_CR_PNB_SHIFT) +#define FLASH_CR_PNB(n) ((n) << FLASH_CR_PNB_SHIFT) /* Page n (if BKER=0) or n+256 (if BKER=1), n=0..255 */ + +#if defined(CONFIG_STM32L4_STM32L4X6) +# define FLASH_CR_BKER (1 << 11) /* Bit 11: Page number MSB (Bank selection) */ +# define FLASH_CR_MER2 (1 << 15) /* Bit 15: Mass Erase Bank 2 */ +#endif +#define FLASH_CR_START (1 << 16) /* Bit 16: Start Erase */ +#define FLASH_CR_OPTSTRT (1 << 17) /* Bit 17: Options modification Start */ +#define FLASH_CR_FSTPG (1 << 23) /* Bit 23: Fast programming */ +#define FLASH_CR_EOPIE (1 << 24) /* Bit 24: End of operation interrupt enable */ +#define FLASH_CR_ERRIE (1 << 25) /* Bit 25: Error interrupt enable */ +#define FLASH_CR_RDERRIE (1 << 26) /* Bit 26: PCROP read error interrupt enable */ +#define FLASH_CR_OBL_LAUNCH (1 << 27) /* Bit 27: Option Byte Loading */ +#define FLASH_CR_OPTLOCK (1 << 30) /* Bit 30: Option Lock */ +#define FLASH_CR_LOCK (1 << 31) /* Bit 31: Lock */ + +/* Flash ECC Register (ECCR) */ + +#define FLASH_ECCR_ADDR_ECC_SHIFT (0) /* Bits 8-15: Read protect */ +#define FLASH_ECCR_ADDR_ECC_MASK (0x07ffff << FLASH_ECCR_ADDR_ECC_SHIFT) +#if defined(CONFIG_STM32L4_STM32L4X6) +# define FLASH_ECCR_BK_ECC (1 << 19) /* Bit 19: ECC fail bank */ +#endif +#define FLASH_ECCR_SYSF_ECC (1 << 20) /* Bit 20: System Flash ECC fail */ +#define FLASH_ECCR_ECCCIE (1 << 24) /* Bit 24: ECC correction interrupt enable */ +#define FLASH_ECCR_ECCC (1 << 30) /* Bit 30: ECC correction */ +#define FLASH_ECCR_ECCD (1 << 31) /* Bit 31: ECC detection */ + +/* Flash Option Control Register (OPTCR) */ + +#define FLASH_OPTCR_NRST_STOP (1 << 12) /* Bit 12: Generate reset when entering the Stop mode */ +#define FLASH_OPTCR_NRST_STDBY (1 << 13) /* Bit 13: Generate reset when entering the Standby mode */ +#define FLASH_OPTCR_NRST_SHDW (1 << 14) /* Bit 14: Generate reset when entering the Shutdown mode */ +#define FLASH_OPTCR_IWDG_SW (1 << 16) /* Bit 16: Independent watchdog selection */ +#define FLASH_OPTCR_IWDG_STOP (1 << 17) /* Bit 17: Independent watchdog counter freeze in Stop mode */ +#define FLASH_OPTCR_IWDG_STDBY (1 << 18) /* Bit 18: Independent watchdog counter freeze in Standby mode*/ +#define FLASH_OPTCR_WWDG_SW (1 << 19) /* Bit 19: Window watchdog selection */ +#if defined(CONFIG_STM32L4_STM32L4X6) +# define FLASH_OPTCR_BFB2 (1 << 20) /* Bit 20: Dual bank boot */ +# define FLASH_OPTCR_DUALBANK (1 << 21) /* Bit 21: Dual bank enable */ +#endif +#define FLASH_OPTCR_NBOOT1 (1 << 23) /* Bit 23: Boot configuration */ +#define FLASH_OPTCR_SRAM2_PE (1 << 24) /* Bit 24: SRAM2 parity check enable */ +#define FLASH_OPTCR_SRAM2_RST (1 << 25) /* Bit 25: SRAM2 Erase when system reset */ +#if defined(CONFIG_STM32L4_STM32L4X3) || defined(CONFIG_STM32L4_STM32L496XX) +# define FLASH_OPTCR_NSWBOOT0 (1 << 26) /* Bit 26: Software BOOT0 */ +# define FLASH_OPTCR_NBOOT0 (1 << 27) /* Bit 27: nBOOT0 option bit */ +#endif + +#define FLASH_OPTCR_BORLEV_SHIFT (8) /* Bits 8-10: BOR reset Level */ +#define FLASH_OPTCR_BORLEV_MASK (7 << FLASH_OPTCR_BORLEV_SHIFT) +#define FLASH_OPTCR_VBOR0 (0 << FLASH_OPTCR_BORLEV_SHIFT) /* 000: BOR Level 0 (1.7 V) */ +#define FLASH_OPTCR_VBOR1 (1 << FLASH_OPTCR_BORLEV_SHIFT) /* 001: BOR Level 1 (2.0 V) */ +#define FLASH_OPTCR_VBOR2 (2 << FLASH_OPTCR_BORLEV_SHIFT) /* 010: BOR Level 2 (2.2 V) */ +#define FLASH_OPTCR_VBOR3 (3 << FLASH_OPTCR_BORLEV_SHIFT) /* 011: BOR Level 3 (2.5 V) */ +#define FLASH_OPTCR_VBOR4 (4 << FLASH_OPTCR_BORLEV_SHIFT) /* 100: BOR Level 4 (2.8 V) */ +#define FLASH_OPTCR_RDP_SHIFT (0) /* Bits 0-7: Read Protection Level */ +#define FLASH_OPTCR_RDP_MASK (0xFF << FLASH_OPTCR_RDP_SHIFT) +#define FLASH_OPTCR_RDP_NONE (0xAA << FLASH_OPTCR_RDP_SHIFT) +#define FLASH_OPTCR_RDP_CHIP (0xCC << FLASH_OPTCR_RDP_SHIFT) /* WARNING, CANNOT BE REVERSED !! */ + +#endif /* __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4_FLASH_H */ diff --git a/arch/arm/src/stm32l4/stm32l4_flash.c b/arch/arm/src/stm32l4/stm32l4_flash.c index 14ac3614d6..f81d48ffab 100644 --- a/arch/arm/src/stm32l4/stm32l4_flash.c +++ b/arch/arm/src/stm32l4/stm32l4_flash.c @@ -62,7 +62,6 @@ #include "up_arch.h" - #if !(defined(CONFIG_STM32L4_STM32L4X3) || defined(CONFIG_STM32L4_STM32L4X6)) # error "Unrecognized STM32 chip" #endif diff --git a/arch/arm/src/stm32l4/stm32l4_flash.h b/arch/arm/src/stm32l4/stm32l4_flash.h index 15745b9377..afa8c7ddfd 100644 --- a/arch/arm/src/stm32l4/stm32l4_flash.h +++ b/arch/arm/src/stm32l4/stm32l4_flash.h @@ -39,224 +39,11 @@ #define __ARCH_ARM_SRC_STM32L4_STM32L4_FLASH_H /************************************************************************************ - * Pre-processor Definitions + * Included Files ************************************************************************************/ -/* Flash size is known from the chip selection: - * - * When CONFIG_STM32L4_FLASH_OVERRIDE_DEFAULT is set the - * CONFIG_STM32L4_FLASH_CONFIG_x selects the default FLASH size based on the chip - * part number. This value can be overridden with CONFIG_STM32L4_FLASH_OVERRIDE_x - * - * Parts STM32L4xxE have 512Kb of FLASH - * Parts STM32L4xxG have 1024Kb of FLASH - * - * N.B. Only Single bank mode is supported - */ - -#define _K(x) ((x)*1024) - -#if !defined(CONFIG_STM32L4_FLASH_OVERRIDE_DEFAULT) && \ - !defined(CONFIG_STM32L4_FLASH_OVERRIDE_B) && \ - !defined(CONFIG_STM32L4_FLASH_OVERRIDE_C) && \ - !defined(CONFIG_STM32L4_FLASH_OVERRIDE_E) && \ - !defined(CONFIG_STM32L4_FLASH_OVERRIDE_G) && \ - !defined(CONFIG_STM32L4_FLASH_CONFIG_B) && \ - !defined(CONFIG_STM32L4_FLASH_CONFIG_C) && \ - !defined(CONFIG_STM32L4_FLASH_CONFIG_E) && \ - !defined(CONFIG_STM32L4_FLASH_CONFIG_G) -# define CONFIG_STM32L4_FLASH_OVERRIDE_E -# warning "Flash size not defined defaulting to 512KiB (E)" -#endif - -/* Override of the Flash has been chosen */ - -#if !defined(CONFIG_STM32L4_FLASH_OVERRIDE_DEFAULT) -# undef CONFIG_STM32L4_FLASH_CONFIG_B -# undef CONFIG_STM32L4_FLASH_CONFIG_C -# undef CONFIG_STM32L4_FLASH_CONFIG_E -# undef CONFIG_STM32L4_FLASH_CONFIG_G -# if defined(CONFIG_STM32L4_FLASH_OVERRIDE_B) -# define CONFIG_STM32L4_FLASH_CONFIG_B -# elif defined(CONFIG_STM32L4_FLASH_OVERRIDE_C) -# define CONFIG_STM32L4_FLASH_CONFIG_C -# elif defined(CONFIG_STM32L4_FLASH_OVERRIDE_E) -# define CONFIG_STM32L4_FLASH_CONFIG_E -# elif defined(CONFIG_STM32L4_FLASH_OVERRIDE_G) -# define CONFIG_STM32L4_FLASH_CONFIG_G -# endif -#endif - -/* Define the valid configuration */ - -#if defined(CONFIG_STM32L4_FLASH_CONFIG_B) /* 128 kB */ -# define STM32L4_FLASH_NPAGES 64 -# define STM32L4_FLASH_PAGESIZE 2048 -#elif defined(CONFIG_STM32L4_FLASH_CONFIG_C) /* 256 kB */ -# define STM32L4_FLASH_NPAGES 128 -# define STM32L4_FLASH_PAGESIZE 2048 -#elif defined(CONFIG_STM32L4_FLASH_CONFIG_E) /* 512 kB */ -# define STM32L4_FLASH_NPAGES 256 -# define STM32L4_FLASH_PAGESIZE 2048 -#elif defined(CONFIG_STM32L4_FLASH_CONFIG_G) /* 1 MB */ -# define STM32L4_FLASH_NPAGES 512 -# define STM32L4_FLASH_PAGESIZE 2048 -#else -# error "unknown flash configuration!" -#endif - -#ifdef STM32L4_FLASH_PAGESIZE -# define STM32L4_FLASH_SIZE (STM32L4_FLASH_NPAGES * STM32L4_FLASH_PAGESIZE) -#endif - -/* Register Offsets *****************************************************************/ - -#define STM32L4_FLASH_ACR_OFFSET 0x0000 -#define STM32L4_FLASH_PDKEYR_OFFSET 0x0004 -#define STM32L4_FLASH_KEYR_OFFSET 0x0008 -#define STM32L4_FLASH_OPTKEYR_OFFSET 0x000c -#define STM32L4_FLASH_SR_OFFSET 0x0010 -#define STM32L4_FLASH_CR_OFFSET 0x0014 -#define STM32L4_FLASH_ECCR_OFFSET 0x0018 -#define STM32L4_FLASH_OPTR_OFFSET 0x0020 -#define STM32L4_FLASH_PCROP1SR_OFFSET 0x0024 -#define STM32L4_FLASH_PCROP1ER_OFFSET 0x0028 -#define STM32L4_FLASH_WRP1AR_OFFSET 0x002c -#define STM32L4_FLASH_WRP1BR_OFFSET 0x0030 -#if defined(CONFIG_STM32L4_STM32L4X6) -# define STM32L4_FLASH_PCROP2SR_OFFSET 0x0044 -# define STM32L4_FLASH_PCROP2ER_OFFSET 0x0048 -# define STM32L4_FLASH_WRP2AR_OFFSET 0x004c -# define STM32L4_FLASH_WRP2BR_OFFSET 0x0050 -#endif - -/* Register Addresses ***************************************************************/ - -#define STM32L4_FLASH_ACR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_ACR_OFFSET) -#define STM32L4_FLASH_PDKEYR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_PDKEYR_OFFSET) -#define STM32L4_FLASH_KEYR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_KEYR_OFFSET) -#define STM32L4_FLASH_OPTKEYR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_OPTKEYR_OFFSET) -#define STM32L4_FLASH_SR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_SR_OFFSET) -#define STM32L4_FLASH_CR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_CR_OFFSET) -#define STM32L4_FLASH_ECCR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_ECCR_OFFSET) -#define STM32L4_FLASH_OPTR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_OPTR_OFFSET) -#define STM32L4_FLASH_PCROP1SR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_PCROP1SR_OFFSET) -#define STM32L4_FLASH_PCROP1ER (STM32L4_FLASHIF_BASE+STM32L4_FLASH_PCROP1ER_OFFSET) -#define STM32L4_FLASH_WRP1AR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_WRP1AR_OFFSET) -#define STM32L4_FLASH_WRP1BR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_WRP1BR_OFFSET) -#if defined(CONFIG_STM32L4_STM32L4X6) -# define STM32L4_FLASH_PCROP2SR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_PCROP2SR_OFFSET) -# define STM32L4_FLASH_PCROP2ER (STM32L4_FLASHIF_BASE+STM32L4_FLASH_PCROP2ER_OFFSET) -# define STM32L4_FLASH_WRP2AR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_WRP2AR_OFFSET) -# define STM32L4_FLASH_WRP2BR (STM32L4_FLASHIF_BASE+STM32L4_FLASH_WRP2BR_OFFSET) -#endif - -/* Register Bitfield Definitions ****************************************************/ -/* Flash Access Control Register (ACR) */ - -#define FLASH_ACR_LATENCY_SHIFT (0) -#define FLASH_ACR_LATENCY_MASK (7 << FLASH_ACR_LATENCY_SHIFT) -# define FLASH_ACR_LATENCY(n) ((n) << FLASH_ACR_LATENCY_SHIFT) /* n wait states , for Vcore range 1 2 */ -# define FLASH_ACR_LATENCY_0 (0 << FLASH_ACR_LATENCY_SHIFT) /* 000: Zero wait states <=16 <=6 */ -# define FLASH_ACR_LATENCY_1 (1 << FLASH_ACR_LATENCY_SHIFT) /* 001: One wait state <=32 <=12 */ -# define FLASH_ACR_LATENCY_2 (2 << FLASH_ACR_LATENCY_SHIFT) /* 010: Two wait states <=48 <=18 */ -# define FLASH_ACR_LATENCY_3 (3 << FLASH_ACR_LATENCY_SHIFT) /* 011: Three wait states <=64 <=26 */ -# define FLASH_ACR_LATENCY_4 (4 << FLASH_ACR_LATENCY_SHIFT) /* 100: Four wait states <=80 <=26 */ - -#define FLASH_ACR_PRFTEN (1 << 8) /* Bit 8: Prefetch enable */ -#define FLASH_ACR_ICEN (1 << 9) /* Bit 9: Instruction cache enable */ -#define FLASH_ACR_DCEN (1 << 10) /* Bit 10: Data cache enable */ -#define FLASH_ACR_ICRST (1 << 11) /* Bit 11: Instruction cache reset */ -#define FLASH_ACR_DCRST (1 << 12) /* Bit 12: Data cache reset */ -#define FLASH_ACR_RUN_PD (1 << 13) /* Bit 13: Flash mode during Run */ -#define FLASH_ACR_SLEEP_PD (1 << 14) /* Bit 14: Flash mode during Sleep */ - -/* Flash Status Register (SR) */ - -#define FLASH_SR_EOP (1 << 0) /* Bit 0: End of operation */ -#define FLASH_SR_OPERR (1 << 1) /* Bit 1: Operation error */ -#define FLASH_SR_PROGERR (1 << 3) /* Bit 3: Programming error */ -#define FLASH_SR_WRPERR (1 << 4) /* Bit 4: Write protection error */ -#define FLASH_SR_PGAERR (1 << 5) /* Bit 5: Programming alignment error */ -#define FLASH_SR_SIZERR (1 << 6) /* Bit 6: Size error */ -#define FLASH_SR_PGSERR (1 << 7) /* Bit 7: Programming sequence error */ -#define FLASH_SR_MISERR (1 << 8) /* Bit 8: Fast programming data miss error */ -#define FLASH_SR_FASTERR (1 << 9) /* Bit 9: Fast programming error */ -#define FLASH_SR_RDERR (1 << 14) /* Bit 14: PCROP read error */ -#define FLASH_SR_OPTVERR (1 << 15) /* Bit 15: Option validity error */ -#define FLASH_SR_BSY (1 << 16) /* Bit 16: Busy */ -#if defined(CONFIG_STM32L4_STM32L4X3) -# define FLASH_SR_PEMPTY (1 << 17) /* Bit 17: Program empty */ -#endif - -/* Flash Control Register (CR) */ - -#define FLASH_CR_PG (1 << 0) /* Bit 0 : Program Page */ -#define FLASH_CR_PER (1 << 1) /* Bit 1 : Page Erase */ -#define FLASH_CR_MER1 (1 << 2) /* Bit 2 : Mass Erase Bank 1 */ - -#define FLASH_CR_PNB_SHIFT (3) /* Bits 3-10: Page number */ -#define FLASH_CR_PNB_MASK (0xFF << FLASH_CR_PNB_SHIFT) -#define FLASH_CR_PNB(n) ((n) << FLASH_CR_PNB_SHIFT) /* Page n (if BKER=0) or n+256 (if BKER=1), n=0..255 */ - -#if defined(CONFIG_STM32L4_STM32L4X6) -# define FLASH_CR_BKER (1 << 11) /* Bit 11: Page number MSB (Bank selection) */ -# define FLASH_CR_MER2 (1 << 15) /* Bit 15: Mass Erase Bank 2 */ -#endif -#define FLASH_CR_START (1 << 16) /* Bit 16: Start Erase */ -#define FLASH_CR_OPTSTRT (1 << 17) /* Bit 17: Options modification Start */ -#define FLASH_CR_FSTPG (1 << 23) /* Bit 23: Fast programming */ -#define FLASH_CR_EOPIE (1 << 24) /* Bit 24: End of operation interrupt enable */ -#define FLASH_CR_ERRIE (1 << 25) /* Bit 25: Error interrupt enable */ -#define FLASH_CR_RDERRIE (1 << 26) /* Bit 26: PCROP read error interrupt enable */ -#define FLASH_CR_OBL_LAUNCH (1 << 27) /* Bit 27: Option Byte Loading */ -#define FLASH_CR_OPTLOCK (1 << 30) /* Bit 30: Option Lock */ -#define FLASH_CR_LOCK (1 << 31) /* Bit 31: Lock */ - -/* Flash ECC Register (ECCR) */ - -#define FLASH_ECCR_ADDR_ECC_SHIFT (0) /* Bits 8-15: Read protect */ -#define FLASH_ECCR_ADDR_ECC_MASK (0x07ffff << FLASH_ECCR_ADDR_ECC_SHIFT) -#if defined(CONFIG_STM32L4_STM32L4X6) -# define FLASH_ECCR_BK_ECC (1 << 19) /* Bit 19: ECC fail bank */ -#endif -#define FLASH_ECCR_SYSF_ECC (1 << 20) /* Bit 20: System Flash ECC fail */ -#define FLASH_ECCR_ECCCIE (1 << 24) /* Bit 24: ECC correction interrupt enable */ -#define FLASH_ECCR_ECCC (1 << 30) /* Bit 30: ECC correction */ -#define FLASH_ECCR_ECCD (1 << 31) /* Bit 31: ECC detection */ - -/* Flash Option Control Register (OPTCR) */ - -#define FLASH_OPTCR_NRST_STOP (1 << 12) /* Bit 12: Generate reset when entering the Stop mode */ -#define FLASH_OPTCR_NRST_STDBY (1 << 13) /* Bit 13: Generate reset when entering the Standby mode */ -#define FLASH_OPTCR_NRST_SHDW (1 << 14) /* Bit 14: Generate reset when entering the Shutdown mode */ -#define FLASH_OPTCR_IWDG_SW (1 << 16) /* Bit 16: Independent watchdog selection */ -#define FLASH_OPTCR_IWDG_STOP (1 << 17) /* Bit 17: Independent watchdog counter freeze in Stop mode */ -#define FLASH_OPTCR_IWDG_STDBY (1 << 18) /* Bit 18: Independent watchdog counter freeze in Standby mode*/ -#define FLASH_OPTCR_WWDG_SW (1 << 19) /* Bit 19: Window watchdog selection */ -#if defined(CONFIG_STM32L4_STM32L4X6) -# define FLASH_OPTCR_BFB2 (1 << 20) /* Bit 20: Dual bank boot */ -# define FLASH_OPTCR_DUALBANK (1 << 21) /* Bit 21: Dual bank enable */ -#endif -#define FLASH_OPTCR_NBOOT1 (1 << 23) /* Bit 23: Boot configuration */ -#define FLASH_OPTCR_SRAM2_PE (1 << 24) /* Bit 24: SRAM2 parity check enable */ -#define FLASH_OPTCR_SRAM2_RST (1 << 25) /* Bit 25: SRAM2 Erase when system reset */ -#if defined(CONFIG_STM32L4_STM32L4X3) || defined(CONFIG_STM32L4_STM32L496XX) -# define FLASH_OPTCR_NSWBOOT0 (1 << 26) /* Bit 26: Software BOOT0 */ -# define FLASH_OPTCR_NBOOT0 (1 << 27) /* Bit 27: nBOOT0 option bit */ -#endif - -#define FLASH_OPTCR_BORLEV_SHIFT (8) /* Bits 8-10: BOR reset Level */ -#define FLASH_OPTCR_BORLEV_MASK (7 << FLASH_OPTCR_BORLEV_SHIFT) -#define FLASH_OPTCR_VBOR0 (0 << FLASH_OPTCR_BORLEV_SHIFT) /* 000: BOR Level 0 (1.7 V) */ -#define FLASH_OPTCR_VBOR1 (1 << FLASH_OPTCR_BORLEV_SHIFT) /* 001: BOR Level 1 (2.0 V) */ -#define FLASH_OPTCR_VBOR2 (2 << FLASH_OPTCR_BORLEV_SHIFT) /* 010: BOR Level 2 (2.2 V) */ -#define FLASH_OPTCR_VBOR3 (3 << FLASH_OPTCR_BORLEV_SHIFT) /* 011: BOR Level 3 (2.5 V) */ -#define FLASH_OPTCR_VBOR4 (4 << FLASH_OPTCR_BORLEV_SHIFT) /* 100: BOR Level 4 (2.8 V) */ -#define FLASH_OPTCR_RDP_SHIFT (0) /* Bits 0-7: Read Protection Level */ -#define FLASH_OPTCR_RDP_MASK (0xFF << FLASH_OPTCR_RDP_SHIFT) -#define FLASH_OPTCR_RDP_NONE (0xAA << FLASH_OPTCR_RDP_SHIFT) -#define FLASH_OPTCR_RDP_CHIP (0xCC << FLASH_OPTCR_RDP_SHIFT) /* WARNING, CANNOT BE REVERSED !! */ +#include +#include "chip/stm32l4_flash.h" /************************************************************************************ * Public Functions -- GitLab From ba933efd9e786ac457bad17d093ee69146a447ef Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Thu, 11 May 2017 07:11:35 -0600 Subject: [PATCH 785/990] When syslog message has addition characters after last new-line. With buffering those now get lost as vsyslog does not flush output after lib_sprintf. Additional trailing characters could be ANSI escape sequence to reset state that message setups. For example, macro here uses colors and resets state after actual message (including '\n'): With flushing added to vsyslog, then there is problem that next syslog line might come from other task before reset sequence, causing wrong line getting color. This could be avoided by not flushing on '\n' but only if IOB is full and/or at end of vsyslog. Would this make sense? --- drivers/syslog/syslog_stream.c | 4 ++-- drivers/syslog/vsyslog.c | 4 ++++ 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/drivers/syslog/syslog_stream.c b/drivers/syslog/syslog_stream.c index 04bb0726b0..ac7e144ceb 100644 --- a/drivers/syslog/syslog_stream.c +++ b/drivers/syslog/syslog_stream.c @@ -82,9 +82,9 @@ static void syslogstream_putc(FAR struct lib_outstream_s *this, int ch) iob->io_len++; this->nput++; - /* Is the buffer full? Did we encounter a new line? */ + /* Is the buffer full? */ - if (iob->io_len >= CONFIG_IOB_BUFSIZE || ch == '\n') + if (iob->io_len >= CONFIG_IOB_BUFSIZE) { /* Yes.. then flush the buffer */ diff --git a/drivers/syslog/vsyslog.c b/drivers/syslog/vsyslog.c index cbb8588240..94e818dc04 100644 --- a/drivers/syslog/vsyslog.c +++ b/drivers/syslog/vsyslog.c @@ -130,6 +130,10 @@ int _vsyslog(int priority, FAR const IPTR char *fmt, FAR va_list *ap) ret = lib_vsprintf(&stream.public, fmt, *ap); + /* Flush the output */ + + stream.public.flush(&stream.public); + #ifdef CONFIG_SYSLOG_BUFFER /* Destroy the syslog stream buffer */ -- GitLab From b5c1dd09f5fba780bf4bba5dc15a86718ad6951a Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 11 May 2017 07:15:57 -0600 Subject: [PATCH 786/990] Syslog: Need inclusion of errno.h for fix building with CONFIG_SYSLOG_TIMESTMAP=y --- drivers/syslog/vsyslog.c | 1 + 1 file changed, 1 insertion(+) diff --git a/drivers/syslog/vsyslog.c b/drivers/syslog/vsyslog.c index 94e818dc04..0b993b7186 100644 --- a/drivers/syslog/vsyslog.c +++ b/drivers/syslog/vsyslog.c @@ -41,6 +41,7 @@ #include #include +#include #include #include -- GitLab From 797e3c3ca4e7cdb1876167c6d540c355a7b294dc Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Thu, 11 May 2017 07:17:29 -0600 Subject: [PATCH 787/990] mtd: build RAMTRON and AT45DB drivers only if selected --- drivers/mtd/Make.defs | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/drivers/mtd/Make.defs b/drivers/mtd/Make.defs index bef1779f7a..ac3ee92116 100644 --- a/drivers/mtd/Make.defs +++ b/drivers/mtd/Make.defs @@ -39,7 +39,7 @@ ifeq ($(CONFIG_MTD),y) -CSRCS += at45db.c ftl.c ramtron.c mtd_config.c +CSRCS += ftl.c mtd_config.c ifeq ($(CONFIG_MTD_PARTITION),y) CSRCS += mtd_partition.c @@ -80,6 +80,14 @@ ifeq ($(CONFIG_MTD_AT24XX),y) CSRCS += at24xx.c endif +ifeq ($(CONFIG_MTD_AT45DB),y) +CSRCS += at45db.c +endif + +ifeq ($(CONFIG_MTD_RAMTRON),y) +CSRCS += ramtron.c +endif + ifeq ($(CONFIG_MTD_SST25),y) CSRCS += sst25.c endif -- GitLab From 58a0b09b82563299c3df02cf41e3a59e49de4cf4 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Thu, 11 May 2017 07:19:24 -0600 Subject: [PATCH 788/990] mtd/config: fix byte read interface test --- drivers/mtd/mtd_config.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/drivers/mtd/mtd_config.c b/drivers/mtd/mtd_config.c index 1502679548..d56c26cc89 100644 --- a/drivers/mtd/mtd_config.c +++ b/drivers/mtd/mtd_config.c @@ -148,7 +148,7 @@ static const struct file_operations mtdconfig_fops = /**************************************************************************** * Name: mtdconfig_readbytes * - * Reads bytes from the contained MTD device. This will either usee + * Reads bytes from the contained MTD device. This will either use * the read function or if that is not available, the bread with a copy. * ****************************************************************************/ @@ -162,9 +162,9 @@ static int mtdconfig_readbytes(FAR struct mtdconfig_struct_s *dev, int offset, int ret = OK; size_t bytes; - /* Test if read interface supported. If it is, use it directly */ + /* Test if read interface supported. If it is, use it directly. */ - if ((dev->mtd->read == NULL) && (readlen < dev->blocksize)) + if ((dev->mtd->read != NULL) && (readlen < dev->blocksize)) { /* Read interface available. Read directly to buffer */ -- GitLab From 0f7210b0ae2f5d70d9cd4636a353ca9ffd161495 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Thu, 11 May 2017 07:22:21 -0600 Subject: [PATCH 789/990] mtd: fix some unallocated and NULL pointer issues. rwb->wrflush and rwb->wrmaxblocks in rwbuffer could get unallocated values from ftl_initialize() in some configurations. Also fixes related assert: up_assert: Assertion failed at file:rwbuffer.c line: 643 that can happen with the following configuration: CONFIG_FTL_WRITEBUFFER=y CONFIG_DRVR_WRITEBUFFER=y # CONFIG_FS_WRITABLE is not set These problems are caused by CONFIG variable differences between the buffer layers. TODO: This is not a perfect solution. readahead support has similar issues. --- drivers/mtd/Kconfig | 2 +- drivers/mtd/ftl.c | 8 ++++- drivers/mtd/mtd_rwbuffer.c | 72 ++++++++++++++++++++------------------ 3 files changed, 45 insertions(+), 37 deletions(-) diff --git a/drivers/mtd/Kconfig b/drivers/mtd/Kconfig index ba45d0f512..8065b95674 100644 --- a/drivers/mtd/Kconfig +++ b/drivers/mtd/Kconfig @@ -29,7 +29,7 @@ config MTD_PARTITION config FTL_WRITEBUFFER bool "Enable write buffering in the FTL layer" default n - depends on DRVR_WRITEBUFFER + depends on DRVR_WRITEBUFFER && FS_WRITABLE config FTL_READAHEAD bool "Enable read-ahead buffering in the FTL layer" diff --git a/drivers/mtd/ftl.c b/drivers/mtd/ftl.c index 13f832c351..e3faab18ac 100644 --- a/drivers/mtd/ftl.c +++ b/drivers/mtd/ftl.c @@ -528,7 +528,7 @@ int ftl_initialize(int minor, FAR struct mtd_dev_s *mtd) /* Allocate a FTL device structure */ - dev = (struct ftl_struct_s *)kmm_malloc(sizeof(struct ftl_struct_s)); + dev = (struct ftl_struct_s *)kmm_zalloc(sizeof(struct ftl_struct_s)); if (dev) { /* Initialize the FTL device structure */ @@ -586,6 +586,9 @@ int ftl_initialize(int minor, FAR struct mtd_dev_s *mtd) if (ret < 0) { ferr("ERROR: rwb_initialize failed: %d\n", ret); +#ifdef CONFIG_FS_WRITABLE + kmm_free(dev->eblock); +#endif kmm_free(dev); return ret; } @@ -601,6 +604,9 @@ int ftl_initialize(int minor, FAR struct mtd_dev_s *mtd) if (ret < 0) { ferr("ERROR: register_blockdriver failed: %d\n", -ret); +#ifdef CONFIG_FS_WRITABLE + kmm_free(dev->eblock); +#endif kmm_free(dev); } } diff --git a/drivers/mtd/mtd_rwbuffer.c b/drivers/mtd/mtd_rwbuffer.c index b775b67cfd..7c76c5b4a5 100644 --- a/drivers/mtd/mtd_rwbuffer.c +++ b/drivers/mtd/mtd_rwbuffer.c @@ -357,57 +357,60 @@ FAR struct mtd_dev_s *mtd_rwb_initialize(FAR struct mtd_dev_s *mtd) */ priv = (FAR struct mtd_rwbuffer_s *)kmm_zalloc(sizeof(struct mtd_rwbuffer_s)); - if (priv) + if (!priv) { - /* Initialize the allocated structure. (unsupported methods/fields - * were already nullified by kmm_zalloc). - */ + ferr("ERROR: Failed to allocate mtd_rwbuffer\n"); + return NULL; + } - priv->mtd.erase = mtd_erase; /* Our MTD erase method */ - priv->mtd.bread = mtd_bread; /* Our MTD bread method */ - priv->mtd.bwrite = mtd_bwrite; /* Our MTD bwrite method */ - priv->mtd.read = mtd_read; /* Our MTD read method */ - priv->mtd.ioctl = mtd_ioctl; /* Our MTD ioctl method */ + /* Initialize the allocated structure. (unsupported methods/fields + * were already nullified by kmm_zalloc). + */ - priv->dev = mtd; /* The contained MTD instance */ + priv->mtd.erase = mtd_erase; /* Our MTD erase method */ + priv->mtd.bread = mtd_bread; /* Our MTD bread method */ + priv->mtd.bwrite = mtd_bwrite; /* Our MTD bwrite method */ + priv->mtd.read = mtd_read; /* Our MTD read method */ + priv->mtd.ioctl = mtd_ioctl; /* Our MTD ioctl method */ - /* Sectors per block. The erase block size must be an even multiple - * of the sector size. - */ + priv->dev = mtd; /* The contained MTD instance */ + + /* Sectors per block. The erase block size must be an even multiple + * of the sector size. + */ - priv->spb = geo.erasesize / geo.blocksize; - DEBUGASSERT((size_t)priv->spb * geo.blocksize == geo.erasesize); + priv->spb = geo.erasesize / geo.blocksize; + DEBUGASSERT((size_t)priv->spb * geo.blocksize == geo.erasesize); - /* Values must be provided to rwb_initialize() */ - /* Supported geometry */ + /* Values must be provided to rwb_initialize() */ + /* Supported geometry */ - priv->rwb.blocksize = geo.blocksize; - priv->rwb.nblocks = geo.neraseblocks * priv->spb; + priv->rwb.blocksize = geo.blocksize; + priv->rwb.nblocks = geo.neraseblocks * priv->spb; - /* Buffer setup */ + /* Buffer setup */ #ifdef CONFIG_DRVR_WRITEBUFFER - priv->rwb.wrmaxblocks = CONFIG_MTD_NWRBLOCKS; + priv->rwb.wrmaxblocks = CONFIG_MTD_NWRBLOCKS; #endif #ifdef CONFIG_DRVR_READAHEAD - priv->rwb.rhmaxblocks = CONFIG_MTD_NRDBLOCKS; + priv->rwb.rhmaxblocks = CONFIG_MTD_NRDBLOCKS; #endif - /* Callouts */ + /* Callouts */ - priv->rwb.dev = priv; /* Device state passed to callouts */ - priv->rwb.wrflush = mtd_flush; /* Callout to flush buffer */ - priv->rwb.rhreload = mtd_reload; /* Callout to reload buffer */ + priv->rwb.dev = priv; /* Device state passed to callouts */ + priv->rwb.wrflush = mtd_flush; /* Callout to flush buffer */ + priv->rwb.rhreload = mtd_reload; /* Callout to reload buffer */ - /* Initialize read-ahead/write buffering */ + /* Initialize read-ahead/write buffering */ - ret = rwb_initialize(&priv->rwb); - if (ret < 0) - { - ferr("ERROR: rwb_initialize failed: %d\n", ret); - kmm_free(priv); - return NULL; - } + ret = rwb_initialize(&priv->rwb); + if (ret < 0) + { + ferr("ERROR: rwb_initialize failed: %d\n", ret); + kmm_free(priv); + return NULL; } /* Register the MTD with the procfs system if enabled */ @@ -418,7 +421,6 @@ FAR struct mtd_dev_s *mtd_rwb_initialize(FAR struct mtd_dev_s *mtd) /* Return the implementation-specific state structure as the MTD device */ - finfo("Return %p\n", priv); return &priv->mtd; } -- GitLab From 41680d376d4f942de29d1ebe3197f73bef866430 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 11 May 2017 13:15:13 -0600 Subject: [PATCH 790/990] Replace 'the the' with 'the' --- fs/inode/fs_inodesearch.c | 17 ++++++++--------- fs/tmpfs/Kconfig | 2 +- fs/tmpfs/fs_tmpfs.c | 4 ++-- fs/unionfs/README.txt | 2 +- fs/unionfs/fs_unionfs.c | 4 ++-- fs/vfs/fs_link.c | 2 +- 6 files changed, 15 insertions(+), 16 deletions(-) diff --git a/fs/inode/fs_inodesearch.c b/fs/inode/fs_inodesearch.c index c4d6cc0792..08f68fe8b1 100644 --- a/fs/inode/fs_inodesearch.c +++ b/fs/inode/fs_inodesearch.c @@ -352,8 +352,8 @@ static int _inode_search(FAR struct inode_search_s *desc) status = _inode_linktarget(node, desc); if (status < 0) { - /* Probably means that the the target of the symbolic - * link does not exist. + /* Probably means that the target of the symbolic link + * does not exist. */ ret = status; @@ -366,8 +366,8 @@ static int _inode_search(FAR struct inode_search_s *desc) if (newnode != node) { /* The node was a valid symbolic link and we have - * jumped to a different, spot in the the pseudo - * file system tree. + * jumped to a different, spot in the pseudo file + * system tree. */ /* Check if this took us to a mountpoint. */ @@ -539,11 +539,10 @@ int inode_search(FAR struct inode_search_s *desc) /* There would be no problem in this case if the link was to * either to the root directory of the MOUNTPOINT or to a - * regular file within the the mounted volume. However, - * there is a problem if the symbolic link is to a directory - * within the mounted volume. In that case, the 'relpath' - * will be relative to the symbolic link and not to the - * MOUNTPOINT. + * regular file within the mounted volume. However, there + * is a problem if the symbolic link is to a directory within + * the mounted volume. In that case, the 'relpath' will be + * relative to the symbolic link and not to the MOUNTPOINT. * * We will handle the worst case by creating the full path * excluding the symbolic link and performing the look-up diff --git a/fs/tmpfs/Kconfig b/fs/tmpfs/Kconfig index 9eebf3b964..04ac7413a8 100644 --- a/fs/tmpfs/Kconfig +++ b/fs/tmpfs/Kconfig @@ -22,7 +22,7 @@ config FS_TMPFS_BLOCKSIZE of blocks. There are, of course, no blocks with the TMPFS. This options is available to control how sizes are reported. For very small TMPFS systems, you might want to set this to something smaller - the the usual 512 bytes. + the usual 512 bytes. config FS_TMPFS_DIRECTORY_ALLOCGUARD int "Directory object over-allocation" diff --git a/fs/tmpfs/fs_tmpfs.c b/fs/tmpfs/fs_tmpfs.c index 44268ea4ab..35bacf0e12 100644 --- a/fs/tmpfs/fs_tmpfs.c +++ b/fs/tmpfs/fs_tmpfs.c @@ -962,7 +962,7 @@ static int tmpfs_find_object(FAR struct tmpfs_s *fs, next_segment = strtok_r(NULL, "/", &tkptr); - /* Search the the next directory. */ + /* Search the next directory. */ tdo = next_tdo; @@ -1301,7 +1301,7 @@ static int tmpfs_foreach(FAR struct tmpfs_directory_s *tdo, FAR struct tmpfs_directory_s *next = (FAR struct tmpfs_directory_s *)to; - /* Yes.. traverse its children first in the case the the final + /* Yes.. traverse its children first in the case the final * action will be to delete the directory. */ diff --git a/fs/unionfs/README.txt b/fs/unionfs/README.txt index 0e913dfacf..f50cdb46eb 100755 --- a/fs/unionfs/README.txt +++ b/fs/unionfs/README.txt @@ -37,7 +37,7 @@ fs/unionfs/README.txt in functions provide CGI programs. But the BINFS file system cannot hold content. Fixed content would need to be retained in a more standard file system such as ROMFS. With this Union File System, you can overly the - BINFS mountpoint on the the ROMFS mountpoint, providing a single directory + BINFS mountpoint on the ROMFS mountpoint, providing a single directory that appears to contain the executables from the BINFS file system along with the web content from the ROMFS file system. diff --git a/fs/unionfs/fs_unionfs.c b/fs/unionfs/fs_unionfs.c index bb3b6abcfb..41ba128c9b 100644 --- a/fs/unionfs/fs_unionfs.c +++ b/fs/unionfs/fs_unionfs.c @@ -275,7 +275,7 @@ static FAR const char *unionfs_offsetpath(FAR const char *relpath, FAR const char *trypath; int pfxlen; - /* Is there a prefix on the the path to this file system? */ + /* Is there a prefix on the path to this file system? */ if (prefix && (pfxlen = strlen(prefix)) > 0) { @@ -1634,7 +1634,7 @@ static int unionfs_readdir(struct inode *mountpt, struct fs_dirent_s *dir) DEBUGASSERT(dir); fu = &dir->u.unionfs; - /* Check if we are at the end of the the directory listing. */ + /* Check if we are at the end of the directory listing. */ if (fu->fu_eod) { diff --git a/fs/vfs/fs_link.c b/fs/vfs/fs_link.c index 556343ecdd..767eda06da 100644 --- a/fs/vfs/fs_link.c +++ b/fs/vfs/fs_link.c @@ -82,7 +82,7 @@ * * Returned Value: * On success, zero (OK) is returned. Otherwise, -1 (ERROR) is returned - * the the errno variable is set appropriately. + * the errno variable is set appropriately. * ****************************************************************************/ -- GitLab From ba12817f9c437d0a84783d6284bcb2e578620bd1 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 11 May 2017 13:15:31 -0600 Subject: [PATCH 791/990] Upate some comments --- sched/pthread/pthread_cancel.c | 4 ++-- sched/sched/sched_idletask.c | 4 ++++ 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/sched/pthread/pthread_cancel.c b/sched/pthread/pthread_cancel.c index 20e6f838b7..4914457c86 100644 --- a/sched/pthread/pthread_cancel.c +++ b/sched/pthread/pthread_cancel.c @@ -60,8 +60,8 @@ int pthread_cancel(pthread_t thread) if (thread == 0) { - /* pid == 0 is the IDLE task. Callers cannot cancel the - * IDLE task. + /* pid == 0 is the IDLE task (in a single CPU configuration). Callers + * cannot cancel the IDLE task. */ return ESRCH; diff --git a/sched/sched/sched_idletask.c b/sched/sched/sched_idletask.c index 9885aca1a7..f8c0b3768d 100644 --- a/sched/sched/sched_idletask.c +++ b/sched/sched/sched_idletask.c @@ -84,6 +84,10 @@ bool sched_idletask(void) * (1) It always lies at the end of the task list, * (2) It always has priority zero, and * (3) It should have the TCB_FLAG_CPU_LOCKED flag set. + * + * In the non-SMP case, the IDLE task will also have PID=0, but that + * is not a portable test because there are multiple IDLE tasks with + * different PIDs in the SMP configuration. */ return (rtcb->flink == NULL); -- GitLab From 0de294a5868f0226a816d73f489e84ae16ba3910 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 11 May 2017 13:35:56 -0600 Subject: [PATCH 792/990] Fix lots of occurrences of 'the the', 'the there', 'the these', 'the then', 'the they. --- ChangeLog | 8 +++---- Documentation/NfsHowto.html | 2 +- Documentation/NuttXBinfmt.html | 2 +- Documentation/NuttxPortingGuide.html | 8 +++---- Documentation/NuttxUserGuide.html | 4 ++-- ReleaseNotes | 4 ++-- TODO | 2 +- arch/Kconfig | 2 +- arch/arm/include/stm32/ltdc.h | 2 +- arch/arm/src/a1x/a1x_lowputc.c | 2 +- arch/arm/src/armv7-a/arm_addrenv.c | 2 +- arch/arm/src/armv7-a/arm_gicv2.c | 2 +- arch/arm/src/armv7-a/pgalloc.h | 2 +- arch/arm/src/armv7-m/gnu/up_exception.S | 4 ++-- arch/arm/src/armv7-m/gnu/up_lazyexception.S | 4 ++-- arch/arm/src/efm32/efm32_dma.h | 2 +- arch/arm/src/efm32/efm32_usbhost.c | 10 ++++----- arch/arm/src/efm32/efm32_vectors.S | 4 ++-- arch/arm/src/imx6/imx_memorymap.h | 2 +- arch/arm/src/kinetis/kinetis_lpserial.c | 2 +- arch/arm/src/kinetis/kinetis_sdhc.c | 2 +- arch/arm/src/kinetis/kinetis_vectors.S | 4 ++-- arch/arm/src/lpc11xx/lpc11_serial.c | 2 +- arch/arm/src/lpc17xx/lpc17_usbhost.c | 2 +- arch/arm/src/lpc17xx/lpc17_vectors.S | 4 ++-- arch/arm/src/lpc31xx/Kconfig | 2 +- arch/arm/src/lpc31xx/lpc31_ehci.c | 6 ++--- arch/arm/src/lpc43xx/lpc43_ehci.c | 6 ++--- arch/arm/src/lpc43xx/lpc43_ethernet.c | 2 +- arch/arm/src/sam34/sam4cm_oneshot.c | 2 +- arch/arm/src/sam34/sam4cm_tc.c | 2 +- arch/arm/src/sam34/sam4cm_tickless.c | 2 +- arch/arm/src/sam34/sam_emac.c | 6 ++--- arch/arm/src/sam34/sam_vectors.S | 4 ++-- arch/arm/src/sama5/Kconfig | 8 +++---- arch/arm/src/sama5/chip/sam_emaca.h | 2 +- arch/arm/src/sama5/chip/sam_emacb.h | 2 +- arch/arm/src/sama5/sam_adc.c | 6 ++--- arch/arm/src/sama5/sam_allocateheap.c | 2 +- arch/arm/src/sama5/sam_dbgu.c | 2 +- arch/arm/src/sama5/sam_ehci.c | 6 ++--- arch/arm/src/sama5/sam_emaca.c | 6 ++--- arch/arm/src/sama5/sam_emacb.c | 6 ++--- arch/arm/src/sama5/sam_gmac.c | 6 ++--- arch/arm/src/sama5/sam_hsmci.c | 2 +- arch/arm/src/sama5/sam_memorymap.h | 2 +- arch/arm/src/sama5/sam_nand.c | 2 +- arch/arm/src/sama5/sam_ohci.c | 2 +- arch/arm/src/sama5/sam_oneshot.c | 2 +- arch/arm/src/sama5/sam_tc.c | 2 +- arch/arm/src/sama5/sam_tickless.c | 2 +- arch/arm/src/sama5/sam_udphs.c | 4 ++-- arch/arm/src/sama5/sama5d2x_pio.c | 6 ++--- arch/arm/src/sama5/sama5d3x4x_pio.c | 8 +++---- arch/arm/src/samdl/sam_timerisr.c | 2 +- arch/arm/src/samdl/saml_clockconfig.c | 2 +- arch/arm/src/samv7/chip/sam_emac.h | 2 +- arch/arm/src/samv7/sam_dac.c | 2 +- arch/arm/src/samv7/sam_emac.c | 6 ++--- arch/arm/src/samv7/sam_hsmci.c | 2 +- arch/arm/src/samv7/sam_oneshot.c | 2 +- arch/arm/src/samv7/sam_tc.c | 2 +- arch/arm/src/samv7/sam_tickless.c | 2 +- arch/arm/src/samv7/sam_usbdevhs.c | 2 +- arch/arm/src/stm32/Kconfig | 2 +- arch/arm/src/stm32/gnu/stm32_vectors.S | 4 ++-- arch/arm/src/stm32/iar/stm32_vectors.S | 4 ++-- arch/arm/src/stm32/stm32_bbsram.c | 2 +- arch/arm/src/stm32/stm32_dma.h | 2 +- arch/arm/src/stm32/stm32_eth.c | 2 +- arch/arm/src/stm32/stm32_ltdc.c | 2 +- arch/arm/src/stm32/stm32_oneshot.c | 2 +- arch/arm/src/stm32/stm32_otgfsdev.c | 2 +- arch/arm/src/stm32/stm32_otgfshost.c | 8 +++---- arch/arm/src/stm32/stm32_otghshost.c | 8 +++---- arch/arm/src/stm32/stm32_tickless.c | 2 +- arch/arm/src/stm32/stm32f40xxx_rtcc.c | 2 +- arch/arm/src/stm32f0/stm32f0_hsi48.c | 2 +- arch/arm/src/stm32f7/stm32_bbsram.c | 2 +- arch/arm/src/stm32f7/stm32_dma.h | 2 +- arch/arm/src/stm32f7/stm32_ethernet.c | 2 +- arch/arm/src/stm32f7/stm32_otghost.c | 8 +++---- arch/arm/src/stm32l4/stm32l4_dma.h | 2 +- arch/arm/src/stm32l4/stm32l4_oneshot.c | 2 +- arch/arm/src/stm32l4/stm32l4_otgfshost.c | 8 +++---- arch/arm/src/stm32l4/stm32l4_rtcc.c | 2 +- arch/arm/src/stm32l4/stm32l4_tickless.c | 2 +- arch/arm/src/tiva/tiva_i2c.c | 4 ++-- arch/arm/src/tiva/tiva_timer.h | 4 ++-- arch/arm/src/tiva/tiva_timerlib.c | 2 +- arch/arm/src/tiva/tiva_timerlow32.c | 2 +- arch/arm/src/tiva/tiva_vectors.S | 4 ++-- arch/arm/src/tiva/tm4c_ethernet.c | 4 ++-- arch/misoc/src/common/misoc.h | 2 +- arch/sim/src/up_simsmp.c | 2 +- arch/sim/src/up_tickless.c | 2 +- arch/xtensa/src/common/xtensa_testset.c | 2 +- arch/xtensa/src/esp32/chip/esp32_uart.h | 2 +- arch/xtensa/src/esp32/esp32_gpio.h | 2 +- .../src/esp32/esp32_intercpu_interrupt.c | 2 +- arch/z16/src/z16f/z16f_clkinit.c | 2 +- arch/z16/src/z16f/z16f_espi.c | 2 +- arch/z16/src/z16f/z16f_serial.c | 2 +- audio/README.txt | 2 +- audio/pcm_decode.c | 4 ++-- binfmt/binfmt_exepath.c | 4 ++-- binfmt/libpcode/README.txt | 2 +- configs/Kconfig | 4 ++-- configs/README.txt | 4 ++-- configs/arduino-due/src/sam_appinit.c | 2 +- configs/bambino-200e/src/lpc43_appinit.c | 2 +- configs/boardctl.c | 2 +- configs/cc3200-launchpad/src/cc3200_boot.c | 2 +- configs/clicker2-stm32/src/stm32_appinit.c | 2 +- configs/cloudctrl/README.txt | 2 +- configs/cloudctrl/src/stm32_appinit.c | 2 +- configs/demo9s12ne64/src/m9s12_appinit.c | 2 +- configs/dk-tm4c129x/src/tm4c_appinit.c | 2 +- configs/ea3131/src/lpc31_appinit.c | 2 +- configs/ea3152/src/lpc31_appinit.c | 2 +- configs/eagle100/src/lm_appinit.c | 2 +- configs/ekk-lm3s9b96/src/lm_appinit.c | 2 +- configs/esp32-core/README.txt | 2 +- configs/esp32-core/src/esp32_appinit.c | 2 +- configs/ez80f910200zco/README.txt | 2 +- configs/fire-stm32v2/src/stm32_appinit.c | 2 +- configs/freedom-k64f/include/board.h | 2 +- configs/freedom-k64f/src/k64_appinit.c | 2 +- configs/freedom-k64f/src/k64_automount.c | 2 +- configs/freedom-k66f/include/board.h | 2 +- configs/freedom-k66f/src/k66_appinit.c | 2 +- configs/freedom-k66f/src/k66_automount.c | 2 +- configs/freedom-kl25z/src/kl_appinit.c | 2 +- configs/freedom-kl26z/src/kl_appinit.c | 2 +- configs/hymini-stm32v/src/stm32_appinit.c | 2 +- configs/kwikstik-k40/src/k40_appinit.c | 2 +- configs/launchxl-tms57004/README.txt | 2 +- .../launchxl-tms57004/src/tms570_appinit.c | 2 +- configs/lincoln60/src/lpc17_appinit.c | 2 +- configs/lm3s6432-s2e/src/lm_appinit.c | 2 +- configs/lm3s6965-ek/src/lm_appinit.c | 2 +- configs/lm3s8962-ek/src/lm_appinit.c | 2 +- configs/lm4f120-launchpad/src/lm4f_appinit.c | 2 +- configs/lpc4330-xplorer/README.txt | 2 +- configs/lpc4330-xplorer/src/lpc43_appinit.c | 2 +- configs/lpc4337-ws/README.txt | 2 +- configs/lpc4337-ws/src/lpc43_appinit.c | 2 +- configs/lpc4357-evb/README.txt | 2 +- configs/lpc4357-evb/src/lpc43_appinit.c | 2 +- configs/lpc4370-link2/README.txt | 2 +- configs/lpc4370-link2/src/lpc43_appinit.c | 2 +- configs/lpcxpresso-lpc1115/README.txt | 2 +- .../lpcxpresso-lpc1115/src/lpc11_appinit.c | 2 +- configs/lpcxpresso-lpc1768/README.txt | 2 +- .../lpcxpresso-lpc1768/src/lpc17_appinit.c | 2 +- configs/maple/src/stm32_appinit.c | 2 +- configs/mbed/src/lpc17_appinit.c | 2 +- configs/mcu123-lpc214x/src/lpc2148_appinit.c | 2 +- configs/mikroe-stm32f4/src/stm32_appinit.c | 2 +- configs/mirtoo/src/pic32_appinit.c | 2 +- configs/moxa/src/moxart_appinit.c | 2 +- configs/ne64badge/src/m9s12_appinit.c | 2 +- configs/nr5m100-nexys4/src/nr5_appinit.c | 2 +- configs/nucleo-144/src/stm32_appinitialize.c | 2 +- configs/nucleo-f072rb/src/stm32_appinit.c | 2 +- configs/nucleo-f091rc/src/stm32_appinit.c | 2 +- .../nucleo-f303re/src/stm32_appinitialize.c | 2 +- configs/nucleo-f334r8/src/stm32_appinit.c | 2 +- configs/nucleo-f4x1re/src/stm32_appinit.c | 2 +- configs/nucleo-l432kc/src/stm32_appinit.c | 2 +- configs/nucleo-l452re/src/stm32_appinit.c | 2 +- configs/nucleo-l476rg/src/stm32_appinit.c | 2 +- .../nucleo-l496zg/src/stm32_appinitialize.c | 2 +- configs/olimex-lpc-h3131/src/lpc31_appinit.c | 2 +- configs/olimex-lpc1766stk/src/lpc17_appinit.c | 2 +- configs/olimex-lpc2378/src/lpc2378_appinit.c | 2 +- configs/olimex-stm32-h405/src/stm32_appinit.c | 2 +- configs/olimex-stm32-h407/src/stm32_appinit.c | 2 +- configs/olimex-stm32-p107/src/stm32_appinit.c | 2 +- configs/olimex-stm32-p207/src/stm32_appinit.c | 2 +- configs/olimex-stm32-p407/README.txt | 2 +- configs/olimex-stm32-p407/src/stm32_appinit.c | 2 +- configs/olimex-strp711/src/str71_appinit.c | 2 +- configs/olimexino-stm32/src/stm32_appinit.c | 2 +- configs/open1788/src/lpc17_appinit.c | 2 +- .../pcblogic-pic32mx/src/pic32mx_appinit.c | 2 +- configs/photon/src/stm32_appinit.c | 2 +- .../pic32mx-starterkit/src/pic32mx_appinit.c | 2 +- configs/pic32mx7mmb/src/pic32_appinit.c | 2 +- configs/pic32mz-starterkit/include/board.h | 2 +- .../pic32mz-starterkit/src/pic32mz_appinit.c | 2 +- configs/sabre-6quad/README.txt | 2 +- configs/sabre-6quad/src/imx_appinit.c | 2 +- configs/sam3u-ek/README.txt | 2 +- configs/sam3u-ek/src/sam_appinit.c | 2 +- configs/sam4cmp-db/src/sam_appinit.c | 2 +- configs/sam4e-ek/src/sam_appinit.c | 2 +- configs/sam4e-ek/src/sam_ethernet.c | 2 +- configs/sam4l-xplained/src/sam_appinit.c | 2 +- configs/sam4s-xplained-pro/src/sam_appinit.c | 2 +- configs/sama5d2-xult/README.txt | 4 ++-- configs/sama5d2-xult/src/sam_appinit.c | 2 +- configs/sama5d3-xplained/src/sam_appinit.c | 2 +- configs/sama5d3-xplained/src/sam_ethernet.c | 2 +- configs/sama5d3x-ek/src/sam_appinit.c | 2 +- configs/sama5d3x-ek/src/sam_ethernet.c | 2 +- configs/sama5d3x-ek/src/sam_wm8904.c | 2 +- configs/sama5d4-ek/README.txt | 22 +++++++++---------- configs/sama5d4-ek/src/sam_appinit.c | 2 +- configs/sama5d4-ek/src/sam_automount.c | 2 +- configs/sama5d4-ek/src/sam_ethernet.c | 2 +- configs/sama5d4-ek/src/sam_wm8904.c | 2 +- configs/sama5d4-ek/src/sama5d4-ek.h | 2 +- configs/samd20-xplained/README.txt | 2 +- configs/samd20-xplained/src/sam_appinit.c | 2 +- configs/samd21-xplained/README.txt | 2 +- configs/samd21-xplained/src/sam_appinit.c | 2 +- configs/same70-xplained/include/board.h | 2 +- configs/same70-xplained/src/sam_appinit.c | 2 +- configs/same70-xplained/src/sam_ethernet.c | 2 +- configs/saml21-xplained/src/sam_appinit.c | 2 +- configs/samv71-xult/README.txt | 2 +- configs/samv71-xult/src/sam_appinit.c | 2 +- configs/samv71-xult/src/sam_ethernet.c | 2 +- configs/samv71-xult/src/sam_wm8904.c | 2 +- configs/shenzhou/src/stm32_appinit.c | 2 +- configs/sim/src/sim_appinit.c | 2 +- configs/spark/src/stm32_appinit.c | 2 +- configs/stm3210e-eval/src/stm32_appinit.c | 2 +- configs/stm3220g-eval/src/stm32_appinit.c | 2 +- configs/stm3240g-eval/src/stm32_appinit.c | 2 +- configs/stm32_tiny/src/stm32_appinit.c | 2 +- configs/stm32f0discovery/src/stm32_appinit.c | 2 +- configs/stm32f103-minimum/src/stm32_appinit.c | 2 +- configs/stm32f3discovery/src/stm32_appinit.c | 2 +- configs/stm32f411e-disco/src/stm32_appinit.c | 2 +- configs/stm32f429i-disco/src/stm32_appinit.c | 2 +- configs/stm32f4discovery/src/stm32_appinit.c | 2 +- configs/stm32f4discovery/src/stm32_ethernet.c | 2 +- .../src/stm32_appinitialize.c | 2 +- configs/stm32l476-mdk/src/stm32_appinit.c | 2 +- configs/stm32l476vg-disco/src/stm32_appinit.c | 2 +- configs/stm32ldiscovery/src/stm32_appinit.c | 2 +- configs/sure-pic32mx/src/pic32mx_appinit.c | 2 +- configs/teensy-2.0/src/at90usb_appinit.c | 2 +- configs/teensy-3.x/README.txt | 2 +- configs/teensy-3.x/src/k20_appinit.c | 2 +- configs/teensy-lc/src/kl_appinit.c | 2 +- configs/tm4c123g-launchpad/src/tm4c_appinit.c | 2 +- configs/tm4c1294-launchpad/src/tm4c_appinit.c | 2 +- configs/twr-k60n512/src/k60_appinit.c | 2 +- configs/twr-k64f120m/src/k64_appinit.c | 2 +- configs/twr-k64f120m/src/k64_automount.c | 2 +- configs/u-blox-c027/src/lpc17_appinit.c | 2 +- configs/ubw32/src/pic32_appinit.c | 2 +- configs/viewtool-stm32f107/README.txt | 4 ++-- .../viewtool-stm32f107/src/stm32_appinit.c | 2 +- .../viewtool-stm32f107/src/stm32_ssd1289.c | 2 +- .../src/viewtool_stm32f107.h | 2 +- configs/xmc4500-relax/src/xmc4_appinit.c | 2 +- configs/z16f2800100zcog/README.txt | 2 +- configs/zkit-arm-1769/src/lpc17_appinit.c | 2 +- configs/zp214xpa/src/lpc2148_appinit.c | 2 +- drivers/input/ajoystick.c | 2 +- drivers/input/button_upper.c | 2 +- drivers/input/djoystick.c | 2 +- drivers/leds/userled_upper.c | 2 +- drivers/mtd/mtd_config.c | 2 +- drivers/mtd/mtd_onfi.c | 2 +- drivers/mtd/smart.c | 2 +- drivers/serial/ptmx.c | 2 +- drivers/syslog/syslog_device.c | 2 +- drivers/usbhost/Kconfig | 2 +- drivers/usbhost/usbhost_composite.c | 2 +- drivers/usbhost/usbhost_devaddr.c | 2 +- drivers/usbhost/usbhost_trace.c | 2 +- drivers/usbmonitor/Kconfig | 4 ++-- drivers/usbmonitor/usbmonitor.c | 2 +- drivers/wireless/cc3000/socket_imp.c | 2 +- graphics/vnc/server/vnc_raw.c | 2 +- graphics/vnc/server/vnc_rre.c | 2 +- graphics/vnc/server/vnc_server.h | 4 ++-- include/nuttx/arch.h | 4 ++-- include/nuttx/audio/wm8904.h | 2 +- include/nuttx/binfmt/binfmt.h | 4 ++-- include/nuttx/board.h | 4 ++-- include/nuttx/input/ajoystick.h | 2 +- include/nuttx/input/buttons.h | 2 +- include/nuttx/input/djoystick.h | 2 +- include/nuttx/leds/userled.h | 2 +- include/nuttx/lib/modlib.h | 2 +- include/nuttx/mtd/onfi.h | 2 +- include/nuttx/net/netdev.h | 2 +- include/nuttx/net/sixlowpan.h | 2 +- include/nuttx/power/battery_charger.h | 2 +- include/nuttx/power/battery_gauge.h | 2 +- include/nuttx/sdio.h | 2 +- include/nuttx/spi/slave.h | 2 +- include/nuttx/usb/usbhost.h | 6 ++--- include/nuttx/usb/usbhost_devaddr.h | 2 +- include/sys/boardctl.h | 2 +- libc/locale/lib_localeconv.c | 2 +- libc/modlib/modlib_registry.c | 4 ++-- libc/netdb/lib_dns.h | 2 +- libc/netdb/lib_dnsquery.c | 4 ++-- libc/wqueue/work_usrthread.c | 4 ++-- libnx/nxfonts/nxfonts_cache.c | 2 +- mm/iob/iob_clone.c | 2 +- mm/shm/README.txt | 2 +- mm/shm/shmat.c | 2 +- mm/shm/shmctl.c | 4 ++-- mm/shm/shmdt.c | 2 +- net/arp/arp.h | 2 +- net/arp/arp_notify.c | 2 +- net/devif/devif.h | 2 +- net/devif/devif_pktsend.c | 2 +- net/netdev/netdev_verify.c | 2 +- net/sixlowpan/sixlowpan_input.c | 2 +- net/sixlowpan/sixlowpan_send.c | 2 +- net/socket/net_monitor.c | 2 +- net/tcp/tcp.h | 4 ++-- net/tcp/tcp_send.c | 4 ++-- net/tcp/tcp_send_buffered.c | 2 +- net/tcp/tcp_send_unbuffered.c | 2 +- net/udp/udp_psock_sendto.c | 2 +- sched/Kconfig | 4 ++-- sched/group/group_join.c | 4 ++-- sched/pthread/pthread_cleanup.c | 2 +- sched/sched/sched_resumescheduler.c | 2 +- sched/sched/sched_setaffinity.c | 2 +- sched/sched/sched_setpriority.c | 2 +- sched/sched/sched_sporadic.c | 6 ++--- sched/sched/sched_suspendscheduler.c | 2 +- sched/task/task_getpid.c | 2 +- sched/task/task_terminate.c | 2 +- sched/task/task_vfork.c | 2 +- sched/wdog/wd_create.c | 2 +- sched/wdog/wd_start.c | 2 +- sched/wdog/wdog.h | 2 +- sched/wqueue/kwork_process.c | 2 +- tools/Config.mk | 2 +- tools/README.txt | 2 +- 342 files changed, 438 insertions(+), 438 deletions(-) diff --git a/ChangeLog b/ChangeLog index e15bf20e50..7466baf3d0 100755 --- a/ChangeLog +++ b/ChangeLog @@ -10770,8 +10770,8 @@ serial device servers. From Anton D. Kachalov (2015-07-29). * drivers/net/ and include/nuttx/net: Add support for a Faraday * FTMAC100 Ethernet MAC Driver. From Anton D. Kachalov (2015-07-29). - * 16550 UART Driver: Add a configuration option to indicate the the - THR empty bit is inverted. This is the the case for the moxART SoC. + * 16550 UART Driver: Add a configuration option to indicate the + THR empty bit is inverted. This is the case for the moxART SoC. Based comments from Anton D. Kachalov (2015-07-29). * STM32 F4: Add DMA support to the ADC driver for STM32 F4. From Max Kriegler (2015-07-30). @@ -13129,7 +13129,7 @@ protect code. So this change adds locking (via enter_critical section) to wdog - expiration logic for the the case if the SMP configuration + expiration logic for the case if the SMP configuration (2016-11-18). * SAM3/4: Add delay between setting and clearing the endpoint RESET bit in sam_ep_resume(). We need to add a delay between setting and @@ -13248,7 +13248,7 @@ select to log only notes from certain CPUs (2016-11-28). * Misoc LM3: Add Misoc Ethernet driver. Integrate network support into configs/misoc/hello. Remove configs/misoc/include/generated directory. - I suppose the the intent now is that this is a symbolic link? DANGER! + I suppose the intent now is that this is a symbolic link? DANGER! This means that you cannot compile this code with first generating these files a providing a symbolic link to this location! From Ramtin Amin (2016-11-28). diff --git a/Documentation/NfsHowto.html b/Documentation/NfsHowto.html index a6e7d3fb2e..95da2bb73c 100644 --- a/Documentation/NfsHowto.html +++ b/Documentation/NfsHowto.html @@ -287,7 +287,7 @@ This is a test

      Setting up the server will be done in two steps: First, setting up the configuration file for NFS, and then starting the NFS services. - But first, you need to install the nfs server on Ubuntu with the these two commands: + But first, you need to install the nfs server on Ubuntu with these two commands:

         # sudo apt-get install nfs-common
        diff --git a/Documentation/NuttXBinfmt.html b/Documentation/NuttXBinfmt.html
        index 49a999846c..600693ba49 100644
        --- a/Documentation/NuttXBinfmt.html
        +++ b/Documentation/NuttXBinfmt.html
        @@ -381,7 +381,7 @@ EXEPATH_HANDLE exepath_init(void);
         
          On success, exepath_init() return a non-NULL, opaque handle that may subsequently be used in calls to exepath_next() and exepath_release(). On error, a NULL handle value will be returned. - The most likely cause of an error would be that the there is no value associated with the PATH variable. + The most likely cause of an error would be that there is no value associated with the PATH variable.

        2.3.9 exepath_next()

        diff --git a/Documentation/NuttxPortingGuide.html b/Documentation/NuttxPortingGuide.html index 1c3ff2d886..e6d3134dee 100644 --- a/Documentation/NuttxPortingGuide.html +++ b/Documentation/NuttxPortingGuide.html @@ -2291,7 +2291,7 @@ config ARCH_SIM In the default configuration where system time is provided by a periodic timer interrupt, the default system timer is configure the timer for 100Hz or CONFIG_USEC_PER_TICK=10000. If CONFIG_SCHED_TICKLESS is selected, then there are no system timer interrupt. In this case, CONFIG_USEC_PER_TICK does not control any timer rates. Rather, it only determines the resolution of time reported by clock_systimer() and the resolution of times that can be set for certain delays including watchdog timers and delayed work.

        - In this case there is still a trade-off: It is better to have the CONFIG_USEC_PER_TICK as low as possible for higher timing resolution. However, the the time is currently held in unsigned int. On some systems, this may be 16-bits in width but on most contemporary systems it will be 32-bits. In either case, smaller values of CONFIG_USEC_PER_TICK will reduce the range of values that delays that can be represented. So the trade-off is between range and resolution (you could also modify the code to use a 64-bit value if you really want both). + In this case there is still a trade-off: It is better to have the CONFIG_USEC_PER_TICK as low as possible for higher timing resolution. However, the time is currently held in unsigned int. On some systems, this may be 16-bits in width but on most contemporary systems it will be 32-bits. In either case, smaller values of CONFIG_USEC_PER_TICK will reduce the range of values that delays that can be represented. So the trade-off is between range and resolution (you could also modify the code to use a 64-bit value if you really want both).

        The default, 100 microseconds, will provide for a range of delays up to 120 hours. @@ -2408,7 +2408,7 @@ int up_timer_gettime(FAR struct timespec *ts);

      Assumptions:

        - Called from the the normal tasking context. The implementation must provide whatever mutual exclusion is necessary for correct operation. This can include disabling interrupts in order to assure atomic register operations. + Called from the normal tasking context. The implementation must provide whatever mutual exclusion is necessary for correct operation. This can include disabling interrupts in order to assure atomic register operations.
      4.3.4.4.3 up_alarm_cancel()
      @@ -2761,7 +2761,7 @@ typedef uint32_t wdparm_t;

      4.4.1 Classes of Work Queues

      Classes of Work Queues. - There are three different classes of work queues, each with different properties and intended usage. These class of work queues along with the the common work queue interface are described in the following paragraphs. + There are three different classes of work queues, each with different properties and intended usage. These class of work queues along with the common work queue interface are described in the following paragraphs.

      4.4.1.1 High Priority Kernel Work queue

      @@ -2786,7 +2786,7 @@ typedef uint32_t wdparm_t; The execution priority of the high-priority worker thread. Default: 224
    • CONFIG_SCHED_HPWORKPERIOD. - How often the worker thread re-checks for work in units of microseconds. This work period is really only necessary if the the high priority thread is performing periodic garbage collection. The worker thread will be awakened immediately with it is queued work to be done. If the high priority worker thread is performing garbage collection, then the default is 50*1000 (50 MS). Otherwise, if the lower priority worker thread is performing garbage collection, the default is 100*1000. + How often the worker thread re-checks for work in units of microseconds. This work period is really only necessary if the high priority thread is performing periodic garbage collection. The worker thread will be awakened immediately with it is queued work to be done. If the high priority worker thread is performing garbage collection, then the default is 50*1000 (50 MS). Otherwise, if the lower priority worker thread is performing garbage collection, the default is 100*1000.
    • CONFIG_SCHED_HPWORKSTACKSIZE. The stack size allocated for the worker thread in bytes. Default: 2048.
    • diff --git a/Documentation/NuttxUserGuide.html b/Documentation/NuttxUserGuide.html index 1fc401217f..4fd477401e 100644 --- a/Documentation/NuttxUserGuide.html +++ b/Documentation/NuttxUserGuide.html @@ -6433,7 +6433,7 @@ The cancellation cleanup handler will be popped from the cancellation cleanup st Input Parameters:

        -
      • routine. The cleanup routine to be pushed on the the cleanup stack.
      • +
      • routine. The cleanup routine to be pushed on the cleanup stack.
      • arg. An argument that will accompany the callback.

      @@ -10115,7 +10115,7 @@ int shmctl(int shmid, int cmd, FAR struct shmid_ds *buf);

      • IPC_SET. - Does not set the the shm_perm.uid or shm_perm.gidmembers of the shmid_ds data structure associated with shmid because user and group IDs are not yet supported by NuttX + Does not set the shm_perm.uid or shm_perm.gidmembers of the shmid_ds data structure associated with shmid because user and group IDs are not yet supported by NuttX
      • IPC_SET. diff --git a/ReleaseNotes b/ReleaseNotes index ed69375e61..b15cf3cd68 100644 --- a/ReleaseNotes +++ b/ReleaseNotes @@ -11146,7 +11146,7 @@ Additional new features and extended functionality: - SYSLOG character device channel will now expand LF to CR-LF. Controllable with a configuration option. - Add a SYSLOG character device that can be used to re-direct output - to the SYSLOG channel (Not be be confused the the SYSLGO output to a + to the SYSLOG channel (Not be be confused the SYSLGO output to a character device). - Debug features are now enabled separately from debug output. (1) CONFIG_DEBUG is gone. It is replaced with CONFIG_DEBUG_FEATURES. @@ -12417,7 +12417,7 @@ Additional new features and extended functionality: - Misoc LM32 Qemu: Integrate network support into configs/misoc/hello. From Ramtin Amin. - Misoc LM32 Qemu: Remove configs/misoc/include/generated directory. I - suppose the the intent now is that this is a symbolic link? DANGER! + suppose the intent now is that this is a symbolic link? DANGER! This means that you cannot compile this code with first generating these files a providing a symbolic link to this location! There is a sample directory containing generated sources. This is really only diff --git a/TODO b/TODO index 24ef691747..c0b3443a83 100644 --- a/TODO +++ b/TODO @@ -2065,7 +2065,7 @@ o Pascal Add-On (pcode/) Priority: Medium Title: PDBG - Description: Move the the pascal p-code debugger into the NuttX apps/ tree + Description: Move the pascal p-code debugger into the NuttX apps/ tree where it can be used from the NSH command line. Status: Open Priority: Low diff --git a/arch/Kconfig b/arch/Kconfig index 7dbad3d037..b7d113cf1d 100644 --- a/arch/Kconfig +++ b/arch/Kconfig @@ -767,7 +767,7 @@ config ARCH_HIPRI_INTERRUPT there will most likely be a system failure. If the interrupt stack is selected, on the other hand, then the - interrupt handler will always set the the MSP to the interrupt + interrupt handler will always set the MSP to the interrupt stack. So when the high priority interrupt occurs, it will either use the MSP of the last privileged thread to run or, in the case of the nested interrupt, the interrupt stack if no privileged task has diff --git a/arch/arm/include/stm32/ltdc.h b/arch/arm/include/stm32/ltdc.h index 704b578a99..c561c680cd 100644 --- a/arch/arm/include/stm32/ltdc.h +++ b/arch/arm/include/stm32/ltdc.h @@ -410,7 +410,7 @@ struct ltdc_layer_s * On error - -EINVAL * * Procedure Information: - * If the srcxpos and srcypos unequal the the xpos and ypos of the coord + * If the srcxpos and srcypos unequal the xpos and ypos of the coord * structure this acts like moving the visible area to another position on * the screen during the next update operation. * diff --git a/arch/arm/src/a1x/a1x_lowputc.c b/arch/arm/src/a1x/a1x_lowputc.c index 0018c88881..e3f682da88 100644 --- a/arch/arm/src/a1x/a1x_lowputc.c +++ b/arch/arm/src/a1x/a1x_lowputc.c @@ -228,7 +228,7 @@ void a1x_lowsetup(void) #warning Missing logic /* Configure UART pins for the selected CONSOLE. If there are multiple - * pin options for a given UART, the the applicable option must be + * pin options for a given UART, the applicable option must be * disambiguated in the board.h header file. */ diff --git a/arch/arm/src/armv7-a/arm_addrenv.c b/arch/arm/src/armv7-a/arm_addrenv.c index 7d2818283d..def1ea66d9 100644 --- a/arch/arm/src/armv7-a/arm_addrenv.c +++ b/arch/arm/src/armv7-a/arm_addrenv.c @@ -149,7 +149,7 @@ * Name: up_addrenv_initdata * * Description: - * Initialize the region of memory at the the beginning of the .bss/.data + * Initialize the region of memory at the beginning of the .bss/.data * region that is shared between the user process and the kernel. * ****************************************************************************/ diff --git a/arch/arm/src/armv7-a/arm_gicv2.c b/arch/arm/src/armv7-a/arm_gicv2.c index ec32fa5271..0232685dc8 100644 --- a/arch/arm/src/armv7-a/arm_gicv2.c +++ b/arch/arm/src/armv7-a/arm_gicv2.c @@ -298,7 +298,7 @@ void arm_gic_initialize(void) #endif #if !defined(CONFIG_ARCH_HAVE_TRUSTZONE) - /* Enable the distributor by setting the the Enable bit in the enable + /* Enable the distributor by setting the Enable bit in the enable * register (no security extensions). */ diff --git a/arch/arm/src/armv7-a/pgalloc.h b/arch/arm/src/armv7-a/pgalloc.h index 32436cf362..485cc666d4 100644 --- a/arch/arm/src/armv7-a/pgalloc.h +++ b/arch/arm/src/armv7-a/pgalloc.h @@ -102,7 +102,7 @@ static inline void arm_tmprestore(uint32_t l1save) * * Description: * If the page memory pool is statically mapped, then we do not have to - * go through the the temporary mapping. We simply have to perform a + * go through the temporary mapping. We simply have to perform a * physical to virtual memory address mapping. * ****************************************************************************/ diff --git a/arch/arm/src/armv7-m/gnu/up_exception.S b/arch/arm/src/armv7-m/gnu/up_exception.S index 4f2927b421..81096aaefe 100644 --- a/arch/arm/src/armv7-m/gnu/up_exception.S +++ b/arch/arm/src/armv7-m/gnu/up_exception.S @@ -60,7 +60,7 @@ * stale MSP, there will most likely be a system failure. * * If the interrupt stack is selected, on the other hand, then the interrupt - * handler will always set the the MSP to the interrupt stack. So when the high + * handler will always set the MSP to the interrupt stack. So when the high * priority interrupt occurs, it will either use the MSP of the last privileged * thread to run or, in the case of the nested interrupt, the interrupt stack if * no privileged task has run. @@ -70,7 +70,7 @@ # error Interrupt stack must be used with high priority interrupts in kernel mode # endif - /* Use the the BASEPRI to control interrupts is required if nested, high + /* Use the BASEPRI to control interrupts is required if nested, high * priority interrupts are supported. */ diff --git a/arch/arm/src/armv7-m/gnu/up_lazyexception.S b/arch/arm/src/armv7-m/gnu/up_lazyexception.S index 0a0e088a62..852883aa22 100644 --- a/arch/arm/src/armv7-m/gnu/up_lazyexception.S +++ b/arch/arm/src/armv7-m/gnu/up_lazyexception.S @@ -58,7 +58,7 @@ * interrupt occurs and uses this stale MSP, there will most likely be a system failure. * * If the interrupt stack is selected, on the other hand, then the interrupt handler will - * always set the the MSP to the interrupt stack. So when the high priority interrupt occurs, + * always set the MSP to the interrupt stack. So when the high priority interrupt occurs, * it will either use the MSP of the last privileged thread to run or, in the case of the * nested interrupt, the interrupt stack if no privileged task has run. */ @@ -67,7 +67,7 @@ # error Interrupt stack must be used with high priority interrupts in kernel mode # endif - /* Use the the BASEPRI to control interrupts is required if nested, high + /* Use the BASEPRI to control interrupts is required if nested, high * priority interrupts are supported. */ diff --git a/arch/arm/src/efm32/efm32_dma.h b/arch/arm/src/efm32/efm32_dma.h index 011a7d9874..813b30bf70 100644 --- a/arch/arm/src/efm32/efm32_dma.h +++ b/arch/arm/src/efm32/efm32_dma.h @@ -96,7 +96,7 @@ typedef FAR void *DMA_HANDLE; /* Description: - * This is the type of the callback that is used to inform the user of the the + * This is the type of the callback that is used to inform the user of the * completion of the DMA. * * Input Parameters: diff --git a/arch/arm/src/efm32/efm32_usbhost.c b/arch/arm/src/efm32/efm32_usbhost.c index 3d5a6888ba..e3c8c548a7 100644 --- a/arch/arm/src/efm32/efm32_usbhost.c +++ b/arch/arm/src/efm32/efm32_usbhost.c @@ -1955,8 +1955,8 @@ static ssize_t efm32_in_transfer(FAR struct efm32_usbhost_s *priv, int chidx, /* Check for a special case: If (1) the transfer was NAKed and (2) * no Tx FIFO empty or Rx FIFO not-empty event occurred, then we * should be able to just flush the Rx and Tx FIFOs and try again. - * We can detect this latter case because the then the transfer - * buffer pointer and buffer size will be unaltered. + * We can detect this latter case because then the transfer buffer + * pointer and buffer size will be unaltered. */ elapsed = clock_systimer() - start; @@ -2221,8 +2221,8 @@ static ssize_t efm32_out_transfer(FAR struct efm32_usbhost_s *priv, int chidx, /* Check for a special case: If (1) the transfer was NAKed and (2) * no Tx FIFO empty or Rx FIFO not-empty event occurred, then we * should be able to just flush the Rx and Tx FIFOs and try again. - * We can detect this latter case because the then the transfer - * buffer pointer and buffer size will be unaltered. + * We can detect this latter case because then the transfer buffer + * pointer and buffer size will be unaltered. */ elapsed = clock_systimer() - start; @@ -4613,7 +4613,7 @@ static ssize_t efm32_transfer(FAR struct usbhost_driver_s *drvr, usbhost_ep_t ep * Description: * Process a request to handle a transfer descriptor. This method will * enqueue the transfer request and return immediately. When the transfer - * completes, the the callback will be invoked with the provided transfer. + * completes, the callback will be invoked with the provided transfer. * This method is useful for receiving interrupt transfers which may come * infrequently. * diff --git a/arch/arm/src/efm32/efm32_vectors.S b/arch/arm/src/efm32/efm32_vectors.S index 488c8581e0..3f125e9f49 100644 --- a/arch/arm/src/efm32/efm32_vectors.S +++ b/arch/arm/src/efm32/efm32_vectors.S @@ -59,7 +59,7 @@ * stale MSP, there will most likely be a system failure. * * If the interrupt stack is selected, on the other hand, then the interrupt - * handler will always set the the MSP to the interrupt stack. So when the high + * handler will always set the MSP to the interrupt stack. So when the high * priority interrupt occurs, it will either use the MSP of the last privileged * thread to run or, in the case of the nested interrupt, the interrupt stack if * no privileged task has run. @@ -69,7 +69,7 @@ # error Interrupt stack must be used with high priority interrupts in kernel mode # endif - /* Use the the BASEPRI to control interrupts is required if nested, high + /* Use the BASEPRI to control interrupts is required if nested, high * priority interrupts are supported. */ diff --git a/arch/arm/src/imx6/imx_memorymap.h b/arch/arm/src/imx6/imx_memorymap.h index 6259c1b7e0..6eb308d658 100644 --- a/arch/arm/src/imx6/imx_memorymap.h +++ b/arch/arm/src/imx6/imx_memorymap.h @@ -50,7 +50,7 @@ ************************************************************************************/ /* The vectors are, by default, positioned at the beginning of the text - * section. Under what conditions do we have to remap the these vectors? + * section. Under what conditions do we have to remap these vectors? * * 1) If we are using high vectors (CONFIG_ARCH_LOWVECTORS=n). In this case, * the vectors will lie at virtual address 0xffff:000 and we will need diff --git a/arch/arm/src/kinetis/kinetis_lpserial.c b/arch/arm/src/kinetis/kinetis_lpserial.c index 515f1f370e..5c0c336237 100644 --- a/arch/arm/src/kinetis/kinetis_lpserial.c +++ b/arch/arm/src/kinetis/kinetis_lpserial.c @@ -457,7 +457,7 @@ static void kinetis_shutdown(struct uart_dev_s *dev) * Description: * Configure the LPUART to operation in interrupt driven mode. This * method is called when the serial port is opened. Normally, this is - * just after the the setup() method is called, however, the serial + * just after the setup() method is called, however, the serial * console may operate in a non-interrupt driven mode during the boot phase. * * RX and TX interrupts are not enabled when by the attach method (unless diff --git a/arch/arm/src/kinetis/kinetis_sdhc.c b/arch/arm/src/kinetis/kinetis_sdhc.c index 8500c95908..4c8ffea18a 100644 --- a/arch/arm/src/kinetis/kinetis_sdhc.c +++ b/arch/arm/src/kinetis/kinetis_sdhc.c @@ -95,7 +95,7 @@ /* Enable pull-up resistors * * Kinetis does not have pullups on all their development boards - * So allow the the board config to enable them. + * So allow the board config to enable them. */ #if defined(BOARD_SDHC_ENABLE_PULLUPS) diff --git a/arch/arm/src/kinetis/kinetis_vectors.S b/arch/arm/src/kinetis/kinetis_vectors.S index 30940199af..676f1cb62b 100644 --- a/arch/arm/src/kinetis/kinetis_vectors.S +++ b/arch/arm/src/kinetis/kinetis_vectors.S @@ -60,7 +60,7 @@ * stale MSP, there will most likely be a system failure. * * If the interrupt stack is selected, on the other hand, then the interrupt - * handler will always set the the MSP to the interrupt stack. So when the high + * handler will always set the MSP to the interrupt stack. So when the high * priority interrupt occurs, it will either use the MSP of the last privileged * thread to run or, in the case of the nested interrupt, the interrupt stack if * no privileged task has run. @@ -70,7 +70,7 @@ # error Interrupt stack must be used with high priority interrupts in kernel mode # endif - /* Use the the BASEPRI to control interrupts is required if nested, high + /* Use the BASEPRI to control interrupts is required if nested, high * priority interrupts are supported. */ diff --git a/arch/arm/src/lpc11xx/lpc11_serial.c b/arch/arm/src/lpc11xx/lpc11_serial.c index cbef799afe..941a4475b4 100644 --- a/arch/arm/src/lpc11xx/lpc11_serial.c +++ b/arch/arm/src/lpc11xx/lpc11_serial.c @@ -498,7 +498,7 @@ static void up_shutdown(struct uart_dev_s *dev) * Description: * Configure the UART to operation in interrupt driven mode. This method * is called when the serial port is opened. Normally, this is just after - * the the setup() method is called, however, the serial console may + * the setup() method is called, however, the serial console may * operate in a non-interrupt driven mode during the boot phase. * * RX and TX interrupts are not enabled when by the attach method (unless diff --git a/arch/arm/src/lpc17xx/lpc17_usbhost.c b/arch/arm/src/lpc17xx/lpc17_usbhost.c index 42825b0213..6bb48cd8f9 100644 --- a/arch/arm/src/lpc17xx/lpc17_usbhost.c +++ b/arch/arm/src/lpc17xx/lpc17_usbhost.c @@ -3164,7 +3164,7 @@ static void lpc17_asynch_completion(struct lpc17_usbhost_s *priv, * Description: * Process a request to handle a transfer descriptor. This method will * enqueue the transfer request and return immediately. When the transfer - * completes, the the callback will be invoked with the provided transfer. + * completes, the callback will be invoked with the provided transfer. * This method is useful for receiving interrupt transfers which may come * infrequently. * diff --git a/arch/arm/src/lpc17xx/lpc17_vectors.S b/arch/arm/src/lpc17xx/lpc17_vectors.S index bf37fc9e81..1b696a6a60 100644 --- a/arch/arm/src/lpc17xx/lpc17_vectors.S +++ b/arch/arm/src/lpc17xx/lpc17_vectors.S @@ -58,7 +58,7 @@ * interrupt occurs and uses this stale MSP, there will most likely be a system failure. * * If the interrupt stack is selected, on the other hand, then the interrupt handler will - * always set the the MSP to the interrupt stack. So when the high priority interrupt occurs, + * always set the MSP to the interrupt stack. So when the high priority interrupt occurs, * it will either use the MSP of the last privileged thread to run or, in the case of the * nested interrupt, the interrupt stack if no privileged task has run. */ @@ -67,7 +67,7 @@ # error Interrupt stack must be used with high priority interrupts in kernel mode # endif - /* Use the the BASEPRI to control interrupts is required if nested, high + /* Use the BASEPRI to control interrupts is required if nested, high * priority interrupts are supported. */ diff --git a/arch/arm/src/lpc31xx/Kconfig b/arch/arm/src/lpc31xx/Kconfig index addeaf16e4..5f1b86bc13 100644 --- a/arch/arm/src/lpc31xx/Kconfig +++ b/arch/arm/src/lpc31xx/Kconfig @@ -263,7 +263,7 @@ config LPC31_EHCI_SDIS Selecting this option ensures that overruns/underruns of the latency FIFO are eliminated for low bandwidth systems where the RX and TX buffers are sufficient to contain the entire packet. Enabling stream - disable also has the effect of ensuring the the TX latency is filled + disable also has the effect of ensuring the TX latency is filled to capacity before the packet is launched onto the USB. Note: Time duration to pre-fill the FIFO becomes significant when stream disable is active. diff --git a/arch/arm/src/lpc31xx/lpc31_ehci.c b/arch/arm/src/lpc31xx/lpc31_ehci.c index 475c4dea89..1884a41241 100644 --- a/arch/arm/src/lpc31xx/lpc31_ehci.c +++ b/arch/arm/src/lpc31xx/lpc31_ehci.c @@ -3008,7 +3008,7 @@ static inline void lpc31_ioc_bottomhalf(void) qh = (struct lpc31_qh_s *)lpc31_virtramaddr(lpc31_swap32(*bp) & QH_HLP_MASK); /* If the asynchronous queue is empty, then the forward point in the - * asynchronous queue head will point back to the the queue head. + * asynchronous queue head will point back to the queue head. */ if (qh && qh != &g_asynchead) @@ -4362,7 +4362,7 @@ errout_with_sem: * Description: * Process a request to handle a transfer descriptor. This method will * enqueue the transfer request and return immediately. When the transfer - * completes, the the callback will be invoked with the provided transfer. + * completes, the callback will be invoked with the provided transfer. * This method is useful for receiving interrupt transfers which may come * infrequently. * @@ -4560,7 +4560,7 @@ static int lpc31_cancel(FAR struct usbhost_driver_s *drvr, usbhost_ep_t ep) qh = (struct lpc31_qh_s *)lpc31_virtramaddr(lpc31_swap32(*bp) & QH_HLP_MASK); /* If the asynchronous queue is empty, then the forward point in - * the asynchronous queue head will point back to the the queue + * the asynchronous queue head will point back to the queue * head. */ diff --git a/arch/arm/src/lpc43xx/lpc43_ehci.c b/arch/arm/src/lpc43xx/lpc43_ehci.c index 5af61fa939..e9bb3ddcdc 100644 --- a/arch/arm/src/lpc43xx/lpc43_ehci.c +++ b/arch/arm/src/lpc43xx/lpc43_ehci.c @@ -2849,7 +2849,7 @@ static inline void lpc43_ioc_bottomhalf(void) qh = (struct lpc43_qh_s *)lpc43_virtramaddr(lpc43_swap32(*bp) & QH_HLP_MASK); /* If the asynchronous queue is empty, then the forward point in the - * asynchronous queue head will point back to the the queue head. + * asynchronous queue head will point back to the queue head. */ if (qh && qh != &g_asynchead) @@ -4193,7 +4193,7 @@ errout_with_sem: * Description: * Process a request to handle a transfer descriptor. This method will * enqueue the transfer request and return immediately. When the transfer - * completes, the the callback will be invoked with the provided transfer. + * completes, the callback will be invoked with the provided transfer. * This method is useful for receiving interrupt transfers which may come * infrequently. * @@ -4391,7 +4391,7 @@ static int lpc43_cancel(FAR struct usbhost_driver_s *drvr, usbhost_ep_t ep) qh = (struct lpc43_qh_s *)lpc43_virtramaddr(lpc43_swap32(*bp) & QH_HLP_MASK); /* If the asynchronous queue is empty, then the forward point in - * the asynchronous queue head will point back to the the queue + * the asynchronous queue head will point back to the queue * head. */ diff --git a/arch/arm/src/lpc43xx/lpc43_ethernet.c b/arch/arm/src/lpc43xx/lpc43_ethernet.c index 2c564aa5ff..955c30684e 100644 --- a/arch/arm/src/lpc43xx/lpc43_ethernet.c +++ b/arch/arm/src/lpc43xx/lpc43_ethernet.c @@ -1483,7 +1483,7 @@ static int lpc43_recvframe(FAR struct lpc43_ethmac_s *priv) { priv->segments++; - /* Check if the there is only one segment in the frame */ + /* Check if there is only one segment in the frame */ if (priv->segments == 1) { diff --git a/arch/arm/src/sam34/sam4cm_oneshot.c b/arch/arm/src/sam34/sam4cm_oneshot.c index 0bf92d1fea..04c9cf8200 100644 --- a/arch/arm/src/sam34/sam4cm_oneshot.c +++ b/arch/arm/src/sam34/sam4cm_oneshot.c @@ -405,7 +405,7 @@ int sam_oneshot_cancel(struct sam_oneshot_s *oneshot, * the counter expires while we are doing this, the counter clock will be * stopped, but the clock will not be disabled. * - * The expected behavior is that the the counter register will freezes at + * The expected behavior is that the counter register will freezes at * a value equal to the RC register when the timer expires. The counter * should have values between 0 and RC in all other cased. * diff --git a/arch/arm/src/sam34/sam4cm_tc.c b/arch/arm/src/sam34/sam4cm_tc.c index c366118f4d..32e465cc77 100644 --- a/arch/arm/src/sam34/sam4cm_tc.c +++ b/arch/arm/src/sam34/sam4cm_tc.c @@ -1166,7 +1166,7 @@ uint32_t sam_tc_divfreq(TC_HANDLE handle) DEBUGASSERT(chan); - /* Get the the TC_CMR register contents for this channel and extract the + /* Get the TC_CMR register contents for this channel and extract the * TCCLKS index. */ diff --git a/arch/arm/src/sam34/sam4cm_tickless.c b/arch/arm/src/sam34/sam4cm_tickless.c index 8f3ee17509..396a8fda88 100644 --- a/arch/arm/src/sam34/sam4cm_tickless.c +++ b/arch/arm/src/sam34/sam4cm_tickless.c @@ -313,7 +313,7 @@ void arm_timer_initialize(void) * any failure. * * Assumptions: - * Called from the the normal tasking context. The implementation must + * Called from the normal tasking context. The implementation must * provide whatever mutual exclusion is necessary for correct operation. * This can include disabling interrupts in order to assure atomic register * operations. diff --git a/arch/arm/src/sam34/sam_emac.c b/arch/arm/src/sam34/sam_emac.c index 7e5839cc19..c45ea9f383 100644 --- a/arch/arm/src/sam34/sam_emac.c +++ b/arch/arm/src/sam34/sam_emac.c @@ -893,7 +893,7 @@ static int sam_txpoll(struct net_driver_s *dev) sam_transmit(priv); - /* Check if the there are any free TX descriptors. We cannot perform + /* Check if there are any free TX descriptors. We cannot perform * the TX poll if we do not have buffering for another packet. */ @@ -941,7 +941,7 @@ static void sam_dopoll(struct sam_emac_s *priv) { struct net_driver_s *dev = &priv->dev; - /* Check if the there are any free TX descriptors. We cannot perform the + /* Check if there are any free TX descriptors. We cannot perform the * TX poll if we do not have buffering for another packet. */ @@ -1747,7 +1747,7 @@ static void sam_poll_work(FAR void *arg) FAR struct sam_emac_s *priv = (FAR struct sam_emac_s *)arg; struct net_driver_s *dev = &priv->dev; - /* Check if the there are any free TX descriptors. We cannot perform the + /* Check if there are any free TX descriptors. We cannot perform the * TX poll if we do not have buffering for another packet. */ diff --git a/arch/arm/src/sam34/sam_vectors.S b/arch/arm/src/sam34/sam_vectors.S index 9d2b5e6b31..4d783f4102 100644 --- a/arch/arm/src/sam34/sam_vectors.S +++ b/arch/arm/src/sam34/sam_vectors.S @@ -57,7 +57,7 @@ * interrupt occurs and uses this stale MSP, there will most likely be a system failure. * * If the interrupt stack is selected, on the other hand, then the interrupt handler will - * always set the the MSP to the interrupt stack. So when the high priority interrupt occurs, + * always set the MSP to the interrupt stack. So when the high priority interrupt occurs, * it will either use the MSP of the last privileged thread to run or, in the case of the * nested interrupt, the interrupt stack if no privileged task has run. */ @@ -66,7 +66,7 @@ # error Interrupt stack must be used with high priority interrupts in kernel mode # endif - /* Use the the BASEPRI to control interrupts is required if nested, high + /* Use the BASEPRI to control interrupts is required if nested, high * priority interrupts are supported. */ diff --git a/arch/arm/src/sama5/Kconfig b/arch/arm/src/sama5/Kconfig index 280894d84e..58b0c3860a 100644 --- a/arch/arm/src/sama5/Kconfig +++ b/arch/arm/src/sama5/Kconfig @@ -953,7 +953,7 @@ config SAMA5_LCDC_BACKCOLOR config SAMA5_LCDC_FB_VBASE hex "Framebuffer memory start address (virtual)" ---help--- - If you are using the the LCDC, then you must provide the virtual + If you are using the LCDC, then you must provide the virtual address of the start of the framebuffer. This address must be aligned to a 1MB bounder (i.e., the last five "digits" of the hexadecimal address must be zero). @@ -961,7 +961,7 @@ config SAMA5_LCDC_FB_VBASE config SAMA5_LCDC_FB_PBASE hex "Framebuffer memory start address (virtual)" ---help--- - If you are using the the LCDC, then you must provide the physical + If you are using the LCDC, then you must provide the physical address of the start of the framebuffer. This address must be aligned to a 1MB bounder (i.e., the last five "digits" of the hexadecimal address must be zero). @@ -4953,7 +4953,7 @@ config SAMA5_DDRCS_PGHEAP_OFFSET If you are executing from DRAM, then you must have already reserved this region with SAMA5_DDRCS_RESERVE, setting SAMA5_DDRCS_HEAP_END so that this page cache region defined by SAMA5_DDRCS_PGHEAP_OFFSET - and SAMA5_DDRCS_PGHEAP_SIZE does not overlap the the region of DRAM + and SAMA5_DDRCS_PGHEAP_SIZE does not overlap the region of DRAM that is added to the heap. If you are not executing from DRAM, then you must have excluding this page cache region from the heap ether by (1) not selecting SAMA5_DDRCS_HEAP, or (2) selecting @@ -4971,7 +4971,7 @@ config SAMA5_DDRCS_PGHEAP_SIZE If you are executing from DRAM, then you must have already reserved this region with SAMA5_DDRCS_RESERVE, setting SAMA5_DDRCS_HEAP_END so that this page cache region defined by SAMA5_DDRCS_PGHEAP_OFFSET - and SAMA5_DDRCS_PGHEAP_SIZE does not overlap the the region of DRAM + and SAMA5_DDRCS_PGHEAP_SIZE does not overlap the region of DRAM that is added to the heap. If you are not executing from DRAM, then you must have excluding this page cache region from the heap ether by (1) not selecting SAMA5_DDRCS_HEAP, or (2) selecting diff --git a/arch/arm/src/sama5/chip/sam_emaca.h b/arch/arm/src/sama5/chip/sam_emaca.h index 536b0cc914..2681b0567c 100644 --- a/arch/arm/src/sama5/chip/sam_emaca.h +++ b/arch/arm/src/sama5/chip/sam_emaca.h @@ -1,6 +1,6 @@ /************************************************************************************ * arch/arm/src/sama5/chip/sam_emaca.h - * This is the form of the EMAC interface used the the SAMA5D3 + * This is the form of the EMAC interface used the SAMA5D3 * * Copyright (C) 2013-2014 Gregory Nutt. All rights reserved. * Author: Gregory Nutt diff --git a/arch/arm/src/sama5/chip/sam_emacb.h b/arch/arm/src/sama5/chip/sam_emacb.h index 6b11086d31..7cbc75d6af 100644 --- a/arch/arm/src/sama5/chip/sam_emacb.h +++ b/arch/arm/src/sama5/chip/sam_emacb.h @@ -1,6 +1,6 @@ /************************************************************************************ * arch/arm/src/sama5/chip/sam_emacb.h - * This is the form of the EMAC interface used the the SAMA5D4 (and also the SAM43). + * This is the form of the EMAC interface used the SAMA5D4 (and also the SAM43). * This is referred as GMAC in the documentation even though it does not support * Gibabit Ethernet. * diff --git a/arch/arm/src/sama5/sam_adc.c b/arch/arm/src/sama5/sam_adc.c index 2f9e4ee406..6688899510 100644 --- a/arch/arm/src/sama5/sam_adc.c +++ b/arch/arm/src/sama5/sam_adc.c @@ -736,7 +736,7 @@ static void sam_adc_dmacallback(DMA_HANDLE handle, void *arg, int result) /* Check of the bottom half is keeping up with us. * * ready == false: Would mean that the worker thready has not ran since - * the the last DMA callback. + * the last DMA callback. * enabled == false: Means that the upper half has asked us nicely to stop * transferring DMA data. */ @@ -1294,7 +1294,7 @@ static int sam_adc_settimer(struct sam_adc_s *priv, uint32_t frequency, return ret; } - /* Set the timer/counter waveform mode the the clock input slected by + /* Set the timer/counter waveform mode the clock input slected by * sam_tc_divisor() */ @@ -1448,7 +1448,7 @@ static int sam_adc_trigger(struct sam_adc_s *priv) /* Configure to trigger using Timer/counter 0, channel 1, 2, or 3. * NOTE: This trigger option depends on having properly configuer * timer/counter 0 to provide this output. That is done independently - * the the timer/counter driver. + * the timer/counter driver. */ /* Set TIOAn trigger where n=0, 1, or 2 */ diff --git a/arch/arm/src/sama5/sam_allocateheap.c b/arch/arm/src/sama5/sam_allocateheap.c index 29dcf728f6..be71204ff8 100644 --- a/arch/arm/src/sama5/sam_allocateheap.c +++ b/arch/arm/src/sama5/sam_allocateheap.c @@ -147,7 +147,7 @@ # define SAMA5_PRIMARY_HEAP_END CONFIG_SAMA5_DDRCS_HEAP_END #else - /* Otherwise, add the RAM all the way to the the end of the primary memory + /* Otherwise, add the RAM all the way to the end of the primary memory * region to the heap. */ diff --git a/arch/arm/src/sama5/sam_dbgu.c b/arch/arm/src/sama5/sam_dbgu.c index 65242b8818..cc4f6bf7f4 100644 --- a/arch/arm/src/sama5/sam_dbgu.c +++ b/arch/arm/src/sama5/sam_dbgu.c @@ -580,7 +580,7 @@ void sam_dbgu_devinitialize(void) putreg32(DBGU_INT_ALLINTS, SAM_DBGU_IDR); #ifdef CONFIG_SAMA5_DBGU_CONSOLE - /* Configuration the DBGU as the the console */ + /* Configuration the DBGU as the console */ g_dbgu_port.isconsole = true; dbgu_configure(); diff --git a/arch/arm/src/sama5/sam_ehci.c b/arch/arm/src/sama5/sam_ehci.c index d84f1c2dbc..4070964863 100644 --- a/arch/arm/src/sama5/sam_ehci.c +++ b/arch/arm/src/sama5/sam_ehci.c @@ -2819,7 +2819,7 @@ static inline void sam_ioc_bottomhalf(void) qh = (struct sam_qh_s *)sam_virtramaddr(sam_swap32(*bp) & QH_HLP_MASK); /* If the asynchronous queue is empty, then the forward point in the - * asynchronous queue head will point back to the the queue head. + * asynchronous queue head will point back to the queue head. */ if (qh && qh != &g_asynchead) @@ -4183,7 +4183,7 @@ errout_with_sem: * Description: * Process a request to handle a transfer descriptor. This method will * enqueue the transfer request and return immediately. When the transfer - * completes, the the callback will be invoked with the provided transfer. + * completes, the callback will be invoked with the provided transfer. * This method is useful for receiving interrupt transfers which may come * infrequently. * @@ -4373,7 +4373,7 @@ static int sam_cancel(FAR struct usbhost_driver_s *drvr, usbhost_ep_t ep) qh = (struct sam_qh_s *)sam_virtramaddr(sam_swap32(*bp) & QH_HLP_MASK); /* If the asynchronous queue is empty, then the forward point in - * the asynchronous queue head will point back to the the queue + * the asynchronous queue head will point back to the queue * head. */ diff --git a/arch/arm/src/sama5/sam_emaca.c b/arch/arm/src/sama5/sam_emaca.c index 494fb7a6e5..1648cab525 100644 --- a/arch/arm/src/sama5/sam_emaca.c +++ b/arch/arm/src/sama5/sam_emaca.c @@ -902,7 +902,7 @@ static int sam_txpoll(struct net_driver_s *dev) sam_transmit(priv); - /* Check if the there are any free TX descriptors. We cannot perform + /* Check if there are any free TX descriptors. We cannot perform * the TX poll if we do not have buffering for another packet. */ @@ -949,7 +949,7 @@ static void sam_dopoll(struct sam_emac_s *priv) { struct net_driver_s *dev = &priv->dev; - /* Check if the there are any free TX descriptors. We cannot perform the + /* Check if there are any free TX descriptors. We cannot perform the * TX poll if we do not have buffering for another packet. */ @@ -1783,7 +1783,7 @@ static void sam_poll_work(FAR void *arg) FAR struct sam_emac_s *priv = (FAR struct sam_emac_s *)arg; struct net_driver_s *dev = &priv->dev; - /* Check if the there are any free TX descriptors. We cannot perform the + /* Check if there are any free TX descriptors. We cannot perform the * TX poll if we do not have buffering for another packet. */ diff --git a/arch/arm/src/sama5/sam_emacb.c b/arch/arm/src/sama5/sam_emacb.c index 2f4fcbf693..c08725216c 100644 --- a/arch/arm/src/sama5/sam_emacb.c +++ b/arch/arm/src/sama5/sam_emacb.c @@ -1237,7 +1237,7 @@ static int sam_txpoll(struct net_driver_s *dev) sam_transmit(priv); - /* Check if the there are any free TX descriptors. We cannot perform + /* Check if there are any free TX descriptors. We cannot perform * the TX poll if we do not have buffering for another packet. */ @@ -1285,7 +1285,7 @@ static void sam_dopoll(struct sam_emac_s *priv) { struct net_driver_s *dev = &priv->dev; - /* Check if the there are any free TX descriptors. We cannot perform the + /* Check if there are any free TX descriptors. We cannot perform the * TX poll if we do not have buffering for another packet. */ @@ -2144,7 +2144,7 @@ static void sam_poll_work(FAR void *arg) FAR struct sam_emac_s *priv = (FAR struct sam_emac_s *)arg; struct net_driver_s *dev = &priv->dev; - /* Check if the there are any free TX descriptors. We cannot perform the + /* Check if there are any free TX descriptors. We cannot perform the * TX poll if we do not have buffering for another packet. */ diff --git a/arch/arm/src/sama5/sam_gmac.c b/arch/arm/src/sama5/sam_gmac.c index 29d42258de..d909962190 100644 --- a/arch/arm/src/sama5/sam_gmac.c +++ b/arch/arm/src/sama5/sam_gmac.c @@ -834,7 +834,7 @@ static int sam_txpoll(struct net_driver_s *dev) sam_transmit(priv); - /* Check if the there are any free TX descriptors. We cannot perform + /* Check if there are any free TX descriptors. We cannot perform * the TX poll if we do not have buffering for another packet. */ @@ -881,7 +881,7 @@ static void sam_dopoll(struct sam_gmac_s *priv) { struct net_driver_s *dev = &priv->dev; - /* Check if the there are any free TX descriptors. We cannot perform the + /* Check if there are any free TX descriptors. We cannot perform the * TX poll if we do not have buffering for another packet. */ @@ -1735,7 +1735,7 @@ static void sam_poll_work(FAR void *arg) FAR struct sam_gmac_s *priv = (FAR struct sam_gmac_s *)arg; struct net_driver_s *dev = &priv->dev; - /* Check if the there are any free TX descriptors. We cannot perform the + /* Check if there are any free TX descriptors. We cannot perform the * TX poll if we do not have buffering for another packet. */ diff --git a/arch/arm/src/sama5/sam_hsmci.c b/arch/arm/src/sama5/sam_hsmci.c index 3aa006d872..7b4cee4749 100644 --- a/arch/arm/src/sama5/sam_hsmci.c +++ b/arch/arm/src/sama5/sam_hsmci.c @@ -3102,7 +3102,7 @@ static void sam_callback(void *arg) priv->cbevents = 0; /* This function is called either from (1) the context of the calling - * thread or from the the context of (2) card detection logic. The + * thread or from the context of (2) card detection logic. The * caller may or may not have interrupts disabled (we have them * disabled here!). * diff --git a/arch/arm/src/sama5/sam_memorymap.h b/arch/arm/src/sama5/sam_memorymap.h index 673f4f9ef3..85612b001a 100644 --- a/arch/arm/src/sama5/sam_memorymap.h +++ b/arch/arm/src/sama5/sam_memorymap.h @@ -50,7 +50,7 @@ ************************************************************************************/ /* The vectors are, by default, positioned at the beginning of the text - * section. Under what conditions do we have to remap the these vectors? + * section. Under what conditions do we have to remap these vectors? * * 1) If we are using high vectors (CONFIG_ARCH_LOWVECTORS=n). In this case, * the vectors will lie at virtual address 0xffff:000 and we will need diff --git a/arch/arm/src/sama5/sam_nand.c b/arch/arm/src/sama5/sam_nand.c index 05182120d9..c7cf74f185 100644 --- a/arch/arm/src/sama5/sam_nand.c +++ b/arch/arm/src/sama5/sam_nand.c @@ -1245,7 +1245,7 @@ static int nand_wait_dma(struct sam_nandcs_s *priv) * * Description: * Called when one NAND DMA sequence completes. This function just wakes - * the the waiting NAND driver logic. + * the waiting NAND driver logic. * ****************************************************************************/ diff --git a/arch/arm/src/sama5/sam_ohci.c b/arch/arm/src/sama5/sam_ohci.c index f6907d1b0f..e90c2fdde6 100644 --- a/arch/arm/src/sama5/sam_ohci.c +++ b/arch/arm/src/sama5/sam_ohci.c @@ -3531,7 +3531,7 @@ static void sam_asynch_completion(struct sam_eplist_s *eplist) * Description: * Process a request to handle a transfer descriptor. This method will * enqueue the transfer request and return immediately. When the transfer - * completes, the the callback will be invoked with the provided transfer. + * completes, the callback will be invoked with the provided transfer. * This method is useful for receiving interrupt transfers which may come * infrequently. * diff --git a/arch/arm/src/sama5/sam_oneshot.c b/arch/arm/src/sama5/sam_oneshot.c index b883606982..1bab862afa 100644 --- a/arch/arm/src/sama5/sam_oneshot.c +++ b/arch/arm/src/sama5/sam_oneshot.c @@ -417,7 +417,7 @@ int sam_oneshot_cancel(struct sam_oneshot_s *oneshot, * the counter expires while we are doing this, the counter clock will be * stopped, but the clock will not be disabled. * - * The expected behavior is that the the counter register will freezes at + * The expected behavior is that the counter register will freezes at * a value equal to the RC register when the timer expires. The counter * should have values between 0 and RC in all other cased. * diff --git a/arch/arm/src/sama5/sam_tc.c b/arch/arm/src/sama5/sam_tc.c index 015d6bc96a..2bdff628ca 100644 --- a/arch/arm/src/sama5/sam_tc.c +++ b/arch/arm/src/sama5/sam_tc.c @@ -1427,7 +1427,7 @@ uint32_t sam_tc_divfreq(TC_HANDLE handle) DEBUGASSERT(chan); - /* Get the the TC_CMR register contents for this channel and extract the + /* Get the TC_CMR register contents for this channel and extract the * TCCLKS index. */ diff --git a/arch/arm/src/sama5/sam_tickless.c b/arch/arm/src/sama5/sam_tickless.c index bb3c678561..e77a96b304 100644 --- a/arch/arm/src/sama5/sam_tickless.c +++ b/arch/arm/src/sama5/sam_tickless.c @@ -325,7 +325,7 @@ void arm_timer_initialize(void) * any failure. * * Assumptions: - * Called from the the normal tasking context. The implementation must + * Called from the normal tasking context. The implementation must * provide whatever mutual exclusion is necessary for correct operation. * This can include disabling interrupts in order to assure atomic register * operations. diff --git a/arch/arm/src/sama5/sam_udphs.c b/arch/arm/src/sama5/sam_udphs.c index 3f27bd3112..090e10b4d8 100644 --- a/arch/arm/src/sama5/sam_udphs.c +++ b/arch/arm/src/sama5/sam_udphs.c @@ -1298,7 +1298,7 @@ static void sam_req_wrsetup(struct sam_usbdev_s *priv, * When this function starts a transfer it will update the request * 'inflight' field to indicate the size of the transfer. * - * When the transfer completes, the the 'inflight' field must hold the + * When the transfer completes, the 'inflight' field must hold the * number of bytes that have completed the transfer. This function will * update 'xfrd' with the new size of the transfer. * @@ -4554,7 +4554,7 @@ int usbdev_register(struct usbdevclass_driver_s *driver) up_enable_irq(SAM_IRQ_UDPHS); /* Enable pull-up to connect the device. The host should enumerate us - * some time after this. The next thing we expect the the ENDRESET + * some time after this. The next thing we expect the ENDRESET * interrupt. */ diff --git a/arch/arm/src/sama5/sama5d2x_pio.c b/arch/arm/src/sama5/sama5d2x_pio.c index 3a87d3da66..4907529be4 100644 --- a/arch/arm/src/sama5/sama5d2x_pio.c +++ b/arch/arm/src/sama5/sama5d2x_pio.c @@ -571,13 +571,13 @@ bool sam_pioread(pio_pinset_t pinset) pin = sam_piopin(pinset); /* For output PIOs, the ODSR register provides the output value to - * drive the pin. The PDSR register, on the the other hand, provides + * drive the pin. The PDSR register, on the other hand, provides * the current sensed value on a pin, whether the pin is configured * as an input, an output or as a peripheral. * * There is small delay between the setting in ODSR and PDSR but - * otherwise the they should be the same unless something external - * is driving the pin. + * otherwise they should be the same unless something external is + * driving the pin. * * Let's assume that PDSR is what the caller wants. */ diff --git a/arch/arm/src/sama5/sama5d3x4x_pio.c b/arch/arm/src/sama5/sama5d3x4x_pio.c index 806fb9fc08..5f979f3c85 100644 --- a/arch/arm/src/sama5/sama5d3x4x_pio.c +++ b/arch/arm/src/sama5/sama5d3x4x_pio.c @@ -262,7 +262,7 @@ static void sam_pio_enableclk(pio_pinset_t cfgset) * 1) No pins are configured as PIO inputs (peripheral inputs don't need * clocking, and * 2) Glitch and debounce filtering are not enabled. Currently, this can - * only happen if the the pin is a PIO input, but we may need to + * only happen if the pin is a PIO input, but we may need to * implement glitch filtering on peripheral inputs as well in the * future??? * 3) The port is not configured for PIO interrupts. At present, the logic @@ -816,13 +816,13 @@ bool sam_pioread(pio_pinset_t pinset) pin = sam_piopin(pinset); /* For output PIOs, the ODSR register provides the output value to - * drive the pin. The PDSR register, on the the other hand, provides + * drive the pin. The PDSR register, on the other hand, provides * the current sensed value on a pin, whether the pin is configured * as an input, an output or as a peripheral. * * There is small delay between the setting in ODSR and PDSR but - * otherwise the they should be the same unless something external - * is driving the pin. + * otherwise they should be the same unless something external is + * driving the pin. * * Let's assume that PDSR is what the caller wants. */ diff --git a/arch/arm/src/samdl/sam_timerisr.c b/arch/arm/src/samdl/sam_timerisr.c index abc61f355f..73dd99af15 100644 --- a/arch/arm/src/samdl/sam_timerisr.c +++ b/arch/arm/src/samdl/sam_timerisr.c @@ -61,7 +61,7 @@ * system clock ticks per second. That value is a user configurable setting * that defaults to 100 (100 ticks per second = 10 MS interval). * - * Then, for example, if the CPU clock is the the SysTick and + * Then, for example, if the CPU clock is the SysTick and * BOARD_CPU_FREQUENCY is 48MHz and CLK_TCK is 100, then the reload value * would be: * diff --git a/arch/arm/src/samdl/saml_clockconfig.c b/arch/arm/src/samdl/saml_clockconfig.c index 11dbaff10f..364933501d 100644 --- a/arch/arm/src/samdl/saml_clockconfig.c +++ b/arch/arm/src/samdl/saml_clockconfig.c @@ -1131,7 +1131,7 @@ static inline void sam_fdpll96m_config(void) static inline void sam_fdpll96m_refclk(void) { #ifdef BOARD_FDPLL96M_LOCKTIME_ENABLE - /* Enable the GCLK that is configured to the the FDPLL lock timer */ + /* Enable the GCLK that is configured to the FDPLL lock timer */ sam_gclk_chan_enable(GCLK_CHAN_DPLL_32K, BOARD_FDPLL96M_LOCKTIME_CLKGEN); #endif diff --git a/arch/arm/src/samv7/chip/sam_emac.h b/arch/arm/src/samv7/chip/sam_emac.h index e0a0cbb9a7..c613c14f1c 100644 --- a/arch/arm/src/samv7/chip/sam_emac.h +++ b/arch/arm/src/samv7/chip/sam_emac.h @@ -1,6 +1,6 @@ /************************************************************************************ * arch/arm/src/samv7/chip/sam_emac.h - * This is the form of the EMAC interface used the the SAMV7. + * This is the form of the EMAC interface used the SAMV7. * This is referred as GMAC in the documentation even though it does not support * Gibabit Ethernet. * diff --git a/arch/arm/src/samv7/sam_dac.c b/arch/arm/src/samv7/sam_dac.c index 78a19929b5..b1293aa5b2 100644 --- a/arch/arm/src/samv7/sam_dac.c +++ b/arch/arm/src/samv7/sam_dac.c @@ -381,7 +381,7 @@ static int dac_timer_init(struct sam_dac_s *priv, uint32_t freq_required, DEBUGASSERT(priv && (freq_required > 0) && (channel >= 0 && channel <= 2)); - /* Set the timer/counter waveform mode the the clock input. Use smallest + /* Set the timer/counter waveform mode the clock input. Use smallest * MCK divisor of 8 to have highest clock resolution thus smallest frequency * error. With 32 bit counter the lowest possible frequency of 1 Hz is easily * supported. diff --git a/arch/arm/src/samv7/sam_emac.c b/arch/arm/src/samv7/sam_emac.c index 5bfb2f4a58..3496331898 100644 --- a/arch/arm/src/samv7/sam_emac.c +++ b/arch/arm/src/samv7/sam_emac.c @@ -1551,7 +1551,7 @@ static int sam_txpoll(struct net_driver_s *dev) sam_transmit(priv, EMAC_QUEUE_0); - /* Check if the there are any free TX descriptors. We cannot perform + /* Check if there are any free TX descriptors. We cannot perform * the TX poll if we do not have buffering for another packet. */ @@ -1601,7 +1601,7 @@ static void sam_dopoll(struct sam_emac_s *priv, int qid) { struct net_driver_s *dev = &priv->dev; - /* Check if the there are any free TX descriptors. We cannot perform the + /* Check if there are any free TX descriptors. We cannot perform the * TX poll if we do not have buffering for another packet. */ @@ -2615,7 +2615,7 @@ static void sam_poll_work(FAR void *arg) FAR struct sam_emac_s *priv = (FAR struct sam_emac_s *)arg; struct net_driver_s *dev = &priv->dev; - /* Check if the there are any free TX descriptors. We cannot perform the + /* Check if there are any free TX descriptors. We cannot perform the * TX poll if we do not have buffering for another packet. */ diff --git a/arch/arm/src/samv7/sam_hsmci.c b/arch/arm/src/samv7/sam_hsmci.c index a83a51ecc0..544cae9524 100644 --- a/arch/arm/src/samv7/sam_hsmci.c +++ b/arch/arm/src/samv7/sam_hsmci.c @@ -3176,7 +3176,7 @@ static void sam_callback(void *arg) priv->cbevents = 0; /* This function is called either from (1) the context of the calling - * thread or from the the context of (2) card detection logic. The + * thread or from the context of (2) card detection logic. The * caller may or may not have interrupts disabled (we have them * disabled here!). * diff --git a/arch/arm/src/samv7/sam_oneshot.c b/arch/arm/src/samv7/sam_oneshot.c index 9a20ec17a7..0162a4d0e6 100644 --- a/arch/arm/src/samv7/sam_oneshot.c +++ b/arch/arm/src/samv7/sam_oneshot.c @@ -419,7 +419,7 @@ int sam_oneshot_cancel(struct sam_oneshot_s *oneshot, * the counter expires while we are doing this, the counter clock will be * stopped, but the clock will not be disabled. * - * The expected behavior is that the the counter register will freezes at + * The expected behavior is that the counter register will freezes at * a value equal to the RC register when the timer expires. The counter * should have values between 0 and RC in all other cased. * diff --git a/arch/arm/src/samv7/sam_tc.c b/arch/arm/src/samv7/sam_tc.c index 4b9303fd53..91b0e36f5f 100644 --- a/arch/arm/src/samv7/sam_tc.c +++ b/arch/arm/src/samv7/sam_tc.c @@ -1615,7 +1615,7 @@ uint32_t sam_tc_divfreq(TC_HANDLE handle) DEBUGASSERT(chan); - /* Get the the TC_CMR register contents for this channel and extract the + /* Get the TC_CMR register contents for this channel and extract the * TCCLKS index. */ diff --git a/arch/arm/src/samv7/sam_tickless.c b/arch/arm/src/samv7/sam_tickless.c index 1cda5dcc73..b1b101455e 100644 --- a/arch/arm/src/samv7/sam_tickless.c +++ b/arch/arm/src/samv7/sam_tickless.c @@ -311,7 +311,7 @@ void arm_timer_initialize(void) * any failure. * * Assumptions: - * Called from the the normal tasking context. The implementation must + * Called from the normal tasking context. The implementation must * provide whatever mutual exclusion is necessary for correct operation. * This can include disabling interrupts in order to assure atomic register * operations. diff --git a/arch/arm/src/samv7/sam_usbdevhs.c b/arch/arm/src/samv7/sam_usbdevhs.c index 4adfa117c1..d2904fc96c 100644 --- a/arch/arm/src/samv7/sam_usbdevhs.c +++ b/arch/arm/src/samv7/sam_usbdevhs.c @@ -1359,7 +1359,7 @@ static void sam_req_wrsetup(struct sam_usbdev_s *priv, * When this function starts a transfer it will update the request * 'inflight' field to indicate the size of the transfer. * - * When the transfer completes, the the 'inflight' field must hold the + * When the transfer completes, the 'inflight' field must hold the * number of bytes that have completed the transfer. This function will * update 'xfrd' with the new size of the transfer. * diff --git a/arch/arm/src/stm32/Kconfig b/arch/arm/src/stm32/Kconfig index a74bfafc59..2242a018df 100644 --- a/arch/arm/src/stm32/Kconfig +++ b/arch/arm/src/stm32/Kconfig @@ -6855,7 +6855,7 @@ config STM32_LTDC_DITHER_BLUE config STM32_LTDC_FB_BASE hex "Framebuffer memory start address" ---help--- - If you are using the the LTDC, then you must provide the address + If you are using the LTDC, then you must provide the address of the start of the framebuffer. This address will typically be in the SRAM or SDRAM memory region of the FSMC. diff --git a/arch/arm/src/stm32/gnu/stm32_vectors.S b/arch/arm/src/stm32/gnu/stm32_vectors.S index c961781f33..4943686dac 100644 --- a/arch/arm/src/stm32/gnu/stm32_vectors.S +++ b/arch/arm/src/stm32/gnu/stm32_vectors.S @@ -63,7 +63,7 @@ * stale MSP, there will most likely be a system failure. * * If the interrupt stack is selected, on the other hand, then the interrupt - * handler will always set the the MSP to the interrupt stack. So when the high + * handler will always set the MSP to the interrupt stack. So when the high * priority interrupt occurs, it will either use the MSP of the last privileged * thread to run or, in the case of the nested interrupt, the interrupt stack if * no privileged task has run. @@ -73,7 +73,7 @@ # error Interrupt stack must be used with high priority interrupts in kernel mode # endif - /* Use the the BASEPRI to control interrupts is required if nested, high + /* Use the BASEPRI to control interrupts is required if nested, high * priority interrupts are supported. */ diff --git a/arch/arm/src/stm32/iar/stm32_vectors.S b/arch/arm/src/stm32/iar/stm32_vectors.S index f46cb7c57b..52fdfb3056 100644 --- a/arch/arm/src/stm32/iar/stm32_vectors.S +++ b/arch/arm/src/stm32/iar/stm32_vectors.S @@ -63,7 +63,7 @@ * stale MSP, there will most likely be a system failure. * * If the interrupt stack is selected, on the other hand, then the interrupt - * handler will always set the the MSP to the interrupt stack. So when the high + * handler will always set the MSP to the interrupt stack. So when the high * priority interrupt occurs, it will either use the MSP of the last privileged * thread to run or, in the case of the nested interrupt, the interrupt stack if * no privileged task has run. @@ -73,7 +73,7 @@ # error Interrupt stack must be used with high priority interrupts in kernel mode # endif - /* Use the the BASEPRI to control interrupts is required if nested, high + /* Use the BASEPRI to control interrupts is required if nested, high * priority interrupts are supported. */ diff --git a/arch/arm/src/stm32/stm32_bbsram.c b/arch/arm/src/stm32/stm32_bbsram.c index a401feca56..f1e0b6d311 100644 --- a/arch/arm/src/stm32/stm32_bbsram.c +++ b/arch/arm/src/stm32/stm32_bbsram.c @@ -612,7 +612,7 @@ static int stm32_bbsram_ioctl(FAR struct file *filep, int cmd, * This function will remove the remove the file from the file system * it will zero the contents and time stamp. It will leave the fileno * and pointer to the BBSRAM intact. - * It should be called called on the the file used for the crash dump + * It should be called called on the file used for the crash dump * to remove it from visibility in the file system after it is created or * read thus arming it. * diff --git a/arch/arm/src/stm32/stm32_dma.h b/arch/arm/src/stm32/stm32_dma.h index c29f7f0d8c..ceee4e0867 100644 --- a/arch/arm/src/stm32/stm32_dma.h +++ b/arch/arm/src/stm32/stm32_dma.h @@ -94,7 +94,7 @@ typedef FAR void *DMA_HANDLE; /* Description: - * This is the type of the callback that is used to inform the user of the the + * This is the type of the callback that is used to inform the user of the * completion of the DMA. * * Input Parameters: diff --git a/arch/arm/src/stm32/stm32_eth.c b/arch/arm/src/stm32/stm32_eth.c index 8b38985f15..2b02b5e345 100644 --- a/arch/arm/src/stm32/stm32_eth.c +++ b/arch/arm/src/stm32/stm32_eth.c @@ -1551,7 +1551,7 @@ static int stm32_recvframe(FAR struct stm32_ethmac_s *priv) { priv->segments++; - /* Check if the there is only one segment in the frame */ + /* Check if there is only one segment in the frame */ if (priv->segments == 1) { diff --git a/arch/arm/src/stm32/stm32_ltdc.c b/arch/arm/src/stm32/stm32_ltdc.c index 2573730172..22b650c598 100644 --- a/arch/arm/src/stm32/stm32_ltdc.c +++ b/arch/arm/src/stm32/stm32_ltdc.c @@ -3014,7 +3014,7 @@ static int stm32_getblendmode(FAR struct ltdc_layer_s *layer, uint32_t *mode) * On error - -EINVAL * * Procedure Information: - * If the srcxpos and srcypos unequal the the xpos and ypos of the area + * If the srcxpos and srcypos unequal the xpos and ypos of the area * structure this acts like moving the visible area to another position on * the screen during the next update operation. * diff --git a/arch/arm/src/stm32/stm32_oneshot.c b/arch/arm/src/stm32/stm32_oneshot.c index ab8d2a4034..ba76bf65b9 100644 --- a/arch/arm/src/stm32/stm32_oneshot.c +++ b/arch/arm/src/stm32/stm32_oneshot.c @@ -393,7 +393,7 @@ int stm32_oneshot_cancel(struct stm32_oneshot_s *oneshot, * If the counter expires while we are doing this, the counter clock will * be stopped, but the clock will not be disabled. * - * The expected behavior is that the the counter register will freezes at + * The expected behavior is that the counter register will freezes at * a value equal to the RC register when the timer expires. The counter * should have values between 0 and RC in all other cased. * diff --git a/arch/arm/src/stm32/stm32_otgfsdev.c b/arch/arm/src/stm32/stm32_otgfsdev.c index 47b212c3c2..4d23392912 100644 --- a/arch/arm/src/stm32/stm32_otgfsdev.c +++ b/arch/arm/src/stm32/stm32_otgfsdev.c @@ -5238,7 +5238,7 @@ static void stm32_hwinitialize(FAR struct stm32_usbdev_s *priv) # endif #else - /* In the case of the the all others the meaning of the bit is No VBUS + /* In the case of the all others the meaning of the bit is No VBUS * Sense when Set */ diff --git a/arch/arm/src/stm32/stm32_otgfshost.c b/arch/arm/src/stm32/stm32_otgfshost.c index c8ce6a2dd8..b28226f5f2 100644 --- a/arch/arm/src/stm32/stm32_otgfshost.c +++ b/arch/arm/src/stm32/stm32_otgfshost.c @@ -1978,7 +1978,7 @@ static ssize_t stm32_in_transfer(FAR struct stm32_usbhost_s *priv, int chidx, { /* Successfully received another chunk of data... add that to the * runing total. Then continue reading until we read 'buflen' - * bytes of data or until the the devices NAKs (implying a short + * bytes of data or until the devices NAKs (implying a short * packet). */ @@ -2235,8 +2235,8 @@ static ssize_t stm32_out_transfer(FAR struct stm32_usbhost_s *priv, int chidx, /* Check for a special case: If (1) the transfer was NAKed and (2) * no Tx FIFO empty or Rx FIFO not-empty event occurred, then we * should be able to just flush the Rx and Tx FIFOs and try again. - * We can detect this latter case because the then the transfer - * buffer pointer and buffer size will be unaltered. + * We can detect this latter case because then the transfer buffer + * pointer and buffer size will be unaltered. */ elapsed = clock_systimer() - start; @@ -4630,7 +4630,7 @@ static ssize_t stm32_transfer(FAR struct usbhost_driver_s *drvr, usbhost_ep_t ep * Description: * Process a request to handle a transfer descriptor. This method will * enqueue the transfer request and return immediately. When the transfer - * completes, the the callback will be invoked with the provided transfer. + * completes, the callback will be invoked with the provided transfer. * This method is useful for receiving interrupt transfers which may come * infrequently. * diff --git a/arch/arm/src/stm32/stm32_otghshost.c b/arch/arm/src/stm32/stm32_otghshost.c index 090ef4292b..17023088b6 100644 --- a/arch/arm/src/stm32/stm32_otghshost.c +++ b/arch/arm/src/stm32/stm32_otghshost.c @@ -1983,7 +1983,7 @@ static ssize_t stm32_in_transfer(FAR struct stm32_usbhost_s *priv, int chidx, { /* Successfully received another chunk of data... add that to the * runing total. Then continue reading until we read 'buflen' - * bytes of data or until the the devices NAKs (implying a short + * bytes of data or until the devices NAKs (implying a short * packet). */ @@ -2240,8 +2240,8 @@ static ssize_t stm32_out_transfer(FAR struct stm32_usbhost_s *priv, int chidx, /* Check for a special case: If (1) the transfer was NAKed and (2) * no Tx FIFO empty or Rx FIFO not-empty event occurred, then we * should be able to just flush the Rx and Tx FIFOs and try again. - * We can detect this latter case because the then the transfer - * buffer pointer and buffer size will be unaltered. + * We can detect this latter case because then the transfer buffer + * pointer and buffer size will be unaltered. */ elapsed = clock_systimer() - start; @@ -4635,7 +4635,7 @@ static ssize_t stm32_transfer(FAR struct usbhost_driver_s *drvr, usbhost_ep_t ep * Description: * Process a request to handle a transfer descriptor. This method will * enqueue the transfer request and return immediately. When the transfer - * completes, the the callback will be invoked with the provided transfer. + * completes, the callback will be invoked with the provided transfer. * This method is useful for receiving interrupt transfers which may come * infrequently. * diff --git a/arch/arm/src/stm32/stm32_tickless.c b/arch/arm/src/stm32/stm32_tickless.c index 38162ad7d7..6d7a004693 100644 --- a/arch/arm/src/stm32/stm32_tickless.c +++ b/arch/arm/src/stm32/stm32_tickless.c @@ -590,7 +590,7 @@ void arm_timer_initialize(void) * any failure. * * Assumptions: - * Called from the the normal tasking context. The implementation must + * Called from the normal tasking context. The implementation must * provide whatever mutual exclusion is necessary for correct operation. * This can include disabling interrupts in order to assure atomic register * operations. diff --git a/arch/arm/src/stm32/stm32f40xxx_rtcc.c b/arch/arm/src/stm32/stm32f40xxx_rtcc.c index 5702904131..e15c995a6c 100644 --- a/arch/arm/src/stm32/stm32f40xxx_rtcc.c +++ b/arch/arm/src/stm32/stm32f40xxx_rtcc.c @@ -1354,7 +1354,7 @@ int stm32_rtc_setalarm(FAR struct alm_setalarm_s *alminfo) ASSERT(alminfo != NULL); DEBUGASSERT(RTC_ALARM_LAST > alminfo->as_id); - /* Make sure the the alarm interrupt is enabled at the NVIC */ + /* Make sure the alarm interrupt is enabled at the NVIC */ rtc_enable_alarm(); diff --git a/arch/arm/src/stm32f0/stm32f0_hsi48.c b/arch/arm/src/stm32f0/stm32f0_hsi48.c index f9d4c52cf6..2a33b9cf85 100644 --- a/arch/arm/src/stm32f0/stm32f0_hsi48.c +++ b/arch/arm/src/stm32f0/stm32f0_hsi48.c @@ -137,7 +137,7 @@ void stm32f0_enable_hsi48(enum syncsrc_e syncsrc) putreg32(regval, STM32F0_CRS_CFGR); - /* Set the AUTOTRIMEN bit the the CRS_CR register to enables the automatic + /* Set the AUTOTRIMEN bit the CRS_CR register to enables the automatic * hardware adjustment of TRIM bits according to the measured frequency * error between the selected SYNC event. */ diff --git a/arch/arm/src/stm32f7/stm32_bbsram.c b/arch/arm/src/stm32f7/stm32_bbsram.c index 71adbcfd21..62905f8326 100644 --- a/arch/arm/src/stm32f7/stm32_bbsram.c +++ b/arch/arm/src/stm32f7/stm32_bbsram.c @@ -613,7 +613,7 @@ static int stm32_bbsram_ioctl(FAR struct file *filep, int cmd, * This function will remove the remove the file from the file system * it will zero the contents and time stamp. It will leave the fileno * and pointer to the BBSRAM intact. - * It should be called called on the the file used for the crash dump + * It should be called called on the file used for the crash dump * to remove it from visibility in the file system after it is created or * read thus arming it. * diff --git a/arch/arm/src/stm32f7/stm32_dma.h b/arch/arm/src/stm32f7/stm32_dma.h index b25cb84e7d..3604d45d0c 100644 --- a/arch/arm/src/stm32f7/stm32_dma.h +++ b/arch/arm/src/stm32f7/stm32_dma.h @@ -69,7 +69,7 @@ typedef FAR void *DMA_HANDLE; /* Description: - * This is the type of the callback that is used to inform the user of the the + * This is the type of the callback that is used to inform the user of the * completion of the DMA. NOTE: The DMA module does *NOT* perform any cache * operations. It is the responsibility of the DMA client to invalidate DMA * buffers after completion of the DMA RX operations. diff --git a/arch/arm/src/stm32f7/stm32_ethernet.c b/arch/arm/src/stm32f7/stm32_ethernet.c index 2ac01c649e..3573100631 100644 --- a/arch/arm/src/stm32f7/stm32_ethernet.c +++ b/arch/arm/src/stm32f7/stm32_ethernet.c @@ -1636,7 +1636,7 @@ static int stm32_recvframe(struct stm32_ethmac_s *priv) { priv->segments++; - /* Check if the there is only one segment in the frame */ + /* Check if there is only one segment in the frame */ if (priv->segments == 1) { diff --git a/arch/arm/src/stm32f7/stm32_otghost.c b/arch/arm/src/stm32f7/stm32_otghost.c index 29de1826ed..f0307be640 100644 --- a/arch/arm/src/stm32f7/stm32_otghost.c +++ b/arch/arm/src/stm32f7/stm32_otghost.c @@ -1977,7 +1977,7 @@ static ssize_t stm32_in_transfer(FAR struct stm32_usbhost_s *priv, int chidx, { /* Successfully received another chunk of data... add that to the * runing total. Then continue reading until we read 'buflen' - * bytes of data or until the the devices NAKs (implying a short + * bytes of data or until the devices NAKs (implying a short * packet). */ @@ -2234,8 +2234,8 @@ static ssize_t stm32_out_transfer(FAR struct stm32_usbhost_s *priv, int chidx, /* Check for a special case: If (1) the transfer was NAKed and (2) * no Tx FIFO empty or Rx FIFO not-empty event occurred, then we * should be able to just flush the Rx and Tx FIFOs and try again. - * We can detect this latter case because the then the transfer - * buffer pointer and buffer size will be unaltered. + * We can detect this latter case because then the transfer buffer + * pointer and buffer size will be unaltered. */ elapsed = clock_systimer() - start; @@ -4628,7 +4628,7 @@ static ssize_t stm32_transfer(FAR struct usbhost_driver_s *drvr, usbhost_ep_t ep * Description: * Process a request to handle a transfer descriptor. This method will * enqueue the transfer request and return immediately. When the transfer - * completes, the the callback will be invoked with the provided transfer. + * completes, the callback will be invoked with the provided transfer. * This method is useful for receiving interrupt transfers which may come * infrequently. * diff --git a/arch/arm/src/stm32l4/stm32l4_dma.h b/arch/arm/src/stm32l4/stm32l4_dma.h index c12013782d..e21a6c1f66 100644 --- a/arch/arm/src/stm32l4/stm32l4_dma.h +++ b/arch/arm/src/stm32l4/stm32l4_dma.h @@ -79,7 +79,7 @@ typedef FAR void *DMA_HANDLE; /* Description: - * This is the type of the callback that is used to inform the user of the the + * This is the type of the callback that is used to inform the user of the * completion of the DMA. * * Input Parameters: diff --git a/arch/arm/src/stm32l4/stm32l4_oneshot.c b/arch/arm/src/stm32l4/stm32l4_oneshot.c index 5ae8e069ad..9a7eb87b61 100644 --- a/arch/arm/src/stm32l4/stm32l4_oneshot.c +++ b/arch/arm/src/stm32l4/stm32l4_oneshot.c @@ -395,7 +395,7 @@ int stm32l4_oneshot_cancel(FAR struct stm32l4_oneshot_s *oneshot, * If the counter expires while we are doing this, the counter clock will * be stopped, but the clock will not be disabled. * - * The expected behavior is that the the counter register will freezes at + * The expected behavior is that the counter register will freezes at * a value equal to the RC register when the timer expires. The counter * should have values between 0 and RC in all other cased. * diff --git a/arch/arm/src/stm32l4/stm32l4_otgfshost.c b/arch/arm/src/stm32l4/stm32l4_otgfshost.c index b24026370d..573cf892a5 100644 --- a/arch/arm/src/stm32l4/stm32l4_otgfshost.c +++ b/arch/arm/src/stm32l4/stm32l4_otgfshost.c @@ -1982,7 +1982,7 @@ static ssize_t stm32l4_in_transfer(FAR struct stm32l4_usbhost_s *priv, { /* Successfully received another chunk of data... add that to the * runing total. Then continue reading until we read 'buflen' - * bytes of data or until the the devices NAKs (implying a short + * bytes of data or until the devices NAKs (implying a short * packet). */ @@ -2240,8 +2240,8 @@ static ssize_t stm32l4_out_transfer(FAR struct stm32l4_usbhost_s *priv, /* Check for a special case: If (1) the transfer was NAKed and (2) * no Tx FIFO empty or Rx FIFO not-empty event occurred, then we * should be able to just flush the Rx and Tx FIFOs and try again. - * We can detect this latter case because the then the transfer - * buffer pointer and buffer size will be unaltered. + * We can detect this latter case because then the transfer buffer + * pointer and buffer size will be unaltered. */ elapsed = clock_systimer() - start; @@ -4635,7 +4635,7 @@ static ssize_t stm32l4_transfer(FAR struct usbhost_driver_s *drvr, usbhost_ep_t * Description: * Process a request to handle a transfer descriptor. This method will * enqueue the transfer request and return immediately. When the transfer - * completes, the the callback will be invoked with the provided transfer. + * completes, the callback will be invoked with the provided transfer. * This method is useful for receiving interrupt transfers which may come * infrequently. * diff --git a/arch/arm/src/stm32l4/stm32l4_rtcc.c b/arch/arm/src/stm32l4/stm32l4_rtcc.c index 84a1f9eab6..f36d4d040c 100644 --- a/arch/arm/src/stm32l4/stm32l4_rtcc.c +++ b/arch/arm/src/stm32l4/stm32l4_rtcc.c @@ -1295,7 +1295,7 @@ int stm32l4_rtc_setalarm(FAR struct alm_setalarm_s *alminfo) ASSERT(alminfo != NULL); DEBUGASSERT(RTC_ALARM_LAST > alminfo->as_id); - /* Make sure the the alarm interrupt is enabled at the NVIC */ + /* Make sure the alarm interrupt is enabled at the NVIC */ rtc_enable_alarm(); diff --git a/arch/arm/src/stm32l4/stm32l4_tickless.c b/arch/arm/src/stm32l4/stm32l4_tickless.c index 2d742daa1f..ad4a55e705 100644 --- a/arch/arm/src/stm32l4/stm32l4_tickless.c +++ b/arch/arm/src/stm32l4/stm32l4_tickless.c @@ -266,7 +266,7 @@ void arm_timer_initialize(void) * any failure. * * Assumptions: - * Called from the the normal tasking context. The implementation must + * Called from the normal tasking context. The implementation must * provide whatever mutual exclusion is necessary for correct operation. * This can include disabling interrupts in order to assure atomic register * operations. diff --git a/arch/arm/src/tiva/tiva_i2c.c b/arch/arm/src/tiva/tiva_i2c.c index 4fe0e54d42..86bea9cef6 100644 --- a/arch/arm/src/tiva/tiva_i2c.c +++ b/arch/arm/src/tiva/tiva_i2c.c @@ -1301,7 +1301,7 @@ static int tiva_i2c_process(struct tiva_i2c_priv_s *priv, uint32_t status) { /* Just continue transferring data. In this case, * no STOP was sent at the end of the last message - * and the there is no new address. + * and there is no new address. * * REVISIT: In this case, the address or the * direction of the transfer cannot be permitted to @@ -1485,7 +1485,7 @@ static int tiva_i2c_initialize(struct tiva_i2c_priv_s *priv, uint32_t frequency) #endif #endif - /* Configure the the initial I2C clock frequency. */ + /* Configure the initial I2C clock frequency. */ tiva_i2c_setclock(priv, frequency); diff --git a/arch/arm/src/tiva/tiva_timer.h b/arch/arm/src/tiva/tiva_timer.h index 2f498581d2..547cd11704 100644 --- a/arch/arm/src/tiva/tiva_timer.h +++ b/arch/arm/src/tiva/tiva_timer.h @@ -600,7 +600,7 @@ uint32_t tiva_timer32_remaining(TIMER_HANDLE handle); * Description: * This function may be called at any time to change the timer interval * match value of a 32-bit timer. This function sets the match register - * the the absolute value specified. + * the absolute value specified. * * Input Parameters: * handle - The handle value returned by tiva_gptm_configure() @@ -625,7 +625,7 @@ static inline void tiva_timer32_absmatch(TIMER_HANDLE handle, * Description: * This function may be called at any time to change the timer interval * match value of a 16-bit timer. This function sets the match register - * the the absolute value specified. + * the absolute value specified. * * Input Parameters: * handle - The handle value returned by tiva_gptm_configure() diff --git a/arch/arm/src/tiva/tiva_timerlib.c b/arch/arm/src/tiva/tiva_timerlib.c index e2d8bcd0b4..0abd19e801 100644 --- a/arch/arm/src/tiva/tiva_timerlib.c +++ b/arch/arm/src/tiva/tiva_timerlib.c @@ -2634,7 +2634,7 @@ uint32_t tiva_timer32_remaining(TIMER_HANDLE handle) * the timeout event (0x0), the timer reloads its start value * from the GPTMTAILR register on the next cycle. * - * The time remaining it then just the the value of the counter + * The time remaining it then just the value of the counter * register. * * REVISIT: Or the counter value +1? diff --git a/arch/arm/src/tiva/tiva_timerlow32.c b/arch/arm/src/tiva/tiva_timerlow32.c index 25478f6641..91f44618b0 100644 --- a/arch/arm/src/tiva/tiva_timerlow32.c +++ b/arch/arm/src/tiva/tiva_timerlow32.c @@ -433,7 +433,7 @@ static int tiva_settimeout(struct timer_lowerhalf_s *lower, uint32_t timeout) tmrinfo("Entry: timeout=%d\n", timeout); - /* Calculate the the new time settings */ + /* Calculate the new time settings */ tiva_timeout(priv, timeout); diff --git a/arch/arm/src/tiva/tiva_vectors.S b/arch/arm/src/tiva/tiva_vectors.S index 89c9c38e82..99db8115cc 100644 --- a/arch/arm/src/tiva/tiva_vectors.S +++ b/arch/arm/src/tiva/tiva_vectors.S @@ -63,7 +63,7 @@ * stale MSP, there will most likely be a system failure. * * If the interrupt stack is selected, on the other hand, then the interrupt - * handler will always set the the MSP to the interrupt stack. So when the high + * handler will always set the MSP to the interrupt stack. So when the high * priority interrupt occurs, it will either use the MSP of the last privileged * thread to run or, in the case of the nested interrupt, the interrupt stack if * no privileged task has run. @@ -73,7 +73,7 @@ # error Interrupt stack must be used with high priority interrupts in kernel mode # endif - /* Use the the BASEPRI to control interrupts is required if nested, high + /* Use the BASEPRI to control interrupts is required if nested, high * priority interrupts are supported. */ diff --git a/arch/arm/src/tiva/tm4c_ethernet.c b/arch/arm/src/tiva/tm4c_ethernet.c index 63cf22689c..b41461eb84 100644 --- a/arch/arm/src/tiva/tm4c_ethernet.c +++ b/arch/arm/src/tiva/tm4c_ethernet.c @@ -1591,7 +1591,7 @@ static int tiva_recvframe(FAR struct tiva_ethmac_s *priv) { priv->segments++; - /* Check if the there is only one segment in the frame */ + /* Check if there is only one segment in the frame */ if (priv->segments == 1) { @@ -4197,7 +4197,7 @@ void up_netinitialize(void) * and SIOCSMIIREG ioctl calls** to communicate with the PHY, * determine what network event took place (Link Up/Down?), and * take the appropriate actions. - * d. It should then interact the the PHY to clear any pending + * d. It should then interact the PHY to clear any pending * interrupts, then re-enable the PHY interrupt. * * * This is an OS internal interface and should not be used from diff --git a/arch/misoc/src/common/misoc.h b/arch/misoc/src/common/misoc.h index ab99f6aca2..564ff123fa 100644 --- a/arch/misoc/src/common/misoc.h +++ b/arch/misoc/src/common/misoc.h @@ -118,7 +118,7 @@ void misoc_puts(const char *str); * Name: misoc_lowputc * * Description: - * Low-level, blocking character output the the serial console. + * Low-level, blocking character output the serial console. * ****************************************************************************/ diff --git a/arch/sim/src/up_simsmp.c b/arch/sim/src/up_simsmp.c index 8a1469976d..fb7ce5cea9 100644 --- a/arch/sim/src/up_simsmp.c +++ b/arch/sim/src/up_simsmp.c @@ -248,7 +248,7 @@ static void sim_handle_signal(int signo, siginfo_t *info, void *context) * * Description: * Create the pthread-specific data key and set the indication of CPU0 - * the the main thread. + * the main thread. * * Input Parameters: * None diff --git a/arch/sim/src/up_tickless.c b/arch/sim/src/up_tickless.c index 9097f751f7..0a4bb64aca 100644 --- a/arch/sim/src/up_tickless.c +++ b/arch/sim/src/up_tickless.c @@ -150,7 +150,7 @@ void sim_timer_initialize(void) * any failure. * * Assumptions: - * Called from the the normal tasking context. The implementation must + * Called from the normal tasking context. The implementation must * provide whatever mutual exclusion is necessary for correct operation. * This can include disabling interrupts in order to assure atomic register * operations. diff --git a/arch/xtensa/src/common/xtensa_testset.c b/arch/xtensa/src/common/xtensa_testset.c index 8dd15fdec9..d8fdec3c00 100644 --- a/arch/xtensa/src/common/xtensa_testset.c +++ b/arch/xtensa/src/common/xtensa_testset.c @@ -133,7 +133,7 @@ spinlock_t up_testset(volatile FAR spinlock_t *lock) * code." * * In any case, the return value of SP_UNLOCKED can be trusted and will - * always mean that the the spinlock was set. + * always mean that the spinlock was set. */ return (prev == SP_UNLOCKED) ? SP_UNLOCKED : SP_LOCKED; diff --git a/arch/xtensa/src/esp32/chip/esp32_uart.h b/arch/xtensa/src/esp32/chip/esp32_uart.h index 0e248a4ea9..710ef41beb 100644 --- a/arch/xtensa/src/esp32/chip/esp32_uart.h +++ b/arch/xtensa/src/esp32/chip/esp32_uart.h @@ -1464,7 +1464,7 @@ /* UART_PRE_IDLE_NUM : R/W ;bitpos:[23:0] ;default: 24'h186a00 ; */ /* Description: This register is used to configure the idle duration time - * before the first at_cmd is received by receiver. when the the duration + * before the first at_cmd is received by receiver. when the duration * is less than this register value it will not take the next data received * as at_cmd char. */ diff --git a/arch/xtensa/src/esp32/esp32_gpio.h b/arch/xtensa/src/esp32/esp32_gpio.h index e4b647b976..dda697e18f 100644 --- a/arch/xtensa/src/esp32/esp32_gpio.h +++ b/arch/xtensa/src/esp32/esp32_gpio.h @@ -100,7 +100,7 @@ #ifndef __ASSEMBLY__ -/* Must be big enough to hold the the above encodings */ +/* Must be big enough to hold the above encodings */ typedef uint16_t gpio_pinattr_t; typedef uint8_t gpio_intrtype_t; diff --git a/arch/xtensa/src/esp32/esp32_intercpu_interrupt.c b/arch/xtensa/src/esp32/esp32_intercpu_interrupt.c index 779aa3d746..ce27269f21 100644 --- a/arch/xtensa/src/esp32/esp32_intercpu_interrupt.c +++ b/arch/xtensa/src/esp32/esp32_intercpu_interrupt.c @@ -93,7 +93,7 @@ static int esp32_fromcpu_interrupt(int fromcpu) DPORT_CPU_INTR_FROM_CPU_1_REG; putreg32(0, regaddr); - /* Get the the inter-CPU interrupt code */ + /* Get the inter-CPU interrupt code */ tocpu = up_cpu_index(); intcode = g_intcode[tocpu]; diff --git a/arch/z16/src/z16f/z16f_clkinit.c b/arch/z16/src/z16f/z16f_clkinit.c index 314020257b..41690dd829 100644 --- a/arch/z16/src/z16f/z16f_clkinit.c +++ b/arch/z16/src/z16f/z16f_clkinit.c @@ -221,7 +221,7 @@ static void z16f_sysclkinit(int clockid, uint32_t frequency) int count; /* In this configuration, we support only the external oscillator/clock - * the the source of the system clock (__DEFCLK is ignored). + * the source of the system clock (__DEFCLK is ignored). */ if ((getreg8(Z16F_OSC_CTL) & 0x03) != 1) diff --git a/arch/z16/src/z16f/z16f_espi.c b/arch/z16/src/z16f/z16f_espi.c index 60db49a88b..312b2276e4 100644 --- a/arch/z16/src/z16f/z16f_espi.c +++ b/arch/z16/src/z16f/z16f_espi.c @@ -641,7 +641,7 @@ static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer, spi_flush(priv); - /* Make sure the the TEOF bit is not set (SSV must also be zero) */ + /* Make sure the TEOF bit is not set (SSV must also be zero) */ spi_putreg8(priv, 0, Z16F_ESPI_CTL); diff --git a/arch/z16/src/z16f/z16f_serial.c b/arch/z16/src/z16f/z16f_serial.c index 1e24c165d1..57d9bf921f 100644 --- a/arch/z16/src/z16f/z16f_serial.c +++ b/arch/z16/src/z16f/z16f_serial.c @@ -789,7 +789,7 @@ int up_putc(int ch) * driver operation. * * REVISIT: I can imagine scenarios where the follow logic gets pre-empted - * and the the UART interrupts get left in a bad state. + * and the UART interrupts get left in a bad state. */ state = z16f_disableuartirq(&CONSOLE_DEV); diff --git a/audio/README.txt b/audio/README.txt index 85ab2e1a36..49dc1de49d 100644 --- a/audio/README.txt +++ b/audio/README.txt @@ -24,7 +24,7 @@ layer for specific lower-half audio device drivers. pcm_decode.c - Routines to decode PCM / WAV type data. README - This file! -Portions of the the audio system interface have application interfaces. Those +Portions of the audio system interface have application interfaces. Those portions reside in the nuttx/libc/audio directory where the will be built for access by both OS driver logic and user application logic. Those relevant files in nuttx/libc/audio include: diff --git a/audio/pcm_decode.c b/audio/pcm_decode.c index 383d8ef261..20b0b2943f 100644 --- a/audio/pcm_decode.c +++ b/audio/pcm_decode.c @@ -93,7 +93,7 @@ struct pcm_decode_s /* These are our operations that intervene between the player application * and the lower level driver. Unlike the ops in the struct * audio_lowerhalf_s, these are writeable because we need to customize a - * few of the methods based upon what is supported by the the lower level + * few of the methods based upon what is supported by the lower level * driver. */ @@ -414,7 +414,7 @@ static bool pcm_parsewav(FAR struct pcm_decode_s *priv, uint8_t *data) #endif } - /* And return true if the the file is a valid WAV header file */ + /* And return true if the file is a valid WAV header file */ return ret; } diff --git a/binfmt/binfmt_exepath.c b/binfmt/binfmt_exepath.c index c99ae8706a..7e286c1336 100644 --- a/binfmt/binfmt_exepath.c +++ b/binfmt/binfmt_exepath.c @@ -100,8 +100,8 @@ struct exepath_s * On success, exepath_init() return a non-NULL, opaque handle that may * subsequently be used in calls to exepath_next() and exepath_release(). * On error, a NULL handle value will be returned. The most likely cause - * of an error would be that the there is no value associated with the - * PATH variable. + * of an error would be that there is no value associated with the PATH + * variable. * ****************************************************************************/ diff --git a/binfmt/libpcode/README.txt b/binfmt/libpcode/README.txt index 4e0724ee07..2a2a15cc64 100644 --- a/binfmt/libpcode/README.txt +++ b/binfmt/libpcode/README.txt @@ -150,7 +150,7 @@ The general idea to fix both of these problems is as follows: program is stored in the filesystem. 3. Modify the logic so that the P-Code execution program runs (instead of - the requested program) an it received the full path the the P-Code file + the requested program) an it received the full path the P-Code file on the command line. This might be accomplished by simply modifying the argv[] structure in the struct binary_s instance. diff --git a/configs/Kconfig b/configs/Kconfig index a2763f7c00..fd5fb80c5e 100644 --- a/configs/Kconfig +++ b/configs/Kconfig @@ -507,7 +507,7 @@ config ARCH_BOARD_OLIMEX_LPC_H3131 depends on ARCH_CHIP_LPC3131 select ARCH_HAVE_LEDS ---help--- - Olimex LPC-H3131 development board. This board is based on the the + Olimex LPC-H3131 development board. This board is based on the NXP LPC3131 MCU. config ARCH_BOARD_OLIMEX_STRP711 @@ -1461,7 +1461,7 @@ config ARCH_BOARD_CUSTOM_DIR to also tell the build system where it can find the board directory for the custom board. - In this case, the board directory is assume to lie outside the the + In this case, the board directory is assume to lie outside the NuttX directory. The provided path must then be a full, absolute path to some location outside of the NuttX source tree (like "~/projects/myboard"). diff --git a/configs/README.txt b/configs/README.txt index cfc90fa0f7..c17dfb6356 100644 --- a/configs/README.txt +++ b/configs/README.txt @@ -227,10 +227,10 @@ configs/eagle100 arm-nuttx-elf toolchain*. STATUS: This port is complete and mature. configs/efm32-g8xx-stk - The port of NuttX to the the EFM32 Gecko Starter Kit (EFM32-G8XX-STK). + The port of NuttX to the EFM32 Gecko Starter Kit (EFM32-G8XX-STK). configs/efm32gg-stk3700 - The port of NuttX to the the EFM32 Giant Gecko Starter Kit + The port of NuttX to the EFM32 Giant Gecko Starter Kit (EFM32GG-STK3700). configs/ekk-lm3s9b96 diff --git a/configs/arduino-due/src/sam_appinit.c b/configs/arduino-due/src/sam_appinit.c index 32132ee330..78587bcce7 100644 --- a/configs/arduino-due/src/sam_appinit.c +++ b/configs/arduino-due/src/sam_appinit.c @@ -84,7 +84,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/bambino-200e/src/lpc43_appinit.c b/configs/bambino-200e/src/lpc43_appinit.c index 785c28758b..c00e497932 100644 --- a/configs/bambino-200e/src/lpc43_appinit.c +++ b/configs/bambino-200e/src/lpc43_appinit.c @@ -147,7 +147,7 @@ static int nsh_spifi_initialize(void) * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/boardctl.c b/configs/boardctl.c index f0d0da114e..6c5185c572 100644 --- a/configs/boardctl.c +++ b/configs/boardctl.c @@ -255,7 +255,7 @@ int boardctl(unsigned int cmd, uintptr_t arg) * board_app_initialize() implementation without modification. * The argument has no meaning to NuttX; the meaning of the * argument is a contract between the board-specific - * initalization logic and the the matching application logic. + * initalization logic and the matching application logic. * The value cold be such things as a mode enumeration value, * a set of DIP switch switch settings, a pointer to * configuration data read from a file or serial FLASH, or diff --git a/configs/cc3200-launchpad/src/cc3200_boot.c b/configs/cc3200-launchpad/src/cc3200_boot.c index 841f40eca7..a63fbeb44f 100644 --- a/configs/cc3200-launchpad/src/cc3200_boot.c +++ b/configs/cc3200-launchpad/src/cc3200_boot.c @@ -81,7 +81,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/clicker2-stm32/src/stm32_appinit.c b/configs/clicker2-stm32/src/stm32_appinit.c index 74c8a2142b..cd19729503 100644 --- a/configs/clicker2-stm32/src/stm32_appinit.c +++ b/configs/clicker2-stm32/src/stm32_appinit.c @@ -71,7 +71,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/cloudctrl/README.txt b/configs/cloudctrl/README.txt index ba2d8972ee..4ef93e2fc8 100644 --- a/configs/cloudctrl/README.txt +++ b/configs/cloudctrl/README.txt @@ -340,7 +340,7 @@ NuttX EABI buildroot Toolchain -CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYW=y +CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y - 9. Set the the PATH variable so tht it includes the path to the newly built + 9. Set the PATH variable so tht it includes the path to the newly built binaries. See the file configs/README.txt in the buildroot source tree. That has more diff --git a/configs/cloudctrl/src/stm32_appinit.c b/configs/cloudctrl/src/stm32_appinit.c index c628bd142a..211029d957 100644 --- a/configs/cloudctrl/src/stm32_appinit.c +++ b/configs/cloudctrl/src/stm32_appinit.c @@ -112,7 +112,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/demo9s12ne64/src/m9s12_appinit.c b/configs/demo9s12ne64/src/m9s12_appinit.c index 0010a71e68..790f7a34bc 100644 --- a/configs/demo9s12ne64/src/m9s12_appinit.c +++ b/configs/demo9s12ne64/src/m9s12_appinit.c @@ -65,7 +65,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/dk-tm4c129x/src/tm4c_appinit.c b/configs/dk-tm4c129x/src/tm4c_appinit.c index 20d889d47e..89b15be570 100644 --- a/configs/dk-tm4c129x/src/tm4c_appinit.c +++ b/configs/dk-tm4c129x/src/tm4c_appinit.c @@ -57,7 +57,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/ea3131/src/lpc31_appinit.c b/configs/ea3131/src/lpc31_appinit.c index 43ef50be72..ef581641d2 100644 --- a/configs/ea3131/src/lpc31_appinit.c +++ b/configs/ea3131/src/lpc31_appinit.c @@ -111,7 +111,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/ea3152/src/lpc31_appinit.c b/configs/ea3152/src/lpc31_appinit.c index e05327622c..ea30724a84 100644 --- a/configs/ea3152/src/lpc31_appinit.c +++ b/configs/ea3152/src/lpc31_appinit.c @@ -111,7 +111,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/eagle100/src/lm_appinit.c b/configs/eagle100/src/lm_appinit.c index 72b7206fad..2690bbdba3 100644 --- a/configs/eagle100/src/lm_appinit.c +++ b/configs/eagle100/src/lm_appinit.c @@ -107,7 +107,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/ekk-lm3s9b96/src/lm_appinit.c b/configs/ekk-lm3s9b96/src/lm_appinit.c index 21be2c1952..f7136cdd8a 100644 --- a/configs/ekk-lm3s9b96/src/lm_appinit.c +++ b/configs/ekk-lm3s9b96/src/lm_appinit.c @@ -64,7 +64,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/esp32-core/README.txt b/configs/esp32-core/README.txt index cde3295ff0..6d7d69c667 100644 --- a/configs/esp32-core/README.txt +++ b/configs/esp32-core/README.txt @@ -731,7 +731,7 @@ Things to Do 4. Currently the Xtensa port copies register state save information from the stack into the TCB. A more efficient alternative would be to just save a pointer to a register state save area in the TCB. This would - add some complexity to signal handling and also also the the + add some complexity to signal handling and also also the up_initialstate(). But the performance improvement might be worth the effort. diff --git a/configs/esp32-core/src/esp32_appinit.c b/configs/esp32-core/src/esp32_appinit.c index ff8d1eb957..dcf65d5e71 100644 --- a/configs/esp32-core/src/esp32_appinit.c +++ b/configs/esp32-core/src/esp32_appinit.c @@ -66,7 +66,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/ez80f910200zco/README.txt b/configs/ez80f910200zco/README.txt index d88114e851..a1c6ce5777 100644 --- a/configs/ez80f910200zco/README.txt +++ b/configs/ez80f910200zco/README.txt @@ -50,7 +50,7 @@ Version 5.1.1 Paths were also updated that are specific to a 32-bit toolchain running on a 64 bit windows platform. Change to a different toolchain, you will need to modify the versioning in Make.defs; if you want to build on a different - platform, you will need to change the path the the ZDS binaries in that + platform, you will need to change the path the ZDS binaries in that files as well as in your PATH environment variable. Version 5.2.1 diff --git a/configs/fire-stm32v2/src/stm32_appinit.c b/configs/fire-stm32v2/src/stm32_appinit.c index aa962b5b77..c82d5f4366 100644 --- a/configs/fire-stm32v2/src/stm32_appinit.c +++ b/configs/fire-stm32v2/src/stm32_appinit.c @@ -200,7 +200,7 @@ static void stm32_i2ctool(void) * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/freedom-k64f/include/board.h b/configs/freedom-k64f/include/board.h index 62eb2fe5e0..b88e37a160 100644 --- a/configs/freedom-k64f/include/board.h +++ b/configs/freedom-k64f/include/board.h @@ -102,7 +102,7 @@ /* * Kinetis does not have pullups on their Freedom-K64F board - * So allow the the board config to enable them. + * So allow the board config to enable them. */ #define BOARD_SDHC_ENABLE_PULLUPS 1 diff --git a/configs/freedom-k64f/src/k64_appinit.c b/configs/freedom-k64f/src/k64_appinit.c index ba19f5b851..f9851a74a1 100644 --- a/configs/freedom-k64f/src/k64_appinit.c +++ b/configs/freedom-k64f/src/k64_appinit.c @@ -63,7 +63,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/freedom-k64f/src/k64_automount.c b/configs/freedom-k64f/src/k64_automount.c index 8ec1be29ff..4a325f1ca2 100644 --- a/configs/freedom-k64f/src/k64_automount.c +++ b/configs/freedom-k64f/src/k64_automount.c @@ -304,7 +304,7 @@ void k64_automount_event(bool inserted) if (!state->enable) { - /* Yes.. just remember the there is a pending interrupt. We will + /* Yes.. just remember that there is a pending interrupt. We will * deliver the interrupt when interrupts are "re-enabled." */ diff --git a/configs/freedom-k66f/include/board.h b/configs/freedom-k66f/include/board.h index b59515e6d8..4a5673e936 100644 --- a/configs/freedom-k66f/include/board.h +++ b/configs/freedom-k66f/include/board.h @@ -147,7 +147,7 @@ /* * Kinetis does not have pullups on their Freedom-K66F board - * So allow the the board config to enable them. + * So allow the board config to enable them. */ #define BOARD_SDHC_ENABLE_PULLUPS 1 diff --git a/configs/freedom-k66f/src/k66_appinit.c b/configs/freedom-k66f/src/k66_appinit.c index 1a31c33134..c52a52e6da 100644 --- a/configs/freedom-k66f/src/k66_appinit.c +++ b/configs/freedom-k66f/src/k66_appinit.c @@ -64,7 +64,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/freedom-k66f/src/k66_automount.c b/configs/freedom-k66f/src/k66_automount.c index fbbe80b72e..2b9c7a3210 100644 --- a/configs/freedom-k66f/src/k66_automount.c +++ b/configs/freedom-k66f/src/k66_automount.c @@ -305,7 +305,7 @@ void k66_automount_event(bool inserted) if (!state->enable) { - /* Yes.. just remember the there is a pending interrupt. We will + /* Yes.. just remember that there is a pending interrupt. We will * deliver the interrupt when interrupts are "re-enabled." */ diff --git a/configs/freedom-kl25z/src/kl_appinit.c b/configs/freedom-kl25z/src/kl_appinit.c index ef425471dd..5686f6e014 100644 --- a/configs/freedom-kl25z/src/kl_appinit.c +++ b/configs/freedom-kl25z/src/kl_appinit.c @@ -63,7 +63,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/freedom-kl26z/src/kl_appinit.c b/configs/freedom-kl26z/src/kl_appinit.c index 6b6550c915..d4b1824b3a 100644 --- a/configs/freedom-kl26z/src/kl_appinit.c +++ b/configs/freedom-kl26z/src/kl_appinit.c @@ -62,7 +62,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/hymini-stm32v/src/stm32_appinit.c b/configs/hymini-stm32v/src/stm32_appinit.c index 2e1d99f742..5b99c4445b 100644 --- a/configs/hymini-stm32v/src/stm32_appinit.c +++ b/configs/hymini-stm32v/src/stm32_appinit.c @@ -155,7 +155,7 @@ static int nsh_cdinterrupt(int irq, FAR void *context, FAR void *arg) * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/kwikstik-k40/src/k40_appinit.c b/configs/kwikstik-k40/src/k40_appinit.c index 790a094551..104b6a339d 100644 --- a/configs/kwikstik-k40/src/k40_appinit.c +++ b/configs/kwikstik-k40/src/k40_appinit.c @@ -189,7 +189,7 @@ static int kinetis_cdinterrupt(int irq, FAR void *context) * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/launchxl-tms57004/README.txt b/configs/launchxl-tms57004/README.txt index 6c9568f913..42d199cc85 100644 --- a/configs/launchxl-tms57004/README.txt +++ b/configs/launchxl-tms57004/README.txt @@ -46,7 +46,7 @@ Toolchain Endian-ness Issues ------------------ - I started using the the "GNU Tools for ARM Embedded Processors" that is + I started using the "GNU Tools for ARM Embedded Processors" that is maintained by ARM. https://launchpad.net/gcc-arm-embedded diff --git a/configs/launchxl-tms57004/src/tms570_appinit.c b/configs/launchxl-tms57004/src/tms570_appinit.c index 6a187b033f..90360ee7ed 100644 --- a/configs/launchxl-tms57004/src/tms570_appinit.c +++ b/configs/launchxl-tms57004/src/tms570_appinit.c @@ -56,7 +56,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/lincoln60/src/lpc17_appinit.c b/configs/lincoln60/src/lpc17_appinit.c index 2e1426635c..7642c91395 100644 --- a/configs/lincoln60/src/lpc17_appinit.c +++ b/configs/lincoln60/src/lpc17_appinit.c @@ -61,7 +61,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/lm3s6432-s2e/src/lm_appinit.c b/configs/lm3s6432-s2e/src/lm_appinit.c index d787ea3258..c7fffb64d9 100644 --- a/configs/lm3s6432-s2e/src/lm_appinit.c +++ b/configs/lm3s6432-s2e/src/lm_appinit.c @@ -61,7 +61,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/lm3s6965-ek/src/lm_appinit.c b/configs/lm3s6965-ek/src/lm_appinit.c index c9eaf61d81..07153314ea 100644 --- a/configs/lm3s6965-ek/src/lm_appinit.c +++ b/configs/lm3s6965-ek/src/lm_appinit.c @@ -111,7 +111,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/lm3s8962-ek/src/lm_appinit.c b/configs/lm3s8962-ek/src/lm_appinit.c index ba601eacb6..2a9e3b4bdb 100644 --- a/configs/lm3s8962-ek/src/lm_appinit.c +++ b/configs/lm3s8962-ek/src/lm_appinit.c @@ -113,7 +113,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/lm4f120-launchpad/src/lm4f_appinit.c b/configs/lm4f120-launchpad/src/lm4f_appinit.c index f667597398..6b19ebdad3 100644 --- a/configs/lm4f120-launchpad/src/lm4f_appinit.c +++ b/configs/lm4f120-launchpad/src/lm4f_appinit.c @@ -83,7 +83,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/lpc4330-xplorer/README.txt b/configs/lpc4330-xplorer/README.txt index c0be108439..83b318ddfd 100644 --- a/configs/lpc4330-xplorer/README.txt +++ b/configs/lpc4330-xplorer/README.txt @@ -85,7 +85,7 @@ Status - lpc43_ssp.c These LPC17xx drivers were not brought into the LPC43xx port because - it appears the these peripherals have been completely redesigned: + it appears that these peripherals have been completely redesigned: - CAN, - Ethernet, diff --git a/configs/lpc4330-xplorer/src/lpc43_appinit.c b/configs/lpc4330-xplorer/src/lpc43_appinit.c index 751daad901..5288a7eb88 100644 --- a/configs/lpc4330-xplorer/src/lpc43_appinit.c +++ b/configs/lpc4330-xplorer/src/lpc43_appinit.c @@ -143,7 +143,7 @@ static int nsh_spifi_initialize(void) * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/lpc4337-ws/README.txt b/configs/lpc4337-ws/README.txt index d8ca540a69..6f40824981 100644 --- a/configs/lpc4337-ws/README.txt +++ b/configs/lpc4337-ws/README.txt @@ -81,7 +81,7 @@ Status - lpc43_ssp.c These LPC17xx drivers were not brought into the LPC43xx port because - it appears the these peripherals have been completely redesigned: + it appears that these peripherals have been completely redesigned: - CAN, - Ethernet, diff --git a/configs/lpc4337-ws/src/lpc43_appinit.c b/configs/lpc4337-ws/src/lpc43_appinit.c index 8f9a074992..31e4c692e7 100644 --- a/configs/lpc4337-ws/src/lpc43_appinit.c +++ b/configs/lpc4337-ws/src/lpc43_appinit.c @@ -121,7 +121,7 @@ static void lpc43_i2ctool(void) * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/lpc4357-evb/README.txt b/configs/lpc4357-evb/README.txt index 95955308cc..d08fe5f105 100644 --- a/configs/lpc4357-evb/README.txt +++ b/configs/lpc4357-evb/README.txt @@ -78,7 +78,7 @@ Status - lpc43_ssp.c These LPC17xx drivers were not brought into the LPC43xx port because - it appears the these peripherals have been completely redesigned: + it appears that these peripherals have been completely redesigned: - CAN, - Ethernet, diff --git a/configs/lpc4357-evb/src/lpc43_appinit.c b/configs/lpc4357-evb/src/lpc43_appinit.c index aea4aaaa19..96e66b1181 100644 --- a/configs/lpc4357-evb/src/lpc43_appinit.c +++ b/configs/lpc4357-evb/src/lpc43_appinit.c @@ -143,7 +143,7 @@ static int nsh_spifi_initialize(void) * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/lpc4370-link2/README.txt b/configs/lpc4370-link2/README.txt index d39515d7f0..1f0c4092c1 100644 --- a/configs/lpc4370-link2/README.txt +++ b/configs/lpc4370-link2/README.txt @@ -81,7 +81,7 @@ Status - lpc43_ssp.c These LPC17xx drivers were not brought into the LPC43xx port because - it appears the these peripherals have been completely redesigned: + it appears that these peripherals have been completely redesigned: - CAN, - Ethernet, diff --git a/configs/lpc4370-link2/src/lpc43_appinit.c b/configs/lpc4370-link2/src/lpc43_appinit.c index ceda373a43..0d8f5817c0 100644 --- a/configs/lpc4370-link2/src/lpc43_appinit.c +++ b/configs/lpc4370-link2/src/lpc43_appinit.c @@ -120,7 +120,7 @@ static void lpc43_i2ctool(void) * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/lpcxpresso-lpc1115/README.txt b/configs/lpcxpresso-lpc1115/README.txt index 5b91b43a1f..41fae32e0e 100644 --- a/configs/lpcxpresso-lpc1115/README.txt +++ b/configs/lpcxpresso-lpc1115/README.txt @@ -159,7 +159,7 @@ Code Red IDE ------------------------------------ Under Cygwin, the Code Red command line tools (e.g., arm-non-eabi-gcc) cannot - be executed because the they only have execut privileges for Administrators. I + be executed because they only have execute privileges for Administrators. I worked around this by: Opening a native Cygwin RXVT as Administrator (Right click, "Run as administrator"), diff --git a/configs/lpcxpresso-lpc1115/src/lpc11_appinit.c b/configs/lpcxpresso-lpc1115/src/lpc11_appinit.c index 3ca2de5969..b4e7be5c1d 100644 --- a/configs/lpcxpresso-lpc1115/src/lpc11_appinit.c +++ b/configs/lpcxpresso-lpc1115/src/lpc11_appinit.c @@ -113,7 +113,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/lpcxpresso-lpc1768/README.txt b/configs/lpcxpresso-lpc1768/README.txt index 534108b309..05e8a7504e 100644 --- a/configs/lpcxpresso-lpc1768/README.txt +++ b/configs/lpcxpresso-lpc1768/README.txt @@ -326,7 +326,7 @@ Code Red IDE ------------------------------------ Under Cygwin, the Code Red command line tools (e.g., arm-non-eabi-gcc) cannot - be executed because the they only have execut privileges for Administrators. I + be executed because they only have execute privileges for Administrators. I worked around this by: Opening a native Cygwin RXVT as Administrator (Right click, "Run as administrator"), diff --git a/configs/lpcxpresso-lpc1768/src/lpc17_appinit.c b/configs/lpcxpresso-lpc1768/src/lpc17_appinit.c index d922e61963..dfcb5fcce1 100644 --- a/configs/lpcxpresso-lpc1768/src/lpc17_appinit.c +++ b/configs/lpcxpresso-lpc1768/src/lpc17_appinit.c @@ -124,7 +124,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/maple/src/stm32_appinit.c b/configs/maple/src/stm32_appinit.c index d1a7c50d22..1453149a00 100644 --- a/configs/maple/src/stm32_appinit.c +++ b/configs/maple/src/stm32_appinit.c @@ -59,7 +59,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/mbed/src/lpc17_appinit.c b/configs/mbed/src/lpc17_appinit.c index f371ab764b..e99d177894 100644 --- a/configs/mbed/src/lpc17_appinit.c +++ b/configs/mbed/src/lpc17_appinit.c @@ -84,7 +84,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/mcu123-lpc214x/src/lpc2148_appinit.c b/configs/mcu123-lpc214x/src/lpc2148_appinit.c index 1e840af361..cec38015c7 100644 --- a/configs/mcu123-lpc214x/src/lpc2148_appinit.c +++ b/configs/mcu123-lpc214x/src/lpc2148_appinit.c @@ -112,7 +112,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/mikroe-stm32f4/src/stm32_appinit.c b/configs/mikroe-stm32f4/src/stm32_appinit.c index f42b6bc917..b0fee207c2 100644 --- a/configs/mikroe-stm32f4/src/stm32_appinit.c +++ b/configs/mikroe-stm32f4/src/stm32_appinit.c @@ -161,7 +161,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/mirtoo/src/pic32_appinit.c b/configs/mirtoo/src/pic32_appinit.c index 2cf57476dd..8491f57860 100644 --- a/configs/mirtoo/src/pic32_appinit.c +++ b/configs/mirtoo/src/pic32_appinit.c @@ -100,7 +100,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/moxa/src/moxart_appinit.c b/configs/moxa/src/moxart_appinit.c index 1b7c8114d6..a550e1f777 100644 --- a/configs/moxa/src/moxart_appinit.c +++ b/configs/moxa/src/moxart_appinit.c @@ -74,7 +74,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/ne64badge/src/m9s12_appinit.c b/configs/ne64badge/src/m9s12_appinit.c index 1550f5d519..113525cb78 100644 --- a/configs/ne64badge/src/m9s12_appinit.c +++ b/configs/ne64badge/src/m9s12_appinit.c @@ -65,7 +65,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/nr5m100-nexys4/src/nr5_appinit.c b/configs/nr5m100-nexys4/src/nr5_appinit.c index 861f1d44a8..3e0f74edd7 100644 --- a/configs/nr5m100-nexys4/src/nr5_appinit.c +++ b/configs/nr5m100-nexys4/src/nr5_appinit.c @@ -66,7 +66,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/nucleo-144/src/stm32_appinitialize.c b/configs/nucleo-144/src/stm32_appinitialize.c index a4ad8423bd..1b3c3150ac 100644 --- a/configs/nucleo-144/src/stm32_appinitialize.c +++ b/configs/nucleo-144/src/stm32_appinitialize.c @@ -65,7 +65,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/nucleo-f072rb/src/stm32_appinit.c b/configs/nucleo-f072rb/src/stm32_appinit.c index 0ce7ce4d66..b82a3d5457 100644 --- a/configs/nucleo-f072rb/src/stm32_appinit.c +++ b/configs/nucleo-f072rb/src/stm32_appinit.c @@ -62,7 +62,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/nucleo-f091rc/src/stm32_appinit.c b/configs/nucleo-f091rc/src/stm32_appinit.c index 784c155b6b..2eb92bcb77 100644 --- a/configs/nucleo-f091rc/src/stm32_appinit.c +++ b/configs/nucleo-f091rc/src/stm32_appinit.c @@ -62,7 +62,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/nucleo-f303re/src/stm32_appinitialize.c b/configs/nucleo-f303re/src/stm32_appinitialize.c index 621488c57f..a72dfcd7bf 100644 --- a/configs/nucleo-f303re/src/stm32_appinitialize.c +++ b/configs/nucleo-f303re/src/stm32_appinitialize.c @@ -80,7 +80,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/nucleo-f334r8/src/stm32_appinit.c b/configs/nucleo-f334r8/src/stm32_appinit.c index 3d1d841092..7f84f6deb2 100644 --- a/configs/nucleo-f334r8/src/stm32_appinit.c +++ b/configs/nucleo-f334r8/src/stm32_appinit.c @@ -79,7 +79,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/nucleo-f4x1re/src/stm32_appinit.c b/configs/nucleo-f4x1re/src/stm32_appinit.c index a76eba4b59..e82a0ef32b 100644 --- a/configs/nucleo-f4x1re/src/stm32_appinit.c +++ b/configs/nucleo-f4x1re/src/stm32_appinit.c @@ -85,7 +85,7 @@ void up_netinitialize(void) * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/nucleo-l432kc/src/stm32_appinit.c b/configs/nucleo-l432kc/src/stm32_appinit.c index 649147101d..34d703372e 100644 --- a/configs/nucleo-l432kc/src/stm32_appinit.c +++ b/configs/nucleo-l432kc/src/stm32_appinit.c @@ -94,7 +94,7 @@ void up_netinitialize(void) * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/nucleo-l452re/src/stm32_appinit.c b/configs/nucleo-l452re/src/stm32_appinit.c index 26b1b4f4c5..2a3ba3c518 100644 --- a/configs/nucleo-l452re/src/stm32_appinit.c +++ b/configs/nucleo-l452re/src/stm32_appinit.c @@ -62,7 +62,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/nucleo-l476rg/src/stm32_appinit.c b/configs/nucleo-l476rg/src/stm32_appinit.c index f66fcdb1ec..479481417e 100644 --- a/configs/nucleo-l476rg/src/stm32_appinit.c +++ b/configs/nucleo-l476rg/src/stm32_appinit.c @@ -94,7 +94,7 @@ void up_netinitialize(void) * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/nucleo-l496zg/src/stm32_appinitialize.c b/configs/nucleo-l496zg/src/stm32_appinitialize.c index 677f184b61..a37ba99f12 100644 --- a/configs/nucleo-l496zg/src/stm32_appinitialize.c +++ b/configs/nucleo-l496zg/src/stm32_appinitialize.c @@ -84,7 +84,7 @@ struct i2c_master_s* i2c4; * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/olimex-lpc-h3131/src/lpc31_appinit.c b/configs/olimex-lpc-h3131/src/lpc31_appinit.c index 0a40bb902c..17916f8b2e 100644 --- a/configs/olimex-lpc-h3131/src/lpc31_appinit.c +++ b/configs/olimex-lpc-h3131/src/lpc31_appinit.c @@ -87,7 +87,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/olimex-lpc1766stk/src/lpc17_appinit.c b/configs/olimex-lpc1766stk/src/lpc17_appinit.c index e3aa02bd45..22e4858fc3 100644 --- a/configs/olimex-lpc1766stk/src/lpc17_appinit.c +++ b/configs/olimex-lpc1766stk/src/lpc17_appinit.c @@ -329,7 +329,7 @@ static int nsh_usbhostinitialize(void) * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/olimex-lpc2378/src/lpc2378_appinit.c b/configs/olimex-lpc2378/src/lpc2378_appinit.c index ed9ee4910a..766295c27a 100644 --- a/configs/olimex-lpc2378/src/lpc2378_appinit.c +++ b/configs/olimex-lpc2378/src/lpc2378_appinit.c @@ -96,7 +96,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/olimex-stm32-h405/src/stm32_appinit.c b/configs/olimex-stm32-h405/src/stm32_appinit.c index d94f29d31b..43fb94d1fd 100644 --- a/configs/olimex-stm32-h405/src/stm32_appinit.c +++ b/configs/olimex-stm32-h405/src/stm32_appinit.c @@ -88,7 +88,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/olimex-stm32-h407/src/stm32_appinit.c b/configs/olimex-stm32-h407/src/stm32_appinit.c index f461c2f193..8d8b56a61f 100644 --- a/configs/olimex-stm32-h407/src/stm32_appinit.c +++ b/configs/olimex-stm32-h407/src/stm32_appinit.c @@ -80,7 +80,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/olimex-stm32-p107/src/stm32_appinit.c b/configs/olimex-stm32-p107/src/stm32_appinit.c index af7736d2ca..997d92fe05 100644 --- a/configs/olimex-stm32-p107/src/stm32_appinit.c +++ b/configs/olimex-stm32-p107/src/stm32_appinit.c @@ -71,7 +71,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/olimex-stm32-p207/src/stm32_appinit.c b/configs/olimex-stm32-p207/src/stm32_appinit.c index fc22cc5aff..1818c08ab3 100644 --- a/configs/olimex-stm32-p207/src/stm32_appinit.c +++ b/configs/olimex-stm32-p207/src/stm32_appinit.c @@ -117,7 +117,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/olimex-stm32-p407/README.txt b/configs/olimex-stm32-p407/README.txt index 0692ffc502..f77162379f 100644 --- a/configs/olimex-stm32-p407/README.txt +++ b/configs/olimex-stm32-p407/README.txt @@ -429,5 +429,5 @@ STATUS CCM memory is not included in the heap (CONFIG_STM32_CCMEXCLUDE=y) because it does not suport DMA, leaving only 128KiB for program usage. -2107-01-23: Added the the knsh configuration and support for the PROTECTED +2107-01-23: Added the knsh configuration and support for the PROTECTED build mode. diff --git a/configs/olimex-stm32-p407/src/stm32_appinit.c b/configs/olimex-stm32-p407/src/stm32_appinit.c index a0a6d02d0f..5880ed2120 100644 --- a/configs/olimex-stm32-p407/src/stm32_appinit.c +++ b/configs/olimex-stm32-p407/src/stm32_appinit.c @@ -71,7 +71,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/olimex-strp711/src/str71_appinit.c b/configs/olimex-strp711/src/str71_appinit.c index e064cd5988..8059d95c81 100644 --- a/configs/olimex-strp711/src/str71_appinit.c +++ b/configs/olimex-strp711/src/str71_appinit.c @@ -113,7 +113,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/olimexino-stm32/src/stm32_appinit.c b/configs/olimexino-stm32/src/stm32_appinit.c index 4fdc6a1c68..dcd7d24a30 100644 --- a/configs/olimexino-stm32/src/stm32_appinit.c +++ b/configs/olimexino-stm32/src/stm32_appinit.c @@ -76,7 +76,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/open1788/src/lpc17_appinit.c b/configs/open1788/src/lpc17_appinit.c index 7a43837649..bb39422956 100644 --- a/configs/open1788/src/lpc17_appinit.c +++ b/configs/open1788/src/lpc17_appinit.c @@ -376,7 +376,7 @@ static int nsh_usbhostinitialize(void) * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/pcblogic-pic32mx/src/pic32mx_appinit.c b/configs/pcblogic-pic32mx/src/pic32mx_appinit.c index 414d4b395b..528b8d4214 100644 --- a/configs/pcblogic-pic32mx/src/pic32mx_appinit.c +++ b/configs/pcblogic-pic32mx/src/pic32mx_appinit.c @@ -73,7 +73,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/photon/src/stm32_appinit.c b/configs/photon/src/stm32_appinit.c index 946dfbe8e2..31c9f61f09 100644 --- a/configs/photon/src/stm32_appinit.c +++ b/configs/photon/src/stm32_appinit.c @@ -63,7 +63,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/pic32mx-starterkit/src/pic32mx_appinit.c b/configs/pic32mx-starterkit/src/pic32mx_appinit.c index 64bba54fc7..68aadbcce2 100644 --- a/configs/pic32mx-starterkit/src/pic32mx_appinit.c +++ b/configs/pic32mx-starterkit/src/pic32mx_appinit.c @@ -359,7 +359,7 @@ static int nsh_usbdevinitialize(void) * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/pic32mx7mmb/src/pic32_appinit.c b/configs/pic32mx7mmb/src/pic32_appinit.c index 8c62c9a766..06f54e3b13 100644 --- a/configs/pic32mx7mmb/src/pic32_appinit.c +++ b/configs/pic32mx7mmb/src/pic32_appinit.c @@ -369,7 +369,7 @@ static int nsh_usbdevinitialize(void) * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/pic32mz-starterkit/include/board.h b/configs/pic32mz-starterkit/include/board.h index 3259ce2c32..05bfa3d8f6 100644 --- a/configs/pic32mz-starterkit/include/board.h +++ b/configs/pic32mz-starterkit/include/board.h @@ -269,7 +269,7 @@ * --------------- --------- -------------- ------------ * * The following pin assignment is used with the MEB-II board. If you are - * using signals from PIC32MZEC Adaptor Board (as described in the the README + * using signals from PIC32MZEC Adaptor Board (as described in the README * file), then UART1 signals are available at these locations on the adaptor * board: * diff --git a/configs/pic32mz-starterkit/src/pic32mz_appinit.c b/configs/pic32mz-starterkit/src/pic32mz_appinit.c index 0b3a3dc823..ab96a4c20e 100644 --- a/configs/pic32mz-starterkit/src/pic32mz_appinit.c +++ b/configs/pic32mz-starterkit/src/pic32mz_appinit.c @@ -61,7 +61,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/sabre-6quad/README.txt b/configs/sabre-6quad/README.txt index bff618371e..61da0e102f 100644 --- a/configs/sabre-6quad/README.txt +++ b/configs/sabre-6quad/README.txt @@ -370,7 +370,7 @@ some other debuggers that you might want to consider. These instructions all assume that you have built NuttX with debug symbols enabled. When debugging the nuttx.bin file on the SD card, it is also -assumed the the nuttx ELF file with the debug symbol addresses is from the +assumed the nuttx ELF file with the debug symbol addresses is from the same build so that the symbols match up. Debugging the NuttX image on the SD card diff --git a/configs/sabre-6quad/src/imx_appinit.c b/configs/sabre-6quad/src/imx_appinit.c index 2e32a6771f..2484d795a8 100644 --- a/configs/sabre-6quad/src/imx_appinit.c +++ b/configs/sabre-6quad/src/imx_appinit.c @@ -63,7 +63,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/sam3u-ek/README.txt b/configs/sam3u-ek/README.txt index f210f1a7cc..047beaf478 100644 --- a/configs/sam3u-ek/README.txt +++ b/configs/sam3u-ek/README.txt @@ -147,7 +147,7 @@ NuttX EABI "buildroot" Toolchain building a Cortex-M3 toolchain for Cygwin under Windows. NOTE: Unfortunately, the 4.6.3 (and later) GCC toolchain is not compatible - with the the NXFLAT tools. See the top-level TODO file (under "Binary loaders") + with the NXFLAT tools. See the top-level TODO file (under "Binary loaders") for more information about this problem. If you plan to use NXFLAT, please do not use the GCC 4.6.3 toochain; instead use an older toolchain (such as the GCC 4.3.3 OABI toolchain discussed below). diff --git a/configs/sam3u-ek/src/sam_appinit.c b/configs/sam3u-ek/src/sam_appinit.c index 632d630394..00f2cd2e21 100644 --- a/configs/sam3u-ek/src/sam_appinit.c +++ b/configs/sam3u-ek/src/sam_appinit.c @@ -113,7 +113,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/sam4cmp-db/src/sam_appinit.c b/configs/sam4cmp-db/src/sam_appinit.c index 6bab1d5751..774bb033a8 100644 --- a/configs/sam4cmp-db/src/sam_appinit.c +++ b/configs/sam4cmp-db/src/sam_appinit.c @@ -61,7 +61,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/sam4e-ek/src/sam_appinit.c b/configs/sam4e-ek/src/sam_appinit.c index aed2a31361..b9ec0bcf11 100644 --- a/configs/sam4e-ek/src/sam_appinit.c +++ b/configs/sam4e-ek/src/sam_appinit.c @@ -74,7 +74,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/sam4e-ek/src/sam_ethernet.c b/configs/sam4e-ek/src/sam_ethernet.c index 7b41e6b622..4b02473bef 100644 --- a/configs/sam4e-ek/src/sam_ethernet.c +++ b/configs/sam4e-ek/src/sam_ethernet.c @@ -159,7 +159,7 @@ void weak_function sam_netinitialize(void) * and SIOCSMIIREG ioctl calls** to communicate with the PHY, * determine what network event took place (Link Up/Down?), and * take the appropriate actions. - * d. It should then interact the the PHY to clear any pending + * d. It should then interact the PHY to clear any pending * interrupts, then re-enable the PHY interrupt. * * * This is an OS internal interface and should not be used from diff --git a/configs/sam4l-xplained/src/sam_appinit.c b/configs/sam4l-xplained/src/sam_appinit.c index 15330a80a2..141c51091e 100644 --- a/configs/sam4l-xplained/src/sam_appinit.c +++ b/configs/sam4l-xplained/src/sam_appinit.c @@ -87,7 +87,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/sam4s-xplained-pro/src/sam_appinit.c b/configs/sam4s-xplained-pro/src/sam_appinit.c index 6cb0cabe91..4ed689f4e8 100644 --- a/configs/sam4s-xplained-pro/src/sam_appinit.c +++ b/configs/sam4s-xplained-pro/src/sam_appinit.c @@ -81,7 +81,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/sama5d2-xult/README.txt b/configs/sama5d2-xult/README.txt index cb48cc0a29..e173355356 100644 --- a/configs/sama5d2-xult/README.txt +++ b/configs/sama5d2-xult/README.txt @@ -24,7 +24,7 @@ STATUS 1. Most of this document is a partially corrected clone of the SAMA5D4-EK README.txt and still contains errors and inconsistencies. -2. Coding is complete for the the basic SAMA5D2-XULT NSH configuration, but +2. Coding is complete for the basic SAMA5D2-XULT NSH configuration, but is completely untested as of this writing (2015-09-15). The primary issue is that I have not yet determine how to load and test code. @@ -994,7 +994,7 @@ Configurations NOTES: - 1. This configuration uses the the USART3 for the serial console + 1. This configuration uses the USART3 for the serial console which is available at the "DBGU" RS-232 connector (J24). That is easily changed by reconfiguring to (1) enable a different serial peripheral, and (2) selecting that serial peripheral as diff --git a/configs/sama5d2-xult/src/sam_appinit.c b/configs/sama5d2-xult/src/sam_appinit.c index 518dc37696..4159585d22 100644 --- a/configs/sama5d2-xult/src/sam_appinit.c +++ b/configs/sama5d2-xult/src/sam_appinit.c @@ -65,7 +65,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/sama5d3-xplained/src/sam_appinit.c b/configs/sama5d3-xplained/src/sam_appinit.c index ad5d8146f8..c50b057e1c 100644 --- a/configs/sama5d3-xplained/src/sam_appinit.c +++ b/configs/sama5d3-xplained/src/sam_appinit.c @@ -70,7 +70,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/sama5d3-xplained/src/sam_ethernet.c b/configs/sama5d3-xplained/src/sam_ethernet.c index 501acac39f..8aff5d9fa4 100644 --- a/configs/sama5d3-xplained/src/sam_ethernet.c +++ b/configs/sama5d3-xplained/src/sam_ethernet.c @@ -225,7 +225,7 @@ void weak_function sam_netinitialize(void) * and SIOCSMIIREG ioctl calls** to communicate with the PHY, * determine what network event took place (Link Up/Down?), and * take the appropriate actions. - * d. It should then interact the the PHY to clear any pending + * d. It should then interact the PHY to clear any pending * interrupts, then re-enable the PHY interrupt. * * * This is an OS internal interface and should not be used from diff --git a/configs/sama5d3x-ek/src/sam_appinit.c b/configs/sama5d3x-ek/src/sam_appinit.c index f352bcdf97..0d3083ad2b 100644 --- a/configs/sama5d3x-ek/src/sam_appinit.c +++ b/configs/sama5d3x-ek/src/sam_appinit.c @@ -74,7 +74,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/sama5d3x-ek/src/sam_ethernet.c b/configs/sama5d3x-ek/src/sam_ethernet.c index 5121a03ff4..3a32d9f882 100644 --- a/configs/sama5d3x-ek/src/sam_ethernet.c +++ b/configs/sama5d3x-ek/src/sam_ethernet.c @@ -225,7 +225,7 @@ void weak_function sam_netinitialize(void) * and SIOCSMIIREG ioctl calls** to communicate with the PHY, * determine what network event took place (Link Up/Down?), and * take the appropriate actions. - * d. It should then interact the the PHY to clear any pending + * d. It should then interact the PHY to clear any pending * interrupts, then re-enable the PHY interrupt. * * * This is an OS internal interface and should not be used from diff --git a/configs/sama5d3x-ek/src/sam_wm8904.c b/configs/sama5d3x-ek/src/sam_wm8904.c index 2bba0f3f04..5a49122f31 100644 --- a/configs/sama5d3x-ek/src/sam_wm8904.c +++ b/configs/sama5d3x-ek/src/sam_wm8904.c @@ -331,7 +331,7 @@ int sam_wm8904_initialize(int minor) } /* No we can embed the WM8904/I2C/I2S conglomerate into a PCM decoder - * instance so that we will have a PCM front end for the the WM8904 + * instance so that we will have a PCM front end for the WM8904 * driver. */ diff --git a/configs/sama5d4-ek/README.txt b/configs/sama5d4-ek/README.txt index bff91b7a06..839daa66df 100644 --- a/configs/sama5d4-ek/README.txt +++ b/configs/sama5d4-ek/README.txt @@ -1276,7 +1276,7 @@ Networking The ETH1 signals go through line drivers that are enabled via the board LCD_ETH1_CONFIG signal. Jumper JP2 selects either the EMAC1 or the LCD by - controlling the the LCD_ETH1_CONFIG signal on the board. + controlling the LCD_ETH1_CONFIG signal on the board. - JP2 open, LCD_ETH1_CONFIG pulled high: @@ -3243,7 +3243,7 @@ TM7000 LCD/Touchscreen J9 pin 8 LCD_TWD0_PA30 J4 pin 8 SDA_0 ------------------------ ----------------- - The schematic indicates the the MXT468E address is 0x4c/0x4d. + The schematic indicates the MXT468E address is 0x4c/0x4d. Here are the configuration settings the configuration settings that will enable the maXTouch touchscreen controller: @@ -3720,7 +3720,7 @@ Configurations NOTES: - 1. This configuration uses the the USART3 for the serial console + 1. This configuration uses the USART3 for the serial console which is available at the "DBGU" RS-232 connector (J24). That is easily changed by reconfiguring to (1) enable a different serial peripheral, and (2) selecting that serial peripheral as @@ -3747,7 +3747,7 @@ Configurations The ETH1 signals go through line drivers that are enabled via the board LCD_ETH1_CONFIG signal. Jumper JP2 selects either the EMAC1 - or the LCD by controlling the the LCD_ETH1_CONFIG signal on the + or the LCD by controlling the LCD_ETH1_CONFIG signal on the board. - JP2 open, LCD_ETH1_CONFIG pulled high: @@ -3789,7 +3789,7 @@ Configurations NOTES: - 1. This configuration uses the the USART3 for the serial console + 1. This configuration uses the USART3 for the serial console which is available at the "DBGU" RS-232 connector (J24). That is easily changed by reconfiguring to (1) enable a different serial peripheral, and (2) selecting that serial peripheral as @@ -3868,7 +3868,7 @@ Configurations NOTES: - 1. This configuration uses the the USART3 for the serial console + 1. This configuration uses the USART3 for the serial console which is available at the "DBGU" RS-232 connector (J24). That is easily changed by reconfiguring to (1) enable a different serial peripheral, and (2) selecting that serial peripheral as @@ -4021,7 +4021,7 @@ Configurations NOTES: - 1. This configuration uses the the USART3 for the serial console + 1. This configuration uses the USART3 for the serial console which is available at the "DBGU" RS-232 connector (J24). That is easily changed by reconfiguring to (1) enable a different serial peripheral, and (2) selecting that serial peripheral as @@ -4109,7 +4109,7 @@ Configurations Then you will need to follow some special build instructions below in order to build and install the ROMFS file system image. - UPDATE: The ROMFS configuration is pre-configured in the the + UPDATE: The ROMFS configuration is pre-configured in the file nuttx/configs/sama5d4-ek/knsh/defconfig.ROMFS 5. Board initialization is performed performed before the application @@ -4166,7 +4166,7 @@ Configurations $ make import : This will build the file system. You will then need to copy the files from apps/bin to an SD card to - create the the bootable SD card. + create the bootable SD card. 6b. General build directions (boot from ROMFS image): @@ -4225,7 +4225,7 @@ Configurations NOTES: - 1. This configuration uses the the USART3 for the serial console + 1. This configuration uses the USART3 for the serial console which is available at the "DBGU" RS-232 connector (J24). That is easily changed by reconfiguring to (1) enable a different serial peripheral, and (2) selecting that serial peripheral as @@ -4933,7 +4933,7 @@ Configurations NOTES: - 1. This configuration uses the the USART3 for the serial console + 1. This configuration uses the USART3 for the serial console which is available at the "DBGU" RS-232 connector (J24). That is easily changed by reconfiguring to (1) enable a different serial peripheral, and (2) selecting that serial peripheral as diff --git a/configs/sama5d4-ek/src/sam_appinit.c b/configs/sama5d4-ek/src/sam_appinit.c index 066bbf00c3..8cce13cb62 100644 --- a/configs/sama5d4-ek/src/sam_appinit.c +++ b/configs/sama5d4-ek/src/sam_appinit.c @@ -65,7 +65,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/sama5d4-ek/src/sam_automount.c b/configs/sama5d4-ek/src/sam_automount.c index b838e693d9..af8fd79813 100644 --- a/configs/sama5d4-ek/src/sam_automount.c +++ b/configs/sama5d4-ek/src/sam_automount.c @@ -375,7 +375,7 @@ void sam_automount_event(int slotno, bool inserted) if (!state->enable) { - /* Yes.. just remember the there is a pending interrupt. We will + /* Yes.. just remember that there is a pending interrupt. We will * deliver the interrupt when interrupts are "re-enabled." */ diff --git a/configs/sama5d4-ek/src/sam_ethernet.c b/configs/sama5d4-ek/src/sam_ethernet.c index c491ec9dd1..419983f02f 100644 --- a/configs/sama5d4-ek/src/sam_ethernet.c +++ b/configs/sama5d4-ek/src/sam_ethernet.c @@ -195,7 +195,7 @@ void weak_function sam_netinitialize(void) * and SIOCSMIIREG ioctl calls** to communicate with the PHY, * determine what network event took place (Link Up/Down?), and * take the appropriate actions. - * d. It should then interact the the PHY to clear any pending + * d. It should then interact the PHY to clear any pending * interrupts, then re-enable the PHY interrupt. * * * This is an OS internal interface and should not be used from diff --git a/configs/sama5d4-ek/src/sam_wm8904.c b/configs/sama5d4-ek/src/sam_wm8904.c index 34ded3756d..084581106b 100644 --- a/configs/sama5d4-ek/src/sam_wm8904.c +++ b/configs/sama5d4-ek/src/sam_wm8904.c @@ -331,7 +331,7 @@ int sam_wm8904_initialize(int minor) } /* No we can embed the WM8904/I2C/I2S conglomerate into a PCM decoder - * instance so that we will have a PCM front end for the the WM8904 + * instance so that we will have a PCM front end for the WM8904 * driver. */ diff --git a/configs/sama5d4-ek/src/sama5d4-ek.h b/configs/sama5d4-ek/src/sama5d4-ek.h index 4bf4031976..1a364f64c2 100644 --- a/configs/sama5d4-ek/src/sama5d4-ek.h +++ b/configs/sama5d4-ek/src/sama5d4-ek.h @@ -563,7 +563,7 @@ * J9 pin 8 LCD_TWD0_PA30 J4 pin 8 SDA_0 * ------------------------ ----------------- * - * The schematic indicates the the MXT468E address is 0x4c/0x4d. + * The schematic indicates the MXT468E address is 0x4c/0x4d. */ #define PIO_CHG_MXT (PIO_INPUT | PIO_CFG_PULLUP | PIO_CFG_DEGLITCH | \ diff --git a/configs/samd20-xplained/README.txt b/configs/samd20-xplained/README.txt index d79a298b69..5d8f9c0518 100644 --- a/configs/samd20-xplained/README.txt +++ b/configs/samd20-xplained/README.txt @@ -38,7 +38,7 @@ STATUS/ISSUES 2. Garbage appears on the display sometimes after a reset (maybe 20% of the time) or after a power cycle (less after a power cycle). I don't understand the cause of of this but most of this can be eliminated by - simply holding the the reset button longer and releasing it cleanly + simply holding the reset button longer and releasing it cleanly (then it fails maybe 5-10% of the time, maybe because of button chatter?) (2014-2-18). diff --git a/configs/samd20-xplained/src/sam_appinit.c b/configs/samd20-xplained/src/sam_appinit.c index 8bc9a35b4f..8e90119742 100644 --- a/configs/samd20-xplained/src/sam_appinit.c +++ b/configs/samd20-xplained/src/sam_appinit.c @@ -105,7 +105,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/samd21-xplained/README.txt b/configs/samd21-xplained/README.txt index 6ac8fafe39..8fdacc8f0e 100644 --- a/configs/samd21-xplained/README.txt +++ b/configs/samd21-xplained/README.txt @@ -467,7 +467,7 @@ Configurations ./configure.sh samd21-xplained/ cd - - Before building, make sure the the PATH environment varaible include the + Before building, make sure the PATH environment varaible include the correct path to the directory than holds your toolchain binaries. And then build NuttX by simply typing the following. At the conclusion of diff --git a/configs/samd21-xplained/src/sam_appinit.c b/configs/samd21-xplained/src/sam_appinit.c index 56afb0ff24..881af05df6 100644 --- a/configs/samd21-xplained/src/sam_appinit.c +++ b/configs/samd21-xplained/src/sam_appinit.c @@ -105,7 +105,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/same70-xplained/include/board.h b/configs/same70-xplained/include/board.h index 2e5378b82c..0eee34dc7e 100644 --- a/configs/same70-xplained/include/board.h +++ b/configs/same70-xplained/include/board.h @@ -57,7 +57,7 @@ * Master Clock (MCK): Source = PLLACK, Prescalar = 1 to generate MCK = 120MHz * CPU clock: 120MHz * - * There can be two on-board crystals. However, the the 32.768 crystal is not + * There can be two on-board crystals. However, the 32.768 crystal is not * populated on the stock SAME70. The fallback is to use th on-chip, slow RC * oscillator which has a frequency of 22-42 KHz, nominally 32 KHz. */ diff --git a/configs/same70-xplained/src/sam_appinit.c b/configs/same70-xplained/src/sam_appinit.c index 4dd89315b7..6dfa27a421 100644 --- a/configs/same70-xplained/src/sam_appinit.c +++ b/configs/same70-xplained/src/sam_appinit.c @@ -63,7 +63,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/same70-xplained/src/sam_ethernet.c b/configs/same70-xplained/src/sam_ethernet.c index 053003fe11..413eec4762 100644 --- a/configs/same70-xplained/src/sam_ethernet.c +++ b/configs/same70-xplained/src/sam_ethernet.c @@ -263,7 +263,7 @@ int sam_emac0_setmac(void) * and SIOCSMIIREG ioctl calls** to communicate with the PHY, * determine what network event took place (Link Up/Down?), and * take the appropriate actions. - * d. It should then interact the the PHY to clear any pending + * d. It should then interact the PHY to clear any pending * interrupts, then re-enable the PHY interrupt. * * * This is an OS internal interface and should not be used from diff --git a/configs/saml21-xplained/src/sam_appinit.c b/configs/saml21-xplained/src/sam_appinit.c index 9f299c1f71..7e4d97a3ea 100644 --- a/configs/saml21-xplained/src/sam_appinit.c +++ b/configs/saml21-xplained/src/sam_appinit.c @@ -105,7 +105,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/samv71-xult/README.txt b/configs/samv71-xult/README.txt index 182b0cc99a..7b190de0e1 100644 --- a/configs/samv71-xult/README.txt +++ b/configs/samv71-xult/README.txt @@ -1598,7 +1598,7 @@ can be selected as follow: ./configure.sh samv71-xult/ cd - -Before building, make sure the the PATH environment variable include the +Before building, make sure the PATH environment variable include the correct path to the directory than holds your toolchain binaries. And then build NuttX by simply typing the following. At the conclusion of diff --git a/configs/samv71-xult/src/sam_appinit.c b/configs/samv71-xult/src/sam_appinit.c index 9e59395cc1..acd195f10a 100644 --- a/configs/samv71-xult/src/sam_appinit.c +++ b/configs/samv71-xult/src/sam_appinit.c @@ -63,7 +63,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/samv71-xult/src/sam_ethernet.c b/configs/samv71-xult/src/sam_ethernet.c index 1278b4d6be..3fff3006b7 100644 --- a/configs/samv71-xult/src/sam_ethernet.c +++ b/configs/samv71-xult/src/sam_ethernet.c @@ -267,7 +267,7 @@ int sam_emac0_setmac(void) * and SIOCSMIIREG ioctl calls** to communicate with the PHY, * determine what network event took place (Link Up/Down?), and * take the appropriate actions. - * d. It should then interact the the PHY to clear any pending + * d. It should then interact the PHY to clear any pending * interrupts, then re-enable the PHY interrupt. * * * This is an OS internal interface and should not be used from diff --git a/configs/samv71-xult/src/sam_wm8904.c b/configs/samv71-xult/src/sam_wm8904.c index 8ffe0dfe21..4d25648503 100644 --- a/configs/samv71-xult/src/sam_wm8904.c +++ b/configs/samv71-xult/src/sam_wm8904.c @@ -331,7 +331,7 @@ int sam_wm8904_initialize(int minor) } /* No we can embed the WM8904/I2C/I2S conglomerate into a PCM decoder - * instance so that we will have a PCM front end for the the WM8904 + * instance so that we will have a PCM front end for the WM8904 * driver. */ diff --git a/configs/shenzhou/src/stm32_appinit.c b/configs/shenzhou/src/stm32_appinit.c index 2bfb40a59f..a260c4ec1e 100644 --- a/configs/shenzhou/src/stm32_appinit.c +++ b/configs/shenzhou/src/stm32_appinit.c @@ -150,7 +150,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/sim/src/sim_appinit.c b/configs/sim/src/sim_appinit.c index 4100ec736b..c3abef2d59 100644 --- a/configs/sim/src/sim_appinit.c +++ b/configs/sim/src/sim_appinit.c @@ -58,7 +58,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/spark/src/stm32_appinit.c b/configs/spark/src/stm32_appinit.c index 1b484caa48..a666eb089e 100644 --- a/configs/spark/src/stm32_appinit.c +++ b/configs/spark/src/stm32_appinit.c @@ -138,7 +138,7 @@ static bool g_app_initialzed; * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/stm3210e-eval/src/stm32_appinit.c b/configs/stm3210e-eval/src/stm32_appinit.c index 0b4a1c52c2..84108fd42b 100644 --- a/configs/stm3210e-eval/src/stm32_appinit.c +++ b/configs/stm3210e-eval/src/stm32_appinit.c @@ -184,7 +184,7 @@ static void stm32_i2ctool(void) * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/stm3220g-eval/src/stm32_appinit.c b/configs/stm3220g-eval/src/stm32_appinit.c index 0fd45e4a6e..447bb24f3d 100644 --- a/configs/stm3220g-eval/src/stm32_appinit.c +++ b/configs/stm3220g-eval/src/stm32_appinit.c @@ -197,7 +197,7 @@ static void stm32_i2ctool(void) * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/stm3240g-eval/src/stm32_appinit.c b/configs/stm3240g-eval/src/stm32_appinit.c index 448c48ba36..d2f847a276 100644 --- a/configs/stm3240g-eval/src/stm32_appinit.c +++ b/configs/stm3240g-eval/src/stm32_appinit.c @@ -215,7 +215,7 @@ static void stm32_i2ctool(void) * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/stm32_tiny/src/stm32_appinit.c b/configs/stm32_tiny/src/stm32_appinit.c index d9152f5ddf..e4dacea565 100644 --- a/configs/stm32_tiny/src/stm32_appinit.c +++ b/configs/stm32_tiny/src/stm32_appinit.c @@ -65,7 +65,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/stm32f0discovery/src/stm32_appinit.c b/configs/stm32f0discovery/src/stm32_appinit.c index a69c731e1e..3a0ae46ab2 100644 --- a/configs/stm32f0discovery/src/stm32_appinit.c +++ b/configs/stm32f0discovery/src/stm32_appinit.c @@ -62,7 +62,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/stm32f103-minimum/src/stm32_appinit.c b/configs/stm32f103-minimum/src/stm32_appinit.c index e8d545ff66..357090b47d 100644 --- a/configs/stm32f103-minimum/src/stm32_appinit.c +++ b/configs/stm32f103-minimum/src/stm32_appinit.c @@ -66,7 +66,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/stm32f3discovery/src/stm32_appinit.c b/configs/stm32f3discovery/src/stm32_appinit.c index 6007b0a4f6..f3da7a8025 100644 --- a/configs/stm32f3discovery/src/stm32_appinit.c +++ b/configs/stm32f3discovery/src/stm32_appinit.c @@ -100,7 +100,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/stm32f411e-disco/src/stm32_appinit.c b/configs/stm32f411e-disco/src/stm32_appinit.c index 984a3d9ab4..1656bb6a9b 100644 --- a/configs/stm32f411e-disco/src/stm32_appinit.c +++ b/configs/stm32f411e-disco/src/stm32_appinit.c @@ -69,7 +69,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/stm32f429i-disco/src/stm32_appinit.c b/configs/stm32f429i-disco/src/stm32_appinit.c index bbd1b18078..d7c352f344 100644 --- a/configs/stm32f429i-disco/src/stm32_appinit.c +++ b/configs/stm32f429i-disco/src/stm32_appinit.c @@ -136,7 +136,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/stm32f4discovery/src/stm32_appinit.c b/configs/stm32f4discovery/src/stm32_appinit.c index 75e635988c..9382ffab67 100644 --- a/configs/stm32f4discovery/src/stm32_appinit.c +++ b/configs/stm32f4discovery/src/stm32_appinit.c @@ -67,7 +67,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/stm32f4discovery/src/stm32_ethernet.c b/configs/stm32f4discovery/src/stm32_ethernet.c index fcd6d6c214..429350a4b2 100644 --- a/configs/stm32f4discovery/src/stm32_ethernet.c +++ b/configs/stm32f4discovery/src/stm32_ethernet.c @@ -187,7 +187,7 @@ void weak_function stm32_netinitialize(void) * and SIOCSMIIREG ioctl calls** to communicate with the PHY, * determine what network event took place (Link Up/Down?), and * take the appropriate actions. - * d. It should then interact the the PHY to clear any pending + * d. It should then interact the PHY to clear any pending * interrupts, then re-enable the PHY interrupt. * * * This is an OS internal interface and should not be used from diff --git a/configs/stm32f746g-disco/src/stm32_appinitialize.c b/configs/stm32f746g-disco/src/stm32_appinitialize.c index 88d62fc154..e1feb21c4a 100644 --- a/configs/stm32f746g-disco/src/stm32_appinitialize.c +++ b/configs/stm32f746g-disco/src/stm32_appinitialize.c @@ -58,7 +58,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/stm32l476-mdk/src/stm32_appinit.c b/configs/stm32l476-mdk/src/stm32_appinit.c index 2633d47302..4e9a08b485 100644 --- a/configs/stm32l476-mdk/src/stm32_appinit.c +++ b/configs/stm32l476-mdk/src/stm32_appinit.c @@ -90,7 +90,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/stm32l476vg-disco/src/stm32_appinit.c b/configs/stm32l476vg-disco/src/stm32_appinit.c index 40b204e59e..00c41a1985 100644 --- a/configs/stm32l476vg-disco/src/stm32_appinit.c +++ b/configs/stm32l476vg-disco/src/stm32_appinit.c @@ -111,7 +111,7 @@ FAR struct mtd_dev_s *g_mtd_fs; * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/stm32ldiscovery/src/stm32_appinit.c b/configs/stm32ldiscovery/src/stm32_appinit.c index 30db4f50f2..b49827fd04 100644 --- a/configs/stm32ldiscovery/src/stm32_appinit.c +++ b/configs/stm32ldiscovery/src/stm32_appinit.c @@ -63,7 +63,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/sure-pic32mx/src/pic32mx_appinit.c b/configs/sure-pic32mx/src/pic32mx_appinit.c index ae36428317..b668e512cb 100644 --- a/configs/sure-pic32mx/src/pic32mx_appinit.c +++ b/configs/sure-pic32mx/src/pic32mx_appinit.c @@ -367,7 +367,7 @@ static int nsh_usbdevinitialize(void) * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/teensy-2.0/src/at90usb_appinit.c b/configs/teensy-2.0/src/at90usb_appinit.c index ab482aa62f..2096fc20ac 100644 --- a/configs/teensy-2.0/src/at90usb_appinit.c +++ b/configs/teensy-2.0/src/at90usb_appinit.c @@ -60,7 +60,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/teensy-3.x/README.txt b/configs/teensy-3.x/README.txt index cdcfee7e62..1513a53256 100644 --- a/configs/teensy-3.x/README.txt +++ b/configs/teensy-3.x/README.txt @@ -143,7 +143,7 @@ Debugging And, at this point, I don't know how to debug the board. There is no way to connect a JTAG SWD debuggger, at least not without cutting leads - to the the MINI54TAN device: + to the MINI54TAN device: See: http://mcuoneclipse.com/2014/08/09/hacking-the-teensy-v3-1-for-swd-debugging/ diff --git a/configs/teensy-3.x/src/k20_appinit.c b/configs/teensy-3.x/src/k20_appinit.c index ae26f993f6..d59d4d9e21 100644 --- a/configs/teensy-3.x/src/k20_appinit.c +++ b/configs/teensy-3.x/src/k20_appinit.c @@ -63,7 +63,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/teensy-lc/src/kl_appinit.c b/configs/teensy-lc/src/kl_appinit.c index cfe2684ebd..6bcf8bbd0f 100644 --- a/configs/teensy-lc/src/kl_appinit.c +++ b/configs/teensy-lc/src/kl_appinit.c @@ -65,7 +65,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/tm4c123g-launchpad/src/tm4c_appinit.c b/configs/tm4c123g-launchpad/src/tm4c_appinit.c index c1ad4dd105..433528659d 100644 --- a/configs/tm4c123g-launchpad/src/tm4c_appinit.c +++ b/configs/tm4c123g-launchpad/src/tm4c_appinit.c @@ -59,7 +59,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/tm4c1294-launchpad/src/tm4c_appinit.c b/configs/tm4c1294-launchpad/src/tm4c_appinit.c index 35b1f1ce1b..f866e5e6a9 100644 --- a/configs/tm4c1294-launchpad/src/tm4c_appinit.c +++ b/configs/tm4c1294-launchpad/src/tm4c_appinit.c @@ -61,7 +61,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/twr-k60n512/src/k60_appinit.c b/configs/twr-k60n512/src/k60_appinit.c index 4bbbaee8dd..78e3933020 100644 --- a/configs/twr-k60n512/src/k60_appinit.c +++ b/configs/twr-k60n512/src/k60_appinit.c @@ -201,7 +201,7 @@ static int kinetis_cdinterrupt(int irq, FAR void *context) * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/twr-k64f120m/src/k64_appinit.c b/configs/twr-k64f120m/src/k64_appinit.c index 1c59c4aa2a..66d11d94d9 100644 --- a/configs/twr-k64f120m/src/k64_appinit.c +++ b/configs/twr-k64f120m/src/k64_appinit.c @@ -71,7 +71,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/twr-k64f120m/src/k64_automount.c b/configs/twr-k64f120m/src/k64_automount.c index 5e0ddfb465..d0ce68f40a 100644 --- a/configs/twr-k64f120m/src/k64_automount.c +++ b/configs/twr-k64f120m/src/k64_automount.c @@ -293,7 +293,7 @@ void k64_automount_event(bool inserted) if (!state->enable) { - /* Yes.. just remember the there is a pending interrupt. We will + /* Yes.. just remember that there is a pending interrupt. We will * deliver the interrupt when interrupts are "re-enabled." */ diff --git a/configs/u-blox-c027/src/lpc17_appinit.c b/configs/u-blox-c027/src/lpc17_appinit.c index 30c6d27161..46ffbfa2f4 100644 --- a/configs/u-blox-c027/src/lpc17_appinit.c +++ b/configs/u-blox-c027/src/lpc17_appinit.c @@ -134,7 +134,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/ubw32/src/pic32_appinit.c b/configs/ubw32/src/pic32_appinit.c index 22cf57b4b0..2fd8dcca46 100644 --- a/configs/ubw32/src/pic32_appinit.c +++ b/configs/ubw32/src/pic32_appinit.c @@ -97,7 +97,7 @@ static int nsh_usbdevinitialize(void) * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/viewtool-stm32f107/README.txt b/configs/viewtool-stm32f107/README.txt index 31d5fc734e..9161b483ea 100644 --- a/configs/viewtool-stm32f107/README.txt +++ b/configs/viewtool-stm32f107/README.txt @@ -430,7 +430,7 @@ Freescale MPL115A barometer sensor LCD/Touchscreen Interface ========================= - An LCD may be connected via J11. Only the the STM32F103 supports the FSMC signals + An LCD may be connected via J11. Only the STM32F103 supports the FSMC signals needed to drive the LCD. The LCD features an (1) HY32D module with built-in SSD1289 LCD controller, and (a) @@ -599,7 +599,7 @@ Configurations NOTES: 1. This configuration will work only on the version the viewtool - board with the the STM32F107VCT6 installed. If you have a board + board with the STM32F107VCT6 installed. If you have a board with the STM32F103VCT6 installed, please use the nsh configuration described below. diff --git a/configs/viewtool-stm32f107/src/stm32_appinit.c b/configs/viewtool-stm32f107/src/stm32_appinit.c index 82e4ff85af..ba6e1fd0c9 100644 --- a/configs/viewtool-stm32f107/src/stm32_appinit.c +++ b/configs/viewtool-stm32f107/src/stm32_appinit.c @@ -131,7 +131,7 @@ static int rtc_driver_initialize(void) * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/viewtool-stm32f107/src/stm32_ssd1289.c b/configs/viewtool-stm32f107/src/stm32_ssd1289.c index de4d3a57a8..0b7a152a2b 100644 --- a/configs/viewtool-stm32f107/src/stm32_ssd1289.c +++ b/configs/viewtool-stm32f107/src/stm32_ssd1289.c @@ -109,7 +109,7 @@ static void stm32_enablefsmc(void); **************************************************************************************/ /* LCD * - * An LCD may be connected via J11. Only the the STM32F103 supports the FSMC signals + * An LCD may be connected via J11. Only the STM32F103 supports the FSMC signals * needed to drive the LCD. * * The LCD features an (1) HY32D module with built-in SSD1289 LCD controller, and (a) diff --git a/configs/viewtool-stm32f107/src/viewtool_stm32f107.h b/configs/viewtool-stm32f107/src/viewtool_stm32f107.h index 508f10c8a2..b9a0329c92 100644 --- a/configs/viewtool-stm32f107/src/viewtool_stm32f107.h +++ b/configs/viewtool-stm32f107/src/viewtool_stm32f107.h @@ -207,7 +207,7 @@ /* LCD * - * An LCD may be connected via J11. Only the the STM32F103 supports the FSMC signals + * An LCD may be connected via J11. Only the STM32F103 supports the FSMC signals * needed to drive the LCD. * * The LCD features an (1) HY32D module with built-in SSD1289 LCD controller, and (a) diff --git a/configs/xmc4500-relax/src/xmc4_appinit.c b/configs/xmc4500-relax/src/xmc4_appinit.c index 1621317d4d..ff79ddfc73 100644 --- a/configs/xmc4500-relax/src/xmc4_appinit.c +++ b/configs/xmc4500-relax/src/xmc4_appinit.c @@ -61,7 +61,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/z16f2800100zcog/README.txt b/configs/z16f2800100zcog/README.txt index 5875a15e0d..aff6105296 100644 --- a/configs/z16f2800100zcog/README.txt +++ b/configs/z16f2800100zcog/README.txt @@ -142,7 +142,7 @@ following steps: Where is the specific board configuration that you wish to build. The following board-specific configurations are available. You may also need to apply a path to NuttX before making. -Please refer the the section "Patches" above" +Please refer the section "Patches" above" Configuration Sub-directories ============================= diff --git a/configs/zkit-arm-1769/src/lpc17_appinit.c b/configs/zkit-arm-1769/src/lpc17_appinit.c index b98cb2bab9..d6e80895fd 100644 --- a/configs/zkit-arm-1769/src/lpc17_appinit.c +++ b/configs/zkit-arm-1769/src/lpc17_appinit.c @@ -146,7 +146,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/configs/zp214xpa/src/lpc2148_appinit.c b/configs/zp214xpa/src/lpc2148_appinit.c index b5efe18344..8d52632333 100644 --- a/configs/zp214xpa/src/lpc2148_appinit.c +++ b/configs/zp214xpa/src/lpc2148_appinit.c @@ -60,7 +60,7 @@ * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/drivers/input/ajoystick.c b/drivers/input/ajoystick.c index 6665b8fdd2..2868e1542a 100644 --- a/drivers/input/ajoystick.c +++ b/drivers/input/ajoystick.c @@ -832,7 +832,7 @@ errout_with_dusem: * * Input Parameters: * devname - The name of the analog joystick device to be registers. - * This should be a string of the form "/priv/ajoyN" where N is the the + * This should be a string of the form "/priv/ajoyN" where N is the * minor device number. * lower - An instance of the platform-specific analog joystick lower * half driver. diff --git a/drivers/input/button_upper.c b/drivers/input/button_upper.c index f5486752fc..12f2896cf5 100644 --- a/drivers/input/button_upper.c +++ b/drivers/input/button_upper.c @@ -824,7 +824,7 @@ errout_with_dusem: * * Input Parameters: * devname - The name of the button device to be registered. - * This should be a string of the form "/dev/btnN" where N is the the + * This should be a string of the form "/dev/btnN" where N is the * minor device number. * lower - An instance of the platform-specific button lower half driver. * diff --git a/drivers/input/djoystick.c b/drivers/input/djoystick.c index bd3c9e4703..62f62fe45a 100644 --- a/drivers/input/djoystick.c +++ b/drivers/input/djoystick.c @@ -828,7 +828,7 @@ errout_with_dusem: * * Input Parameters: * devname - The name of the discrete joystick device to be registers. - * This should be a string of the form "/priv/djoyN" where N is the the + * This should be a string of the form "/priv/djoyN" where N is the * minor device number. * lower - An instance of the platform-specific discrete joystick lower * half driver. diff --git a/drivers/leds/userled_upper.c b/drivers/leds/userled_upper.c index abf7cc719e..dbf8f919c1 100644 --- a/drivers/leds/userled_upper.c +++ b/drivers/leds/userled_upper.c @@ -523,7 +523,7 @@ static int userled_ioctl(FAR struct file *filep, int cmd, unsigned long arg) * * Input Parameters: * devname - The name of the LED device to be registered. - * This should be a string of the form "/dev/ledN" where N is the the + * This should be a string of the form "/dev/ledN" where N is the * minor device number. * lower - An instance of the platform-specific LED lower half driver. * diff --git a/drivers/mtd/mtd_config.c b/drivers/mtd/mtd_config.c index d56c26cc89..69ac00237d 100644 --- a/drivers/mtd/mtd_config.c +++ b/drivers/mtd/mtd_config.c @@ -276,7 +276,7 @@ static int mtdconfig_writebytes(FAR struct mtdconfig_struct_s *dev, int offset, while (writelen) { - /* Read existing data from the the block into the buffer */ + /* Read existing data from the block into the buffer */ block = offset / dev->blocksize; ret = MTD_BREAD(dev->mtd, block, 1, dev->buffer); diff --git a/drivers/mtd/mtd_onfi.c b/drivers/mtd/mtd_onfi.c index 4a2a150f0f..ace56104a1 100644 --- a/drivers/mtd/mtd_onfi.c +++ b/drivers/mtd/mtd_onfi.c @@ -261,7 +261,7 @@ bool onfi_compatible(uintptr_t cmdaddr, uintptr_t addraddr, * onfi - The ONFI data structure to populate. * * Returned Value: - * OK is returned on success and the the ONFI data structure is initialized + * OK is returned on success and the ONFI data structure is initialized * with NAND data. A negated errno value is returned in the event of an * error. * diff --git a/drivers/mtd/smart.c b/drivers/mtd/smart.c index bbd7be3cdd..c5c6e80a3e 100644 --- a/drivers/mtd/smart.c +++ b/drivers/mtd/smart.c @@ -249,7 +249,7 @@ struct smart_struct_s uint8_t minwearlevel; /* Min level in the wear level bits */ uint8_t maxwearlevel; /* Max level in the wear level bits */ uint8_t *wearstatus; /* Array of wear leveling bits */ - uint32_t uneven_wearcount; /* Number of times the the wear level has gone over max */ + uint32_t uneven_wearcount; /* Number of times the wear level has gone over max */ #endif #ifdef CONFIG_MTD_SMART_ENABLE_CRC FAR struct smart_allocsector_s *allocsector; /* Pointer to first alloc sector */ diff --git a/drivers/serial/ptmx.c b/drivers/serial/ptmx.c index dd6bd9fd3c..6a8a3359ce 100644 --- a/drivers/serial/ptmx.c +++ b/drivers/serial/ptmx.c @@ -247,7 +247,7 @@ static int ptmx_open(FAR struct file *filep) DEBUGASSERT(fd >= 0); /* open() should never fail */ /* No unlink the master. This will remove it from the VFS namespace, - * the the driver will still persist because of the open count on the + * the driver will still persist because of the open count on the * driver. */ diff --git a/drivers/syslog/syslog_device.c b/drivers/syslog/syslog_device.c index 748f6908d1..0d49ea4e8a 100644 --- a/drivers/syslog/syslog_device.c +++ b/drivers/syslog/syslog_device.c @@ -335,7 +335,7 @@ int syslog_dev_initialize(FAR const char *devpath, int oflags, int mode) DEBUGASSERT(g_syslog_dev.sl_state == SYSLOG_UNINITIALIZED || g_syslog_dev.sl_state == SYSLOG_REOPEN); - /* Save the the path to the device in case we have to re-open it. + /* Save the path to the device in case we have to re-open it. * If we get here and sl_devpath is not equal to NULL, that is a clue * that we will are re-openingthe file. */ diff --git a/drivers/usbhost/Kconfig b/drivers/usbhost/Kconfig index 5e49aa7b86..e8a9a27934 100644 --- a/drivers/usbhost/Kconfig +++ b/drivers/usbhost/Kconfig @@ -142,7 +142,7 @@ config USBHOST_CDCACM_REDUCED status lines. This mode is useful if the number of available endpoints is limited by hardware restrictions. - If the the CDC/ACM compliant protocol is selected, then the reduced + If the CDC/ACM compliant protocol is selected, then the reduced protocol is supported for devices that provide not interrupt IN endpoint. This option is then most useful for testing purposes or if there are insufficient resources to support the compliant diff --git a/drivers/usbhost/usbhost_composite.c b/drivers/usbhost/usbhost_composite.c index cc60adff94..05b8e8b030 100644 --- a/drivers/usbhost/usbhost_composite.c +++ b/drivers/usbhost/usbhost_composite.c @@ -70,7 +70,7 @@ struct usbhost_member_s { - /* This the the classobject returned by each contained class */ + /* This the classobject returned by each contained class */ FAR struct usbhost_class_s *usbclass; diff --git a/drivers/usbhost/usbhost_devaddr.c b/drivers/usbhost/usbhost_devaddr.c index 58fbe04297..1b51a08926 100644 --- a/drivers/usbhost/usbhost_devaddr.c +++ b/drivers/usbhost/usbhost_devaddr.c @@ -269,7 +269,7 @@ void usbhost_devaddr_initialize(FAR struct usbhost_roothubport_s *rhport) * newly connected and so is in need of a function address. * * Returned Value: - * On success, a new device function address in the the range 0x01 to 0x7f + * On success, a new device function address in the range 0x01 to 0x7f * is returned. On failure, a negated errno value is returned. * ****************************************************************************/ diff --git a/drivers/usbhost/usbhost_trace.c b/drivers/usbhost/usbhost_trace.c index ba47097fa8..bc9963893c 100644 --- a/drivers/usbhost/usbhost_trace.c +++ b/drivers/usbhost/usbhost_trace.c @@ -111,7 +111,7 @@ static int usbhost_trsyslog(uint32_t event, FAR void *arg) syslog(LOG_INFO, fmt, (unsigned int)TRACE_DECODE_U23(event)); } - /* No, then it must the the two argument format first. */ + /* No, then it must the two argument format first. */ else { diff --git a/drivers/usbmonitor/Kconfig b/drivers/usbmonitor/Kconfig index e35c47e490..69862378e8 100644 --- a/drivers/usbmonitor/Kconfig +++ b/drivers/usbmonitor/Kconfig @@ -8,13 +8,13 @@ config USBMONITOR_STACKSIZE int "USB Monitor daemon stack size" default 2048 ---help--- - The stack size to use the the USB monitor daemon. Default: 2048 + The stack size to use the USB monitor daemon. Default: 2048 config USBMONITOR_PRIORITY int "USB Monitor daemon priority" default 50 ---help--- - The priority to use the the USB monitor daemon. Default: 50 + The priority to use the USB monitor daemon. Default: 50 config USBMONITOR_INTERVAL int "USB Monitor dump frequency" diff --git a/drivers/usbmonitor/usbmonitor.c b/drivers/usbmonitor/usbmonitor.c index 22e34ed5e4..913ceeb110 100644 --- a/drivers/usbmonitor/usbmonitor.c +++ b/drivers/usbmonitor/usbmonitor.c @@ -272,7 +272,7 @@ int usbmonitor_stop(void) if (g_usbmonitor.started) { /* Stop the USB monitor. The next time the monitor wakes up, - * it will see the the stop indication and will exist. + * it will see the stop indication and will exist. */ uinfo("Stopping: %d\n", g_usbmonitor.pid); diff --git a/drivers/wireless/cc3000/socket_imp.c b/drivers/wireless/cc3000/socket_imp.c index 38341b2939..2ec41d92e1 100644 --- a/drivers/wireless/cc3000/socket_imp.c +++ b/drivers/wireless/cc3000/socket_imp.c @@ -148,7 +148,7 @@ int HostFlowControlConsumeBuff(int sd) return -1; } - /* We must yield here for the the Event to get processed that returns + /* We must yield here for the Event to get processed that returns * the buffers */ diff --git a/graphics/vnc/server/vnc_raw.c b/graphics/vnc/server/vnc_raw.c index 8e58cfc1d3..35f9f1895d 100644 --- a/graphics/vnc/server/vnc_raw.c +++ b/graphics/vnc/server/vnc_raw.c @@ -279,7 +279,7 @@ static size_t vnc_copy32(FAR struct vnc_session_s *session, * * Returned Value: * Zero (OK) on success; A negated errno value is returned on failure that - * indicates the the nature of the failure. A failure is only returned + * indicates the nature of the failure. A failure is only returned * in cases of a network failure and unexpected internal failures. * ****************************************************************************/ diff --git a/graphics/vnc/server/vnc_rre.c b/graphics/vnc/server/vnc_rre.c index cc0d3c9317..5463d42b42 100644 --- a/graphics/vnc/server/vnc_rre.c +++ b/graphics/vnc/server/vnc_rre.c @@ -195,7 +195,7 @@ ssize_t vnc_rre32(FAR struct vnc_session_s *session, * Zero is returned if RRE coding was not performed (but not error was) * encountered. Otherwise, the size of the framebuffer update message * is returned on success or a negated errno value is returned on failure - * that indicates the the nature of the failure. A failure is only + * that indicates the nature of the failure. A failure is only * returned in cases of a network failure and unexpected internal failures. * ****************************************************************************/ diff --git a/graphics/vnc/server/vnc_server.h b/graphics/vnc/server/vnc_server.h index b513861fe8..3abc10dacf 100644 --- a/graphics/vnc/server/vnc_server.h +++ b/graphics/vnc/server/vnc_server.h @@ -491,7 +491,7 @@ int vnc_receiver(FAR struct vnc_session_s *session); * Zero is returned if RRE coding was not performed (but not error was) * encountered. Otherwise, the size of the framebuffer update message * is returned on success or a negated errno value is returned on failure - * that indicates the the nature of the failure. A failure is only + * that indicates the nature of the failure. A failure is only * returned in cases of a network failure and unexpected internal failures. * ****************************************************************************/ @@ -511,7 +511,7 @@ int vnc_rre(FAR struct vnc_session_s *session, FAR struct nxgl_rect_s *rect); * * Returned Value: * Zero (OK) on success; A negated errno value is returned on failure that - * indicates the the nature of the failure. A failure is only returned + * indicates the nature of the failure. A failure is only returned * in cases of a network failure and unexpected internal failures. * ****************************************************************************/ diff --git a/include/nuttx/arch.h b/include/nuttx/arch.h index 925ae988ed..8e02bc3529 100644 --- a/include/nuttx/arch.h +++ b/include/nuttx/arch.h @@ -1470,7 +1470,7 @@ int up_prioritize_irq(int irq, int priority); * any failure. * * Assumptions: - * Called from the the normal tasking context. The implementation must + * Called from the normal tasking context. The implementation must * provide whatever mutual exclusion is necessary for correct operation. * This can include disabling interrupts in order to assure atomic register * operations. @@ -2268,7 +2268,7 @@ int up_rtc_settime(FAR const struct timespec *tp); * and SIOCSMIIREG ioctl calls** to communicate with the PHY, * determine what network event took place (Link Up/Down?), and * take the appropriate actions. - * d. It should then interact the the PHY to clear any pending + * d. It should then interact the PHY to clear any pending * interrupts, then re-enable the PHY interrupt. * * * This is an OS internal interface and should not be used from diff --git a/include/nuttx/audio/wm8904.h b/include/nuttx/audio/wm8904.h index 5b2bd7e549..dc1488b85d 100644 --- a/include/nuttx/audio/wm8904.h +++ b/include/nuttx/audio/wm8904.h @@ -64,7 +64,7 @@ * thread. * CONFIG_WM8904_BUFFER_SIZE - Preferred buffer size * CONFIG_WM8904_NUM_BUFFERS - Preferred number of buffers - * CONFIG_WM8904_WORKER_STACKSIZE - Stack size to use when creating the the + * CONFIG_WM8904_WORKER_STACKSIZE - Stack size to use when creating the * WM8904 worker thread. * CONFIG_WM8904_REGDUMP - Enable logic to dump all WM8904 registers to * the SYSLOG device. diff --git a/include/nuttx/binfmt/binfmt.h b/include/nuttx/binfmt/binfmt.h index 8ee4b161bc..40e133ece9 100644 --- a/include/nuttx/binfmt/binfmt.h +++ b/include/nuttx/binfmt/binfmt.h @@ -336,8 +336,8 @@ int exec(FAR const char *filename, FAR char * const *argv, * On success, exepath_init() return a non-NULL, opaque handle that may * subsequently be used in calls to exepath_next() and exepath_release(). * On error, a NULL handle value will be returned. The most likely cause - * of an error would be that the there is no value associated with the - * PATH variable. + * of an error would be that there is no value associated with the PATH + * variable. * ****************************************************************************/ diff --git a/include/nuttx/board.h b/include/nuttx/board.h index c00d09ce3c..bc67a03a2d 100644 --- a/include/nuttx/board.h +++ b/include/nuttx/board.h @@ -46,7 +46,7 @@ * definitions provide the common interface between NuttX and the * architecture-specific implementation in arch/ * - * These definitions are retained in the the header file + * These definitions are retained in the header file * nuttx/include/arch.h * * NOTE: up_ is supposed to stand for microprocessor; the u is like the @@ -148,7 +148,7 @@ void board_initialize(void); * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the + * between the board-specific initalization logic and the * matching application logic. The value cold be such things as a * mode enumeration value, a set of DIP switch switch settings, a * pointer to configuration data read from a file or serial FLASH, diff --git a/include/nuttx/input/ajoystick.h b/include/nuttx/input/ajoystick.h index b50d98d56e..9704943db6 100644 --- a/include/nuttx/input/ajoystick.h +++ b/include/nuttx/input/ajoystick.h @@ -278,7 +278,7 @@ extern "C" * * Input Parameters: * devname - The name of the analog joystick device to be registered. - * This should be a string of the form "/dev/ajoyN" where N is the the + * This should be a string of the form "/dev/ajoyN" where N is the * minor device number. * lower - An instance of the platform-specific analog joystick lower * half driver. diff --git a/include/nuttx/input/buttons.h b/include/nuttx/input/buttons.h index 13ba28c3aa..dbaaec45e1 100644 --- a/include/nuttx/input/buttons.h +++ b/include/nuttx/input/buttons.h @@ -187,7 +187,7 @@ extern "C" * * Input Parameters: * devname - The name of the button device to be registered. - * This should be a string of the form "/dev/btnN" where N is the the + * This should be a string of the form "/dev/btnN" where N is the * minor device number. * lower - An instance of the platform-specific button lower half driver. * diff --git a/include/nuttx/input/djoystick.h b/include/nuttx/input/djoystick.h index fc136cdfd2..84dbf318af 100644 --- a/include/nuttx/input/djoystick.h +++ b/include/nuttx/input/djoystick.h @@ -255,7 +255,7 @@ extern "C" * * Input Parameters: * devname - The name of the discrete joystick device to be registers. - * This should be a string of the form "/dev/djoyN" where N is the the + * This should be a string of the form "/dev/djoyN" where N is the * minor device number. * lower - An instance of the platform-specific discrete joystick lower * half driver. diff --git a/include/nuttx/leds/userled.h b/include/nuttx/leds/userled.h index 093c3b5b9a..0b9f8b0e25 100644 --- a/include/nuttx/leds/userled.h +++ b/include/nuttx/leds/userled.h @@ -166,7 +166,7 @@ extern "C" * * Input Parameters: * devname - The name of the LED device to be registered. - * This should be a string of the form "/dev/ledN" where N is the the + * This should be a string of the form "/dev/ledN" where N is the * minor device number. * lower - An instance of the platform-specific LED lower half driver. * diff --git a/include/nuttx/lib/modlib.h b/include/nuttx/lib/modlib.h index 7df5e34462..b1f00ef30a 100644 --- a/include/nuttx/lib/modlib.h +++ b/include/nuttx/lib/modlib.h @@ -480,7 +480,7 @@ int modlib_registry_del(FAR struct module_s *modp); * * Returned Value: * If the registry entry is found, a pointer to the module entry is - * returned. NULL is returned if the they entry is not found. + * returned. NULL is returned if the entry is not found. * * Assumptions: * The caller holds the lock on the module registry. diff --git a/include/nuttx/mtd/onfi.h b/include/nuttx/mtd/onfi.h index a26d3e3afb..6ae1649b6f 100644 --- a/include/nuttx/mtd/onfi.h +++ b/include/nuttx/mtd/onfi.h @@ -131,7 +131,7 @@ bool onfi_compatible(uintptr_t cmdaddr, uintptr_t addraddr, * onfi - The ONFI data structure to populate. * * Returned Value: - * OK is returned on success and the the ONFI data structure is initialized + * OK is returned on success and the ONFI data structure is initialized * with NAND data. A negated errno value is returned in the event of an * error. * diff --git a/include/nuttx/net/netdev.h b/include/nuttx/net/netdev.h index 782c2e3399..18ea237945 100644 --- a/include/nuttx/net/netdev.h +++ b/include/nuttx/net/netdev.h @@ -258,7 +258,7 @@ struct net_driver_s FAR uint8_t *d_buf; /* d_appdata points to the location where application data can be read from - * or written to in the the packet buffer. + * or written to in the packet buffer. */ uint8_t *d_appdata; diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index 45395d1c29..f9b9655f15 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -512,7 +512,7 @@ struct ieee802154_driver_s * * When the packet in the d_buf is fully reassembled, it will be provided * to the network as with any other received packet. d_len will be set - * the the length of the uncompressed, reassembled packet. + * the length of the uncompressed, reassembled packet. * * After the network processes the packet, d_len will be set to zero. * Network logic may also decide to send a response to the packet. In diff --git a/include/nuttx/power/battery_charger.h b/include/nuttx/power/battery_charger.h index d90db10154..76cfa9e447 100644 --- a/include/nuttx/power/battery_charger.h +++ b/include/nuttx/power/battery_charger.h @@ -68,7 +68,7 @@ * around the lower-half battery charger driver that does all of the real work. * Since there is no real data transfer to/or from a battery, all of the * driver interaction is through IOCTL commands. The IOCTL commands - * supported by the upper-half driver simply provide calls into the the + * supported by the upper-half driver simply provide calls into the * lower half as summarized below: * * BATIOC_STATE - Return the current state of the battery (see diff --git a/include/nuttx/power/battery_gauge.h b/include/nuttx/power/battery_gauge.h index 8351faee8c..e97f8a3d74 100644 --- a/include/nuttx/power/battery_gauge.h +++ b/include/nuttx/power/battery_gauge.h @@ -69,7 +69,7 @@ * real work. * Since there is no real data transfer to/or from a battery, all of the * driver interaction is through IOCTIL commands. The IOCTL commands - * supported by the upper-half driver simply provide calls into the the + * supported by the upper-half driver simply provide calls into the * lower half as summarized below: * * BATIOC_STATE - Return the current state of the battery (see diff --git a/include/nuttx/sdio.h b/include/nuttx/sdio.h index 035e267710..41752a264c 100644 --- a/include/nuttx/sdio.h +++ b/include/nuttx/sdio.h @@ -68,7 +68,7 @@ * avoid potentially very long (600Ms+) busy waiting in the MMCSD driver. * * To implement D0 Busy signalling, the underlying SDIO driver must be - * capable of switching the the D0 GPIO to be a rising edge sensitive + * capable of switching the D0 GPIO to be a rising edge sensitive * interrupt pin. It must then, condition that pin to detect the rising * edge on receipt of SDWAIT_WRCOMPLETE in the SDIO_WAITENABLE call and * return it back to regular SDIO mode, when either the ISR fires or pin diff --git a/include/nuttx/spi/slave.h b/include/nuttx/spi/slave.h index b53ce28f51..ba11c26394 100644 --- a/include/nuttx/spi/slave.h +++ b/include/nuttx/spi/slave.h @@ -268,7 +268,7 @@ * 1) struct spi_sctrlr_s: Defines one interface between the SPI * slave device and the SPI slave controller hardware. This interface * is implemented by the SPI slave device controller lower-half driver - * and is provided to the the SPI slave device driver when that driver + * and is provided to the SPI slave device driver when that driver * is initialized. That SPI slave device initialization function is * unique to the SPI slave implementation. The prototype is probably * something like: diff --git a/include/nuttx/usb/usbhost.h b/include/nuttx/usb/usbhost.h index 6b6b495954..7f95b1d5b3 100644 --- a/include/nuttx/usb/usbhost.h +++ b/include/nuttx/usb/usbhost.h @@ -516,7 +516,7 @@ * will enqueue the transfer request and return immediately. Only one * transfer may be queued on a given endpoint/ * - * When the transfer completes, the the callback will be invoked with the + * When the transfer completes, the callback will be invoked with the * provided argument. * * This method is useful for receiving interrupt transfers which may come @@ -638,7 +638,7 @@ struct usbhost_id_s uint16_t pid; /* Product ID (for vendor/product specific devices) */ }; -/* The struct usbhost_registry_s type describes information that is kept in the the +/* The struct usbhost_registry_s type describes information that is kept in the * USB host registry. USB host class implementations register this information so * that USB host drivers can later find the class that matches the device that is * connected to the USB port. @@ -880,7 +880,7 @@ struct usbhost_driver_s * will enqueue the transfer request and return immediately. Only one * transfer may be queued on a given endpoint/ * - * When the transfer completes, the the callback will be invoked with the + * When the transfer completes, the callback will be invoked with the * provided argument. * * This method is useful for receiving interrupt transfers which may come diff --git a/include/nuttx/usb/usbhost_devaddr.h b/include/nuttx/usb/usbhost_devaddr.h index 378196b7d3..f62578e7d4 100644 --- a/include/nuttx/usb/usbhost_devaddr.h +++ b/include/nuttx/usb/usbhost_devaddr.h @@ -120,7 +120,7 @@ void usbhost_devaddr_initialize(FAR struct usbhost_roothubport_s *rhport); * newly connected and so is in need of a function address. * * Returned Value: - * On success, a new device function address in the the range 0x01 to 0x7f + * On success, a new device function address in the range 0x01 to 0x7f * is returned. On failure, a negated errno value is returned. * ****************************************************************************/ diff --git a/include/sys/boardctl.h b/include/sys/boardctl.h index c96215ec93..e0294e6437 100644 --- a/include/sys/boardctl.h +++ b/include/sys/boardctl.h @@ -58,7 +58,7 @@ * board_app_initialize() implementation without modification. * The argument has no meaning to NuttX; the meaning of the * argument is a contract between the board-specific - * initalization logic and the the matching application logic. + * initalization logic and the matching application logic. * The value cold be such things as a mode enumeration value, * a set of DIP switch switch settings, a pointer to * configuration data read from a file or serial FLASH, or diff --git a/libc/locale/lib_localeconv.c b/libc/locale/lib_localeconv.c index 697f369cf4..b0338a982e 100644 --- a/libc/locale/lib_localeconv.c +++ b/libc/locale/lib_localeconv.c @@ -62,7 +62,7 @@ FAR struct lconv *localeconv(void) { - /* NULL indicates the the locale was not changed */ + /* NULL indicates the locale was not changed */ return NULL; } diff --git a/libc/modlib/modlib_registry.c b/libc/modlib/modlib_registry.c index 2cab201230..7fd46289a7 100644 --- a/libc/modlib/modlib_registry.c +++ b/libc/modlib/modlib_registry.c @@ -248,7 +248,7 @@ int modlib_registry_del(FAR struct module_s *modp) * * Returned Value: * If the registry entry is found, a pointer to the module entry is - * returned. NULL is returned if the they entry is not found. + * returned. NULL is returned if the entry is not found. * * Assumptions: * The caller holds the lock on the module registry. @@ -344,4 +344,4 @@ int modlib_registry_foreach(mod_callback_t callback, FAR void *arg) modlib_registry_unlock(); return ret; -} \ No newline at end of file +} diff --git a/libc/netdb/lib_dns.h b/libc/netdb/lib_dns.h index 9a6f25b7e6..ad9661edca 100644 --- a/libc/netdb/lib_dns.h +++ b/libc/netdb/lib_dns.h @@ -178,7 +178,7 @@ int dns_bind(void); * Name: dns_query * * Description: - * Using the DNS resolver socket (sd), look up the the 'hostname', and + * Using the DNS resolver socket (sd), look up the 'hostname', and * return its IP address in 'ipaddr' * * Input Parameters: diff --git a/libc/netdb/lib_dnsquery.c b/libc/netdb/lib_dnsquery.c index 3602a5c8dd..59196206b6 100644 --- a/libc/netdb/lib_dnsquery.c +++ b/libc/netdb/lib_dnsquery.c @@ -411,7 +411,7 @@ static int dns_recv_response(int sd, FAR struct sockaddr *addr, * Name: dns_query_callback * * Description: - * Using the DNS information and this DNS server address, look up the the + * Using the DNS information and this DNS server address, look up the * hostname. * * Input Parameters: @@ -624,7 +624,7 @@ static int dns_query_callback(FAR void *arg, FAR struct sockaddr *addr, * Name: dns_query * * Description: - * Using the DNS resolver socket (sd), look up the the 'hostname', and + * Using the DNS resolver socket (sd), look up the 'hostname', and * return its IP address in 'ipaddr' * * Input Parameters: diff --git a/libc/wqueue/work_usrthread.c b/libc/wqueue/work_usrthread.c index f0815ac0c7..925e8d6f78 100644 --- a/libc/wqueue/work_usrthread.c +++ b/libc/wqueue/work_usrthread.c @@ -188,7 +188,7 @@ void work_process(FAR struct usr_wqueue_s *wqueue) work->worker = NULL; - /* Do the work. Unlock the the work queue while the work is being + /* Do the work. Unlock the work queue while the work is being * performed... we don't have any idea how long this will take! */ @@ -223,7 +223,7 @@ void work_process(FAR struct usr_wqueue_s *wqueue) { /* This one is not ready. * - * NOTE that elapsed is relative to the the current time, + * NOTE that elapsed is relative to the current time, * not the time of beginning of this queue processing pass. * So it may need an adjustment. */ diff --git a/libnx/nxfonts/nxfonts_cache.c b/libnx/nxfonts/nxfonts_cache.c index 9d45827826..b2cdf74da0 100644 --- a/libnx/nxfonts/nxfonts_cache.c +++ b/libnx/nxfonts/nxfonts_cache.c @@ -300,7 +300,7 @@ nxf_findglyph(FAR struct nxfonts_fcache_s *priv, uint8_t ch) glyph != NULL; prev = glyph, glyph = glyph->flink) { - /* Check if we found the the glyph for this character */ + /* Check if we found the glyph for this character */ if (glyph->code == ch) { diff --git a/mm/iob/iob_clone.c b/mm/iob/iob_clone.c index 8b3754b482..cfa8150f10 100644 --- a/mm/iob/iob_clone.c +++ b/mm/iob/iob_clone.c @@ -86,7 +86,7 @@ int iob_clone(FAR struct iob_s *iob1, FAR struct iob_s *iob2, bool throttled) iob2->io_pktlen = iob1->io_pktlen; /* Handle special case where there are empty buffers at the head - * the the list. + * the list. */ while (iob1->io_len <= 0) diff --git a/mm/shm/README.txt b/mm/shm/README.txt index 681f5a0eb9..81bdfab86e 100644 --- a/mm/shm/README.txt +++ b/mm/shm/README.txt @@ -79,7 +79,7 @@ Concepts int shmctl(int shmid, int cmd, struct shmid_ds *buf); In order for a process to make use of the memory region, it must be - "attached" the the process using: + "attached" the process using: FAR void *shmat(int shmid, FAR const void *shmaddr, int shmflg); diff --git a/mm/shm/shmat.c b/mm/shm/shmat.c index 6b677e5ddd..a81f974759 100644 --- a/mm/shm/shmat.c +++ b/mm/shm/shmat.c @@ -175,7 +175,7 @@ FAR void *shmat(int shmid, FAR const void *shmaddr, int shmflg) region->sr_ds.shm_nattch++; - /* Save the process ID of the the last operation */ + /* Save the process ID of the last operation */ region->sr_ds.shm_lpid = tcb->pid; diff --git a/mm/shm/shmctl.c b/mm/shm/shmctl.c index 4e5ac13c5f..0c468b36af 100644 --- a/mm/shm/shmctl.c +++ b/mm/shm/shmctl.c @@ -106,7 +106,7 @@ * to be stored in the structure pointed to by the buf argument. * * POSIX Deviations: - * - IPC_SET. Does not set the the shm_perm.uid or shm_perm.gid + * - IPC_SET. Does not set the shm_perm.uid or shm_perm.gid * members of the shmid_ds data structure associated with shmid * because user and group IDs are not yet supported by NuttX * - IPC_SET. Does not restrict the operation to processes with @@ -195,7 +195,7 @@ int shmctl(int shmid, int cmd, struct shmid_ds *buf) goto errout_with_semaphore; } - /* Save the process ID of the the last operation */ + /* Save the process ID of the last operation */ region = &g_shminfo.si_region[shmid]; region->sr_ds.shm_lpid = getpid(); diff --git a/mm/shm/shmdt.c b/mm/shm/shmdt.c index 55c2fd0554..28c993b641 100644 --- a/mm/shm/shmdt.c +++ b/mm/shm/shmdt.c @@ -173,7 +173,7 @@ int shmdt(FAR const void *shmaddr) region->sr_ds.shm_nattch--; } - /* Save the process ID of the the last operation */ + /* Save the process ID of the last operation */ region->sr_ds.shm_lpid = tcb->pid; diff --git a/net/arp/arp.h b/net/arp/arp.h index 46cd0039f8..4aca859476 100644 --- a/net/arp/arp.h +++ b/net/arp/arp.h @@ -297,7 +297,7 @@ int arp_poll(FAR struct net_driver_s *dev, devif_poll_callback_t callback); * * Description: * Called BEFORE an ARP request is sent. This function sets up the ARP - * response timeout before the the ARP request is sent so that there is + * response timeout before the ARP request is sent so that there is * no race condition when arp_wait() is called. * * Assumptions: diff --git a/net/arp/arp_notify.c b/net/arp/arp_notify.c index 112cb6614a..ebc7faaea6 100644 --- a/net/arp/arp_notify.c +++ b/net/arp/arp_notify.c @@ -72,7 +72,7 @@ static FAR struct arp_notify_s *g_arp_waiters; * * Description: * Called BEFORE an ARP request is sent. This function sets up the ARP - * response timeout before the the ARP request is sent so that there is + * response timeout before the ARP request is sent so that there is * no race condition when arp_wait() is called. * * Assumptions: diff --git a/net/devif/devif.h b/net/devif/devif.h index df45f7d8be..e90377dd58 100644 --- a/net/devif/devif.h +++ b/net/devif/devif.h @@ -477,7 +477,7 @@ void devif_iob_send(FAR struct net_driver_s *dev, FAR struct iob_s *buf, * * Description: * Called from socket logic in order to send a raw packet in response to - * an xmit or poll request from the the network interface driver. + * an xmit or poll request from the network interface driver. * * This is almost identical to calling devif_send() except that the data to * be sent is copied into dev->d_buf (vs. dev->d_appdata), since there is diff --git a/net/devif/devif_pktsend.c b/net/devif/devif_pktsend.c index 7e6c83a209..a2b7f07c50 100644 --- a/net/devif/devif_pktsend.c +++ b/net/devif/devif_pktsend.c @@ -84,7 +84,7 @@ * * Description: * Called from socket logic in order to send a raw packet in response to - * an xmit or poll request from the the network interface driver. + * an xmit or poll request from the network interface driver. * * This is almost identical to calling devif_send() except that the data to * be sent is copied into dev->d_buf (vs. dev->d_appdata), since there is diff --git a/net/netdev/netdev_verify.c b/net/netdev/netdev_verify.c index 14e05b97a0..4d859e2b98 100644 --- a/net/netdev/netdev_verify.c +++ b/net/netdev/netdev_verify.c @@ -71,7 +71,7 @@ bool netdev_verify(FAR struct net_driver_s *dev) net_lock(); for (chkdev = g_netdevices; chkdev != NULL; chkdev = chkdev->flink) { - /* Is the the network device that we are looking for? */ + /* Is the network device that we are looking for? */ if (chkdev == dev) { diff --git a/net/sixlowpan/sixlowpan_input.c b/net/sixlowpan/sixlowpan_input.c index 9739ab7f61..db4f1c2c9f 100644 --- a/net/sixlowpan/sixlowpan_input.c +++ b/net/sixlowpan/sixlowpan_input.c @@ -739,7 +739,7 @@ static int sixlowpan_dispatch(FAR struct ieee802154_driver_s *ieee) * * When the packet in the d_buf is fully reassembled, it will be provided * to the network as with any other received packet. d_len will be set - * the the length of the uncompressed, reassembled packet. + * the length of the uncompressed, reassembled packet. * * After the network processes the packet, d_len will be set to zero. * Network logic may also decide to send a response to the packet. In diff --git a/net/sixlowpan/sixlowpan_send.c b/net/sixlowpan/sixlowpan_send.c index db8337834c..a8fcdea983 100644 --- a/net/sixlowpan/sixlowpan_send.c +++ b/net/sixlowpan/sixlowpan_send.c @@ -312,7 +312,7 @@ int sixlowpan_send(FAR struct net_driver_s *dev, sinfo.s_cb->priv = (FAR void *)&sinfo; sinfo.s_cb->event = send_interrupt; - /* Notify the the IEEE802.15.4 MAC that we have data to send. */ + /* Notify the IEEE802.15.4 MAC that we have data to send. */ netdev_txnotify_dev(dev); diff --git a/net/socket/net_monitor.c b/net/socket/net_monitor.c index d44a6fe515..4f41acb591 100644 --- a/net/socket/net_monitor.c +++ b/net/socket/net_monitor.c @@ -241,7 +241,7 @@ int net_startmonitor(FAR struct socket *psock) conn->connection_devcb = NULL; conn->connection_event = NULL; - /* And return -ENOTCONN to indicate the the monitor was not started + /* And return -ENOTCONN to indicate the monitor was not started * because the socket was already disconnected. */ diff --git a/net/tcp/tcp.h b/net/tcp/tcp.h index 8d25bf6ff0..4b3bb85e75 100644 --- a/net/tcp/tcp.h +++ b/net/tcp/tcp.h @@ -259,7 +259,7 @@ struct tcp_conn_s * accept_private: This is private data that will be available to the * accept() handler when it is invoked with a point to this structure * as an argument. - * accept: This is the the pointer to the accept handler. + * accept: This is the pointer to the accept handler. */ FAR void *accept_private; @@ -273,7 +273,7 @@ struct tcp_conn_s * this structure as an argument. * connection_devcb: this is the allocated callback structure that is * used to - * connection_event: This is the the pointer to the connection event + * connection_event: This is the pointer to the connection event * handler. */ diff --git a/net/tcp/tcp_send.c b/net/tcp/tcp_send.c index a68394b24c..efe8be243f 100644 --- a/net/tcp/tcp_send.c +++ b/net/tcp/tcp_send.c @@ -550,7 +550,7 @@ void tcp_ack(FAR struct net_driver_s *dev, FAR struct tcp_conn_s *conn, tcp = TCPIPv6BUF; tcp_mss = TCP_IPv6_MSS(dev); - /* Set the the packet length for the TCP Maximum Segment Size */ + /* Set the packet length for the TCP Maximum Segment Size */ dev->d_len = IPv6TCP_HDRLEN + TCP_OPT_MSS_LEN; } @@ -566,7 +566,7 @@ void tcp_ack(FAR struct net_driver_s *dev, FAR struct tcp_conn_s *conn, tcp = TCPIPv4BUF; tcp_mss = TCP_IPv4_MSS(dev); - /* Set the the packet length for the TCP Maximum Segment Size */ + /* Set the packet length for the TCP Maximum Segment Size */ dev->d_len = IPv4TCP_HDRLEN + TCP_OPT_MSS_LEN; } diff --git a/net/tcp/tcp_send_buffered.c b/net/tcp/tcp_send_buffered.c index f88b9d5f2b..7b6d7e639e 100644 --- a/net/tcp/tcp_send_buffered.c +++ b/net/tcp/tcp_send_buffered.c @@ -230,7 +230,7 @@ static inline void psock_lost_connection(FAR struct socket *psock, static inline void send_ipselect(FAR struct net_driver_s *dev, FAR struct tcp_conn_s *conn) { - /* Which domain the the socket support */ + /* Which domain the socket support */ if (conn->domain == PF_INET) { diff --git a/net/tcp/tcp_send_unbuffered.c b/net/tcp/tcp_send_unbuffered.c index 9571819952..2ad73a02d4 100644 --- a/net/tcp/tcp_send_unbuffered.c +++ b/net/tcp/tcp_send_unbuffered.c @@ -181,7 +181,7 @@ static inline int send_timeout(FAR struct send_s *pstate) static inline void tcpsend_ipselect(FAR struct net_driver_s *dev, FAR struct tcp_conn_s *conn) { - /* Which domain the the socket support */ + /* Which domain the socket support */ if (conn->domain == PF_INET) { diff --git a/net/udp/udp_psock_sendto.c b/net/udp/udp_psock_sendto.c index a7b7a9d032..8cdac7ff4b 100644 --- a/net/udp/udp_psock_sendto.c +++ b/net/udp/udp_psock_sendto.c @@ -181,7 +181,7 @@ static inline void sendto_ipselect(FAR struct net_driver_s *dev, FAR struct socket *psock = pstate->st_sock; DEBUGASSERT(psock); - /* Which domain the the socket support */ + /* Which domain the socket support */ if (psock->s_domain == PF_INET) { diff --git a/sched/Kconfig b/sched/Kconfig index 6cefe0e121..c8725bae9f 100644 --- a/sched/Kconfig +++ b/sched/Kconfig @@ -101,7 +101,7 @@ config USEC_PER_TICK In the "normal" configuration where system time is provided by a periodic timer interrupt, the default system timer is expected to run at 100Hz or USEC_PER_TICK=10000. This setting must be defined - to inform of NuttX the interval that the the processor hardware is + to inform of NuttX the interval that the processor hardware is providing system timer interrupts to the OS. If SCHED_TICKLESS is selected, then there are no system timer @@ -110,7 +110,7 @@ config USEC_PER_TICK by clock_systimer() and the resolution of times that can be set for certain delays including watchdog timers and delayed work. In this case there is a trade-off: It is better to have the USEC_PER_TICK as - low as possible for higher timing resolution. However, the the time + low as possible for higher timing resolution. However, the time is currently held in 'unsigned int' on some systems, this may be 16-bits but on most contemporary systems it will be 32-bits. In either case, smaller values of USEC_PER_TICK will reduce the range diff --git a/sched/group/group_join.c b/sched/group/group_join.c index 5aecedebe7..7fb2a817fa 100644 --- a/sched/group/group_join.c +++ b/sched/group/group_join.c @@ -157,7 +157,7 @@ static inline int group_addmember(FAR struct task_group_s *group, pid_t pid) * * Assumptions: * - The parent task from which the group will be inherited is the task at - * the thead of the ready to run list. + * the head of the ready to run list. * - Called during thread creation in a safe context. No special precautions * are required here. * @@ -194,7 +194,7 @@ int group_bind(FAR struct pthread_tcb_s *tcb) * * Assumptions: * - The parent task from which the group will be inherited is the task at - * the thead of the ready to run list. + * the head of the ready to run list. * - Called during thread creation in a safe context. No special precautions * are required here. * diff --git a/sched/pthread/pthread_cleanup.c b/sched/pthread/pthread_cleanup.c index 6c71cd8c13..1fa0f6d0b6 100644 --- a/sched/pthread/pthread_cleanup.c +++ b/sched/pthread/pthread_cleanup.c @@ -127,7 +127,7 @@ static void pthread_cleanup_pop_tcb(FAR struct pthread_tcb_s *tcb, int execute) * - The thread calls pthread_cleanup_pop() with a non-zero execute argument. * * Input Parameters: - * routine - The cleanup routine to be pushed on the the cleanup stack. + * routine - The cleanup routine to be pushed on the cleanup stack. * arg - An argument that will accompany the callback. * execute - Execute the popped cleanup function immediately. * diff --git a/sched/sched/sched_resumescheduler.c b/sched/sched/sched_resumescheduler.c index 0c451e1577..52eaef8374 100644 --- a/sched/sched/sched_resumescheduler.c +++ b/sched/sched/sched_resumescheduler.c @@ -96,7 +96,7 @@ void sched_resume_scheduler(FAR struct tcb_s *tcb) #endif #ifdef CONFIG_SCHED_INSTRUMENTATION - /* Inidicate the the task has been resumed */ + /* Inidicate the task has been resumed */ sched_note_resume(tcb); #endif diff --git a/sched/sched/sched_setaffinity.c b/sched/sched/sched_setaffinity.c index c2d50af146..734745e177 100644 --- a/sched/sched/sched_setaffinity.c +++ b/sched/sched/sched_setaffinity.c @@ -137,7 +137,7 @@ int sched_setaffinity(pid_t pid, size_t cpusetsize, FAR const cpu_set_t *mask) if ((tcb->affinity & (1 << tcb->cpu)) == 0) { - /* No.. then we will need to move the task from the the assigned + /* No.. then we will need to move the task from the assigned * task list to some other ready to run list. * * sched_setpriority() will do just what we want... it will remove diff --git a/sched/sched/sched_setpriority.c b/sched/sched/sched_setpriority.c index bf273e1e5b..abad51b801 100644 --- a/sched/sched/sched_setpriority.c +++ b/sched/sched/sched_setpriority.c @@ -215,7 +215,7 @@ static void sched_readytorun_setpriority(FAR struct tcb_s *tcb, cpu = tcb->cpu; } - /* The running task is the the task at the head of the g_assignedtasks[] + /* The running task is the task at the head of the g_assignedtasks[] * associated with the selected CPU. */ diff --git a/sched/sched/sched_sporadic.c b/sched/sched/sched_sporadic.c index 086e27d44f..68996012fe 100644 --- a/sched/sched/sched_sporadic.c +++ b/sched/sched/sched_sporadic.c @@ -1153,7 +1153,7 @@ int sched_sporadic_suspend(FAR struct tcb_s *tcb) * * Returned Value: * The number if ticks remaining until the budget interval expires. - * Zero is returned if we are in the low-priority phase of the the + * Zero is returned if we are in the low-priority phase of the * replenishment interval. * * Assumptions: @@ -1182,7 +1182,7 @@ uint32_t sched_sporadic_process(FAR struct tcb_s *tcb, uint32_t ticks, return 0; } - /* Check if the the budget interval has elapse If 'ticks' is greater + /* Check if the budget interval has elapse If 'ticks' is greater * than the timeslice value, then we ignore any excess amount. * * 'ticks' should never be greater than the remaining timeslice. We try @@ -1231,7 +1231,7 @@ uint32_t sched_sporadic_process(FAR struct tcb_s *tcb, uint32_t ticks, return 1; } - /* Another possibility is the the budget interval is equal to the + /* Another possibility is the budget interval is equal to the * entire replenishment interval. This would not seem like such a * good thing to do, but is certainly permitted. */ diff --git a/sched/sched/sched_suspendscheduler.c b/sched/sched/sched_suspendscheduler.c index f938a82e01..857cb0be17 100644 --- a/sched/sched/sched_suspendscheduler.c +++ b/sched/sched/sched_suspendscheduler.c @@ -84,7 +84,7 @@ void sched_suspend_scheduler(FAR struct tcb_s *tcb) #endif #ifdef CONFIG_SCHED_INSTRUMENTATION - /* Inidicate the the task has been suspended */ + /* Inidicate the task has been suspended */ sched_note_suspend(tcb); #endif diff --git a/sched/task/task_getpid.c b/sched/task/task_getpid.c index 29ae703e87..51460f97f2 100644 --- a/sched/task/task_getpid.c +++ b/sched/task/task_getpid.c @@ -60,7 +60,7 @@ pid_t getpid(void) { FAR struct tcb_s *rtcb; - /* Get the the TCB at the head of the ready-to-run task list. That + /* Get the TCB at the head of the ready-to-run task list. That * will be the currently executing task. There is an exception to * this: Early in the start-up sequence, the ready-to-run list may be * empty! This case, of course, the start-up/IDLE thread with pid == 0 diff --git a/sched/task/task_terminate.c b/sched/task/task_terminate.c index 4a42c8232e..415ba8994b 100644 --- a/sched/task/task_terminate.c +++ b/sched/task/task_terminate.c @@ -146,7 +146,7 @@ int task_terminate(pid_t pid, bool nonblocking) cpu = sched_cpu_pause(dtcb); - /* Get the task list associated with the the thread's state and CPU */ + /* Get the task list associated with the thread's state and CPU */ tasklist = TLIST_HEAD(dtcb->task_state, cpu); #else diff --git a/sched/task/task_vfork.c b/sched/task/task_vfork.c index 73246ac76e..7c15868cc9 100644 --- a/sched/task/task_vfork.c +++ b/sched/task/task_vfork.c @@ -399,7 +399,7 @@ pid_t task_vforkstart(FAR struct task_tcb_s *child) /* Eliminate a race condition by disabling pre-emption. The child task * can be instantiated, but cannot run until we call waitpid(). This - * assures us that we cannot miss the the death-of-child signal (only + * assures us that we cannot miss the death-of-child signal (only * needed in the SMP case). */ diff --git a/sched/wdog/wd_create.c b/sched/wdog/wd_create.c index 6b9f944cd9..8bd6496153 100644 --- a/sched/wdog/wd_create.c +++ b/sched/wdog/wd_create.c @@ -82,7 +82,7 @@ WDOG_ID wd_create (void) flags = enter_critical_section(); /* If we are in an interrupt handler -OR- if the number of pre-allocated - * timer structures exceeds the reserve, then take the the next timer from + * timer structures exceeds the reserve, then take the next timer from * the head of the free list. */ diff --git a/sched/wdog/wd_start.c b/sched/wdog/wd_start.c index 227a7933bd..f94f9c2320 100644 --- a/sched/wdog/wd_start.c +++ b/sched/wdog/wd_start.c @@ -403,7 +403,7 @@ int wd_start(WDOG_ID wdog, int32_t delay, wdentry_t wdentry, int argc, ...) * * Parameters: * ticks - If CONFIG_SCHED_TICKLESS is defined then the number of ticks - * in the the interval that just expired is provided. Otherwise, + * in the interval that just expired is provided. Otherwise, * this function is called on each timer interrupt and a value of one * is implicit. * diff --git a/sched/wdog/wdog.h b/sched/wdog/wdog.h index 73e4d4b969..4b51b2355f 100644 --- a/sched/wdog/wdog.h +++ b/sched/wdog/wdog.h @@ -116,7 +116,7 @@ void weak_function wd_initialize(void); * * Parameters: * ticks - If CONFIG_SCHED_TICKLESS is defined then the number of ticks - * in the the interval that just expired is provided. Otherwise, + * in the interval that just expired is provided. Otherwise, * this function is called on each timer interrupt and a value of one * is implicit. * diff --git a/sched/wqueue/kwork_process.c b/sched/wqueue/kwork_process.c index 8354a81fca..2a5fab2611 100644 --- a/sched/wqueue/kwork_process.c +++ b/sched/wqueue/kwork_process.c @@ -185,7 +185,7 @@ void work_process(FAR struct kwork_wqueue_s *wqueue, systime_t period, int wndx) { /* This one is not ready. * - * NOTE that elapsed is relative to the the current time, + * NOTE that elapsed is relative to the current time, * not the time of beginning of this queue processing pass. * So it may need an adjustment. */ diff --git a/tools/Config.mk b/tools/Config.mk index f222cc0e0e..9a78aea743 100644 --- a/tools/Config.mk +++ b/tools/Config.mk @@ -156,7 +156,7 @@ endef # Example: $(call MOVEOBJ, prefix, directory) # # This is only used in directories that keep object files in sub-directories. -# Certain compilers (ZDS-II) always place the resulting files in the the +# Certain compilers (ZDS-II) always place the resulting files in the # directory where the compiler was invoked with not option to generate objects # in a different location. diff --git a/tools/README.txt b/tools/README.txt index 282be57b42..e44f64a8d4 100644 --- a/tools/README.txt +++ b/tools/README.txt @@ -682,7 +682,7 @@ refresh.sh The steps to refresh the file taken by refresh.sh are: 1. Make tools/cmpconfig if it is not already built. - 2. Copy the the defconfig file to the top-level NuttX + 2. Copy the defconfig file to the top-level NuttX directory as .config (being careful to save any previous .config file that you might want to keep!). 3. Execute 'make oldconfig' to update the configuration. -- GitLab From 2c807e47507c25d67ba4938258447cd957baa93d Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 12 May 2017 02:48:30 +0000 Subject: [PATCH 793/990] Makefile edited online with Bitbucket --- configs/ea3131/locked/Makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/configs/ea3131/locked/Makefile b/configs/ea3131/locked/Makefile index e8d1f17934..92b9caff5d 100644 --- a/configs/ea3131/locked/Makefile +++ b/configs/ea3131/locked/Makefile @@ -56,7 +56,7 @@ ifeq ($(WINTOOL),y) PASS1_LDSCRIPT = -T "${shell cygpath -w $(TOPDIR)$(DELIM)configs$(DELIM)$(CONFIG_ARCH_BOARD)$(DELIM)locked$(DELIM)ld-locked.inc}" else # Linux/Cygwin-native toolchain - PASS1_LIBPATHS += -L"(TOPDIR)$(DELIM)lib" + PASS1_LIBPATHS += -L"$(TOPDIR)$(DELIM)lib" PASS1_LDSCRIPT = -T$(TOPDIR)$(DELIM)configs$(DELIM)$(CONFIG_ARCH_BOARD)$(DELIM)locked$(DELIM)ld-locked.inc endif -- GitLab From 46851b33b2842129af794f38e70f3b0f0dd45dda Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Fri, 12 May 2017 15:54:48 +0300 Subject: [PATCH 794/990] STM32L4: port stm32l4_serial_get_uart function from STM32F7 --- arch/arm/src/stm32l4/stm32l4_serial.c | 47 ++++++++++++++++++++++++--- arch/arm/src/stm32l4/stm32l4_uart.h | 11 +++++++ 2 files changed, 54 insertions(+), 4 deletions(-) diff --git a/arch/arm/src/stm32l4/stm32l4_serial.c b/arch/arm/src/stm32l4/stm32l4_serial.c index 955fb548e1..15b9cbd120 100644 --- a/arch/arm/src/stm32l4/stm32l4_serial.c +++ b/arch/arm/src/stm32l4/stm32l4_serial.c @@ -200,6 +200,10 @@ struct stm32l4_serial_s uint16_t ie; /* Saved interrupt mask bits value */ uint16_t sr; /* Saved status bits */ + /* Has been initialized and HW is setup. */ + + bool initialized; + /* If termios are supported, then the following fields may vary at * runtime. */ @@ -1169,6 +1173,11 @@ static int stm32l4serial_setup(FAR struct uart_dev_s *dev) /* Set up the cached interrupt enables value */ priv->ie = 0; + + /* Mark device as initialized. */ + + priv->initialized = true; + return OK; } @@ -1279,6 +1288,10 @@ static void stm32l4serial_shutdown(FAR struct uart_dev_s *dev) FAR struct stm32l4_serial_s *priv = (FAR struct stm32l4_serial_s *)dev->priv; uint32_t regval; + /* Mark device as uninitialized. */ + + priv->initialized = false; + /* Disable all interrupts */ stm32l4serial_disableusartint(priv, NULL); @@ -2327,6 +2340,32 @@ static int stm32l4serial_pmprepare(FAR struct pm_callback_s *cb, int domain, #ifdef USE_SERIALDRIVER +/**************************************************************************** + * Name: stm32l4_serial_get_uart + * + * Description: + * Get serial driver structure for STM32 USART + * + ****************************************************************************/ + +FAR uart_dev_t *stm32l4_serial_get_uart(int uart_num) +{ + int uart_idx = uart_num - 1; + + if (uart_idx < 0 || uart_idx >= STM32L4_NUSART+STM32L4_NUART || \ + !uart_devs[uart_idx]) + { + return NULL; + } + + if (!uart_devs[uart_idx]->initialized) + { + return NULL; + } + + return &uart_devs[uart_idx]->dev; +} + /**************************************************************************** * Name: up_earlyserialinit * @@ -2360,10 +2399,10 @@ void up_earlyserialinit(void) #endif #endif /* HAVE UART */ } -#endif +#endif /* USE_EARLYSERIALINIT */ /**************************************************************************** - * Name: stm32l4serial_getregit + * Name: up_serialinit * * Description: * Register serial console and serial ports. This assumes @@ -2441,7 +2480,7 @@ void up_serialinit(void) } /**************************************************************************** - * Name: stm32l4serial_dmapoll + * Name: stm32l4_serial_dma_poll * * Description: * Checks receive DMA buffers for received bytes that have not accumulated @@ -2452,7 +2491,7 @@ void up_serialinit(void) ****************************************************************************/ #ifdef SERIAL_HAVE_DMA -void stm32l4serial_dmapoll(void) +void stm32l4_serial_dma_poll(void) { irqstate_t flags; diff --git a/arch/arm/src/stm32l4/stm32l4_uart.h b/arch/arm/src/stm32l4/stm32l4_uart.h index 286ba8eeb8..218e0c6b6f 100644 --- a/arch/arm/src/stm32l4/stm32l4_uart.h +++ b/arch/arm/src/stm32l4/stm32l4_uart.h @@ -41,6 +41,7 @@ ************************************************************************************/ #include +#include #include "chip.h" @@ -236,6 +237,16 @@ extern "C" * Public Functions ************************************************************************************/ +/************************************************************************************ + * Name: stm32l4_serial_get_uart + * + * Description: + * Get serial driver structure for STM32 USART + * + ************************************************************************************/ + +FAR uart_dev_t *stm32l4_serial_get_uart(int uart_num); + /************************************************************************************ * Name: stm32l4_serial_dma_poll * -- GitLab From 0fc068cc9c5ab6832478561804b667f477a31cba Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 12 May 2017 06:58:33 -0600 Subject: [PATCH 795/990] syslog: Avoid flushing syslog_stream buffer, if possible, until lib_vsprintf() completely parses the format. This assures that the flush will flush the entire output, even data that may potentially follow the linefeed. And, in that case, it cannot be interleaved with other devug output. Suggested by Jussi Kivilinna. --- TODO | 2 +- drivers/syslog/syslog_stream.c | 100 ++++++++++++++++----------------- drivers/syslog/vsyslog.c | 6 +- 3 files changed, 52 insertions(+), 56 deletions(-) diff --git a/TODO b/TODO index c0b3443a83..25e5127b8d 100644 --- a/TODO +++ b/TODO @@ -490,7 +490,7 @@ o pthreads (sched/pthreads) Status: Not really open. This is just the way it is. Priority: Nothing additional is planned. - Title: PTHREAD FILES IN WRONG LOCATTION + Title: PTHREAD FILES IN WRONG LOCATION Description: There are many pthread interface functions in files located in sched/pthread. These should be moved from that location to libc/pthread. In the flat build, this really does not matter, diff --git a/drivers/syslog/syslog_stream.c b/drivers/syslog/syslog_stream.c index ac7e144ceb..b463a3e5ef 100644 --- a/drivers/syslog/syslog_stream.c +++ b/drivers/syslog/syslog_stream.c @@ -54,6 +54,46 @@ * Private Functions ****************************************************************************/ +/**************************************************************************** + * Name: syslogstream_flush + ****************************************************************************/ + +#ifdef CONFIG_SYSLOG_BUFFER +static int syslogstream_flush(FAR struct lib_syslogstream_s *stream) +{ + FAR struct iob_s *iob; + int ret = OK; + + DEBUGASSERT(stream != NULL); + iob = stream->iob; + + /* Do we have an IO buffer? Is there anything buffered? */ + + if (iob != NULL && iob->io_len > 0) + { + /* Yes write the buffered data */ + + do + { + ssize_t nbytes = syslog_write((FAR const char *)iob->io_data, + (size_t)iob->io_len); + if (nbytes < 0) + { + ret = -get_errno(); + } + else + { + iob->io_len = 0; + ret = OK; + } + } + while (ret == -EINTR); + } + + return ret; +} +#endif + /**************************************************************************** * Name: syslogstream_putc ****************************************************************************/ @@ -88,7 +128,7 @@ static void syslogstream_putc(FAR struct lib_outstream_s *this, int ch) { /* Yes.. then flush the buffer */ - (void)this->flush(this); + syslogstream_flush(stream); } } else @@ -123,48 +163,6 @@ static void syslogstream_putc(FAR struct lib_outstream_s *this, int ch) } } -/**************************************************************************** - * Name: syslogstream_flush - ****************************************************************************/ - -#ifdef CONFIG_SYSLOG_BUFFER -static int syslogstream_flush(FAR struct lib_outstream_s *this) -{ - FAR struct lib_syslogstream_s *stream; - FAR struct iob_s *iob; - int ret = OK; - - DEBUGASSERT(this != NULL); - stream = (FAR struct lib_syslogstream_s *)this; - iob = stream->iob; - - /* Do we have an IO buffer? Is there anything buffered? */ - - if (iob != NULL && iob->io_len > 0) - { - /* Yes write the buffered data */ - - do - { - ssize_t nbytes = syslog_write((FAR const char *)iob->io_data, - (size_t)iob->io_len); - if (nbytes < 0) - { - ret = -get_errno(); - } - else - { - iob->io_len = 0; - ret = OK; - } - } - while (ret == -EINTR); - } - - return ret; -} -#endif - /**************************************************************************** * Public Functions ****************************************************************************/ @@ -187,17 +185,19 @@ static int syslogstream_flush(FAR struct lib_outstream_s *this) void syslogstream_create(FAR struct lib_syslogstream_s *stream) { - DEBUGASSERT(stream != NULL); - #ifdef CONFIG_SYSLOG_BUFFER FAR struct iob_s *iob; +#endif + + DEBUGASSERT(stream != NULL); /* Initialize the common fields */ stream->public.put = syslogstream_putc; - stream->public.flush = syslogstream_flush; + stream->public.flush = lib_noflush; stream->public.nput = 0; +#ifdef CONFIG_SYSLOG_BUFFER /* Allocate an IOB */ iob = iob_alloc(true); @@ -211,10 +211,6 @@ void syslogstream_create(FAR struct lib_syslogstream_s *stream) iob->io_offset = 0; iob->io_pktlen = 0; } -#else - stream->public.put = syslogstream_putc; - stream->public.flush = lib_noflush; - stream->public.nput = 0; #endif } @@ -242,6 +238,10 @@ void syslogstream_destroy(FAR struct lib_syslogstream_s *stream) if (stream->iob != NULL) { + /* Flush the output buffered in the IOB */ + + syslogstream_flush(stream); + /* Free the IOB */ iob_free(stream->iob); diff --git a/drivers/syslog/vsyslog.c b/drivers/syslog/vsyslog.c index 0b993b7186..76ba239968 100644 --- a/drivers/syslog/vsyslog.c +++ b/drivers/syslog/vsyslog.c @@ -131,12 +131,8 @@ int _vsyslog(int priority, FAR const IPTR char *fmt, FAR va_list *ap) ret = lib_vsprintf(&stream.public, fmt, *ap); - /* Flush the output */ - - stream.public.flush(&stream.public); - #ifdef CONFIG_SYSLOG_BUFFER - /* Destroy the syslog stream buffer */ + /* Flush and destroy the syslog stream buffer */ if (priority != LOG_EMERG) { -- GitLab From 1c9859520fc3b6d6bf5ad425a546a93d94695ebb Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 12 May 2017 07:31:50 -0600 Subject: [PATCH 796/990] syslog: There is yet another place where the output can get split. That is in syslog_dev_write(): It will break up the stream to insert a CR before the LF. This can that can be avoid be generating the CR-LF sequence in the buffer and then detecting and ignoring valid CR-LF sequences, rather than expecting syslog_dev_write() to insert the CR in this case. I don't like the idea that syslog_dev_write() still scans the entire output buffer to expand CR-LF sequence. This seems really wasteful, especially in this case where we can be sure that the is no CR or LF without a matching LF or CR. Bu, I think, the existing behavior in syslog_dev_write() must be retained because it is needed in other contexts. --- drivers/syslog/syslog_device.c | 15 +++++++++- drivers/syslog/syslog_stream.c | 55 ++++++++++++++++++++++++---------- 2 files changed, 53 insertions(+), 17 deletions(-) diff --git a/drivers/syslog/syslog_device.c b/drivers/syslog/syslog_device.c index 0d49ea4e8a..4cc65734ad 100644 --- a/drivers/syslog/syslog_device.c +++ b/drivers/syslog/syslog_device.c @@ -518,9 +518,22 @@ ssize_t syslog_dev_write(FAR const char *buffer, size_t buflen) remaining > 0; endptr++, remaining--) { + bool crlf = false; + + /* Check for a CR-LF sequence */ + + if (remaining > 1 && + ((endptr[0] == '\r' && endptr[1] == '\n') || + (endptr[0] == '\n' && endptr[1] == '\r'))) + { + endptr++; + remaining--; + crlf = true; + } + /* Special case carriage return and line feed */ - if (*endptr == '\r' || *endptr == '\n') + if (!crlf && (*endptr == '\r' || *endptr == '\n')) { /* Write everything up to this point, ignore the special * character. diff --git a/drivers/syslog/syslog_stream.c b/drivers/syslog/syslog_stream.c index b463a3e5ef..2119b9e917 100644 --- a/drivers/syslog/syslog_stream.c +++ b/drivers/syslog/syslog_stream.c @@ -94,6 +94,33 @@ static int syslogstream_flush(FAR struct lib_syslogstream_s *stream) } #endif +/**************************************************************************** + * Name: syslogstream_addchar + ****************************************************************************/ + +static void syslogstream_addchar(FAR struct lib_syslogstream_s *stream, int ch) +{ + FAR struct iob_s *iob = stream->iob; + + /* Add the incoming character to the buffer */ + + iob->io_data[iob->io_len] = ch; + iob->io_len++; + + /* Increment the total number of bytes buffered. */ + + stream->public.nput++; + + /* Is the buffer full? */ + + if (iob->io_len >= CONFIG_IOB_BUFSIZE) + { + /* Yes.. then flush the buffer */ + + syslogstream_flush(stream); + } +} + /**************************************************************************** * Name: syslogstream_putc ****************************************************************************/ @@ -105,31 +132,27 @@ static void syslogstream_putc(FAR struct lib_outstream_s *this, int ch) if (ch != '\r') { #ifdef CONFIG_SYSLOG_BUFFER - FAR struct lib_syslogstream_s *stream; - FAR struct iob_s *iob; + FAR struct lib_syslogstream_s *stream = + (FAR struct lib_syslogstream_s *)this; - DEBUGASSERT(this != NULL); - stream = (FAR struct lib_syslogstream_s *)this; - iob = stream->iob; + DEBUGASSERT(stream != NULL); /* Do we have an IO buffer? */ - if (iob != NULL) + if (stream->iob != NULL) { - /* Yes.. Add the incoming character to the buffer */ - - iob->io_data[iob->io_len] = ch; - iob->io_len++; - this->nput++; - - /* Is the buffer full? */ + /* Is this a linefeed? */ - if (iob->io_len >= CONFIG_IOB_BUFSIZE) + if (ch == '\n') { - /* Yes.. then flush the buffer */ + /* Yes... pre-pend carriage return */ - syslogstream_flush(stream); + syslogstream_addchar(stream, '\r'); } + + /* Add the incoming character to the buffer */ + + syslogstream_addchar(stream, ch); } else #endif -- GitLab From c84a3e3519caddcbfa6f371793342cff2a3a9235 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 12 May 2017 07:57:45 -0600 Subject: [PATCH 797/990] Bitbucket Issue 47: Some of last syslog changes needed to be condition on #ifdef CONFIG_SYSLOG_BUFFER in order to be built without syslog buffering enabled. --- drivers/syslog/syslog_stream.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/drivers/syslog/syslog_stream.c b/drivers/syslog/syslog_stream.c index 2119b9e917..a14a5d4f12 100644 --- a/drivers/syslog/syslog_stream.c +++ b/drivers/syslog/syslog_stream.c @@ -98,6 +98,7 @@ static int syslogstream_flush(FAR struct lib_syslogstream_s *stream) * Name: syslogstream_addchar ****************************************************************************/ +#ifdef CONFIG_SYSLOG_BUFFER static void syslogstream_addchar(FAR struct lib_syslogstream_s *stream, int ch) { FAR struct iob_s *iob = stream->iob; @@ -120,6 +121,7 @@ static void syslogstream_addchar(FAR struct lib_syslogstream_s *stream, int ch) syslogstream_flush(stream); } } +#endif /**************************************************************************** * Name: syslogstream_putc -- GitLab From 853d332b6cb361072028510b7d52775741a74765 Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Fri, 12 May 2017 11:23:16 -0300 Subject: [PATCH 798/990] Move CAN subsystem to its own directory and put device drivers there Signed-off-by: Alan Carvalho de Assis --- Documentation/NuttxPortingGuide.html | 2 +- arch/arm/src/lpc17xx/lpc17_can.c | 2 +- arch/arm/src/sama5/sam_can.c | 2 +- arch/arm/src/sama5/sam_can.h | 2 +- arch/arm/src/samv7/sam_mcan.c | 2 +- arch/arm/src/samv7/sam_mcan.h | 2 +- arch/arm/src/stm32/stm32_can.c | 2 +- arch/arm/src/stm32/stm32_can.h | 2 +- arch/arm/src/stm32l4/stm32l4_can.c | 2 +- arch/arm/src/stm32l4/stm32l4_can.h | 2 +- configs/clicker2-stm32/src/stm32_can.c | 2 +- configs/nucleo-f303re/src/stm32_can.c | 2 +- configs/olimex-lpc1766stk/src/lpc17_can.c | 2 +- configs/olimex-stm32-e407/src/stm32_can.c | 2 +- configs/olimex-stm32-h405/src/stm32_can.c | 2 +- configs/olimex-stm32-h407/src/stm32_can.c | 2 +- configs/olimex-stm32-p107/src/stm32_can.c | 2 +- configs/olimex-stm32-p207/src/stm32_can.c | 2 +- configs/olimex-stm32-p407/src/stm32_can.c | 2 +- configs/olimexino-stm32/src/stm32_can.c | 2 +- configs/sama5d3-xplained/src/sam_can.c | 2 +- configs/sama5d3x-ek/src/sam_can.c | 2 +- configs/same70-xplained/src/sam_mcan.c | 2 +- configs/samv71-xult/src/sam_mcan.c | 2 +- configs/shenzhou/src/stm32_can.c | 2 +- configs/stm3210e-eval/src/stm32_can.c | 2 +- configs/stm3220g-eval/src/stm32_can.c | 2 +- configs/stm3240g-eval/src/stm32_can.c | 2 +- configs/stm32f4discovery/src/stm32_can.c | 2 +- configs/viewtool-stm32f107/src/stm32_can.c | 2 +- configs/zkit-arm-1769/src/lpc17_can.c | 2 +- drivers/Kconfig | 125 +------------------- drivers/Makefile | 1 + drivers/README.txt | 6 +- drivers/can/Kconfig | 127 +++++++++++++++++++++ drivers/can/Make.defs | 52 +++++++++ drivers/{ => can}/can.c | 0 include/nuttx/analog/adc.h | 2 +- include/nuttx/analog/dac.h | 2 +- include/nuttx/{drivers => can}/can.h | 0 include/nuttx/fs/ioctl.h | 2 +- 41 files changed, 220 insertions(+), 159 deletions(-) create mode 100644 drivers/can/Kconfig create mode 100644 drivers/can/Make.defs rename drivers/{ => can}/can.c (100%) rename include/nuttx/{drivers => can}/can.h (100%) diff --git a/Documentation/NuttxPortingGuide.html b/Documentation/NuttxPortingGuide.html index e6d3134dee..c1db0c7eeb 100644 --- a/Documentation/NuttxPortingGuide.html +++ b/Documentation/NuttxPortingGuide.html @@ -4545,7 +4545,7 @@ void board_autoled_off(int led);

        • Interface Definition. - The header file for the NuttX CAN driver resides at include/nuttx/drivers/can.h. + The header file for the NuttX CAN driver resides at include/nuttx/can/can.h. This header file includes both the application level interface to the CAN driver as well as the interface between the "upper half" and "lower half" drivers. The CAN module uses a standard character driver framework.
        • diff --git a/arch/arm/src/lpc17xx/lpc17_can.c b/arch/arm/src/lpc17xx/lpc17_can.c index 11ac88cc04..94f1987280 100644 --- a/arch/arm/src/lpc17xx/lpc17_can.c +++ b/arch/arm/src/lpc17xx/lpc17_can.c @@ -57,7 +57,7 @@ #include #include #include -#include +#include #include "up_internal.h" #include "up_arch.h" diff --git a/arch/arm/src/sama5/sam_can.c b/arch/arm/src/sama5/sam_can.c index 4020055e89..029a4df1c6 100644 --- a/arch/arm/src/sama5/sam_can.c +++ b/arch/arm/src/sama5/sam_can.c @@ -60,7 +60,7 @@ #include #include -#include +#include #include "up_internal.h" #include "up_arch.h" diff --git a/arch/arm/src/sama5/sam_can.h b/arch/arm/src/sama5/sam_can.h index 5a26fe8314..83a08f756b 100644 --- a/arch/arm/src/sama5/sam_can.h +++ b/arch/arm/src/sama5/sam_can.h @@ -45,7 +45,7 @@ #include "chip.h" #include "chip/sam_can.h" -#include +#include #if defined(CONFIG_CAN) && (defined(CONFIG_SAMA5_CAN0) || defined(CONFIG_SAMA5_CAN1)) diff --git a/arch/arm/src/samv7/sam_mcan.c b/arch/arm/src/samv7/sam_mcan.c index 7d16f0898d..d4807941a4 100644 --- a/arch/arm/src/samv7/sam_mcan.c +++ b/arch/arm/src/samv7/sam_mcan.c @@ -56,7 +56,7 @@ #include #include #include -#include +#include #include "cache.h" #include "up_internal.h" diff --git a/arch/arm/src/samv7/sam_mcan.h b/arch/arm/src/samv7/sam_mcan.h index 07ecdd71ad..3672547788 100644 --- a/arch/arm/src/samv7/sam_mcan.h +++ b/arch/arm/src/samv7/sam_mcan.h @@ -45,7 +45,7 @@ #include "chip.h" #include "chip/sam_mcan.h" -#include +#include #if defined(CONFIG_CAN) && (defined(CONFIG_SAMV7_MCAN0) || \ defined(CONFIG_SAMV7_MCAN1)) diff --git a/arch/arm/src/stm32/stm32_can.c b/arch/arm/src/stm32/stm32_can.c index d90e5cd06d..4497dd9766 100644 --- a/arch/arm/src/stm32/stm32_can.c +++ b/arch/arm/src/stm32/stm32_can.c @@ -53,7 +53,7 @@ #include #include #include -#include +#include #include "up_internal.h" #include "up_arch.h" diff --git a/arch/arm/src/stm32/stm32_can.h b/arch/arm/src/stm32/stm32_can.h index 765dc95c0c..f06231ab60 100644 --- a/arch/arm/src/stm32/stm32_can.h +++ b/arch/arm/src/stm32/stm32_can.h @@ -45,7 +45,7 @@ #include "chip.h" #include "chip/stm32_can.h" -#include +#include /************************************************************************************ * Pre-processor Definitions diff --git a/arch/arm/src/stm32l4/stm32l4_can.c b/arch/arm/src/stm32l4/stm32l4_can.c index ed14ca4360..7667481c6c 100644 --- a/arch/arm/src/stm32l4/stm32l4_can.c +++ b/arch/arm/src/stm32l4/stm32l4_can.c @@ -57,7 +57,7 @@ #include #include #include -#include +#include #include "up_internal.h" #include "up_arch.h" diff --git a/arch/arm/src/stm32l4/stm32l4_can.h b/arch/arm/src/stm32l4/stm32l4_can.h index 86eb26fb65..b5db2c4286 100644 --- a/arch/arm/src/stm32l4/stm32l4_can.h +++ b/arch/arm/src/stm32l4/stm32l4_can.h @@ -49,7 +49,7 @@ #include "chip.h" #include "chip/stm32l4_can.h" -#include +#include /************************************************************************************ * Pre-processor Definitions diff --git a/configs/clicker2-stm32/src/stm32_can.c b/configs/clicker2-stm32/src/stm32_can.c index 2c3b98ea6f..003c0fd390 100644 --- a/configs/clicker2-stm32/src/stm32_can.c +++ b/configs/clicker2-stm32/src/stm32_can.c @@ -42,7 +42,7 @@ #include #include -#include +#include #include #include "stm32.h" diff --git a/configs/nucleo-f303re/src/stm32_can.c b/configs/nucleo-f303re/src/stm32_can.c index e1f1a2d713..1541c8b2ac 100644 --- a/configs/nucleo-f303re/src/stm32_can.c +++ b/configs/nucleo-f303re/src/stm32_can.c @@ -45,7 +45,7 @@ #include #include -#include +#include #include "stm32.h" diff --git a/configs/olimex-lpc1766stk/src/lpc17_can.c b/configs/olimex-lpc1766stk/src/lpc17_can.c index a9e1b68c88..fcc99e54dd 100644 --- a/configs/olimex-lpc1766stk/src/lpc17_can.c +++ b/configs/olimex-lpc1766stk/src/lpc17_can.c @@ -42,7 +42,7 @@ #include #include -#include +#include #include #include "chip.h" diff --git a/configs/olimex-stm32-e407/src/stm32_can.c b/configs/olimex-stm32-e407/src/stm32_can.c index b5c7bce8bc..f4e941bf5a 100644 --- a/configs/olimex-stm32-e407/src/stm32_can.c +++ b/configs/olimex-stm32-e407/src/stm32_can.c @@ -42,7 +42,7 @@ #include #include -#include +#include #include #include "stm32.h" diff --git a/configs/olimex-stm32-h405/src/stm32_can.c b/configs/olimex-stm32-h405/src/stm32_can.c index 6f361af940..42164d8959 100644 --- a/configs/olimex-stm32-h405/src/stm32_can.c +++ b/configs/olimex-stm32-h405/src/stm32_can.c @@ -42,7 +42,7 @@ #include #include -#include +#include #include diff --git a/configs/olimex-stm32-h407/src/stm32_can.c b/configs/olimex-stm32-h407/src/stm32_can.c index b482342e61..a14d0f3f50 100644 --- a/configs/olimex-stm32-h407/src/stm32_can.c +++ b/configs/olimex-stm32-h407/src/stm32_can.c @@ -42,7 +42,7 @@ #include #include -#include +#include #include #include "stm32.h" diff --git a/configs/olimex-stm32-p107/src/stm32_can.c b/configs/olimex-stm32-p107/src/stm32_can.c index 9889f836b2..85d36cf515 100644 --- a/configs/olimex-stm32-p107/src/stm32_can.c +++ b/configs/olimex-stm32-p107/src/stm32_can.c @@ -42,7 +42,7 @@ #include #include -#include +#include #include #include "chip.h" diff --git a/configs/olimex-stm32-p207/src/stm32_can.c b/configs/olimex-stm32-p207/src/stm32_can.c index ab20e9fcb9..0f9e2dffe2 100644 --- a/configs/olimex-stm32-p207/src/stm32_can.c +++ b/configs/olimex-stm32-p207/src/stm32_can.c @@ -42,7 +42,7 @@ #include #include -#include +#include #include #include "stm32.h" diff --git a/configs/olimex-stm32-p407/src/stm32_can.c b/configs/olimex-stm32-p407/src/stm32_can.c index 763df54e78..373d15e969 100644 --- a/configs/olimex-stm32-p407/src/stm32_can.c +++ b/configs/olimex-stm32-p407/src/stm32_can.c @@ -42,7 +42,7 @@ #include #include -#include +#include #include #include "stm32.h" diff --git a/configs/olimexino-stm32/src/stm32_can.c b/configs/olimexino-stm32/src/stm32_can.c index 862def8094..5e942ea6fc 100644 --- a/configs/olimexino-stm32/src/stm32_can.c +++ b/configs/olimexino-stm32/src/stm32_can.c @@ -43,7 +43,7 @@ #include #include -#include +#include #include #include "chip.h" diff --git a/configs/sama5d3-xplained/src/sam_can.c b/configs/sama5d3-xplained/src/sam_can.c index cbd76837d8..f9e39e8612 100644 --- a/configs/sama5d3-xplained/src/sam_can.c +++ b/configs/sama5d3-xplained/src/sam_can.c @@ -42,7 +42,7 @@ #include #include -#include +#include #include #include "chip.h" diff --git a/configs/sama5d3x-ek/src/sam_can.c b/configs/sama5d3x-ek/src/sam_can.c index 4fc441f110..3c083a9ff1 100644 --- a/configs/sama5d3x-ek/src/sam_can.c +++ b/configs/sama5d3x-ek/src/sam_can.c @@ -42,7 +42,7 @@ #include #include -#include +#include #include #include "chip.h" diff --git a/configs/same70-xplained/src/sam_mcan.c b/configs/same70-xplained/src/sam_mcan.c index 5a96930a63..f09f8504c7 100644 --- a/configs/same70-xplained/src/sam_mcan.c +++ b/configs/same70-xplained/src/sam_mcan.c @@ -43,7 +43,7 @@ #include #include -#include +#include #include #include "sam_mcan.h" diff --git a/configs/samv71-xult/src/sam_mcan.c b/configs/samv71-xult/src/sam_mcan.c index f17d9ccb20..d977e8f16d 100644 --- a/configs/samv71-xult/src/sam_mcan.c +++ b/configs/samv71-xult/src/sam_mcan.c @@ -43,7 +43,7 @@ #include #include -#include +#include #include #include "sam_mcan.h" diff --git a/configs/shenzhou/src/stm32_can.c b/configs/shenzhou/src/stm32_can.c index 6a08cc1fc0..34b1c9e7c3 100644 --- a/configs/shenzhou/src/stm32_can.c +++ b/configs/shenzhou/src/stm32_can.c @@ -42,7 +42,7 @@ #include #include -#include +#include #include #include "chip.h" diff --git a/configs/stm3210e-eval/src/stm32_can.c b/configs/stm3210e-eval/src/stm32_can.c index 06e24930ea..6da4ee58d6 100644 --- a/configs/stm3210e-eval/src/stm32_can.c +++ b/configs/stm3210e-eval/src/stm32_can.c @@ -42,7 +42,7 @@ #include #include -#include +#include #include #include "chip.h" diff --git a/configs/stm3220g-eval/src/stm32_can.c b/configs/stm3220g-eval/src/stm32_can.c index e362ad95c5..e1264c9e52 100644 --- a/configs/stm3220g-eval/src/stm32_can.c +++ b/configs/stm3220g-eval/src/stm32_can.c @@ -42,7 +42,7 @@ #include #include -#include +#include #include #include "chip.h" diff --git a/configs/stm3240g-eval/src/stm32_can.c b/configs/stm3240g-eval/src/stm32_can.c index 3ebae0dfa3..82697c7ed5 100644 --- a/configs/stm3240g-eval/src/stm32_can.c +++ b/configs/stm3240g-eval/src/stm32_can.c @@ -42,7 +42,7 @@ #include #include -#include +#include #include #include "chip.h" diff --git a/configs/stm32f4discovery/src/stm32_can.c b/configs/stm32f4discovery/src/stm32_can.c index 702dff902f..5464205b66 100644 --- a/configs/stm32f4discovery/src/stm32_can.c +++ b/configs/stm32f4discovery/src/stm32_can.c @@ -42,7 +42,7 @@ #include #include -#include +#include #include #include "chip.h" diff --git a/configs/viewtool-stm32f107/src/stm32_can.c b/configs/viewtool-stm32f107/src/stm32_can.c index 462e5a72ba..0ddfaa074d 100644 --- a/configs/viewtool-stm32f107/src/stm32_can.c +++ b/configs/viewtool-stm32f107/src/stm32_can.c @@ -42,7 +42,7 @@ #include #include -#include +#include #include #include "chip.h" diff --git a/configs/zkit-arm-1769/src/lpc17_can.c b/configs/zkit-arm-1769/src/lpc17_can.c index 6b4a1021f8..3815c7f1ef 100644 --- a/configs/zkit-arm-1769/src/lpc17_can.c +++ b/configs/zkit-arm-1769/src/lpc17_can.c @@ -47,7 +47,7 @@ #include #include -#include +#include #include #include "chip.h" diff --git a/drivers/Kconfig b/drivers/Kconfig index d7bc265374..937a5e13fe 100644 --- a/drivers/Kconfig +++ b/drivers/Kconfig @@ -157,130 +157,11 @@ menuconfig CAN default n ---help--- This selection enables building of the "upper-half" CAN driver. - See include/nuttx/drivers/can.h for further CAN driver information. + See include/nuttx/can/can.h for further CAN driver information. if CAN - -config CAN_EXTID - bool "CAN extended IDs" - default n - ---help--- - Enables support for the 28-bit extended ID. Default Standard 11-bit - IDs. - -config ARCH_HAVE_CAN_ERRORS - bool - default n - -config CAN_ERRORS - bool "CAN error reporting" - default n - depends on ARCH_HAVE_CAN_ERRORS - ---help--- - Support CAN error reporting. If this option is selected then CAN - error reporting is enabled. In the event of an error, the ch_error - bit will be set in the CAN message and the following message payload - will include a more detailed description of certain errors. - -config CAN_FD - bool "CAN FD" - default n - ---help--- - Enables support for the CAN_FD mode. - -config CAN_FIFOSIZE - int "CAN driver I/O buffer size" - default 8 - ---help--- - The size of the circular buffer of CAN messages. Default: 8 - -config CAN_NPENDINGRTR - int "Number of pending RTRs" - default 4 - ---help--- - The size of the list of pending RTR requests. Default: 4 - -config CAN_TXREADY - bool "can_txready interface" - default n - select SCHED_WORKQUEUE - ---help--- - This selection enables the can_txready() interface. This interface - is needed only for CAN hardware that supports queing of outgoing - messages in a H/W FIFO. - - The CAN upper half driver also supports a queue of output messages - in a S/W FIFO. Messages are added to that queue when when - can_write() is called and removed from the queue in can_txdone() - when each TX message is complete. - - After each message is added to the S/W FIFO, the CAN upper half - driver will attempt to send the message by calling into the lower - half driver. That send will not be performed if the lower half - driver is busy, i.e., if dev_txready() returns false. In that - case, the number of messages in the S/W FIFO can grow. If the - S/W FIFO becomes full, then can_write() will wait for space in - the S/W FIFO. - - If the CAN hardware does not support a H/W FIFO then busy means - that the hardware is actively sending the message and is - guaranteed to become non busy (i.e, dev_txready()) when the - send transfer completes and can_txdone() is called. So the call - to can_txdone() means that the transfer has completed and also - that the hardware is ready to accept another transfer. - - If the CAN hardware supports a H/W FIFO, can_txdone() is not - called when the tranfer is complete, but rather when the - transfer is queued in the H/W FIFO. When the H/W FIFO becomes - full, then dev_txready() will report false and the number of - queued messages in the S/W FIFO will grow. - - There is no mechanism in this case to inform the upper half - driver when the hardware is again available, when there is - again space in the H/W FIFO. can_txdone() will not be called - again. If the S/W FIFO becomes full, then the upper half - driver will wait for space to become available, but there is - no event to awaken it and the driver will hang. - - Enabling this feature adds support for the can_txready() - interface. This function is called from the lower half - driver's CAN interrupt handler each time a TX transfer - completes. This is a sure indication that the H/W FIFO is - no longer full. can_txready() will then awaken the - can_write() logic and the hang condition is avoided. - -choice - prompt "TX Ready Work Queue" - default CAN_TXREADY_HIPRI - depends on CAN_TXREADY - -config CAN_TXREADY_LOPRI - bool "Low-priority work queue" - select SCHED_LPWORK - -config CAN_TXREADY_HIPRI - bool "High-priority work queue" - select SCHED_HPWORK - -endchoice # TX Ready Work Queue - -config CAN_LOOPBACK - bool "CAN loopback mode" - default n - ---help--- - A CAN driver may or may not support a loopback mode for testing. If the - driver does support loopback mode, the setting will enable it. (If the - driver does not, this setting will have no effect). - -config CAN_NPOLLWAITERS - int "Number of poll waiters" - default 2 - depends on !DISABLE_POLL - ---help--- - The maximum number of threads that may be waiting on the - poll method. - -endif # CAN +source drivers/can/Kconfig +endif config ARCH_HAVE_PWM_PULSECOUNT bool diff --git a/drivers/Makefile b/drivers/Makefile index 5946cc123a..83d830c8ab 100644 --- a/drivers/Makefile +++ b/drivers/Makefile @@ -52,6 +52,7 @@ VPATH = . include analog$(DELIM)Make.defs include audio$(DELIM)Make.defs include bch$(DELIM)Make.defs +include can$(DELIM)Make.defs include i2c$(DELIM)Make.defs include input$(DELIM)Make.defs include ioexpander$(DELIM)Make.defs diff --git a/drivers/README.txt b/drivers/README.txt index f9f23af06f..7cf2938d5a 100644 --- a/drivers/README.txt +++ b/drivers/README.txt @@ -12,9 +12,9 @@ Contents: Files in this directory ^^^^^^^^^^^^^^^^^^^^^^^ -can.c - This is a CAN driver. See include/nuttx/drivers/can.h for usage - information. +can/ + This is the CAN drivers and logic support. See include/nuttx/can/can.h + for usage information. dev_null.c and dev_zero.c These files provide the standard /dev/null and /dev/zero devices. diff --git a/drivers/can/Kconfig b/drivers/can/Kconfig new file mode 100644 index 0000000000..577dbea8d1 --- /dev/null +++ b/drivers/can/Kconfig @@ -0,0 +1,127 @@ +# +# For a description of the syntax of this configuration file, +# see the file kconfig-language.txt in the NuttX tools repository. +# + +if CAN + +config CAN_EXTID + bool "CAN extended IDs" + default n + ---help--- + Enables support for the 29-bit extended ID. Default Standard 11-bit + IDs. + +config ARCH_HAVE_CAN_ERRORS + bool + default n + +config CAN_ERRORS + bool "CAN error reporting" + default n + depends on ARCH_HAVE_CAN_ERRORS + ---help--- + Support CAN error reporting. If this option is selected then CAN + error reporting is enabled. In the event of an error, the ch_error + bit will be set in the CAN message and the following message payload + will include a more detailed description of certain errors. + +config CAN_FD + bool "CAN FD" + default n + ---help--- + Enables support for the CAN_FD mode. + +config CAN_FIFOSIZE + int "CAN driver I/O buffer size" + default 8 + ---help--- + The size of the circular buffer of CAN messages. Default: 8 + +config CAN_NPENDINGRTR + int "Number of pending RTRs" + default 4 + ---help--- + The size of the list of pending RTR requests. Default: 4 + +config CAN_TXREADY + bool "can_txready interface" + default n + select SCHED_WORKQUEUE + ---help--- + This selection enables the can_txready() interface. This interface + is needed only for CAN hardware that supports queing of outgoing + messages in a H/W FIFO. + + The CAN upper half driver also supports a queue of output messages + in a S/W FIFO. Messages are added to that queue when when + can_write() is called and removed from the queue in can_txdone() + when each TX message is complete. + + After each message is added to the S/W FIFO, the CAN upper half + driver will attempt to send the message by calling into the lower + half driver. That send will not be performed if the lower half + driver is busy, i.e., if dev_txready() returns false. In that + case, the number of messages in the S/W FIFO can grow. If the + S/W FIFO becomes full, then can_write() will wait for space in + the S/W FIFO. + + If the CAN hardware does not support a H/W FIFO then busy means + that the hardware is actively sending the message and is + guaranteed to become non busy (i.e, dev_txready()) when the + send transfer completes and can_txdone() is called. So the call + to can_txdone() means that the transfer has completed and also + that the hardware is ready to accept another transfer. + + If the CAN hardware supports a H/W FIFO, can_txdone() is not + called when the tranfer is complete, but rather when the + transfer is queued in the H/W FIFO. When the H/W FIFO becomes + full, then dev_txready() will report false and the number of + queued messages in the S/W FIFO will grow. + + There is no mechanism in this case to inform the upper half + driver when the hardware is again available, when there is + again space in the H/W FIFO. can_txdone() will not be called + again. If the S/W FIFO becomes full, then the upper half + driver will wait for space to become available, but there is + no event to awaken it and the driver will hang. + + Enabling this feature adds support for the can_txready() + interface. This function is called from the lower half + driver's CAN interrupt handler each time a TX transfer + completes. This is a sure indication that the H/W FIFO is + no longer full. can_txready() will then awaken the + can_write() logic and the hang condition is avoided. + +choice + prompt "TX Ready Work Queue" + default CAN_TXREADY_HIPRI + depends on CAN_TXREADY + +config CAN_TXREADY_LOPRI + bool "Low-priority work queue" + select SCHED_LPWORK + +config CAN_TXREADY_HIPRI + bool "High-priority work queue" + select SCHED_HPWORK + +endchoice # TX Ready Work Queue + +config CAN_LOOPBACK + bool "CAN loopback mode" + default n + ---help--- + A CAN driver may or may not support a loopback mode for testing. If the + driver does support loopback mode, the setting will enable it. (If the + driver does not, this setting will have no effect). + +config CAN_NPOLLWAITERS + int "Number of poll waiters" + default 2 + depends on !DISABLE_POLL + ---help--- + The maximum number of threads that may be waiting on the + poll method. + +endif # CAN diff --git a/drivers/can/Make.defs b/drivers/can/Make.defs new file mode 100644 index 0000000000..25d9997165 --- /dev/null +++ b/drivers/can/Make.defs @@ -0,0 +1,52 @@ +############################################################################ +# drivers/can/Make.defs +# +# Copyright (C) 2016 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. +# +############################################################################ + +# Don't build anything if there is no CAN support + +ifeq ($(CONFIG_CAN),y) + +CSRCS += can.c + +ifeq ($(CONFIG_MCP2515),y) +CSRCS += mcp2515.c +endif + +# Include CAN device driver build support + +DEPPATH += --dep-path can +VPATH += :can +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)$(DELIM)drivers$(DELIM)can} +endif + diff --git a/drivers/can.c b/drivers/can/can.c similarity index 100% rename from drivers/can.c rename to drivers/can/can.c diff --git a/include/nuttx/analog/adc.h b/include/nuttx/analog/adc.h index 214143357a..73d839b003 100644 --- a/include/nuttx/analog/adc.h +++ b/include/nuttx/analog/adc.h @@ -6,7 +6,7 @@ * Author: Li Zhuoyi * Gregory Nutt * - * Derived from include/nuttx/drivers/can.h + * Derived from include/nuttx/can/can.h * * Copyright (C) 2008, 2009 Gregory Nutt. All rights reserved. * Author: Gregory Nutt diff --git a/include/nuttx/analog/dac.h b/include/nuttx/analog/dac.h index 249100d89b..93f1282ef5 100644 --- a/include/nuttx/analog/dac.h +++ b/include/nuttx/analog/dac.h @@ -6,7 +6,7 @@ * Author: Li Zhuoyi * History: 0.1 2011-08-04 initial version * - * Derived from include/nuttx/drivers/can.h + * Derived from include/nuttx/can/can.h * * Copyright (C) 2008, 2009 Gregory Nutt. All rights reserved. * Author: Gregory Nutt diff --git a/include/nuttx/drivers/can.h b/include/nuttx/can/can.h similarity index 100% rename from include/nuttx/drivers/can.h rename to include/nuttx/can/can.h diff --git a/include/nuttx/fs/ioctl.h b/include/nuttx/fs/ioctl.h index cfcc4507d6..ccd829f918 100644 --- a/include/nuttx/fs/ioctl.h +++ b/include/nuttx/fs/ioctl.h @@ -357,7 +357,7 @@ #define _RELAYIOC(nr) _IOC(_RELAYBASE,nr) /* CAN driver ioctl definitions *********************************************/ -/* (see nuttx/drivers/can.h */ +/* (see nuttx/can/can.h */ #define _CANIOCVALID(c) (_IOC_TYPE(c)==_CANBASE) #define _CANIOC(nr) _IOC(_CANBASE,nr) -- GitLab From fc7c3f5328525cfe5b4c7e66aa5161451597a1e9 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 12 May 2017 08:50:56 -0600 Subject: [PATCH 799/990] syslog: I think this might speed upt the CR-LF scan in syslog_dev_write(). --- drivers/syslog/syslog_device.c | 81 +++++++++++++++++----------------- 1 file changed, 41 insertions(+), 40 deletions(-) diff --git a/drivers/syslog/syslog_device.c b/drivers/syslog/syslog_device.c index 4cc65734ad..025bcf745f 100644 --- a/drivers/syslog/syslog_device.c +++ b/drivers/syslog/syslog_device.c @@ -518,59 +518,60 @@ ssize_t syslog_dev_write(FAR const char *buffer, size_t buflen) remaining > 0; endptr++, remaining--) { - bool crlf = false; + /* Check for carriage return or line feed */ - /* Check for a CR-LF sequence */ - - if (remaining > 1 && - ((endptr[0] == '\r' && endptr[1] == '\n') || - (endptr[0] == '\n' && endptr[1] == '\r'))) + if (*endptr == '\r' || *endptr == '\n') { - endptr++; - remaining--; - crlf = true; - } - - /* Special case carriage return and line feed */ + /* Check for pre-formatted CR-LF sequence */ - if (!crlf && (*endptr == '\r' || *endptr == '\n')) - { - /* Write everything up to this point, ignore the special - * character. - * - * - buffer points to next byte to output. - * - endptr points to the special character. - */ + if (remaining > 1 && + ((endptr[0] == '\r' && endptr[1] == '\n') || + (endptr[0] == '\n' && endptr[1] == '\r'))) + { + /* Just skip over pre-formatted CR-LF or LF-CR sequence */ - writelen = (size_t)((uintptr_t)endptr - (uintptr_t)buffer); - if (writelen > 0) + endptr++; + remaining--; + } + else { - nwritten = file_write(&g_syslog_dev.sl_file, buffer, writelen); - if (nwritten < 0) + /* Write everything up to the position of the special + * character. + * + * - buffer points to next byte to output. + * - endptr points to the special character. + */ + + writelen = (size_t)((uintptr_t)endptr - (uintptr_t)buffer); + if (writelen > 0) { - errcode = -nwritten; - goto errout_with_sem; + nwritten = file_write(&g_syslog_dev.sl_file, buffer, writelen); + if (nwritten < 0) + { + errcode = -nwritten; + goto errout_with_sem; + } } - } - /* Ignore the carriage return, but for the linefeed, output - * both a carriage return and a linefeed. - */ + /* Ignore the carriage return, but for the linefeed, output + * both a carriage return and a linefeed. + */ - if (*endptr == '\n') - { - nwritten = file_write(&g_syslog_dev.sl_file, g_syscrlf, 2); - if (nwritten < 0) + if (*endptr == '\n') { - errcode = -nwritten; - goto errout_with_sem; + nwritten = file_write(&g_syslog_dev.sl_file, g_syscrlf, 2); + if (nwritten < 0) + { + errcode = -nwritten; + goto errout_with_sem; + } } - } - /* Adjust pointers */ + /* Adjust pointers */ - writelen++; /* Skip the special character */ - buffer += writelen; /* Points past the special character */ + writelen++; /* Skip the special character */ + buffer += writelen; /* Points past the special character */ + } } } -- GitLab From 7698790be127ed7b0f854f327de4da553b1a61fd Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 12 May 2017 09:04:52 -0600 Subject: [PATCH 800/990] Changes from review of last PR --- drivers/README.txt | 8 ++++---- drivers/can/Make.defs | 4 ++-- drivers/can/can.c | 4 ++-- include/nuttx/can/can.h | 8 ++++---- 4 files changed, 12 insertions(+), 12 deletions(-) diff --git a/drivers/README.txt b/drivers/README.txt index 7cf2938d5a..ec65ccbe8e 100644 --- a/drivers/README.txt +++ b/drivers/README.txt @@ -12,10 +12,6 @@ Contents: Files in this directory ^^^^^^^^^^^^^^^^^^^^^^^ -can/ - This is the CAN drivers and logic support. See include/nuttx/can/can.h - for usage information. - dev_null.c and dev_zero.c These files provide the standard /dev/null and /dev/zero devices. See include/nuttx/fs/fs.h for functions that should be called if you @@ -55,6 +51,10 @@ bch/ performed by loop.c. See include/nuttx/fs/fs.h for registration information. +can/ + This is the CAN drivers and logic support. See include/nuttx/can/can.h + for usage information. + contactless/ Contactless devices are related to wireless devices. They are not communication devices with other similar peers, but couplers/interfaces diff --git a/drivers/can/Make.defs b/drivers/can/Make.defs index 25d9997165..9a1504664c 100644 --- a/drivers/can/Make.defs +++ b/drivers/can/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # drivers/can/Make.defs # -# Copyright (C) 2016 Gregory Nutt. All rights reserved. +# Copyright (C) 2017 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -39,7 +39,7 @@ ifeq ($(CONFIG_CAN),y) CSRCS += can.c -ifeq ($(CONFIG_MCP2515),y) +ifeq ($(CONFIG_CAN_MCP2515),y) CSRCS += mcp2515.c endif diff --git a/drivers/can/can.c b/drivers/can/can.c index dd810ebcd1..730d7e84b5 100644 --- a/drivers/can/can.c +++ b/drivers/can/can.c @@ -1,5 +1,5 @@ /**************************************************************************** - * drivers/can.c + * drivers/can/can.c * * Copyright (C) 2008-2009, 2011-2012, 2014-2015 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -57,7 +57,7 @@ #include #include #include -#include +#include #ifdef CONFIG_CAN_TXREADY # include diff --git a/include/nuttx/can/can.h b/include/nuttx/can/can.h index 68df58dd79..e85a9fa54d 100644 --- a/include/nuttx/can/can.h +++ b/include/nuttx/can/can.h @@ -1,5 +1,5 @@ /************************************************************************************ - * include/nuttx/drivers/can.h + * include/nuttx/can/can.h * * Copyright (C) 2008, 2009, 2011-2012, 2015-2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -33,8 +33,8 @@ * ************************************************************************************/ -#ifndef __INCLUDE_NUTTX_DRVERS_CAN_H -#define __INCLUDE_NUTTX_DRVERS_CAN_H +#ifndef __INCLUDE_NUTTX_CAN_CAN_H +#define __INCLUDE_NUTTX_CAN_CAN_H /************************************************************************************ * Included Files @@ -819,4 +819,4 @@ int can_txready(FAR struct can_dev_s *dev); #endif #endif /* CONFIG_CAN */ -#endif /* __INCLUDE_NUTTX_DRVERS_CAN_H */ +#endif /* __INCLUDE_NUTTX_CAN_CAN_H */ -- GitLab From 14ae6df1824a43cf5320f32f60b2300eb30ec9fe Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 12 May 2017 10:13:18 -0600 Subject: [PATCH 801/990] locale.h: Add a bogus definition of locale_t --- drivers/README.txt | 10 +++++----- include/cxx/clocale | 1 + include/locale.h | 10 ++++++++++ 3 files changed, 16 insertions(+), 5 deletions(-) diff --git a/drivers/README.txt b/drivers/README.txt index ec65ccbe8e..b5df427b9c 100644 --- a/drivers/README.txt +++ b/drivers/README.txt @@ -12,11 +12,11 @@ Contents: Files in this directory ^^^^^^^^^^^^^^^^^^^^^^^ -dev_null.c and dev_zero.c - These files provide the standard /dev/null and /dev/zero devices. - See include/nuttx/fs/fs.h for functions that should be called if you - want to register these devices (devnull_register() and - devzero_register()). +dev_null.c, dev_urandom, and dev_zero.c + These files provide the standard /dev/null, /dev/urandom, and /dev/zero + devices. See include/nuttx/drivers/driers.h for prototypes of functions + that should be called if you want to register these devices + (devnull_register(), devurandom_register(), and devzero_register()). pwm.c Provides the "upper half" of a pulse width modulation (PWM) driver. diff --git a/include/cxx/clocale b/include/cxx/clocale index 154bf8040a..498d4041b7 100644 --- a/include/cxx/clocale +++ b/include/cxx/clocale @@ -48,6 +48,7 @@ namespace std { + using ::locale_t; using ::setlocale; using ::localeconv; } diff --git a/include/locale.h b/include/locale.h index 16923e4a3d..37d334173a 100644 --- a/include/locale.h +++ b/include/locale.h @@ -59,6 +59,10 @@ * Public Type Definitions ****************************************************************************/ +/* OpenGroup.org: "The locale.h header shall define the lconv structure, + * which shall include at least the following members. ..." + */ + struct lconv { FAR char *decimal_point; @@ -87,6 +91,12 @@ struct lconv FAR char int_p_sign_posn; }; +/* OpenGroup.org: The locale.h header shall define the locale_t type, + * representing a locale object + */ + +typedef FAR void *locale_t; + /**************************************************************************** * Public Function Prototypes ****************************************************************************/ -- GitLab From 6811e1898024808cedb0a845da5ace05f2dcbaca Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Fri, 12 May 2017 16:33:22 -0300 Subject: [PATCH 802/990] Fix the libcanard link version to get it compiling without errors. --- configs/stm32f4discovery/canard/defconfig | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/configs/stm32f4discovery/canard/defconfig b/configs/stm32f4discovery/canard/defconfig index f10465c2c0..cb66dbf231 100644 --- a/configs/stm32f4discovery/canard/defconfig +++ b/configs/stm32f4discovery/canard/defconfig @@ -1097,7 +1097,7 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_CANUTILS_CANLIB is not set CONFIG_CANUTILS_LIBCANARD=y CONFIG_LIBCANARD_URL="https://github.com/UAVCAN/libcanard/archive" -CONFIG_LIBCANARD_VERSION="e4a1d52be862b03e5872add75890e67bf1d9187c" +CONFIG_LIBCANARD_VERSION="5ad65c6a4efda60cda7a8f0512da0f465822bbb8" # # Examples -- GitLab From 700e4ff5b60f85d4f26573d3de0d5e5533d28f19 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Fri, 12 May 2017 17:03:27 -1000 Subject: [PATCH 803/990] kinetis:K66 fixed TMP2_CH1 definition --- arch/arm/src/kinetis/chip/kinetis_k66pinmux.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/arch/arm/src/kinetis/chip/kinetis_k66pinmux.h b/arch/arm/src/kinetis/chip/kinetis_k66pinmux.h index ad15c5ac02..93676e9903 100644 --- a/arch/arm/src/kinetis/chip/kinetis_k66pinmux.h +++ b/arch/arm/src/kinetis/chip/kinetis_k66pinmux.h @@ -615,7 +615,7 @@ #define PIN_TPM1_CH1_3 (PIN_ALT6 | PIN_PORTB | PIN1) #define PIN_TPM2_CH0_1 (PIN_ALT6 | PIN_PORTA | PIN10) #define PIN_TPM2_CH0_2 (PIN_ALT6 | PIN_PORTB | PIN18) -#define PIN_TPM2_CH1_1 (PIN_ALT1 | PIN_PORTA | PIN11) +#define PIN_TPM2_CH1_1 (PIN_ALT6 | PIN_PORTA | PIN11) #define PIN_TPM2_CH1_2 (PIN_ALT6 | PIN_PORTB | PIN19) #define PIN_TPM_CLKIN0_1 (PIN_ALT7 | PIN_PORTA | PIN18) -- GitLab From 69a8aecbc8098b2b5fa2e709c295e57d123e7e72 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Fri, 12 May 2017 17:18:26 -1000 Subject: [PATCH 804/990] kinetis:K66 define ALT1 to match ref manual --- arch/arm/src/kinetis/kinetis.h | 15 ++++++++++++++- 1 file changed, 14 insertions(+), 1 deletion(-) diff --git a/arch/arm/src/kinetis/kinetis.h b/arch/arm/src/kinetis/kinetis.h index 89ab791741..a1558179fd 100644 --- a/arch/arm/src/kinetis/kinetis.h +++ b/arch/arm/src/kinetis/kinetis.h @@ -82,7 +82,8 @@ /* Port Modes */ /* Unshifted versions: */ #define PIN_MODE_ANALOG (0) /* 000 Pin Disabled (Analog) */ -#define PIN_MODE_GPIO (1) /* 001 Alternative 1 (GPIO) */ +#define PIN_MODE_ALT1 (1) /* 001 Alternative 1 */ +#define PIN_MODE_GPIO PIN_MODE_ALT1 /* 001 Alternative 1 (GPIO) */ #define PIN_MODE_ALT2 (2) /* 010 Alternative 2 */ #define PIN_MODE_ALT3 (3) /* 011 Alternative 3 */ #define PIN_MODE_ALT4 (4) /* 100 Alternative 4 */ @@ -91,6 +92,7 @@ #define PIN_MODE_ALT7 (7) /* 111 Alternative 7 */ /* Shifted versions: */ #define _PIN_MODE_ANALOG (0 << _PIN_MODE_SHIFT) /* 000 Pin Disabled (Analog) */ +#define _PIN_MODE_ALT1 (1 << _PIN_MODE_SHIFT) /* 001 Alternative 1 */ #define _PIN_MODE_GPIO (1 << _PIN_MODE_SHIFT) /* 001 Alternative 1 (GPIO) */ #define _PIN_MODE_ALT2 (2 << _PIN_MODE_SHIFT) /* 010 Alternative 2 */ #define _PIN_MODE_ALT3 (3 << _PIN_MODE_SHIFT) /* 011 Alternative 3 */ @@ -137,6 +139,17 @@ #define GPIO_LOWDRIVE (_PIN_MODE_GPIO | _PIN_OUTPUT_LOWDRIVE) #define GPIO_HIGHDRIVE (_PIN_MODE_GPIO | _PIN_OUTPUT_HIGHDRIVE) +#define PIN_ALT1 _PIN_MODE_ALT1 +#define PIN_ALT1_INPUT (_PIN_MODE_ALT1 | _PIN_INPUT) +#define PIN_ALT1_PULLDOWN (_PIN_MODE_ALT1 | _PIN_INPUT_PULLDOWN) +#define PIN_ALT1_PULLUP (_PIN_MODE_ALT1 | _PIN_INPUT_PULLUP) +#define PIN_ALT1_OUTPUT (_PIN_MODE_ALT1 | _PIN_OUTPUT) +#define PIN_ALT1_FAST (_PIN_MODE_ALT1 | _PIN_OUTPUT_FAST) +#define PIN_ALT1_SLOW (_PIN_MODE_ALT1 | _PIN_OUTPUT_SLOW) +#define PIN_ALT1_OPENDRAIN (_PIN_MODE_ALT1 | _PIN_OUTPUT_OPENDRAIN) +#define PIN_ALT1_LOWDRIVE (_PIN_MODE_ALT1 | _PIN_OUTPUT_LOWDRIVE) +#define PIN_ALT1_HIGHDRIVE (_PIN_MODE_ALT1 | _PIN_OUTPUT_HIGHDRIVE) + #define PIN_ALT2 _PIN_MODE_ALT2 #define PIN_ALT2_INPUT (_PIN_MODE_ALT2 | _PIN_INPUT) #define PIN_ALT2_PULLDOWN (_PIN_MODE_ALT2 | _PIN_INPUT_PULLDOWN) -- GitLab From 02535be36a9abfa8c526e0a3d84f1306d42bf5c6 Mon Sep 17 00:00:00 2001 From: Gwenhael Goavec-Merou Date: Sat, 13 May 2017 08:39:36 -0600 Subject: [PATCH 805/990] STM32F410. Add support for STM32Fr10. STM32F410 is a version of STM32F4 with 32 KB of RAM and 62 or 128 KB of flash. --- arch/arm/include/stm32/chip.h | 38 ++ arch/arm/include/stm32/stm32f40xxx_irq.h | 382 +++++++++++------- arch/arm/src/stm32/Kconfig | 18 + arch/arm/src/stm32/chip/stm32f40xxx_vectors.h | 119 +++++- arch/arm/src/stm32/stm32_allocateheap.c | 4 +- 5 files changed, 419 insertions(+), 142 deletions(-) diff --git a/arch/arm/include/stm32/chip.h b/arch/arm/include/stm32/chip.h index b56a6b3d61..a9eca2813f 100644 --- a/arch/arm/include/stm32/chip.h +++ b/arch/arm/include/stm32/chip.h @@ -1881,6 +1881,44 @@ # define STM32_NRNG 0 /* No Random number generator (RNG) */ # define STM32_NDCMI 0 /* No digital camera interface (DCMI) */ +#elif defined(CONFIG_ARCH_CHIP_STM32F410RB) /* LQFP64 package, 512Kb FLASH, 96KiB SRAM */ +# undef CONFIG_STM32_STM32L15XX /* STM32L151xx and STM32L152xx family */ +# undef CONFIG_STM32_ENERGYLITE /* STM32L EnergyLite family */ +# undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */ +# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */ +# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */ +# undef CONFIG_STM32_MEDIUMPLUSDENSITY /* STM32L15xxC w/ 32/256 Kbytes */ +# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */ +# undef CONFIG_STM32_VALUELINE /* STM32F100x */ +# undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ +# undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */ +# undef CONFIG_STM32_STM32F30XX /* STM32F30xxx family */ +# undef CONFIG_STM32_STM32F37XX /* STM32F37xxx family */ +# define CONFIG_STM32_STM32F40XX 1 /* STM32F405xx and STM32407xx */ +# define STM32_NFSMC 0 /* No FSMC */ +# define STM32_NATIM 1 /* One advanced timers TIM1 */ +# define STM32_NGTIM 4 /* 16-bit general timers TIM3 and 4 with DMA + * 32-bit general timers TIM2 and 5 with DMA */ +# define STM32_NGTIMNDMA 3 /* 16-bit general timers TIM9-11 without DMA */ +# define STM32_NBTIM 0 /* No basic timers */ +# define STM32_NDMA 2 /* DMA1-2 with 8 streams each*/ +# define STM32_NSPI 3 /* SPI1-4 */ +# define STM32_NI2S 0 /* I2S1-2 (multiplexed with SPI2-3) */ +# define STM32_NUSART 3 /* Actually only 3: USART1, 2 and 6 */ +# define STM32_NI2C 3 /* I2C1-3 */ +# define STM32_NCAN 0 /* No CAN */ +# define STM32_NSDIO 0 /* One SDIO interface */ +# define STM32_NLCD 0 /* No LCD */ +# define STM32_NUSBOTG 0 /* USB OTG FS (only) */ +# define STM32_NGPIO 50 /* GPIOA-H */ +# define STM32_NADC 1 /* One 12-bit ADC1, 16 channels */ +# define STM32_NDAC 1 /* No DAC */ +# define STM32_NCAPSENSE 0 /* No capacitive sensing channels */ +# define STM32_NCRC 1 /* No CRC */ +# define STM32_NETHERNET 0 /* No Ethernet MAC */ +# define STM32_NRNG 1 /* No Random number generator (RNG) */ +# define STM32_NDCMI 0 /* No digital camera interface (DCMI) */ + #elif defined(CONFIG_ARCH_CHIP_STM32F411RE) /* LQFP64 package, 512Kb FLASH, 128KiB SRAM */ # undef CONFIG_STM32_STM32L15XX /* STM32L151xx and STM32L152xx family */ # undef CONFIG_STM32_ENERGYLITE /* STM32L EnergyLite family */ diff --git a/arch/arm/include/stm32/stm32f40xxx_irq.h b/arch/arm/include/stm32/stm32f40xxx_irq.h index 64df1a6fe5..6f4c23c018 100644 --- a/arch/arm/include/stm32/stm32f40xxx_irq.h +++ b/arch/arm/include/stm32/stm32f40xxx_irq.h @@ -1,7 +1,7 @@ /**************************************************************************************************** * arch/arm/include/stm32/stm32f40xxx_irq.h * - * Copyright (C) 2009, 2014-2015 Gregory Nutt. All rights reserved. + * Copyright (C) 2009, 2014-2015, 2017 Gregory Nutt. All rights reserved. * Copyright (C) 2016 Omni Hoverboards Inc. All rights reserved. * Author: Gregory Nutt * David Sidrane @@ -64,170 +64,280 @@ * External interrupts (vectors >= 16) */ -#define STM32_IRQ_WWDG (STM32_IRQ_FIRST+0) /* 0: Window Watchdog interrupt */ -#define STM32_IRQ_PVD (STM32_IRQ_FIRST+1) /* 1: PVD through EXTI Line detection interrupt */ -#define STM32_IRQ_TAMPER (STM32_IRQ_FIRST+2) /* 2: Tamper and time stamp interrupts */ -#define STM32_IRQ_TIMESTAMP (STM32_IRQ_FIRST+2) /* 2: Tamper and time stamp interrupts */ -#define STM32_IRQ_RTC_WKUP (STM32_IRQ_FIRST+3) /* 3: RTC global interrupt */ -#define STM32_IRQ_FLASH (STM32_IRQ_FIRST+4) /* 4: Flash global interrupt */ -#define STM32_IRQ_RCC (STM32_IRQ_FIRST+5) /* 5: RCC global interrupt */ -#define STM32_IRQ_EXTI0 (STM32_IRQ_FIRST+6) /* 6: EXTI Line 0 interrupt */ -#define STM32_IRQ_EXTI1 (STM32_IRQ_FIRST+7) /* 7: EXTI Line 1 interrupt */ -#define STM32_IRQ_EXTI2 (STM32_IRQ_FIRST+8) /* 8: EXTI Line 2 interrupt */ -#define STM32_IRQ_EXTI3 (STM32_IRQ_FIRST+9) /* 9: EXTI Line 3 interrupt */ -#define STM32_IRQ_EXTI4 (STM32_IRQ_FIRST+10) /* 10: EXTI Line 4 interrupt */ -#define STM32_IRQ_DMA1S0 (STM32_IRQ_FIRST+11) /* 11: DMA1 Stream 0 global interrupt */ -#define STM32_IRQ_DMA1S1 (STM32_IRQ_FIRST+12) /* 12: DMA1 Stream 1 global interrupt */ -#define STM32_IRQ_DMA1S2 (STM32_IRQ_FIRST+13) /* 13: DMA1 Stream 2 global interrupt */ -#define STM32_IRQ_DMA1S3 (STM32_IRQ_FIRST+14) /* 14: DMA1 Stream 3 global interrupt */ -#define STM32_IRQ_DMA1S4 (STM32_IRQ_FIRST+15) /* 15: DMA1 Stream 4 global interrupt */ -#define STM32_IRQ_DMA1S5 (STM32_IRQ_FIRST+16) /* 16: DMA1 Stream 5 global interrupt */ -#define STM32_IRQ_DMA1S6 (STM32_IRQ_FIRST+17) /* 17: DMA1 Stream 6 global interrupt */ -#define STM32_IRQ_ADC (STM32_IRQ_FIRST+18) /* 18: ADC1, ADC2, and ADC3 global interrupt */ -#define STM32_IRQ_CAN1TX (STM32_IRQ_FIRST+19) /* 19: CAN1 TX interrupts */ -#define STM32_IRQ_CAN1RX0 (STM32_IRQ_FIRST+20) /* 20: CAN1 RX0 interrupts */ -#define STM32_IRQ_CAN1RX1 (STM32_IRQ_FIRST+21) /* 21: CAN1 RX1 interrupt */ -#define STM32_IRQ_CAN1SCE (STM32_IRQ_FIRST+22) /* 22: CAN1 SCE interrupt */ -#define STM32_IRQ_EXTI95 (STM32_IRQ_FIRST+23) /* 23: EXTI Line[9:5] interrupts */ -#define STM32_IRQ_TIM1BRK (STM32_IRQ_FIRST+24) /* 24: TIM1 Break interrupt */ -#define STM32_IRQ_TIM9 (STM32_IRQ_FIRST+24) /* 24: TIM9 global interrupt */ -#define STM32_IRQ_TIM1UP (STM32_IRQ_FIRST+25) /* 25: TIM1 Update interrupt */ -#define STM32_IRQ_TIM10 (STM32_IRQ_FIRST+25) /* 25: TIM10 global interrupt */ -#define STM32_IRQ_TIM1TRGCOM (STM32_IRQ_FIRST+26) /* 26: TIM1 Trigger and Commutation interrupts */ -#define STM32_IRQ_TIM11 (STM32_IRQ_FIRST+26) /* 26: TIM11 global interrupt */ -#define STM32_IRQ_TIM1CC (STM32_IRQ_FIRST+27) /* 27: TIM1 Capture Compare interrupt */ -#define STM32_IRQ_TIM2 (STM32_IRQ_FIRST+28) /* 28: TIM2 global interrupt */ -#define STM32_IRQ_TIM3 (STM32_IRQ_FIRST+29) /* 29: TIM3 global interrupt */ -#define STM32_IRQ_TIM4 (STM32_IRQ_FIRST+30) /* 30: TIM4 global interrupt */ -#define STM32_IRQ_I2C1EV (STM32_IRQ_FIRST+31) /* 31: I2C1 event interrupt */ -#define STM32_IRQ_I2C1ER (STM32_IRQ_FIRST+32) /* 32: I2C1 error interrupt */ -#define STM32_IRQ_I2C2EV (STM32_IRQ_FIRST+33) /* 33: I2C2 event interrupt */ -#define STM32_IRQ_I2C2ER (STM32_IRQ_FIRST+34) /* 34: I2C2 error interrupt */ -#define STM32_IRQ_SPI1 (STM32_IRQ_FIRST+35) /* 35: SPI1 global interrupt */ -#define STM32_IRQ_SPI2 (STM32_IRQ_FIRST+36) /* 36: SPI2 global interrupt */ -#define STM32_IRQ_USART1 (STM32_IRQ_FIRST+37) /* 37: USART1 global interrupt */ -#define STM32_IRQ_USART2 (STM32_IRQ_FIRST+38) /* 38: USART2 global interrupt */ -#define STM32_IRQ_USART3 (STM32_IRQ_FIRST+39) /* 39: USART3 global interrupt */ -#define STM32_IRQ_EXTI1510 (STM32_IRQ_FIRST+40) /* 40: EXTI Line[15:10] interrupts */ -#define STM32_IRQ_RTCALRM (STM32_IRQ_FIRST+41) /* 41: RTC alarm through EXTI line interrupt */ -#define STM32_IRQ_OTGFSWKUP (STM32_IRQ_FIRST+42) /* 42: USB On-The-Go FS Wakeup through EXTI line interrupt */ -#define STM32_IRQ_TIM8BRK (STM32_IRQ_FIRST+43) /* 43: TIM8 Break interrupt */ -#define STM32_IRQ_TIM12 (STM32_IRQ_FIRST+43) /* 43: TIM12 global interrupt */ -#define STM32_IRQ_TIM8UP (STM32_IRQ_FIRST+44) /* 44: TIM8 Update interrupt */ -#define STM32_IRQ_TIM13 (STM32_IRQ_FIRST+44) /* 44: TIM13 global interrupt */ -#define STM32_IRQ_TIM8TRGCOM (STM32_IRQ_FIRST+45) /* 45: TIM8 Trigger and Commutation interrupts */ -#define STM32_IRQ_TIM14 (STM32_IRQ_FIRST+45) /* 45: TIM14 global interrupt */ -#define STM32_IRQ_TIM8CC (STM32_IRQ_FIRST+46) /* 46: TIM8 Capture Compare interrupt */ -#define STM32_IRQ_DMA1S7 (STM32_IRQ_FIRST+47) /* 47: DMA1 Stream 7 global interrupt */ -#define STM32_IRQ_FSMC (STM32_IRQ_FIRST+48) /* 48: FSMC global interrupt */ -#define STM32_IRQ_SDIO (STM32_IRQ_FIRST+49) /* 49: SDIO global interrupt */ -#define STM32_IRQ_TIM5 (STM32_IRQ_FIRST+50) /* 50: TIM5 global interrupt */ -#define STM32_IRQ_SPI3 (STM32_IRQ_FIRST+51) /* 51: SPI3 global interrupt */ -#define STM32_IRQ_UART4 (STM32_IRQ_FIRST+52) /* 52: UART4 global interrupt */ -#define STM32_IRQ_UART5 (STM32_IRQ_FIRST+53) /* 53: UART5 global interrupt */ -#define STM32_IRQ_TIM6 (STM32_IRQ_FIRST+54) /* 54: TIM6 global interrupt */ -#define STM32_IRQ_DAC (STM32_IRQ_FIRST+54) /* 54: DAC1 and DAC2 underrun error interrupts */ -#define STM32_IRQ_TIM7 (STM32_IRQ_FIRST+55) /* 55: TIM7 global interrupt */ -#define STM32_IRQ_DMA2S0 (STM32_IRQ_FIRST+56) /* 56: DMA2 Stream 0 global interrupt */ -#define STM32_IRQ_DMA2S1 (STM32_IRQ_FIRST+57) /* 57: DMA2 Stream 1 global interrupt */ -#define STM32_IRQ_DMA2S2 (STM32_IRQ_FIRST+58) /* 58: DMA2 Stream 2 global interrupt */ -#define STM32_IRQ_DMA2S3 (STM32_IRQ_FIRST+59) /* 59: DMA2 Stream 3 global interrupt */ -#define STM32_IRQ_DMA2S4 (STM32_IRQ_FIRST+60) /* 60: DMA2 Stream 4 global interrupt */ +#define STM32_IRQ_WWDG (STM32_IRQ_FIRST+0) /* 0: Window Watchdog interrupt */ +#define STM32_IRQ_PVD (STM32_IRQ_FIRST+1) /* 1: PVD through EXTI Line detection interrupt */ +#define STM32_IRQ_TAMPER (STM32_IRQ_FIRST+2) /* 2: Tamper and time stamp interrupts */ +#define STM32_IRQ_TIMESTAMP (STM32_IRQ_FIRST+2) /* 2: Tamper and time stamp interrupts */ +#define STM32_IRQ_RTC_WKUP (STM32_IRQ_FIRST+3) /* 3: RTC global interrupt */ +#define STM32_IRQ_FLASH (STM32_IRQ_FIRST+4) /* 4: Flash global interrupt */ +#define STM32_IRQ_RCC (STM32_IRQ_FIRST+5) /* 5: RCC global interrupt */ +#define STM32_IRQ_EXTI0 (STM32_IRQ_FIRST+6) /* 6: EXTI Line 0 interrupt */ +#define STM32_IRQ_EXTI1 (STM32_IRQ_FIRST+7) /* 7: EXTI Line 1 interrupt */ +#define STM32_IRQ_EXTI2 (STM32_IRQ_FIRST+8) /* 8: EXTI Line 2 interrupt */ +#define STM32_IRQ_EXTI3 (STM32_IRQ_FIRST+9) /* 9: EXTI Line 3 interrupt */ +#define STM32_IRQ_EXTI4 (STM32_IRQ_FIRST+10) /* 10: EXTI Line 4 interrupt */ +#define STM32_IRQ_DMA1S0 (STM32_IRQ_FIRST+11) /* 11: DMA1 Stream 0 global interrupt */ +#define STM32_IRQ_DMA1S1 (STM32_IRQ_FIRST+12) /* 12: DMA1 Stream 1 global interrupt */ +#define STM32_IRQ_DMA1S2 (STM32_IRQ_FIRST+13) /* 13: DMA1 Stream 2 global interrupt */ +#define STM32_IRQ_DMA1S3 (STM32_IRQ_FIRST+14) /* 14: DMA1 Stream 3 global interrupt */ +#define STM32_IRQ_DMA1S4 (STM32_IRQ_FIRST+15) /* 15: DMA1 Stream 4 global interrupt */ +#define STM32_IRQ_DMA1S5 (STM32_IRQ_FIRST+16) /* 16: DMA1 Stream 5 global interrupt */ +#define STM32_IRQ_DMA1S6 (STM32_IRQ_FIRST+17) /* 17: DMA1 Stream 6 global interrupt */ +#define STM32_IRQ_ADC (STM32_IRQ_FIRST+18) /* 18: ADC1, ADC2, and ADC3 global interrupt */ + +#if defined(CONFIG_STM32_STM32F410) +# define STM32_IRQ_RESERVED19 (STM32_IRQ_FIRST+19) /* 19: Reserved */ +# define STM32_IRQ_RESERVED20 (STM32_IRQ_FIRST+20) /* 20: Reserved */ +# define STM32_IRQ_RESERVED21 (STM32_IRQ_FIRST+21) /* 21: Reserved */ +# define STM32_IRQ_RESERVED22 (STM32_IRQ_FIRST+22) /* 22: Reserved */ +#else +# define STM32_IRQ_CAN1TX (STM32_IRQ_FIRST+19) /* 19: CAN1 TX interrupts */ +# define STM32_IRQ_CAN1RX0 (STM32_IRQ_FIRST+20) /* 20: CAN1 RX0 interrupts */ +# define STM32_IRQ_CAN1RX1 (STM32_IRQ_FIRST+21) /* 21: CAN1 RX1 interrupt */ +# define STM32_IRQ_CAN1SCE (STM32_IRQ_FIRST+22) /* 22: CAN1 SCE interrupt */ +#endif + +#define STM32_IRQ_EXTI95 (STM32_IRQ_FIRST+23) /* 23: EXTI Line[9:5] interrupts */ +#define STM32_IRQ_TIM1BRK (STM32_IRQ_FIRST+24) /* 24: TIM1 Break interrupt */ +#define STM32_IRQ_TIM9 (STM32_IRQ_FIRST+24) /* 24: TIM9 global interrupt */ +#define STM32_IRQ_TIM1UP (STM32_IRQ_FIRST+25) /* 25: TIM1 Update interrupt */ +#define STM32_IRQ_TIM10 (STM32_IRQ_FIRST+25) /* 25: TIM10 global interrupt */ +#define STM32_IRQ_TIM1TRGCOM (STM32_IRQ_FIRST+26) /* 26: TIM1 Trigger and Commutation interrupts */ +#define STM32_IRQ_TIM11 (STM32_IRQ_FIRST+26) /* 26: TIM11 global interrupt */ +#define STM32_IRQ_TIM1CC (STM32_IRQ_FIRST+27) /* 27: TIM1 Capture Compare interrupt */ + +#if defined(CONFIG_STM32_STM32F410) +# define STM32_IRQ_RESERVED28 (STM32_IRQ_FIRST+28) /* 28: Reserved */ +# define STM32_IRQ_RESERVED29 (STM32_IRQ_FIRST+29) /* 29: Reserved */ +# define STM32_IRQ_RESERVED30 (STM32_IRQ_FIRST+30) /* 30: Reserved */ +#else +# define STM32_IRQ_TIM2 (STM32_IRQ_FIRST+28) /* 28: TIM2 global interrupt */ +# define STM32_IRQ_TIM3 (STM32_IRQ_FIRST+29) /* 29: TIM3 global interrupt */ +# define STM32_IRQ_TIM4 (STM32_IRQ_FIRST+30) /* 30: TIM4 global interrupt */ +#endif + +#define STM32_IRQ_I2C1EV (STM32_IRQ_FIRST+31) /* 31: I2C1 event interrupt */ +#define STM32_IRQ_I2C1ER (STM32_IRQ_FIRST+32) /* 32: I2C1 error interrupt */ +#define STM32_IRQ_I2C2EV (STM32_IRQ_FIRST+33) /* 33: I2C2 event interrupt */ +#define STM32_IRQ_I2C2ER (STM32_IRQ_FIRST+34) /* 34: I2C2 error interrupt */ +#define STM32_IRQ_SPI1 (STM32_IRQ_FIRST+35) /* 35: SPI1 global interrupt */ +#define STM32_IRQ_SPI2 (STM32_IRQ_FIRST+36) /* 36: SPI2 global interrupt */ +#define STM32_IRQ_USART1 (STM32_IRQ_FIRST+37) /* 37: USART1 global interrupt */ +#define STM32_IRQ_USART2 (STM32_IRQ_FIRST+38) /* 38: USART2 global interrupt */ + +#if defined(CONFIG_STM32_STM32F410) +# define STM32_IRQ_RESERVED39 (STM32_IRQ_FIRST+39) /* 39: Reserved */ +#else +# define STM32_IRQ_USART3 (STM32_IRQ_FIRST+39) /* 39: USART3 global interrupt */ +#endif + +#define STM32_IRQ_EXTI1510 (STM32_IRQ_FIRST+40) /* 40: EXTI Line[15:10] interrupts */ +#define STM32_IRQ_RTCALRM (STM32_IRQ_FIRST+41) /* 41: RTC alarm through EXTI line interrupt */ + +#if defined(CONFIG_STM32_STM32F410) +# define STM32_IRQ_RESERVED42 (STM32_IRQ_FIRST+42) /* 42: Reserved */ +# define STM32_IRQ_RESERVED43 (STM32_IRQ_FIRST+43) /* 43: Reserved */ +# define STM32_IRQ_RESERVED44 (STM32_IRQ_FIRST+44) /* 44: Reserved */ +# define STM32_IRQ_RESERVED45 (STM32_IRQ_FIRST+45) /* 45: Reserved */ +# define STM32_IRQ_RESERVED46 (STM32_IRQ_FIRST+46) /* 46: Reserved */ +#else +# define STM32_IRQ_OTGFSWKUP (STM32_IRQ_FIRST+42) /* 42: USB On-The-Go FS Wakeup through EXTI line interrupt */ +# define STM32_IRQ_TIM8BRK (STM32_IRQ_FIRST+43) /* 43: TIM8 Break interrupt */ +# define STM32_IRQ_TIM12 (STM32_IRQ_FIRST+43) /* 43: TIM12 global interrupt */ +# define STM32_IRQ_TIM8UP (STM32_IRQ_FIRST+44) /* 44: TIM8 Update interrupt */ +# define STM32_IRQ_TIM13 (STM32_IRQ_FIRST+44) /* 44: TIM13 global interrupt */ +# define STM32_IRQ_TIM8TRGCOM (STM32_IRQ_FIRST+45) /* 45: TIM8 Trigger and Commutation interrupts */ +# define STM32_IRQ_TIM14 (STM32_IRQ_FIRST+45) /* 45: TIM14 global interrupt */ +# define STM32_IRQ_TIM8CC (STM32_IRQ_FIRST+46) /* 46: TIM8 Capture Compare interrupt */ +#endif + +#define STM32_IRQ_DMA1S7 (STM32_IRQ_FIRST+47) /* 47: DMA1 Stream 7 global interrupt */ + +#if defined(CONFIG_STM32_STM32F410) +# define STM32_IRQ_RESERVED48 (STM32_IRQ_FIRST+48) /* 48: Reserved */ +# define STM32_IRQ_RESERVED49 (STM32_IRQ_FIRST+49) /* 48: Reserved */ +#else +# define STM32_IRQ_FSMC (STM32_IRQ_FIRST+48) /* 48: FSMC global interrupt */ +# define STM32_IRQ_SDIO (STM32_IRQ_FIRST+49) /* 49: SDIO global interrupt */ +#endif + +#define STM32_IRQ_TIM5 (STM32_IRQ_FIRST+50) /* 50: TIM5 global interrupt */ + +#if defined(CONFIG_STM32_STM32F410) +# define STM32_IRQ_RESERVED51 (STM32_IRQ_FIRST+51) /* 51: Reserved */ +# define STM32_IRQ_RESERVED52 (STM32_IRQ_FIRST+52) /* 52: Reserved */ +# define STM32_IRQ_RESERVED53 (STM32_IRQ_FIRST+53) /* 53: Reserved */ +#else +# define STM32_IRQ_SPI3 (STM32_IRQ_FIRST+51) /* 51: SPI3 global interrupt */ +# define STM32_IRQ_UART4 (STM32_IRQ_FIRST+52) /* 52: UART4 global interrupt */ +# define STM32_IRQ_UART5 (STM32_IRQ_FIRST+53) /* 53: UART5 global interrupt */ +#endif + +#define STM32_IRQ_TIM6 (STM32_IRQ_FIRST+54) /* 54: TIM6 global interrupt */ +#define STM32_IRQ_DAC (STM32_IRQ_FIRST+54) /* 54: DAC1 and DAC2 underrun error interrupts */ + +#if defined(CONFIG_STM32_STM32F410) +# define STM32_IRQ_RESERVED55 (STM32_IRQ_FIRST+55) /* 55: Reserved */ +#else +# define STM32_IRQ_TIM7 (STM32_IRQ_FIRST+55) /* 55: TIM7 global interrupt */ +#endif + +#define STM32_IRQ_DMA2S0 (STM32_IRQ_FIRST+56) /* 56: DMA2 Stream 0 global interrupt */ +#define STM32_IRQ_DMA2S1 (STM32_IRQ_FIRST+57) /* 57: DMA2 Stream 1 global interrupt */ +#define STM32_IRQ_DMA2S2 (STM32_IRQ_FIRST+58) /* 58: DMA2 Stream 2 global interrupt */ +#define STM32_IRQ_DMA2S3 (STM32_IRQ_FIRST+59) /* 59: DMA2 Stream 3 global interrupt */ +#define STM32_IRQ_DMA2S4 (STM32_IRQ_FIRST+60) /* 60: DMA2 Stream 4 global interrupt */ + #if defined(CONFIG_STM32_STM32F446) -# define STM32_IRQ_RESERVED61 (STM32_IRQ_FIRST+61) /* 61: Reserved */ -# define STM32_IRQ_RESERVED62 (STM32_IRQ_FIRST+62) /* 62: Reserved */ +# define STM32_IRQ_RESERVED61 (STM32_IRQ_FIRST+61) /* 61: Reserved */ +# define STM32_IRQ_RESERVED62 (STM32_IRQ_FIRST+62) /* 62: Reserved */ #else -# define STM32_IRQ_ETH (STM32_IRQ_FIRST+61) /* 61: Ethernet global interrupt */ -# define STM32_IRQ_ETHWKUP (STM32_IRQ_FIRST+62) /* 62: Ethernet Wakeup through EXTI line interrupt */ +# define STM32_IRQ_ETH (STM32_IRQ_FIRST+61) /* 61: Ethernet global interrupt */ +# define STM32_IRQ_ETHWKUP (STM32_IRQ_FIRST+62) /* 62: Ethernet Wakeup through EXTI line interrupt */ #endif -#define STM32_IRQ_CAN2TX (STM32_IRQ_FIRST+63) /* 63: CAN2 TX interrupts */ -#define STM32_IRQ_CAN2RX0 (STM32_IRQ_FIRST+64) /* 64: CAN2 RX0 interrupts */ -#define STM32_IRQ_CAN2RX1 (STM32_IRQ_FIRST+65) /* 65: CAN2 RX1 interrupt */ -#define STM32_IRQ_CAN2SCE (STM32_IRQ_FIRST+66) /* 66: CAN2 SCE interrupt */ -#define STM32_IRQ_OTGFS (STM32_IRQ_FIRST+67) /* 67: USB On The Go FS global interrupt */ -#define STM32_IRQ_DMA2S5 (STM32_IRQ_FIRST+68) /* 68: DMA2 Stream 5 global interrupt */ -#define STM32_IRQ_DMA2S6 (STM32_IRQ_FIRST+69) /* 69: DMA2 Stream 6 global interrupt */ -#define STM32_IRQ_DMA2S7 (STM32_IRQ_FIRST+70) /* 70: DMA2 Stream 7 global interrupt */ -#define STM32_IRQ_USART6 (STM32_IRQ_FIRST+71) /* 71: USART6 global interrupt */ -#define STM32_IRQ_I2C3EV (STM32_IRQ_FIRST+72) /* 72: I2C3 event interrupt */ -#define STM32_IRQ_I2C3ER (STM32_IRQ_FIRST+73) /* 73: I2C3 error interrupt */ -#define STM32_IRQ_OTGHSEP1OUT (STM32_IRQ_FIRST+74) /* 74: USB On The Go HS End Point 1 Out global interrupt */ -#define STM32_IRQ_OTGHSEP1IN (STM32_IRQ_FIRST+75) /* 75: USB On The Go HS End Point 1 In global interrupt */ -#define STM32_IRQ_OTGHSWKUP (STM32_IRQ_FIRST+76) /* 76: USB On The Go HS Wakeup through EXTI interrupt */ -#define STM32_IRQ_OTGHS (STM32_IRQ_FIRST+77) /* 77: USB On The Go HS global interrupt */ -#define STM32_IRQ_DCMI (STM32_IRQ_FIRST+78) /* 78: DCMI global interrupt */ + +#if defined(CONFIG_STM32_STM32F410) +# define STM32_IRQ_RESERVED63 (STM32_IRQ_FIRST+63) /* 63: Reserved */ +# define STM32_IRQ_RESERVED64 (STM32_IRQ_FIRST+64) /* 63: Reserved */ +# define STM32_IRQ_RESERVED65 (STM32_IRQ_FIRST+65) /* 63: Reserved */ +# define STM32_IRQ_RESERVED66 (STM32_IRQ_FIRST+66) /* 63: Reserved */ +# define STM32_IRQ_RESERVED67 (STM32_IRQ_FIRST+67) /* 63: Reserved */ +#else +# define STM32_IRQ_CAN2TX (STM32_IRQ_FIRST+63) /* 63: CAN2 TX interrupts */ +# define STM32_IRQ_CAN2RX0 (STM32_IRQ_FIRST+64) /* 64: CAN2 RX0 interrupts */ +# define STM32_IRQ_CAN2RX1 (STM32_IRQ_FIRST+65) /* 65: CAN2 RX1 interrupt */ +# define STM32_IRQ_CAN2SCE (STM32_IRQ_FIRST+66) /* 66: CAN2 SCE interrupt */ +# define STM32_IRQ_OTGFS (STM32_IRQ_FIRST+67) /* 67: USB On The Go FS global interrupt */ +#endif + +#define STM32_IRQ_DMA2S5 (STM32_IRQ_FIRST+68) /* 68: DMA2 Stream 5 global interrupt */ +#define STM32_IRQ_DMA2S6 (STM32_IRQ_FIRST+69) /* 69: DMA2 Stream 6 global interrupt */ +#define STM32_IRQ_DMA2S7 (STM32_IRQ_FIRST+70) /* 70: DMA2 Stream 7 global interrupt */ +#define STM32_IRQ_USART6 (STM32_IRQ_FIRST+71) /* 71: USART6 global interrupt */ + +#if defined(CONFIG_STM32_STM32F410) +# define STM32_IRQ_RESERVED72 (STM32_IRQ_FIRST+72) /* 72: Reserved */ +# define STM32_IRQ_RESERVED73 (STM32_IRQ_FIRST+73) /* 73: Reserved */ +# define STM32_IRQ_RESERVED74 (STM32_IRQ_FIRST+74) /* 74: Reserved */ +# define STM32_IRQ_RESERVED75 (STM32_IRQ_FIRST+75) /* 75: Reserved */ +# define STM32_IRQ_RESERVED76 (STM32_IRQ_FIRST+76) /* 76: Reserved */ +# define STM32_IRQ_RESERVED77 (STM32_IRQ_FIRST+77) /* 77: Reserved */ +# define STM32_IRQ_RESERVED78 (STM32_IRQ_FIRST+78) /* 78: Reserved */ +#else +# define STM32_IRQ_I2C3EV (STM32_IRQ_FIRST+72) /* 72: I2C3 event interrupt */ +# define STM32_IRQ_I2C3ER (STM32_IRQ_FIRST+73) /* 73: I2C3 error interrupt */ +# define STM32_IRQ_OTGHSEP1OUT (STM32_IRQ_FIRST+74) /* 74: USB On The Go HS End Point 1 Out global interrupt */ +# define STM32_IRQ_OTGHSEP1IN (STM32_IRQ_FIRST+75) /* 75: USB On The Go HS End Point 1 In global interrupt */ +# define STM32_IRQ_OTGHSWKUP (STM32_IRQ_FIRST+76) /* 76: USB On The Go HS Wakeup through EXTI interrupt */ +# define STM32_IRQ_OTGHS (STM32_IRQ_FIRST+77) /* 77: USB On The Go HS global interrupt */ +# define STM32_IRQ_DCMI (STM32_IRQ_FIRST+78) /* 78: DCMI global interrupt */ +#endif + #if defined(CONFIG_STM32_STM32F446) -# define STM32_IRQ_RESERVED79 (STM32_IRQ_FIRST+79) /* 79: Reserved */ -# define STM32_IRQ_RESERVED80 (STM32_IRQ_FIRST+80) /* 80: Reserved */ +# define STM32_IRQ_RESERVED79 (STM32_IRQ_FIRST+79) /* 79: Reserved */ +# define STM32_IRQ_RESERVED80 (STM32_IRQ_FIRST+80) /* 80: Reserved */ #else -# define STM32_IRQ_CRYP (STM32_IRQ_FIRST+79) /* 79: CRYP crypto global interrupt */ -# define STM32_IRQ_HASH (STM32_IRQ_FIRST+80) /* 80: Hash and Rng global interrupt */ -# define STM32_IRQ_RNG (STM32_IRQ_FIRST+80) /* 80: Hash and Rng global interrupt */ +# if defined(CONFIG_STM32_STM32F410) +# define STM32_IRQ_RESERVED79 (STM32_IRQ_FIRST+79) /* 79: Reserved */ +# else +# define STM32_IRQ_CRYP (STM32_IRQ_FIRST+79) /* 79: CRYP crypto global interrupt */ +# endif +# define STM32_IRQ_HASH (STM32_IRQ_FIRST+80) /* 80: Hash and Rng global interrupt */ +# define STM32_IRQ_RNG (STM32_IRQ_FIRST+80) /* 80: Hash and Rng global interrupt */ #endif -#define STM32_IRQ_FPU (STM32_IRQ_FIRST+81) /* 81: FPU global interrupt */ + +#define STM32_IRQ_FPU (STM32_IRQ_FIRST+81) /* 81: FPU global interrupt */ + #if defined(CONFIG_STM32_STM32F427) || defined(CONFIG_STM32_STM32F429) || \ defined(CONFIG_STM32_STM32F469) -# define STM32_IRQ_UART7 (STM32_IRQ_FIRST+82) /* 82: UART7 interrupt */ -# define STM32_IRQ_UART8 (STM32_IRQ_FIRST+83) /* 83: UART8 interrupt */ -#elif defined(CONFIG_STM32_STM32F446) -# define STM32_IRQ_RESERVED82 (STM32_IRQ_FIRST+82) /* 82: Reserved */ -# define STM32_IRQ_RESERVED83 (STM32_IRQ_FIRST+83) /* 83: Reserved */ +# define STM32_IRQ_UART7 (STM32_IRQ_FIRST+82) /* 82: UART7 interrupt */ +# define STM32_IRQ_UART8 (STM32_IRQ_FIRST+83) /* 83: UART8 interrupt */ +#elif defined(CONFIG_STM32_STM32F446) || defined(CONFIG_STM32_STM32F410) +# define STM32_IRQ_RESERVED82 (STM32_IRQ_FIRST+82) /* 82: Reserved */ +# define STM32_IRQ_RESERVED83 (STM32_IRQ_FIRST+83) /* 83: Reserved */ #endif -#if defined(CONFIG_STM32_STM32F427) || defined(CONFIG_STM32_STM32F429) || \ + +#if defined(CONFIG_STM32_STM32F410) +# define STM32_IRQ_RESERVED84 (STM32_IRQ_FIRST+84) /* 84: Reserved */ +#elif defined(CONFIG_STM32_STM32F427) || defined(CONFIG_STM32_STM32F429) || \ defined(CONFIG_STM32_STM32F446) || defined(CONFIG_STM32_STM32F469) -# define STM32_IRQ_SPI4 (STM32_IRQ_FIRST+84) /* 84: SPI4 interrupt */ +# define STM32_IRQ_SPI4 (STM32_IRQ_FIRST+84) /* 84: SPI4 interrupt */ #endif -#if defined(CONFIG_STM32_STM32F427) || defined(CONFIG_STM32_STM32F429) || \ + +#if defined(CONFIG_STM32_STM32F410) +# define STM32_IRQ_SPI5 (STM32_IRQ_FIRST+85) /* 85: SPI5 interrupt */ +# define STM32_IRQ_RESERVED86 (STM32_IRQ_FIRST+86) /* 86: Reserved */ +#elif defined(CONFIG_STM32_STM32F427) || defined(CONFIG_STM32_STM32F429) || \ defined(CONFIG_STM32_STM32F469) -# define STM32_IRQ_SPI5 (STM32_IRQ_FIRST+85) /* 85: SPI5 interrupt */ -# define STM32_IRQ_SPI6 (STM32_IRQ_FIRST+86) /* 86: SPI6 interrupt */ +# define STM32_IRQ_SPI5 (STM32_IRQ_FIRST+85) /* 85: SPI5 interrupt */ +# define STM32_IRQ_SPI6 (STM32_IRQ_FIRST+86) /* 86: SPI6 interrupt */ #elif defined(CONFIG_STM32_STM32F446) -# define STM32_IRQ_RESERVED85 (STM32_IRQ_FIRST+85) /* 85: Reserved */ -# define STM32_IRQ_RESERVED86 (STM32_IRQ_FIRST+86) /* 86: Reserved */ +# define STM32_IRQ_RESERVED85 (STM32_IRQ_FIRST+85) /* 85: Reserved */ +# define STM32_IRQ_RESERVED86 (STM32_IRQ_FIRST+86) /* 86: Reserved */ #endif -#if defined(CONFIG_STM32_STM32F429) || defined(CONFIG_STM32_STM32F446) || \ + +#if defined(CONFIG_STM32_STM32F410) +# define STM32_IRQ_RESERVED87 (STM32_IRQ_FIRST+87) /* 87: Reserved */ +#elif defined(CONFIG_STM32_STM32F429) || defined(CONFIG_STM32_STM32F446) || \ defined(CONFIG_STM32_STM32F446) || defined(CONFIG_STM32_STM32F469) -# define STM32_IRQ_SAI1 (STM32_IRQ_FIRST+87) /* 87: SAI1 interrupt */ +# define STM32_IRQ_SAI1 (STM32_IRQ_FIRST+87) /* 87: SAI1 interrupt */ #endif + #if defined(CONFIG_STM32_STM32F429) || defined(CONFIG_STM32_STM32F469) -# define STM32_IRQ_LTDCINT (STM32_IRQ_FIRST+88) /* 88: LTDCINT interrupt */ -# define STM32_IRQ_LTDCERRINT (STM32_IRQ_FIRST+89) /* 89: LTDCERRINT interrupt */ -# define STM32_IRQ_DMA2D (STM32_IRQ_FIRST+90) /* 90: DMA2D interrupt */ -#elif defined(CONFIG_STM32_STM32F446) -# define STM32_IRQ_RESERVED88 (STM32_IRQ_FIRST+88) /* 88: Reserved */ -# define STM32_IRQ_RESERVED89 (STM32_IRQ_FIRST+89) /* 89: Reserved */ -# define STM32_IRQ_RESERVED90 (STM32_IRQ_FIRST+90) /* 90: Reserved */ +# define STM32_IRQ_LTDCINT (STM32_IRQ_FIRST+88) /* 88: LTDCINT interrupt */ +# define STM32_IRQ_LTDCERRINT (STM32_IRQ_FIRST+89) /* 89: LTDCERRINT interrupt */ +# define STM32_IRQ_DMA2D (STM32_IRQ_FIRST+90) /* 90: DMA2D interrupt */ +#elif defined(CONFIG_STM32_STM32F446) || defined(CONFIG_STM32_STM32F410) +# define STM32_IRQ_RESERVED88 (STM32_IRQ_FIRST+88) /* 88: Reserved */ +# define STM32_IRQ_RESERVED89 (STM32_IRQ_FIRST+89) /* 89: Reserved */ +# define STM32_IRQ_RESERVED90 (STM32_IRQ_FIRST+90) /* 90: Reserved */ #endif -#if defined(CONFIG_STM32_STM32F446) -# define STM32_IRQ_SAI2 (STM32_IRQ_FIRST+91) /* 91: SAI2 Global interrupt */ -# define STM32_IRQ_QUADSPI (STM32_IRQ_FIRST+92) /* 92: QuadSPI Global interrupt */ + +#if defined(CONFIG_STM32_STM32F410) +# define STM32_IRQ_RESERVED91 (STM32_IRQ_FIRST+91) /* 91: Reserved */ +# define STM32_IRQ_RESERVED92 (STM32_IRQ_FIRST+92) /* 92: Reserved */ +#elif defined(CONFIG_STM32_STM32F446) +# define STM32_IRQ_SAI2 (STM32_IRQ_FIRST+91) /* 91: SAI2 Global interrupt */ +# define STM32_IRQ_QUADSPI (STM32_IRQ_FIRST+92) /* 92: QuadSPI Global interrupt */ #elif defined(CONFIG_STM32_STM32F469) -# define STM32_IRQ_QUADSPI (STM32_IRQ_FIRST+91) /* 92: QuadSPI Global interrupt */ -# define STM32_IRQ_DSI (STM32_IRQ_FIRST+92) /* 91: DSI Global interrupt */ +# define STM32_IRQ_QUADSPI (STM32_IRQ_FIRST+91) /* 92: QuadSPI Global interrupt */ +# define STM32_IRQ_DSI (STM32_IRQ_FIRST+92) /* 91: DSI Global interrupt */ #endif + #if defined(CONFIG_STM32_STM32F446) -# define STM32_IRQ_HDMICEC (STM32_IRQ_FIRST+93) /* 93: HDMI-CEC Global interrupt */ -# define STM32_IRQ_SPDIFRX (STM32_IRQ_FIRST+94) /* 94: SPDIF-Rx Global interrupt */ -# define STM32_IRQ_FMPI2C1 (STM32_IRQ_FIRST+95) /* 95: FMPI2C1 event interrupt */ -# define STM32_IRQ_FMPI2C1ERR (STM32_IRQ_FIRST+96) /* 96: FMPI2C1 Error event interrupt */ +# define STM32_IRQ_HDMICEC (STM32_IRQ_FIRST+93) /* 93: HDMI-CEC Global interrupt */ +# define STM32_IRQ_SPDIFRX (STM32_IRQ_FIRST+94) /* 94: SPDIF-Rx Global interrupt */ +# define STM32_IRQ_FMPI2C1 (STM32_IRQ_FIRST+95) /* 95: FMPI2C1 event interrupt */ +# define STM32_IRQ_FMPI2C1ERR (STM32_IRQ_FIRST+96) /* 96: FMPI2C1 Error event interrupt */ +#endif + +#if defined(CONFIG_STM32_STM32F410) +# define STM32_IRQ_RESERVED93 (STM32_IRQ_FIRST+93) /* 93: Reserved */ +# define STM32_IRQ_RESERVED94 (STM32_IRQ_FIRST+94) /* 94: Reserved */ +# define STM32_IRQ_RESERVED95 (STM32_IRQ_FIRST+95) /* 95: Reserved */ +# define STM32_IRQ_RESERVED96 (STM32_IRQ_FIRST+96) /* 96: Reserved */ +# define STM32_IRQ_RESERVED97 (STM32_IRQ_FIRST+97) /* 97: Reserved */ #endif #if defined(CONFIG_STM32_STM32F401) || defined(CONFIG_STM32_STM32F411) || \ defined(CONFIG_STM32_STM32F405) || defined(CONFIG_STM32_STM32F407) -# define NR_VECTORS (STM32_IRQ_FIRST+82) -# define NR_IRQS (STM32_IRQ_FIRST+82) +# define NR_VECTORS (STM32_IRQ_FIRST+82) +# define NR_IRQS (STM32_IRQ_FIRST+82) +#elif defined(CONFIG_STM32_STM32F410) +# define NR_VECTORS (STM32_IRQ_FIRST+98) +# define NR_IRQS (STM32_IRQ_FIRST+98) #elif defined(CONFIG_STM32_STM32F427) -# define NR_VECTORS (STM32_IRQ_FIRST+87) -# define NR_IRQS (STM32_IRQ_FIRST+87) +# define NR_VECTORS (STM32_IRQ_FIRST+87) +# define NR_IRQS (STM32_IRQ_FIRST+87) #elif defined(CONFIG_STM32_STM32F429) -# define NR_VECTORS (STM32_IRQ_FIRST+91) -# define NR_IRQS (STM32_IRQ_FIRST+91) +# define NR_VECTORS (STM32_IRQ_FIRST+91) +# define NR_IRQS (STM32_IRQ_FIRST+91) #elif defined(CONFIG_STM32_STM32F446) -# define NR_VECTORS (STM32_IRQ_FIRST+97) -# define NR_IRQS (STM32_IRQ_FIRST+97) +# define NR_VECTORS (STM32_IRQ_FIRST+97) +# define NR_IRQS (STM32_IRQ_FIRST+97) #elif defined(CONFIG_STM32_STM32F469) -# define NR_VECTORS (STM32_IRQ_FIRST+93) -# define NR_IRQS (STM32_IRQ_FIRST+93) +# define NR_VECTORS (STM32_IRQ_FIRST+93) +# define NR_IRQS (STM32_IRQ_FIRST+93) #endif /**************************************************************************************************** diff --git a/arch/arm/src/stm32/Kconfig b/arch/arm/src/stm32/Kconfig index 2242a018df..647bbee4c1 100644 --- a/arch/arm/src/stm32/Kconfig +++ b/arch/arm/src/stm32/Kconfig @@ -972,6 +972,13 @@ config ARCH_CHIP_STM32F401RE select STM32_STM32F401 select ARCH_HAVE_FPU +config ARCH_CHIP_STM32F410RB + bool "STM32F410RB" + select ARCH_CORTEXM4 + select STM32_STM32F40XX + select STM32_STM32F410 + select ARCH_HAVE_FPU + config ARCH_CHIP_STM32F411RE bool "STM32F411RE" select ARCH_CORTEXM4 @@ -1536,6 +1543,17 @@ config STM32_STM32F401 select STM32_HAVE_TIM10 select STM32_HAVE_TIM11 +config STM32_STM32F410 + bool + default n + select STM32_HAVE_USART6 + select STM32_HAVE_TIM1 + select STM32_HAVE_TIM5 + select STM32_HAVE_TIM6 + select STM32_HAVE_TIM9 + select STM32_HAVE_TIM11 + select STM32_HAVE_SPI5 + config STM32_STM32F411 bool default n diff --git a/arch/arm/src/stm32/chip/stm32f40xxx_vectors.h b/arch/arm/src/stm32/chip/stm32f40xxx_vectors.h index b661cecbc5..31546ed7e6 100644 --- a/arch/arm/src/stm32/chip/stm32f40xxx_vectors.h +++ b/arch/arm/src/stm32/chip/stm32f40xxx_vectors.h @@ -1,7 +1,7 @@ /************************************************************************************ * arch/arm/src/stm32/chip/stm32f40xxx_vectors.h * - * Copyright (C) 2011-2012, 2014-2015 Gregory Nutt. All rights reserved. + * Copyright (C) 2011-2012, 2014-2015, 2017 Gregory Nutt. All rights reserved. * Copyright (C) 2016 Omni Hoverboards Inc. All rights reserved. * Author: Gregory Nutt * David Sidrane @@ -58,6 +58,8 @@ # if defined(CONFIG_STM32_STM32F401) || defined(CONFIG_STM32_STM32F411) || \ defined(CONFIG_STM32_STM32F405) || defined(CONFIG_STM32_STM32F407) # define ARMV7M_PERIPHERAL_INTERRUPTS 82 +# elif defined(CONFIG_STM32_STM32F410) +# define ARMV7M_PERIPHERAL_INTERRUPTS 98 # elif defined(CONFIG_STM32_STM32F427) # define ARMV7M_PERIPHERAL_INTERRUPTS 87 # elif defined(CONFIG_STM32_STM32F429) @@ -89,18 +91,35 @@ VECTOR(stm32_dma1s4, STM32_IRQ_DMA1S4) /* Vector 16+15: DMA1 Stream 4 VECTOR(stm32_dma1s5, STM32_IRQ_DMA1S5) /* Vector 16+16: DMA1 Stream 5 global interrupt */ VECTOR(stm32_dma1s6, STM32_IRQ_DMA1S6) /* Vector 16+17: DMA1 Stream 6 global interrupt */ VECTOR(stm32_adc, STM32_IRQ_ADC) /* Vector 16+18: ADC1, ADC2, and ADC3 global interrupt */ + +#if defined(CONFIG_STM32_STM32F410) +UNUSED(STM32_IRQ_RESERVED19) /* Vector 16+19: Reserved */ +UNUSED(STM32_IRQ_RESERVED20) /* Vector 16+20: Reserved */ +UNUSED(STM32_IRQ_RESERVED21) /* Vector 16+21: Reserved */ +UNUSED(STM32_IRQ_RESERVED22) /* Vector 16+22: Reserved */ +#else VECTOR(stm32_can1tx, STM32_IRQ_CAN1TX) /* Vector 16+19: CAN1 TX interrupts */ VECTOR(stm32_can1rx0, STM32_IRQ_CAN1RX0) /* Vector 16+20: CAN1 RX0 interrupts */ VECTOR(stm32_can1rx1, STM32_IRQ_CAN1RX1) /* Vector 16+21: CAN1 RX1 interrupt */ VECTOR(stm32_can1sce, STM32_IRQ_CAN1SCE) /* Vector 16+22: CAN1 SCE interrupt */ +#endif + VECTOR(stm32_exti95, STM32_IRQ_EXTI95) /* Vector 16+23: EXTI Line[9:5] interrupts */ VECTOR(stm32_tim1brk, STM32_IRQ_TIM1BRK) /* Vector 16+24: TIM1 Break interrupt/TIM9 global interrupt */ VECTOR(stm32_tim1up, STM32_IRQ_TIM1UP) /* Vector 16+25: TIM1 Update interrupt/TIM10 global interrupt */ VECTOR(stm32_tim1trgcom, STM32_IRQ_TIM1TRGCOM) /* Vector 16+26: TIM1 Trigger and Commutation interrupts/TIM11 global interrupt */ VECTOR(stm32_tim1cc, STM32_IRQ_TIM1CC) /* Vector 16+27: TIM1 Capture Compare interrupt */ + +#if defined(CONFIG_STM32_STM32F410) +UNUSED(STM32_IRQ_RESERVED28) /* Vector 16+28: Reserved */ +UNUSED(STM32_IRQ_RESERVED29) /* Vector 16+29: Reserved */ +UNUSED(STM32_IRQ_RESERVED30) /* Vector 16+30: Reserved */ +#else VECTOR(stm32_tim2, STM32_IRQ_TIM2) /* Vector 16+28: TIM2 global interrupt */ VECTOR(stm32_tim3, STM32_IRQ_TIM3) /* Vector 16+29: TIM3 global interrupt */ VECTOR(stm32_tim4, STM32_IRQ_TIM4) /* Vector 16+30: TIM4 global interrupt */ +#endif + VECTOR(stm32_i2c1ev, STM32_IRQ_I2C1EV) /* Vector 16+31: I2C1 event interrupt */ VECTOR(stm32_i2c1er, STM32_IRQ_I2C1ER) /* Vector 16+32: I2C1 error interrupt */ VECTOR(stm32_i2c2ev, STM32_IRQ_I2C2EV) /* Vector 16+33: I2C2 event interrupt */ @@ -109,44 +128,102 @@ VECTOR(stm32_spi1, STM32_IRQ_SPI1) /* Vector 16+35: SPI1 global in VECTOR(stm32_spi2, STM32_IRQ_SPI2) /* Vector 16+36: SPI2 global interrupt */ VECTOR(stm32_usart1, STM32_IRQ_USART1) /* Vector 16+37: USART1 global interrupt */ VECTOR(stm32_usart2, STM32_IRQ_USART2) /* Vector 16+38: USART2 global interrupt */ + +#if defined(CONFIG_STM32_STM32F410) +UNUSED(STM32_IRQ_RESERVED39) /* Vector 16+39: Reserved */ +#else VECTOR(stm32_usart3, STM32_IRQ_USART3) /* Vector 16+39: USART3 global interrupt */ +#endif + VECTOR(stm32_exti1510, STM32_IRQ_EXTI1510) /* Vector 16+40: EXTI Line[15:10] interrupts */ VECTOR(stm32_rtcalrm, STM32_IRQ_RTCALRM) /* Vector 16+41: RTC alarm through EXTI line interrupt */ + +#if defined(CONFIG_STM32_STM32F410) +UNUSED(STM32_IRQ_RESERVED42) /* Vector 16+42: Reserved */ +UNUSED(STM32_IRQ_RESERVED43) /* Vector 16+43: Reserved */ +UNUSED(STM32_IRQ_RESERVED44) /* Vector 16+44: Reserved */ +UNUSED(STM32_IRQ_RESERVED45) /* Vector 16+45: Reserved */ +UNUSED(STM32_IRQ_RESERVED46) /* Vector 16+46: Reserved */ +#else VECTOR(stm32_otgfswkup, STM32_IRQ_OTGFSWKUP) /* Vector 16+42: USB On-The-Go FS Wakeup through EXTI line interrupt */ VECTOR(stm32_tim8brk, STM32_IRQ_TIM8BRK) /* Vector 16+43: TIM8 Break interrupt/TIM12 global interrupt */ VECTOR(stm32_tim8up, STM32_IRQ_TIM8UP) /* Vector 16+44: TIM8 Update interrupt/TIM13 global interrupt */ VECTOR(stm32_tim8trgcom, STM32_IRQ_TIM8TRGCOM) /* Vector 16+45: TIM8 Trigger and Commutation interrupts/TIM14 global interrupt */ VECTOR(stm32_tim8cc, STM32_IRQ_TIM8CC) /* Vector 16+46: TIM8 Capture Compare interrupt */ +#endif + VECTOR(stm32_dma1s7, STM32_IRQ_DMA1S7) /* Vector 16+47: DMA1 Stream 7 global interrupt */ + +#if defined(CONFIG_STM32_STM32F410) +UNUSED(STM32_IRQ_RESERVED48) /* Vector 16+48: Reserved */ +UNUSED(STM32_IRQ_RESERVED49) /* Vector 16+49: Reserved */ +#else VECTOR(stm32_fsmc, STM32_IRQ_FSMC) /* Vector 16+48: FSMC global interrupt */ VECTOR(stm32_sdio, STM32_IRQ_SDIO) /* Vector 16+49: SDIO global interrupt */ +#endif + VECTOR(stm32_tim5, STM32_IRQ_TIM5) /* Vector 16+50: TIM5 global interrupt */ + +#if defined(CONFIG_STM32_STM32F410) +UNUSED(STM32_IRQ_RESERVED51) /* Vector 16+51: Reserved */ +UNUSED(STM32_IRQ_RESERVED52) /* Vector 16+52: Reserved */ +UNUSED(STM32_IRQ_RESERVED53) /* Vector 16+53: Reserved */ +#else VECTOR(stm32_spi3, STM32_IRQ_SPI3) /* Vector 16+51: SPI3 global interrupt */ VECTOR(stm32_uart4, STM32_IRQ_UART4) /* Vector 16+52: UART4 global interrupt */ VECTOR(stm32_uart5, STM32_IRQ_UART5) /* Vector 16+53: UART5 global interrupt */ +#endif + VECTOR(stm32_tim6, STM32_IRQ_TIM6) /* Vector 16+54: TIM6 global interrupt/DAC1 and DAC2 underrun error interrupts */ + +#if defined(CONFIG_STM32_STM32F410) +UNUSED(STM32_IRQ_RESERVED55) /* Vector 16+55: Reserved */ +#else VECTOR(stm32_tim7, STM32_IRQ_TIM7) /* Vector 16+55: TIM7 global interrupt */ +#endif + VECTOR(stm32_dma2s0, STM32_IRQ_DMA2S0) /* Vector 16+56: DMA2 Stream 0 global interrupt */ VECTOR(stm32_dma2s1, STM32_IRQ_DMA2S1) /* Vector 16+57: DMA2 Stream 1 global interrupt */ VECTOR(stm32_dma2s2, STM32_IRQ_DMA2S2) /* Vector 16+58: DMA2 Stream 2 global interrupt */ VECTOR(stm32_dma2s3, STM32_IRQ_DMA2S3) /* Vector 16+59: DMA2 Stream 3 global interrupt */ VECTOR(stm32_dma2s4, STM32_IRQ_DMA2S4) /* Vector 16+60: DMA2 Stream 4 global interrupt */ -#if defined(CONFIG_STM32_STM32F446) + +#if defined(CONFIG_STM32_STM32F446) || defined(CONFIG_STM32_STM32F410) UNUSED(STM32_IRQ_RESERVED61) /* Vector 16+61: Reserved */ UNUSED(STM32_IRQ_RESERVED62) /* Vector 16+62: Reserved */ #else VECTOR(stm32_eth, STM32_IRQ_ETH) /* Vector 16+61: Ethernet global interrupt */ VECTOR(stm32_ethwkup, STM32_IRQ_ETHWKUP) /* Vector 16+62: Ethernet Wakeup through EXTI line interrupt */ #endif + +#if defined(CONFIG_STM32_STM32F410) +UNUSED(STM32_IRQ_RESERVED63) /* Vector 16+63: Reserved */ +UNUSED(STM32_IRQ_RESERVED64) /* Vector 16+64: Reserved */ +UNUSED(STM32_IRQ_RESERVED65) /* Vector 16+65: Reserved */ +UNUSED(STM32_IRQ_RESERVED66) /* Vector 16+66: Reserved */ +UNUSED(STM32_IRQ_RESERVED67) /* Vector 16+67: Reserved */ +#else VECTOR(stm32_can2tx, STM32_IRQ_CAN2TX) /* Vector 16+63: CAN2 TX interrupts */ VECTOR(stm32_can2rx0, STM32_IRQ_CAN2RX0) /* Vector 16+64: CAN2 RX0 interrupts */ VECTOR(stm32_can2rx1, STM32_IRQ_CAN2RX1) /* Vector 16+65: CAN2 RX1 interrupt */ VECTOR(stm32_can2sce, STM32_IRQ_CAN2SCE) /* Vector 16+66: CAN2 SCE interrupt */ VECTOR(stm32_otgfs, STM32_IRQ_OTGFS) /* Vector 16+67: USB On The Go FS global interrupt */ +#endif + VECTOR(stm32_dma2s5, STM32_IRQ_DMA2S5) /* Vector 16+68: DMA2 Stream 5 global interrupt */ VECTOR(stm32_dma2s6, STM32_IRQ_DMA2S6) /* Vector 16+69: DMA2 Stream 6 global interrupt */ VECTOR(stm32_dma2s7, STM32_IRQ_DMA2S7) /* Vector 16+70: DMA2 Stream 7 global interrupt */ VECTOR(stm32_usart6, STM32_IRQ_USART6) /* Vector 16+71: USART6 global interrupt */ + +#if defined(CONFIG_STM32_STM32F410) +UNUSED(STM32_IRQ_RESERVED72) /* Vector 16+72: Reserved */ +UNUSED(STM32_IRQ_RESERVED73) /* Vector 16+73: Reserved */ +UNUSED(STM32_IRQ_RESERVED74) /* Vector 16+74: Reserved */ +UNUSED(STM32_IRQ_RESERVED75) /* Vector 16+75: Reserved */ +UNUSED(STM32_IRQ_RESERVED76) /* Vector 16+76: Reserved */ +UNUSED(STM32_IRQ_RESERVED77) /* Vector 16+77: Reserved */ +UNUSED(STM32_IRQ_RESERVED78) /* Vector 16+78: Reserved */ +#else VECTOR(stm32_i2c3ev, STM32_IRQ_I2C3EV) /* Vector 16+72: I2C3 event interrupt */ VECTOR(stm32_i2c3er, STM32_IRQ_I2C3ER) /* Vector 16+73: I2C3 error interrupt */ VECTOR(stm32_otghsep1out, STM32_IRQ_OTGHSEP1OUT) /* Vector 16+74: USB On The Go HS End Point 1 Out global interrupt */ @@ -154,26 +231,38 @@ VECTOR(stm32_otghsep1in, STM32_IRQ_OTGHSEP1IN) /* Vector 16+75: USB On The Go VECTOR(stm32_otghswkup, STM32_IRQ_OTGHSWKUP) /* Vector 16+76: USB On The Go HS Wakeup through EXTI interrupt */ VECTOR(stm32_otghs, STM32_IRQ_OTGHS) /* Vector 16+77: USB On The Go HS global interrupt */ VECTOR(stm32_dcmi, STM32_IRQ_DCMI) /* Vector 16+78: DCMI global interrupt */ +#endif + #if defined(CONFIG_STM32_STM32F446) UNUSED(STM32_IRQ_RESERVED79) /* Vector 16+79: Reserved */ UNUSED(STM32_IRQ_RESERVED80) /* Vector 16+80: Reserved */ #else +# if defined(CONFIG_STM32_STM32F410) +UNUSED(STM32_IRQ_RESERVED79) /* Vector 16+79: Reserved */ +# else VECTOR(stm32_cryp, STM32_IRQ_CRYP) /* Vector 16+79: CRYP crypto global interrupt */ +# endif VECTOR(stm32_hash, STM32_IRQ_HASH) /* Vector 16+80: Hash and Rng global interrupt */ #endif + VECTOR(stm32_fpu, STM32_IRQ_FPU) /* Vector 16+81: FPU global interrupt */ + #if defined(CONFIG_STM32_STM32F427) || defined(CONFIG_STM32_STM32F429) || \ defined(CONFIG_STM32_STM32F469) VECTOR(stm32_uart7, STM32_IRQ_UART7) /* Vector 16+82: UART7 interrupt */ VECTOR(stm32_uart8, STM32_IRQ_UART8) /* Vector 16+83: UART8 interrupt */ -#elif defined(CONFIG_STM32_STM32F446) +#elif defined(CONFIG_STM32_STM32F446) || defined(CONFIG_STM32_STM32F410) UNUSED(STM32_IRQ_RESERVED82) /* Vector 16+82: Reserved */ UNUSED(STM32_IRQ_RESERVED83) /* Vector 16+83: Reserved */ #endif + #if defined(CONFIG_STM32_STM32F427) || defined(CONFIG_STM32_STM32F429) || \ defined(CONFIG_STM32_STM32F446) || defined(CONFIG_STM32_STM32F469) VECTOR(stm32_spi4, STM32_IRQ_SPI4) /* Vector 16+84: SPI4 interrupt */ +#elif defined(CONFIG_STM32_STM32F410) +UNUSED(STM32_IRQ_RESERVED84) /* Vector 16+84: Reserved */ #endif + #if defined(CONFIG_STM32_STM32F427) || defined(CONFIG_STM32_STM32F429) || \ defined(CONFIG_STM32_STM32F469) VECTOR(stm32_spi5, STM32_IRQ_SPI5) /* Vector 16+85: SPI5 interrupt */ @@ -181,27 +270,39 @@ VECTOR(stm32_spi6, STM32_IRQ_SPI6) /* Vector 16+86: SPI6 interrupt #elif defined(CONFIG_STM32_STM32F446) UNUSED(STM32_IRQ_RESERVED85) /* Vector 16+85: Reserved */ UNUSED(STM32_IRQ_RESERVED86) /* Vector 16+86: Reserved */ +#elif defined(CONFIG_STM32_STM32F410) +VECTOR(stm32_spi5, STM32_IRQ_SPI5) /* Vector 16+85: SPI5 interrupt */ +UNUSED(STM32_IRQ_RESERVED86) /* Vector 16+86: Reserved */ #endif + #if defined(CONFIG_STM32_STM32F429) || defined(CONFIG_STM32_STM32F446) || \ defined(CONFIG_STM32_STM32F446) || defined(CONFIG_STM32_STM32F469) VECTOR(stm32_sai1, STM32_IRQ_SAI1) /* Vector 16+87: SAI1 interrupt */ +#elif defined(CONFIG_STM32_STM32F410) +UNUSED(STM32_IRQ_RESERVED87) /* Vector 16+87: Reserved */ #endif + #if defined(CONFIG_STM32_STM32F429) || defined(CONFIG_STM32_STM32F469) VECTOR(stm32_ltdcint, STM32_IRQ_LTDCINT) /* Vector 16+88: LTDC interrupt */ VECTOR(stm32_ltdcerrint, STM32_IRQ_LTDCERRINT) /* Vector 16+89: LTDC Error interrupt */ VECTOR(stm32_dma2d, STM32_IRQ_DMA2D) /* Vector 16+90: DMA2D interrupt */ -#elif defined(CONFIG_STM32_STM32F446) +#elif defined(CONFIG_STM32_STM32F446) || defined(CONFIG_STM32_STM32F410) UNUSED(STM32_IRQ_RESERVED88) /* Vector 16+88: Reserved */ UNUSED(STM32_IRQ_RESERVED89) /* Vector 16+89: Reserved */ UNUSED(STM32_IRQ_RESERVED90) /* Vector 16+90: Reserved */ #endif -#if defined(CONFIG_STM32_STM32F446) + +#if defined(CONFIG_STM32_STM32F410) +UNUSED(STM32_IRQ_RESERVED91) /* Vector 16+91: Reserved */ +UNUSED(STM32_IRQ_RESERVED92) /* Vector 16+92: Reserved */ +#elif defined(CONFIG_STM32_STM32F446) VECTOR(stm32_sai2, STM32_IRQ_SAI2) /* Vector 16+91: SAI2 Global interrupt */ VECTOR(stm32_quadspi, STM32_IRQ_QUADSPI) /* Vector 16+92: QuadSPI Global interrupt */ #elif defined(CONFIG_STM32_STM32F469) VECTOR(stm32_quadspi, STM32_IRQ_QUADSPI) /* Vector 16+91: QuadSPI Global interrupt */ VECTOR(stm32_dsi, STM32_IRQ_DSI) /* Vector 16+92: DSI Global interrupt */ #endif + #if defined(CONFIG_STM32_STM32F446) VECTOR(stm32_hdmicec, STM32_IRQ_HDMICEC) /* Vector 16+93: HDMI-CEC Global interrupt */ VECTOR(stm32_spdifrx, STM32_IRQ_SPDIFRX) /* Vector 16+94: SPDIF-Rx Global interrupt */ @@ -209,4 +310,12 @@ VECTOR(stm32_fmpi2c1, STM32_IRQ_FMPI2C1) /* Vector 16+95: FMPI2C1 event VECTOR(stm32_fmpi2c1err, STM32_IRQ_FMPI2C1ERR) /* Vector 16+96: FMPI2C1 Error event interrupt */ #endif +#if defined(CONFIG_STM32_STM32F410) +UNUSED(STM32_IRQ_RESERVED93) /* Vector 16+93: Reserved */ +UNUSED(STM32_IRQ_RESERVED94) /* Vector 16+94: Reserved */ +UNUSED(STM32_IRQ_RESERVED95) /* Vector 16+95: Reserved */ +UNUSED(STM32_IRQ_RESERVED96) /* Vector 16+96: Reserved */ +UNUSED(STM32_IRQ_RESERVED97) /* Vector 16+97: Reserved */ +#endif + #endif /* CONFIG_ARMV7M_CMNVECTOR */ diff --git a/arch/arm/src/stm32/stm32_allocateheap.c b/arch/arm/src/stm32/stm32_allocateheap.c index 3e6a73f2cd..a6a9161244 100644 --- a/arch/arm/src/stm32/stm32_allocateheap.c +++ b/arch/arm/src/stm32/stm32_allocateheap.c @@ -353,7 +353,7 @@ /* The STM32 F2 and the STM32 F401/F411 have no CCM SRAM */ # if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F401) || \ - defined(CONFIG_STM32_STM32F411) + defined(CONFIG_STM32_STM32F411) || defined(CONFIG_STM32_STM32F410) # undef CONFIG_STM32_CCMEXCLUDE # define CONFIG_STM32_CCMEXCLUDE 1 # endif @@ -362,6 +362,8 @@ # if defined(CONFIG_STM32_STM32F401) # define SRAM1_END 0x20018000 +# elif defined(CONFIG_STM32_STM32F410) +# define SRAM1_END 0x20008000 # elif defined(CONFIG_STM32_STM32F427) || defined(CONFIG_STM32_STM32F429) # define SRAM1_END 0x20030000 # elif defined(CONFIG_STM32_STM32F446) -- GitLab From 7fe112fe4cb5f86dba88d8fd30c6573862e86aec Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 13 May 2017 11:44:12 -0600 Subject: [PATCH 806/990] Kconfig/deconfigs: Add CONFIG_ARCH_TOOLCHAIN_GNU to indicate that the toolchain is based on GNU gcc/as/ld. This is in addition to the CPU-specific versions of the same definition. --- arch/Kconfig | 4 + arch/arm/Kconfig | 1 + arch/arm/src/armv6-m/Kconfig | 9 ++ arch/mips/src/mips32/Kconfig | 10 ++ arch/misoc/src/lm32/Kconfig | 3 + arch/risc-v/src/rv32im/Kconfig | 2 + arch/xtensa/Kconfig | 1 + configs/arduino-due/nsh/defconfig | 31 +++- configs/clicker2-stm32/knsh/defconfig | 24 +++- .../clicker2-stm32/mrf24j40-radio/defconfig | 30 +++- configs/clicker2-stm32/nsh/defconfig | 46 +++++- configs/clicker2-stm32/usbnsh/defconfig | 41 +++++- configs/esp32-core/nsh/defconfig | 27 +++- configs/esp32-core/ostest/defconfig | 27 +++- configs/esp32-core/smp/defconfig | 27 +++- configs/mikroe-stm32f4/fulldemo/defconfig | 50 ++++++- configs/mikroe-stm32f4/kostest/defconfig | 51 ++++++- configs/mikroe-stm32f4/nsh/defconfig | 49 ++++++- configs/mikroe-stm32f4/nx/defconfig | 48 ++++++- configs/mikroe-stm32f4/nxlines/defconfig | 48 ++++++- configs/mikroe-stm32f4/nxtext/defconfig | 48 ++++++- configs/mikroe-stm32f4/usbnsh/defconfig | 48 ++++++- configs/nr5m100-nexys4/nsh/defconfig | 26 +++- configs/nucleo-144/f746-evalos/defconfig | 36 ++++- configs/nucleo-144/f746-nsh/defconfig | 35 ++++- configs/nucleo-144/f767-evalos/defconfig | 36 ++++- configs/nucleo-144/f767-nsh/defconfig | 35 ++++- configs/nucleo-f303re/uavcan/defconfig | 46 +++++- configs/nucleo-f4x1re/f401-nsh/defconfig | 47 +++++- configs/nucleo-f4x1re/f411-nsh/defconfig | 47 +++++- configs/nucleo-l432kc/nsh/defconfig | 29 ++-- configs/nucleo-l452re/nsh/defconfig | 34 ++++- configs/nucleo-l476rg/nsh/defconfig | 136 +++++++++++++++--- configs/nucleo-l496zg/nsh/defconfig | 34 ++++- configs/olimex-stm32-e407/discover/defconfig | 32 +++-- configs/olimex-stm32-e407/netnsh/defconfig | 32 +++-- configs/olimex-stm32-e407/nsh/defconfig | 47 +++++- configs/olimex-stm32-e407/telnetd/defconfig | 32 +++-- configs/olimex-stm32-e407/usbnsh/defconfig | 47 +++++- configs/olimex-stm32-e407/webserver/defconfig | 32 +++-- configs/olimex-stm32-h405/usbnsh/defconfig | 23 +++ configs/olimex-stm32-h407/nsh/defconfig | 47 +++++- configs/olimex-stm32-p207/nsh/defconfig | 32 +++-- configs/olimex-stm32-p407/knsh/defconfig | 48 ++++++- configs/olimex-stm32-p407/nsh/defconfig | 48 ++++++- configs/olimexino-stm32/can/defconfig | 51 ++++++- configs/olimexino-stm32/composite/defconfig | 51 ++++++- configs/olimexino-stm32/nsh/defconfig | 51 ++++++- configs/olimexino-stm32/smallnsh/defconfig | 48 ++++++- configs/olimexino-stm32/tiny/defconfig | 48 ++++++- configs/pcduino-a10/nsh/defconfig | 31 +++- configs/photon/nsh/defconfig | 28 ++++ configs/photon/usbnsh/defconfig | 64 +++++++-- configs/photon/wlan/defconfig | 23 +-- configs/sabre-6quad/nsh/defconfig | 30 +++- configs/sabre-6quad/smp/defconfig | 29 +++- configs/sam3u-ek/nxwm/defconfig | 31 +++- configs/sam4e-ek/nxwm/defconfig | 29 ++-- configs/sam4l-xplained/nsh/defconfig | 31 +++- configs/sam4s-xplained-pro/nsh/defconfig | 31 +++- configs/sam4s-xplained/nsh/defconfig | 31 +++- configs/sama5d2-xult/nsh/defconfig | 31 +++- configs/sama5d3-xplained/bridge/defconfig | 23 ++- configs/sama5d3-xplained/nsh/defconfig | 31 +++- configs/sama5d3x-ek/demo/defconfig | 32 ++++- configs/sama5d3x-ek/nsh/defconfig | 31 +++- configs/sama5d3x-ek/nx/defconfig | 31 +++- configs/sama5d3x-ek/nxplayer/defconfig | 31 +++- configs/sama5d3x-ek/nxwm/defconfig | 34 ++++- configs/sama5d4-ek/at25boot/defconfig | 31 +++- configs/sama5d4-ek/bridge/defconfig | 23 ++- configs/sama5d4-ek/dramboot/defconfig | 31 +++- configs/sama5d4-ek/elf/defconfig | 30 +++- configs/sama5d4-ek/ipv6/defconfig | 30 ++-- configs/sama5d4-ek/knsh/defconfig | 31 +++- configs/sama5d4-ek/nsh/defconfig | 30 ++-- configs/sama5d4-ek/nxwm/defconfig | 30 ++-- configs/sama5d4-ek/ramtest/defconfig | 31 +++- configs/samd20-xplained/nsh/defconfig | 33 ++++- configs/samd21-xplained/nsh/defconfig | 33 ++++- configs/saml21-xplained/nsh/defconfig | 33 ++++- configs/samv71-xult/nxwm/defconfig | 31 +++- configs/samv71-xult/vnxwm/defconfig | 30 ++-- configs/shenzhou/nxwm/defconfig | 31 ++-- configs/stm3220g-eval/dhcpd/defconfig | 31 ++-- configs/stm3220g-eval/nettest/defconfig | 31 ++-- configs/stm3220g-eval/nsh/defconfig | 31 ++-- configs/stm3220g-eval/nsh2/defconfig | 30 ++-- configs/stm3220g-eval/nxwm/defconfig | 31 ++-- configs/stm3220g-eval/telnetd/defconfig | 31 ++-- configs/stm3240g-eval/dhcpd/defconfig | 31 ++-- configs/stm3240g-eval/discover/defconfig | 32 +++-- configs/stm3240g-eval/knxwm/defconfig | 49 ++++++- configs/stm3240g-eval/nettest/defconfig | 31 ++-- configs/stm3240g-eval/nsh/defconfig | 31 ++-- configs/stm3240g-eval/nsh2/defconfig | 30 ++-- configs/stm3240g-eval/nxterm/defconfig | 31 ++-- configs/stm3240g-eval/nxwm/defconfig | 31 ++-- configs/stm3240g-eval/telnetd/defconfig | 31 ++-- configs/stm3240g-eval/webserver/defconfig | 31 ++-- configs/stm3240g-eval/xmlrpc/defconfig | 32 +++-- configs/stm32f3discovery/nsh/defconfig | 47 +++++- configs/stm32f3discovery/usbnsh/defconfig | 47 +++++- configs/stm32f429i-disco/extflash/defconfig | 51 ++++++- configs/stm32f429i-disco/lcd/defconfig | 51 ++++++- configs/stm32f429i-disco/ltdc/defconfig | 51 ++++++- configs/stm32f429i-disco/nsh/defconfig | 51 ++++++- configs/stm32f429i-disco/nxwm/defconfig | 51 ++++++- configs/stm32f429i-disco/usbmsc/defconfig | 52 ++++++- configs/stm32f429i-disco/usbnsh/defconfig | 50 ++++++- configs/stm32f4discovery/canard/defconfig | 48 ++++++- configs/stm32f4discovery/cxxtest/defconfig | 48 ++++++- configs/stm32f4discovery/ipv6/defconfig | 33 +++-- configs/stm32f4discovery/netnsh/defconfig | 33 +++-- configs/stm32f4discovery/nsh/defconfig | 48 ++++++- configs/stm32f4discovery/nxlines/defconfig | 48 ++++++- configs/stm32f4discovery/pm/defconfig | 49 ++++++- configs/stm32f4discovery/pseudoterm/defconfig | 47 +++++- configs/stm32f4discovery/rgbled/defconfig | 48 ++++++- configs/stm32f4discovery/uavcan/defconfig | 47 +++++- configs/stm32f4discovery/usbnsh/defconfig | 48 ++++++- configs/stm32f4discovery/xen1210/defconfig | 51 ++++++- configs/stm32f746-ws/nsh/defconfig | 39 ++++- configs/stm32f746g-disco/nsh/defconfig | 35 ++++- configs/stm32l476vg-disco/nsh/defconfig | 136 +++++++++++++++--- configs/teensy-lc/nsh/defconfig | 33 ++++- 126 files changed, 4131 insertions(+), 551 deletions(-) diff --git a/arch/Kconfig b/arch/Kconfig index b7d113cf1d..5ed2d5dcea 100644 --- a/arch/Kconfig +++ b/arch/Kconfig @@ -124,6 +124,10 @@ source arch/xtensa/Kconfig source arch/z16/Kconfig source arch/z80/Kconfig +config ARCH_TOOLCHAIN_GNU + bool + default n + comment "Architecture Options" config ARCH_NOINTC diff --git a/arch/arm/Kconfig b/arch/arm/Kconfig index c8964e3c81..8eb1159947 100644 --- a/arch/arm/Kconfig +++ b/arch/arm/Kconfig @@ -463,6 +463,7 @@ config ARM_TOOLCHAIN_IAR config ARM_TOOLCHAIN_GNU bool default n + select ARCH_TOOLCHAIN_GNU config ARMV7M_USEBASEPRI bool "Use BASEPRI Register" diff --git a/arch/arm/src/armv6-m/Kconfig b/arch/arm/src/armv6-m/Kconfig index ed56bc9a71..cd1f9216dc 100644 --- a/arch/arm/src/armv6-m/Kconfig +++ b/arch/arm/src/armv6-m/Kconfig @@ -13,33 +13,41 @@ choice config ARMV6M_TOOLCHAIN_ATOLLIC bool "Atollic Lite/Pro for Windows" depends on TOOLCHAIN_WINDOWS + select ARM_TOOLCHAIN_GNU config ARMV6M_TOOLCHAIN_BUILDROOT bool "Buildroot (Cygwin or Linux)" depends on !WINDOWS_NATIVE + select ARM_TOOLCHAIN_GNU config ARMV6M_TOOLCHAIN_CODEREDL bool "CodeRed for Linux" depends on HOST_LINUX + select ARM_TOOLCHAIN_GNU config ARMV6M_TOOLCHAIN_CODEREDW bool "CodeRed for Windows" depends on TOOLCHAIN_WINDOWS + select ARM_TOOLCHAIN_GNU config ARMV6M_TOOLCHAIN_CODESOURCERYL bool "CodeSourcery GNU toolchain under Linux" depends on HOST_LINUX + select ARM_TOOLCHAIN_GNU config ARMV6M_TOOLCHAIN_CODESOURCERYW bool "CodeSourcery GNU toolchain under Windows" depends on TOOLCHAIN_WINDOWS + select ARM_TOOLCHAIN_GNU config ARMV6M_TOOLCHAIN_DEVKITARM bool "devkitARM GNU toolchain" depends on TOOLCHAIN_WINDOWS + select ARM_TOOLCHAIN_GNU config ARMV6M_TOOLCHAIN_GNU_EABIL bool "Generic GNU EABI toolchain under Linux (or other POSIX environment)" + select ARM_TOOLCHAIN_GNU ---help--- This option should work for any modern GNU toolchain (GCC 4.5 or newer) configured for arm-none-eabi. @@ -47,6 +55,7 @@ config ARMV6M_TOOLCHAIN_GNU_EABIL config ARMV6M_TOOLCHAIN_GNU_EABIW bool "Generic GNU EABI toolchain under Windows" depends on TOOLCHAIN_WINDOWS + select ARM_TOOLCHAIN_GNU ---help--- This option should work for any modern GNU toolchain (GCC 4.5 or newer) configured for arm-none-eabi. diff --git a/arch/mips/src/mips32/Kconfig b/arch/mips/src/mips32/Kconfig index 5363ecbd54..ca4675ec31 100644 --- a/arch/mips/src/mips32/Kconfig +++ b/arch/mips/src/mips32/Kconfig @@ -13,6 +13,7 @@ choice config MIPS32_TOOLCHAIN_GNU_ELF bool "Generic GNU ELF toolchain" + select ARCH_TOOLCHAIN_GNU ---help--- This option should work for any modern GNU toolchain (GCC 4.5 or newer) configured for mips32-elf. @@ -20,38 +21,47 @@ config MIPS32_TOOLCHAIN_GNU_ELF config MIPS32_TOOLCHAIN_MICROCHIPL_XC32 bool "Microchip XC32 toolchain under Linux" depends on HOST_LINUX + select ARCH_TOOLCHAIN_GNU config MIPS32_TOOLCHAIN_MICROCHIPL bool "Microchip C32 toolchain under Linux" depends on HOST_LINUX + select ARCH_TOOLCHAIN_GNU config MIPS32_TOOLCHAIN_MICROCHIPL_LITE bool "Microchip C32 toolchain under Linux (Lite edition)" depends on HOST_LINUX + select ARCH_TOOLCHAIN_GNU config MIPS32_TOOLCHAIN_MICROCHIPW_XC32 bool "Microchip XC32 toolchain under Windows" depends on TOOLCHAIN_WINDOWS + select ARCH_TOOLCHAIN_GNU config MIPS32_TOOLCHAIN_MICROCHIPW bool "Microchip C32 toolchain under Windows" depends on TOOLCHAIN_WINDOWS + select ARCH_TOOLCHAIN_GNU config MIPS32_TOOLCHAIN_MICROCHIPW_LITE bool "Microchip C32 toolchain under Windows (Lite edition)" depends on TOOLCHAIN_WINDOWS + select ARCH_TOOLCHAIN_GNU config MIPS32_TOOLCHAIN_MICROCHIPOPENL bool "microchipOpen toolchain under Linux" depends on HOST_LINUX + select ARCH_TOOLCHAIN_GNU config MIPS32_TOOLCHAIN_PINGUINOW bool "Pinguino mips-elf toolchain under Windows" depends on TOOLCHAIN_WINDOWS + select ARCH_TOOLCHAIN_GNU config MIPS32_TOOLCHAIN_PINGUINOL bool "Pinguino mips-elf toolchain under OS X or Linux" depends on HOST_LINUX || HOST_OSX + select ARCH_TOOLCHAIN_GNU endchoice diff --git a/arch/misoc/src/lm32/Kconfig b/arch/misoc/src/lm32/Kconfig index c10407ef28..fe021ee6ae 100644 --- a/arch/misoc/src/lm32/Kconfig +++ b/arch/misoc/src/lm32/Kconfig @@ -13,9 +13,11 @@ choice config LM32_TOOLCHAIN_BUILDROOT bool "Buildroot (Cygwin or Linux)" depends on !WINDOWS_NATIVE + select ARCH_TOOLCHAIN_GNU config LM32_TOOLCHAIN_GNUL bool "Generic GNU toolchain under Linux (or other POSIX environment)" + select ARCH_TOOLCHAIN_GNU ---help--- This option should work for any modern GNU toolchain (GCC 4.5 or newer) configured for lm32-elf-. @@ -23,6 +25,7 @@ config LM32_TOOLCHAIN_GNUL config LM32_TOOLCHAIN_GNUW bool "Generic GNU toolchain under Windows" depends on TOOLCHAIN_WINDOWS + select ARCH_TOOLCHAIN_GNU ---help--- This option should work for any modern GNU toolchain (GCC 4.5 or newer) configured for lm32-elf-. diff --git a/arch/risc-v/src/rv32im/Kconfig b/arch/risc-v/src/rv32im/Kconfig index e1607047b0..7bb70adf29 100644 --- a/arch/risc-v/src/rv32im/Kconfig +++ b/arch/risc-v/src/rv32im/Kconfig @@ -12,12 +12,14 @@ choice config RV32IM_TOOLCHAIN_GNU_RVGL bool "Generic GNU RVG toolchain under Linux (or other POSIX environment)" + select ARCH_TOOLCHAIN_GNU ---help--- This option should work for any modern GNU toolchain (GCC 5.2 or newer) configured for riscv32-unknown-elf. config RV32IM_TOOLCHAIN_GNU_RVGW bool "Generic GNU RVG toolchain under Windows" + select ARCH_TOOLCHAIN_GNU depends on TOOLCHAIN_WINDOWS ---help--- This option should work for any modern GNU toolchain (GCC 5.2 or newer) diff --git a/arch/xtensa/Kconfig b/arch/xtensa/Kconfig index b00d8f0d23..948f0edd53 100644 --- a/arch/xtensa/Kconfig +++ b/arch/xtensa/Kconfig @@ -14,6 +14,7 @@ config ARCH_CHIP_ESP32 select ARCH_FAMILY_LX6 select XTENSA_HAVE_INTERRUPTS select ARCH_HAVE_MULTICPU + select ARCH_TOOLCHAIN_GNU ---help--- The ESP32 is a dual-core system from Expressif with two Harvard architecture Xtensa LX6 CPUs. All embedded memory, external memory diff --git a/configs/arduino-due/nsh/defconfig b/configs/arduino-due/nsh/defconfig index 00694eb692..a43823cce6 100644 --- a/configs/arduino-due/nsh/defconfig +++ b/configs/arduino-due/nsh/defconfig @@ -28,6 +28,7 @@ CONFIG_BUILD_FLAT=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -89,6 +90,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -96,11 +98,12 @@ CONFIG_ARCH="arm" CONFIG_ARCH_CHIP_SAM34=y # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -266,6 +269,7 @@ CONFIG_SAM34_HAVE_GPIOE_IRQ=y CONFIG_SAM34_HAVE_GPIOF_IRQ=y # CONFIG_SAM34_GPIO_IRQ is not set # CONFIG_SAM34_TC is not set +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -286,6 +290,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -394,6 +399,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -574,6 +581,7 @@ CONFIG_UART0_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -582,7 +590,9 @@ CONFIG_UART0_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -636,6 +646,11 @@ CONFIG_MM_REGIONS=3 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -644,6 +659,7 @@ CONFIG_MM_REGIONS=3 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -810,7 +826,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -842,6 +857,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1008,3 +1024,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/clicker2-stm32/knsh/defconfig b/configs/clicker2-stm32/knsh/defconfig index f25787284d..5a4d128ac2 100644 --- a/configs/clicker2-stm32/knsh/defconfig +++ b/configs/clicker2-stm32/knsh/defconfig @@ -33,6 +33,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -269,6 +270,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -327,6 +329,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -531,6 +534,7 @@ CONFIG_STM32_USART3_SERIALDRIVER=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -754,11 +758,6 @@ CONFIG_DEV_NULL=y # # Buffering # - -# -# Common I/O Buffer Support -# -# CONFIG_MM_IOB is not set # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -875,7 +874,9 @@ CONFIG_USART3_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -945,6 +946,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -953,6 +959,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1330,3 +1337,10 @@ CONFIG_READLINE_ECHO=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/clicker2-stm32/mrf24j40-radio/defconfig b/configs/clicker2-stm32/mrf24j40-radio/defconfig index 33284b022c..95adaa7012 100644 --- a/configs/clicker2-stm32/mrf24j40-radio/defconfig +++ b/configs/clicker2-stm32/mrf24j40-radio/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -98,6 +99,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set @@ -174,6 +176,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -259,6 +264,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -317,6 +323,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -528,6 +535,7 @@ CONFIG_STM32_USART3_SERIALDRIVER=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -548,6 +556,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -883,7 +892,9 @@ CONFIG_IEEE802154_MRF24J40=y # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -951,6 +962,14 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=8 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=0 + # # Audio Support # @@ -963,7 +982,10 @@ CONFIG_WIRELESS=y CONFIG_WIRELESS_IEEE802154=y CONFIG_IEEE802154_MAC=y # CONFIG_IEEE802154_MAC_DEV is not set -CONFIG_IEEE802154_DEV=y +CONFIG_MAC802154_HPWORK=y +CONFIG_IEEE802154_NTXDESC=3 +CONFIG_IEEE802154_IND_PREALLOC=20 +CONFIG_IEEE802154_IND_IRQRESERVE=10 # # Binary Loader @@ -1350,6 +1372,8 @@ CONFIG_READLINE_ECHO=y # # IEEE 802.15.4 applications # -CONFIG_IEEE802154_COMMON=y -CONFIG_IEEE802154_COORD=y +# CONFIG_IEEE802154_LIBMAC is not set +CONFIG_IEEE802154_LIBUTILS=y CONFIG_IEEE802154_I8SAK=y +CONFIG_IEEE802154_I8SAK_PRIORITY=100 +CONFIG_IEEE802154_I8SAK_STACKSIZE=2048 diff --git a/configs/clicker2-stm32/nsh/defconfig b/configs/clicker2-stm32/nsh/defconfig index 22ba79f501..02dc18e067 100644 --- a/configs/clicker2-stm32/nsh/defconfig +++ b/configs/clicker2-stm32/nsh/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -98,6 +99,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set @@ -174,6 +176,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -259,6 +264,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -317,6 +323,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -373,9 +380,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -389,7 +400,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -410,6 +424,7 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set # CONFIG_STM32_OTGFS is not set # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -513,6 +528,7 @@ CONFIG_STM32_USART3_SERIALDRIVER=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -533,6 +549,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -653,6 +670,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -839,6 +858,7 @@ CONFIG_USART3_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -847,7 +867,9 @@ CONFIG_USART3_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -886,10 +908,6 @@ CONFIG_FS_WRITABLE=y CONFIG_FS_MQUEUE_MPATH="/var/mqueue" # CONFIG_FS_RAMMAP is not set # CONFIG_FS_FAT is not set -# CONFIG_FS_FATTIME is not set -# CONFIG_FAT_FORCE_INDIRECT is not set -# CONFIG_FAT_DMAMEMORY is not set -# CONFIG_FAT_DIRECT_RETRY is not set # CONFIG_FS_NXFFS is not set # CONFIG_FS_ROMFS is not set # CONFIG_FS_TMPFS is not set @@ -919,6 +937,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -927,6 +950,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1224,7 +1248,6 @@ CONFIG_NSH_DISABLE_LOSMART=y # CONFIG_NSH_DISABLE_LS is not set # CONFIG_NSH_DISABLE_MB is not set # CONFIG_NSH_DISABLE_MKDIR is not set -# CONFIG_NSH_DISABLE_MKFATFS is not set # CONFIG_NSH_DISABLE_MKRD is not set # CONFIG_NSH_DISABLE_MH is not set # CONFIG_NSH_DISABLE_MOUNT is not set @@ -1305,3 +1328,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/clicker2-stm32/usbnsh/defconfig b/configs/clicker2-stm32/usbnsh/defconfig index 55d3bb7423..943e8a7cc8 100644 --- a/configs/clicker2-stm32/usbnsh/defconfig +++ b/configs/clicker2-stm32/usbnsh/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -98,6 +99,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set @@ -174,6 +176,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -259,6 +264,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -317,6 +323,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -373,9 +380,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -389,7 +400,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -410,6 +424,7 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set CONFIG_STM32_OTGFS=y # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -513,6 +528,7 @@ CONFIG_STM32_USART3_SERIALDRIVER=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -533,6 +549,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -654,6 +671,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -879,6 +898,7 @@ CONFIG_CDCACM_VENDORSTR="NuttX" CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial" # CONFIG_USBMSC is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -887,7 +907,9 @@ CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial" # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set CONFIG_SYSLOG_INTBUFFER=y CONFIG_SYSLOG_INTBUFSIZE=396 # CONFIG_SYSLOG_TIMESTAMP is not set @@ -964,6 +986,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -972,6 +999,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1352,3 +1380,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/esp32-core/nsh/defconfig b/configs/esp32-core/nsh/defconfig index 5b2d824242..3336506326 100644 --- a/configs/esp32-core/nsh/defconfig +++ b/configs/esp32-core/nsh/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -100,6 +101,7 @@ CONFIG_ESP32_ULP_COPROC_RESERVE_MEM=0 # CONFIG_ESP32_UART0_TXPIN=0 CONFIG_ESP32_UART0_RXPIN=0 +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -120,6 +122,7 @@ CONFIG_ARCH_HAVE_MULTICPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set # CONFIG_ARCH_HAVE_RESET is not set +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set CONFIG_ARCH_STACKDUMP=y # CONFIG_ENDIAN_BIG is not set # CONFIG_ARCH_IDLE_CUSTOM is not set @@ -226,6 +229,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -413,6 +418,7 @@ CONFIG_UART0_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -421,7 +427,9 @@ CONFIG_UART0_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -489,6 +497,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -497,6 +510,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -661,7 +675,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -694,6 +707,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -864,3 +878,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/esp32-core/ostest/defconfig b/configs/esp32-core/ostest/defconfig index 1add834b7a..f85490c507 100644 --- a/configs/esp32-core/ostest/defconfig +++ b/configs/esp32-core/ostest/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -100,6 +101,7 @@ CONFIG_ESP32_ULP_COPROC_RESERVE_MEM=0 # CONFIG_ESP32_UART0_TXPIN=0 CONFIG_ESP32_UART0_RXPIN=0 +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -120,6 +122,7 @@ CONFIG_ARCH_HAVE_MULTICPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set # CONFIG_ARCH_HAVE_RESET is not set +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set CONFIG_ARCH_STACKDUMP=y # CONFIG_ENDIAN_BIG is not set # CONFIG_ARCH_IDLE_CUSTOM is not set @@ -226,6 +229,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -413,6 +418,7 @@ CONFIG_UART0_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -421,7 +427,9 @@ CONFIG_UART0_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -489,6 +497,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -497,6 +510,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -661,7 +675,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set # CONFIG_EXAMPLES_NSH is not set # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -698,6 +711,7 @@ CONFIG_EXAMPLES_OSTEST_WAITRESULT=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -773,3 +787,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/esp32-core/smp/defconfig b/configs/esp32-core/smp/defconfig index e603eab3a7..327cbc8976 100644 --- a/configs/esp32-core/smp/defconfig +++ b/configs/esp32-core/smp/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -100,6 +101,7 @@ CONFIG_ESP32_ULP_COPROC_RESERVE_MEM=0 # CONFIG_ESP32_UART0_TXPIN=0 CONFIG_ESP32_UART0_RXPIN=0 +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -120,6 +122,7 @@ CONFIG_ARCH_HAVE_MULTICPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set # CONFIG_ARCH_HAVE_RESET is not set +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set CONFIG_ARCH_STACKDUMP=y # CONFIG_ENDIAN_BIG is not set # CONFIG_ARCH_IDLE_CUSTOM is not set @@ -228,6 +231,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -415,6 +420,7 @@ CONFIG_UART0_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -423,7 +429,9 @@ CONFIG_UART0_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -491,6 +499,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -499,6 +512,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -663,7 +677,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -699,6 +712,7 @@ CONFIG_EXAMPLES_SMP_STACKSIZE=2048 # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -869,3 +883,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/mikroe-stm32f4/fulldemo/defconfig b/configs/mikroe-stm32f4/fulldemo/defconfig index bbf651b901..e3bfddddd7 100644 --- a/configs/mikroe-stm32f4/fulldemo/defconfig +++ b/configs/mikroe-stm32f4/fulldemo/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -173,6 +176,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -258,6 +264,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -316,6 +323,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -372,9 +380,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -388,7 +400,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set CONFIG_STM32_ADC2=y # CONFIG_STM32_ADC3 is not set @@ -409,6 +424,7 @@ CONFIG_STM32_DMA1=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set CONFIG_STM32_OTGFS=y # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -448,6 +464,7 @@ CONFIG_STM32_SPI=y # Alternate Pin Mapping # CONFIG_STM32_FLASH_PREFETCH=y +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -481,6 +498,7 @@ CONFIG_STM32_DMACAPABLE=y # # ADC Configuration # +# CONFIG_STM32_ADC_NO_STARTUP_CONV is not set CONFIG_STM32_USART=y CONFIG_STM32_SERIALDRIVER=y @@ -513,6 +531,7 @@ CONFIG_STM32_SPI_DMA=y # CONFIG_STM32_HAVE_RTC_SUBSECONDS is not set CONFIG_RTC_MAGIC_REG=0 CONFIG_RTC_MAGIC=0xfacefeee +CONFIG_RTC_MAGIC_TIME_SET=0xfacefeef CONFIG_RTC_LSECLOCK=y # CONFIG_RTC_LSICLOCK is not set # CONFIG_RTC_HSECLOCK is not set @@ -532,6 +551,7 @@ CONFIG_RTC_LSECLOCK=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -552,6 +572,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -595,6 +616,7 @@ CONFIG_RAM_SIZE=114688 # # Board Selection # +# CONFIG_ARCH_BOARD_CLICKER2_STM32 is not set # CONFIG_ARCH_BOARD_STM32F4_DISCOVERY is not set CONFIG_ARCH_BOARD_MIKROE_STM32F4=y # CONFIG_ARCH_BOARD_CUSTOM is not set @@ -671,6 +693,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -1018,6 +1042,7 @@ CONFIG_CDCACM_VENDORSTR="NuttX" CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial" # CONFIG_USBMSC is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -1026,7 +1051,9 @@ CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial" # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set # CONFIG_SYSLOG_SERIAL_CONSOLE is not set @@ -1211,6 +1238,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -1252,6 +1284,7 @@ CONFIG_AUDIO_EXCLUDE_REWIND=y # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1429,7 +1462,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set # CONFIG_EXAMPLES_MTDPART is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1485,6 +1517,7 @@ CONFIG_EXAMPLES_TOUCHSCREEN_ARCHINIT=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1886,3 +1919,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/mikroe-stm32f4/kostest/defconfig b/configs/mikroe-stm32f4/kostest/defconfig index 821dbd9b9f..46e0e594fe 100644 --- a/configs/mikroe-stm32f4/kostest/defconfig +++ b/configs/mikroe-stm32f4/kostest/defconfig @@ -33,6 +33,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -95,6 +96,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -102,11 +104,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -179,6 +182,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -264,6 +270,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -322,6 +329,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -378,9 +386,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -394,7 +406,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set CONFIG_STM32_ADC2=y # CONFIG_STM32_ADC3 is not set @@ -415,6 +430,7 @@ CONFIG_STM32_ADC2=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set CONFIG_STM32_OTGFS=y # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -454,6 +470,7 @@ CONFIG_STM32_SPI=y # Alternate Pin Mapping # CONFIG_STM32_FLASH_PREFETCH=y +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -486,6 +503,7 @@ CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG=y # # ADC Configuration # +# CONFIG_STM32_ADC_NO_STARTUP_CONV is not set CONFIG_STM32_USART=y CONFIG_STM32_SERIALDRIVER=y @@ -517,6 +535,7 @@ CONFIG_STM32_USART2_SERIALDRIVER=y # CONFIG_STM32_HAVE_RTC_SUBSECONDS is not set CONFIG_RTC_MAGIC_REG=0 CONFIG_RTC_MAGIC=0xfacefeee +CONFIG_RTC_MAGIC_TIME_SET=0xfacefeef CONFIG_RTC_LSECLOCK=y # CONFIG_RTC_LSICLOCK is not set # CONFIG_RTC_HSECLOCK is not set @@ -536,6 +555,7 @@ CONFIG_RTC_LSECLOCK=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -556,6 +576,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set CONFIG_ARCH_USE_MPU=y # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -599,6 +620,7 @@ CONFIG_RAM_SIZE=114688 # # Board Selection # +# CONFIG_ARCH_BOARD_CLICKER2_STM32 is not set # CONFIG_ARCH_BOARD_STM32F4_DISCOVERY is not set CONFIG_ARCH_BOARD_MIKROE_STM32F4=y # CONFIG_ARCH_BOARD_CUSTOM is not set @@ -673,6 +695,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -973,6 +997,7 @@ CONFIG_CDCACM_VENDORSTR="NuttX" CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial" # CONFIG_USBMSC is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -981,7 +1006,9 @@ CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial" # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set # CONFIG_SYSLOG_SERIAL_CONSOLE is not set @@ -1053,6 +1080,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -1061,6 +1093,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1226,6 +1259,7 @@ CONFIG_HAVE_CXXINITIALIZE=y # CONFIG_EXAMPLES_FTPD is not set # CONFIG_EXAMPLES_HELLO is not set # CONFIG_EXAMPLES_HELLOXX is not set +# CONFIG_EXAMPLES_HIDKBD is not set # CONFIG_EXAMPLES_IGMP is not set # CONFIG_EXAMPLES_JSON is not set # CONFIG_EXAMPLES_KEYPADTEST is not set @@ -1233,7 +1267,6 @@ CONFIG_HAVE_CXXINITIALIZE=y # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NSH_CXXINITIALIZE is not set # CONFIG_EXAMPLES_NULL is not set @@ -1272,6 +1305,7 @@ CONFIG_EXAMPLES_OSTEST_WAITRESULT=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1450,3 +1484,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/mikroe-stm32f4/nsh/defconfig b/configs/mikroe-stm32f4/nsh/defconfig index fa6618f860..5a7361f71b 100644 --- a/configs/mikroe-stm32f4/nsh/defconfig +++ b/configs/mikroe-stm32f4/nsh/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -173,6 +176,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -258,6 +264,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -316,6 +323,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -372,9 +380,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -388,7 +400,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -409,6 +424,7 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set # CONFIG_STM32_OTGFS is not set # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -447,6 +463,7 @@ CONFIG_STM32_SPI=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -518,6 +535,7 @@ CONFIG_STM32_USART2_SERIALDRIVER=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -538,6 +556,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -581,6 +600,7 @@ CONFIG_RAM_SIZE=114688 # # Board Selection # +# CONFIG_ARCH_BOARD_CLICKER2_STM32 is not set # CONFIG_ARCH_BOARD_STM32F4_DISCOVERY is not set CONFIG_ARCH_BOARD_MIKROE_STM32F4=y # CONFIG_ARCH_BOARD_CUSTOM is not set @@ -648,6 +668,9 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -896,6 +919,7 @@ CONFIG_USART2_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -904,7 +928,9 @@ CONFIG_USART2_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set # CONFIG_SYSLOG_SERIAL_CONSOLE is not set @@ -975,6 +1001,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -983,6 +1014,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1159,7 +1191,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set # CONFIG_EXAMPLES_MTDPART is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1196,6 +1227,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1374,3 +1406,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/mikroe-stm32f4/nx/defconfig b/configs/mikroe-stm32f4/nx/defconfig index 762f5db69a..f725a5e05e 100644 --- a/configs/mikroe-stm32f4/nx/defconfig +++ b/configs/mikroe-stm32f4/nx/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -172,6 +175,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -257,6 +263,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -315,6 +322,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -371,9 +379,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -387,7 +399,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -408,6 +423,7 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set # CONFIG_STM32_OTGFS is not set # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -445,6 +461,7 @@ CONFIG_STM32_SYSCFG=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -489,6 +506,7 @@ CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -509,6 +527,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -552,6 +571,7 @@ CONFIG_RAM_SIZE=114688 # # Board Selection # +# CONFIG_ARCH_BOARD_CLICKER2_STM32 is not set # CONFIG_ARCH_BOARD_STM32F4_DISCOVERY is not set CONFIG_ARCH_BOARD_MIKROE_STM32F4=y # CONFIG_ARCH_BOARD_CUSTOM is not set @@ -622,6 +642,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -783,6 +805,7 @@ CONFIG_LCD_LANDSCAPE=y # CONFIG_SERIAL is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -791,7 +814,9 @@ CONFIG_LCD_LANDSCAPE=y # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set # CONFIG_SYSLOG_SERIAL_CONSOLE is not set @@ -942,6 +967,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -950,6 +980,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1121,7 +1152,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set # CONFIG_EXAMPLES_NSH is not set # CONFIG_EXAMPLES_NULL is not set CONFIG_EXAMPLES_NX=y @@ -1161,6 +1191,7 @@ CONFIG_EXAMPLES_NX_TOOLBAR_HEIGHT=16 # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1330,3 +1361,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/mikroe-stm32f4/nxlines/defconfig b/configs/mikroe-stm32f4/nxlines/defconfig index 0c3708e13a..3d0cfb98af 100644 --- a/configs/mikroe-stm32f4/nxlines/defconfig +++ b/configs/mikroe-stm32f4/nxlines/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -172,6 +175,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -257,6 +263,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -315,6 +322,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -371,9 +379,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -387,7 +399,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -408,6 +423,7 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set # CONFIG_STM32_OTGFS is not set # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -445,6 +461,7 @@ CONFIG_STM32_SYSCFG=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -489,6 +506,7 @@ CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -509,6 +527,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -552,6 +571,7 @@ CONFIG_RAM_SIZE=114688 # # Board Selection # +# CONFIG_ARCH_BOARD_CLICKER2_STM32 is not set # CONFIG_ARCH_BOARD_STM32F4_DISCOVERY is not set CONFIG_ARCH_BOARD_MIKROE_STM32F4=y # CONFIG_ARCH_BOARD_CUSTOM is not set @@ -622,6 +642,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -783,6 +805,7 @@ CONFIG_LCD_LANDSCAPE=y # CONFIG_SERIAL is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -791,7 +814,9 @@ CONFIG_LCD_LANDSCAPE=y # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set # CONFIG_SYSLOG_SERIAL_CONSOLE is not set @@ -942,6 +967,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -950,6 +980,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1120,7 +1151,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set # CONFIG_EXAMPLES_NSH is not set # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -1163,6 +1193,7 @@ CONFIG_EXAMPLES_NXLINES_BPP=16 # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1331,3 +1362,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/mikroe-stm32f4/nxtext/defconfig b/configs/mikroe-stm32f4/nxtext/defconfig index 00091f13c8..37b66b8c38 100644 --- a/configs/mikroe-stm32f4/nxtext/defconfig +++ b/configs/mikroe-stm32f4/nxtext/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -172,6 +175,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -257,6 +263,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -315,6 +322,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -371,9 +379,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -387,7 +399,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -408,6 +423,7 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set # CONFIG_STM32_OTGFS is not set # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -445,6 +461,7 @@ CONFIG_STM32_SYSCFG=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -489,6 +506,7 @@ CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -509,6 +527,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -552,6 +571,7 @@ CONFIG_RAM_SIZE=114688 # # Board Selection # +# CONFIG_ARCH_BOARD_CLICKER2_STM32 is not set # CONFIG_ARCH_BOARD_STM32F4_DISCOVERY is not set CONFIG_ARCH_BOARD_MIKROE_STM32F4=y # CONFIG_ARCH_BOARD_CUSTOM is not set @@ -622,6 +642,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -783,6 +805,7 @@ CONFIG_LCD_LANDSCAPE=y # CONFIG_SERIAL is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -791,7 +814,9 @@ CONFIG_LCD_LANDSCAPE=y # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set # CONFIG_SYSLOG_SERIAL_CONSOLE is not set @@ -942,6 +967,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -950,6 +980,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1120,7 +1151,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set # CONFIG_EXAMPLES_NSH is not set # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -1173,6 +1203,7 @@ CONFIG_EXAMPLES_NXTEXT_DEFAULT_FONT=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1341,3 +1372,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/mikroe-stm32f4/usbnsh/defconfig b/configs/mikroe-stm32f4/usbnsh/defconfig index 6aff27e81a..b70490f816 100644 --- a/configs/mikroe-stm32f4/usbnsh/defconfig +++ b/configs/mikroe-stm32f4/usbnsh/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -173,6 +176,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -258,6 +264,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -316,6 +323,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -372,9 +380,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -388,7 +400,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -409,6 +424,7 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set CONFIG_STM32_OTGFS=y # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -447,6 +463,7 @@ CONFIG_STM32_SPI=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -518,6 +535,7 @@ CONFIG_STM32_USART2_SERIALDRIVER=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -538,6 +556,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -581,6 +600,7 @@ CONFIG_RAM_SIZE=114688 # # Board Selection # +# CONFIG_ARCH_BOARD_CLICKER2_STM32 is not set # CONFIG_ARCH_BOARD_STM32F4_DISCOVERY is not set CONFIG_ARCH_BOARD_MIKROE_STM32F4=y # CONFIG_ARCH_BOARD_CUSTOM is not set @@ -657,6 +677,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -945,6 +967,7 @@ CONFIG_CDCACM_VENDORSTR="NuttX" CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial" # CONFIG_USBMSC is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -953,7 +976,9 @@ CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial" # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set # CONFIG_SYSLOG_SERIAL_CONSOLE is not set @@ -1024,6 +1049,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -1032,6 +1062,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1208,7 +1239,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set # CONFIG_EXAMPLES_MTDPART is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1245,6 +1275,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1425,3 +1456,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/nr5m100-nexys4/nsh/defconfig b/configs/nr5m100-nexys4/nsh/defconfig index d3e363576f..16f28bfcae 100644 --- a/configs/nr5m100-nexys4/nsh/defconfig +++ b/configs/nr5m100-nexys4/nsh/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -110,6 +111,7 @@ CONFIG_NR5_UART1=y CONFIG_NR5_UART=y CONFIG_NR5_UART_RX_BUF_SIZE=64 CONFIG_NR5_UART_TX_BUF_SIZE=64 +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -130,6 +132,7 @@ CONFIG_NR5_UART_TX_BUF_SIZE=64 # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set # CONFIG_ARCH_HAVE_RESET is not set +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set CONFIG_ARCH_STACKDUMP=y # CONFIG_ARCH_IDLE_CUSTOM is not set # CONFIG_ARCH_HAVE_RAMFUNCS is not set @@ -232,6 +235,8 @@ CONFIG_MAX_TASKS=16 # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -425,6 +430,7 @@ CONFIG_UART1_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -433,6 +439,7 @@ CONFIG_UART1_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +# CONFIG_SYSLOG_WRITE is not set # CONFIG_RAMLOG is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set @@ -494,6 +501,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -502,6 +514,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -668,7 +681,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -701,6 +713,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -868,3 +881,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/nucleo-144/f746-evalos/defconfig b/configs/nucleo-144/f746-evalos/defconfig index 5603a1aaa2..7661a07ba8 100644 --- a/configs/nucleo-144/f746-evalos/defconfig +++ b/configs/nucleo-144/f746-evalos/defconfig @@ -28,6 +28,7 @@ CONFIG_BUILD_FLAT=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set CONFIG_ARCH_CHIP_STM32F7=y # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -244,6 +247,7 @@ CONFIG_STM32F7_STM32F746XX=y # CONFIG_STM32F7_STM32F779XX is not set # CONFIG_STM32F7_STM32F779AX is not set # CONFIG_STM32F7_FLASH_CONFIG_E is not set +CONFIG_STM32F7_FLASH_CONFIG_G=y # CONFIG_STM32F7_FLASH_CONFIG_I is not set CONFIG_STM32F7_FLASH_OVERRIDE_DEFAULT=y # CONFIG_STM32F7_FLASH_OVERRIDE_E is not set @@ -346,17 +350,17 @@ CONFIG_STM32F7_USART3=y # # U[S]ART Configuration # -CONFIG_STM32F7_FLOWCONTROL_BROKEN=y CONFIG_STM32F7_USART_BREAKS=y CONFIG_STM32F7_SERIALBRK_BSDCOMPAT=y # CONFIG_STM32F7_HAVE_RTC_COUNTER is not set -# CONFIG_STM32F7_HAVE_RTC_SUBSECONDS is not set +CONFIG_STM32F7_HAVE_RTC_SUBSECONDS=y # CONFIG_STM32F7_CUSTOM_CLOCKCONFIG is not set # CONFIG_STM32F7_DTCMEXCLUDE is not set # # Timer Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -377,6 +381,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +CONFIG_ARCH_HAVE_RTC_SUBSECONDS=y # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -490,6 +495,9 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -692,6 +700,7 @@ CONFIG_USART3_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -700,7 +709,9 @@ CONFIG_USART3_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -761,6 +772,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -769,6 +785,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -945,7 +962,6 @@ CONFIG_EXAMPLES_LEDS_LEDSET=0x0f # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -978,6 +994,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1151,3 +1168,14 @@ CONFIG_READLINE_CMD_HISTORY_LEN=16 # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/nucleo-144/f746-nsh/defconfig b/configs/nucleo-144/f746-nsh/defconfig index 98eb5c263e..076d5b8c8a 100644 --- a/configs/nucleo-144/f746-nsh/defconfig +++ b/configs/nucleo-144/f746-nsh/defconfig @@ -28,6 +28,7 @@ CONFIG_BUILD_FLAT=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set CONFIG_ARCH_CHIP_STM32F7=y # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -244,6 +247,7 @@ CONFIG_STM32F7_STM32F746XX=y # CONFIG_STM32F7_STM32F779XX is not set # CONFIG_STM32F7_STM32F779AX is not set # CONFIG_STM32F7_FLASH_CONFIG_E is not set +CONFIG_STM32F7_FLASH_CONFIG_G=y # CONFIG_STM32F7_FLASH_CONFIG_I is not set CONFIG_STM32F7_FLASH_OVERRIDE_DEFAULT=y # CONFIG_STM32F7_FLASH_OVERRIDE_E is not set @@ -346,17 +350,17 @@ CONFIG_STM32F7_USART6=y # # U[S]ART Configuration # -CONFIG_STM32F7_FLOWCONTROL_BROKEN=y CONFIG_STM32F7_USART_BREAKS=y CONFIG_STM32F7_SERIALBRK_BSDCOMPAT=y # CONFIG_STM32F7_HAVE_RTC_COUNTER is not set -# CONFIG_STM32F7_HAVE_RTC_SUBSECONDS is not set +CONFIG_STM32F7_HAVE_RTC_SUBSECONDS=y # CONFIG_STM32F7_CUSTOM_CLOCKCONFIG is not set # CONFIG_STM32F7_DTCMEXCLUDE is not set # # Timer Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -377,6 +381,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +CONFIG_ARCH_HAVE_RTC_SUBSECONDS=y # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -491,6 +496,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -680,6 +687,7 @@ CONFIG_USART6_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -688,7 +696,9 @@ CONFIG_USART6_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -748,6 +758,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -756,6 +771,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -926,7 +942,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NSH_CXXINITIALIZE is not set # CONFIG_EXAMPLES_NULL is not set @@ -958,6 +973,7 @@ CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1127,3 +1143,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/nucleo-144/f767-evalos/defconfig b/configs/nucleo-144/f767-evalos/defconfig index 57a3aeeed0..a6a7365474 100644 --- a/configs/nucleo-144/f767-evalos/defconfig +++ b/configs/nucleo-144/f767-evalos/defconfig @@ -28,6 +28,7 @@ CONFIG_BUILD_FLAT=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set CONFIG_ARCH_CHIP_STM32F7=y # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -244,6 +247,7 @@ CONFIG_STM32F7_STM32F767XX=y # CONFIG_STM32F7_STM32F779XX is not set # CONFIG_STM32F7_STM32F779AX is not set # CONFIG_STM32F7_FLASH_CONFIG_E is not set +# CONFIG_STM32F7_FLASH_CONFIG_G is not set CONFIG_STM32F7_FLASH_CONFIG_I=y CONFIG_STM32F7_FLASH_OVERRIDE_DEFAULT=y # CONFIG_STM32F7_FLASH_OVERRIDE_E is not set @@ -350,17 +354,17 @@ CONFIG_STM32F7_USART3=y # # U[S]ART Configuration # -CONFIG_STM32F7_FLOWCONTROL_BROKEN=y CONFIG_STM32F7_USART_BREAKS=y CONFIG_STM32F7_SERIALBRK_BSDCOMPAT=y # CONFIG_STM32F7_HAVE_RTC_COUNTER is not set -# CONFIG_STM32F7_HAVE_RTC_SUBSECONDS is not set +CONFIG_STM32F7_HAVE_RTC_SUBSECONDS=y # CONFIG_STM32F7_CUSTOM_CLOCKCONFIG is not set # CONFIG_STM32F7_DTCMEXCLUDE is not set # # Timer Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -381,6 +385,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +CONFIG_ARCH_HAVE_RTC_SUBSECONDS=y # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -494,6 +499,9 @@ CONFIG_SCHED_WAITPID=y # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -696,6 +704,7 @@ CONFIG_USART3_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -704,7 +713,9 @@ CONFIG_USART3_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -765,6 +776,11 @@ CONFIG_MM_REGIONS=3 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -773,6 +789,7 @@ CONFIG_MM_REGIONS=3 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -949,7 +966,6 @@ CONFIG_EXAMPLES_LEDS_LEDSET=0x0f # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -982,6 +998,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1155,3 +1172,14 @@ CONFIG_READLINE_CMD_HISTORY_LEN=16 # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/nucleo-144/f767-nsh/defconfig b/configs/nucleo-144/f767-nsh/defconfig index 772f1f89b6..165ae152cf 100644 --- a/configs/nucleo-144/f767-nsh/defconfig +++ b/configs/nucleo-144/f767-nsh/defconfig @@ -28,6 +28,7 @@ CONFIG_BUILD_FLAT=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set CONFIG_ARCH_CHIP_STM32F7=y # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -244,6 +247,7 @@ CONFIG_STM32F7_STM32F767XX=y # CONFIG_STM32F7_STM32F779XX is not set # CONFIG_STM32F7_STM32F779AX is not set # CONFIG_STM32F7_FLASH_CONFIG_E is not set +# CONFIG_STM32F7_FLASH_CONFIG_G is not set CONFIG_STM32F7_FLASH_CONFIG_I=y CONFIG_STM32F7_FLASH_OVERRIDE_DEFAULT=y # CONFIG_STM32F7_FLASH_OVERRIDE_E is not set @@ -350,17 +354,17 @@ CONFIG_STM32F7_USART6=y # # U[S]ART Configuration # -CONFIG_STM32F7_FLOWCONTROL_BROKEN=y CONFIG_STM32F7_USART_BREAKS=y CONFIG_STM32F7_SERIALBRK_BSDCOMPAT=y # CONFIG_STM32F7_HAVE_RTC_COUNTER is not set -# CONFIG_STM32F7_HAVE_RTC_SUBSECONDS is not set +CONFIG_STM32F7_HAVE_RTC_SUBSECONDS=y # CONFIG_STM32F7_CUSTOM_CLOCKCONFIG is not set # CONFIG_STM32F7_DTCMEXCLUDE is not set # # Timer Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -381,6 +385,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +CONFIG_ARCH_HAVE_RTC_SUBSECONDS=y # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -495,6 +500,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -684,6 +691,7 @@ CONFIG_USART6_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -692,7 +700,9 @@ CONFIG_USART6_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -752,6 +762,11 @@ CONFIG_MM_REGIONS=3 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -760,6 +775,7 @@ CONFIG_MM_REGIONS=3 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -930,7 +946,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NSH_CXXINITIALIZE is not set # CONFIG_EXAMPLES_NULL is not set @@ -962,6 +977,7 @@ CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1131,3 +1147,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/nucleo-f303re/uavcan/defconfig b/configs/nucleo-f303re/uavcan/defconfig index 090fcb42e8..ee831187d6 100644 --- a/configs/nucleo-f303re/uavcan/defconfig +++ b/configs/nucleo-f303re/uavcan/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -172,6 +175,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -257,6 +263,7 @@ CONFIG_ARCH_CHIP_STM32F303RE=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -315,6 +322,7 @@ CONFIG_STM32_STM32F303=y # CONFIG_STM32_STM32F37XX is not set # CONFIG_STM32_STM32F40XX is not set # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set # CONFIG_STM32_STM32F407 is not set @@ -371,9 +379,13 @@ CONFIG_STM32_HAVE_ADC4=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y # CONFIG_STM32_HAVE_CAN2 is not set +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y # CONFIG_STM32_HAVE_RNG is not set @@ -387,7 +399,10 @@ CONFIG_STM32_HAVE_SPI4=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -401,6 +416,7 @@ CONFIG_STM32_HAVE_SPI4=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set # CONFIG_STM32_PWR is not set # CONFIG_STM32_SDIO is not set # CONFIG_STM32_SPI1 is not set @@ -432,6 +448,7 @@ CONFIG_STM32_SYSCFG=y # # Alternate Pin Mapping # +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -468,6 +485,7 @@ CONFIG_STM32_JTAG_SW_ENABLE=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -488,6 +506,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -599,6 +618,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -730,6 +751,7 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y # CONFIG_SERIAL is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -738,6 +760,7 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y # System Logging # # CONFIG_ARCH_SYSLOG is not set +# CONFIG_SYSLOG_WRITE is not set # CONFIG_RAMLOG is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set @@ -796,6 +819,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -804,6 +832,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -999,7 +1028,6 @@ CONFIG_LIBUAVCAN_INIT_RETRIES=0 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set # CONFIG_EXAMPLES_NSH is not set # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -1033,6 +1061,7 @@ CONFIG_EXAMPLES_UAVCAN_NODE_ID=1 CONFIG_EXAMPLES_UAVCAN_NODE_NAME="org.nuttx.apps.examples.uavcan" # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1104,3 +1133,14 @@ CONFIG_EXAMPLES_UAVCAN_NODE_NAME="org.nuttx.apps.examples.uavcan" # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/nucleo-f4x1re/f401-nsh/defconfig b/configs/nucleo-f4x1re/f401-nsh/defconfig index 6ac098d6b0..5a0c090de1 100644 --- a/configs/nucleo-f4x1re/f401-nsh/defconfig +++ b/configs/nucleo-f4x1re/f401-nsh/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -173,6 +176,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -258,6 +264,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set CONFIG_ARCH_CHIP_STM32F401RE=y +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -316,6 +323,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y CONFIG_STM32_STM32F401=y +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set # CONFIG_STM32_STM32F407 is not set @@ -372,9 +380,13 @@ CONFIG_STM32_HAVE_TIM11=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set # CONFIG_STM32_HAVE_CAN1 is not set # CONFIG_STM32_HAVE_CAN2 is not set +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set # CONFIG_STM32_HAVE_DAC1 is not set # CONFIG_STM32_HAVE_DAC2 is not set # CONFIG_STM32_HAVE_RNG is not set @@ -388,7 +400,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_BKPSRAM is not set # CONFIG_STM32_CCMDATARAM is not set @@ -401,6 +416,7 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set CONFIG_STM32_OTGFS=y # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -428,6 +444,7 @@ CONFIG_STM32_USART2=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -487,6 +504,7 @@ CONFIG_STM32_USART2_SERIALDRIVER=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -507,6 +525,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -618,6 +637,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -807,6 +828,7 @@ CONFIG_USART2_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -815,7 +837,9 @@ CONFIG_USART2_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -875,6 +899,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -883,6 +912,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1053,7 +1083,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1085,6 +1114,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1252,3 +1282,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/nucleo-f4x1re/f411-nsh/defconfig b/configs/nucleo-f4x1re/f411-nsh/defconfig index ddbdc44dac..13e3a553fe 100644 --- a/configs/nucleo-f4x1re/f411-nsh/defconfig +++ b/configs/nucleo-f4x1re/f411-nsh/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -173,6 +176,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -258,6 +264,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set CONFIG_ARCH_CHIP_STM32F411RE=y # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -316,6 +323,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set CONFIG_STM32_STM32F411=y # CONFIG_STM32_STM32F405 is not set # CONFIG_STM32_STM32F407 is not set @@ -372,9 +380,13 @@ CONFIG_STM32_HAVE_TIM11=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set # CONFIG_STM32_HAVE_CAN1 is not set # CONFIG_STM32_HAVE_CAN2 is not set +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set # CONFIG_STM32_HAVE_DAC1 is not set # CONFIG_STM32_HAVE_DAC2 is not set # CONFIG_STM32_HAVE_RNG is not set @@ -388,7 +400,10 @@ CONFIG_STM32_HAVE_SPI5=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_BKPSRAM is not set # CONFIG_STM32_CCMDATARAM is not set @@ -401,6 +416,7 @@ CONFIG_STM32_CRC=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set CONFIG_STM32_OTGFS=y # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -430,6 +446,7 @@ CONFIG_STM32_USART2=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -489,6 +506,7 @@ CONFIG_STM32_USART2_SERIALDRIVER=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -509,6 +527,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -620,6 +639,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -809,6 +830,7 @@ CONFIG_USART2_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -817,7 +839,9 @@ CONFIG_USART2_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -877,6 +901,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -885,6 +914,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1055,7 +1085,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1087,6 +1116,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1254,3 +1284,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/nucleo-l432kc/nsh/defconfig b/configs/nucleo-l432kc/nsh/defconfig index 1f261b0c1d..c8fae71740 100644 --- a/configs/nucleo-l432kc/nsh/defconfig +++ b/configs/nucleo-l432kc/nsh/defconfig @@ -16,7 +16,7 @@ CONFIG_HOST_LINUX=y # # Build Configuration # -CONFIG_APPS_DIR="../apps" +# CONFIG_APPS_DIR="../apps" CONFIG_BUILD_FLAT=y # CONFIG_BUILD_2PASS is not set @@ -362,6 +362,7 @@ CONFIG_STM32L4_HAVE_USART3=y # # CONFIG_STM32L4_FLOWCONTROL_BROKEN is not set # CONFIG_STM32L4_USART_BREAKS is not set +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -427,9 +428,6 @@ CONFIG_RAM_SIZE=98304 # Board Selection # CONFIG_ARCH_BOARD_NUCLEO_L432KC=y -# CONFIG_ARCH_BOARD_NUCLEO_L476RG is not set -# CONFIG_ARCH_BOARD_STM32L476VG_DISCO is not set -# CONFIG_ARCH_BOARD_STM32L476_MDK is not set # CONFIG_ARCH_BOARD_CUSTOM is not set CONFIG_ARCH_BOARD="nucleo-l432kc" @@ -578,11 +576,6 @@ CONFIG_DEV_RANDOM=y # # Buffering # - -# -# Common I/O Buffer Support -# -# CONFIG_DRIVERS_IOB is not set # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -714,7 +707,9 @@ CONFIG_USART2_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -774,6 +769,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -930,7 +930,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # # CAN Utilities # -# CONFIG_CANUTILS_CANDUMP is not set # # Examples @@ -962,10 +961,10 @@ CONFIG_EXAMPLES_ALARM_SIGNO=1 CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NX is not set # CONFIG_EXAMPLES_NXFFS is not set # CONFIG_EXAMPLES_NXHELLO is not set # CONFIG_EXAMPLES_NXIMAGE is not set -# CONFIG_EXAMPLES_NX is not set # CONFIG_EXAMPLES_NXLINES is not set # CONFIG_EXAMPLES_NXTERM is not set # CONFIG_EXAMPLES_NXTEXT is not set @@ -1022,7 +1021,6 @@ CONFIG_EXAMPLES_NSAMPLES=8 # Interpreters # # CONFIG_INTERPRETERS_FICL is not set -# CONFIG_INTERPRETERS_LUA is not set # CONFIG_INTERPRETERS_MICROPYTHON is not set # CONFIG_INTERPRETERS_MINIBASIC is not set # CONFIG_INTERPRETERS_PCODE is not set @@ -1173,3 +1171,10 @@ CONFIG_READLINE_ECHO=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/nucleo-l452re/nsh/defconfig b/configs/nucleo-l452re/nsh/defconfig index c09ddaf382..b01b5c2356 100644 --- a/configs/nucleo-l452re/nsh/defconfig +++ b/configs/nucleo-l452re/nsh/defconfig @@ -16,7 +16,7 @@ CONFIG_HOST_LINUX=y # # Build Configuration # -CONFIG_APPS_DIR="../apps" +# CONFIG_APPS_DIR="../apps" CONFIG_BUILD_FLAT=y # CONFIG_BUILD_2PASS is not set @@ -28,6 +28,7 @@ CONFIG_BUILD_FLAT=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -199,6 +200,14 @@ CONFIG_SERIAL_TERMIOS=y # CONFIG_ARCH_CHIP_STM32L432KB is not set # CONFIG_ARCH_CHIP_STM32L432KC is not set # CONFIG_ARCH_CHIP_STM32L442KC is not set +# CONFIG_ARCH_CHIP_STM32L433CB is not set +# CONFIG_ARCH_CHIP_STM32L433CC is not set +# CONFIG_ARCH_CHIP_STM32L433RB is not set +# CONFIG_ARCH_CHIP_STM32L433RC is not set +# CONFIG_ARCH_CHIP_STM32L433VC is not set +# CONFIG_ARCH_CHIP_STM32L443CC is not set +# CONFIG_ARCH_CHIP_STM32L443RC is not set +# CONFIG_ARCH_CHIP_STM32L443VC is not set # CONFIG_ARCH_CHIP_STM32L451CC is not set # CONFIG_ARCH_CHIP_STM32L451CE is not set # CONFIG_ARCH_CHIP_STM32L451RC is not set @@ -409,6 +418,7 @@ CONFIG_STM32L4_I2CTIMEOSEC=0 CONFIG_STM32L4_I2CTIMEOMS=500 CONFIG_STM32L4_I2CTIMEOTICKS=500 # CONFIG_STM32L4_I2C_DUTY16_9 is not set +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -623,11 +633,6 @@ CONFIG_DEV_RANDOM=y # # Buffering # - -# -# Common I/O Buffer Support -# -# CONFIG_MM_IOB is not set # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -770,7 +775,9 @@ CONFIG_USART2_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -838,6 +845,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -846,6 +858,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1025,10 +1038,10 @@ CONFIG_EXAMPLES_ALARM_SIGNO=1 CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NX is not set # CONFIG_EXAMPLES_NXFFS is not set # CONFIG_EXAMPLES_NXHELLO is not set # CONFIG_EXAMPLES_NXIMAGE is not set -# CONFIG_EXAMPLES_NX is not set # CONFIG_EXAMPLES_NXLINES is not set # CONFIG_EXAMPLES_NXTERM is not set # CONFIG_EXAMPLES_NXTEXT is not set @@ -1256,3 +1269,10 @@ CONFIG_SYSTEM_TEE_PRIORITY=100 # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/nucleo-l476rg/nsh/defconfig b/configs/nucleo-l476rg/nsh/defconfig index f78446519f..80a8d83c9c 100644 --- a/configs/nucleo-l476rg/nsh/defconfig +++ b/configs/nucleo-l476rg/nsh/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set CONFIG_ARCH_CHIP_STM32L4=y # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -129,7 +132,7 @@ CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y # CONFIG_ARMV7M_LAZYFPU is not set CONFIG_ARCH_HAVE_FPU=y -CONFIG_ARCH_HAVE_DPFPU=y +# CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_FPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set CONFIG_ARM_HAVE_MPU_UNIFIED=y @@ -140,10 +143,8 @@ CONFIG_ARM_HAVE_MPU_UNIFIED=y # # CONFIG_ARMV7M_HAVE_ICACHE is not set # CONFIG_ARMV7M_HAVE_DCACHE is not set -CONFIG_ARMV7M_HAVE_ITCM=y -CONFIG_ARMV7M_HAVE_DTCM=y -# CONFIG_ARMV7M_ITCM is not set -# CONFIG_ARMV7M_DTCM is not set +# CONFIG_ARMV7M_HAVE_ITCM is not set +# CONFIG_ARMV7M_HAVE_DTCM is not set # CONFIG_ARMV7M_TOOLCHAIN_IARL is not set # CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set # CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set @@ -160,16 +161,73 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # # STM32L4 Configuration Options # +# CONFIG_ARCH_CHIP_STM32L432KB is not set +# CONFIG_ARCH_CHIP_STM32L432KC is not set +# CONFIG_ARCH_CHIP_STM32L442KC is not set +# CONFIG_ARCH_CHIP_STM32L433CB is not set +# CONFIG_ARCH_CHIP_STM32L433CC is not set +# CONFIG_ARCH_CHIP_STM32L433RB is not set +# CONFIG_ARCH_CHIP_STM32L433RC is not set +# CONFIG_ARCH_CHIP_STM32L433VC is not set +# CONFIG_ARCH_CHIP_STM32L443CC is not set +# CONFIG_ARCH_CHIP_STM32L443RC is not set +# CONFIG_ARCH_CHIP_STM32L443VC is not set +# CONFIG_ARCH_CHIP_STM32L451CC is not set +# CONFIG_ARCH_CHIP_STM32L451CE is not set +# CONFIG_ARCH_CHIP_STM32L451RC is not set +# CONFIG_ARCH_CHIP_STM32L451RE is not set +# CONFIG_ARCH_CHIP_STM32L451VC is not set +# CONFIG_ARCH_CHIP_STM32L451VE is not set +# CONFIG_ARCH_CHIP_STM32L452CC is not set +# CONFIG_ARCH_CHIP_STM32L452CE is not set +# CONFIG_ARCH_CHIP_STM32L452RC is not set +# CONFIG_ARCH_CHIP_STM32L452RE is not set +# CONFIG_ARCH_CHIP_STM32L452VC is not set +# CONFIG_ARCH_CHIP_STM32L452VE is not set +# CONFIG_ARCH_CHIP_STM32L462CE is not set +# CONFIG_ARCH_CHIP_STM32L462RE is not set +# CONFIG_ARCH_CHIP_STM32L462VE is not set CONFIG_ARCH_CHIP_STM32L476RG=y # CONFIG_ARCH_CHIP_STM32L476RE is not set # CONFIG_ARCH_CHIP_STM32L486 is not set +# CONFIG_ARCH_CHIP_STM32L496ZE is not set +# CONFIG_ARCH_CHIP_STM32L496ZG is not set +# CONFIG_ARCH_CHIP_STM32L4A6 is not set +# CONFIG_STM32L4_STM32L4X1 is not set +# CONFIG_STM32L4_STM32L4X2 is not set # CONFIG_STM32L4_STM32L4X3 is not set +# CONFIG_STM32L4_STM32L4X5 is not set CONFIG_STM32L4_STM32L4X6=y +# CONFIG_STM32L4_STM32L431XX is not set +# CONFIG_STM32L4_STM32L432XX is not set +# CONFIG_STM32L4_STM32L433XX is not set +# CONFIG_STM32L4_STM32L442XX is not set +# CONFIG_STM32L4_STM32L443XX is not set +# CONFIG_STM32L4_STM32L451XX is not set +# CONFIG_STM32L4_STM32L452XX is not set +# CONFIG_STM32L4_STM32L462XX is not set +# CONFIG_STM32L4_STM32L471XX is not set CONFIG_STM32L4_STM32L476XX=y # CONFIG_STM32L4_STM32L486XX is not set -# CONFIG_STM32L4_FLASH_256KB is not set -# CONFIG_STM32L4_FLASH_512KB is not set -CONFIG_STM32L4_FLASH_1024KB=y +# CONFIG_STM32L4_STM32L496XX is not set +# CONFIG_STM32L4_STM32L4A6XX is not set +CONFIG_STM32L4_FLASH_OVERRIDE_DEFAULT=y +# CONFIG_STM32L4_FLASH_OVERRIDE_B is not set +# CONFIG_STM32L4_FLASH_OVERRIDE_C is not set +# CONFIG_STM32L4_FLASH_OVERRIDE_E is not set +# CONFIG_STM32L4_FLASH_OVERRIDE_G is not set +# CONFIG_STM32L4_FLASH_CONFIG_C is not set +# CONFIG_STM32L4_FLASH_CONFIG_E is not set +CONFIG_STM32L4_FLASH_CONFIG_G=y +# CONFIG_STM32L4_IO_CONFIG_K is not set +# CONFIG_STM32L4_IO_CONFIG_C is not set +CONFIG_STM32L4_IO_CONFIG_R=y +# CONFIG_STM32L4_IO_CONFIG_J is not set +# CONFIG_STM32L4_IO_CONFIG_M is not set +# CONFIG_STM32L4_IO_CONFIG_V is not set +# CONFIG_STM32L4_IO_CONFIG_Q is not set +# CONFIG_STM32L4_IO_CONFIG_Z is not set +# CONFIG_STM32L4_IO_CONFIG_A is not set # # STM32L4 SRAM2 Options @@ -184,12 +242,32 @@ CONFIG_STM32L4_SRAM2_INIT=y # # STM32L4 Peripheral Support # +CONFIG_STM32L4_HAVE_ADC2=y +CONFIG_STM32L4_HAVE_ADC3=y +# CONFIG_STM32L4_HAVE_AES is not set +# CONFIG_STM32L4_HAVE_CAN2 is not set +CONFIG_STM32L4_HAVE_COMP=y +CONFIG_STM32L4_HAVE_DAC2=y +# CONFIG_STM32L4_HAVE_DCMI is not set +# CONFIG_STM32L4_HAVE_DFSDM1 is not set +# CONFIG_STM32L4_HAVE_DMA2D is not set +CONFIG_STM32L4_HAVE_FSMC=y +# CONFIG_STM32L4_HAVE_HASH is not set +# CONFIG_STM32L4_HAVE_I2C4 is not set +CONFIG_STM32L4_HAVE_LCD=y # CONFIG_STM32L4_HAVE_LTDC is not set CONFIG_STM32L4_HAVE_LPTIM1=y CONFIG_STM32L4_HAVE_LPTIM2=y -CONFIG_STM32L4_HAVE_COMP=y +CONFIG_STM32L4_HAVE_OTGFS=y CONFIG_STM32L4_HAVE_SAI1=y CONFIG_STM32L4_HAVE_SAI2=y +CONFIG_STM32L4_HAVE_SDMMC1=y +CONFIG_STM32L4_HAVE_TIM3=y +CONFIG_STM32L4_HAVE_TIM4=y +CONFIG_STM32L4_HAVE_TIM5=y +CONFIG_STM32L4_HAVE_TIM7=y +CONFIG_STM32L4_HAVE_TIM8=y +CONFIG_STM32L4_HAVE_TIM17=y # CONFIG_STM32L4_ADC is not set # CONFIG_STM32L4_CAN is not set # CONFIG_STM32L4_DAC is not set @@ -215,17 +293,12 @@ CONFIG_STM32L4_DMA2=y # CONFIG_STM32L4_ADC1 is not set # CONFIG_STM32L4_ADC2 is not set # CONFIG_STM32L4_ADC3 is not set -# CONFIG_STM32L4_AES is not set CONFIG_STM32L4_RNG=y -# CONFIG_STM32L4_SAI1_A is not set -# CONFIG_STM32L4_SAI1_B is not set -# CONFIG_STM32L4_SAI2_A is not set -# CONFIG_STM32L4_SAI2_B is not set # # AHB3 Peripherals # -# CONFIG_STM32L4_FMC is not set +# CONFIG_STM32L4_FSMC is not set # CONFIG_STM32L4_QSPI is not set # @@ -273,7 +346,6 @@ CONFIG_STM32L4_FIREWALL=y # CONFIG_STM32L4_COMP is not set # CONFIG_STM32L4_SAI1 is not set # CONFIG_STM32L4_SAI2 is not set -# CONFIG_STM32L4_DFSDM is not set # # Other Peripherals @@ -295,6 +367,10 @@ CONFIG_STM32L4_SAI1PLL=y # # CONFIG_STM32L4_ONESHOT is not set # CONFIG_STM32L4_FREERUN is not set +# CONFIG_STM32L4_TIM3_CAP is not set +# CONFIG_STM32L4_TIM4_CAP is not set +# CONFIG_STM32L4_TIM5_CAP is not set +# CONFIG_STM32L4_TIM8_CAP is not set CONFIG_STM32L4_HAVE_USART1=y CONFIG_STM32L4_HAVE_USART2=y CONFIG_STM32L4_HAVE_USART3=y @@ -306,6 +382,7 @@ CONFIG_STM32L4_HAVE_UART5=y # # CONFIG_STM32L4_FLOWCONTROL_BROKEN is not set # CONFIG_STM32L4_USART_BREAKS is not set +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -326,6 +403,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -443,6 +521,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -640,6 +720,7 @@ CONFIG_USART2_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -648,7 +729,9 @@ CONFIG_USART2_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -708,6 +791,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -716,6 +804,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -891,7 +980,6 @@ CONFIG_EXAMPLES_ALARM_SIGNO=1 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -933,6 +1021,7 @@ CONFIG_EXAMPLES_NSAMPLES=8 # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1100,3 +1189,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/nucleo-l496zg/nsh/defconfig b/configs/nucleo-l496zg/nsh/defconfig index a048b1c048..34f924b27f 100644 --- a/configs/nucleo-l496zg/nsh/defconfig +++ b/configs/nucleo-l496zg/nsh/defconfig @@ -16,7 +16,7 @@ CONFIG_HOST_LINUX=y # # Build Configuration # -CONFIG_APPS_DIR="../apps" +# CONFIG_APPS_DIR="../apps" CONFIG_BUILD_FLAT=y # CONFIG_BUILD_2PASS is not set @@ -28,6 +28,7 @@ CONFIG_BUILD_FLAT=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -201,6 +202,14 @@ CONFIG_SERIAL_TERMIOS=y # CONFIG_ARCH_CHIP_STM32L432KB is not set # CONFIG_ARCH_CHIP_STM32L432KC is not set # CONFIG_ARCH_CHIP_STM32L442KC is not set +# CONFIG_ARCH_CHIP_STM32L433CB is not set +# CONFIG_ARCH_CHIP_STM32L433CC is not set +# CONFIG_ARCH_CHIP_STM32L433RB is not set +# CONFIG_ARCH_CHIP_STM32L433RC is not set +# CONFIG_ARCH_CHIP_STM32L433VC is not set +# CONFIG_ARCH_CHIP_STM32L443CC is not set +# CONFIG_ARCH_CHIP_STM32L443RC is not set +# CONFIG_ARCH_CHIP_STM32L443VC is not set # CONFIG_ARCH_CHIP_STM32L451CC is not set # CONFIG_ARCH_CHIP_STM32L451CE is not set # CONFIG_ARCH_CHIP_STM32L451RC is not set @@ -434,6 +443,7 @@ CONFIG_STM32L4_I2CTIMEOSEC=0 CONFIG_STM32L4_I2CTIMEOMS=500 CONFIG_STM32L4_I2CTIMEOTICKS=500 # CONFIG_STM32L4_I2C_DUTY16_9 is not set +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -648,11 +658,6 @@ CONFIG_DEV_RANDOM=y # # Buffering # - -# -# Common I/O Buffer Support -# -# CONFIG_MM_IOB is not set # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -809,7 +814,9 @@ CONFIG_USART3_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -877,6 +884,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -885,6 +897,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1064,10 +1077,10 @@ CONFIG_EXAMPLES_ALARM_SIGNO=1 CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NX is not set # CONFIG_EXAMPLES_NXFFS is not set # CONFIG_EXAMPLES_NXHELLO is not set # CONFIG_EXAMPLES_NXIMAGE is not set -# CONFIG_EXAMPLES_NX is not set # CONFIG_EXAMPLES_NXLINES is not set # CONFIG_EXAMPLES_NXTERM is not set # CONFIG_EXAMPLES_NXTEXT is not set @@ -1295,3 +1308,10 @@ CONFIG_SYSTEM_TEE_PRIORITY=100 # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/olimex-stm32-e407/discover/defconfig b/configs/olimex-stm32-e407/discover/defconfig index 23760ac7b9..a0f4c0ff34 100644 --- a/configs/olimex-stm32-e407/discover/defconfig +++ b/configs/olimex-stm32-e407/discover/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -264,6 +265,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -322,6 +324,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -547,6 +550,7 @@ CONFIG_STM32_ETHMAC_HPWORK=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -567,6 +571,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -760,14 +765,6 @@ CONFIG_DEV_NULL=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=24 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -932,7 +929,9 @@ CONFIG_USART2_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1099,6 +1098,14 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 + # # Audio Support # @@ -1107,6 +1114,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1360,6 +1368,7 @@ CONFIG_EXAMPLES_DISCOVER_NETMASK=0xffffff00 # CONFIG_NETUTILS_CHAT is not set # CONFIG_NETUTILS_CODECS is not set CONFIG_NETUTILS_DHCPC=y +CONFIG_NETUTILS_DHCPC_DEVNAME="eth0" # CONFIG_NETUTILS_DHCPD is not set CONFIG_NETUTILS_DISCOVER=y CONFIG_DISCOVER_STACK_SIZE=1024 @@ -1418,3 +1427,10 @@ CONFIG_NETUTILS_NETLIB=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/olimex-stm32-e407/netnsh/defconfig b/configs/olimex-stm32-e407/netnsh/defconfig index 17ffb5f783..3f03801630 100644 --- a/configs/olimex-stm32-e407/netnsh/defconfig +++ b/configs/olimex-stm32-e407/netnsh/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -264,6 +265,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -322,6 +324,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -547,6 +550,7 @@ CONFIG_STM32_ETHMAC_HPWORK=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -567,6 +571,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -760,14 +765,6 @@ CONFIG_DEV_NULL=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=24 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -934,7 +931,9 @@ CONFIG_USART2_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1101,6 +1100,14 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 + # # Audio Support # @@ -1109,6 +1116,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1359,6 +1367,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_NETUTILS_CHAT is not set # CONFIG_NETUTILS_CODECS is not set CONFIG_NETUTILS_DHCPC=y +CONFIG_NETUTILS_DHCPC_DEVNAME="eth0" # CONFIG_NETUTILS_DHCPD is not set CONFIG_NETUTILS_DISCOVER=y CONFIG_DISCOVER_STACK_SIZE=1024 @@ -1551,3 +1560,10 @@ CONFIG_READLINE_ECHO=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/olimex-stm32-e407/nsh/defconfig b/configs/olimex-stm32-e407/nsh/defconfig index b74992be34..c9761c262b 100644 --- a/configs/olimex-stm32-e407/nsh/defconfig +++ b/configs/olimex-stm32-e407/nsh/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -173,6 +176,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -258,6 +264,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -316,6 +323,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -372,9 +380,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -388,7 +400,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -409,6 +424,7 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set # CONFIG_STM32_OTGFS is not set # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -446,6 +462,7 @@ CONFIG_STM32_USART2=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -511,6 +528,7 @@ CONFIG_STM32_USART2_SERIALDRIVER=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -531,6 +549,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -644,6 +663,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -824,6 +845,7 @@ CONFIG_USART2_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -832,7 +854,9 @@ CONFIG_USART2_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -900,6 +924,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -908,6 +937,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1082,7 +1112,6 @@ CONFIG_EXAMPLES_HELLOXX_CXXINITIALIZE=y # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1114,6 +1143,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1284,3 +1314,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/olimex-stm32-e407/telnetd/defconfig b/configs/olimex-stm32-e407/telnetd/defconfig index 6ce58a9247..b110e20a11 100644 --- a/configs/olimex-stm32-e407/telnetd/defconfig +++ b/configs/olimex-stm32-e407/telnetd/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -264,6 +265,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -322,6 +324,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -547,6 +550,7 @@ CONFIG_STM32_ETHMAC_HPWORK=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -567,6 +571,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -760,14 +765,6 @@ CONFIG_DEV_NULL=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=24 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -934,7 +931,9 @@ CONFIG_USART2_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1101,6 +1100,14 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 + # # Audio Support # @@ -1109,6 +1116,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1366,6 +1374,7 @@ CONFIG_EXAMPLES_TELNETD_CLIENTSTACKSIZE=2048 # CONFIG_NETUTILS_CHAT is not set # CONFIG_NETUTILS_CODECS is not set CONFIG_NETUTILS_DHCPC=y +CONFIG_NETUTILS_DHCPC_DEVNAME="eth0" # CONFIG_NETUTILS_DHCPD is not set CONFIG_NETUTILS_DISCOVER=y CONFIG_DISCOVER_STACK_SIZE=1024 @@ -1424,3 +1433,10 @@ CONFIG_NETUTILS_TELNETD=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/olimex-stm32-e407/usbnsh/defconfig b/configs/olimex-stm32-e407/usbnsh/defconfig index ca08e311f8..7c51b6e66a 100644 --- a/configs/olimex-stm32-e407/usbnsh/defconfig +++ b/configs/olimex-stm32-e407/usbnsh/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -173,6 +176,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -258,6 +264,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -316,6 +323,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -372,9 +380,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -388,7 +400,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -409,6 +424,7 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set CONFIG_STM32_OTGFS=y # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -446,6 +462,7 @@ CONFIG_STM32_USART2=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -511,6 +528,7 @@ CONFIG_STM32_USART2_SERIALDRIVER=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -531,6 +549,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -650,6 +669,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -878,6 +899,7 @@ CONFIG_CDCACM_VENDORSTR="NuttX" CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial" # CONFIG_USBMSC is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -886,7 +908,9 @@ CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial" # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set # CONFIG_SYSLOG_SERIAL_CONSOLE is not set @@ -955,6 +979,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -963,6 +992,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1137,7 +1167,6 @@ CONFIG_EXAMPLES_HELLOXX_CXXINITIALIZE=y # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1170,6 +1199,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1342,3 +1372,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/olimex-stm32-e407/webserver/defconfig b/configs/olimex-stm32-e407/webserver/defconfig index c6a7e03b37..8f74cb8be1 100644 --- a/configs/olimex-stm32-e407/webserver/defconfig +++ b/configs/olimex-stm32-e407/webserver/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -264,6 +265,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -322,6 +324,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -547,6 +550,7 @@ CONFIG_STM32_ETHMAC_HPWORK=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -567,6 +571,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -760,14 +765,6 @@ CONFIG_DEV_NULL=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=24 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -932,7 +929,9 @@ CONFIG_USART2_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1099,6 +1098,14 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 + # # Audio Support # @@ -1107,6 +1114,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1360,6 +1368,7 @@ CONFIG_EXAMPLES_WEBSERVER_NOMAC=y # CONFIG_NETUTILS_CHAT is not set # CONFIG_NETUTILS_CODECS is not set CONFIG_NETUTILS_DHCPC=y +CONFIG_NETUTILS_DHCPC_DEVNAME="eth0" # CONFIG_NETUTILS_DHCPD is not set CONFIG_NETUTILS_DISCOVER=y CONFIG_DISCOVER_STACK_SIZE=1024 @@ -1429,3 +1438,10 @@ CONFIG_NETUTILS_HTTPD_KEEPALIVE_DISABLE=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/olimex-stm32-h405/usbnsh/defconfig b/configs/olimex-stm32-h405/usbnsh/defconfig index 60a9d7d2e8..12a579f044 100644 --- a/configs/olimex-stm32-h405/usbnsh/defconfig +++ b/configs/olimex-stm32-h405/usbnsh/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -181,6 +182,9 @@ CONFIG_CAN_TSEG2=8 # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -266,6 +270,7 @@ CONFIG_CAN_TSEG2=8 # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set CONFIG_ARCH_CHIP_STM32F405RG=y @@ -324,6 +329,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set CONFIG_STM32_STM32F405=y # CONFIG_STM32_STM32F407 is not set @@ -543,6 +549,7 @@ CONFIG_STM32_USART3_SERIALDRIVER=y # # CAN driver configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -563,6 +570,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -797,6 +805,7 @@ CONFIG_ADC_FIFOSIZE=8 # CONFIG_ADC_PGA11X is not set # CONFIG_COMP is not set # CONFIG_DAC is not set +# CONFIG_OPAMP is not set # CONFIG_AUDIO_DEVICES is not set # CONFIG_VIDEO_DEVICES is not set # CONFIG_BCH is not set @@ -929,6 +938,7 @@ CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial" # System Logging # # CONFIG_ARCH_SYSLOG is not set +# CONFIG_SYSLOG_WRITE is not set # CONFIG_RAMLOG is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set @@ -988,6 +998,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -996,6 +1011,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1383,3 +1399,10 @@ CONFIG_READLINE_ECHO=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/olimex-stm32-h407/nsh/defconfig b/configs/olimex-stm32-h407/nsh/defconfig index 8c44dd395b..0941dcadf8 100644 --- a/configs/olimex-stm32-h407/nsh/defconfig +++ b/configs/olimex-stm32-h407/nsh/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -173,6 +176,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -258,6 +264,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -316,6 +323,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -372,9 +380,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -388,7 +400,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -409,6 +424,7 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set CONFIG_STM32_OTGFS=y # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -446,6 +462,7 @@ CONFIG_STM32_USART2=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -511,6 +528,7 @@ CONFIG_STM32_USART2_SERIALDRIVER=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -531,6 +549,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -644,6 +663,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -832,6 +853,7 @@ CONFIG_USART2_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -840,7 +862,9 @@ CONFIG_USART2_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -908,6 +932,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -916,6 +945,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1087,7 +1117,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1119,6 +1148,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1289,3 +1319,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/olimex-stm32-p207/nsh/defconfig b/configs/olimex-stm32-p207/nsh/defconfig index 2f1c5e6149..16c37e7427 100644 --- a/configs/olimex-stm32-p207/nsh/defconfig +++ b/configs/olimex-stm32-p207/nsh/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -271,6 +272,7 @@ CONFIG_ARCH_CHIP_STM32F207ZE=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -329,6 +331,7 @@ CONFIG_STM32_STM32F207=y # CONFIG_STM32_STM32F37XX is not set # CONFIG_STM32_STM32F40XX is not set # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set # CONFIG_STM32_STM32F407 is not set @@ -573,6 +576,7 @@ CONFIG_STM32_OTGFS_DESCSIZE=128 # # CAN driver configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -593,6 +597,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -790,14 +795,6 @@ CONFIG_DEV_NULL=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=24 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -834,6 +831,7 @@ CONFIG_ADC_FIFOSIZE=8 # CONFIG_ADC_PGA11X is not set # CONFIG_COMP is not set # CONFIG_DAC is not set +# CONFIG_OPAMP is not set # CONFIG_AUDIO_DEVICES is not set # CONFIG_VIDEO_DEVICES is not set # CONFIG_BCH is not set @@ -977,7 +975,9 @@ CONFIG_USBHOST_HAVE_ASYNCH=y # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1144,6 +1144,14 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 + # # Audio Support # @@ -1152,6 +1160,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1579,3 +1588,10 @@ CONFIG_READLINE_ECHO=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/olimex-stm32-p407/knsh/defconfig b/configs/olimex-stm32-p407/knsh/defconfig index ec07cf7e05..eba898d922 100644 --- a/configs/olimex-stm32-p407/knsh/defconfig +++ b/configs/olimex-stm32-p407/knsh/defconfig @@ -33,6 +33,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -95,6 +96,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -102,11 +104,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -180,6 +183,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -265,6 +271,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -323,6 +330,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -379,9 +387,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -395,7 +407,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -416,6 +431,7 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set # CONFIG_STM32_OTGFS is not set # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -453,6 +469,7 @@ CONFIG_STM32_USART3=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -518,6 +535,7 @@ CONFIG_STM32_USART3_SERIALDRIVER=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -538,6 +556,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set CONFIG_ARCH_USE_MPU=y # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -656,6 +675,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -843,6 +864,7 @@ CONFIG_USART3_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -851,7 +873,9 @@ CONFIG_USART3_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -921,6 +945,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -929,6 +958,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1091,6 +1121,7 @@ CONFIG_HAVE_CXXINITIALIZE=y # CONFIG_EXAMPLES_FTPD is not set # CONFIG_EXAMPLES_HELLO is not set # CONFIG_EXAMPLES_HELLOXX is not set +# CONFIG_EXAMPLES_HIDKBD is not set # CONFIG_EXAMPLES_IGMP is not set # CONFIG_EXAMPLES_JSON is not set # CONFIG_EXAMPLES_KEYPADTEST is not set @@ -1098,7 +1129,6 @@ CONFIG_HAVE_CXXINITIALIZE=y # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1130,6 +1160,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1298,3 +1329,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/olimex-stm32-p407/nsh/defconfig b/configs/olimex-stm32-p407/nsh/defconfig index ed41bffe55..01d6cb9c0b 100644 --- a/configs/olimex-stm32-p407/nsh/defconfig +++ b/configs/olimex-stm32-p407/nsh/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -177,6 +180,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -262,6 +268,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -320,6 +327,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -376,9 +384,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -392,7 +404,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -413,6 +428,7 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set CONFIG_STM32_OTGFS=y # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -450,6 +466,7 @@ CONFIG_STM32_USART3=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -520,6 +537,7 @@ CONFIG_STM32_OTGFS_DESCSIZE=128 # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -540,6 +558,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -660,6 +679,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -855,7 +876,9 @@ CONFIG_USBHOST_MSC=y # CONFIG_USBHOST_CDCACM is not set # CONFIG_USBHOST_HIDKBD is not set # CONFIG_USBHOST_HIDMOUSE is not set +# CONFIG_USBHOST_XBOXCONTROLLER is not set # CONFIG_USBHOST_TRACE is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -864,7 +887,9 @@ CONFIG_USBHOST_MSC=y # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -939,6 +964,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -947,6 +977,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1121,7 +1152,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1154,6 +1184,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1325,3 +1356,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/olimexino-stm32/can/defconfig b/configs/olimexino-stm32/can/defconfig index 25eaf0aefc..4c0164e941 100644 --- a/configs/olimexino-stm32/can/defconfig +++ b/configs/olimexino-stm32/can/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -177,6 +180,9 @@ CONFIG_CAN_LOOPBACK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -262,6 +268,7 @@ CONFIG_ARCH_CHIP_STM32F103RB=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -320,6 +327,7 @@ CONFIG_STM32_MEDIUMDENSITY=y # CONFIG_STM32_STM32F37XX is not set # CONFIG_STM32_STM32F40XX is not set # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set # CONFIG_STM32_STM32F407 is not set @@ -376,9 +384,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y # CONFIG_STM32_HAVE_CAN2 is not set +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set # CONFIG_STM32_HAVE_DAC1 is not set # CONFIG_STM32_HAVE_DAC2 is not set # CONFIG_STM32_HAVE_RNG is not set @@ -392,7 +404,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set CONFIG_STM32_ADC1=y # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -403,6 +418,7 @@ CONFIG_STM32_CAN1=y # CONFIG_STM32_DMA2 is not set # CONFIG_STM32_I2C1 is not set CONFIG_STM32_I2C2=y +# CONFIG_STM32_OPAMP is not set CONFIG_STM32_PWR=y # CONFIG_STM32_SDIO is not set # CONFIG_STM32_SPI1 is not set @@ -443,6 +459,7 @@ CONFIG_STM32_TIM1_PARTIAL_REMAP=y # CONFIG_STM32_TIM3_FULL_REMAP is not set CONFIG_STM32_TIM3_PARTIAL_REMAP=y # CONFIG_STM32_USART1_REMAP is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set CONFIG_STM32_JTAG_FULL_ENABLE=y # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -469,6 +486,7 @@ CONFIG_STM32_FORCEPOWER=y # # ADC Configuration # +# CONFIG_STM32_ADC_NO_STARTUP_CONV is not set CONFIG_STM32_USART=y CONFIG_STM32_SERIALDRIVER=y @@ -528,6 +546,7 @@ CONFIG_STM32_HAVE_RTC_COUNTER=y # # CAN driver configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -548,6 +567,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set CONFIG_ARCH_IRQPRIO=y CONFIG_ARCH_STACKDUMP=y @@ -659,6 +679,9 @@ CONFIG_MAX_TASKS=12 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -780,7 +803,9 @@ CONFIG_SPI_EXCHANGE=y # CONFIG_TIMERS_CS2100CP is not set CONFIG_ANALOG=y # CONFIG_ADC is not set +# CONFIG_COMP is not set # CONFIG_DAC is not set +# CONFIG_OPAMP is not set # CONFIG_AUDIO_DEVICES is not set # CONFIG_VIDEO_DEVICES is not set # CONFIG_BCH is not set @@ -866,6 +891,7 @@ CONFIG_USART1_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -874,7 +900,9 @@ CONFIG_USART1_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -942,6 +970,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -950,6 +983,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1133,7 +1167,6 @@ CONFIG_EXAMPLES_HELLOXX_CXXINITIALIZE=y # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NSH_CXXINITIALIZE is not set # CONFIG_EXAMPLES_NULL is not set @@ -1166,6 +1199,7 @@ CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1337,3 +1371,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/olimexino-stm32/composite/defconfig b/configs/olimexino-stm32/composite/defconfig index 8eb861aff4..4d6f9915d6 100644 --- a/configs/olimexino-stm32/composite/defconfig +++ b/configs/olimexino-stm32/composite/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -172,6 +175,9 @@ CONFIG_SERIAL_TERMIOS=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -257,6 +263,7 @@ CONFIG_ARCH_CHIP_STM32F103RB=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -315,6 +322,7 @@ CONFIG_STM32_MEDIUMDENSITY=y # CONFIG_STM32_STM32F37XX is not set # CONFIG_STM32_STM32F40XX is not set # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set # CONFIG_STM32_STM32F407 is not set @@ -371,9 +379,13 @@ CONFIG_STM32_HAVE_ADC1_DMA=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y # CONFIG_STM32_HAVE_CAN2 is not set +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set # CONFIG_STM32_HAVE_DAC1 is not set # CONFIG_STM32_HAVE_DAC2 is not set # CONFIG_STM32_HAVE_RNG is not set @@ -387,7 +399,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set CONFIG_STM32_ADC1=y # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -398,6 +413,7 @@ CONFIG_STM32_DMA1=y CONFIG_STM32_DMA2=y # CONFIG_STM32_I2C1 is not set CONFIG_STM32_I2C2=y +# CONFIG_STM32_OPAMP is not set CONFIG_STM32_PWR=y # CONFIG_STM32_SDIO is not set CONFIG_STM32_SPI1=y @@ -436,6 +452,7 @@ CONFIG_STM32_TIM1_PARTIAL_REMAP=y CONFIG_STM32_TIM3_PARTIAL_REMAP=y # CONFIG_STM32_USART1_REMAP is not set # CONFIG_STM32_USART2_REMAP is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set CONFIG_STM32_JTAG_FULL_ENABLE=y # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -463,6 +480,7 @@ CONFIG_STM32_DMACAPABLE=y # # ADC Configuration # +# CONFIG_STM32_ADC_NO_STARTUP_CONV is not set # CONFIG_STM32_ADC1_DMA is not set CONFIG_STM32_USART=y CONFIG_STM32_SERIALDRIVER=y @@ -527,6 +545,7 @@ CONFIG_RTC_LSECLOCK=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -547,6 +566,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set CONFIG_ARCH_IRQPRIO=y CONFIG_ARCH_STACKDUMP=y @@ -659,6 +679,9 @@ CONFIG_MAX_TASKS=12 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -774,7 +797,9 @@ CONFIG_WATCHDOG=y CONFIG_WATCHDOG_DEVPATH="/dev/watchdog0" CONFIG_ANALOG=y # CONFIG_ADC is not set +# CONFIG_COMP is not set # CONFIG_DAC is not set +# CONFIG_OPAMP is not set # CONFIG_AUDIO_DEVICES is not set # CONFIG_VIDEO_DEVICES is not set # CONFIG_BCH is not set @@ -955,6 +980,7 @@ CONFIG_USBMSC_REMOVABLE=y CONFIG_USBMSC_SCSI_PRIO=128 CONFIG_USBMSC_SCSI_STACKSIZE=340 # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -963,7 +989,9 @@ CONFIG_USBMSC_SCSI_STACKSIZE=340 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1031,6 +1059,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -1039,6 +1072,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1215,7 +1249,6 @@ CONFIG_EXAMPLES_HELLOXX_CXXINITIALIZE=y # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NSH_CXXINITIALIZE is not set # CONFIG_EXAMPLES_NULL is not set @@ -1248,6 +1281,7 @@ CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1437,3 +1471,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_USBMSC is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/olimexino-stm32/nsh/defconfig b/configs/olimexino-stm32/nsh/defconfig index 7fb0682188..53eea4afe2 100644 --- a/configs/olimexino-stm32/nsh/defconfig +++ b/configs/olimexino-stm32/nsh/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -172,6 +175,9 @@ CONFIG_SERIAL_TERMIOS=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -257,6 +263,7 @@ CONFIG_ARCH_CHIP_STM32F103RB=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -315,6 +322,7 @@ CONFIG_STM32_MEDIUMDENSITY=y # CONFIG_STM32_STM32F37XX is not set # CONFIG_STM32_STM32F40XX is not set # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set # CONFIG_STM32_STM32F407 is not set @@ -371,9 +379,13 @@ CONFIG_STM32_HAVE_ADC1_DMA=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y # CONFIG_STM32_HAVE_CAN2 is not set +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set # CONFIG_STM32_HAVE_DAC1 is not set # CONFIG_STM32_HAVE_DAC2 is not set # CONFIG_STM32_HAVE_RNG is not set @@ -387,7 +399,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set CONFIG_STM32_ADC1=y # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -398,6 +413,7 @@ CONFIG_STM32_DMA1=y CONFIG_STM32_DMA2=y # CONFIG_STM32_I2C1 is not set CONFIG_STM32_I2C2=y +# CONFIG_STM32_OPAMP is not set CONFIG_STM32_PWR=y # CONFIG_STM32_SDIO is not set CONFIG_STM32_SPI1=y @@ -436,6 +452,7 @@ CONFIG_STM32_TIM1_PARTIAL_REMAP=y CONFIG_STM32_TIM3_PARTIAL_REMAP=y # CONFIG_STM32_USART1_REMAP is not set # CONFIG_STM32_USART2_REMAP is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set CONFIG_STM32_JTAG_FULL_ENABLE=y # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -463,6 +480,7 @@ CONFIG_STM32_DMACAPABLE=y # # ADC Configuration # +# CONFIG_STM32_ADC_NO_STARTUP_CONV is not set # CONFIG_STM32_ADC1_DMA is not set CONFIG_STM32_USART=y CONFIG_STM32_SERIALDRIVER=y @@ -527,6 +545,7 @@ CONFIG_RTC_LSECLOCK=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -547,6 +566,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set CONFIG_ARCH_IRQPRIO=y CONFIG_ARCH_STACKDUMP=y @@ -658,6 +678,9 @@ CONFIG_MAX_TASKS=12 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -773,7 +796,9 @@ CONFIG_WATCHDOG=y CONFIG_WATCHDOG_DEVPATH="/dev/watchdog0" CONFIG_ANALOG=y # CONFIG_ADC is not set +# CONFIG_COMP is not set # CONFIG_DAC is not set +# CONFIG_OPAMP is not set # CONFIG_AUDIO_DEVICES is not set # CONFIG_VIDEO_DEVICES is not set # CONFIG_BCH is not set @@ -884,6 +909,7 @@ CONFIG_USART2_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -892,7 +918,9 @@ CONFIG_USART2_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -960,6 +988,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -968,6 +1001,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1144,7 +1178,6 @@ CONFIG_EXAMPLES_HELLOXX_CXXINITIALIZE=y # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NSH_CXXINITIALIZE is not set # CONFIG_EXAMPLES_NULL is not set @@ -1177,6 +1210,7 @@ CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1351,3 +1385,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/olimexino-stm32/smallnsh/defconfig b/configs/olimexino-stm32/smallnsh/defconfig index fc5194b8ec..622916d8c2 100644 --- a/configs/olimexino-stm32/smallnsh/defconfig +++ b/configs/olimexino-stm32/smallnsh/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -177,6 +180,9 @@ CONFIG_CAN_LOOPBACK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -262,6 +268,7 @@ CONFIG_ARCH_CHIP_STM32F103RB=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -320,6 +327,7 @@ CONFIG_STM32_MEDIUMDENSITY=y # CONFIG_STM32_STM32F37XX is not set # CONFIG_STM32_STM32F40XX is not set # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set # CONFIG_STM32_STM32F407 is not set @@ -376,9 +384,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y # CONFIG_STM32_HAVE_CAN2 is not set +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set # CONFIG_STM32_HAVE_DAC1 is not set # CONFIG_STM32_HAVE_DAC2 is not set # CONFIG_STM32_HAVE_RNG is not set @@ -392,7 +404,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -403,6 +418,7 @@ CONFIG_STM32_CAN1=y # CONFIG_STM32_DMA2 is not set # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set +# CONFIG_STM32_OPAMP is not set CONFIG_STM32_PWR=y # CONFIG_STM32_SDIO is not set # CONFIG_STM32_SPI1 is not set @@ -441,6 +457,7 @@ CONFIG_STM32_TIM1_PARTIAL_REMAP=y # CONFIG_STM32_TIM3_FULL_REMAP is not set CONFIG_STM32_TIM3_PARTIAL_REMAP=y # CONFIG_STM32_USART1_REMAP is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set CONFIG_STM32_JTAG_FULL_ENABLE=y # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -510,6 +527,7 @@ CONFIG_STM32_HAVE_RTC_COUNTER=y # # CAN driver configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -530,6 +548,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set CONFIG_ARCH_IRQPRIO=y CONFIG_ARCH_STACKDUMP=y @@ -640,6 +659,9 @@ CONFIG_MAX_TASKS=4 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -844,6 +866,7 @@ CONFIG_USART1_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -852,7 +875,9 @@ CONFIG_USART1_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -912,6 +937,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -920,6 +950,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1098,7 +1129,6 @@ CONFIG_EXAMPLES_CAN_READWRITE=y # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NSH_CXXINITIALIZE is not set # CONFIG_EXAMPLES_NULL is not set @@ -1131,6 +1161,7 @@ CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1296,3 +1327,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/olimexino-stm32/tiny/defconfig b/configs/olimexino-stm32/tiny/defconfig index 9991232442..11959d3f77 100644 --- a/configs/olimexino-stm32/tiny/defconfig +++ b/configs/olimexino-stm32/tiny/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -177,6 +180,9 @@ CONFIG_CAN_LOOPBACK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -262,6 +268,7 @@ CONFIG_ARCH_CHIP_STM32F103RB=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -320,6 +327,7 @@ CONFIG_STM32_MEDIUMDENSITY=y # CONFIG_STM32_STM32F37XX is not set # CONFIG_STM32_STM32F40XX is not set # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set # CONFIG_STM32_STM32F407 is not set @@ -376,9 +384,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y # CONFIG_STM32_HAVE_CAN2 is not set +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set # CONFIG_STM32_HAVE_DAC1 is not set # CONFIG_STM32_HAVE_DAC2 is not set # CONFIG_STM32_HAVE_RNG is not set @@ -392,7 +404,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -403,6 +418,7 @@ CONFIG_STM32_CAN1=y # CONFIG_STM32_DMA2 is not set # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set +# CONFIG_STM32_OPAMP is not set CONFIG_STM32_PWR=y # CONFIG_STM32_SDIO is not set # CONFIG_STM32_SPI1 is not set @@ -441,6 +457,7 @@ CONFIG_STM32_TIM1_PARTIAL_REMAP=y # CONFIG_STM32_TIM3_FULL_REMAP is not set CONFIG_STM32_TIM3_PARTIAL_REMAP=y # CONFIG_STM32_USART1_REMAP is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set CONFIG_STM32_JTAG_FULL_ENABLE=y # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -510,6 +527,7 @@ CONFIG_STM32_HAVE_RTC_COUNTER=y # # CAN driver configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -530,6 +548,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set CONFIG_ARCH_IRQPRIO=y CONFIG_ARCH_STACKDUMP=y @@ -640,6 +659,9 @@ CONFIG_MAX_TASKS=4 # Pthread Options # # CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -847,6 +869,7 @@ CONFIG_USART1_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -855,7 +878,9 @@ CONFIG_USART1_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -909,6 +934,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -917,6 +947,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1095,7 +1126,6 @@ CONFIG_EXAMPLES_CAN_READWRITE=y # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set # CONFIG_EXAMPLES_NSH is not set # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -1126,6 +1156,7 @@ CONFIG_EXAMPLES_CAN_READWRITE=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1201,3 +1232,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/pcduino-a10/nsh/defconfig b/configs/pcduino-a10/nsh/defconfig index c6402c0564..b547394dfc 100644 --- a/configs/pcduino-a10/nsh/defconfig +++ b/configs/pcduino-a10/nsh/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -95,6 +96,7 @@ CONFIG_ARCH_CHIP_A1X=y # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -102,11 +104,12 @@ CONFIG_ARCH_CHIP_A1X=y # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -240,6 +243,7 @@ CONFIG_A1X_BOOT_SDCARD=y CONFIG_A1X_DDR_MAPOFFSET=0 CONFIG_A1X_DDR_MAPSIZE=1073741824 # CONFIG_SERIAL_TERMIOS is not set +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -260,6 +264,7 @@ CONFIG_ARCH_HAVE_MMU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set # CONFIG_ARCH_HAVE_RESET is not set +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set CONFIG_ARCH_USE_MMU=y # CONFIG_ARCH_ADDRENV is not set # CONFIG_PAGING is not set @@ -369,6 +374,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -549,6 +556,7 @@ CONFIG_UART0_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -557,7 +565,9 @@ CONFIG_UART0_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -625,6 +635,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_GRAN is not set # CONFIG_MM_PGALLOC is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -633,6 +648,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -804,7 +820,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -836,6 +851,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1006,3 +1022,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/photon/nsh/defconfig b/configs/photon/nsh/defconfig index c82bde94e9..67f2d12700 100644 --- a/configs/photon/nsh/defconfig +++ b/configs/photon/nsh/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -98,6 +99,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set @@ -173,6 +175,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -258,6 +263,7 @@ CONFIG_ARCH_CHIP_STM32F205RG=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -316,6 +322,7 @@ CONFIG_STM32_STM32F205=y # CONFIG_STM32_STM32F37XX is not set # CONFIG_STM32_STM32F40XX is not set # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set # CONFIG_STM32_STM32F407 is not set @@ -509,6 +516,7 @@ CONFIG_STM32_USART1_SERIALDRIVER=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -529,6 +537,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -845,7 +854,9 @@ CONFIG_USART1_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -913,6 +924,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -921,6 +937,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1296,3 +1313,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/photon/usbnsh/defconfig b/configs/photon/usbnsh/defconfig index 8b0111b326..8050de9c8e 100644 --- a/configs/photon/usbnsh/defconfig +++ b/configs/photon/usbnsh/defconfig @@ -16,7 +16,7 @@ CONFIG_HOST_LINUX=y # # Build Configuration # -CONFIG_APPS_DIR="../apps" +# CONFIG_APPS_DIR="../apps" CONFIG_BUILD_FLAT=y # CONFIG_BUILD_2PASS is not set @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -172,6 +175,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -257,6 +263,7 @@ CONFIG_ARCH_CHIP_STM32F205RG=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -315,6 +322,7 @@ CONFIG_STM32_STM32F205=y # CONFIG_STM32_STM32F37XX is not set # CONFIG_STM32_STM32F40XX is not set # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set # CONFIG_STM32_STM32F407 is not set @@ -371,9 +379,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -387,7 +399,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -401,6 +416,7 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set # CONFIG_STM32_OTGFS is not set CONFIG_STM32_OTGHS=y # CONFIG_STM32_PWR is not set @@ -436,6 +452,7 @@ CONFIG_STM32_IWDG=y # # Alternate Pin Mapping # +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -499,6 +516,7 @@ CONFIG_STM32_USART1_SERIALDRIVER=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -519,6 +537,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -569,6 +588,11 @@ CONFIG_ARCH_BOARD="photon" # # Common Board Options # +CONFIG_ARCH_HAVE_LEDS=y +CONFIG_ARCH_LEDS=y +CONFIG_ARCH_HAVE_BUTTONS=y +# CONFIG_ARCH_BUTTONS is not set +CONFIG_ARCH_HAVE_IRQBUTTONS=y # # Board-Specific Options @@ -639,6 +663,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -756,6 +782,7 @@ CONFIG_WATCHDOG_DEVPATH="/dev/watchdog0" # # LED Support # +# CONFIG_USERLED is not set # CONFIG_RGBLED is not set # CONFIG_PCA9635PW is not set # CONFIG_NCP5623C is not set @@ -858,6 +885,7 @@ CONFIG_CDCACM_VENDORSTR="NuttX" CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial" # CONFIG_USBMSC is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -866,7 +894,9 @@ CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial" # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set # CONFIG_SYSLOG_SERIAL_CONSOLE is not set @@ -935,6 +965,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -943,6 +978,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1083,10 +1119,6 @@ CONFIG_HAVE_CXXINITIALIZE=y # Application Configuration # -# -# NxWidgets/NxWM -# - # # Built-In Applications # @@ -1099,6 +1131,7 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # # Examples # +# CONFIG_EXAMPLES_BUTTONS is not set # CONFIG_EXAMPLES_CCTYPE is not set # CONFIG_EXAMPLES_CHAT is not set # CONFIG_EXAMPLES_CONFIGDATA is not set @@ -1147,9 +1180,9 @@ CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_TIFF is not set # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_USBSERIAL is not set -# CONFIG_EXAMPLES_USBTERM is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1291,6 +1324,10 @@ CONFIG_NSH_ARCHINIT=y # CONFIG_NSH_LOGIN is not set # CONFIG_NSH_CONSOLE_LOGIN is not set +# +# NxWidgets/NxWM +# + # # Platform-specific Support # @@ -1318,3 +1355,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/photon/wlan/defconfig b/configs/photon/wlan/defconfig index 0f5060e846..0aa452a9fe 100644 --- a/configs/photon/wlan/defconfig +++ b/configs/photon/wlan/defconfig @@ -308,6 +308,7 @@ CONFIG_ARCH_CHIP_STM32F205RG=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -366,6 +367,7 @@ CONFIG_STM32_STM32F205=y # CONFIG_STM32_STM32F37XX is not set # CONFIG_STM32_STM32F40XX is not set # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set # CONFIG_STM32_STM32F407 is not set @@ -568,6 +570,7 @@ CONFIG_STM32_SDIO_DMAPRIO=0x00010000 # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -795,15 +798,6 @@ CONFIG_DEV_NULL=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=24 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 -# CONFIG_IOB_DEBUG is not set # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -968,7 +962,9 @@ CONFIG_IEEE80211_BROADCOM_NINTERFACES=1 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1149,6 +1145,15 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 +# CONFIG_IOB_DEBUG is not set + # # Audio Support # diff --git a/configs/sabre-6quad/nsh/defconfig b/configs/sabre-6quad/nsh/defconfig index 0caeea2138..fb5901f395 100644 --- a/configs/sabre-6quad/nsh/defconfig +++ b/configs/sabre-6quad/nsh/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -95,6 +96,7 @@ CONFIG_ARCH_CHIP_IMX6=y # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -102,11 +104,12 @@ CONFIG_ARCH_CHIP_IMX6=y # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -190,6 +193,7 @@ CONFIG_IMX_DDR_SIZE=1073741824 CONFIG_IMX6_BOOT_SDRAM=y # CONFIG_IMX6_BOOT_NOR is not set # CONFIG_IMX6_BOOT_SRAM is not set +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -210,6 +214,7 @@ CONFIG_ARCH_HAVE_MMU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set # CONFIG_ARCH_HAVE_RESET is not set +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set CONFIG_ARCH_USE_MMU=y # CONFIG_ARCH_ADDRENV is not set # CONFIG_PAGING is not set @@ -324,6 +329,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -510,6 +517,7 @@ CONFIG_UART1_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -518,6 +526,7 @@ CONFIG_UART1_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +# CONFIG_SYSLOG_WRITE is not set CONFIG_RAMLOG=y # CONFIG_RAMLOG_CONSOLE is not set CONFIG_RAMLOG_BUFSIZE=16384 @@ -594,6 +603,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_GRAN is not set # CONFIG_MM_PGALLOC is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -602,6 +616,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -773,7 +788,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -806,6 +820,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -977,3 +992,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/sabre-6quad/smp/defconfig b/configs/sabre-6quad/smp/defconfig index 1aec2d84ed..c98713873a 100644 --- a/configs/sabre-6quad/smp/defconfig +++ b/configs/sabre-6quad/smp/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -95,6 +96,7 @@ CONFIG_ARCH_CHIP_IMX6=y # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -102,11 +104,12 @@ CONFIG_ARCH_CHIP_IMX6=y # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -193,6 +196,7 @@ CONFIG_IMX_DDR_SIZE=1073741824 CONFIG_IMX6_BOOT_SDRAM=y # CONFIG_IMX6_BOOT_NOR is not set # CONFIG_IMX6_BOOT_SRAM is not set +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -213,6 +217,7 @@ CONFIG_ARCH_HAVE_MMU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set # CONFIG_ARCH_HAVE_RESET is not set +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set CONFIG_ARCH_USE_MMU=y # CONFIG_ARCH_ADDRENV is not set # CONFIG_PAGING is not set @@ -329,6 +334,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -515,6 +522,7 @@ CONFIG_UART1_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -523,6 +531,7 @@ CONFIG_UART1_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +# CONFIG_SYSLOG_WRITE is not set CONFIG_RAMLOG=y # CONFIG_RAMLOG_CONSOLE is not set CONFIG_RAMLOG_BUFSIZE=16384 @@ -599,6 +608,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_GRAN is not set # CONFIG_MM_PGALLOC is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -779,7 +793,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -815,6 +828,7 @@ CONFIG_EXAMPLES_SMP_STACKSIZE=2048 # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -986,3 +1000,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/sam3u-ek/nxwm/defconfig b/configs/sam3u-ek/nxwm/defconfig index f6ac263211..2f6d760377 100644 --- a/configs/sam3u-ek/nxwm/defconfig +++ b/configs/sam3u-ek/nxwm/defconfig @@ -28,6 +28,7 @@ CONFIG_BUILD_FLAT=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -89,6 +90,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -96,11 +98,12 @@ CONFIG_ARCH="arm" CONFIG_ARCH_CHIP_SAM34=y # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -262,6 +265,7 @@ CONFIG_SAM34_GPIOA_IRQ=y # AT91SAM3/4 SPI device driver options # # CONFIG_SAM34_TC is not set +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -282,6 +286,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -397,6 +402,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -640,6 +647,7 @@ CONFIG_UART0_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -648,7 +656,9 @@ CONFIG_UART0_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -818,6 +828,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -826,6 +841,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -992,7 +1008,6 @@ CONFIG_CXX_NEWLONG=y # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set # CONFIG_EXAMPLES_NSH is not set # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -1023,6 +1038,7 @@ CONFIG_CXX_NEWLONG=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1359,3 +1375,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/sam4e-ek/nxwm/defconfig b/configs/sam4e-ek/nxwm/defconfig index 2b86e3a1c8..ca7322f492 100644 --- a/configs/sam4e-ek/nxwm/defconfig +++ b/configs/sam4e-ek/nxwm/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -304,6 +305,7 @@ CONFIG_SAM34_EMAC_PHYSR_100FD=0x6 CONFIG_SAM34_EMAC_ISETH0=y CONFIG_SAM34_EMAC_HPWORK=y # CONFIG_SAM34_TC is not set +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -324,6 +326,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -527,14 +530,6 @@ CONFIG_DEV_NULL=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=24 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -795,7 +790,9 @@ CONFIG_USART1_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1082,6 +1079,14 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 + # # Audio Support # @@ -1090,6 +1095,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1710,3 +1716,10 @@ CONFIG_READLINE_ECHO=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/sam4l-xplained/nsh/defconfig b/configs/sam4l-xplained/nsh/defconfig index 34b6e44043..a5c734aa40 100644 --- a/configs/sam4l-xplained/nsh/defconfig +++ b/configs/sam4l-xplained/nsh/defconfig @@ -28,6 +28,7 @@ CONFIG_BUILD_FLAT=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -89,6 +90,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -96,11 +98,12 @@ CONFIG_ARCH="arm" CONFIG_ARCH_CHIP_SAM34=y # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -271,6 +274,7 @@ CONFIG_SAM34_USART0=y # CONFIG_SAM34_HAVE_GPIOE_IRQ is not set # CONFIG_SAM34_HAVE_GPIOF_IRQ is not set # CONFIG_SAM34_TC is not set +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -291,6 +295,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -408,6 +413,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -588,6 +595,7 @@ CONFIG_USART0_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -596,7 +604,9 @@ CONFIG_USART0_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -656,6 +666,11 @@ CONFIG_MM_REGIONS=3 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -664,6 +679,7 @@ CONFIG_MM_REGIONS=3 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -831,7 +847,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -863,6 +878,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1030,3 +1046,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/sam4s-xplained-pro/nsh/defconfig b/configs/sam4s-xplained-pro/nsh/defconfig index 1e32e6a8f6..1f60e17c36 100644 --- a/configs/sam4s-xplained-pro/nsh/defconfig +++ b/configs/sam4s-xplained-pro/nsh/defconfig @@ -29,6 +29,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" CONFIG_ARCH_CHIP_SAM34=y # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -292,6 +295,7 @@ CONFIG_WDT_THREAD_NAME="wdog" CONFIG_WDT_THREAD_INTERVAL=2500 CONFIG_WDT_THREAD_PRIORITY=200 CONFIG_WDT_THREAD_STACKSIZE=512 +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -312,6 +316,7 @@ CONFIG_ARCH_HAVE_MPU=y CONFIG_ARCH_HAVE_EXTCLK=y # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set CONFIG_ARCH_USE_MPU=y # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -429,6 +434,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -712,6 +719,7 @@ CONFIG_CDCACM_VENDORSTR="NuttX" CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial" # CONFIG_USBMSC is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -720,7 +728,9 @@ CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial" # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -795,6 +805,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -803,6 +818,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -978,7 +994,6 @@ CONFIG_EXAMPLES_CPUHOG_PRIORITY=50 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1022,6 +1037,7 @@ CONFIG_EXAMPLES_SERIALRX_PRINTHEX=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1198,3 +1214,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/sam4s-xplained/nsh/defconfig b/configs/sam4s-xplained/nsh/defconfig index 2f62a8f4ba..c59c5a0f8b 100644 --- a/configs/sam4s-xplained/nsh/defconfig +++ b/configs/sam4s-xplained/nsh/defconfig @@ -28,6 +28,7 @@ CONFIG_BUILD_FLAT=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -89,6 +90,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -96,11 +98,12 @@ CONFIG_ARCH="arm" CONFIG_ARCH_CHIP_SAM34=y # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -258,6 +261,7 @@ CONFIG_SAM34_UART1=y # CONFIG_SAM34_HAVE_GPIOF_IRQ is not set # CONFIG_SAM34_GPIO_IRQ is not set # CONFIG_SAM34_TC is not set +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -278,6 +282,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -388,6 +393,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -568,6 +575,7 @@ CONFIG_UART1_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -576,7 +584,9 @@ CONFIG_UART1_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -630,6 +640,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -638,6 +653,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -805,7 +821,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -837,6 +852,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1003,3 +1019,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/sama5d2-xult/nsh/defconfig b/configs/sama5d2-xult/nsh/defconfig index 9ea5e61920..db65ee79d5 100644 --- a/configs/sama5d2-xult/nsh/defconfig +++ b/configs/sama5d2-xult/nsh/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -95,6 +96,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set CONFIG_ARCH_CHIP_SAMA5=y # CONFIG_ARCH_CHIP_SAMD is not set @@ -102,11 +104,12 @@ CONFIG_ARCH_CHIP_SAMA5=y # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -325,6 +328,7 @@ CONFIG_SAMA5_BOOT_SDRAM=y CONFIG_SAMA5_ISRAM_HEAP=y CONFIG_SAMA5_DDRCS_RESERVE=y CONFIG_SAMA5_DDRCS_HEAP_END=0x2fa00000 +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -345,6 +349,7 @@ CONFIG_ARCH_NAND_HWECC=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set # CONFIG_ARCH_HAVE_RESET is not set +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set CONFIG_ARCH_USE_MMU=y # CONFIG_ARCH_ADDRENV is not set # CONFIG_PAGING is not set @@ -464,6 +469,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -673,7 +680,9 @@ CONFIG_HIDKBD_NPOLLWAITERS=2 # CONFIG_HIDKBD_ALLSCANCODES is not set # CONFIG_HIDKBD_NODEBOUNCE is not set # CONFIG_USBHOST_HIDMOUSE is not set +# CONFIG_USBHOST_XBOXCONTROLLER is not set # CONFIG_USBHOST_TRACE is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -682,6 +691,7 @@ CONFIG_HIDKBD_NPOLLWAITERS=2 # System Logging # # CONFIG_ARCH_SYSLOG is not set +# CONFIG_SYSLOG_WRITE is not set CONFIG_RAMLOG=y # CONFIG_RAMLOG_CONSOLE is not set CONFIG_RAMLOG_BUFSIZE=16384 @@ -765,6 +775,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_GRAN is not set # CONFIG_MM_PGALLOC is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -806,6 +821,7 @@ CONFIG_AUDIO_EXCLUDE_REWIND=y # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -980,7 +996,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1014,6 +1029,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1199,3 +1215,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/sama5d3-xplained/bridge/defconfig b/configs/sama5d3-xplained/bridge/defconfig index bad6c2f17f..c89f19ed61 100644 --- a/configs/sama5d3-xplained/bridge/defconfig +++ b/configs/sama5d3-xplained/bridge/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -329,6 +330,7 @@ CONFIG_SAMA5_BOOT_SDRAM=y # # CONFIG_SAMA5_ISRAM_HEAP is not set # CONFIG_SAMA5_DDRCS_RESERVE is not set +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -349,6 +351,7 @@ CONFIG_ARCH_NAND_HWECC=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set # CONFIG_ARCH_HAVE_RESET is not set +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set CONFIG_ARCH_USE_MMU=y # CONFIG_ARCH_ADDRENV is not set # CONFIG_PAGING is not set @@ -544,11 +547,6 @@ CONFIG_DEV_NULL=y # # Buffering # - -# -# Common I/O Buffer Support -# -# CONFIG_MM_IOB is not set # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -699,7 +697,9 @@ CONFIG_OTHER_SERIAL_CONSOLE=y # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -866,6 +866,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_GRAN is not set # CONFIG_MM_PGALLOC is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -874,6 +879,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1203,3 +1209,10 @@ CONFIG_READLINE_ECHO=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/sama5d3-xplained/nsh/defconfig b/configs/sama5d3-xplained/nsh/defconfig index 6e7fed8017..4a7584dfbd 100644 --- a/configs/sama5d3-xplained/nsh/defconfig +++ b/configs/sama5d3-xplained/nsh/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -95,6 +96,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set CONFIG_ARCH_CHIP_SAMA5=y # CONFIG_ARCH_CHIP_SAMD is not set @@ -102,11 +104,12 @@ CONFIG_ARCH_CHIP_SAMA5=y # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -292,6 +295,7 @@ CONFIG_SAMA5_BOOT_SDRAM=y # CONFIG_SAMA5_ISRAM_HEAP=y # CONFIG_SAMA5_DDRCS_RESERVE is not set +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -312,6 +316,7 @@ CONFIG_ARCH_NAND_HWECC=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set # CONFIG_ARCH_HAVE_RESET is not set +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set CONFIG_ARCH_USE_MMU=y # CONFIG_ARCH_ADDRENV is not set # CONFIG_PAGING is not set @@ -427,6 +432,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -593,6 +600,7 @@ CONFIG_OTHER_SERIAL_CONSOLE=y # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -601,7 +609,9 @@ CONFIG_OTHER_SERIAL_CONSOLE=y # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -677,6 +687,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_GRAN is not set # CONFIG_MM_PGALLOC is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -685,6 +700,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -856,7 +872,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -888,6 +903,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1059,3 +1075,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/sama5d3x-ek/demo/defconfig b/configs/sama5d3x-ek/demo/defconfig index 8f2c5d2cd3..e7b781f1a7 100644 --- a/configs/sama5d3x-ek/demo/defconfig +++ b/configs/sama5d3x-ek/demo/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -95,6 +96,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set CONFIG_ARCH_CHIP_SAMA5=y # CONFIG_ARCH_CHIP_SAMD is not set @@ -102,11 +104,12 @@ CONFIG_ARCH_CHIP_SAMA5=y # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -338,6 +341,7 @@ CONFIG_SAMA5_ISRAM_HEAP=y CONFIG_SAMA5_DDRCS_HEAP=y CONFIG_SAMA5_DDRCS_HEAP_OFFSET=0 CONFIG_SAMA5_DDRCS_HEAP_SIZE=268435456 +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -358,6 +362,7 @@ CONFIG_ARCH_NAND_HWECC=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set # CONFIG_ARCH_HAVE_RESET is not set +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set CONFIG_ARCH_USE_MMU=y # CONFIG_ARCH_ADDRENV is not set # CONFIG_PAGING is not set @@ -490,6 +495,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -788,7 +795,9 @@ CONFIG_HIDKBD_BUFSIZE=64 # CONFIG_HIDKBD_ALLSCANCODES is not set # CONFIG_HIDKBD_NODEBOUNCE is not set # CONFIG_USBHOST_HIDMOUSE is not set +# CONFIG_USBHOST_XBOXCONTROLLER is not set # CONFIG_USBHOST_TRACE is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -797,7 +806,9 @@ CONFIG_HIDKBD_BUFSIZE=64 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -874,6 +885,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_GRAN is not set # CONFIG_MM_PGALLOC is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -882,6 +898,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1053,7 +1070,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1087,6 +1103,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1273,3 +1290,14 @@ CONFIG_SYSTEM_USBMSC_CMD_STACKSIZE=768 CONFIG_SYSTEM_USBMSC_CMD_PRIORITY=100 # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/sama5d3x-ek/nsh/defconfig b/configs/sama5d3x-ek/nsh/defconfig index 9854da0346..6ed56ba51e 100644 --- a/configs/sama5d3x-ek/nsh/defconfig +++ b/configs/sama5d3x-ek/nsh/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -95,6 +96,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set CONFIG_ARCH_CHIP_SAMA5=y # CONFIG_ARCH_CHIP_SAMD is not set @@ -102,11 +104,12 @@ CONFIG_ARCH_CHIP_SAMA5=y # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -286,6 +289,7 @@ CONFIG_SAMA5_BOOT_CS0FLASH=y # Heap Configuration # CONFIG_SAMA5_ISRAM_HEAP=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -306,6 +310,7 @@ CONFIG_ARCH_NAND_HWECC=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set # CONFIG_ARCH_HAVE_RESET is not set +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set CONFIG_ARCH_USE_MMU=y # CONFIG_ARCH_ADDRENV is not set # CONFIG_PAGING is not set @@ -426,6 +431,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -606,6 +613,7 @@ CONFIG_USART1_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -614,7 +622,9 @@ CONFIG_USART1_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -690,6 +700,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_GRAN is not set # CONFIG_MM_PGALLOC is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -698,6 +713,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -869,7 +885,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -901,6 +916,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1072,3 +1088,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/sama5d3x-ek/nx/defconfig b/configs/sama5d3x-ek/nx/defconfig index 9d50e995e5..7c4fd0babb 100644 --- a/configs/sama5d3x-ek/nx/defconfig +++ b/configs/sama5d3x-ek/nx/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -95,6 +96,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set CONFIG_ARCH_CHIP_SAMA5=y # CONFIG_ARCH_CHIP_SAMD is not set @@ -102,11 +104,12 @@ CONFIG_ARCH_CHIP_SAMA5=y # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -325,6 +328,7 @@ CONFIG_SAMA5_ISRAM_HEAP=y CONFIG_SAMA5_DDRCS_HEAP=y CONFIG_SAMA5_DDRCS_HEAP_OFFSET=5767168 CONFIG_SAMA5_DDRCS_HEAP_SIZE=262668288 +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -345,6 +349,7 @@ CONFIG_ARCH_NAND_HWECC=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set # CONFIG_ARCH_HAVE_RESET is not set +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set CONFIG_ARCH_USE_MMU=y # CONFIG_ARCH_ADDRENV is not set # CONFIG_PAGING is not set @@ -468,6 +473,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -648,6 +655,7 @@ CONFIG_USART1_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -656,7 +664,9 @@ CONFIG_USART1_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -804,6 +814,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_GRAN is not set # CONFIG_MM_PGALLOC is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -812,6 +827,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -979,7 +995,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set # CONFIG_EXAMPLES_NSH is not set # CONFIG_EXAMPLES_NULL is not set CONFIG_EXAMPLES_NX=y @@ -1016,6 +1031,7 @@ CONFIG_EXAMPLES_NX_TOOLBAR_HEIGHT=16 # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1090,3 +1106,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/sama5d3x-ek/nxplayer/defconfig b/configs/sama5d3x-ek/nxplayer/defconfig index f5f62d6b77..bfac9ef93c 100644 --- a/configs/sama5d3x-ek/nxplayer/defconfig +++ b/configs/sama5d3x-ek/nxplayer/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -95,6 +96,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set CONFIG_ARCH_CHIP_SAMA5=y # CONFIG_ARCH_CHIP_SAMD is not set @@ -102,11 +104,12 @@ CONFIG_ARCH_CHIP_SAMA5=y # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -337,6 +340,7 @@ CONFIG_SAMA5_ISRAM_HEAP=y CONFIG_SAMA5_DDRCS_HEAP=y CONFIG_SAMA5_DDRCS_HEAP_OFFSET=0 CONFIG_SAMA5_DDRCS_HEAP_SIZE=268435456 +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -357,6 +361,7 @@ CONFIG_ARCH_NAND_HWECC=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set # CONFIG_ARCH_HAVE_RESET is not set +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set CONFIG_ARCH_USE_MMU=y # CONFIG_ARCH_ADDRENV is not set # CONFIG_PAGING is not set @@ -487,6 +492,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -703,6 +710,7 @@ CONFIG_USART1_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -711,7 +719,9 @@ CONFIG_USART1_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -787,6 +797,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_GRAN is not set # CONFIG_MM_PGALLOC is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -828,6 +843,7 @@ CONFIG_AUDIO_EXCLUDE_REWIND=y # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -999,7 +1015,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1032,6 +1047,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1217,3 +1233,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/sama5d3x-ek/nxwm/defconfig b/configs/sama5d3x-ek/nxwm/defconfig index e8ae80a84a..d3d488735c 100644 --- a/configs/sama5d3x-ek/nxwm/defconfig +++ b/configs/sama5d3x-ek/nxwm/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -95,6 +96,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set CONFIG_ARCH_CHIP_SAMA5=y # CONFIG_ARCH_CHIP_SAMD is not set @@ -102,11 +104,12 @@ CONFIG_ARCH_CHIP_SAMA5=y # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -354,6 +357,7 @@ CONFIG_SAMA5_ISRAM_HEAP=y CONFIG_SAMA5_DDRCS_HEAP=y CONFIG_SAMA5_DDRCS_HEAP_OFFSET=5767168 CONFIG_SAMA5_DDRCS_HEAP_SIZE=262668288 +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -374,6 +378,7 @@ CONFIG_ARCH_NAND_HWECC=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set # CONFIG_ARCH_HAVE_RESET is not set +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set CONFIG_ARCH_USE_MMU=y # CONFIG_ARCH_ADDRENV is not set # CONFIG_PAGING is not set @@ -502,6 +507,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -608,8 +615,11 @@ CONFIG_ADC=y CONFIG_ADC_FIFOSIZE=8 # CONFIG_ADC_ADS1242 is not set # CONFIG_ADC_ADS125X is not set +# CONFIG_ADC_LTC1867L is not set # CONFIG_ADC_PGA11X is not set +# CONFIG_COMP is not set # CONFIG_DAC is not set +# CONFIG_OPAMP is not set # CONFIG_AUDIO_DEVICES is not set # CONFIG_VIDEO_DEVICES is not set # CONFIG_BCH is not set @@ -703,6 +713,7 @@ CONFIG_USART1_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -711,7 +722,9 @@ CONFIG_USART1_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -892,6 +905,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_GRAN is not set # CONFIG_MM_PGALLOC is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -900,6 +918,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1072,7 +1091,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set # CONFIG_EXAMPLES_NSH is not set # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -1103,6 +1121,7 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1450,3 +1469,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/sama5d4-ek/at25boot/defconfig b/configs/sama5d4-ek/at25boot/defconfig index 7eb4be0921..e8a887220d 100644 --- a/configs/sama5d4-ek/at25boot/defconfig +++ b/configs/sama5d4-ek/at25boot/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -95,6 +96,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set CONFIG_ARCH_CHIP_SAMA5=y # CONFIG_ARCH_CHIP_SAMD is not set @@ -102,11 +104,12 @@ CONFIG_ARCH_CHIP_SAMA5=y # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -306,6 +309,7 @@ CONFIG_SAMA5_BOOT_ISRAM=y CONFIG_SAMA5_DDRCS_HEAP=y CONFIG_SAMA5_DDRCS_HEAP_OFFSET=0 CONFIG_SAMA5_DDRCS_HEAP_SIZE=0 +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -326,6 +330,7 @@ CONFIG_ARCH_NAND_HWECC=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set # CONFIG_ARCH_HAVE_RESET is not set +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set CONFIG_ARCH_USE_MMU=y # CONFIG_ARCH_ADDRENV is not set # CONFIG_PAGING is not set @@ -452,6 +457,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -673,6 +680,7 @@ CONFIG_USART3_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -681,7 +689,9 @@ CONFIG_USART3_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -749,6 +759,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_GRAN is not set # CONFIG_MM_PGALLOC is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -757,6 +772,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -928,7 +944,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set # CONFIG_EXAMPLES_NSH is not set # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -958,6 +973,7 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1034,3 +1050,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/sama5d4-ek/bridge/defconfig b/configs/sama5d4-ek/bridge/defconfig index 565cd8c324..9248a99e8c 100644 --- a/configs/sama5d4-ek/bridge/defconfig +++ b/configs/sama5d4-ek/bridge/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -344,6 +345,7 @@ CONFIG_SAMA5_BOOT_SDRAM=y # # CONFIG_SAMA5_ISRAM_HEAP is not set # CONFIG_SAMA5_DDRCS_RESERVE is not set +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -364,6 +366,7 @@ CONFIG_ARCH_NAND_HWECC=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set # CONFIG_ARCH_HAVE_RESET is not set +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set CONFIG_ARCH_USE_MMU=y # CONFIG_ARCH_ADDRENV is not set # CONFIG_PAGING is not set @@ -562,11 +565,6 @@ CONFIG_DEV_NULL=y # # Buffering # - -# -# Common I/O Buffer Support -# -# CONFIG_MM_IOB is not set # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -731,7 +729,9 @@ CONFIG_USART3_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -898,6 +898,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_GRAN is not set # CONFIG_MM_PGALLOC is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -906,6 +911,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1235,3 +1241,10 @@ CONFIG_READLINE_ECHO=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/sama5d4-ek/dramboot/defconfig b/configs/sama5d4-ek/dramboot/defconfig index 99a516b291..84ccf16d8b 100644 --- a/configs/sama5d4-ek/dramboot/defconfig +++ b/configs/sama5d4-ek/dramboot/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -95,6 +96,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set CONFIG_ARCH_CHIP_SAMA5=y # CONFIG_ARCH_CHIP_SAMD is not set @@ -102,11 +104,12 @@ CONFIG_ARCH_CHIP_SAMA5=y # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -302,6 +305,7 @@ CONFIG_SAMA5_BOOT_ISRAM=y CONFIG_SAMA5_DDRCS_HEAP=y CONFIG_SAMA5_DDRCS_HEAP_OFFSET=0 CONFIG_SAMA5_DDRCS_HEAP_SIZE=0 +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -322,6 +326,7 @@ CONFIG_ARCH_NAND_HWECC=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set # CONFIG_ARCH_HAVE_RESET is not set +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set CONFIG_ARCH_USE_MMU=y # CONFIG_ARCH_ADDRENV is not set # CONFIG_PAGING is not set @@ -445,6 +450,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -625,6 +632,7 @@ CONFIG_USART3_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -633,7 +641,9 @@ CONFIG_USART3_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -701,6 +711,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_GRAN is not set # CONFIG_MM_PGALLOC is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -709,6 +724,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -880,7 +896,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set # CONFIG_EXAMPLES_NSH is not set # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -910,6 +925,7 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -985,3 +1001,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/sama5d4-ek/elf/defconfig b/configs/sama5d4-ek/elf/defconfig index fcbad45992..6b8363dbbb 100644 --- a/configs/sama5d4-ek/elf/defconfig +++ b/configs/sama5d4-ek/elf/defconfig @@ -35,6 +35,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -96,6 +97,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set CONFIG_ARCH_CHIP_SAMA5=y # CONFIG_ARCH_CHIP_SAMD is not set @@ -103,11 +105,12 @@ CONFIG_ARCH_CHIP_SAMA5=y # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -305,6 +308,7 @@ CONFIG_SAMA5_DDRCS_HEAP_END=0x28000000 CONFIG_SAMA5_DDRCS_PGHEAP=y CONFIG_SAMA5_DDRCS_PGHEAP_OFFSET=0x08000000 CONFIG_SAMA5_DDRCS_PGHEAP_SIZE=134217728 +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -325,6 +329,7 @@ CONFIG_ARCH_NAND_HWECC=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set # CONFIG_ARCH_HAVE_RESET is not set +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set CONFIG_ARCH_USE_MMU=y CONFIG_ARCH_ADDRENV=y CONFIG_ARCH_TEXT_VBASE=0x80000000 @@ -455,6 +460,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -669,6 +676,7 @@ CONFIG_USART4_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -677,7 +685,9 @@ CONFIG_USART4_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -741,6 +751,11 @@ CONFIG_GRAN_SINGLE=y CONFIG_MM_PGALLOC=y CONFIG_MM_PGSIZE=4096 +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -929,7 +944,6 @@ CONFIG_EXAMPLES_ELF_CXXINITIALIZE=y # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set # CONFIG_EXAMPLES_NSH is not set # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -963,6 +977,7 @@ CONFIG_EXAMPLES_ELF_CXXINITIALIZE=y # CONFIG_EXAMPLES_UNIONFS is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1040,3 +1055,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/sama5d4-ek/ipv6/defconfig b/configs/sama5d4-ek/ipv6/defconfig index 60d4077d20..afe653afc8 100644 --- a/configs/sama5d4-ek/ipv6/defconfig +++ b/configs/sama5d4-ek/ipv6/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -424,6 +425,7 @@ CONFIG_SAMA5_BOOT_SDRAM=y CONFIG_SAMA5_ISRAM_HEAP=y CONFIG_SAMA5_DDRCS_RESERVE=y CONFIG_SAMA5_DDRCS_HEAP_END=0x2fa00000 +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -444,6 +446,7 @@ CONFIG_ARCH_NAND_HWECC=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set # CONFIG_ARCH_HAVE_RESET is not set +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set CONFIG_ARCH_USE_MMU=y # CONFIG_ARCH_ADDRENV is not set # CONFIG_PAGING is not set @@ -663,15 +666,6 @@ CONFIG_DEV_RANDOM=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=36 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 -CONFIG_IOB_THROTTLE=8 # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -908,6 +902,7 @@ CONFIG_HIDKBD_NPOLLWAITERS=2 # System Logging # # CONFIG_ARCH_SYSLOG is not set +# CONFIG_SYSLOG_WRITE is not set CONFIG_RAMLOG=y # CONFIG_RAMLOG_CONSOLE is not set CONFIG_RAMLOG_BUFSIZE=16384 @@ -1186,6 +1181,15 @@ CONFIG_MM_REGIONS=1 # CONFIG_GRAN is not set # CONFIG_MM_PGALLOC is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=36 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 +CONFIG_IOB_THROTTLE=8 + # # Audio Support # @@ -1227,6 +1231,7 @@ CONFIG_AUDIO_EXCLUDE_REWIND=y # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1729,3 +1734,10 @@ CONFIG_READLINE_ECHO=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/sama5d4-ek/knsh/defconfig b/configs/sama5d4-ek/knsh/defconfig index e617e8e206..8731f0ebe9 100644 --- a/configs/sama5d4-ek/knsh/defconfig +++ b/configs/sama5d4-ek/knsh/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -95,6 +96,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set CONFIG_ARCH_CHIP_SAMA5=y # CONFIG_ARCH_CHIP_SAMD is not set @@ -102,11 +104,12 @@ CONFIG_ARCH_CHIP_SAMA5=y # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -315,6 +318,7 @@ CONFIG_SAMA5_DDRCS_HEAP_END=0x28000000 CONFIG_SAMA5_DDRCS_PGHEAP=y CONFIG_SAMA5_DDRCS_PGHEAP_OFFSET=0x08000000 CONFIG_SAMA5_DDRCS_PGHEAP_SIZE=134217728 +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -335,6 +339,7 @@ CONFIG_ARCH_NAND_HWECC=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set # CONFIG_ARCH_HAVE_RESET is not set +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set CONFIG_ARCH_USE_MMU=y CONFIG_ARCH_ADDRENV=y CONFIG_ARCH_TEXT_VBASE=0x80000000 @@ -472,6 +477,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -697,6 +704,7 @@ CONFIG_USART4_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -705,7 +713,9 @@ CONFIG_USART4_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -788,6 +798,11 @@ CONFIG_MM_PGALLOC=y CONFIG_MM_PGSIZE=4096 # CONFIG_MM_SHM is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -975,6 +990,7 @@ CONFIG_EXAMPLES_HELLO_PROGNAME="hello" CONFIG_EXAMPLES_HELLO_PRIORITY=100 CONFIG_EXAMPLES_HELLO_STACKSIZE=2048 # CONFIG_EXAMPLES_HELLOXX is not set +# CONFIG_EXAMPLES_HIDKBD is not set # CONFIG_EXAMPLES_IGMP is not set # CONFIG_EXAMPLES_JSON is not set # CONFIG_EXAMPLES_KEYPADTEST is not set @@ -982,7 +998,6 @@ CONFIG_EXAMPLES_HELLO_STACKSIZE=2048 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_PROGNAME="init" # CONFIG_EXAMPLES_NSH_CXXINITIALIZE is not set @@ -1015,6 +1030,7 @@ CONFIG_EXAMPLES_NSH_PROGNAME="init" # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1190,3 +1206,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/sama5d4-ek/nsh/defconfig b/configs/sama5d4-ek/nsh/defconfig index fa51ddcf86..f25cb4b431 100644 --- a/configs/sama5d4-ek/nsh/defconfig +++ b/configs/sama5d4-ek/nsh/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -424,6 +425,7 @@ CONFIG_SAMA5_BOOT_SDRAM=y CONFIG_SAMA5_ISRAM_HEAP=y CONFIG_SAMA5_DDRCS_RESERVE=y CONFIG_SAMA5_DDRCS_HEAP_END=0x2fa00000 +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -444,6 +446,7 @@ CONFIG_ARCH_NAND_HWECC=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set # CONFIG_ARCH_HAVE_RESET is not set +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set CONFIG_ARCH_USE_MMU=y # CONFIG_ARCH_ADDRENV is not set # CONFIG_PAGING is not set @@ -663,15 +666,6 @@ CONFIG_DEV_RANDOM=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=36 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 -CONFIG_IOB_THROTTLE=8 # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -910,6 +904,7 @@ CONFIG_HIDKBD_NPOLLWAITERS=2 # System Logging # # CONFIG_ARCH_SYSLOG is not set +# CONFIG_SYSLOG_WRITE is not set CONFIG_RAMLOG=y # CONFIG_RAMLOG_CONSOLE is not set CONFIG_RAMLOG_BUFSIZE=16384 @@ -1190,6 +1185,15 @@ CONFIG_MM_REGIONS=1 # CONFIG_GRAN is not set # CONFIG_MM_PGALLOC is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=36 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 +CONFIG_IOB_THROTTLE=8 + # # Audio Support # @@ -1231,6 +1235,7 @@ CONFIG_AUDIO_EXCLUDE_REWIND=y # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1730,3 +1735,10 @@ CONFIG_READLINE_ECHO=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/sama5d4-ek/nxwm/defconfig b/configs/sama5d4-ek/nxwm/defconfig index a47b489608..4690d35918 100644 --- a/configs/sama5d4-ek/nxwm/defconfig +++ b/configs/sama5d4-ek/nxwm/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -398,6 +399,7 @@ CONFIG_SAMA5_BOOT_SDRAM=y CONFIG_SAMA5_ISRAM_HEAP=y CONFIG_SAMA5_DDRCS_RESERVE=y CONFIG_SAMA5_DDRCS_HEAP_END=0x2fa00000 +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -418,6 +420,7 @@ CONFIG_ARCH_NAND_HWECC=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set # CONFIG_ARCH_HAVE_RESET is not set +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set CONFIG_ARCH_USE_MMU=y # CONFIG_ARCH_ADDRENV is not set # CONFIG_PAGING is not set @@ -637,15 +640,6 @@ CONFIG_DEV_RANDOM=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=36 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 -CONFIG_IOB_THROTTLE=8 # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -879,6 +873,7 @@ CONFIG_HIDKBD_NPOLLWAITERS=2 # System Logging # # CONFIG_ARCH_SYSLOG is not set +# CONFIG_SYSLOG_WRITE is not set CONFIG_RAMLOG=y # CONFIG_RAMLOG_CONSOLE is not set CONFIG_RAMLOG_BUFSIZE=16384 @@ -1182,6 +1177,15 @@ CONFIG_MM_REGIONS=1 # CONFIG_GRAN is not set # CONFIG_MM_PGALLOC is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=36 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 +CONFIG_IOB_THROTTLE=8 + # # Audio Support # @@ -1223,6 +1227,7 @@ CONFIG_AUDIO_EXCLUDE_REWIND=y # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1919,3 +1924,10 @@ CONFIG_READLINE_ECHO=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/sama5d4-ek/ramtest/defconfig b/configs/sama5d4-ek/ramtest/defconfig index b5466c4c02..44720daf54 100644 --- a/configs/sama5d4-ek/ramtest/defconfig +++ b/configs/sama5d4-ek/ramtest/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -95,6 +96,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set CONFIG_ARCH_CHIP_SAMA5=y # CONFIG_ARCH_CHIP_SAMD is not set @@ -102,11 +104,12 @@ CONFIG_ARCH_CHIP_SAMA5=y # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -302,6 +305,7 @@ CONFIG_SAMA5_BOOT_ISRAM=y CONFIG_SAMA5_DDRCS_HEAP=y CONFIG_SAMA5_DDRCS_HEAP_OFFSET=0 CONFIG_SAMA5_DDRCS_HEAP_SIZE=0 +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -322,6 +326,7 @@ CONFIG_ARCH_NAND_HWECC=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set # CONFIG_ARCH_HAVE_RESET is not set +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set CONFIG_ARCH_USE_MMU=y # CONFIG_ARCH_ADDRENV is not set # CONFIG_PAGING is not set @@ -444,6 +449,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -624,6 +631,7 @@ CONFIG_USART3_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -632,7 +640,9 @@ CONFIG_USART3_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -708,6 +718,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_GRAN is not set # CONFIG_MM_PGALLOC is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -716,6 +731,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -887,7 +903,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -919,6 +934,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1085,3 +1101,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/samd20-xplained/nsh/defconfig b/configs/samd20-xplained/nsh/defconfig index 9985c9cc06..f2fece4c3f 100644 --- a/configs/samd20-xplained/nsh/defconfig +++ b/configs/samd20-xplained/nsh/defconfig @@ -34,6 +34,7 @@ CONFIG_BUILD_FLAT=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -95,6 +96,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set CONFIG_ARCH_CHIP_SAMD=y @@ -102,11 +104,12 @@ CONFIG_ARCH_CHIP_SAMD=y # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -128,7 +131,7 @@ CONFIG_ARCH_CORTEXM0=y CONFIG_ARCH_FAMILY="armv6-m" CONFIG_ARCH_CHIP="samdl" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set +CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set # CONFIG_ARMV7M_LAZYFPU is not set @@ -236,6 +239,7 @@ CONFIG_SAMDL_SERCOM3_ISUSART=y # CONFIG_SAMDL_SERCOM4_ISI2C is not set # CONFIG_SAMDL_SERCOM4_ISSPI is not set CONFIG_SAMDL_SERCOM4_ISUSART=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -256,6 +260,7 @@ CONFIG_ARCH_HAVE_VFORK=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y # CONFIG_ENDIAN_BIG is not set @@ -371,6 +376,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -565,6 +572,7 @@ CONFIG_USART4_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -573,7 +581,9 @@ CONFIG_USART4_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -632,6 +642,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -640,6 +655,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -806,7 +822,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -838,6 +853,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1004,3 +1020,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/samd21-xplained/nsh/defconfig b/configs/samd21-xplained/nsh/defconfig index 1f42da0c98..bfbf127c9e 100644 --- a/configs/samd21-xplained/nsh/defconfig +++ b/configs/samd21-xplained/nsh/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set # CONFIG_RAW_BINARY is not set # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -95,6 +96,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set CONFIG_ARCH_CHIP_SAMD=y @@ -102,11 +104,12 @@ CONFIG_ARCH_CHIP_SAMD=y # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -128,7 +131,7 @@ CONFIG_ARCH_CORTEXM0=y CONFIG_ARCH_FAMILY="armv6-m" CONFIG_ARCH_CHIP="samdl" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set +CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set # CONFIG_ARMV7M_LAZYFPU is not set @@ -234,6 +237,7 @@ CONFIG_SAMDL_SERCOM3_ISUSART=y # CONFIG_SAMDL_SERCOM4_ISI2C is not set # CONFIG_SAMDL_SERCOM4_ISSPI is not set CONFIG_SAMDL_SERCOM4_ISUSART=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -254,6 +258,7 @@ CONFIG_ARCH_HAVE_VFORK=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y # CONFIG_ENDIAN_BIG is not set @@ -369,6 +374,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -563,6 +570,7 @@ CONFIG_USART4_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -571,7 +579,9 @@ CONFIG_USART4_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -630,6 +640,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -638,6 +653,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -804,7 +820,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -836,6 +851,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1002,3 +1018,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/saml21-xplained/nsh/defconfig b/configs/saml21-xplained/nsh/defconfig index aab9988399..17eff8509f 100644 --- a/configs/saml21-xplained/nsh/defconfig +++ b/configs/saml21-xplained/nsh/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set # CONFIG_RAW_BINARY is not set # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -95,6 +96,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -102,11 +104,12 @@ CONFIG_ARCH_CHIP_SAML=y # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -128,7 +131,7 @@ CONFIG_ARCH_CORTEXM0=y CONFIG_ARCH_FAMILY="armv6-m" CONFIG_ARCH_CHIP="samdl" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set +CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set # CONFIG_ARMV7M_LAZYFPU is not set @@ -211,6 +214,7 @@ CONFIG_SAMDL_SERCOM3_ISUSART=y # CONFIG_SAMDL_SERCOM4_ISI2C is not set # CONFIG_SAMDL_SERCOM4_ISSPI is not set CONFIG_SAMDL_SERCOM4_ISUSART=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -231,6 +235,7 @@ CONFIG_ARCH_HAVE_VFORK=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y # CONFIG_ENDIAN_BIG is not set @@ -357,6 +362,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -551,6 +558,7 @@ CONFIG_USART4_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -559,7 +567,9 @@ CONFIG_USART4_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -618,6 +628,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -626,6 +641,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -792,7 +808,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -824,6 +839,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -990,3 +1006,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/samv71-xult/nxwm/defconfig b/configs/samv71-xult/nxwm/defconfig index 19da1735ac..0953e98bf0 100644 --- a/configs/samv71-xult/nxwm/defconfig +++ b/configs/samv71-xult/nxwm/defconfig @@ -34,6 +34,7 @@ CONFIG_BUILD_FLAT=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -95,6 +96,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -102,11 +104,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set CONFIG_ARCH_CHIP_SAMV7=y # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -297,6 +300,7 @@ CONFIG_SAMV7_HSMCI_DMA=y # CONFIG_SAMV7_HSMCI_RDPROOF is not set # CONFIG_SAMV7_HSMCI_WRPROOF is not set # CONFIG_SAMV7_HSMCI_UNALIGNED is not set +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -317,6 +321,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -441,6 +446,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -741,6 +748,7 @@ CONFIG_USART0_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -749,7 +757,9 @@ CONFIG_USART0_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -927,6 +937,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -935,6 +950,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1110,7 +1126,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set # CONFIG_EXAMPLES_NSH is not set # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -1142,6 +1157,7 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1499,3 +1515,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/samv71-xult/vnxwm/defconfig b/configs/samv71-xult/vnxwm/defconfig index 1a2738b66b..8a0cb8029c 100644 --- a/configs/samv71-xult/vnxwm/defconfig +++ b/configs/samv71-xult/vnxwm/defconfig @@ -34,6 +34,7 @@ CONFIG_BUILD_FLAT=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -320,6 +321,7 @@ CONFIG_SAMV7_EMAC0_ISETH0=y # CONFIG_SAMV7_EMAC_PREALLOCATE is not set # CONFIG_SAMV7_EMAC_NBC is not set CONFIG_SAMV7_EMAC_HPWORK=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -340,6 +342,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -541,15 +544,6 @@ CONFIG_DEV_NULL=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=72 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 -CONFIG_IOB_THROTTLE=32 # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -778,7 +772,9 @@ CONFIG_UART3_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1089,6 +1085,15 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=72 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 +CONFIG_IOB_THROTTLE=32 + # # Audio Support # @@ -1695,3 +1700,10 @@ CONFIG_READLINE_ECHO=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/shenzhou/nxwm/defconfig b/configs/shenzhou/nxwm/defconfig index e64dfed648..8136459843 100644 --- a/configs/shenzhou/nxwm/defconfig +++ b/configs/shenzhou/nxwm/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set # CONFIG_RAW_BINARY is not set # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -272,6 +273,7 @@ CONFIG_ARCH_CHIP_STM32F107VC=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -330,6 +332,7 @@ CONFIG_STM32_CONNECTIVITYLINE=y # CONFIG_STM32_STM32F37XX is not set # CONFIG_STM32_STM32F40XX is not set # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set # CONFIG_STM32_STM32F407 is not set @@ -535,6 +538,7 @@ CONFIG_STM32_ETHMAC_HPWORK=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -555,6 +559,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -771,14 +776,6 @@ CONFIG_DEV_NULL=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=24 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -996,7 +993,9 @@ CONFIG_USART2_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1276,6 +1275,14 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 + # # Audio Support # @@ -1284,6 +1291,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1880,3 +1888,10 @@ CONFIG_READLINE_ECHO=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm3220g-eval/dhcpd/defconfig b/configs/stm3220g-eval/dhcpd/defconfig index 9168df6ad7..2771754291 100644 --- a/configs/stm3220g-eval/dhcpd/defconfig +++ b/configs/stm3220g-eval/dhcpd/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set # CONFIG_RAW_BINARY is not set # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -272,6 +273,7 @@ CONFIG_ARCH_CHIP_STM32F207IG=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -330,6 +332,7 @@ CONFIG_STM32_STM32F207=y # CONFIG_STM32_STM32F37XX is not set # CONFIG_STM32_STM32F40XX is not set # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set # CONFIG_STM32_STM32F407 is not set @@ -550,6 +553,7 @@ CONFIG_STM32_ETHMAC_HPWORK=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -570,6 +574,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -742,14 +747,6 @@ CONFIG_DEV_NULL=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=8 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -903,7 +900,9 @@ CONFIG_USART3_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1051,6 +1050,14 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=8 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 + # # Audio Support # @@ -1059,6 +1066,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1349,3 +1357,10 @@ CONFIG_NETUTILS_NETLIB=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm3220g-eval/nettest/defconfig b/configs/stm3220g-eval/nettest/defconfig index 7067e766aa..78726df3c1 100644 --- a/configs/stm3220g-eval/nettest/defconfig +++ b/configs/stm3220g-eval/nettest/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set # CONFIG_RAW_BINARY is not set # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -272,6 +273,7 @@ CONFIG_ARCH_CHIP_STM32F207IG=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -330,6 +332,7 @@ CONFIG_STM32_STM32F207=y # CONFIG_STM32_STM32F37XX is not set # CONFIG_STM32_STM32F40XX is not set # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set # CONFIG_STM32_STM32F407 is not set @@ -550,6 +553,7 @@ CONFIG_STM32_ETHMAC_HPWORK=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -570,6 +574,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -742,14 +747,6 @@ CONFIG_DEV_NULL=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=24 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -903,7 +900,9 @@ CONFIG_USART3_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1056,6 +1055,14 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 + # # Audio Support # @@ -1064,6 +1071,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1349,3 +1357,10 @@ CONFIG_NETUTILS_NETLIB=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm3220g-eval/nsh/defconfig b/configs/stm3220g-eval/nsh/defconfig index a37ca34d75..b64cbf7a36 100644 --- a/configs/stm3220g-eval/nsh/defconfig +++ b/configs/stm3220g-eval/nsh/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set # CONFIG_RAW_BINARY is not set # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -262,6 +263,7 @@ CONFIG_ARCH_CHIP_STM32F207IG=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -320,6 +322,7 @@ CONFIG_STM32_STM32F207=y # CONFIG_STM32_STM32F37XX is not set # CONFIG_STM32_STM32F40XX is not set # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set # CONFIG_STM32_STM32F407 is not set @@ -557,6 +560,7 @@ CONFIG_STM32_ETHMAC_HPWORK=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -577,6 +581,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -767,14 +772,6 @@ CONFIG_DEV_NULL=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=24 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -978,7 +975,9 @@ CONFIG_USART3_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1152,6 +1151,14 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 + # # Audio Support # @@ -1160,6 +1167,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1593,3 +1601,10 @@ CONFIG_READLINE_ECHO=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm3220g-eval/nsh2/defconfig b/configs/stm3220g-eval/nsh2/defconfig index c0d61540dc..439c8390c5 100644 --- a/configs/stm3220g-eval/nsh2/defconfig +++ b/configs/stm3220g-eval/nsh2/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set # CONFIG_RAW_BINARY is not set # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -271,6 +272,7 @@ CONFIG_ARCH_CHIP_STM32F207IG=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -329,6 +331,7 @@ CONFIG_STM32_STM32F207=y # CONFIG_STM32_STM32F37XX is not set # CONFIG_STM32_STM32F40XX is not set # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set # CONFIG_STM32_STM32F407 is not set @@ -553,6 +556,7 @@ CONFIG_STM32_ETHMAC_HPWORK=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -573,6 +577,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -768,14 +773,6 @@ CONFIG_DEV_NULL=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=24 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -970,6 +967,7 @@ CONFIG_SERIAL=y # System Logging # # CONFIG_ARCH_SYSLOG is not set +# CONFIG_SYSLOG_WRITE is not set CONFIG_RAMLOG=y CONFIG_RAMLOG_BUFSIZE=1024 # CONFIG_RAMLOG_CRLF is not set @@ -1148,6 +1146,14 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 + # # Audio Support # @@ -1156,6 +1162,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1611,3 +1618,10 @@ CONFIG_READLINE_ECHO=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm3220g-eval/nxwm/defconfig b/configs/stm3220g-eval/nxwm/defconfig index 68a215312e..170b1cfa0e 100644 --- a/configs/stm3220g-eval/nxwm/defconfig +++ b/configs/stm3220g-eval/nxwm/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set # CONFIG_RAW_BINARY is not set # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -272,6 +273,7 @@ CONFIG_ARCH_CHIP_STM32F207IG=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -330,6 +332,7 @@ CONFIG_STM32_STM32F207=y # CONFIG_STM32_STM32F37XX is not set # CONFIG_STM32_STM32F40XX is not set # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set # CONFIG_STM32_STM32F407 is not set @@ -568,6 +571,7 @@ CONFIG_STM32_ETHMAC_HPWORK=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -588,6 +592,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -788,14 +793,6 @@ CONFIG_DEV_NULL=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=24 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -1022,7 +1019,9 @@ CONFIG_USART3_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1309,6 +1308,14 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 + # # Audio Support # @@ -1317,6 +1324,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1920,3 +1928,10 @@ CONFIG_READLINE_ECHO=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm3220g-eval/telnetd/defconfig b/configs/stm3220g-eval/telnetd/defconfig index e1531299a4..53b2e42c7e 100644 --- a/configs/stm3220g-eval/telnetd/defconfig +++ b/configs/stm3220g-eval/telnetd/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set # CONFIG_RAW_BINARY is not set # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -272,6 +273,7 @@ CONFIG_ARCH_CHIP_STM32F207IG=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -330,6 +332,7 @@ CONFIG_STM32_STM32F207=y # CONFIG_STM32_STM32F37XX is not set # CONFIG_STM32_STM32F40XX is not set # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set # CONFIG_STM32_STM32F407 is not set @@ -550,6 +553,7 @@ CONFIG_STM32_ETHMAC_HPWORK=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -570,6 +574,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -742,14 +747,6 @@ CONFIG_DEV_NULL=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=24 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -905,7 +902,9 @@ CONFIG_USART3_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1058,6 +1057,14 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 + # # Audio Support # @@ -1066,6 +1073,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1346,3 +1354,10 @@ CONFIG_NETUTILS_TELNETD=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm3240g-eval/dhcpd/defconfig b/configs/stm3240g-eval/dhcpd/defconfig index d14a03b0bf..3685d5da3a 100644 --- a/configs/stm3240g-eval/dhcpd/defconfig +++ b/configs/stm3240g-eval/dhcpd/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set # CONFIG_RAW_BINARY is not set # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -273,6 +274,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -331,6 +333,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -554,6 +557,7 @@ CONFIG_STM32_ETHMAC_HPWORK=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -574,6 +578,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -746,14 +751,6 @@ CONFIG_DEV_NULL=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=8 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -907,7 +904,9 @@ CONFIG_USART3_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1055,6 +1054,14 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=8 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 + # # Audio Support # @@ -1063,6 +1070,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1353,3 +1361,10 @@ CONFIG_NETUTILS_NETLIB=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm3240g-eval/discover/defconfig b/configs/stm3240g-eval/discover/defconfig index e55ee92107..7644480cc2 100644 --- a/configs/stm3240g-eval/discover/defconfig +++ b/configs/stm3240g-eval/discover/defconfig @@ -28,6 +28,7 @@ CONFIG_BUILD_FLAT=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -263,6 +264,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -321,6 +323,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -555,6 +558,7 @@ CONFIG_STM32_ETHMAC_HPWORK=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -575,6 +579,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -765,14 +770,6 @@ CONFIG_DEV_NULL=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=24 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -933,7 +930,9 @@ CONFIG_USART3_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1106,6 +1105,14 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 + # # Audio Support # @@ -1114,6 +1121,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1367,6 +1375,7 @@ CONFIG_EXAMPLES_DISCOVER_NETMASK=0xffffff00 # # CONFIG_NETUTILS_CODECS is not set CONFIG_NETUTILS_DHCPC=y +CONFIG_NETUTILS_DHCPC_DEVNAME="eth0" # CONFIG_NETUTILS_DHCPD is not set CONFIG_NETUTILS_DISCOVER=y CONFIG_DISCOVER_STACK_SIZE=1024 @@ -1425,3 +1434,10 @@ CONFIG_NETUTILS_NETLIB=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm3240g-eval/knxwm/defconfig b/configs/stm3240g-eval/knxwm/defconfig index f1925469d8..8f8dbb1f0a 100644 --- a/configs/stm3240g-eval/knxwm/defconfig +++ b/configs/stm3240g-eval/knxwm/defconfig @@ -39,6 +39,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set # CONFIG_RAW_BINARY is not set # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -101,6 +102,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -108,11 +110,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -190,6 +193,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -275,6 +281,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -333,6 +340,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -389,9 +397,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -405,7 +417,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -426,6 +441,7 @@ CONFIG_STM32_FSMC=y CONFIG_STM32_I2C1=y # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set # CONFIG_STM32_OTGFS is not set # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -464,6 +480,7 @@ CONFIG_STM32_I2C=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set CONFIG_STM32_JTAG_FULL_ENABLE=y # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -526,6 +543,7 @@ CONFIG_STM32_I2CTIMEOTICKS=500 # CONFIG_STM32_HAVE_RTC_SUBSECONDS is not set CONFIG_RTC_MAGIC_REG=0 CONFIG_RTC_MAGIC=0xfacefeee +CONFIG_RTC_MAGIC_TIME_SET=0xfacefeef CONFIG_RTC_LSECLOCK=y # CONFIG_RTC_LSICLOCK is not set # CONFIG_RTC_HSECLOCK is not set @@ -545,6 +563,7 @@ CONFIG_RTC_LSECLOCK=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -565,6 +584,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set CONFIG_ARCH_USE_MPU=y # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -686,6 +706,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -936,6 +958,7 @@ CONFIG_USART3_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -944,7 +967,9 @@ CONFIG_USART3_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1109,6 +1134,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -1117,6 +1147,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1285,6 +1316,7 @@ CONFIG_CXX_NEWLONG=y # CONFIG_EXAMPLES_FTPD is not set # CONFIG_EXAMPLES_HELLO is not set # CONFIG_EXAMPLES_HELLOXX is not set +# CONFIG_EXAMPLES_HIDKBD is not set # CONFIG_EXAMPLES_IGMP is not set # CONFIG_EXAMPLES_JSON is not set # CONFIG_EXAMPLES_KEYPADTEST is not set @@ -1293,7 +1325,6 @@ CONFIG_CXX_NEWLONG=y # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set # CONFIG_EXAMPLES_NSH is not set # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -1324,6 +1355,7 @@ CONFIG_CXX_NEWLONG=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1567,3 +1599,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm3240g-eval/nettest/defconfig b/configs/stm3240g-eval/nettest/defconfig index c4f9f51a6c..43f5d3cfae 100644 --- a/configs/stm3240g-eval/nettest/defconfig +++ b/configs/stm3240g-eval/nettest/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set # CONFIG_RAW_BINARY is not set # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -273,6 +274,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -331,6 +333,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -554,6 +557,7 @@ CONFIG_STM32_ETHMAC_HPWORK=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -574,6 +578,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -746,14 +751,6 @@ CONFIG_DEV_NULL=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=24 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -907,7 +904,9 @@ CONFIG_USART3_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1060,6 +1059,14 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 + # # Audio Support # @@ -1068,6 +1075,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1353,3 +1361,10 @@ CONFIG_NETUTILS_NETLIB=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm3240g-eval/nsh/defconfig b/configs/stm3240g-eval/nsh/defconfig index d9f65117d5..b6e2403b4a 100644 --- a/configs/stm3240g-eval/nsh/defconfig +++ b/configs/stm3240g-eval/nsh/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set # CONFIG_RAW_BINARY is not set # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -273,6 +274,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -331,6 +333,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -571,6 +574,7 @@ CONFIG_STM32_ETHMAC_HPWORK=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -591,6 +595,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -783,14 +788,6 @@ CONFIG_DEV_RANDOM=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=24 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -957,7 +954,9 @@ CONFIG_USART3_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1131,6 +1130,14 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 + # # Audio Support # @@ -1139,6 +1146,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1588,3 +1596,10 @@ CONFIG_READLINE_ECHO=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm3240g-eval/nsh2/defconfig b/configs/stm3240g-eval/nsh2/defconfig index 63aa6a234b..31b84e446f 100644 --- a/configs/stm3240g-eval/nsh2/defconfig +++ b/configs/stm3240g-eval/nsh2/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set # CONFIG_RAW_BINARY is not set # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -272,6 +273,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -330,6 +332,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -557,6 +560,7 @@ CONFIG_STM32_ETHMAC_HPWORK=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -577,6 +581,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -772,14 +777,6 @@ CONFIG_DEV_NULL=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=24 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -974,6 +971,7 @@ CONFIG_SERIAL=y # System Logging # # CONFIG_ARCH_SYSLOG is not set +# CONFIG_SYSLOG_WRITE is not set CONFIG_RAMLOG=y CONFIG_RAMLOG_BUFSIZE=1024 # CONFIG_RAMLOG_CRLF is not set @@ -1152,6 +1150,14 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 + # # Audio Support # @@ -1160,6 +1166,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1615,3 +1622,10 @@ CONFIG_READLINE_ECHO=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm3240g-eval/nxterm/defconfig b/configs/stm3240g-eval/nxterm/defconfig index c68bc68be6..d7cc5d4f73 100644 --- a/configs/stm3240g-eval/nxterm/defconfig +++ b/configs/stm3240g-eval/nxterm/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set # CONFIG_RAW_BINARY is not set # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -273,6 +274,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -331,6 +333,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -572,6 +575,7 @@ CONFIG_STM32_ETHMAC_HPWORK=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -592,6 +596,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -791,14 +796,6 @@ CONFIG_DEV_NULL=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=24 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -996,7 +993,9 @@ CONFIG_USART3_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1279,6 +1278,14 @@ CONFIG_HEAP2_BASE=0x64000000 CONFIG_HEAP2_SIZE=2097152 # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 + # # Audio Support # @@ -1287,6 +1294,7 @@ CONFIG_HEAP2_SIZE=2097152 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1729,3 +1737,10 @@ CONFIG_READLINE_ECHO=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm3240g-eval/nxwm/defconfig b/configs/stm3240g-eval/nxwm/defconfig index 980d63b0c5..3fc81f25e1 100644 --- a/configs/stm3240g-eval/nxwm/defconfig +++ b/configs/stm3240g-eval/nxwm/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set # CONFIG_RAW_BINARY is not set # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -273,6 +274,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -331,6 +333,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -572,6 +575,7 @@ CONFIG_STM32_ETHMAC_HPWORK=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -592,6 +596,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -792,14 +797,6 @@ CONFIG_DEV_NULL=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=24 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -1018,7 +1015,9 @@ CONFIG_USART3_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1305,6 +1304,14 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 + # # Audio Support # @@ -1313,6 +1320,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1924,3 +1932,10 @@ CONFIG_READLINE_ECHO=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm3240g-eval/telnetd/defconfig b/configs/stm3240g-eval/telnetd/defconfig index d3ea732595..edd1dbb11e 100644 --- a/configs/stm3240g-eval/telnetd/defconfig +++ b/configs/stm3240g-eval/telnetd/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set # CONFIG_RAW_BINARY is not set # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -273,6 +274,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -331,6 +333,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -554,6 +557,7 @@ CONFIG_STM32_ETHMAC_HPWORK=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -574,6 +578,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -746,14 +751,6 @@ CONFIG_DEV_NULL=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=24 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -909,7 +906,9 @@ CONFIG_USART3_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1062,6 +1061,14 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 + # # Audio Support # @@ -1070,6 +1077,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1350,3 +1358,10 @@ CONFIG_NETUTILS_TELNETD=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm3240g-eval/webserver/defconfig b/configs/stm3240g-eval/webserver/defconfig index 910033f2d9..3c9e8c2530 100644 --- a/configs/stm3240g-eval/webserver/defconfig +++ b/configs/stm3240g-eval/webserver/defconfig @@ -28,6 +28,7 @@ CONFIG_BUILD_FLAT=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -263,6 +264,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -321,6 +323,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -561,6 +564,7 @@ CONFIG_STM32_ETHMAC_HPWORK=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -581,6 +585,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -771,14 +776,6 @@ CONFIG_DEV_NULL=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=24 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -976,7 +973,9 @@ CONFIG_USART3_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1149,6 +1148,14 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 + # # Audio Support # @@ -1157,6 +1164,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1611,3 +1619,10 @@ CONFIG_READLINE_ECHO=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm3240g-eval/xmlrpc/defconfig b/configs/stm3240g-eval/xmlrpc/defconfig index aa0f34e696..a88b63ae19 100644 --- a/configs/stm3240g-eval/xmlrpc/defconfig +++ b/configs/stm3240g-eval/xmlrpc/defconfig @@ -28,6 +28,7 @@ CONFIG_BUILD_FLAT=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -263,6 +264,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -321,6 +323,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -555,6 +558,7 @@ CONFIG_STM32_ETHMAC_HPWORK=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -575,6 +579,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -760,14 +765,6 @@ CONFIG_DEV_NULL=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=24 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -929,7 +926,9 @@ CONFIG_USART3_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1102,6 +1101,14 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 + # # Audio Support # @@ -1110,6 +1117,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1366,6 +1374,7 @@ CONFIG_EXAMPLES_XMLRPC_NETMASK=0xffffff00 # CONFIG_NETUTILS_CHAT is not set # CONFIG_NETUTILS_CODECS is not set CONFIG_NETUTILS_DHCPC=y +CONFIG_NETUTILS_DHCPC_DEVNAME="eth0" # CONFIG_NETUTILS_DHCPD is not set # CONFIG_NETUTILS_DISCOVER is not set # CONFIG_NETUTILS_ESP8266 is not set @@ -1420,3 +1429,10 @@ CONFIG_XMLRPC_STRINGSIZE=64 # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm32f3discovery/nsh/defconfig b/configs/stm32f3discovery/nsh/defconfig index 2234c65bea..a39d117485 100644 --- a/configs/stm32f3discovery/nsh/defconfig +++ b/configs/stm32f3discovery/nsh/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -96,6 +97,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -103,11 +105,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -183,6 +186,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -268,6 +274,7 @@ CONFIG_ARCH_CHIP_STM32F303VC=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -326,6 +333,7 @@ CONFIG_STM32_STM32F303=y # CONFIG_STM32_STM32F37XX is not set # CONFIG_STM32_STM32F40XX is not set # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set # CONFIG_STM32_STM32F407 is not set @@ -382,9 +390,13 @@ CONFIG_STM32_HAVE_ADC4=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y # CONFIG_STM32_HAVE_CAN2 is not set +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y # CONFIG_STM32_HAVE_RNG is not set @@ -398,7 +410,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -411,6 +426,7 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_DAC2 is not set # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set +# CONFIG_STM32_OPAMP is not set CONFIG_STM32_PWR=y # CONFIG_STM32_SDIO is not set # CONFIG_STM32_SPI1 is not set @@ -441,6 +457,7 @@ CONFIG_STM32_USB=y # # Alternate Pin Mapping # +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -499,6 +516,7 @@ CONFIG_STM32_USART2_SERIALDRIVER=y # USB Device Configuration # # CONFIG_STM32_USB_ITRMP is not set +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -519,6 +537,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -636,6 +655,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -856,6 +877,7 @@ CONFIG_CDCACM_VENDORSTR="NuttX" CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial" # CONFIG_USBMSC is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -864,7 +886,9 @@ CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial" # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -924,6 +948,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -932,6 +961,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1102,7 +1132,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1135,6 +1164,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1305,3 +1335,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm32f3discovery/usbnsh/defconfig b/configs/stm32f3discovery/usbnsh/defconfig index c068636085..5ddb409c8a 100644 --- a/configs/stm32f3discovery/usbnsh/defconfig +++ b/configs/stm32f3discovery/usbnsh/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -96,6 +97,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -103,11 +105,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -183,6 +186,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -268,6 +274,7 @@ CONFIG_ARCH_CHIP_STM32F303VC=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -326,6 +333,7 @@ CONFIG_STM32_STM32F303=y # CONFIG_STM32_STM32F37XX is not set # CONFIG_STM32_STM32F40XX is not set # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set # CONFIG_STM32_STM32F407 is not set @@ -382,9 +390,13 @@ CONFIG_STM32_HAVE_ADC4=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y # CONFIG_STM32_HAVE_CAN2 is not set +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y # CONFIG_STM32_HAVE_RNG is not set @@ -398,7 +410,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -411,6 +426,7 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_DAC2 is not set # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set +# CONFIG_STM32_OPAMP is not set CONFIG_STM32_PWR=y # CONFIG_STM32_SDIO is not set CONFIG_STM32_SPI1=y @@ -442,6 +458,7 @@ CONFIG_STM32_SPI=y # # Alternate Pin Mapping # +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -506,6 +523,7 @@ CONFIG_STM32_USART2_SERIALDRIVER=y # USB Device Configuration # # CONFIG_STM32_USB_ITRMP is not set +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -526,6 +544,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -643,6 +662,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -871,6 +892,7 @@ CONFIG_CDCACM_VENDORSTR="NuttX" CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial" # CONFIG_USBMSC is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -879,7 +901,9 @@ CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial" # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set # CONFIG_SYSLOG_SERIAL_CONSOLE is not set @@ -940,6 +964,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -948,6 +977,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1118,7 +1148,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1151,6 +1180,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1320,3 +1350,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm32f429i-disco/extflash/defconfig b/configs/stm32f429i-disco/extflash/defconfig index 763981c2b8..bbca59a2f8 100644 --- a/configs/stm32f429i-disco/extflash/defconfig +++ b/configs/stm32f429i-disco/extflash/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -173,6 +176,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -258,6 +264,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -316,6 +323,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set # CONFIG_STM32_STM32F407 is not set @@ -344,7 +352,7 @@ CONFIG_STM32_HAVE_TIM1=y # CONFIG_STM32_HAVE_TIM2 is not set CONFIG_STM32_HAVE_TIM3=y CONFIG_STM32_HAVE_TIM4=y -# CONFIG_STM32_HAVE_TIM5 is not set +CONFIG_STM32_HAVE_TIM5=y CONFIG_STM32_HAVE_TIM6=y CONFIG_STM32_HAVE_TIM7=y CONFIG_STM32_HAVE_TIM8=y @@ -372,9 +380,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -388,7 +400,10 @@ CONFIG_STM32_HAVE_SPI5=y CONFIG_STM32_HAVE_SPI6=y # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -411,6 +426,7 @@ CONFIG_STM32_FSMC=y # CONFIG_STM32_I2C3 is not set # CONFIG_STM32_LTDC is not set # CONFIG_STM32_DMA2D is not set +# CONFIG_STM32_OPAMP is not set # CONFIG_STM32_OTGFS is not set # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -427,6 +443,7 @@ CONFIG_STM32_SYSCFG=y # CONFIG_STM32_TIM2 is not set # CONFIG_STM32_TIM3 is not set # CONFIG_STM32_TIM4 is not set +# CONFIG_STM32_TIM5 is not set # CONFIG_STM32_TIM6 is not set # CONFIG_STM32_TIM7 is not set # CONFIG_STM32_TIM8 is not set @@ -453,6 +470,7 @@ CONFIG_STM32_SPI=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -471,6 +489,7 @@ CONFIG_STM32_FSMC_SRAM=y # CONFIG_STM32_TIM1_CAP is not set # CONFIG_STM32_TIM3_CAP is not set # CONFIG_STM32_TIM4_CAP is not set +# CONFIG_STM32_TIM5_CAP is not set # CONFIG_STM32_TIM8_CAP is not set # CONFIG_STM32_TIM9_CAP is not set # CONFIG_STM32_TIM10_CAP is not set @@ -523,6 +542,7 @@ CONFIG_STM32_USART1_SERIALDRIVER=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -543,6 +563,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -670,6 +691,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -911,6 +934,7 @@ CONFIG_USART1_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -919,7 +943,9 @@ CONFIG_USART1_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -996,6 +1022,11 @@ CONFIG_HEAP2_BASE=0xD0000000 CONFIG_HEAP2_SIZE=8388608 # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -1004,6 +1035,7 @@ CONFIG_HEAP2_SIZE=8388608 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1180,7 +1212,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set # CONFIG_EXAMPLES_MTDPART is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1214,6 +1245,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1388,3 +1420,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm32f429i-disco/lcd/defconfig b/configs/stm32f429i-disco/lcd/defconfig index f4510f5f18..40f7f3cb77 100644 --- a/configs/stm32f429i-disco/lcd/defconfig +++ b/configs/stm32f429i-disco/lcd/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -91,6 +92,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -98,11 +100,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -174,6 +177,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -259,6 +265,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -317,6 +324,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set # CONFIG_STM32_STM32F407 is not set @@ -345,7 +353,7 @@ CONFIG_STM32_HAVE_TIM1=y # CONFIG_STM32_HAVE_TIM2 is not set CONFIG_STM32_HAVE_TIM3=y CONFIG_STM32_HAVE_TIM4=y -# CONFIG_STM32_HAVE_TIM5 is not set +CONFIG_STM32_HAVE_TIM5=y CONFIG_STM32_HAVE_TIM6=y CONFIG_STM32_HAVE_TIM7=y CONFIG_STM32_HAVE_TIM8=y @@ -373,9 +381,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -389,7 +401,10 @@ CONFIG_STM32_HAVE_SPI5=y CONFIG_STM32_HAVE_SPI6=y # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -412,6 +427,7 @@ CONFIG_STM32_FSMC=y # CONFIG_STM32_I2C3 is not set # CONFIG_STM32_LTDC is not set # CONFIG_STM32_DMA2D is not set +# CONFIG_STM32_OPAMP is not set # CONFIG_STM32_OTGFS is not set # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -428,6 +444,7 @@ CONFIG_STM32_SYSCFG=y # CONFIG_STM32_TIM2 is not set # CONFIG_STM32_TIM3 is not set # CONFIG_STM32_TIM4 is not set +# CONFIG_STM32_TIM5 is not set # CONFIG_STM32_TIM6 is not set # CONFIG_STM32_TIM7 is not set # CONFIG_STM32_TIM8 is not set @@ -453,6 +470,7 @@ CONFIG_STM32_USART1=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -471,6 +489,7 @@ CONFIG_STM32_FSMC_SRAM=y # CONFIG_STM32_TIM1_CAP is not set # CONFIG_STM32_TIM3_CAP is not set # CONFIG_STM32_TIM4_CAP is not set +# CONFIG_STM32_TIM5_CAP is not set # CONFIG_STM32_TIM8_CAP is not set # CONFIG_STM32_TIM9_CAP is not set # CONFIG_STM32_TIM10_CAP is not set @@ -517,6 +536,7 @@ CONFIG_STM32_USART1_SERIALDRIVER=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -537,6 +557,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -661,6 +682,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -880,6 +903,7 @@ CONFIG_USART1_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -888,7 +912,9 @@ CONFIG_USART1_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1044,6 +1070,11 @@ CONFIG_HEAP2_BASE=0xD0000000 CONFIG_HEAP2_SIZE=8388608 # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -1052,6 +1083,7 @@ CONFIG_HEAP2_SIZE=8388608 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1226,7 +1258,6 @@ CONFIG_EXAMPLES_LDCRW_YRES=240 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1274,6 +1305,7 @@ CONFIG_EXAMPLES_NX_NOTIFYSIGNO=4 # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1442,3 +1474,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm32f429i-disco/ltdc/defconfig b/configs/stm32f429i-disco/ltdc/defconfig index d65a073981..bfbad09b9e 100644 --- a/configs/stm32f429i-disco/ltdc/defconfig +++ b/configs/stm32f429i-disco/ltdc/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -91,6 +92,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -98,11 +100,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -174,6 +177,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -259,6 +265,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -317,6 +324,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set # CONFIG_STM32_STM32F407 is not set @@ -345,7 +353,7 @@ CONFIG_STM32_HAVE_TIM1=y # CONFIG_STM32_HAVE_TIM2 is not set CONFIG_STM32_HAVE_TIM3=y CONFIG_STM32_HAVE_TIM4=y -# CONFIG_STM32_HAVE_TIM5 is not set +CONFIG_STM32_HAVE_TIM5=y CONFIG_STM32_HAVE_TIM6=y CONFIG_STM32_HAVE_TIM7=y CONFIG_STM32_HAVE_TIM8=y @@ -373,9 +381,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -389,7 +401,10 @@ CONFIG_STM32_HAVE_SPI5=y CONFIG_STM32_HAVE_SPI6=y # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -412,6 +427,7 @@ CONFIG_STM32_FSMC=y # CONFIG_STM32_I2C3 is not set CONFIG_STM32_LTDC=y CONFIG_STM32_DMA2D=y +# CONFIG_STM32_OPAMP is not set # CONFIG_STM32_OTGFS is not set # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -428,6 +444,7 @@ CONFIG_STM32_SYSCFG=y # CONFIG_STM32_TIM2 is not set # CONFIG_STM32_TIM3 is not set # CONFIG_STM32_TIM4 is not set +# CONFIG_STM32_TIM5 is not set # CONFIG_STM32_TIM6 is not set # CONFIG_STM32_TIM7 is not set # CONFIG_STM32_TIM8 is not set @@ -454,6 +471,7 @@ CONFIG_STM32_SPI=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -473,6 +491,7 @@ CONFIG_STM32_FSMC_SRAM=y # CONFIG_STM32_TIM1_CAP is not set # CONFIG_STM32_TIM3_CAP is not set # CONFIG_STM32_TIM4_CAP is not set +# CONFIG_STM32_TIM5_CAP is not set # CONFIG_STM32_TIM8_CAP is not set # CONFIG_STM32_TIM9_CAP is not set # CONFIG_STM32_TIM10_CAP is not set @@ -567,6 +586,7 @@ CONFIG_STM32_DMA2D_RGB565=y # CONFIG_STM32_DMA2D_ARGB1555 is not set # CONFIG_STM32_DMA2D_RGB888 is not set # CONFIG_STM32_DMA2D_ARGB8888 is not set +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -587,6 +607,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -707,6 +728,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -897,6 +920,7 @@ CONFIG_USART1_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -905,7 +929,9 @@ CONFIG_USART1_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1062,6 +1088,11 @@ CONFIG_HEAP2_BASE=0xD0000000 CONFIG_HEAP2_SIZE=8081408 # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -1070,6 +1101,7 @@ CONFIG_HEAP2_SIZE=8081408 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1242,7 +1274,6 @@ CONFIG_EXAMPLES_LTDC=y # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1281,6 +1312,7 @@ CONFIG_EXAMPLES_NX_TOOLBAR_HEIGHT=16 # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1452,3 +1484,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm32f429i-disco/nsh/defconfig b/configs/stm32f429i-disco/nsh/defconfig index c1c3bbce8d..f8a7096efd 100644 --- a/configs/stm32f429i-disco/nsh/defconfig +++ b/configs/stm32f429i-disco/nsh/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -173,6 +176,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -258,6 +264,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -316,6 +323,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set # CONFIG_STM32_STM32F407 is not set @@ -344,7 +352,7 @@ CONFIG_STM32_HAVE_TIM1=y # CONFIG_STM32_HAVE_TIM2 is not set CONFIG_STM32_HAVE_TIM3=y CONFIG_STM32_HAVE_TIM4=y -# CONFIG_STM32_HAVE_TIM5 is not set +CONFIG_STM32_HAVE_TIM5=y CONFIG_STM32_HAVE_TIM6=y CONFIG_STM32_HAVE_TIM7=y CONFIG_STM32_HAVE_TIM8=y @@ -372,9 +380,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -388,7 +400,10 @@ CONFIG_STM32_HAVE_SPI5=y CONFIG_STM32_HAVE_SPI6=y # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -411,6 +426,7 @@ CONFIG_STM32_FSMC=y # CONFIG_STM32_I2C3 is not set # CONFIG_STM32_LTDC is not set # CONFIG_STM32_DMA2D is not set +# CONFIG_STM32_OPAMP is not set # CONFIG_STM32_OTGFS is not set # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -427,6 +443,7 @@ CONFIG_STM32_SYSCFG=y # CONFIG_STM32_TIM2 is not set # CONFIG_STM32_TIM3 is not set # CONFIG_STM32_TIM4 is not set +# CONFIG_STM32_TIM5 is not set # CONFIG_STM32_TIM6 is not set # CONFIG_STM32_TIM7 is not set # CONFIG_STM32_TIM8 is not set @@ -452,6 +469,7 @@ CONFIG_STM32_USART1=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -470,6 +488,7 @@ CONFIG_STM32_FSMC_SRAM=y # CONFIG_STM32_TIM1_CAP is not set # CONFIG_STM32_TIM3_CAP is not set # CONFIG_STM32_TIM4_CAP is not set +# CONFIG_STM32_TIM5_CAP is not set # CONFIG_STM32_TIM8_CAP is not set # CONFIG_STM32_TIM9_CAP is not set # CONFIG_STM32_TIM10_CAP is not set @@ -516,6 +535,7 @@ CONFIG_STM32_USART1_SERIALDRIVER=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -536,6 +556,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -650,6 +671,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -839,6 +862,7 @@ CONFIG_USART1_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -847,7 +871,9 @@ CONFIG_USART1_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -909,6 +935,11 @@ CONFIG_HEAP2_BASE=0xD0000000 CONFIG_HEAP2_SIZE=8388608 # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -917,6 +948,7 @@ CONFIG_HEAP2_SIZE=8388608 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1087,7 +1119,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1119,6 +1150,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1286,3 +1318,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm32f429i-disco/nxwm/defconfig b/configs/stm32f429i-disco/nxwm/defconfig index 709795e9a0..b161e8af4a 100644 --- a/configs/stm32f429i-disco/nxwm/defconfig +++ b/configs/stm32f429i-disco/nxwm/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -91,6 +92,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -98,11 +100,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -174,6 +177,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -259,6 +265,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -317,6 +324,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set # CONFIG_STM32_STM32F407 is not set @@ -345,7 +353,7 @@ CONFIG_STM32_HAVE_TIM1=y # CONFIG_STM32_HAVE_TIM2 is not set CONFIG_STM32_HAVE_TIM3=y CONFIG_STM32_HAVE_TIM4=y -# CONFIG_STM32_HAVE_TIM5 is not set +CONFIG_STM32_HAVE_TIM5=y CONFIG_STM32_HAVE_TIM6=y CONFIG_STM32_HAVE_TIM7=y CONFIG_STM32_HAVE_TIM8=y @@ -373,9 +381,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -389,7 +401,10 @@ CONFIG_STM32_HAVE_SPI5=y CONFIG_STM32_HAVE_SPI6=y # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -412,6 +427,7 @@ CONFIG_STM32_FSMC=y CONFIG_STM32_I2C3=y # CONFIG_STM32_LTDC is not set # CONFIG_STM32_DMA2D is not set +# CONFIG_STM32_OPAMP is not set # CONFIG_STM32_OTGFS is not set # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -428,6 +444,7 @@ CONFIG_STM32_SYSCFG=y # CONFIG_STM32_TIM2 is not set # CONFIG_STM32_TIM3 is not set # CONFIG_STM32_TIM4 is not set +# CONFIG_STM32_TIM5 is not set # CONFIG_STM32_TIM6 is not set # CONFIG_STM32_TIM7 is not set # CONFIG_STM32_TIM8 is not set @@ -454,6 +471,7 @@ CONFIG_STM32_I2C=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -472,6 +490,7 @@ CONFIG_STM32_FSMC_SRAM=y # CONFIG_STM32_TIM1_CAP is not set # CONFIG_STM32_TIM3_CAP is not set # CONFIG_STM32_TIM4_CAP is not set +# CONFIG_STM32_TIM5_CAP is not set # CONFIG_STM32_TIM8_CAP is not set # CONFIG_STM32_TIM9_CAP is not set # CONFIG_STM32_TIM10_CAP is not set @@ -528,6 +547,7 @@ CONFIG_STM32_I2CTIMEOTICKS=500 # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -548,6 +568,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -672,6 +693,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -924,6 +947,7 @@ CONFIG_USART1_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -932,7 +956,9 @@ CONFIG_USART1_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1115,6 +1141,11 @@ CONFIG_HEAP2_BASE=0xD0000000 CONFIG_HEAP2_SIZE=8388608 # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -1123,6 +1154,7 @@ CONFIG_HEAP2_SIZE=8388608 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1298,7 +1330,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set # CONFIG_EXAMPLES_NSH is not set # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -1330,6 +1361,7 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1676,3 +1708,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm32f429i-disco/usbmsc/defconfig b/configs/stm32f429i-disco/usbmsc/defconfig index 28f46a636e..1707faa7de 100644 --- a/configs/stm32f429i-disco/usbmsc/defconfig +++ b/configs/stm32f429i-disco/usbmsc/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -176,6 +179,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -261,6 +267,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -319,6 +326,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set # CONFIG_STM32_STM32F407 is not set @@ -347,7 +355,7 @@ CONFIG_STM32_HAVE_TIM1=y # CONFIG_STM32_HAVE_TIM2 is not set CONFIG_STM32_HAVE_TIM3=y CONFIG_STM32_HAVE_TIM4=y -# CONFIG_STM32_HAVE_TIM5 is not set +CONFIG_STM32_HAVE_TIM5=y CONFIG_STM32_HAVE_TIM6=y CONFIG_STM32_HAVE_TIM7=y CONFIG_STM32_HAVE_TIM8=y @@ -375,9 +383,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -391,7 +403,10 @@ CONFIG_STM32_HAVE_SPI5=y CONFIG_STM32_HAVE_SPI6=y # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -414,6 +429,7 @@ CONFIG_STM32_FSMC=y # CONFIG_STM32_I2C3 is not set # CONFIG_STM32_LTDC is not set # CONFIG_STM32_DMA2D is not set +# CONFIG_STM32_OPAMP is not set # CONFIG_STM32_OTGFS is not set CONFIG_STM32_OTGHS=y CONFIG_STM32_PWR=y @@ -430,6 +446,7 @@ CONFIG_STM32_SYSCFG=y # CONFIG_STM32_TIM2 is not set # CONFIG_STM32_TIM3 is not set # CONFIG_STM32_TIM4 is not set +# CONFIG_STM32_TIM5 is not set # CONFIG_STM32_TIM6 is not set # CONFIG_STM32_TIM7 is not set # CONFIG_STM32_TIM8 is not set @@ -455,6 +472,7 @@ CONFIG_STM32_USART1=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -473,6 +491,7 @@ CONFIG_STM32_FSMC_SRAM=y # CONFIG_STM32_TIM1_CAP is not set # CONFIG_STM32_TIM3_CAP is not set # CONFIG_STM32_TIM4_CAP is not set +# CONFIG_STM32_TIM5_CAP is not set # CONFIG_STM32_TIM8_CAP is not set # CONFIG_STM32_TIM9_CAP is not set # CONFIG_STM32_TIM10_CAP is not set @@ -524,6 +543,7 @@ CONFIG_STM32_OTGHS_DESCSIZE=128 # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -544,6 +564,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -665,6 +686,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -868,7 +891,9 @@ CONFIG_USBHOST_MSC=y # CONFIG_USBHOST_CDCACM is not set # CONFIG_USBHOST_HIDKBD is not set # CONFIG_USBHOST_HIDMOUSE is not set +# CONFIG_USBHOST_XBOXCONTROLLER is not set # CONFIG_USBHOST_TRACE is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -877,7 +902,9 @@ CONFIG_USBHOST_MSC=y # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -945,6 +972,11 @@ CONFIG_HEAP2_BASE=0xD0000000 CONFIG_HEAP2_SIZE=8388608 # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -953,6 +985,7 @@ CONFIG_HEAP2_SIZE=8388608 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1127,7 +1160,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1160,6 +1192,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1330,3 +1363,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm32f429i-disco/usbnsh/defconfig b/configs/stm32f429i-disco/usbnsh/defconfig index fce584c68c..bc4c70dec6 100644 --- a/configs/stm32f429i-disco/usbnsh/defconfig +++ b/configs/stm32f429i-disco/usbnsh/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -173,6 +176,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -258,6 +264,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -316,6 +323,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set # CONFIG_STM32_STM32F407 is not set @@ -344,7 +352,7 @@ CONFIG_STM32_HAVE_TIM1=y # CONFIG_STM32_HAVE_TIM2 is not set CONFIG_STM32_HAVE_TIM3=y CONFIG_STM32_HAVE_TIM4=y -# CONFIG_STM32_HAVE_TIM5 is not set +CONFIG_STM32_HAVE_TIM5=y CONFIG_STM32_HAVE_TIM6=y CONFIG_STM32_HAVE_TIM7=y CONFIG_STM32_HAVE_TIM8=y @@ -372,9 +380,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -388,7 +400,10 @@ CONFIG_STM32_HAVE_SPI5=y CONFIG_STM32_HAVE_SPI6=y # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -411,6 +426,7 @@ CONFIG_STM32_FSMC=y # CONFIG_STM32_I2C3 is not set # CONFIG_STM32_LTDC is not set # CONFIG_STM32_DMA2D is not set +# CONFIG_STM32_OPAMP is not set # CONFIG_STM32_OTGFS is not set CONFIG_STM32_OTGHS=y CONFIG_STM32_PWR=y @@ -427,6 +443,7 @@ CONFIG_STM32_SYSCFG=y # CONFIG_STM32_TIM2 is not set # CONFIG_STM32_TIM3 is not set # CONFIG_STM32_TIM4 is not set +# CONFIG_STM32_TIM5 is not set # CONFIG_STM32_TIM6 is not set # CONFIG_STM32_TIM7 is not set # CONFIG_STM32_TIM8 is not set @@ -452,6 +469,7 @@ CONFIG_STM32_USART1=y # Alternate Pin Mapping # CONFIG_STM32_FLASH_PREFETCH=y +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -470,6 +488,7 @@ CONFIG_STM32_FSMC_SRAM=y # CONFIG_STM32_TIM1_CAP is not set # CONFIG_STM32_TIM3_CAP is not set # CONFIG_STM32_TIM4_CAP is not set +# CONFIG_STM32_TIM5_CAP is not set # CONFIG_STM32_TIM8_CAP is not set # CONFIG_STM32_TIM9_CAP is not set # CONFIG_STM32_TIM10_CAP is not set @@ -516,6 +535,7 @@ CONFIG_STM32_USART1_SERIALDRIVER=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -536,6 +556,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -656,6 +677,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -884,6 +907,7 @@ CONFIG_CDCACM_VENDORSTR="NuttX" CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial" # CONFIG_USBMSC is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -892,6 +916,7 @@ CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial" # System Logging # # CONFIG_ARCH_SYSLOG is not set +# CONFIG_SYSLOG_WRITE is not set # CONFIG_RAMLOG is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set @@ -959,6 +984,11 @@ CONFIG_HEAP2_BASE=0xD0000000 CONFIG_HEAP2_SIZE=8388608 # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -967,6 +997,7 @@ CONFIG_HEAP2_SIZE=8388608 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1142,7 +1173,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1175,6 +1205,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1348,3 +1379,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm32f4discovery/canard/defconfig b/configs/stm32f4discovery/canard/defconfig index cb66dbf231..8a34f9a42b 100644 --- a/configs/stm32f4discovery/canard/defconfig +++ b/configs/stm32f4discovery/canard/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -178,6 +181,9 @@ CONFIG_CAN_TSEG2=7 # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -263,6 +269,7 @@ CONFIG_CAN_TSEG2=7 # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -321,6 +328,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -377,9 +385,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -393,7 +405,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -414,6 +429,7 @@ CONFIG_STM32_CAN1=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set CONFIG_STM32_OTGFS=y # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -453,6 +469,7 @@ CONFIG_STM32_CAN=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -528,6 +545,7 @@ CONFIG_STM32_USART2_SERIALDRIVER=y # # CAN driver configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -548,6 +566,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -591,6 +610,7 @@ CONFIG_RAM_SIZE=114688 # # Board Selection # +# CONFIG_ARCH_BOARD_CLICKER2_STM32 is not set CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y # CONFIG_ARCH_BOARD_MIKROE_STM32F4 is not set # CONFIG_ARCH_BOARD_CUSTOM is not set @@ -666,6 +686,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -862,6 +884,7 @@ CONFIG_USART2_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -870,7 +893,9 @@ CONFIG_USART2_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -938,6 +963,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -946,6 +976,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1129,7 +1160,6 @@ CONFIG_EXAMPLES_LIBCANARD_STACKSIZE=2048 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1162,6 +1192,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1333,3 +1364,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm32f4discovery/cxxtest/defconfig b/configs/stm32f4discovery/cxxtest/defconfig index 9986935fc0..fb1f67612f 100644 --- a/configs/stm32f4discovery/cxxtest/defconfig +++ b/configs/stm32f4discovery/cxxtest/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -96,6 +97,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -103,11 +105,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -183,6 +186,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -268,6 +274,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -326,6 +333,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -382,9 +390,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -398,7 +410,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -419,6 +434,7 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set # CONFIG_STM32_OTGFS is not set # CONFIG_STM32_OTGHS is not set # CONFIG_STM32_PWR is not set @@ -456,6 +472,7 @@ CONFIG_STM32_USART2=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -521,6 +538,7 @@ CONFIG_STM32_USART2_SERIALDRIVER=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -541,6 +559,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -584,6 +603,7 @@ CONFIG_RAM_SIZE=114688 # # Board Selection # +# CONFIG_ARCH_BOARD_CLICKER2_STM32 is not set CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y # CONFIG_ARCH_BOARD_MIKROE_STM32F4 is not set # CONFIG_ARCH_BOARD_CUSTOM is not set @@ -653,6 +673,8 @@ CONFIG_MAX_TASKS=16 # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -834,6 +856,7 @@ CONFIG_USART2_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -842,7 +865,9 @@ CONFIG_USART2_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -895,6 +920,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -903,6 +933,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1069,7 +1100,6 @@ CONFIG_EXAMPLES_CXXTEST_CXXINITIALIZE=y # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set # CONFIG_EXAMPLES_NSH is not set # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -1099,6 +1129,7 @@ CONFIG_EXAMPLES_CXXTEST_CXXINITIALIZE=y # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1169,3 +1200,14 @@ CONFIG_EXAMPLES_CXXTEST_CXXINITIALIZE=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm32f4discovery/ipv6/defconfig b/configs/stm32f4discovery/ipv6/defconfig index 7e027d640c..d860767e3e 100644 --- a/configs/stm32f4discovery/ipv6/defconfig +++ b/configs/stm32f4discovery/ipv6/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -273,6 +274,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -331,6 +333,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -572,6 +575,7 @@ CONFIG_STM32_ETHMAC_HPWORK=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -592,6 +596,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -791,15 +796,6 @@ CONFIG_DEV_NULL=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=36 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 -CONFIG_IOB_THROTTLE=8 # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -978,7 +974,9 @@ CONFIG_USART6_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1161,6 +1159,15 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=36 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 +CONFIG_IOB_THROTTLE=8 + # # Audio Support # @@ -1169,6 +1176,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1616,3 +1624,10 @@ CONFIG_READLINE_ECHO=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm32f4discovery/netnsh/defconfig b/configs/stm32f4discovery/netnsh/defconfig index 57050f7dae..73c893e58a 100644 --- a/configs/stm32f4discovery/netnsh/defconfig +++ b/configs/stm32f4discovery/netnsh/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -273,6 +274,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -331,6 +333,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -572,6 +575,7 @@ CONFIG_STM32_ETHMAC_HPWORK=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -592,6 +596,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -791,15 +796,6 @@ CONFIG_DEV_NULL=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=36 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 -CONFIG_IOB_THROTTLE=8 # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -980,7 +976,9 @@ CONFIG_USART6_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1165,6 +1163,15 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=36 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 +CONFIG_IOB_THROTTLE=8 + # # Audio Support # @@ -1173,6 +1180,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1622,3 +1630,10 @@ CONFIG_READLINE_ECHO=y # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm32f4discovery/nsh/defconfig b/configs/stm32f4discovery/nsh/defconfig index dcf72ec51b..fb476819e8 100644 --- a/configs/stm32f4discovery/nsh/defconfig +++ b/configs/stm32f4discovery/nsh/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -96,6 +97,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -103,11 +105,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -183,6 +186,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -268,6 +274,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -326,6 +333,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -382,9 +390,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -398,7 +410,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -419,6 +434,7 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set CONFIG_STM32_OTGFS=y # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -457,6 +473,7 @@ CONFIG_STM32_SPI=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -528,6 +545,7 @@ CONFIG_STM32_USART2_SERIALDRIVER=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -548,6 +566,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -591,6 +610,7 @@ CONFIG_RAM_SIZE=114688 # # Board Selection # +# CONFIG_ARCH_BOARD_CLICKER2_STM32 is not set CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y # CONFIG_ARCH_BOARD_MIKROE_STM32F4 is not set # CONFIG_ARCH_BOARD_CUSTOM is not set @@ -661,6 +681,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -850,6 +872,7 @@ CONFIG_USART2_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -858,7 +881,9 @@ CONFIG_USART2_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -926,6 +951,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -934,6 +964,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1105,7 +1136,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1137,6 +1167,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1307,3 +1338,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm32f4discovery/nxlines/defconfig b/configs/stm32f4discovery/nxlines/defconfig index ec02af8c74..00bc8ce335 100644 --- a/configs/stm32f4discovery/nxlines/defconfig +++ b/configs/stm32f4discovery/nxlines/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -96,6 +97,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -103,11 +105,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -183,6 +186,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -268,6 +274,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -326,6 +333,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -382,9 +390,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -398,7 +410,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -419,6 +434,7 @@ CONFIG_STM32_FSMC=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set # CONFIG_STM32_OTGFS is not set # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -457,6 +473,7 @@ CONFIG_STM32_SPI=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -529,6 +546,7 @@ CONFIG_STM32_USART2_SERIALDRIVER=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -549,6 +567,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -592,6 +611,7 @@ CONFIG_RAM_SIZE=114688 # # Board Selection # +# CONFIG_ARCH_BOARD_CLICKER2_STM32 is not set CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y # CONFIG_ARCH_BOARD_MIKROE_STM32F4 is not set # CONFIG_ARCH_BOARD_CUSTOM is not set @@ -662,6 +682,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -886,6 +908,7 @@ CONFIG_USART2_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -894,7 +917,9 @@ CONFIG_USART2_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -1051,6 +1076,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -1059,6 +1089,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1226,7 +1257,6 @@ CONFIG_HAVE_CXXINITIALIZE=y # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set # CONFIG_EXAMPLES_NSH is not set # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -1266,6 +1296,7 @@ CONFIG_EXAMPLES_NXLINES_BPP=16 # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1436,3 +1467,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm32f4discovery/pm/defconfig b/configs/stm32f4discovery/pm/defconfig index 96432718e4..60084550d8 100644 --- a/configs/stm32f4discovery/pm/defconfig +++ b/configs/stm32f4discovery/pm/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -96,6 +97,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -103,11 +105,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -183,6 +186,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -268,6 +274,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -326,6 +333,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -382,9 +390,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -398,7 +410,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -419,6 +434,7 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set CONFIG_STM32_OTGFS=y # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -456,6 +472,7 @@ CONFIG_STM32_USART2=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -508,6 +525,7 @@ CONFIG_STM32_USART2_SERIALDRIVER=y # CONFIG_STM32_HAVE_RTC_SUBSECONDS is not set CONFIG_RTC_MAGIC_REG=0 CONFIG_RTC_MAGIC=0xfacefeee +CONFIG_RTC_MAGIC_TIME_SET=0xfacefeef CONFIG_RTC_LSECLOCK=y # CONFIG_RTC_LSICLOCK is not set # CONFIG_RTC_HSECLOCK is not set @@ -527,6 +545,7 @@ CONFIG_RTC_LSECLOCK=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -547,6 +566,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -591,6 +611,7 @@ CONFIG_RAM_SIZE=114688 # # Board Selection # +# CONFIG_ARCH_BOARD_CLICKER2_STM32 is not set CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y # CONFIG_ARCH_BOARD_MIKROE_STM32F4 is not set # CONFIG_ARCH_BOARD_CUSTOM is not set @@ -668,6 +689,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -876,6 +899,7 @@ CONFIG_USART2_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -884,7 +908,9 @@ CONFIG_USART2_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -952,6 +978,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -960,6 +991,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1132,7 +1164,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1164,6 +1195,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1334,3 +1366,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm32f4discovery/pseudoterm/defconfig b/configs/stm32f4discovery/pseudoterm/defconfig index f894b7ace2..f07e6f5639 100644 --- a/configs/stm32f4discovery/pseudoterm/defconfig +++ b/configs/stm32f4discovery/pseudoterm/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -173,6 +176,9 @@ CONFIG_SERIAL_TERMIOS=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -258,6 +264,7 @@ CONFIG_SERIAL_TERMIOS=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -316,6 +323,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -372,9 +380,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -388,7 +400,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -409,6 +424,7 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set CONFIG_STM32_OTGFS=y # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -447,6 +463,7 @@ CONFIG_STM32_SPI=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -521,6 +538,7 @@ CONFIG_STM32_USART3_SERIALDRIVER=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -541,6 +559,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -584,6 +603,7 @@ CONFIG_RAM_SIZE=114688 # # Board Selection # +# CONFIG_ARCH_BOARD_CLICKER2_STM32 is not set CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y # CONFIG_ARCH_BOARD_MIKROE_STM32F4 is not set # CONFIG_ARCH_BOARD_CUSTOM is not set @@ -655,6 +675,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -866,6 +888,7 @@ CONFIG_PSEUDOTERM_RXBUFSIZE=256 CONFIG_PSEUDOTERM_TXBUFSIZE=256 # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -874,7 +897,9 @@ CONFIG_PSEUDOTERM_TXBUFSIZE=256 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -942,6 +967,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -1123,7 +1153,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1162,6 +1191,7 @@ CONFIG_EXAMPLES_PTYTEST_DAEMONPRIO=100 # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1334,3 +1364,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm32f4discovery/rgbled/defconfig b/configs/stm32f4discovery/rgbled/defconfig index bd94652e9d..ddecfe7d27 100644 --- a/configs/stm32f4discovery/rgbled/defconfig +++ b/configs/stm32f4discovery/rgbled/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -173,6 +176,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -258,6 +264,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -316,6 +323,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -372,9 +380,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -388,7 +400,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -409,6 +424,7 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set CONFIG_STM32_OTGFS=y # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -447,6 +463,7 @@ CONFIG_STM32_SPI=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -531,6 +548,7 @@ CONFIG_STM32_USART2_SERIALDRIVER=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -551,6 +569,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -594,6 +613,7 @@ CONFIG_RAM_SIZE=114688 # # Board Selection # +# CONFIG_ARCH_BOARD_CLICKER2_STM32 is not set CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y # CONFIG_ARCH_BOARD_MIKROE_STM32F4 is not set # CONFIG_ARCH_BOARD_CUSTOM is not set @@ -664,6 +684,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -855,6 +877,7 @@ CONFIG_USART2_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -863,7 +886,9 @@ CONFIG_USART2_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -931,6 +956,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -939,6 +969,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1110,7 +1141,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1146,6 +1176,7 @@ CONFIG_EXAMPLES_RGBLED_STACKSIZE=2048 # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1316,3 +1347,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm32f4discovery/uavcan/defconfig b/configs/stm32f4discovery/uavcan/defconfig index 72cdd50da0..6fc7f915d2 100644 --- a/configs/stm32f4discovery/uavcan/defconfig +++ b/configs/stm32f4discovery/uavcan/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -172,6 +175,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -257,6 +263,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -315,6 +322,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -371,9 +379,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -387,7 +399,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -408,6 +423,7 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set # CONFIG_STM32_OTGFS is not set # CONFIG_STM32_OTGHS is not set # CONFIG_STM32_PWR is not set @@ -445,6 +461,7 @@ CONFIG_STM32_SYSCFG=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -489,6 +506,7 @@ CONFIG_STM32_JTAG_SW_ENABLE=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -509,6 +527,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -552,6 +571,7 @@ CONFIG_RAM_SIZE=114688 # # Board Selection # +# CONFIG_ARCH_BOARD_CLICKER2_STM32 is not set CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y # CONFIG_ARCH_BOARD_MIKROE_STM32F4 is not set # CONFIG_ARCH_BOARD_CUSTOM is not set @@ -622,6 +642,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -753,6 +775,7 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y # CONFIG_SERIAL is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -761,6 +784,7 @@ CONFIG_ARCH_HAVE_SPI_BITORDER=y # System Logging # # CONFIG_ARCH_SYSLOG is not set +# CONFIG_SYSLOG_WRITE is not set CONFIG_RAMLOG=y CONFIG_RAMLOG_BUFSIZE=1024 # CONFIG_RAMLOG_CRLF is not set @@ -824,6 +848,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -832,6 +861,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1028,7 +1058,6 @@ CONFIG_LIBUAVCAN_INIT_RETRIES=0 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set # CONFIG_EXAMPLES_NSH is not set # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -1062,6 +1091,7 @@ CONFIG_EXAMPLES_UAVCAN_NODE_ID=1 CONFIG_EXAMPLES_UAVCAN_NODE_NAME="org.nuttx.apps.examples.uavcan" # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1133,3 +1163,14 @@ CONFIG_EXAMPLES_UAVCAN_NODE_NAME="org.nuttx.apps.examples.uavcan" # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm32f4discovery/usbnsh/defconfig b/configs/stm32f4discovery/usbnsh/defconfig index c76b16a4e9..f5c9f5d7ab 100644 --- a/configs/stm32f4discovery/usbnsh/defconfig +++ b/configs/stm32f4discovery/usbnsh/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -96,6 +97,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -103,11 +105,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -183,6 +186,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -268,6 +274,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -326,6 +333,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -382,9 +390,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -398,7 +410,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -419,6 +434,7 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set CONFIG_STM32_OTGFS=y # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -457,6 +473,7 @@ CONFIG_STM32_SPI=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -528,6 +545,7 @@ CONFIG_STM32_USART2_SERIALDRIVER=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -548,6 +566,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -591,6 +610,7 @@ CONFIG_RAM_SIZE=114688 # # Board Selection # +# CONFIG_ARCH_BOARD_CLICKER2_STM32 is not set CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y # CONFIG_ARCH_BOARD_MIKROE_STM32F4 is not set # CONFIG_ARCH_BOARD_CUSTOM is not set @@ -667,6 +687,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -895,6 +917,7 @@ CONFIG_CDCACM_VENDORSTR="NuttX" CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial" # CONFIG_USBMSC is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -903,7 +926,9 @@ CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial" # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set # CONFIG_SYSLOG_SERIAL_CONSOLE is not set @@ -972,6 +997,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -980,6 +1010,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1151,7 +1182,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1184,6 +1214,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1356,3 +1387,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm32f4discovery/xen1210/defconfig b/configs/stm32f4discovery/xen1210/defconfig index b1c87f136e..1a29b5fba6 100644 --- a/configs/stm32f4discovery/xen1210/defconfig +++ b/configs/stm32f4discovery/xen1210/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -173,6 +176,9 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32L152V6 is not set # CONFIG_ARCH_CHIP_STM32L152V8 is not set # CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set # CONFIG_ARCH_CHIP_STM32L162ZD is not set # CONFIG_ARCH_CHIP_STM32L162VE is not set # CONFIG_ARCH_CHIP_STM32F100C8 is not set @@ -258,6 +264,7 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -316,6 +323,7 @@ CONFIG_STM32_FLASH_CONFIG_DEFAULT=y # CONFIG_STM32_STM32F37XX is not set CONFIG_STM32_STM32F40XX=y # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set CONFIG_STM32_STM32F407=y @@ -372,9 +380,13 @@ CONFIG_STM32_HAVE_ADC3=y # CONFIG_STM32_HAVE_SDADC3_DMA is not set CONFIG_STM32_HAVE_CAN1=y CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set # CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set # CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set # CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set CONFIG_STM32_HAVE_DAC1=y CONFIG_STM32_HAVE_DAC2=y CONFIG_STM32_HAVE_RNG=y @@ -388,7 +400,10 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_HAVE_SPI6 is not set # CONFIG_STM32_HAVE_SAIPLL is not set # CONFIG_STM32_HAVE_I2SPLL is not set -# CONFIG_STM32_HAVE_OPAMP is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set # CONFIG_STM32_ADC1 is not set # CONFIG_STM32_ADC2 is not set # CONFIG_STM32_ADC3 is not set @@ -409,6 +424,7 @@ CONFIG_STM32_HAVE_SPI3=y # CONFIG_STM32_I2C1 is not set # CONFIG_STM32_I2C2 is not set # CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP is not set CONFIG_STM32_OTGFS=y # CONFIG_STM32_OTGHS is not set CONFIG_STM32_PWR=y @@ -447,6 +463,7 @@ CONFIG_STM32_SPI=y # Alternate Pin Mapping # # CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set # CONFIG_STM32_JTAG_DISABLE is not set # CONFIG_STM32_JTAG_FULL_ENABLE is not set # CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set @@ -523,6 +540,7 @@ CONFIG_STM32_USART2_SERIALDRIVER=y # # USB Device Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -543,6 +561,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -586,6 +605,7 @@ CONFIG_RAM_SIZE=114688 # # Board Selection # +# CONFIG_ARCH_BOARD_CLICKER2_STM32 is not set CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y # CONFIG_ARCH_BOARD_MIKROE_STM32F4 is not set # CONFIG_ARCH_BOARD_CUSTOM is not set @@ -656,6 +676,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -804,10 +826,13 @@ CONFIG_SENSORS=y # CONFIG_BH1750FVI is not set # CONFIG_BMG160 is not set # CONFIG_BMP180 is not set +# CONFIG_HTS221 is not set # CONFIG_SENSORS_L3GD20 is not set # CONFIG_SENSOR_KXTJ9 is not set +# CONFIG_LIS2DH is not set # CONFIG_LIS3DSH is not set # CONFIG_LIS331DL is not set +# CONFIG_LPS25H is not set # CONFIG_MB7040 is not set # CONFIG_MLX90393 is not set # CONFIG_MCP9844 is not set @@ -876,6 +901,7 @@ CONFIG_USART2_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -884,7 +910,9 @@ CONFIG_USART2_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -952,6 +980,11 @@ CONFIG_MM_REGIONS=2 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -960,6 +993,7 @@ CONFIG_MM_REGIONS=2 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1131,7 +1165,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1164,6 +1197,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1334,3 +1368,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm32f746-ws/nsh/defconfig b/configs/stm32f746-ws/nsh/defconfig index cf198fc2f6..80f7526520 100644 --- a/configs/stm32f746-ws/nsh/defconfig +++ b/configs/stm32f746-ws/nsh/defconfig @@ -28,6 +28,7 @@ CONFIG_BUILD_FLAT=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set CONFIG_ARCH_CHIP_STM32F7=y # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -245,6 +248,7 @@ CONFIG_STM32F7_STM32F746XX=y # CONFIG_STM32F7_STM32F779XX is not set # CONFIG_STM32F7_STM32F779AX is not set # CONFIG_STM32F7_FLASH_CONFIG_E is not set +CONFIG_STM32F7_FLASH_CONFIG_G=y # CONFIG_STM32F7_FLASH_CONFIG_I is not set CONFIG_STM32F7_FLASH_OVERRIDE_DEFAULT=y # CONFIG_STM32F7_FLASH_OVERRIDE_E is not set @@ -347,7 +351,6 @@ CONFIG_STM32F7_USART6=y # # U[S]ART Configuration # -# CONFIG_STM32F7_FLOWCONTROL_BROKEN is not set # CONFIG_STM32F7_USART_BREAKS is not set # @@ -376,7 +379,7 @@ CONFIG_STM32F7_SDMMC_DMA=y CONFIG_STM32F7_SDMMC1_DMAPRIO=0x00010000 # CONFIG_SDMMC1_WIDTH_D1_ONLY is not set # CONFIG_STM32F7_HAVE_RTC_COUNTER is not set -# CONFIG_STM32F7_HAVE_RTC_SUBSECONDS is not set +CONFIG_STM32F7_HAVE_RTC_SUBSECONDS=y # CONFIG_STM32F7_CUSTOM_CLOCKCONFIG is not set # CONFIG_STM32F7_DTCMEXCLUDE is not set CONFIG_STM32F7_DMACAPABLE=y @@ -388,7 +391,9 @@ CONFIG_STM32F7_DMACAPABLE=y # # ADC Configuration # +# CONFIG_STM32F7_ADC_NO_STARTUP_CONV is not set # CONFIG_STM32F7_ADC1_DMA is not set +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -409,6 +414,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +CONFIG_ARCH_HAVE_RTC_SUBSECONDS=y # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -518,6 +524,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -649,8 +657,11 @@ CONFIG_ADC=y CONFIG_ADC_FIFOSIZE=8 # CONFIG_ADC_ADS1242 is not set # CONFIG_ADC_ADS125X is not set +# CONFIG_ADC_LTC1867L is not set # CONFIG_ADC_PGA11X is not set +# CONFIG_COMP is not set # CONFIG_DAC is not set +# CONFIG_OPAMP is not set # CONFIG_AUDIO_DEVICES is not set # CONFIG_VIDEO_DEVICES is not set # CONFIG_BCH is not set @@ -793,6 +804,7 @@ CONFIG_CDCACM_VENDORSTR="NuttX" CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial" # CONFIG_USBMSC is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -801,7 +813,9 @@ CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial" # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -871,6 +885,11 @@ CONFIG_GRAN=y # CONFIG_GRAN_SINGLE is not set CONFIG_GRAN_INTR=y +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -879,6 +898,7 @@ CONFIG_GRAN_INTR=y # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1055,7 +1075,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NSH_CXXINITIALIZE is not set # CONFIG_EXAMPLES_NULL is not set @@ -1089,6 +1108,7 @@ CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1275,3 +1295,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm32f746g-disco/nsh/defconfig b/configs/stm32f746g-disco/nsh/defconfig index f956e3bc16..190d776f42 100644 --- a/configs/stm32f746g-disco/nsh/defconfig +++ b/configs/stm32f746g-disco/nsh/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -96,6 +97,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -103,11 +105,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set CONFIG_ARCH_CHIP_STM32F7=y # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -254,6 +257,7 @@ CONFIG_STM32F7_STM32F746XX=y # CONFIG_STM32F7_STM32F779XX is not set # CONFIG_STM32F7_STM32F779AX is not set # CONFIG_STM32F7_FLASH_CONFIG_E is not set +CONFIG_STM32F7_FLASH_CONFIG_G=y # CONFIG_STM32F7_FLASH_CONFIG_I is not set CONFIG_STM32F7_FLASH_OVERRIDE_DEFAULT=y # CONFIG_STM32F7_FLASH_OVERRIDE_E is not set @@ -356,16 +360,16 @@ CONFIG_STM32F7_USART6=y # # U[S]ART Configuration # -# CONFIG_STM32F7_FLOWCONTROL_BROKEN is not set # CONFIG_STM32F7_USART_BREAKS is not set # CONFIG_STM32F7_HAVE_RTC_COUNTER is not set -# CONFIG_STM32F7_HAVE_RTC_SUBSECONDS is not set +CONFIG_STM32F7_HAVE_RTC_SUBSECONDS=y # CONFIG_STM32F7_CUSTOM_CLOCKCONFIG is not set # CONFIG_STM32F7_DTCMEXCLUDE is not set # # Timer Configuration # +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -386,6 +390,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +CONFIG_ARCH_HAVE_RTC_SUBSECONDS=y # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -495,6 +500,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -684,6 +691,7 @@ CONFIG_USART6_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -692,7 +700,9 @@ CONFIG_USART6_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -752,6 +762,11 @@ CONFIG_MM_REGIONS=3 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -760,6 +775,7 @@ CONFIG_MM_REGIONS=3 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -930,7 +946,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -962,6 +977,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1129,3 +1145,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm32l476vg-disco/nsh/defconfig b/configs/stm32l476vg-disco/nsh/defconfig index 76859b3105..fcb84c92cc 100644 --- a/configs/stm32l476vg-disco/nsh/defconfig +++ b/configs/stm32l476vg-disco/nsh/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set CONFIG_ARCH_CHIP_STM32L4=y # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -129,7 +132,7 @@ CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y # CONFIG_ARMV7M_LAZYFPU is not set CONFIG_ARCH_HAVE_FPU=y -CONFIG_ARCH_HAVE_DPFPU=y +# CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_FPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set CONFIG_ARM_HAVE_MPU_UNIFIED=y @@ -140,10 +143,8 @@ CONFIG_ARM_HAVE_MPU_UNIFIED=y # # CONFIG_ARMV7M_HAVE_ICACHE is not set # CONFIG_ARMV7M_HAVE_DCACHE is not set -CONFIG_ARMV7M_HAVE_ITCM=y -CONFIG_ARMV7M_HAVE_DTCM=y -# CONFIG_ARMV7M_ITCM is not set -# CONFIG_ARMV7M_DTCM is not set +# CONFIG_ARMV7M_HAVE_ITCM is not set +# CONFIG_ARMV7M_HAVE_DTCM is not set # CONFIG_ARMV7M_TOOLCHAIN_IARL is not set # CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set # CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set @@ -160,16 +161,73 @@ CONFIG_ARMV7M_HAVE_STACKCHECK=y # # STM32L4 Configuration Options # +# CONFIG_ARCH_CHIP_STM32L432KB is not set +# CONFIG_ARCH_CHIP_STM32L432KC is not set +# CONFIG_ARCH_CHIP_STM32L442KC is not set +# CONFIG_ARCH_CHIP_STM32L433CB is not set +# CONFIG_ARCH_CHIP_STM32L433CC is not set +# CONFIG_ARCH_CHIP_STM32L433RB is not set +# CONFIG_ARCH_CHIP_STM32L433RC is not set +# CONFIG_ARCH_CHIP_STM32L433VC is not set +# CONFIG_ARCH_CHIP_STM32L443CC is not set +# CONFIG_ARCH_CHIP_STM32L443RC is not set +# CONFIG_ARCH_CHIP_STM32L443VC is not set +# CONFIG_ARCH_CHIP_STM32L451CC is not set +# CONFIG_ARCH_CHIP_STM32L451CE is not set +# CONFIG_ARCH_CHIP_STM32L451RC is not set +# CONFIG_ARCH_CHIP_STM32L451RE is not set +# CONFIG_ARCH_CHIP_STM32L451VC is not set +# CONFIG_ARCH_CHIP_STM32L451VE is not set +# CONFIG_ARCH_CHIP_STM32L452CC is not set +# CONFIG_ARCH_CHIP_STM32L452CE is not set +# CONFIG_ARCH_CHIP_STM32L452RC is not set +# CONFIG_ARCH_CHIP_STM32L452RE is not set +# CONFIG_ARCH_CHIP_STM32L452VC is not set +# CONFIG_ARCH_CHIP_STM32L452VE is not set +# CONFIG_ARCH_CHIP_STM32L462CE is not set +# CONFIG_ARCH_CHIP_STM32L462RE is not set +# CONFIG_ARCH_CHIP_STM32L462VE is not set CONFIG_ARCH_CHIP_STM32L476RG=y # CONFIG_ARCH_CHIP_STM32L476RE is not set # CONFIG_ARCH_CHIP_STM32L486 is not set +# CONFIG_ARCH_CHIP_STM32L496ZE is not set +# CONFIG_ARCH_CHIP_STM32L496ZG is not set +# CONFIG_ARCH_CHIP_STM32L4A6 is not set +# CONFIG_STM32L4_STM32L4X1 is not set +# CONFIG_STM32L4_STM32L4X2 is not set # CONFIG_STM32L4_STM32L4X3 is not set +# CONFIG_STM32L4_STM32L4X5 is not set CONFIG_STM32L4_STM32L4X6=y +# CONFIG_STM32L4_STM32L431XX is not set +# CONFIG_STM32L4_STM32L432XX is not set +# CONFIG_STM32L4_STM32L433XX is not set +# CONFIG_STM32L4_STM32L442XX is not set +# CONFIG_STM32L4_STM32L443XX is not set +# CONFIG_STM32L4_STM32L451XX is not set +# CONFIG_STM32L4_STM32L452XX is not set +# CONFIG_STM32L4_STM32L462XX is not set +# CONFIG_STM32L4_STM32L471XX is not set CONFIG_STM32L4_STM32L476XX=y # CONFIG_STM32L4_STM32L486XX is not set -# CONFIG_STM32L4_FLASH_256KB is not set -# CONFIG_STM32L4_FLASH_512KB is not set -CONFIG_STM32L4_FLASH_1024KB=y +# CONFIG_STM32L4_STM32L496XX is not set +# CONFIG_STM32L4_STM32L4A6XX is not set +CONFIG_STM32L4_FLASH_OVERRIDE_DEFAULT=y +# CONFIG_STM32L4_FLASH_OVERRIDE_B is not set +# CONFIG_STM32L4_FLASH_OVERRIDE_C is not set +# CONFIG_STM32L4_FLASH_OVERRIDE_E is not set +# CONFIG_STM32L4_FLASH_OVERRIDE_G is not set +# CONFIG_STM32L4_FLASH_CONFIG_C is not set +# CONFIG_STM32L4_FLASH_CONFIG_E is not set +CONFIG_STM32L4_FLASH_CONFIG_G=y +# CONFIG_STM32L4_IO_CONFIG_K is not set +# CONFIG_STM32L4_IO_CONFIG_C is not set +CONFIG_STM32L4_IO_CONFIG_R=y +# CONFIG_STM32L4_IO_CONFIG_J is not set +# CONFIG_STM32L4_IO_CONFIG_M is not set +# CONFIG_STM32L4_IO_CONFIG_V is not set +# CONFIG_STM32L4_IO_CONFIG_Q is not set +# CONFIG_STM32L4_IO_CONFIG_Z is not set +# CONFIG_STM32L4_IO_CONFIG_A is not set # # STM32L4 SRAM2 Options @@ -184,12 +242,32 @@ CONFIG_STM32L4_FLASH_1024KB=y # # STM32L4 Peripheral Support # +CONFIG_STM32L4_HAVE_ADC2=y +CONFIG_STM32L4_HAVE_ADC3=y +# CONFIG_STM32L4_HAVE_AES is not set +# CONFIG_STM32L4_HAVE_CAN2 is not set +CONFIG_STM32L4_HAVE_COMP=y +CONFIG_STM32L4_HAVE_DAC2=y +# CONFIG_STM32L4_HAVE_DCMI is not set +# CONFIG_STM32L4_HAVE_DFSDM1 is not set +# CONFIG_STM32L4_HAVE_DMA2D is not set +CONFIG_STM32L4_HAVE_FSMC=y +# CONFIG_STM32L4_HAVE_HASH is not set +# CONFIG_STM32L4_HAVE_I2C4 is not set +CONFIG_STM32L4_HAVE_LCD=y # CONFIG_STM32L4_HAVE_LTDC is not set CONFIG_STM32L4_HAVE_LPTIM1=y CONFIG_STM32L4_HAVE_LPTIM2=y -CONFIG_STM32L4_HAVE_COMP=y +CONFIG_STM32L4_HAVE_OTGFS=y CONFIG_STM32L4_HAVE_SAI1=y CONFIG_STM32L4_HAVE_SAI2=y +CONFIG_STM32L4_HAVE_SDMMC1=y +CONFIG_STM32L4_HAVE_TIM3=y +CONFIG_STM32L4_HAVE_TIM4=y +CONFIG_STM32L4_HAVE_TIM5=y +CONFIG_STM32L4_HAVE_TIM7=y +CONFIG_STM32L4_HAVE_TIM8=y +CONFIG_STM32L4_HAVE_TIM17=y # CONFIG_STM32L4_ADC is not set # CONFIG_STM32L4_CAN is not set # CONFIG_STM32L4_DAC is not set @@ -215,17 +293,12 @@ CONFIG_STM32L4_DMA2=y # CONFIG_STM32L4_ADC1 is not set # CONFIG_STM32L4_ADC2 is not set # CONFIG_STM32L4_ADC3 is not set -# CONFIG_STM32L4_AES is not set CONFIG_STM32L4_RNG=y -# CONFIG_STM32L4_SAI1_A is not set -# CONFIG_STM32L4_SAI1_B is not set -# CONFIG_STM32L4_SAI2_A is not set -# CONFIG_STM32L4_SAI2_B is not set # # AHB3 Peripherals # -# CONFIG_STM32L4_FMC is not set +# CONFIG_STM32L4_FSMC is not set CONFIG_STM32L4_QSPI=y CONFIG_STM32L4_QSPI_FLASH_SIZE=16777216 CONFIG_STM32L4_QSPI_FIFO_THESHOLD=4 @@ -286,7 +359,6 @@ CONFIG_STM32L4_FIREWALL=y # CONFIG_STM32L4_COMP is not set # CONFIG_STM32L4_SAI1 is not set # CONFIG_STM32L4_SAI2 is not set -# CONFIG_STM32L4_DFSDM is not set # # Other Peripherals @@ -308,6 +380,10 @@ CONFIG_STM32L4_SAI1PLL=y # # CONFIG_STM32L4_ONESHOT is not set # CONFIG_STM32L4_FREERUN is not set +# CONFIG_STM32L4_TIM3_CAP is not set +# CONFIG_STM32L4_TIM4_CAP is not set +# CONFIG_STM32L4_TIM5_CAP is not set +# CONFIG_STM32L4_TIM8_CAP is not set CONFIG_STM32L4_HAVE_USART1=y CONFIG_STM32L4_HAVE_USART2=y CONFIG_STM32L4_HAVE_USART3=y @@ -319,6 +395,7 @@ CONFIG_STM32L4_HAVE_UART5=y # # CONFIG_STM32L4_FLOWCONTROL_BROKEN is not set # CONFIG_STM32L4_USART_BREAKS is not set +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -339,6 +416,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -458,6 +536,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -690,6 +770,7 @@ CONFIG_USART2_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -698,7 +779,9 @@ CONFIG_USART2_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -773,6 +856,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -781,6 +869,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -963,7 +1052,6 @@ CONFIG_EXAMPLES_MEDIA_BLOCKSIZE=512 # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set # CONFIG_EXAMPLES_MTDPART is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set @@ -1000,6 +1088,7 @@ CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1181,3 +1270,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/teensy-lc/nsh/defconfig b/configs/teensy-lc/nsh/defconfig index a863cbaff9..15e83500b8 100644 --- a/configs/teensy-lc/nsh/defconfig +++ b/configs/teensy-lc/nsh/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set # CONFIG_RAW_BINARY is not set # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -90,6 +91,7 @@ CONFIG_ARCH_CHIP_KL=y # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -97,11 +99,12 @@ CONFIG_ARCH_CHIP_KL=y # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -123,7 +126,7 @@ CONFIG_ARCH_CORTEXM0=y CONFIG_ARCH_FAMILY="armv6-m" CONFIG_ARCH_CHIP="kl" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set +CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set # CONFIG_ARMV7M_LAZYFPU is not set @@ -199,6 +202,7 @@ CONFIG_KL_TPM2_CHANNEL=0 # Kinetis GPIO Interrupt Configuration # # CONFIG_KL_GPIOIRQ is not set +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -219,6 +223,7 @@ CONFIG_ARCH_HAVE_VFORK=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y # CONFIG_ENDIAN_BIG is not set @@ -326,6 +331,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=0 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -508,6 +515,7 @@ CONFIG_UART0_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -516,7 +524,9 @@ CONFIG_UART0_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -568,6 +578,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -576,6 +591,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -739,7 +755,6 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NSH_CXXINITIALIZE is not set # CONFIG_EXAMPLES_NULL is not set @@ -773,6 +788,7 @@ CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -940,3 +956,14 @@ CONFIG_SYSTEM_STACKMONITOR_INTERVAL=2 # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set -- GitLab From 6e4918c55766d9599f6979b0cae423f8894dd0db Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 13 May 2017 13:28:15 -0600 Subject: [PATCH 807/990] Remove CONFIG_ARM_TOOLCHAIN_GNU; replace with CONFIG_ARCH_TOOLCHAIN_GNU --- arch/arm/Kconfig | 5 ----- arch/arm/src/Makefile | 2 +- arch/arm/src/armv6-m/Kconfig | 18 ++++++++--------- arch/arm/src/armv7-a/Kconfig | 14 ++++++------- arch/arm/src/armv7-m/Kconfig | 20 +++++++++---------- arch/arm/src/armv7-r/Kconfig | 14 ++++++------- configs/arduino-due/nsh/defconfig | 1 - configs/bambino-200e/netnsh/defconfig | 2 +- configs/bambino-200e/nsh/defconfig | 2 +- configs/bambino-200e/usbnsh/defconfig | 2 +- configs/c5471evm/httpd/defconfig | 1 - configs/c5471evm/nettest/defconfig | 1 - configs/c5471evm/nsh/defconfig | 1 - configs/cc3200-launchpad/nsh/defconfig | 2 +- configs/clicker2-stm32/knsh/defconfig | 1 - .../clicker2-stm32/mrf24j40-radio/defconfig | 1 - configs/clicker2-stm32/nsh/defconfig | 1 - configs/clicker2-stm32/usbnsh/defconfig | 1 - configs/cloudctrl/nsh/defconfig | 2 +- configs/dk-tm4c129x/ipv6/defconfig | 2 +- configs/dk-tm4c129x/nsh/defconfig | 2 +- configs/ea3131/nsh/defconfig | 1 - configs/ea3131/pgnsh/defconfig | 1 - configs/ea3131/usbserial/defconfig | 1 - configs/ea3152/ostest/defconfig | 1 - configs/eagle100/httpd/defconfig | 2 +- configs/eagle100/nettest/defconfig | 2 +- configs/eagle100/nsh/defconfig | 2 +- configs/eagle100/nxflat/defconfig | 2 +- configs/eagle100/thttpd/defconfig | 2 +- configs/efm32-g8xx-stk/nsh/defconfig | 2 +- configs/efm32gg-stk3700/nsh/defconfig | 2 +- configs/ekk-lm3s9b96/nsh/defconfig | 2 +- configs/fire-stm32v2/nsh/defconfig | 2 +- configs/freedom-k64f/netnsh/defconfig | 2 +- configs/freedom-k64f/nsh/defconfig | 2 +- configs/freedom-k66f/netnsh/defconfig | 2 +- configs/freedom-k66f/nsh/defconfig | 2 +- configs/freedom-kl25z/nsh/defconfig | 1 - configs/freedom-kl26z/nsh/defconfig | 1 - configs/hymini-stm32v/nsh/defconfig | 2 +- configs/hymini-stm32v/nsh2/defconfig | 2 +- configs/hymini-stm32v/usbmsc/defconfig | 2 +- configs/hymini-stm32v/usbnsh/defconfig | 2 +- configs/hymini-stm32v/usbserial/defconfig | 2 +- configs/kwikstik-k40/ostest/defconfig | 2 +- configs/launchxl-tms57004/nsh/defconfig | 2 +- configs/lincoln60/netnsh/defconfig | 2 +- configs/lincoln60/nsh/defconfig | 2 +- configs/lincoln60/thttpd-binfs/defconfig | 2 +- configs/lm3s6432-s2e/nsh/defconfig | 2 +- configs/lm3s6965-ek/discover/defconfig | 2 +- configs/lm3s6965-ek/nsh/defconfig | 2 +- configs/lm3s6965-ek/nx/defconfig | 2 +- configs/lm3s6965-ek/tcpecho/defconfig | 2 +- configs/lm3s8962-ek/nsh/defconfig | 2 +- configs/lm3s8962-ek/nx/defconfig | 2 +- configs/lm4f120-launchpad/nsh/defconfig | 2 +- configs/lpc4330-xplorer/nsh/defconfig | 2 +- configs/lpc4337-ws/nsh/defconfig | 2 +- configs/lpc4357-evb/nsh/defconfig | 2 +- configs/lpc4370-link2/nsh/defconfig | 2 +- configs/lpcxpresso-lpc1115/nsh/defconfig | 1 - configs/lpcxpresso-lpc1768/dhcpd/defconfig | 2 +- configs/lpcxpresso-lpc1768/nsh/defconfig | 2 +- configs/lpcxpresso-lpc1768/nx/defconfig | 2 +- configs/lpcxpresso-lpc1768/thttpd/defconfig | 2 +- configs/lpcxpresso-lpc1768/usbmsc/defconfig | 2 +- configs/maple/nsh/defconfig | 2 +- configs/maple/nx/defconfig | 2 +- configs/maple/usbnsh/defconfig | 2 +- configs/mbed/nsh/defconfig | 2 +- configs/mcu123-lpc214x/composite/defconfig | 1 - configs/mcu123-lpc214x/nsh/defconfig | 1 - configs/mcu123-lpc214x/usbmsc/defconfig | 1 - configs/mcu123-lpc214x/usbserial/defconfig | 1 - configs/mikroe-stm32f4/fulldemo/defconfig | 1 - configs/mikroe-stm32f4/kostest/defconfig | 1 - configs/mikroe-stm32f4/nsh/defconfig | 1 - configs/mikroe-stm32f4/nx/defconfig | 1 - configs/mikroe-stm32f4/nxlines/defconfig | 1 - configs/mikroe-stm32f4/nxtext/defconfig | 1 - configs/mikroe-stm32f4/usbnsh/defconfig | 1 - configs/moxa/nsh/defconfig | 1 - configs/mx1ads/ostest/defconfig | 1 - configs/ntosd-dm320/nettest/defconfig | 1 - configs/ntosd-dm320/nsh/defconfig | 1 - configs/ntosd-dm320/poll/defconfig | 1 - configs/ntosd-dm320/thttpd/defconfig | 1 - configs/ntosd-dm320/udp/defconfig | 1 - configs/ntosd-dm320/webserver/defconfig | 1 - configs/nucleo-144/f746-evalos/defconfig | 1 - configs/nucleo-144/f746-nsh/defconfig | 1 - configs/nucleo-144/f767-evalos/defconfig | 1 - configs/nucleo-144/f767-nsh/defconfig | 1 - configs/nucleo-f072rb/nsh/defconfig | 1 - configs/nucleo-f091rc/nsh/defconfig | 1 - configs/nucleo-f303re/adc/defconfig | 2 +- configs/nucleo-f303re/can/defconfig | 2 +- configs/nucleo-f303re/hello/defconfig | 2 +- configs/nucleo-f303re/nxlines/defconfig | 2 +- configs/nucleo-f303re/pwm/defconfig | 2 +- configs/nucleo-f303re/serialrx/defconfig | 2 +- configs/nucleo-f303re/uavcan/defconfig | 1 - configs/nucleo-f334r8/adc/defconfig | 2 +- configs/nucleo-f334r8/nsh/defconfig | 2 +- configs/nucleo-f4x1re/f401-nsh/defconfig | 1 - configs/nucleo-f4x1re/f411-nsh/defconfig | 1 - configs/nucleo-l432kc/nsh/defconfig | 1 - configs/nucleo-l452re/nsh/defconfig | 1 - configs/nucleo-l476rg/nsh/defconfig | 1 - configs/nucleo-l496zg/nsh/defconfig | 1 - configs/nutiny-nuc120/nsh/defconfig | 1 - .../olimex-efm32g880f128-stk/nsh/defconfig | 2 +- configs/olimex-lpc-h3131/nsh/defconfig | 1 - configs/olimex-lpc1766stk/ftpc/defconfig | 2 +- configs/olimex-lpc1766stk/hidmouse/defconfig | 2 +- configs/olimex-lpc1766stk/nettest/defconfig | 2 +- configs/olimex-lpc1766stk/nsh/defconfig | 2 +- configs/olimex-lpc1766stk/nx/defconfig | 2 +- .../olimex-lpc1766stk/slip-httpd/defconfig | 2 +- .../olimex-lpc1766stk/thttpd-binfs/defconfig | 2 +- .../olimex-lpc1766stk/thttpd-nxflat/defconfig | 2 +- configs/olimex-lpc1766stk/usbmsc/defconfig | 2 +- configs/olimex-lpc1766stk/usbserial/defconfig | 2 +- configs/olimex-lpc1766stk/zmodem/defconfig | 2 +- configs/olimex-lpc2378/nsh/defconfig | 1 - configs/olimex-stm32-e407/discover/defconfig | 1 - configs/olimex-stm32-e407/netnsh/defconfig | 1 - configs/olimex-stm32-e407/nsh/defconfig | 1 - configs/olimex-stm32-e407/telnetd/defconfig | 1 - configs/olimex-stm32-e407/usbnsh/defconfig | 1 - configs/olimex-stm32-e407/webserver/defconfig | 1 - configs/olimex-stm32-h405/usbnsh/defconfig | 1 - configs/olimex-stm32-h407/nsh/defconfig | 1 - configs/olimex-stm32-p107/nsh/defconfig | 2 +- configs/olimex-stm32-p207/nsh/defconfig | 1 - configs/olimex-stm32-p407/knsh/defconfig | 1 - configs/olimex-stm32-p407/nsh/defconfig | 1 - configs/olimex-strp711/nettest/defconfig | 1 - configs/olimex-strp711/nsh/defconfig | 1 - configs/olimexino-stm32/can/defconfig | 1 - configs/olimexino-stm32/composite/defconfig | 1 - configs/olimexino-stm32/nsh/defconfig | 1 - configs/olimexino-stm32/smallnsh/defconfig | 1 - configs/olimexino-stm32/tiny/defconfig | 1 - configs/open1788/knsh/defconfig | 2 +- configs/open1788/nsh/defconfig | 2 +- configs/open1788/nxlines/defconfig | 2 +- configs/pcduino-a10/nsh/defconfig | 1 - configs/photon/nsh/defconfig | 1 - configs/photon/usbnsh/defconfig | 1 - configs/photon/wlan/defconfig | 1 - configs/sabre-6quad/nsh/defconfig | 1 - configs/sabre-6quad/smp/defconfig | 1 - configs/sam3u-ek/knsh/defconfig | 2 +- configs/sam3u-ek/nsh/defconfig | 2 +- configs/sam3u-ek/nx/defconfig | 2 +- configs/sam3u-ek/nxwm/defconfig | 1 - configs/sam4cmp-db/nsh/defconfig | 2 +- configs/sam4e-ek/nsh/defconfig | 2 +- configs/sam4e-ek/nxwm/defconfig | 1 - configs/sam4e-ek/usbnsh/defconfig | 2 +- configs/sam4l-xplained/nsh/defconfig | 1 - configs/sam4s-xplained-pro/nsh/defconfig | 1 - configs/sam4s-xplained/nsh/defconfig | 1 - configs/sama5d2-xult/nsh/defconfig | 1 - configs/sama5d3-xplained/bridge/defconfig | 1 - configs/sama5d3-xplained/nsh/defconfig | 1 - configs/sama5d3x-ek/demo/defconfig | 1 - configs/sama5d3x-ek/hello/defconfig | 2 +- configs/sama5d3x-ek/norboot/defconfig | 2 +- configs/sama5d3x-ek/nsh/defconfig | 1 - configs/sama5d3x-ek/nx/defconfig | 1 - configs/sama5d3x-ek/nxplayer/defconfig | 1 - configs/sama5d3x-ek/nxwm/defconfig | 1 - configs/sama5d3x-ek/ov2640/defconfig | 2 +- configs/sama5d4-ek/at25boot/defconfig | 1 - configs/sama5d4-ek/bridge/defconfig | 1 - configs/sama5d4-ek/dramboot/defconfig | 1 - configs/sama5d4-ek/elf/defconfig | 1 - configs/sama5d4-ek/ipv6/defconfig | 1 - configs/sama5d4-ek/knsh/defconfig | 1 - configs/sama5d4-ek/nsh/defconfig | 1 - configs/sama5d4-ek/nxwm/defconfig | 1 - configs/sama5d4-ek/ramtest/defconfig | 1 - configs/samd20-xplained/nsh/defconfig | 1 - configs/samd21-xplained/nsh/defconfig | 1 - configs/same70-xplained/netnsh/defconfig | 2 +- configs/same70-xplained/nsh/defconfig | 2 +- configs/saml21-xplained/nsh/defconfig | 1 - configs/samv71-xult/knsh/defconfig | 2 +- configs/samv71-xult/module/defconfig | 2 +- configs/samv71-xult/mxtxplnd/defconfig | 2 +- configs/samv71-xult/netnsh/defconfig | 2 +- configs/samv71-xult/nsh/defconfig | 2 +- configs/samv71-xult/nxwm/defconfig | 1 - configs/samv71-xult/vnc/defconfig | 2 +- configs/samv71-xult/vnxwm/defconfig | 1 - configs/shenzhou/nsh/defconfig | 2 +- configs/shenzhou/nxwm/defconfig | 1 - configs/shenzhou/thttpd/defconfig | 2 +- configs/spark/composite/defconfig | 2 +- configs/spark/nsh/defconfig | 2 +- configs/spark/usbmsc/defconfig | 2 +- configs/spark/usbnsh/defconfig | 2 +- configs/spark/usbserial/defconfig | 2 +- configs/stm3210e-eval/composite/defconfig | 2 +- configs/stm3210e-eval/nsh/defconfig | 2 +- configs/stm3210e-eval/nsh2/defconfig | 2 +- configs/stm3210e-eval/nx/defconfig | 2 +- configs/stm3210e-eval/nxterm/defconfig | 2 +- configs/stm3210e-eval/pm/defconfig | 2 +- configs/stm3210e-eval/usbmsc/defconfig | 2 +- configs/stm3210e-eval/usbserial/defconfig | 2 +- configs/stm3220g-eval/dhcpd/defconfig | 1 - configs/stm3220g-eval/nettest/defconfig | 1 - configs/stm3220g-eval/nsh/defconfig | 1 - configs/stm3220g-eval/nsh2/defconfig | 1 - configs/stm3220g-eval/nxwm/defconfig | 1 - configs/stm3220g-eval/telnetd/defconfig | 1 - configs/stm3240g-eval/dhcpd/defconfig | 1 - configs/stm3240g-eval/discover/defconfig | 1 - configs/stm3240g-eval/knxwm/defconfig | 1 - configs/stm3240g-eval/nettest/defconfig | 1 - configs/stm3240g-eval/nsh/defconfig | 1 - configs/stm3240g-eval/nsh2/defconfig | 1 - configs/stm3240g-eval/nxterm/defconfig | 1 - configs/stm3240g-eval/nxwm/defconfig | 1 - configs/stm3240g-eval/telnetd/defconfig | 1 - configs/stm3240g-eval/webserver/defconfig | 1 - configs/stm3240g-eval/xmlrpc/defconfig | 1 - configs/stm32_tiny/nsh/defconfig | 2 +- configs/stm32_tiny/usbnsh/defconfig | 2 +- configs/stm32butterfly2/nsh/defconfig | 2 +- configs/stm32butterfly2/nshnet/defconfig | 2 +- configs/stm32butterfly2/nshusbdev/defconfig | 2 +- configs/stm32butterfly2/nshusbhost/defconfig | 2 +- configs/stm32f0discovery/nsh/defconfig | 1 - .../stm32f103-minimum/audio_tone/defconfig | 2 +- configs/stm32f103-minimum/buttons/defconfig | 2 +- configs/stm32f103-minimum/jlx12864g/defconfig | 2 +- configs/stm32f103-minimum/nrf24/defconfig | 2 +- configs/stm32f103-minimum/nsh/defconfig | 2 +- configs/stm32f103-minimum/pwm/defconfig | 2 +- .../stm32f103-minimum/rfid-rc522/defconfig | 2 +- configs/stm32f103-minimum/rgbled/defconfig | 2 +- configs/stm32f103-minimum/usbnsh/defconfig | 2 +- configs/stm32f103-minimum/userled/defconfig | 2 +- configs/stm32f103-minimum/veml6070/defconfig | 2 +- configs/stm32f3discovery/nsh/defconfig | 1 - configs/stm32f3discovery/usbnsh/defconfig | 1 - configs/stm32f411e-disco/nsh/defconfig | 2 +- configs/stm32f429i-disco/extflash/defconfig | 1 - configs/stm32f429i-disco/lcd/defconfig | 1 - configs/stm32f429i-disco/ltdc/defconfig | 1 - configs/stm32f429i-disco/nsh/defconfig | 1 - configs/stm32f429i-disco/nxwm/defconfig | 1 - configs/stm32f429i-disco/usbmsc/defconfig | 1 - configs/stm32f429i-disco/usbnsh/defconfig | 1 - configs/stm32f4discovery/canard/defconfig | 1 - configs/stm32f4discovery/cxxtest/defconfig | 1 - configs/stm32f4discovery/elf/defconfig | 2 +- configs/stm32f4discovery/ipv6/defconfig | 1 - configs/stm32f4discovery/kostest/defconfig | 2 +- configs/stm32f4discovery/netnsh/defconfig | 1 - configs/stm32f4discovery/nsh/defconfig | 1 - configs/stm32f4discovery/nxlines/defconfig | 1 - configs/stm32f4discovery/pm/defconfig | 1 - .../stm32f4discovery/posix_spawn/defconfig | 2 +- configs/stm32f4discovery/pseudoterm/defconfig | 1 - configs/stm32f4discovery/rgbled/defconfig | 1 - configs/stm32f4discovery/uavcan/defconfig | 1 - configs/stm32f4discovery/usbnsh/defconfig | 1 - configs/stm32f4discovery/winbuild/defconfig | 2 +- configs/stm32f4discovery/xen1210/defconfig | 1 - configs/stm32f746-ws/nsh/defconfig | 1 - configs/stm32f746g-disco/nsh/defconfig | 1 - configs/stm32l476-mdk/nsh/defconfig | 2 +- configs/stm32l476vg-disco/nsh/defconfig | 1 - configs/stm32ldiscovery/nsh/defconfig | 2 +- configs/stm32vldiscovery/nsh/defconfig | 2 +- configs/teensy-3.x/nsh/defconfig | 2 +- configs/teensy-3.x/usbnsh/defconfig | 2 +- configs/teensy-lc/nsh/defconfig | 1 - configs/tm4c123g-launchpad/nsh/defconfig | 2 +- configs/tm4c1294-launchpad/ipv6/defconfig | 2 +- configs/tm4c1294-launchpad/nsh/defconfig | 2 +- configs/twr-k60n512/nsh/defconfig | 2 +- configs/twr-k64f120m/netnsh/defconfig | 2 +- configs/twr-k64f120m/nsh/defconfig | 2 +- configs/u-blox-c027/nsh/defconfig | 2 +- configs/viewtool-stm32f107/highpri/defconfig | 2 +- configs/viewtool-stm32f107/netnsh/defconfig | 2 +- configs/viewtool-stm32f107/nsh/defconfig | 2 +- configs/xmc4500-relax/nsh/defconfig | 2 +- configs/zkit-arm-1769/hello/defconfig | 2 +- configs/zkit-arm-1769/nsh/defconfig | 2 +- configs/zkit-arm-1769/nxhello/defconfig | 2 +- configs/zkit-arm-1769/thttpd/defconfig | 2 +- configs/zp214xpa/nsh/defconfig | 1 - configs/zp214xpa/nxlines/defconfig | 1 - libc/machine/arm/armv7-a/Kconfig | 2 +- libc/machine/arm/armv7-m/Kconfig | 2 +- libc/machine/arm/armv7-r/Kconfig | 2 +- tools/testbuild.sh | 2 +- 306 files changed, 187 insertions(+), 339 deletions(-) diff --git a/arch/arm/Kconfig b/arch/arm/Kconfig index 8eb1159947..fc9dd38894 100644 --- a/arch/arm/Kconfig +++ b/arch/arm/Kconfig @@ -460,11 +460,6 @@ config ARM_TOOLCHAIN_IAR bool default n -config ARM_TOOLCHAIN_GNU - bool - default n - select ARCH_TOOLCHAIN_GNU - config ARMV7M_USEBASEPRI bool "Use BASEPRI Register" default n diff --git a/arch/arm/src/Makefile b/arch/arm/src/Makefile index e505b956da..80281d4ce2 100644 --- a/arch/arm/src/Makefile +++ b/arch/arm/src/Makefile @@ -175,7 +175,7 @@ VPATH += $(ARCH_SUBDIR) ifeq ($(CONFIG_ARM_TOOLCHAIN_IAR),y) VPATH += chip$(DELIM)iar VPATH += $(ARCH_SUBDIR)$(DELIM)iar -else # ifeq ($(CONFIG_ARM_TOOLCHAIN_GNU),y) +else # ifeq ($(CONFIG_ARCH_TOOLCHAIN_GNU),y) VPATH += chip$(DELIM)gnu VPATH += $(ARCH_SUBDIR)$(DELIM)gnu endif diff --git a/arch/arm/src/armv6-m/Kconfig b/arch/arm/src/armv6-m/Kconfig index cd1f9216dc..4a22655a05 100644 --- a/arch/arm/src/armv6-m/Kconfig +++ b/arch/arm/src/armv6-m/Kconfig @@ -13,41 +13,41 @@ choice config ARMV6M_TOOLCHAIN_ATOLLIC bool "Atollic Lite/Pro for Windows" depends on TOOLCHAIN_WINDOWS - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU config ARMV6M_TOOLCHAIN_BUILDROOT bool "Buildroot (Cygwin or Linux)" depends on !WINDOWS_NATIVE - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU config ARMV6M_TOOLCHAIN_CODEREDL bool "CodeRed for Linux" depends on HOST_LINUX - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU config ARMV6M_TOOLCHAIN_CODEREDW bool "CodeRed for Windows" depends on TOOLCHAIN_WINDOWS - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU config ARMV6M_TOOLCHAIN_CODESOURCERYL bool "CodeSourcery GNU toolchain under Linux" depends on HOST_LINUX - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU config ARMV6M_TOOLCHAIN_CODESOURCERYW bool "CodeSourcery GNU toolchain under Windows" depends on TOOLCHAIN_WINDOWS - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU config ARMV6M_TOOLCHAIN_DEVKITARM bool "devkitARM GNU toolchain" depends on TOOLCHAIN_WINDOWS - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU config ARMV6M_TOOLCHAIN_GNU_EABIL bool "Generic GNU EABI toolchain under Linux (or other POSIX environment)" - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU ---help--- This option should work for any modern GNU toolchain (GCC 4.5 or newer) configured for arm-none-eabi. @@ -55,7 +55,7 @@ config ARMV6M_TOOLCHAIN_GNU_EABIL config ARMV6M_TOOLCHAIN_GNU_EABIW bool "Generic GNU EABI toolchain under Windows" depends on TOOLCHAIN_WINDOWS - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU ---help--- This option should work for any modern GNU toolchain (GCC 4.5 or newer) configured for arm-none-eabi. diff --git a/arch/arm/src/armv7-a/Kconfig b/arch/arm/src/armv7-a/Kconfig index e4746900a3..a8dc919e35 100644 --- a/arch/arm/src/armv7-a/Kconfig +++ b/arch/arm/src/armv7-a/Kconfig @@ -133,12 +133,12 @@ choice config ARMV7A_TOOLCHAIN_BUILDROOT bool "Buildroot (Cygwin or Linux)" - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU depends on !WINDOWS_NATIVE config ARMV7A_TOOLCHAIN_CODESOURCERYL bool "CodeSourcery GNU toolchain under Linux" - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU depends on HOST_LINUX ---help--- For use with the GNU toolchain built with the NuttX buildroot package. @@ -147,24 +147,24 @@ config ARMV7A_TOOLCHAIN_CODESOURCERYL config ARMV7A_TOOLCHAIN_CODESOURCERYW bool "CodeSourcery GNU toolchain under Windows" - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU depends on TOOLCHAIN_WINDOWS config ARMV7A_TOOLCHAIN_DEVKITARM bool "devkitARM GNU toolchain" - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU depends on TOOLCHAIN_WINDOWS config ARMV7A_TOOLCHAIN_GNU_EABIL bool "Generic GNU EABI toolchain under Linux (or other POSIX environment)" - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU ---help--- This option should work for any modern GNU toolchain (GCC 4.5 or newer) configured for arm-none-eabi-. config ARMV7A_TOOLCHAIN_GNU_EABIW bool "Generic GNU EABI toolchain under Windows" - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU depends on TOOLCHAIN_WINDOWS ---help--- This option should work for any modern GNU toolchain (GCC 4.5 or newer) @@ -172,7 +172,7 @@ config ARMV7A_TOOLCHAIN_GNU_EABIW config ARMV7A_TOOLCHAIN_GNU_OABI bool "Generic GNU OABI toolchain" - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU ---help--- This option should work for any GNU toolchain configured for arm-elf-. diff --git a/arch/arm/src/armv7-m/Kconfig b/arch/arm/src/armv7-m/Kconfig index 4c66b55d54..0901db06da 100644 --- a/arch/arm/src/armv7-m/Kconfig +++ b/arch/arm/src/armv7-m/Kconfig @@ -64,42 +64,42 @@ config ARMV7M_TOOLCHAIN_IARL config ARMV7M_TOOLCHAIN_ATOLLIC bool "Atollic Lite/Pro for Windows" depends on TOOLCHAIN_WINDOWS - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU config ARMV7M_TOOLCHAIN_BUILDROOT bool "Buildroot (Cygwin or Linux)" depends on !WINDOWS_NATIVE - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU config ARMV7M_TOOLCHAIN_CODEREDL bool "CodeRed for Linux" depends on HOST_LINUX - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU config ARMV7M_TOOLCHAIN_CODEREDW bool "CodeRed for Windows" depends on TOOLCHAIN_WINDOWS - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU config ARMV7M_TOOLCHAIN_CODESOURCERYL bool "CodeSourcery GNU toolchain under Linux" depends on HOST_LINUX - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU config ARMV7M_TOOLCHAIN_CODESOURCERYW bool "CodeSourcery GNU toolchain under Windows" depends on TOOLCHAIN_WINDOWS - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU config ARMV7M_TOOLCHAIN_DEVKITARM bool "devkitARM GNU toolchain" depends on TOOLCHAIN_WINDOWS - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU config ARMV7M_TOOLCHAIN_GNU_EABIL bool "Generic GNU EABI toolchain under Linux (or other POSIX environment)" depends on !WINDOWS_NATIVE - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU ---help--- This option should work for any modern GNU toolchain (GCC 4.5 or newer) configured for arm-none-eabi. @@ -107,7 +107,7 @@ config ARMV7M_TOOLCHAIN_GNU_EABIL config ARMV7M_TOOLCHAIN_GNU_EABIW bool "Generic GNU EABI toolchain under Windows" depends on TOOLCHAIN_WINDOWS - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU ---help--- This option should work for any modern GNU toolchain (GCC 4.5 or newer) configured for arm-none-eabi. @@ -115,7 +115,7 @@ config ARMV7M_TOOLCHAIN_GNU_EABIW config ARMV7M_TOOLCHAIN_RAISONANCE bool "STMicro Raisonance for Windows" depends on TOOLCHAIN_WINDOWS - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU endchoice diff --git a/arch/arm/src/armv7-r/Kconfig b/arch/arm/src/armv7-r/Kconfig index b4ec974db0..f5ce353584 100644 --- a/arch/arm/src/armv7-r/Kconfig +++ b/arch/arm/src/armv7-r/Kconfig @@ -149,12 +149,12 @@ choice config ARMV7R_TOOLCHAIN_BUILDROOT bool "Buildroot (Cygwin or Linux)" - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU depends on !WINDOWS_NATIVE config ARMV7R_TOOLCHAIN_CODESOURCERYL bool "CodeSourcery GNU toolchain under Linux" - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU depends on HOST_LINUX ---help--- For use with the GNU toolchain built with the NuttX buildroot package. @@ -163,24 +163,24 @@ config ARMV7R_TOOLCHAIN_CODESOURCERYL config ARMV7R_TOOLCHAIN_CODESOURCERYW bool "CodeSourcery GNU toolchain under Windows" - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU depends on TOOLCHAIN_WINDOWS config ARMV7R_TOOLCHAIN_DEVKITARM bool "devkitARM GNU toolchain" - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU depends on TOOLCHAIN_WINDOWS config ARMV7R_TOOLCHAIN_GNU_EABIL bool "Generic GNU EABI toolchain under Linux (or other POSIX environment)" - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU ---help--- This option should work for any modern GNU toolchain (GCC 4.5 or newer) configured for arm-none-eabi-. config ARMV7R_TOOLCHAIN_GNU_EABIW bool "Generic GNU EABI toolchain under Windows" - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU depends on TOOLCHAIN_WINDOWS ---help--- This option should work for any modern GNU toolchain (GCC 4.5 or newer) @@ -188,7 +188,7 @@ config ARMV7R_TOOLCHAIN_GNU_EABIW config ARMV7R_TOOLCHAIN_GNU_OABI bool "Generic GNU OABI toolchain" - select ARM_TOOLCHAIN_GNU + select ARCH_TOOLCHAIN_GNU ---help--- This option should work for any GNU toolchain configured for arm-elf-. diff --git a/configs/arduino-due/nsh/defconfig b/configs/arduino-due/nsh/defconfig index a43823cce6..a9efd1b409 100644 --- a/configs/arduino-due/nsh/defconfig +++ b/configs/arduino-due/nsh/defconfig @@ -125,7 +125,6 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="sam34" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/bambino-200e/netnsh/defconfig b/configs/bambino-200e/netnsh/defconfig index 7b3e53b6cc..ae943545e6 100644 --- a/configs/bambino-200e/netnsh/defconfig +++ b/configs/bambino-200e/netnsh/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc43xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/bambino-200e/nsh/defconfig b/configs/bambino-200e/nsh/defconfig index 3d4282dbc8..9999a7f74a 100644 --- a/configs/bambino-200e/nsh/defconfig +++ b/configs/bambino-200e/nsh/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc43xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/bambino-200e/usbnsh/defconfig b/configs/bambino-200e/usbnsh/defconfig index 01f5f86561..9059baeb98 100644 --- a/configs/bambino-200e/usbnsh/defconfig +++ b/configs/bambino-200e/usbnsh/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc43xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/c5471evm/httpd/defconfig b/configs/c5471evm/httpd/defconfig index 763da2a5bd..0a5a307ce3 100644 --- a/configs/c5471evm/httpd/defconfig +++ b/configs/c5471evm/httpd/defconfig @@ -124,7 +124,6 @@ CONFIG_ARCH_ARM7TDMI=y CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="c5471" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/c5471evm/nettest/defconfig b/configs/c5471evm/nettest/defconfig index 72dc20b6f1..3283887cde 100644 --- a/configs/c5471evm/nettest/defconfig +++ b/configs/c5471evm/nettest/defconfig @@ -124,7 +124,6 @@ CONFIG_ARCH_ARM7TDMI=y CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="c5471" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/c5471evm/nsh/defconfig b/configs/c5471evm/nsh/defconfig index bb9f485700..8ca4c5145d 100644 --- a/configs/c5471evm/nsh/defconfig +++ b/configs/c5471evm/nsh/defconfig @@ -124,7 +124,6 @@ CONFIG_ARCH_ARM7TDMI=y CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="c5471" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/cc3200-launchpad/nsh/defconfig b/configs/cc3200-launchpad/nsh/defconfig index 0c3ea5e93d..01f8b14b6d 100644 --- a/configs/cc3200-launchpad/nsh/defconfig +++ b/configs/cc3200-launchpad/nsh/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/clicker2-stm32/knsh/defconfig b/configs/clicker2-stm32/knsh/defconfig index 5a4d128ac2..80aee6dd1c 100644 --- a/configs/clicker2-stm32/knsh/defconfig +++ b/configs/clicker2-stm32/knsh/defconfig @@ -131,7 +131,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/clicker2-stm32/mrf24j40-radio/defconfig b/configs/clicker2-stm32/mrf24j40-radio/defconfig index 95adaa7012..2a9e6b3d30 100644 --- a/configs/clicker2-stm32/mrf24j40-radio/defconfig +++ b/configs/clicker2-stm32/mrf24j40-radio/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/clicker2-stm32/nsh/defconfig b/configs/clicker2-stm32/nsh/defconfig index 02dc18e067..86859d28bc 100644 --- a/configs/clicker2-stm32/nsh/defconfig +++ b/configs/clicker2-stm32/nsh/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/clicker2-stm32/usbnsh/defconfig b/configs/clicker2-stm32/usbnsh/defconfig index 943e8a7cc8..88c8f5b534 100644 --- a/configs/clicker2-stm32/usbnsh/defconfig +++ b/configs/clicker2-stm32/usbnsh/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/cloudctrl/nsh/defconfig b/configs/cloudctrl/nsh/defconfig index f14809e3f8..702ba56801 100644 --- a/configs/cloudctrl/nsh/defconfig +++ b/configs/cloudctrl/nsh/defconfig @@ -131,7 +131,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/dk-tm4c129x/ipv6/defconfig b/configs/dk-tm4c129x/ipv6/defconfig index 86189d524b..ad36404f11 100644 --- a/configs/dk-tm4c129x/ipv6/defconfig +++ b/configs/dk-tm4c129x/ipv6/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/dk-tm4c129x/nsh/defconfig b/configs/dk-tm4c129x/nsh/defconfig index 92a8d79c74..cbaa62ed3e 100644 --- a/configs/dk-tm4c129x/nsh/defconfig +++ b/configs/dk-tm4c129x/nsh/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/ea3131/nsh/defconfig b/configs/ea3131/nsh/defconfig index dc4dd7bff8..f7de159baf 100644 --- a/configs/ea3131/nsh/defconfig +++ b/configs/ea3131/nsh/defconfig @@ -128,7 +128,6 @@ CONFIG_ARCH_ARM926EJS=y CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="lpc31xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/ea3131/pgnsh/defconfig b/configs/ea3131/pgnsh/defconfig index 1d6a5864ac..99ccdd58db 100644 --- a/configs/ea3131/pgnsh/defconfig +++ b/configs/ea3131/pgnsh/defconfig @@ -131,7 +131,6 @@ CONFIG_ARCH_ARM926EJS=y CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="lpc31xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/ea3131/usbserial/defconfig b/configs/ea3131/usbserial/defconfig index 4a502be9b7..bacdd9bb4a 100644 --- a/configs/ea3131/usbserial/defconfig +++ b/configs/ea3131/usbserial/defconfig @@ -128,7 +128,6 @@ CONFIG_ARCH_ARM926EJS=y CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="lpc31xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/ea3152/ostest/defconfig b/configs/ea3152/ostest/defconfig index 74acabf1d2..73b24c8859 100644 --- a/configs/ea3152/ostest/defconfig +++ b/configs/ea3152/ostest/defconfig @@ -128,7 +128,6 @@ CONFIG_ARCH_ARM926EJS=y CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="lpc31xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/eagle100/httpd/defconfig b/configs/eagle100/httpd/defconfig index d18b5ce513..173603d8ef 100644 --- a/configs/eagle100/httpd/defconfig +++ b/configs/eagle100/httpd/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/eagle100/nettest/defconfig b/configs/eagle100/nettest/defconfig index 91197d61e3..cd0911d540 100644 --- a/configs/eagle100/nettest/defconfig +++ b/configs/eagle100/nettest/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/eagle100/nsh/defconfig b/configs/eagle100/nsh/defconfig index 34b86ded78..b53dcf1df2 100644 --- a/configs/eagle100/nsh/defconfig +++ b/configs/eagle100/nsh/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/eagle100/nxflat/defconfig b/configs/eagle100/nxflat/defconfig index c6af5b59d5..5fb625a468 100644 --- a/configs/eagle100/nxflat/defconfig +++ b/configs/eagle100/nxflat/defconfig @@ -128,7 +128,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/eagle100/thttpd/defconfig b/configs/eagle100/thttpd/defconfig index fc7aef9061..729eb0e04e 100644 --- a/configs/eagle100/thttpd/defconfig +++ b/configs/eagle100/thttpd/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/efm32-g8xx-stk/nsh/defconfig b/configs/efm32-g8xx-stk/nsh/defconfig index 999021c231..eff463d023 100644 --- a/configs/efm32-g8xx-stk/nsh/defconfig +++ b/configs/efm32-g8xx-stk/nsh/defconfig @@ -128,7 +128,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="efm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/efm32gg-stk3700/nsh/defconfig b/configs/efm32gg-stk3700/nsh/defconfig index 73141e3451..19d86bf2ee 100644 --- a/configs/efm32gg-stk3700/nsh/defconfig +++ b/configs/efm32gg-stk3700/nsh/defconfig @@ -128,7 +128,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="efm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/ekk-lm3s9b96/nsh/defconfig b/configs/ekk-lm3s9b96/nsh/defconfig index a9fb835bb8..c15bdf04fe 100644 --- a/configs/ekk-lm3s9b96/nsh/defconfig +++ b/configs/ekk-lm3s9b96/nsh/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/fire-stm32v2/nsh/defconfig b/configs/fire-stm32v2/nsh/defconfig index 1255771f4a..ec18e9ce68 100644 --- a/configs/fire-stm32v2/nsh/defconfig +++ b/configs/fire-stm32v2/nsh/defconfig @@ -131,7 +131,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/freedom-k64f/netnsh/defconfig b/configs/freedom-k64f/netnsh/defconfig index bcac9353a2..870d04628c 100644 --- a/configs/freedom-k64f/netnsh/defconfig +++ b/configs/freedom-k64f/netnsh/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="kinetis" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/freedom-k64f/nsh/defconfig b/configs/freedom-k64f/nsh/defconfig index 9494c766b7..c20b9516ba 100644 --- a/configs/freedom-k64f/nsh/defconfig +++ b/configs/freedom-k64f/nsh/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="kinetis" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/freedom-k66f/netnsh/defconfig b/configs/freedom-k66f/netnsh/defconfig index 71f0cd33b2..605211c45c 100644 --- a/configs/freedom-k66f/netnsh/defconfig +++ b/configs/freedom-k66f/netnsh/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="kinetis" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/freedom-k66f/nsh/defconfig b/configs/freedom-k66f/nsh/defconfig index c1b4346b06..ee3cdbd812 100644 --- a/configs/freedom-k66f/nsh/defconfig +++ b/configs/freedom-k66f/nsh/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="kinetis" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/freedom-kl25z/nsh/defconfig b/configs/freedom-kl25z/nsh/defconfig index 44409adf6f..66209901fd 100644 --- a/configs/freedom-kl25z/nsh/defconfig +++ b/configs/freedom-kl25z/nsh/defconfig @@ -122,7 +122,6 @@ CONFIG_ARCH_CORTEXM0=y CONFIG_ARCH_FAMILY="armv6-m" CONFIG_ARCH_CHIP="kl" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set # CONFIG_ARMV7M_LAZYFPU is not set diff --git a/configs/freedom-kl26z/nsh/defconfig b/configs/freedom-kl26z/nsh/defconfig index fc1c40a759..20e2a5773a 100644 --- a/configs/freedom-kl26z/nsh/defconfig +++ b/configs/freedom-kl26z/nsh/defconfig @@ -122,7 +122,6 @@ CONFIG_ARCH_CORTEXM0=y CONFIG_ARCH_FAMILY="armv6-m" CONFIG_ARCH_CHIP="kl" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set # CONFIG_ARMV7M_LAZYFPU is not set diff --git a/configs/hymini-stm32v/nsh/defconfig b/configs/hymini-stm32v/nsh/defconfig index fe68926811..bb3ca8f375 100644 --- a/configs/hymini-stm32v/nsh/defconfig +++ b/configs/hymini-stm32v/nsh/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/hymini-stm32v/nsh2/defconfig b/configs/hymini-stm32v/nsh2/defconfig index ee5e4f93f1..9d6ac794f5 100644 --- a/configs/hymini-stm32v/nsh2/defconfig +++ b/configs/hymini-stm32v/nsh2/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/hymini-stm32v/usbmsc/defconfig b/configs/hymini-stm32v/usbmsc/defconfig index eec91e46a4..287eb70cb7 100644 --- a/configs/hymini-stm32v/usbmsc/defconfig +++ b/configs/hymini-stm32v/usbmsc/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/hymini-stm32v/usbnsh/defconfig b/configs/hymini-stm32v/usbnsh/defconfig index 239c6c2383..f601f22f85 100644 --- a/configs/hymini-stm32v/usbnsh/defconfig +++ b/configs/hymini-stm32v/usbnsh/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/hymini-stm32v/usbserial/defconfig b/configs/hymini-stm32v/usbserial/defconfig index e5ec56e3e1..3d6cf703e6 100644 --- a/configs/hymini-stm32v/usbserial/defconfig +++ b/configs/hymini-stm32v/usbserial/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/kwikstik-k40/ostest/defconfig b/configs/kwikstik-k40/ostest/defconfig index 17e0f84d14..fd60f30842 100644 --- a/configs/kwikstik-k40/ostest/defconfig +++ b/configs/kwikstik-k40/ostest/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="kinetis" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/launchxl-tms57004/nsh/defconfig b/configs/launchxl-tms57004/nsh/defconfig index 22236f0c96..e4c1a1a3ad 100644 --- a/configs/launchxl-tms57004/nsh/defconfig +++ b/configs/launchxl-tms57004/nsh/defconfig @@ -128,7 +128,7 @@ CONFIG_ARCH_CORTEXR4=y CONFIG_ARCH_FAMILY="armv7-r" CONFIG_ARCH_CHIP="tms570" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/lincoln60/netnsh/defconfig b/configs/lincoln60/netnsh/defconfig index 40dfb528ef..329f574d86 100644 --- a/configs/lincoln60/netnsh/defconfig +++ b/configs/lincoln60/netnsh/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/lincoln60/nsh/defconfig b/configs/lincoln60/nsh/defconfig index 5151256ba6..0f3f84f13c 100644 --- a/configs/lincoln60/nsh/defconfig +++ b/configs/lincoln60/nsh/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/lincoln60/thttpd-binfs/defconfig b/configs/lincoln60/thttpd-binfs/defconfig index 4f4316e9c7..526196caa8 100644 --- a/configs/lincoln60/thttpd-binfs/defconfig +++ b/configs/lincoln60/thttpd-binfs/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/lm3s6432-s2e/nsh/defconfig b/configs/lm3s6432-s2e/nsh/defconfig index fe849d782c..218e59dc08 100644 --- a/configs/lm3s6432-s2e/nsh/defconfig +++ b/configs/lm3s6432-s2e/nsh/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/lm3s6965-ek/discover/defconfig b/configs/lm3s6965-ek/discover/defconfig index 305695abfb..4430849fe6 100644 --- a/configs/lm3s6965-ek/discover/defconfig +++ b/configs/lm3s6965-ek/discover/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/lm3s6965-ek/nsh/defconfig b/configs/lm3s6965-ek/nsh/defconfig index 305695abfb..4430849fe6 100644 --- a/configs/lm3s6965-ek/nsh/defconfig +++ b/configs/lm3s6965-ek/nsh/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/lm3s6965-ek/nx/defconfig b/configs/lm3s6965-ek/nx/defconfig index 890bf26a43..cd5a4ff64d 100644 --- a/configs/lm3s6965-ek/nx/defconfig +++ b/configs/lm3s6965-ek/nx/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/lm3s6965-ek/tcpecho/defconfig b/configs/lm3s6965-ek/tcpecho/defconfig index ff3212eaae..1322a6b086 100644 --- a/configs/lm3s6965-ek/tcpecho/defconfig +++ b/configs/lm3s6965-ek/tcpecho/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/lm3s8962-ek/nsh/defconfig b/configs/lm3s8962-ek/nsh/defconfig index 86971dec84..4f430bcbe1 100644 --- a/configs/lm3s8962-ek/nsh/defconfig +++ b/configs/lm3s8962-ek/nsh/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/lm3s8962-ek/nx/defconfig b/configs/lm3s8962-ek/nx/defconfig index dfa2360292..fb7972fcce 100644 --- a/configs/lm3s8962-ek/nx/defconfig +++ b/configs/lm3s8962-ek/nx/defconfig @@ -128,7 +128,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/lm4f120-launchpad/nsh/defconfig b/configs/lm4f120-launchpad/nsh/defconfig index b62982b2d4..68e93a91db 100644 --- a/configs/lm4f120-launchpad/nsh/defconfig +++ b/configs/lm4f120-launchpad/nsh/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/lpc4330-xplorer/nsh/defconfig b/configs/lpc4330-xplorer/nsh/defconfig index 15fdeb23a5..36341064ed 100644 --- a/configs/lpc4330-xplorer/nsh/defconfig +++ b/configs/lpc4330-xplorer/nsh/defconfig @@ -128,7 +128,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc43xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/lpc4337-ws/nsh/defconfig b/configs/lpc4337-ws/nsh/defconfig index 85c38182c0..1d9816c93a 100644 --- a/configs/lpc4337-ws/nsh/defconfig +++ b/configs/lpc4337-ws/nsh/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc43xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/lpc4357-evb/nsh/defconfig b/configs/lpc4357-evb/nsh/defconfig index f12eb6b565..2ca8bcb4ef 100644 --- a/configs/lpc4357-evb/nsh/defconfig +++ b/configs/lpc4357-evb/nsh/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc43xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/lpc4370-link2/nsh/defconfig b/configs/lpc4370-link2/nsh/defconfig index e8c417a638..44b6a22d2e 100644 --- a/configs/lpc4370-link2/nsh/defconfig +++ b/configs/lpc4370-link2/nsh/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc43xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/lpcxpresso-lpc1115/nsh/defconfig b/configs/lpcxpresso-lpc1115/nsh/defconfig index deeddca94b..ccbeff2668 100644 --- a/configs/lpcxpresso-lpc1115/nsh/defconfig +++ b/configs/lpcxpresso-lpc1115/nsh/defconfig @@ -122,7 +122,6 @@ CONFIG_ARCH_CORTEXM0=y CONFIG_ARCH_FAMILY="armv6-m" CONFIG_ARCH_CHIP="lpc11xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set # CONFIG_ARMV7M_LAZYFPU is not set diff --git a/configs/lpcxpresso-lpc1768/dhcpd/defconfig b/configs/lpcxpresso-lpc1768/dhcpd/defconfig index 6e8638e71d..e43bad3bee 100644 --- a/configs/lpcxpresso-lpc1768/dhcpd/defconfig +++ b/configs/lpcxpresso-lpc1768/dhcpd/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/lpcxpresso-lpc1768/nsh/defconfig b/configs/lpcxpresso-lpc1768/nsh/defconfig index 1246035ad3..ac4954e96b 100644 --- a/configs/lpcxpresso-lpc1768/nsh/defconfig +++ b/configs/lpcxpresso-lpc1768/nsh/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/lpcxpresso-lpc1768/nx/defconfig b/configs/lpcxpresso-lpc1768/nx/defconfig index 48816c4ef3..dca6d00aae 100644 --- a/configs/lpcxpresso-lpc1768/nx/defconfig +++ b/configs/lpcxpresso-lpc1768/nx/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/lpcxpresso-lpc1768/thttpd/defconfig b/configs/lpcxpresso-lpc1768/thttpd/defconfig index 60845d6a63..a680bbcbb5 100644 --- a/configs/lpcxpresso-lpc1768/thttpd/defconfig +++ b/configs/lpcxpresso-lpc1768/thttpd/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/lpcxpresso-lpc1768/usbmsc/defconfig b/configs/lpcxpresso-lpc1768/usbmsc/defconfig index ef5d2b4b47..e2e0b98a3d 100644 --- a/configs/lpcxpresso-lpc1768/usbmsc/defconfig +++ b/configs/lpcxpresso-lpc1768/usbmsc/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/maple/nsh/defconfig b/configs/maple/nsh/defconfig index 5a9f920921..6e8ab0b117 100644 --- a/configs/maple/nsh/defconfig +++ b/configs/maple/nsh/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/maple/nx/defconfig b/configs/maple/nx/defconfig index 7a3e615430..624e6d72cd 100644 --- a/configs/maple/nx/defconfig +++ b/configs/maple/nx/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/maple/usbnsh/defconfig b/configs/maple/usbnsh/defconfig index b74195b592..7c218e3470 100644 --- a/configs/maple/usbnsh/defconfig +++ b/configs/maple/usbnsh/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/mbed/nsh/defconfig b/configs/mbed/nsh/defconfig index 98949e8db0..32e19cbb1a 100644 --- a/configs/mbed/nsh/defconfig +++ b/configs/mbed/nsh/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/mcu123-lpc214x/composite/defconfig b/configs/mcu123-lpc214x/composite/defconfig index 4df7bb1f41..e3d6a6728e 100644 --- a/configs/mcu123-lpc214x/composite/defconfig +++ b/configs/mcu123-lpc214x/composite/defconfig @@ -122,7 +122,6 @@ CONFIG_ARCH_ARM7TDMI=y CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="lpc214x" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/mcu123-lpc214x/nsh/defconfig b/configs/mcu123-lpc214x/nsh/defconfig index eceeefccba..3f42176bd5 100644 --- a/configs/mcu123-lpc214x/nsh/defconfig +++ b/configs/mcu123-lpc214x/nsh/defconfig @@ -122,7 +122,6 @@ CONFIG_ARCH_ARM7TDMI=y CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="lpc214x" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/mcu123-lpc214x/usbmsc/defconfig b/configs/mcu123-lpc214x/usbmsc/defconfig index 8c544ff681..d19e88bbd1 100644 --- a/configs/mcu123-lpc214x/usbmsc/defconfig +++ b/configs/mcu123-lpc214x/usbmsc/defconfig @@ -122,7 +122,6 @@ CONFIG_ARCH_ARM7TDMI=y CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="lpc214x" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/mcu123-lpc214x/usbserial/defconfig b/configs/mcu123-lpc214x/usbserial/defconfig index a0e67fe99b..5b5975cb38 100644 --- a/configs/mcu123-lpc214x/usbserial/defconfig +++ b/configs/mcu123-lpc214x/usbserial/defconfig @@ -122,7 +122,6 @@ CONFIG_ARCH_ARM7TDMI=y CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="lpc214x" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/mikroe-stm32f4/fulldemo/defconfig b/configs/mikroe-stm32f4/fulldemo/defconfig index e3bfddddd7..b3f16f6c83 100644 --- a/configs/mikroe-stm32f4/fulldemo/defconfig +++ b/configs/mikroe-stm32f4/fulldemo/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/mikroe-stm32f4/kostest/defconfig b/configs/mikroe-stm32f4/kostest/defconfig index 46e0e594fe..b099d5b86d 100644 --- a/configs/mikroe-stm32f4/kostest/defconfig +++ b/configs/mikroe-stm32f4/kostest/defconfig @@ -131,7 +131,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/mikroe-stm32f4/nsh/defconfig b/configs/mikroe-stm32f4/nsh/defconfig index 5a7361f71b..9f680a8f4d 100644 --- a/configs/mikroe-stm32f4/nsh/defconfig +++ b/configs/mikroe-stm32f4/nsh/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/mikroe-stm32f4/nx/defconfig b/configs/mikroe-stm32f4/nx/defconfig index f725a5e05e..1019848edd 100644 --- a/configs/mikroe-stm32f4/nx/defconfig +++ b/configs/mikroe-stm32f4/nx/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/mikroe-stm32f4/nxlines/defconfig b/configs/mikroe-stm32f4/nxlines/defconfig index 3d0cfb98af..05abbbcd90 100644 --- a/configs/mikroe-stm32f4/nxlines/defconfig +++ b/configs/mikroe-stm32f4/nxlines/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/mikroe-stm32f4/nxtext/defconfig b/configs/mikroe-stm32f4/nxtext/defconfig index 37b66b8c38..6acc4817f7 100644 --- a/configs/mikroe-stm32f4/nxtext/defconfig +++ b/configs/mikroe-stm32f4/nxtext/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/mikroe-stm32f4/usbnsh/defconfig b/configs/mikroe-stm32f4/usbnsh/defconfig index b70490f816..193621ba02 100644 --- a/configs/mikroe-stm32f4/usbnsh/defconfig +++ b/configs/mikroe-stm32f4/usbnsh/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/moxa/nsh/defconfig b/configs/moxa/nsh/defconfig index 76da9497d6..4629cded4a 100644 --- a/configs/moxa/nsh/defconfig +++ b/configs/moxa/nsh/defconfig @@ -124,7 +124,6 @@ CONFIG_ARCH_ARM7TDMI=y CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="moxart" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/mx1ads/ostest/defconfig b/configs/mx1ads/ostest/defconfig index 7de94989e1..2a5f6df09f 100644 --- a/configs/mx1ads/ostest/defconfig +++ b/configs/mx1ads/ostest/defconfig @@ -122,7 +122,6 @@ CONFIG_ARCH_ARM920T=y CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="imx1" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/ntosd-dm320/nettest/defconfig b/configs/ntosd-dm320/nettest/defconfig index e088110948..311ee15aae 100644 --- a/configs/ntosd-dm320/nettest/defconfig +++ b/configs/ntosd-dm320/nettest/defconfig @@ -124,7 +124,6 @@ CONFIG_ARCH_ARM926EJS=y CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="dm320" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/ntosd-dm320/nsh/defconfig b/configs/ntosd-dm320/nsh/defconfig index 12b46adc25..b1b2f6fb42 100644 --- a/configs/ntosd-dm320/nsh/defconfig +++ b/configs/ntosd-dm320/nsh/defconfig @@ -124,7 +124,6 @@ CONFIG_ARCH_ARM926EJS=y CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="dm320" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/ntosd-dm320/poll/defconfig b/configs/ntosd-dm320/poll/defconfig index 16874144a1..e314ef41d3 100644 --- a/configs/ntosd-dm320/poll/defconfig +++ b/configs/ntosd-dm320/poll/defconfig @@ -124,7 +124,6 @@ CONFIG_ARCH_ARM926EJS=y CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="dm320" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/ntosd-dm320/thttpd/defconfig b/configs/ntosd-dm320/thttpd/defconfig index 77f922ff67..6d92deb481 100644 --- a/configs/ntosd-dm320/thttpd/defconfig +++ b/configs/ntosd-dm320/thttpd/defconfig @@ -124,7 +124,6 @@ CONFIG_ARCH_ARM926EJS=y CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="dm320" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/ntosd-dm320/udp/defconfig b/configs/ntosd-dm320/udp/defconfig index 1f0c2d5c07..796fd42634 100644 --- a/configs/ntosd-dm320/udp/defconfig +++ b/configs/ntosd-dm320/udp/defconfig @@ -124,7 +124,6 @@ CONFIG_ARCH_ARM926EJS=y CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="dm320" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/ntosd-dm320/webserver/defconfig b/configs/ntosd-dm320/webserver/defconfig index a41eb42fdc..73f3f5c832 100644 --- a/configs/ntosd-dm320/webserver/defconfig +++ b/configs/ntosd-dm320/webserver/defconfig @@ -124,7 +124,6 @@ CONFIG_ARCH_ARM926EJS=y CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="dm320" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/nucleo-144/f746-evalos/defconfig b/configs/nucleo-144/f746-evalos/defconfig index 7661a07ba8..5641f155a6 100644 --- a/configs/nucleo-144/f746-evalos/defconfig +++ b/configs/nucleo-144/f746-evalos/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM7=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32f7" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/nucleo-144/f746-nsh/defconfig b/configs/nucleo-144/f746-nsh/defconfig index 076d5b8c8a..45debe992f 100644 --- a/configs/nucleo-144/f746-nsh/defconfig +++ b/configs/nucleo-144/f746-nsh/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM7=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32f7" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/nucleo-144/f767-evalos/defconfig b/configs/nucleo-144/f767-evalos/defconfig index a6a7365474..ef02b1ec18 100644 --- a/configs/nucleo-144/f767-evalos/defconfig +++ b/configs/nucleo-144/f767-evalos/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM7=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32f7" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/nucleo-144/f767-nsh/defconfig b/configs/nucleo-144/f767-nsh/defconfig index 165ae152cf..b441fea4f6 100644 --- a/configs/nucleo-144/f767-nsh/defconfig +++ b/configs/nucleo-144/f767-nsh/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM7=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32f7" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/nucleo-f072rb/nsh/defconfig b/configs/nucleo-f072rb/nsh/defconfig index ebce1f4dc3..873055d9b6 100644 --- a/configs/nucleo-f072rb/nsh/defconfig +++ b/configs/nucleo-f072rb/nsh/defconfig @@ -124,7 +124,6 @@ CONFIG_ARCH_CORTEXM0=y CONFIG_ARCH_FAMILY="armv6-m" CONFIG_ARCH_CHIP="stm32f0" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set # CONFIG_ARMV7M_LAZYFPU is not set diff --git a/configs/nucleo-f091rc/nsh/defconfig b/configs/nucleo-f091rc/nsh/defconfig index e3c9cadefb..8a4dfca1f0 100644 --- a/configs/nucleo-f091rc/nsh/defconfig +++ b/configs/nucleo-f091rc/nsh/defconfig @@ -154,7 +154,6 @@ CONFIG_ARCH_CORTEXM0=y CONFIG_ARCH_FAMILY="armv6-m" CONFIG_ARCH_CHIP="stm32f0" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set # CONFIG_ARMV7M_LAZYFPU is not set diff --git a/configs/nucleo-f303re/adc/defconfig b/configs/nucleo-f303re/adc/defconfig index ee469d2e8d..f68cbba519 100644 --- a/configs/nucleo-f303re/adc/defconfig +++ b/configs/nucleo-f303re/adc/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/nucleo-f303re/can/defconfig b/configs/nucleo-f303re/can/defconfig index 4db532a862..13c676f841 100644 --- a/configs/nucleo-f303re/can/defconfig +++ b/configs/nucleo-f303re/can/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/nucleo-f303re/hello/defconfig b/configs/nucleo-f303re/hello/defconfig index 6a1e7fb7c4..77b3b74b64 100644 --- a/configs/nucleo-f303re/hello/defconfig +++ b/configs/nucleo-f303re/hello/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/nucleo-f303re/nxlines/defconfig b/configs/nucleo-f303re/nxlines/defconfig index 60d56ecc84..216ddd0d15 100644 --- a/configs/nucleo-f303re/nxlines/defconfig +++ b/configs/nucleo-f303re/nxlines/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/nucleo-f303re/pwm/defconfig b/configs/nucleo-f303re/pwm/defconfig index 630d14fa4e..485e8e95d6 100644 --- a/configs/nucleo-f303re/pwm/defconfig +++ b/configs/nucleo-f303re/pwm/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/nucleo-f303re/serialrx/defconfig b/configs/nucleo-f303re/serialrx/defconfig index 1565a99eca..52040cacf1 100644 --- a/configs/nucleo-f303re/serialrx/defconfig +++ b/configs/nucleo-f303re/serialrx/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/nucleo-f303re/uavcan/defconfig b/configs/nucleo-f303re/uavcan/defconfig index ee831187d6..6d7f1f9f03 100644 --- a/configs/nucleo-f303re/uavcan/defconfig +++ b/configs/nucleo-f303re/uavcan/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/nucleo-f334r8/adc/defconfig b/configs/nucleo-f334r8/adc/defconfig index 9a8481f516..8a50305c7b 100644 --- a/configs/nucleo-f334r8/adc/defconfig +++ b/configs/nucleo-f334r8/adc/defconfig @@ -153,7 +153,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/nucleo-f334r8/nsh/defconfig b/configs/nucleo-f334r8/nsh/defconfig index a3918af537..b41fa89e69 100644 --- a/configs/nucleo-f334r8/nsh/defconfig +++ b/configs/nucleo-f334r8/nsh/defconfig @@ -151,7 +151,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/nucleo-f4x1re/f401-nsh/defconfig b/configs/nucleo-f4x1re/f401-nsh/defconfig index 5a0c090de1..483c4074a2 100644 --- a/configs/nucleo-f4x1re/f401-nsh/defconfig +++ b/configs/nucleo-f4x1re/f401-nsh/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/nucleo-f4x1re/f411-nsh/defconfig b/configs/nucleo-f4x1re/f411-nsh/defconfig index 13e3a553fe..05a9151ea9 100644 --- a/configs/nucleo-f4x1re/f411-nsh/defconfig +++ b/configs/nucleo-f4x1re/f411-nsh/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/nucleo-l432kc/nsh/defconfig b/configs/nucleo-l432kc/nsh/defconfig index c8fae71740..ba0cb740ba 100644 --- a/configs/nucleo-l432kc/nsh/defconfig +++ b/configs/nucleo-l432kc/nsh/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32l4" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/nucleo-l452re/nsh/defconfig b/configs/nucleo-l452re/nsh/defconfig index b01b5c2356..f076feb63f 100644 --- a/configs/nucleo-l452re/nsh/defconfig +++ b/configs/nucleo-l452re/nsh/defconfig @@ -161,7 +161,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32l4" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/nucleo-l476rg/nsh/defconfig b/configs/nucleo-l476rg/nsh/defconfig index 80a8d83c9c..ea45b09938 100644 --- a/configs/nucleo-l476rg/nsh/defconfig +++ b/configs/nucleo-l476rg/nsh/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32l4" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/nucleo-l496zg/nsh/defconfig b/configs/nucleo-l496zg/nsh/defconfig index 34f924b27f..e2acced8f8 100644 --- a/configs/nucleo-l496zg/nsh/defconfig +++ b/configs/nucleo-l496zg/nsh/defconfig @@ -161,7 +161,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32l4" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/nutiny-nuc120/nsh/defconfig b/configs/nutiny-nuc120/nsh/defconfig index a2966eee96..be52dbd671 100644 --- a/configs/nutiny-nuc120/nsh/defconfig +++ b/configs/nutiny-nuc120/nsh/defconfig @@ -128,7 +128,6 @@ CONFIG_ARCH_CORTEXM0=y CONFIG_ARCH_FAMILY="armv6-m" CONFIG_ARCH_CHIP="nuc1xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set # CONFIG_ARMV7M_LAZYFPU is not set diff --git a/configs/olimex-efm32g880f128-stk/nsh/defconfig b/configs/olimex-efm32g880f128-stk/nsh/defconfig index 75527d42c7..7085701ec9 100644 --- a/configs/olimex-efm32g880f128-stk/nsh/defconfig +++ b/configs/olimex-efm32g880f128-stk/nsh/defconfig @@ -128,7 +128,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="efm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/olimex-lpc-h3131/nsh/defconfig b/configs/olimex-lpc-h3131/nsh/defconfig index 26a8a77162..d9e216fecf 100644 --- a/configs/olimex-lpc-h3131/nsh/defconfig +++ b/configs/olimex-lpc-h3131/nsh/defconfig @@ -128,7 +128,6 @@ CONFIG_ARCH_ARM926EJS=y CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="lpc31xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/olimex-lpc1766stk/ftpc/defconfig b/configs/olimex-lpc1766stk/ftpc/defconfig index a39d8ceacc..3726d1d81e 100644 --- a/configs/olimex-lpc1766stk/ftpc/defconfig +++ b/configs/olimex-lpc1766stk/ftpc/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-lpc1766stk/hidmouse/defconfig b/configs/olimex-lpc1766stk/hidmouse/defconfig index da29b55e98..1caa4aa30c 100644 --- a/configs/olimex-lpc1766stk/hidmouse/defconfig +++ b/configs/olimex-lpc1766stk/hidmouse/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-lpc1766stk/nettest/defconfig b/configs/olimex-lpc1766stk/nettest/defconfig index 20e9abafa1..e956880266 100644 --- a/configs/olimex-lpc1766stk/nettest/defconfig +++ b/configs/olimex-lpc1766stk/nettest/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-lpc1766stk/nsh/defconfig b/configs/olimex-lpc1766stk/nsh/defconfig index 44a0c97d2e..b5848d74a3 100644 --- a/configs/olimex-lpc1766stk/nsh/defconfig +++ b/configs/olimex-lpc1766stk/nsh/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-lpc1766stk/nx/defconfig b/configs/olimex-lpc1766stk/nx/defconfig index 5728b04b04..ad17276f38 100644 --- a/configs/olimex-lpc1766stk/nx/defconfig +++ b/configs/olimex-lpc1766stk/nx/defconfig @@ -128,7 +128,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-lpc1766stk/slip-httpd/defconfig b/configs/olimex-lpc1766stk/slip-httpd/defconfig index 04137cab7a..b2833ca2b2 100644 --- a/configs/olimex-lpc1766stk/slip-httpd/defconfig +++ b/configs/olimex-lpc1766stk/slip-httpd/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-lpc1766stk/thttpd-binfs/defconfig b/configs/olimex-lpc1766stk/thttpd-binfs/defconfig index 714ed7e341..d52c9fb0e4 100644 --- a/configs/olimex-lpc1766stk/thttpd-binfs/defconfig +++ b/configs/olimex-lpc1766stk/thttpd-binfs/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-lpc1766stk/thttpd-nxflat/defconfig b/configs/olimex-lpc1766stk/thttpd-nxflat/defconfig index bf1693614c..036163064a 100644 --- a/configs/olimex-lpc1766stk/thttpd-nxflat/defconfig +++ b/configs/olimex-lpc1766stk/thttpd-nxflat/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-lpc1766stk/usbmsc/defconfig b/configs/olimex-lpc1766stk/usbmsc/defconfig index 47fffba1f5..890d285c0f 100644 --- a/configs/olimex-lpc1766stk/usbmsc/defconfig +++ b/configs/olimex-lpc1766stk/usbmsc/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-lpc1766stk/usbserial/defconfig b/configs/olimex-lpc1766stk/usbserial/defconfig index 14ddc45c0b..8198a854c2 100644 --- a/configs/olimex-lpc1766stk/usbserial/defconfig +++ b/configs/olimex-lpc1766stk/usbserial/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-lpc1766stk/zmodem/defconfig b/configs/olimex-lpc1766stk/zmodem/defconfig index 4fdff449c1..07688ee8da 100644 --- a/configs/olimex-lpc1766stk/zmodem/defconfig +++ b/configs/olimex-lpc1766stk/zmodem/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-lpc2378/nsh/defconfig b/configs/olimex-lpc2378/nsh/defconfig index 7aa2abee46..e81825c9cd 100644 --- a/configs/olimex-lpc2378/nsh/defconfig +++ b/configs/olimex-lpc2378/nsh/defconfig @@ -122,7 +122,6 @@ CONFIG_ARCH_ARM7TDMI=y CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="lpc2378" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/olimex-stm32-e407/discover/defconfig b/configs/olimex-stm32-e407/discover/defconfig index a0f4c0ff34..14fe43cf1d 100644 --- a/configs/olimex-stm32-e407/discover/defconfig +++ b/configs/olimex-stm32-e407/discover/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-stm32-e407/netnsh/defconfig b/configs/olimex-stm32-e407/netnsh/defconfig index 3f03801630..025ce138b2 100644 --- a/configs/olimex-stm32-e407/netnsh/defconfig +++ b/configs/olimex-stm32-e407/netnsh/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-stm32-e407/nsh/defconfig b/configs/olimex-stm32-e407/nsh/defconfig index c9761c262b..599b9ed4c0 100644 --- a/configs/olimex-stm32-e407/nsh/defconfig +++ b/configs/olimex-stm32-e407/nsh/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-stm32-e407/telnetd/defconfig b/configs/olimex-stm32-e407/telnetd/defconfig index b110e20a11..29aa5cb615 100644 --- a/configs/olimex-stm32-e407/telnetd/defconfig +++ b/configs/olimex-stm32-e407/telnetd/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-stm32-e407/usbnsh/defconfig b/configs/olimex-stm32-e407/usbnsh/defconfig index 7c51b6e66a..5b106256e3 100644 --- a/configs/olimex-stm32-e407/usbnsh/defconfig +++ b/configs/olimex-stm32-e407/usbnsh/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-stm32-e407/webserver/defconfig b/configs/olimex-stm32-e407/webserver/defconfig index 8f74cb8be1..1dc4a81350 100644 --- a/configs/olimex-stm32-e407/webserver/defconfig +++ b/configs/olimex-stm32-e407/webserver/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-stm32-h405/usbnsh/defconfig b/configs/olimex-stm32-h405/usbnsh/defconfig index 12a579f044..d7b93c6f39 100644 --- a/configs/olimex-stm32-h405/usbnsh/defconfig +++ b/configs/olimex-stm32-h405/usbnsh/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-stm32-h407/nsh/defconfig b/configs/olimex-stm32-h407/nsh/defconfig index 0941dcadf8..5b7fc3953c 100644 --- a/configs/olimex-stm32-h407/nsh/defconfig +++ b/configs/olimex-stm32-h407/nsh/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-stm32-p107/nsh/defconfig b/configs/olimex-stm32-p107/nsh/defconfig index d6fdc7e496..31419f01d3 100644 --- a/configs/olimex-stm32-p107/nsh/defconfig +++ b/configs/olimex-stm32-p107/nsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-stm32-p207/nsh/defconfig b/configs/olimex-stm32-p207/nsh/defconfig index 16c37e7427..4d722560c9 100644 --- a/configs/olimex-stm32-p207/nsh/defconfig +++ b/configs/olimex-stm32-p207/nsh/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-stm32-p407/knsh/defconfig b/configs/olimex-stm32-p407/knsh/defconfig index eba898d922..6d16d46801 100644 --- a/configs/olimex-stm32-p407/knsh/defconfig +++ b/configs/olimex-stm32-p407/knsh/defconfig @@ -131,7 +131,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-stm32-p407/nsh/defconfig b/configs/olimex-stm32-p407/nsh/defconfig index 01d6cb9c0b..ba3df2081c 100644 --- a/configs/olimex-stm32-p407/nsh/defconfig +++ b/configs/olimex-stm32-p407/nsh/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-strp711/nettest/defconfig b/configs/olimex-strp711/nettest/defconfig index 4a23d44266..c674451e64 100644 --- a/configs/olimex-strp711/nettest/defconfig +++ b/configs/olimex-strp711/nettest/defconfig @@ -124,7 +124,6 @@ CONFIG_ARCH_ARM7TDMI=y CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="str71x" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/olimex-strp711/nsh/defconfig b/configs/olimex-strp711/nsh/defconfig index 84f66ba8c2..403c18d2d8 100644 --- a/configs/olimex-strp711/nsh/defconfig +++ b/configs/olimex-strp711/nsh/defconfig @@ -122,7 +122,6 @@ CONFIG_ARCH_ARM7TDMI=y CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="str71x" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/olimexino-stm32/can/defconfig b/configs/olimexino-stm32/can/defconfig index 4c0164e941..70af8286ac 100644 --- a/configs/olimexino-stm32/can/defconfig +++ b/configs/olimexino-stm32/can/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimexino-stm32/composite/defconfig b/configs/olimexino-stm32/composite/defconfig index 4d6f9915d6..7868baf421 100644 --- a/configs/olimexino-stm32/composite/defconfig +++ b/configs/olimexino-stm32/composite/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimexino-stm32/nsh/defconfig b/configs/olimexino-stm32/nsh/defconfig index 53eea4afe2..cbd0b1ee53 100644 --- a/configs/olimexino-stm32/nsh/defconfig +++ b/configs/olimexino-stm32/nsh/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimexino-stm32/smallnsh/defconfig b/configs/olimexino-stm32/smallnsh/defconfig index 622916d8c2..733b350a76 100644 --- a/configs/olimexino-stm32/smallnsh/defconfig +++ b/configs/olimexino-stm32/smallnsh/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimexino-stm32/tiny/defconfig b/configs/olimexino-stm32/tiny/defconfig index 11959d3f77..e9623a27c1 100644 --- a/configs/olimexino-stm32/tiny/defconfig +++ b/configs/olimexino-stm32/tiny/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/open1788/knsh/defconfig b/configs/open1788/knsh/defconfig index a4be59b062..d212c88d60 100644 --- a/configs/open1788/knsh/defconfig +++ b/configs/open1788/knsh/defconfig @@ -127,7 +127,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/open1788/nsh/defconfig b/configs/open1788/nsh/defconfig index bcfeb085de..e82b30e6fc 100644 --- a/configs/open1788/nsh/defconfig +++ b/configs/open1788/nsh/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/open1788/nxlines/defconfig b/configs/open1788/nxlines/defconfig index e419534665..03cbe946cf 100644 --- a/configs/open1788/nxlines/defconfig +++ b/configs/open1788/nxlines/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/pcduino-a10/nsh/defconfig b/configs/pcduino-a10/nsh/defconfig index b547394dfc..979c390657 100644 --- a/configs/pcduino-a10/nsh/defconfig +++ b/configs/pcduino-a10/nsh/defconfig @@ -131,7 +131,6 @@ CONFIG_ARCH_CORTEXA8=y CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="a1x" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/photon/nsh/defconfig b/configs/photon/nsh/defconfig index 67f2d12700..cc15facab1 100644 --- a/configs/photon/nsh/defconfig +++ b/configs/photon/nsh/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/photon/usbnsh/defconfig b/configs/photon/usbnsh/defconfig index 8050de9c8e..6ed65236de 100644 --- a/configs/photon/usbnsh/defconfig +++ b/configs/photon/usbnsh/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/photon/wlan/defconfig b/configs/photon/wlan/defconfig index 0aa452a9fe..a7343600a3 100644 --- a/configs/photon/wlan/defconfig +++ b/configs/photon/wlan/defconfig @@ -170,7 +170,6 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/sabre-6quad/nsh/defconfig b/configs/sabre-6quad/nsh/defconfig index fb5901f395..d1150487a1 100644 --- a/configs/sabre-6quad/nsh/defconfig +++ b/configs/sabre-6quad/nsh/defconfig @@ -131,7 +131,6 @@ CONFIG_ARCH_CORTEXA9=y CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="imx6" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sabre-6quad/smp/defconfig b/configs/sabre-6quad/smp/defconfig index c98713873a..aaa6ab6f57 100644 --- a/configs/sabre-6quad/smp/defconfig +++ b/configs/sabre-6quad/smp/defconfig @@ -131,7 +131,6 @@ CONFIG_ARCH_CORTEXA9=y CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="imx6" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sam3u-ek/knsh/defconfig b/configs/sam3u-ek/knsh/defconfig index 1bac14a860..957d6793f9 100644 --- a/configs/sam3u-ek/knsh/defconfig +++ b/configs/sam3u-ek/knsh/defconfig @@ -127,7 +127,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="sam34" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/sam3u-ek/nsh/defconfig b/configs/sam3u-ek/nsh/defconfig index 39d9271e1f..cb160f53f9 100644 --- a/configs/sam3u-ek/nsh/defconfig +++ b/configs/sam3u-ek/nsh/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="sam34" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/sam3u-ek/nx/defconfig b/configs/sam3u-ek/nx/defconfig index 836d29844c..e1b4343fea 100644 --- a/configs/sam3u-ek/nx/defconfig +++ b/configs/sam3u-ek/nx/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="sam34" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/sam3u-ek/nxwm/defconfig b/configs/sam3u-ek/nxwm/defconfig index 2f6d760377..1d52e79483 100644 --- a/configs/sam3u-ek/nxwm/defconfig +++ b/configs/sam3u-ek/nxwm/defconfig @@ -125,7 +125,6 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="sam34" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/sam4cmp-db/nsh/defconfig b/configs/sam4cmp-db/nsh/defconfig index c7e96c2425..d2668d7d97 100644 --- a/configs/sam4cmp-db/nsh/defconfig +++ b/configs/sam4cmp-db/nsh/defconfig @@ -151,7 +151,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="sam34" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/sam4e-ek/nsh/defconfig b/configs/sam4e-ek/nsh/defconfig index 7bbdf3723b..0304c87164 100644 --- a/configs/sam4e-ek/nsh/defconfig +++ b/configs/sam4e-ek/nsh/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="sam34" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/sam4e-ek/nxwm/defconfig b/configs/sam4e-ek/nxwm/defconfig index ca7322f492..de7f8e0ff7 100644 --- a/configs/sam4e-ek/nxwm/defconfig +++ b/configs/sam4e-ek/nxwm/defconfig @@ -125,7 +125,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="sam34" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/sam4e-ek/usbnsh/defconfig b/configs/sam4e-ek/usbnsh/defconfig index e8292655ca..bf1d810406 100644 --- a/configs/sam4e-ek/usbnsh/defconfig +++ b/configs/sam4e-ek/usbnsh/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="sam34" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/sam4l-xplained/nsh/defconfig b/configs/sam4l-xplained/nsh/defconfig index a5c734aa40..9e348834a9 100644 --- a/configs/sam4l-xplained/nsh/defconfig +++ b/configs/sam4l-xplained/nsh/defconfig @@ -125,7 +125,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="sam34" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/sam4s-xplained-pro/nsh/defconfig b/configs/sam4s-xplained-pro/nsh/defconfig index 1f60e17c36..7b457d4c1b 100644 --- a/configs/sam4s-xplained-pro/nsh/defconfig +++ b/configs/sam4s-xplained-pro/nsh/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="sam34" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/sam4s-xplained/nsh/defconfig b/configs/sam4s-xplained/nsh/defconfig index c59c5a0f8b..c65076ca53 100644 --- a/configs/sam4s-xplained/nsh/defconfig +++ b/configs/sam4s-xplained/nsh/defconfig @@ -125,7 +125,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="sam34" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/sama5d2-xult/nsh/defconfig b/configs/sama5d2-xult/nsh/defconfig index db65ee79d5..38b839251a 100644 --- a/configs/sama5d2-xult/nsh/defconfig +++ b/configs/sama5d2-xult/nsh/defconfig @@ -131,7 +131,6 @@ CONFIG_ARCH_CORTEXA5=y CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d3-xplained/bridge/defconfig b/configs/sama5d3-xplained/bridge/defconfig index c89f19ed61..1ea7843df9 100644 --- a/configs/sama5d3-xplained/bridge/defconfig +++ b/configs/sama5d3-xplained/bridge/defconfig @@ -131,7 +131,6 @@ CONFIG_ARCH_CORTEXA5=y CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d3-xplained/nsh/defconfig b/configs/sama5d3-xplained/nsh/defconfig index 4a7584dfbd..5ec73af6b2 100644 --- a/configs/sama5d3-xplained/nsh/defconfig +++ b/configs/sama5d3-xplained/nsh/defconfig @@ -131,7 +131,6 @@ CONFIG_ARCH_CORTEXA5=y CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d3x-ek/demo/defconfig b/configs/sama5d3x-ek/demo/defconfig index e7b781f1a7..cb022bfbf6 100644 --- a/configs/sama5d3x-ek/demo/defconfig +++ b/configs/sama5d3x-ek/demo/defconfig @@ -131,7 +131,6 @@ CONFIG_ARCH_CORTEXA5=y CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d3x-ek/hello/defconfig b/configs/sama5d3x-ek/hello/defconfig index db156cbd32..f50c4635f7 100644 --- a/configs/sama5d3x-ek/hello/defconfig +++ b/configs/sama5d3x-ek/hello/defconfig @@ -128,7 +128,7 @@ CONFIG_ARCH_CORTEXA5=y CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d3x-ek/norboot/defconfig b/configs/sama5d3x-ek/norboot/defconfig index 56ffd88c53..9cb9df10b0 100644 --- a/configs/sama5d3x-ek/norboot/defconfig +++ b/configs/sama5d3x-ek/norboot/defconfig @@ -128,7 +128,7 @@ CONFIG_ARCH_CORTEXA5=y CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d3x-ek/nsh/defconfig b/configs/sama5d3x-ek/nsh/defconfig index 6ed56ba51e..b93f5f7bd9 100644 --- a/configs/sama5d3x-ek/nsh/defconfig +++ b/configs/sama5d3x-ek/nsh/defconfig @@ -131,7 +131,6 @@ CONFIG_ARCH_CORTEXA5=y CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d3x-ek/nx/defconfig b/configs/sama5d3x-ek/nx/defconfig index 7c4fd0babb..ec4167e1f8 100644 --- a/configs/sama5d3x-ek/nx/defconfig +++ b/configs/sama5d3x-ek/nx/defconfig @@ -131,7 +131,6 @@ CONFIG_ARCH_CORTEXA5=y CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d3x-ek/nxplayer/defconfig b/configs/sama5d3x-ek/nxplayer/defconfig index bfac9ef93c..895711e473 100644 --- a/configs/sama5d3x-ek/nxplayer/defconfig +++ b/configs/sama5d3x-ek/nxplayer/defconfig @@ -131,7 +131,6 @@ CONFIG_ARCH_CORTEXA5=y CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d3x-ek/nxwm/defconfig b/configs/sama5d3x-ek/nxwm/defconfig index d3d488735c..7fde00d212 100644 --- a/configs/sama5d3x-ek/nxwm/defconfig +++ b/configs/sama5d3x-ek/nxwm/defconfig @@ -131,7 +131,6 @@ CONFIG_ARCH_CORTEXA5=y CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d3x-ek/ov2640/defconfig b/configs/sama5d3x-ek/ov2640/defconfig index 76c5dcf66d..8e347a5bbf 100644 --- a/configs/sama5d3x-ek/ov2640/defconfig +++ b/configs/sama5d3x-ek/ov2640/defconfig @@ -128,7 +128,7 @@ CONFIG_ARCH_CORTEXA5=y CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d4-ek/at25boot/defconfig b/configs/sama5d4-ek/at25boot/defconfig index e8a887220d..ee0cb7bcc0 100644 --- a/configs/sama5d4-ek/at25boot/defconfig +++ b/configs/sama5d4-ek/at25boot/defconfig @@ -131,7 +131,6 @@ CONFIG_ARCH_CORTEXA5=y CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d4-ek/bridge/defconfig b/configs/sama5d4-ek/bridge/defconfig index 9248a99e8c..f3d5a25f98 100644 --- a/configs/sama5d4-ek/bridge/defconfig +++ b/configs/sama5d4-ek/bridge/defconfig @@ -131,7 +131,6 @@ CONFIG_ARCH_CORTEXA5=y CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d4-ek/dramboot/defconfig b/configs/sama5d4-ek/dramboot/defconfig index 84ccf16d8b..eb434699a6 100644 --- a/configs/sama5d4-ek/dramboot/defconfig +++ b/configs/sama5d4-ek/dramboot/defconfig @@ -131,7 +131,6 @@ CONFIG_ARCH_CORTEXA5=y CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d4-ek/elf/defconfig b/configs/sama5d4-ek/elf/defconfig index 6b8363dbbb..18e83b0f28 100644 --- a/configs/sama5d4-ek/elf/defconfig +++ b/configs/sama5d4-ek/elf/defconfig @@ -132,7 +132,6 @@ CONFIG_ARCH_CORTEXA5=y CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d4-ek/ipv6/defconfig b/configs/sama5d4-ek/ipv6/defconfig index afe653afc8..a2e87c41a4 100644 --- a/configs/sama5d4-ek/ipv6/defconfig +++ b/configs/sama5d4-ek/ipv6/defconfig @@ -131,7 +131,6 @@ CONFIG_ARCH_CORTEXA5=y CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d4-ek/knsh/defconfig b/configs/sama5d4-ek/knsh/defconfig index 8731f0ebe9..405444e65e 100644 --- a/configs/sama5d4-ek/knsh/defconfig +++ b/configs/sama5d4-ek/knsh/defconfig @@ -131,7 +131,6 @@ CONFIG_ARCH_CORTEXA5=y CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d4-ek/nsh/defconfig b/configs/sama5d4-ek/nsh/defconfig index f25cb4b431..7e46c8e891 100644 --- a/configs/sama5d4-ek/nsh/defconfig +++ b/configs/sama5d4-ek/nsh/defconfig @@ -131,7 +131,6 @@ CONFIG_ARCH_CORTEXA5=y CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d4-ek/nxwm/defconfig b/configs/sama5d4-ek/nxwm/defconfig index 4690d35918..2f64e48067 100644 --- a/configs/sama5d4-ek/nxwm/defconfig +++ b/configs/sama5d4-ek/nxwm/defconfig @@ -131,7 +131,6 @@ CONFIG_ARCH_CORTEXA5=y CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d4-ek/ramtest/defconfig b/configs/sama5d4-ek/ramtest/defconfig index 44720daf54..eb0e9975c8 100644 --- a/configs/sama5d4-ek/ramtest/defconfig +++ b/configs/sama5d4-ek/ramtest/defconfig @@ -131,7 +131,6 @@ CONFIG_ARCH_CORTEXA5=y CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/samd20-xplained/nsh/defconfig b/configs/samd20-xplained/nsh/defconfig index f2fece4c3f..2698d1f26b 100644 --- a/configs/samd20-xplained/nsh/defconfig +++ b/configs/samd20-xplained/nsh/defconfig @@ -131,7 +131,6 @@ CONFIG_ARCH_CORTEXM0=y CONFIG_ARCH_FAMILY="armv6-m" CONFIG_ARCH_CHIP="samdl" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set # CONFIG_ARMV7M_LAZYFPU is not set diff --git a/configs/samd21-xplained/nsh/defconfig b/configs/samd21-xplained/nsh/defconfig index bfbf127c9e..2ca7f6cc7e 100644 --- a/configs/samd21-xplained/nsh/defconfig +++ b/configs/samd21-xplained/nsh/defconfig @@ -131,7 +131,6 @@ CONFIG_ARCH_CORTEXM0=y CONFIG_ARCH_FAMILY="armv6-m" CONFIG_ARCH_CHIP="samdl" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set # CONFIG_ARMV7M_LAZYFPU is not set diff --git a/configs/same70-xplained/netnsh/defconfig b/configs/same70-xplained/netnsh/defconfig index 45b670fc14..8551c2f5af 100644 --- a/configs/same70-xplained/netnsh/defconfig +++ b/configs/same70-xplained/netnsh/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXM7=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="samv7" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/same70-xplained/nsh/defconfig b/configs/same70-xplained/nsh/defconfig index 106f249814..34c5952009 100644 --- a/configs/same70-xplained/nsh/defconfig +++ b/configs/same70-xplained/nsh/defconfig @@ -128,7 +128,7 @@ CONFIG_ARCH_CORTEXM7=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="samv7" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/saml21-xplained/nsh/defconfig b/configs/saml21-xplained/nsh/defconfig index 17eff8509f..daeeadbcb9 100644 --- a/configs/saml21-xplained/nsh/defconfig +++ b/configs/saml21-xplained/nsh/defconfig @@ -131,7 +131,6 @@ CONFIG_ARCH_CORTEXM0=y CONFIG_ARCH_FAMILY="armv6-m" CONFIG_ARCH_CHIP="samdl" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set # CONFIG_ARMV7M_LAZYFPU is not set diff --git a/configs/samv71-xult/knsh/defconfig b/configs/samv71-xult/knsh/defconfig index c23bda38ee..9da3cefc30 100644 --- a/configs/samv71-xult/knsh/defconfig +++ b/configs/samv71-xult/knsh/defconfig @@ -133,7 +133,7 @@ CONFIG_ARCH_CORTEXM7=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="samv7" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/samv71-xult/module/defconfig b/configs/samv71-xult/module/defconfig index e4172937e3..5089cd6c51 100644 --- a/configs/samv71-xult/module/defconfig +++ b/configs/samv71-xult/module/defconfig @@ -128,7 +128,7 @@ CONFIG_ARCH_CORTEXM7=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="samv7" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/samv71-xult/mxtxplnd/defconfig b/configs/samv71-xult/mxtxplnd/defconfig index d34d7ffdac..9a75d142e9 100644 --- a/configs/samv71-xult/mxtxplnd/defconfig +++ b/configs/samv71-xult/mxtxplnd/defconfig @@ -128,7 +128,7 @@ CONFIG_ARCH_CORTEXM7=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="samv7" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/samv71-xult/netnsh/defconfig b/configs/samv71-xult/netnsh/defconfig index 2e59f382ba..9b1053f824 100644 --- a/configs/samv71-xult/netnsh/defconfig +++ b/configs/samv71-xult/netnsh/defconfig @@ -131,7 +131,7 @@ CONFIG_ARCH_CORTEXM7=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="samv7" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/samv71-xult/nsh/defconfig b/configs/samv71-xult/nsh/defconfig index 99e63b5e88..ff014cd174 100644 --- a/configs/samv71-xult/nsh/defconfig +++ b/configs/samv71-xult/nsh/defconfig @@ -128,7 +128,7 @@ CONFIG_ARCH_CORTEXM7=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="samv7" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/samv71-xult/nxwm/defconfig b/configs/samv71-xult/nxwm/defconfig index 0953e98bf0..4cbb4db7bf 100644 --- a/configs/samv71-xult/nxwm/defconfig +++ b/configs/samv71-xult/nxwm/defconfig @@ -131,7 +131,6 @@ CONFIG_ARCH_CORTEXM7=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="samv7" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/samv71-xult/vnc/defconfig b/configs/samv71-xult/vnc/defconfig index 58de7ce621..f915136f6d 100644 --- a/configs/samv71-xult/vnc/defconfig +++ b/configs/samv71-xult/vnc/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXM7=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="samv7" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/samv71-xult/vnxwm/defconfig b/configs/samv71-xult/vnxwm/defconfig index 8a0cb8029c..0203c8dbcc 100644 --- a/configs/samv71-xult/vnxwm/defconfig +++ b/configs/samv71-xult/vnxwm/defconfig @@ -131,7 +131,6 @@ CONFIG_ARCH_CORTEXM7=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="samv7" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/shenzhou/nsh/defconfig b/configs/shenzhou/nsh/defconfig index 8bd378dc89..c42f1f9c5b 100644 --- a/configs/shenzhou/nsh/defconfig +++ b/configs/shenzhou/nsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/shenzhou/nxwm/defconfig b/configs/shenzhou/nxwm/defconfig index 8136459843..16444b5295 100644 --- a/configs/shenzhou/nxwm/defconfig +++ b/configs/shenzhou/nxwm/defconfig @@ -132,7 +132,6 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/shenzhou/thttpd/defconfig b/configs/shenzhou/thttpd/defconfig index cb5aaf0458..df08fe16e2 100644 --- a/configs/shenzhou/thttpd/defconfig +++ b/configs/shenzhou/thttpd/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/spark/composite/defconfig b/configs/spark/composite/defconfig index 4c53bfb69f..ddfcc9aac7 100644 --- a/configs/spark/composite/defconfig +++ b/configs/spark/composite/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/spark/nsh/defconfig b/configs/spark/nsh/defconfig index 2768858395..a44e488a3f 100644 --- a/configs/spark/nsh/defconfig +++ b/configs/spark/nsh/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/spark/usbmsc/defconfig b/configs/spark/usbmsc/defconfig index bf8b9101fc..cf97cd3832 100644 --- a/configs/spark/usbmsc/defconfig +++ b/configs/spark/usbmsc/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/spark/usbnsh/defconfig b/configs/spark/usbnsh/defconfig index cb810ac38a..e6727e2d5d 100644 --- a/configs/spark/usbnsh/defconfig +++ b/configs/spark/usbnsh/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/spark/usbserial/defconfig b/configs/spark/usbserial/defconfig index c50bae0087..4be8fdeae3 100644 --- a/configs/spark/usbserial/defconfig +++ b/configs/spark/usbserial/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3210e-eval/composite/defconfig b/configs/stm3210e-eval/composite/defconfig index 7293f13d64..949b9d986d 100644 --- a/configs/stm3210e-eval/composite/defconfig +++ b/configs/stm3210e-eval/composite/defconfig @@ -129,7 +129,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3210e-eval/nsh/defconfig b/configs/stm3210e-eval/nsh/defconfig index de6c8fbada..b2de1b24a6 100644 --- a/configs/stm3210e-eval/nsh/defconfig +++ b/configs/stm3210e-eval/nsh/defconfig @@ -129,7 +129,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3210e-eval/nsh2/defconfig b/configs/stm3210e-eval/nsh2/defconfig index 846aceb4f8..785325e187 100644 --- a/configs/stm3210e-eval/nsh2/defconfig +++ b/configs/stm3210e-eval/nsh2/defconfig @@ -129,7 +129,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3210e-eval/nx/defconfig b/configs/stm3210e-eval/nx/defconfig index 72cffd064c..1c2caadb46 100644 --- a/configs/stm3210e-eval/nx/defconfig +++ b/configs/stm3210e-eval/nx/defconfig @@ -129,7 +129,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3210e-eval/nxterm/defconfig b/configs/stm3210e-eval/nxterm/defconfig index 2b7d5531d0..59e50dc2d5 100644 --- a/configs/stm3210e-eval/nxterm/defconfig +++ b/configs/stm3210e-eval/nxterm/defconfig @@ -129,7 +129,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3210e-eval/pm/defconfig b/configs/stm3210e-eval/pm/defconfig index 301b8afa07..36a1d96c0b 100644 --- a/configs/stm3210e-eval/pm/defconfig +++ b/configs/stm3210e-eval/pm/defconfig @@ -129,7 +129,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3210e-eval/usbmsc/defconfig b/configs/stm3210e-eval/usbmsc/defconfig index 62b5513ad4..487998ea6f 100644 --- a/configs/stm3210e-eval/usbmsc/defconfig +++ b/configs/stm3210e-eval/usbmsc/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3210e-eval/usbserial/defconfig b/configs/stm3210e-eval/usbserial/defconfig index 6506425af5..777dcca2b1 100644 --- a/configs/stm3210e-eval/usbserial/defconfig +++ b/configs/stm3210e-eval/usbserial/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3220g-eval/dhcpd/defconfig b/configs/stm3220g-eval/dhcpd/defconfig index 2771754291..160af24c19 100644 --- a/configs/stm3220g-eval/dhcpd/defconfig +++ b/configs/stm3220g-eval/dhcpd/defconfig @@ -132,7 +132,6 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3220g-eval/nettest/defconfig b/configs/stm3220g-eval/nettest/defconfig index 78726df3c1..79f91ed9c9 100644 --- a/configs/stm3220g-eval/nettest/defconfig +++ b/configs/stm3220g-eval/nettest/defconfig @@ -132,7 +132,6 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3220g-eval/nsh/defconfig b/configs/stm3220g-eval/nsh/defconfig index b64cbf7a36..5f77349013 100644 --- a/configs/stm3220g-eval/nsh/defconfig +++ b/configs/stm3220g-eval/nsh/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3220g-eval/nsh2/defconfig b/configs/stm3220g-eval/nsh2/defconfig index 439c8390c5..03e70710e6 100644 --- a/configs/stm3220g-eval/nsh2/defconfig +++ b/configs/stm3220g-eval/nsh2/defconfig @@ -132,7 +132,6 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3220g-eval/nxwm/defconfig b/configs/stm3220g-eval/nxwm/defconfig index 170b1cfa0e..a8289003d3 100644 --- a/configs/stm3220g-eval/nxwm/defconfig +++ b/configs/stm3220g-eval/nxwm/defconfig @@ -132,7 +132,6 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3220g-eval/telnetd/defconfig b/configs/stm3220g-eval/telnetd/defconfig index 53b2e42c7e..23207c48d3 100644 --- a/configs/stm3220g-eval/telnetd/defconfig +++ b/configs/stm3220g-eval/telnetd/defconfig @@ -132,7 +132,6 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3240g-eval/dhcpd/defconfig b/configs/stm3240g-eval/dhcpd/defconfig index 3685d5da3a..489af9d107 100644 --- a/configs/stm3240g-eval/dhcpd/defconfig +++ b/configs/stm3240g-eval/dhcpd/defconfig @@ -132,7 +132,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3240g-eval/discover/defconfig b/configs/stm3240g-eval/discover/defconfig index 7644480cc2..ff9492a797 100644 --- a/configs/stm3240g-eval/discover/defconfig +++ b/configs/stm3240g-eval/discover/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3240g-eval/knxwm/defconfig b/configs/stm3240g-eval/knxwm/defconfig index 8f8dbb1f0a..bedd01275c 100644 --- a/configs/stm3240g-eval/knxwm/defconfig +++ b/configs/stm3240g-eval/knxwm/defconfig @@ -137,7 +137,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3240g-eval/nettest/defconfig b/configs/stm3240g-eval/nettest/defconfig index 43f5d3cfae..74ee1bf174 100644 --- a/configs/stm3240g-eval/nettest/defconfig +++ b/configs/stm3240g-eval/nettest/defconfig @@ -132,7 +132,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3240g-eval/nsh/defconfig b/configs/stm3240g-eval/nsh/defconfig index b6e2403b4a..03fd25607c 100644 --- a/configs/stm3240g-eval/nsh/defconfig +++ b/configs/stm3240g-eval/nsh/defconfig @@ -132,7 +132,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3240g-eval/nsh2/defconfig b/configs/stm3240g-eval/nsh2/defconfig index 31b84e446f..5df0cbb4ae 100644 --- a/configs/stm3240g-eval/nsh2/defconfig +++ b/configs/stm3240g-eval/nsh2/defconfig @@ -132,7 +132,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3240g-eval/nxterm/defconfig b/configs/stm3240g-eval/nxterm/defconfig index d7cc5d4f73..c0091e5014 100644 --- a/configs/stm3240g-eval/nxterm/defconfig +++ b/configs/stm3240g-eval/nxterm/defconfig @@ -132,7 +132,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3240g-eval/nxwm/defconfig b/configs/stm3240g-eval/nxwm/defconfig index 3fc81f25e1..25302bfd13 100644 --- a/configs/stm3240g-eval/nxwm/defconfig +++ b/configs/stm3240g-eval/nxwm/defconfig @@ -132,7 +132,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3240g-eval/telnetd/defconfig b/configs/stm3240g-eval/telnetd/defconfig index edd1dbb11e..a61c0b9e53 100644 --- a/configs/stm3240g-eval/telnetd/defconfig +++ b/configs/stm3240g-eval/telnetd/defconfig @@ -132,7 +132,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3240g-eval/webserver/defconfig b/configs/stm3240g-eval/webserver/defconfig index 3c9e8c2530..c17a8808a7 100644 --- a/configs/stm3240g-eval/webserver/defconfig +++ b/configs/stm3240g-eval/webserver/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3240g-eval/xmlrpc/defconfig b/configs/stm3240g-eval/xmlrpc/defconfig index a88b63ae19..b305f8a0ec 100644 --- a/configs/stm3240g-eval/xmlrpc/defconfig +++ b/configs/stm3240g-eval/xmlrpc/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32_tiny/nsh/defconfig b/configs/stm32_tiny/nsh/defconfig index cb39c3b326..0fc0869f59 100644 --- a/configs/stm32_tiny/nsh/defconfig +++ b/configs/stm32_tiny/nsh/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32_tiny/usbnsh/defconfig b/configs/stm32_tiny/usbnsh/defconfig index 82b6a3f2fb..cf42fb77ab 100644 --- a/configs/stm32_tiny/usbnsh/defconfig +++ b/configs/stm32_tiny/usbnsh/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32butterfly2/nsh/defconfig b/configs/stm32butterfly2/nsh/defconfig index 9d8bc5eb15..af2ce5eaff 100644 --- a/configs/stm32butterfly2/nsh/defconfig +++ b/configs/stm32butterfly2/nsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32butterfly2/nshnet/defconfig b/configs/stm32butterfly2/nshnet/defconfig index 08cc2425c4..19f09b84d8 100644 --- a/configs/stm32butterfly2/nshnet/defconfig +++ b/configs/stm32butterfly2/nshnet/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32butterfly2/nshusbdev/defconfig b/configs/stm32butterfly2/nshusbdev/defconfig index 8fd69ba946..a7e8ea4682 100644 --- a/configs/stm32butterfly2/nshusbdev/defconfig +++ b/configs/stm32butterfly2/nshusbdev/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32butterfly2/nshusbhost/defconfig b/configs/stm32butterfly2/nshusbhost/defconfig index 9d8bc5eb15..af2ce5eaff 100644 --- a/configs/stm32butterfly2/nshusbhost/defconfig +++ b/configs/stm32butterfly2/nshusbhost/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f0discovery/nsh/defconfig b/configs/stm32f0discovery/nsh/defconfig index 6c34641ae8..2de0149b07 100644 --- a/configs/stm32f0discovery/nsh/defconfig +++ b/configs/stm32f0discovery/nsh/defconfig @@ -124,7 +124,6 @@ CONFIG_ARCH_CORTEXM0=y CONFIG_ARCH_FAMILY="armv6-m" CONFIG_ARCH_CHIP="stm32f0" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set # CONFIG_ARMV7M_LAZYFPU is not set diff --git a/configs/stm32f103-minimum/audio_tone/defconfig b/configs/stm32f103-minimum/audio_tone/defconfig index 18a2d09978..b1aaff58c7 100644 --- a/configs/stm32f103-minimum/audio_tone/defconfig +++ b/configs/stm32f103-minimum/audio_tone/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f103-minimum/buttons/defconfig b/configs/stm32f103-minimum/buttons/defconfig index 0312f7554b..9df3702195 100644 --- a/configs/stm32f103-minimum/buttons/defconfig +++ b/configs/stm32f103-minimum/buttons/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f103-minimum/jlx12864g/defconfig b/configs/stm32f103-minimum/jlx12864g/defconfig index 4a8569c328..6e2609d3de 100644 --- a/configs/stm32f103-minimum/jlx12864g/defconfig +++ b/configs/stm32f103-minimum/jlx12864g/defconfig @@ -158,7 +158,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f103-minimum/nrf24/defconfig b/configs/stm32f103-minimum/nrf24/defconfig index a13598ba74..e4f64d8a78 100644 --- a/configs/stm32f103-minimum/nrf24/defconfig +++ b/configs/stm32f103-minimum/nrf24/defconfig @@ -154,7 +154,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f103-minimum/nsh/defconfig b/configs/stm32f103-minimum/nsh/defconfig index 7664d88825..22a2e0f4c5 100644 --- a/configs/stm32f103-minimum/nsh/defconfig +++ b/configs/stm32f103-minimum/nsh/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f103-minimum/pwm/defconfig b/configs/stm32f103-minimum/pwm/defconfig index d8b9bc38da..866f13a871 100644 --- a/configs/stm32f103-minimum/pwm/defconfig +++ b/configs/stm32f103-minimum/pwm/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f103-minimum/rfid-rc522/defconfig b/configs/stm32f103-minimum/rfid-rc522/defconfig index a8daaf44f6..a37fd7fc97 100644 --- a/configs/stm32f103-minimum/rfid-rc522/defconfig +++ b/configs/stm32f103-minimum/rfid-rc522/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f103-minimum/rgbled/defconfig b/configs/stm32f103-minimum/rgbled/defconfig index bae4f13a9f..ee2a4acaf8 100644 --- a/configs/stm32f103-minimum/rgbled/defconfig +++ b/configs/stm32f103-minimum/rgbled/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f103-minimum/usbnsh/defconfig b/configs/stm32f103-minimum/usbnsh/defconfig index 312a2e8505..7df553e8f2 100644 --- a/configs/stm32f103-minimum/usbnsh/defconfig +++ b/configs/stm32f103-minimum/usbnsh/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f103-minimum/userled/defconfig b/configs/stm32f103-minimum/userled/defconfig index d49398b75d..e2a5fb92e2 100644 --- a/configs/stm32f103-minimum/userled/defconfig +++ b/configs/stm32f103-minimum/userled/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f103-minimum/veml6070/defconfig b/configs/stm32f103-minimum/veml6070/defconfig index 3d2065e1fa..feccccdff7 100644 --- a/configs/stm32f103-minimum/veml6070/defconfig +++ b/configs/stm32f103-minimum/veml6070/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f3discovery/nsh/defconfig b/configs/stm32f3discovery/nsh/defconfig index a39d117485..c653d03d9b 100644 --- a/configs/stm32f3discovery/nsh/defconfig +++ b/configs/stm32f3discovery/nsh/defconfig @@ -132,7 +132,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f3discovery/usbnsh/defconfig b/configs/stm32f3discovery/usbnsh/defconfig index 5ddb409c8a..6be7f12386 100644 --- a/configs/stm32f3discovery/usbnsh/defconfig +++ b/configs/stm32f3discovery/usbnsh/defconfig @@ -132,7 +132,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f411e-disco/nsh/defconfig b/configs/stm32f411e-disco/nsh/defconfig index da44560a90..9686d0eb47 100644 --- a/configs/stm32f411e-disco/nsh/defconfig +++ b/configs/stm32f411e-disco/nsh/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f429i-disco/extflash/defconfig b/configs/stm32f429i-disco/extflash/defconfig index bbca59a2f8..72f0cb1103 100644 --- a/configs/stm32f429i-disco/extflash/defconfig +++ b/configs/stm32f429i-disco/extflash/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f429i-disco/lcd/defconfig b/configs/stm32f429i-disco/lcd/defconfig index 40f7f3cb77..0b1afd96f3 100644 --- a/configs/stm32f429i-disco/lcd/defconfig +++ b/configs/stm32f429i-disco/lcd/defconfig @@ -127,7 +127,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f429i-disco/ltdc/defconfig b/configs/stm32f429i-disco/ltdc/defconfig index bfbad09b9e..b37b090ad9 100644 --- a/configs/stm32f429i-disco/ltdc/defconfig +++ b/configs/stm32f429i-disco/ltdc/defconfig @@ -127,7 +127,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f429i-disco/nsh/defconfig b/configs/stm32f429i-disco/nsh/defconfig index f8a7096efd..6a557ca398 100644 --- a/configs/stm32f429i-disco/nsh/defconfig +++ b/configs/stm32f429i-disco/nsh/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f429i-disco/nxwm/defconfig b/configs/stm32f429i-disco/nxwm/defconfig index b161e8af4a..9f23c31269 100644 --- a/configs/stm32f429i-disco/nxwm/defconfig +++ b/configs/stm32f429i-disco/nxwm/defconfig @@ -127,7 +127,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f429i-disco/usbmsc/defconfig b/configs/stm32f429i-disco/usbmsc/defconfig index 1707faa7de..41f8d4a71f 100644 --- a/configs/stm32f429i-disco/usbmsc/defconfig +++ b/configs/stm32f429i-disco/usbmsc/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f429i-disco/usbnsh/defconfig b/configs/stm32f429i-disco/usbnsh/defconfig index bc4c70dec6..6a1151e902 100644 --- a/configs/stm32f429i-disco/usbnsh/defconfig +++ b/configs/stm32f429i-disco/usbnsh/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f4discovery/canard/defconfig b/configs/stm32f4discovery/canard/defconfig index 8a34f9a42b..a749dd7184 100644 --- a/configs/stm32f4discovery/canard/defconfig +++ b/configs/stm32f4discovery/canard/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f4discovery/cxxtest/defconfig b/configs/stm32f4discovery/cxxtest/defconfig index fb1f67612f..311c6b7bef 100644 --- a/configs/stm32f4discovery/cxxtest/defconfig +++ b/configs/stm32f4discovery/cxxtest/defconfig @@ -132,7 +132,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f4discovery/elf/defconfig b/configs/stm32f4discovery/elf/defconfig index 332126c7c7..9a207fd361 100644 --- a/configs/stm32f4discovery/elf/defconfig +++ b/configs/stm32f4discovery/elf/defconfig @@ -129,7 +129,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f4discovery/ipv6/defconfig b/configs/stm32f4discovery/ipv6/defconfig index d860767e3e..fef1a68da4 100644 --- a/configs/stm32f4discovery/ipv6/defconfig +++ b/configs/stm32f4discovery/ipv6/defconfig @@ -132,7 +132,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f4discovery/kostest/defconfig b/configs/stm32f4discovery/kostest/defconfig index 0f4e7f2882..b61b1b9266 100644 --- a/configs/stm32f4discovery/kostest/defconfig +++ b/configs/stm32f4discovery/kostest/defconfig @@ -134,7 +134,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f4discovery/netnsh/defconfig b/configs/stm32f4discovery/netnsh/defconfig index 73c893e58a..c83039d231 100644 --- a/configs/stm32f4discovery/netnsh/defconfig +++ b/configs/stm32f4discovery/netnsh/defconfig @@ -132,7 +132,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f4discovery/nsh/defconfig b/configs/stm32f4discovery/nsh/defconfig index fb476819e8..512b380bc3 100644 --- a/configs/stm32f4discovery/nsh/defconfig +++ b/configs/stm32f4discovery/nsh/defconfig @@ -132,7 +132,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f4discovery/nxlines/defconfig b/configs/stm32f4discovery/nxlines/defconfig index 00bc8ce335..74e43686b3 100644 --- a/configs/stm32f4discovery/nxlines/defconfig +++ b/configs/stm32f4discovery/nxlines/defconfig @@ -132,7 +132,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f4discovery/pm/defconfig b/configs/stm32f4discovery/pm/defconfig index 60084550d8..09c3cd9844 100644 --- a/configs/stm32f4discovery/pm/defconfig +++ b/configs/stm32f4discovery/pm/defconfig @@ -132,7 +132,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f4discovery/posix_spawn/defconfig b/configs/stm32f4discovery/posix_spawn/defconfig index 1c8d37ccdd..66c4784a2c 100644 --- a/configs/stm32f4discovery/posix_spawn/defconfig +++ b/configs/stm32f4discovery/posix_spawn/defconfig @@ -129,7 +129,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f4discovery/pseudoterm/defconfig b/configs/stm32f4discovery/pseudoterm/defconfig index f07e6f5639..97133261f9 100644 --- a/configs/stm32f4discovery/pseudoterm/defconfig +++ b/configs/stm32f4discovery/pseudoterm/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f4discovery/rgbled/defconfig b/configs/stm32f4discovery/rgbled/defconfig index ddecfe7d27..8388526708 100644 --- a/configs/stm32f4discovery/rgbled/defconfig +++ b/configs/stm32f4discovery/rgbled/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f4discovery/uavcan/defconfig b/configs/stm32f4discovery/uavcan/defconfig index 6fc7f915d2..faf7a59692 100644 --- a/configs/stm32f4discovery/uavcan/defconfig +++ b/configs/stm32f4discovery/uavcan/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f4discovery/usbnsh/defconfig b/configs/stm32f4discovery/usbnsh/defconfig index f5c9f5d7ab..69afe5c0f0 100644 --- a/configs/stm32f4discovery/usbnsh/defconfig +++ b/configs/stm32f4discovery/usbnsh/defconfig @@ -132,7 +132,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f4discovery/winbuild/defconfig b/configs/stm32f4discovery/winbuild/defconfig index db8d26e2ff..0deb8cd65b 100644 --- a/configs/stm32f4discovery/winbuild/defconfig +++ b/configs/stm32f4discovery/winbuild/defconfig @@ -108,7 +108,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXA8 is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f4discovery/xen1210/defconfig b/configs/stm32f4discovery/xen1210/defconfig index 1a29b5fba6..4cb55120be 100644 --- a/configs/stm32f4discovery/xen1210/defconfig +++ b/configs/stm32f4discovery/xen1210/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f746-ws/nsh/defconfig b/configs/stm32f746-ws/nsh/defconfig index 80f7526520..78a78b6b6d 100644 --- a/configs/stm32f746-ws/nsh/defconfig +++ b/configs/stm32f746-ws/nsh/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM7=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32f7" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/stm32f746g-disco/nsh/defconfig b/configs/stm32f746g-disco/nsh/defconfig index 190d776f42..44de2fce8e 100644 --- a/configs/stm32f746g-disco/nsh/defconfig +++ b/configs/stm32f746g-disco/nsh/defconfig @@ -132,7 +132,6 @@ CONFIG_ARCH_CORTEXM7=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32f7" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/stm32l476-mdk/nsh/defconfig b/configs/stm32l476-mdk/nsh/defconfig index a529cb5fbf..b2fa084959 100644 --- a/configs/stm32l476-mdk/nsh/defconfig +++ b/configs/stm32l476-mdk/nsh/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32l4" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/stm32l476vg-disco/nsh/defconfig b/configs/stm32l476vg-disco/nsh/defconfig index fcb84c92cc..271fa59a8a 100644 --- a/configs/stm32l476vg-disco/nsh/defconfig +++ b/configs/stm32l476vg-disco/nsh/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32l4" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/stm32ldiscovery/nsh/defconfig b/configs/stm32ldiscovery/nsh/defconfig index 9c226c4dd4..b232b87651 100644 --- a/configs/stm32ldiscovery/nsh/defconfig +++ b/configs/stm32ldiscovery/nsh/defconfig @@ -129,7 +129,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32vldiscovery/nsh/defconfig b/configs/stm32vldiscovery/nsh/defconfig index d838755522..dae7c1499f 100644 --- a/configs/stm32vldiscovery/nsh/defconfig +++ b/configs/stm32vldiscovery/nsh/defconfig @@ -129,7 +129,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/teensy-3.x/nsh/defconfig b/configs/teensy-3.x/nsh/defconfig index ce5428eb7e..b25f07cda7 100644 --- a/configs/teensy-3.x/nsh/defconfig +++ b/configs/teensy-3.x/nsh/defconfig @@ -128,7 +128,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="kinetis" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/teensy-3.x/usbnsh/defconfig b/configs/teensy-3.x/usbnsh/defconfig index b8d5a1086b..20c9140b35 100644 --- a/configs/teensy-3.x/usbnsh/defconfig +++ b/configs/teensy-3.x/usbnsh/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="kinetis" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/teensy-lc/nsh/defconfig b/configs/teensy-lc/nsh/defconfig index 15e83500b8..869e6ffda4 100644 --- a/configs/teensy-lc/nsh/defconfig +++ b/configs/teensy-lc/nsh/defconfig @@ -126,7 +126,6 @@ CONFIG_ARCH_CORTEXM0=y CONFIG_ARCH_FAMILY="armv6-m" CONFIG_ARCH_CHIP="kl" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set # CONFIG_ARMV7M_LAZYFPU is not set diff --git a/configs/tm4c123g-launchpad/nsh/defconfig b/configs/tm4c123g-launchpad/nsh/defconfig index b617f84f4a..3de4f3483a 100644 --- a/configs/tm4c123g-launchpad/nsh/defconfig +++ b/configs/tm4c123g-launchpad/nsh/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/tm4c1294-launchpad/ipv6/defconfig b/configs/tm4c1294-launchpad/ipv6/defconfig index 422e5b40be..18fcdb5a44 100644 --- a/configs/tm4c1294-launchpad/ipv6/defconfig +++ b/configs/tm4c1294-launchpad/ipv6/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/tm4c1294-launchpad/nsh/defconfig b/configs/tm4c1294-launchpad/nsh/defconfig index 7ce75c3e86..5b43f5a0b3 100644 --- a/configs/tm4c1294-launchpad/nsh/defconfig +++ b/configs/tm4c1294-launchpad/nsh/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/twr-k60n512/nsh/defconfig b/configs/twr-k60n512/nsh/defconfig index f4b6bf7f5e..97c292fa10 100644 --- a/configs/twr-k60n512/nsh/defconfig +++ b/configs/twr-k60n512/nsh/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="kinetis" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/twr-k64f120m/netnsh/defconfig b/configs/twr-k64f120m/netnsh/defconfig index ead54aade6..c21f3e406d 100644 --- a/configs/twr-k64f120m/netnsh/defconfig +++ b/configs/twr-k64f120m/netnsh/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="kinetis" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/twr-k64f120m/nsh/defconfig b/configs/twr-k64f120m/nsh/defconfig index 911905fe7c..79b091ba48 100644 --- a/configs/twr-k64f120m/nsh/defconfig +++ b/configs/twr-k64f120m/nsh/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="kinetis" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/u-blox-c027/nsh/defconfig b/configs/u-blox-c027/nsh/defconfig index 68b549e9f6..b86c883a7e 100644 --- a/configs/u-blox-c027/nsh/defconfig +++ b/configs/u-blox-c027/nsh/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/viewtool-stm32f107/highpri/defconfig b/configs/viewtool-stm32f107/highpri/defconfig index a77a31403d..8bd3da10e6 100644 --- a/configs/viewtool-stm32f107/highpri/defconfig +++ b/configs/viewtool-stm32f107/highpri/defconfig @@ -129,7 +129,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/viewtool-stm32f107/netnsh/defconfig b/configs/viewtool-stm32f107/netnsh/defconfig index e422e035c8..e8b3aa5884 100644 --- a/configs/viewtool-stm32f107/netnsh/defconfig +++ b/configs/viewtool-stm32f107/netnsh/defconfig @@ -131,7 +131,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/viewtool-stm32f107/nsh/defconfig b/configs/viewtool-stm32f107/nsh/defconfig index d1231a7b2b..84a800c995 100644 --- a/configs/viewtool-stm32f107/nsh/defconfig +++ b/configs/viewtool-stm32f107/nsh/defconfig @@ -129,7 +129,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/xmc4500-relax/nsh/defconfig b/configs/xmc4500-relax/nsh/defconfig index c6b5a1761b..517820a864 100644 --- a/configs/xmc4500-relax/nsh/defconfig +++ b/configs/xmc4500-relax/nsh/defconfig @@ -129,7 +129,7 @@ CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="xmc4" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/zkit-arm-1769/hello/defconfig b/configs/zkit-arm-1769/hello/defconfig index aee6780233..f641d6ca31 100644 --- a/configs/zkit-arm-1769/hello/defconfig +++ b/configs/zkit-arm-1769/hello/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/zkit-arm-1769/nsh/defconfig b/configs/zkit-arm-1769/nsh/defconfig index 7f6021ea8e..684cbdb20e 100644 --- a/configs/zkit-arm-1769/nsh/defconfig +++ b/configs/zkit-arm-1769/nsh/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/zkit-arm-1769/nxhello/defconfig b/configs/zkit-arm-1769/nxhello/defconfig index 372619e563..acd07157a0 100644 --- a/configs/zkit-arm-1769/nxhello/defconfig +++ b/configs/zkit-arm-1769/nxhello/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/zkit-arm-1769/thttpd/defconfig b/configs/zkit-arm-1769/thttpd/defconfig index 0866830194..6529e993a1 100644 --- a/configs/zkit-arm-1769/thttpd/defconfig +++ b/configs/zkit-arm-1769/thttpd/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" # CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/zp214xpa/nsh/defconfig b/configs/zp214xpa/nsh/defconfig index 10176fb054..427e4093ee 100644 --- a/configs/zp214xpa/nsh/defconfig +++ b/configs/zp214xpa/nsh/defconfig @@ -122,7 +122,6 @@ CONFIG_ARCH_ARM7TDMI=y CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="lpc214x" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/zp214xpa/nxlines/defconfig b/configs/zp214xpa/nxlines/defconfig index 49360faa84..d7ba60feaa 100644 --- a/configs/zp214xpa/nxlines/defconfig +++ b/configs/zp214xpa/nxlines/defconfig @@ -122,7 +122,6 @@ CONFIG_ARCH_ARM7TDMI=y CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="lpc214x" # CONFIG_ARM_TOOLCHAIN_IAR is not set -# CONFIG_ARM_TOOLCHAIN_GNU is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/libc/machine/arm/armv7-a/Kconfig b/libc/machine/arm/armv7-a/Kconfig index 7a216e711c..64a769aa96 100644 --- a/libc/machine/arm/armv7-a/Kconfig +++ b/libc/machine/arm/armv7-a/Kconfig @@ -6,6 +6,6 @@ config ARMV7A_MEMCPY bool "Enable optimized memcpy() for ARMv7-A" select LIBC_ARCH_MEMCPY - depends on ARM_TOOLCHAIN_GNU + depends on ARCH_TOOLCHAIN_GNU ---help--- Enable optimized ARMv7-A specific memcpy() library function diff --git a/libc/machine/arm/armv7-m/Kconfig b/libc/machine/arm/armv7-m/Kconfig index 7148c25c4b..a95e6f5a14 100644 --- a/libc/machine/arm/armv7-m/Kconfig +++ b/libc/machine/arm/armv7-m/Kconfig @@ -6,6 +6,6 @@ config ARMV7M_MEMCPY bool "Enable optimized memcpy() for ARMv7-M" select LIBC_ARCH_MEMCPY - depends on ARM_TOOLCHAIN_GNU + depends on ARCH_TOOLCHAIN_GNU ---help--- Enable optimized ARMv7-M specific memcpy() library function diff --git a/libc/machine/arm/armv7-r/Kconfig b/libc/machine/arm/armv7-r/Kconfig index e772a2942d..881d8646fc 100644 --- a/libc/machine/arm/armv7-r/Kconfig +++ b/libc/machine/arm/armv7-r/Kconfig @@ -6,6 +6,6 @@ config ARMV7R_MEMCPY bool "Enable optimized memcpy() for ARMv7-R" select LIBC_ARCH_MEMCPY - depends on ARM_TOOLCHAIN_GNU + depends on ARCH_TOOLCHAIN_GNU ---help--- Enable optimized ARMv7-R specific memcpy() library function diff --git a/tools/testbuild.sh b/tools/testbuild.sh index e0ceb13bb1..7e67b06137 100755 --- a/tools/testbuild.sh +++ b/tools/testbuild.sh @@ -212,7 +212,7 @@ function configure { fi if [ "X$toolchain" != "X" ]; then - setting=`grep TOOLCHAIN $nuttx/.config | grep -v CONFIG_ARM_TOOLCHAIN_GNU=y | grep =y` + setting=`grep TOOLCHAIN $nuttx/.config | grep -v CONFIG_ARCH_TOOLCHAIN_GNU=y | grep =y` varname=`echo $setting | cut -d'=' -f1` if [ ! -z "varname" ]; then echo " Disabling $varname" -- GitLab From 27805315f488195a10feddc852015a5c6253ad63 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 13 May 2017 14:01:42 -0600 Subject: [PATCH 808/990] Tiva I2C: Correct an in conditional compilation --- arch/arm/src/tiva/tiva_i2c.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/arch/arm/src/tiva/tiva_i2c.c b/arch/arm/src/tiva/tiva_i2c.c index 86bea9cef6..6cc2d5fbe1 100644 --- a/arch/arm/src/tiva/tiva_i2c.c +++ b/arch/arm/src/tiva/tiva_i2c.c @@ -1,7 +1,7 @@ /************************************************************************************ * arch/arm/src/tiva/tiva_i2c.c * - * Copyright (C) 2014-2016 Gregory Nutt. All rights reserved. + * Copyright (C) 2014-2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * The basic structure of this driver derives in spirit (if nothing more) from the @@ -1378,7 +1378,7 @@ static int tiva_i2c_process(struct tiva_i2c_priv_s *priv, uint32_t status) * ************************************************************************************/ -#if !defined(CONFIG_I2C_POLLED) && defined(CONFIG_TIVA_I2C0) +#ifndef CONFIG_I2C_POLLED static int tiva_i2c_interrupt(int irq, void *context, void *arg) { struct tiva_i2c_priv_s *priv = (struct tiva_i2c_priv_s *)arg; -- GitLab From b0fda33e1382cbfa7edd16b18cd2f2591cb123f0 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 13 May 2017 16:01:38 -0600 Subject: [PATCH 809/990] Kconfig: Rename CONFIG_ARM_TOOLCHAIN_IAR to CONFIG_ARCH_TOOLCHAIN_IAR --- arch/Kconfig | 4 ++++ arch/arm/Kconfig | 4 ---- arch/arm/src/Makefile | 2 +- arch/arm/src/armv7-m/Kconfig | 4 ++-- configs/arduino-due/nsh/defconfig | 2 +- configs/bambino-200e/netnsh/defconfig | 2 +- configs/bambino-200e/nsh/defconfig | 2 +- configs/bambino-200e/usbnsh/defconfig | 2 +- configs/c5471evm/httpd/defconfig | 2 +- configs/c5471evm/nettest/defconfig | 2 +- configs/c5471evm/nsh/defconfig | 2 +- configs/cc3200-launchpad/nsh/defconfig | 2 +- configs/clicker2-stm32/knsh/defconfig | 2 +- configs/clicker2-stm32/mrf24j40-radio/defconfig | 2 +- configs/clicker2-stm32/nsh/defconfig | 2 +- configs/clicker2-stm32/usbnsh/defconfig | 2 +- configs/cloudctrl/nsh/defconfig | 2 +- configs/dk-tm4c129x/ipv6/defconfig | 2 +- configs/dk-tm4c129x/nsh/defconfig | 2 +- configs/ea3131/nsh/defconfig | 2 +- configs/ea3131/pgnsh/defconfig | 2 +- configs/ea3131/usbserial/defconfig | 2 +- configs/ea3152/ostest/defconfig | 2 +- configs/eagle100/httpd/defconfig | 2 +- configs/eagle100/nettest/defconfig | 2 +- configs/eagle100/nsh/defconfig | 2 +- configs/eagle100/nxflat/defconfig | 2 +- configs/eagle100/thttpd/defconfig | 2 +- configs/efm32-g8xx-stk/nsh/defconfig | 2 +- configs/efm32gg-stk3700/nsh/defconfig | 2 +- configs/ekk-lm3s9b96/nsh/defconfig | 2 +- configs/fire-stm32v2/nsh/defconfig | 2 +- configs/freedom-k64f/netnsh/defconfig | 2 +- configs/freedom-k64f/nsh/defconfig | 2 +- configs/freedom-k66f/netnsh/defconfig | 2 +- configs/freedom-k66f/nsh/defconfig | 2 +- configs/freedom-kl25z/nsh/defconfig | 2 +- configs/freedom-kl26z/nsh/defconfig | 2 +- configs/hymini-stm32v/nsh/defconfig | 2 +- configs/hymini-stm32v/nsh2/defconfig | 2 +- configs/hymini-stm32v/usbmsc/defconfig | 2 +- configs/hymini-stm32v/usbnsh/defconfig | 2 +- configs/hymini-stm32v/usbserial/defconfig | 2 +- configs/kwikstik-k40/ostest/defconfig | 2 +- configs/launchxl-tms57004/nsh/defconfig | 2 +- configs/lincoln60/netnsh/defconfig | 2 +- configs/lincoln60/nsh/defconfig | 2 +- configs/lincoln60/thttpd-binfs/defconfig | 2 +- configs/lm3s6432-s2e/nsh/defconfig | 2 +- configs/lm3s6965-ek/discover/defconfig | 2 +- configs/lm3s6965-ek/nsh/defconfig | 2 +- configs/lm3s6965-ek/nx/defconfig | 2 +- configs/lm3s6965-ek/tcpecho/defconfig | 2 +- configs/lm3s8962-ek/nsh/defconfig | 2 +- configs/lm3s8962-ek/nx/defconfig | 2 +- configs/lm4f120-launchpad/nsh/defconfig | 2 +- configs/lpc4330-xplorer/nsh/defconfig | 2 +- configs/lpc4337-ws/nsh/defconfig | 2 +- configs/lpc4357-evb/nsh/defconfig | 2 +- configs/lpc4370-link2/nsh/defconfig | 2 +- configs/lpcxpresso-lpc1115/nsh/defconfig | 2 +- configs/lpcxpresso-lpc1768/dhcpd/defconfig | 2 +- configs/lpcxpresso-lpc1768/nsh/defconfig | 2 +- configs/lpcxpresso-lpc1768/nx/defconfig | 2 +- configs/lpcxpresso-lpc1768/thttpd/defconfig | 2 +- configs/lpcxpresso-lpc1768/usbmsc/defconfig | 2 +- configs/maple/nsh/defconfig | 2 +- configs/maple/nx/defconfig | 2 +- configs/maple/usbnsh/defconfig | 2 +- configs/mbed/nsh/defconfig | 2 +- configs/mcu123-lpc214x/composite/defconfig | 2 +- configs/mcu123-lpc214x/nsh/defconfig | 2 +- configs/mcu123-lpc214x/usbmsc/defconfig | 2 +- configs/mcu123-lpc214x/usbserial/defconfig | 2 +- configs/mikroe-stm32f4/fulldemo/defconfig | 2 +- configs/mikroe-stm32f4/kostest/defconfig | 2 +- configs/mikroe-stm32f4/nsh/defconfig | 2 +- configs/mikroe-stm32f4/nx/defconfig | 2 +- configs/mikroe-stm32f4/nxlines/defconfig | 2 +- configs/mikroe-stm32f4/nxtext/defconfig | 2 +- configs/mikroe-stm32f4/usbnsh/defconfig | 2 +- configs/moxa/nsh/defconfig | 2 +- configs/mx1ads/ostest/defconfig | 2 +- configs/ntosd-dm320/nettest/defconfig | 2 +- configs/ntosd-dm320/nsh/defconfig | 2 +- configs/ntosd-dm320/poll/defconfig | 2 +- configs/ntosd-dm320/thttpd/defconfig | 2 +- configs/ntosd-dm320/udp/defconfig | 2 +- configs/ntosd-dm320/webserver/defconfig | 2 +- configs/nucleo-144/f746-evalos/defconfig | 2 +- configs/nucleo-144/f746-nsh/defconfig | 2 +- configs/nucleo-144/f767-evalos/defconfig | 2 +- configs/nucleo-144/f767-nsh/defconfig | 2 +- configs/nucleo-f072rb/nsh/defconfig | 2 +- configs/nucleo-f091rc/nsh/defconfig | 2 +- configs/nucleo-f303re/adc/defconfig | 2 +- configs/nucleo-f303re/can/defconfig | 2 +- configs/nucleo-f303re/hello/defconfig | 2 +- configs/nucleo-f303re/nxlines/defconfig | 2 +- configs/nucleo-f303re/pwm/defconfig | 2 +- configs/nucleo-f303re/serialrx/defconfig | 2 +- configs/nucleo-f303re/uavcan/defconfig | 2 +- configs/nucleo-f334r8/adc/defconfig | 2 +- configs/nucleo-f334r8/nsh/defconfig | 2 +- configs/nucleo-f4x1re/f401-nsh/defconfig | 2 +- configs/nucleo-f4x1re/f411-nsh/defconfig | 2 +- configs/nucleo-l432kc/nsh/defconfig | 2 +- configs/nucleo-l452re/nsh/defconfig | 2 +- configs/nucleo-l476rg/nsh/defconfig | 2 +- configs/nucleo-l496zg/nsh/defconfig | 2 +- configs/nutiny-nuc120/nsh/defconfig | 2 +- configs/olimex-efm32g880f128-stk/nsh/defconfig | 2 +- configs/olimex-lpc-h3131/nsh/defconfig | 2 +- configs/olimex-lpc1766stk/ftpc/defconfig | 2 +- configs/olimex-lpc1766stk/hidmouse/defconfig | 2 +- configs/olimex-lpc1766stk/nettest/defconfig | 2 +- configs/olimex-lpc1766stk/nsh/defconfig | 2 +- configs/olimex-lpc1766stk/nx/defconfig | 2 +- configs/olimex-lpc1766stk/slip-httpd/defconfig | 2 +- configs/olimex-lpc1766stk/thttpd-binfs/defconfig | 2 +- configs/olimex-lpc1766stk/thttpd-nxflat/defconfig | 2 +- configs/olimex-lpc1766stk/usbmsc/defconfig | 2 +- configs/olimex-lpc1766stk/usbserial/defconfig | 2 +- configs/olimex-lpc1766stk/zmodem/defconfig | 2 +- configs/olimex-lpc2378/nsh/defconfig | 2 +- configs/olimex-stm32-e407/discover/defconfig | 2 +- configs/olimex-stm32-e407/netnsh/defconfig | 2 +- configs/olimex-stm32-e407/nsh/defconfig | 2 +- configs/olimex-stm32-e407/telnetd/defconfig | 2 +- configs/olimex-stm32-e407/usbnsh/defconfig | 2 +- configs/olimex-stm32-e407/webserver/defconfig | 2 +- configs/olimex-stm32-h405/usbnsh/defconfig | 2 +- configs/olimex-stm32-h407/nsh/defconfig | 2 +- configs/olimex-stm32-p107/nsh/defconfig | 2 +- configs/olimex-stm32-p207/nsh/defconfig | 2 +- configs/olimex-stm32-p407/knsh/defconfig | 2 +- configs/olimex-stm32-p407/nsh/defconfig | 2 +- configs/olimex-strp711/nettest/defconfig | 2 +- configs/olimex-strp711/nsh/defconfig | 2 +- configs/olimexino-stm32/can/defconfig | 2 +- configs/olimexino-stm32/composite/defconfig | 2 +- configs/olimexino-stm32/nsh/defconfig | 2 +- configs/olimexino-stm32/smallnsh/defconfig | 2 +- configs/olimexino-stm32/tiny/defconfig | 2 +- configs/open1788/knsh/defconfig | 2 +- configs/open1788/nsh/defconfig | 2 +- configs/open1788/nxlines/defconfig | 2 +- configs/pcduino-a10/nsh/defconfig | 2 +- configs/photon/nsh/defconfig | 2 +- configs/photon/usbnsh/defconfig | 2 +- configs/photon/wlan/defconfig | 2 +- configs/sabre-6quad/nsh/defconfig | 2 +- configs/sabre-6quad/smp/defconfig | 2 +- configs/sam3u-ek/knsh/defconfig | 2 +- configs/sam3u-ek/nsh/defconfig | 2 +- configs/sam3u-ek/nx/defconfig | 2 +- configs/sam3u-ek/nxwm/defconfig | 2 +- configs/sam4cmp-db/nsh/defconfig | 2 +- configs/sam4e-ek/nsh/defconfig | 2 +- configs/sam4e-ek/nxwm/defconfig | 2 +- configs/sam4e-ek/usbnsh/defconfig | 2 +- configs/sam4l-xplained/nsh/defconfig | 2 +- configs/sam4s-xplained-pro/nsh/defconfig | 2 +- configs/sam4s-xplained/nsh/defconfig | 2 +- configs/sama5d2-xult/nsh/defconfig | 2 +- configs/sama5d3-xplained/bridge/defconfig | 2 +- configs/sama5d3-xplained/nsh/defconfig | 2 +- configs/sama5d3x-ek/demo/defconfig | 2 +- configs/sama5d3x-ek/hello/defconfig | 2 +- configs/sama5d3x-ek/norboot/defconfig | 2 +- configs/sama5d3x-ek/nsh/defconfig | 2 +- configs/sama5d3x-ek/nx/defconfig | 2 +- configs/sama5d3x-ek/nxplayer/defconfig | 2 +- configs/sama5d3x-ek/nxwm/defconfig | 2 +- configs/sama5d3x-ek/ov2640/defconfig | 2 +- configs/sama5d4-ek/at25boot/defconfig | 2 +- configs/sama5d4-ek/bridge/defconfig | 2 +- configs/sama5d4-ek/dramboot/defconfig | 2 +- configs/sama5d4-ek/elf/defconfig | 2 +- configs/sama5d4-ek/ipv6/defconfig | 2 +- configs/sama5d4-ek/knsh/defconfig | 2 +- configs/sama5d4-ek/nsh/defconfig | 2 +- configs/sama5d4-ek/nxwm/defconfig | 2 +- configs/sama5d4-ek/ramtest/defconfig | 2 +- configs/samd20-xplained/nsh/defconfig | 2 +- configs/samd21-xplained/nsh/defconfig | 2 +- configs/same70-xplained/netnsh/defconfig | 2 +- configs/same70-xplained/nsh/defconfig | 2 +- configs/saml21-xplained/nsh/defconfig | 2 +- configs/samv71-xult/knsh/defconfig | 2 +- configs/samv71-xult/module/defconfig | 2 +- configs/samv71-xult/mxtxplnd/defconfig | 2 +- configs/samv71-xult/netnsh/defconfig | 2 +- configs/samv71-xult/nsh/defconfig | 2 +- configs/samv71-xult/nxwm/defconfig | 2 +- configs/samv71-xult/vnc/defconfig | 2 +- configs/samv71-xult/vnxwm/defconfig | 2 +- configs/shenzhou/nsh/defconfig | 2 +- configs/shenzhou/nxwm/defconfig | 2 +- configs/shenzhou/thttpd/defconfig | 2 +- configs/spark/composite/defconfig | 2 +- configs/spark/nsh/defconfig | 2 +- configs/spark/usbmsc/defconfig | 2 +- configs/spark/usbnsh/defconfig | 2 +- configs/spark/usbserial/defconfig | 2 +- configs/stm3210e-eval/composite/defconfig | 2 +- configs/stm3210e-eval/nsh/defconfig | 2 +- configs/stm3210e-eval/nsh2/defconfig | 2 +- configs/stm3210e-eval/nx/defconfig | 2 +- configs/stm3210e-eval/nxterm/defconfig | 2 +- configs/stm3210e-eval/pm/defconfig | 2 +- configs/stm3210e-eval/usbmsc/defconfig | 2 +- configs/stm3210e-eval/usbserial/defconfig | 2 +- configs/stm3220g-eval/dhcpd/defconfig | 2 +- configs/stm3220g-eval/nettest/defconfig | 2 +- configs/stm3220g-eval/nsh/defconfig | 2 +- configs/stm3220g-eval/nsh2/defconfig | 2 +- configs/stm3220g-eval/nxwm/defconfig | 2 +- configs/stm3220g-eval/telnetd/defconfig | 2 +- configs/stm3240g-eval/dhcpd/defconfig | 2 +- configs/stm3240g-eval/discover/defconfig | 2 +- configs/stm3240g-eval/knxwm/defconfig | 2 +- configs/stm3240g-eval/nettest/defconfig | 2 +- configs/stm3240g-eval/nsh/defconfig | 2 +- configs/stm3240g-eval/nsh2/defconfig | 2 +- configs/stm3240g-eval/nxterm/defconfig | 2 +- configs/stm3240g-eval/nxwm/defconfig | 2 +- configs/stm3240g-eval/telnetd/defconfig | 2 +- configs/stm3240g-eval/webserver/defconfig | 2 +- configs/stm3240g-eval/xmlrpc/defconfig | 2 +- configs/stm32_tiny/nsh/defconfig | 2 +- configs/stm32_tiny/usbnsh/defconfig | 2 +- configs/stm32butterfly2/nsh/defconfig | 2 +- configs/stm32butterfly2/nshnet/defconfig | 2 +- configs/stm32butterfly2/nshusbdev/defconfig | 2 +- configs/stm32butterfly2/nshusbhost/defconfig | 2 +- configs/stm32f0discovery/nsh/defconfig | 2 +- configs/stm32f103-minimum/audio_tone/defconfig | 2 +- configs/stm32f103-minimum/buttons/defconfig | 2 +- configs/stm32f103-minimum/jlx12864g/defconfig | 2 +- configs/stm32f103-minimum/nrf24/defconfig | 2 +- configs/stm32f103-minimum/nsh/defconfig | 2 +- configs/stm32f103-minimum/pwm/defconfig | 2 +- configs/stm32f103-minimum/rfid-rc522/defconfig | 2 +- configs/stm32f103-minimum/rgbled/defconfig | 2 +- configs/stm32f103-minimum/usbnsh/defconfig | 2 +- configs/stm32f103-minimum/userled/defconfig | 2 +- configs/stm32f103-minimum/veml6070/defconfig | 2 +- configs/stm32f3discovery/nsh/defconfig | 2 +- configs/stm32f3discovery/usbnsh/defconfig | 2 +- configs/stm32f411e-disco/nsh/defconfig | 2 +- configs/stm32f429i-disco/extflash/defconfig | 2 +- configs/stm32f429i-disco/lcd/defconfig | 2 +- configs/stm32f429i-disco/ltdc/defconfig | 2 +- configs/stm32f429i-disco/nsh/defconfig | 2 +- configs/stm32f429i-disco/nxwm/defconfig | 2 +- configs/stm32f429i-disco/usbmsc/defconfig | 2 +- configs/stm32f429i-disco/usbnsh/defconfig | 2 +- configs/stm32f4discovery/canard/defconfig | 2 +- configs/stm32f4discovery/cxxtest/defconfig | 2 +- configs/stm32f4discovery/elf/defconfig | 2 +- configs/stm32f4discovery/ipv6/defconfig | 2 +- configs/stm32f4discovery/kostest/defconfig | 2 +- configs/stm32f4discovery/netnsh/defconfig | 2 +- configs/stm32f4discovery/nsh/defconfig | 2 +- configs/stm32f4discovery/nxlines/defconfig | 2 +- configs/stm32f4discovery/pm/defconfig | 2 +- configs/stm32f4discovery/posix_spawn/defconfig | 2 +- configs/stm32f4discovery/pseudoterm/defconfig | 2 +- configs/stm32f4discovery/rgbled/defconfig | 2 +- configs/stm32f4discovery/uavcan/defconfig | 2 +- configs/stm32f4discovery/usbnsh/defconfig | 2 +- configs/stm32f4discovery/xen1210/defconfig | 2 +- configs/stm32f746-ws/nsh/defconfig | 2 +- configs/stm32f746g-disco/nsh/defconfig | 2 +- configs/stm32l476-mdk/nsh/defconfig | 2 +- configs/stm32l476vg-disco/nsh/defconfig | 2 +- configs/stm32ldiscovery/nsh/defconfig | 2 +- configs/stm32vldiscovery/nsh/defconfig | 2 +- configs/teensy-3.x/nsh/defconfig | 2 +- configs/teensy-3.x/usbnsh/defconfig | 2 +- configs/teensy-lc/nsh/defconfig | 2 +- configs/tm4c123g-launchpad/nsh/defconfig | 2 +- configs/tm4c1294-launchpad/ipv6/defconfig | 2 +- configs/tm4c1294-launchpad/nsh/defconfig | 2 +- configs/twr-k60n512/nsh/defconfig | 2 +- configs/twr-k64f120m/netnsh/defconfig | 2 +- configs/twr-k64f120m/nsh/defconfig | 2 +- configs/u-blox-c027/nsh/defconfig | 2 +- configs/viewtool-stm32f107/highpri/defconfig | 2 +- configs/viewtool-stm32f107/netnsh/defconfig | 2 +- configs/viewtool-stm32f107/nsh/defconfig | 2 +- configs/xmc4500-relax/nsh/defconfig | 2 +- configs/zkit-arm-1769/hello/defconfig | 2 +- configs/zkit-arm-1769/nsh/defconfig | 2 +- configs/zkit-arm-1769/nxhello/defconfig | 2 +- configs/zkit-arm-1769/thttpd/defconfig | 2 +- configs/zp214xpa/nsh/defconfig | 2 +- configs/zp214xpa/nxlines/defconfig | 2 +- 299 files changed, 302 insertions(+), 302 deletions(-) diff --git a/arch/Kconfig b/arch/Kconfig index 5ed2d5dcea..a621f6f163 100644 --- a/arch/Kconfig +++ b/arch/Kconfig @@ -124,6 +124,10 @@ source arch/xtensa/Kconfig source arch/z16/Kconfig source arch/z80/Kconfig +config ARCH_TOOLCHAIN_IAR + bool + default n + config ARCH_TOOLCHAIN_GNU bool default n diff --git a/arch/arm/Kconfig b/arch/arm/Kconfig index fc9dd38894..54f254ff68 100644 --- a/arch/arm/Kconfig +++ b/arch/arm/Kconfig @@ -456,10 +456,6 @@ config ARCH_CHIP default "tms570" if ARCH_CHIP_TMS570 default "xmc4" if ARCH_CHIP_XMC4 -config ARM_TOOLCHAIN_IAR - bool - default n - config ARMV7M_USEBASEPRI bool "Use BASEPRI Register" default n diff --git a/arch/arm/src/Makefile b/arch/arm/src/Makefile index 80281d4ce2..9cdf5898fe 100644 --- a/arch/arm/src/Makefile +++ b/arch/arm/src/Makefile @@ -172,7 +172,7 @@ VPATH += chip VPATH += common VPATH += $(ARCH_SUBDIR) -ifeq ($(CONFIG_ARM_TOOLCHAIN_IAR),y) +ifeq ($(CONFIG_ARCH_TOOLCHAIN_IAR),y) VPATH += chip$(DELIM)iar VPATH += $(ARCH_SUBDIR)$(DELIM)iar else # ifeq ($(CONFIG_ARCH_TOOLCHAIN_GNU),y) diff --git a/arch/arm/src/armv7-m/Kconfig b/arch/arm/src/armv7-m/Kconfig index 0901db06da..381725e006 100644 --- a/arch/arm/src/armv7-m/Kconfig +++ b/arch/arm/src/armv7-m/Kconfig @@ -54,12 +54,12 @@ choice config ARMV7M_TOOLCHAIN_IARW bool "IAR for Windows" depends on TOOLCHAIN_WINDOWS - select ARM_TOOLCHAIN_IAR + select ARCH_TOOLCHAIN_IAR config ARMV7M_TOOLCHAIN_IARL bool "IAR for Linux" depends on HOST_LINUX - select ARM_TOOLCHAIN_IAR + select ARCH_TOOLCHAIN_IAR config ARMV7M_TOOLCHAIN_ATOLLIC bool "Atollic Lite/Pro for Windows" diff --git a/configs/arduino-due/nsh/defconfig b/configs/arduino-due/nsh/defconfig index a9efd1b409..e1101645f9 100644 --- a/configs/arduino-due/nsh/defconfig +++ b/configs/arduino-due/nsh/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="sam34" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/bambino-200e/netnsh/defconfig b/configs/bambino-200e/netnsh/defconfig index ae943545e6..5cad2e7172 100644 --- a/configs/bambino-200e/netnsh/defconfig +++ b/configs/bambino-200e/netnsh/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc43xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/bambino-200e/nsh/defconfig b/configs/bambino-200e/nsh/defconfig index 9999a7f74a..fc72cef1ae 100644 --- a/configs/bambino-200e/nsh/defconfig +++ b/configs/bambino-200e/nsh/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc43xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/bambino-200e/usbnsh/defconfig b/configs/bambino-200e/usbnsh/defconfig index 9059baeb98..558c13c30e 100644 --- a/configs/bambino-200e/usbnsh/defconfig +++ b/configs/bambino-200e/usbnsh/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc43xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/c5471evm/httpd/defconfig b/configs/c5471evm/httpd/defconfig index 0a5a307ce3..227ca4a58a 100644 --- a/configs/c5471evm/httpd/defconfig +++ b/configs/c5471evm/httpd/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_ARM7TDMI=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="c5471" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/c5471evm/nettest/defconfig b/configs/c5471evm/nettest/defconfig index 3283887cde..7df297ee2c 100644 --- a/configs/c5471evm/nettest/defconfig +++ b/configs/c5471evm/nettest/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_ARM7TDMI=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="c5471" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/c5471evm/nsh/defconfig b/configs/c5471evm/nsh/defconfig index 8ca4c5145d..5dff7fac5f 100644 --- a/configs/c5471evm/nsh/defconfig +++ b/configs/c5471evm/nsh/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_ARM7TDMI=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="c5471" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/cc3200-launchpad/nsh/defconfig b/configs/cc3200-launchpad/nsh/defconfig index 01f8b14b6d..f0db72f06e 100644 --- a/configs/cc3200-launchpad/nsh/defconfig +++ b/configs/cc3200-launchpad/nsh/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/clicker2-stm32/knsh/defconfig b/configs/clicker2-stm32/knsh/defconfig index 80aee6dd1c..caa991f103 100644 --- a/configs/clicker2-stm32/knsh/defconfig +++ b/configs/clicker2-stm32/knsh/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/clicker2-stm32/mrf24j40-radio/defconfig b/configs/clicker2-stm32/mrf24j40-radio/defconfig index 2a9e6b3d30..e7c649d2c5 100644 --- a/configs/clicker2-stm32/mrf24j40-radio/defconfig +++ b/configs/clicker2-stm32/mrf24j40-radio/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/clicker2-stm32/nsh/defconfig b/configs/clicker2-stm32/nsh/defconfig index 86859d28bc..ae4b8ff23c 100644 --- a/configs/clicker2-stm32/nsh/defconfig +++ b/configs/clicker2-stm32/nsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/clicker2-stm32/usbnsh/defconfig b/configs/clicker2-stm32/usbnsh/defconfig index 88c8f5b534..c82313ce75 100644 --- a/configs/clicker2-stm32/usbnsh/defconfig +++ b/configs/clicker2-stm32/usbnsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/cloudctrl/nsh/defconfig b/configs/cloudctrl/nsh/defconfig index 702ba56801..5f87a306d1 100644 --- a/configs/cloudctrl/nsh/defconfig +++ b/configs/cloudctrl/nsh/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/dk-tm4c129x/ipv6/defconfig b/configs/dk-tm4c129x/ipv6/defconfig index ad36404f11..0e08299917 100644 --- a/configs/dk-tm4c129x/ipv6/defconfig +++ b/configs/dk-tm4c129x/ipv6/defconfig @@ -129,7 +129,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/dk-tm4c129x/nsh/defconfig b/configs/dk-tm4c129x/nsh/defconfig index cbaa62ed3e..8b8ea559d0 100644 --- a/configs/dk-tm4c129x/nsh/defconfig +++ b/configs/dk-tm4c129x/nsh/defconfig @@ -129,7 +129,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/ea3131/nsh/defconfig b/configs/ea3131/nsh/defconfig index f7de159baf..5820f7eb95 100644 --- a/configs/ea3131/nsh/defconfig +++ b/configs/ea3131/nsh/defconfig @@ -127,7 +127,7 @@ CONFIG_ARCH_ARM926EJS=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="lpc31xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/ea3131/pgnsh/defconfig b/configs/ea3131/pgnsh/defconfig index 99ccdd58db..c70463809c 100644 --- a/configs/ea3131/pgnsh/defconfig +++ b/configs/ea3131/pgnsh/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_ARM926EJS=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="lpc31xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/ea3131/usbserial/defconfig b/configs/ea3131/usbserial/defconfig index bacdd9bb4a..6acce61b13 100644 --- a/configs/ea3131/usbserial/defconfig +++ b/configs/ea3131/usbserial/defconfig @@ -127,7 +127,7 @@ CONFIG_ARCH_ARM926EJS=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="lpc31xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/ea3152/ostest/defconfig b/configs/ea3152/ostest/defconfig index 73b24c8859..188d64ca4a 100644 --- a/configs/ea3152/ostest/defconfig +++ b/configs/ea3152/ostest/defconfig @@ -127,7 +127,7 @@ CONFIG_ARCH_ARM926EJS=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="lpc31xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/eagle100/httpd/defconfig b/configs/eagle100/httpd/defconfig index 173603d8ef..2f5fac899d 100644 --- a/configs/eagle100/httpd/defconfig +++ b/configs/eagle100/httpd/defconfig @@ -129,7 +129,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/eagle100/nettest/defconfig b/configs/eagle100/nettest/defconfig index cd0911d540..bec8a97047 100644 --- a/configs/eagle100/nettest/defconfig +++ b/configs/eagle100/nettest/defconfig @@ -129,7 +129,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/eagle100/nsh/defconfig b/configs/eagle100/nsh/defconfig index b53dcf1df2..ffa99ab8ca 100644 --- a/configs/eagle100/nsh/defconfig +++ b/configs/eagle100/nsh/defconfig @@ -129,7 +129,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/eagle100/nxflat/defconfig b/configs/eagle100/nxflat/defconfig index 5fb625a468..7f14f43553 100644 --- a/configs/eagle100/nxflat/defconfig +++ b/configs/eagle100/nxflat/defconfig @@ -127,7 +127,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/eagle100/thttpd/defconfig b/configs/eagle100/thttpd/defconfig index 729eb0e04e..b7858460af 100644 --- a/configs/eagle100/thttpd/defconfig +++ b/configs/eagle100/thttpd/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/efm32-g8xx-stk/nsh/defconfig b/configs/efm32-g8xx-stk/nsh/defconfig index eff463d023..2b1e12ffe0 100644 --- a/configs/efm32-g8xx-stk/nsh/defconfig +++ b/configs/efm32-g8xx-stk/nsh/defconfig @@ -127,7 +127,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="efm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/efm32gg-stk3700/nsh/defconfig b/configs/efm32gg-stk3700/nsh/defconfig index 19d86bf2ee..8118f915ca 100644 --- a/configs/efm32gg-stk3700/nsh/defconfig +++ b/configs/efm32gg-stk3700/nsh/defconfig @@ -127,7 +127,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="efm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/ekk-lm3s9b96/nsh/defconfig b/configs/ekk-lm3s9b96/nsh/defconfig index c15bdf04fe..d2eabf737b 100644 --- a/configs/ekk-lm3s9b96/nsh/defconfig +++ b/configs/ekk-lm3s9b96/nsh/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/fire-stm32v2/nsh/defconfig b/configs/fire-stm32v2/nsh/defconfig index ec18e9ce68..53063ac7af 100644 --- a/configs/fire-stm32v2/nsh/defconfig +++ b/configs/fire-stm32v2/nsh/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/freedom-k64f/netnsh/defconfig b/configs/freedom-k64f/netnsh/defconfig index 870d04628c..691747b286 100644 --- a/configs/freedom-k64f/netnsh/defconfig +++ b/configs/freedom-k64f/netnsh/defconfig @@ -129,7 +129,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="kinetis" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/freedom-k64f/nsh/defconfig b/configs/freedom-k64f/nsh/defconfig index c20b9516ba..47e37626e8 100644 --- a/configs/freedom-k64f/nsh/defconfig +++ b/configs/freedom-k64f/nsh/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="kinetis" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/freedom-k66f/netnsh/defconfig b/configs/freedom-k66f/netnsh/defconfig index 605211c45c..97e053710c 100644 --- a/configs/freedom-k66f/netnsh/defconfig +++ b/configs/freedom-k66f/netnsh/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="kinetis" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/freedom-k66f/nsh/defconfig b/configs/freedom-k66f/nsh/defconfig index ee3cdbd812..3ba8a3d279 100644 --- a/configs/freedom-k66f/nsh/defconfig +++ b/configs/freedom-k66f/nsh/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="kinetis" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/freedom-kl25z/nsh/defconfig b/configs/freedom-kl25z/nsh/defconfig index 66209901fd..7f1ca58fe7 100644 --- a/configs/freedom-kl25z/nsh/defconfig +++ b/configs/freedom-kl25z/nsh/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_CORTEXM0=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv6-m" CONFIG_ARCH_CHIP="kl" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set # CONFIG_ARMV7M_LAZYFPU is not set diff --git a/configs/freedom-kl26z/nsh/defconfig b/configs/freedom-kl26z/nsh/defconfig index 20e2a5773a..9c5d47ab79 100644 --- a/configs/freedom-kl26z/nsh/defconfig +++ b/configs/freedom-kl26z/nsh/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_CORTEXM0=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv6-m" CONFIG_ARCH_CHIP="kl" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set # CONFIG_ARMV7M_LAZYFPU is not set diff --git a/configs/hymini-stm32v/nsh/defconfig b/configs/hymini-stm32v/nsh/defconfig index bb3ca8f375..7df3f16f96 100644 --- a/configs/hymini-stm32v/nsh/defconfig +++ b/configs/hymini-stm32v/nsh/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/hymini-stm32v/nsh2/defconfig b/configs/hymini-stm32v/nsh2/defconfig index 9d6ac794f5..78b8a93b10 100644 --- a/configs/hymini-stm32v/nsh2/defconfig +++ b/configs/hymini-stm32v/nsh2/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/hymini-stm32v/usbmsc/defconfig b/configs/hymini-stm32v/usbmsc/defconfig index 287eb70cb7..aa41f35bfb 100644 --- a/configs/hymini-stm32v/usbmsc/defconfig +++ b/configs/hymini-stm32v/usbmsc/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/hymini-stm32v/usbnsh/defconfig b/configs/hymini-stm32v/usbnsh/defconfig index f601f22f85..f8bdf8cd52 100644 --- a/configs/hymini-stm32v/usbnsh/defconfig +++ b/configs/hymini-stm32v/usbnsh/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/hymini-stm32v/usbserial/defconfig b/configs/hymini-stm32v/usbserial/defconfig index 3d6cf703e6..7ea3f00e64 100644 --- a/configs/hymini-stm32v/usbserial/defconfig +++ b/configs/hymini-stm32v/usbserial/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/kwikstik-k40/ostest/defconfig b/configs/kwikstik-k40/ostest/defconfig index fd60f30842..6234ea74dd 100644 --- a/configs/kwikstik-k40/ostest/defconfig +++ b/configs/kwikstik-k40/ostest/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="kinetis" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/launchxl-tms57004/nsh/defconfig b/configs/launchxl-tms57004/nsh/defconfig index e4c1a1a3ad..d48b4c9b34 100644 --- a/configs/launchxl-tms57004/nsh/defconfig +++ b/configs/launchxl-tms57004/nsh/defconfig @@ -127,7 +127,7 @@ CONFIG_ARCH_CORTEXR4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-r" CONFIG_ARCH_CHIP="tms570" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set diff --git a/configs/lincoln60/netnsh/defconfig b/configs/lincoln60/netnsh/defconfig index 329f574d86..8e2ddd336b 100644 --- a/configs/lincoln60/netnsh/defconfig +++ b/configs/lincoln60/netnsh/defconfig @@ -129,7 +129,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/lincoln60/nsh/defconfig b/configs/lincoln60/nsh/defconfig index 0f3f84f13c..099a29380d 100644 --- a/configs/lincoln60/nsh/defconfig +++ b/configs/lincoln60/nsh/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/lincoln60/thttpd-binfs/defconfig b/configs/lincoln60/thttpd-binfs/defconfig index 526196caa8..fe524e1cab 100644 --- a/configs/lincoln60/thttpd-binfs/defconfig +++ b/configs/lincoln60/thttpd-binfs/defconfig @@ -129,7 +129,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/lm3s6432-s2e/nsh/defconfig b/configs/lm3s6432-s2e/nsh/defconfig index 218e59dc08..7f4046a18b 100644 --- a/configs/lm3s6432-s2e/nsh/defconfig +++ b/configs/lm3s6432-s2e/nsh/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/lm3s6965-ek/discover/defconfig b/configs/lm3s6965-ek/discover/defconfig index 4430849fe6..fa9015122c 100644 --- a/configs/lm3s6965-ek/discover/defconfig +++ b/configs/lm3s6965-ek/discover/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/lm3s6965-ek/nsh/defconfig b/configs/lm3s6965-ek/nsh/defconfig index 4430849fe6..fa9015122c 100644 --- a/configs/lm3s6965-ek/nsh/defconfig +++ b/configs/lm3s6965-ek/nsh/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/lm3s6965-ek/nx/defconfig b/configs/lm3s6965-ek/nx/defconfig index cd5a4ff64d..38ca2f3c28 100644 --- a/configs/lm3s6965-ek/nx/defconfig +++ b/configs/lm3s6965-ek/nx/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/lm3s6965-ek/tcpecho/defconfig b/configs/lm3s6965-ek/tcpecho/defconfig index 1322a6b086..b7f9e0a3ff 100644 --- a/configs/lm3s6965-ek/tcpecho/defconfig +++ b/configs/lm3s6965-ek/tcpecho/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/lm3s8962-ek/nsh/defconfig b/configs/lm3s8962-ek/nsh/defconfig index 4f430bcbe1..96b19a018d 100644 --- a/configs/lm3s8962-ek/nsh/defconfig +++ b/configs/lm3s8962-ek/nsh/defconfig @@ -129,7 +129,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/lm3s8962-ek/nx/defconfig b/configs/lm3s8962-ek/nx/defconfig index fb7972fcce..c78f7a54f2 100644 --- a/configs/lm3s8962-ek/nx/defconfig +++ b/configs/lm3s8962-ek/nx/defconfig @@ -127,7 +127,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/lm4f120-launchpad/nsh/defconfig b/configs/lm4f120-launchpad/nsh/defconfig index 68e93a91db..723ef7ac64 100644 --- a/configs/lm4f120-launchpad/nsh/defconfig +++ b/configs/lm4f120-launchpad/nsh/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/lpc4330-xplorer/nsh/defconfig b/configs/lpc4330-xplorer/nsh/defconfig index 36341064ed..b133fea022 100644 --- a/configs/lpc4330-xplorer/nsh/defconfig +++ b/configs/lpc4330-xplorer/nsh/defconfig @@ -127,7 +127,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc43xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/lpc4337-ws/nsh/defconfig b/configs/lpc4337-ws/nsh/defconfig index 1d9816c93a..b228af1f60 100644 --- a/configs/lpc4337-ws/nsh/defconfig +++ b/configs/lpc4337-ws/nsh/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc43xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/lpc4357-evb/nsh/defconfig b/configs/lpc4357-evb/nsh/defconfig index 2ca8bcb4ef..cd8935a19f 100644 --- a/configs/lpc4357-evb/nsh/defconfig +++ b/configs/lpc4357-evb/nsh/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc43xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/lpc4370-link2/nsh/defconfig b/configs/lpc4370-link2/nsh/defconfig index 44b6a22d2e..81a79dfeb5 100644 --- a/configs/lpc4370-link2/nsh/defconfig +++ b/configs/lpc4370-link2/nsh/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc43xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/lpcxpresso-lpc1115/nsh/defconfig b/configs/lpcxpresso-lpc1115/nsh/defconfig index ccbeff2668..d46c1d2b71 100644 --- a/configs/lpcxpresso-lpc1115/nsh/defconfig +++ b/configs/lpcxpresso-lpc1115/nsh/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_CORTEXM0=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv6-m" CONFIG_ARCH_CHIP="lpc11xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set # CONFIG_ARMV7M_LAZYFPU is not set diff --git a/configs/lpcxpresso-lpc1768/dhcpd/defconfig b/configs/lpcxpresso-lpc1768/dhcpd/defconfig index e43bad3bee..185cbfeeae 100644 --- a/configs/lpcxpresso-lpc1768/dhcpd/defconfig +++ b/configs/lpcxpresso-lpc1768/dhcpd/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/lpcxpresso-lpc1768/nsh/defconfig b/configs/lpcxpresso-lpc1768/nsh/defconfig index ac4954e96b..5885acd549 100644 --- a/configs/lpcxpresso-lpc1768/nsh/defconfig +++ b/configs/lpcxpresso-lpc1768/nsh/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/lpcxpresso-lpc1768/nx/defconfig b/configs/lpcxpresso-lpc1768/nx/defconfig index dca6d00aae..d68db2998e 100644 --- a/configs/lpcxpresso-lpc1768/nx/defconfig +++ b/configs/lpcxpresso-lpc1768/nx/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/lpcxpresso-lpc1768/thttpd/defconfig b/configs/lpcxpresso-lpc1768/thttpd/defconfig index a680bbcbb5..c854c8a66c 100644 --- a/configs/lpcxpresso-lpc1768/thttpd/defconfig +++ b/configs/lpcxpresso-lpc1768/thttpd/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/lpcxpresso-lpc1768/usbmsc/defconfig b/configs/lpcxpresso-lpc1768/usbmsc/defconfig index e2e0b98a3d..3c0c09a6fd 100644 --- a/configs/lpcxpresso-lpc1768/usbmsc/defconfig +++ b/configs/lpcxpresso-lpc1768/usbmsc/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/maple/nsh/defconfig b/configs/maple/nsh/defconfig index 6e8ab0b117..0dbf9308c1 100644 --- a/configs/maple/nsh/defconfig +++ b/configs/maple/nsh/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/maple/nx/defconfig b/configs/maple/nx/defconfig index 624e6d72cd..083bfcf053 100644 --- a/configs/maple/nx/defconfig +++ b/configs/maple/nx/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/maple/usbnsh/defconfig b/configs/maple/usbnsh/defconfig index 7c218e3470..c2d7fb75aa 100644 --- a/configs/maple/usbnsh/defconfig +++ b/configs/maple/usbnsh/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/mbed/nsh/defconfig b/configs/mbed/nsh/defconfig index 32e19cbb1a..d72476da05 100644 --- a/configs/mbed/nsh/defconfig +++ b/configs/mbed/nsh/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/mcu123-lpc214x/composite/defconfig b/configs/mcu123-lpc214x/composite/defconfig index e3d6a6728e..64d1898909 100644 --- a/configs/mcu123-lpc214x/composite/defconfig +++ b/configs/mcu123-lpc214x/composite/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_ARM7TDMI=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="lpc214x" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/mcu123-lpc214x/nsh/defconfig b/configs/mcu123-lpc214x/nsh/defconfig index 3f42176bd5..35d07253e0 100644 --- a/configs/mcu123-lpc214x/nsh/defconfig +++ b/configs/mcu123-lpc214x/nsh/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_ARM7TDMI=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="lpc214x" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/mcu123-lpc214x/usbmsc/defconfig b/configs/mcu123-lpc214x/usbmsc/defconfig index d19e88bbd1..516afa4720 100644 --- a/configs/mcu123-lpc214x/usbmsc/defconfig +++ b/configs/mcu123-lpc214x/usbmsc/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_ARM7TDMI=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="lpc214x" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/mcu123-lpc214x/usbserial/defconfig b/configs/mcu123-lpc214x/usbserial/defconfig index 5b5975cb38..9e9a05c8d5 100644 --- a/configs/mcu123-lpc214x/usbserial/defconfig +++ b/configs/mcu123-lpc214x/usbserial/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_ARM7TDMI=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="lpc214x" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/mikroe-stm32f4/fulldemo/defconfig b/configs/mikroe-stm32f4/fulldemo/defconfig index b3f16f6c83..956df4df96 100644 --- a/configs/mikroe-stm32f4/fulldemo/defconfig +++ b/configs/mikroe-stm32f4/fulldemo/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/mikroe-stm32f4/kostest/defconfig b/configs/mikroe-stm32f4/kostest/defconfig index b099d5b86d..df4088feca 100644 --- a/configs/mikroe-stm32f4/kostest/defconfig +++ b/configs/mikroe-stm32f4/kostest/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/mikroe-stm32f4/nsh/defconfig b/configs/mikroe-stm32f4/nsh/defconfig index 9f680a8f4d..ac5595096f 100644 --- a/configs/mikroe-stm32f4/nsh/defconfig +++ b/configs/mikroe-stm32f4/nsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/mikroe-stm32f4/nx/defconfig b/configs/mikroe-stm32f4/nx/defconfig index 1019848edd..b6d01b2b68 100644 --- a/configs/mikroe-stm32f4/nx/defconfig +++ b/configs/mikroe-stm32f4/nx/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/mikroe-stm32f4/nxlines/defconfig b/configs/mikroe-stm32f4/nxlines/defconfig index 05abbbcd90..c299e729b8 100644 --- a/configs/mikroe-stm32f4/nxlines/defconfig +++ b/configs/mikroe-stm32f4/nxlines/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/mikroe-stm32f4/nxtext/defconfig b/configs/mikroe-stm32f4/nxtext/defconfig index 6acc4817f7..7ea8085608 100644 --- a/configs/mikroe-stm32f4/nxtext/defconfig +++ b/configs/mikroe-stm32f4/nxtext/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/mikroe-stm32f4/usbnsh/defconfig b/configs/mikroe-stm32f4/usbnsh/defconfig index 193621ba02..0b24f1d0e4 100644 --- a/configs/mikroe-stm32f4/usbnsh/defconfig +++ b/configs/mikroe-stm32f4/usbnsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/moxa/nsh/defconfig b/configs/moxa/nsh/defconfig index 4629cded4a..489a186b49 100644 --- a/configs/moxa/nsh/defconfig +++ b/configs/moxa/nsh/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_ARM7TDMI=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="moxart" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/mx1ads/ostest/defconfig b/configs/mx1ads/ostest/defconfig index 2a5f6df09f..25ead2ce11 100644 --- a/configs/mx1ads/ostest/defconfig +++ b/configs/mx1ads/ostest/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_ARM920T=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="imx1" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/ntosd-dm320/nettest/defconfig b/configs/ntosd-dm320/nettest/defconfig index 311ee15aae..afe277011f 100644 --- a/configs/ntosd-dm320/nettest/defconfig +++ b/configs/ntosd-dm320/nettest/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_ARM926EJS=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="dm320" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/ntosd-dm320/nsh/defconfig b/configs/ntosd-dm320/nsh/defconfig index b1b2f6fb42..7346dc05a6 100644 --- a/configs/ntosd-dm320/nsh/defconfig +++ b/configs/ntosd-dm320/nsh/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_ARM926EJS=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="dm320" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/ntosd-dm320/poll/defconfig b/configs/ntosd-dm320/poll/defconfig index e314ef41d3..4c5c1343b9 100644 --- a/configs/ntosd-dm320/poll/defconfig +++ b/configs/ntosd-dm320/poll/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_ARM926EJS=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="dm320" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/ntosd-dm320/thttpd/defconfig b/configs/ntosd-dm320/thttpd/defconfig index 6d92deb481..d5ae0d1cba 100644 --- a/configs/ntosd-dm320/thttpd/defconfig +++ b/configs/ntosd-dm320/thttpd/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_ARM926EJS=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="dm320" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/ntosd-dm320/udp/defconfig b/configs/ntosd-dm320/udp/defconfig index 796fd42634..291f86c54b 100644 --- a/configs/ntosd-dm320/udp/defconfig +++ b/configs/ntosd-dm320/udp/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_ARM926EJS=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="dm320" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/ntosd-dm320/webserver/defconfig b/configs/ntosd-dm320/webserver/defconfig index 73f3f5c832..16966d5862 100644 --- a/configs/ntosd-dm320/webserver/defconfig +++ b/configs/ntosd-dm320/webserver/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_ARM926EJS=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="dm320" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/nucleo-144/f746-evalos/defconfig b/configs/nucleo-144/f746-evalos/defconfig index 5641f155a6..6a333e8185 100644 --- a/configs/nucleo-144/f746-evalos/defconfig +++ b/configs/nucleo-144/f746-evalos/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM7=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32f7" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/nucleo-144/f746-nsh/defconfig b/configs/nucleo-144/f746-nsh/defconfig index 45debe992f..4e100930ac 100644 --- a/configs/nucleo-144/f746-nsh/defconfig +++ b/configs/nucleo-144/f746-nsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM7=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32f7" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/nucleo-144/f767-evalos/defconfig b/configs/nucleo-144/f767-evalos/defconfig index ef02b1ec18..cbc8fd6181 100644 --- a/configs/nucleo-144/f767-evalos/defconfig +++ b/configs/nucleo-144/f767-evalos/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM7=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32f7" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/nucleo-144/f767-nsh/defconfig b/configs/nucleo-144/f767-nsh/defconfig index b441fea4f6..3fc8fc5181 100644 --- a/configs/nucleo-144/f767-nsh/defconfig +++ b/configs/nucleo-144/f767-nsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM7=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32f7" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/nucleo-f072rb/nsh/defconfig b/configs/nucleo-f072rb/nsh/defconfig index 873055d9b6..978624897e 100644 --- a/configs/nucleo-f072rb/nsh/defconfig +++ b/configs/nucleo-f072rb/nsh/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM0=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv6-m" CONFIG_ARCH_CHIP="stm32f0" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set # CONFIG_ARMV7M_LAZYFPU is not set diff --git a/configs/nucleo-f091rc/nsh/defconfig b/configs/nucleo-f091rc/nsh/defconfig index 8a4dfca1f0..924c68ec5c 100644 --- a/configs/nucleo-f091rc/nsh/defconfig +++ b/configs/nucleo-f091rc/nsh/defconfig @@ -153,7 +153,7 @@ CONFIG_ARCH_CORTEXM0=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv6-m" CONFIG_ARCH_CHIP="stm32f0" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set # CONFIG_ARMV7M_LAZYFPU is not set diff --git a/configs/nucleo-f303re/adc/defconfig b/configs/nucleo-f303re/adc/defconfig index f68cbba519..f2dae45cf7 100644 --- a/configs/nucleo-f303re/adc/defconfig +++ b/configs/nucleo-f303re/adc/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/nucleo-f303re/can/defconfig b/configs/nucleo-f303re/can/defconfig index 13c676f841..f6252ea707 100644 --- a/configs/nucleo-f303re/can/defconfig +++ b/configs/nucleo-f303re/can/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/nucleo-f303re/hello/defconfig b/configs/nucleo-f303re/hello/defconfig index 77b3b74b64..736dfa88f8 100644 --- a/configs/nucleo-f303re/hello/defconfig +++ b/configs/nucleo-f303re/hello/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/nucleo-f303re/nxlines/defconfig b/configs/nucleo-f303re/nxlines/defconfig index 216ddd0d15..f3e7fc382e 100644 --- a/configs/nucleo-f303re/nxlines/defconfig +++ b/configs/nucleo-f303re/nxlines/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/nucleo-f303re/pwm/defconfig b/configs/nucleo-f303re/pwm/defconfig index 485e8e95d6..489bb99455 100644 --- a/configs/nucleo-f303re/pwm/defconfig +++ b/configs/nucleo-f303re/pwm/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/nucleo-f303re/serialrx/defconfig b/configs/nucleo-f303re/serialrx/defconfig index 52040cacf1..2e6e2181fa 100644 --- a/configs/nucleo-f303re/serialrx/defconfig +++ b/configs/nucleo-f303re/serialrx/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/nucleo-f303re/uavcan/defconfig b/configs/nucleo-f303re/uavcan/defconfig index 6d7f1f9f03..a111dce0a8 100644 --- a/configs/nucleo-f303re/uavcan/defconfig +++ b/configs/nucleo-f303re/uavcan/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/nucleo-f334r8/adc/defconfig b/configs/nucleo-f334r8/adc/defconfig index 8a50305c7b..ff470c333f 100644 --- a/configs/nucleo-f334r8/adc/defconfig +++ b/configs/nucleo-f334r8/adc/defconfig @@ -152,7 +152,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/nucleo-f334r8/nsh/defconfig b/configs/nucleo-f334r8/nsh/defconfig index b41fa89e69..94238e0628 100644 --- a/configs/nucleo-f334r8/nsh/defconfig +++ b/configs/nucleo-f334r8/nsh/defconfig @@ -150,7 +150,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/nucleo-f4x1re/f401-nsh/defconfig b/configs/nucleo-f4x1re/f401-nsh/defconfig index 483c4074a2..4748f70509 100644 --- a/configs/nucleo-f4x1re/f401-nsh/defconfig +++ b/configs/nucleo-f4x1re/f401-nsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/nucleo-f4x1re/f411-nsh/defconfig b/configs/nucleo-f4x1re/f411-nsh/defconfig index 05a9151ea9..6e70b6ec40 100644 --- a/configs/nucleo-f4x1re/f411-nsh/defconfig +++ b/configs/nucleo-f4x1re/f411-nsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/nucleo-l432kc/nsh/defconfig b/configs/nucleo-l432kc/nsh/defconfig index ba0cb740ba..efb716c902 100644 --- a/configs/nucleo-l432kc/nsh/defconfig +++ b/configs/nucleo-l432kc/nsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32l4" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/nucleo-l452re/nsh/defconfig b/configs/nucleo-l452re/nsh/defconfig index f076feb63f..354b25f7c7 100644 --- a/configs/nucleo-l452re/nsh/defconfig +++ b/configs/nucleo-l452re/nsh/defconfig @@ -160,7 +160,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32l4" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/nucleo-l476rg/nsh/defconfig b/configs/nucleo-l476rg/nsh/defconfig index ea45b09938..7094ab8803 100644 --- a/configs/nucleo-l476rg/nsh/defconfig +++ b/configs/nucleo-l476rg/nsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32l4" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/nucleo-l496zg/nsh/defconfig b/configs/nucleo-l496zg/nsh/defconfig index e2acced8f8..ad95f558a8 100644 --- a/configs/nucleo-l496zg/nsh/defconfig +++ b/configs/nucleo-l496zg/nsh/defconfig @@ -160,7 +160,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32l4" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/nutiny-nuc120/nsh/defconfig b/configs/nutiny-nuc120/nsh/defconfig index be52dbd671..2f9d28a88b 100644 --- a/configs/nutiny-nuc120/nsh/defconfig +++ b/configs/nutiny-nuc120/nsh/defconfig @@ -127,7 +127,7 @@ CONFIG_ARCH_CORTEXM0=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv6-m" CONFIG_ARCH_CHIP="nuc1xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set # CONFIG_ARMV7M_LAZYFPU is not set diff --git a/configs/olimex-efm32g880f128-stk/nsh/defconfig b/configs/olimex-efm32g880f128-stk/nsh/defconfig index 7085701ec9..f2da9812c1 100644 --- a/configs/olimex-efm32g880f128-stk/nsh/defconfig +++ b/configs/olimex-efm32g880f128-stk/nsh/defconfig @@ -127,7 +127,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="efm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/olimex-lpc-h3131/nsh/defconfig b/configs/olimex-lpc-h3131/nsh/defconfig index d9e216fecf..b2620d8888 100644 --- a/configs/olimex-lpc-h3131/nsh/defconfig +++ b/configs/olimex-lpc-h3131/nsh/defconfig @@ -127,7 +127,7 @@ CONFIG_ARCH_ARM926EJS=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="lpc31xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/olimex-lpc1766stk/ftpc/defconfig b/configs/olimex-lpc1766stk/ftpc/defconfig index 3726d1d81e..41bc62fc8a 100644 --- a/configs/olimex-lpc1766stk/ftpc/defconfig +++ b/configs/olimex-lpc1766stk/ftpc/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/olimex-lpc1766stk/hidmouse/defconfig b/configs/olimex-lpc1766stk/hidmouse/defconfig index 1caa4aa30c..4751e49360 100644 --- a/configs/olimex-lpc1766stk/hidmouse/defconfig +++ b/configs/olimex-lpc1766stk/hidmouse/defconfig @@ -129,7 +129,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/olimex-lpc1766stk/nettest/defconfig b/configs/olimex-lpc1766stk/nettest/defconfig index e956880266..6cac49f3ef 100644 --- a/configs/olimex-lpc1766stk/nettest/defconfig +++ b/configs/olimex-lpc1766stk/nettest/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/olimex-lpc1766stk/nsh/defconfig b/configs/olimex-lpc1766stk/nsh/defconfig index b5848d74a3..373eeb3daa 100644 --- a/configs/olimex-lpc1766stk/nsh/defconfig +++ b/configs/olimex-lpc1766stk/nsh/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/olimex-lpc1766stk/nx/defconfig b/configs/olimex-lpc1766stk/nx/defconfig index ad17276f38..0b67c54f61 100644 --- a/configs/olimex-lpc1766stk/nx/defconfig +++ b/configs/olimex-lpc1766stk/nx/defconfig @@ -127,7 +127,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/olimex-lpc1766stk/slip-httpd/defconfig b/configs/olimex-lpc1766stk/slip-httpd/defconfig index b2833ca2b2..fefac5aa76 100644 --- a/configs/olimex-lpc1766stk/slip-httpd/defconfig +++ b/configs/olimex-lpc1766stk/slip-httpd/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/olimex-lpc1766stk/thttpd-binfs/defconfig b/configs/olimex-lpc1766stk/thttpd-binfs/defconfig index d52c9fb0e4..7a15c4c5ef 100644 --- a/configs/olimex-lpc1766stk/thttpd-binfs/defconfig +++ b/configs/olimex-lpc1766stk/thttpd-binfs/defconfig @@ -129,7 +129,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/olimex-lpc1766stk/thttpd-nxflat/defconfig b/configs/olimex-lpc1766stk/thttpd-nxflat/defconfig index 036163064a..208c90d50f 100644 --- a/configs/olimex-lpc1766stk/thttpd-nxflat/defconfig +++ b/configs/olimex-lpc1766stk/thttpd-nxflat/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/olimex-lpc1766stk/usbmsc/defconfig b/configs/olimex-lpc1766stk/usbmsc/defconfig index 890d285c0f..9ae53e827a 100644 --- a/configs/olimex-lpc1766stk/usbmsc/defconfig +++ b/configs/olimex-lpc1766stk/usbmsc/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/olimex-lpc1766stk/usbserial/defconfig b/configs/olimex-lpc1766stk/usbserial/defconfig index 8198a854c2..16a873814f 100644 --- a/configs/olimex-lpc1766stk/usbserial/defconfig +++ b/configs/olimex-lpc1766stk/usbserial/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/olimex-lpc1766stk/zmodem/defconfig b/configs/olimex-lpc1766stk/zmodem/defconfig index 07688ee8da..ec2b96b615 100644 --- a/configs/olimex-lpc1766stk/zmodem/defconfig +++ b/configs/olimex-lpc1766stk/zmodem/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/olimex-lpc2378/nsh/defconfig b/configs/olimex-lpc2378/nsh/defconfig index e81825c9cd..5fb9b94171 100644 --- a/configs/olimex-lpc2378/nsh/defconfig +++ b/configs/olimex-lpc2378/nsh/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_ARM7TDMI=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="lpc2378" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/olimex-stm32-e407/discover/defconfig b/configs/olimex-stm32-e407/discover/defconfig index 14fe43cf1d..c44bf12478 100644 --- a/configs/olimex-stm32-e407/discover/defconfig +++ b/configs/olimex-stm32-e407/discover/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-stm32-e407/netnsh/defconfig b/configs/olimex-stm32-e407/netnsh/defconfig index 025ce138b2..70f2e93be0 100644 --- a/configs/olimex-stm32-e407/netnsh/defconfig +++ b/configs/olimex-stm32-e407/netnsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-stm32-e407/nsh/defconfig b/configs/olimex-stm32-e407/nsh/defconfig index 599b9ed4c0..ac026758f0 100644 --- a/configs/olimex-stm32-e407/nsh/defconfig +++ b/configs/olimex-stm32-e407/nsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-stm32-e407/telnetd/defconfig b/configs/olimex-stm32-e407/telnetd/defconfig index 29aa5cb615..87dc6849d7 100644 --- a/configs/olimex-stm32-e407/telnetd/defconfig +++ b/configs/olimex-stm32-e407/telnetd/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-stm32-e407/usbnsh/defconfig b/configs/olimex-stm32-e407/usbnsh/defconfig index 5b106256e3..11f6948f93 100644 --- a/configs/olimex-stm32-e407/usbnsh/defconfig +++ b/configs/olimex-stm32-e407/usbnsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-stm32-e407/webserver/defconfig b/configs/olimex-stm32-e407/webserver/defconfig index 1dc4a81350..2e790c9e1b 100644 --- a/configs/olimex-stm32-e407/webserver/defconfig +++ b/configs/olimex-stm32-e407/webserver/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-stm32-h405/usbnsh/defconfig b/configs/olimex-stm32-h405/usbnsh/defconfig index d7b93c6f39..042364cd6d 100644 --- a/configs/olimex-stm32-h405/usbnsh/defconfig +++ b/configs/olimex-stm32-h405/usbnsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-stm32-h407/nsh/defconfig b/configs/olimex-stm32-h407/nsh/defconfig index 5b7fc3953c..0936be97e1 100644 --- a/configs/olimex-stm32-h407/nsh/defconfig +++ b/configs/olimex-stm32-h407/nsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-stm32-p107/nsh/defconfig b/configs/olimex-stm32-p107/nsh/defconfig index 31419f01d3..4ce159df73 100644 --- a/configs/olimex-stm32-p107/nsh/defconfig +++ b/configs/olimex-stm32-p107/nsh/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/olimex-stm32-p207/nsh/defconfig b/configs/olimex-stm32-p207/nsh/defconfig index 4d722560c9..965a7c32a8 100644 --- a/configs/olimex-stm32-p207/nsh/defconfig +++ b/configs/olimex-stm32-p207/nsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-stm32-p407/knsh/defconfig b/configs/olimex-stm32-p407/knsh/defconfig index 6d16d46801..f5b9cc2d99 100644 --- a/configs/olimex-stm32-p407/knsh/defconfig +++ b/configs/olimex-stm32-p407/knsh/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-stm32-p407/nsh/defconfig b/configs/olimex-stm32-p407/nsh/defconfig index ba3df2081c..0131469661 100644 --- a/configs/olimex-stm32-p407/nsh/defconfig +++ b/configs/olimex-stm32-p407/nsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimex-strp711/nettest/defconfig b/configs/olimex-strp711/nettest/defconfig index c674451e64..e0ccedba80 100644 --- a/configs/olimex-strp711/nettest/defconfig +++ b/configs/olimex-strp711/nettest/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_ARM7TDMI=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="str71x" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/olimex-strp711/nsh/defconfig b/configs/olimex-strp711/nsh/defconfig index 403c18d2d8..01d338d07f 100644 --- a/configs/olimex-strp711/nsh/defconfig +++ b/configs/olimex-strp711/nsh/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_ARM7TDMI=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="str71x" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/olimexino-stm32/can/defconfig b/configs/olimexino-stm32/can/defconfig index 70af8286ac..6cc8af2285 100644 --- a/configs/olimexino-stm32/can/defconfig +++ b/configs/olimexino-stm32/can/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimexino-stm32/composite/defconfig b/configs/olimexino-stm32/composite/defconfig index 7868baf421..898f6ae919 100644 --- a/configs/olimexino-stm32/composite/defconfig +++ b/configs/olimexino-stm32/composite/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimexino-stm32/nsh/defconfig b/configs/olimexino-stm32/nsh/defconfig index cbd0b1ee53..486a4aea62 100644 --- a/configs/olimexino-stm32/nsh/defconfig +++ b/configs/olimexino-stm32/nsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimexino-stm32/smallnsh/defconfig b/configs/olimexino-stm32/smallnsh/defconfig index 733b350a76..39a7a0efdf 100644 --- a/configs/olimexino-stm32/smallnsh/defconfig +++ b/configs/olimexino-stm32/smallnsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/olimexino-stm32/tiny/defconfig b/configs/olimexino-stm32/tiny/defconfig index e9623a27c1..ec4bcd7661 100644 --- a/configs/olimexino-stm32/tiny/defconfig +++ b/configs/olimexino-stm32/tiny/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/open1788/knsh/defconfig b/configs/open1788/knsh/defconfig index d212c88d60..830d16a862 100644 --- a/configs/open1788/knsh/defconfig +++ b/configs/open1788/knsh/defconfig @@ -126,7 +126,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/open1788/nsh/defconfig b/configs/open1788/nsh/defconfig index e82b30e6fc..fe79328722 100644 --- a/configs/open1788/nsh/defconfig +++ b/configs/open1788/nsh/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/open1788/nxlines/defconfig b/configs/open1788/nxlines/defconfig index 03cbe946cf..4718ef242c 100644 --- a/configs/open1788/nxlines/defconfig +++ b/configs/open1788/nxlines/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/pcduino-a10/nsh/defconfig b/configs/pcduino-a10/nsh/defconfig index 979c390657..5bf38982d2 100644 --- a/configs/pcduino-a10/nsh/defconfig +++ b/configs/pcduino-a10/nsh/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXA8=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="a1x" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/photon/nsh/defconfig b/configs/photon/nsh/defconfig index cc15facab1..cb67991831 100644 --- a/configs/photon/nsh/defconfig +++ b/configs/photon/nsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/photon/usbnsh/defconfig b/configs/photon/usbnsh/defconfig index 6ed65236de..1e72753651 100644 --- a/configs/photon/usbnsh/defconfig +++ b/configs/photon/usbnsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/photon/wlan/defconfig b/configs/photon/wlan/defconfig index a7343600a3..652636ab5e 100644 --- a/configs/photon/wlan/defconfig +++ b/configs/photon/wlan/defconfig @@ -169,7 +169,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/sabre-6quad/nsh/defconfig b/configs/sabre-6quad/nsh/defconfig index d1150487a1..e6854aefa3 100644 --- a/configs/sabre-6quad/nsh/defconfig +++ b/configs/sabre-6quad/nsh/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXA9=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="imx6" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sabre-6quad/smp/defconfig b/configs/sabre-6quad/smp/defconfig index aaa6ab6f57..d8f479ef6d 100644 --- a/configs/sabre-6quad/smp/defconfig +++ b/configs/sabre-6quad/smp/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXA9=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="imx6" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sam3u-ek/knsh/defconfig b/configs/sam3u-ek/knsh/defconfig index 957d6793f9..0d45737050 100644 --- a/configs/sam3u-ek/knsh/defconfig +++ b/configs/sam3u-ek/knsh/defconfig @@ -126,7 +126,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="sam34" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/sam3u-ek/nsh/defconfig b/configs/sam3u-ek/nsh/defconfig index cb160f53f9..1115ecb270 100644 --- a/configs/sam3u-ek/nsh/defconfig +++ b/configs/sam3u-ek/nsh/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="sam34" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/sam3u-ek/nx/defconfig b/configs/sam3u-ek/nx/defconfig index e1b4343fea..2494de67ac 100644 --- a/configs/sam3u-ek/nx/defconfig +++ b/configs/sam3u-ek/nx/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="sam34" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/sam3u-ek/nxwm/defconfig b/configs/sam3u-ek/nxwm/defconfig index 1d52e79483..8cd9244edf 100644 --- a/configs/sam3u-ek/nxwm/defconfig +++ b/configs/sam3u-ek/nxwm/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="sam34" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/sam4cmp-db/nsh/defconfig b/configs/sam4cmp-db/nsh/defconfig index d2668d7d97..1794bf5c2f 100644 --- a/configs/sam4cmp-db/nsh/defconfig +++ b/configs/sam4cmp-db/nsh/defconfig @@ -150,7 +150,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="sam34" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/sam4e-ek/nsh/defconfig b/configs/sam4e-ek/nsh/defconfig index 0304c87164..cd4b617a70 100644 --- a/configs/sam4e-ek/nsh/defconfig +++ b/configs/sam4e-ek/nsh/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="sam34" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/sam4e-ek/nxwm/defconfig b/configs/sam4e-ek/nxwm/defconfig index de7f8e0ff7..ed4c3f7e1a 100644 --- a/configs/sam4e-ek/nxwm/defconfig +++ b/configs/sam4e-ek/nxwm/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="sam34" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/sam4e-ek/usbnsh/defconfig b/configs/sam4e-ek/usbnsh/defconfig index bf1d810406..f26914f97d 100644 --- a/configs/sam4e-ek/usbnsh/defconfig +++ b/configs/sam4e-ek/usbnsh/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="sam34" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/sam4l-xplained/nsh/defconfig b/configs/sam4l-xplained/nsh/defconfig index 9e348834a9..c31e95a224 100644 --- a/configs/sam4l-xplained/nsh/defconfig +++ b/configs/sam4l-xplained/nsh/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="sam34" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/sam4s-xplained-pro/nsh/defconfig b/configs/sam4s-xplained-pro/nsh/defconfig index 7b457d4c1b..ab547b3535 100644 --- a/configs/sam4s-xplained-pro/nsh/defconfig +++ b/configs/sam4s-xplained-pro/nsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="sam34" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/sam4s-xplained/nsh/defconfig b/configs/sam4s-xplained/nsh/defconfig index c65076ca53..d8874cd629 100644 --- a/configs/sam4s-xplained/nsh/defconfig +++ b/configs/sam4s-xplained/nsh/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="sam34" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/sama5d2-xult/nsh/defconfig b/configs/sama5d2-xult/nsh/defconfig index 38b839251a..29da9edcbc 100644 --- a/configs/sama5d2-xult/nsh/defconfig +++ b/configs/sama5d2-xult/nsh/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXA5=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d3-xplained/bridge/defconfig b/configs/sama5d3-xplained/bridge/defconfig index 1ea7843df9..7e940c157c 100644 --- a/configs/sama5d3-xplained/bridge/defconfig +++ b/configs/sama5d3-xplained/bridge/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXA5=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d3-xplained/nsh/defconfig b/configs/sama5d3-xplained/nsh/defconfig index 5ec73af6b2..9800716ad6 100644 --- a/configs/sama5d3-xplained/nsh/defconfig +++ b/configs/sama5d3-xplained/nsh/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXA5=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d3x-ek/demo/defconfig b/configs/sama5d3x-ek/demo/defconfig index cb022bfbf6..fde9166472 100644 --- a/configs/sama5d3x-ek/demo/defconfig +++ b/configs/sama5d3x-ek/demo/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXA5=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d3x-ek/hello/defconfig b/configs/sama5d3x-ek/hello/defconfig index f50c4635f7..b89238191d 100644 --- a/configs/sama5d3x-ek/hello/defconfig +++ b/configs/sama5d3x-ek/hello/defconfig @@ -127,7 +127,7 @@ CONFIG_ARCH_CORTEXA5=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set diff --git a/configs/sama5d3x-ek/norboot/defconfig b/configs/sama5d3x-ek/norboot/defconfig index 9cb9df10b0..f17b0631dc 100644 --- a/configs/sama5d3x-ek/norboot/defconfig +++ b/configs/sama5d3x-ek/norboot/defconfig @@ -127,7 +127,7 @@ CONFIG_ARCH_CORTEXA5=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set diff --git a/configs/sama5d3x-ek/nsh/defconfig b/configs/sama5d3x-ek/nsh/defconfig index b93f5f7bd9..cced99e1ed 100644 --- a/configs/sama5d3x-ek/nsh/defconfig +++ b/configs/sama5d3x-ek/nsh/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXA5=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d3x-ek/nx/defconfig b/configs/sama5d3x-ek/nx/defconfig index ec4167e1f8..5f847f9088 100644 --- a/configs/sama5d3x-ek/nx/defconfig +++ b/configs/sama5d3x-ek/nx/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXA5=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d3x-ek/nxplayer/defconfig b/configs/sama5d3x-ek/nxplayer/defconfig index 895711e473..0fe83187f0 100644 --- a/configs/sama5d3x-ek/nxplayer/defconfig +++ b/configs/sama5d3x-ek/nxplayer/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXA5=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d3x-ek/nxwm/defconfig b/configs/sama5d3x-ek/nxwm/defconfig index 7fde00d212..15b961d99f 100644 --- a/configs/sama5d3x-ek/nxwm/defconfig +++ b/configs/sama5d3x-ek/nxwm/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXA5=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d3x-ek/ov2640/defconfig b/configs/sama5d3x-ek/ov2640/defconfig index 8e347a5bbf..b9330a2019 100644 --- a/configs/sama5d3x-ek/ov2640/defconfig +++ b/configs/sama5d3x-ek/ov2640/defconfig @@ -127,7 +127,7 @@ CONFIG_ARCH_CORTEXA5=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set diff --git a/configs/sama5d4-ek/at25boot/defconfig b/configs/sama5d4-ek/at25boot/defconfig index ee0cb7bcc0..11a0dab220 100644 --- a/configs/sama5d4-ek/at25boot/defconfig +++ b/configs/sama5d4-ek/at25boot/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXA5=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d4-ek/bridge/defconfig b/configs/sama5d4-ek/bridge/defconfig index f3d5a25f98..bbb4e9e530 100644 --- a/configs/sama5d4-ek/bridge/defconfig +++ b/configs/sama5d4-ek/bridge/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXA5=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d4-ek/dramboot/defconfig b/configs/sama5d4-ek/dramboot/defconfig index eb434699a6..c25c40e231 100644 --- a/configs/sama5d4-ek/dramboot/defconfig +++ b/configs/sama5d4-ek/dramboot/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXA5=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d4-ek/elf/defconfig b/configs/sama5d4-ek/elf/defconfig index 18e83b0f28..07a6c79d33 100644 --- a/configs/sama5d4-ek/elf/defconfig +++ b/configs/sama5d4-ek/elf/defconfig @@ -131,7 +131,7 @@ CONFIG_ARCH_CORTEXA5=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d4-ek/ipv6/defconfig b/configs/sama5d4-ek/ipv6/defconfig index a2e87c41a4..fbcd409311 100644 --- a/configs/sama5d4-ek/ipv6/defconfig +++ b/configs/sama5d4-ek/ipv6/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXA5=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d4-ek/knsh/defconfig b/configs/sama5d4-ek/knsh/defconfig index 405444e65e..39104b9481 100644 --- a/configs/sama5d4-ek/knsh/defconfig +++ b/configs/sama5d4-ek/knsh/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXA5=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d4-ek/nsh/defconfig b/configs/sama5d4-ek/nsh/defconfig index 7e46c8e891..5a4c97c83c 100644 --- a/configs/sama5d4-ek/nsh/defconfig +++ b/configs/sama5d4-ek/nsh/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXA5=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d4-ek/nxwm/defconfig b/configs/sama5d4-ek/nxwm/defconfig index 2f64e48067..63014d2966 100644 --- a/configs/sama5d4-ek/nxwm/defconfig +++ b/configs/sama5d4-ek/nxwm/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXA5=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/sama5d4-ek/ramtest/defconfig b/configs/sama5d4-ek/ramtest/defconfig index eb0e9975c8..e199864e5a 100644 --- a/configs/sama5d4-ek/ramtest/defconfig +++ b/configs/sama5d4-ek/ramtest/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXA5=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-a" CONFIG_ARCH_CHIP="sama5" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_FPU=y # CONFIG_ARCH_HAVE_DPFPU is not set CONFIG_ARCH_FPU=y diff --git a/configs/samd20-xplained/nsh/defconfig b/configs/samd20-xplained/nsh/defconfig index 2698d1f26b..f7143f1a8c 100644 --- a/configs/samd20-xplained/nsh/defconfig +++ b/configs/samd20-xplained/nsh/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXM0=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv6-m" CONFIG_ARCH_CHIP="samdl" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set # CONFIG_ARMV7M_LAZYFPU is not set diff --git a/configs/samd21-xplained/nsh/defconfig b/configs/samd21-xplained/nsh/defconfig index 2ca7f6cc7e..67c907795d 100644 --- a/configs/samd21-xplained/nsh/defconfig +++ b/configs/samd21-xplained/nsh/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXM0=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv6-m" CONFIG_ARCH_CHIP="samdl" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set # CONFIG_ARMV7M_LAZYFPU is not set diff --git a/configs/same70-xplained/netnsh/defconfig b/configs/same70-xplained/netnsh/defconfig index 8551c2f5af..ea1f8fbbdc 100644 --- a/configs/same70-xplained/netnsh/defconfig +++ b/configs/same70-xplained/netnsh/defconfig @@ -129,7 +129,7 @@ CONFIG_ARCH_CORTEXM7=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="samv7" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/same70-xplained/nsh/defconfig b/configs/same70-xplained/nsh/defconfig index 34c5952009..4cdbf698ca 100644 --- a/configs/same70-xplained/nsh/defconfig +++ b/configs/same70-xplained/nsh/defconfig @@ -127,7 +127,7 @@ CONFIG_ARCH_CORTEXM7=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="samv7" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/saml21-xplained/nsh/defconfig b/configs/saml21-xplained/nsh/defconfig index daeeadbcb9..3e1d6fdd03 100644 --- a/configs/saml21-xplained/nsh/defconfig +++ b/configs/saml21-xplained/nsh/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXM0=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv6-m" CONFIG_ARCH_CHIP="samdl" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set # CONFIG_ARMV7M_LAZYFPU is not set diff --git a/configs/samv71-xult/knsh/defconfig b/configs/samv71-xult/knsh/defconfig index 9da3cefc30..084a65b9f0 100644 --- a/configs/samv71-xult/knsh/defconfig +++ b/configs/samv71-xult/knsh/defconfig @@ -132,7 +132,7 @@ CONFIG_ARCH_CORTEXM7=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="samv7" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/samv71-xult/module/defconfig b/configs/samv71-xult/module/defconfig index 5089cd6c51..2f89f12a0a 100644 --- a/configs/samv71-xult/module/defconfig +++ b/configs/samv71-xult/module/defconfig @@ -127,7 +127,7 @@ CONFIG_ARCH_CORTEXM7=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="samv7" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/samv71-xult/mxtxplnd/defconfig b/configs/samv71-xult/mxtxplnd/defconfig index 9a75d142e9..d9fc28ec2d 100644 --- a/configs/samv71-xult/mxtxplnd/defconfig +++ b/configs/samv71-xult/mxtxplnd/defconfig @@ -127,7 +127,7 @@ CONFIG_ARCH_CORTEXM7=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="samv7" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/samv71-xult/netnsh/defconfig b/configs/samv71-xult/netnsh/defconfig index 9b1053f824..0cf0b67a8e 100644 --- a/configs/samv71-xult/netnsh/defconfig +++ b/configs/samv71-xult/netnsh/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXM7=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="samv7" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/samv71-xult/nsh/defconfig b/configs/samv71-xult/nsh/defconfig index ff014cd174..3233d2a89f 100644 --- a/configs/samv71-xult/nsh/defconfig +++ b/configs/samv71-xult/nsh/defconfig @@ -127,7 +127,7 @@ CONFIG_ARCH_CORTEXM7=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="samv7" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/samv71-xult/nxwm/defconfig b/configs/samv71-xult/nxwm/defconfig index 4cbb4db7bf..704a09e308 100644 --- a/configs/samv71-xult/nxwm/defconfig +++ b/configs/samv71-xult/nxwm/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXM7=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="samv7" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/samv71-xult/vnc/defconfig b/configs/samv71-xult/vnc/defconfig index f915136f6d..da546e0dd0 100644 --- a/configs/samv71-xult/vnc/defconfig +++ b/configs/samv71-xult/vnc/defconfig @@ -129,7 +129,7 @@ CONFIG_ARCH_CORTEXM7=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="samv7" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/samv71-xult/vnxwm/defconfig b/configs/samv71-xult/vnxwm/defconfig index 0203c8dbcc..454f319c8c 100644 --- a/configs/samv71-xult/vnxwm/defconfig +++ b/configs/samv71-xult/vnxwm/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXM7=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="samv7" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/shenzhou/nsh/defconfig b/configs/shenzhou/nsh/defconfig index c42f1f9c5b..b43530adc2 100644 --- a/configs/shenzhou/nsh/defconfig +++ b/configs/shenzhou/nsh/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/shenzhou/nxwm/defconfig b/configs/shenzhou/nxwm/defconfig index 16444b5295..e1f8f33041 100644 --- a/configs/shenzhou/nxwm/defconfig +++ b/configs/shenzhou/nxwm/defconfig @@ -131,7 +131,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/shenzhou/thttpd/defconfig b/configs/shenzhou/thttpd/defconfig index df08fe16e2..98020af006 100644 --- a/configs/shenzhou/thttpd/defconfig +++ b/configs/shenzhou/thttpd/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/spark/composite/defconfig b/configs/spark/composite/defconfig index ddfcc9aac7..281a489e6c 100644 --- a/configs/spark/composite/defconfig +++ b/configs/spark/composite/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/spark/nsh/defconfig b/configs/spark/nsh/defconfig index a44e488a3f..1e1c422438 100644 --- a/configs/spark/nsh/defconfig +++ b/configs/spark/nsh/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/spark/usbmsc/defconfig b/configs/spark/usbmsc/defconfig index cf97cd3832..feca6a0a92 100644 --- a/configs/spark/usbmsc/defconfig +++ b/configs/spark/usbmsc/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/spark/usbnsh/defconfig b/configs/spark/usbnsh/defconfig index e6727e2d5d..8fcdcc3ce6 100644 --- a/configs/spark/usbnsh/defconfig +++ b/configs/spark/usbnsh/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/spark/usbserial/defconfig b/configs/spark/usbserial/defconfig index 4be8fdeae3..8d6a8293da 100644 --- a/configs/spark/usbserial/defconfig +++ b/configs/spark/usbserial/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm3210e-eval/composite/defconfig b/configs/stm3210e-eval/composite/defconfig index 949b9d986d..4bfafde9e3 100644 --- a/configs/stm3210e-eval/composite/defconfig +++ b/configs/stm3210e-eval/composite/defconfig @@ -128,7 +128,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm3210e-eval/nsh/defconfig b/configs/stm3210e-eval/nsh/defconfig index b2de1b24a6..8ccc2e7606 100644 --- a/configs/stm3210e-eval/nsh/defconfig +++ b/configs/stm3210e-eval/nsh/defconfig @@ -128,7 +128,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm3210e-eval/nsh2/defconfig b/configs/stm3210e-eval/nsh2/defconfig index 785325e187..4e78fee3f0 100644 --- a/configs/stm3210e-eval/nsh2/defconfig +++ b/configs/stm3210e-eval/nsh2/defconfig @@ -128,7 +128,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm3210e-eval/nx/defconfig b/configs/stm3210e-eval/nx/defconfig index 1c2caadb46..951415392f 100644 --- a/configs/stm3210e-eval/nx/defconfig +++ b/configs/stm3210e-eval/nx/defconfig @@ -128,7 +128,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm3210e-eval/nxterm/defconfig b/configs/stm3210e-eval/nxterm/defconfig index 59e50dc2d5..a577757298 100644 --- a/configs/stm3210e-eval/nxterm/defconfig +++ b/configs/stm3210e-eval/nxterm/defconfig @@ -128,7 +128,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm3210e-eval/pm/defconfig b/configs/stm3210e-eval/pm/defconfig index 36a1d96c0b..a05bfcc94b 100644 --- a/configs/stm3210e-eval/pm/defconfig +++ b/configs/stm3210e-eval/pm/defconfig @@ -128,7 +128,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm3210e-eval/usbmsc/defconfig b/configs/stm3210e-eval/usbmsc/defconfig index 487998ea6f..84983fb9fc 100644 --- a/configs/stm3210e-eval/usbmsc/defconfig +++ b/configs/stm3210e-eval/usbmsc/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm3210e-eval/usbserial/defconfig b/configs/stm3210e-eval/usbserial/defconfig index 777dcca2b1..fb49e872c7 100644 --- a/configs/stm3210e-eval/usbserial/defconfig +++ b/configs/stm3210e-eval/usbserial/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm3220g-eval/dhcpd/defconfig b/configs/stm3220g-eval/dhcpd/defconfig index 160af24c19..ca619c0056 100644 --- a/configs/stm3220g-eval/dhcpd/defconfig +++ b/configs/stm3220g-eval/dhcpd/defconfig @@ -131,7 +131,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3220g-eval/nettest/defconfig b/configs/stm3220g-eval/nettest/defconfig index 79f91ed9c9..010d4fa174 100644 --- a/configs/stm3220g-eval/nettest/defconfig +++ b/configs/stm3220g-eval/nettest/defconfig @@ -131,7 +131,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3220g-eval/nsh/defconfig b/configs/stm3220g-eval/nsh/defconfig index 5f77349013..1b8ee32471 100644 --- a/configs/stm3220g-eval/nsh/defconfig +++ b/configs/stm3220g-eval/nsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3220g-eval/nsh2/defconfig b/configs/stm3220g-eval/nsh2/defconfig index 03e70710e6..003e9148ac 100644 --- a/configs/stm3220g-eval/nsh2/defconfig +++ b/configs/stm3220g-eval/nsh2/defconfig @@ -131,7 +131,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3220g-eval/nxwm/defconfig b/configs/stm3220g-eval/nxwm/defconfig index a8289003d3..c09050cf11 100644 --- a/configs/stm3220g-eval/nxwm/defconfig +++ b/configs/stm3220g-eval/nxwm/defconfig @@ -131,7 +131,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3220g-eval/telnetd/defconfig b/configs/stm3220g-eval/telnetd/defconfig index 23207c48d3..be338e0500 100644 --- a/configs/stm3220g-eval/telnetd/defconfig +++ b/configs/stm3220g-eval/telnetd/defconfig @@ -131,7 +131,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3240g-eval/dhcpd/defconfig b/configs/stm3240g-eval/dhcpd/defconfig index 489af9d107..49863ae158 100644 --- a/configs/stm3240g-eval/dhcpd/defconfig +++ b/configs/stm3240g-eval/dhcpd/defconfig @@ -131,7 +131,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3240g-eval/discover/defconfig b/configs/stm3240g-eval/discover/defconfig index ff9492a797..67c33f4078 100644 --- a/configs/stm3240g-eval/discover/defconfig +++ b/configs/stm3240g-eval/discover/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3240g-eval/knxwm/defconfig b/configs/stm3240g-eval/knxwm/defconfig index bedd01275c..2dc44e36db 100644 --- a/configs/stm3240g-eval/knxwm/defconfig +++ b/configs/stm3240g-eval/knxwm/defconfig @@ -136,7 +136,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3240g-eval/nettest/defconfig b/configs/stm3240g-eval/nettest/defconfig index 74ee1bf174..be929fb671 100644 --- a/configs/stm3240g-eval/nettest/defconfig +++ b/configs/stm3240g-eval/nettest/defconfig @@ -131,7 +131,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3240g-eval/nsh/defconfig b/configs/stm3240g-eval/nsh/defconfig index 03fd25607c..ab364fa992 100644 --- a/configs/stm3240g-eval/nsh/defconfig +++ b/configs/stm3240g-eval/nsh/defconfig @@ -131,7 +131,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3240g-eval/nsh2/defconfig b/configs/stm3240g-eval/nsh2/defconfig index 5df0cbb4ae..e412f481f3 100644 --- a/configs/stm3240g-eval/nsh2/defconfig +++ b/configs/stm3240g-eval/nsh2/defconfig @@ -131,7 +131,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3240g-eval/nxterm/defconfig b/configs/stm3240g-eval/nxterm/defconfig index c0091e5014..bd0d5919b4 100644 --- a/configs/stm3240g-eval/nxterm/defconfig +++ b/configs/stm3240g-eval/nxterm/defconfig @@ -131,7 +131,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3240g-eval/nxwm/defconfig b/configs/stm3240g-eval/nxwm/defconfig index 25302bfd13..d4f41b9d83 100644 --- a/configs/stm3240g-eval/nxwm/defconfig +++ b/configs/stm3240g-eval/nxwm/defconfig @@ -131,7 +131,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3240g-eval/telnetd/defconfig b/configs/stm3240g-eval/telnetd/defconfig index a61c0b9e53..abb14d9aae 100644 --- a/configs/stm3240g-eval/telnetd/defconfig +++ b/configs/stm3240g-eval/telnetd/defconfig @@ -131,7 +131,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3240g-eval/webserver/defconfig b/configs/stm3240g-eval/webserver/defconfig index c17a8808a7..877d772f46 100644 --- a/configs/stm3240g-eval/webserver/defconfig +++ b/configs/stm3240g-eval/webserver/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm3240g-eval/xmlrpc/defconfig b/configs/stm3240g-eval/xmlrpc/defconfig index b305f8a0ec..32ec3cb2eb 100644 --- a/configs/stm3240g-eval/xmlrpc/defconfig +++ b/configs/stm3240g-eval/xmlrpc/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32_tiny/nsh/defconfig b/configs/stm32_tiny/nsh/defconfig index 0fc0869f59..2588da219c 100644 --- a/configs/stm32_tiny/nsh/defconfig +++ b/configs/stm32_tiny/nsh/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm32_tiny/usbnsh/defconfig b/configs/stm32_tiny/usbnsh/defconfig index cf42fb77ab..f471ae9dbc 100644 --- a/configs/stm32_tiny/usbnsh/defconfig +++ b/configs/stm32_tiny/usbnsh/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm32butterfly2/nsh/defconfig b/configs/stm32butterfly2/nsh/defconfig index af2ce5eaff..ce0251c52c 100644 --- a/configs/stm32butterfly2/nsh/defconfig +++ b/configs/stm32butterfly2/nsh/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm32butterfly2/nshnet/defconfig b/configs/stm32butterfly2/nshnet/defconfig index 19f09b84d8..fbf702ddf1 100644 --- a/configs/stm32butterfly2/nshnet/defconfig +++ b/configs/stm32butterfly2/nshnet/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm32butterfly2/nshusbdev/defconfig b/configs/stm32butterfly2/nshusbdev/defconfig index a7e8ea4682..920a2e768c 100644 --- a/configs/stm32butterfly2/nshusbdev/defconfig +++ b/configs/stm32butterfly2/nshusbdev/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm32butterfly2/nshusbhost/defconfig b/configs/stm32butterfly2/nshusbhost/defconfig index af2ce5eaff..ce0251c52c 100644 --- a/configs/stm32butterfly2/nshusbhost/defconfig +++ b/configs/stm32butterfly2/nshusbhost/defconfig @@ -124,7 +124,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm32f0discovery/nsh/defconfig b/configs/stm32f0discovery/nsh/defconfig index 2de0149b07..643b2b8269 100644 --- a/configs/stm32f0discovery/nsh/defconfig +++ b/configs/stm32f0discovery/nsh/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM0=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv6-m" CONFIG_ARCH_CHIP="stm32f0" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set # CONFIG_ARMV7M_LAZYFPU is not set diff --git a/configs/stm32f103-minimum/audio_tone/defconfig b/configs/stm32f103-minimum/audio_tone/defconfig index b1aaff58c7..a02e34ff9f 100644 --- a/configs/stm32f103-minimum/audio_tone/defconfig +++ b/configs/stm32f103-minimum/audio_tone/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm32f103-minimum/buttons/defconfig b/configs/stm32f103-minimum/buttons/defconfig index 9df3702195..741e878765 100644 --- a/configs/stm32f103-minimum/buttons/defconfig +++ b/configs/stm32f103-minimum/buttons/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm32f103-minimum/jlx12864g/defconfig b/configs/stm32f103-minimum/jlx12864g/defconfig index 6e2609d3de..5044311070 100644 --- a/configs/stm32f103-minimum/jlx12864g/defconfig +++ b/configs/stm32f103-minimum/jlx12864g/defconfig @@ -157,7 +157,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm32f103-minimum/nrf24/defconfig b/configs/stm32f103-minimum/nrf24/defconfig index e4f64d8a78..e47dac3b56 100644 --- a/configs/stm32f103-minimum/nrf24/defconfig +++ b/configs/stm32f103-minimum/nrf24/defconfig @@ -153,7 +153,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm32f103-minimum/nsh/defconfig b/configs/stm32f103-minimum/nsh/defconfig index 22a2e0f4c5..9c30d971fd 100644 --- a/configs/stm32f103-minimum/nsh/defconfig +++ b/configs/stm32f103-minimum/nsh/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm32f103-minimum/pwm/defconfig b/configs/stm32f103-minimum/pwm/defconfig index 866f13a871..d7926d95f4 100644 --- a/configs/stm32f103-minimum/pwm/defconfig +++ b/configs/stm32f103-minimum/pwm/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm32f103-minimum/rfid-rc522/defconfig b/configs/stm32f103-minimum/rfid-rc522/defconfig index a37fd7fc97..105cc29402 100644 --- a/configs/stm32f103-minimum/rfid-rc522/defconfig +++ b/configs/stm32f103-minimum/rfid-rc522/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm32f103-minimum/rgbled/defconfig b/configs/stm32f103-minimum/rgbled/defconfig index ee2a4acaf8..057b09e1be 100644 --- a/configs/stm32f103-minimum/rgbled/defconfig +++ b/configs/stm32f103-minimum/rgbled/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm32f103-minimum/usbnsh/defconfig b/configs/stm32f103-minimum/usbnsh/defconfig index 7df553e8f2..4d93790163 100644 --- a/configs/stm32f103-minimum/usbnsh/defconfig +++ b/configs/stm32f103-minimum/usbnsh/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm32f103-minimum/userled/defconfig b/configs/stm32f103-minimum/userled/defconfig index e2a5fb92e2..43ee87336b 100644 --- a/configs/stm32f103-minimum/userled/defconfig +++ b/configs/stm32f103-minimum/userled/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm32f103-minimum/veml6070/defconfig b/configs/stm32f103-minimum/veml6070/defconfig index feccccdff7..115d1fa491 100644 --- a/configs/stm32f103-minimum/veml6070/defconfig +++ b/configs/stm32f103-minimum/veml6070/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm32f3discovery/nsh/defconfig b/configs/stm32f3discovery/nsh/defconfig index c653d03d9b..dcf4905161 100644 --- a/configs/stm32f3discovery/nsh/defconfig +++ b/configs/stm32f3discovery/nsh/defconfig @@ -131,7 +131,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f3discovery/usbnsh/defconfig b/configs/stm32f3discovery/usbnsh/defconfig index 6be7f12386..1ffe9da444 100644 --- a/configs/stm32f3discovery/usbnsh/defconfig +++ b/configs/stm32f3discovery/usbnsh/defconfig @@ -131,7 +131,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f411e-disco/nsh/defconfig b/configs/stm32f411e-disco/nsh/defconfig index 9686d0eb47..0dd9aff2d1 100644 --- a/configs/stm32f411e-disco/nsh/defconfig +++ b/configs/stm32f411e-disco/nsh/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm32f429i-disco/extflash/defconfig b/configs/stm32f429i-disco/extflash/defconfig index 72f0cb1103..4815ca65f5 100644 --- a/configs/stm32f429i-disco/extflash/defconfig +++ b/configs/stm32f429i-disco/extflash/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f429i-disco/lcd/defconfig b/configs/stm32f429i-disco/lcd/defconfig index 0b1afd96f3..ca01660057 100644 --- a/configs/stm32f429i-disco/lcd/defconfig +++ b/configs/stm32f429i-disco/lcd/defconfig @@ -126,7 +126,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f429i-disco/ltdc/defconfig b/configs/stm32f429i-disco/ltdc/defconfig index b37b090ad9..c657306064 100644 --- a/configs/stm32f429i-disco/ltdc/defconfig +++ b/configs/stm32f429i-disco/ltdc/defconfig @@ -126,7 +126,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f429i-disco/nsh/defconfig b/configs/stm32f429i-disco/nsh/defconfig index 6a557ca398..5ef88f3db5 100644 --- a/configs/stm32f429i-disco/nsh/defconfig +++ b/configs/stm32f429i-disco/nsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f429i-disco/nxwm/defconfig b/configs/stm32f429i-disco/nxwm/defconfig index 9f23c31269..c79f7605eb 100644 --- a/configs/stm32f429i-disco/nxwm/defconfig +++ b/configs/stm32f429i-disco/nxwm/defconfig @@ -126,7 +126,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f429i-disco/usbmsc/defconfig b/configs/stm32f429i-disco/usbmsc/defconfig index 41f8d4a71f..b7f855e112 100644 --- a/configs/stm32f429i-disco/usbmsc/defconfig +++ b/configs/stm32f429i-disco/usbmsc/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f429i-disco/usbnsh/defconfig b/configs/stm32f429i-disco/usbnsh/defconfig index 6a1151e902..2b2c0a4ea9 100644 --- a/configs/stm32f429i-disco/usbnsh/defconfig +++ b/configs/stm32f429i-disco/usbnsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f4discovery/canard/defconfig b/configs/stm32f4discovery/canard/defconfig index a749dd7184..e3378d9df3 100644 --- a/configs/stm32f4discovery/canard/defconfig +++ b/configs/stm32f4discovery/canard/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f4discovery/cxxtest/defconfig b/configs/stm32f4discovery/cxxtest/defconfig index 311c6b7bef..736dca9f6c 100644 --- a/configs/stm32f4discovery/cxxtest/defconfig +++ b/configs/stm32f4discovery/cxxtest/defconfig @@ -131,7 +131,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f4discovery/elf/defconfig b/configs/stm32f4discovery/elf/defconfig index 9a207fd361..cf42ee96b1 100644 --- a/configs/stm32f4discovery/elf/defconfig +++ b/configs/stm32f4discovery/elf/defconfig @@ -128,7 +128,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm32f4discovery/ipv6/defconfig b/configs/stm32f4discovery/ipv6/defconfig index fef1a68da4..2db3c1beeb 100644 --- a/configs/stm32f4discovery/ipv6/defconfig +++ b/configs/stm32f4discovery/ipv6/defconfig @@ -131,7 +131,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f4discovery/kostest/defconfig b/configs/stm32f4discovery/kostest/defconfig index b61b1b9266..ea9e35d2f9 100644 --- a/configs/stm32f4discovery/kostest/defconfig +++ b/configs/stm32f4discovery/kostest/defconfig @@ -133,7 +133,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm32f4discovery/netnsh/defconfig b/configs/stm32f4discovery/netnsh/defconfig index c83039d231..ada356f924 100644 --- a/configs/stm32f4discovery/netnsh/defconfig +++ b/configs/stm32f4discovery/netnsh/defconfig @@ -131,7 +131,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f4discovery/nsh/defconfig b/configs/stm32f4discovery/nsh/defconfig index 512b380bc3..78f20fe4e4 100644 --- a/configs/stm32f4discovery/nsh/defconfig +++ b/configs/stm32f4discovery/nsh/defconfig @@ -131,7 +131,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f4discovery/nxlines/defconfig b/configs/stm32f4discovery/nxlines/defconfig index 74e43686b3..3ca9c479ad 100644 --- a/configs/stm32f4discovery/nxlines/defconfig +++ b/configs/stm32f4discovery/nxlines/defconfig @@ -131,7 +131,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f4discovery/pm/defconfig b/configs/stm32f4discovery/pm/defconfig index 09c3cd9844..11fc388755 100644 --- a/configs/stm32f4discovery/pm/defconfig +++ b/configs/stm32f4discovery/pm/defconfig @@ -131,7 +131,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f4discovery/posix_spawn/defconfig b/configs/stm32f4discovery/posix_spawn/defconfig index 66c4784a2c..f9eaa1d647 100644 --- a/configs/stm32f4discovery/posix_spawn/defconfig +++ b/configs/stm32f4discovery/posix_spawn/defconfig @@ -128,7 +128,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm32f4discovery/pseudoterm/defconfig b/configs/stm32f4discovery/pseudoterm/defconfig index 97133261f9..a4e5461f78 100644 --- a/configs/stm32f4discovery/pseudoterm/defconfig +++ b/configs/stm32f4discovery/pseudoterm/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f4discovery/rgbled/defconfig b/configs/stm32f4discovery/rgbled/defconfig index 8388526708..f9d9463532 100644 --- a/configs/stm32f4discovery/rgbled/defconfig +++ b/configs/stm32f4discovery/rgbled/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f4discovery/uavcan/defconfig b/configs/stm32f4discovery/uavcan/defconfig index faf7a59692..ca307a2006 100644 --- a/configs/stm32f4discovery/uavcan/defconfig +++ b/configs/stm32f4discovery/uavcan/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f4discovery/usbnsh/defconfig b/configs/stm32f4discovery/usbnsh/defconfig index 69afe5c0f0..35c6cd7d45 100644 --- a/configs/stm32f4discovery/usbnsh/defconfig +++ b/configs/stm32f4discovery/usbnsh/defconfig @@ -131,7 +131,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f4discovery/xen1210/defconfig b/configs/stm32f4discovery/xen1210/defconfig index 4cb55120be..514ce52a4e 100644 --- a/configs/stm32f4discovery/xen1210/defconfig +++ b/configs/stm32f4discovery/xen1210/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set diff --git a/configs/stm32f746-ws/nsh/defconfig b/configs/stm32f746-ws/nsh/defconfig index 78a78b6b6d..eeb171767e 100644 --- a/configs/stm32f746-ws/nsh/defconfig +++ b/configs/stm32f746-ws/nsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM7=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32f7" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/stm32f746g-disco/nsh/defconfig b/configs/stm32f746g-disco/nsh/defconfig index 44de2fce8e..5fdda7f074 100644 --- a/configs/stm32f746g-disco/nsh/defconfig +++ b/configs/stm32f746g-disco/nsh/defconfig @@ -131,7 +131,7 @@ CONFIG_ARCH_CORTEXM7=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32f7" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/stm32l476-mdk/nsh/defconfig b/configs/stm32l476-mdk/nsh/defconfig index b2fa084959..c94b92be89 100644 --- a/configs/stm32l476-mdk/nsh/defconfig +++ b/configs/stm32l476-mdk/nsh/defconfig @@ -122,7 +122,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32l4" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm32l476vg-disco/nsh/defconfig b/configs/stm32l476vg-disco/nsh/defconfig index 271fa59a8a..ec45e553a1 100644 --- a/configs/stm32l476vg-disco/nsh/defconfig +++ b/configs/stm32l476vg-disco/nsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32l4" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y diff --git a/configs/stm32ldiscovery/nsh/defconfig b/configs/stm32ldiscovery/nsh/defconfig index b232b87651..9dfcacb8a2 100644 --- a/configs/stm32ldiscovery/nsh/defconfig +++ b/configs/stm32ldiscovery/nsh/defconfig @@ -128,7 +128,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/stm32vldiscovery/nsh/defconfig b/configs/stm32vldiscovery/nsh/defconfig index dae7c1499f..3865292e7a 100644 --- a/configs/stm32vldiscovery/nsh/defconfig +++ b/configs/stm32vldiscovery/nsh/defconfig @@ -128,7 +128,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/teensy-3.x/nsh/defconfig b/configs/teensy-3.x/nsh/defconfig index b25f07cda7..e4b50bd3c2 100644 --- a/configs/teensy-3.x/nsh/defconfig +++ b/configs/teensy-3.x/nsh/defconfig @@ -127,7 +127,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="kinetis" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/teensy-3.x/usbnsh/defconfig b/configs/teensy-3.x/usbnsh/defconfig index 20c9140b35..cf01c27675 100644 --- a/configs/teensy-3.x/usbnsh/defconfig +++ b/configs/teensy-3.x/usbnsh/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="kinetis" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/teensy-lc/nsh/defconfig b/configs/teensy-lc/nsh/defconfig index 869e6ffda4..66fc7e6177 100644 --- a/configs/teensy-lc/nsh/defconfig +++ b/configs/teensy-lc/nsh/defconfig @@ -125,7 +125,7 @@ CONFIG_ARCH_CORTEXM0=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv6-m" CONFIG_ARCH_CHIP="kl" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set # CONFIG_ARMV7M_LAZYFPU is not set diff --git a/configs/tm4c123g-launchpad/nsh/defconfig b/configs/tm4c123g-launchpad/nsh/defconfig index 3de4f3483a..625f0d748c 100644 --- a/configs/tm4c123g-launchpad/nsh/defconfig +++ b/configs/tm4c123g-launchpad/nsh/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/tm4c1294-launchpad/ipv6/defconfig b/configs/tm4c1294-launchpad/ipv6/defconfig index 18fcdb5a44..e663a9301b 100644 --- a/configs/tm4c1294-launchpad/ipv6/defconfig +++ b/configs/tm4c1294-launchpad/ipv6/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/tm4c1294-launchpad/nsh/defconfig b/configs/tm4c1294-launchpad/nsh/defconfig index 5b43f5a0b3..91c0781f88 100644 --- a/configs/tm4c1294-launchpad/nsh/defconfig +++ b/configs/tm4c1294-launchpad/nsh/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="tiva" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/twr-k60n512/nsh/defconfig b/configs/twr-k60n512/nsh/defconfig index 97c292fa10..9f8055ba1b 100644 --- a/configs/twr-k60n512/nsh/defconfig +++ b/configs/twr-k60n512/nsh/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="kinetis" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/twr-k64f120m/netnsh/defconfig b/configs/twr-k64f120m/netnsh/defconfig index c21f3e406d..ac3ca96275 100644 --- a/configs/twr-k64f120m/netnsh/defconfig +++ b/configs/twr-k64f120m/netnsh/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="kinetis" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/twr-k64f120m/nsh/defconfig b/configs/twr-k64f120m/nsh/defconfig index 79b091ba48..c3b81237e9 100644 --- a/configs/twr-k64f120m/nsh/defconfig +++ b/configs/twr-k64f120m/nsh/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="kinetis" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/u-blox-c027/nsh/defconfig b/configs/u-blox-c027/nsh/defconfig index b86c883a7e..d4295f62f9 100644 --- a/configs/u-blox-c027/nsh/defconfig +++ b/configs/u-blox-c027/nsh/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/viewtool-stm32f107/highpri/defconfig b/configs/viewtool-stm32f107/highpri/defconfig index 8bd3da10e6..6e883f2526 100644 --- a/configs/viewtool-stm32f107/highpri/defconfig +++ b/configs/viewtool-stm32f107/highpri/defconfig @@ -128,7 +128,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/viewtool-stm32f107/netnsh/defconfig b/configs/viewtool-stm32f107/netnsh/defconfig index e8b3aa5884..92708d6039 100644 --- a/configs/viewtool-stm32f107/netnsh/defconfig +++ b/configs/viewtool-stm32f107/netnsh/defconfig @@ -130,7 +130,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/viewtool-stm32f107/nsh/defconfig b/configs/viewtool-stm32f107/nsh/defconfig index 84a800c995..bca8db1a3d 100644 --- a/configs/viewtool-stm32f107/nsh/defconfig +++ b/configs/viewtool-stm32f107/nsh/defconfig @@ -128,7 +128,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/xmc4500-relax/nsh/defconfig b/configs/xmc4500-relax/nsh/defconfig index 517820a864..db33aac810 100644 --- a/configs/xmc4500-relax/nsh/defconfig +++ b/configs/xmc4500-relax/nsh/defconfig @@ -128,7 +128,7 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="xmc4" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/zkit-arm-1769/hello/defconfig b/configs/zkit-arm-1769/hello/defconfig index f641d6ca31..7bea34aa2d 100644 --- a/configs/zkit-arm-1769/hello/defconfig +++ b/configs/zkit-arm-1769/hello/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/zkit-arm-1769/nsh/defconfig b/configs/zkit-arm-1769/nsh/defconfig index 684cbdb20e..0afb96b403 100644 --- a/configs/zkit-arm-1769/nsh/defconfig +++ b/configs/zkit-arm-1769/nsh/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/zkit-arm-1769/nxhello/defconfig b/configs/zkit-arm-1769/nxhello/defconfig index acd07157a0..5472c32bc3 100644 --- a/configs/zkit-arm-1769/nxhello/defconfig +++ b/configs/zkit-arm-1769/nxhello/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/zkit-arm-1769/thttpd/defconfig b/configs/zkit-arm-1769/thttpd/defconfig index 6529e993a1..50238485e5 100644 --- a/configs/zkit-arm-1769/thttpd/defconfig +++ b/configs/zkit-arm-1769/thttpd/defconfig @@ -123,7 +123,7 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y diff --git a/configs/zp214xpa/nsh/defconfig b/configs/zp214xpa/nsh/defconfig index 427e4093ee..1f6698b93a 100644 --- a/configs/zp214xpa/nsh/defconfig +++ b/configs/zp214xpa/nsh/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_ARM7TDMI=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="lpc214x" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set diff --git a/configs/zp214xpa/nxlines/defconfig b/configs/zp214xpa/nxlines/defconfig index d7ba60feaa..8358bb153b 100644 --- a/configs/zp214xpa/nxlines/defconfig +++ b/configs/zp214xpa/nxlines/defconfig @@ -121,7 +121,7 @@ CONFIG_ARCH_ARM7TDMI=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="lpc214x" -# CONFIG_ARM_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARCH_HAVE_FPU is not set # CONFIG_ARCH_HAVE_DPFPU is not set # CONFIG_ARCH_HAVE_TRUSTZONE is not set -- GitLab From 7fd08a60a326dc13b1554b246dc4d29c0b440f58 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 13 May 2017 16:53:55 -0600 Subject: [PATCH 810/990] Move prototype from nuttx/include/nuttx/arch.h to apps/include/platform/cxxinitialize.h --- include/nuttx/arch.h | 20 -------------------- libxx/Kconfig | 8 -------- 2 files changed, 28 deletions(-) diff --git a/include/nuttx/arch.h b/include/nuttx/arch.h index 8e02bc3529..6bbdf758b4 100644 --- a/include/nuttx/arch.h +++ b/include/nuttx/arch.h @@ -1940,26 +1940,6 @@ char up_romgetc(FAR const char *ptr); void up_mdelay(unsigned int milliseconds); void up_udelay(useconds_t microseconds); -/**************************************************************************** - * Name: up_cxxinitialize - * - * Description: - * If C++ and C++ static constructors are supported, then this function - * must be provided by board-specific logic in order to perform - * initialization of the static C++ class instances. - * - * This function should then be called in the application-specific - * logic in order to perform the C++ initialization. NOTE that no - * component of the core NuttX RTOS logic is involved; This function - * definition only provides the 'contract' between application - * specific C++ code and platform-specific toolchain support - * - ****************************************************************************/ - -#if defined(CONFIG_HAVE_CXX) && defined(CONFIG_HAVE_CXXINITIALIZE) -void up_cxxinitialize(void); -#endif - /**************************************************************************** * These are standard interfaces that are exported by the OS for use by the * architecture specific logic diff --git a/libxx/Kconfig b/libxx/Kconfig index b55bcd799a..722207e6b9 100644 --- a/libxx/Kconfig +++ b/libxx/Kconfig @@ -22,14 +22,6 @@ config HAVE_CXX if HAVE_CXX -config HAVE_CXXINITIALIZE - bool "Have C++ initialization" - default n - ---help--- - The platform-specific logic includes support for initialization - of static C++ instances for this architecture and for the selected - toolchain (via up_cxxinitialize()). - config CXX_NEWLONG bool "size_t is type long" default n -- GitLab From 7cc2ee25ec932540e2b1aa382f80bfd58660f723 Mon Sep 17 00:00:00 2001 From: Matias v01d Date: Sat, 13 May 2017 17:06:58 -0600 Subject: [PATCH 811/990] libc/wchar: Versions mbrlen and mbsrtowcs taken and adapted from FreeBSD code (at https://github.com/freebsd/freebsd/) --- libc/wchar/Make.defs | 1 + libc/wchar/lib_mbrlen.c | 68 +++++++++++++++++++++++++++++++++++++ libc/wchar/lib_mbsrtowcs.c | 69 ++++++++++++++++++++++++++++++++++++++ 3 files changed, 138 insertions(+) create mode 100644 libc/wchar/lib_mbrlen.c create mode 100644 libc/wchar/lib_mbsrtowcs.c diff --git a/libc/wchar/Make.defs b/libc/wchar/Make.defs index 12c559a5ce..c9a3efec05 100644 --- a/libc/wchar/Make.defs +++ b/libc/wchar/Make.defs @@ -43,6 +43,7 @@ CSRCS += lib_wcslcpy.c lib_wcsxfrm.c lib_wcrtomb.c lib_wcsftime.c CSRCS += lib_wcscoll.c lib_wcstol.c lib_wcstoll.c lib_wcstoul.c CSRCS += lib_wcstoull.c lib_wcstold.c lib_wcstof.c lib_wcstod.c CSRCS += lib_swprintf.c lib_mbsnrtowcs.c lib_wcsnrtombs.c +CSRCS += lib_mbrlen.c lib_mbsrtowcs.c # Add the wchar directory to the build diff --git a/libc/wchar/lib_mbrlen.c b/libc/wchar/lib_mbrlen.c new file mode 100644 index 0000000000..de075005d4 --- /dev/null +++ b/libc/wchar/lib_mbrlen.c @@ -0,0 +1,68 @@ +/**************************************************************************** + * libc/wchar/lib_mbrtowc.c + * + * Copyright (c) 2002-2004 Tim J. Robbins. + * All rights reserved. + * + * Copyright (c) 2011 The FreeBSD Foundation + * All rights reserved. + * + * Portions of this software were developed by David Chisnall + * under sponsorship from the FreeBSD Foundation. + * + * 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. + * + * THIS SOFTWARE IS PROVIDED BY THE AUTHOR 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 AUTHOR 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 + +#ifdef CONFIG_LIBC_WCHAR + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: mbrlen + * + * Description: + * Determine number of bytes in next multibyte character + * + ****************************************************************************/ + +size_t mbrlen(const char *s, size_t n, mbstate_t *ps) +{ + return mbrtowc(NULL, s, n, ps); +} + +#endif diff --git a/libc/wchar/lib_mbsrtowcs.c b/libc/wchar/lib_mbsrtowcs.c new file mode 100644 index 0000000000..a3630b3439 --- /dev/null +++ b/libc/wchar/lib_mbsrtowcs.c @@ -0,0 +1,69 @@ +/**************************************************************************** + * libc/wchar/lib_mbsrtowcs.c + * + * Copyright (c) 2002-2004 Tim J. Robbins. + * All rights reserved. + * + * Copyright (c) 2011 The FreeBSD Foundation + * All rights reserved. + * + * Portions of this software were developed by David Chisnall + * under sponsorship from the FreeBSD Foundation. + * + * 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. + * + * THIS SOFTWARE IS PROVIDED BY THE AUTHOR 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 AUTHOR 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 + +#ifdef CONFIG_LIBC_WCHAR + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: mbsrtowcs + * + * Description: + * Convert a multibyte string to a wide-character string + * + ****************************************************************************/ + +size_t mbsrtowcs(wchar_t *dst, const char **src, size_t len, mbstate_t *ps) +{ + return mbsnrtowcs(dst, src, SIZE_MAX, len, ps); +} + +#endif -- GitLab From 820ef7059e5c2ce36d59f37261f3a6d9ca5438cf Mon Sep 17 00:00:00 2001 From: Matias v01d Date: Sat, 13 May 2017 17:07:40 -0600 Subject: [PATCH 812/990] libc/wchar: Versions mbrlen and mbsrtowcs taken and adapted from FreeBSD code (at https://github.com/freebsd/freebsd/) --- libc/wchar/lib_mbsrtowcs.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libc/wchar/lib_mbsrtowcs.c b/libc/wchar/lib_mbsrtowcs.c index a3630b3439..ffab88d184 100644 --- a/libc/wchar/lib_mbsrtowcs.c +++ b/libc/wchar/lib_mbsrtowcs.c @@ -54,7 +54,7 @@ ****************************************************************************/ /**************************************************************************** - * Name: mbsrtowcs + * Name: mbsrtowcs * * Description: * Convert a multibyte string to a wide-character string -- GitLab From a52967a772b310ae10250d6b9905ac017fadc22d Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 13 May 2017 17:40:46 -0600 Subject: [PATCH 813/990] Syslog interrrupt buffer: eliminate a warning about an uninitialized variable; simply some related logic. --- drivers/syslog/syslog_intbuffer.c | 26 ++++++-------------------- 1 file changed, 6 insertions(+), 20 deletions(-) diff --git a/drivers/syslog/syslog_intbuffer.c b/drivers/syslog/syslog_intbuffer.c index e68ff3fb74..59aad10954 100644 --- a/drivers/syslog/syslog_intbuffer.c +++ b/drivers/syslog/syslog_intbuffer.c @@ -120,11 +120,8 @@ static const char g_overrun_msg[SYSLOG_BUFOVERRUN_SIZE] = SYSLOG_BUFOVERRUN_MESS int syslog_remove_intbuffer(void) { irqstate_t flags; - uint32_t inndx; uint32_t outndx; - uint32_t endndx; - int inuse = 0; - int ch; + int ret = EOF; /* Extraction of the character and adjustment of the circular buffer * indices must be performed in a critical section to protect from @@ -133,25 +130,14 @@ int syslog_remove_intbuffer(void) flags = enter_critical_section(); - /* How much space is left in the intbuffer? */ + /* Check if the interrupt buffer? is empty */ - inndx = (uint32_t)g_syslog_intbuffer.si_inndx; outndx = (uint32_t)g_syslog_intbuffer.si_outndx; - if (inndx != outndx) + if (outndx != (uint32_t)g_syslog_intbuffer.si_inndx) { - /* Handle the case where the inndx has wrapped around */ + /* Not empty.. Take the next character from the interrupt buffer */ - endndx = inndx; - if (endndx < outndx) - { - endndx += SYSLOG_INTBUFSIZE; - } - - inuse = (int)(endndx - outndx); - - /* Take the next character from the interrupt buffer */ - - ch = g_syslog_intbuffer.si_buffer[outndx]; + ret = g_syslog_intbuffer.si_buffer[outndx]; /* Increment the OUT index, handling wrap-around */ @@ -167,7 +153,7 @@ int syslog_remove_intbuffer(void) /* Now we can send the extracted character to the SYSLOG device */ - return (inuse > 0) ? ch : EOF; + return ret; } /**************************************************************************** -- GitLab From 06db5614e71465e5d354d2c3b2841aa97b642ec9 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 13 May 2017 18:05:40 -0600 Subject: [PATCH 814/990] Fix a warning about can.o appearing twice in the same rule. --- drivers/Makefile | 4 ---- 1 file changed, 4 deletions(-) diff --git a/drivers/Makefile b/drivers/Makefile index 83d830c8ab..41f5d06c03 100644 --- a/drivers/Makefile +++ b/drivers/Makefile @@ -93,10 +93,6 @@ endif endif endif -ifeq ($(CONFIG_CAN),y) - CSRCS += can.c -endif - ifeq ($(CONFIG_PWM),y) CSRCS += pwm.c endif -- GitLab From fa649df52eb7eeb57d0dc8d70c1e738c75ef8093 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 14 May 2017 08:39:53 -0600 Subject: [PATCH 815/990] Photon: Small update from Simon Piriou. --- drivers/wireless/ieee80211/bcmf_driver.c | 4 +--- drivers/wireless/ieee80211/bcmf_netdev.c | 10 +++++----- 2 files changed, 6 insertions(+), 8 deletions(-) diff --git a/drivers/wireless/ieee80211/bcmf_driver.c b/drivers/wireless/ieee80211/bcmf_driver.c index 4666d8da9f..94a2c750c5 100644 --- a/drivers/wireless/ieee80211/bcmf_driver.c +++ b/drivers/wireless/ieee80211/bcmf_driver.c @@ -370,7 +370,6 @@ void bcmf_wl_scan_event_handler(FAR struct bcmf_dev_s *priv, struct bcmf_event_s *event, unsigned int len) { uint32_t status; - uint32_t reason; uint32_t event_len; struct wl_escan_result *result; struct wl_bss_info *bss; @@ -387,7 +386,6 @@ void bcmf_wl_scan_event_handler(FAR struct bcmf_dev_s *priv, } status = bcmf_getle32(&event->status); - reason = bcmf_getle32(&event->reason); escan_result_len = bcmf_getle32(&event->len); len -= sizeof(struct bcmf_event_s); @@ -464,7 +462,7 @@ wl_escan_result_processed: /* Scan done */ - wlinfo("escan done event %d %d\n", status, reason); + wlinfo("escan done event %d %d\n", status, bcmf_getle32(&event->reason)); wd_cancel(priv->scan_timeout); diff --git a/drivers/wireless/ieee80211/bcmf_netdev.c b/drivers/wireless/ieee80211/bcmf_netdev.c index 02527fe60c..455b15529b 100644 --- a/drivers/wireless/ieee80211/bcmf_netdev.c +++ b/drivers/wireless/ieee80211/bcmf_netdev.c @@ -177,7 +177,7 @@ int bcmf_netdev_alloc_tx_frame(FAR struct bcmf_dev_s *priv) priv->cur_tx_frame = bcmf_bdc_allocate_frame(priv, MAX_NET_DEV_MTU, true); if (!priv->cur_tx_frame) { - wlerr("Cannot allocate TX frame\n"); + wlerr("ERROR: Cannot allocate TX frame\n"); return -ENOMEM; } @@ -215,7 +215,7 @@ static int bcmf_transmit(FAR struct bcmf_dev_s *priv, if (ret) { - wlerr("Failed to transmit frame\n"); + wlerr("ERROR: Failed to transmit frame\n"); return -EIO; } @@ -392,7 +392,7 @@ static void bcmf_receive(FAR struct bcmf_dev_s *priv) else #endif { - wlinfo("RX dropped\n"); + wlerr("ERROR: RX dropped\n"); NETDEV_RXDROPPED(&priv->bc_dev); priv->bus->free_frame(priv, frame); } @@ -992,11 +992,11 @@ static int bcmf_ioctl(FAR struct net_driver_s *dev, int cmd, switch (cmd) { case SIOCSIWSCAN: - ret = bcmf_wl_start_scan(priv, (struct ifreq *)arg); + ret = bcmf_wl_start_scan(priv, (struct iwreq *)arg); break; case SIOCGIWSCAN: - ret = bcmf_wl_get_scan_results(priv, (struct ifreq *)arg); + ret = bcmf_wl_get_scan_results(priv, (struct iwreq *)arg); break; case SIOCSIFHWADDR: /* Set device MAC address */ -- GitLab From 8dc7f6d79e63b26b5890fcee318334f196d0a595 Mon Sep 17 00:00:00 2001 From: Simon Piriou Date: Sun, 14 May 2017 09:08:32 -0600 Subject: [PATCH 816/990] tcp: wait for 3-Way Handshare before accept() returns --- net/tcp/Kconfig | 7 +++++++ net/tcp/tcp_input.c | 20 ++++++++++++++++++++ 2 files changed, 27 insertions(+) diff --git a/net/tcp/Kconfig b/net/tcp/Kconfig index fac41794dc..1660b080ee 100644 --- a/net/tcp/Kconfig +++ b/net/tcp/Kconfig @@ -156,6 +156,13 @@ config NET_TCPBACKLOG Incoming connections pend in a backlog until accept() is called. The size of the backlog is selected when listen() is called. +config NET_ACCEPT_ON_ACK + bool "accept() returns on TCP 3-Way Handshake completion" + default n + ---help--- + accept() returns after 3-Way Handshake is complete (SYN, SYN/ACK, ACK). + Without this flag it returns after SYN packet is received. + config NET_TCP_SPLIT bool "Enable packet splitting" default n diff --git a/net/tcp/tcp_input.c b/net/tcp/tcp_input.c index 1918bd3492..22e11be7ae 100644 --- a/net/tcp/tcp_input.c +++ b/net/tcp/tcp_input.c @@ -185,6 +185,8 @@ static void tcp_input(FAR struct net_driver_s *dev, unsigned int iplen) */ conn->crefs = 1; + +#ifndef CONFIG_NET_ACCEPT_ON_ACK if (tcp_accept_connection(dev, conn, tmp16) != OK) { /* No, then we have to give the connection back and drop the packet */ @@ -193,6 +195,7 @@ static void tcp_input(FAR struct net_driver_s *dev, unsigned int iplen) tcp_free(conn); conn = NULL; } +#endif } if (!conn) @@ -464,6 +467,23 @@ found: { conn->tcpstateflags = TCP_ESTABLISHED; +#ifdef CONFIG_NET_ACCEPT_ON_ACK + if (tcp_accept_connection(dev, conn, tcp->destport) != OK) + { + /* No more listener for current port. We can free conn here + * because it has not been shared with upper layers yet as + * handshake is not complete + */ + + nerr("Listen canceled while waiting for ACK on port %d\n", + tcp->destport); + conn->crefs = 0; + tcp_free(conn); + conn = NULL; + goto drop; + } +#endif + #ifdef CONFIG_NET_TCP_WRITE_BUFFERS conn->isn = tcp_getsequence(tcp->ackno); tcp_setsequence(conn->sndseq, conn->isn); -- GitLab From d339ba9e0eb743d5444d9d3b1e31cebb033f5641 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 14 May 2017 10:56:25 -0600 Subject: [PATCH 817/990] TCP: Fix some potential error conditions that could result from deferring the connection until the full 3-way handshake has completed. --- net/tcp/Kconfig | 7 ------ net/tcp/tcp.h | 13 +++++++++++ net/tcp/tcp_input.c | 38 ++++++++++++++++++-------------- net/tcp/tcp_listen.c | 2 +- net/tcp/tcp_timer.c | 52 +++++++++++++++++++++++++++++++++++++++----- 5 files changed, 82 insertions(+), 30 deletions(-) diff --git a/net/tcp/Kconfig b/net/tcp/Kconfig index 1660b080ee..fac41794dc 100644 --- a/net/tcp/Kconfig +++ b/net/tcp/Kconfig @@ -156,13 +156,6 @@ config NET_TCPBACKLOG Incoming connections pend in a backlog until accept() is called. The size of the backlog is selected when listen() is called. -config NET_ACCEPT_ON_ACK - bool "accept() returns on TCP 3-Way Handshake completion" - default n - ---help--- - accept() returns after 3-Way Handshake is complete (SYN, SYN/ACK, ACK). - Without this flag it returns after SYN packet is received. - config NET_TCP_SPLIT bool "Enable packet splitting" default n diff --git a/net/tcp/tcp.h b/net/tcp/tcp.h index 4b3bb85e75..2797f4f3bc 100644 --- a/net/tcp/tcp.h +++ b/net/tcp/tcp.h @@ -697,6 +697,19 @@ void tcp_timer(FAR struct net_driver_s *dev, FAR struct tcp_conn_s *conn, void tcp_listen_initialize(void); +/**************************************************************************** + * Name: tcp_findlistener + * + * Description: + * Return the connection listener for connections on this port (if any) + * + * Assumptions: + * Called at interrupt level + * + ****************************************************************************/ + +FAR struct tcp_conn_s *tcp_findlistener(uint16_t portno); + /**************************************************************************** * Name: tcp_unlisten * diff --git a/net/tcp/tcp_input.c b/net/tcp/tcp_input.c index 22e11be7ae..8788b5ca95 100644 --- a/net/tcp/tcp_input.c +++ b/net/tcp/tcp_input.c @@ -179,23 +179,25 @@ static void tcp_input(FAR struct net_driver_s *dev, unsigned int iplen) conn = tcp_alloc_accept(dev, tcp); if (conn) { - /* The connection structure was successfully allocated. Now see if - * there is an application waiting to accept the connection (or at - * least queue it it for acceptance). + /* The connection structure was successfully allocated and has + * been initialized in the TCP_SYN_RECVD state. The expected + * sequence of events is then the rest of the 3-way handshake: + * + * 1. We just received a TCP SYN packet from a remote host. + * 2. We will send the SYN-ACK response below (perhaps + * repeatedly in the event of a timeout) + * 3. Then we expect to receive an ACK from the remote host + * indicated the TCP socket connection is ESTABLISHED. + * + * Possible failure: + * + * 1. The ACK is never received. This will be handled by + * a timeout managed by tcp_timer(). + * 2. The listener "unlistens()". This will be handled by + * the failure of tcp_accept_connection() when the ACK is received. */ conn->crefs = 1; - -#ifndef CONFIG_NET_ACCEPT_ON_ACK - if (tcp_accept_connection(dev, conn, tmp16) != OK) - { - /* No, then we have to give the connection back and drop the packet */ - - conn->crefs = 0; - tcp_free(conn); - conn = NULL; - } -#endif } if (!conn) @@ -465,9 +467,14 @@ found: if ((flags & TCP_ACKDATA) != 0) { + /* The three way handshake is complete and the TCP connection + * is now in the ESTABLISHED state. + */ + conn->tcpstateflags = TCP_ESTABLISHED; -#ifdef CONFIG_NET_ACCEPT_ON_ACK + /* Wake up any listener waiting for a connection on this port */ + if (tcp_accept_connection(dev, conn, tcp->destport) != OK) { /* No more listener for current port. We can free conn here @@ -482,7 +489,6 @@ found: conn = NULL; goto drop; } -#endif #ifdef CONFIG_NET_TCP_WRITE_BUFFERS conn->isn = tcp_getsequence(tcp->ackno); diff --git a/net/tcp/tcp_listen.c b/net/tcp/tcp_listen.c index f7d771d2b6..b3d36a126d 100644 --- a/net/tcp/tcp_listen.c +++ b/net/tcp/tcp_listen.c @@ -257,7 +257,7 @@ int tcp_accept_connection(FAR struct net_driver_s *dev, */ listener = tcp_findlistener(portno); - if (listener) + if (listener != NULL) { /* Yes, there is a listener. Is it accepting connections now? */ diff --git a/net/tcp/tcp_timer.c b/net/tcp/tcp_timer.c index 245e849ec6..8e21bb5d8f 100644 --- a/net/tcp/tcp_timer.c +++ b/net/tcp/tcp_timer.c @@ -218,17 +218,57 @@ void tcp_timer(FAR struct net_driver_s *dev, FAR struct tcp_conn_s *conn, goto done; } #endif - /* Should we close the connection? */ + /* Check for a timeout on connection in the TCP_SYN_RCVD state. + * On such timeouts, we would normally resend the SYNACK until + * the ACK is received, completing the 3-way handshek. But if + * the retry count elapsed, then we must assume that no ACK is + * forthcoming and terminate the attempted connection. + */ + + if (conn->tcpstateflags == TCP_SYN_RCVD && + conn->nrtx >= TCP_MAXSYNRTX) + { + FAR struct tcp_conn_s *listener; + + conn->tcpstateflags = TCP_CLOSED; + ninfo("TCP state: TCP_CLOSED\n"); + + /* Find the listener for this connectins */ + + listener = tcp_findlistener(conn->lport); + if (listener != NULL) + { + /* We call tcp_callback() for the connection with + * TCP_TIMEDOUT to inform the listener that the + * connection has timed out. + */ + + result = tcp_callback(dev, listener, TCP_TIMEDOUT); + } + + /* We also send a reset packet to the remote host. */ + + tcp_send(dev, conn, TCP_RST | TCP_ACK, hdrlen); + + /* Finally, we must free this TCP connection structure */ + + tcp_free(conn); + goto done; + } + + /* Otherwise, check for a timeout on an established connection. + * If the retry count is exceeded in this case, we should + * close the connection. + */ - if ( + else if ( #ifdef CONFIG_NET_TCP_WRITE_BUFFERS conn->expired > 0 || #else - conn->nrtx == TCP_MAXRTX || + conn->nrtx >= TCP_MAXRTX || #endif - ((conn->tcpstateflags == TCP_SYN_SENT || - conn->tcpstateflags == TCP_SYN_RCVD) && - conn->nrtx == TCP_MAXSYNRTX) + (conn->tcpstateflags == TCP_SYN_SENT && + conn->nrtx >= TCP_MAXSYNRTX) ) { conn->tcpstateflags = TCP_CLOSED; -- GitLab From 7e75d61ea020773a4e143559c86f02992c0dcec3 Mon Sep 17 00:00:00 2001 From: Simon Piriou Date: Sun, 14 May 2017 19:29:44 +0200 Subject: [PATCH 818/990] photon/wlan: disable network logs and add nsh over telnet --- configs/photon/wlan/defconfig | 54 +++++++++++++++++++++-------------- 1 file changed, 33 insertions(+), 21 deletions(-) diff --git a/configs/photon/wlan/defconfig b/configs/photon/wlan/defconfig index 652636ab5e..996eed2273 100644 --- a/configs/photon/wlan/defconfig +++ b/configs/photon/wlan/defconfig @@ -65,14 +65,11 @@ CONFIG_DEBUG_INFO=y # CONFIG_DEBUG_GRAPHICS is not set # CONFIG_DEBUG_LIB is not set # CONFIG_DEBUG_MM is not set -CONFIG_DEBUG_NET=y -CONFIG_DEBUG_NET_ERROR=y -CONFIG_DEBUG_NET_WARN=y -CONFIG_DEBUG_NET_INFO=y +# CONFIG_DEBUG_NET is not set CONFIG_DEBUG_WIRELESS=y CONFIG_DEBUG_WIRELESS_ERROR=y CONFIG_DEBUG_WIRELESS_WARN=y -CONFIG_DEBUG_WIRELESS_INFO=y +# CONFIG_DEBUG_WIRELESS_INFO is not set # CONFIG_DEBUG_SCHED is not set # @@ -169,7 +166,6 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARCH_TOOLCHAIN_IAR is not set # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set @@ -569,6 +565,7 @@ CONFIG_STM32_SDIO_DMAPRIO=0x00010000 # # USB Device Configuration # +# CONFIG_ARCH_TOOLCHAIN_IAR is not set CONFIG_ARCH_TOOLCHAIN_GNU=y # @@ -870,7 +867,9 @@ CONFIG_NETDEVICES=y # General Ethernet MAC Driver Options # # CONFIG_NETDEV_LOOPBACK is not set -# CONFIG_NETDEV_TELNET is not set +CONFIG_NETDEV_TELNET=y +CONFIG_TELNET_RXBUFFER_SIZE=256 +CONFIG_TELNET_TXBUFFER_SIZE=256 # CONFIG_NETDEV_MULTINIC is not set # CONFIG_ARCH_HAVE_NETDEV_STATISTICS is not set CONFIG_NETDEV_LATEINIT=y @@ -892,7 +891,7 @@ CONFIG_NETDEV_LATEINIT=y CONFIG_SERIAL=y # CONFIG_DEV_LOWCONSOLE is not set # CONFIG_SERIAL_REMOVABLE is not set -CONFIG_SERIAL_CONSOLE=y +# CONFIG_SERIAL_CONSOLE is not set # CONFIG_16550_UART is not set # CONFIG_UART_SERIALDRIVER is not set # CONFIG_UART0_SERIALDRIVER is not set @@ -923,9 +922,9 @@ CONFIG_STANDARD_SERIAL=y # CONFIG_SERIAL_DMA is not set # CONFIG_SERIAL_TIOCSERGSTRUCT is not set CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y -CONFIG_USART1_SERIAL_CONSOLE=y +# CONFIG_USART1_SERIAL_CONSOLE is not set # CONFIG_OTHER_SERIAL_CONSOLE is not set -# CONFIG_NO_SERIAL_CONSOLE is not set +CONFIG_NO_SERIAL_CONSOLE=y # # USART1 Configuration @@ -966,11 +965,14 @@ CONFIG_SYSLOG_WRITE=y # CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set -CONFIG_SYSLOG_SERIAL_CONSOLE=y -# CONFIG_SYSLOG_CHAR is not set -CONFIG_SYSLOG_CONSOLE=y +# CONFIG_SYSLOG_SERIAL_CONSOLE is not set +CONFIG_SYSLOG_CHAR=y +# CONFIG_SYSLOG_CONSOLE is not set # CONFIG_SYSLOG_NONE is not set # CONFIG_SYSLOG_FILE is not set +# CONFIG_CONSOLE_SYSLOG is not set +CONFIG_SYSLOG_CHAR_CRLF=y +CONFIG_SYSLOG_DEVPATH="/dev/ttyS0" # CONFIG_SYSLOG_CHARDEV is not set # @@ -1076,7 +1078,6 @@ CONFIG_NET_ARPTAB_SIZE=16 CONFIG_NET_ARP_MAXAGE=120 # CONFIG_NET_ARP_IPIN is not set # CONFIG_NET_ARP_SEND is not set -# CONFIG_NET_ARP_DUMP is not set # # User-space networking stack API @@ -1293,7 +1294,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512 # # CONFIG_C99_BOOL8 is not set CONFIG_HAVE_CXX=y -CONFIG_HAVE_CXXINITIALIZE=y # CONFIG_CXX_NEWLONG is not set # @@ -1310,6 +1310,10 @@ CONFIG_HAVE_CXXINITIALIZE=y # Application Configuration # +# +# NxWidgets/NxWM +# + # # Built-In Applications # @@ -1430,7 +1434,7 @@ CONFIG_NETUTILS_PING=y CONFIG_NETUTILS_PING_SIGNO=13 # CONFIG_NETUTILS_PPPD is not set # CONFIG_NETUTILS_SMTP is not set -# CONFIG_NETUTILS_TELNETD is not set +CONFIG_NETUTILS_TELNETD=y # CONFIG_NETUTILS_TFTPC is not set # CONFIG_NETUTILS_WEBCLIENT is not set # CONFIG_NETUTILS_WEBSERVER is not set @@ -1533,8 +1537,7 @@ CONFIG_NSH_FILEIOSIZE=512 # # Console Configuration # -CONFIG_NSH_CONSOLE=y -# CONFIG_NSH_ALTCONDEV is not set +# CONFIG_NSH_CONSOLE is not set CONFIG_NSH_ARCHINIT=y # @@ -1567,17 +1570,26 @@ CONFIG_NSH_WAPI_ALG=3 CONFIG_NSH_WAPI_SSID="myApSSID" CONFIG_NSH_WAPI_PASSPHRASE="mySSIDpassphrase" CONFIG_NSH_MAX_ROUNDTRIP=20 -# CONFIG_NSH_LOGIN is not set -# CONFIG_NSH_CONSOLE_LOGIN is not set # -# NxWidgets/NxWM +# Telnet Configuration # +CONFIG_NSH_TELNET=y +CONFIG_NSH_TELNETD_PORT=23 +CONFIG_NSH_TELNETD_DAEMONPRIO=100 +CONFIG_NSH_TELNETD_DAEMONSTACKSIZE=2048 +CONFIG_NSH_TELNETD_CLIENTPRIO=100 +CONFIG_NSH_TELNETD_CLIENTSTACKSIZE=2048 +CONFIG_NSH_IOBUFFER_SIZE=512 +# CONFIG_NSH_LOGIN is not set +# CONFIG_NSH_CONSOLE_LOGIN is not set +# CONFIG_NSH_TELNET_LOGIN is not set # # Platform-specific Support # # CONFIG_PLATFORM_CONFIGDATA is not set +CONFIG_HAVE_CXXINITIALIZE=y # # System Libraries and NSH Add-Ons -- GitLab From 8acfea1197e7b6d74672511126bda331d329d6c8 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 14 May 2017 12:14:31 -0600 Subject: [PATCH 819/990] Fix some typos --- configs/photon/wlan/defconfig | 8 ++++---- net/tcp/tcp_input.c | 12 +++++++----- net/tcp/tcp_timer.c | 4 ++-- 3 files changed, 13 insertions(+), 11 deletions(-) diff --git a/configs/photon/wlan/defconfig b/configs/photon/wlan/defconfig index 996eed2273..409aae40fc 100644 --- a/configs/photon/wlan/defconfig +++ b/configs/photon/wlan/defconfig @@ -1310,10 +1310,6 @@ CONFIG_HAVE_CXX=y # Application Configuration # -# -# NxWidgets/NxWM -# - # # Built-In Applications # @@ -1585,6 +1581,10 @@ CONFIG_NSH_IOBUFFER_SIZE=512 # CONFIG_NSH_CONSOLE_LOGIN is not set # CONFIG_NSH_TELNET_LOGIN is not set +# +# NxWidgets/NxWM +# + # # Platform-specific Support # diff --git a/net/tcp/tcp_input.c b/net/tcp/tcp_input.c index 8788b5ca95..dc911bbf3f 100644 --- a/net/tcp/tcp_input.c +++ b/net/tcp/tcp_input.c @@ -194,7 +194,8 @@ static void tcp_input(FAR struct net_driver_s *dev, unsigned int iplen) * 1. The ACK is never received. This will be handled by * a timeout managed by tcp_timer(). * 2. The listener "unlistens()". This will be handled by - * the failure of tcp_accept_connection() when the ACK is received. + * the failure of tcp_accept_connection() when the ACK is + * received. */ conn->crefs = 1; @@ -202,10 +203,11 @@ static void tcp_input(FAR struct net_driver_s *dev, unsigned int iplen) if (!conn) { - /* Either (1) all available connections are in use, or (2) there is no - * application in place to accept the connection. We drop packet and hope that - * the remote end will retransmit the packet at a time when we - * have more spare connections or someone waiting to accept the connection. + /* Either (1) all available connections are in use, or (2) + * there is no application in place to accept the connection. + * We drop packet and hope that the remote end will retransmit + * the packet at a time when we have more spare connections + * or someone waiting to accept the connection. */ #ifdef CONFIG_NET_STATISTICS diff --git a/net/tcp/tcp_timer.c b/net/tcp/tcp_timer.c index 8e21bb5d8f..a9047fc478 100644 --- a/net/tcp/tcp_timer.c +++ b/net/tcp/tcp_timer.c @@ -220,7 +220,7 @@ void tcp_timer(FAR struct net_driver_s *dev, FAR struct tcp_conn_s *conn, #endif /* Check for a timeout on connection in the TCP_SYN_RCVD state. * On such timeouts, we would normally resend the SYNACK until - * the ACK is received, completing the 3-way handshek. But if + * the ACK is received, completing the 3-way handshake. But if * the retry count elapsed, then we must assume that no ACK is * forthcoming and terminate the attempted connection. */ @@ -233,7 +233,7 @@ void tcp_timer(FAR struct net_driver_s *dev, FAR struct tcp_conn_s *conn, conn->tcpstateflags = TCP_CLOSED; ninfo("TCP state: TCP_CLOSED\n"); - /* Find the listener for this connectins */ + /* Find the listener for this connection. */ listener = tcp_findlistener(conn->lport); if (listener != NULL) -- GitLab From aa57fb159da6b20b9b11e79b0dc09e9340bc0826 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 14 May 2017 13:30:59 -0600 Subject: [PATCH 820/990] TCP: Send RST if applicaiton 'unlistens()' before we complete the connection sequence. --- net/tcp/tcp_input.c | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/net/tcp/tcp_input.c b/net/tcp/tcp_input.c index dc911bbf3f..23bec6a6e5 100644 --- a/net/tcp/tcp_input.c +++ b/net/tcp/tcp_input.c @@ -486,10 +486,16 @@ found: nerr("Listen canceled while waiting for ACK on port %d\n", tcp->destport); + + /* Free the connection structure */ + conn->crefs = 0; tcp_free(conn); conn = NULL; - goto drop; + + /* And send a reset packet to the remote host. */ + + goto reset; } #ifdef CONFIG_NET_TCP_WRITE_BUFFERS -- GitLab From 2b5e415fabc4b12d8aa03d947daa12085d3d9f00 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Tue, 9 May 2017 17:22:30 -0400 Subject: [PATCH 821/990] wireless/ieee802154: Starts implementing START.request primitive --- wireless/ieee802154/mac802154.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index a345d81933..8b7b545699 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -1842,6 +1842,8 @@ int mac802154_req_start(MACHANDLE mac, FAR struct ieee802154_start_req_s *req) return -ENOTTY; } + mac802154_givesem(&priv->exclsem); + return OK; errout: -- GitLab From 8ec0b71a599d93a3a1917185b3949af711df3029 Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Sun, 14 May 2017 17:55:07 -0400 Subject: [PATCH 822/990] wireless/ieee802154: Updates configuration settings --- .../clicker2-stm32/mrf24j40-radio/defconfig | 9 ++++---- configs/clicker2-stm32/src/stm32_mrf24j40.c | 7 +----- include/sys/ioctl.h | 2 -- wireless/ieee802154/Kconfig | 23 +++++-------------- wireless/ieee802154/Make.defs | 10 +------- 5 files changed, 12 insertions(+), 39 deletions(-) diff --git a/configs/clicker2-stm32/mrf24j40-radio/defconfig b/configs/clicker2-stm32/mrf24j40-radio/defconfig index e7c649d2c5..b258d177c3 100644 --- a/configs/clicker2-stm32/mrf24j40-radio/defconfig +++ b/configs/clicker2-stm32/mrf24j40-radio/defconfig @@ -16,7 +16,7 @@ CONFIG_HOST_LINUX=y # # Build Configuration # -# CONFIG_APPS_DIR="../apps" +CONFIG_APPS_DIR="../apps" CONFIG_BUILD_FLAT=y # CONFIG_BUILD_2PASS is not set @@ -979,8 +979,7 @@ CONFIG_IOB_NCHAINS=0 # CONFIG_WIRELESS=y CONFIG_WIRELESS_IEEE802154=y -CONFIG_IEEE802154_MAC=y -# CONFIG_IEEE802154_MAC_DEV is not set +CONFIG_IEEE802154_MAC_DEV=y CONFIG_MAC802154_HPWORK=y CONFIG_IEEE802154_NTXDESC=3 CONFIG_IEEE802154_IND_PREALLOC=20 @@ -1163,10 +1162,10 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y # CONFIG_EXAMPLES_NULL is not set -# CONFIG_EXAMPLES_NX is not set # CONFIG_EXAMPLES_NXFFS is not set # CONFIG_EXAMPLES_NXHELLO is not set # CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NX is not set # CONFIG_EXAMPLES_NXLINES is not set # CONFIG_EXAMPLES_NXTERM is not set # CONFIG_EXAMPLES_NXTEXT is not set @@ -1371,7 +1370,7 @@ CONFIG_READLINE_ECHO=y # # IEEE 802.15.4 applications # -# CONFIG_IEEE802154_LIBMAC is not set +CONFIG_IEEE802154_LIBMAC=y CONFIG_IEEE802154_LIBUTILS=y CONFIG_IEEE802154_I8SAK=y CONFIG_IEEE802154_I8SAK_PRIORITY=100 diff --git a/configs/clicker2-stm32/src/stm32_mrf24j40.c b/configs/clicker2-stm32/src/stm32_mrf24j40.c index c92b93239b..c89b28b838 100644 --- a/configs/clicker2-stm32/src/stm32_mrf24j40.c +++ b/configs/clicker2-stm32/src/stm32_mrf24j40.c @@ -1,5 +1,5 @@ /**************************************************************************** - * configs/freedom-kl25z/src/stm32_mrf24j40.c + * configs/clicker2-stm32/src/stm32_mrf24j40.c * * Copyright (C) 2017 Gregory Nutt, All rights reserver * Author: Gregory Nutt @@ -220,9 +220,7 @@ static void stm32_enable_irq(FAR const struct mrf24j40_lower_s *lower, static int stm32_mrf24j40_devsetup(FAR struct stm32_priv_s *priv) { FAR struct ieee802154_radio_s *radio; -#ifdef CONFIG_IEEE802154_MAC MACHANDLE mac; -#endif FAR struct spi_dev_s *spi; int ret; @@ -248,7 +246,6 @@ static int stm32_mrf24j40_devsetup(FAR struct stm32_priv_s *priv) return -ENODEV; } -#if defined(CONFIG_IEEE802154_MAC) /* Create a 802.15.4 MAC device from a 802.15.4 compatible radio device. */ mac = mac802154_create(radio); @@ -285,8 +282,6 @@ static int stm32_mrf24j40_devsetup(FAR struct stm32_priv_s *priv) } #endif -#endif /* CONFIG_IEEE802154_MAC */ - return OK; } diff --git a/include/sys/ioctl.h b/include/sys/ioctl.h index 76abe7f01f..ded8c5a659 100644 --- a/include/sys/ioctl.h +++ b/include/sys/ioctl.h @@ -66,11 +66,9 @@ #ifdef CONFIG_WIRELESS_IEEE802154 -#ifdef CONFIG_IEEE802154_MAC /* Include ieee802.15.4 MAC IOCTL definitions */ # include -#endif #ifdef CONFIG_IEEE802154_MAC_DEV /* Include ieee802.15.4 character driver IOCTL definitions */ diff --git a/wireless/ieee802154/Kconfig b/wireless/ieee802154/Kconfig index 670ea474f3..9e12f8b1bb 100644 --- a/wireless/ieee802154/Kconfig +++ b/wireless/ieee802154/Kconfig @@ -3,31 +3,22 @@ # see the file kconfig-language.txt in the NuttX tools repository. # -config WIRELESS_IEEE802154 - bool "IEEE 802.15.4 Wireless Support" +menuconfig WIRELESS_IEEE802154 + bool "IEEE 802.15.4 Support" default n select MM_IOB - ---help--- - Enables support for the IEEE 802.14.5 Wireless library. - -if WIRELESS_IEEE802154 - -menuconfig IEEE802154_MAC - bool "Generic Media Access Control (MAC) layer for 802.15.4 radios" - default n - depends on WIRELESS_IEEE802154 + depends on WIRELESS ---help--- Enables a Media Access Controller for any IEEE802.15.4 radio device. This in turn can be used by higher layer entities - such as 6lowpan. It is not required to use 802.15.4 radios, - but is strongly suggested to ensure exchange of valid frames. + such as 6lowpan. -if IEEE802154_MAC +if WIRELESS_IEEE802154 config IEEE802154_MAC_DEV bool "Character driver for IEEE 802.15.4 MAC layer" default n - depends on IEEE802154_MAC + depends on WIRELESS_IEEE802154 ---help--- Enable the device driver to expose the IEEE 802.15.4 MAC layer access to user space as IOCTLs @@ -58,8 +49,6 @@ config IEEE802154_NTXDESC ---help--- Configured number of Tx descriptors. Default: 3 -endif # IEEE802154_MAC - config IEEE802154_IND_PREALLOC int "Number of pre-allocated meta-data structures" default 20 diff --git a/wireless/ieee802154/Make.defs b/wireless/ieee802154/Make.defs index 73354b2609..eedec934eb 100644 --- a/wireless/ieee802154/Make.defs +++ b/wireless/ieee802154/Make.defs @@ -37,22 +37,14 @@ ifeq ($(CONFIG_WIRELESS_IEEE802154),y) # Include IEEE 802.15.4 support -CSRCS += mac802154_indalloc.c +CSRCS += mac802154.c mac802154_indalloc.c # Include wireless devices build support -ifeq ($(CONFIG_IEEE802154_MAC),y) -CSRCS += mac802154.c -endif - ifeq ($(CONFIG_IEEE802154_MAC_DEV),y) CSRCS += mac802154_device.c endif -ifeq ($(CONFIG_IEEE802154_DEV),y) -CSRCS += radio802154_device.c -endif - ifeq ($(CONFIG_IEEE802154_NETDEV),y) CSRCS += mac802154_netdev.c endif -- GitLab From b9a769d65decf20c811fdec092a956a2d0cecf66 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Mon, 15 May 2017 07:20:32 -0600 Subject: [PATCH 823/990] drivers: fix some bad NULL checks --- drivers/audio/audio_null.c | 6 ++---- drivers/input/ajoystick.c | 10 ++++++---- drivers/input/djoystick.c | 10 ++++++---- drivers/modem/u-blox.c | 12 ++++++++---- drivers/pwm.c | 12 ++++++++---- drivers/sensors/qencoder.c | 9 ++++++--- drivers/timers/timer.c | 9 ++++++--- drivers/timers/watchdog.c | 12 ++++++++---- 8 files changed, 50 insertions(+), 30 deletions(-) diff --git a/drivers/audio/audio_null.c b/drivers/audio/audio_null.c index d6c522101a..4ed7a010a6 100644 --- a/drivers/audio/audio_null.c +++ b/drivers/audio/audio_null.c @@ -653,6 +653,8 @@ static int null_enqueuebuffer(FAR struct audio_lowerhalf_s *dev, FAR struct null_dev_s *priv = (FAR struct null_dev_s *)dev; bool done; + DEBUGASSERT(priv && apb && priv->dev.upper); + audinfo("apb=%p curbyte=%d nbytes=%d\n", apb, apb->curbyte, apb->nbytes); /* Say that we consumed all of the data */ @@ -663,10 +665,6 @@ static int null_enqueuebuffer(FAR struct audio_lowerhalf_s *dev, done = ((apb->flags & AUDIO_APB_FINAL) != 0); - /* And return the buffer to the upper level */ - - DEBUGASSERT(priv && apb && priv->dev.upper); - /* The buffer belongs to to an upper level. Just forward the event to * the next level up. */ diff --git a/drivers/input/ajoystick.c b/drivers/input/ajoystick.c index 2868e1542a..76c93e43c7 100644 --- a/drivers/input/ajoystick.c +++ b/drivers/input/ajoystick.c @@ -201,7 +201,7 @@ static inline int ajoy_takesem(sem_t *sem) #if !defined(CONFIG_DISABLE_POLL) || !defined(CONFIG_DISABLE_SIGNALS) static void ajoy_enable(FAR struct ajoy_upperhalf_s *priv) { - FAR const struct ajoy_lowerhalf_s *lower = priv->au_lower; + FAR const struct ajoy_lowerhalf_s *lower; FAR struct ajoy_open_s *opriv; ajoy_buttonset_t press; ajoy_buttonset_t release; @@ -210,8 +210,9 @@ static void ajoy_enable(FAR struct ajoy_upperhalf_s *priv) int i; #endif - DEBUGASSERT(priv && priv->au_lower); + DEBUGASSERT(priv); lower = priv->au_lower; + DEBUGASSERT(lower); /* This routine is called both task level and interrupt level, so * interrupts must be disabled. @@ -295,7 +296,7 @@ static void ajoy_interrupt(FAR const struct ajoy_lowerhalf_s *lower, static void ajoy_sample(FAR struct ajoy_upperhalf_s *priv) { - FAR const struct ajoy_lowerhalf_s *lower = priv->au_lower; + FAR const struct ajoy_lowerhalf_s *lower; FAR struct ajoy_open_s *opriv; ajoy_buttonset_t sample; #if !defined(CONFIG_DISABLE_POLL) || !defined(CONFIG_DISABLE_SIGNALS) @@ -308,8 +309,9 @@ static void ajoy_sample(FAR struct ajoy_upperhalf_s *priv) int i; #endif - DEBUGASSERT(priv && priv->au_lower); + DEBUGASSERT(priv); lower = priv->au_lower; + DEBUGASSERT(lower); /* This routine is called both task level and interrupt level, so * interrupts must be disabled. diff --git a/drivers/input/djoystick.c b/drivers/input/djoystick.c index 62f62fe45a..c0559208fb 100644 --- a/drivers/input/djoystick.c +++ b/drivers/input/djoystick.c @@ -201,7 +201,7 @@ static inline int djoy_takesem(sem_t *sem) #if !defined(CONFIG_DISABLE_POLL) || !defined(CONFIG_DISABLE_SIGNALS) static void djoy_enable(FAR struct djoy_upperhalf_s *priv) { - FAR const struct djoy_lowerhalf_s *lower = priv->du_lower; + FAR const struct djoy_lowerhalf_s *lower; FAR struct djoy_open_s *opriv; djoy_buttonset_t press; djoy_buttonset_t release; @@ -210,8 +210,9 @@ static void djoy_enable(FAR struct djoy_upperhalf_s *priv) int i; #endif - DEBUGASSERT(priv && priv->du_lower); + DEBUGASSERT(priv); lower = priv->du_lower; + DEBUGASSERT(lower); /* This routine is called both task level and interrupt level, so * interrupts must be disabled. @@ -295,7 +296,7 @@ static void djoy_interrupt(FAR const struct djoy_lowerhalf_s *lower, static void djoy_sample(FAR struct djoy_upperhalf_s *priv) { - FAR const struct djoy_lowerhalf_s *lower = priv->du_lower; + FAR const struct djoy_lowerhalf_s *lower; FAR struct djoy_open_s *opriv; djoy_buttonset_t sample; #if !defined(CONFIG_DISABLE_POLL) || !defined(CONFIG_DISABLE_SIGNALS) @@ -308,8 +309,9 @@ static void djoy_sample(FAR struct djoy_upperhalf_s *priv) int i; #endif - DEBUGASSERT(priv && priv->du_lower); + DEBUGASSERT(priv); lower = priv->du_lower; + DEBUGASSERT(lower); /* This routine is called both task level and interrupt level, so * interrupts must be disabled. diff --git a/drivers/modem/u-blox.c b/drivers/modem/u-blox.c index 95a7fc29d2..014dac102e 100644 --- a/drivers/modem/u-blox.c +++ b/drivers/modem/u-blox.c @@ -141,13 +141,16 @@ static int ubxmdm_ioctl(FAR struct file* filep, unsigned long arg) { FAR struct inode* inode = filep->f_inode; - FAR struct ubxmdm_upper* upper = inode->i_private; - FAR struct ubxmdm_lower* lower = upper->lower; + FAR struct ubxmdm_upper* upper; + FAR struct ubxmdm_lower* lower; int ret; FAR struct ubxmdm_status* status; m_info("cmd: %d arg: %ld\n", cmd, arg); - DEBUGASSERT(upper && lower); + upper = inode->i_private; + DEBUGASSERT(upper != NULL); + lower = upper->lower; + DEBUGASSERT(lower != NULL); switch (cmd) { @@ -320,8 +323,9 @@ void ubxmdm_unregister(FAR void *handle) FAR struct ubxmdm_lower *lower; upper = (FAR struct ubxmdm_upper*) handle; + DEBUGASSERT(upper != NULL); lower = upper->lower; - DEBUGASSERT(upper && lower); + DEBUGASSERT(lower != NULL); m_info("Unregistering: %s\n", upper->path); diff --git a/drivers/pwm.c b/drivers/pwm.c index 78b60751c0..24c5ae4105 100644 --- a/drivers/pwm.c +++ b/drivers/pwm.c @@ -318,11 +318,13 @@ static ssize_t pwm_write(FAR struct file *filep, FAR const char *buffer, #ifdef CONFIG_PWM_PULSECOUNT static int pwm_start(FAR struct pwm_upperhalf_s *upper, unsigned int oflags) { - FAR struct pwm_lowerhalf_s *lower = upper->dev; + FAR struct pwm_lowerhalf_s *lower; irqstate_t flags; int ret = OK; - DEBUGASSERT(upper != NULL && lower->ops->start != NULL); + DEBUGASSERT(upper != NULL); + lower = upper->dev; + DEBUGASSERT(lower != NULL && lower->ops->start != NULL); /* Verify that the PWM is not already running */ @@ -385,10 +387,12 @@ static int pwm_start(FAR struct pwm_upperhalf_s *upper, unsigned int oflags) #else static int pwm_start(FAR struct pwm_upperhalf_s *upper, unsigned int oflags) { - FAR struct pwm_lowerhalf_s *lower = upper->dev; + FAR struct pwm_lowerhalf_s *lower; int ret = OK; - DEBUGASSERT(upper != NULL && lower->ops->start != NULL); + DEBUGASSERT(upper != NULL); + lower = upper->dev; + DEBUGASSERT(lower != NULL && lower->ops->start != NULL); /* Verify that the PWM is not already running */ diff --git a/drivers/sensors/qencoder.c b/drivers/sensors/qencoder.c index 7f6edd0978..ead9ec6de7 100644 --- a/drivers/sensors/qencoder.c +++ b/drivers/sensors/qencoder.c @@ -276,12 +276,15 @@ static ssize_t qe_write(FAR struct file *filep, FAR const char *buffer, size_t b static int qe_ioctl(FAR struct file *filep, int cmd, unsigned long arg) { FAR struct inode *inode = filep->f_inode; - FAR struct qe_upperhalf_s *upper = inode->i_private; - FAR struct qe_lowerhalf_s *lower = upper->lower; + FAR struct qe_upperhalf_s *upper; + FAR struct qe_lowerhalf_s *lower; int ret; sninfo("cmd: %d arg: %ld\n", cmd, arg); - DEBUGASSERT(upper && lower); + upper = inode->i_private; + DEBUGASSERT(upper != NULL); + lower = upper->lower; + DEBUGASSERT(lower != NULL); /* Get exclusive access to the device structures */ diff --git a/drivers/timers/timer.c b/drivers/timers/timer.c index 667be5276d..4cfdacaac7 100644 --- a/drivers/timers/timer.c +++ b/drivers/timers/timer.c @@ -254,12 +254,15 @@ static ssize_t timer_write(FAR struct file *filep, FAR const char *buffer, static int timer_ioctl(FAR struct file *filep, int cmd, unsigned long arg) { FAR struct inode *inode = filep->f_inode; - FAR struct timer_upperhalf_s *upper = inode->i_private; - FAR struct timer_lowerhalf_s *lower = upper->lower; + FAR struct timer_upperhalf_s *upper; + FAR struct timer_lowerhalf_s *lower; int ret; tmrinfo("cmd: %d arg: %ld\n", cmd, arg); - DEBUGASSERT(upper && lower); + upper = inode->i_private; + DEBUGASSERT(upper != NULL); + lower = upper->lower; + DEBUGASSERT(lower != NULL); /* Handle built-in ioctl commands */ diff --git a/drivers/timers/watchdog.c b/drivers/timers/watchdog.c index e9320a9612..7ccab15a06 100644 --- a/drivers/timers/watchdog.c +++ b/drivers/timers/watchdog.c @@ -240,12 +240,15 @@ static ssize_t wdog_write(FAR struct file *filep, FAR const char *buffer, size_t static int wdog_ioctl(FAR struct file *filep, int cmd, unsigned long arg) { FAR struct inode *inode = filep->f_inode; - FAR struct watchdog_upperhalf_s *upper = inode->i_private; - FAR struct watchdog_lowerhalf_s *lower = upper->lower; + FAR struct watchdog_upperhalf_s *upper; + FAR struct watchdog_lowerhalf_s *lower; int ret; wdinfo("cmd: %d arg: %ld\n", cmd, arg); - DEBUGASSERT(upper && lower); + upper = inode->i_private; + DEBUGASSERT(upper != NULL); + lower = upper->lower; + DEBUGASSERT(lower != NULL); /* Get exclusive access to the device structures */ @@ -533,8 +536,9 @@ void watchdog_unregister(FAR void *handle) /* Recover the pointer to the upper-half driver state */ upper = (FAR struct watchdog_upperhalf_s *)handle; + DEBUGASSERT(upper != NULL); lower = upper->lower; - DEBUGASSERT(upper && lower); + DEBUGASSERT(lower != NULL); wdinfo("Unregistering: %s\n", upper->path); -- GitLab From 34e68a569b8dcbddf0501c6bb0665d7941a908e2 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Mon, 15 May 2017 07:22:17 -0600 Subject: [PATCH 824/990] drivers: rename newly introduced up_i2creset to I2C_RESET --- drivers/sensors/Kconfig | 1 + drivers/sensors/hts221.c | 8 ++++---- drivers/sensors/lis2dh.c | 6 ++++-- drivers/sensors/lps25h.c | 8 ++++---- drivers/usbmisc/fusb301.c | 8 ++++---- 5 files changed, 17 insertions(+), 14 deletions(-) diff --git a/drivers/sensors/Kconfig b/drivers/sensors/Kconfig index b5fc76cb41..03911022b5 100644 --- a/drivers/sensors/Kconfig +++ b/drivers/sensors/Kconfig @@ -201,6 +201,7 @@ config MS58XX_I2C_FREQUENCY config MS58XX_VDD int "MEAS MS58XX VDD" default 30 + depends on MS58XX config MPL115A bool "Freescale MPL115A Barometer Sensor support" diff --git a/drivers/sensors/hts221.c b/drivers/sensors/hts221.c index 59c5790ad5..9f3138bddf 100644 --- a/drivers/sensors/hts221.c +++ b/drivers/sensors/hts221.c @@ -201,10 +201,10 @@ static int hts221_do_transfer(FAR struct hts221_dev_s *priv, break; } - ret = up_i2creset(priv->i2c); + ret = I2C_RESET(priv->i2c); if (ret < 0) { - hts221_dbg("up_i2creset failed: %d\n", ret); + hts221_dbg("I2C_RESET failed: %d\n", ret); return ret; } #endif @@ -892,7 +892,7 @@ static int hts221_ioctl(FAR struct file *filep, int cmd, unsigned long arg) { FAR struct inode *inode = filep->f_inode; FAR struct hts221_dev_s *priv = inode->i_private; - int32_t ret = 0; + int ret = OK; while (sem_wait(&priv->devsem) != 0) { @@ -932,7 +932,7 @@ static int hts221_ioctl(FAR struct file *filep, int cmd, unsigned long arg) break; default: - ret = -EINVAL; + ret = -ENOTTY; break; } diff --git a/drivers/sensors/lis2dh.c b/drivers/sensors/lis2dh.c index b24aa782e3..f7a982f151 100644 --- a/drivers/sensors/lis2dh.c +++ b/drivers/sensors/lis2dh.c @@ -131,9 +131,11 @@ static int lis2dh_get_reading(FAR struct lis2dh_dev_s *dev, FAR struct lis2dh_vector_s *res, bool force_read); static int lis2dh_powerdown(FAR struct lis2dh_dev_s *dev); static int lis2dh_reboot(FAR struct lis2dh_dev_s *dev); +#ifndef CONFIG_DISABLE_POLL static int lis2dh_poll(FAR struct file *filep, FAR struct pollfd *fds, bool setup); static void lis2dh_notify(FAR struct lis2dh_dev_s *priv); +#endif static int lis2dh_int_handler(int irq, FAR void *context, FAR void *arg); static int lis2dh_setup(FAR struct lis2dh_dev_s *dev, @@ -1614,10 +1616,10 @@ static int lis2dh_access(FAR struct lis2dh_dev_s *dev, uint8_t subaddr, { /* Some error. Try to reset I2C bus and keep trying. */ #ifdef CONFIG_I2C_RESET - int ret = up_i2creset(dev->i2c); + int ret = I2C_RESET(dev->i2c); if (ret < 0) { - lis2dh_dbg("up_i2creset failed: %d\n", ret); + lis2dh_dbg("I2C_RESET failed: %d\n", ret); return ret; } #endif diff --git a/drivers/sensors/lps25h.c b/drivers/sensors/lps25h.c index 3ebba98285..bd35f38043 100644 --- a/drivers/sensors/lps25h.c +++ b/drivers/sensors/lps25h.c @@ -257,10 +257,10 @@ static int lps25h_do_transfer(FAR struct lps25h_dev_s *dev, break; } - ret = up_i2creset(dev->i2c); + ret = I2C_RESET(dev->i2c); if (ret < 0) { - lps25h_dbg("up_i2creset failed: %d\n", ret); + lps25h_dbg("I2C_RESET failed: %d\n", ret); return ret; } #endif @@ -708,7 +708,7 @@ 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; + int ret = OK; while (sem_wait(&dev->devsem) != 0) { @@ -742,7 +742,7 @@ static int lps25h_ioctl(FAR struct file *filep, int cmd, unsigned long arg) break; default: - ret = -EINVAL; + ret = -ENOTTY; break; } diff --git a/drivers/usbmisc/fusb301.c b/drivers/usbmisc/fusb301.c index c3627fd909..f24ae78558 100644 --- a/drivers/usbmisc/fusb301.c +++ b/drivers/usbmisc/fusb301.c @@ -176,10 +176,10 @@ static int fusb301_getreg(FAR struct fusb301_dev_s *priv, uint8_t reg) break; } - ret = up_i2creset(priv->i2c); + ret = I2C_RESET(priv->i2c); if (ret < 0) { - fusb301_err("ERROR: up_i2creset failed: %d\n", ret); + fusb301_err("ERROR: I2C_RESET failed: %d\n", ret); return ret; } #endif @@ -246,10 +246,10 @@ static int fusb301_putreg(FAR struct fusb301_dev_s *priv, uint8_t regaddr, break; } - ret = up_i2creset(priv->i2c); + ret = I2C_RESET(priv->i2c); if (ret < 0) { - fusb301_err("ERROR: up_i2creset failed: %d\n", ret); + fusb301_err("ERROR: I2C_RESET failed: %d\n", ret); return ret; } #endif -- GitLab From 914c5dad0cd846870efd5e6b10faf5d0bbb9febe Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 15 May 2017 08:10:43 -0600 Subject: [PATCH 825/990] TCP: An RST recevied suring the 3-way handshake requires a little more clean-up --- net/tcp/tcp_input.c | 40 +++++++++++++++++++++++++++++++++++++--- net/tcp/tcp_timer.c | 2 +- 2 files changed, 38 insertions(+), 4 deletions(-) diff --git a/net/tcp/tcp_input.c b/net/tcp/tcp_input.c index 23bec6a6e5..d1addb0bbf 100644 --- a/net/tcp/tcp_input.c +++ b/net/tcp/tcp_input.c @@ -314,10 +314,44 @@ found: if ((tcp->flags & TCP_RST) != 0) { - conn->tcpstateflags = TCP_CLOSED; - nwarn("WARNING: RESET - TCP state: TCP_CLOSED\n"); + FAR struct tcp_conn_s *listener = NULL; + + /* An RST received during the 3-way connection handshake requires + * little more clean-up. + */ + + if ((conn->tcpstateflags & TCP_STATE_MASK) == TCP_SYN_RCVD) + { + conn->tcpstateflags = TCP_CLOSED; + nwarn("WARNING: RESET in TCP_SYN_RCVD\n"); + + /* Notify the listerner for connection of the reset event */ + + listener = tcp_findlistener(conn->lport); + + /* We must free this TCP connection structure, this connection + * will never be established. + */ + + tcp_free(conn); + } + else + { + conn->tcpstateflags = TCP_CLOSED; + nwarn("WARNING: RESET TCP state: TCP_CLOSED\n"); + + /* Notify this connection of the reset event */ + + listener = conn; + } + + /* Perform the TCP_ABORT callback and drop the packet */ + + if (listener != NULL) + { + (void)tcp_callback(dev, listener, TCP_ABORT); + } - (void)tcp_callback(dev, conn, TCP_ABORT); goto drop; } diff --git a/net/tcp/tcp_timer.c b/net/tcp/tcp_timer.c index a9047fc478..03935c964b 100644 --- a/net/tcp/tcp_timer.c +++ b/net/tcp/tcp_timer.c @@ -231,7 +231,7 @@ void tcp_timer(FAR struct net_driver_s *dev, FAR struct tcp_conn_s *conn, FAR struct tcp_conn_s *listener; conn->tcpstateflags = TCP_CLOSED; - ninfo("TCP state: TCP_CLOSED\n"); + ninfo("TCP state: TCP_SYN_RCVD->TCP_CLOSED\n"); /* Find the listener for this connection. */ -- GitLab From 06634afbe08766929b26ee35f7514aa6d836ee4b Mon Sep 17 00:00:00 2001 From: Anthony Merlino Date: Mon, 15 May 2017 21:44:51 -0400 Subject: [PATCH 826/990] wireless/ieee802154: Restructuring of MAC notifications. Simplifes some interfaces --- drivers/wireless/ieee802154/mrf24j40.c | 44 +- .../wireless/ieee802154/ieee802154_ioctl.h | 5 +- .../wireless/ieee802154/ieee802154_mac.h | 236 +++--- .../wireless/ieee802154/ieee802154_radio.h | 24 +- wireless/ieee802154/mac802154.c | 755 +++++++++++++----- wireless/ieee802154/mac802154.h | 56 +- wireless/ieee802154/mac802154_device.c | 494 +++++------- wireless/ieee802154/mac802154_netdev.c | 102 +-- 8 files changed, 1036 insertions(+), 680 deletions(-) diff --git a/drivers/wireless/ieee802154/mrf24j40.c b/drivers/wireless/ieee802154/mrf24j40.c index fe022d5114..903b843c9c 100644 --- a/drivers/wireless/ieee802154/mrf24j40.c +++ b/drivers/wireless/ieee802154/mrf24j40.c @@ -107,13 +107,6 @@ * Private Types ****************************************************************************/ -struct mrf24j40_txdesc_s -{ - struct ieee802154_txdesc_s pub; - - uint8_t busy : 1; /* Is this txdesc being used */ -}; - /* A MRF24J40 device instance */ struct mrf24j40_radio_s @@ -145,11 +138,13 @@ struct mrf24j40_radio_s /* Buffer Allocations */ - struct mrf24j40_txdesc_s csma_desc; + struct ieee802154_txdesc_s *csma_desc; FAR struct iob_s *csma_frame; + bool csma_busy; - struct mrf24j40_txdesc_s gts_desc[MRF24J40_GTS_SLOTS]; + struct ieee802154_txdesc_s *gts_desc[MRF24J40_GTS_SLOTS]; FAR struct iob_s *gts_frame[MRF24J40_GTS_SLOTS]; + bool gts_busy[MRF24J40_GTS_SLOTS]; }; /**************************************************************************** @@ -189,7 +184,6 @@ static int mrf24j40_gts_setup(FAR struct mrf24j40_radio_s *dev, uint8_t gts, static int mrf24j40_setup_fifo(FAR struct mrf24j40_radio_s *dev, FAR struct iob_s *frame, uint32_t fifo_addr); - static int mrf24j40_setchannel(FAR struct mrf24j40_radio_s *dev, uint8_t chan); static int mrf24j40_getchannel(FAR struct mrf24j40_radio_s *dev, @@ -206,10 +200,6 @@ static int mrf24j40_seteaddr(FAR struct mrf24j40_radio_s *dev, FAR const uint8_t *eaddr); static int mrf24j40_geteaddr(FAR struct mrf24j40_radio_s *dev, FAR uint8_t *eaddr); -static int mrf24j40_setpromisc(FAR struct mrf24j40_radio_s *dev, - bool promisc); -static int mrf24j40_getpromisc(FAR struct mrf24j40_radio_s *dev, - FAR bool *promisc); static int mrf24j40_setdevmode(FAR struct mrf24j40_radio_s *dev, uint8_t mode); static int mrf24j40_getdevmode(FAR struct mrf24j40_radio_s *dev, @@ -446,17 +436,17 @@ static void mrf24j40_dopoll_csma(FAR void *arg) /* If this a CSMA transaction and we have room in the CSMA fifo */ - if (!dev->csma_desc.busy) + if (!dev->csma_busy) { /* need to somehow allow for a handle to be passed */ - len = dev->radiocb->poll_csma(dev->radiocb, &dev->csma_desc.pub, + len = dev->radiocb->poll_csma(dev->radiocb, &dev->csma_desc, &dev->csma_frame); if (len > 0) { /* Now the txdesc is in use */ - dev->csma_desc.busy = 1; + dev->csma_busy = 1; /* Setup the transaction on the device in the CSMA FIFO */ @@ -501,15 +491,15 @@ static void mrf24j40_dopoll_gts(FAR void *arg) for (gts = 0; gts < MRF24J40_GTS_SLOTS; gts++) { - if (!dev->gts_desc[gts].busy) + if (!dev->gts_busy[gts]) { - len = dev->radiocb->poll_gts(dev->radiocb, &dev->gts_desc[gts].pub, + len = dev->radiocb->poll_gts(dev->radiocb, &dev->gts_desc[gts], &dev->gts_frame[0]); if (len > 0) { /* Now the txdesc is in use */ - dev->gts_desc[gts].busy = 1; + dev->gts_busy[gts]= 1; /* Setup the transaction on the device in the open GTS FIFO */ @@ -1406,15 +1396,15 @@ static void mrf24j40_irqwork_txnorm(FAR struct mrf24j40_radio_s *dev) */ txstat = mrf24j40_getreg(dev->spi, MRF24J40_TXSTAT); - dev->csma_desc.pub.status = txstat & MRF24J40_TXSTAT_TXNSTAT; + dev->csma_desc->conf->status = txstat & MRF24J40_TXSTAT_TXNSTAT; /* Inform the next layer of the transmission success/failure */ - dev->radiocb->txdone(dev->radiocb, &dev->csma_desc.pub); + dev->radiocb->txdone(dev->radiocb, dev->csma_desc); /* We are now done with the transaction */ - dev->csma_desc.busy = 0; + dev->csma_busy = 0; /* Free the IOB */ @@ -1451,20 +1441,20 @@ static void mrf24j40_irqwork_txgts(FAR struct mrf24j40_radio_s *dev, if (gts == 0) { - dev->csma_desc.pub.status = txstat & MRF24J40_TXSTAT_TXG1STAT; + dev->csma_desc->conf->status = txstat & MRF24J40_TXSTAT_TXG1STAT; } else if (gts == 1) { - dev->csma_desc.pub.status = txstat & MRF24J40_TXSTAT_TXG2STAT; + dev->csma_desc->conf->status = txstat & MRF24J40_TXSTAT_TXG2STAT; } /* Inform the next layer of the transmission success/failure */ - dev->radiocb->txdone(dev->radiocb, &dev->gts_desc[gts].pub); + dev->radiocb->txdone(dev->radiocb, dev->gts_desc[gts]); /* We are now done with the transaction */ - dev->gts_desc[gts].busy = 0; + dev->gts_busy[gts]= 0; /* Free the IOB */ diff --git a/include/nuttx/wireless/ieee802154/ieee802154_ioctl.h b/include/nuttx/wireless/ieee802154/ieee802154_ioctl.h index 5f14f2e2c6..318289b4db 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_ioctl.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_ioctl.h @@ -62,8 +62,9 @@ /* IEEE 802.15.4 MAC Character Driver IOCTL commands ********************************/ -#define MAC802154IOC_MCPS_REGISTER _WLCIOC(IEEE802154_FIRST) -#define MAC802154IOC_MLME_REGISTER _WLCIOC(IEEE802154_FIRST+1) +#define MAC802154IOC_NOTIFY_REGISTER _WLCIOC(IEEE802154_FIRST) +#define MAC802154IOC_GET_EVENT _WLCIOC(IEEE802154_FIRST+1) +#define MAC802154IOC_ENABLE_EVENTS _WLCIOC(IEEE802154_FIRST+2) /************************************************************************************ * Public Types diff --git a/include/nuttx/wireless/ieee802154/ieee802154_mac.h b/include/nuttx/wireless/ieee802154/ieee802154_mac.h index 15963b46e1..5f28cfa0c7 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_mac.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_mac.h @@ -102,31 +102,12 @@ /* IEEE 802.15.4 MAC Interface **********************************************/ -/* Frame Type */ - -#define IEEE802154_FRAME_BEACON 0x00 -#define IEEE802154_FRAME_DATA 0x01 -#define IEEE802154_FRAME_ACK 0x02 -#define IEEE802154_FRAME_COMMAND 0x03 - -/* MAC commands */ - -#define IEEE802154_CMD_ASSOC_REQ 0x01 -#define IEEE802154_CMD_ASSOC_RESP 0x02 -#define IEEE802154_CMD_DISASSOC_NOT 0x03 -#define IEEE802154_CMD_DATA_REQ 0x04 -#define IEEE802154_CMD_PANID_CONF_NOT 0x05 -#define IEEE802154_CMD_ORPHAN_NOT 0x06 -#define IEEE802154_CMD_BEACON_REQ 0x07 -#define IEEE802154_CMD_COORD_REALIGN 0x08 -#define IEEE802154_CMD_GTS_REQ 0x09 - /* Some addresses */ #define IEEE802154_PAN_UNSPEC (uint16_t)0xFFFF #define IEEE802154_SADDR_UNSPEC (uint16_t)0xFFFF #define IEEE802154_SADDR_BCAST (uint16_t)0xFFFE -#define IEEE802154_EADDR_UNSPEC (uint8_t*)"\xff\xff\xff\xff\xff\xff\xff\xff" +#define IEEE802154_EADDR_UNSPEC (uint8_t[]){0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF} /* Frame control field masks, 2 bytes * Seee IEEE 802.15.4/2011 5.2.1.1 page 57 @@ -150,6 +131,22 @@ #define IEEE802154_FRAMECTRL_SHIFT_VERSION 12 /* Source addressing mode, bits 12-13 */ #define IEEE802154_FRAMECTRL_SHIFT_SADDR 14 /* Source addressing mode, bits 14-15 */ +/* Capability Information Bitfield + * + */ + +#define IEEE802154_CAPABILITY_DEVTYPE 0x02 +#define IEEE802154_CAPABILITY_PWRSRC 0x04 +#define IEEE802154_CAPABILITY_RXONIDLE 0x08 +#define IEEE802154_CAPABILITY_SECURITY 0x40 +#define IEEE802154_CAPABILITY_ALLOCADDR 0x80 + +#define IEEE802154_CAPABILITY_SHIFT_DEVTYPE 1 +#define IEEE802154_CAPABILITY_SHIFT_PWRSRC 2 +#define IEEE802154_CAPABILITY_SHIFT_RXONIDLE 3 +#define IEEE802154_CAPABILITY_SHIFT_SECURITY 6 +#define IEEE802154_CAPABILITY_SHIFT_ALLOCADDR 7 + /* IEEE 802.15.4 PHY constants */ #define IEEE802154_MAX_PHY_PACKET_SIZE 127 @@ -194,7 +191,6 @@ #define MAX_ORPHAN_ADDR 32 /* REVISIT */ -// TODO: Add macros /**************************************************************************** * Public Types @@ -329,6 +325,31 @@ enum ieee802154_pib_attr_e IEEE802154_PIB_MAC_PANCOORD_SHORT_ADDR, }; +/* Frame Type */ + +enum ieee802154_frametype_e +{ + IEEE802154_FRAME_BEACON = 0, + IEEE802154_FRAME_DATA, + IEEE802154_FRAME_ACK, + IEEE802154_FRAME_COMMAND +}; + +/* MAC command IDs */ + +enum ieee802154_cmdid_e +{ + IEEE802154_CMD_ASSOC_REQ = 1, + IEEE802154_CMD_ASSOC_RESP, + IEEE802154_CMD_DISASSOC_NOT, + IEEE802154_CMD_DATA_REQ, + IEEE802154_CMD_PANID_CONF_NOT, + IEEE802154_CMD_ORPHAN_NOT, + IEEE802154_CMD_BEACON_REQ, + IEEE802154_CMD_COORD_REALIGN, + IEEE802154_CMD_GTS_REQ, +}; + enum ieee802154_devmode_e { IEEE802154_DEVMODE_ENDPOINT, @@ -405,13 +426,13 @@ enum ieee802154_ranging_e struct ieee802154_capability_info_s { uint8_t reserved_0 : 1; /* Reserved */ - uint8_t device_type : 1; /* 0=RFD, 1=FFD */ - uint8_t power_source : 1; /* 1=AC, 0=Other */ - uint8_t rx_on_idle : 1; /* 0=Receiver off when idle + uint8_t devtype : 1; /* 0=RFD, 1=FFD */ + uint8_t powersource : 1; /* 1=AC, 0=Other */ + uint8_t rxonidle : 1; /* 0=Receiver off when idle * 1=Receiver on when idle */ uint8_t reserved_45 : 2; /* Reserved */ uint8_t security : 1; /* 0=disabled, 1=enabled */ - uint8_t allocate_addr : 1; /* 1=Coordinator allocates short address + uint8_t allocaddr : 1; /* 1=Coordinator allocates short address * 0=otherwise */ }; @@ -462,31 +483,6 @@ struct ieee802154_pend_addr_s struct ieee802154_addr_s addr[7]; /* Array of at most 7 addresses */ }; -#ifdef CONFIG_IEEE802154_RANGING -#define IEEE802154_TXDESC_FIELDS \ - uint8_t handle; \ - uint32_t timestamp; \ - uint8_t status; -#else -#define IEEE802154_TXDESC_FIELDS \ - uint8_t handle; \ - uint32_t timestamp; \ - uint8_t status; - bool rng_rcvd; \ - uint32_t rng_counter_start; \ - uint32_t rng_counter_stop; \ - uint32_t rng_tracking_interval; \ - uint32_t rng_offset;\ - uint8_t rng_fom; -#endif - -struct ieee802154_txdesc_s -{ - IEEE802154_TXDESC_FIELDS - - /* TODO: Add slotting information for GTS transactions */ -}; - struct ieee802154_cca_s { uint8_t use_ed : 1; /* CCA using ED */ @@ -631,7 +627,44 @@ struct ieee802154_frame_meta_s struct ieee802154_data_conf_s { - IEEE802154_TXDESC_FIELDS + uint8_t handle; /* Handle assoc. with MSDU */ + + /* The time, in symbols, at which the data were transmitted */ + + uint32_t timestamp; + enum ieee802154_status_e status; /* The status of the MSDU transmission */ + +#ifdef CONFIG_IEEE802154_RANGING + bool rng_rcvd; /* Ranging indicated by MSDU */ + + /* A count of the time units corresponding to an RMARKER at the antenna at + * the beginning of the ranging exchange + */ + + uint32_t rng_counter_start; + + /* A count of the time units corresponding to an RMARKER at the antenna at + * end of the ranging exchange + */ + + uint32_t rng_counter_stop; + + /* A count of the time units in a message exchange over which the tracking + * offset was measured + */ + + uint32_t rng_tracking_interval; + + /* A count of the time units slipped or advanced by the radio tracking + * system over the course of the entire tracking interval + */ + + uint32_t rng_offset; + + /* The Figure of Merit (FoM) characterizing the ranging measurement */ + + uint8_t rng_fom; +#endif }; /***************************************************************************** @@ -734,12 +767,12 @@ struct ieee802154_purge_req_s struct ieee802154_assoc_req_s { - uint8_t channel; /* Channel number to attempt association */ - uint8_t channel_page; /* Channel page to attempt association */ + uint8_t chnum; /* Channel number to attempt association */ + uint8_t chpage; /* Channel page to attempt association */ /* Coordinator Address with which to associate */ - struct ieee802154_addr_s coord_addr; + struct ieee802154_addr_s coordaddr; /* Capabilities of associating device */ @@ -1307,8 +1340,42 @@ struct ieee802154_poll_conf_s enum ieee802154_status_e status; }; -union ieee802154_mlme_notify_u +/* MAC Service Notifications */ + +enum ieee802154_notify_e +{ + /* MCPS Notifications */ + + IEEE802154_NOTIFY_CONF_DATA = 0x00, + + /* MLME Notifications */ + + IEEE802154_NOTIFY_CONF_ASSOC, + IEEE802154_NOTIFY_CONF_DISASSOC, + IEEE802154_NOTIFY_CONF_GTS, + IEEE802154_NOTIFY_CONF_RESET, + IEEE802154_NOTIFY_CONF_RXENABLE, + IEEE802154_NOTIFY_CONF_SCAN, + IEEE802154_NOTIFY_CONF_START, + IEEE802154_NOTIFY_CONF_POLL, + + IEEE802154_NOTIFY_IND_ASSOC, + IEEE802154_NOTIFY_IND_DISASSOC, + IEEE802154_NOTIFY_IND_BEACONNOTIFY, + IEEE802154_NOTIFY_IND_GTS, + IEEE802154_NOTIFY_IND_ORPHAN, + IEEE802154_NOTIFY_IND_COMMSTATUS, + IEEE802154_NOTIFY_IND_SYNCLOSS +}; + +union ieee802154_notif_u { + /* MCPS Notifications */ + + struct ieee802154_data_conf_s dataconf; + + /* MLME Notifications */ + struct ieee802154_assoc_conf_s assocconf; struct ieee802154_disassoc_conf_s disassocconf; struct ieee802154_gts_conf_s gtsconf; @@ -1326,10 +1393,18 @@ union ieee802154_mlme_notify_u struct ieee802154_syncloss_ind_s synclossind; }; -union ieee802154_mcps_notify_u +struct ieee802154_notif_s { - struct ieee802154_data_conf_s dataconf; - struct ieee802154_data_ind_s *dataind; + /* Must be first member so that we can interchange between the actual + *notification and this extended struct. + */ + + union ieee802154_notif_u u; + enum ieee802154_notify_e notiftype; + + /* Support a singly linked list */ + + FAR struct ieee802154_notif_s *flink; }; /* A pointer to this structure is passed as the argument of each IOCTL @@ -1376,51 +1451,6 @@ struct ieee802154_netmac_s typedef FAR void *MACHANDLE; -/* MAC Service Notifications */ - -enum ieee802154_macnotify_e -{ - /* MCPS Notifications */ - - IEEE802154_NOTIFY_CONF_DATA = 0x00, - IEEE802154_NOTIFY_IND_DATA, - - /* MLME Notifications */ - - IEEE802154_NOTIFY_CONF_ASSOC, - IEEE802154_NOTIFY_CONF_DISASSOC, - IEEE802154_NOTIFY_CONF_GTS, - IEEE802154_NOTIFY_CONF_RESET, - IEEE802154_NOTIFY_CONF_RXENABLE, - IEEE802154_NOTIFY_CONF_SCAN, - IEEE802154_NOTIFY_CONF_START, - IEEE802154_NOTIFY_CONF_POLL, - - IEEE802154_NOTIFY_IND_ASSOC, - IEEE802154_NOTIFY_IND_DISASSOC, - IEEE802154_NOTIFY_IND_BEACONNOTIFY, - IEEE802154_NOTIFY_IND_GTS, - IEEE802154_NOTIFY_IND_ORPHAN, - IEEE802154_NOTIFY_IND_COMMSTATUS, - IEEE802154_NOTIFY_IND_SYNCLOSS -}; - -/* Callback operations to notify the next highest layer of various asynchronous - * events, usually triggered by some previous request or response invoked by the - * upper layer. - */ - -struct ieee802154_maccb_s -{ - CODE void (*mlme_notify)(FAR const struct ieee802154_maccb_s *maccb, - enum ieee802154_macnotify_e notif, - FAR const union ieee802154_mlme_notify_u *arg); - - CODE void (*mcps_notify)(FAR const struct ieee802154_maccb_s *maccb, - enum ieee802154_macnotify_e notif, - FAR const union ieee802154_mcps_notify_u *arg); -}; - #ifdef __cplusplus #define EXTERN extern "C" extern "C" diff --git a/include/nuttx/wireless/ieee802154/ieee802154_radio.h b/include/nuttx/wireless/ieee802154/ieee802154_radio.h index d3fcb5db74..e0ff8b664f 100644 --- a/include/nuttx/wireless/ieee802154/ieee802154_radio.h +++ b/include/nuttx/wireless/ieee802154/ieee802154_radio.h @@ -58,15 +58,35 @@ * Public Types ****************************************************************************/ +/* Data only used between radio and MAC layer */ + +struct ieee802154_txdesc_s +{ + /* Support a singly linked list of tx descriptors */ + + FAR struct ieee802154_txdesc_s *flink; + + /* Pointer to the data confirmation structure to be populated upon + * success/failure of the transmission. + */ + + FAR struct ieee802154_data_conf_s *conf; + + enum ieee802154_frametype_e frametype; /* Frame type. Used by MAC layer to + * control how tx done is handled */ + + /* TODO: Add slotting information for GTS transactions */ +}; + /* IEEE802.15.4 Radio Interface Operations **********************************/ struct ieee802154_radiocb_s { CODE int (*poll_csma) (FAR const struct ieee802154_radiocb_s *radiocb, - FAR struct ieee802154_txdesc_s *tx_desc, + FAR struct ieee802154_txdesc_s **tx_desc, FAR struct iob_s **frame); CODE int (*poll_gts) (FAR const struct ieee802154_radiocb_s *radiocb, - FAR struct ieee802154_txdesc_s *tx_desc, + FAR struct ieee802154_txdesc_s **tx_desc, FAR struct iob_s **frame); CODE void (*txdone) (FAR const struct ieee802154_radiocb_s *radiocb, FAR const struct ieee802154_txdesc_s *tx_desc); diff --git a/wireless/ieee802154/mac802154.c b/wireless/ieee802154/mac802154.c index 8b7b545699..c57891f83c 100644 --- a/wireless/ieee802154/mac802154.c +++ b/wireless/ieee802154/mac802154.c @@ -52,11 +52,11 @@ #include +#include "mac802154.h" + #include #include -#include "mac802154.h" - /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ @@ -80,17 +80,32 @@ # endif #endif +#if !defined(CONFIG_MAC802154_NNOTIF) || CONFIG_MAC802154_NNOTIF <= 0 +# undef CONFIG_MAC802154_NNOTIF +# define CONFIG_MAC802154_NNOTIF 6 +#endif + +#if !defined(CONFIG_MAC802154_NTXDESC) || CONFIG_MAC802154_NTXDESC <= 0 +# undef CONFIG_MAC802154_NTXDESC +# define CONFIG_MAC802154_NTXDESC 3 +#endif + +#if CONFIG_MAC802154_NTXDESC > CONFIG_MAC802154_NNOTIF +#error CONFIG_MAC802154_NNOTIF must be greater than CONFIG_MAC802154_NTXDESC +#endif + /**************************************************************************** * Private Types ****************************************************************************/ -struct mac802154_txframe_s +struct mac802154_txtrans_s { /* Supports a singly linked list */ - FAR struct mac802154_txframe_s *flink; + FAR struct mac802154_txtrans_s *flink; FAR struct iob_s *frame; - uint8_t msdu_handle; + uint8_t handle; + enum ieee802154_frametype_e frametype; sem_t sem; }; @@ -118,11 +133,46 @@ struct mac802154_radiocb_s struct ieee802154_privmac_s { FAR struct ieee802154_radio_s *radio; /* Contained IEEE802.15.4 radio dev */ - FAR const struct ieee802154_maccb_s *cb; /* Contained MAC callbacks */ + FAR const struct mac802154_maccb_s *cb; /* Contained MAC callbacks */ FAR struct mac802154_radiocb_s radiocb; /* Interface to bind to radio */ sem_t exclsem; /* Support exclusive access */ + /* Support a single transaction dedicated to commands. As of now I see no + * condition where you need to have more than one command frame simultaneously + */ + + struct + { + sem_t sem; /* Exclusive use of the cmdtrans */ + enum ieee802154_cmdid_e type; /* Type of cmd in the cmdtrans */ + struct mac802154_txtrans_s trans; /* Dedicated txframe for cmds */ + + /* Has the command been successfully sent. This is to help protect + * against an odd edge case that may or may not ever happen. The condition + * occurs when you receive a seemingly appropriate response to the command + * yet the command was never actually sent. + */ + + bool txdone; + } cmd; + + /* Pre-allocated notifications to be passed to the registered callback. These + * need to be freed by the application using mac802154_xxxxnotif_free when + * the callee layer is finished with it's use. + */ + + FAR struct ieee802154_notif_s *notif_free; + struct ieee802154_notif_s notif_alloc[CONFIG_MAC802154_NNOTIF]; + sq_queue_t notif_queue; + + FAR struct ieee802154_txdesc_s *txdesc_free; + struct ieee802154_txdesc_s txdesc_alloc[CONFIG_IEEE802154_NTXDESC]; + sq_queue_t txdesc_queue; + sq_queue_t txdone_queue; + + /* Work structures for offloading aynchronous work */ + struct work_s tx_work; struct work_s rx_work; @@ -132,8 +182,7 @@ struct ieee802154_privmac_s * during the CAP of the Coordinator's superframe. */ - FAR struct mac802154_txframe_s *csma_head; - FAR struct mac802154_txframe_s *csma_tail; + sq_queue_t csma_queue; /* Support a singly linked list of transactions that will be sent indirectly. * This list should only be used by a MAC acting as a coordinator. These @@ -142,16 +191,12 @@ struct ieee802154_privmac_s * list should also be used to populate the address list of the outgoing * beacon frame. */ - - FAR struct mac802154_txframe_s *indirect_head; - FAR struct mac802154_txframe_s *indirect_tail; - - uint8_t txdesc_count; - struct ieee802154_txdesc_s txdesc[CONFIG_IEEE802154_NTXDESC]; + + sq_queue_t indirect_queue; /* Support a singly linked list of frames received */ - FAR struct ieee802154_data_ind_s *dataind_head; - FAR struct ieee802154_data_ind_s *dataind_tail; + + sq_queue_t dataind_queue; /* MAC PIB attributes, grouped to save memory */ @@ -264,7 +309,10 @@ struct ieee802154_privmac_s enum ieee802154_devmode_e devmode : 2; - /* 11-bits remaining */ + bool csma_tryagain : 1; + bool gts_tryagain : 1; + + /* 10-bits remaining */ /* End of 32-bit bitfield. */ @@ -275,25 +323,33 @@ struct ieee802154_privmac_s * Private Function Prototypes ****************************************************************************/ +/* Internal Functions */ + static inline int mac802154_takesem(sem_t *sem); #define mac802154_givesem(s) sem_post(s); -static void mac802154_txdone_worker(FAR void *arg); -static void mac802154_rxframe_worker(FAR void *arg); - -/* Internal Functions */ +static void mac802154_resetqueues(FAR struct ieee802154_privmac_s *priv); +static void mac802154_notifpool_init(FAR struct ieee802154_privmac_s *priv); +static FAR struct ieee802154_notif_s * + mac802154_notif_alloc(FAR struct ieee802154_privmac_s *priv); static int mac802154_defaultmib(FAR struct ieee802154_privmac_s *priv); static int mac802154_applymib(FAR struct ieee802154_privmac_s *priv); +static void mac802154_txdone_worker(FAR void *arg); +static void mac802154_rxframe_worker(FAR void *arg); + +static void mac802154_cmd_txdone(FAR struct ieee802154_privmac_s *priv, + FAR struct ieee802154_txdesc_s *txdesc); + /* IEEE 802.15.4 PHY Interface OPs */ static int mac802154_poll_csma(FAR const struct ieee802154_radiocb_s *radiocb, - FAR struct ieee802154_txdesc_s *tx_desc, + FAR struct ieee802154_txdesc_s **tx_desc, FAR struct iob_s **frame); static int mac802154_poll_gts(FAR const struct ieee802154_radiocb_s *radiocb, - FAR struct ieee802154_txdesc_s *tx_desc, + FAR struct ieee802154_txdesc_s **tx_desc, FAR struct iob_s **frame); static void mac802154_txdone(FAR const struct ieee802154_radiocb_s *radiocb, @@ -339,149 +395,100 @@ static inline int mac802154_takesem(sem_t *sem) } /**************************************************************************** - * Name: mac802154_push_csma + * Name: mac802154_resetqueues * * Description: - * Push a CSMA transaction onto the list + * Initializes the various queues used in the MAC layer. Called on creation + * of MAC. * ****************************************************************************/ -static void mac802154_push_csma(FAR struct ieee802154_privmac_s *priv, - FAR struct mac802154_txframe_s *trans) +static void mac802154_resetqueues(FAR struct ieee802154_privmac_s *priv) { - /* Ensure the transactions forward link is NULL */ + int i; - trans->flink = NULL; + sq_init(&priv->txdone_queue); + sq_init(&priv->csma_queue); + sq_init(&priv->indirect_queue); + sq_init(&priv->dataind_queue); - /* If the tail is not empty, make the transaction pointed to by the tail, - * point to the new transaction */ + sq_init(&priv->notif_queue); + sq_init(&priv->txdesc_queue); - if (priv->csma_tail != NULL) + for (i = 0; i < CONFIG_MAC802154_NNOTIF; i++) { - priv->csma_tail->flink = trans; + sq_addlast((FAR sq_entry_t *)&priv->notif_alloc[i], &priv->notif_queue); } - /* Point the tail at the new transaction */ - - priv->csma_tail = trans; - - /* If the head is NULL, we need to point it at the transaction since there - * is only one transaction in the list at this point */ - - if (priv->csma_head == NULL) + for (i = 0; i < CONFIG_MAC802154_NTXDESC; i++) { - priv->csma_head = trans; + sq_addlast((FAR sq_entry_t *)&priv->txdesc_alloc[i], &priv->txdesc_queue); } + + mac802154_notifpool_init(priv); } /**************************************************************************** - * Name: mac802154_pop_csma + * Name: mac802154_notifpool_init * * Description: - * Pop a CSMA transaction from the list + * This function initializes the notification structure pool. It allows the + * MAC to pass notifications and for the callee to free them when they are + * done using them, saving copying the data when passing. * ****************************************************************************/ -static FAR struct mac802154_txframe_s * - mac802154_pop_csma(FAR struct ieee802154_privmac_s *priv) +static void mac802154_notifpool_init(FAR struct ieee802154_privmac_s *priv) { - FAR struct mac802154_txframe_s *trans; + FAR struct ieee802154_notif_s *pool = priv->notif_alloc; + int remaining = CONFIG_MAC802154_NNOTIF; - if (priv->csma_head == NULL) + priv->notif_free = NULL; + while (remaining > 0) { - return NULL; - } - - /* Get the transaction from the head of the list */ - - trans = priv->csma_head; - trans->flink = NULL; + FAR struct ieee802154_notif_s *notif = pool; - /* Move the head pointer to the next transaction */ + /* Add the next meta data structure from the pool to the list of + * general structures. + */ - priv->csma_head = trans->flink; + notif->flink = priv->notif_free; + priv->notif_free = notif; - /* If the head is now NULL, the list is empty, so clear the tail too */ + /* Set up for the next structure from the pool */ - if (priv->csma_head == NULL) - { - priv->csma_tail = NULL; + pool++; + remaining--; } - - return trans; } /**************************************************************************** - * Name: mac802154_push_dataind + * Name: mac802154_notif_alloc * * Description: - * Push a data indication onto the list to be processed - * - ****************************************************************************/ - -static void mac802154_push_dataind(FAR struct ieee802154_privmac_s *priv, - FAR struct ieee802154_data_ind_s *ind) -{ - /* Ensure the forward link is NULL */ - - ind->flink = NULL; - - /* If the tail is not empty, make the frame pointed to by the tail, - * point to the new data indication */ - - if (priv->dataind_tail != NULL) - { - priv->dataind_tail->flink = ind; - } - - /* Point the tail at the new frame */ - - priv->dataind_tail = ind; - - /* If the head is NULL, we need to point it at the data indication since there - * is only one indication in the list at this point */ - - if (priv->dataind_head == NULL) - { - priv->dataind_head = ind; - } -} - -/**************************************************************************** - * Name: mac802154_pop_dataind + * This function allocates a free notification structure from the free list + * to be used for passing to the registered notify callback. The callee software + * is responsible for freeing the notification structure after it is done using + * it via mac802154_notif_free. * - * Description: - * Pop a data indication from the list + * Assumptions: + * priv MAC struct is locked when calling. * ****************************************************************************/ - -static FAR struct ieee802154_data_ind_s * - mac802154_pop_dataind(FAR struct ieee802154_privmac_s *priv) +static FAR struct ieee802154_notif_s * + mac802154_notif_alloc(FAR struct ieee802154_privmac_s *priv) { - FAR struct ieee802154_data_ind_s *ind; + FAR struct ieee802154_notif_s *notif; - if (priv->dataind_head == NULL) + if (priv->notif_free == NULL) { return NULL; } - /* Get the data indication from the head of the list */ - - ind = priv->dataind_head; - ind->flink = NULL; + notif = priv->notif_free; + priv->notif_free = notif->flink; - /* Move the head pointer to the next data indication */ - - priv->dataind_head = ind->flink; - - /* If the head is now NULL, the list is empty, so clear the tail too */ - - if (priv->dataind_head == NULL) - { - priv->dataind_tail = NULL; - } - - return ind; + return notif; } /**************************************************************************** @@ -518,7 +525,6 @@ static int mac802154_defaultmib(FAR struct ieee802154_privmac_s *priv) priv->trans_persisttime = 0x01F4; - /* Reset the Coordinator address */ priv->coordaddr.mode = IEEE802154_ADDRMODE_NONE; @@ -580,13 +586,15 @@ static int mac802154_applymib(FAR struct ieee802154_privmac_s *priv) ****************************************************************************/ static int mac802154_poll_csma(FAR const struct ieee802154_radiocb_s *radiocb, - FAR struct ieee802154_txdesc_s *tx_desc, + FAR struct ieee802154_txdesc_s **txdesc, FAR struct iob_s **frame) { FAR struct mac802154_radiocb_s *cb = (FAR struct mac802154_radiocb_s *)radiocb; FAR struct ieee802154_privmac_s *priv; - FAR struct mac802154_txframe_s *trans; + FAR struct mac802154_txtrans_s *trans; + FAR struct ieee802154_txdesc_s *desc; + FAR struct ieee802154_notif_s *notif; DEBUGASSERT(cb != NULL && cb->priv != NULL); priv = cb->priv; @@ -599,16 +607,41 @@ static int mac802154_poll_csma(FAR const struct ieee802154_radiocb_s *radiocb, /* Check to see if there are any CSMA transactions waiting */ - trans = mac802154_pop_csma(priv); + trans = (FAR struct mac802154_txtrans_s *)sq_remfirst(&priv->csma_queue); mac802154_givesem(&priv->exclsem); if (trans != NULL) { - /* Setup the transmit descriptor */ + /* Allocate a Tx descriptor to pass */ + + desc = (FAR struct ieee802154_txdesc_s *)sq_remfirst(&priv->txdesc_queue); + if (desc == NULL) + { + wlerr("ERROR: Failed to allocate ieee802154_txdesc_s"); + goto errout; + } + + /* Allocate a notif struct (ie data confirmation struct) to pass with + * the tx descriptor. + */ + + notif = mac802154_notif_alloc(priv); + if (notif == NULL) + { + wlerr("ERROR: Failed to allocate ieee802154_notif_s"); + + /* Free the tx descriptor */ + + sq_addlast((FAR sq_entry_t *)desc, &priv->txdesc_queue); + goto errout; + } - tx_desc->handle = trans->msdu_handle; + desc->conf = (FAR struct ieee802154_data_conf_s *)notif; + desc->conf->handle = trans->handle; + desc->frametype = trans->frametype; *frame = trans->frame; + *txdesc = desc; /* Now that we've passed off the data, notify the waiting thread. * NOTE: The transaction was allocated on the waiting thread's stack so @@ -619,6 +652,13 @@ static int mac802154_poll_csma(FAR const struct ieee802154_radiocb_s *radiocb, return (trans->frame->io_len); } +errout: + /* Need to set flag to tell MAC to retry notifying radio layer about transmit + * since we couldn't allocate the required data structures at this time. + */ + + priv->csma_tryagain = true; + mac802154_givesem(&priv->exclsem); return 0; } @@ -634,13 +674,14 @@ static int mac802154_poll_csma(FAR const struct ieee802154_radiocb_s *radiocb, ****************************************************************************/ static int mac802154_poll_gts(FAR const struct ieee802154_radiocb_s *radiocb, - FAR struct ieee802154_txdesc_s *tx_desc, + FAR struct ieee802154_txdesc_s **tx_desc, FAR struct iob_s **frame) { FAR struct mac802154_radiocb_s *cb = (FAR struct mac802154_radiocb_s *)radiocb; FAR struct ieee802154_privmac_s *priv; - FAR struct mac802154_txframe_s *trans; + FAR struct mac802154_txtrans_s *trans; + FAR struct ieee802154_txdesc_s *desc; int ret = 0; DEBUGASSERT(cb != NULL && cb->priv != NULL); @@ -657,6 +698,15 @@ static int mac802154_poll_gts(FAR const struct ieee802154_radiocb_s *radiocb, mac802154_givesem(&priv->exclsem); return 0; + +errout: + /* Need to set flag to tell MAC to retry notifying radio layer about transmit + * since we couldn't allocate the required data structures at this time. + */ + + priv->gts_tryagain = true; + mac802154_givesem(&priv->exclsem); + return 0; } /**************************************************************************** @@ -673,7 +723,7 @@ static int mac802154_poll_gts(FAR const struct ieee802154_radiocb_s *radiocb, ****************************************************************************/ static void mac802154_txdone(FAR const struct ieee802154_radiocb_s *radiocb, - FAR const struct ieee802154_txdesc_s *tx_desc) + FAR const struct ieee802154_txdesc_s *txdesc) { FAR struct mac802154_radiocb_s *cb = (FAR struct mac802154_radiocb_s *)radiocb; @@ -688,20 +738,7 @@ static void mac802154_txdone(FAR const struct ieee802154_radiocb_s *radiocb, while (mac802154_takesem(&priv->exclsem) != 0); - /* Check to see if there is an available tx descriptor slot. If there is - * not we simply drop the notification */ - - if (priv->txdesc_count < CONFIG_IEEE802154_NTXDESC) - { - /* Copy the txdesc over and link it into our list */ - - memcpy(&priv->txdesc[priv->txdesc_count++], tx_desc, - sizeof(struct ieee802154_txdesc_s)); - } - else - { - wlinfo("MAC802154: No room for TX Desc.\n"); - } + sq_addlast((FAR sq_entry_t *)txdesc, &priv->txdone_queue); mac802154_givesem(&priv->exclsem); @@ -728,7 +765,11 @@ static void mac802154_txdone_worker(FAR void *arg) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)arg; - int i = 0; + FAR struct ieee802154_txdesc_s *txdesc; + FAR struct ieee802154_data_conf_s *conf; + FAR struct ieee802154_notif_s *notif; + enum ieee802154_frametype_e frametype; + int count; /* Get exclusive access to the driver structure. We don't care about any * signals so if we see one, just go back to trying to get access again. @@ -736,20 +777,121 @@ static void mac802154_txdone_worker(FAR void *arg) while (mac802154_takesem(&priv->exclsem) != 0); - /* For each pending TX descriptor, send an application callback */ + while (1) + { + txdesc = (FAR struct ieee802154_txdesc_s *)sq_remfirst(&priv->txdone_queue); + + if (txdesc == NULL) + { + break; + } + + count++; + + /* Once we get the frametype and data confirmation struct, we can free + * the tx descriptor. + */ + + conf = txdesc->conf; + frametype = txdesc->frametype; + sq_addlast((FAR sq_entry_t *)txdesc, &priv->txdesc_queue); + + /* Cast the data_conf to a notification */ + + notif = (FAR struct ieee802154_notif_s *)conf; + + switch(frametype) + { + case IEEE802154_FRAME_DATA: + { + notif->notiftype = IEEE802154_NOTIFY_CONF_DATA; + + /* Release the MAC then call the callback */ + + mac802154_givesem(&priv->exclsem); + priv->cb->notify(priv->cb, notif); + } + break; + + case IEEE802154_FRAME_COMMAND: + { + mac802154_cmd_txdone(priv, txdesc); + + /* We can deallocate the data conf notification as it is no longer + * needed. We don't use the public function here since we already + * have the MAC locked. Additionally, we are already handling the + * tx_tryagain here, so we wouldn't want to handle it twice. + */ + + notif->flink = priv->notif_free; + priv->notif_free = notif; + mac802154_givesem(&priv->exclsem); + } + break; + + default: + { + mac802154_givesem(&priv->exclsem); + } + break; + + } + } + + /* If we've freed a tx descriptor or notification structure and a previous + * attempt at passing data to the radio layer failed due to insufficient + * available structures, try again now that we've freed some resources */ - for (i = 0; i < priv->txdesc_count; i++) + if (count > 0 && priv->csma_tryagain) { - priv->cb->mcps_notify(priv->cb, IEEE802154_NOTIFY_CONF_DATA, - (FAR const union ieee802154_mcps_notify_u *) &priv->txdesc[i]); + priv->csma_tryagain = false; + priv->radio->ops->txnotify_csma(priv->radio); } + + if (count > 0 && priv->gts_tryagain) + { + priv->gts_tryagain = false; + priv->radio->ops->txnotify_gts(priv->radio); + } +} - /* We've handled all the descriptors and no further desc could have been added - * since we have the struct locked */ +/**************************************************************************** + * Name: mac802154_cmd_txdone + * + * Description: + * Called from mac802154_txdone_worker, this is a helper function for + * handling command frames that have either successfully sent or failed. + * + ****************************************************************************/ - priv->txdesc_count = 0; +static void mac802154_cmd_txdone(FAR struct ieee802154_privmac_s *priv, + FAR struct ieee802154_txdesc_s *txdesc) +{ - mac802154_givesem(&priv->exclsem); + /* Check to see what type of command it was. All information about the command + * will still be valid because it is protected by a semaphore. + */ + + switch (priv->cmd.type) + { + case IEEE802154_CMD_ASSOC_REQ: + if(txdesc->conf->status != IEEE802154_STATUS_SUCCESS) + { + /* if the association request command cannot be sent due to a + * channel access failure, the MAC sublayer shall notify the next + * higher layer. [1] pg. 33 + */ + + + } + else + { + priv->cmd.txdone = true; + } + break; + default: + break; + } } /**************************************************************************** @@ -784,7 +926,7 @@ static void mac802154_rxframe(FAR const struct ieee802154_radiocb_s *radiocb, /* Push the iob onto the tail of the frame list for processing */ - mac802154_push_dataind(priv, ind); + sq_addlast((FAR sq_entry_t *)ind, &priv->dataind_queue); mac802154_givesem(&priv->exclsem); @@ -813,7 +955,6 @@ static void mac802154_rxframe_worker(FAR void *arg) FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)arg; FAR struct ieee802154_data_ind_s *ind; - union ieee802154_mcps_notify_u mcps_notify; FAR struct iob_s *frame; uint16_t *frame_ctrl; bool panid_comp; @@ -829,7 +970,7 @@ static void mac802154_rxframe_worker(FAR void *arg) /* Push the iob onto the tail of the frame list for processing */ - ind = mac802154_pop_dataind(priv); + ind = (FAR struct ieee802154_data_ind_s *)sq_remfirst(&priv->dataind_queue); if (ind == NULL) { @@ -932,11 +1073,9 @@ static void mac802154_rxframe_worker(FAR void *arg) * the frame, otherwise, throw it out. */ - if (priv->cb->mcps_notify != NULL) + if (priv->cb->rxframe != NULL) { - mcps_notify.dataind = ind; - priv->cb->mcps_notify(priv->cb, IEEE802154_NOTIFY_IND_DATA, - &mcps_notify); + priv->cb->rxframe(priv->cb, ind); } else { @@ -1009,6 +1148,15 @@ MACHANDLE mac802154_create(FAR struct ieee802154_radio_s *radiodev) sem_init(&mac->exclsem, 0, 1); + /* Allow exlusive access to the dedicated command transaction */ + + sem_init(&mac->cmd.sem, 0, 1); + + /* Setup the signaling semaphore for the dedicated command transaction */ + + sem_init(&mac->cmd.trans.sem, 0, 0); + sem_setprotocol(&mac->cmd.trans.sem, SEM_PRIO_NONE); + /* Initialize fields */ mac->radio = radiodev; @@ -1030,10 +1178,11 @@ MACHANDLE mac802154_create(FAR struct ieee802154_radio_s *radiodev) radiodev->ops->bind(radiodev, &mac->radiocb.cb); - /* Initialize our data indication pool */ + /* Initialize our various data pools */ ieee802154_indpool_initialize(); - + mac802154_resetqueues(mac); + return (MACHANDLE)mac; } @@ -1052,7 +1201,7 @@ MACHANDLE mac802154_create(FAR struct ieee802154_radio_s *radiodev) * ****************************************************************************/ -int mac802154_bind(MACHANDLE mac, FAR const struct ieee802154_maccb_s *cb) +int mac802154_bind(MACHANDLE mac, FAR const struct mac802154_maccb_s *cb) { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; @@ -1260,7 +1409,7 @@ int mac802154_get_mhrlen(MACHANDLE mac, * The MCPS-DATA.request primitive requests the transfer of a data SPDU * (i.e., MSDU) from a local SSCS entity to a single peer SSCS entity. * Confirmation is returned via the - * struct ieee802154_maccb_s->conf_data callback. + * struct mac802154_maccb_s->conf_data callback. * ****************************************************************************/ @@ -1270,7 +1419,7 @@ int mac802154_req_data(MACHANDLE mac, { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; - FAR struct mac802154_txframe_s trans; + FAR struct mac802154_txtrans_s trans; uint16_t *frame_ctrl; uint8_t mhr_len = 3; /* Start assuming frame control and seq. num */ int ret; @@ -1284,7 +1433,7 @@ int mac802154_req_data(MACHANDLE mac, /* Cast the first two bytes of the IOB to a uint16_t frame control field */ - frame_ctrl = (uint16_t *)&frame->io_data[0]; + frame_ctrl = (FAR uint16_t *)&frame->io_data[0]; /* Ensure we start with a clear frame control field */ @@ -1415,9 +1564,11 @@ int mac802154_req_data(MACHANDLE mac, /* Setup our transaction */ - trans.msdu_handle = meta->msdu_handle; + trans.handle = meta->msdu_handle; + trans.frametype = IEEE802154_FRAME_DATA; trans.frame = frame; - sem_init(&trans.sem, 0, 1); + sem_init(&trans.sem, 0, 0); + sem_setprotocol(&trans.sem, SEM_PRIO_NONE); /* If the TxOptions parameter specifies that a GTS transmission is required, * the MAC sublayer will determine whether it has a valid GTS as described @@ -1477,7 +1628,7 @@ int mac802154_req_data(MACHANDLE mac, { /* Link the transaction into the CSMA transaction list */ - mac802154_push_csma(priv, &trans); + sq_addlast((FAR sq_entry_t *)&trans, &priv->csma_queue); /* We no longer need to have the MAC layer locked. */ @@ -1505,7 +1656,7 @@ int mac802154_req_data(MACHANDLE mac, * Description: * The MCPS-PURGE.request primitive allows the next higher layer to purge * an MSDU from the transaction queue. Confirmation is returned via - * the struct ieee802154_maccb_s->conf_purge callback. + * the struct mac802154_maccb_s->conf_purge callback. * * NOTE: The standard specifies that confirmation should be indicated via * the asynchronous MLME-PURGE.confirm primitve. However, in our @@ -1528,7 +1679,7 @@ int mac802154_req_purge(MACHANDLE mac, uint8_t msdu_handle) * Description: * The MLME-ASSOCIATE.request primitive allows a device to request an * association with a coordinator. Confirmation is returned via the - * struct ieee802154_maccb_s->conf_associate callback. + * struct mac802154_maccb_s->conf_associate callback. * ****************************************************************************/ @@ -1537,31 +1688,213 @@ int mac802154_req_associate(MACHANDLE mac, { FAR struct ieee802154_privmac_s *priv = (FAR struct ieee802154_privmac_s *)mac; + FAR struct mac802154_txtrans_s trans; + FAR struct iob_s *iob; + FAR uint16_t *u16; + bool rxonidle; + int ret; - /* Set the channel of the PHY layer */ - - /* Set the channel page of the PHY layer */ - - /* Set the macPANId */ + /* On receipt of the MLME-ASSOCIATE.request primitive, the MLME of an + * unassociated device first updates the appropriate PHY and MAC PIB + * attributes, as described in 5.1.3.1, and then generates an association + * request command, as defined in 5.3.1 [1] pg.80 + */ - /* Set either the macCoordExtendedAddress and macCoordShortAddress - * depending on the CoordAddrMode in the primitive. + /* Get exlusive access to the shared command transaction. This must happen + * before getting exclusive access to the MAC struct or else there could be + * a lockup condition. This would occur if another thread is using the cmdtrans + * but needs access to the MAC in order to unlock it. */ - if (req->coord_addr.mode == IEEE802154_ADDRMODE_EXTENDED) + if (sem_wait(&priv->cmd.sem) < 0) { + /* EINTR is the only error that we expect */ + int errcode = get_errno(); + DEBUGASSERT(errcode == EINTR); + return -errcode; } - else if (req->coord_addr.mode == IEEE802154_ADDRMODE_EXTENDED) - { + /* Get exclusive access to the MAC */ + + ret = mac802154_takesem(&priv->exclsem); + if (ret < 0) + { + wlerr("ERROR: mac802154_takesem failed: %d\n", ret); + return ret; + } + + /* Set the channel and channel page of the PHY layer */ + + priv->radio->ops->set_attr(priv->radio, IEEE802154_PIB_PHY_CURRENT_CHANNEL, + (FAR const union ieee802154_attr_u *)&req->chnum); + + priv->radio->ops->set_attr(priv->radio, IEEE802154_PIB_PHY_CURRENT_PAGE, + (FAR const union ieee802154_attr_u *)&req->chpage); + + /* Set the PANID attribute */ + + priv->addr.panid = req->coordaddr.panid; + priv->coordaddr.panid = req->coordaddr.panid; + priv->radio->ops->set_attr(priv->radio, IEEE802154_PIB_MAC_PANID, + (FAR const union ieee802154_attr_u *)&req->coordaddr.panid); + + /* Set the coordinator address attributes */ + + priv->coordaddr.mode = req->coordaddr.mode; + + if (priv->coordaddr.mode == IEEE802154_ADDRMODE_SHORT) + { + priv->coordaddr.saddr = req->coordaddr.saddr; + memcpy(&priv->coordaddr.eaddr[0], IEEE802154_EADDR_UNSPEC, + IEEE802154_EADDR_LEN); + } + else if (priv->coordaddr.mode == IEEE802154_ADDRMODE_EXTENDED) + { + priv->coordaddr.saddr = IEEE802154_SADDR_UNSPEC; + memcpy(&priv->coordaddr.eaddr[0], &req->coordaddr.eaddr[0], + IEEE802154_EADDR_LEN); } else + { + ret = -EINVAL; + goto errout; + } + + /* Copy in the capabilities information bitfield */ + + priv->devmode = (req->capabilities.devtype) ? + IEEE802154_DEVMODE_COORD : IEEE802154_DEVMODE_ENDPOINT; + + /* Unlike other attributes, we can't simply cast this one since it is a bit + * in a bitfield. Casting it will give us unpredicatble results. Instead + * of creating a ieee802154_attr_u, we use a local bool. Allocating the + * ieee802154_attr_u value would take up more room on the stack since it is + * as large as the largest attribute type. + */ + + rxonidle = req->capabilities.rxonidle; + priv->radio->ops->set_attr(priv->radio, IEEE802154_PIB_MAC_RX_ON_WHEN_IDLE, + (FAR const union ieee802154_attr_u *)&rxonidle); + + /* Allocate an IOB to put the frame in */ + + iob = iob_alloc(false); + DEBUGASSERT(iob != NULL); + + iob->io_flink = NULL; + iob->io_len = 0; + iob->io_offset = 0; + iob->io_pktlen = 0; + + /* Get a uin16_t reference to the first two bytes. ie frame control field */ + + u16 = (FAR uint16_t *)&iob->io_data[0]; + + *u16 = (IEEE802154_FRAME_COMMAND << IEEE802154_FRAMECTRL_SHIFT_FTYPE); + *u16 |= IEEE802154_FRAMECTRL_ACKREQ; + *u16 |= (priv->coordaddr.mode << IEEE802154_FRAMECTRL_SHIFT_DADDR); + *u16 |= (IEEE802154_ADDRMODE_EXTENDED << IEEE802154_FRAMECTRL_SHIFT_SADDR); + + iob->io_len = 2; + + /* Each time a data or a MAC command frame is generated, the MAC sublayer + * shall copy the value of macDSN into the Sequence Number field of the MHR + * of the outgoing frame and then increment it by one. [1] pg. 40. + */ + + iob->io_data[iob->io_len++] = priv->dsn++; + + /* The Destination PAN Identifier field shall contain the identifier of the + * PAN to which to associate. [1] pg. 68 + */ + + memcpy(&iob->io_data[iob->io_len], &priv->coordaddr.panid, 2); + + /* The Destination Address field shall contain the address from the beacon + * frame that was transmitted by the coordinator to which the association + * request command is being sent. [1] pg. 68 + */ + + if (priv->coordaddr.mode == IEEE802154_ADDRMODE_SHORT) { - return -EINVAL; + memcpy(&iob->io_data[iob->io_len], &priv->coordaddr.saddr, 2); + iob->io_len += 2; } + else if (priv->coordaddr.mode == IEEE802154_ADDRMODE_EXTENDED) + { + memcpy(&iob->io_data[iob->io_len], &priv->coordaddr.eaddr[0], + IEEE802154_EADDR_LEN); + iob->io_len += IEEE802154_EADDR_LEN; + } + + /* The Source PAN Identifier field shall contain the broadcast PAN identifier.*/ - return -ENOTTY; + u16 = (uint16_t *)&iob->io_data[iob->io_len]; + *u16 = IEEE802154_SADDR_BCAST; + iob->io_len += 2; + + /* The Source Address field shall contain the value of macExtendedAddress. */ + + memcpy(&iob->io_data[iob->io_len], &priv->addr.eaddr[0], + IEEE802154_EADDR_LEN); + iob->io_len += IEEE802154_EADDR_LEN; + + /* Copy in the Command Frame Identifier */ + + iob->io_data[iob->io_len++] = IEEE802154_CMD_ASSOC_REQ; + + /* Copy in the capability information bits */ + + iob->io_data[iob->io_len] = 0; + iob->io_data[iob->io_len] |= (req->capabilities.devtype << + IEEE802154_CAPABILITY_SHIFT_DEVTYPE); + iob->io_data[iob->io_len] |= (req->capabilities.powersource << + IEEE802154_CAPABILITY_SHIFT_PWRSRC); + iob->io_data[iob->io_len] |= (req->capabilities.rxonidle << + IEEE802154_CAPABILITY_SHIFT_RXONIDLE); + iob->io_data[iob->io_len] |= (req->capabilities.security << + IEEE802154_CAPABILITY_SHIFT_SECURITY); + iob->io_data[iob->io_len] |= (req->capabilities.allocaddr << + IEEE802154_CAPABILITY_SHIFT_ALLOCADDR); + + iob->io_len++; + + /* Copy reference to the frame into the shared command transaction */ + + priv->cmd.trans.frame = iob; + priv->cmd.trans.frametype = IEEE802154_FRAME_COMMAND; + priv->cmd.type = IEEE802154_CMD_ASSOC_REQ; + + /* Link the transaction into the CSMA transaction list */ + + sq_addlast((FAR sq_entry_t *)&trans, &priv->csma_queue); + + /* We no longer need to have the MAC layer locked. */ + + mac802154_givesem(&priv->exclsem); + + /* TODO: Need to setup a timeout here so that we can return an error to the + * user if the device never receives a response. + */ + + /* Notify the radio driver that there is data available */ + + priv->radio->ops->txnotify_csma(priv->radio); + + /* Wait for the transaction to be passed to the radio layer */ + + ret = sem_wait(&priv->cmd.trans.sem); + if (ret < 0) + { + return -EINTR; + } + + return OK; + +errout: + mac802154_givesem(&priv->exclsem); + return ret; } /**************************************************************************** @@ -1572,7 +1905,7 @@ int mac802154_req_associate(MACHANDLE mac, * notify the coordinator of its intent to leave the PAN. It is also used by * the coordinator to instruct an associated device to leave the PAN. * Confirmation is returned via the - * struct ieee802154_maccb_s->conf_disassociate callback. + * struct mac802154_maccb_s->conf_disassociate callback. * ****************************************************************************/ @@ -1584,7 +1917,6 @@ int mac802154_req_disassociate(MACHANDLE mac, return -ENOTTY; } - /**************************************************************************** * Name: mac802154_req_gts * @@ -1592,7 +1924,7 @@ int mac802154_req_disassociate(MACHANDLE mac, * The MLME-GTS.request primitive allows a device to send a request to the PAN * coordinator to allocate a new GTS or to deallocate an existing GTS. * Confirmation is returned via the - * struct ieee802154_maccb_s->conf_gts callback. + * struct mac802154_maccb_s->conf_gts callback. * ****************************************************************************/ @@ -1636,7 +1968,7 @@ int mac802154_req_reset(MACHANDLE mac, bool rst_pibattr) * The MLME-RX-ENABLE.request primitive allows the next higher layer to * request that the receiver is enable for a finite period of time. * Confirmation is returned via the - * struct ieee802154_maccb_s->conf_rxenable callback. + * struct mac802154_maccb_s->conf_rxenable callback. * ****************************************************************************/ @@ -1657,7 +1989,7 @@ int mac802154_req_rxenable(MACHANDLE mac, * energy on the channel, search for the coordinator with which it associated, * or search for all coordinators transmitting beacon frames within the POS of * the scanning device. Scan results are returned - * via MULTIPLE calls to the struct ieee802154_maccb_s->conf_scan callback. + * via MULTIPLE calls to the struct mac802154_maccb_s->conf_scan callback. * This is a difference with the official 802.15.4 specification, implemented * here to save memory. * @@ -1750,7 +2082,7 @@ int mac802154_req_set(MACHANDLE mac, enum ieee802154_pib_attr_e pib_attr, * Description: * The MLME-START.request primitive makes a request for the device to start * using a new superframe configuration. Confirmation is returned - * via the struct ieee802154_maccb_s->conf_start callback. + * via the struct mac802154_maccb_s->conf_start callback. * ****************************************************************************/ @@ -1858,7 +2190,7 @@ errout: * The MLME-SYNC.request primitive requests to synchronize with the * coordinator by acquiring and, if specified, tracking its beacons. * Confirmation is returned via the - * struct ieee802154_maccb_s->int_commstatus callback. TOCHECK. + * struct mac802154_maccb_s->int_commstatus callback. TOCHECK. * ****************************************************************************/ @@ -1875,8 +2207,8 @@ int mac802154_req_sync(MACHANDLE mac, FAR struct ieee802154_sync_req_s *req) * Description: * The MLME-POLL.request primitive prompts the device to request data from * the coordinator. Confirmation is returned via the - * struct ieee802154_maccb_s->conf_poll callback, followed by a - * struct ieee802154_maccb_s->ind_data callback. + * struct mac802154_maccb_s->conf_poll callback, followed by a + * struct mac802154_maccb_s->ind_data callback. * ****************************************************************************/ @@ -1921,3 +2253,42 @@ int mac802154_resp_orphan(MACHANDLE mac, return -ENOTTY; } +/**************************************************************************** + * Name: mac802154_notif_free + * + * Description: + * When the MAC calls the registered callback, it passes a reference + * to a mac802154_notify_s structure. This structure needs to be freed + * after the callback handler is done using it. + * + ****************************************************************************/ + +int mac802154_notif_free(MACHANDLE mac, + FAR struct ieee802154_notif_s *notif) +{ + FAR struct ieee802154_privmac_s *priv = + (FAR struct ieee802154_privmac_s *)mac; + + /* Get exclusive access to the MAC */ + + while(mac802154_takesem(&priv->exclsem) < 0); + + notif->flink = priv->notif_free; + priv->notif_free = notif; + + mac802154_givesem(&priv->exclsem); + + if (priv->csma_tryagain) + { + priv->csma_tryagain = false; + priv->radio->ops->txnotify_csma(priv->radio); + } + + if (priv->gts_tryagain) + { + priv->gts_tryagain = false; + priv->radio->ops->txnotify_gts(priv->radio); + } + + return -ENOTTY; +} diff --git a/wireless/ieee802154/mac802154.h b/wireless/ieee802154/mac802154.h index 168bc33cf2..2e8110f755 100644 --- a/wireless/ieee802154/mac802154.h +++ b/wireless/ieee802154/mac802154.h @@ -54,6 +54,26 @@ #include +/**************************************************************************** + * Public Data Types + ****************************************************************************/ + + + +/* Callback operations to notify the next highest layer of various asynchronous + * events, usually triggered by some previous request or response invoked by the + * upper layer. + */ + +struct mac802154_maccb_s +{ + CODE void (*notify)(FAR const struct mac802154_maccb_s *maccb, + FAR struct ieee802154_notif_s *notif); + + CODE void (*rxframe)(FAR const struct mac802154_maccb_s *maccb, + FAR struct ieee802154_data_ind_s *ind); +}; + /**************************************************************************** * Public Function Prototypes ****************************************************************************/ @@ -75,7 +95,7 @@ struct iob_s; /* Forward reference */ * ****************************************************************************/ -int mac802154_bind(MACHANDLE mac, FAR const struct ieee802154_maccb_s *cb); +int mac802154_bind(MACHANDLE mac, FAR const struct mac802154_maccb_s *cb); /**************************************************************************** * Name: mac802154_ioctl @@ -117,7 +137,7 @@ int mac802154_get_mhrlen(MACHANDLE mac, * The MCPS-DATA.request primitive requests the transfer of a data SPDU * (i.e., MSDU) from a local SSCS entity to a single peer SSCS entity. * Confirmation is returned via the - * struct ieee802154_maccb_s->conf_data callback. + * struct mac802154_maccb_s->conf_data callback. * ****************************************************************************/ @@ -131,7 +151,7 @@ int mac802154_req_data(MACHANDLE mac, * Description: * The MCPS-PURGE.request primitive allows the next higher layer to purge * an MSDU from the transaction queue. Confirmation is returned via - * the struct ieee802154_maccb_s->conf_purge callback. + * the struct mac802154_maccb_s->conf_purge callback. * * NOTE: The standard specifies that confirmation should be indicated via * the asynchronous MLME-PURGE.confirm primitve. However, in our @@ -149,7 +169,7 @@ int mac802154_req_purge(MACHANDLE mac, uint8_t msdu_handle); * Description: * The MLME-ASSOCIATE.request primitive allows a device to request an * association with a coordinator. Confirmation is returned via the - * struct ieee802154_maccb_s->conf_associate callback. + * struct mac802154_maccb_s->conf_associate callback. * ****************************************************************************/ @@ -166,7 +186,7 @@ int mac802154_req_associate(MACHANDLE mac, * PAN. * * Confirmation is returned via the - * struct ieee802154_maccb_s->conf_disassociate callback. + * struct mac802154_maccb_s->conf_disassociate callback. * ****************************************************************************/ @@ -180,7 +200,7 @@ int mac802154_req_disassociate(MACHANDLE mac, * The MLME-GTS.request primitive allows a device to send a request to the * PAN coordinator to allocate a new GTS or to deallocate an existing GTS. * Confirmation is returned via the - * struct ieee802154_maccb_s->conf_gts callback. + * struct mac802154_maccb_s->conf_gts callback. * ****************************************************************************/ @@ -214,7 +234,7 @@ int mac802154_req_reset(MACHANDLE mac, bool rst_pibattr); * The MLME-RX-ENABLE.request primitive allows the next higher layer to * request that the receiver is enable for a finite period of time. * Confirmation is returned via the - * struct ieee802154_maccb_s->conf_rxenable callback. + * struct mac802154_maccb_s->conf_rxenable callback. * ****************************************************************************/ @@ -230,7 +250,7 @@ int mac802154_req_rxenable(MACHANDLE mac, * the energy on the channel, search for the coordinator with which it * associated, or search for all coordinators transmitting beacon frames * within the POS of the scanning device. Scan results are returned - * via MULTIPLE calls to the struct ieee802154_maccb_s->conf_scan + * via MULTIPLE calls to the struct mac802154_maccb_s->conf_scan * callback. This is a difference with the official 802.15.4 * specification, implemented here to save memory. * @@ -280,7 +300,7 @@ int mac802154_req_set(MACHANDLE mac, enum ieee802154_pib_attr_e pib_attr, * Description: * The MLME-START.request primitive makes a request for the device to * start using a new superframe configuration. Confirmation is returned - * via the struct ieee802154_maccb_s->conf_start callback. + * via the struct mac802154_maccb_s->conf_start callback. * ****************************************************************************/ @@ -293,7 +313,7 @@ int mac802154_req_start(MACHANDLE mac, FAR struct ieee802154_start_req_s *req); * The MLME-SYNC.request primitive requests to synchronize with the * coordinator by acquiring and, if specified, tracking its beacons. * Confirmation is returned via the - * struct ieee802154_maccb_s->int_commstatus callback. TOCHECK. + * struct mac802154_maccb_s->int_commstatus callback. TOCHECK. * ****************************************************************************/ @@ -305,8 +325,8 @@ int mac802154_req_sync(MACHANDLE mac, FAR struct ieee802154_sync_req_s *req); * Description: * The MLME-POLL.request primitive prompts the device to request data from * the coordinator. Confirmation is returned via the - * struct ieee802154_maccb_s->conf_poll callback, followed by a - * struct ieee802154_maccb_s->ind_data callback. + * struct mac802154_maccb_s->conf_poll callback, followed by a + * struct mac802154_maccb_s->ind_data callback. * ****************************************************************************/ @@ -336,6 +356,18 @@ int mac802154_resp_associate(MACHANDLE mac, int mac802154_resp_orphan(MACHANDLE mac, FAR struct ieee802154_orphan_resp_s *resp); +/**************************************************************************** + * Name: mac802154_notif_free + * + * Description: + * When the MAC calls the registered callback, it passes a reference + * to a mac802154_notify_s structure. This structure needs to be freed + * after the callback handler is done using it. + * + ****************************************************************************/ + +int mac802154_notif_free(MACHANDLE mac, + FAR struct ieee802154_notif_s *notif); #undef EXTERN #ifdef __cplusplus diff --git a/wireless/ieee802154/mac802154_device.c b/wireless/ieee802154/mac802154_device.c index 309ca2c99c..a41ff240bf 100644 --- a/wireless/ieee802154/mac802154_device.c +++ b/wireless/ieee802154/mac802154_device.c @@ -83,22 +83,11 @@ struct mac802154dev_open_s volatile bool md_closing; }; -struct mac802154dev_dwait_s -{ - uint8_t mw_handle; /* The msdu handle identifying the frame */ - sem_t mw_sem; /* The semaphore used to signal the completion */ - int mw_status; /* The success/error of the transaction */ - - /* Supports a singly linked list */ - - FAR struct mac802154dev_dwait_s *mw_flink; -}; - struct mac802154dev_callback_s { /* This holds the information visible to the MAC layer */ - struct ieee802154_maccb_s mc_cb; /* Interface understood by the MAC layer */ + struct mac802154_maccb_s mc_cb; /* Interface understood by the MAC layer */ FAR struct mac802154_chardevice_s *mc_priv; /* Our priv data */ }; @@ -108,31 +97,33 @@ struct mac802154_chardevice_s struct mac802154dev_callback_s md_cb; /* Callback information */ sem_t md_exclsem; /* Exclusive device access */ - bool readpending; /* Is there a read using the semaphore? */ - sem_t readsem; /* Signaling semaphore for waiting read */ + /* Hold a list of events */ + + bool enableevents : 1; /* Are events enabled? */ + bool geteventpending : 1; /* Is there a get event using the semaphore? */ + sem_t geteventsem; /* Signaling semaphore for waiting get event */ + FAR struct ieee802154_notif_s *event_head; + FAR struct ieee802154_notif_s *event_tail; /* The following is a singly linked list of open references to the * MAC device. */ FAR struct mac802154dev_open_s *md_open; - FAR struct mac802154dev_dwait_s *md_dwait; /* Hold a list of transactions as a "readahead" buffer */ - FAR struct ieee802154_data_ind_s *dataind_head; - FAR struct ieee802154_data_ind_s *dataind_tail; + bool readpending; /* Is there a read using the semaphore? */ + sem_t readsem; /* Signaling semaphore for waiting read */ + sq_queue_t dataind_queue; #ifndef CONFIG_DISABLE_SIGNALS - /* MCPS Service notification information */ + /* MAC Service notification information */ - struct mac802154dev_notify_s md_mcps_notify; - pid_t md_mcps_pid; + bool notify_registered; + struct mac802154dev_notify_s md_notify; + pid_t md_notify_pid; - /* MLME Service notification information */ - - struct mac802154dev_notify_s md_mlme_notify; - pid_t md_mlme_pid; #endif }; @@ -145,19 +136,16 @@ struct mac802154_chardevice_s static inline int mac802154dev_takesem(sem_t *sem); #define mac802154dev_givesem(s) sem_post(s); -static void mac802154dev_push_dataind(FAR struct mac802154_chardevice_s *dev, - FAR struct ieee802154_data_ind_s *ind); -static FAR struct ieee802154_data_ind_s * - mac802154dev_pop_dataind(FAR struct mac802154_chardevice_s *dev); - +static inline void mac802154dev_pushevent(FAR struct mac802154_chardevice_s *dev, + FAR struct ieee802154_notif_s *notif); +static inline FAR struct ieee802154_notif_s * + mac802154dev_popevent(FAR struct mac802154_chardevice_s *dev); -static void mac802154dev_mlme_notify(FAR const struct ieee802154_maccb_s *maccb, - enum ieee802154_macnotify_e notif, - FAR const union ieee802154_mlme_notify_u *arg); +static void mac802154dev_notify(FAR const struct mac802154_maccb_s *maccb, + FAR struct ieee802154_notif_s *notif); -static void mac802154dev_mcps_notify(FAR const struct ieee802154_maccb_s *maccb, - enum ieee802154_macnotify_e notif, - FAR const union ieee802154_mcps_notify_u *arg); +static void mac802154dev_rxframe(FAR const struct mac802154_maccb_s *maccb, + FAR struct ieee802154_data_ind_s *ind); static int mac802154dev_open(FAR struct file *filep); static int mac802154dev_close(FAR struct file *filep); @@ -168,13 +156,6 @@ static ssize_t mac802154dev_write(FAR struct file *filep, static int mac802154dev_ioctl(FAR struct file *filep, int cmd, unsigned long arg); -/* MAC callback helpers */ - -static void mac802154dev_conf_data(FAR struct mac802154_chardevice_s *dev, - FAR const struct ieee802154_data_conf_s *conf); -static void mac802154dev_ind_data(FAR struct mac802154_chardevice_s *dev, - FAR struct ieee802154_data_ind_s *ind); - /**************************************************************************** * Private Data ****************************************************************************/ @@ -224,76 +205,60 @@ static inline int mac802154dev_takesem(sem_t *sem) } /**************************************************************************** - * Name: mac802154dev_push_dataind + * Name: mac802154dev_pushevent * * Description: - * Push a data indication onto the list to be processed + * Push event onto the event queue + * + * Assumptions: + * Called with the char device struct locked. * ****************************************************************************/ -static void mac802154dev_push_dataind(FAR struct mac802154_chardevice_s *dev, - FAR struct ieee802154_data_ind_s *ind) +static inline void mac802154dev_pushevent(FAR struct mac802154_chardevice_s *dev, + FAR struct ieee802154_notif_s *notif) { - /* Ensure the forward link is NULL */ - - ind->flink = NULL; - - /* If the tail is not empty, make the frame pointed to by the tail, - * point to the new data indication */ - - if (dev->dataind_tail != NULL) + notif->flink = NULL; + if (!dev->event_head) { - dev->dataind_tail->flink = ind; + dev->event_head = notif; + dev->event_tail = notif; } - - /* Point the tail at the new frame */ - - dev->dataind_tail = ind; - - /* If the head is NULL, we need to point it at the data indication since there - * is only one indication in the list at this point */ - - if (dev->dataind_head == NULL) + else { - dev->dataind_head = ind; + dev->event_tail->flink = notif; + dev->event_tail = notif; } } /**************************************************************************** - * Name: mac802154dev_pop_dataind + * Name: mac802154dev_popevent * * Description: - * Pop a data indication from the list + * Pop an event off of the event queue + * + * Assumptions: + * Called with the char device struct locked. * ****************************************************************************/ -static FAR struct ieee802154_data_ind_s * - mac802154dev_pop_dataind(FAR struct mac802154_chardevice_s *dev) +static inline FAR struct ieee802154_notif_s * + mac802154dev_popevent(FAR struct mac802154_chardevice_s *dev) { - FAR struct ieee802154_data_ind_s *ind; + FAR struct ieee802154_notif_s *notif = dev->event_head; - if (dev->dataind_head == NULL) + if (notif) { - return NULL; - } - - /* Get the data indication from the head of the list */ - - ind = dev->dataind_head; - ind->flink = NULL; - - /* Move the head pointer to the next data indication */ - - dev->dataind_head = ind->flink; - - /* If the head is now NULL, the list is empty, so clear the tail too */ - - if (dev->dataind_head == NULL) - { - dev->dataind_tail = NULL; + dev->event_head = notif->flink; + if (!dev->event_head) + { + dev->event_head = NULL; + } + + notif->flink = NULL; } - return ind; + return notif; } /**************************************************************************** @@ -383,7 +348,7 @@ static int mac802154dev_close(FAR struct file *filep) * * This is actually a pretty feeble attempt to handle this. The * improbable race condition occurs if two different threads try to - * close the joystick driver at the same time. The rule: don't do + * close the driver at the same time. The rule: don't do * that! It is feeble because we do not really enforce stale pointer * detection anyway. */ @@ -437,6 +402,23 @@ static int mac802154dev_close(FAR struct file *filep) /* And free the open structure */ kmm_free(opriv); + + /* If there are now no open instances of the driver and a signal handler is + * not registered, purge the list of events. + */ + + if (dev->md_open) + { + FAR struct ieee802154_notif_s *notif; + + while (dev->event_head != NULL) + { + notif = mac802154dev_popevent(dev); + DEBUGASSERT(notif != NULL); + mac802154_notif_free(dev->md_mac, notif); + } + } + ret = OK; errout_with_exclsem: @@ -491,7 +473,7 @@ static ssize_t mac802154dev_read(FAR struct file *filep, FAR char *buffer, /* Try popping a data indication off the list */ - ind = mac802154dev_pop_dataind(dev); + ind = (FAR struct ieee802154_data_ind_s *)sq_remfirst(&dev->dataind_queue); /* If the indication is not null, we can exit the loop and copy the data */ @@ -522,11 +504,7 @@ static ssize_t mac802154dev_read(FAR struct file *filep, FAR char *buffer, if (sem_wait(&dev->readsem) < 0) { DEBUGASSERT(errno == EINTR); - /* Need to get exclusive access again to change the pending bool */ - - ret = mac802154dev_takesem(&dev->md_exclsem); dev->readpending = false; - mac802154dev_givesem(&dev->md_exclsem); return -EINTR; } @@ -571,7 +549,6 @@ static ssize_t mac802154dev_write(FAR struct file *filep, FAR struct mac802154_chardevice_s *dev; FAR struct mac802154dev_txframe_s *tx; FAR struct iob_s *iob; - struct mac802154dev_dwait_s dwait; int ret; DEBUGASSERT(filep && filep->f_inode); @@ -579,7 +556,7 @@ static ssize_t mac802154dev_write(FAR struct file *filep, DEBUGASSERT(inode->i_private); dev = (FAR struct mac802154_chardevice_s *)inode->i_private; - /* Check if the struct is write */ + /* Check if the struct is the correct size */ if (len != sizeof(struct mac802154dev_txframe_s)) { @@ -618,38 +595,6 @@ static ssize_t mac802154dev_write(FAR struct file *filep, iob->io_len += tx->length; - /* If this is a blocking operation, we need to setup a wait struct so we - * can unblock when the packet transmission has finished. If this is a - * non-blocking write, we pass off the data and then move along. Technically - * we stil have to wait for the transaction to get put into the buffer, but we - * won't wait for the transaction to actually finish. */ - - if (!(filep->f_oflags & O_NONBLOCK)) - { - /* Get exclusive access to the driver structure */ - - ret = mac802154dev_takesem(&dev->md_exclsem); - if (ret < 0) - { - wlerr("ERROR: mac802154dev_takesem failed: %d\n", ret); - return ret; - } - - /* Setup the wait struct */ - - dwait.mw_handle = tx->meta.msdu_handle; - - /* Link the wait struct */ - - dwait.mw_flink = dev->md_dwait; - dev->md_dwait = &dwait; - - sem_init(&dwait.mw_sem, 0, 0); - sem_setprotocol(&dwait.mw_sem, SEM_PRIO_NONE); - - mac802154dev_givesem(&dev->md_exclsem); - } - /* Pass the request to the MAC layer */ ret = mac802154_req_data(dev->md_mac, &tx->meta, iob); @@ -659,28 +604,6 @@ static ssize_t mac802154dev_write(FAR struct file *filep, return ret; } - if (!(filep->f_oflags & O_NONBLOCK)) - { - /* Wait for the DATA.confirm callback to be called for our handle */ - - if (sem_wait(&dwait.mw_sem) < 0) - { - /* This should only happen if the wait was canceled by an signal */ - - sem_destroy(&dwait.mw_sem); - DEBUGASSERT(errno == EINTR); - return -EINTR; - } - - /* The unlinking of the wait struct happens inside the callback. This - * is more efficient since it will already have to find the struct in - * the list in order to perform the sem_post. - */ - - sem_destroy(&dwait.mw_sem); - return dwait.mw_status; - } - return OK; } @@ -688,7 +611,7 @@ static ssize_t mac802154dev_write(FAR struct file *filep, * Name: mac802154dev_ioctl * * Description: - * Control the MAC layer via MLME IOCTL commands. + * Control the MAC layer via IOCTL commands. * ****************************************************************************/ @@ -728,7 +651,7 @@ static int mac802154dev_ioctl(FAR struct file *filep, int cmd, * failure with the errno value set appropriately. */ - case MAC802154IOC_MLME_REGISTER: + case MAC802154IOC_NOTIFY_REGISTER: { FAR struct mac802154dev_notify_s *notify = (FAR struct mac802154dev_notify_s *)((uintptr_t)arg); @@ -737,38 +660,101 @@ static int mac802154dev_ioctl(FAR struct file *filep, int cmd, { /* Save the notification events */ - dev->md_mlme_notify.mn_signo = notify->mn_signo; - dev->md_mlme_pid = getpid(); + dev->md_notify.mn_signo = notify->mn_signo; + dev->md_notify_pid = getpid(); + dev->notify_registered = true; - return OK; + ret = OK; + } + else + { + ret = -EINVAL; } } break; +#endif - case MAC802154IOC_MCPS_REGISTER: + case MAC802154IOC_GET_EVENT: { - FAR struct mac802154dev_notify_s *notify = - (FAR struct mac802154dev_notify_s *)((uintptr_t)arg); + FAR struct ieee802154_notif_s *usr_notif = + (FAR struct ieee802154_notif_s *)((uintptr_t)arg); + FAR struct ieee802154_notif_s *notif; - if (notify) + while (1) { - /* Save the notification events */ - - dev->md_mcps_notify.mn_signo = notify->mn_signo; - dev->md_mcps_pid = getpid(); - - return OK; + /* Try popping an event off the queue */ + + notif = mac802154dev_popevent(dev); + + /* If there was an event to pop off, copy it into the user data and + * free it from the MAC layer's memory. + */ + + if (notif != NULL) + { + memcpy(usr_notif, notif, sizeof(struct ieee802154_notif_s)); + + /* Free the notification */ + + mac802154_notif_free(dev->md_mac, notif); + + ret = OK; + break; + } + + /* If this is a non-blocking call, or if there is another getevent + * operation already pending, don't block. This driver returns + * EAGAIN even when configured as non-blocking if another getevent + * operation is already pending This situation should be rare. + * It will only occur when there are 2 calls from separate threads + * and there was no events in the queue. + */ + + if ((filep->f_oflags & O_NONBLOCK) || dev->geteventpending) + { + ret = -EAGAIN; + break; + } + + dev->geteventpending = true; + mac802154dev_givesem(&dev->md_exclsem); + + /* Wait to be signaled when an event is queued */ + + if (sem_wait(&dev->geteventsem) < 0) + { + DEBUGASSERT(errno == EINTR); + dev->geteventpending = false; + return -EINTR; + } + + /* Get exclusive access again, then loop back around and try and + * pop an event off the queue + */ + + ret = mac802154dev_takesem(&dev->md_exclsem); + if (ret < 0) + { + wlerr("ERROR: mac802154dev_takesem failed: %d\n", ret); + return ret; + } } } break; -#endif + + case MAC802154IOC_ENABLE_EVENTS: + { + dev->enableevents = (bool)arg; + ret = OK; + } + break; + default: { /* Forward any unrecognized commands to the MAC layer */ - mac802154_ioctl(dev->md_mac, cmd, arg); + ret = mac802154_ioctl(dev->md_mac, cmd, arg); } - break; } @@ -776,28 +762,8 @@ static int mac802154dev_ioctl(FAR struct file *filep, int cmd, return ret; } -static void mac802154dev_mlme_notify(FAR const struct ieee802154_maccb_s *maccb, - enum ieee802154_macnotify_e notif, - FAR const union ieee802154_mlme_notify_u *arg) -{ - FAR struct mac802154dev_callback_s *cb = - (FAR struct mac802154dev_callback_s *)maccb; - FAR struct mac802154_chardevice_s *dev; - - DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); - dev = cb->mc_priv; - - switch (notif) - { -#warning Handle MLME notifications - default: - break; - } -} - -static void mac802154dev_mcps_notify(FAR const struct ieee802154_maccb_s *maccb, - enum ieee802154_macnotify_e notif, - FAR const union ieee802154_mcps_notify_u *arg) +static void mac802154dev_notify(FAR const struct mac802154_maccb_s *maccb, + FAR struct ieee802154_notif_s *notif) { FAR struct mac802154dev_callback_s *cb = (FAR struct mac802154dev_callback_s *)maccb; @@ -806,89 +772,70 @@ static void mac802154dev_mcps_notify(FAR const struct ieee802154_maccb_s *maccb, DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); dev = cb->mc_priv; - switch (notif) - { - case IEEE802154_NOTIFY_CONF_DATA: - { - mac802154dev_conf_data(dev, &arg->dataconf); - } - break; - case IEEE802154_NOTIFY_IND_DATA: - { - mac802154dev_ind_data(dev, arg->dataind); - } - break; - default: - break; - } -} - -static void mac802154dev_conf_data(FAR struct mac802154_chardevice_s *dev, - FAR const struct ieee802154_data_conf_s *conf) -{ - FAR struct mac802154dev_dwait_s *curr; - FAR struct mac802154dev_dwait_s *prev; - /* Get exclusive access to the driver structure. We don't care about any * signals so if we see one, just go back to trying to get access again */ while (mac802154dev_takesem(&dev->md_exclsem) != 0); - /* Search to see if there is a dwait pending for this transaction */ - - for (prev = NULL, curr = dev->md_dwait; - curr && curr->mw_handle != conf->handle; - prev = curr, curr = curr->mw_flink); + /* If there is a registered notification receiver, queue the event and signal + * the receiver. Events should be popped from the queue from the application + * at a reasonable rate in order for the MAC layer to be able to allocate new + * notifications. + */ - /* If a dwait is found */ + if (dev->enableevents && (dev->md_open != NULL || dev->notify_registered)) + { + mac802154dev_pushevent(dev, notif); - if (curr) - { - /* Unlink the structure from the list. The struct should be allocated on - * the calling write's stack, so we don't need to worry about deallocating - * here */ + /* Check if there is a read waiting for data */ - if (prev) + if (dev->geteventpending) { - prev->mw_flink = curr->mw_flink; - } - else - { - dev->md_dwait = curr->mw_flink; - } + /* Wake the thread waiting for the data transmission */ - /* Copy the transmission status into the dwait struct */ - - curr->mw_status = conf->status; - - /* Wake the thread waiting for the data transmission */ - - sem_post(&curr->mw_sem); + dev->geteventpending = false; + sem_post(&dev->geteventsem); + } - /* Release the driver */ +#ifndef CONFIG_DISABLE_SIGNALS + if (dev->notify_registered) + { - mac802154dev_givesem(&dev->md_exclsem); +#ifdef CONFIG_CAN_PASS_STRUCTS + union sigval value; + value.sival_int = (int)notif->notiftype; + (void)sigqueue(dev->md_notify_pid, dev->md_notify.mn_signo, value); +#else + (void)sigqueue(dev->md_notify_pid, dev->md_notify.mn_signo, + (FAR void *)notif->notiftype); +#endif + } +#endif } + else + { + /* Just free the event if the driver is closed and there isn't a registered + * signal number. + */ -#ifndef CONFIG_DISABLE_SIGNALS - /* Send a signal to the registered application */ + mac802154_notif_free(dev->md_mac, notif); + } -#ifdef CONFIG_CAN_PASS_STRUCTS - /* Copy the status as the signal data to be optionally used by app */ + /* Release the driver */ - union sigval value; - value.sival_int = (int)conf->status; - (void)sigqueue(dev->md_mcps_pid, dev->md_mcps_notify.mn_signo, value); -#else - (void)sigqueue(dev->md_mcps_pid, dev->md_mcps_notify.mn_signo, - value.sival_ptr); -#endif -#endif + mac802154dev_givesem(&dev->md_exclsem); } -static void mac802154dev_ind_data(FAR struct mac802154_chardevice_s *dev, - FAR struct ieee802154_data_ind_s *ind) +static void mac802154dev_rxframe(FAR const struct mac802154_maccb_s *maccb, + FAR struct ieee802154_data_ind_s *ind) { + FAR struct mac802154dev_callback_s *cb = + (FAR struct mac802154dev_callback_s *)maccb; + FAR struct mac802154_chardevice_s *dev; + + DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); + dev = cb->mc_priv; + /* Get exclusive access to the driver structure. We don't care about any * signals so if we see one, just go back to trying to get access again */ @@ -896,7 +843,7 @@ static void mac802154dev_ind_data(FAR struct mac802154_chardevice_s *dev, /* Push the indication onto the list */ - mac802154dev_push_dataind(dev, ind); + sq_addlast((FAR sq_entry_t *)ind, &dev->dataind_queue); /* Check if there is a read waiting for data */ @@ -911,21 +858,6 @@ static void mac802154dev_ind_data(FAR struct mac802154_chardevice_s *dev, /* Release the driver */ mac802154dev_givesem(&dev->md_exclsem); - -#ifndef CONFIG_DISABLE_SIGNALS - /* Send a signal to the registered application */ - -#ifdef CONFIG_CAN_PASS_STRUCTS - /* Copy the status as the signal data to be optionally used by app */ - - union sigval value; - value.sival_int = IEEE802154_STATUS_SUCCESS; - (void)sigqueue(dev->md_mcps_pid, dev->md_mcps_notify.mn_signo, value); -#else - (void)sigqueue(dev->md_mcps_pid, dev->md_mcps_notify.mn_signo, - value.sival_ptr); -#endif -#endif } /**************************************************************************** @@ -953,7 +885,7 @@ static void mac802154dev_ind_data(FAR struct mac802154_chardevice_s *dev, int mac802154dev_register(MACHANDLE mac, int minor) { FAR struct mac802154_chardevice_s *dev; - FAR struct ieee802154_maccb_s *maccb; + FAR struct mac802154_maccb_s *maccb; char devname[DEVNAME_FMTLEN]; int ret; @@ -974,13 +906,25 @@ int mac802154dev_register(MACHANDLE mac, int minor) sem_setprotocol(&dev->readsem, SEM_PRIO_NONE); dev->readpending = false; + sq_init(&dev->dataind_queue); + + dev->geteventpending = false; + sem_init(&dev->geteventsem, 0, 0); + sem_setprotocol(&dev->geteventsem, SEM_PRIO_NONE); + + dev->event_head = NULL; + dev->event_tail = NULL; + + dev->enableevents = true; + dev->notify_registered = false; + /* Initialize the MAC callbacks */ dev->md_cb.mc_priv = dev; - maccb = &dev->md_cb.mc_cb; - maccb->mlme_notify = mac802154dev_mlme_notify; - maccb->mcps_notify = mac802154dev_mcps_notify; + maccb = &dev->md_cb.mc_cb; + maccb->notify = mac802154dev_notify; + maccb->rxframe = mac802154dev_rxframe; /* Bind the callback structure */ diff --git a/wireless/ieee802154/mac802154_netdev.c b/wireless/ieee802154/mac802154_netdev.c index b09ea4493c..7fcd25e3af 100644 --- a/wireless/ieee802154/mac802154_netdev.c +++ b/wireless/ieee802154/mac802154_netdev.c @@ -109,7 +109,7 @@ struct macnet_callback_s { /* This holds the information visible to the MAC layer */ - struct ieee802154_maccb_s mc_cb; /* Interface understood by the MAC layer */ + struct mac802154_maccb_s mc_cb; /* Interface understood by the MAC layer */ FAR struct macnet_driver_s *mc_priv; /* Our priv data */ }; @@ -138,12 +138,10 @@ struct macnet_driver_s /* IEE802.15.4 MAC callback functions ***************************************/ -static void macnet_mlme_notify(FAR const struct ieee802154_maccb_s *maccb, - enum ieee802154_macnotify_e notif, - FAR const union ieee802154_mlme_notify_u *arg); -static void macnet_mcps_notify(FAR const struct ieee802154_maccb_s *maccb, - enum ieee802154_macnotify_e notif, - FAR const union ieee802154_mcps_notify_u *arg); +static void macnet_notify(FAR const struct mac802154_maccb_s *maccb, + FAR struct ieee802154_notif_s *notif); +static void macnet_rxframe(FAR const struct mac802154_maccb_s *maccb, + FAR struct ieee802154_data_ind_s *ind); /* Asynchronous confirmations to requests */ @@ -166,8 +164,6 @@ static void macnet_conf_poll(FAR struct macnet_driver_s *priv, /* Asynchronous event indications, replied to synchronously with responses */ -static void macnet_ind_data(FAR struct macnet_driver_s *priv, - FAR struct ieee802154_data_ind_s *conf); static void macnet_ind_associate(FAR struct macnet_driver_s *priv, FAR struct ieee802154_assoc_ind_s *conf); static void macnet_ind_disassociate(FAR struct macnet_driver_s *priv, @@ -221,15 +217,14 @@ static int macnet_req_data(FAR struct ieee802154_driver_s *netdev, ****************************************************************************/ /**************************************************************************** - * Name: macnet_mlme_notify + * Name: macnet_notify * * Description: * ****************************************************************************/ -static void macnet_mlme_notify(FAR const struct ieee802154_maccb_s *maccb, - enum ieee802154_macnotify_e notif, - FAR const union ieee802154_mlme_notify_u *arg) +static void macnet_notify(FAR const struct mac802154_maccb_s *maccb, + FAR struct ieee802154_notif_s *notif) { FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)maccb; @@ -238,8 +233,13 @@ static void macnet_mlme_notify(FAR const struct ieee802154_maccb_s *maccb, DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); priv = cb->mc_priv; - switch (notif) + switch (notif->notiftype) { + case IEEE802154_NOTIFY_CONF_DATA: + { + macnet_conf_data(priv, ¬if->u.dataconf); + } + break; default: break; @@ -247,40 +247,38 @@ static void macnet_mlme_notify(FAR const struct ieee802154_maccb_s *maccb, } /**************************************************************************** - * Name: macnet_mcps_notify + * Name: macnet_rxframe * * Description: * ****************************************************************************/ -static void macnet_mcps_notify(FAR const struct ieee802154_maccb_s *maccb, - enum ieee802154_macnotify_e notif, - FAR const union ieee802154_mcps_notify_u *arg) +static void macnet_rxframe(FAR const struct mac802154_maccb_s *maccb, + FAR struct ieee802154_data_ind_s *ind) { FAR struct macnet_callback_s *cb = (FAR struct macnet_callback_s *)maccb; FAR struct macnet_driver_s *priv; + FAR struct iob_s *iob; DEBUGASSERT(cb != NULL && cb->mc_priv != NULL); priv = cb->mc_priv; - switch (notif) - { - case IEEE802154_NOTIFY_CONF_DATA: - { - macnet_conf_data(priv, &arg->dataconf); - } - break; + /* Extract the IOB containing the frame from the struct ieee802154_data_ind_s */ - case IEEE802154_NOTIFY_IND_DATA: - { - macnet_ind_data(priv, arg->dataind); - } - break; + DEBUGASSERT(priv != NULL && ind != NULL && ind->frame != NULL); + iob = ind->frame; + ind->frame = NULL; - default: - break; - } + /* Transfer the frame to the network logic */ + + sixlowpan_input(&priv->md_dev, iob, ind); + + /* sixlowpan_input() will free the IOB, but we must free the struct + * ieee802154_data_ind_s container here. + */ + + ieee802154_ind_free(ind); } /**************************************************************************** @@ -391,36 +389,6 @@ static void macnet_conf_poll(FAR struct macnet_driver_s *priv, } -/**************************************************************************** - * Name: macnet_ind_data - * - * Description: - * Data frame received - * - ****************************************************************************/ - -static void macnet_ind_data(FAR struct macnet_driver_s *priv, - FAR struct ieee802154_data_ind_s *ind) -{ - FAR struct iob_s *iob; - - /* Extract the IOB containing the frame from the struct ieee802154_data_ind_s */ - - DEBUGASSERT(priv != NULL && ind != NULL && ind->frame != NULL); - iob = ind->frame; - ind->frame = NULL; - - /* Transfer the frame to the network logic */ - - sixlowpan_input(&priv->md_dev, iob, ind); - - /* sixlowpan_input() will free the IOB, but we must free the struct - * ieee802154_data_ind_s container here. - */ - - ieee802154_ind_free(ind); -} - /**************************************************************************** * Name: macnet_ind_associate * @@ -1041,7 +1009,7 @@ int mac802154netdev_register(MACHANDLE mac) FAR struct macnet_driver_s *priv; FAR struct ieee802154_driver_s *ieee; FAR struct net_driver_s *dev; - FAR struct ieee802154_maccb_s *maccb; + FAR struct mac802154_maccb_s *maccb; FAR uint8_t *pktbuf; int ret; @@ -1103,9 +1071,9 @@ int mac802154netdev_register(MACHANDLE mac) priv->md_cb.mc_priv = priv; - maccb = &priv->md_cb.mc_cb; - maccb->mlme_notify = macnet_mlme_notify; - maccb->mcps_notify = macnet_mcps_notify; + maccb = &priv->md_cb.mc_cb; + maccb->notify = macnet_notify; + maccb->rxframe = macnet_rxframe; /* Bind the callback structure */ -- GitLab From 56c8456ff037583ce5b6ea6a3e74c22b1fb34409 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 16 May 2017 07:38:57 -0600 Subject: [PATCH 827/990] Update some comments. --- net/tcp/tcp_input.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/net/tcp/tcp_input.c b/net/tcp/tcp_input.c index d1addb0bbf..a064fb0763 100644 --- a/net/tcp/tcp_input.c +++ b/net/tcp/tcp_input.c @@ -325,11 +325,11 @@ found: conn->tcpstateflags = TCP_CLOSED; nwarn("WARNING: RESET in TCP_SYN_RCVD\n"); - /* Notify the listerner for connection of the reset event */ + /* Notify the listener for the connection of the reset event */ listener = tcp_findlistener(conn->lport); - /* We must free this TCP connection structure, this connection + /* We must free this TCP connection structure; this connection * will never be established. */ -- GitLab From b8e7d5c455abd98deb11edb7bf682353ba438f6f Mon Sep 17 00:00:00 2001 From: Lederhilger Martin Date: Tue, 16 May 2017 07:47:18 -0600 Subject: [PATCH 828/990] I had the problem that the transmit FIFO size (= actual elements in FIFO) was slowly increasing over time, and was full after a few hours. The reason was that the code hit the line "canerr("ERROR: No available mailbox\n");" in stm32_cansend, so can_xmit thinks it has sent the packet to the hardware, but actually has not. Therefore the transmit interrupt never happens which would call can_txdone, and so the size of the FIFO size does not decrease. The reason why the code actually hit the mentioned line above, is because stm32can_txready uses a different (incomplete) condition than stm32can_send to determine if the mailbox can be used for sending, and thus can_xmit forwards the packet to stm32can_send. stm32can_txready considered mailboxes OK for sending if the mailbox was empty, but did not consider that mailboxes may not yet be used if the request completed bit is set - stm32can_txinterrupt has to process these mailboxes first. Note that I have also modified stm32can_txinterrupt - I removed the if condition, because the CAN controller retries to send the packet until it succeeds. Also if the condition would not evaluate to true, can_txdone would not be called and the FIFO size would not decrease also. --- arch/arm/src/stm32/stm32_can.c | 102 +++++++++++++++++++++++---------- 1 file changed, 71 insertions(+), 31 deletions(-) diff --git a/arch/arm/src/stm32/stm32_can.c b/arch/arm/src/stm32/stm32_can.c index 4497dd9766..9e23a48f36 100644 --- a/arch/arm/src/stm32/stm32_can.c +++ b/arch/arm/src/stm32/stm32_can.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/arm/src/stm32/stm32_can.c * - * Copyright (C) 2011, 2016 Gregory Nutt. All rights reserved. + * Copyright (C) 2011, 2016-2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Copyright (C) 2016 Omni Hoverboards Inc. All rights reserved. @@ -74,10 +74,6 @@ #define INAK_TIMEOUT 65535 -/* Mailboxes ****************************************************************/ - -#define CAN_ALL_MAILBOXES (CAN_TSR_TME0 | CAN_TSR_TME1 | CAN_TSR_TME2) - /* Bit timing ***************************************************************/ #define CAN_BIT_QUANTA (CONFIG_CAN_TSEG1 + CONFIG_CAN_TSEG2 + 1) @@ -172,6 +168,12 @@ static int stm32can_bittiming(FAR struct stm32_can_s *priv); static int stm32can_cellinit(FAR struct stm32_can_s *priv); static int stm32can_filterinit(FAR struct stm32_can_s *priv); +/* TX mailbox status */ + +static bool stm32can_txmb0empty(uint32_t tsr_regval); +static bool stm32can_txmb1empty(uint32_t tsr_regval); +static bool stm32can_txmb2empty(uint32_t tsr_regval); + /**************************************************************************** * Private Data ****************************************************************************/ @@ -1170,15 +1172,15 @@ static int stm32can_send(FAR struct can_dev_s *dev, /* Select one empty transmit mailbox */ regval = stm32can_getreg(priv, STM32_CAN_TSR_OFFSET); - if ((regval & CAN_TSR_TME0) != 0 && (regval & CAN_TSR_RQCP0) == 0) + if (stm32can_txmb0empty(regval)) { txmb = 0; } - else if ((regval & CAN_TSR_TME1) != 0 && (regval & CAN_TSR_RQCP1) == 0) + else if (stm32can_txmb1empty(regval)) { txmb = 1; } - else if ((regval & CAN_TSR_TME2) != 0 && (regval & CAN_TSR_RQCP2) == 0) + else if (stm32can_txmb2empty(regval)) { txmb = 2; } @@ -1321,7 +1323,8 @@ static bool stm32can_txready(FAR struct can_dev_s *dev) regval = stm32can_getreg(priv, STM32_CAN_TSR_OFFSET); caninfo("CAN%d TSR: %08x\n", priv->port, regval); - return (regval & CAN_ALL_MAILBOXES) != 0; + return stm32can_txmb0empty(regval) || stm32can_txmb1empty(regval) || + stm32can_txmb2empty(regval); } /**************************************************************************** @@ -1352,7 +1355,8 @@ static bool stm32can_txempty(FAR struct can_dev_s *dev) regval = stm32can_getreg(priv, STM32_CAN_TSR_OFFSET); caninfo("CAN%d TSR: %08x\n", priv->port, regval); - return (regval & CAN_ALL_MAILBOXES) == CAN_ALL_MAILBOXES; + return stm32can_txmb0empty(regval) && stm32can_txmb1empty(regval) && + stm32can_txmb2empty(regval); } /**************************************************************************** @@ -1553,14 +1557,9 @@ static int stm32can_txinterrupt(int irq, FAR void *context, FAR void *arg) stm32can_putreg(priv, STM32_CAN_TSR_OFFSET, CAN_TSR_RQCP0); - /* Check for errors */ - - if ((regval & CAN_TSR_TXOK0) != 0) - { - /* Tell the upper half that the tansfer is finished. */ + /* Tell the upper half that the transfer is finished. */ - (void)can_txdone(dev); - } + (void)can_txdone(dev); } /* Check for RQCP1: Request completed mailbox 1 */ @@ -1573,14 +1572,9 @@ static int stm32can_txinterrupt(int irq, FAR void *context, FAR void *arg) stm32can_putreg(priv, STM32_CAN_TSR_OFFSET, CAN_TSR_RQCP1); - /* Check for errors */ - - if ((regval & CAN_TSR_TXOK1) != 0) - { - /* Tell the upper half that the tansfer is finished. */ + /* Tell the upper half that the transfer is finished. */ - (void)can_txdone(dev); - } + (void)can_txdone(dev); } /* Check for RQCP2: Request completed mailbox 2 */ @@ -1593,14 +1587,9 @@ static int stm32can_txinterrupt(int irq, FAR void *context, FAR void *arg) stm32can_putreg(priv, STM32_CAN_TSR_OFFSET, CAN_TSR_RQCP2); - /* Check for errors */ - - if ((regval & CAN_TSR_TXOK2) != 0) - { - /* Tell the upper half that the tansfer is finished. */ + /* Tell the upper half that the transfer is finished. */ - (void)can_txdone(dev); - } + (void)can_txdone(dev); } return OK; @@ -2111,6 +2100,57 @@ static int stm32can_delstdfilter(FAR struct stm32_can_s *priv, int arg) return -ENOTTY; } +/**************************************************************************** + * Name: stm32can_txmb0empty + * + * Input Parameter: + * tsr_regval - value of CAN transmit status register + * + * Returned Value: + * Returns true if mailbox 0 is empty and can be used for sending. + * + ****************************************************************************/ + +static bool stm32can_txmb0empty(uint32_t tsr_regval) +{ + return (tsr_regval & CAN_TSR_TME0) != 0 && + (tsr_regval & CAN_TSR_RQCP0) == 0; +} + +/**************************************************************************** + * Name: stm32can_txmb1empty + * + * Input Parameter: + * tsr_regval - value of CAN transmit status register + * + * Returned Value: + * Returns true if mailbox 1 is empty and can be used for sending. + * + ****************************************************************************/ + +static bool stm32can_txmb1empty(uint32_t tsr_regval) +{ + return (tsr_regval & CAN_TSR_TME1) != 0 && + (tsr_regval & CAN_TSR_RQCP1) == 0; +} + +/**************************************************************************** + * Name: stm32can_txmb2empty + * + * Input Parameter: + * tsr_regval - value of CAN transmit status register + * + * Returned Value: + * Returns true if mailbox 2 is empty and can be used for sending. + * + ****************************************************************************/ + +static bool stm32can_txmb2empty(uint32_t tsr_regval) +{ + return (tsr_regval & CAN_TSR_TME2) != 0 && + (tsr_regval & CAN_TSR_RQCP2) == 0; +} + /**************************************************************************** * Public Functions ****************************************************************************/ -- GitLab From 5ef00f0b9192749d7fb2bb28524c40558f449f60 Mon Sep 17 00:00:00 2001 From: EunBong Song Date: Tue, 16 May 2017 08:01:05 -0600 Subject: [PATCH 829/990] drivers/bch: BCH character driver bch_ioctl() always returns -ENOTTY for DIOC_GETPRIV command. It should returns OK if DIOC_GETPRIV command succeeds. --- drivers/bch/bchdev_driver.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/drivers/bch/bchdev_driver.c b/drivers/bch/bchdev_driver.c index e74ef3f7f7..438bdfd9d0 100644 --- a/drivers/bch/bchdev_driver.c +++ b/drivers/bch/bchdev_driver.c @@ -339,12 +339,13 @@ static int bch_ioctl(FAR struct file *filep, int cmd, unsigned long arg) bchlib_semtake(bch); if (!bchr || bch->refs == MAX_OPENCNT) { - ret = -EINVAL; + ret = -EINVAL; } else { bch->refs++; *bchr = bch; + ret = OK; } bchlib_semgive(bch); -- GitLab From a6e556d31ce3932fb24ab7eab0ab1cebdd3ff7b4 Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Tue, 16 May 2017 10:56:49 -0600 Subject: [PATCH 830/990] I had to make following change to fix interrupt context syslog (INTBUFFER untested) --- drivers/syslog/syslog_write.c | 20 +++++++++++++++++--- 1 file changed, 17 insertions(+), 3 deletions(-) diff --git a/drivers/syslog/syslog_write.c b/drivers/syslog/syslog_write.c index a3100702ca..390f594237 100644 --- a/drivers/syslog/syslog_write.c +++ b/drivers/syslog/syslog_write.c @@ -40,6 +40,7 @@ #include #include +#include #include #include "syslog.h" @@ -100,8 +101,21 @@ ssize_t syslog_default_write(FAR const char *buffer, size_t buflen) ssize_t syslog_write(FAR const char *buffer, size_t buflen) { #ifdef CONFIG_SYSLOG_WRITE - return g_syslog_channel->sc_write(buffer, buflen); -#else - return syslog_default_write(buffer, buflen); + if (!up_interrupt_context() && !sched_idletask()) + { +#ifdef CONFIG_SYSLOG_INTBUFFER + /* Flush any characters that may have been added to the interrupt + * buffer. + */ + + (void)syslog_flush_intbuffer(g_syslog_channel, false); #endif + + return g_syslog_channel->sc_write(buffer, buflen); + } + else +#endif + { + return syslog_default_write(buffer, buflen); + } } -- GitLab From 6a3800f611854e61f3183c89c706c24841cc8eea Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 16 May 2017 11:03:35 -0600 Subject: [PATCH 831/990] There can be a failure in IOB allocation to some asynchronous behavior caused by the use of sem_post(). Consider this scenario: MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Task A holds an IOB.  There are no further IOBs.  The value of semcount is zero. Task B calls iob_alloc().  Since there are not IOBs, it calls sem_wait().  The v alue of semcount is now -1. Task A frees the IOB.  iob_free() adds the IOB to the free list and calls sem_post() this makes Task B ready to run and sets semcount to zero NOT 1.  There is one IOB in the free list and semcount is zero.  When Task B wakes up it would increment the sem_count back to the correct value. But an interrupt or another task runs occurs before Task B executes.  The interrupt or other tak takes the IOB off of the free list and decrements the semcount.  But since semcount is then < 0, this causes the assertion because that is an invalid state in the interrupt handler. So I think that the root cause is that there the asynchrony between incrementing the semcount. This change separates the list of IOBs: Currently there is only a free list of IOBs. The problem, I believe, is because of asynchronies due sem_post() post cause the semcount and the list content to become out of sync. This change adds a new 'committed' list: When there is a task waiting for an IOB, it will go into the committed list rather than the free list before the semaphore is posted. On the waiting side, when awakened from the semaphore wait, it will expect to find its IOB in the committed list, rather than free list. In this way, the content of the free list and the value of the semaphore count always remain in sync. --- mm/iob/Kconfig | 5 +- mm/iob/iob.h | 10 ++- mm/iob/iob_alloc.c | 138 +++++++++++++++++++++++++------------- mm/iob/iob_alloc_qentry.c | 137 ++++++++++++++++++++++++------------- mm/iob/iob_free.c | 34 ++++++++-- mm/iob/iob_free_qentry.c | 35 ++++++++-- mm/iob/iob_initialize.c | 25 ++++++- 7 files changed, 271 insertions(+), 113 deletions(-) diff --git a/mm/iob/Kconfig b/mm/iob/Kconfig index 3d603fde38..0790961a79 100644 --- a/mm/iob/Kconfig +++ b/mm/iob/Kconfig @@ -63,12 +63,15 @@ config IOB_THROTTLE config IOB_DEBUG bool "Force I/O buffer debug" default n - depends on DEBUG_FEATURES + depends on DEBUG_FEATURES && !SYSLOG_BUFFER ---help--- This option will force debug output from I/O buffer logic. This is not normally something that would want to do but is convenient if you are debugging the I/O buffer logic and do not want to get overloaded with other un-related debug output. + NOTE that this selection is not avaiable with IOBs are being used + to syslog buffering logic (CONFIG_SYSLOG_BUFFER=y)! + endif # MM_IOB endmenu # Common I/O buffer support diff --git a/mm/iob/iob.h b/mm/iob/iob.h index 5f4436980c..9f43612d71 100644 --- a/mm/iob/iob.h +++ b/mm/iob/iob.h @@ -91,10 +91,18 @@ extern FAR struct iob_s *g_iob_freelist; -/* A list of all free, unallocated I/O buffer queue containers */ +/* A list of I/O buffers that are committed for allocation */ + +extern FAR struct iob_s *g_iob_committed; #if CONFIG_IOB_NCHAINS > 0 +/* A list of all free, unallocated I/O buffer queue containers */ + extern FAR struct iob_qentry_s *g_iob_freeqlist; + +/* A list of I/O buffer queue containers that are committed for allocation */ + +extern FAR struct iob_s *g_iob_qcommitted; #endif /* Counting semaphores that tracks the number of free IOBs/qentries */ diff --git a/mm/iob/iob_alloc.c b/mm/iob/iob_alloc.c index 27de294670..9aee7ab8d4 100644 --- a/mm/iob/iob_alloc.c +++ b/mm/iob/iob_alloc.c @@ -1,7 +1,7 @@ /**************************************************************************** * mm/iob/iob_alloc.c * - * Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved. + * Copyright (C) 2014, 2016-2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -54,6 +54,47 @@ * Private Functions ****************************************************************************/ +/**************************************************************************** + * Name: iob_alloc_committed + * + * Description: + * Allocate an I/O buffer by taking the buffer at the head of the committed + * list. + * + ****************************************************************************/ + +static FAR struct iob_s *iob_alloc_committed(void) +{ + FAR struct iob_s *iob = NULL; + irqstate_t flags; + + /* We don't know what context we are called from so we use extreme measures + * to protect the committed list: We disable interrupts very briefly. + */ + + flags = enter_critical_section(); + + /* Take the I/O buffer from the head of the committed list */ + + iob = g_iob_committed; + if (iob != NULL) + { + /* Remove the I/O buffer from the committed list */ + + g_iob_committed = iob->io_flink; + + /* Put the I/O buffer in a known state */ + + iob->io_flink = NULL; /* Not in a chain */ + iob->io_len = 0; /* Length of the data in the entry */ + iob->io_offset = 0; /* Offset to the beginning of data */ + iob->io_pktlen = 0; /* Total length of the packet */ + } + + leave_critical_section(flags); + return iob; +} + /**************************************************************************** * Name: iob_allocwait * @@ -85,73 +126,76 @@ static FAR struct iob_s *iob_allocwait(bool throttled) */ flags = enter_critical_section(); - do + + /* Try to get an I/O buffer. If successful, the semaphore count will be + * decremented atomically. + */ + + iob = iob_tryalloc(throttled); + while (ret == OK && iob == NULL) { - /* Try to get an I/O buffer. If successful, the semaphore count - * will be decremented atomically. + /* If not successful, then the semaphore count was less than or equal + * to zero (meaning that there are no free buffers). We need to wait + * for an I/O buffer to be released and placed in the committed + * list. */ - iob = iob_tryalloc(throttled); - if (!iob) + ret = sem_wait(sem); + if (ret < 0) { - /* If not successful, then the semaphore count was less than or - * equal to zero (meaning that there are no free buffers). We - * need to wait for an I/O buffer to be released when the semaphore - * count will be incremented. + int errcode = get_errno(); + + /* EINTR is not an error! EINTR simply means that we were + * awakened by a signal and we should try again. + * + * REVISIT: Many end-user interfaces are required to return with + * an error if EINTR is set. Most uses of this function are in + * internal, non-user logic. But are there cases where the error + * should be returned. */ - ret = sem_wait(sem); - if (ret < 0) + if (errcode == EINTR) { - int errcode = get_errno(); - - /* EINTR is not an error! EINTR simply means that we were - * awakened by a signal and we should try again. - * - * REVISIT: Many end-user interfaces are required to return - * with an error if EINTR is set. Most uses of this function - * is in internal, non-user logic. But are there cases where - * the error should be returned. - */ + /* Force a success indication so that we will continue looping. */ - if (errcode == EINTR) - { - /* Force a success indication so that we will continue - * looping. - */ - - ret = 0; - } - else - { - /* Stop the loop and return a error */ - - DEBUGASSERT(errcode > 0); - ret = -errcode; - } + ret = 0; } else { - /* When we wake up from wait successfully, an I/O buffer was - * returned to the free list. However, if there are concurrent - * allocations from interrupt handling, then I suspect that - * there is a race condition. But no harm, we will just wait - * again in that case. + /* Stop the loop and return a error */ + + DEBUGASSERT(errcode > 0); + ret = -errcode; + } + } + else + { + /* When we wake up from wait successfully, an I/O buffer was + * freed and we hold a count for one IOB. Unless somehting + * failed, we should have an IOB waiting for us in the + * committed list. + */ + + iob = iob_alloc_committed(); + DEBUGASSERT(iob != NULL); + + if (iob == NULL) + { + /* This should not fail, but we allow for that possibility to + * handle any potential, non-obvious race condition. Perhaps + * the free IOB ended up in the g_iob_free list? * * We need release our count so that it is available to * iob_tryalloc(), perhaps allowing another thread to take our * count. In that event, iob_tryalloc() will fail above and * we will have to wait again. - * - * TODO: Consider a design modification to permit us to - * complete the allocation without losing our count. */ sem_post(sem); + iob = iob_tryalloc(throttled); } } } - while (ret == OK && iob == NULL); leave_critical_section(flags); return iob; @@ -225,7 +269,7 @@ FAR struct iob_s *iob_tryalloc(bool throttled) /* Take the I/O buffer from the head of the free list */ iob = g_iob_freelist; - if (iob) + if (iob != NULL) { /* Remove the I/O buffer from the free list and decrement the * counting semaphore(s) that tracks the number of available diff --git a/mm/iob/iob_alloc_qentry.c b/mm/iob/iob_alloc_qentry.c index a1d4044bc4..2a54358b71 100644 --- a/mm/iob/iob_alloc_qentry.c +++ b/mm/iob/iob_alloc_qentry.c @@ -55,6 +55,44 @@ * Private Functions ****************************************************************************/ +/**************************************************************************** + * Name: iob_alloc_qcommitted + * + * Description: + * Allocate an I/O buffer by taking the buffer at the head of the committed + * list. + * + ****************************************************************************/ + +FAR struct iob_qentry_s *iob_alloc_qcommitted(void) +{ + FAR struct iob_qentry_s *iobq = NULL; + irqstate_t flags; + + /* We don't know what context we are called from so we use extreme measures + * to protect the committed list: We disable interrupts very briefly. + */ + + flags = enter_critical_section(); + + /* Take the I/O buffer from the head of the committed list */ + + iobq = g_iob_qcommitted; + if (iobq != NULL) + { + /* Remove the I/O buffer from the committed list */ + + g_iob_qcommitted = iobq->io_flink; + + /* Put the I/O buffer in a known state */ + + iobq->qe_head = NULL; /* Nothing is contained */ + } + + leave_critical_section(flags); + return iobq; +} + /**************************************************************************** * Name: iob_allocwait_qentry * @@ -78,73 +116,78 @@ static FAR struct iob_qentry_s *iob_allocwait_qentry(void) */ flags = enter_critical_section(); - do + + /* Try to get an I/O buffer chain container. If successful, the semaphore + * count will bedecremented atomically. + */ + + qentry = iob_tryalloc_qentry(); + while (ret == OK && qentry == NULL) { - /* Try to get an I/O buffer chain container. If successful, the - * semaphore count will be decremented atomically. + /* If not successful, then the semaphore count was less than or equal + * to zero (meaning that there are no free buffers). We need to wait + * for an I/O buffer chain container to be released when the + * semaphore count will be incremented. */ - qentry = iob_tryalloc_qentry(); - if (!qentry) + ret = sem_wait(&g_qentry_sem); + if (ret < 0) { - /* If not successful, then the semaphore count was less than or - * equal to zero (meaning that there are no free buffers). We - * need to wait for an I/O buffer chain container to be released - * when the semaphore count will be incremented. + int errcode = get_errno(); + + /* EINTR is not an error! EINTR simply means that we were + * awakened by a signal and we should try again. + * + * REVISIT: Many end-user interfaces are required to return + * with an error if EINTR is set. Most uses of this function + * is in internal, non-user logic. But are there cases where + * the error should be returned. */ - ret = sem_wait(&g_qentry_sem); - if (ret < 0) + if (errcode == EINTR) { - int errcode = get_errno(); - - /* EINTR is not an error! EINTR simply means that we were - * awakened by a signal and we should try again. - * - * REVISIT: Many end-user interfaces are required to return - * with an error if EINTR is set. Most uses of this function - * is in internal, non-user logic. But are there cases where - * the error should be returned. + /* Force a success indication so that we will continue + * looping. */ - if (errcode == EINTR) - { - /* Force a success indication so that we will continue - * looping. - */ - - ret = 0; - } - else - { - /* Stop the loop and return a error */ - - DEBUGASSERT(errcode > 0); - ret = -errcode; - } + ret = 0; } else { - /* When we wake up from wait successfully, an I/O buffer chain - * container was returned to the free list. However, if there - * are concurrent allocations from interrupt handling, then I - * suspect that there is a race condition. But no harm, we - * will just wait again in that case. + /* Stop the loop and return a error */ + + DEBUGASSERT(errcode > 0); + ret = -errcode; + } + } + else + { + /* When we wake up from wait successfully, an I/O buffer chain container was + * freed and we hold a count for one IOB. Unless somehting + * failed, we should have an IOB waiting for us in the + * committed list. + */ + + qentry = iob_alloc_qcommitted(); + DEBUGASSERT(qentry != NULL); + + if (qentry == NULL) + { + /* This should not fail, but we allow for that possibility to + * handle any potential, non-obvious race condition. Perhaps + * the free IOB ended up in the g_iob_free list? * * We need release our count so that it is available to - * iob_tryalloc_qentry(), perhaps allowing another thread to - * take our count. In that event, iob_tryalloc_qentry() will - * fail above and we will have to wait again. - * - * TODO: Consider a design modification to permit us to - * complete the allocation without losing our count. + * iob_tryalloc(), perhaps allowing another thread to take our + * count. In that event, iob_tryalloc() will fail above and + * we will have to wait again. */ sem_post(&g_qentry_sem); + qentry = iob_tryalloc_qentry(); } } } - while (ret == OK && !qentry); leave_critical_section(flags); return qentry; diff --git a/mm/iob/iob_free.c b/mm/iob/iob_free.c index 75a01cf89b..0265e2d899 100644 --- a/mm/iob/iob_free.c +++ b/mm/iob/iob_free.c @@ -74,7 +74,7 @@ FAR struct iob_s *iob_free(FAR struct iob_s *iob) * the next entry. */ - if (next) + if (next != NULL) { /* Copy and decrement the total packet length, being careful to * do nothing too crazy. @@ -101,16 +101,36 @@ FAR struct iob_s *iob_free(FAR struct iob_s *iob) next, next->io_pktlen, next->io_len); } - /* Free the I/O buffer by adding it to the head of the free list. We don't - * know what context we are called from so we use extreme measures to - * protect the free list: We disable interrupts very briefly. + /* Free the I/O buffer by adding it to the head of the free or the + * committed list. We don't know what context we are called from so + * we use extreme measures to protect the free list: We disable + * interrupts very briefly. */ flags = enter_critical_section(); - iob->io_flink = g_iob_freelist; - g_iob_freelist = iob; - /* Signal that an IOB is available */ + /* Which list? If there is a task waiting for an IOB, then put + * the IOB on either the free list or on the committed list where + * it is reserved for that allocation (and not available to + * iob_tryalloc()). + */ + + if (g_iob_sem.semcount < 0) + { + iob->io_flink = g_iob_committed; + g_iob_committed = iob; + } + else + { + iob->io_flink = g_iob_freelist; + g_iob_freelist = iob; + } + + /* Signal that an IOB is available. If there is a thread waiting + * for an IOB, this will wake up exactly one thread. The semaphore + * count will correctly indicated that the awakened task owns an + * IOB and should find it in the committed list. + */ sem_post(&g_iob_sem); #if CONFIG_IOB_THROTTLE > 0 diff --git a/mm/iob/iob_free_qentry.c b/mm/iob/iob_free_qentry.c index 393f0ee47b..135cd3ae3a 100644 --- a/mm/iob/iob_free_qentry.c +++ b/mm/iob/iob_free_qentry.c @@ -1,7 +1,7 @@ /**************************************************************************** * mm/iob/iob_free_qentry.c * - * Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved. + * Copyright (C) 2014, 2016-2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -68,16 +68,37 @@ FAR struct iob_qentry_s *iob_free_qentry(FAR struct iob_qentry_s *iobq) FAR struct iob_qentry_s *nextq = iobq->qe_flink; irqstate_t flags; - /* Free the I/O buffer chain container by adding it to the head of the free - * list. We don't know what context we are called from so we use extreme - * measures to protect the free list: We disable interrupts very briefly. + /* Free the I/O buffer chain container by adding it to the head of the + * free or the committed list. We don't know what context we are called + * from so we use extreme measures to protect the free list: We disable + * interrupts very briefly. */ flags = enter_critical_section(); - iobq->qe_flink = g_iob_freeqlist; - g_iob_freeqlist = iobq; - /* Signal that an I/O buffer chain container is available */ + /* Which list? If there is a task waiting for an IOB, then put + * the IOB on either the free list or on the committed list where + * it is reserved for that allocation (and not available to + * iob_tryalloc()). + */ + + if (g_iob_sem.semcount < 0) + { + iobq->qe_flink = g_iob_qcommitted; + g_iob_qcommitted = iobq; + } + else + { + iobq->qe_flink = g_iob_freeqlist; + g_iob_freeqlist = iobq; + } + + /* Signal that an I/O buffer chain container is available. If there + * is a thread waiting for an I/O buffer chain container, this will + * wake up exactly one thread. The semaphore count will correctly + * indicated that the awakened task owns an I/O buffer chain container + * and should find it in the committed list. + */ sem_post(&g_qentry_sem); leave_critical_section(flags); diff --git a/mm/iob/iob_initialize.c b/mm/iob/iob_initialize.c index 1662fe4772..6c0df54454 100644 --- a/mm/iob/iob_initialize.c +++ b/mm/iob/iob_initialize.c @@ -1,7 +1,7 @@ /**************************************************************************** * mm/iob/iob_initialize.c * - * Copyright (C) 2014 Gregory Nutt. All rights reserved. + * Copyright (C) 2014, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -46,6 +46,14 @@ #include "iob.h" +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#ifndef NULL +# define NULL ((FAR void *)0) +#endif + /**************************************************************************** * Private Data ****************************************************************************/ @@ -65,10 +73,18 @@ static struct iob_qentry_s g_iob_qpool[CONFIG_IOB_NCHAINS]; FAR struct iob_s *g_iob_freelist; -/* A list of all free, unallocated I/O buffer queue containers */ +/* A list of I/O buffers that are committed for allocation */ + +FAR struct iob_s *g_iob_committed; #if CONFIG_IOB_NCHAINS > 0 +/* A list of all free, unallocated I/O buffer queue containers */ + FAR struct iob_qentry_s *g_iob_freeqlist; + +/* A list of I/O buffer queue containers that are committed for allocation */ + +extern FAR struct iob_s *g_iob_qcommitted; #endif /* Counting semaphores that tracks the number of free IOBs/qentries */ @@ -114,8 +130,9 @@ void iob_initialize(void) g_iob_freelist = iob; } - sem_init(&g_iob_sem, 0, CONFIG_IOB_NBUFFERS); + g_iob_committed = NULL; + sem_init(&g_iob_sem, 0, CONFIG_IOB_NBUFFERS); #if CONFIG_IOB_THROTTLE > 0 sem_init(&g_throttle_sem, 0, CONFIG_IOB_NBUFFERS - CONFIG_IOB_THROTTLE); #endif @@ -133,6 +150,8 @@ void iob_initialize(void) g_iob_freeqlist = iobq; } + g_iob_qcommitted = NULL; + sem_init(&g_qentry_sem, 0, CONFIG_IOB_NCHAINS); #endif initialized = true; -- GitLab From 5ce2ece1344d2fff24a3c303571a34800d689d11 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 16 May 2017 12:26:23 -0600 Subject: [PATCH 832/990] syslog: Add header file inclusion to eliminate a warning; mm/iob: private function needs static storage class. --- drivers/syslog/syslog_write.c | 2 ++ mm/iob/iob_alloc_qentry.c | 2 +- 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/drivers/syslog/syslog_write.c b/drivers/syslog/syslog_write.c index 390f594237..02efde09ff 100644 --- a/drivers/syslog/syslog_write.c +++ b/drivers/syslog/syslog_write.c @@ -40,6 +40,8 @@ #include #include + +#include #include #include diff --git a/mm/iob/iob_alloc_qentry.c b/mm/iob/iob_alloc_qentry.c index 2a54358b71..4caba97a9c 100644 --- a/mm/iob/iob_alloc_qentry.c +++ b/mm/iob/iob_alloc_qentry.c @@ -64,7 +64,7 @@ * ****************************************************************************/ -FAR struct iob_qentry_s *iob_alloc_qcommitted(void) +static FAR struct iob_qentry_s *iob_alloc_qcommitted(void) { FAR struct iob_qentry_s *iobq = NULL; irqstate_t flags; -- GitLab From 9169ff6a15fe65ba4af134b470dbf89220274c19 Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Wed, 17 May 2017 06:50:46 -0600 Subject: [PATCH 833/990] stm32_serial: fix freezing serial port. Serial interrupt enable/disable functions do not disable interrupts and can freeze device when serial interrupt is received while execution is at those functions. Trivially triggered with two or more threads write to regular syslog stream and to emergency stream. In this case, freeze happens because of mismatch of priv->ie (TXEIE == 0) and actually enabled interrupts in USART registers (TXEIE == 1), which leads to unhandled TXE interrupt and causes interrupt storm for USART. --- arch/arm/src/stm32/stm32_serial.c | 29 +++++++++++++++++++---- arch/arm/src/stm32f0/stm32f0_serial.c | 32 +++++++++++++++++++++---- arch/arm/src/stm32f7/stm32_serial.c | 30 +++++++++++++++++++---- arch/arm/src/stm32l4/stm32l4_serial.c | 34 ++++++++++++++++++++++----- 4 files changed, 106 insertions(+), 19 deletions(-) diff --git a/arch/arm/src/stm32/stm32_serial.c b/arch/arm/src/stm32/stm32_serial.c index 77c07ea68e..7aa362c38f 100644 --- a/arch/arm/src/stm32/stm32_serial.c +++ b/arch/arm/src/stm32/stm32_serial.c @@ -1050,10 +1050,10 @@ static inline void up_serialout(struct up_dev_s *priv, int offset, uint32_t valu } /**************************************************************************** - * Name: up_restoreusartint + * Name: up_setusartint ****************************************************************************/ -static void up_restoreusartint(struct up_dev_s *priv, uint16_t ie) +static inline void up_setusartint(struct up_dev_s *priv, uint16_t ie) { uint32_t cr; @@ -1074,12 +1074,31 @@ static void up_restoreusartint(struct up_dev_s *priv, uint16_t ie) up_serialout(priv, STM32_USART_CR3_OFFSET, cr); } +/**************************************************************************** + * Name: up_restoreusartint + ****************************************************************************/ + +static void up_restoreusartint(struct up_dev_s *priv, uint16_t ie) +{ + irqstate_t flags; + + flags = enter_critical_section(); + + up_setusartint(priv, ie); + + leave_critical_section(flags); +} + /**************************************************************************** * Name: up_disableusartint ****************************************************************************/ -static inline void up_disableusartint(struct up_dev_s *priv, uint16_t *ie) +static void up_disableusartint(struct up_dev_s *priv, uint16_t *ie) { + irqstate_t flags; + + flags = enter_critical_section(); + if (ie) { uint32_t cr1; @@ -1116,7 +1135,9 @@ static inline void up_disableusartint(struct up_dev_s *priv, uint16_t *ie) /* Disable all interrupts */ - up_restoreusartint(priv, 0); + up_setusartint(priv, 0); + + leave_critical_section(flags); } /**************************************************************************** diff --git a/arch/arm/src/stm32f0/stm32f0_serial.c b/arch/arm/src/stm32f0/stm32f0_serial.c index f0975fad2c..788967c231 100644 --- a/arch/arm/src/stm32f0/stm32f0_serial.c +++ b/arch/arm/src/stm32f0/stm32f0_serial.c @@ -769,10 +769,10 @@ static inline void stm32f0serial_putreg(FAR struct stm32f0_serial_s *priv, } /**************************************************************************** - * Name: stm32f0serial_restoreusartint + * Name: stm32f0serial_setusartint ****************************************************************************/ -static void stm32f0serial_restoreusartint(FAR struct stm32f0_serial_s *priv, +static void stm32f0serial_setusartint(FAR struct stm32f0_serial_s *priv, uint16_t ie) { uint32_t cr; @@ -794,13 +794,33 @@ static void stm32f0serial_restoreusartint(FAR struct stm32f0_serial_s *priv, stm32f0serial_putreg(priv, STM32F0_USART_CR3_OFFSET, cr); } +/**************************************************************************** + * Name: stm32f0serial_restoreusartint + ****************************************************************************/ + +static void stm32f0serial_restoreusartint(FAR struct stm32f0_serial_s *priv, + uint16_t ie) +{ + irqstate_t flags; + + flags = enter_critical_section(); + + stm32f0serial_setusartint(priv, ie); + + leave_critical_section(flags); +} + /**************************************************************************** * Name: stm32f0serial_disableusartint ****************************************************************************/ -static inline void stm32f0serial_disableusartint(FAR struct stm32f0_serial_s *priv, - FAR uint16_t *ie) +static void stm32f0serial_disableusartint(FAR struct stm32f0_serial_s *priv, + FAR uint16_t *ie) { + irqstate_t flags; + + flags = enter_critical_section(); + if (ie) { uint32_t cr1; @@ -837,7 +857,9 @@ static inline void stm32f0serial_disableusartint(FAR struct stm32f0_serial_s *pr /* Disable all interrupts */ - stm32f0serial_restoreusartint(priv, 0); + stm32f0serial_setusartint(priv, 0); + + leave_critical_section(flags); } /**************************************************************************** diff --git a/arch/arm/src/stm32f7/stm32_serial.c b/arch/arm/src/stm32f7/stm32_serial.c index ce6e7db9a7..f400a9b379 100644 --- a/arch/arm/src/stm32f7/stm32_serial.c +++ b/arch/arm/src/stm32f7/stm32_serial.c @@ -1096,10 +1096,10 @@ static inline void up_serialout(struct up_dev_s *priv, int offset, uint32_t valu } /**************************************************************************** - * Name: up_restoreusartint + * Name: up_setusartint ****************************************************************************/ -static void up_restoreusartint(struct up_dev_s *priv, uint16_t ie) +static inline void up_setusartint(struct up_dev_s *priv, uint16_t ie) { uint32_t cr; @@ -1120,12 +1120,31 @@ static void up_restoreusartint(struct up_dev_s *priv, uint16_t ie) up_serialout(priv, STM32_USART_CR3_OFFSET, cr); } +/**************************************************************************** + * Name: up_restoreusartint + ****************************************************************************/ + +static void up_restoreusartint(struct up_dev_s *priv, uint16_t ie) +{ + irqstate_t flags; + + flags = enter_critical_section(); + + up_setusartint(priv, ie); + + leave_critical_section(flags); +} + /**************************************************************************** * Name: up_disableusartint ****************************************************************************/ -static inline void up_disableusartint(struct up_dev_s *priv, uint16_t *ie) +static void up_disableusartint(struct up_dev_s *priv, uint16_t *ie) { + irqstate_t flags; + + flags = enter_critical_section(); + if (ie) { uint32_t cr1; @@ -1162,7 +1181,9 @@ static inline void up_disableusartint(struct up_dev_s *priv, uint16_t *ie) /* Disable all interrupts */ - up_restoreusartint(priv, 0); + up_setusartint(priv, 0); + + leave_critical_section(flags); } /**************************************************************************** @@ -2868,6 +2889,7 @@ int up_putc(int ch) up_lowputc(ch); up_restoreusartint(priv, ie); + #endif return ch; } diff --git a/arch/arm/src/stm32l4/stm32l4_serial.c b/arch/arm/src/stm32l4/stm32l4_serial.c index 15b9cbd120..f1a5550212 100644 --- a/arch/arm/src/stm32l4/stm32l4_serial.c +++ b/arch/arm/src/stm32l4/stm32l4_serial.c @@ -765,11 +765,11 @@ static inline void stm32l4serial_putreg(FAR struct stm32l4_serial_s *priv, } /**************************************************************************** - * Name: stm32l4serial_restoreusartint + * Name: stm32l4serial_setusartint ****************************************************************************/ -static void stm32l4serial_restoreusartint(FAR struct stm32l4_serial_s *priv, - uint16_t ie) +static inline void stm32l4serial_setusartint(FAR struct stm32l4_serial_s *priv, + uint16_t ie) { uint32_t cr; @@ -790,13 +790,33 @@ static void stm32l4serial_restoreusartint(FAR struct stm32l4_serial_s *priv, stm32l4serial_putreg(priv, STM32L4_USART_CR3_OFFSET, cr); } +/**************************************************************************** + * Name: up_restoreusartint + ****************************************************************************/ + +static void stm32l4serial_restoreusartint(FAR struct stm32l4_serial_s *priv, + uint16_t ie) +{ + irqstate_t flags; + + flags = enter_critical_section(); + + stm32l4serial_setusartint(priv, ie); + + leave_critical_section(flags); +} + /**************************************************************************** * Name: stm32l4serial_disableusartint ****************************************************************************/ -static inline void stm32l4serial_disableusartint(FAR struct stm32l4_serial_s *priv, - FAR uint16_t *ie) +static void stm32l4serial_disableusartint(FAR struct stm32l4_serial_s *priv, + FAR uint16_t *ie) { + irqstate_t flags; + + flags = enter_critical_section(); + if (ie) { uint32_t cr1; @@ -833,7 +853,9 @@ static inline void stm32l4serial_disableusartint(FAR struct stm32l4_serial_s *pr /* Disable all interrupts */ - stm32l4serial_restoreusartint(priv, 0); + stm32l4serial_setusartint(priv, 0); + + leave_critical_section(flags); } /**************************************************************************** -- GitLab From 8896f91f5352b2b1c8e6be8c7559b13214d04582 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Wed, 17 May 2017 08:05:24 -0600 Subject: [PATCH 834/990] STM32L4: remove duplicate USART selects from Kconfig --- arch/arm/src/stm32l4/Kconfig | 14 ++------------ 1 file changed, 2 insertions(+), 12 deletions(-) diff --git a/arch/arm/src/stm32l4/Kconfig b/arch/arm/src/stm32l4/Kconfig index 76d2dae613..2721ca3871 100644 --- a/arch/arm/src/stm32l4/Kconfig +++ b/arch/arm/src/stm32l4/Kconfig @@ -1008,14 +1008,6 @@ config STM32L4_SPI3 select SPI select STM32L4_SPI -config STM32L4_USART1 - bool "USART1" - default n - depends on STM32L4_HAVE_USART1 - select ARCH_HAVE_SERIAL_TERMIOS - select USART1_SERIALDRIVER - select STM32L4_USART - config STM32L4_USART2 bool "USART2" default n @@ -1155,8 +1147,9 @@ config STM32L4_TIM8 config STM32L4_USART1 bool "USART1" default n - select USART1_SERIALDRIVER + depends on STM32L4_HAVE_USART1 select ARCH_HAVE_SERIAL_TERMIOS + select USART1_SERIALDRIVER select STM32L4_USART config STM32L4_TIM15 @@ -1306,9 +1299,6 @@ config STM32L4_SAI2PLL Set this true and provide configuration parameters in board.h to use this PLL. -config STM32L4_USART - bool - menu "Timer Configuration" if SCHED_TICKLESS -- GitLab From 2c6ea23aee8e7f2341c8ce78b30c929088eeab8d Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Wed, 17 May 2017 10:04:49 -0600 Subject: [PATCH 835/990] STM32 Ethernet: Add support for KSZ8081 PHY interrupts. --- arch/arm/src/stm32/stm32_eth.c | 50 ++++++++++++++++++++++++++++++++-- 1 file changed, 48 insertions(+), 2 deletions(-) diff --git a/arch/arm/src/stm32/stm32_eth.c b/arch/arm/src/stm32/stm32_eth.c index 2b02b5e345..1049479892 100644 --- a/arch/arm/src/stm32/stm32_eth.c +++ b/arch/arm/src/stm32/stm32_eth.c @@ -54,6 +54,7 @@ #include #include #include +#include #include #include #include @@ -189,6 +190,40 @@ # endif #endif +/* These definitions are used to enable the PHY interrupts */ + +#if defined( CONFIG_ETH0_PHY_AM79C874) +# error missing logic +#elif defined( CONFIG_ETH0_PHY_KS8721) +# error missing logic +#elif defined( CONFIG_ETH0_PHY_KSZ8041) +# error missing logic +#elif defined( CONFIG_ETH0_PHY_KSZ8051) +# error missing logic +#elif defined( CONFIG_ETH0_PHY_KSZ8061) +# error missing logic +#elif defined( CONFIG_ETH0_PHY_KSZ8081) +# define MII_INT_REG MII_KSZ8081_INT +# define MII_INT_SETEN MII_KSZ80x1_INT_LDEN | MII_KSZ80x1_INT_LUEN +# define MII_INT_CLREN 0 +#elif defined( CONFIG_ETH0_PHY_KSZ90x1) +# error missing logic +#elif defined( CONFIG_ETH0_PHY_DP83848C) +# error missing logic +#elif defined( CONFIG_ETH0_PHY_LAN8720) +# error missing logic +#elif defined( CONFIG_ETH0_PHY_LAN8740) +# error missing logic +#elif defined( CONFIG_ETH0_PHY_LAN8740A) +# error missing logic +#elif defined( CONFIG_ETH0_PHY_LAN8742A) +# error missing logic +#elif defined( CONFIG_ETH0_PHY_DM9161) +# error missing logic +#else +# error unknown PHY +#endif + #ifdef CONFIG_STM32_ETH_PTP # warning "CONFIG_STM32_ETH_PTP is not yet supported" #endif @@ -2889,8 +2924,19 @@ static int stm32_ioctl(struct net_driver_s *dev, int cmd, unsigned long arg) #if defined(CONFIG_NETDEV_PHY_IOCTL) && defined(CONFIG_ARCH_PHY_INTERRUPT) static int stm32_phyintenable(struct stm32_ethmac_s *priv) { -#warning Missing logic - return -ENOSYS; + uint16_t phyval; + int ret; + + ret = stm32_phyread(CONFIG_STM32_PHYADDR, MII_INT_REG, &phyval); + if (ret == OK) + { + /* Enable link up/down interrupts */ + + ret = stm32_phywrite(CONFIG_STM32_PHYADDR, MII_INT_REG, + (phyval & ~MII_INT_CLREN) | MII_INT_SETEN); + } + + return 0; } #endif -- GitLab From aac3a3df8e0a49e1be77513cceb6125465bdc6ac Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 17 May 2017 10:07:09 -0600 Subject: [PATCH 836/990] STM32 Ethernet: Should not stm32_phyintenable() return a failure if it could not enable the PHY interrupt? --- arch/arm/src/stm32/stm32_eth.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/arch/arm/src/stm32/stm32_eth.c b/arch/arm/src/stm32/stm32_eth.c index 1049479892..db7c5a6e81 100644 --- a/arch/arm/src/stm32/stm32_eth.c +++ b/arch/arm/src/stm32/stm32_eth.c @@ -2936,7 +2936,7 @@ static int stm32_phyintenable(struct stm32_ethmac_s *priv) (phyval & ~MII_INT_CLREN) | MII_INT_SETEN); } - return 0; + return ret; } #endif -- GitLab From 989195cec81b40704d8911e7122f0d062ea32746 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 17 May 2017 15:36:57 -0600 Subject: [PATCH 837/990] STM32 Ethernet: Last patch breaks every board that does not use the KSZ80801 PHY. --- arch/arm/src/stm32/stm32_eth.c | 62 ++++++++++++++++++---------------- 1 file changed, 32 insertions(+), 30 deletions(-) diff --git a/arch/arm/src/stm32/stm32_eth.c b/arch/arm/src/stm32/stm32_eth.c index db7c5a6e81..77493cd880 100644 --- a/arch/arm/src/stm32/stm32_eth.c +++ b/arch/arm/src/stm32/stm32_eth.c @@ -192,36 +192,38 @@ /* These definitions are used to enable the PHY interrupts */ -#if defined( CONFIG_ETH0_PHY_AM79C874) -# error missing logic -#elif defined( CONFIG_ETH0_PHY_KS8721) -# error missing logic -#elif defined( CONFIG_ETH0_PHY_KSZ8041) -# error missing logic -#elif defined( CONFIG_ETH0_PHY_KSZ8051) -# error missing logic -#elif defined( CONFIG_ETH0_PHY_KSZ8061) -# error missing logic -#elif defined( CONFIG_ETH0_PHY_KSZ8081) -# define MII_INT_REG MII_KSZ8081_INT -# define MII_INT_SETEN MII_KSZ80x1_INT_LDEN | MII_KSZ80x1_INT_LUEN -# define MII_INT_CLREN 0 -#elif defined( CONFIG_ETH0_PHY_KSZ90x1) -# error missing logic -#elif defined( CONFIG_ETH0_PHY_DP83848C) -# error missing logic -#elif defined( CONFIG_ETH0_PHY_LAN8720) -# error missing logic -#elif defined( CONFIG_ETH0_PHY_LAN8740) -# error missing logic -#elif defined( CONFIG_ETH0_PHY_LAN8740A) -# error missing logic -#elif defined( CONFIG_ETH0_PHY_LAN8742A) -# error missing logic -#elif defined( CONFIG_ETH0_PHY_DM9161) -# error missing logic -#else -# error unknown PHY +#if defined(CONFIG_NETDEV_PHY_IOCTL) && defined(CONFIG_ARCH_PHY_INTERRUPT) +# if defined( CONFIG_ETH0_PHY_AM79C874) +# error missing logic +# elif defined( CONFIG_ETH0_PHY_KS8721) +# error missing logic +# elif defined( CONFIG_ETH0_PHY_KSZ8041) +# error missing logic +# elif defined( CONFIG_ETH0_PHY_KSZ8051) +# error missing logic +# elif defined( CONFIG_ETH0_PHY_KSZ8061) +# error missing logic +# elif defined( CONFIG_ETH0_PHY_KSZ8081) +# define MII_INT_REG MII_KSZ8081_INT +# define MII_INT_SETEN MII_KSZ80x1_INT_LDEN | MII_KSZ80x1_INT_LUEN +# define MII_INT_CLREN 0 +# elif defined( CONFIG_ETH0_PHY_KSZ90x1) +# error missing logic +# elif defined( CONFIG_ETH0_PHY_DP83848C) +# error missing logic +# elif defined( CONFIG_ETH0_PHY_LAN8720) +# error missing logic +# elif defined( CONFIG_ETH0_PHY_LAN8740) +# error missing logic +# elif defined( CONFIG_ETH0_PHY_LAN8740A) +# error missing logic +# elif defined( CONFIG_ETH0_PHY_LAN8742A) +# error missing logic +# elif defined( CONFIG_ETH0_PHY_DM9161) +# error missing logic +# else +# error unknown PHY +# endif #endif #ifdef CONFIG_STM32_ETH_PTP -- GitLab From f10e10e465fcf876907712cd104830886fc9ea3d Mon Sep 17 00:00:00 2001 From: Masayuki Ishikawa Date: Thu, 18 May 2017 12:57:29 +0900 Subject: [PATCH 838/990] IOBs: Fix build break Signed-off-by: Masayuki Ishikawa --- mm/iob/iob_alloc_qentry.c | 2 +- mm/iob/iob_initialize.c | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/mm/iob/iob_alloc_qentry.c b/mm/iob/iob_alloc_qentry.c index 4caba97a9c..10bc1123d7 100644 --- a/mm/iob/iob_alloc_qentry.c +++ b/mm/iob/iob_alloc_qentry.c @@ -82,7 +82,7 @@ static FAR struct iob_qentry_s *iob_alloc_qcommitted(void) { /* Remove the I/O buffer from the committed list */ - g_iob_qcommitted = iobq->io_flink; + g_iob_qcommitted = iobq->qe_flink; /* Put the I/O buffer in a known state */ diff --git a/mm/iob/iob_initialize.c b/mm/iob/iob_initialize.c index 6c0df54454..adab03c228 100644 --- a/mm/iob/iob_initialize.c +++ b/mm/iob/iob_initialize.c @@ -84,7 +84,7 @@ FAR struct iob_qentry_s *g_iob_freeqlist; /* A list of I/O buffer queue containers that are committed for allocation */ -extern FAR struct iob_s *g_iob_qcommitted; +FAR struct iob_s *g_iob_qcommitted; #endif /* Counting semaphores that tracks the number of free IOBs/qentries */ -- GitLab From 980b17d951281886f43e5d83e99975c9eedeffa6 Mon Sep 17 00:00:00 2001 From: Masayuki Ishikawa Date: Thu, 18 May 2017 09:22:33 +0900 Subject: [PATCH 839/990] IPv6: Fix net_ipv6_pref2mask() Signed-off-by: Masayuki Ishikawa --- net/utils/net_ipv6_pref2mask.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/net/utils/net_ipv6_pref2mask.c b/net/utils/net_ipv6_pref2mask.c index 6b04635413..7155f5856b 100644 --- a/net/utils/net_ipv6_pref2mask.c +++ b/net/utils/net_ipv6_pref2mask.c @@ -82,7 +82,7 @@ void net_ipv6_pref2mask(uint8_t preflen, net_ipv6addr_t mask) * 1..6 7..2 3..8 9..4 5..0 1..6 7..2 3..8 */ - for (i = 0; i < 7; i++) + for (i = 0; i < 8; i++) { /* bit = {0, 16, 32, 48, 64, 80, 96, 112} */ @@ -92,7 +92,7 @@ void net_ipv6_pref2mask(uint8_t preflen, net_ipv6addr_t mask) { /* Eg. preflen = 38, bit = {0, 16, 32} */ - if (preflen > (bit + 16)) + if (preflen >= (bit + 16)) { /* Eg. preflen = 38, bit = {0, 16} */ @@ -102,7 +102,7 @@ void net_ipv6_pref2mask(uint8_t preflen, net_ipv6addr_t mask) { /* Eg. preflen = 38, bit = {32} * bit - preflen = 6 - * make = 0xffff << (16-6) + * mask = 0xffff << (16-6) * = 0xfc00 */ @@ -111,7 +111,7 @@ void net_ipv6_pref2mask(uint8_t preflen, net_ipv6addr_t mask) } else { - /* Eg. preflen=38, bit= {48, 64, 80, 112} */ + /* Eg. preflen=38, bit= {48, 64, 80, 96, 112} */ mask[i] = 0x0000; } -- GitLab From 49a70079c17bb962acc243aa7681726e430c7b73 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 18 May 2017 09:50:54 -0600 Subject: [PATCH 840/990] Update TODO list --- TODO | 41 +++++++++++++++++++++++++++++++++++++++-- 1 file changed, 39 insertions(+), 2 deletions(-) diff --git a/TODO b/TODO index 25e5127b8d..3d3755b679 100644 --- a/TODO +++ b/TODO @@ -1,4 +1,4 @@ -NuttX TODO List (Last updated April 15, 2017) +NuttX TODO List (Last updated May 18, 2017) ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ This file summarizes known NuttX bugs, limitations, inconsistencies with @@ -25,7 +25,7 @@ nuttx/: (12) Libraries (libc/, libm/) (10) File system/Generic drivers (fs/, drivers/) (9) Graphics Subsystem (graphics/) - (2) Build system / Toolchains + (3) Build system / Toolchains (3) Linux/Cywgin simulation (arch/sim) (4) ARM (arch/arm/) @@ -1825,6 +1825,43 @@ o Build system Priority: Low, since I am not aware of anyone using the Windows Native build. But, of course, very high if you want to use it. + Title: CONTROL-C CAN BREAK DEPENDENCIES + Description: If you control C out of a make, then there are things that can go + wrong. For one, you can break the dependencies in this scenario: + + - The build in a given directory begins with all of the compilations. + On terminal, this the long phase with CC: on each line. As each + .o file is created, it is timestamped with the current time. + + - The dependencies on each .o are such that the C file will be re- + compile if the .o file is OLDER that the corresponding .a archive + file. + + - The compilation phase is followed by a single, relatively short + AR: phase that adds each of the file to the .a archive file. As + each file is added to archive, the timestamp of the of archive is + updated to the current time. After the first .o file has been + added, then archive file will have a newly timestamp than any of + the newly compiled .o file. + + - If the user aborts with control-C during this AR: phase, then we + are left with: (1) not all of the files have bee added to the + archive, and (2) the archive file has a newer timestamp than any + of the .o file. + + So when the make is restarted after a control, the dependencies will + see that the .a archive file has the newer time stamp and those .o + file will never be added to the archive until the directory is cleaned + or some other dependency changes. + Status Open + Priority: Medium-High. It is a rare event that control-C happens at just the + point in time. However, when it does occur the resulting code may + have binary incompatiblies in the code taken from the out-of-sync + archives and cost a lot of debug time before you realize the issue. + + A work-around is to do 'make clean' if you ever decide to control-C + out of a make. + o Other drivers (drivers/) ^^^^^^^^^^^^^^^^^^^^^^^^ -- GitLab From 0260891c96d2e23b78d23e329381671e0730442a Mon Sep 17 00:00:00 2001 From: Masayuki Ishikawa Date: Thu, 18 May 2017 16:30:12 +0900 Subject: [PATCH 841/990] net procfs: Fix buffer corruption and refactor netdev_statistics.c Signed-off-by: Masayuki Ishikawa --- net/procfs/netdev_statistics.c | 50 ++++++++++++++++++++++------------ net/procfs/procfs.h | 2 +- 2 files changed, 34 insertions(+), 18 deletions(-) diff --git a/net/procfs/netdev_statistics.c b/net/procfs/netdev_statistics.c index 109f4cdca2..cd7dde177d 100644 --- a/net/procfs/netdev_statistics.c +++ b/net/procfs/netdev_statistics.c @@ -61,9 +61,12 @@ ****************************************************************************/ static int netprocfs_linklayer(FAR struct netprocfs_file_s *netfile); -static int netprocfs_ipaddresses(FAR struct netprocfs_file_s *netfile); +#ifdef CONFIG_NET_IPv4 +static int netprocfs_inet4addresses(FAR struct netprocfs_file_s *netfile); +#endif #ifdef CONFIG_NET_IPv6 -static int netprocfs_dripaddress(FAR struct netprocfs_file_s *netfile); +static int netprocfs_inet6address(FAR struct netprocfs_file_s *netfile); +static int netprocfs_inet6draddress(FAR struct netprocfs_file_s *netfile); #endif #ifdef CONFIG_NETDEV_STATISTICS static int netprocfs_rxstatistics_header(FAR struct netprocfs_file_s *netfile); @@ -83,10 +86,13 @@ static int netprocfs_errors(FAR struct netprocfs_file_s *netfile); static const linegen_t g_linegen[] = { - netprocfs_linklayer, - netprocfs_ipaddresses + netprocfs_linklayer +#ifdef CONFIG_NET_IPv4 + , netprocfs_inet4addresses +#endif #ifdef CONFIG_NET_IPv6 - , netprocfs_dripaddress + , netprocfs_inet6address + , netprocfs_inet6draddress #endif #ifdef CONFIG_NETDEV_STATISTICS , netprocfs_rxstatistics_header, @@ -255,25 +261,19 @@ static int netprocfs_linklayer(FAR struct netprocfs_file_s *netfile) } /**************************************************************************** - * Name: netprocfs_ipaddresses + * Name: netprocfs_inet4addresses ****************************************************************************/ -static int netprocfs_ipaddresses(FAR struct netprocfs_file_s *netfile) +#ifdef CONFIG_NET_IPv4 +static int netprocfs_inet4addresses(FAR struct netprocfs_file_s *netfile) { FAR struct net_driver_s *dev; -#ifdef CONFIG_NET_IPv4 struct in_addr addr; -#endif -#ifdef CONFIG_NET_IPv6 - char addrstr[INET6_ADDRSTRLEN]; - uint8_t preflen; -#endif int len = 0; DEBUGASSERT(netfile != NULL && netfile->dev != NULL); dev = netfile->dev; -#ifdef CONFIG_NET_IPv4 /* Show the IPv4 address */ addr.s_addr = dev->d_ipaddr; @@ -291,9 +291,25 @@ static int netprocfs_ipaddresses(FAR struct netprocfs_file_s *netfile) addr.s_addr = dev->d_netmask; len += snprintf(&netfile->line[len], NET_LINELEN - len, "Mask:%s\n\n", inet_ntoa(addr)); + return len; +} #endif +/**************************************************************************** + * Name: netprocfs_inet6address + ****************************************************************************/ + #ifdef CONFIG_NET_IPv6 +static int netprocfs_inet6address(FAR struct netprocfs_file_s *netfile) +{ + FAR struct net_driver_s *dev; + char addrstr[INET6_ADDRSTRLEN]; + uint8_t preflen; + int len = 0; + + DEBUGASSERT(netfile != NULL && netfile->dev != NULL); + dev = netfile->dev; + /* Convert the 128 network mask to a human friendly prefix length */ preflen = net_ipv6_mask2pref(dev->d_ipv6netmask); @@ -305,17 +321,17 @@ static int netprocfs_ipaddresses(FAR struct netprocfs_file_s *netfile) len += snprintf(&netfile->line[len], NET_LINELEN - len, "\tinet6 addr:%s/%d\n", addrstr, preflen); } -#endif return len; } +#endif /**************************************************************************** - * Name: netprocfs_dripaddress + * Name: netprocfs_inet6draddress ****************************************************************************/ #ifdef CONFIG_NET_IPv6 -static int netprocfs_dripaddress(FAR struct netprocfs_file_s *netfile) +static int netprocfs_inet6draddress(FAR struct netprocfs_file_s *netfile) { FAR struct net_driver_s *dev; char addrstr[INET6_ADDRSTRLEN]; diff --git a/net/procfs/procfs.h b/net/procfs/procfs.h index 889f350725..9b0d7bfd49 100644 --- a/net/procfs/procfs.h +++ b/net/procfs/procfs.h @@ -54,7 +54,7 @@ * to handle the longest line generated by this logic. */ -#define NET_LINELEN 64 +#define NET_LINELEN 80 /**************************************************************************** * Public Type Definitions -- GitLab From b1008477ac921bdb56edab43e07141d79674216c Mon Sep 17 00:00:00 2001 From: Yasuhiro Osaki Date: Thu, 11 Sep 2014 09:44:09 +0900 Subject: [PATCH 842/990] binfmt: Fix .dtor memory allocation Jira: PDFW15IS-265 Coverity-ID: 11053 Signed-off-by: Masayuki Ishikawa --- binfmt/libelf/libelf_dtors.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/binfmt/libelf/libelf_dtors.c b/binfmt/libelf/libelf_dtors.c index 6d0b0cff1a..9e10f703f7 100644 --- a/binfmt/libelf/libelf_dtors.c +++ b/binfmt/libelf/libelf_dtors.c @@ -163,14 +163,14 @@ int elf_loaddtors(FAR struct elf_loadinfo_s *loadinfo) { /* Allocate memory to hold a copy of the .dtor section */ - loadinfo->ctoralloc = (binfmt_dtor_t *)kumm_malloc(dtorsize); - if (!loadinfo->ctoralloc) + loadinfo->dtoralloc = (binfmt_dtor_t *)kumm_malloc(dtorsize); + if (!loadinfo->dtoralloc) { berr("Failed to allocate memory for .dtors\n"); return -ENOMEM; } - loadinfo->dtors = (binfmt_dtor_t *)loadinfo->ctoralloc; + loadinfo->dtors = (binfmt_dtor_t *)loadinfo->dtoralloc; /* Read the section header table into memory */ -- GitLab From 819a6e049efcc50e8b209b5f889a22bf9c7ce069 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Fri, 19 May 2017 07:15:27 -0600 Subject: [PATCH 843/990] stm32_i2c: make private symbols static --- arch/arm/src/stm32/stm32f30xxx_i2c.c | 8 +- arch/arm/src/stm32f0/stm32f0_i2c.c | 8 +- arch/arm/src/stm32f7/stm32_i2c.c | 252 +++++++++++++-------------- arch/arm/src/stm32l4/stm32l4_i2c.c | 12 +- 4 files changed, 140 insertions(+), 140 deletions(-) diff --git a/arch/arm/src/stm32/stm32f30xxx_i2c.c b/arch/arm/src/stm32/stm32f30xxx_i2c.c index 539305194d..e779c040ed 100644 --- a/arch/arm/src/stm32/stm32f30xxx_i2c.c +++ b/arch/arm/src/stm32/stm32f30xxx_i2c.c @@ -318,7 +318,7 @@ static int stm32_i2c_reset(FAR struct i2c_master_s *dev); /* Device Structures, Instantiation */ -const struct i2c_ops_s stm32_i2c_ops = +static const struct i2c_ops_s stm32_i2c_ops = { .transfer = stm32_i2c_transfer #ifdef CONFIG_I2C_RESET @@ -340,7 +340,7 @@ static const struct stm32_i2c_config_s stm32_i2c1_config = #endif }; -struct stm32_i2c_priv_s stm32_i2c1_priv = +static struct stm32_i2c_priv_s stm32_i2c1_priv = { .ops = &stm32_i2c_ops, .config = &stm32_i2c1_config, @@ -369,7 +369,7 @@ static const struct stm32_i2c_config_s stm32_i2c2_config = #endif }; -struct stm32_i2c_priv_s stm32_i2c2_priv = +static struct stm32_i2c_priv_s stm32_i2c2_priv = { .ops = &stm32_i2c_ops, .config = &stm32_i2c2_config, @@ -398,7 +398,7 @@ static const struct stm32_i2c_config_s stm32_i2c3_config = #endif }; -struct stm32_i2c_priv_s stm32_i2c3_priv = +static struct stm32_i2c_priv_s stm32_i2c3_priv = { .ops = &stm32_i2c_ops, .config = &stm32_i2c3_config, diff --git a/arch/arm/src/stm32f0/stm32f0_i2c.c b/arch/arm/src/stm32f0/stm32f0_i2c.c index c782754fc3..69c5a1b53f 100644 --- a/arch/arm/src/stm32f0/stm32f0_i2c.c +++ b/arch/arm/src/stm32f0/stm32f0_i2c.c @@ -307,7 +307,7 @@ static int stm32f0_i2c_reset(FAR struct i2c_master_s *dev); /* Device Structures, Instantiation */ -const struct i2c_ops_s stm32f0_i2c_ops = +static const struct i2c_ops_s stm32f0_i2c_ops = { .transfer = stm32f0_i2c_transfer #ifdef CONFIG_I2C_RESET @@ -328,7 +328,7 @@ static const struct stm32f0_i2c_config_s stm32f0_i2c1_config = #endif }; -struct stm32f0_i2c_priv_s stm32f0_i2c1_priv = +static struct stm32f0_i2c_priv_s stm32f0_i2c1_priv = { .ops = &stm32f0_i2c_ops, .config = &stm32f0_i2c1_config, @@ -356,7 +356,7 @@ static const struct stm32f0_i2c_config_s stm32f0_i2c2_config = #endif }; -struct stm32f0_i2c_priv_s stm32f0_i2c2_priv = +static struct stm32f0_i2c_priv_s stm32f0_i2c2_priv = { .ops = &stm32f0_i2c_ops, .config = &stm32f0_i2c2_config, @@ -384,7 +384,7 @@ static const struct stm32f0_i2c_config_s stm32f0_i2c3_config = #endif }; -struct stm32f0_i2c_priv_s stm32f0_i2c3_priv = +static struct stm32f0_i2c_priv_s stm32f0_i2c3_priv = { .ops = &stm32f0_i2c_ops, .config = &stm32f0_i2c3_config, diff --git a/arch/arm/src/stm32f7/stm32_i2c.c b/arch/arm/src/stm32f7/stm32_i2c.c index 38c1f08268..c9ae571094 100644 --- a/arch/arm/src/stm32f7/stm32_i2c.c +++ b/arch/arm/src/stm32f7/stm32_i2c.c @@ -290,7 +290,7 @@ #if !defined(CONFIG_STM32F7_I2CTIMEOSEC) && !defined(CONFIG_STM32F7_I2CTIMEOMS) # define CONFIG_STM32F7_I2CTIMEOSEC 0 # define CONFIG_STM32F7_I2CTIMEOMS 500 /* Default is 500 milliseconds */ -# warning "Using Defualt 500 Ms Timeout" +# warning "Using Default 500 Ms Timeout" #elif !defined(CONFIG_STM32F7_I2CTIMEOSEC) # define CONFIG_STM32F7_I2CTIMEOSEC 0 /* User provided milliseconds */ #elif !defined(CONFIG_STM32F7_I2CTIMEOMS) @@ -445,7 +445,7 @@ struct stm32_i2c_priv_s struct stm32_i2c_inst_s { - struct i2c_ops_s *ops; /* Standard I2C operations */ + const struct i2c_ops_s *ops; /* Standard I2C operations */ struct stm32_i2c_priv_s *priv; /* Common driver private data structure */ }; @@ -495,7 +495,7 @@ static int stm32_i2c_process(FAR struct i2c_master_s *dev, FAR struct i2c_msg_s static int stm32_i2c_transfer(FAR struct i2c_master_s *dev, FAR struct i2c_msg_s *msgs, int count); #ifdef CONFIG_I2C_RESET -int stm32_i2c_reset(FAR struct i2c_master_s * dev); +static int stm32_i2c_reset(FAR struct i2c_master_s * dev); #endif /************************************************************************************ @@ -516,7 +516,7 @@ static const struct stm32_i2c_config_s stm32_i2c1_config = #endif }; -struct stm32_i2c_priv_s stm32_i2c1_priv = +static struct stm32_i2c_priv_s stm32_i2c1_priv = { .config = &stm32_i2c1_config, .refs = 0, @@ -545,7 +545,7 @@ static const struct stm32_i2c_config_s stm32_i2c2_config = #endif }; -struct stm32_i2c_priv_s stm32_i2c2_priv = +static struct stm32_i2c_priv_s stm32_i2c2_priv = { .config = &stm32_i2c2_config, .refs = 0, @@ -574,7 +574,7 @@ static const struct stm32_i2c_config_s stm32_i2c3_config = #endif }; -struct stm32_i2c_priv_s stm32_i2c3_priv = +static struct stm32_i2c_priv_s stm32_i2c3_priv = { .config = &stm32_i2c3_config, .refs = 0, @@ -603,7 +603,7 @@ static const struct stm32_i2c_config_s stm32_i2c4_config = #endif }; -struct stm32_i2c_priv_s stm32_i2c4_priv = +static struct stm32_i2c_priv_s stm32_i2c4_priv = { .config = &stm32_i2c4_config, .refs = 0, @@ -620,7 +620,7 @@ struct stm32_i2c_priv_s stm32_i2c4_priv = /* Device Structures, Instantiation */ -struct i2c_ops_s stm32_i2c_ops = +static const struct i2c_ops_s stm32_i2c_ops = { .transfer = stm32_i2c_transfer #ifdef CONFIG_I2C_RESET @@ -2485,6 +2485,124 @@ static int stm32_i2c_transfer(FAR struct i2c_master_s *dev, FAR struct i2c_msg_s return stm32_i2c_process(dev, msgs, count); } +/************************************************************************************ + * Name: stm32_i2c_reset + * + * Description: + * Reset an I2C bus + * + ************************************************************************************/ + +#ifdef CONFIG_I2C_RESET +static int stm32_i2c_reset(FAR struct i2c_master_s * dev) +{ + struct stm32_i2c_priv_s * priv; + unsigned int clock_count; + unsigned int stretch_count; + uint32_t scl_gpio; + uint32_t sda_gpio; + int ret = ERROR; + + ASSERT(dev); + + /* Get I2C private structure */ + + priv = ((struct stm32_i2c_inst_s *)dev)->priv; + + /* Our caller must own a ref */ + + ASSERT(priv->refs > 0); + + /* Lock out other clients */ + + stm32_i2c_sem_wait(dev); + + /* De-init the port */ + + stm32_i2c_deinit(priv); + + /* Use GPIO configuration to un-wedge the bus */ + + scl_gpio = MKI2C_OUTPUT(priv->config->scl_pin); + sda_gpio = MKI2C_OUTPUT(priv->config->sda_pin); + + /* Let SDA go high */ + + stm32_gpiowrite(sda_gpio, 1); + + /* Clock the bus until any slaves currently driving it let it go. */ + + clock_count = 0; + while (!stm32_gpioread(sda_gpio)) + { + /* Give up if we have tried too hard */ + + if (clock_count++ > 10) + { + goto out; + } + + /* Sniff to make sure that clock stretching has finished. + * + * If the bus never relaxes, the reset has failed. + */ + + stretch_count = 0; + while (!stm32_gpioread(scl_gpio)) + { + /* Give up if we have tried too hard */ + + if (stretch_count++ > 10) + { + goto out; + } + + up_udelay(10); + } + + /* Drive SCL low */ + + stm32_gpiowrite(scl_gpio, 0); + up_udelay(10); + + /* Drive SCL high again */ + + stm32_gpiowrite(scl_gpio, 1); + up_udelay(10); + } + + /* Generate a start followed by a stop to reset slave + * state machines. + */ + + stm32_gpiowrite(sda_gpio, 0); + up_udelay(10); + stm32_gpiowrite(scl_gpio, 0); + up_udelay(10); + stm32_gpiowrite(scl_gpio, 1); + up_udelay(10); + stm32_gpiowrite(sda_gpio, 1); + up_udelay(10); + + /* Revert the GPIO configuration. */ + + stm32_unconfiggpio(sda_gpio); + stm32_unconfiggpio(scl_gpio); + + /* Re-init the port */ + + stm32_i2c_init(priv); + ret = OK; + +out: + + /* Release the port for re-use by other clients */ + + stm32_i2c_sem_post(dev); + return ret; +} +#endif /* CONFIG_I2C_RESET */ + /************************************************************************************ * Public Functions ************************************************************************************/ @@ -2608,122 +2726,4 @@ int stm32_i2cbus_uninitialize(FAR struct i2c_master_s * dev) return OK; } -/************************************************************************************ - * Name: stm32_i2c_reset - * - * Description: - * Reset an I2C bus - * - ************************************************************************************/ - -#ifdef CONFIG_I2C_RESET -int stm32_i2c_reset(FAR struct i2c_master_s * dev) -{ - struct stm32_i2c_priv_s * priv; - unsigned int clock_count; - unsigned int stretch_count; - uint32_t scl_gpio; - uint32_t sda_gpio; - int ret = ERROR; - - ASSERT(dev); - - /* Get I2C private structure */ - - priv = ((struct stm32_i2c_inst_s *)dev)->priv; - - /* Our caller must own a ref */ - - ASSERT(priv->refs > 0); - - /* Lock out other clients */ - - stm32_i2c_sem_wait(dev); - - /* De-init the port */ - - stm32_i2c_deinit(priv); - - /* Use GPIO configuration to un-wedge the bus */ - - scl_gpio = MKI2C_OUTPUT(priv->config->scl_pin); - sda_gpio = MKI2C_OUTPUT(priv->config->sda_pin); - - /* Let SDA go high */ - - stm32_gpiowrite(sda_gpio, 1); - - /* Clock the bus until any slaves currently driving it let it go. */ - - clock_count = 0; - while (!stm32_gpioread(sda_gpio)) - { - /* Give up if we have tried too hard */ - - if (clock_count++ > 10) - { - goto out; - } - - /* Sniff to make sure that clock stretching has finished. - * - * If the bus never relaxes, the reset has failed. - */ - - stretch_count = 0; - while (!stm32_gpioread(scl_gpio)) - { - /* Give up if we have tried too hard */ - - if (stretch_count++ > 10) - { - goto out; - } - - up_udelay(10); - } - - /* Drive SCL low */ - - stm32_gpiowrite(scl_gpio, 0); - up_udelay(10); - - /* Drive SCL high again */ - - stm32_gpiowrite(scl_gpio, 1); - up_udelay(10); - } - - /* Generate a start followed by a stop to reset slave - * state machines. - */ - - stm32_gpiowrite(sda_gpio, 0); - up_udelay(10); - stm32_gpiowrite(scl_gpio, 0); - up_udelay(10); - stm32_gpiowrite(scl_gpio, 1); - up_udelay(10); - stm32_gpiowrite(sda_gpio, 1); - up_udelay(10); - - /* Revert the GPIO configuration. */ - - stm32_unconfiggpio(sda_gpio); - stm32_unconfiggpio(scl_gpio); - - /* Re-init the port */ - - stm32_i2c_init(priv); - ret = OK; - -out: - - /* Release the port for re-use by other clients */ - - stm32_i2c_sem_post(dev); - return ret; -} -#endif /* CONFIG_I2C_RESET */ - #endif /* CONFIG_STM32F7_I2C1 || CONFIG_STM32F7_I2C2 || CONFIG_STM32F7_I2C3 */ diff --git a/arch/arm/src/stm32l4/stm32l4_i2c.c b/arch/arm/src/stm32l4/stm32l4_i2c.c index 18da3a2d26..892cde5f69 100644 --- a/arch/arm/src/stm32l4/stm32l4_i2c.c +++ b/arch/arm/src/stm32l4/stm32l4_i2c.c @@ -307,7 +307,7 @@ static int stm32l4_i2c_reset(FAR struct i2c_master_s *dev); /* Device Structures, Instantiation */ -const struct i2c_ops_s stm32l4_i2c_ops = +static const struct i2c_ops_s stm32l4_i2c_ops = { .transfer = stm32l4_i2c_transfer #ifdef CONFIG_I2C_RESET @@ -329,7 +329,7 @@ static const struct stm32l4_i2c_config_s stm32l4_i2c1_config = #endif }; -struct stm32l4_i2c_priv_s stm32l4_i2c1_priv = +static struct stm32l4_i2c_priv_s stm32l4_i2c1_priv = { .ops = &stm32l4_i2c_ops, .config = &stm32l4_i2c1_config, @@ -358,7 +358,7 @@ static const struct stm32l4_i2c_config_s stm32l4_i2c2_config = #endif }; -struct stm32l4_i2c_priv_s stm32l4_i2c2_priv = +static struct stm32l4_i2c_priv_s stm32l4_i2c2_priv = { .ops = &stm32l4_i2c_ops, .config = &stm32l4_i2c2_config, @@ -387,7 +387,7 @@ static const struct stm32l4_i2c_config_s stm32l4_i2c3_config = #endif }; -struct stm32l4_i2c_priv_s stm32l4_i2c3_priv = +static struct stm32l4_i2c_priv_s stm32l4_i2c3_priv = { .ops = &stm32l4_i2c_ops, .config = &stm32l4_i2c3_config, @@ -416,7 +416,7 @@ static const struct stm32l4_i2c_config_s stm32l4_i2c4_config = #endif }; -struct stm32l4_i2c_priv_s stm32l4_i2c4_priv = +static struct stm32l4_i2c_priv_s stm32l4_i2c4_priv = { .ops = &stm32l4_i2c_ops, .config = &stm32l4_i2c4_config, @@ -1831,7 +1831,7 @@ static int stm32l4_i2c_transfer(FAR struct i2c_master_s *dev, FAR struct i2c_msg * dev - Device-specific state data * * Returned Value: - * Zero (OK) on success; a negated errno value on failure. + * Zero (OK) on success; negative value on failure. * ************************************************************************************/ -- GitLab From c9dc1d928d009df6018d3956c309660a44ae94b7 Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Fri, 19 May 2017 10:04:57 -0600 Subject: [PATCH 844/990] network IOCTL commands: The only place in net/netdev/netdev_ioctl.c where the interface state should change is for SIOCSIFFLAGS. the other ones .. SIOCSIFADDR, SIOSLIFADDR, SIODIFADDR .. should not change the link state. --- net/netdev/netdev_ioctl.c | 5 ----- 1 file changed, 5 deletions(-) diff --git a/net/netdev/netdev_ioctl.c b/net/netdev/netdev_ioctl.c index dae8064645..3978819d21 100644 --- a/net/netdev/netdev_ioctl.c +++ b/net/netdev/netdev_ioctl.c @@ -506,9 +506,7 @@ static int netdev_ifr_ioctl(FAR struct socket *psock, int cmd, dev = netdev_ifr_dev(req); if (dev) { - netdev_ifdown(dev); ioctl_set_ipv4addr(&dev->d_ipaddr, &req->ifr_addr); - netdev_ifup(dev); ret = OK; } } @@ -599,9 +597,7 @@ static int netdev_ifr_ioctl(FAR struct socket *psock, int cmd, { FAR struct lifreq *lreq = (FAR struct lifreq *)req; - netdev_ifdown(dev); ioctl_set_ipv6addr(dev->d_ipv6addr, &lreq->lifr_addr); - netdev_ifup(dev); ret = OK; } } @@ -830,7 +826,6 @@ static int netdev_ifr_ioctl(FAR struct socket *psock, int cmd, dev = netdev_ifr_dev(req); if (dev) { - netdev_ifdown(dev); #ifdef CONFIG_NET_IPv4 dev->d_ipaddr = 0; #endif -- GitLab From 2c00825dcf9fbf4c470a4c03d0ecb61faadf85f5 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 20 May 2017 08:50:05 -0600 Subject: [PATCH 845/990] Porting Guide: Add description of IOBs. --- Documentation/NuttxPortingGuide.html | 432 ++++++++++++++++++++++++++- mm/iob/Kconfig | 3 +- 2 files changed, 432 insertions(+), 3 deletions(-) diff --git a/Documentation/NuttxPortingGuide.html b/Documentation/NuttxPortingGuide.html index c1db0c7eeb..58bc32c041 100644 --- a/Documentation/NuttxPortingGuide.html +++ b/Documentation/NuttxPortingGuide.html @@ -12,7 +12,7 @@

          NuttX RTOS Porting Guide

          -

          Last Updated: February 7, 2017

          +

          Last Updated: May 20, 2017

          @@ -178,6 +178,14 @@ 4.11.2 LED Definitions
          4.11.3 Common LED interfaces
        + 4.12 I/O Buffer Management +
      5.0 NuttX File System
      6.0 NuttX Device Drivers @@ -4172,6 +4180,428 @@ void board_autoled_off(int led);
    +

    4.12 I/O Buffer Management

    + +NuttX supports generic I/O buffer management (IOB) logic. +This logic was originally added to support network I/O buffering, but has been generalized to meet buffering requirements by all device drivers. +At the time of this writing, IOBs are currently used not only be networking but also by logic in drivers/syslog and drivers/wireless. +This objectives of this feature are: + +
      +
    1. + Provide common I/O buffer management logic for all drivers, +
    2. +
    3. + Support I/O buffer allocation from both the tasking and interrupt level contexts. +
    4. +
    5. + Use a fixed amount of pre-allocated memory. +
    6. +
    7. + No costly, non-deterministic dynamic memory allocation. +
    8. +
    9. + When the fixed number of pre-allocated I/O buffers is exhausted, further attempts to allocate memory from tasking logic will cause the task to block and wait until a an I/O buffer to be freed. +
    10. +
    11. + Each I/O buffer should be small, but can be chained together to support buffering of larger thinks such as full size network packets. +
    12. +
    13. + Support throttling logic to prevent lower priority tasks from hogging all available I/O buffering. +
    14. +
    + +

    4.12.1 Configuration Options

    + +
    +
    CONFIG_MM_IOB +
    Enables generic I/O buffer support. This setting will build the common I/O buffer (IOB) support library. + +
    CONFIG_IOB_NBUFFERS +
    Number of pre-allocated I/O buffers. Each packet is represented by a series of small I/O buffers in a chain. This setting determines the number of preallocated I/O buffers available for packet data. + + The default value is setup for network support. The default is 8 buffers if neither TCP read-ahead or TCP write buffering is enabled (neither CONFIG_NET_TCP_WRITE_BUFFERS nor CONFIG_NET_TCP_READAHEAD), 24 if only write buffering is enabled, and 36 if both read-ahead and write buffering are enabled. + +
    CONFIG_IOB_BUFSIZE +
    Payload size of one I/O buffer. Each packet is represented by a series of small I/O buffers in a chain. This setting determines the data payload each preallocated I/O buffer. The default value is 196 bytes. + +
    CONFIG_IOB_NCHAINS +
    Number of pre-allocated I/O buffer chain heads. These tiny nodes are used as containers to support queueing of I/O buffer chains. This will limit the number of I/O transactions that can be in-flight at any give time. The default value of zero disables this features. + +
    These generic I/O buffer chain containers are not currently used by any logic in NuttX. That is because their other other specialized I/O buffer chain containers that also carry a payload of usage specific information. + + The default value is zero if nether TCP nor UDP read-ahead buffering is enabled (i.e., neither CONFIG_NET_TCP_READAHEAD && !CONFIG_NET_UDP_READAHEAD or eight if either is enabled. + +
    CONFIG_IOB_THROTTLE +
    I/O buffer throttle value. TCP write buffering and read-ahead buffer use the same pool of free I/O buffers. In order to prevent uncontrolled incoming TCP packets from hogging all of the available, pre-allocated I/O buffers, a throttling value is required. This throttle value assures that I/O buffers will be denied to the read-ahead logic before TCP writes are halted. + + The default 0 if neither TCP write buffering nor TCP reada-ahead buffering is enabled. Otherwise, the default is 8. + +
    CONFIG_IOB_DEBUG +
    Force I/O buffer debug. This option will force debug output from I/O buffer logic. This is not normally something that would want to do but is convenient if you are debugging the I/O buffer logic and do not want to get overloaded with other un-related debug output. + + NOTE that this selection is not avaiable if DEBUG features are not enabled (CONFIG_DEBUG_FEATURES) with IOBs are being used to syslog buffering logic (CONFIG_SYSLOG_BUFFER). +
    + +

    4.12.2 Throttling

    + + +An allocation throttle was added. I/O buffer allocation logic supports a throttle value originally for read-ahead buffering to prevent the read-ahead logic from consuming all available I/O buffers and blocking the write buffering logic. This throttle logic is only needed for networking only if both write buffering and read-ahead buffering are used. Of use of I/O buffering might have other motivations for throttling. + +

    4.12.3 Public Types

    + +

    + This structure epresents one I/O buffer. A packet is contained by one or more I/O buffers in a chain. The io_pktlen is only valid for the I/O buffer at the head of the chain. +

    + +
    +struct iob_s
    +{
    +  /* Singly-link list support */
    +
    +  FAR struct iob_s *io_flink;
    +
    +  /* Payload */
    +
    +#if CONFIG_IOB_BUFSIZE < 256
    +  uint8_t  io_len;      /* Length of the data in the entry */
    +  uint8_t  io_offset;   /* Data begins at this offset */
    +#else
    +  uint16_t io_len;      /* Length of the data in the entry */
    +  uint16_t io_offset;   /* Data begins at this offset */
    +#endif
    +  uint16_t io_pktlen;   /* Total length of the packet */
    +
    +  uint8_t  io_data[CONFIG_IOB_BUFSIZE];
    +};
    +
    + +

    + This container structure supports queuing of I/O buffer chains. This structure is intended only for internal use by the IOB module. +

    + +
    +#if CONFIG_IOB_NCHAINS > 0
    +struct iob_qentry_s
    +{
    +  /* Singly-link list support */
    +
    +  FAR struct iob_qentry_s *qe_flink;
    +
    +  /* Payload -- Head of the I/O buffer chain */
    +
    +  FAR struct iob_s *qe_head;
    +};
    +#endif /* CONFIG_IOB_NCHAINS > 0 */
    +
    + +

    + The I/O buffer queue head structure. +

    + +
    +#if CONFIG_IOB_NCHAINS > 0
    +struct iob_queue_s
    +{
    +  /* Head of the I/O buffer chain list */
    +
    +  FAR struct iob_qentry_s *qh_head;
    +  FAR struct iob_qentry_s *qh_tail;
    +};
    +#endif /* CONFIG_IOB_NCHAINS > 0 */
    +
    + +

    4.12.4 Public Function Prototypes

    + + + +

    4.12.4.1 iob_initialize()

    +

    Function Prototype: +

    +#include <nuttx/mm/iob.h>
    +void iob_initialize(void);
    +
    + +

    Description. + Set up the I/O buffers for normal operations. +

    + +

    4.12.4.2 iob_alloc()

    +

    Function Prototype: +

    +#include <nuttx/mm/iob.h>
    +FAR struct iob_s *iob_alloc(bool throttled);
    +
    + +

    Description. + Allocate an I/O buffer by taking the buffer at the head of the free list. +

    + +

    4.12.4.3 iob_tryalloc()

    +

    Function Prototype: +

    +#include <nuttx/mm/iob.h>
    +FAR struct iob_s *iob_tryalloc(bool throttled);
    +
    + +

    Description. + Try to allocate an I/O buffer by taking the buffer at the head of the free list without waiting for a buffer to become free. +

    + +

    4.12.4.4 iob_free()

    +

    Function Prototype: +

    +#include <nuttx/mm/iob.h>
    +FAR struct iob_s *iob_free(FAR struct iob_s *iob);
    +
    + +

    Description. + Free the I/O buffer at the head of a buffer chain returning it to the free list. The link to the next I/O buffer in the chain is return. +

    + +

    4.12.4.5 iob_free_chain()

    +

    Function Prototype: +

    +#include <nuttx/mm/iob.h>
    +void iob_free_chain(FAR struct iob_s *iob);
    +
    + +

    Description. + Free an entire buffer chain, starting at the beginning of the I/O buffer chain +

    + +

    4.12.4.6 iob_add_queue()

    +

    Function Prototype: +

    +#include <nuttx/mm/iob.h>
    +#if CONFIG_IOB_NCHAINS > 0
    +int iob_add_queue(FAR struct iob_s *iob, FAR struct iob_queue_s *iobq);
    +#endif /* CONFIG_IOB_NCHAINS > 0 */
    +
    + +

    Description. + Add one I/O buffer chain to the end of a queue. May fail due to lack of resources. +

    + +

    4.12.4.7 iob_tryadd_queue()

    +

    Function Prototype: +

    +#include <nuttx/mm/iob.h>
    +#if CONFIG_IOB_NCHAINS > 0
    +int iob_tryadd_queue(FAR struct iob_s *iob, FAR struct iob_queue_s *iobq);
    +#endif /* CONFIG_IOB_NCHAINS > 0 */
    +
    + +

    Description. + Add one I/O buffer chain to the end of a queue without waiting for resources to become free. +

    + +

    4.12.4.8 iob_remove_queue()

    +

    Function Prototype: +

    +#include <nuttx/mm/iob.h>
    +#if CONFIG_IOB_NCHAINS > 0
    +FAR struct iob_s *iob_remove_queue(FAR struct iob_queue_s *iobq);
    +#endif /* CONFIG_IOB_NCHAINS > 0 */
    +
    + +

    Description. + Remove and return one I/O buffer chain from the head of a queue. +

    + +

    Returned Value. + Returns a reference to the I/O buffer chain at the head of the queue. +

    + +

    4.12.4.9 iob_peek_queue()

    +

    Function Prototype: +

    +#include <nuttx/mm/iob.h>
    +#if CONFIG_IOB_NCHAINS > 0
    +FAR struct iob_s *iob_peek_queue(FAR struct iob_queue_s *iobq);
    +#endif
    +
    + +

    Description. + Return a reference to the I/O buffer chain at the head of a queue. This is similar to iob_remove_queue except that the I/O buffer chain is in place at the head of the queue. The I/O buffer chain may safely be modified by the caller but must be removed from the queue before it can be freed. +

    + +

    Returned Value. + Returns a reference to the I/O buffer chain at the head of the queue. +

    + +

    4.12.4.10 iob_free_queue()

    +

    Function Prototype: +

    +#include <nuttx/mm/iob.h>
    +#if CONFIG_IOB_NCHAINS > 0
    +void iob_free_queue(FAR struct iob_queue_s *qhead);
    +#endif /* CONFIG_IOB_NCHAINS > 0 */
    +
    + +

    Description. + Free an entire queue of I/O buffer chains. +

    + +

    4.12.4.11 iob_copyin()

    +

    Function Prototype: +

    +#include <nuttx/mm/iob.h>
    +int iob_copyin(FAR struct iob_s *iob, FAR const uint8_t *src,
    +               unsigned int len, unsigned int offset, bool throttled);
    +
    + +

    Description. + Copy data len bytes from a user buffer into the I/O buffer chain, starting at offset, extending the chain as necessary. +

    + +

    4.12.4.12 iob_trycopyin()

    +

    Function Prototype: +

    +#include <nuttx/mm/iob.h>
    +int iob_trycopyin(FAR struct iob_s *iob, FAR const uint8_t *src,
    +                  unsigned int len, unsigned int offset, bool throttled);
    +
    + +

    Description. + Copy data len bytes from a user buffer into the I/O buffer chain, starting at offset, extending the chain as necessary BUT without waiting if buffers are not available. +

    + +

    4.12.4.13 iob_copyout()

    +

    Function Prototype: +

    +#include <nuttx/mm/iob.h>
    +int iob_copyout(FAR uint8_t *dest, FAR const struct iob_s *iob,
    +                unsigned int len, unsigned int offset);
    +
    + +

    Description. + Copy data len bytes of data into the user buffer starting at offset in the I/O buffer, returning that actual number of bytes copied out. +

    + +

    4.12.4.14 iob_clone()

    +

    Function Prototype: +

    +#include <nuttx/mm/iob.h>
    +int iob_clone(FAR struct iob_s *iob1, FAR struct iob_s *iob2, bool throttled);
    +
    + +

    Description. + Duplicate (and pack) the data in iob1 in iob2. iob2 must be empty. +

    + +

    4.12.4.15 iob_concat()

    +

    Function Prototype: +

    +#include <nuttx/mm/iob.h>
    +void iob_concat(FAR struct iob_s *iob1, FAR struct iob_s *iob2);
    +
    + +

    Description. + Concatenate iob_s chain iob2 to iob1. +

    + +

    4.12.4.16 iob_trimhead()

    +

    Function Prototype: +

    +#include <nuttx/mm/iob.h>
    +FAR struct iob_s *iob_trimhead(FAR struct iob_s *iob, unsigned int trimlen);
    +
    + +

    Description. + Remove bytes from the beginning of an I/O chain. Emptied I/O buffers are freed and, hence, the beginning of the chain may change. +

    + +

    4.12.4.17 iob_trimhead_queue()

    +

    Function Prototype: +

    +#include <nuttx/mm/iob.h>
    +#if CONFIG_IOB_NCHAINS > 0
    +FAR struct iob_s *iob_trimhead_queue(FAR struct iob_queue_s *qhead,
    +                                     unsigned int trimlen);
    +#endif
    +
    + +

    Description. + Remove bytes from the beginning of an I/O chain at the head of the queue. Emptied I/O buffers are freed and, hence, the head of the queue may change. +

    +

    + This function is just a wrapper around iob_trimhead() that assures that the iob at the head of queue is modified with the trimming operations. +

    + +

    Returned Value. + The new iob at the head of the queue is returned. +

    + +

    4.12.4.18 iob_trimtail()

    +

    Function Prototype: +

    +#include <nuttx/mm/iob.h>
    +FAR struct iob_s *iob_trimtail(FAR struct iob_s *iob, unsigned int trimlen);
    +
    + +

    Description. + Remove bytes from the end of an I/O chain. Emptied I/O buffers are freed NULL will be returned in the special case where the entry I/O buffer chain is freed. +

    + +

    4.12.4.19 iob_pack()

    +

    Function Prototype: +

    +#include <nuttx/mm/iob.h>
    +FAR struct iob_s *iob_pack(FAR struct iob_s *iob);
    +
    + +

    Description. + Pack all data in the I/O buffer chain so that the data offset is zero and all but the final buffer in the chain are filled. Any emptied buffers at the end of the chain are freed. +

    + +

    4.12.4.20 iob_contig()

    +

    Function Prototype: +

    +#include <nuttx/mm/iob.h>
    +int iob_contig(FAR struct iob_s *iob, unsigned int len);
    +
    + +

    Description. + Ensure that there is len bytes of contiguous space at the beginning of the I/O buffer chain starting at iob. +

    + +

    4.12.4.21 iob_dump()

    +

    Function Prototype: +

    +#include <nuttx/mm/iob.h>
    +#ifdef CONFIG_DEBUG_FEATURES
    +void iob_dump(FAR const char *msg, FAR struct iob_s *iob, unsigned int len,
    +              unsigned int offset);
    +#endif
    +
    + +

    Description. + Dump the contents of a I/O buffer chain +

    +
    diff --git a/mm/iob/Kconfig b/mm/iob/Kconfig index 0790961a79..b64f90e3ce 100644 --- a/mm/iob/Kconfig +++ b/mm/iob/Kconfig @@ -51,7 +51,6 @@ config IOB_THROTTLE int "I/O buffer throttle value" default 0 if !NET_TCP_WRITE_BUFFERS || !NET_TCP_READAHEAD default 8 if NET_TCP_WRITE_BUFFERS && NET_TCP_READAHEAD - depends on NET_TCP_WRITE_BUFFERS && NET_TCP_READAHEAD ---help--- TCP write buffering and read-ahead buffer use the same pool of free I/O buffers. In order to prevent uncontrolled incoming TCP packets @@ -70,7 +69,7 @@ config IOB_DEBUG if you are debugging the I/O buffer logic and do not want to get overloaded with other un-related debug output. - NOTE that this selection is not avaiable with IOBs are being used + NOTE that this selection is not available if IOBs are being used to syslog buffering logic (CONFIG_SYSLOG_BUFFER=y)! endif # MM_IOB -- GitLab From 6b15c26e5655e24a97a5f099abe390e975a655a7 Mon Sep 17 00:00:00 2001 From: Simon Piriou Date: Sat, 20 May 2017 22:13:15 +0200 Subject: [PATCH 846/990] bcmf: add SIOCGIWSCAN ioctl support --- drivers/wireless/ieee80211/bcmf_driver.c | 287 ++++++++++++++++++- drivers/wireless/ieee80211/bcmf_driver.h | 2 + drivers/wireless/ieee80211/bcmf_ioctl.h | 4 + drivers/wireless/ieee80211/bcmf_utils.h | 8 + include/nuttx/wireless/ieee80211/ieee80211.h | 26 +- include/nuttx/wireless/wireless.h | 66 +++++ 6 files changed, 369 insertions(+), 24 deletions(-) diff --git a/drivers/wireless/ieee80211/bcmf_driver.c b/drivers/wireless/ieee80211/bcmf_driver.c index 94a2c750c5..c0024f5ca0 100644 --- a/drivers/wireless/ieee80211/bcmf_driver.c +++ b/drivers/wireless/ieee80211/bcmf_driver.c @@ -50,6 +50,8 @@ #include #include #include +#include +#include #include "bcmf_driver.h" #include "bcmf_cdc.h" @@ -65,6 +67,12 @@ #define DOT11_BSSTYPE_ANY 2 #define BCMF_SCAN_TIMEOUT_TICK (5*CLOCKS_PER_SEC) #define BCMF_AUTH_TIMEOUT_MS 10000 +#define BCMF_SCAN_RESULT_SIZE 1024 + +/* Helper to get iw_event size */ + +#define BCMF_IW_EVENT_SIZE(field) \ + (offsetof(struct iw_event, u)+sizeof(((union iwreq_data*)0)->field)) /**************************************************************************** * Private Types @@ -366,6 +374,9 @@ void bcmf_wl_auth_event_handler(FAR struct bcmf_dev_s *priv, } } +/* bcmf_wl_scan_event_handler must run at high priority else + * race condition may occur on priv->scan_result field + */ void bcmf_wl_scan_event_handler(FAR struct bcmf_dev_s *priv, struct bcmf_event_s *event, unsigned int len) { @@ -414,7 +425,7 @@ void bcmf_wl_scan_event_handler(FAR struct bcmf_dev_s *priv, goto exit_invalid_frame; } - /* wl_escan_result already cointains a wl_bss_info field */ + /* wl_escan_result structure cointains a wl_bss_info field */ len = result->buflen - sizeof(struct wl_escan_result) + sizeof(struct wl_bss_info); @@ -425,6 +436,14 @@ void bcmf_wl_scan_event_handler(FAR struct bcmf_dev_s *priv, while (len > 0 && bss_count < result->bss_count) { + struct iw_event *iwe; + unsigned int result_size; + size_t essid_len; + size_t essid_len_aligned; + uint8_t *ie_buffer; + unsigned int ie_offset; + + result_size = BCMF_SCAN_RESULT_SIZE - priv->scan_result_size; bss_info_len = bss->length; if (len < bss_info_len) @@ -435,14 +454,192 @@ void bcmf_wl_scan_event_handler(FAR struct bcmf_dev_s *priv, wlinfo("Scan result: <%.32s> %02x:%02x:%02x:%02x:%02x:%02x\n", bss->SSID, bss->BSSID.ether_addr_octet[0], bss->BSSID.ether_addr_octet[1], - bss->BSSID.ether_addr_octet[3], bss->BSSID.ether_addr_octet[3], + bss->BSSID.ether_addr_octet[2], bss->BSSID.ether_addr_octet[3], bss->BSSID.ether_addr_octet[4], bss->BSSID.ether_addr_octet[5]); + /* Append current bss_info to priv->scan_results + * FIXME protect this against race conditions + */ + + /* Copy BSSID */ + + if (result_size < BCMF_IW_EVENT_SIZE(ap_addr)) + { + goto scan_result_full; + } + + iwe = (struct iw_event*)&priv->scan_result[priv->scan_result_size]; + iwe->len = BCMF_IW_EVENT_SIZE(ap_addr); + iwe->cmd = SIOCGIWAP; + memcpy(&iwe->u.ap_addr.sa_data, bss->BSSID.ether_addr_octet, + sizeof(bss->BSSID.ether_addr_octet)); + iwe->u.ap_addr.sa_family = ARPHRD_ETHER; + + priv->scan_result_size += BCMF_IW_EVENT_SIZE(ap_addr); + result_size -= BCMF_IW_EVENT_SIZE(ap_addr); + + /* Copy ESSID */ + + essid_len = min(strlen((const char*)bss->SSID), 32); + essid_len_aligned = (essid_len + 3) & -4; + + if (result_size < BCMF_IW_EVENT_SIZE(essid)+essid_len_aligned) + { + goto scan_result_full; + } + + iwe = (struct iw_event*)&priv->scan_result[priv->scan_result_size]; + iwe->len = BCMF_IW_EVENT_SIZE(essid)+essid_len_aligned; + iwe->cmd = SIOCGIWESSID; + iwe->u.essid.flags = 0; + iwe->u.essid.length = essid_len; + + /* Special processing for iw_point, set offset in pointer field */ + + iwe->u.essid.pointer = (FAR void*)sizeof(iwe->u.essid); + memcpy(&iwe->u.essid+1, bss->SSID, essid_len); + + priv->scan_result_size += BCMF_IW_EVENT_SIZE(essid)+essid_len_aligned; + result_size -= BCMF_IW_EVENT_SIZE(essid)+essid_len_aligned; + + /* Copy link quality info */ + + if (result_size < BCMF_IW_EVENT_SIZE(qual)) + { + goto scan_result_full; + } + + iwe = (struct iw_event*)&priv->scan_result[priv->scan_result_size]; + iwe->len = BCMF_IW_EVENT_SIZE(qual); + iwe->cmd = IWEVQUAL; + iwe->u.qual.qual = bss->SNR; + wlinfo("signal %d %d %d\n", bss->RSSI, bss->phy_noise, bss->SNR); + iwe->u.qual.level = bss->RSSI; + iwe->u.qual.noise = bss->phy_noise; + iwe->u.qual.updated = IW_QUAL_DBM | IW_QUAL_ALL_UPDATED; + + priv->scan_result_size += BCMF_IW_EVENT_SIZE(qual); + result_size -= BCMF_IW_EVENT_SIZE(qual); + + /* Copy AP mode */ + + if (result_size < BCMF_IW_EVENT_SIZE(mode)) + { + goto scan_result_full; + } + + iwe = (struct iw_event*)&priv->scan_result[priv->scan_result_size]; + iwe->len = BCMF_IW_EVENT_SIZE(mode); + iwe->cmd = SIOCGIWMODE; + if (bss->capability & DOT11_CAP_ESS) + { + iwe->u.mode = IW_MODE_INFRA; + } + else if (bss->capability & DOT11_CAP_IBSS) + { + iwe->u.mode = IW_MODE_ADHOC; + } + else + { + iwe->u.mode = IW_MODE_AUTO; + } + + priv->scan_result_size += BCMF_IW_EVENT_SIZE(mode); + result_size -= BCMF_IW_EVENT_SIZE(mode); + + /* Copy AP encryption mode */ + + if (result_size < BCMF_IW_EVENT_SIZE(data)) + { + goto scan_result_full; + } + + iwe = (struct iw_event*)&priv->scan_result[priv->scan_result_size]; + iwe->len = BCMF_IW_EVENT_SIZE(data); + iwe->cmd = SIOCGIWENCODE; + iwe->u.data.flags = bss->capability & DOT11_CAP_PRIVACY ? + IW_ENCODE_ENABLED | IW_ENCODE_NOKEY : + IW_ENCODE_DISABLED; + iwe->u.data.length = 0; + iwe->u.essid.pointer = NULL; + + priv->scan_result_size += BCMF_IW_EVENT_SIZE(data); + result_size -= BCMF_IW_EVENT_SIZE(data); + + /* Copy relevant raw IE frame */ + + if (bss->ie_offset >= bss_info_len || + bss->ie_length > bss_info_len-bss->ie_offset) + { + goto process_next_bss; + } + + ie_offset = 0; + ie_buffer = (uint8_t*)bss + bss->ie_offset; + + while (1) + { + size_t ie_frame_size; + + if (bss->ie_length - ie_offset < 2) + { + /* Minimum Information element size is 2 bytes */ + break; + } + + ie_frame_size = ie_buffer[ie_offset+1] + 2; + + if (ie_frame_size > bss->ie_length - ie_offset) + { + /* Entry too big */ + break; + } + + switch (ie_buffer[ie_offset]) + { + case IEEE80211_ELEMID_RSN: + { + size_t ie_frame_size_aligned; + ie_frame_size_aligned = (ie_frame_size + 3) & -4; + wlinfo("found RSN\n"); + if (result_size < BCMF_IW_EVENT_SIZE(data) + ie_frame_size_aligned) + { + break; + } + + iwe = (struct iw_event*)&priv->scan_result[priv->scan_result_size]; + iwe->len = BCMF_IW_EVENT_SIZE(data)+ie_frame_size_aligned; + iwe->cmd = IWEVGENIE; + iwe->u.data.flags = 0; + iwe->u.data.length = ie_frame_size; + iwe->u.data.pointer = (FAR void*)sizeof(iwe->u.data); + memcpy(&iwe->u.data+1, &ie_buffer[ie_offset], ie_frame_size); + + priv->scan_result_size += BCMF_IW_EVENT_SIZE(essid)+ie_frame_size_aligned; + result_size -= BCMF_IW_EVENT_SIZE(essid)+ie_frame_size_aligned; + break; + } + default: + wlinfo("unhandled IE entry %d %d\n", ie_buffer[ie_offset], + ie_buffer[ie_offset+1]); + } + + ie_offset += ie_buffer[ie_offset+1] + 2; + } + + process_next_bss: /* Process next bss_info */ len -= bss_info_len; bss = (struct wl_bss_info *)((uint8_t *)bss + bss_info_len); bss_count += 1; + continue; + + scan_result_full: + /* Continue instead of break to log dropped AP results */ + + wlerr("No more space in scan_result buffer\n"); + continue; } wl_escan_result_processed: @@ -632,12 +829,26 @@ int bcmf_wl_start_scan(FAR struct bcmf_dev_s *priv, struct iwreq *iwr) /* Lock control_mutex semaphore */ if ((ret = sem_wait(&priv->control_mutex)) != OK) + { + goto exit_failed; + } + + /* Allocate buffer to store scan result */ + + if (priv->scan_result == NULL) { - goto exit_failed; + priv->scan_result = kmm_malloc(BCMF_SCAN_RESULT_SIZE); + if (priv->scan_result == NULL) + { + wlerr("Cannot allocate result buffer\n"); + ret = -ENOMEM; + goto exit_sem_post; + } } wlinfo("start scan\n"); + priv->scan_result_size = 0; priv->scan_status = BCMF_SCAN_RUN; out_len = sizeof(scan_params); @@ -658,8 +869,8 @@ int bcmf_wl_start_scan(FAR struct bcmf_dev_s *priv, struct iwreq *iwr) return OK; exit_sem_post: - sem_post(&priv->control_mutex); priv->scan_status = BCMF_SCAN_DISABLED; + sem_post(&priv->control_mutex); exit_failed: wlinfo("Failed\n"); return ret; @@ -667,19 +878,73 @@ exit_failed: int bcmf_wl_get_scan_results(FAR struct bcmf_dev_s *priv, struct iwreq *iwr) { - /* Not implemented yet, set len to zero */ - - iwr->u.data.length = 0; + int ret = OK; if (priv->scan_status == BCMF_SCAN_RUN) { - return -EAGAIN; + ret = -EAGAIN; + goto exit_failed; + } + + if (priv->scan_status != BCMF_SCAN_DONE) + { + ret = -EINVAL; + goto exit_failed; + } + + /* Lock control_mutex semaphore to avoid race condition */ + + if ((ret = sem_wait(&priv->control_mutex)) != OK) + { + ret = -EIO; + goto exit_failed; + } + + if (!priv->scan_result) + { + /* Result have already been requested */ + ret = OK; + iwr->u.data.length = 0; + goto exit_sem_post; } - if (priv->scan_status == BCMF_SCAN_DONE) + + if (priv->scan_result_size <= 0) { - return OK; + ret = OK; + iwr->u.data.length = 0; + goto exit_free_buffer; } - return -EINVAL; + + if (iwr->u.data.pointer == NULL) + { + ret = -EINVAL; + goto exit_free_buffer; + } + + /* Copy result to user buffer */ + + if (iwr->u.data.length > priv->scan_result_size) + { + iwr->u.data.length = priv->scan_result_size; + } + + memcpy(iwr->u.data.pointer, priv->scan_result, iwr->u.data.length); + +exit_free_buffer: + /* Free scan result buffer */ + kmm_free(priv->scan_result); + priv->scan_result = NULL; + priv->scan_result_size = 0; + +exit_sem_post: + sem_post(&priv->control_mutex); + +exit_failed: + if (ret) + { + iwr->u.data.length = 0; + } + return ret; } int bcmf_wl_set_auth_param(FAR struct bcmf_dev_s *priv, struct iwreq *iwr) diff --git a/drivers/wireless/ieee80211/bcmf_driver.h b/drivers/wireless/ieee80211/bcmf_driver.h index 937427a49b..a9d712011f 100644 --- a/drivers/wireless/ieee80211/bcmf_driver.h +++ b/drivers/wireless/ieee80211/bcmf_driver.h @@ -93,6 +93,8 @@ struct bcmf_dev_s int scan_status; /* Current scan status */ WDOG_ID scan_timeout; /* Scan timeout timer */ + FAR uint8_t *scan_result; /* Temp buffer that holds results */ + unsigned int scan_result_size; /* Current size of temp buffer */ sem_t auth_signal; /* Authentication notification signal */ int auth_status; /* Authentication status */ diff --git a/drivers/wireless/ieee80211/bcmf_ioctl.h b/drivers/wireless/ieee80211/bcmf_ioctl.h index 7c4cc235f2..48d69bf184 100644 --- a/drivers/wireless/ieee80211/bcmf_ioctl.h +++ b/drivers/wireless/ieee80211/bcmf_ioctl.h @@ -106,6 +106,10 @@ typedef struct wl_bss_info /* variable length Information Elements */ } wl_bss_info_t; +#define DOT11_CAP_ESS 0x0001 +#define DOT11_CAP_IBSS 0x0002 +#define DOT11_CAP_PRIVACY 0x0010 + typedef struct wlc_ssid { uint32_t SSID_len; diff --git a/drivers/wireless/ieee80211/bcmf_utils.h b/drivers/wireless/ieee80211/bcmf_utils.h index 32fd4ca562..ede2098c2b 100644 --- a/drivers/wireless/ieee80211/bcmf_utils.h +++ b/drivers/wireless/ieee80211/bcmf_utils.h @@ -47,6 +47,14 @@ #define container_of(ptr, type, member) \ (type *)((uint8_t *)(ptr) - offsetof(type, member)) +#ifndef min +#define min(a,b) ((a) < (b) ? (a) : (b)) +#endif + +#ifndef max +#define max(a,b) ((a) > (b) ? (a) : (b)) +#endif + /**************************************************************************** * Public Function Prototypes ****************************************************************************/ diff --git a/include/nuttx/wireless/ieee80211/ieee80211.h b/include/nuttx/wireless/ieee80211/ieee80211.h index b109487d0b..62ea4491d3 100644 --- a/include/nuttx/wireless/ieee80211/ieee80211.h +++ b/include/nuttx/wireless/ieee80211/ieee80211.h @@ -504,7 +504,7 @@ begin_packed_struct struct ieee80211_qosframe uint8_t i_addr3[IEEE80211_ADDR_LEN]; uint8_t i_seq[2]; uint8_t i_qos[2]; -} end_packet_struct; +} end_packed_struct; begin_packed_struct struct ieee80211_htframe /* 11n */ { @@ -516,7 +516,7 @@ begin_packed_struct struct ieee80211_htframe /* 11n */ uint8_t i_seq[2]; uint8_t i_qos[2]; uint8_t i_ht[4]; -} end_packet_struct; +} end_packed_struct; begin_packed_struct struct ieee80211_frame_addr4 { @@ -527,7 +527,7 @@ begin_packed_struct struct ieee80211_frame_addr4 uint8_t i_addr3[IEEE80211_ADDR_LEN]; uint8_t i_seq[2]; uint8_t i_addr4[IEEE80211_ADDR_LEN]; -} end_packet_struct; +} end_packed_struct; begin_packed_struct struct ieee80211_qosframe_addr4 { @@ -539,7 +539,7 @@ begin_packed_struct struct ieee80211_qosframe_addr4 uint8_t i_seq[2]; uint8_t i_addr4[IEEE80211_ADDR_LEN]; uint8_t i_qos[2]; -} end_packet_struct; +} end_packed_struct; begin_packed_struct struct ieee80211_htframe_addr4 /* 11n */ { @@ -552,7 +552,7 @@ begin_packed_struct struct ieee80211_htframe_addr4 /* 11n */ uint8_t i_addr4[IEEE80211_ADDR_LEN]; uint8_t i_qos[2]; uint8_t i_ht[4]; -} end_packet_struct; +} end_packed_struct; /* Control frames. */ @@ -565,7 +565,7 @@ begin_packed_struct struct ieee80211_frame_min /* FCS */ -} end_packet_struct; +} end_packed_struct; begin_packed_struct struct ieee80211_frame_rts { @@ -576,7 +576,7 @@ begin_packed_struct struct ieee80211_frame_rts /* FCS */ -} end_packet_struct; +} end_packed_struct; struct ieee80211_frame_cts { @@ -586,7 +586,7 @@ struct ieee80211_frame_cts /* FCS */ -} end_packet_struct; +} end_packed_struct; struct ieee80211_frame_ack { @@ -596,7 +596,7 @@ struct ieee80211_frame_ack /* FCS */ -} end_packet_struct; +} end_packed_struct; struct ieee80211_frame_pspoll { @@ -607,7 +607,7 @@ struct ieee80211_frame_pspoll /* FCS */ -} end_packet_struct; +} end_packed_struct; struct ieee80211_frame_cfend { /* NB: also CF-End+CF-Ack */ @@ -618,7 +618,7 @@ struct ieee80211_frame_cfend /* FCS */ -} end_packet_struct; +} end_packed_struct; /* Information elements (see Table 7-26). */ @@ -818,7 +818,7 @@ struct ieee80211_eapol_key uint8_t reserved[8]; uint8_t mic[EAPOL_KEY_MIC_LEN]; uint8_t paylen[2]; -} end_packet_struct; +} end_packed_struct; /* Pairwise Transient Key (see 8.5.1.2) */ @@ -827,7 +827,7 @@ struct ieee80211_ptk uint8_t kck[16]; /* Key Confirmation Key */ uint8_t kek[16]; /* Key Encryption Key */ uint8_t tk[32]; /* Temporal Key */ -} end_packet_struct; +} end_packed_struct; /* Key Data Encapsulation (see Table 62) */ diff --git a/include/nuttx/wireless/wireless.h b/include/nuttx/wireless/wireless.h index 5455e14d4f..144e346fca 100644 --- a/include/nuttx/wireless/wireless.h +++ b/include/nuttx/wireless/wireless.h @@ -160,6 +160,47 @@ #define WL_NNETCMDS 0x0032 /* Number of network commands */ #define WL_USERFIRST (WL_NETFIRST + WL_NNETCMDS) +/* ----------------------- WIRELESS EVENTS ----------------------- */ +/* Those are *NOT* ioctls, do not issue request on them !!! */ +/* Most events use the same identifier as ioctl requests */ + +#define IWEVTXDROP 0x8C00 /* Packet dropped to excessive retry */ +#define IWEVQUAL 0x8C01 /* Quality part of statistics (scan) */ +#define IWEVCUSTOM 0x8C02 /* Driver specific ascii string */ +#define IWEVREGISTERED 0x8C03 /* Discovered a new node (AP mode) */ +#define IWEVEXPIRED 0x8C04 /* Expired a node (AP mode) */ +#define IWEVGENIE 0x8C05 /* Generic IE (WPA, RSN, WMM, ..) + * (scan results); This includes id and + * length fields. One IWEVGENIE may + * contain more than one IE. Scan + * results may contain one or more + * IWEVGENIE events. */ +#define IWEVMICHAELMICFAILURE 0x8C06 /* Michael MIC failure + * (struct iw_michaelmicfailure) + */ +#define IWEVASSOCREQIE 0x8C07 /* IEs used in (Re)Association Request. + * The data includes id and length + * fields and may contain more than one + * IE. This event is required in + * Managed mode if the driver + * generates its own WPA/RSN IE. This + * should be sent just before + * IWEVREGISTERED event for the + * association. */ +#define IWEVASSOCRESPIE 0x8C08 /* IEs used in (Re)Association + * Response. The data includes id and + * length fields and may contain more + * than one IE. This may be sent + * between IWEVASSOCREQIE and + * IWEVREGISTERED events for the + * association. */ +#define IWEVPMKIDCAND 0x8C09 /* PMKID candidate for RSN + * pre-authentication + * (struct iw_pmkid_cand) */ + +#define IWEVFIRST 0x8C00 +#define IW_EVENT_IDX(cmd) ((cmd) - IWEVFIRST) + /* Other Common Wireless Definitions ***********************************************/ /* Maximum size of the ESSID and NICKN strings */ @@ -178,6 +219,31 @@ #define IW_MODE_MESH 7 /* Mesh (IEEE 802.11s) network */ #define IW_MODE_NFLAGS 8 +/* Statistics flags (bitmask in updated) */ + +#define IW_QUAL_QUAL_UPDATED 0x01 /* Value was updated since last read */ +#define IW_QUAL_LEVEL_UPDATED 0x02 +#define IW_QUAL_NOISE_UPDATED 0x04 +#define IW_QUAL_ALL_UPDATED 0x07 +#define IW_QUAL_DBM 0x08 /* Level + Noise are dBm */ +#define IW_QUAL_QUAL_INVALID 0x10 /* Driver doesn't provide value */ +#define IW_QUAL_LEVEL_INVALID 0x20 +#define IW_QUAL_NOISE_INVALID 0x40 +#define IW_QUAL_RCPI 0x80 /* Level + Noise are 802.11k RCPI */ +#define IW_QUAL_ALL_INVALID 0x70 + +/* Flags for encoding (along with the token) */ + +#define IW_ENCODE_INDEX 0x00FF /* Token index (if needed) */ +#define IW_ENCODE_FLAGS 0xFF00 /* Flags defined below */ +#define IW_ENCODE_MODE 0xF000 /* Modes defined below */ +#define IW_ENCODE_DISABLED 0x8000 /* Encoding disabled */ +#define IW_ENCODE_ENABLED 0x0000 /* Encoding enabled */ +#define IW_ENCODE_RESTRICTED 0x4000 /* Refuse non-encoded packets */ +#define IW_ENCODE_OPEN 0x2000 /* Accept non-encoded packets */ +#define IW_ENCODE_NOKEY 0x0800 /* Key is write only, so not present */ +#define IW_ENCODE_TEMP 0x0400 /* Temporary key */ + /* Frequency flags */ #define IW_FREQ_AUTO 0 /* Let the driver decides */ -- GitLab From d764942e9d74da8bb37daeb5daa5fa1b80c5e846 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 20 May 2017 16:36:55 -0600 Subject: [PATCH 847/990] Update README and a Document --- Documentation/NuttxPortingGuide.html | 2 +- configs/stm32f0discovery/README.txt | 17 +++++++++++++++++ 2 files changed, 18 insertions(+), 1 deletion(-) diff --git a/Documentation/NuttxPortingGuide.html b/Documentation/NuttxPortingGuide.html index 58bc32c041..ce18662b6d 100644 --- a/Documentation/NuttxPortingGuide.html +++ b/Documentation/NuttxPortingGuide.html @@ -180,7 +180,6 @@ 4.12 I/O Buffer Management
      - 4.12.1 Configuration Options
      4.12.1 Configuration Options
      4.12.2 Throttling
      4.12.3 Public Types
      @@ -4185,6 +4184,7 @@ void board_autoled_off(int led); NuttX supports generic I/O buffer management (IOB) logic. This logic was originally added to support network I/O buffering, but has been generalized to meet buffering requirements by all device drivers. At the time of this writing, IOBs are currently used not only be networking but also by logic in drivers/syslog and drivers/wireless. +NOTE that some of the wording in this section still reflects those legacy roots as a part of the networking subsystem. This objectives of this feature are:
        diff --git a/configs/stm32f0discovery/README.txt b/configs/stm32f0discovery/README.txt index e69de29bb2..243dee3376 100644 --- a/configs/stm32f0discovery/README.txt +++ b/configs/stm32f0discovery/README.txt @@ -0,0 +1,17 @@ +STATUS +====== + +05/17: The basic NSH configuration is functional and shows that there is + 3-4KB of free heap space. However, attempts to extend this have + failed. I suspect that 8KB of SRAM is insufficient to do much + with the existing NSH configuration. Perhaps some fine tuning + can improve this situation but at this point, I think this board + is only useful for the initial STM32 F0 bring-up, perhaps for + embedded solutions that do not use NSH and for general + experimentation. + + There is also support for the Nucleo boards with the STM32 F072 + and F092 MCUs. Those ports do not suffer from these problems and + seem to work well in fairly complex configurations. Apparently 8KB + is SRAM is not usable but the parts with larger 16KB and 32KB SRAMs + are better matches. -- GitLab From a332c4b9ce4119bc29493164ea3a10406c018ee7 Mon Sep 17 00:00:00 2001 From: Simon Piriou Date: Sun, 21 May 2017 16:04:24 +0200 Subject: [PATCH 848/990] bcmf: fix issue in AP scan event processing --- drivers/wireless/ieee80211/bcmf_driver.c | 68 +++++++++++++++++------- 1 file changed, 49 insertions(+), 19 deletions(-) diff --git a/drivers/wireless/ieee80211/bcmf_driver.c b/drivers/wireless/ieee80211/bcmf_driver.c index c0024f5ca0..39fdcabd94 100644 --- a/drivers/wireless/ieee80211/bcmf_driver.c +++ b/drivers/wireless/ieee80211/bcmf_driver.c @@ -442,6 +442,7 @@ void bcmf_wl_scan_event_handler(FAR struct bcmf_dev_s *priv, size_t essid_len_aligned; uint8_t *ie_buffer; unsigned int ie_offset; + unsigned int check_offset; result_size = BCMF_SCAN_RESULT_SIZE - priv->scan_result_size; bss_info_len = bss->length; @@ -452,15 +453,36 @@ void bcmf_wl_scan_event_handler(FAR struct bcmf_dev_s *priv, goto exit_invalid_frame; } + /* Append current bss_info to priv->scan_results + * FIXME protect this against race conditions + */ + + /* Check if current bss AP is not already detected */ + + check_offset = 0; + + while (priv->scan_result_size - check_offset + >= offsetof(struct iw_event, u)) + { + iwe = (struct iw_event*)&priv->scan_result[check_offset]; + + if (iwe->cmd == SIOCGIWAP) + { + if (memcmp(&iwe->u.ap_addr.sa_data, bss->BSSID.ether_addr_octet, + sizeof(bss->BSSID.ether_addr_octet)) == 0) + { + goto process_next_bss; + } + } + + check_offset += iwe->len; + } + wlinfo("Scan result: <%.32s> %02x:%02x:%02x:%02x:%02x:%02x\n", bss->SSID, bss->BSSID.ether_addr_octet[0], bss->BSSID.ether_addr_octet[1], bss->BSSID.ether_addr_octet[2], bss->BSSID.ether_addr_octet[3], bss->BSSID.ether_addr_octet[4], bss->BSSID.ether_addr_octet[5]); - /* Append current bss_info to priv->scan_results - * FIXME protect this against race conditions - */ - /* Copy BSSID */ if (result_size < BCMF_IW_EVENT_SIZE(ap_addr)) @@ -620,26 +642,27 @@ void bcmf_wl_scan_event_handler(FAR struct bcmf_dev_s *priv, break; } default: - wlinfo("unhandled IE entry %d %d\n", ie_buffer[ie_offset], - ie_buffer[ie_offset+1]); + // wlinfo("unhandled IE entry %d %d\n", ie_buffer[ie_offset], + // ie_buffer[ie_offset+1]); + break; } ie_offset += ie_buffer[ie_offset+1] + 2; } + goto process_next_bss; + + scan_result_full: + /* Continue instead of break to log dropped AP results */ + + wlerr("No more space in scan_result buffer\n"); + process_next_bss: /* Process next bss_info */ len -= bss_info_len; bss = (struct wl_bss_info *)((uint8_t *)bss + bss_info_len); bss_count += 1; - continue; - - scan_result_full: - /* Continue instead of break to log dropped AP results */ - - wlerr("No more space in scan_result buffer\n"); - continue; } wl_escan_result_processed: @@ -903,21 +926,27 @@ int bcmf_wl_get_scan_results(FAR struct bcmf_dev_s *priv, struct iwreq *iwr) if (!priv->scan_result) { /* Result have already been requested */ + ret = OK; iwr->u.data.length = 0; goto exit_sem_post; } - if (priv->scan_result_size <= 0) + if (iwr->u.data.pointer == NULL || + iwr->u.data.length < priv->scan_result_size) { - ret = OK; - iwr->u.data.length = 0; - goto exit_free_buffer; + /* Stat request, return scan_result_size */ + + ret = -E2BIG; + iwr->u.data.pointer = NULL; + iwr->u.data.length = priv->scan_result_size; + goto exit_sem_post; } - if (iwr->u.data.pointer == NULL) + if (priv->scan_result_size <= 0) { - ret = -EINVAL; + ret = OK; + iwr->u.data.length = 0; goto exit_free_buffer; } @@ -932,6 +961,7 @@ int bcmf_wl_get_scan_results(FAR struct bcmf_dev_s *priv, struct iwreq *iwr) exit_free_buffer: /* Free scan result buffer */ + kmm_free(priv->scan_result); priv->scan_result = NULL; priv->scan_result_size = 0; -- GitLab From 4ab2a3661ea57211f4ae12fe21c5de3454ba0ef2 Mon Sep 17 00:00:00 2001 From: Taras Drozdovsky Date: Sun, 21 May 2017 14:14:09 -0600 Subject: [PATCH 849/990] STM32F4: add cs43l22 audio driver and i2s driver --- arch/arm/src/stm32/Kconfig | 89 + arch/arm/src/stm32/Make.defs | 2 +- arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h | 2 +- arch/arm/src/stm32/stm32_i2s.c | 2658 +++++++++++++++++ arch/arm/src/stm32/stm32_i2s.h | 90 + configs/stm32f4discovery/include/board.h | 34 +- configs/stm32f4discovery/src/Makefile | 4 + configs/stm32f4discovery/src/stm32_bringup.c | 10 + configs/stm32f4discovery/src/stm32_cs43l22.c | 389 +++ .../stm32f4discovery/src/stm32f4discovery.h | 55 + drivers/audio/Kconfig | 61 + drivers/audio/Make.defs | 11 + drivers/audio/cs43l22.c | 1959 ++++++++++++ drivers/audio/cs43l22.h | 388 +++ drivers/audio/cs43l22_debug.c | 184 ++ include/nuttx/audio/cs43l22.h | 280 ++ 16 files changed, 6211 insertions(+), 5 deletions(-) create mode 100644 arch/arm/src/stm32/stm32_i2s.c create mode 100644 arch/arm/src/stm32/stm32_i2s.h create mode 100644 configs/stm32f4discovery/src/stm32_cs43l22.c create mode 100644 drivers/audio/cs43l22.c create mode 100644 drivers/audio/cs43l22.h create mode 100644 drivers/audio/cs43l22_debug.c create mode 100644 include/nuttx/audio/cs43l22.h diff --git a/arch/arm/src/stm32/Kconfig b/arch/arm/src/stm32/Kconfig index 647bbee4c1..ba6bdb4b79 100644 --- a/arch/arm/src/stm32/Kconfig +++ b/arch/arm/src/stm32/Kconfig @@ -1530,6 +1530,7 @@ config STM32_STM32F40XX select STM32_HAVE_TIM4 select STM32_HAVE_SPI2 select STM32_HAVE_SPI3 + select STM32_HAVE_I2S3 select STM32_HAVE_I2C2 select STM32_HAVE_I2C3 @@ -1542,6 +1543,9 @@ config STM32_STM32F401 select STM32_HAVE_TIM9 select STM32_HAVE_TIM10 select STM32_HAVE_TIM11 + select STM32_HAVE_SPI2 + select STM32_HAVE_SPI3 + select STM32_HAVE_I2S3 config STM32_STM32F410 bool @@ -1563,6 +1567,9 @@ config STM32_STM32F411 select STM32_HAVE_TIM9 select STM32_HAVE_TIM10 select STM32_HAVE_TIM11 + select STM32_HAVE_SPI2 + select STM32_HAVE_SPI3 + select STM32_HAVE_I2S3 select STM32_HAVE_SPI4 select STM32_HAVE_SPI5 @@ -1655,6 +1662,9 @@ config STM32_STM32F427 select STM32_HAVE_DAC2 select STM32_HAVE_RNG select STM32_HAVE_ETHMAC + select STM32_HAVE_SPI2 + select STM32_HAVE_SPI3 + select STM32_HAVE_I2S3 select STM32_HAVE_SPI4 select STM32_HAVE_SPI5 select STM32_HAVE_SPI6 @@ -1691,6 +1701,9 @@ config STM32_STM32F429 select STM32_HAVE_DAC2 select STM32_HAVE_RNG select STM32_HAVE_ETHMAC + select STM32_HAVE_SPI2 + select STM32_HAVE_SPI3 + select STM32_HAVE_I2S3 select STM32_HAVE_SPI4 select STM32_HAVE_SPI5 select STM32_HAVE_SPI6 @@ -2016,6 +2029,10 @@ config STM32_HAVE_SPI3 bool default n +config STM32_HAVE_I2S3 + bool + default n + config STM32_HAVE_SPI4 bool default n @@ -2353,6 +2370,13 @@ config STM32_SPI3 select SPI select STM32_SPI +config STM32_I2S3 + bool "I2S3" + default n + depends on STM32_HAVE_I2S3 + select I2S + select STM32_I2S + config STM32_SPI4 bool "SPI4" default n @@ -2610,6 +2634,11 @@ config STM32_SPI3_REMAP default n depends on STM32_STM32F10XX && STM32_SPI3 && !STM32_VALUELINE +config STM32_I2S3_REMAP + bool "I2S3 Alternate Pin Mapping" + default n + depends on STM32_STM32F10XX && STM32_I2S3 && !STM32_VALUELINE + choice prompt "TIM1 Alternate Pin Mappings" depends on STM32_STM32F10XX && STM32_TIM1 @@ -6270,6 +6299,66 @@ config STM32_SPI_DMA endmenu +menu "I2S Configuration" + depends on STM32_I2S3 + +config STM32_I2S_MCK + bool "I2S_MCK" + default n + ---help--- + TBD. + +config STM32_I2S_MAXINFLIGHT + int "I2S queue size" + default 16 + ---help--- + This is the total number of transfers, both RX and TX, that can be + enqueue before the caller is required to wait. This setting + determines the number certain queue data structures that will be + pre-allocated. + +comment "I2S3 Configuration" + +config STM32_I2S3_DATALEN + int "Data width (bits)" + default 16 + ---help--- + Data width in bits. This is a default value and may be change + via the I2S interface + +#if STM32_I2S +config STM32_I2S3_RX + bool "Enable I2C receiver" + default n + ---help--- + Enable I2S receipt logic + +config STM32_I2S3_TX + bool "Enable I2C transmitter" + default n + ---help--- + Enable I2S transmission logic + +config STM32_I2S_DMADEBUG + bool "I2S DMA transfer debug" + depends on DEBUG_DMA + default n + ---help--- + Enable special debug instrumentation analyze I2S DMA data transfers. + This logic is as non-invasive as possible: It samples DMA + registers at key points in the data transfer and then dumps all of + the registers at the end of the transfer. + +config STM32_I2S_REGDEBUG + bool "SSC Register level debug" + depends on DEBUG + default n + ---help--- + Output detailed register-level SSC device debug information. + Very invasive! Requires also DEBUG. + +endmenu # I2S Configuration + menu "I2C Configuration" depends on STM32_I2C diff --git a/arch/arm/src/stm32/Make.defs b/arch/arm/src/stm32/Make.defs index 3429ba88a4..07e31f7329 100644 --- a/arch/arm/src/stm32/Make.defs +++ b/arch/arm/src/stm32/Make.defs @@ -101,7 +101,7 @@ CHIP_ASRCS = CHIP_CSRCS = stm32_allocateheap.c stm32_start.c stm32_rcc.c stm32_lse.c CHIP_CSRCS += stm32_lsi.c stm32_gpio.c stm32_exti_gpio.c stm32_flash.c CHIP_CSRCS += stm32_irq.c stm32_dma.c stm32_lowputc.c -CHIP_CSRCS += stm32_serial.c stm32_spi.c stm32_sdio.c stm32_tim.c +CHIP_CSRCS += stm32_serial.c stm32_spi.c stm32_i2s.c stm32_sdio.c stm32_tim.c CHIP_CSRCS += stm32_waste.c stm32_ccm.c stm32_uid.c stm32_capture.c ifeq ($(CONFIG_TIMER),y) diff --git a/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h b/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h index d44c664edb..1f7b5944ea 100644 --- a/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h +++ b/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h @@ -615,7 +615,7 @@ #endif #define GPIO_SPI3_MISO_1 (GPIO_ALT|GPIO_AF6|GPIO_SPEED_50MHz|GPIO_PORTB|GPIO_PIN4) -#define GPIO_SPI3_MISO_2 (GPIO_ALT|GPIO_AF6|GPIO_SPEED_50MHz|GPIO_PORTC|GPIO_PIN11) +#define GPIO_SPI3_MISO_2 (GPIO_ALT|GPIO_AF6|GPIO_SPEED_50MHz|GPIO_PORTC|GPIO_PIN7) #define GPIO_SPI3_MOSI_1 (GPIO_ALT|GPIO_AF6|GPIO_SPEED_50MHz|GPIO_PORTB|GPIO_PIN5) #define GPIO_SPI3_MOSI_2 (GPIO_ALT|GPIO_AF6|GPIO_SPEED_50MHz|GPIO_PORTC|GPIO_PIN12) #define GPIO_SPI3_NSS_1 (GPIO_ALT|GPIO_AF6|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN15) diff --git a/arch/arm/src/stm32/stm32_i2s.c b/arch/arm/src/stm32/stm32_i2s.c new file mode 100644 index 0000000000..0f246f5763 --- /dev/null +++ b/arch/arm/src/stm32/stm32_i2s.c @@ -0,0 +1,2658 @@ +/**************************************************************************** + * arm/arm/src/stm32/stm32_i2s.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Taras Drozdovskiy + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * The external functions, stm32_spi1/2/3select and stm32_spi1/2/3status + * must be provided by board-specific logic. They are implementations of + * the select and status methods of the SPI interface defined by struct + * spi_ops_s (see include/nuttx/spi/spi.h). All other methods (including + * up_spiinitialize()) are provided by common STM32 logic. To use this + * common SPI logic on your board: + * + * 1. Provide logic in stm32_boardinitialize() to configure I2S chip select + * pins. + * 2. Provide stm32_i2s2/3select() and stm32_i2s2/3status() functions in your + * board-specific logic. These functions will perform chip selection and + * status operations using GPIOs in the way your board is configured. + * 3. Add a calls to up_spiinitialize() in your low level application + * initialization logic + * 4. The handle returned by stm32_i2sdev_initialize() may then be used to + * bind the I2S driver to higher level logic + * + ****************************************************c***********************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include + +#include +#include +#include +#include +#include +#include + +#include "up_internal.h" +#include "up_arch.h" + +#if defined(CONFIG_STM32_I2S2) || defined(CONFIG_STM32_I2S3) + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +#ifndef CONFIG_SCHED_WORKQUEUE +# error Work queue support is required (CONFIG_SCHED_WORKQUEUE) +#endif + +#ifndef CONFIG_AUDIO +# error CONFIG_AUDIO required by this driver +#endif + +#ifndef CONFIG_STM32_I2S_MAXINFLIGHT +# define CONFIG_STM32_I2S_MAXINFLIGHT 16 +#endif + +/* Assume no RX/TX support until we learn better */ + +#undef I2S_HAVE_RX +#undef I2S_HAVE_TX + +/* Check for I2S RX support */ + +# if defined(CONFIG_STM32_I2S3_RX) +# define I2S_HAVE_RX 1 + +# ifdef CONFIG_STM32_I2S_MCK +# define I2S_HAVE_MCK 1 +# endif + +# endif + +/* Check for I2S3 TX support */ + +# if defined(CONFIG_STM32_I2S3_TX) +# define I2S_HAVE_TX 1 + +# ifdef CONFIG_STM32_I2S_MCK +# define I2S_HAVE_MCK 1 +# endif + +# endif + +/* Configuration ********************************************************************/ +/* I2S interrupts */ + +#ifdef CONFIG_STM32_SPI_INTERRUPTS +# error "Interrupt driven I2S not yet supported" +#endif + +/* Can't have both interrupt driven SPI and SPI DMA */ + +#if defined(CONFIG_STM32_SPI_INTERRUPTS) && defined(CONFIG_STM32_SPI_DMA) +# error "Cannot enable both interrupt mode and DMA mode for SPI" +#endif + +/* SPI DMA priority */ + +#ifdef CONFIG_STM32_SPI_DMA + +# if defined(CONFIG_SPI_DMAPRIO) +# define SPI_DMA_PRIO CONFIG_SPI_DMAPRIO +# elif defined(CONFIG_STM32_STM32F10XX) || defined(CONFIG_STM32_STM32L15XX) +# define SPI_DMA_PRIO DMA_CCR_PRIMED +# elif defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX) +# define SPI_DMA_PRIO DMA_SCR_PRIMED +# else +# error "Unknown STM32 DMA" +# endif + +# if defined(CONFIG_STM32_STM32F10XX) || defined(CONFIG_STM32_STM32L15XX) +# if (SPI_DMA_PRIO & ~DMA_CCR_PL_MASK) != 0 +# error "Illegal value for CONFIG_SPI_DMAPRIO" +# endif +# elif defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX) +# if (SPI_DMA_PRIO & ~DMA_SCR_PL_MASK) != 0 +# error "Illegal value for CONFIG_SPI_DMAPRIO" +# endif +# else +# error "Unknown STM32 DMA" +# endif + +#endif + +/* DMA channel configuration */ + +#if defined(CONFIG_STM32_STM32F10XX) || defined(CONFIG_STM32_STM32F30XX) || \ + defined(CONFIG_STM32_STM32L15XX) +# define SPI_RXDMA16_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_16BITS|DMA_CCR_PSIZE_16BITS|DMA_CCR_MINC ) +# define SPI_RXDMA8_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS |DMA_CCR_MINC ) +# define SPI_RXDMA16NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_16BITS ) +# define SPI_RXDMA8NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS ) +# define SPI_TXDMA16_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_16BITS|DMA_CCR_PSIZE_16BITS|DMA_CCR_MINC|DMA_CCR_DIR) +# define SPI_TXDMA8_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS |DMA_CCR_MINC|DMA_CCR_DIR) +# define SPI_TXDMA16NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_16BITS |DMA_CCR_DIR) +# define SPI_TXDMA8NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS |DMA_CCR_DIR) +#elif defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX) +# define SPI_RXDMA16_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_16BITS|DMA_SCR_PSIZE_16BITS|DMA_SCR_MINC|DMA_SCR_DIR_P2M) +# define SPI_RXDMA8_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_8BITS |DMA_SCR_PSIZE_8BITS |DMA_SCR_MINC|DMA_SCR_DIR_P2M) +# define SPI_RXDMA16NULL_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_8BITS |DMA_SCR_PSIZE_16BITS |DMA_SCR_DIR_P2M) +# define SPI_RXDMA8NULL_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_8BITS |DMA_SCR_PSIZE_8BITS |DMA_SCR_DIR_P2M) +# define SPI_TXDMA16_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_16BITS|DMA_SCR_PSIZE_16BITS|DMA_SCR_MINC|DMA_SCR_DIR_M2P) +# define SPI_TXDMA8_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_8BITS |DMA_SCR_PSIZE_8BITS |DMA_SCR_MINC|DMA_SCR_DIR_M2P) +# define SPI_TXDMA16NULL_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_8BITS |DMA_SCR_PSIZE_16BITS |DMA_SCR_DIR_M2P) +# define SPI_TXDMA8NULL_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_8BITS |DMA_SCR_PSIZE_8BITS |DMA_SCR_DIR_M2P) +#else +# error "Unknown STM32 DMA" +#endif + +/* Debug *******************************************************************/ +/* Check if SSC debug is enabled (non-standard.. no support in + * include/debug.h + */ + +#ifndef CONFIG_DEBUG_I2S_INFO +# undef CONFIG_STM32_I2S_DMADEBUG +# undef CONFIG_STM32_I2S_REGDEBUG +# undef CONFIG_STM32_I2S_QDEBUG +# undef CONFIG_STM32_I2S_DUMPBUFFERS +#endif + +/* The I2S can handle most any bit width from 8 to 32. However, the DMA + * logic here is constrained to byte, half-word, and word sizes. + */ + +#ifndef CONFIG_STM32_I2S3_DATALEN +# define CONFIG_STM32_I2S3_DATALEN 16 +#endif + +#if CONFIG_STM32_I2S3_DATALEN == 8 +# define STM32_I2S3_DATAMASK 0 +#elif CONFIG_STM32_I2S3_DATALEN == 16 +# define STM32_I2S3_DATAMASK 1 +#elif CONFIG_STM32_I2S3_DATALEN < 8 || CONFIG_STM32_I2S3_DATALEN > 16 +# error Invalid value for CONFIG_STM32_I2S3_DATALEN +#else +# error Valid but supported value for CONFIG_STM32_I2S3_DATALEN +#endif + +/* Check if we need to build RX and/or TX support */ + +#if defined(I2S_HAVE_RX) || defined(I2S_HAVE_TX) + +#ifndef CONFIG_DEBUG_DMA +# undef CONFIG_STM32_I2S_DMADEBUG +#endif + +#define DMA_INITIAL 0 +#define DMA_AFTER_SETUP 1 +#define DMA_AFTER_START 2 +#define DMA_CALLBACK 3 +#define DMA_TIMEOUT 3 +#define DMA_END_TRANSFER 4 +#define DMA_NSAMPLES 5 + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/* I2S buffer container */ + +struct stm32_buffer_s +{ + struct stm32_buffer_s *flink; /* Supports a singly linked list */ + i2s_callback_t callback; /* Function to call when the transfer completes */ + uint32_t timeout; /* The timeout value to use with DMA transfers */ + void *arg; /* The argument to be returned with the callback */ + struct ap_buffer_s *apb; /* The audio buffer */ + int result; /* The result of the transfer */ +}; + +/* This structure describes the state of one receiver or transmitter transport */ + +struct stm32_transport_s +{ + DMA_HANDLE dma; /* I2S DMA handle */ + WDOG_ID dog; /* Watchdog that handles DMA timeouts */ + sq_queue_t pend; /* A queue of pending transfers */ + sq_queue_t act; /* A queue of active transfers */ + sq_queue_t done; /* A queue of completed transfers */ + struct work_s work; /* Supports worker thread operations */ + +#ifdef CONFIG_STM32_I2S_DMADEBUG + struct stm32_dmaregs_s dmaregs[DMA_NSAMPLES]; +#endif +}; + +/* The state of the one I2S peripheral */ + +struct stm32_i2s_s +{ + struct i2s_dev_s dev; /* Externally visible I2S interface */ + uintptr_t base; /* I2S controller register base address */ + sem_t exclsem; /* Assures mutually exclusive acess to I2S */ + uint8_t datalen; /* Data width (8 or 16) */ +#ifdef CONFIG_DEBUG_FEATURES + uint8_t align; /* Log2 of data width (0 or 1) */ +#endif + uint8_t rxenab:1; /* True: RX transfers enabled */ + uint8_t txenab:1; /* True: TX transfers enabled */ + uint8_t i2sno:6; /* I2S controller number (0 or 1) */ +#ifdef I2S_HAVE_MCK + uint32_t samplerate; /* Data sample rate (determines only MCK divider) */ +#endif + uint32_t rxccr; /* DMA control register for RX transfers */ + uint32_t txccr; /* DMA control register for TX transfers */ +#ifdef I2S_HAVE_RX + struct stm32_transport_s rx; /* RX transport state */ +#endif +#ifdef I2S_HAVE_TX + struct stm32_transport_s tx; /* TX transport state */ +#endif + + /* Pre-allocated pool of buffer containers */ + + sem_t bufsem; /* Buffer wait semaphore */ + struct stm32_buffer_s *freelist; /* A list a free buffer containers */ + struct stm32_buffer_s containers[CONFIG_STM32_I2S_MAXINFLIGHT]; + + /* Debug stuff */ + +#ifdef CONFIG_STM32_I2S_REGDEBUG + bool wr; /* Last was a write */ + uint32_t regaddr; /* Last address */ + uint16_t regval; /* Last value */ + int count; /* Number of times */ +#endif /* CONFIG_STM32_I2S_REGDEBUG */ +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* Register helpers */ + +#ifdef CONFIG_STM32_I2S_REGDEBUG +static bool i2s_checkreg(struct stm32_i2s_s *priv, bool wr, uint16_t regval, + uint32_t regaddr); +#else +# define i2s_checkreg(priv,wr,regval,regaddr) (false) +#endif + +static inline uint16_t i2s_getreg(struct stm32_i2s_s *priv, uint8_t offset); +static inline void i2s_putreg(struct stm32_i2s_s *priv, uint8_t offset, + uint16_t regval); + +#if defined(CONFIG_DEBUG_I2S_INFO) +static void i2s_dump_regs(struct stm32_i2s_s *priv, const char *msg); +#else +# define i2s_dump_regs(s,m) +#endif + +#ifdef CONFIG_STM32_I2S_DUMPBUFFERS +# define i2s_init_buffer(b,s) memset(b, 0x55, s); +# define i2s_dump_buffer(m,b,s) lib_dumpbuffer(m,b,s) +#else +# define i2s_init_buffer(b,s) +# define i2s_dump_buffer(m,b,s) +#endif + +/* Semaphore helpers */ + +static void i2s_exclsem_take(struct stm32_i2s_s *priv); +#define i2s_exclsem_give(priv) sem_post(&priv->exclsem) + +static void i2s_bufsem_take(struct stm32_i2s_s *priv); +#define i2s_bufsem_give(priv) sem_post(&priv->bufsem) + +/* Buffer container helpers */ + +static struct stm32_buffer_s * + i2s_buf_allocate(struct stm32_i2s_s *priv); +static void i2s_buf_free(struct stm32_i2s_s *priv, + struct stm32_buffer_s *bfcontainer); +static void i2s_buf_initialize(struct stm32_i2s_s *priv); + +/* DMA support */ + +#ifdef CONFIG_STM32_I2S_DMADEBUG +static void i2s_dma_sampleinit(struct stm32_i2s_s *priv, + struct stm32_transport_s *xpt); +#endif + +#if defined(CONFIG_STM32_I2S_DMADEBUG) && defined(I2S_HAVE_RX) +# define i2s_rxdma_sample(s,i) stm32_dmasample((s)->rx.dma, &(s)->rx.dmaregs[i]) +# define i2s_rxdma_sampleinit(s) i2s_dma_sampleinit(s, &(s)->rx) +static void i2s_rxdma_sampledone(struct stm32_i2s_s *priv, int result); + +#else +# define i2s_rxdma_sample(s,i) +# define i2s_rxdma_sampleinit(s) +# define i2s_rxdma_sampledone(s,r) + +#endif + +#if defined(CONFIG_STM32_I2S_DMADEBUG) && defined(I2S_HAVE_TX) +# define i2s_txdma_sample(s,i) stm32_dmasample((s)->tx.dma, &(s)->tx.dmaregs[i]) +# define i2s_txdma_sampleinit(s) i2s_dma_sampleinit(s, &(s)->tx) +static void i2s_txdma_sampledone(struct stm32_i2s_s *priv, int result); + +#else +# define i2s_txdma_sample(s,i) +# define i2s_txdma_sampleinit(s) +# define i2s_txdma_sampledone(s,r) + +#endif + +#ifdef I2S_HAVE_RX +static void i2s_rxdma_timeout(int argc, uint32_t arg); +static int i2s_rxdma_setup(struct stm32_i2s_s *priv); +static void i2s_rx_worker(void *arg); +static void i2s_rx_schedule(struct stm32_i2s_s *priv, int result); +static void i2s_rxdma_callback(DMA_HANDLE handle, uint8_t result, void *arg); +#endif +#ifdef I2S_HAVE_TX +static void i2s_txdma_timeout(int argc, uint32_t arg); +static int i2s_txdma_setup(struct stm32_i2s_s *priv); +static void i2s_tx_worker(void *arg); +static void i2s_tx_schedule(struct stm32_i2s_s *priv, int result); +static void i2s_txdma_callback(DMA_HANDLE handle, uint8_t result, void *arg); +#endif + +/* I2S methods (and close friends) */ + +static int i2s_checkwidth(struct stm32_i2s_s *priv, int bits); + +static uint32_t stm32_i2s_rxsamplerate(struct i2s_dev_s *dev, uint32_t rate); +static uint32_t stm32_i2s_rxdatawidth(struct i2s_dev_s *dev, int bits); +static int stm32_i2s_receive(struct i2s_dev_s *dev, struct ap_buffer_s *apb, + i2s_callback_t callback, void *arg, uint32_t timeout); +static uint32_t stm32_i2s_txsamplerate(struct i2s_dev_s *dev, uint32_t rate); +static uint32_t stm32_i2s_txdatawidth(struct i2s_dev_s *dev, int bits); +static int stm32_i2s_send(struct i2s_dev_s *dev, struct ap_buffer_s *apb, + i2s_callback_t callback, void *arg, + uint32_t timeout); + +/* Initialization */ + +static uint32_t i2s_mckdivider(struct stm32_i2s_s *priv); +static int i2s_dma_flags(struct stm32_i2s_s *priv); +static int i2s_dma_allocate(struct stm32_i2s_s *priv); +static void i2s_dma_free(struct stm32_i2s_s *priv); +#ifdef CONFIG_STM32_I2S2 +static void i2s2_configure(struct stm32_i2s_s *priv); +#endif +#ifdef CONFIG_STM32_I2S3 +static void i2s3_configure(struct stm32_i2s_s *priv); +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* I2S device operations */ + +static const struct i2s_ops_s g_i2sops = +{ + /* Receiver methods */ + + .i2s_rxsamplerate = stm32_i2s_rxsamplerate, + .i2s_rxdatawidth = stm32_i2s_rxdatawidth, + .i2s_receive = stm32_i2s_receive, + + /* Transmitter methods */ + + .i2s_txsamplerate = stm32_i2s_txsamplerate, + .i2s_txdatawidth = stm32_i2s_txdatawidth, + .i2s_send = stm32_i2s_send, +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: i2s_checkreg + * + * Description: + * Check if the current register access is a duplicate of the preceding. + * + * Input Parameters: + * regval - The value to be written + * regaddr - The address of the register to write to + * + * Returned Value: + * true: This is the first register access of this type. + * flase: This is the same as the preceding register access. + * + ****************************************************************************/ + +#ifdef CONFIG_STM32_I2S_REGDEBUG +static bool i2s_checkreg(struct stm32_i2s_s *priv, bool wr, uint16_t regval, + uint32_t regaddr) +{ + if (wr == priv->wr && /* Same kind of access? */ + regval == priv->regval && /* Same value? */ + regaddr == priv->regaddr) /* Same address? */ + { + /* Yes, then just keep a count of the number of times we did this. */ + + priv->count++; + return false; + } + else + { + /* Did we do the previous operation more than once? */ + + if (priv->count > 0) + { + /* Yes... show how many times we did it */ + + i2sinfo("...[Repeats %d times]...\n", priv->count); + } + + /* Save information about the new access */ + + priv->wr = wr; + priv->regval = regval; + priv->regaddr = regaddr; + priv->count = 0; + } + + /* Return true if this is the first time that we have done this operation */ + + return true; +} +#endif + +/**************************************************************************** + * Name: i2s_getreg + * + * Description: + * Get the contents of the I2S register at offset + * + * Input Parameters: + * priv - private I2S device structure + * offset - offset to the register of interest + * + * Returned Value: + * The contents of the 16-bit register + * + ****************************************************************************/ + +static inline uint16_t i2s_getreg(FAR struct stm32_i2s_s *priv, + uint8_t offset) +{ + uint32_t regaddr = priv->base + offset; + uint16_t regval = getreg16(regaddr); + +#ifdef CONFIG_STM32_I2S_REGDEBUG + if (i2s_checkreg(priv, false, regval, regaddr)) + { + i2sinfo("%08x->%04x\n", regaddr, regval); + } +#endif + + return regval; +} + +/**************************************************************************** + * Name: spi_putreg + * + * Description: + * Write a 16-bit value to the SPI register at offset + * + * Input Parameters: + * priv - private SPI device structure + * offset - offset to the register of interest + * value - the 16-bit value to be written + * + * Returned Value: + * The contents of the 16-bit register + * + ****************************************************************************/ + +static inline void i2s_putreg(FAR struct stm32_i2s_s *priv, uint8_t offset, + uint16_t regval) +{ + uint32_t regaddr = priv->base + offset; + +#ifdef CONFIG_STM32_I2S_REGDEBUG + if (i2s_checkreg(priv, true, regval, regaddr)) + { + i2sinfo("%08x<-%04x\n", regaddr, regval); + } +#endif + + putreg16(regval, regaddr); +} + +/**************************************************************************** + * Name: i2s_dump_regs + * + * Description: + * Dump the contents of all I2S registers + * + * Input Parameters: + * priv - The I2S controller to dump + * msg - Message to print before the register data + * + * Returned Value: + * None + * + ****************************************************************************/ + +#if defined(CONFIG_DEBUG_I2S) +static void i2s_dump_regs(struct stm32_i2s_s *priv, const char *msg) +{ + i2sinfo("I2S%d: %s\n", priv->i2sno, msg); + i2sinfo(" CR1:%04x CR2:%04x SR:%04x DR:%04x\n", + i2s_getreg(priv, STM32_SPI_CR1_OFFSET), + i2s_getreg(priv, STM32_SPI_CR2_OFFSET), + i2s_getreg(priv, STM32_SPI_SR_OFFSET), + i2s_getreg(priv, STM32_SPI_DR_OFFSET)); + i2sinfo(" I2SCFGR:%04x I2SPR:%04x\n", + i2s_getreg(priv, STM32_SPI_I2SCFGR_OFFSET), + i2s_getreg(priv, STM32_SPI_I2SPR_OFFSET)); +} +#endif + +/**************************************************************************** + * Name: i2s_exclsem_take + * + * Description: + * Take the exclusive access semaphore handling any exceptional conditions + * + * Input Parameters: + * priv - A reference to the i2s peripheral state + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void i2s_exclsem_take(struct stm32_i2s_s *priv) +{ + int ret; + + /* Wait until we successfully get the semaphore. EINTR is the only + * expected 'failure' (meaning that the wait for the semaphore was + * interrupted by a signal. + */ + + do + { + ret = sem_wait(&priv->exclsem); + DEBUGASSERT(ret == 0 || errno == EINTR); + } + while (ret < 0); +} + +/**************************************************************************** + * Name: i2s_bufsem_take + * + * Description: + * Take the buffer semaphore handling any exceptional conditions + * + * Input Parameters: + * priv - A reference to the i2s peripheral state + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void i2s_bufsem_take(struct stm32_i2s_s *priv) +{ + int ret; + + /* Wait until we successfully get the semaphore. EINTR is the only + * expected 'failure' (meaning that the wait for the semaphore was + * interrupted by a signal. + */ + + do + { + ret = sem_wait(&priv->bufsem); + DEBUGASSERT(ret == 0 || errno == EINTR); + } + while (ret < 0); +} + +/**************************************************************************** + * Name: i2s_buf_allocate + * + * Description: + * Allocate a buffer container by removing the one at the head of the + * free list + * + * Input Parameters: + * priv - I2S state instance + * + * Returned Value: + * A non-NULL pointer to the allocate buffer container on success; NULL if + * there are no available buffer containers. + * + * Assumptions: + * The caller does NOT have exclusive access to the I2S state structure. + * That would result in a deadlock! + * + ****************************************************************************/ + +static struct stm32_buffer_s *i2s_buf_allocate(struct stm32_i2s_s *priv) +{ + struct stm32_buffer_s *bfcontainer; + irqstate_t flags; + + /* Set aside a buffer container. By doing this, we guarantee that we will + * have at least one free buffer container. + */ + + i2s_bufsem_take(priv); + + /* Get the buffer from the head of the free list */ + + flags = enter_critical_section(); + bfcontainer = priv->freelist; + ASSERT(bfcontainer); + + /* Unlink the buffer from the freelist */ + + priv->freelist = bfcontainer->flink; + leave_critical_section(flags); + return bfcontainer; +} + +/**************************************************************************** + * Name: i2s_buf_free + * + * Description: + * Free buffer container by adding it to the head of the free list + * + * Input Parameters: + * priv - I2S state instance + * bfcontainer - The buffer container to be freed + * + * Returned Value: + * None + * + * Assumptions: + * The caller has exclusive access to the I2S state structure + * + ****************************************************************************/ + +static void i2s_buf_free(struct stm32_i2s_s *priv, struct stm32_buffer_s *bfcontainer) +{ + irqstate_t flags; + + /* Put the buffer container back on the free list */ + + flags = enter_critical_section(); + bfcontainer->flink = priv->freelist; + priv->freelist = bfcontainer; + leave_critical_section(flags); + + /* Wake up any threads waiting for a buffer container */ + + i2s_bufsem_give(priv); +} + +/**************************************************************************** + * Name: i2s_buf_initialize + * + * Description: + * Initialize the buffer container allocator by adding all of the + * pre-allocated buffer containers to the free list + * + * Input Parameters: + * priv - I2S state instance + * + * Returned Value: + * None + * + * Assumptions: + * Called early in I2S initialization so that there are no issues with + * concurrency. + * + ****************************************************************************/ + +static void i2s_buf_initialize(struct stm32_i2s_s *priv) +{ + int i; + + priv->freelist = NULL; + sem_init(&priv->bufsem, 0, CONFIG_STM32_I2S_MAXINFLIGHT); + + for (i = 0; i < CONFIG_STM32_I2S_MAXINFLIGHT; i++) + { + i2s_buf_free(priv, &priv->containers[i]); + } +} + +/**************************************************************************** + * Name: i2s_dma_sampleinit + * + * Description: + * Initialize sampling of DMA registers (if CONFIG_STM32_I2S_DMADEBUG) + * + * Input Parameters: + * priv - I2S state instance + * + * Returned Value: + * None + * + ****************************************************************************/ + +#if defined(CONFIG_STM32_I2S_DMADEBUG) +static void i2s_dma_sampleinit(struct stm32_i2s_s *priv, + struct stm32_transport_s *xpt) +{ + /* Put contents of register samples into a known state */ + + memset(xpt->dmaregs, 0xff, DMA_NSAMPLES * sizeof(struct stm32_dmaregs_s)); + + /* Then get the initial samples */ + + stm32_dmasample(xpt->dma, &xpt->dmaregs[DMA_INITIAL]); +} +#endif + +/**************************************************************************** + * Name: i2s_rxdma_sampledone + * + * Description: + * Dump sampled RX DMA registers + * + * Input Parameters: + * priv - I2S state instance + * + * Returned Value: + * None + * + ****************************************************************************/ + +#if defined(CONFIG_STM32_I2S_DMADEBUG) && defined(I2S_HAVE_RX) +static void i2s_rxdma_sampledone(struct stm32_i2s_s *priv, int result) +{ + i2sinfo("result: %d\n", result); + + /* Sample the final registers */ + + stm32_dmasample(priv->rx.dma, &priv->rx.dmaregs[DMA_END_TRANSFER]); + + /* Then dump the sampled DMA registers */ + /* Initial register values */ + + stm32_dmadump(priv->rx.dma, &priv->rx.dmaregs[DMA_INITIAL], + "RX: Initial Registers"); + + /* Register values after DMA setup */ + + stm32_dmadump(priv->rx.dma, &priv->rx.dmaregs[DMA_AFTER_SETUP], + "RX: After DMA Setup"); + + /* Register values after DMA start */ + + stm32_dmadump(priv->rx.dma, &priv->rx.dmaregs[DMA_AFTER_START], + "RX: After DMA Start"); + + /* Register values at the time of the TX and RX DMA callbacks + * -OR- DMA timeout. + * + * If the DMA timedout, then there will not be any RX DMA + * callback samples. There is probably no TX DMA callback + * samples either, but we don't know for sure. + */ + + if (result == -ETIMEDOUT || result == -EINTR) + { + stm32_dmadump(priv->rx.dma, &priv->rx.dmaregs[DMA_TIMEOUT], + "RX: At DMA timeout"); + } + else + { + stm32_dmadump(priv->rx.dma, &priv->rx.dmaregs[DMA_CALLBACK], + "RX: At DMA callback"); + } + + stm32_dmadump(priv->rx.dma, &priv->rx.dmaregs[DMA_END_TRANSFER], + "RX: At End-of-Transfer"); + + i2s_dump_regs(priv, "RX: At End-of-Transfer"); +} +#endif + +/**************************************************************************** + * Name: i2s_txdma_sampledone + * + * Description: + * Dump sampled DMA registers + * + * Input Parameters: + * priv - I2S state instance + * + * Returned Value: + * None + * + ****************************************************************************/ + +#if defined(CONFIG_STM32_I2S_DMADEBUG) && defined(I2S_HAVE_TX) +static void i2s_txdma_sampledone(struct stm32_i2s_s *priv, int result) +{ + i2sinfo("result: %d\n", result); + + /* Sample the final registers */ + + stm32_dmasample(priv->tx.dma, &priv->tx.dmaregs[DMA_END_TRANSFER]); + + /* Then dump the sampled DMA registers */ + /* Initial register values */ + + stm32_dmadump(priv->tx.dma, &priv->tx.dmaregs[DMA_INITIAL], + "TX: Initial Registers"); + + /* Register values after DMA setup */ + + stm32_dmadump(priv->tx.dma, &priv->tx.dmaregs[DMA_AFTER_SETUP], + "TX: After DMA Setup"); + + /* Register values after DMA start */ + + stm32_dmadump(priv->tx.dma, &priv->tx.dmaregs[DMA_AFTER_START], + "TX: After DMA Start"); + + /* Register values at the time of the TX and RX DMA callbacks + * -OR- DMA timeout. + */ + + if (result == -ETIMEDOUT || result == -EINTR) + { + stm32_dmadump(priv->tx.dma, &priv->tx.dmaregs[DMA_TIMEOUT], + "TX: At DMA timeout"); + } + else + { + stm32_dmadump(priv->tx.dma, &priv->tx.dmaregs[DMA_CALLBACK], + "TX: At DMA callback"); + } + + stm32_dmadump(priv->tx.dma, &priv->tx.dmaregs[DMA_END_TRANSFER], + "TX: At End-of-Transfer"); + + i2s_dump_regs(priv, "TX: At End-of-Transfer"); +} +#endif + +/**************************************************************************** + * Name: i2s_rxdma_timeout + * + * Description: + * The RX watchdog timeout without completion of the RX DMA. + * + * Input Parameters: + * argc - The number of arguments (should be 1) + * arg - The argument (state structure reference cast to uint32_t) + * + * Returned Value: + * None + * + * Assumptions: + * Always called from the interrupt level with interrupts disabled. + * + ****************************************************************************/ + +#ifdef I2S_HAVE_RX +static void i2s_rxdma_timeout(int argc, uint32_t arg) +{ + struct stm32_i2s_s *priv = (struct stm32_i2s_s *)arg; + DEBUGASSERT(priv != NULL); + + /* Sample DMA registers at the time of the timeout */ + + i2s_rxdma_sample(priv, DMA_TIMEOUT); + + /* Cancel the DMA */ + + stm32_dmastop(priv->rx.dma); + + /* Then schedule completion of the transfer to occur on the worker thread. + * NOTE: stm32_dmastop() will call the DMA complete callback with an error + * of -EINTR. So the following is just insurance and should have no + * effect if the worker is already schedule. + */ + + i2s_rx_schedule(priv, -ETIMEDOUT); +} +#endif + +/**************************************************************************** + * Name: i2s_rxdma_setup + * + * Description: + * Setup and initiate the next RX DMA transfer + * + * Input Parameters: + * priv - I2S state instance + * + * Returned Value: + * OK on success; a negated errno value on failure + * + * Assumptions: + * Interrupts are disabled + * + ****************************************************************************/ + +#ifdef I2S_HAVE_RX +static int i2s_rxdma_setup(struct stm32_i2s_s *priv) +{ + struct stm32_buffer_s *bfcontainer; + struct ap_buffer_s *apb; + uintptr_t samp; + uint32_t timeout; + bool notimeout; + int ret; + + /* If there is already an active transmission in progress, then bail + * returning success. + */ + + if (!sq_empty(&priv->rx.act)) + { + return OK; + } + + /* If there are no pending transfer, then bail returning success */ + + if (sq_empty(&priv->rx.pend)) + { + return OK; + } + + /* Initialize DMA register sampling */ + + i2s_rxdma_sampleinit(priv); + + /* Loop, adding each pending DMA */ + + timeout = 0; + notimeout = false; + + do + { + /* Remove the pending RX transfer at the head of the RX pending queue. */ + + bfcontainer = (struct stm32_buffer_s *)sq_remfirst(&priv->rx.pend); + DEBUGASSERT(bfcontainer && bfcontainer->apb); + + apb = bfcontainer->apb; + DEBUGASSERT(((uintptr_t)apb->samp % priv->align) == 0); + + /* No data received yet */ + + apb->nbytes = 0; + apb->curbyte = 0; + samp = (uintptr_t)&apb->samp[apb->curbyte]; + + /* Configure the RX DMA */ + + stm32_dmasetup(priv->rx.dma, priv->base + STM32_SPI_DR_OFFSET, + (uint32_t)samp, apb->nmaxbytes, priv->rxccr); + + /* Increment the DMA timeout */ + + if (bfcontainer->timeout > 0) + { + timeout += bfcontainer->timeout; + } + else + { + notimeout = true; + } + + /* Add the container to the list of active DMAs */ + + sq_addlast((sq_entry_t *)bfcontainer, &priv->rx.act); + } +#if 1 /* REVISIT: Chained RX transfers */ + while (0); +#else + while (!sq_empty(&priv->rx.pend)); +#endif + + /* Sample DMA registers */ + + i2s_rxdma_sample(priv, DMA_AFTER_SETUP); + + /* Start the DMA, saving the container as the current active transfer */ + + stm32_dmastart(priv->rx.dma, i2s_rxdma_callback, priv, false); + + i2s_rxdma_sample(priv, DMA_AFTER_START); + + /* Enable the receiver */ + + i2s_putreg(priv, STM32_SPI_CR2_OFFSET, + i2s_getreg(priv, STM32_SPI_CR2_OFFSET) | SPI_CR2_RXDMAEN); + + /* Start a watchdog to catch DMA timeouts */ + + if (!notimeout) + { + ret = wd_start(priv->rx.dog, timeout, (wdentry_t)i2s_rxdma_timeout, + 1, (uint32_t)priv); + + /* Check if we have successfully started the watchdog timer. Note + * that we do nothing in the case of failure to start the timer. We + * are already committed to the DMA anyway. Let's just hope that the + * DMA does not hang. + */ + + if (ret < 0) + { + i2serr("ERROR: wd_start failed: %d\n", errno); + } + } + + return OK; +} +#endif + +/**************************************************************************** + * Name: i2s_rx_worker + * + * Description: + * RX transfer done worker + * + * Input Parameters: + * arg - the I2S device instance cast to void* + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef I2S_HAVE_RX +static void i2s_rx_worker(void *arg) +{ + struct stm32_i2s_s *priv = (struct stm32_i2s_s *)arg; + struct stm32_buffer_s *bfcontainer; + struct ap_buffer_s *apb; + irqstate_t flags; + + DEBUGASSERT(priv); + + /* When the transfer was started, the active buffer containers were removed + * from the rx.pend queue and saved in the rx.act queue. We get here when the + * DMA is finished... either successfully, with a DMA error, or with a DMA + * timeout. + * + * In any case, the buffer containers in rx.act will be moved to the end + * of the rx.done queue and rx.act queue will be emptied before this worker + * is started. + * + * REVISIT: Normal DMA callback processing should restart the DMA + * immediately to avoid audio artifacts at the boundaries between DMA + * transfers. Unfortunately, the DMA callback occurs at the interrupt + * level and we cannot call dma_rxsetup() from the interrupt level. + * So we have to start the next DMA here. + */ + + i2sinfo("rx.act.head=%p rx.done.head=%p\n", + priv->rx.act.head, priv->rx.done.head); + + /* Check if the DMA is IDLE */ + + if (sq_empty(&priv->rx.act)) + { +#ifdef CONFIG_STM32_I2S_DMADEBUG + bfcontainer = (struct stm32_buffer_s *)sq_peek(&priv->rx.done); + if (bfcontainer) + { + /* Dump the DMA registers */ + + i2s_rxdma_sampledone(priv, bfcontainer->result); + } +#endif + + /* Then start the next DMA. This must be done with interrupts + * disabled. + */ + + flags = enter_critical_section(); + (void)i2s_rxdma_setup(priv); + leave_critical_section(flags); + } + + /* Process each buffer in the rx.done queue */ + + while (sq_peek(&priv->rx.done) != NULL) + { + /* Remove the buffer container from the rx.done queue. NOTE that + * interrupts must be enabled to do this because the rx.done queue is + * also modified from the interrupt level. + */ + + flags = enter_critical_section(); + bfcontainer = (struct stm32_buffer_s *)sq_remfirst(&priv->rx.done); + leave_critical_section(flags); + + DEBUGASSERT(bfcontainer && bfcontainer->apb && bfcontainer->callback); + apb = bfcontainer->apb; + + /* If the DMA was successful, then update the number of valid bytes in + * the audio buffer. + */ + + if (bfcontainer->result == OK) + { + apb->nbytes = apb->nmaxbytes; + } + + i2s_dump_buffer("Received", apb->samp, apb->nbytes); + + /* Perform the RX transfer done callback */ + + bfcontainer->callback(&priv->dev, apb, bfcontainer->arg, + bfcontainer->result); + + /* Release our reference on the audio buffer. This may very likely + * cause the audio buffer to be freed. + */ + + apb_free(apb); + + /* And release the buffer container */ + + i2s_buf_free(priv, bfcontainer); + } +} +#endif + +/**************************************************************************** + * Name: i2s_rx_schedule + * + * Description: + * An RX DMA completion or timeout has occurred. Schedule processing on + * the working thread. + * + * Input Parameters: + * handle - The DMA handler + * arg - A pointer to the chip select struction + * result - The result of the DMA transfer + * + * Returned Value: + * None + * + * Assumptions: + * Interrupts are disabled + * + ****************************************************************************/ + +#ifdef I2S_HAVE_RX +static void i2s_rx_schedule(struct stm32_i2s_s *priv, int result) +{ + struct stm32_buffer_s *bfcontainer; + int ret; + + /* Upon entry, the transfer(s) that just completed are the ones in the + * priv->rx.act queue. NOTE: In certain conditions, this function may + * be called an additional time, hence, we can't assert this to be true. + * For example, in the case of a timeout, this function will be called by + * both indirectly via the stm32_dmastop() logic and directly via the + * i2s_rxdma_timeout() logic. + */ + + /* Move all entries from the rx.act queue to the rx.done queue */ + + while (!sq_empty(&priv->rx.act)) + { + /* Remove the next buffer container from the rx.act list */ + + bfcontainer = (struct stm32_buffer_s *)sq_remfirst(&priv->rx.act); + + /* Report the result of the transfer */ + + bfcontainer->result = result; + + /* Add the completed buffer container to the tail of the rx.done queue */ + + sq_addlast((sq_entry_t *)bfcontainer, &priv->rx.done); + } + + /* If the worker has completed running, then reschedule the working thread. + * REVISIT: There may be a race condition here. So we do nothing is the + * worker is not available. + */ + + if (work_available(&priv->rx.work)) + { + /* Schedule the TX DMA done processing to occur on the worker thread. */ + + ret = work_queue(HPWORK, &priv->rx.work, i2s_rx_worker, priv, 0); + if (ret != 0) + { + i2serr("ERROR: Failed to queue RX work: %d\n", ret); + } + } +} +#endif + +/**************************************************************************** + * Name: i2s_rxdma_callback + * + * Description: + * This callback function is invoked at the completion of the I2S RX DMA. + * + * Input Parameters: + * handle - The DMA handler + * arg - A pointer to the chip select struction + * result - The result of the DMA transfer + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef I2S_HAVE_RX +static void i2s_rxdma_callback(DMA_HANDLE handle, uint8_t result, void *arg) +{ + struct stm32_i2s_s *priv = (struct stm32_i2s_s *)arg; + DEBUGASSERT(priv != NULL); + + /* Cancel the watchdog timeout */ + + (void)wd_cancel(priv->rx.dog); + + /* Sample DMA registers at the time of the DMA completion */ + + i2s_rxdma_sample(priv, DMA_CALLBACK); + + /* REVISIT: We would like to the next DMA started here so that we do not + * get audio glitches at the boundaries between DMA transfers. + * Unfortunately, we cannot call stm32_dmasetup() from an interrupt handler! + */ + + /* Then schedule completion of the transfer to occur on the worker thread */ + + i2s_rx_schedule(priv, result); +} +#endif + +/**************************************************************************** + * Name: i2s_txdma_timeout + * + * Description: + * The RX watchdog timeout without completion of the RX DMA. + * + * Input Parameters: + * argc - The number of arguments (should be 1) + * arg - The argument (state structure reference cast to uint32_t) + * + * Returned Value: + * None + * + * Assumptions: + * Always called from the interrupt level with interrupts disabled. + * + ****************************************************************************/ + +#ifdef I2S_HAVE_TX +static void i2s_txdma_timeout(int argc, uint32_t arg) +{ + struct stm32_i2s_s *priv = (struct stm32_i2s_s *)arg; + DEBUGASSERT(priv != NULL); + + /* Sample DMA registers at the time of the timeout */ + + i2s_txdma_sample(priv, DMA_TIMEOUT); + + /* Cancel the DMA */ + + stm32_dmastop(priv->tx.dma); + + /* Then schedule completion of the transfer to occur on the worker thread. + * NOTE: stm32_dmastop() will call the DMA complete callback with an error + * of -EINTR. So the following is just insurance and should have no + * effect if the worker is already schedule. + */ + + i2s_tx_schedule(priv, -ETIMEDOUT); +} +#endif + +/**************************************************************************** + * Name: i2s_txdma_setup + * + * Description: + * Setup and initiate the next TX DMA transfer + * + * Input Parameters: + * priv - I2S state instance + * + * Returned Value: + * OK on success; a negated errno value on failure + * + * Assumptions: + * Interrupts are disabled + * + ****************************************************************************/ + +#ifdef I2S_HAVE_TX +static int i2s_txdma_setup(struct stm32_i2s_s *priv) +{ + struct stm32_buffer_s *bfcontainer; + struct ap_buffer_s *apb; + uintptr_t samp; + uint32_t timeout; + apb_samp_t nbytes; + bool notimeout; + int ret; + + /* If there is already an active transmission in progress, then bail + * returning success. + */ + + if (!sq_empty(&priv->tx.act)) + { + return OK; + } + + /* If there are no pending transfer, then bail returning success */ + + if (sq_empty(&priv->tx.pend)) + { + return OK; + } + + /* Initialize DMA register sampling */ + + i2s_txdma_sampleinit(priv); + + /* Loop, adding each pending DMA */ + + timeout = 0; + notimeout = false; + + do + { + /* Remove the pending TX transfer at the head of the TX pending queue. */ + + bfcontainer = (struct stm32_buffer_s *)sq_remfirst(&priv->tx.pend); + DEBUGASSERT(bfcontainer && bfcontainer->apb); + + apb = bfcontainer->apb; + + /* Get the transfer information, accounting for any data offset */ + + samp = (uintptr_t)&apb->samp[apb->curbyte]; + nbytes = apb->nbytes - apb->curbyte; + DEBUGASSERT((samp & priv->align) == 0 && (nbytes & priv->align) == 0); + + /* Configure DMA stream */ + + stm32_dmasetup(priv->tx.dma, priv->base + STM32_SPI_DR_OFFSET, + (uint32_t)samp, nbytes/2, priv->txccr); + + /* Increment the DMA timeout */ + if (bfcontainer->timeout > 0) + { + timeout += bfcontainer->timeout; + } + else + { + notimeout = true; + } + + /* Add the container to the list of active DMAs */ + + sq_addlast((sq_entry_t *)bfcontainer, &priv->tx.act); + } +#if 1 /* REVISIT: Chained TX transfers */ + while (0); +#else + while (!sq_empty(&priv->tx.pend)); +#endif + + /* Sample DMA registers */ + + i2s_txdma_sample(priv, DMA_AFTER_SETUP); + + /* Start the DMA, saving the container as the current active transfer */ + + stm32_dmastart(priv->tx.dma, i2s_txdma_callback, priv, true); + + i2s_txdma_sample(priv, DMA_AFTER_START); + + /* Enable the transmitter */ + + i2s_putreg(priv, STM32_SPI_CR2_OFFSET, i2s_getreg(priv, STM32_SPI_CR2_OFFSET) | SPI_CR2_TXDMAEN); + + /* Start a watchdog to catch DMA timeouts */ + + if (!notimeout) + { + ret = wd_start(priv->tx.dog, timeout, (wdentry_t)i2s_txdma_timeout, + 1, (uint32_t)priv); + + /* Check if we have successfully started the watchdog timer. Note + * that we do nothing in the case of failure to start the timer. We + * are already committed to the DMA anyway. Let's just hope that the + * DMA does not hang. + */ + + if (ret < 0) + { + i2serr("ERROR: wd_start failed: %d\n", errno); + } + } + + return OK; +} +#endif + +/**************************************************************************** + * Name: i2s_tx_worker + * + * Description: + * TX transfer done worker + * + * Input Parameters: + * arg - the I2S device instance cast to void* + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef I2S_HAVE_TX +static void i2s_tx_worker(void *arg) +{ + struct stm32_i2s_s *priv = (struct stm32_i2s_s *)arg; + struct stm32_buffer_s *bfcontainer; + irqstate_t flags; + + DEBUGASSERT(priv); + + /* When the transfer was started, the active buffer containers were removed + * from the tx.pend queue and saved in the tx.act queue. We get here when the + * DMA is finished... either successfully, with a DMA error, or with a DMA + * timeout. + * + * In any case, the buffer containers in tx.act will be moved to the end + * of the tx.done queue and tx.act will be emptied before this worker is + * started. + * + * REVISIT: Normal DMA callback processing should restart the DMA + * immediately to avoid audio artifacts at the boundaries between DMA + * transfers. Unfortunately, the DMA callback occurs at the interrupt + * level and we cannot call dma_txsetup() from the interrupt level. + * So we have to start the next DMA here. + */ + + i2sinfo("tx.act.head=%p tx.done.head=%p\n", + priv->tx.act.head, priv->tx.done.head); + + /* Check if the DMA is IDLE */ + + if (sq_empty(&priv->tx.act)) + { +#ifdef CONFIG_STM32_I2S_DMADEBUG + bfcontainer = (struct stm32_buffer_s *)sq_peek(&priv->tx.done); + if (bfcontainer) + { + /* Dump the DMA registers */ + + i2s_txdma_sampledone(priv, bfcontainer->result); + } +#endif + + /* Then start the next DMA. This must be done with interrupts + * disabled. + */ + + flags = enter_critical_section(); + (void)i2s_txdma_setup(priv); + leave_critical_section(flags); + } + + /* Process each buffer in the tx.done queue */ + + while (sq_peek(&priv->tx.done) != NULL) + { + /* Remove the buffer container from the tx.done queue. NOTE that + * interupts must be enabled to do this because the tx.done queue is + * also modified from the interrupt level. + */ + + flags = enter_critical_section(); + bfcontainer = (struct stm32_buffer_s *)sq_remfirst(&priv->tx.done); + leave_critical_section(flags); + + /* Perform the TX transfer done callback */ + + DEBUGASSERT(bfcontainer && bfcontainer->callback); + bfcontainer->callback(&priv->dev, bfcontainer->apb, + bfcontainer->arg, bfcontainer->result); + + /* Release our reference on the audio buffer. This may very likely + * cause the audio buffer to be freed. + */ + + apb_free(bfcontainer->apb); + + /* And release the buffer container */ + + i2s_buf_free(priv, bfcontainer); + } +} +#endif + +/**************************************************************************** + * Name: i2s_tx_schedule + * + * Description: + * An TX DMA completion or timeout has occurred. Schedule processing on + * the working thread. + * + * Input Parameters: + * handle - The DMA handler + * arg - A pointer to the chip select struction + * result - The result of the DMA transfer + * + * Returned Value: + * None + * + * Assumptions: + * - Interrupts are disabled + * - The TX timeout has been canceled. + * + ****************************************************************************/ + +#ifdef I2S_HAVE_TX +static void i2s_tx_schedule(struct stm32_i2s_s *priv, int result) +{ + struct stm32_buffer_s *bfcontainer; + int ret; + + /* Upon entry, the transfer(s) that just completed are the ones in the + * priv->tx.act queue. NOTE: In certain conditions, this function may + * be called an additional time, hence, we can't assert this to be true. + * For example, in the case of a timeout, this function will be called by + * both indirectly via the stm32_dmastop() logic and directly via the + * i2s_txdma_timeout() logic. + */ + + /* Move all entries from the tx.act queue to the tx.done queue */ + + while (!sq_empty(&priv->tx.act)) + { + /* Remove the next buffer container from the tx.act list */ + + bfcontainer = (struct stm32_buffer_s *)sq_remfirst(&priv->tx.act); + + /* Report the result of the transfer */ + + bfcontainer->result = result; + + /* Add the completed buffer container to the tail of the tx.done queue */ + + sq_addlast((sq_entry_t *)bfcontainer, &priv->tx.done); + } + + /* If the worker has completed running, then reschedule the working thread. + * REVISIT: There may be a race condition here. So we do nothing is the + * worker is not available. + */ + + if (work_available(&priv->tx.work)) + { + /* Schedule the TX DMA done processing to occur on the worker thread. */ + + ret = work_queue(HPWORK, &priv->tx.work, i2s_tx_worker, priv, 0); + if (ret != 0) + { + i2serr("ERROR: Failed to queue TX work: %d\n", ret); + } + } +} +#endif + +/**************************************************************************** + * Name: i2s_txdma_callback + * + * Description: + * This callback function is invoked at the completion of the I2S TX DMA. + * + * Input Parameters: + * handle - The DMA handler + * arg - A pointer to the chip select struction + * result - The result of the DMA transfer + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef I2S_HAVE_TX +static void i2s_txdma_callback(DMA_HANDLE handle, uint8_t result, void *arg) +{ + struct stm32_i2s_s *priv = (struct stm32_i2s_s *)arg; + DEBUGASSERT(priv != NULL); + + /* Cancel the watchdog timeout */ + + (void)wd_cancel(priv->tx.dog); + + /* Sample DMA registers at the time of the DMA completion */ + + i2s_txdma_sample(priv, DMA_CALLBACK); + + /* REVISIT: We would like to the next DMA started here so that we do not + * get audio glitches at the boundaries between DMA transfers. + * Unfortunately, we cannot call stm32_dmasetup() from an interrupt handler! + */ + + /* Then schedule completion of the transfer to occur on the worker thread */ + + i2s_tx_schedule(priv, result); +} +#endif + +/**************************************************************************** + * Name: i2s_checkwidth + * + * Description: + * Check for a valid bit width. The I2S is capable of handling most any + * bit width from 8 to 16, but the DMA logic in this driver is constrained + * to 8- and 16-bit data widths + * + * Input Parameters: + * dev - Device-specific state data + * rate - The I2S sample rate in samples (not bits) per second + * + * Returned Value: + * Returns the resulting bitrate + * + ****************************************************************************/ + +static int i2s_checkwidth(struct stm32_i2s_s *priv, int bits) +{ + /* The I2S can handle most any bit width from 8 to 32. However, the DMA + * logic here is constrained to byte, half-word, and word sizes. + */ + + switch (bits) + { + case 8: +#ifdef CONFIG_DEBUG + priv->align = 0; +#endif + break; + + case 16: +#ifdef CONFIG_DEBUG + priv->align = 1; +#endif + break; + + default: + i2serr("ERROR: Unsupported or invalid data width: %d\n", bits); + return (bits < 8 || bits > 16) ? -EINVAL : -ENOSYS; + } + + /* Save the new data width */ + + priv->datalen = bits; + return OK; +} + +/**************************************************************************** + * Name: stm32_i2s_rxsamplerate + * + * Description: + * Set the I2S RX sample rate. NOTE: This will have no effect if (1) the + * driver does not support an I2C receiver or if (2) the sample rate is + * driven by the I2C frame clock. This may also have unexpected side- + * effects of the RX sample is coupled with the TX sample rate. + * + * Input Parameters: + * dev - Device-specific state data + * rate - The I2S sample rate in samples (not bits) per second + * + * Returned Value: + * Returns the resulting bitrate + * + ****************************************************************************/ + +static uint32_t stm32_i2s_rxsamplerate(struct i2s_dev_s *dev, uint32_t rate) +{ +#if defined(I2S_HAVE_RX) && defined(I2S_HAVE_MCK) + struct stm32_i2s_s *priv = (struct stm32_i2s_s *)dev; + DEBUGASSERT(priv && priv->samplerate > 0 && rate > 0); + + /* Check if the receiver is driven by the MCK */ + + if (priv->samplerate != rate) + { + /* Save the new sample rate and update the MCK divider */ + + priv->samplerate = rate; + return i2s_mckdivider(priv); + } +#endif + + return 0; +} + +/**************************************************************************** + * Name: stm32_i2s_rxdatawidth + * + * Description: + * Set the I2S RX data width. The RX bitrate is determined by + * sample_rate * data_width. + * + * Input Parameters: + * dev - Device-specific state data + * width - The I2S data with in bits. + * + * Returned Value: + * Returns the resulting bitrate + * + ****************************************************************************/ + +static uint32_t stm32_i2s_rxdatawidth(struct i2s_dev_s *dev, int bits) +{ +#ifdef I2S_HAVE_RX + struct stm32_i2s_s *priv = (struct stm32_i2s_s *)dev; + int ret; + + DEBUGASSERT(priv && bits > 1); + + /* Check if this is a bit width that we are configured to handle */ + + ret = i2s_checkwidth(priv, bits); + if (ret < 0) + { + i2serr("ERROR: i2s_checkwidth failed: %d\n", ret); + return 0; + } + + /* Update the DMA flags */ + + ret = i2s_dma_flags(priv); + if (ret < 0) + { + i2serr("ERROR: i2s_dma_flags failed: %d\n", ret); + return 0; + } + +#endif + + return 0; +} + +/**************************************************************************** + * Name: stm32_i2s_receive + * + * Description: + * Receive a block of data from I2S. + * + * Input Parameters: + * dev - Device-specific state data + * apb - A pointer to the audio buffer in which to recieve data + * callback - A user provided callback function that will be called at + * the completion of the transfer. The callback will be + * performed in the context of the worker thread. + * arg - An opaque argument that will be provided to the callback + * when the transfer complete + * timeout - The timeout value to use. The transfer will be canceled + * and an ETIMEDOUT error will be reported if this timeout + * elapsed without completion of the DMA transfer. Units + * are system clock ticks. Zero means no timeout. + * + * Returned Value: + * OK on success; a negated errno value on failure. NOTE: This function + * only enqueues the transfer and returns immediately. Success here only + * means that the transfer was enqueued correctly. + * + * When the transfer is complete, a 'result' value will be provided as + * an argument to the callback function that will indicate if the transfer + * failed. + * + ****************************************************************************/ + +static int stm32_i2s_receive(struct i2s_dev_s *dev, struct ap_buffer_s *apb, + i2s_callback_t callback, void *arg, uint32_t timeout) +{ + struct stm32_i2s_s *priv = (struct stm32_i2s_s *)dev; +#ifdef I2S_HAVE_RX + struct stm32_buffer_s *bfcontainer; + irqstate_t flags; + int ret; +#endif + + DEBUGASSERT(priv && apb && ((uintptr_t)apb->samp & priv->align) == 0); + i2sinfo("apb=%p nmaxbytes=%d arg=%p timeout=%d\n", + apb, apb->nmaxbytes, arg, timeout); + + i2s_init_buffer(apb->samp, apb->nmaxbytes); + +#ifdef I2S_HAVE_RX + /* Allocate a buffer container in advance */ + + bfcontainer = i2s_buf_allocate(priv); + DEBUGASSERT(bfcontainer); + + /* Get exclusive access to the I2S driver data */ + + i2s_exclsem_take(priv); + + /* Has the RX channel been enabled? */ + + if (!priv->rxenab) + { + i2serr("ERROR: I2S%d has no receiver\n", priv->i2sno); + ret = -EAGAIN; + goto errout_with_exclsem; + } + + /* Add a reference to the audio buffer */ + + apb_reference(apb); + + /* Initialize the buffer container structure */ + + bfcontainer->callback = (void *)callback; + bfcontainer->timeout = timeout; + bfcontainer->arg = arg; + bfcontainer->apb = apb; + bfcontainer->result = -EBUSY; + + /* Add the buffer container to the end of the RX pending queue */ + + flags = enter_critical_section(); + sq_addlast((sq_entry_t *)bfcontainer, &priv->rx.pend); + + /* Then start the next transfer. If there is already a transfer in progess, + * then this will do nothing. + */ + + ret = i2s_rxdma_setup(priv); + DEBUGASSERT(ret == OK); + leave_critical_section(flags); + i2s_exclsem_give(priv); + return OK; + +errout_with_exclsem: + i2s_exclsem_give(priv); + i2s_buf_free(priv, bfcontainer); + return ret; + +#else + i2serr("ERROR: I2S%d has no receiver\n", priv->i2sno); + UNUSED(priv); + return -ENOSYS; +#endif +} + +static int roundf(float num) +{ + if(((int)(num + 0.5f)) > num) + { + return num + 1; + } + + return num; +} + +/**************************************************************************** + * Name: stm32_i2s_txsamplerate + * + * Description: + * Set the I2S TX sample rate. NOTE: This will have no effect if (1) the + * driver does not support an I2C transmitter or if (2) the sample rate is + * driven by the I2C frame clock. This may also have unexpected side- + * effects of the TX sample is coupled with the RX sample rate. + * + * Input Parameters: + * dev - Device-specific state data + * rate - The I2S sample rate in samples (not bits) per second + * + * Returned Value: + * Returns the resulting bitrate + * + ****************************************************************************/ + +static uint32_t stm32_i2s_txsamplerate(struct i2s_dev_s *dev, uint32_t rate) +{ +#if defined(I2S_HAVE_TX) && defined(I2S_HAVE_MCK) + struct stm32_i2s_s *priv = (struct stm32_i2s_s *)dev; + + DEBUGASSERT(priv && priv->samplerate > 0 && rate > 0); + + /* Check if the receiver is driven by the MCK/2 */ + + if (priv->samplerate != rate) + { + /* Save the new sample rate and update the MCK/2 divider */ + + priv->samplerate = rate; + return i2s_mckdivider(priv); + } +#endif + + return 0; +} + +/**************************************************************************** + * Name: stm32_i2s_txdatawidth + * + * Description: + * Set the I2S TX data width. The TX bitrate is determined by + * sample_rate * data_width. + * + * Input Parameters: + * dev - Device-specific state data + * width - The I2S data with in bits. + * + * Returned Value: + * Returns the resulting bitrate + * + ****************************************************************************/ + +static uint32_t stm32_i2s_txdatawidth(struct i2s_dev_s *dev, int bits) +{ +#ifdef I2S_HAVE_TX + struct stm32_i2s_s *priv = (struct stm32_i2s_s *)dev; + int ret; + + i2sinfo("Data width bits of tx = %d\n",bits); + DEBUGASSERT(priv && bits > 1); + + /* Check if this is a bit width that we are configured to handle */ + + ret = i2s_checkwidth(priv, bits); + if (ret < 0) + { + i2serr("ERROR: i2s_checkwidth failed: %d\n", ret); + return 0; + } + + /* Upate the DMA flags */ + + ret = i2s_dma_flags(priv); + if (ret < 0) + { + i2serr("ERROR: i2s_dma_flags failed: %d\n", ret); + return 0; + } +#endif + + return 0; +} + +/**************************************************************************** + * Name: stm32_i2s_send + * + * Description: + * Send a block of data on I2S. + * + * Input Parameters: + * dev - Device-specific state data + * apb - A pointer to the audio buffer from which to send data + * callback - A user provided callback function that will be called at + * the completion of the transfer. The callback will be + * performed in the context of the worker thread. + * arg - An opaque argument that will be provided to the callback + * when the transfer complete + * timeout - The timeout value to use. The transfer will be canceled + * and an ETIMEDOUT error will be reported if this timeout + * elapsed without completion of the DMA transfer. Units + * are system clock ticks. Zero means no timeout. + * + * Returned Value: + * OK on success; a negated errno value on failure. NOTE: This function + * only enqueues the transfer and returns immediately. Success here only + * means that the transfer was enqueued correctly. + * + * When the transfer is complete, a 'result' value will be provided as + * an argument to the callback function that will indicate if the transfer + * failed. + * + ****************************************************************************/ + +static int stm32_i2s_send(struct i2s_dev_s *dev, struct ap_buffer_s *apb, + i2s_callback_t callback, void *arg, uint32_t timeout) +{ + struct stm32_i2s_s *priv = (struct stm32_i2s_s *)dev; +#ifdef I2S_HAVE_TX + struct stm32_buffer_s *bfcontainer; + irqstate_t flags; + int ret; +#endif + + /* Make sure that we have valid pointers that that the data has uint32_t + * alignment. + */ + + DEBUGASSERT(priv && apb); + i2sinfo("apb=%p nbytes=%d arg=%p timeout=%d\n", + apb, apb->nbytes - apb->curbyte, arg, timeout); + + i2s_dump_buffer("Sending", &apb->samp[apb->curbyte], + apb->nbytes - apb->curbyte); + DEBUGASSERT(((uintptr_t)&apb->samp[apb->curbyte] & priv->align) == 0); + +#ifdef I2S_HAVE_TX + /* Allocate a buffer container in advance */ + + bfcontainer = i2s_buf_allocate(priv); + DEBUGASSERT(bfcontainer); + + /* Get exclusive access to the I2S driver data */ + + i2s_exclsem_take(priv); + + /* Has the TX channel been enabled? */ + + if (!priv->txenab) + { + i2serr("ERROR: I2S%d has no transmitter\n", priv->i2sno); + ret = -EAGAIN; + goto errout_with_exclsem; + } + + /* Add a reference to the audio buffer */ + + apb_reference(apb); + + /* Initialize the buffer container structure */ + + bfcontainer->callback = (void *)callback; + bfcontainer->timeout = timeout; + bfcontainer->arg = arg; + bfcontainer->apb = apb; + bfcontainer->result = -EBUSY; + + /* Add the buffer container to the end of the TX pending queue */ + + flags = enter_critical_section(); + sq_addlast((sq_entry_t *)bfcontainer, &priv->tx.pend); + + /* Then start the next transfer. If there is already a transfer in progess, + * then this will do nothing. + */ + + ret = i2s_txdma_setup(priv); + DEBUGASSERT(ret == OK); + leave_critical_section(flags); + i2s_exclsem_give(priv); + return OK; + +errout_with_exclsem: + i2s_exclsem_give(priv); + i2s_buf_free(priv, bfcontainer); + return ret; + +#else + i2serr("ERROR: I2S%d has no transmitter\n", priv->i2sno); + UNUSED(priv); + return -ENOSYS; +#endif +} + +/**************************************************************************** + * Name: i2s_mckdivider + * + * Description: + * Setup the MCK divider based on the currently selected data width and + * the sample rate + * + * Input Parameter: + * priv - I2C device structure (only the sample rate and data length is + * needed at this point). + * + * Returned Value: + * The current bitrate + * + ****************************************************************************/ + +static uint32_t i2s_mckdivider(struct stm32_i2s_s *priv) +{ +#ifdef I2S_HAVE_MCK + uint32_t bitrate; + uint32_t regval; + + uint16_t pllr = 5, plln = 256, div = 12, odd = 1; + + DEBUGASSERT(priv && priv->samplerate > 0 && priv->datalen > 0); + + /* A zero sample rate means to disable the MCK/2 clock */ + + if (priv->samplerate == 0) + { + bitrate = 0; + regval = 0; + } + else + { + int R, n, Od; + int Napprox; + int diff; + int diff_min = 500000000; + + for (Od = 0; Od <= 1; ++Od) + { + for (R = 2; R <= 7; ++R) + { + for (n = 2; n <= 256; ++n) + { + Napprox = roundf(priv->samplerate / 1000000.0f * (8 * 32 * R * (2 * n + Od))); + if ((Napprox > 432) || (Napprox < 50)) + { + continue; + } + + diff = abs(priv->samplerate - 1000000 * Napprox / (8 * 32 * R * (2 * n + Od))); + if (diff_min > diff) + { + diff_min = diff; + plln = Napprox; + pllr = R; + div = n; + odd = Od; + } + } + } + } + + /* Calculate the new bitrate in Hz */ + + bitrate = priv->samplerate * priv->datalen; + } + + /* Configure MCK divider */ + + /* Disable I2S */ + + i2s_putreg(priv, STM32_SPI_I2SCFGR_OFFSET, 0); + + /* I2S clock configuration */ + + putreg32((getreg32(STM32_RCC_CR) & (~RCC_CR_PLLI2SON)), STM32_RCC_CR); + + /* PLLI2S clock used as I2S clock source */ + + putreg32(((getreg32(STM32_RCC_CFGR)) & (~RCC_CFGR_I2SSRC)), STM32_RCC_CFGR); + regval = (pllr << 28) | (plln << 6); + putreg32(regval, STM32_RCC_PLLI2SCFGR); + + /* Enable PLLI2S and wait until it is ready */ + + putreg32((getreg32(STM32_RCC_CR) | RCC_CR_PLLI2SON), STM32_RCC_CR); + while (!(getreg32(STM32_RCC_CR) & RCC_CR_PLLI2SRDY)); + + i2s_putreg(priv, STM32_SPI_I2SPR_OFFSET, + div | (odd << 8) | SPI_I2SPR_MCKOE); + i2s_putreg(priv, STM32_SPI_I2SCFGR_OFFSET, + SPI_I2SCFGR_I2SMOD | SPI_I2SCFGR_I2SCFG_MTX | SPI_I2SCFGR_I2SE); + + putreg32(((getreg32(STM32_DMA1_HIFCR)) | 0x80000000 /* DMA_HIFCR_CTCIF7 */), + STM32_DMA1_HIFCR); + + return bitrate; +#else + return 0; +#endif +} + +/**************************************************************************** + * Name: i2s_dma_flags + * + * Description: + * Determine DMA FLAGS based on PID and data width + * + * Input Parameters: + * priv - Partially initialized I2C device structure. + * + * Returned Value: + * OK on success; a negated errno value on failure + * + ****************************************************************************/ + +static int i2s_dma_flags(struct stm32_i2s_s *priv) +{ + switch (priv->datalen) + { + case 8: + /* Reconfigure the RX DMA (and TX DMA if applicable) */ + priv->rxccr = SPI_RXDMA8_CONFIG; + priv->txccr = SPI_TXDMA8_CONFIG; + break; + + case 16: + priv->rxccr = SPI_RXDMA16_CONFIG; + priv->txccr = SPI_TXDMA16_CONFIG; + break; + + default: + i2serr("ERROR: Unsupported data width: %d\n", priv->datalen); + return -ENOSYS; + } + + return OK; +} + +/**************************************************************************** + * Name: i2s_dma_allocate + * + * Description: + * Allocate I2S DMA channels + * + * Input Parameters: + * priv - Partially initialized I2S device structure. This function + * will complete the DMA specific portions of the initialization + * + * Returned Value: + * OK on success; A negated errno value on failure. + * + ****************************************************************************/ + +static int i2s_dma_allocate(struct stm32_i2s_s *priv) +{ + int ret; + + /* Get the DMA flags for this channel */ + + ret = i2s_dma_flags(priv); + if (ret < 0) + { + i2serr("ERROR: i2s_dma_flags failed: %d\n", ret); + return ret; + } + + /* Allocate DMA channels. These allocations exploit that fact that + * I2S2 is managed by DMA1 and I2S3 is managed by DMA2. Hence, + * the I2S number (i2sno) is the same as the DMA number. + */ + +#ifdef I2S_HAVE_RX + if (priv->rxenab) + { + /* Allocate an RX DMA channel */ + + priv->rx.dma = stm32_dmachannel(DMAMAP_SPI3_RX_2); + if (!priv->rx.dma) + { + i2serr("ERROR: Failed to allocate the RX DMA channel\n"); + goto errout; + } + + /* Create a watchdog time to catch RX DMA timeouts */ + + priv->rx.dog = wd_create(); + if (!priv->rx.dog) + { + i2serr("ERROR: Failed to create the RX DMA watchdog\n"); + goto errout; + } + } +#endif + +#ifdef I2S_HAVE_TX + if (priv->txenab) + { + /* Allocate a TX DMA channel */ + + priv->tx.dma = stm32_dmachannel(DMAMAP_SPI3_TX_2); + if (!priv->tx.dma) + { + i2serr("ERROR: Failed to allocate the TX DMA channel\n"); + goto errout; + } + + /* Create a watchdog time to catch TX DMA timeouts */ + + priv->tx.dog = wd_create(); + if (!priv->tx.dog) + { + i2serr("ERROR: Failed to create the TX DMA watchdog\n"); + goto errout; + } + } +#endif + + /* Success exit */ + + return OK; + + /* Error exit */ + +errout: + i2s_dma_free(priv); + return -ENOMEM; +} + +/**************************************************************************** + * Name: i2s_dma_free + * + * Description: + * Release DMA-related resources allocated by i2s_dma_allocate() + * + * Input Parameters: + * priv - Partially initialized I2C device structure. + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void i2s_dma_free(struct stm32_i2s_s *priv) +{ +#ifdef I2S_HAVE_TX + if (priv->tx.dog) + { + wd_delete(priv->tx.dog); + } + + if (priv->tx.dma) + { + stm32_dmafree(priv->tx.dma); + } +#endif + +#ifdef I2S_HAVE_RX + if (priv->rx.dog) + { + wd_delete(priv->rx.dog); + } + + if (priv->rx.dma) + { + stm32_dmafree(priv->rx.dma); + } +#endif +} + +/**************************************************************************** + * Name: i2s2_configure + * + * Description: + * Configure I2S2 + * + * Input Parameters: + * priv - Partially initialized I2C device structure. These functions + * will complete the I2S specific portions of the initialization + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_STM32_I2S2 +static void i2s2_configure(struct stm32_i2s_s *priv) +{ + /* Configure multiplexed pins as connected on the board. Chip + * select pins must be selected by board-specific logic. + */ + + priv->base = STM32_I2S2_BASE; + +#ifdef CONFIG_STM32_I2S2_RX + priv->rxenab = true; + + if ((i2s_getreg(priv, STM32_SPI_CR1_OFFSET) & SPI_CR1_SPE) == 0) + { + /* Configure I2S2 pins: MCK, SD, CK, WS */ + + stm32_configgpio(GPIO_I2S2_MCK); + stm32_configgpio(GPIO_I2S2_SD); + stm32_configgpio(GPIO_I2S2_CK); + stm32_configgpio(GPIO_I2S2_WS); + } +#endif /* CONFIG_STM32_I2S2_RX */ + +#ifdef CONFIG_STM32_I2S2_TX + priv->txenab = true; + + /* Only configure if the port is not already configured */ + + if ((i2s_getreg(priv, STM32_SPI_CR1_OFFSET) & SPI_CR1_SPE) == 0) + { + /* Configure I2S2 pins: MCK, SD, CK, WS */ + + stm32_configgpio(GPIO_I2S2_MCK); + stm32_configgpio(GPIO_I2S2_SD); + stm32_configgpio(GPIO_I2S2_CK); + stm32_configgpio(GPIO_I2S2_WS); + } +#endif /* CONFIG_STM32_I2S2_TX */ + + /* Configure driver state specific to this I2S peripheral */ + + priv->datalen = CONFIG_STM32_I2S2_DATALEN; +#ifdef CONFIG_DEBUG + priv->align = STM32_I2S2_DATAMASK; +#endif +} +#endif /* CONFIG_STM32_I2S2 */ + +/**************************************************************************** + * Name: i2s3_configure + * + * Description: + * Configure I2S3 + * + * Input Parameters: + * priv - Partially initialized I2C device structure. These functions + * will complete the I2S specific portions of the initialization + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_STM32_I2S3 +static void i2s3_configure(struct stm32_i2s_s *priv) +{ + /* Configure multiplexed pins as connected on the board. Chip + * select pins must be selected by board-specific logic. + */ + + priv->base = STM32_I2S3_BASE; + +#ifdef CONFIG_STM32_I2S3_RX + priv->rxenab = true; + + if ((i2s_getreg(priv, STM32_SPI_CR1_OFFSET) & SPI_CR1_SPE) == 0) + { + /* Configure I2S3 pins: MCK, SD, CK, WS */ + + stm32_configgpio(GPIO_I2S3_MCK); + stm32_configgpio(GPIO_I2S3_SD); + stm32_configgpio(GPIO_I2S3_CK); + stm32_configgpio(GPIO_I2S3_WS); + } +#endif /* CONFIG_STM32_I2S3_RX */ + +#ifdef CONFIG_STM32_I2S3_TX + priv->txenab = true; + + /* Only configure if the port is not already configured */ + + if ((i2s_getreg(priv, STM32_SPI_CR1_OFFSET) & SPI_CR1_SPE) == 0) + { + /* Configure I2S3 pins: MCK, SD, CK, WS */ + + stm32_configgpio(GPIO_I2S3_MCK); + stm32_configgpio(GPIO_I2S3_SD); + stm32_configgpio(GPIO_I2S3_CK); + stm32_configgpio(GPIO_I2S3_WS); + } +#endif /* CONFIG_STM32_I2S3_TX */ + + /* Configure driver state specific to this I2S peripheral */ + + priv->datalen = CONFIG_STM32_I2S3_DATALEN; +#ifdef CONFIG_DEBUG + priv->align = STM32_I2S3_DATAMASK; +#endif +} +#endif /* CONFIG_STM32_I2S3 */ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/************************************************************************************ + * Name: stm32_i2sdev_initialize + * + * Description: + * Initialize the selected i2S port + * + * Input Parameter: + * Port number (for hardware that has mutiple I2S interfaces) + * + * Returned Value: + * Valid I2S device structure reference on succcess; a NULL on failure + * + ************************************************************************************/ + +FAR struct i2s_dev_s *stm32_i2sdev_initialize(int port) +{ + FAR struct stm32_i2s_s *priv = NULL; + irqstate_t flags; + int ret; + + /* The support STM32 parts have only a single I2S port */ + + i2sinfo("port: %d\n", port); + + /* Allocate a new state structure for this chip select. NOTE that there + * is no protection if the same chip select is used in two different + * chip select structures. + */ + + priv = (struct stm32_i2s_s *)zalloc(sizeof(struct stm32_i2s_s)); + if (!priv) + { + i2serr("ERROR: Failed to allocate a chip select structure\n"); + return NULL; + } + + /* Set up the initial state for this chip select structure. Other fields + * were zeroed by zalloc(). + */ + + /* Initialize the common parts for the I2S device structure */ + + sem_init(&priv->exclsem, 0, 1); + priv->dev.ops = &g_i2sops; + priv->i2sno = port; + + /* Initialize buffering */ + + i2s_buf_initialize(priv); + + flags = enter_critical_section(); + +#ifdef CONFIG_STM32_I2S2 + if (port == 2) + { + /* Select I2S2 */ + + i2s2_configure(priv); + } + else +#endif +#ifdef CONFIG_STM32_I2S3 + if (port == 3) + { + /* Select I2S3 */ + + i2s3_configure(priv); + } + else +#endif + { + i2serr("ERROR: Unsupported I2S port: %d\n", port); + return NULL; + } + + /* Allocate DMA channels */ + + ret = i2s_dma_allocate(priv); + if (ret < 0) + { + goto errout_with_alloc; + } + + leave_critical_section(flags); + i2s_dump_regs(priv, "After initialization"); + + /* Success exit */ + + return &priv->dev; + + /* Failure exits */ + +errout_with_alloc: + sem_destroy(&priv->exclsem); + kmm_free(priv); + return NULL; +} +#endif /* I2S_HAVE_RX || I2S_HAVE_TX */ + +#endif /* CONFIG_STM32_I2S2 || CONFIG_STM32_I2S3 */ diff --git a/arch/arm/src/stm32/stm32_i2s.h b/arch/arm/src/stm32/stm32_i2s.h new file mode 100644 index 0000000000..5e6d51b817 --- /dev/null +++ b/arch/arm/src/stm32/stm32_i2s.h @@ -0,0 +1,90 @@ +/************************************************************************************ + * arch/arm/src/stm32/stm32_i2s.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32_I2S_H +#define __ARCH_ARM_SRC_STM32_I2S_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include + +#include "chip.h" +#include "chip/stm32_i2s.h" + +#ifndef __ASSEMBLY__ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_i2sdev_initialize + * + * Description: + * Initialize the selected I2S port + * + * Input Parameter: + * Port number (for hardware that has mutiple I2S interfaces) + * + * Returned Value: + * Valid I2S device structure reference on succcess; a NULL on failure + * + ************************************************************************************/ + +FAR struct i2s_dev_s *stm32_i2sdev_initialize(int port); + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __ARCH_ARM_SRC_STM32_I2S_H */ diff --git a/configs/stm32f4discovery/include/board.h b/configs/stm32f4discovery/include/board.h index 805d5f6ce1..91077e674f 100644 --- a/configs/stm32f4discovery/include/board.h +++ b/configs/stm32f4discovery/include/board.h @@ -300,9 +300,9 @@ /* SPI - There is a MEMS device on SPI1 using these pins: */ -#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 -#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 -#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1 +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 +#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1 /* SPI2 - Test MAX31855 on SPI2 PB10 = SCK, PB14 = MISO */ @@ -310,10 +310,38 @@ #define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1 #define GPIO_SPI2_SCK GPIO_SPI2_SCK_1 +/* SPI3 - Onboard devices use SPI3 */ + +#define GPIO_SPI3_MISO GPIO_SPI3_MISO_2 +#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_2 +#define GPIO_SPI3_SCK GPIO_SPI3_SCK_2 +#define GPIO_SPI3_NSS GPIO_SPI3_NSS_2 + +/* I2S3 - Onboard devices use I2S3 */ + +#define GPIO_I2S3_SD GPIO_I2S3_SD_2 +#define GPIO_I2S3_CK GPIO_I2S3_CK_2 +#define GPIO_I2S3_WS GPIO_I2S3_WS_1 + +#define DMACHAN_SPI3_RX DMAMAP_SPI3_RX_2 +#define DMACHAN_SPI3_TX DMAMAP_SPI3_TX_2 + /* I2C config to use with Nunchuk PB7 (SDA) and PB8 (SCL) */ +#if 0 #define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 #define GPIO_I2C1_SDA GPIO_I2C1_SDA_1 +#endif + +/* I2C. Only I2C1 is available on the stm32f4discovery. I2C1_SCL and I2C1_SDA are + * available on the following pins: + * + * - PB6 is I2C1_SCL + * - PB9 is I2C1_SDA + */ + +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_1 +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* Timer Inputs/Outputs (see the README.txt file for options) */ diff --git a/configs/stm32f4discovery/src/Makefile b/configs/stm32f4discovery/src/Makefile index d51d09ce1d..d7154251b3 100644 --- a/configs/stm32f4discovery/src/Makefile +++ b/configs/stm32f4discovery/src/Makefile @@ -44,6 +44,10 @@ else CSRCS += stm32_userleds.c endif +ifeq ($(CONFIG_AUDIO_CS43L22),y) +CSRCS += stm32_cs43l22.c +endif + ifeq ($(CONFIG_ARCH_BUTTONS),y) CSRCS += stm32_buttons.c endif diff --git a/configs/stm32f4discovery/src/stm32_bringup.c b/configs/stm32f4discovery/src/stm32_bringup.c index e360c8cc0c..042c3386fc 100644 --- a/configs/stm32f4discovery/src/stm32_bringup.c +++ b/configs/stm32f4discovery/src/stm32_bringup.c @@ -216,6 +216,16 @@ int stm32_bringup(void) } #endif +#ifdef HAVE_CS43L22 + /* Configure CS43L22 audio */ + + ret = stm32_cs43l22_initialize(1); + if (ret != OK) + { + serr("Failed to initialize CS43L22 audio: %d\n", ret); + } +#endif + #ifdef HAVE_ELF /* Initialize the ELF binary loader */ diff --git a/configs/stm32f4discovery/src/stm32_cs43l22.c b/configs/stm32f4discovery/src/stm32_cs43l22.c new file mode 100644 index 0000000000..156458ead8 --- /dev/null +++ b/configs/stm32f4discovery/src/stm32_cs43l22.c @@ -0,0 +1,389 @@ +/************************************************************************************ + * configs/stm32f4discovery/src/stm32_cs43l22.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Taras Drozdovskiy + * + * 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 + +#include + +#include "stm32.h" +#include "stm32f4discovery.h" + +#ifdef HAVE_CS43L22 + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct stm32_mwinfo_s +{ + /* Standard CS43L22 interface */ + + struct cs43l22_lower_s lower; + + /* Extensions for the stm32f4discovery board */ + + cs43l22_handler_t handler; + FAR void *arg; +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* IRQ/PIO access callbacks. These operations all hidden behind + * callbacks to isolate the CS43L22 driver from differences in PIO + * interrupt handling by varying boards and MCUs. If possible, + * interrupts should be configured on both rising and falling edges + * so that contact and loss-of-contact events can be detected. + * + * attach - Attach the CS43L22 interrupt handler to the PIO interrupt + * enable - Enable or disable the PIO interrupt + */ + +static int cs43l22_attach(FAR const struct cs43l22_lower_s *lower, + cs43l22_handler_t isr, FAR void *arg); +static bool cs43l22_enable(FAR const struct cs43l22_lower_s *lower, + bool enable); +static void cs43l22_hw_reset(FAR const struct cs43l22_lower_s *lower); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* A reference to a structure of this type must be passed to the CS43L22 + * driver. This structure provides information about the configuration + * of the CS43L22 and provides some board-specific hooks. + * + * Memory for this structure is provided by the caller. It is not copied + * by the driver and is presumed to persist while the driver is active. + */ + +#define CONFIG_STM32_CS43L22_I2CFREQUENCY 100000 +#define BOARD_MAINCK_FREQUENCY 8000000 + +static struct stm32_mwinfo_s g_cs43l22info = +{ + .lower = + { + .address = CS43L22_I2C_ADDRESS, + .frequency = CONFIG_STM32_CS43L22_I2CFREQUENCY, +#ifdef CONFIG_STM32_CS43L22_SRCSCK + .mclk = BOARD_SLOWCLK_FREQUENCY, +#else + .mclk = BOARD_MAINCK_FREQUENCY, +#endif + .attach = cs43l22_attach, + .enable = cs43l22_enable, + .reset = cs43l22_hw_reset, + }, +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * IRQ/PIO access callbacks. These operations all hidden behind + * callbacks to isolate the CS43L22 driver from differences in PIO + * interrupt handling by varying boards and MCUs. If possible, + * interrupts should be configured on both rising and falling edges + * so that contact and loss-of-contact events can be detected. + * + * attach - Attach the CS43L22 interrupt handler to the PIO interrupt + * enable - Enable or disable the PIO interrupt + * clear - Acknowledge/clear any pending PIO interrupt + * + ****************************************************************************/ + +static int cs43l22_attach(FAR const struct cs43l22_lower_s *lower, + cs43l22_handler_t isr, FAR void *arg) +{ + if (isr) + { + /* Just save the address of the handler and its argument for now. The + * new handler will called via cs43l22_interrupt() when the interrupt occurs. + */ + + audinfo("Attaching %p\n", isr); + g_cs43l22info.handler = isr; + g_cs43l22info.arg = arg; + } + else + { + audinfo("Detaching %p\n", g_cs43l22info.handler); + (void)cs43l22_enable(lower, false); + g_cs43l22info.handler = NULL; + g_cs43l22info.arg = NULL; + } + + return OK; +} + +static bool cs43l22_enable(FAR const struct cs43l22_lower_s *lower, bool enable) +{ + static bool enabled; + irqstate_t flags; + bool ret; + + /* Has the interrupt state changed */ + + flags = enter_critical_section(); + if (enable != enabled) + { + /* Enable or disable interrupts */ + + if (enable && g_cs43l22info.handler) + { + audinfo("Enabling\n"); + /* TODO: stm32_pioirqenable(IRQ_INT_CS43L22); */ + enabled = true; + } + else + { + + audinfo("Disabling\n"); + /* TODO: stm32_pioirqdisable(IRQ_INT_CS43L22); */ + enabled = false; + } + } + + ret = enabled; + leave_critical_section(flags); + return ret; +} + +#if 0 +static int cs43l22_interrupt(int irq, FAR void *context) +{ + Just forward the interrupt to the CS43L22 driver + + audinfo("handler %p\n", g_cs43l22info.handler); + if (g_cs43l22info.handler) + { + return g_cs43l22info.handler(&g_cs43l22info.lower, g_cs43l22info.arg); + } + + We got an interrupt with no handler. This should not + happen. + + TODO: stm32_pioirqdisable(IRQ_INT_CS43L22); + return OK; +} +#endif + +static void cs43l22_hw_reset(FAR const struct cs43l22_lower_s *lower) +{ + int i; + + /* Reset the codec */ + + stm32_gpiowrite(GPIO_CS43L22_RESET, false); + for (i = 0; i < 0x4fff; i++) + { + __asm__ volatile("nop"); + } + + stm32_gpiowrite(GPIO_CS43L22_RESET, true); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_cs43l22_initialize + * + * Description: + * This function is called by platform-specific, setup logic to configure + * and register the CS43L22 device. This function will register the driver + * as /dev/audio/pcm[x] where x is determined by the minor device number. + * + * Input Parameters: + * minor - The input device minor number + * + * Returned Value: + * Zero is returned on success. Otherwise, a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +int stm32_cs43l22_initialize(int minor) +{ + FAR struct audio_lowerhalf_s *cs43l22; + FAR struct audio_lowerhalf_s *pcm; + FAR struct i2c_master_s *i2c; + FAR struct i2s_dev_s *i2s; + static bool initialized = false; + char devname[12]; + int ret; + + audinfo("minor %d\n", minor); + DEBUGASSERT(minor >= 0 && minor <= 25); + + /* Have we already initialized? Since we never uninitialize we must prevent + * multiple initializations. This is necessary, for example, when the + * touchscreen example is used as a built-in application in NSH and can be + * called numerous time. It will attempt to initialize each time. + */ + + if (!initialized) + { + stm32_configgpio(GPIO_CS43L22_RESET); + + /* Configure the CS43L22 interrupt pin */ + + /* TODO: (void)stm32_configgpio(PIO_INT_CS43L22); */ + + /* Get an instance of the I2C interface for the CS43L22 chip select */ + + i2c = stm32_i2cbus_initialize(CS43L22_I2C_BUS); + if (!i2c) + { + auderr("ERROR: Failed to initialize TWI%d\n", CS43L22_I2C_BUS); + ret = -ENODEV; + goto errout; + } + /* Get an instance of the I2S interface for the CS43L22 data channel */ + + i2s = stm32_i2sdev_initialize(CS43L22_I2S_BUS); + if (!i2s) + { + auderr("ERROR: Failed to initialize I2S%d\n", CS43L22_I2S_BUS); + ret = -ENODEV; + goto errout_with_i2c; + } + + /* Configure the DAC master clock. This clock is provided by PCK2 (PB10) + * that is connected to the CS43L22 MCLK. + */ + + /* Configure CS43L22 interrupts */ + +#if 0 /* TODO: */ + stm32_pioirq(PIO_INT_CS43L22); + ret = irq_attach(IRQ_INT_CS43L22, cs43l22_interrupt); + if (ret < 0) + { + auderr("ERROR: Failed to attach CS43L22 interrupt: %d\n", ret); + goto errout_with_i2s; + } +#endif + + /* Now we can use these I2C and I2S interfaces to initialize the + * CS43L22 which will return an audio interface. + */ + + cs43l22 = cs43l22_initialize(i2c, i2s, &g_cs43l22info.lower); + if (!cs43l22) + { + auderr("ERROR: Failed to initialize the CS43L22\n"); + ret = -ENODEV; + goto errout_with_irq; + } + /* No we can embed the CS43L22/I2C/I2S conglomerate into a PCM decoder + * instance so that we will have a PCM front end for the the CS43L22 + * driver. + */ + + pcm = pcm_decode_initialize(cs43l22); + if (!pcm) + { + auderr("ERROR: Failed create the PCM decoder\n"); + ret = -ENODEV; + goto errout_with_cs43l22; + } + /* Create a device name */ + + snprintf(devname, 12, "pcm%d", minor); + + /* Finally, we can register the PCM/CS43L22/I2C/I2S audio device. + * + * Is anyone young enough to remember Rube Goldberg? + */ + + ret = audio_register(devname, pcm); + if (ret < 0) + { + auderr("ERROR: Failed to register /dev/%s device: %d\n", + devname, ret); + goto errout_with_pcm; + } + + /* Now we are initialized */ + + initialized = true; + } + + return OK; + + /* Error exits. Unfortunately there is no mechanism in place now to + * recover resources from most errors on initialization failures. + */ + +errout_with_pcm: +errout_with_cs43l22: +errout_with_irq: + +#if 0 + irq_detach(IRQ_INT_CS43L22); +errout_with_i2s: +#endif + +errout_with_i2c: +errout: + return ret; +} + +#endif /* HAVE_CS43L22 */ diff --git a/configs/stm32f4discovery/src/stm32f4discovery.h b/configs/stm32f4discovery/src/stm32f4discovery.h index 75892830ad..ebb618095e 100644 --- a/configs/stm32f4discovery/src/stm32f4discovery.h +++ b/configs/stm32f4discovery/src/stm32f4discovery.h @@ -77,6 +77,7 @@ #define HAVE_USBHOST 1 #define HAVE_USBMONITOR 1 #define HAVE_SDIO 1 +#define HAVE_CS43L22 1 #define HAVE_RTC_DRIVER 1 #define HAVE_ELF 1 #define HAVE_NETMONITOR 1 @@ -148,6 +149,26 @@ # endif #endif +/* The CS43L22 depends on the CS43L22 driver, I2C1, and I2S3 support */ + +#if !defiend(CONFIG_AUDIO_CS43L22) || !defined(CONFIG_STM32_I2C1) || \ + !defined(CONFIG_STM32_I2S3) +# undef HAVE_CS43L22 +#endif + +#ifdef HAVE_CS43L22 + /* The CS43L22 communicates on I2C1, I2C address 0x1a for control + * operations + */ + +# define CS43L22_I2C_BUS 1 +# define CS43L22_I2C_ADDRESS (0x94 >> 1) + + /* The CS43L22 transfers data on I2S3 */ + +# define CS43L22_I2S_BUS 3 +#endif + /* Check if we can support the RTC driver */ #if !defined(CONFIG_RTC) || !defined(CONFIG_RTC_DRIVER) @@ -216,6 +237,8 @@ #define GPIO_ZEROCROSS (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN0) +#define GPIO_CS43L22_RESET (GPIO_OUTPUT|GPIO_SPEED_50MHz|GPIO_PORTD|GPIO_PIN4) + /* PWM * * The STM32F4 Discovery has no real on-board PWM devices, but the board can be @@ -369,6 +392,17 @@ void weak_function stm32_spidev_initialize(void); + /**************************************************************************** + * Name: stm32_i2sdev_initialize + * + * Description: + * Called to configure I2S chip select GPIO pins for the stm32f4discovery + * board. + * + ****************************************************************************/ + + FAR struct i2s_dev_s *stm32_i2sdev_initialize(int port); + /**************************************************************************** * Name: stm32_bh1750initialize * @@ -608,6 +642,27 @@ int stm32_zerocross_initialize(void); int stm32_max6675initialize(FAR const char *devpath); #endif +/**************************************************************************** + * Name: stm32_cs43l22_initialize + * + * Description: + * This function is called by platform-specific, setup logic to configure + * and register the CS43L22 device. This function will register the driver + * as /dev/cs43l22[x] where x is determined by the minor device number. + * + * Input Parameters: + * minor - The input device minor number + * + * Returned Value: + * Zero is returned on success. Otherwise, a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +#ifdef HAVE_CS43L22 +int stm32_cs43l22_initialize(int minor); +#endif /* HAVE_CS43L22 */ + /**************************************************************************** * Name: stm32_pca9635_initialize * diff --git a/drivers/audio/Kconfig b/drivers/audio/Kconfig index ade8bc9375..3de9d1f60a 100644 --- a/drivers/audio/Kconfig +++ b/drivers/audio/Kconfig @@ -95,6 +95,67 @@ endif # AUDIO_DRIVER_SPECIFIC_BUFFERS endif # VS1053 +config AUDIO_CS43L22 + bool "CS43L22 audio chip" + default n + depends on AUDIO + ---help--- + Select to enable support for the CS43L22 Audio codec by Cirrus Logic. + This chip is a lower level audio chip.. basically + an exotic D-to-A. It includes no built-in support for audio CODECS + The CS43L22 provides: + + - Low power consumption + - High SNR + - Stereo digital microphone input + - Digital Dynamic Range Controller (compressor / limiter) + - Digital sidetone mixing + - Ground-referenced headphone driver + - Ground-referenced line outputs + + NOTE: This driver also depends on both I2C and I2S support although + that dependency is not explicit here. + +if AUDIO_CS43L22 + +config CS43L22_INITVOLUME + int "CS43L22 initial volume setting" + default 250 + +config CS43L22_INFLIGHT + int "CS43L22 maximum in-flight audio buffers" + default 2 + +config CS43L22_MSG_PRIO + int "CS43L22 message priority" + default 1 + +config CS43L22_BUFFER_SIZE + int "CS43L22 preferred buffer size" + default 8192 + +config CS43L22_NUM_BUFFERS + int "CS43L22 preferred number of buffers" + default 4 + +config CS43L22_WORKER_STACKSIZE + int "CS43L22 worker thread stack size" + default 768 + +config CS43L22_REGDUMP + bool "CS43L22 register dump" + default n + ---help--- + Enable logic to dump the contents of all CS43L22 registers. + +config CS43L22_CLKDEBUG + bool "CS43L22 clock analysis" + default n + ---help--- + Enable logic to analyze CS43L22 clock configuation. + +endif # AUDIO_CS43L22 + config AUDIO_WM8904 bool "WM8904 audio chip" default n diff --git a/drivers/audio/Make.defs b/drivers/audio/Make.defs index 5932714f6d..96db396860 100644 --- a/drivers/audio/Make.defs +++ b/drivers/audio/Make.defs @@ -43,6 +43,17 @@ ifeq ($(CONFIG_VS1053),y) CSRCS += vs1053.c endif +ifeq ($(CONFIG_AUDIO_CS43L22),y) +CSRCS += cs43l22.c +ifeq ($(CONFIG_CS43L22_REGDUMP),y) +CSRCS += cs43l22_debug.c +else +ifeq ($(CONFIG_CS43L22_CLKDEBUG),y) +CSRCS += cs43l22_debug.c +endif +endif +endif + ifeq ($(CONFIG_AUDIO_WM8904),y) CSRCS += wm8904.c ifeq ($(CONFIG_WM8904_REGDUMP),y) diff --git a/drivers/audio/cs43l22.c b/drivers/audio/cs43l22.c new file mode 100644 index 0000000000..239144c6da --- /dev/null +++ b/drivers/audio/cs43l22.c @@ -0,0 +1,1959 @@ +/**************************************************************************** + * drivers/audio/cs43l22.c + * Audio device driver for Cirrus logic CS43L22 Audio codec. + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Taras Drozdovskiy + * + * 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 + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "cs43l22.h" + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +#if !defined(CONFIG_CS43L22_REGDUMP) && !defined(CONFIG_CS43L22_CLKDEBUG) +static +#endif +uint8_t cs43l22_readreg(FAR struct cs43l22_dev_s *priv, uint8_t regaddr); +static void cs43l22_writereg(FAR struct cs43l22_dev_s *priv, uint8_t regaddr, + uint8_t regval); +static void cs43l22_takesem(sem_t * sem); +#define cs43l22_givesem(s) sem_post(s) + +#ifndef CONFIG_AUDIO_EXCLUDE_VOLUME +static inline uint16_t cs43l22_scalevolume(uint16_t volume, b16_t scale); +static void cs43l22_setvolume(FAR struct cs43l22_dev_s *priv, uint16_t volume, + bool mute); +#endif +#ifndef CONFIG_AUDIO_EXCLUDE_TONE +static void cs43l22_setbass(FAR struct cs43l22_dev_s *priv, uint8_t bass); +static void cs43l22_settreble(FAR struct cs43l22_dev_s *priv, uint8_t treble); +#endif + +static void cs43l22_setdatawidth(FAR struct cs43l22_dev_s *priv); +static void cs43l22_setbitrate(FAR struct cs43l22_dev_s *priv); + +/* Audio lower half methods (and close friends) */ + +static int cs43l22_getcaps(FAR struct audio_lowerhalf_s *dev, int type, + FAR struct audio_caps_s *caps); +#ifdef CONFIG_AUDIO_MULTI_SESSION +static int cs43l22_configure(FAR struct audio_lowerhalf_s *dev, + FAR void *session, + FAR const struct audio_caps_s *caps); +#else +static int cs43l22_configure(FAR struct audio_lowerhalf_s *dev, + FAR const struct audio_caps_s *caps); +#endif +static int cs43l22_shutdown(FAR struct audio_lowerhalf_s *dev); +static void cs43l22_senddone(FAR struct i2s_dev_s *i2s, + FAR struct ap_buffer_s *apb, FAR void *arg, + int result); +static void cs43l22_returnbuffers(FAR struct cs43l22_dev_s *priv); +static int cs43l22_sendbuffer(FAR struct cs43l22_dev_s *priv); + +#ifdef CONFIG_AUDIO_MULTI_SESSION +static int cs43l22_start(FAR struct audio_lowerhalf_s *dev, FAR void *session); +#else +static int cs43l22_start(FAR struct audio_lowerhalf_s *dev); +#endif +#ifndef CONFIG_AUDIO_EXCLUDE_STOP +#ifdef CONFIG_AUDIO_MULTI_SESSION +static int cs43l22_stop(FAR struct audio_lowerhalf_s *dev, FAR void *session); +#else +static int cs43l22_stop(FAR struct audio_lowerhalf_s *dev); +#endif +#endif +#ifndef CONFIG_AUDIO_EXCLUDE_PAUSE_RESUME +#ifdef CONFIG_AUDIO_MULTI_SESSION +static int cs43l22_pause(FAR struct audio_lowerhalf_s *dev, FAR void *session); +static int cs43l22_resume(FAR struct audio_lowerhalf_s *dev, FAR void *session); +#else +static int cs43l22_pause(FAR struct audio_lowerhalf_s *dev); +static int cs43l22_resume(FAR struct audio_lowerhalf_s *dev); +#endif +#endif +static int cs43l22_enqueuebuffer(FAR struct audio_lowerhalf_s *dev, + FAR struct ap_buffer_s *apb); +static int cs43l22_cancelbuffer(FAR struct audio_lowerhalf_s *dev, + FAR struct ap_buffer_s *apb); +static int cs43l22_ioctl(FAR struct audio_lowerhalf_s *dev, int cmd, + unsigned long arg); +#ifdef CONFIG_AUDIO_MULTI_SESSION +static int cs43l22_reserve(FAR struct audio_lowerhalf_s *dev, + FAR void **session); +#else +static int cs43l22_reserve(FAR struct audio_lowerhalf_s *dev); +#endif +#ifdef CONFIG_AUDIO_MULTI_SESSION +static int cs43l22_release(FAR struct audio_lowerhalf_s *dev, + FAR void *session); +#else +static int cs43l22_release(FAR struct audio_lowerhalf_s *dev); +#endif + +/* Interrupt handling an worker thread */ + +#ifdef CS43L22_USE_FFLOCK_INT +static void cs43l22_interrupt_work(FAR void *arg); +static int cs43l22_interrupt(FAR const struct cs43l22_lower_s *lower, + FAR void *arg); +#endif + +static void *cs43l22_workerthread(pthread_addr_t pvarg); + +/* Initialization */ + +static void cs43l22_audio_output(FAR struct cs43l22_dev_s *priv); +#if 0 /* Not used */ +static void cs43l22_audio_input(FAR struct cs43l22_dev_s *priv); +#endif +#ifdef CS43L22_USE_FFLOCK_INT +static void cs43l22_configure_ints(FAR struct cs43l22_dev_s *priv); +#else +# define cs43l22_configure_ints(p) +#endif +static void cs43l22_reset(FAR struct cs43l22_dev_s *priv); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const struct audio_ops_s g_audioops = +{ + cs43l22_getcaps, /* getcaps */ + cs43l22_configure, /* configure */ + cs43l22_shutdown, /* shutdown */ + cs43l22_start, /* start */ +#ifndef CONFIG_AUDIO_EXCLUDE_STOP + cs43l22_stop, /* stop */ +#endif +#ifndef CONFIG_AUDIO_EXCLUDE_PAUSE_RESUME + cs43l22_pause, /* pause */ + cs43l22_resume, /* resume */ +#endif + NULL, /* allocbuffer */ + NULL, /* freebuffer */ + cs43l22_enqueuebuffer, /* enqueue_buffer */ + cs43l22_cancelbuffer, /* cancel_buffer */ + cs43l22_ioctl, /* ioctl */ + NULL, /* read */ + NULL, /* write */ + cs43l22_reserve, /* reserve */ + cs43l22_release /* release */ +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: cs43l22_readreg + * + * Description + * Read the specified 16-bit register from the CS43L22 device. + * + ****************************************************************************/ + +#if !defined(CONFIG_CS43L22_REGDUMP) && !defined(CONFIG_CS43L22_CLKDEBUG) +static +#endif +uint8_t cs43l22_readreg(FAR struct cs43l22_dev_s *priv, uint8_t regaddr) +{ + int retries; + + /* Try up to three times to read the register */ + + for (retries = 1; retries <= 3; retries++) + { + struct i2c_msg_s msg[2]; + uint8_t data; + int ret; + + /* Set up to write the address */ + + msg[0].frequency = priv->lower->frequency; + msg[0].addr = priv->lower->address; + msg[0].flags = 0; + msg[0].buffer = ®addr; + msg[0].length = 1; + + /* Followed by the read data */ + + msg[1].frequency = priv->lower->frequency; + msg[1].addr = priv->lower->address; + msg[1].flags = I2C_M_READ; + msg[1].buffer = &data; + msg[1].length = 12; + + /* Read the register data. The returned value is the number messages + * completed. + */ + + ret = I2C_TRANSFER(priv->i2c, msg, 2); + if (ret < 0) + { +#ifdef CONFIG_I2C_RESET + /* Perhaps the I2C bus is locked up? Try to shake the bus free */ + + audwarn("WARNING: I2C_TRANSFER failed: %d ... Resetting\n", ret); + + ret = I2C_RESET(priv->i2c); + if (ret < 0) + { + auderr("ERROR: I2C_RESET failed: %d\n", ret); + break; + } +#else + auderr("ERROR: I2C_TRANSFER failed: %d\n", ret); +#endif + } + else + { + + /* The I2C transfer was successful... break out of the loop and + * return the value read. + */ + + audinfo("Read: %02x -> %02x\n", regaddr, data); + return data; + } + + audinfo("retries=%d regaddr=%02x\n", retries, regaddr); + } + + /* No error indication is returned on a failure... just return zero */ + + return 0; +} + +/************************************************************************************ + * Name: cs43l22_writereg + * + * Description: + * Write the specified 16-bit register to the CS43L22 device. + * + ************************************************************************************/ + +static void +cs43l22_writereg(FAR struct cs43l22_dev_s *priv, uint8_t regaddr, + uint8_t regval) +{ + struct i2c_config_s config; + int retries; + + /* Setup up the I2C configuration */ + + config.frequency = priv->lower->frequency; + config.address = priv->lower->address; + config.addrlen = 7; + + /* Try up to three times to read the register */ + + for (retries = 1; retries <= 3; retries++) + { + uint8_t data[2]; + int ret; + + /* Set up the data to write */ + + data[0] = regaddr; + data[1] = regval; + + /* Read the register data. The returned value is the number messages + * completed. + */ + + ret = i2c_write(priv->i2c, &config, data, 2); + if (ret < 0) + { +#ifdef CONFIG_I2C_RESET + /* Perhaps the I2C bus is locked up? Try to shake the bus free */ + + audwarn("WARNING: i2c_write failed: %d ... Resetting\n", ret); + + ret = I2C_RESET(priv->i2c); + if (ret < 0) + { + auderr("ERROR: I2C_RESET failed: %d\n", ret); + break; + } +#else + auderr("ERROR: I2C_TRANSFER failed: %d\n", ret); +#endif + } + else + { + /* The I2C transfer was successful... break out of the loop and + * return the value read. + */ + + audinfo("Write: %02x <- %02x\n", regaddr, regval); + return; + } + + audinfo("retries=%d regaddr=%02x\n", retries, regaddr); + } +} + +/************************************************************************************ + * Name: cs43l22_takesem + * + * Description: + * Take a semaphore count, handling the nasty EINTR return if we are interrupted + * by a signal. + * + ************************************************************************************/ + +static void cs43l22_takesem(sem_t * sem) +{ + int ret; + + do + { + ret = sem_wait(sem); + DEBUGASSERT(ret == 0 || errno == EINTR); + } + while (ret < 0); +} + +/************************************************************************************ + * Name: cs43l22_scalevolume + * + * Description: + * Set the right and left volume values in the CS43L22 device based on the current + * volume and balance settings. + * + ************************************************************************************/ + +#ifndef CONFIG_AUDIO_EXCLUDE_VOLUME +static inline uint16_t cs43l22_scalevolume(uint16_t volume, b16_t scale) +{ + return b16toi((b16_t) volume * scale); +} +#endif + +/************************************************************************************ + * Name: cs43l22_setvolume + * + * Description: + * Set the right and left volume values in the CS43L22 device based on the current + * volume and balance settings. + * + ************************************************************************************/ + +#ifndef CONFIG_AUDIO_EXCLUDE_VOLUME +static void +cs43l22_setvolume(FAR struct cs43l22_dev_s *priv, uint16_t volume, bool mute) +{ + uint32_t leftlevel; + uint32_t rightlevel; + uint8_t regval; + + audinfo("volume=%u mute=%u\n", volume, mute); + +#ifndef CONFIG_AUDIO_EXCLUDE_BALANCE + /* Calculate the left channel volume level {0..1000} */ + + if (priv->balance <= 500) + { + leftlevel = volume; + } + else if (priv->balance == 1000) + { + leftlevel = 0; + } + else + { + leftlevel = ((((1000 - priv->balance) * 100) / 500) * volume) / 100; + } + +/* Calculate the right channel volume level {0..1000} */ + + if (priv->balance >= 500) + { + rightlevel = volume; + } + else if (priv->balance == 0) + { + rightlevel = 0; + } + else + { + rightlevel = (((priv->balance * 100) / 500) * volume) / 100; + } + +# else + leftlevel = priv->volume; + rightlevel = priv->volume; +# endif + + /* Set the volume */ + + regval = (rightlevel + 0x19) & 0xff; + cs43l22_writereg(priv, CS43L22_MS_VOL_CTRL_A, regval); + regval = ((leftlevel + 0x19) & 0xff); + cs43l22_writereg(priv, CS43L22_MS_VOL_CTRL_B, regval); + +#if 0 + regval = (rightlevel + 0x01) & 0xff; + cs43l22_writereg(priv, CS43L22_HP_VOL_CTRL_A, regval); + regval = (leftlevel + 0x01) & 0xff; + cs43l22_writereg(priv, CS43L22_HP_VOL_CTRL_B, regval); +#endif + + regval = cs43l22_readreg(priv, CS43L22_PLAYBACK_CTRL2); + + if (mute) + { + regval |= (CS43L22_HPAMUTE | CS43L22_HPBMUTE); + } + else + { + regval &= ~(CS43L22_HPAMUTE | CS43L22_HPBMUTE); + } + + cs43l22_writereg(priv, CS43L22_PLAYBACK_CTRL2, regval); + + /* Remember the volume level and mute settings */ + + priv->volume = volume; + priv->mute = mute; +} +#endif /* CONFIG_AUDIO_EXCLUDE_VOLUME */ + +/************************************************************************************ + * Name: cs43l22_setbass + * + * Description: + * Set the bass level. + * + * The level and range are in whole percentage levels (0-100). + * + ************************************************************************************/ + +#ifndef CONFIG_AUDIO_EXCLUDE_TONE +static void cs43l22_setbass(FAR struct cs43l22_dev_s *priv, uint8_t bass) +{ + audinfo("bass=%u\n", bass); +#warning Missing logic +} +#endif /* CONFIG_AUDIO_EXCLUDE_TONE */ + +/************************************************************************************ + * Name: cs43l22_settreble + * + * Description: + * Set the treble level . + * + * The level and range are in whole percentage levels (0-100). + * + ************************************************************************************/ + +#ifndef CONFIG_AUDIO_EXCLUDE_TONE +static void cs43l22_settreble(FAR struct cs43l22_dev_s *priv, uint8_t treble) +{ + audinfo("treble=%u\n", treble); +#warning Missing logic +} +#endif /* CONFIG_AUDIO_EXCLUDE_TONE */ + +/**************************************************************************** + * Name: cs43l22_setdatawidth + * + * Description: + * Set the 8- or 16-bit data modes + * + ****************************************************************************/ + +static void cs43l22_setdatawidth(FAR struct cs43l22_dev_s *priv) +{ + if (priv->bpsamp == 16) + { + /* Reset default default setting */ + priv->i2s->ops->i2s_txdatawidth(priv->i2s, 16); + } + else + { + /* This should select 8-bit with no companding */ + priv->i2s->ops->i2s_txdatawidth(priv->i2s, 8); + } +} + +/**************************************************************************** + * Name: cs43l22_setbitrate + * + ****************************************************************************/ + +static void cs43l22_setbitrate(FAR struct cs43l22_dev_s *priv) +{ + DEBUGASSERT(priv && priv->lower); + + priv->i2s->ops->i2s_txsamplerate(priv->i2s, priv->samprate); + + audinfo("sample rate=%u nchannels=%u bpsamp=%u\n", + priv->samprate, priv->nchannels, priv->bpsamp); +} + +/**************************************************************************** + * Name: cs43l22_getcaps + * + * Description: + * Get the audio device capabilities + * + ****************************************************************************/ + +static int cs43l22_getcaps(FAR struct audio_lowerhalf_s *dev, int type, + FAR struct audio_caps_s *caps) +{ + /* Validate the structure */ + + DEBUGASSERT(caps && caps->ac_len >= sizeof(struct audio_caps_s)); + audinfo("type=%d ac_type=%d\n", type, caps->ac_type); + + /* Fill in the caller's structure based on requested info */ + + caps->ac_format.hw = 0; + caps->ac_controls.w = 0; + + switch (caps->ac_type) + { + /* Caller is querying for the types of units we support */ + + case AUDIO_TYPE_QUERY: + + /* Provide our overall capabilities. The interfacing software + * must then call us back for specific info for each capability. + */ + + caps->ac_channels = 2; /* Stereo output */ + + switch (caps->ac_subtype) + { + case AUDIO_TYPE_QUERY: + /* We don't decode any formats! Only something above us in + * the audio stream can perform decoding on our behalf. + */ + + /* The types of audio units we implement */ + + caps->ac_controls.b[0] = AUDIO_TYPE_OUTPUT | AUDIO_TYPE_FEATURE | + AUDIO_TYPE_PROCESSING; + break; + + case AUDIO_FMT_MIDI: + /* We only support Format 0 */ + + caps->ac_controls.b[0] = AUDIO_SUBFMT_END; + break; + + default: + caps->ac_controls.b[0] = AUDIO_SUBFMT_END; + break; + } + + break; + + /* Provide capabilities of our OUTPUT unit */ + + case AUDIO_TYPE_OUTPUT: + + caps->ac_channels = 2; + + switch (caps->ac_subtype) + { + case AUDIO_TYPE_QUERY: + + /* Report the Sample rates we support */ + + caps->ac_controls.b[0] = AUDIO_SAMP_RATE_8K | AUDIO_SAMP_RATE_11K | + AUDIO_SAMP_RATE_16K | AUDIO_SAMP_RATE_22K | + AUDIO_SAMP_RATE_32K | AUDIO_SAMP_RATE_44K | + AUDIO_SAMP_RATE_48K; + break; + + case AUDIO_FMT_MP3: + case AUDIO_FMT_WMA: + case AUDIO_FMT_PCM: + break; + + default: + break; + } + + break; + + /* Provide capabilities of our FEATURE units */ + + case AUDIO_TYPE_FEATURE: + + /* If the sub-type is UNDEF, then report the Feature Units we support */ + + if (caps->ac_subtype == AUDIO_FU_UNDEF) + { + /* Fill in the ac_controls section with the Feature Units we have */ + + caps->ac_controls.b[0] = AUDIO_FU_VOLUME | AUDIO_FU_BASS | AUDIO_FU_TREBLE; + caps->ac_controls.b[1] = AUDIO_FU_BALANCE >> 8; + } + else + { + /* TODO: Do we need to provide specific info for the Feature Units, + * such as volume setting ranges, etc.? + */ + } + + break; + + /* Provide capabilities of our PROCESSING unit */ + + case AUDIO_TYPE_PROCESSING: + + switch (caps->ac_subtype) + { + case AUDIO_PU_UNDEF: + /* Provide the type of Processing Units we support */ + + caps->ac_controls.b[0] = AUDIO_PU_STEREO_EXTENDER; + break; + + case AUDIO_PU_STEREO_EXTENDER: + /* Provide capabilities of our Stereo Extender */ + + caps->ac_controls.b[0] = AUDIO_STEXT_ENABLE | AUDIO_STEXT_WIDTH; + break; + + default: + /* Other types of processing uint we don't support */ + + break; + } + break; + + /* All others we don't support */ + + default: + + /* Zero out the fields to indicate no support */ + + caps->ac_subtype = 0; + caps->ac_channels = 0; + + break; + } + + /* Return the length of the audio_caps_s struct for validation of + * proper Audio device type. + */ + + return caps->ac_len; +} + +/**************************************************************************** + * Name: cs43l22_configure + * + * Description: + * Configure the audio device for the specified mode of operation. + * + ****************************************************************************/ + +#ifdef CONFIG_AUDIO_MULTI_SESSION +static int +cs43l22_configure(FAR struct audio_lowerhalf_s *dev, + FAR void *session, FAR const struct audio_caps_s *caps) +#else +static int +cs43l22_configure(FAR struct audio_lowerhalf_s *dev, + FAR const struct audio_caps_s *caps) +#endif +{ +#if !defined(CONFIG_AUDIO_EXCLUDE_VOLUME) || !defined(CONFIG_AUDIO_EXCLUDE_TONE) + FAR struct cs43l22_dev_s *priv = (FAR struct cs43l22_dev_s *)dev; +#endif + int ret = OK; + + DEBUGASSERT(priv && caps); + audinfo("ac_type: %d\n", caps->ac_type); + + /* Process the configure operation */ + + switch (caps->ac_type) + { + case AUDIO_TYPE_FEATURE: + audinfo(" AUDIO_TYPE_FEATURE\n"); + + /* Process based on Feature Unit */ + + switch (caps->ac_format.hw) + { +#ifndef CONFIG_AUDIO_EXCLUDE_VOLUME + case AUDIO_FU_VOLUME: + { + /* Set the volume */ + + uint16_t volume = caps->ac_controls.hw[0]; + audinfo(" Volume: %d\n", volume); + + if (volume >= 0 && volume <= 1000) + { + /* Scale the volume setting to the range {76..255} */ + + cs43l22_setvolume(priv, (179 * volume / 1000) + 76, priv->mute); + } + else + { + ret = -EDOM; + } + } + break; +#endif /* CONFIG_AUDIO_EXCLUDE_VOLUME */ + +#ifndef CONFIG_AUDIO_EXCLUDE_BALANCE + case AUDIO_FU_BALANCE: + { + /* Set the Balance */ + + uint16_t balance = caps->ac_controls.hw[0]; + audinfo(" Balance: %d\n", balance); + if (balance >= 0 && balance <= 1000) + { + /* Scale the volume setting to the range {76..255} */ + + cs43l22_setvolume(priv, (179 * priv->volume / 1000) + 76, + priv->mute); + } + else + { + ret = -EDOM; + } + } + break; +#endif /* CONFIG_AUDIO_EXCLUDE_VOLUME */ + +#ifndef CONFIG_AUDIO_EXCLUDE_TONE + case AUDIO_FU_BASS: + { + /* Set the bass. The percentage level (0-100) is in the + * ac_controls.b[0] parameter. + */ + + uint8_t bass = caps->ac_controls.b[0]; + audinfo(" Bass: %d\n", bass); + + if (bass <= 100) + { + cs43l22_setbass(priv, bass); + } + else + { + ret = -EDOM; + } + } + break; + + case AUDIO_FU_TREBLE: + { + /* Set the treble. The percentage level (0-100) is in the + * ac_controls.b[0] parameter. + */ + + uint8_t treble = caps->ac_controls.b[0]; + audinfo(" Treble: %d\n", treble); + + if (treble <= 100) + { + cs43l22_settreble(priv, treble); + } + else + { + ret = -EDOM; + } + } + break; +#endif /* CONFIG_AUDIO_EXCLUDE_TONE */ + + default: + auderr(" ERROR: Unrecognized feature unit\n"); + ret = -ENOTTY; + break; + } + break; + + case AUDIO_TYPE_OUTPUT: + { + audinfo(" AUDIO_TYPE_OUTPUT:\n"); + audinfo(" Number of channels: %u\n", caps->ac_channels); + audinfo(" Sample rate: %u\n", caps->ac_controls.hw[0]); + audinfo(" Sample width: %u\n", caps->ac_controls.b[2]); + + /* Verify that all of the requested values are supported */ + + ret = -ERANGE; + if (caps->ac_channels != 1 && caps->ac_channels != 2) + { + auderr("ERROR: Unsupported number of channels: %d\n", + caps->ac_channels); + break; + } + + if (caps->ac_controls.b[2] != 8 && caps->ac_controls.b[2] != 16) + { + auderr("ERROR: Unsupported bits per sample: %d\n", + caps->ac_controls.b[2]); + break; + } + + /* Save the current stream configuration */ + + priv->samprate = caps->ac_controls.hw[0]; + priv->nchannels = caps->ac_channels; + priv->bpsamp = caps->ac_controls.b[2]; + + /* Reconfigure the FLL to support the resulting number or channels, + * bits per sample, and bitrate. + */ + + cs43l22_setdatawidth(priv); + cs43l22_setbitrate(priv); + cs43l22_clock_analysis(&priv->dev, "AUDIO_TYPE_OUTPUT"); + ret = OK; + } + break; + + case AUDIO_TYPE_PROCESSING: + break; + } + + return ret; +} + +/**************************************************************************** + * Name: cs43l22_shutdown + * + * Description: + * Shutdown the CS43L22 chip and put it in the lowest power state possible. + * + ****************************************************************************/ + +static int cs43l22_shutdown(FAR struct audio_lowerhalf_s *dev) +{ + FAR struct cs43l22_dev_s *priv = (FAR struct cs43l22_dev_s *)dev; + + DEBUGASSERT(priv); + + /* First disable interrupts */ + + CS43L22_DISABLE(priv->lower); + + /* Now issue a software reset. This puts all CS43L22 registers back in + * their default state. + */ + + cs43l22_reset(priv); + return OK; +} + +/**************************************************************************** + * Name: cs43l22_senddone + * + * Description: + * This is the I2S callback function that is invoked when the transfer + * completes. + * + ****************************************************************************/ + +static void +cs43l22_senddone(FAR struct i2s_dev_s *i2s, + FAR struct ap_buffer_s *apb, FAR void *arg, int result) +{ + FAR struct cs43l22_dev_s *priv = (FAR struct cs43l22_dev_s *)arg; + struct audio_msg_s msg; + irqstate_t flags; + int ret; + + DEBUGASSERT(i2s && priv && priv->running && apb); + audinfo("apb=%p inflight=%d result=%d\n", apb, priv->inflight, result); + + /* We do not place any restriction on the context in which this function + * is called. It may be called from an interrupt handler. Therefore, the + * doneq and in-flight values might be accessed from the interrupt level. + * Not the best design. But we will use interrupt controls to protect + * against that possibility. + */ + + flags = enter_critical_section(); + + /* Add the completed buffer to the end of our doneq. We do not yet + * decrement the reference count. + */ + + dq_addlast((FAR dq_entry_t *)apb, &priv->doneq); + + /* And decrement the number of buffers in-flight */ + + DEBUGASSERT(priv->inflight > 0); + priv->inflight--; + + /* Save the result of the transfer */ + /* REVISIT: This can be overwritten */ + + priv->result = result; + leave_critical_section(flags); + + /* Now send a message to the worker thread, informing it that there are + * buffers in the done queue that need to be cleaned up. + */ + + msg.msgId = AUDIO_MSG_COMPLETE; + ret = mq_send(priv->mq, (FAR const char *)&msg, sizeof(msg), + CONFIG_CS43L22_MSG_PRIO); + if (ret < 0) + { + auderr("ERROR: mq_send failed: %d\n", errno); + } +} + +/**************************************************************************** + * Name: cs43l22_returnbuffers + * + * Description: + * This function is called after the complete of one or more data + * transfers. This function will empty the done queue and release our + * reference to each buffer. + * + ****************************************************************************/ + +static void cs43l22_returnbuffers(FAR struct cs43l22_dev_s *priv) +{ + FAR struct ap_buffer_s *apb; + irqstate_t flags; + + /* The doneq and in-flight values might be accessed from the interrupt + * level in some implementations. Not the best design. But we will + * use interrupt controls to protect against that possibility. + */ + + flags = enter_critical_section(); + while (dq_peek(&priv->doneq) != NULL) + { + /* Take the next buffer from the queue of completed transfers */ + + apb = (FAR struct ap_buffer_s *)dq_remfirst(&priv->doneq); + leave_critical_section(flags); + + audinfo("Returning: apb=%p curbyte=%d nbytes=%d flags=%04x\n", + apb, apb->curbyte, apb->nbytes, apb->flags); + + /* Are we returning the final buffer in the stream? */ + + if ((apb->flags & AUDIO_APB_FINAL) != 0) + { + /* Both the pending and the done queues should be empty and there + * should be no buffers in-flight. + */ + + DEBUGASSERT(dq_empty(&priv->doneq) && dq_empty(&priv->pendq) && + priv->inflight == 0); + + /* Set the terminating flag. This will, eventually, cause the + * worker thread to exit (if it is not already terminating). + */ + + audinfo("Terminating\n"); + priv->terminating = true; + } + + /* Release our reference to the audio buffer */ + + apb_free(apb); + + /* Send the buffer back up to the previous level. */ + +#ifdef CONFIG_AUDIO_MULTI_SESSION + priv->dev.upper(priv->dev.priv, AUDIO_CALLBACK_DEQUEUE, apb, OK, NULL); +#else + priv->dev.upper(priv->dev.priv, AUDIO_CALLBACK_DEQUEUE, apb, OK); +#endif + flags = enter_critical_section(); + } + + leave_critical_section(flags); +} + +/**************************************************************************** + * Name: cs43l22_sendbuffer + * + * Description: + * Start the transfer an audio buffer to the CS43L22 via I2S. This + * will not wait for the transfer to complete but will return immediately. + * the wmd8904_senddone called will be invoked when the transfer + * completes, stimulating the worker thread to call this function again. + * + ****************************************************************************/ + +static int cs43l22_sendbuffer(FAR struct cs43l22_dev_s *priv) +{ + FAR struct ap_buffer_s *apb; + irqstate_t flags; + uint32_t timeout; + int shift; + int ret = OK; + + /* Loop while there are audio buffers to be sent and we have few than + * CONFIG_CS43L22_INFLIGHT then "in-flight" + * + * The 'inflight' value might be modified from the interrupt level in some + * implementations. We will use interrupt controls to protect against + * that possibility. + * + * The 'pendq', on the other hand, is protected via a semaphore. Let's + * hold the semaphore while we are busy here and disable the interrupts + * only while accessing 'inflight'. + */ + + cs43l22_takesem(&priv->pendsem); + while (priv->inflight < CONFIG_CS43L22_INFLIGHT && + dq_peek(&priv->pendq) != NULL && !priv->paused) + { + /* Take next buffer from the queue of pending transfers */ + + apb = (FAR struct ap_buffer_s *)dq_remfirst(&priv->pendq); + audinfo("Sending apb=%p, size=%d inflight=%d\n", + apb, apb->nbytes, priv->inflight); + + /* Increment the number of buffers in-flight before sending in order + * to avoid a possible race condition. + */ + + flags = enter_critical_section(); + priv->inflight++; + leave_critical_section(flags); + + /* Send the entire audio buffer via I2S. What is a reasonable timeout + * to use? This would depend on the bit rate and size of the buffer. + * + * Samples in the buffer (samples): + * = buffer_size * 8 / bpsamp samples + * Sample rate (samples/second): + * = samplerate * nchannels + * Expected transfer time (seconds): + * = (buffer_size * 8) / bpsamp / samplerate / nchannels + * + * We will set the timeout about twice that. + * + * NOTES: + * - The multiplier of 8 becomes 16000 for 2x and units of + * milliseconds. + * - 16000 is a approximately 16384 (1 << 14), bpsamp is either + * (1 << 3) or (1 << 4), and nchannels is either (1 << 0) or + * (1 << 1). So this can be simplifies to (milliseconds): + * + * = (buffer_size << shift) / samplerate + */ + + shift = (priv->bpsamp == 8) ? 14 - 3 : 14 - 4; + shift -= (priv->nchannels > 1) ? 1 : 0; + + timeout = MSEC2TICK(((uint32_t)(apb->nbytes - apb->curbyte) << shift) / + (uint32_t)priv->samprate); + + ret = I2S_SEND(priv->i2s, apb, cs43l22_senddone, priv, timeout); + if (ret < 0) + { + auderr("ERROR: I2S_SEND failed: %d\n", ret); + break; + } + } + + cs43l22_givesem(&priv->pendsem); + return ret; +} + +/**************************************************************************** + * Name: cs43l22_start + * + * Description: + * Start the configured operation (audio streaming, volume enabled, etc.). + * + ****************************************************************************/ + +#ifdef CONFIG_AUDIO_MULTI_SESSION +static int cs43l22_start(FAR struct audio_lowerhalf_s *dev, FAR void *session) +#else +static int cs43l22_start(FAR struct audio_lowerhalf_s *dev) +#endif +{ + FAR struct cs43l22_dev_s *priv = (FAR struct cs43l22_dev_s *)dev; + struct sched_param sparam; + struct mq_attr attr; + pthread_attr_t tattr; + FAR void *value; + int ret; + + audinfo("Entry\n"); + + /* Exit reduced power modes of operation */ + /* REVISIT */ + + /* Create a message queue for the worker thread */ + + snprintf(priv->mqname, sizeof(priv->mqname), "/tmp/%X", priv); + + attr.mq_maxmsg = 16; + attr.mq_msgsize = sizeof(struct audio_msg_s); + attr.mq_curmsgs = 0; + attr.mq_flags = 0; + + priv->mq = mq_open(priv->mqname, O_RDWR | O_CREAT, 0644, &attr); + if (priv->mq == NULL) + { + /* Error creating message queue! */ + + auderr("ERROR: Couldn't allocate message queue\n"); + return -ENOMEM; + } + + /* Join any old worker thread we had created to prevent a memory leak */ + + if (priv->threadid != 0) + { + audinfo("Joining old thread\n"); + pthread_join(priv->threadid, &value); + } + + /* Start our thread for sending data to the device */ + + pthread_attr_init(&tattr); + sparam.sched_priority = sched_get_priority_max(SCHED_FIFO) - 3; + (void)pthread_attr_setschedparam(&tattr, &sparam); + (void)pthread_attr_setstacksize(&tattr, CONFIG_CS43L22_WORKER_STACKSIZE); + + audinfo("Starting worker thread\n"); + ret = pthread_create(&priv->threadid, &tattr, cs43l22_workerthread, + (pthread_addr_t)priv); + if (ret != OK) + { + auderr("ERROR: pthread_create failed: %d\n", ret); + } + else + { + pthread_setname_np(priv->threadid, "cs43l22"); + audinfo("Created worker thread\n"); + } + + return ret; +} + +/**************************************************************************** + * Name: cs43l22_stop + * + * Description: Stop the configured operation (audio streaming, volume + * disabled, etc.). + * + ****************************************************************************/ + +#ifndef CONFIG_AUDIO_EXCLUDE_STOP +# ifdef CONFIG_AUDIO_MULTI_SESSION +static int cs43l22_stop(FAR struct audio_lowerhalf_s *dev, FAR void *session) +# else +static int cs43l22_stop(FAR struct audio_lowerhalf_s *dev) +# endif +{ + FAR struct cs43l22_dev_s *priv = (FAR struct cs43l22_dev_s *)dev; + struct audio_msg_s term_msg; + FAR void *value; + + /* Send a message to stop all audio streaming */ + + term_msg.msgId = AUDIO_MSG_STOP; + term_msg.u.data = 0; + mq_send(priv->mq, (FAR const char *)&term_msg, sizeof(term_msg), + CONFIG_CS43L22_MSG_PRIO); + + /* Join the worker thread */ + + pthread_join(priv->threadid, &value); + priv->threadid = 0; + + /* Enter into a reduced power usage mode */ + /* REVISIT: */ + + return OK; +} +#endif + +/**************************************************************************** + * Name: cs43l22_pause + * + * Description: Pauses the playback. + * + ****************************************************************************/ + +#ifndef CONFIG_AUDIO_EXCLUDE_PAUSE_RESUME +# ifdef CONFIG_AUDIO_MULTI_SESSION +static int cs43l22_pause(FAR struct audio_lowerhalf_s *dev, FAR void *session) +# else +static int cs43l22_pause(FAR struct audio_lowerhalf_s *dev) +# endif +{ + FAR struct cs43l22_dev_s *priv = (FAR struct cs43l22_dev_s *)dev; + + if (priv->running && !priv->paused) + { + /* Disable interrupts to prevent us from suppling any more data */ + + priv->paused = true; + cs43l22_setvolume(priv, priv->volume, true); + CS43L22_DISABLE(priv->lower); + } + + return OK; +} +#endif /* CONFIG_AUDIO_EXCLUDE_PAUSE_RESUME */ + +/**************************************************************************** + * Name: cs43l22_resume + * + * Description: Resumes the playback. + * + ****************************************************************************/ + +#ifndef CONFIG_AUDIO_EXCLUDE_PAUSE_RESUME +# ifdef CONFIG_AUDIO_MULTI_SESSION +static int cs43l22_resume(FAR struct audio_lowerhalf_s *dev, FAR void *session) +# else +static int cs43l22_resume(FAR struct audio_lowerhalf_s *dev) +# endif +{ + FAR struct cs43l22_dev_s *priv = (FAR struct cs43l22_dev_s *)dev; + + if (priv->running && priv->paused) + { + priv->paused = false; + cs43l22_setvolume(priv, priv->volume, false); + + /* Enable interrupts to allow sampling data */ + + cs43l22_sendbuffer(priv); +#ifdef CS43L22_USE_FFLOCK_INT + CS43L22_ENABLE(priv->lower); +#endif + } + + return OK; +} +#endif /* CONFIG_AUDIO_EXCLUDE_PAUSE_RESUME */ + +/**************************************************************************** + * Name: cs43l22_enqueuebuffer + * + * Description: Enqueue an Audio Pipeline Buffer for playback/ processing. + * + ****************************************************************************/ + +static int cs43l22_enqueuebuffer(FAR struct audio_lowerhalf_s *dev, + FAR struct ap_buffer_s *apb) +{ + FAR struct cs43l22_dev_s *priv = (FAR struct cs43l22_dev_s *)dev; + struct audio_msg_s term_msg; + int ret; + + audinfo("Enqueueing: apb=%p curbyte=%d nbytes=%d flags=%04x\n", + apb, apb->curbyte, apb->nbytes, apb->flags); + + /* Take a reference on the new audio buffer */ + + apb_reference(apb); + + /* Add the new buffer to the tail of pending audio buffers */ + + cs43l22_takesem(&priv->pendsem); + apb->flags |= AUDIO_APB_OUTPUT_ENQUEUED; + dq_addlast(&apb->dq_entry, &priv->pendq); + cs43l22_givesem(&priv->pendsem); + + /* Send a message to the worker thread indicating that a new buffer has been + * enqueued. If mq is NULL, then the playing has not yet started. In that + * case we are just "priming the pump" and we don't need to send any message. + */ + + ret = OK; + if (priv->mq != NULL) + { + term_msg.msgId = AUDIO_MSG_ENQUEUE; + term_msg.u.data = 0; + + ret = mq_send(priv->mq, (FAR const char *)&term_msg, sizeof(term_msg), + CONFIG_CS43L22_MSG_PRIO); + if (ret < 0) + { + int errcode = errno; + DEBUGASSERT(errcode > 0); + + auderr("ERROR: mq_send failed: %d\n", errcode); + UNUSED(errcode); + } + } + + return ret; +} + +/**************************************************************************** + * Name: cs43l22_cancelbuffer + * + * Description: Called when an enqueued buffer is being cancelled. + * + ****************************************************************************/ + +static int cs43l22_cancelbuffer(FAR struct audio_lowerhalf_s *dev, + FAR struct ap_buffer_s *apb) +{ + audinfo("apb=%p\n", apb); + return OK; +} + +/**************************************************************************** + * Name: cs43l22_ioctl + * + * Description: Perform a device ioctl + * + ****************************************************************************/ + +static int cs43l22_ioctl(FAR struct audio_lowerhalf_s *dev, int cmd, + unsigned long arg) +{ +#ifdef CONFIG_AUDIO_DRIVER_SPECIFIC_BUFFERS + FAR struct ap_buffer_info_s *bufinfo; +#endif + + /* Deal with ioctls passed from the upper-half driver */ + + switch (cmd) + { + /* Check for AUDIOIOC_HWRESET ioctl. This ioctl is passed straight + * through from the upper-half audio driver. + */ + + case AUDIOIOC_HWRESET: + { + /* REVISIT: Should we completely re-initialize the chip? We + * can't just issue a software reset; that would puts all WM8904 + * registers back in their default state. + */ + + audinfo("AUDIOIOC_HWRESET:\n"); + } + break; + + /* Report our preferred buffer size and quantity */ + +#ifdef CONFIG_AUDIO_DRIVER_SPECIFIC_BUFFERS + case AUDIOIOC_GETBUFFERINFO: + { + audinfo("AUDIOIOC_GETBUFFERINFO:\n"); + bufinfo = (FAR struct ap_buffer_info_s *)arg; + bufinfo->buffer_size = CONFIG_CS43L22_BUFFER_SIZE; + bufinfo->nbuffers = CONFIG_CS43L22_NUM_BUFFERS; + } + break; +#endif + + default: + audinfo("Ignored\n"); + break; + } + + return OK; +} + +/**************************************************************************** + * Name: cs43l22_reserve + * + * Description: Reserves a session (the only one we have). + * + ****************************************************************************/ + +#ifdef CONFIG_AUDIO_MULTI_SESSION +static int +cs43l22_reserve(FAR struct audio_lowerhalf_s *dev, FAR void **session) +#else +static int cs43l22_reserve(FAR struct audio_lowerhalf_s *dev) +#endif +{ + FAR struct cs43l22_dev_s *priv = (FAR struct cs43l22_dev_s *)dev; + int ret = OK; + + /* Borrow the APBQ semaphore for thread sync */ + + cs43l22_takesem(&priv->pendsem); + if (priv->reserved) + { + ret = -EBUSY; + } + else + { + /* Initialize the session context */ + +#ifdef CONFIG_AUDIO_MULTI_SESSION + *session = NULL; +#endif + priv->inflight = 0; + priv->running = false; + priv->paused = false; +#ifndef CONFIG_AUDIO_EXCLUDE_STOP + priv->terminating = false; +#endif + priv->reserved = true; + } + + cs43l22_givesem(&priv->pendsem); + + return ret; +} + +/**************************************************************************** + * Name: cs43l22_release + * + * Description: Releases the session (the only one we have). + * + ****************************************************************************/ + +#ifdef CONFIG_AUDIO_MULTI_SESSION +static int cs43l22_release(FAR struct audio_lowerhalf_s *dev, FAR void *session) +#else +static int cs43l22_release(FAR struct audio_lowerhalf_s *dev) +#endif +{ + FAR struct cs43l22_dev_s *priv = (FAR struct cs43l22_dev_s *)dev; + void *value; + + /* Join any old worker thread we had created to prevent a memory leak */ + + if (priv->threadid != 0) + { + pthread_join(priv->threadid, &value); + priv->threadid = 0; + } + + /* Borrow the APBQ semaphore for thread sync */ + + cs43l22_takesem(&priv->pendsem); + + /* Really we should free any queued buffers here */ + + priv->reserved = false; + cs43l22_givesem(&priv->pendsem); + + return OK; +} + +/**************************************************************************** + * Name: cs43l22_interrupt_work + * + * Description: + * CS43L22 interrupt actions cannot be performed in the interrupt handler + * because I2C access is not possible in that context. Instead, all I2C + * operations are deferred to the work queue. + * + * Assumptions: + * CS43L22 interrupts were disabled in the interrupt handler. + * + ****************************************************************************/ + +#ifdef CS43L22_USE_FFLOCK_INT +static void cs43l22_interrupt_work(FAR void *arg) +{ + /* TODO */ +#warning Missing logic +} +#endif + +/**************************************************************************** + * Name: cs43l22_interrupt + * + * Description: + * This is the ISR that services the GPIO1/IRQ pin from the CS43L22. It + * signals CS43L22 events such FLL lock. + * + ****************************************************************************/ + +#ifdef CS43L22_USE_FFLOCK_INT +static int +cs43l22_interrupt(FAR const struct cs43l22_lower_s *lower, FAR void *arg) +{ + /* TODO */ +#warning Missing logic +} +#endif + +/**************************************************************************** + * Name: cs43l22_workerthread + * + * This is the thread that feeds data to the chip and keeps the audio + * stream going. + * + ****************************************************************************/ + +static void *cs43l22_workerthread(pthread_addr_t pvarg) +{ + FAR struct cs43l22_dev_s *priv = (struct cs43l22_dev_s *)pvarg; + struct audio_msg_s msg; + FAR struct ap_buffer_s *apb; + int msglen; + int prio; + + audinfo("Entry\n"); + +#ifndef CONFIG_AUDIO_EXCLUDE_STOP + priv->terminating = false; +#endif + +/* Mark ourself as running and make sure that CS43L22 interrupts are + * enabled. + */ + + priv->running = true; +#ifdef CS43L22_USE_FFLOCK_INT + CS43L22_ENABLE(priv->lower); +#endif + cs43l22_setvolume(priv, priv->volume, false); + + /* Loop as long as we are supposed to be running and as long as we have + * buffers in-flight. + */ + + while (priv->running || priv->inflight > 0) + { + /* Check if we have been asked to terminate. We have to check if we + * still have buffers in-flight. If we do, then we can't stop until + * birds come back to roost. + */ + + if (priv->terminating && priv->inflight <= 0) + { + /* We are IDLE. Break out of the loop and exit. */ + + break; + } + else + { + /* Check if we can send more audio buffers to the CS43L22 */ + + cs43l22_sendbuffer(priv); + } + + /* Wait for messages from our message queue */ + + msglen = mq_receive(priv->mq, (FAR char *)&msg, sizeof(msg), &prio); + + /* Handle the case when we return with no message */ + + if (msglen < sizeof(struct audio_msg_s)) + { + auderr("ERROR: Message too small: %d\n", msglen); + continue; + } + + /* Process the message */ + + switch (msg.msgId) + { + /* The ISR has requested more data. We will catch this case at + * the top of the loop. + */ + + case AUDIO_MSG_DATA_REQUEST: + audinfo("AUDIO_MSG_DATA_REQUEST\n"); + break; + + /* Stop the playback */ + +#ifndef CONFIG_AUDIO_EXCLUDE_STOP + case AUDIO_MSG_STOP: + /* Indicate that we are terminating */ + + audinfo("AUDIO_MSG_STOP: Terminating\n"); + priv->terminating = true; + break; +#endif + + /* We have a new buffer to send. We will catch this case at + * the top of the loop. + */ + + case AUDIO_MSG_ENQUEUE: + audinfo("AUDIO_MSG_ENQUEUE\n"); + break; + + /* We will wake up from the I2S callback with this message */ + + case AUDIO_MSG_COMPLETE: + audinfo("AUDIO_MSG_COMPLETE\n"); + cs43l22_returnbuffers(priv); + break; + + default: + auderr("ERROR: Ignoring message ID %d\n", msg.msgId); + break; + } + } + + /* Reset the CS43L22 hardware */ + + cs43l22_reset(priv); + + /* Return any pending buffers in our pending queue */ + + cs43l22_takesem(&priv->pendsem); + while ((apb = (FAR struct ap_buffer_s *)dq_remfirst(&priv->pendq)) != NULL) + { + /* Release our reference to the buffer */ + + apb_free(apb); + + /* Send the buffer back up to the previous level. */ + +#ifdef CONFIG_AUDIO_MULTI_SESSION + priv->dev.upper(priv->dev.priv, AUDIO_CALLBACK_DEQUEUE, apb, OK, NULL); +#else + priv->dev.upper(priv->dev.priv, AUDIO_CALLBACK_DEQUEUE, apb, OK); +#endif + } + + cs43l22_givesem(&priv->pendsem); + + /* Return any pending buffers in our done queue */ + + cs43l22_returnbuffers(priv); + + /* Close the message queue */ + + mq_close(priv->mq); + mq_unlink(priv->mqname); + priv->mq = NULL; + + /* Send an AUDIO_MSG_COMPLETE message to the client */ + +#ifdef CONFIG_AUDIO_MULTI_SESSION + priv->dev.upper(priv->dev.priv, AUDIO_CALLBACK_COMPLETE, NULL, OK, NULL); +#else + priv->dev.upper(priv->dev.priv, AUDIO_CALLBACK_COMPLETE, NULL, OK); +#endif + + audinfo("Exit\n"); + return NULL; +} + +/**************************************************************************** + * Name: cs43l22_audio_output + * + * Description: + * Initialize and configure the CS43L22 device as an audio output device. + * + * Input Parameters: + * priv - A reference to the driver state structure + * + * Returned Value: + * None. No failures are detected. + * + ****************************************************************************/ + +static void cs43l22_audio_output(FAR struct cs43l22_dev_s *priv) +{ + uint8_t regval; + + /* Keep codec powered off */ + + regval = CS43L22_POWER_DOWN; + cs43l22_writereg(priv, CS43L22_POWER_CTRL1, regval); + + /* SPK always off and HP always on */ + + regval = CS43L22_PDN_HPB_ON | CS43L22_PDN_HPA_ON | CS43L22_PDN_SPKB_OFF | CS43L22_PDN_SPKA_OFF; + cs43l22_writereg(priv, CS43L22_POWER_CTRL2, regval); + + /* Clock configuration: Auto detection */ + + regval = CS43L22_AUTO_DETECT_ENABLE | CS43L22_CLKDIV2_ENABLE; + cs43l22_writereg(priv, CS43L22_CLOCK_CTRL, regval); + + /* Set slave mode and Philips audio standard */ + + regval = CS43L22_DAC_IF_I2S; + cs43l22_writereg(priv, CS43L22_INTERFACE_CTRL1, regval); + + /* Power on the codec */ + + regval = CS43L22_POWER_UP; + cs43l22_writereg(priv, CS43L22_POWER_CTRL1, regval); + + /* Disable the analog soft ramp */ + + regval = 0x00; + cs43l22_writereg(priv, CS43L22_ANLG_ZC_SR_SEL, regval); + + /* Disable the digital soft ramp */ + + regval = CS43L22_DEEMPHASIS_ENABLE; + cs43l22_writereg(priv, CS43L22_MISCLLNS_CTRL, regval); + + /* Disable the limiter attack level */ + + regval = 0x00; + cs43l22_writereg(priv, CS43L22_LIM_CTRL1, regval); + + /* Adjust bass and treble levels */ + + regval = CS43L22_BASS_GAIN(0x0f); + cs43l22_writereg(priv, CS43L22_TONE_CTRL, regval); + + /* Adjust PCM volume level */ + + regval = 0x0a; + cs43l22_writereg(priv, CS43L22_PCM_VOL_A, regval); + cs43l22_writereg(priv, CS43L22_PCM_VOL_B, regval); + + cs43l22_setdatawidth(priv); + + cs43l22_setvolume(priv, CONFIG_CS43L22_INITVOLUME, false); +} + +/**************************************************************************** + * Name: cs43l22_audio_input + * + * Description: + * Initialize and configure the CS43L22 device as an audio output device + * (Right input only). cs43l22_audio_output() must be called first, this + * function then modifies the configuration to support audio input. + * + * Input Parameters: + * priv - A reference to the driver state structure + * + * Returned Value: + * None. No failures are detected. + * + ****************************************************************************/ + +#if 0 /* Not used */ +static void cs43l22_audio_input(FAR struct cs43l22_dev_s *priv) +{ + /* TODO */ +#warning Missing logic +} +#endif + +/**************************************************************************** + * Name: cs43l22_configure_ints + * + * Description: + * Configure the GPIO/IRQ interrupt + * + * Input Parameters: + * priv - A reference to the driver state structure + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CS43L22_USE_FFLOCK_INT +static void cs43l22_configure_ints(FAR struct cs43l22_dev_s *priv) +{ + /* TODO */ +#warning Missing logic +} +#endif + +/**************************************************************************** + * Name: cs43l22_reset + * + * Description: + * Reset and re-initialize the CS43L22 + * + * Input Parameters: + * priv - A reference to the driver state structure + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void cs43l22_reset(FAR struct cs43l22_dev_s *priv) +{ + /* Put audio output back to its initial configuration */ + + /* Put audio output back to its initial configuration */ + + priv->samprate = CS43L22_DEFAULT_SAMPRATE; + priv->nchannels = CS43L22_DEFAULT_NCHANNELS; + priv->bpsamp = CS43L22_DEFAULT_BPSAMP; +#if !defined(CONFIG_AUDIO_EXCLUDE_VOLUME) && !defined(CONFIG_AUDIO_EXCLUDE_BALANCE) + priv->balance = 500; // b16HALF; /* Center balance */ +#endif + + /* Software reset. This puts all CS43L22 registers back in their + * default state. + */ + + /* cs43l22_writereg(priv, CS43L22_SWRST, 0); */ + + /* Configure the CS43L22 hardware as an audio input device */ + + cs43l22_audio_output(priv); + + /* Configure interrupts */ + + /* cs43l22_configure_ints(priv); */ + + /* Configure the FLL and the LRCLK */ + + cs43l22_setbitrate(priv); + + /* Dump some information and return the device instance */ + + cs43l22_dump_registers(&priv->dev, "After configuration"); + cs43l22_clock_analysis(&priv->dev, "After configuration"); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: cs43l22_initialize + * + * Description: + * Initialize the CS43L22 device. + * + * Input Parameters: + * i2c - An I2C driver instance + * i2s - An I2S driver instance + * lower - Persistent board configuration data + * + * Returned Value: + * A new lower half audio interface for the CS43L22 device is returned on + * success; NULL is returned on failure. + * + ****************************************************************************/ + +FAR struct audio_lowerhalf_s *cs43l22_initialize(FAR struct i2c_master_s *i2c, + FAR struct i2s_dev_s *i2s, + FAR const struct + cs43l22_lower_s *lower) +{ + FAR struct cs43l22_dev_s *priv; + uint16_t regval; + + /* Sanity check */ + + DEBUGASSERT(i2c && i2s && lower); + + /* Allocate a CS43L22 device structure */ + + priv = (FAR struct cs43l22_dev_s *)kmm_zalloc(sizeof(struct cs43l22_dev_s)); + if (priv) + { + /* Initialize the CS43L22 device structure. Since we used kmm_zalloc, + * only the non-zero elements of the structure need to be initialized. + */ + + priv->dev.ops = &g_audioops; + priv->lower = lower; + priv->i2c = i2c; + priv->i2s = i2s; + + sem_init(&priv->pendsem, 0, 1); + dq_init(&priv->pendq); + dq_init(&priv->doneq); + + /* Initialize I2C */ + + audinfo("address=%02x frequency=%d\n", lower->address, lower->frequency); + + /* Software reset. This puts all CS43L22 registers back in their default + * state. */ + + CS43L22_HW_RESET(priv->lower); + + cs43l22_dump_registers(&priv->dev, "After reset"); + + /* Verify that CS43L22 is present and available on this I2C */ + + regval = cs43l22_readreg(priv, CS43L22_ID_REV); + if ((regval & 0xff) != CS43L22_DEV_ID_REV) + { + auderr("ERROR: CS43L22 not found: ID=%02x\n", regval); + goto errout_with_dev; + } + + /* Reset and reconfigure the CS43L22 hardware */ + + cs43l22_reset(priv); + return &priv->dev; + } + + return NULL; + +errout_with_dev: + sem_destroy(&priv->pendsem); + kmm_free(priv); + return NULL; +} diff --git a/drivers/audio/cs43l22.h b/drivers/audio/cs43l22.h new file mode 100644 index 0000000000..f2ec078e10 --- /dev/null +++ b/drivers/audio/cs43l22.h @@ -0,0 +1,388 @@ +/**************************************************************************** + * drivers/audio/cs43l22.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Reference: + * "CS43L22 Ultra Low Power CODEC for Portable Audio Applications, Pre- + * Production", September 2012, Rev 3.3, Wolfson Microelectronics + * + * 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 __DRIVERS_AUDIO_CS43L22_H +#define __DRIVERS_AUDIO_CS43L22_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include + +#include +#include + +#define getreg32(a) (*(volatile uint32_t *)(a)) +#define putreg32(v,a) (*(volatile uint32_t *)(a) = (v)) +#define getreg16(a) (*(volatile uint16_t *)(a)) +#define putreg16(v,a) (*(volatile uint16_t *)(a) = (v)) + +#ifdef CONFIG_AUDIO + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ +/* So far, I have not been able to get FLL lock interrupts. Worse, I have + * been able to get the FLL to claim that it is locked at all even when + * polling. What am I doing wrong? + * + * Hmmm.. seems unnecessary anyway + */ + +#undef CS43L22_USE_FFLOCK_INT +#undef CS43L22_USE_FFLOCK_POLL + +/* Registers Addresses ******************************************************/ + +#define CS43L22_ID_REV 0x01 /* Chip I.D. and Revision */ +#define CS43L22_POWER_CTRL1 0x02 /* Power Control 1 */ +#define CS43L22_POWER_CTRL2 0x04 /* Power Control 2 */ +#define CS43L22_CLOCK_CTRL 0x05 /* Clocking Control */ +#define CS43L22_INTERFACE_CTRL1 0x06 /* Interface Control 1 */ +#define CS43L22_INTERFACE_CTRL2 0x07 /* Interface Control 2 */ +#define CS43L22_PASS_SEL_A 0x08 /* Passthrough x Select: PassA */ +#define CS43L22_PASS_SEL_B 0x09 /* Passthrough x Select: PassB */ +#define CS43L22_ANLG_ZC_SR_SEL 0x0A /* Analog ZC and SR Settings */ +#define CS43L22_PASS_GANG_CTRL 0x0C /* Passthrough Gang Control */ +#define CS43L22_PLAYBACK_CTRL1 0x0D /* Playback Control 1 */ +#define CS43L22_MISCLLNS_CTRL 0x0E /* Miscellaneous Controls */ +#define CS43L22_PLAYBACK_CTRL2 0x0F /* Playback Control 2 */ +#define CS43L22_PASS_VOL_A 0x14 /* Passthrough x Volume: PASSAVOL */ +#define CS43L22_PASS_VOL_B 0x15 /* Passthrough x Volume: PASSBVOL */ +#define CS43L22_PCM_VOL_A 0x1A /* PCMx Volume: PCMA */ +#define CS43L22_PCM_VOL_B 0x1B /* PCMx Volume: PCMB */ +#define CS43L22_BP_FREQ_ON_TIME 0x1C /* Beep Frequency & On Time */ +#define CS43L22_BP_VOL_OFF_TIME 0x1D /* Beep Volume & Off Time */ +#define CS43L22_BP_TONE_CFG 0x1E /* Beep & Tone Configuration */ +#define CS43L22_TONE_CTRL 0x1F /* Tone Control */ +#define CS43L22_MS_VOL_CTRL_A 0x20 /* Master Volume Control: MSTA */ +#define CS43L22_MS_VOL_CTRL_B 0x21 /* Master Volume Control: MSTB */ +#define CS43L22_HP_VOL_CTRL_A 0x22 /* Headphone Volume Control: HPA */ +#define CS43L22_HP_VOL_CTRL_B 0x23 /* Headphone Volume Control: HPB */ +#define CS43L22_SPK_VOL_CTRL_A 0x24 /* Speaker Volume Control: SPKA */ +#define CS43L22_SPK_VOL_CTRL_B 0x25 /* Speaker Volume Control: SPKB */ +#define CS43L22_PCM_CH_SWAP 0x26 /* PCM Channel Swap */ +#define CS43L22_LIM_CTRL1 0x27 /* Limiter Control 1, Min/Max Thresholds */ +#define CS43L22_LIM_CTRL2 0x28 /* Limiter Control 2, Release Rate */ +#define CS43L22_LIM_ATTACK_RATE 0x29 /* Limiter Attack Rate */ +#define CS43L22_STATUS 0x2E /* Status */ +#define CS43L22_BAT_COMP 0x2F /* Battery Compensation */ +#define CS43L22_VP_BAT_LEVEL 0x30 /* VP Battery Level */ +#define CS43L22_SPK_STATUS 0x31 /* Speaker Status */ +#define CS43L22_TEMP_MON_CTRL 0x32 /* Temperature Monitor Control */ +#define CS43L22_THERMAL_FOLDBACK 0x33 /* Thermal Foldback */ +#define CS43L22_CHRG_PUMP_FREQ 0x34 /* Charge Pump Frequency */ + +#define CS43L22_HPBMUTE (1 << 7) +#define CS43L22_HPAMUTE (1 << 6) +#define CS43L22_SPKBMUTE (1 << 5) +#define CS43L22_SPKAMUTE (1 << 4) + +/* Register Default Values **************************************************/ +/* Registers have some undocumented bits set on power up. These probably + * should be retained on writes (?). + */ + +#define CS43L22_ID_REV_DEFAULT 0xe3 /* Chip I.D. and Revision */ +#define CS43L22_POWER_CTRL1_DEFAULT 0x01 /* Power Control 1 */ +#define CS43L22_POWER_CTRL2_DEFAULT 0x05 /* Power Control 2 */ +#define CS43L22_CLOCK_CTRL_DEFAULT 0xa0 /* Clocking Control */ +#define CS43L22_INTERFACE_CTRL1_DEFAULT 0x00 /* Interface Control 1 */ +#define CS43L22_INTERFACE_CTRL2_DEFAULT 0x00 /* Interface Control 2 */ +#define CS43L22_PASS_SEL_A_DEFAULT 0x81 /* Passthrough x Select: PassA */ +#define CS43L22_PASS_SEL_B_DEFAULT 0x81 /* Passthrough x Select: PassB */ +#define CS43L22_ANLG_ZC_SR_SEL_DEFAULT 0xa5 /* Analog ZC and SR Settings */ +#define CS43L22_PASS_GANG_CTRL_DEFAULT 0x00 /* Passthrough Gang Control */ +#define CS43L22_PLAYBACK_CTRL1_DEFAULT 0x60 /* Playback Control 1 */ +#define CS43L22_MISCLLNS_CTRL_DEFAULT 0x02 /* Miscellaneous Controls */ +#define CS43L22_PLAYBACK_CTRL2_DEFAULT 0x00 /* Playback Control 2 */ +#define CS43L22_PASS_VOL_A_DEFAULT 0x00 /* Passthrough x Volume: PASSAVOL */ +#define CS43L22_PASS_VOL_B_DEFAULT 0x00 /* Passthrough x Volume: PASSBVOL */ +#define CS43L22_PCM_VOL_A_DEFAULT 0x00 /* PCMx Volume: PCMA */ +#define CS43L22_PCM_VOL_B_DEFAULT 0x00 /* PCMx Volume: PCMB */ +#define CS43L22_BP_FREQ_ON_TIME_DEFAULT 0x00 /* Beep Frequency & On Time */ +#define CS43L22_BP_VOL_OFF_TIME_DEFAULT 0x00 /* Beep Volume & Off Time */ +#define CS43L22_BP_TONE_CFG_DEFAULT 0x00 /* Beep & Tone Configuration */ +#define CS43L22_TONE_CTRL_DEFAULT 0x88 /* Tone Control */ +#define CS43L22_MS_VOL_CTRL_A_DEFAULT 0x00 /* Master Volume Control: MSTA */ +#define CS43L22_MS_VOL_CTRL_B_DEFAULT 0x00 /* Master Volume Control: MSTB */ +#define CS43L22_HP_VOL_CTRL_A_DEFAULT 0x00 /* Headphone Volume Control: HPA */ +#define CS43L22_HP_VOL_CTRL_B_DEFAULT 0x00 /* Headphone Volume Control: HPB */ +#define CS43L22_SPK_VOL_CTRL_A_DEFAULT 0x00 /* Speaker Volume Control: SPKA */ +#define CS43L22_SPK_VOL_CTRL_B_DEFAULT 0x00 /* Speaker Volume Control: SPKB */ +#define CS43L22_PCM_CH_SWAP_DEFAULT 0x00 /* PCM Channel Swap */ +#define CS43L22_LIM_CTRL1_DEFAULT 0x00 /* Limiter Control 1, Min/Max Thresholds */ +#define CS43L22_LIM_CTRL2_DEFAULT 0x7f /* Limiter Control 2, Release Rate */ +#define CS43L22_LIM_ATTACK_RATE_DEFAULT 0xc0 /* Limiter Attack Rate */ +#define CS43L22_STATUS_DEFAULT 0x00 /* Status */ +#define CS43L22_BAT_COMP_DEFAULT 0x00 /* Battery Compensation */ +#define CS43L22_VP_BAT_LEVEL_DEFAULT 0x00 /* VP Battery Level */ +#define CS43L22_SPK_STATUS_DEFAULT 0x00 /* Speaker Status */ +#define CS43L22_TEMP_MON_CTRL_DEFAULT 0x3b /* Temperature Monitor Control */ +#define CS43L22_THERMAL_FOLDBACK_DEFAULT 0x00 /* Thermal Foldback */ +#define CS43L22_CHRG_PUMP_FREQ_DEFAULT 0x5f /* Charge Pump Frequency */ + +/* Register Bit Definitions *************************************************/ + +/* 0x01 Chip I.D. and Revision (Read Only) */ +#define CS43L22_DEV_ID_REV (0xe3) +#define CS43L22_ID_SHIFT (3) +#define CS43L22_ID_MASK (0x1f << CS43L22_ID_SHIFT) +#define CS43L22_REV_SHIFT (0) +#define CS43L22_REV_MASK (0x07 << CS43L22_REV_SHIFT) + +/* 0x02 Power Control 1 */ +#define CS43L22_POWER_DOWN (0x01) /* Powered Down */ +#define CS43L22_POWER_UP (0x9e) /* Powered Up */ + +/* 0x04 Power Control 2 */ +#define CS43L22_PDN_HPB_SHIFT (6) /* Bits 6-7: Headphone channel B Control */ +#define CS43L22_PDN_HPB_ON_HW_PIN_LO (0 << CS43L22_PDN_HPB_SHIFT) /* PDN_HPx[1:0] 00 Headphone channel is ON when the SPK/HP_SW pin, 6, is LO + Headphone channel is OFF when the SPK/HP_SW pin, 6, is HI */ +#define CS43L22_PDN_HPB_ON_HW_PIN_HI (1 << CS43L22_PDN_HPB_SHIFT) /* PDN_HPx[1:0] 01 Headphone channel is ON when the SPK/HP_SW pin, 6, is HI + Headphone channel is OFF when the SPK/HP_SW pin, 6, is LO */ +#define CS43L22_PDN_HPB_ON (2 << CS43L22_PDN_HPB_SHIFT) /* PDN_HPx[1:0] 10 Headphone channel is always ON */ +#define CS43L22_PDN_HPB_OFF (3 << CS43L22_PDN_HPB_SHIFT) /* PDN_HPx[1:0] 11 Headphone channel is always OFF */ + +#define CS43L22_PDN_HPA_SHIFT (4) /* Bits 4-5: Headphone channel A Control */ +#define CS43L22_PDN_HPA_ON_HW_PIN_LO (0 << CS43L22_PDN_HPA_SHIFT) /* PDN_HPx[1:0] 00 Headphone channel is ON when the SPK/HP_SW pin, 6, is LO + Headphone channel is OFF when the SPK/HP_SW pin, 6, is HI */ +#define CS43L22_PDN_HPA_ON_HW_PIN_HI (1 << CS43L22_PDN_HPA_SHIFT) /* PDN_HPx[1:0] 01 Headphone channel is ON when the SPK/HP_SW pin, 6, is HI + Headphone channel is OFF when the SPK/HP_SW pin, 6, is LO */ +#define CS43L22_PDN_HPA_ON (2 << CS43L22_PDN_HPA_SHIFT) /* PDN_HPx[1:0] 10 Headphone channel is always ON */ +#define CS43L22_PDN_HPA_OFF (3 << CS43L22_PDN_HPA_SHIFT) /* PDN_HPx[1:0] 11 Headphone channel is always OFF */ + +#define CS43L22_PDN_SPKB_SHIFT (2) /* Bits 2-3: Speaker channel B Control */ +#define CS43L22_PDN_SPKB_ON_HW_PIN_LO (0 << CS43L22_PDN_SPKB_SHIFT) /* PDN_HPx[1:0] 00 Speaker channel is ON when the SPK/HP_SW pin, 6, is LO + Speaker channel is OFF when the SPK/HP_SW pin, 6, is HI */ +#define CS43L22_PDN_SPKB_ON_HW_PIN_HI (1 << CS43L22_PDN_SPKB_SHIFT) /* PDN_HPx[1:0] 01 Speaker channel is ON when the SPK/HP_SW pin, 6, is HI + Speaker channel is OFF when the SPK/HP_SW pin, 6, is LO */ +#define CS43L22_PDN_SPKB_ON (2 << CS43L22_PDN_SPKB_SHIFT) /* PDN_HPx[1:0] 10 Speaker channel is always ON */ +#define CS43L22_PDN_SPKB_OFF (3 << CS43L22_PDN_SPKB_SHIFT) /* PDN_HPx[1:0] 11 Speaker channel is always OFF */ + +#define CS43L22_PDN_SPKA_SHIFT (0) /* Bits 0-1: Speaker channel A Control */ +#define CS43L22_PDN_SPKA_ON_HW_PIN_LO (0 << CS43L22_PDN_SPKA_SHIFT) /* PDN_HPx[1:0] 00 Speaker channel is ON when the SPK/HP_SW pin, 6, is LO + Speaker channel is OFF when the SPK/HP_SW pin, 6, is HI */ +#define CS43L22_PDN_SPKA_ON_HW_PIN_HI (1 << CS43L22_PDN_SPKA_SHIFT) /* PDN_HPx[1:0] 01 Speaker channel is ON when the SPK/HP_SW pin, 6, is HI + Speaker channel is OFF when the SPK/HP_SW pin, 6, is LO */ +#define CS43L22_PDN_SPKA_ON (2 << CS43L22_PDN_SPKA_SHIFT) /* PDN_HPx[1:0] 10 Speaker channel is always ON */ +#define CS43L22_PDN_SPKA_OFF (3 << CS43L22_PDN_SPKA_SHIFT) /* PDN_HPx[1:0] 11 Speaker channel is always OFF */ + +/* 0x05 Clocking Control */ +#define CS43L22_AUTO_DETECT_ENABLE (1 << 7) /* Auto-detection of speed mode enable */ + +#define CS43L22_SPEED_SHIFT (5) /* Bits 5-6: Speed mode */ +#define CS43L22_SPEED_DOUBLE (0 << CS43L22_SPEED_SHIFT) /* Slave: Double-Speed Mode (DSM - 50 kHz -100 kHz Fs) Master: MCLK=512 SCLK=64*/ +#define CS43L22_SPEED_SINGLE (1 << CS43L22_SPEED_SHIFT) /* Slave: Single-Speed Mode (SSM - 4 kHz -50 kHz Fs) Master: MCLK=256 SCLK=64*/ +#define CS43L22_SPEED_HALF (2 << CS43L22_SPEED_SHIFT) /* Slave: Half-Speed Mode (HSM - 12.5kHz -25 kHz Fs) Master: MCLK=128 SCLK=64*/ +#define CS43L22_SPEED_QUARTER (3 << CS43L22_SPEED_SHIFT) /* Slave: Quarter-Speed Mode (QSM - 4 kHz -12.5 kHz Fs)Master: MCLK=128 SCLK=64*/ + +#define CS43L22_32k_GROUP_ENABLE (1 << 4) /* Bit 4: Specifies whether or not the input/output sample rate is 8 kHz, 16 kHz or 32 kHz */ + +#define CS43L22_VIDEOCLK_ENABLE (1 << 3) /* Bit 3: Specifies whether or not the external MCLK frequency is 27 MHz */ + +#define CS43L22_MCLK_LRCK_RATIO_SHIFT (1) /* Bits 1-2: Internal MCLK/LRCK Ratio */ +#define CS43L22_RATIO_128_64 (0 << CS43L22_MCLK_LRCK_RATIO_SHIFT) /* RATIO[1:0] Internal MCLK Cycles per LRCK=128, SCLK/LRCK=64 Ratio in Master Mode */ +#define CS43L22_RATIO_125_62 (1 << CS43L22_MCLK_LRCK_RATIO_SHIFT) /* RATIO[1:0] Internal MCLK Cycles per LRCK=125, SCLK/LRCK=62 Ratio in Master Mode */ +#define CS43L22_RATIO_132_66 (2 << CS43L22_MCLK_LRCK_RATIO_SHIFT) /* RATIO[1:0] Internal MCLK Cycles per LRCK=132, SCLK/LRCK=66 Ratio in Master Mode */ +#define CS43L22_RATIO_136_68 (3 << CS43L22_MCLK_LRCK_RATIO_SHIFT) /* RATIO[1:0] Internal MCLK Cycles per LRCK=136, SCLK/LRCK=68 Ratio in Master Mode */ + +#define CS43L22_CLKDIV2_ENABLE (1 << 0) /* Bit 0: Divided by 2 */ + +/* 0x06 Interface Control 1 */ +#define CS43L22_MODE_MASTER (1 << 7) /* Configures the serial port I/O clocking */ + +#define CS43L22_SCLK_POLARITY_INVERT (1 << 6) /* Configures the polarity of the SCLK signal */ + +#define CS43L22_DSP_MODE_ENABLE (1 << 4) /* Configures a data-packed interface format for the DAC */ + +#define CS43L22_DAC_IF_FORMAT_SHIFT (2) /* Bits 2-3: Configures the digital interface format for data on SDIN */ +#define CS43L22_DAC_IF_LEFT_JUSTIFIED (0 << CS43L22_DAC_IF_FORMAT_SHIFT) /* DACDIF[1:0] Left Justified, up to 24-bit data */ +#define CS43L22_DAC_IF_I2S (1 << CS43L22_DAC_IF_FORMAT_SHIFT) /* DACDIF[1:0] I2S, up to 24-bit data */ +#define CS43L22_DAC_IF_RIGHT_JUSTIFIED (2 << CS43L22_DAC_IF_FORMAT_SHIFT) /* DACDIF[1:0] Right Justified */ +#define CS43L22_DAC_IF_RESERVED (3 << CS43L22_DAC_IF_FORMAT_SHIFT) /* DACDIF[1:0] Reserved */ + +#define CS43L22_AUDIO_WORD_LENGHT_SHIFT (0) /* Bits 0-1: Configures the audio sample word length used for the data into SDIN */ +#define CS43L22_AWL_DSP_32_RJ_24 (0 << CS43L22_AUDIO_WORD_LENGHT_SHIFT)/* AWL[1:0] DSP Mode: 32-bit data, Right Justified: 24-bit data */ +#define CS43L22_AWL_DSP_24_RJ_20 (1 << CS43L22_AUDIO_WORD_LENGHT_SHIFT)/* AWL[1:0] DSP Mode: 24-bit data, Right Justified: 20-bit data */ +#define CS43L22_AWL_DSP_20_RJ_18 (2 << CS43L22_AUDIO_WORD_LENGHT_SHIFT)/* AWL[1:0] DSP Mode: 20-bit data, Right Justified: 18-bit data */ +#define CS43L22_AWL_DSP_16_RJ_16 (3 << CS43L22_AUDIO_WORD_LENGHT_SHIFT)/* AWL[1:0] DSP Mode: 16 bit data, Right Justified: 16-bit data */ + +/* 0x0E Miscellaneous Controls */ +#define CS43L22_FREEZE (1 << 3) /* Configures a hold on all register settings */ +#define CS43L22_DEEMPHASIS_ENABLE (1 << 2) /* Configures a 15μs/50μs digital de-emphasis filter response on the headphone/line and speaker outputs */ + +/* 0x1F Tone Control */ +#define CS43L22_TREB_GAIN_SHIFT (4) /* Sets the gain of the treble shelving filter */ +#define CS43L22_TREB_GAIN(a) ((a) << CS43L22_TREB_GAIN_SHIFT) + /* TREB[3:0] Gain Setting:*/ + /* 0000 +12.0 dB */ + /* ··· ··· */ + /* 0111 +1.5 dB */ + /* 1000 0 dB */ + /* 1001 -1.5 dB */ + /* 1111 -10.5 dB */ + /* Step Size: 1.5 dB */ + +#define CS43L22_BASS_GAIN_SHIFT (0) /* Sets the gain of the bass shelving filter */ +#define CS43L22_BASS_GAIN(a) ((a) << CS43L22_BASS_GAIN_SHIFT) + /* BASS[3:0] Gain Setting:*/ + /* 0000 +12.0 dB */ + /* ··· ··· */ + /* 0111 +1.5 dB */ + /* 1000 0 dB */ + /* 1001 -1.5 dB */ + /* 1111 -10.5 dB */ + /* Step Size: 1.5 dB */ + +/* FLL Configuration *********************************************************/ +/* Default FLL configuration */ + +#define CS43L22_DEFAULT_SAMPRATE 11025 /* Initial sample rate */ +#define CS43L22_DEFAULT_NCHANNELS 1 /* Initial number of channels */ +#define CS43L22_DEFAULT_BPSAMP 16 /* Initial bits per sample */ + +#define CS43L22_NFLLRATIO 5 /* Number of FLL_RATIO values */ + +#define CS43L22_MINOUTDIV 4 /* Minimum FLL_OUTDIV divider */ +#define CS43L22_MAXOUTDIV 64 /* Maximum FLL_OUTDIV divider */ + +#define CS43L22_BCLK_MAXDIV 20 /* Maximum BCLK divider */ + +#define CS43L22_FRAMELEN8 14 /* Bits per frame for 8-bit data */ +#define CS43L22_FRAMELEN16 32 /* Bits per frame for 16-bit data */ + +/* Commonly defined and redefined macros */ + +#ifndef MIN +# define MIN(a,b) (((a) < (b)) ? (a) : (b)) +#endif + +#ifndef MAX +# define MAX(a,b) (((a) > (b)) ? (a) : (b)) +#endif + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +struct cs43l22_dev_s +{ + /* We are an audio lower half driver (We are also the upper "half" of + * the CS43L22 driver with respect to the board lower half driver). + * + * Terminology: Our "lower" half audio instances will be called dev for the + * publicly visible version and "priv" for the version that only this driver + * knows. From the point of view of this driver, it is the board lower + * "half" that is referred to as "lower". + */ + + struct audio_lowerhalf_s dev; /* CS43L22 audio lower half (this device) */ + + /* Our specific driver data goes here */ + + const FAR struct cs43l22_lower_s *lower; /* Pointer to the board lower functions */ + FAR struct i2c_master_s *i2c; /* I2C driver to use */ + FAR struct i2s_dev_s *i2s; /* I2S driver to use */ + struct dq_queue_s pendq; /* Queue of pending buffers to be sent */ + struct dq_queue_s doneq; /* Queue of sent buffers to be returned */ + mqd_t mq; /* Message queue for receiving messages */ + char mqname[16]; /* Our message queue name */ + pthread_t threadid; /* ID of our thread */ + uint32_t bitrate; /* Actual programmed bit rate */ + sem_t pendsem; /* Protect pendq */ +#ifdef CS43L22_USE_FFLOCK_INT + struct work_s work; /* Interrupt work */ +#endif + uint16_t samprate; /* Configured samprate (samples/sec) */ +#ifndef CONFIG_AUDIO_EXCLUDE_VOLUME +#ifndef CONFIG_AUDIO_EXCLUDE_BALANCE + uint16_t balance; /* Current balance level (b16) */ +#endif /* CONFIG_AUDIO_EXCLUDE_BALANCE */ + uint8_t volume; /* Current volume level {0..63} */ +#endif /* CONFIG_AUDIO_EXCLUDE_VOLUME */ + uint8_t nchannels; /* Number of channels (1 or 2) */ + uint8_t bpsamp; /* Bits per sample (8 or 16) */ + volatile uint8_t inflight; /* Number of audio buffers in-flight */ +#ifdef CS43L22_USE_FFLOCK_INT + volatile bool locked; /* FLL is locked */ +#endif + bool running; /* True: Worker thread is running */ + bool paused; /* True: Playing is paused */ + bool mute; /* True: Output is muted */ +#ifndef CONFIG_AUDIO_EXCLUDE_STOP + bool terminating; /* True: Stop requested */ +#endif + bool reserved; /* True: Device is reserved */ + volatile int result; /* The result of the last transfer */ +}; + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +#ifdef CONFIG_CS43L22_CLKDEBUG +extern const uint8_t g_sysclk_scaleb1[CS43L22_BCLK_MAXDIV+1]; +extern const uint8_t g_fllratio[CS43L22_NFLLRATIO]; +#endif + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Name: cs43l22_readreg + * + * Description + * Read the specified 8-bit register from the CS43L22 device. + * + ****************************************************************************/ + +#if defined(CONFIG_CS43L22_REGDUMP) || defined(CONFIG_CS43L22_CLKDEBUG) +struct cs43l22_dev_s; +uint8_t cs43l22_readreg(FAR struct cs43l22_dev_s *priv, uint8_t regaddr); +#endif + +#endif /* CONFIG_AUDIO */ +#endif /* __DRIVERS_AUDIO_CS43L22_H */ diff --git a/drivers/audio/cs43l22_debug.c b/drivers/audio/cs43l22_debug.c new file mode 100644 index 0000000000..2d39fe988a --- /dev/null +++ b/drivers/audio/cs43l22_debug.c @@ -0,0 +1,184 @@ +/**************************************************************************** + * drivers/audio/cs43l22_debug.c + * Audio device driver for Cirrus Logic CS43L22 Audio codec. + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Taras Drozdovsky + * + * References: + * - "CS43L22 Ultra Low Power CODEC for Portable Audio Applications, Pre- + * Production", September 2012, Rev b1, Cirrus Logic + * - The framework for this driver is based on Ken Pettit's VS1053 driver. + * + * 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 "cs43l22.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +#ifdef CONFIG_CS43L22_REGDUMP +struct cs43l22_regdump_s +{ + FAR const char *regname; + uint8_t regaddr; +}; +#endif + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +#ifdef CONFIG_CS43L22_REGDUMP +static const struct cs43l22_regdump_s g_cs43l22_debug[] = +{ + {"CHIP_ID_REV", CS43L22_ID_REV }, + {"POWER_CTRL1", CS43L22_POWER_CTRL1 }, + {"POWER_CTRL2", CS43L22_POWER_CTRL2 }, + {"CLOCK_CTRL", CS43L22_CLOCK_CTRL }, + {"INTERFACE_CTRL1", CS43L22_INTERFACE_CTRL1 }, + {"INTERFACE_CTRL2", CS43L22_INTERFACE_CTRL2 }, + {"PASS_SEL_A", CS43L22_PASS_SEL_A }, + {"PASS_SEL_B", CS43L22_PASS_SEL_B }, + {"ANLG_ZC_SR_SEL", CS43L22_ANLG_ZC_SR_SEL }, + {"PASS_GANG_CTRL", CS43L22_PASS_GANG_CTRL }, + {"PLAYBACK_CTRL1", CS43L22_PLAYBACK_CTRL1 }, + {"MISCLLNS_CTRL", CS43L22_MISCLLNS_CTRL }, + {"PLAYBACK_CTRL2", CS43L22_PLAYBACK_CTRL2 }, + {"PASS_VOL_A", CS43L22_PASS_VOL_A }, + {"PASS_VOL_B", CS43L22_PASS_VOL_B }, + {"PCM_VOL_A", CS43L22_PCM_VOL_A }, + {"PCM_VOL_B", CS43L22_PCM_VOL_B }, + {"BP_FREQ_ON_T", CS43L22_BP_FREQ_ON_TIME }, + {"BP_VOL_OFF_T", CS43L22_BP_VOL_OFF_TIME }, + {"BP_TONE_CFG", CS43L22_BP_TONE_CFG }, + {"TONE_CTRL", CS43L22_TONE_CTRL }, + {"MS_VOL_CTRL_A", CS43L22_MS_VOL_CTRL_A }, + {"MS_VOL_CTRL_B", CS43L22_MS_VOL_CTRL_B }, + {"HP_VOL_CTRL_A", CS43L22_HP_VOL_CTRL_A }, + {"HP_VOL_CTRL_B", CS43L22_HP_VOL_CTRL_B }, + {"SPK_VOL_CTRL_A", CS43L22_SPK_VOL_CTRL_A }, + {"SPK_VOL_CTRL_B", CS43L22_SPK_VOL_CTRL_B }, + {"PCM_CH_SWAP", CS43L22_PCM_CH_SWAP }, + {"LIM_CTRL1", CS43L22_LIM_CTRL1 }, + {"LIM_CTRL2", CS43L22_LIM_CTRL2 }, + {"LIM_ATTACK_RATE", CS43L22_LIM_ATTACK_RATE }, + {"STATUS", CS43L22_STATUS }, + {"BAT_COMP", CS43L22_BAT_COMP }, + {"VP_BAT_LEVEL", CS43L22_VP_BAT_LEVEL }, + {"SPK_STATUS", CS43L22_SPK_STATUS }, + {"TEMP_MON_CTRL", CS43L22_TEMP_MON_CTRL }, + {"THERMAL_FOLDBACK",CS43L22_THERMAL_FOLDBACK}, + {"CHRG_PUMP_FREQ", CS43L22_CHRG_PUMP_FREQ } +}; + +# define CS43L22_NREGISTERS (sizeof(g_cs43l22_debug)/sizeof(struct cs43l22_regdump_s)) +#endif /* CONFIG_CS43L22_REGDUMP */ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: cs43l22_dump_registers + * + * Description: + * Dump the contents of all CS43L22 registers to the syslog device + * + * Input Parameters: + * dev - The device instance returned by cs43l22_initialize + * + * Returned Value: + * None. + * + ****************************************************************************/ + +#ifdef CONFIG_CS43L22_REGDUMP +void cs43l22_dump_registers(FAR struct audio_lowerhalf_s *dev, + FAR const char *msg) +{ + int i; + + syslog(LOG_INFO, "CS43L22 Registers: %s\n", msg); + for (i = 0; i < CS43L22_NREGISTERS; i++) + { + syslog(LOG_INFO, "%16s[%02x]: %02x\n", + g_cs43l22_debug[i].regname, g_cs43l22_debug[i].regaddr, + cs43l22_readreg((FAR struct cs43l22_dev_s *)dev, + g_cs43l22_debug[i].regaddr)); + } +} +#endif /* CONFIG_CS43L22_REGDUMP */ + +/**************************************************************************** + * Name: cs43l22_clock_analysis + * + * Description: + * Analyze the settings in the clock chain and dump to syslog. + * + * Input Parameters: + * dev - The device instance returned by cs43l22_initialize + * + * Returned Value: + * None. + * + ****************************************************************************/ + +#ifdef CONFIG_CS43L22_CLKDEBUG +void cs43l22_clock_analysis(FAR struct audio_lowerhalf_s *dev, + FAR const char *msg) +{ + #warning Missing logic + /* TODO */ +} +#endif /* CONFIG_CS43L22_CLKDEBUG */ diff --git a/include/nuttx/audio/cs43l22.h b/include/nuttx/audio/cs43l22.h new file mode 100644 index 0000000000..9065478c2d --- /dev/null +++ b/include/nuttx/audio/cs43l22.h @@ -0,0 +1,280 @@ +/**************************************************************************** + * include/nuttx/audio/cs43l22.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Reference: + * "CS43L22 Ultra Low Power CODEC for Portable Audio Applications, Pre- + * Production", September 2012, Rev 3.3, Wolfson Microelectronics + * + * 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_AUDIO_CS43L22_H +#define __INCLUDE_NUTTX_AUDIO_CS43L22_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include + +#ifdef CONFIG_AUDIO_CS43L22 + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ +/* Configuration ************************************************************ + * + * CONFIG_AUDIO_CS43L22 - Enables CS43L22 support + * CONFIG_CS43L22_INITVOLUME - The initial volume level in the range {0..1000} + * CONFIG_CS43L22_INFLIGHT - Maximum number of buffers that the CS43L22 driver + * will send to the I2S driver before any have completed. + * CONFIG_CS43L22_MSG_PRIO - Priority of messages sent to the CS43L22 worker + * thread. + * CONFIG_CS43L22_BUFFER_SIZE - Preferred buffer size + * CONFIG_CS43L22_NUM_BUFFERS - Preferred number of buffers + * CONFIG_CS43L22_WORKER_STACKSIZE - Stack size to use when creating the the + * CS43L22 worker thread. + * CONFIG_CS43L22_REGDUMP - Enable logic to dump all CS43L22 registers to + * the SYSLOG device. + */ + +/* Pre-requisites */ + +#ifndef CONFIG_AUDIO +# error CONFIG_AUDIO is required for audio subsystem support +#endif + +#ifndef CONFIG_I2S +# error CONFIG_I2S is required by the CS43L22 driver +#endif + +#ifndef CONFIG_I2C +# error CONFIG_I2C is required by the CS43L22 driver +#endif + +#ifndef CONFIG_SCHED_WORKQUEUE +# error CONFIG_SCHED_WORKQUEUE is required by the CS43L22 driver +#endif + +/* Default configuration values */ + +#ifndef CONFIG_CS43L22_INITVOLUME +# define CONFIG_CS43L22_INITVOLUME 400 +#endif + +#ifndef CONFIG_CS43L22_INFLIGHT +# define CONFIG_CS43L22_INFLIGHT 2 +#endif + +#if CONFIG_CS43L22_INFLIGHT > 255 +# error CONFIG_CS43L22_INFLIGHT must fit in a uint8_t +#endif + +#ifndef CONFIG_CS43L22_MSG_PRIO +# define CONFIG_CS43L22_MSG_PRIO 1 +#endif + +#ifndef CONFIG_CS43L22_BUFFER_SIZE +# define CONFIG_CS43L22_BUFFER_SIZE 8192 +#endif + +#ifndef CONFIG_CS43L22_NUM_BUFFERS +# define CONFIG_CS43L22_NUM_BUFFERS 4 +#endif + +#ifndef CONFIG_CS43L22_WORKER_STACKSIZE +# define CONFIG_CS43L22_WORKER_STACKSIZE 768 +#endif + +/* Helper macros ************************************************************/ + +#define CS43L22_ATTACH(s,isr,arg) ((s)->attach(s,isr,arg)) +#define CS43L22_DETACH(s) ((s)->attach(s,NULL,NULL)) +#define CS43L22_ENABLE(s) ((s)->enable(s,true)) +#define CS43L22_DISABLE(s) ((s)->enable(s,false)) +#define CS43L22_RESTORE(s,e) ((s)->enable(s,e)) +#define CS43L22_HW_RESET(s) ((s)->reset(s)) + +/**************************************************************************** + * Public Types + ****************************************************************************/ +/* This is the type of the CS43L22 interrupt handler. The lower level code + * will intercept the interrupt and provide the upper level with the private + * data that was provided when the interrupt was attached. + */ + +struct cs43l22_lower_s; /* Forward reference. Defined below */ + +typedef CODE int (*cs43l22_handler_t)(FAR const struct cs43l22_lower_s *lower, + FAR void *arg); + +/* A reference to a structure of this type must be passed to the CS43L22 + * driver. This structure provides information about the configuration + * of the CS43L22 and provides some board-specific hooks. + * + * Memory for this structure is provided by the caller. It is not copied + * by the driver and is presumed to persist while the driver is active. + */ + +struct cs43l22_lower_s +{ + /* I2C characterization */ + + uint32_t frequency; /* Initial I2C frequency */ + uint8_t address; /* 7-bit I2C address (only bits 0-6 used) */ + + /* Clocking is provided via MCLK. The CS43L22 driver will need to know + * the frequency of MCLK in order to generate the correct bitrates. + */ + + uint32_t mclk; /* CS43L22 Master clock frequency */ + + /* IRQ/GPIO access callbacks. These operations all hidden behind + * callbacks to isolate the CS43L22 driver from differences in GPIO + * interrupt handling by varying boards and MCUs. If possible, + * interrupts should be configured on both rising and falling edges + * so that contact and loss-of-contact events can be detected. + * + * attach - Attach or detach the CS43L22 interrupt handler to the GPIO + * interrupt + * enable - Enable or disable the GPIO interrupt. Returns the + * previous interrupt state. + * reset - HW reset of the CS43L22 chip + */ + + CODE int (*attach)(FAR const struct cs43l22_lower_s *lower, + cs43l22_handler_t isr, FAR void *arg); + CODE bool (*enable)(FAR const struct cs43l22_lower_s *lower, bool enable); + CODE void (*reset)(FAR const struct cs43l22_lower_s *lower); +}; + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Name: cs43l22_initialize + * + * Description: + * Initialize the CS43L22 device. + * + * Input Parameters: + * i2c - An I2C driver instance + * i2s - An I2S driver instance + * lower - Persistent board configuration data + * + * Returned Value: + * A new lower half audio interface for the CS43L22 device is returned on + * success; NULL is returned on failure. + * + ****************************************************************************/ + +struct i2c_master_s; /* Forward reference. Defined in include/nuttx/i2c/i2c_master.h */ +struct i2s_dev_s; /* Forward reference. Defined in include/nuttx/audio/i2s.h */ +struct audio_lowerhalf_s; /* Forward reference. Defined in nuttx/audio/audio.h */ + +FAR struct audio_lowerhalf_s * + cs43l22_initialize(FAR struct i2c_master_s *i2c, FAR struct i2s_dev_s *i2s, + FAR const struct cs43l22_lower_s *lower); + +/**************************************************************************** + * Name: cs43l22_dump_registers + * + * Description: + * Dump the contents of all CS43L22 registers to the syslog device + * + * Input Parameters: + * dev - The device instance returned by cs43l22_initialize + * + * Returned Value: + * None. + * + ****************************************************************************/ + +#ifdef CONFIG_CS43L22_REGDUMP +void cs43l22_dump_registers(FAR struct audio_lowerhalf_s *dev, + FAR const char *msg); +#else + /* This eliminates the need for any conditional compilation in the + * including file. + */ + +# define cs43l22_dump_registers(d,m) +#endif + +/**************************************************************************** + * Name: cs43l22_clock_analysis + * + * Description: + * Analyze the settings in the clock chain and dump to syslog. + * + * Input Parameters: + * dev - The device instance returned by cs43l22_initialize + * + * Returned Value: + * None. + * + ****************************************************************************/ + +#ifdef CONFIG_CS43L22_CLKDEBUG +void cs43l22_clock_analysis(FAR struct audio_lowerhalf_s *dev, + FAR const char *msg); +#else + /* This eliminates the need for any conditional compilation in the + * including file. + */ + +# define cs43l22_clock_analysis(d,m) +#endif + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* CONFIG_AUDIO_CS43L22 */ +#endif /* __INCLUDE_NUTTX_AUDIO_CS43L22_H */ -- GitLab From 7ffbb704d66c75c84f9b4b346092b8e96ca3421f Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 21 May 2017 14:28:29 -0600 Subject: [PATCH 850/990] This is based on a patch by Taras Drozdovsky. Basically, the delay that was added during the integration of the CDC/ACM host driver was interfering with streaming audio. That delay was put there to prevent build endpoints from hogging the system bandwidth. So what do we do? Do we hog the bandwidth or do we insert arbitrarity delays. I think both ideas such. --- arch/arm/src/stm32/stm32_otgfshost.c | 21 ++++++++++++++++----- arch/arm/src/stm32/stm32_otghshost.c | 21 ++++++++++++++++----- arch/arm/src/stm32f7/stm32_otghost.c | 21 ++++++++++++++++----- 3 files changed, 48 insertions(+), 15 deletions(-) diff --git a/arch/arm/src/stm32/stm32_otgfshost.c b/arch/arm/src/stm32/stm32_otgfshost.c index b28226f5f2..bf3bbc8b91 100644 --- a/arch/arm/src/stm32/stm32_otgfshost.c +++ b/arch/arm/src/stm32/stm32_otgfshost.c @@ -1952,14 +1952,25 @@ static ssize_t stm32_in_transfer(FAR struct stm32_usbhost_s *priv, int chidx, delay = 1000; } - /* Wait for the next polling interval. + /* Wait for the next polling interval. For interrupt and + * isochronous endpoints, this is necessaryto assure the + * polling interval. It is used in other cases only to + * prevent the polling from consuming too much CPU bandwith. * - * REVISIT: This delay could require more resolution than - * is provided by the system timer. In that case, the - * delay could be significantly longer than required. + * Small delays could require more resolution than is provided + * by the system timer. For example, if the system timer + * resolution is 10MS, then usleep(1000) will actually request + * a delay 20MS (due to both quantization and rounding). + * + * REVISIT: So which is better? To ignore tiny delays and + * hog the system bandwidth? Or to wait for an excessive + * amount and destroy system throughput? */ - usleep(delay); + if (delay > CONFIG_USEC_PER_TICK) + { + usleep(delay - CONFIG_USEC_PER_TICK); + } } } else diff --git a/arch/arm/src/stm32/stm32_otghshost.c b/arch/arm/src/stm32/stm32_otghshost.c index 17023088b6..1836808764 100644 --- a/arch/arm/src/stm32/stm32_otghshost.c +++ b/arch/arm/src/stm32/stm32_otghshost.c @@ -1957,14 +1957,25 @@ static ssize_t stm32_in_transfer(FAR struct stm32_usbhost_s *priv, int chidx, delay = 1000; } - /* Wait for the next polling interval. + /* Wait for the next polling interval. For interrupt and + * isochronous endpoints, this is necessaryto assure the + * polling interval. It is used in other cases only to + * prevent the polling from consuming too much CPU bandwith. * - * REVISIT: This delay could require more resolution than - * is provided by the system timer. In that case, the - * delay could be significantly longer than required. + * Small delays could require more resolution than is provided + * by the system timer. For example, if the system timer + * resolution is 10MS, then usleep(1000) will actually request + * a delay 20MS (due to both quantization and rounding). + * + * REVISIT: So which is better? To ignore tiny delays and + * hog the system bandwidth? Or to wait for an excessive + * amount and destroy system throughput? */ - usleep(delay); + if (delay > CONFIG_USEC_PER_TICK) + { + usleep(delay - CONFIG_USEC_PER_TICK); + } } } else diff --git a/arch/arm/src/stm32f7/stm32_otghost.c b/arch/arm/src/stm32f7/stm32_otghost.c index f0307be640..92fc2bc7d0 100644 --- a/arch/arm/src/stm32f7/stm32_otghost.c +++ b/arch/arm/src/stm32f7/stm32_otghost.c @@ -1951,14 +1951,25 @@ static ssize_t stm32_in_transfer(FAR struct stm32_usbhost_s *priv, int chidx, delay = 1000; } - /* Wait for the next polling interval. + /* Wait for the next polling interval. For interrupt and + * isochronous endpoints, this is necessaryto assure the + * polling interval. It is used in other cases only to + * prevent the polling from consuming too much CPU bandwith. * - * REVISIT: This delay could require more resolution than - * is provided by the system timer. In that case, the - * delay could be significantly longer than required. + * Small delays could require more resolution than is provided + * by the system timer. For example, if the system timer + * resolution is 10MS, then usleep(1000) will actually request + * a delay 20MS (due to both quantization and rounding). + * + * REVISIT: So which is better? To ignore tiny delays and + * hog the system bandwidth? Or to wait for an excessive + * amount and destroy system throughput? */ - usleep(delay); + if (delay > CONFIG_USEC_PER_TICK) + { + usleep(delay - CONFIG_USEC_PER_TICK); + } } } else -- GitLab From 32eb5ca99a8d096465d91764908303a4d1a62cad Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 21 May 2017 15:02:00 -0600 Subject: [PATCH 851/990] Missed one change in the previous commit. --- arch/arm/src/stm32l4/stm32l4_otgfshost.c | 21 ++++++++++++++++----- 1 file changed, 16 insertions(+), 5 deletions(-) diff --git a/arch/arm/src/stm32l4/stm32l4_otgfshost.c b/arch/arm/src/stm32l4/stm32l4_otgfshost.c index 573cf892a5..aadae1721c 100644 --- a/arch/arm/src/stm32l4/stm32l4_otgfshost.c +++ b/arch/arm/src/stm32l4/stm32l4_otgfshost.c @@ -1956,14 +1956,25 @@ static ssize_t stm32l4_in_transfer(FAR struct stm32l4_usbhost_s *priv, delay = 1000; } - /* Wait for the next polling interval. + /* Wait for the next polling interval. For interrupt and + * isochronous endpoints, this is necessaryto assure the + * polling interval. It is used in other cases only to + * prevent the polling from consuming too much CPU bandwith. * - * REVISIT: This delay could require more resolution than - * is provided by the system timer. In that case, the - * delay could be significantly longer than required. + * Small delays could require more resolution than is provided + * by the system timer. For example, if the system timer + * resolution is 10MS, then usleep(1000) will actually request + * a delay 20MS (due to both quantization and rounding). + * + * REVISIT: So which is better? To ignore tiny delays and + * hog the system bandwidth? Or to wait for an excessive + * amount and destroy system throughput? */ - usleep(delay); + if (delay > CONFIG_USEC_PER_TICK) + { + usleep(delay - CONFIG_USEC_PER_TICK); + } } } else -- GitLab From 0fdb000e53612f492de2e170fc854fadcd7c148b Mon Sep 17 00:00:00 2001 From: Taras Drozdovsky Date: Sun, 21 May 2017 17:09:53 -0600 Subject: [PATCH 852/990] Fix define CONFIG_AUDIO_CS43L22 typo --- configs/stm32f4discovery/src/stm32f4discovery.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/configs/stm32f4discovery/src/stm32f4discovery.h b/configs/stm32f4discovery/src/stm32f4discovery.h index ebb618095e..eaeed15448 100644 --- a/configs/stm32f4discovery/src/stm32f4discovery.h +++ b/configs/stm32f4discovery/src/stm32f4discovery.h @@ -151,7 +151,7 @@ /* The CS43L22 depends on the CS43L22 driver, I2C1, and I2S3 support */ -#if !defiend(CONFIG_AUDIO_CS43L22) || !defined(CONFIG_STM32_I2C1) || \ +#if !defined(CONFIG_AUDIO_CS43L22) || !defined(CONFIG_STM32_I2C1) || \ !defined(CONFIG_STM32_I2S3) # undef HAVE_CS43L22 #endif -- GitLab From a862b653bd6657a60dbc3ae280fa2a2d04891b5d Mon Sep 17 00:00:00 2001 From: Nobutaka Toyoshima Date: Tue, 9 Sep 2014 09:38:32 +0900 Subject: [PATCH 853/990] Replace sprintf() with snprintf() in pipe.c Jira: PDFW15IS-265 Coverity-ID: 10696 Signed-off-by: Masayuki Ishikawa --- drivers/pipes/pipe.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/drivers/pipes/pipe.c b/drivers/pipes/pipe.c index eb898bfec7..8ffa3a2d7c 100644 --- a/drivers/pipes/pipe.c +++ b/drivers/pipes/pipe.c @@ -218,7 +218,7 @@ int pipe2(int fd[2], size_t bufsize) /* Create a pathname to the pipe device */ - sprintf(devname, "/dev/pipe%d", pipeno); + snprintf(devname, sizeof(devname), "/dev/pipe%d", pipeno); /* Check if the pipe device has already been created */ -- GitLab From 810f9b516c6ca8246f9afe9acf33089630c623b7 Mon Sep 17 00:00:00 2001 From: Masayuki Ishikawa Date: Tue, 9 Sep 2014 12:54:42 +0900 Subject: [PATCH 854/990] drivers/bch: Fix 'Missing Unlock' in bchdev_driver.c Jira: PDFW15IS-265 Coverity-ID: 10597 Signed-off-by: Masayuki Ishikawa --- drivers/bch/bchdev_driver.c | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/drivers/bch/bchdev_driver.c b/drivers/bch/bchdev_driver.c index 438bdfd9d0..9a7f8dcbd2 100644 --- a/drivers/bch/bchdev_driver.c +++ b/drivers/bch/bchdev_driver.c @@ -113,6 +113,7 @@ static int bch_open(FAR struct file *filep) { FAR struct inode *inode = filep->f_inode; FAR struct bchlib_s *bch; + int ret = OK; DEBUGASSERT(inode && inode->i_private); bch = (FAR struct bchlib_s *)inode->i_private; @@ -122,7 +123,7 @@ static int bch_open(FAR struct file *filep) bchlib_semtake(bch); if (bch->refs == MAX_OPENCNT) { - return -EMFILE; + ret = -EMFILE; } else { @@ -130,7 +131,7 @@ static int bch_open(FAR struct file *filep) } bchlib_semgive(bch); - return OK; + return ret; } /**************************************************************************** -- GitLab From 99bdab3ac32bfc590f9c54ee214da412ed4c8027 Mon Sep 17 00:00:00 2001 From: Masayuki Ishikawa Date: Tue, 9 Sep 2014 13:30:04 +0900 Subject: [PATCH 855/990] FAT: Fix 'Missing unlock' in fs_fat32.c Jira: PDFW15IS-265 Coverity-ID: 10590 10589 Signed-off-by: Masayuki Ishikawa --- fs/fat/fs_fat32.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/fs/fat/fs_fat32.c b/fs/fat/fs_fat32.c index 78df1f1024..7c0c610332 100644 --- a/fs/fat/fs_fat32.c +++ b/fs/fat/fs_fat32.c @@ -547,7 +547,7 @@ static ssize_t fat_read(FAR struct file *filep, FAR char *buffer, ret = fat_currentsector(fs, ff, filep->f_pos); if (ret < 0) { - return ret; + goto errout_with_semaphore; } } @@ -799,7 +799,7 @@ static ssize_t fat_write(FAR struct file *filep, FAR const char *buffer, ret = fat_currentsector(fs, ff, filep->f_pos); if (ret < 0) { - return ret; + goto errout_with_semaphore; } } -- GitLab From 2b028bc4e5c7e9e0c0af55ac0cabdc7b51df71a7 Mon Sep 17 00:00:00 2001 From: Masayuki Ishikawa Date: Tue, 23 May 2017 15:56:33 +0900 Subject: [PATCH 856/990] netdb: Fix time info in lib_dnscache.c Signed-off-by: Masayuki Ishikawa --- libc/netdb/lib_dnscache.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libc/netdb/lib_dnscache.c b/libc/netdb/lib_dnscache.c index 30cfdcd577..ee7d0e68e8 100644 --- a/libc/netdb/lib_dnscache.c +++ b/libc/netdb/lib_dnscache.c @@ -156,7 +156,7 @@ void dns_save_answer(FAR const char *hostname, #if CONFIG_NETDB_DNSCLIENT_LIFESEC > 0 /* Get the current time, using CLOCK_MONOTONIC if possible */ - (void)clock_settime(DNS_CLOCK, &now); + (void)clock_gettime(DNS_CLOCK, &now); entry->ctime = (time_t)now.tv_sec; #endif @@ -218,7 +218,7 @@ int dns_find_answer(FAR const char *hostname, FAR struct sockaddr *addr, #if CONFIG_NETDB_DNSCLIENT_LIFESEC > 0 /* Get the current time, using CLOCK_MONOTONIC if possible */ - ret = clock_settime(DNS_CLOCK, &now); + ret = clock_gettime(DNS_CLOCK, &now); #endif /* REVISIT: This is not thread safe */ -- GitLab From 0c9abbfe679e7f8b520dc2432043696098a44557 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Tue, 23 May 2017 07:02:13 -0600 Subject: [PATCH 857/990] STM32L4: Add IWDG peripheral. This is the same as for STM32 except that prescale and reload can be changed after watchdog has been started, as this seems to work on L4. --- arch/arm/src/stm32/stm32_iwdg.c | 4 - arch/arm/src/stm32l4/Make.defs | 7 +- arch/arm/src/stm32l4/README.txt | 8 +- arch/arm/src/stm32l4/chip/stm32l4_wdg.h | 154 ++++++ arch/arm/src/stm32l4/stm32l4_iwdg.c | 658 ++++++++++++++++++++++++ arch/arm/src/stm32l4/stm32l4_lsi.c | 87 ++++ arch/arm/src/stm32l4/stm32l4_wdg.h | 119 +++++ 7 files changed, 1027 insertions(+), 10 deletions(-) create mode 100644 arch/arm/src/stm32l4/chip/stm32l4_wdg.h create mode 100644 arch/arm/src/stm32l4/stm32l4_iwdg.c create mode 100644 arch/arm/src/stm32l4/stm32l4_lsi.c diff --git a/arch/arm/src/stm32/stm32_iwdg.c b/arch/arm/src/stm32/stm32_iwdg.c index 64495b71ab..7b114fefa5 100644 --- a/arch/arm/src/stm32/stm32_iwdg.c +++ b/arch/arm/src/stm32/stm32_iwdg.c @@ -271,10 +271,6 @@ static void stm32_putreg(uint16_t val, uint32_t addr) * Input Parameters: * priv - A pointer the internal representation of the "lower-half" * driver state structure. - * timeout - The new timeout value in milliseconds. - * - * Returned Values: - * Zero on success; a negated errno value on failure. * ****************************************************************************/ diff --git a/arch/arm/src/stm32l4/Make.defs b/arch/arm/src/stm32l4/Make.defs index 313e4195e7..5454ddc127 100644 --- a/arch/arm/src/stm32l4/Make.defs +++ b/arch/arm/src/stm32l4/Make.defs @@ -102,8 +102,8 @@ CHIP_ASRCS = CHIP_CSRCS = stm32l4_allocateheap.c stm32l4_exti_gpio.c stm32l4_gpio.c CHIP_CSRCS += stm32l4_idle.c stm32l4_irq.c stm32l4_lowputc.c stm32l4_rcc.c CHIP_CSRCS += stm32l4_serial.c stm32l4_start.c stm32l4_waste.c stm32l4_uid.c -CHIP_CSRCS += stm32l4_spi.c stm32l4_i2c.c stm32l4_lse.c stm32l4_pwr.c -CHIP_CSRCS += stm32l4_tim.c stm32l4_flash.c +CHIP_CSRCS += stm32l4_spi.c stm32l4_i2c.c stm32l4_lse.c stm32l4_lsi.c +CHIP_CSRCS += stm32l4_pwr.c stm32l4_tim.c stm32l4_flash.c ifeq ($(CONFIG_TIMER),y) CHIP_CSRCS += stm32l4_tim_lowerhalf.c @@ -216,3 +216,6 @@ ifeq ($(CONFIG_STM32L4_FIREWALL),y) CHIP_CSRCS += stm32l4_firewall.c endif +ifeq ($(CONFIG_STM32L4_IWDG),y) +CHIP_CSRCS += stm32l4_iwdg.c +endif diff --git a/arch/arm/src/stm32l4/README.txt b/arch/arm/src/stm32l4/README.txt index 9124d966a7..6adf0eac12 100644 --- a/arch/arm/src/stm32l4/README.txt +++ b/arch/arm/src/stm32l4/README.txt @@ -8,7 +8,7 @@ Most code is copied and adapted from the STM32 Port. TODO list --------- -Peripherals with equivalent implementation in STM32 port +Peripherals with implementation in STM32 port: IRQs : OK GPIO : OK @@ -42,10 +42,11 @@ AES : TODO RNG : works CRC : TODO (configurable polynomial) WWDG : TODO -IWDG : TODO +IWDG : works MMCSD : TODO ADC : TODO DAC : TODO +DMA2D : TODO (Chrom-Art Accelerator for image manipulation) New peripherals with implementation to be written from scratch These are Low Priority TODO items, unless someone requests or contributes @@ -61,7 +62,6 @@ COMP : There is some code (Analog comparators) DFSDM : TODO (Digital Filter and Sigma-Delta Modulator) LCD : TODO (Segment LCD controller) SAIPLL : works (PLL For Digital Audio interfaces, and other things) -SAI : TODO (Digital Audio interfaces, I2S, SPDIF, etc) +SAI : There is some code (Digital Audio interfaces, I2S, SPDIF, etc) HASH : TODO (SHA-1, SHA-224, SHA-256, HMAC) DCMI : TODO (Digital Camera interfaces) -DMA2D : TODO (Chrom-Art Accelerator for image manipulation) diff --git a/arch/arm/src/stm32l4/chip/stm32l4_wdg.h b/arch/arm/src/stm32l4/chip/stm32l4_wdg.h new file mode 100644 index 0000000000..9c381f790a --- /dev/null +++ b/arch/arm/src/stm32l4/chip/stm32l4_wdg.h @@ -0,0 +1,154 @@ +/************************************************************************************ + * arch/arm/src/stm32l4/chip/stm32l4_wdg.h + * + * Copyright (C) 2009, 2011-2013, 2017 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * 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 __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4_WDG_H +#define __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4_WDG_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include "chip.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Register Offsets *****************************************************************/ + +#define STM32L4_IWDG_KR_OFFSET 0x0000 /* Key register (32-bit) */ +#define STM32L4_IWDG_PR_OFFSET 0x0004 /* Prescaler register (32-bit) */ +#define STM32L4_IWDG_RLR_OFFSET 0x0008 /* Reload register (32-bit) */ +#define STM32L4_IWDG_SR_OFFSET 0x000c /* Status register (32-bit) */ +#define STM32L4_IWDG_WINR_OFFSET 0x0010 /* Window register (32-bit) */ + +#define STM32L4_WWDG_CR_OFFSET 0x0000 /* Control Register (32-bit) */ +#define STM32L4_WWDG_CFR_OFFSET 0x0004 /* Configuration register (32-bit) */ +#define STM32L4_WWDG_SR_OFFSET 0x0008 /* Status register (32-bit) */ + +/* Register Addresses ***************************************************************/ + +#define STM32L4_IWDG_KR (STM32L4_IWDG_BASE+STM32L4_IWDG_KR_OFFSET) +#define STM32L4_IWDG_PR (STM32L4_IWDG_BASE+STM32L4_IWDG_PR_OFFSET) +#define STM32L4_IWDG_RLR (STM32L4_IWDG_BASE+STM32L4_IWDG_RLR_OFFSET) +#define STM32L4_IWDG_SR (STM32L4_IWDG_BASE+STM32L4_IWDG_SR_OFFSET) +#define STM32L4_IWDG_WINR (STM32L4_IWDG_BASE+STM32L4_IWDG_WINR_OFFSET) + +#define STM32L4_WWDG_CR (STM32L4_WWDG_BASE+STM32L4_WWDG_CR_OFFSET) +#define STM32L4_WWDG_CFR (STM32L4_WWDG_BASE+STM32L4_WWDG_CFR_OFFSET) +#define STM32L4_WWDG_SR (STM32L4_WWDG_BASE+STM32L4_WWDG_SR_OFFSET) + +/* Register Bitfield Definitions ****************************************************/ + +/* Key register (32-bit) */ + +#define IWDG_KR_KEY_SHIFT (0) /* Bits 15:0: Key value (write only, read 0000h) */ +#define IWDG_KR_KEY_MASK (0xffff << IWDG_KR_KEY_SHIFT) + +#define IWDG_KR_KEY_ENABLE (0x5555) /* Enable register access */ +#define IWDG_KR_KEY_DISABLE (0x0000) /* Disable register access */ +#define IWDG_KR_KEY_RELOAD (0xaaaa) /* Reload the counter */ +#define IWDG_KR_KEY_START (0xcccc) /* Start the watchdog */ + +/* Prescaler register (32-bit) */ + +#define IWDG_PR_SHIFT (0) /* Bits 2:0: Prescaler divider */ +#define IWDG_PR_MASK (7 << IWDG_PR_SHIFT) +# define IWDG_PR_DIV4 (0 << IWDG_PR_SHIFT) /* 000: divider /4 */ +# define IWDG_PR_DIV8 (1 << IWDG_PR_SHIFT) /* 001: divider /8 */ +# define IWDG_PR_DIV16 (2 << IWDG_PR_SHIFT) /* 010: divider /16 */ +# define IWDG_PR_DIV32 (3 << IWDG_PR_SHIFT) /* 011: divider /32 */ +# define IWDG_PR_DIV64 (4 << IWDG_PR_SHIFT) /* 100: divider /64 */ +# define IWDG_PR_DIV128 (5 << IWDG_PR_SHIFT) /* 101: divider /128 */ +# define IWDG_PR_DIV256 (6 << IWDG_PR_SHIFT) /* 11x: divider /256 */ + +/* Reload register (32-bit) */ + +#define IWDG_RLR_RL_SHIFT (0) /* Bits 11:0 RL[11:0]: Watchdog counter reload value */ +#define IWDG_RLR_RL_MASK (0x0fff << IWDG_RLR_RL_SHIFT) + +#define IWDG_RLR_MAX (0xfff) + +/* Status register (32-bit) */ + +#define IWDG_SR_PVU (1 << 0) /* Bit 0: Watchdog prescaler value update */ +#define IWDG_SR_RVU (1 << 1) /* Bit 1: Watchdog counter reload value update */ +#define IWDG_SR_WVU (1 << 2) /* Bit 2: Watchdog counter window value update */ + +/* Window register (32-bit) */ + +#define IWDG_WINR_SHIFT (0) /* Bits 11:0 WIN[11:0]: Watchdog counter window value */ +#define IWDG_WINR_MASK (0x0fff << IWDG_WINR_SHIFT) + +/* Control Register (32-bit) */ + +#define WWDG_CR_T_SHIFT (0) /* Bits 6:0 T[6:0]: 7-bit counter (MSB to LSB) */ +#define WWDG_CR_T_MASK (0x7f << WWDG_CR_T_SHIFT) +# define WWDG_CR_T_MAX (0x3f << WWDG_CR_T_SHIFT) +# define WWDG_CR_T_RESET (0x40 << WWDG_CR_T_SHIFT) +#define WWDG_CR_WDGA (1 << 7) /* Bit 7: Activation bit */ + +/* Configuration register (32-bit) */ + +#define WWDG_CFR_W_SHIFT (0) /* Bits 6:0 W[6:0] 7-bit window value */ +#define WWDG_CFR_W_MASK (0x7f << WWDG_CFR_W_SHIFT) +#define WWDG_CFR_WDGTB_SHIFT (7) /* Bits 8:7 [1:0]: Timer Base */ +#define WWDG_CFR_WDGTB_MASK (3 << WWDG_CFR_WDGTB_SHIFT) +# define WWDG_CFR_PCLK1 (0 << WWDG_CFR_WDGTB_SHIFT) /* 00: CK Counter Clock (PCLK1 div 4096) div 1 */ +# define WWDG_CFR_PCLK1d2 (1 << WWDG_CFR_WDGTB_SHIFT) /* 01: CK Counter Clock (PCLK1 div 4096) div 2 */ +# define WWDG_CFR_PCLK1d4 (2 << WWDG_CFR_WDGTB_SHIFT) /* 10: CK Counter Clock (PCLK1 div 4096) div 4 */ +# define WWDG_CFR_PCLK1d8 (3 << WWDG_CFR_WDGTB_SHIFT) /* 11: CK Counter Clock (PCLK1 div 4096) div 8 */ +#define WWDG_CFR_EWI (1 << 9) /* Bit 9: Early Wakeup Interrupt */ + +/* Status register (32-bit) */ + +#define WWDG_SR_EWIF (1 << 0) /* Bit 0: Early Wakeup Interrupt Flag */ + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4_WDG_H */ diff --git a/arch/arm/src/stm32l4/stm32l4_iwdg.c b/arch/arm/src/stm32l4/stm32l4_iwdg.c new file mode 100644 index 0000000000..9977e4d727 --- /dev/null +++ b/arch/arm/src/stm32l4/stm32l4_iwdg.c @@ -0,0 +1,658 @@ +/**************************************************************************** + * arch/arm/src/stm32l4/stm32l4_iwdg.c + * + * Copyright (C) 2012, 2016, 2017 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * 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 "up_arch.h" +#include "stm32l4_rcc.h" +#include "chip/stm32l4_dbgmcu.h" +#include "stm32l4_wdg.h" + +#if defined(CONFIG_WATCHDOG) && defined(CONFIG_STM32L4_IWDG) + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ +/* Clocking *****************************************************************/ +/* The minimum frequency of the IWDG clock is: + * + * Fmin = Flsi / 256 + * + * So the maximum delay (in milliseconds) is then: + * + * 1000 * IWDG_RLR_MAX / Fmin + * + * For example, if Flsi = 30Khz (the nominal, uncalibrated value), then the + * maximum delay is: + * + * Fmin = 117.1875 + * 1000 * 4095 / Fmin = 34,944 MSec + */ + +#define IWDG_FMIN (STM32L4_LSI_FREQUENCY / 256) +#define IWDG_MAXTIMEOUT (1000 * IWDG_RLR_MAX / IWDG_FMIN) + +/* Configuration ************************************************************/ + +#ifndef CONFIG_STM32L4_IWDG_DEFTIMOUT +# define CONFIG_STM32L4_IWDG_DEFTIMOUT IWDG_MAXTIMEOUT +#endif + +#ifndef CONFIG_DEBUG_WATCHDOG_INFO +# undef CONFIG_STM32L4_IWDG_REGDEBUG +#endif + +/**************************************************************************** + * Private Types + ****************************************************************************/ +/* This structure provides the private representation of the "lower-half" + * driver state structure. This structure must be cast-compatible with the + * well-known watchdog_lowerhalf_s structure. + */ + +struct stm32l4_lowerhalf_s +{ + FAR const struct watchdog_ops_s *ops; /* Lower half operations */ + uint32_t lsifreq; /* The calibrated frequency of the LSI oscillator */ + uint32_t timeout; /* The (actual) selected timeout */ + uint32_t lastreset; /* The last reset time */ + bool started; /* true: The watchdog timer has been started */ + uint8_t prescaler; /* Clock prescaler value */ + uint16_t reload; /* Timer reload value */ +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ +/* Register operations ******************************************************/ + +#ifdef CONFIG_STM32L4_IWDG_REGDEBUG +static uint16_t stm32l4_getreg(uint32_t addr); +static void stm32l4_putreg(uint16_t val, uint32_t addr); +#else +# define stm32l4_getreg(addr) getreg16(addr) +# define stm32l4_putreg(val,addr) putreg16(val,addr) +#endif + +static inline void stm32l4_setprescaler(FAR struct stm32l4_lowerhalf_s *priv); + +/* "Lower half" driver methods **********************************************/ + +static int stm32l4_start(FAR struct watchdog_lowerhalf_s *lower); +static int stm32l4_stop(FAR struct watchdog_lowerhalf_s *lower); +static int stm32l4_keepalive(FAR struct watchdog_lowerhalf_s *lower); +static int stm32l4_getstatus(FAR struct watchdog_lowerhalf_s *lower, + FAR struct watchdog_status_s *status); +static int stm32l4_settimeout(FAR struct watchdog_lowerhalf_s *lower, + uint32_t timeout); + +/**************************************************************************** + * Private Data + ****************************************************************************/ +/* "Lower half" driver methods */ + +static const struct watchdog_ops_s g_wdgops = +{ + .start = stm32l4_start, + .stop = stm32l4_stop, + .keepalive = stm32l4_keepalive, + .getstatus = stm32l4_getstatus, + .settimeout = stm32l4_settimeout, + .capture = NULL, + .ioctl = NULL, +}; + +/* "Lower half" driver state */ + +static struct stm32l4_lowerhalf_s g_wdgdev; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32l4_getreg + * + * Description: + * Get the contents of an STM32 IWDG register + * + ****************************************************************************/ + +#ifdef CONFIG_STM32_IWDG_REGDEBUG +static uint16_t stm32l4_getreg(uint32_t addr) +{ + static uint32_t prevaddr = 0; + static uint32_t count = 0; + static uint16_t preval = 0; + + /* Read the value from the register */ + + uint16_t val = getreg16(addr); + + /* Is this the same value that we read from the same register last time? Are + * we polling the register? If so, suppress some of the output. + */ + + if (addr == prevaddr && val == preval) + { + if (count == 0xffffffff || ++count > 3) + { + if (count == 4) + { + wdinfo("...\n"); + } + + return val; + } + } + + /* No this is a new address or value */ + + else + { + /* Did we print "..." for the previous value? */ + + if (count > 3) + { + /* Yes.. then show how many times the value repeated */ + + wdinfo("[repeats %d more times]\n", count-3); + } + + /* Save the new address, value, and count */ + + prevaddr = addr; + preval = val; + count = 1; + } + + /* Show the register value read */ + + wdinfo("%08x->%04x\n", addr, val); + return val; +} +#endif + +/**************************************************************************** + * Name: stm32l4_putreg + * + * Description: + * Set the contents of an STM32 register to a value + * + ****************************************************************************/ + +#ifdef CONFIG_STM32L4_IWDG_REGDEBUG +static void stm32l4_putreg(uint16_t val, uint32_t addr) +{ + /* Show the register value being written */ + + wdinfo("%08x<-%04x\n", addr, val); + + /* Write the value */ + + putreg16(val, addr); +} +#endif + +/**************************************************************************** + * Name: stm32l4_setprescaler + * + * Description: + * Set up the prescaler and reload values. + * + * Input Parameters: + * priv - A pointer the internal representation of the "lower-half" + * driver state structure. + * + ****************************************************************************/ + +static inline void stm32l4_setprescaler(FAR struct stm32l4_lowerhalf_s *priv) +{ + irqstate_t flags; + + flags = enter_critical_section(); + + /* Enable write access to IWDG_PR and IWDG_RLR registers */ + + stm32l4_putreg(IWDG_KR_KEY_ENABLE, STM32L4_IWDG_KR); + + /* Wait for the PVU and RVU bits to be reset by hardware. These bits + * were set the last time that the PR register was written and may not + * yet be cleared. + */ + + while ((stm32l4_getreg(STM32L4_IWDG_SR) & (IWDG_SR_PVU | IWDG_SR_RVU)) != 0); + + /* Set the prescaler */ + + stm32l4_putreg((uint16_t)priv->prescaler << IWDG_PR_SHIFT, STM32L4_IWDG_PR); + + /* Set the reload value */ + + stm32l4_putreg((uint16_t)priv->reload, STM32L4_IWDG_RLR); + + /* Reload the counter (and disable write access) */ + + stm32l4_putreg(IWDG_KR_KEY_RELOAD, STM32L4_IWDG_KR); + + /* Wait for the PVU and RVU bits to be reset by hardware. This is + * to wait for the change to take effect before exiting critical section, + * as we are not allowed to enter any low-power modes while this update is + * in progress. + * + * REVISIT: PVU and RVU don't get cleared as promised, until the IWDG is + * started by writing IWDG_KR_KEY_START into IWDG_KR, regardless of whether + * LSI has been started explicitly previously, or not. RM does not document + * this behavior. Lets hope no low-power mode entry happens in this case + * during the next up to five RC 40 kHz cycles. + */ + + if (priv->started) + { + while ((stm32l4_getreg(STM32L4_IWDG_SR) & (IWDG_SR_PVU | IWDG_SR_RVU)) != 0); + } + + leave_critical_section(flags); +} + +/**************************************************************************** + * Name: stm32l4_start + * + * Description: + * Start the watchdog timer, resetting the time to the current timeout, + * + * Input Parameters: + * lower - A pointer the publicly visible representation of the "lower-half" + * driver state structure. + * + * Returned Values: + * Zero on success; a negated errno value on failure. + * + ****************************************************************************/ + +static int stm32l4_start(FAR struct watchdog_lowerhalf_s *lower) +{ + FAR struct stm32l4_lowerhalf_s *priv = (FAR struct stm32l4_lowerhalf_s *)lower; + irqstate_t flags; + + wdinfo("Entry: started=%d\n"); + DEBUGASSERT(priv); + + /* Have we already been started? */ + + if (!priv->started) + { + /* Set up prescaler and reload value for the selected timeout before + * starting the watchdog timer. + */ + + stm32l4_setprescaler(priv); + + /* Enable IWDG (the LSI oscillator will be enabled by hardware). NOTE: + * If the "Hardware watchdog" feature is enabled through the device option + * bits, the watchdog is automatically enabled at power-on. + */ + + flags = enter_critical_section(); + stm32l4_putreg(IWDG_KR_KEY_START, STM32L4_IWDG_KR); + priv->lastreset = clock_systimer(); + priv->started = true; + leave_critical_section(flags); + } + + return OK; +} + +/**************************************************************************** + * Name: stm32l4_stop + * + * Description: + * Stop the watchdog timer + * + * Input Parameters: + * lower - A pointer the publicly visible representation of the "lower-half" + * driver state structure. + * + * Returned Values: + * Zero on success; a negated errno value on failure. + * + ****************************************************************************/ + +static int stm32l4_stop(FAR struct watchdog_lowerhalf_s *lower) +{ + /* There is no way to disable the IDWG timer once it has been started */ + + wdinfo("Entry\n"); + return -ENOSYS; +} + +/**************************************************************************** + * Name: stm32l4_keepalive + * + * Description: + * Reset the watchdog timer to the current timeout value, prevent any + * imminent watchdog timeouts. This is sometimes referred as "pinging" + * the watchdog timer or "petting the dog". + * + * Input Parameters: + * lower - A pointer the publicly visible representation of the "lower-half" + * driver state structure. + * + * Returned Values: + * Zero on success; a negated errno value on failure. + * + ****************************************************************************/ + +static int stm32l4_keepalive(FAR struct watchdog_lowerhalf_s *lower) +{ + FAR struct stm32l4_lowerhalf_s *priv = (FAR struct stm32l4_lowerhalf_s *)lower; + irqstate_t flags; + + wdinfo("Entry\n"); + + /* Reload the IWDG timer */ + + flags = enter_critical_section(); + stm32l4_putreg(IWDG_KR_KEY_RELOAD, STM32L4_IWDG_KR); + priv->lastreset = clock_systimer(); + leave_critical_section(flags); + + return OK; +} + +/**************************************************************************** + * Name: stm32l4_getstatus + * + * Description: + * Get the current watchdog timer status + * + * Input Parameters: + * lower - A pointer the publicly visible representation of the "lower-half" + * driver state structure. + * status - The location to return the watchdog status information. + * + * Returned Values: + * Zero on success; a negated errno value on failure. + * + ****************************************************************************/ + +static int stm32l4_getstatus(FAR struct watchdog_lowerhalf_s *lower, + FAR struct watchdog_status_s *status) +{ + FAR struct stm32l4_lowerhalf_s *priv = (FAR struct stm32l4_lowerhalf_s *)lower; + uint32_t ticks; + uint32_t elapsed; + + wdinfo("Entry\n"); + DEBUGASSERT(priv); + + /* Return the status bit */ + + status->flags = WDFLAGS_RESET; + if (priv->started) + { + status->flags |= WDFLAGS_ACTIVE; + } + + /* Return the actual timeout in milliseconds */ + + status->timeout = priv->timeout; + + /* Get the elapsed time since the last ping */ + + ticks = clock_systimer() - priv->lastreset; + elapsed = (int32_t)TICK2MSEC(ticks); + + if (elapsed > priv->timeout) + { + elapsed = priv->timeout; + } + + /* Return the approximate time until the watchdog timer expiration */ + + status->timeleft = priv->timeout - elapsed; + + wdinfo("Status :\n"); + wdinfo(" flags : %08x\n", status->flags); + wdinfo(" timeout : %d\n", status->timeout); + wdinfo(" timeleft : %d\n", status->timeleft); + return OK; +} + +/**************************************************************************** + * Name: stm32l4_settimeout + * + * Description: + * Set a new timeout value (and reset the watchdog timer) + * + * Input Parameters: + * lower - A pointer the publicly visible representation of the "lower-half" + * driver state structure. + * timeout - The new timeout value in milliseconds. + * + * Returned Values: + * Zero on success; a negated errno value on failure. + * + ****************************************************************************/ + +static int stm32l4_settimeout(FAR struct watchdog_lowerhalf_s *lower, + uint32_t timeout) +{ + FAR struct stm32l4_lowerhalf_s *priv = (FAR struct stm32l4_lowerhalf_s *)lower; + uint32_t fiwdg; + uint64_t reload; + int prescaler; + int shift; + + wdinfo("Entry: timeout=%d\n", timeout); + DEBUGASSERT(priv); + + /* Can this timeout be represented? */ + + if (timeout < 1 || timeout > IWDG_MAXTIMEOUT) + { + wderr("ERROR: Cannot represent timeout=%d > %d\n", + timeout, IWDG_MAXTIMEOUT); + return -ERANGE; + } + + /* Select the smallest prescaler that will result in a reload value that is + * less than the maximum. + */ + + for (prescaler = 0; ; prescaler++) + { + /* PR = 0 -> Divider = 4 = 1 << 2 + * PR = 1 -> Divider = 8 = 1 << 3 + * PR = 2 -> Divider = 16 = 1 << 4 + * PR = 3 -> Divider = 32 = 1 << 5 + * PR = 4 -> Divider = 64 = 1 << 6 + * PR = 5 -> Divider = 128 = 1 << 7 + * PR = 6 -> Divider = 256 = 1 << 8 + * PR = n -> Divider = 1 << (n+2) + */ + + shift = prescaler + 2; + + /* Get the IWDG counter frequency in Hz. For a nominal 32Khz LSI clock, + * this is value in the range of 7500 and 125. + */ + + fiwdg = priv->lsifreq >> shift; + + /* We want: + * 1000 * reload / Fiwdg = timeout + * Or: + * reload = Fiwdg * timeout / 1000 + */ + + reload = (uint64_t)fiwdg * (uint64_t)timeout / 1000; + + /* If this reload valid is less than the maximum or we are not ready + * at the prescaler value, then break out of the loop to use these + * settings. + */ + + if (reload <= IWDG_RLR_MAX || prescaler == 6) + { + /* Note that we explicitly break out of the loop rather than using + * the 'for' loop termination logic because we do not want the + * value of prescaler to be incremented. + */ + + break; + } + } + + /* Make sure that the final reload value is within range */ + + if (reload > IWDG_RLR_MAX) + { + reload = IWDG_RLR_MAX; + } + + /* Get the actual timeout value in milliseconds. + * + * We have: + * reload = Fiwdg * timeout / 1000 + * So we want: + * timeout = 1000 * reload / Fiwdg + */ + + priv->timeout = (1000 * (uint32_t)reload) / fiwdg; + + /* Save setup values for later use */ + + priv->prescaler = prescaler; + priv->reload = reload; + + /* Write the prescaler and reload values to the IWDG registers. */ + + if (priv->started) + { + stm32l4_setprescaler(priv); + } + + wdinfo("prescaler=%d fiwdg=%d reload=%d\n", prescaler, fiwdg, reload); + + return OK; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32l4_iwdginitialize + * + * Description: + * Initialize the IWDG watchdog timer. The watchdog timer is initialized and + * registers as 'devpath'. The initial state of the watchdog timer is + * disabled. + * + * Input Parameters: + * devpath - The full path to the watchdog. This should be of the form + * /dev/watchdog0 + * lsifreq - The calibrated LSI clock frequency + * + * Returned Values: + * None + * + ****************************************************************************/ + +void stm32l4_iwdginitialize(FAR const char *devpath, uint32_t lsifreq) +{ + FAR struct stm32l4_lowerhalf_s *priv = &g_wdgdev; + uint32_t cr; + + wdinfo("Entry: devpath=%s lsifreq=%d\n", devpath, lsifreq); + + /* NOTE we assume that clocking to the IWDG has already been provided by + * the RCC initialization logic. + */ + + /* Initialize the driver state structure. */ + + priv->ops = &g_wdgops; + priv->lsifreq = lsifreq; + priv->started = false; + + /* Make sure that the LSI oscillator is enabled. NOTE: The LSI oscillator + * is enabled here but is not disabled by this file, because this file does + * not know the global usage of the oscillator. Any clock management + * logic (say, as part of a power management scheme) needs handle other + * LSI controls outside of this file. + */ + + stm32l4_rcc_enablelsi(); + wdinfo("RCC CSR: %08x\n", getreg32(STM32L4_RCC_CSR)); + + /* Select an arbitrary initial timeout value. But don't start the watchdog + * yet. NOTE: If the "Hardware watchdog" feature is enabled through the + * device option bits, the watchdog is automatically enabled at power-on. + */ + + stm32l4_settimeout((FAR struct watchdog_lowerhalf_s *)priv, CONFIG_STM32L4_IWDG_DEFTIMOUT); + + /* Register the watchdog driver as /dev/watchdog0 */ + + (void)watchdog_register(devpath, (FAR struct watchdog_lowerhalf_s *)priv); + + /* When the microcontroller enters debug mode (Cortex-M4F core halted), + * the IWDG counter either continues to work normally or stops, depending + * on DBG_IWDG_STOP configuration bit in DBG module. + */ + + cr = getreg32(STM32_DBGMCU_APB1_FZ); + cr |= DBGMCU_APB1_IWDGSTOP; + putreg32(cr, STM32_DBGMCU_APB1_FZ); +} + +#endif /* CONFIG_WATCHDOG && CONFIG_STM32L4_IWDG */ diff --git a/arch/arm/src/stm32l4/stm32l4_lsi.c b/arch/arm/src/stm32l4/stm32l4_lsi.c new file mode 100644 index 0000000000..cc0a8d64bf --- /dev/null +++ b/arch/arm/src/stm32l4/stm32l4_lsi.c @@ -0,0 +1,87 @@ +/**************************************************************************** + * arch/arm/src/stm32l4/stm32l4_lsi.c + * + * Copyright (C) 2012, 2015-2017 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * 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 "up_arch.h" +#include "stm32l4_rcc.h" + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32l4_rcc_enablelsi + * + * Description: + * Enable the Internal Low-Speed (LSI) RC Oscillator. + * + ****************************************************************************/ + +void stm32l4_rcc_enablelsi(void) +{ + /* Enable the Internal Low-Speed (LSI) RC Oscillator by setting the LSION + * bit the RCC CSR register. + */ + + modifyreg32(STM32L4_RCC_CSR, 0, RCC_CSR_LSION); + + /* Wait for the internal LSI oscillator to be stable. */ + + while ((getreg32(STM32L4_RCC_CSR) & RCC_CSR_LSIRDY) == 0); +} + +/**************************************************************************** + * Name: stm32l4_rcc_disablelsi + * + * Description: + * Disable the Internal Low-Speed (LSI) RC Oscillator. + * + ****************************************************************************/ + +void stm32l4_rcc_disablelsi(void) +{ + /* Enable the Internal Low-Speed (LSI) RC Oscillator by setting the LSION + * bit the RCC CSR register. + */ + + modifyreg32(STM32L4_RCC_CSR, RCC_CSR_LSION, 0); + + /* LSIRDY should go low after 3 LSI clock cycles */ +} diff --git a/arch/arm/src/stm32l4/stm32l4_wdg.h b/arch/arm/src/stm32l4/stm32l4_wdg.h index e69de29bb2..794c5e2aef 100644 --- a/arch/arm/src/stm32l4/stm32l4_wdg.h +++ b/arch/arm/src/stm32l4/stm32l4_wdg.h @@ -0,0 +1,119 @@ +/**************************************************************************** + * arch/arm/src/stm32l4/stm32l4_wdg.h + * + * Copyright (C) 2012, 2015, 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. + * + ****************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32L4_STM32L4_WDG_H +#define __ARCH_ARM_SRC_STM32L4_STM32L4_WDG_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include "chip.h" +#include "chip/stm32l4_wdg.h" + +#ifdef CONFIG_WATCHDOG + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32l4_iwdginitialize + * + * Description: + * Initialize the IWDG watchdog time. The watchdog timer is initialized + * and registers as 'devpath. The initial state of the watchdog time is + * disabled. + * + * Input Parameters: + * devpath - The full path to the watchdog. This should be of the form + * /dev/watchdog0 + * lsifreq - The calibrated LSI clock frequency + * + * Returned Values: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_STM32L4_IWDG +void stm32l4_iwdginitialize(FAR const char *devpath, uint32_t lsifreq); +#endif + +/**************************************************************************** + * Name: stm32l4_wwdginitialize + * + * Description: + * Initialize the WWDG watchdog time. The watchdog timer is initialized and + * registers as 'devpath. The initial state of the watchdog time is + * disabled. + * + * Input Parameters: + * devpath - The full path to the watchdog. This should be of the form + * /dev/watchdog0 + * + * Returned Values: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_STM32L4_WWDG +void stm32l4_wwdginitialize(FAR const char *devpath); +#endif + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* CONFIG_WATCHDOG */ +#endif /* __ARCH_ARM_SRC_STM32L4_STM32L4_WDG_H */ -- GitLab From b59f583171e6168c33ff4270e0773f6f51ae298c Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 23 May 2017 10:29:53 -0600 Subject: [PATCH 858/990] Update TODO list --- TODO | 29 ++++++++++++++++++++++++++++- 1 file changed, 28 insertions(+), 1 deletion(-) diff --git a/TODO b/TODO index 3d3755b679..503f2df46e 100644 --- a/TODO +++ b/TODO @@ -1860,7 +1860,34 @@ o Build system archives and cost a lot of debug time before you realize the issue. A work-around is to do 'make clean' if you ever decide to control-C - out of a make. + out of a make. A couple of solutions have been considered: + + - Currently, there is a sequence of compilations ins a directory + with messages like CC:, CC:, CC: etc. This is followed by one big + archival AR: + + The window in which the control-C problem can occur could be + minimized (but not eliminated) by performing a archival for each + compiliation like CC: AR:, CC: AR:, etc. + + - Introduce a spurious dependency that has the correct time stamp. + For example given Make like like (from nuttx/sched/Makefile): + + $(BIN): $(OBJS) + $(call ARCHIVE, $@, $(OBJS)) + + Could be changed like: + + .archive: $(OBJS) + $(call ARCHIVE, $@, $(OBJS)) + @touch .archive + + $(BIN): .archive + + .archive would be a totally spurious file that is touched only AFTER + ALL .o files have been archived. Thus is the user control-C's out of + the make during the archival, the timestamp on .archive is not + updated. o Other drivers (drivers/) ^^^^^^^^^^^^^^^^^^^^^^^^ -- GitLab From eb7373cedfaa10a8cccc608ef51f4b570aa46260 Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Tue, 23 May 2017 14:28:52 -0300 Subject: [PATCH 859/990] Add Microchip MCP2515 CAN Bus controller driver --- drivers/can/Kconfig | 48 + drivers/can/mcp2515.c | 2581 +++++++++++++++++++++++++++++++++++ drivers/can/mcp2515.h | 397 ++++++ include/nuttx/can/mcp2515.h | 164 +++ 4 files changed, 3190 insertions(+) create mode 100644 drivers/can/mcp2515.c create mode 100644 drivers/can/mcp2515.h create mode 100644 include/nuttx/can/mcp2515.h diff --git a/drivers/can/Kconfig b/drivers/can/Kconfig index 577dbea8d1..69b044d274 100644 --- a/drivers/can/Kconfig +++ b/drivers/can/Kconfig @@ -124,4 +124,52 @@ config CAN_NPOLLWAITERS The maximum number of threads that may be waiting on the poll method. +comment "CAN Bus Controllers:" + +config CAN_MCP2515 + bool "Microchip MCP2515 CAN Bus Controller over SPI" + default n + depends on SPI + select ARCH_HAVE_CAN_ERRORS + ---help--- + Enable driver support for Microchip MCP2515. + +if CAN_MCP2515 + +config MCP2515_BITRATE + int "MCP2515 bitrate" + default 500000 + ---help--- + MCP2515 bitrate in bits per second. + +config MCP2515_PROPSEG + int "MCP2515 Propagation Segment TQ" + default 2 + range 1 8 + ---help--- + The length of the bit time is Tquanta * (SyncSeg + PropSeg + PhaseSeg1 + PhaseSeg2). + +config MCP2515_PHASESEG1 + int "MCP2515 Phase Segment 1" + default 2 + range 1 8 + ---help--- + The length of the bit time is Tquanta * (SyncSeg + PropSeg + PhaseSeg1 + PhaseSeg2). + +config MCP2515_PHASESEG2 + int "MCP2515 Phase Segment 2" + default 3 + range 2 8 + ---help--- + The length of the bit time is Tquanta * (SyncSeg + PropSeg + PhaseSeg1 + PhaseSeg2). + +config MCP2515_SJW + int "MCP2515 Synchronization Jump Width" + default 1 + range 1 4 + ---help--- + The duration of a synchronization jump is SJW. + +endif # CAN_MCP2515 + endif # CAN diff --git a/drivers/can/mcp2515.c b/drivers/can/mcp2515.c new file mode 100644 index 0000000000..5a514e48e8 --- /dev/null +++ b/drivers/can/mcp2515.c @@ -0,0 +1,2581 @@ +/**************************************************************************** + * drivers/can/mcp2515.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Copyright (C) 2017 Alan Carvalho de Assis. All rights reserved. + * Author: Alan Carvalho de Assis + * + * 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, Atmel, nor the names of its contributors may + * be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +#include "mcp2515.h" + +#if defined(CONFIG_CAN) && defined(CONFIG_CAN_MCP2515) + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ +/* Common definitions *******************************************************/ + +/* General Configuration ****************************************************/ + +#ifndef CONFIG_CAN_TXREADY +# warning WARNING!!! CONFIG_CAN_TXREADY is required by this driver +#endif + +/* MCP2515 Configuration ****************************************************/ + +/* Bit timing */ + +#define MCP2515_PROPSEG CONFIG_MCP2515_PROPSEG +#define MCP2515_PHSEG1 CONFIG_MCP2515_PHASESEG1 +#define MCP2515_PHSEG2 CONFIG_MCP2515_PHASESEG2 +#define MCP2515_TSEG1 (MCP2515_PROPSEG + MCP2515_PHSEG1) +#define MCP2515_TSEG2 MCP2515_PHSEG2 +#define MCP2515_BRP ((uint8_t)(((float) MCP2515_CANCLK_FREQUENCY / \ + ((float)(MCP2515_TSEG1 + MCP2515_TSEG2 + 1) * \ + (float)CONFIG_MCP2515_BITRATE)) - 1)) +#define MCP2515_SJW CONFIG_MCP2515_SJW + +#if MCP2515_TSEG1 > 16 +# error Invalid MCP2515 TSEG1 +#endif +#if MCP2515_TSEG2 < 2 +# error Invalid TSEG2. It cannot be lower than 2 +#endif +#if MCP2515_TSEG2 > 8 +# error Invalid TSEG2. It cannot be greater than 8 +#endif +#if MCP2515_SJW > 4 +# error Invalid SJW. It cannot be greater than 4 +#endif + +/* MCP2515 RXB0 element size */ + +/* MCP2515 RXB1 element size */ + +/* MCP2515 Filters */ + +# ifndef CONFIG_MCP2515_NSTDFILTERS +# define CONFIG_MCP2515_NSTDFILTERS 0 +# endif + +# if (CONFIG_MCP2515_NSTDFILTERS > 128) +# error Invalid MCP25150 number of Standard Filters +# endif + +# ifndef CONFIG_MCP2515_NEXTFILTERS +# define CONFIG_MCP2515_NEXTFILTERS 0 +# endif + +# if (CONFIG_MCP2515_NEXTFILTERS > 64) +# error Invalid MCP25150 number of Extended Filters +# endif + +# define MCP2515_STDFILTER_BYTES \ + MCP2515_ALIGN_UP(CONFIG_MCP2515_NSTDFILTERS << 2) +# define MCP2515_STDFILTER_WORDS (MCP2515_STDFILTER_BYTES >> 2) + +# define MCP2515_EXTFILTER_BYTES \ + MCP2515_ALIGN_UP(CONFIG_MCP2515_NEXTFILTERS << 3) +# define MCP2515_EXTFILTER_WORDS (MCP2515_EXTFILTER_BYTES >> 2) + +/* MCP25150 TX buffer element size */ + +/* MCP25150 TX FIFOs */ + +/* Loopback mode */ + +#undef MCP2515_LOOPBACK +#if defined(CONFIG_MCP2515_LOOPBACK) +# define MCP2515_LOOPBACK 1 +#endif + +/* Interrupts ***************************************************************/ +/* Interrupts Errors + * + * MCP2515_INT_MERR - Message Error Interrupt Flag bit + * MCP2515_INT_ERR - Error Interrupt Flag bit (mult src in EFLG register) + */ + +#define MCP2515_ERROR_INTS (MCP2515_INT_MERR | MCP2515_INT_ERR) + +/* RXn buffer interrupts + * + * MCP2515_INT_RX0 - Receive Buffer 0 New Message + * MCP2515_INT_RX1 - Receive Buffer 1 New Message + */ + +#define MCP2515_RXBUFFER_INTS (MCP2515_INT_RX0 | MCP2515_INT_RX1) + +/* TXn buffer interrupts + * + * MCP2515_INT_TX0 - Transmmit Buffer 0 Empty Interrupt + * MCP2515_INT_TX1 - Transmmit Buffer 1 Empty Interrupt + * MCP2515_INT_TX2 - Transmmit Buffer 2 Empty Interrupt + */ + +#define MCP2515_TXBUFFER_INTS (MCP2515_INT_TX0 | MCP2515_INT_TX1 | MCP2515_INT_TX2) + +/* Debug ********************************************************************/ +/* Debug configurations that may be enabled just for testing MCP2515 */ + +#ifndef CONFIG_DEBUG_CAN_INFO +# undef CONFIG_MCP2515_REGDEBUG +#endif + +#ifdef CONFIG_MCP2515_REGDEBUG +# define reginfo caninfo +#else +# define reginfo(x...) +#endif + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/* CAN driver state */ + +enum can_state_s +{ + MCP2515_STATE_UNINIT = 0, /* Not yet initialized */ + MCP2515_STATE_RESET, /* Initialized, reset state */ + MCP2515_STATE_SETUP, /* can_setup() has been called */ +}; + +/* This structure provides the current state of a CAN peripheral */ + +struct mcp2515_can_s +{ + struct mcp2515_config_s *config; /* The constant configuration */ + uint8_t state; /* See enum can_state_s */ + uint8_t nalloc; /* Number of allocated filters */ + sem_t locksem; /* Enforces mutually exclusive access */ + sem_t txfsem; /* Used to wait for TX FIFO availability */ + uint32_t btp; /* Current bit timing */ + uint8_t rxints; /* Configured RX interrupts */ + uint8_t txints; /* Configured TX interrupts */ +#ifdef CONFIG_CAN_ERRORS + uint32_t olderrors; /* Used to detect the changes in error states */ +#endif + uint8_t filters; /* Standard/Extende filter bit allocator. */ + uint8_t ntxbufs; /* Number of allocated TX Buffers */ + uint8_t txbuffers; /* TX Buffers bit allocator. */ + +#ifdef CONFIG_MCP2515_REGDEBUG + uintptr_t regaddr; /* Last register address read */ + uint32_t regval; /* Last value read from the register */ + unsigned int count; /* Number of times that the value was read */ +#endif +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* MCP2515 Register access */ + +static void mcp2515_readregs(FAR struct mcp2515_can_s *priv, uint8_t regaddr, + uint8_t *buffer, uint8_t len); +static void mcp2515_writeregs(FAR struct mcp2515_can_s *priv, uint8_t regaddr, + uint8_t *buffer, uint8_t len); +static void mcp2515_modifyreg(FAR struct mcp2515_can_s *priv, uint8_t regaddr, + uint8_t mask, uint8_t value); +#ifdef CONFIG_MCP2515_REGDEBUG +static void mcp2515_dumpregs(FAR struct mcp2515_can_s *priv, FAR const char *msg); +#else +# define mcp2515_dumpregs(priv,msg) +#endif + +/* Semaphore helpers */ + +static void mcp2515_dev_lock(FAR struct mcp2515_can_s *priv); +#define mcp2515_dev_unlock(priv) sem_post(&priv->locksem) + +/* MCP2515 helpers */ + +#ifdef CONFIG_CAN_EXTID +static int mcp2515_add_extfilter(FAR struct mcp2515_can_s *priv, + FAR struct canioc_extfilter_s *extconfig); +static int mcp2515_del_extfilter(FAR struct mcp2515_can_s *priv, int ndx); +#endif +static int mcp2515_add_stdfilter(FAR struct mcp2515_can_s *priv, + FAR struct canioc_stdfilter_s *stdconfig); +static int mcp2515_del_stdfilter(FAR struct mcp2515_can_s *priv, int ndx); + +/* CAN driver methods */ + +static void mcp2515_reset(FAR struct can_dev_s *dev); +static int mcp2515_setup(FAR struct can_dev_s *dev); +static void mcp2515_shutdown(FAR struct can_dev_s *dev); +static void mcp2515_rxint(FAR struct can_dev_s *dev, bool enable); +static void mcp2515_txint(FAR struct can_dev_s *dev, bool enable); +static int mcp2515_ioctl(FAR struct can_dev_s *dev, int cmd, + unsigned long arg); +static int mcp2515_remoterequest(FAR struct can_dev_s *dev, uint16_t id); +static int mcp2515_send(FAR struct can_dev_s *dev, FAR struct can_msg_s *msg); +static bool mcp2515_txready(FAR struct can_dev_s *dev); +static bool mcp2515_txempty(FAR struct can_dev_s *dev); + +/* MCP2515 interrupt handling */ + +#ifdef CONFIG_CAN_ERRORS +static void mcp2515_error(FAR struct can_dev_s *dev, uint8_t status, + uint8_t oldstatus); +#endif +static void mcp2515_receive(FAR struct can_dev_s *dev, uint8_t offset); +static int mcp2515_interrupt(FAR struct mcp2515_config_s *config, FAR void *arg); + +/* Hardware initialization */ + +static int mcp2515_hw_initialize(FAR struct mcp2515_can_s *priv); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const struct can_ops_s g_mcp2515ops = +{ + .co_reset = mcp2515_reset, + .co_setup = mcp2515_setup, + .co_shutdown = mcp2515_shutdown, + .co_rxint = mcp2515_rxint, + .co_txint = mcp2515_txint, + .co_ioctl = mcp2515_ioctl, + .co_remoterequest = mcp2515_remoterequest, + .co_send = mcp2515_send, + .co_txready = mcp2515_txready, + .co_txempty = mcp2515_txempty, +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: mcp2515_readregs + * + * Description: + * Read value(s) of MCP2515 register(s). + * + * Input Parameters: + * priv - A reference to the MCP2515 peripheral state + * offset - The offset to the register to read + * + * Returned Value: + * + ****************************************************************************/ + +static void mcp2515_readregs(FAR struct mcp2515_can_s *priv, uint8_t regaddr, + uint8_t *buffer, uint8_t len) +{ + FAR struct mcp2515_config_s *config = priv->config; +#ifdef CONFIG_CANBUS_REGDEBUG + int i; +#endif + + (void)SPI_LOCK(config->spi, true); + + /* Select the MCP2515 */ + + SPI_SELECT(config->spi, SPIDEV_CANBUS(0), true); + + /* Send the READ command */ + + (void)SPI_SEND(config->spi, MCP2515_READ); + + /* Send register to read and get the next bytes read back */ + + (void)SPI_SEND(config->spi, regaddr); + SPI_RECVBLOCK(config->spi, buffer, len); + + /* Deselect the MCP2515 */ + + SPI_SELECT(config->spi, SPIDEV_CANBUS(0), false); + + /* Unlock bus */ + + (void)SPI_LOCK(config->spi, false); + +#ifdef CONFIG_CANBUS_REGDEBUG + for (i = 0; i < len; i++) + { + caninfo("%02x->%02x\n", regaddr, buffer[i]); + } +#endif +} + +/**************************************************************************** + * Name: mcp2515_writeregs + * + * Description: + * Set the value of a MCP2515 register. + * + * Input Parameters: + * priv - A reference to the MCP2515 peripheral state + * offset - The offset to the register to write + * regval - The value to write to the register + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void mcp2515_writeregs(FAR struct mcp2515_can_s *priv, uint8_t regaddr, + uint8_t *buffer, uint8_t len) +{ + FAR struct mcp2515_config_s *config = priv->config; +#ifdef CONFIG_CANBUS_REGDEBUG + int i; + + for (i = 0; i < len; i++) + { + caninfo("%02x<-%02x\n", regaddr+i, buffer[i]); + } +#endif + + (void)SPI_LOCK(config->spi, true); + + /* Select the MCP2515 */ + + SPI_SELECT(config->spi, SPIDEV_CANBUS(0), true); + + /* Send the READ command */ + + (void)SPI_SEND(config->spi, MCP2515_WRITE); + + /* Send initial register to be written */ + + (void)SPI_SEND(config->spi, regaddr); + SPI_SNDBLOCK(config->spi, buffer, len); + + /* Deselect the MCP2515 */ + + SPI_SELECT(config->spi, SPIDEV_CANBUS(0), false); + + /* Unlock bus */ + + (void)SPI_LOCK(config->spi, false); + +} + +/**************************************************************************** + * Name: mcp2515_modifyreg + * + * Description: + * Modify individuals bits of MCP2515 register + * + * Input Parameters: + * priv - A reference to the MCP2515 peripheral state + * offset - The offset to the register to write + * regval - The value to write to the register + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void mcp2515_modifyreg(FAR struct mcp2515_can_s *priv, uint8_t regaddr, + uint8_t mask, uint8_t value) +{ + FAR struct mcp2515_config_s *config = priv->config; + + (void)SPI_LOCK(config->spi, true); + + /* Select the MCP2515 */ + + SPI_SELECT(config->spi, SPIDEV_CANBUS(0), true); + + /* Send the Modify command */ + + (void)SPI_SEND(config->spi, MCP2515_BITMOD); + + /* Send the register address */ + + (void)SPI_SEND(config->spi, regaddr); + + /* Send the mask */ + + (void)SPI_SEND(config->spi, mask); + + /* Send the value */ + + (void)SPI_SEND(config->spi, value); + + /* Deselect the MCP2515 */ + + SPI_SELECT(config->spi, SPIDEV_CANBUS(0), false); + + /* Unlock bus */ + + (void)SPI_LOCK(config->spi, false); + +} + +/**************************************************************************** + * Name: mcp2515_dumpregs + * + * Description: + * Dump the contents of all MCP2515 control registers + * + * Input Parameters: + * priv - A reference to the MCP2515 peripheral state + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_MCP2515_REGDEBUG +static void mcp2515_dumpregs(FAR struct mcp2515_can_s *priv, FAR const char *msg) +{ + FAR struct mcp2515_config_s *config = priv->config; +} +#endif + +/**************************************************************************** + * Name: mcp2515_dev_lock + * + * Description: + * Take the semaphore that enforces mutually exclusive access to device + * structures, handling any exceptional conditions + * + * Input Parameters: + * priv - A reference to the MCP2515 peripheral state + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void mcp2515_dev_lock(FAR struct mcp2515_can_s *priv) +{ + int ret; + + /* Wait until we successfully get the semaphore. EINTR is the only + * expected 'failure' (meaning that the wait for the semaphore was + * interrupted by a signal. + */ + + do + { + ret = sem_wait(&priv->locksem); + DEBUGASSERT(ret == 0 || errno == EINTR); + } + while (ret < 0); +} + +/**************************************************************************** + * Name: mcp2515_add_extfilter + * + * Description: + * Add an address filter for a extended 29 bit address. + * + * Input Parameters: + * priv - An instance of the MCP2515 driver state structure. + * extconfig - The configuration of the extended filter + * + * Returned Value: + * A non-negative filter ID is returned on success. Otherwise a negated + * errno value is returned to indicate the nature of the error. + * + ****************************************************************************/ + +#ifdef CONFIG_CAN_EXTID +static int mcp2515_add_extfilter(FAR struct mcp2515_can_s *priv, + FAR struct canioc_extfilter_s *extconfig) +{ + FAR struct mcp2515_config_s *config; + uint8_t regval; + uint8_t offset; + uint8_t mode = CAN_FILTER_MASK; + int ndx; + + DEBUGASSERT(priv != NULL && priv->config != NULL); + config = priv->config; + + /* Get exclusive excess to the MCP2515 hardware */ + + mcp2515_dev_lock(priv); + + /* Find an unused standard filter */ + + for (ndx = 0; ndx < config->nfilters; ndx++) + { + /* Is this filter assigned? */ + + if ((priv->filters & (1 << ndx)) == 0) + { + /* No, assign the filter */ + + DEBUGASSERT(priv->nalloc < priv->config->nfilters); + priv->filters |= (1 << ndx); + priv->nalloc++; + + /* Format and write filter */ + + DEBUGASSERT(extconfig->sf_id1 <= CAN_MAX_STDMSGID); + + DEBUGASSERT(extconfig->sf_id2 <= CAN_MAX_STDMSGID); + + /* We can reach all RXFn registers (RXFnSIDH, RXFnSIDL, + * RXFnEID8 and RXFnEID0) using this formula: + * + * filterN = RXF0reg + offset + ((priv->nalloc - 1) * 4) ; + * maskN = RXM0reg + offset + */ + + if (priv->nalloc <= 3) + { + offset = 0; + } + else + { + offset = 4; + } + +#if 0 + /* N.B. Buffer 0 is higher priority than Buffer 1 + * but to separate these messages we will make this + * driver more complex. So let to consider that the + * first 2 IDs inserted in the filter will have more + * priority than the latest 4 IDs*/ + + if (extconfig->sf_prio == CAN_MSGPRIO_LOW) + { + /* Use RXB1 filters */ + } + else + { + /* Use RXB0 filters */ + } +#endif + + switch (extconfig->xf_type) + { + default: + case CAN_FILTER_DUAL: + mode = CAN_FILTER_DUAL; + break; + + case CAN_FILTER_MASK: + mode = CAN_FILTER_MASK; + break; + + case CAN_FILTER_RANGE: + /* not supported */ + break; + } + + /* Setup the CONFIG Mode */ + + mcp2515_readregs(priv, MCP2515_CANCTRL, ®val, 1); + regval = (regval & ~CANCTRL_REQOP_MASK) | (CANCTRL_REQOP_CONFIG); + mcp2515_writeregs(priv, MCP2515_CANCTRL, ®val, 1); + + if (mode == CAN_FILTER_DUAL) + { + /* The MSD IDs will be filtered by separated Mask and Filter */ + + /* Setup the Filter */ + + /* EID0 - EID7 */ + + regval = (uint8_t) (extconfig->xf_id1 & 0xff); + mcp2515_writeregs(priv, MCP2515_RXF0EID0 + offset + + ((priv->nalloc - 1) * 4), ®val, 1); + + /* EID8 - EID15 */ + + regval = (uint8_t) ((extconfig->xf_id1 & 0xff00) >> 8); + mcp2515_writeregs(priv, MCP2515_RXF0EID8 + offset + + ((priv->nalloc - 1) * 4), ®val, 1); + + /* EID16 - EID17 */ + + regval = (uint8_t) ((extconfig->xf_id1 & 0x30000) >> 16); + + /* STD0 - STD2*/ + + regval = (regval) | (uint8_t) (((extconfig->xf_id1 & 0x1C0000) >> 16) << 3); + mcp2515_writeregs(priv, MCP2515_RXF0SIDL + offset + + ((priv->nalloc - 1) * 4), ®val, 1); + + /* STD3 - STD10 */ + + regval = (uint8_t) ((extconfig->xf_id1 & 0x1fe00000 ) >> 21); + regval |= RXFSIDL_EXIDE; + mcp2515_writeregs(priv, MCP2515_RXF0SIDL + offset + + ((priv->nalloc - 1) * 4), ®val, 1); + + /* Setup the Mask */ + + /* EID0 - EID7 */ + + regval = (uint8_t) (extconfig->xf_id2 & 0xff); + mcp2515_writeregs(priv, MCP2515_RXM0EID0 + offset, ®val, 1); + + /* EID8 - EID15 */ + + regval = (uint8_t) ((extconfig->xf_id2 & 0xff00) >> 8); + mcp2515_writeregs(priv, MCP2515_RXM0EID8 + offset, ®val, 1); + + /* EID16 - EID17 */ + + regval = (uint8_t) ((extconfig->xf_id2 & 0x30000) >> 16); + + /* STD0 - STD2*/ + + regval = (regval) | (uint8_t) (((extconfig->xf_id2 & 0x1c0000) >> 16) << 3); + mcp2515_writeregs(priv, MCP2515_RXM0SIDL + offset, ®val, 1); + + /* STD3 - STD10 */ + + regval = (uint8_t) ((extconfig->xf_id2 & 0x1fe00000 ) >> 21); + mcp2515_writeregs(priv, MCP2515_RXM0SIDL + offset, ®val, 1); + } + else + { + /* The IDs will be filtered only by the Filter register (Mask == Filter) */ + + /* Setup the Filter */ + + /* EID0 - EID7 */ + + regval = (uint8_t) (extconfig->xf_id1 & 0xff); + mcp2515_writeregs(priv, MCP2515_RXF0EID0 + offset + + ((priv->nalloc - 1) * 4), ®val, 1); + mcp2515_writeregs(priv, MCP2515_RXM0EID0 + offset, ®val, 1); + + /* EID8 - EID15 */ + + regval = (uint8_t) ((extconfig->xf_id1 & 0xff00) >> 8); + mcp2515_writeregs(priv, MCP2515_RXF0EID8 + offset + + ((priv->nalloc - 1) * 4), ®val, 1); + mcp2515_writeregs(priv, MCP2515_RXM0EID8 + offset, ®val, 1); + + /* EID16 - EID17 */ + + regval = (uint8_t) ((extconfig->xf_id1 & 0x30000) >> 16); + + /* STD0 - STD2 */ + + regval = (regval) | (uint8_t) (((extconfig->xf_id1 & + 0x1c0000) >> 16) << 3) | RXFSIDL_EXIDE; + mcp2515_writeregs(priv, MCP2515_RXF0SIDL + offset + + ((priv->nalloc - 1) * 4), ®val, 1); + mcp2515_writeregs(priv, MCP2515_RXM0SIDL + offset, ®val, 1); + + /* STD3 - STD10 */ + + regval = (uint8_t) ((extconfig->xf_id1 & 0x1fe00000 ) >> 21); + mcp2515_writeregs(priv, MCP2515_RXF0SIDL + offset + + ((priv->nalloc - 1) * 4), ®val, 1); + mcp2515_writeregs(priv, MCP2515_RXF0SIDL + offset, ®val, 1); + } + + /* Leave the Configuration mode, Move to Normal mode */ + + mcp2515_readregs(priv, MCP2515_CANCTRL, ®val, 1); + regval = (regval & ~CANCTRL_REQOP_MASK) | (CANCTRL_REQOP_NORMAL); + mcp2515_writeregs(priv, MCP2515_CANCTRL, ®val, 1); + + mcp2515_dev_unlock(priv); + return ndx; + } + } + + DEBUGASSERT(priv->nstdalloc == priv->config->nstdfilters); + mcp2515_dev_unlock(priv); + return -EAGAIN; +} +#endif + +/**************************************************************************** + * Name: mcp2515_del_extfilter + * + * Description: + * Remove an address filter for a standard 29 bit address. + * + * Input Parameters: + * priv - An instance of the MCP2515 driver state structure. + * ndx - The filter index previously returned by the mcp2515_add_extfilter(). + * + * Returned Value: + * Zero (OK) is returned on success. Otherwise a negated errno value is + * returned to indicate the nature of the error. + * + ****************************************************************************/ + +#ifdef CONFIG_CAN_EXTID +static int mcp2515_del_extfilter(FAR struct mcp2515_can_s *priv, int ndx) +{ + FAR struct mcp2515_config_s *config; + uint8_t regval; + uint8_t offset; + + DEBUGASSERT(priv != NULL && priv->config != NULL); + config = priv->config; + + /* Check Userspace Parameters */ + + DEBUGASSERT(ndx >= 0 || ndx < config->nfilters); + + caninfo("ndx = %d\n", ndx); + + if (ndx < 0 || ndx >= config->nfilters) + { + return -EINVAL; + } + + /* Get exclusive excess to the MCP2515 hardware */ + + mcp2515_dev_lock(priv); + + /* Check if this filter is really assigned */ + + if ((priv->filters & (1 << ndx)) == 0) + { + /* No, error out */ + + mcp2515_dev_unlock(priv); + return -ENOENT; + } + + /* Release the filter */ + + priv->filters &= ~(1 << ndx); + + DEBUGASSERT(priv->nalloc > 0); + priv->nalloc--; + + /* We can reach all RXFn registers (RXFnSIDH, RXFnSIDL, + * RXFnEID8 and RXFnEID0) using this formula: + * + * filterN = RXF0reg + offset + ((priv->nalloc - 1) * 4) ; + * maskN = RXM0reg + offset + */ + + if (ndx < 3) + { + offset = 0; + } + else + { + offset = 4; + } + + /* Setup the CONFIG Mode */ + + mcp2515_readregs(priv, MCP2515_CANCTRL, ®val, 1); + regval = (regval & ~CANCTRL_REQOP_MASK) | (CANCTRL_REQOP_CONFIG); + mcp2515_writeregs(priv, MCP2515_CANCTRL, ®val, 1); + + /* Invalidate this filter, set its ID to 0 */ + + regval = 0; + mcp2515_writeregs(priv, MCP2515_RXF0SIDH + offset + (ndx * 4), ®val, 1); + mcp2515_writeregs(priv, MCP2515_RXF0SIDL + offset + (ndx * 4), ®val, 1); + mcp2515_writeregs(priv, MCP2515_RXF0EID8 + offset + (ndx * 4), ®val, 1); + mcp2515_writeregs(priv, MCP2515_RXF0EID0 + offset + (ndx * 4), ®val, 1); + + /* Leave the Configuration mode, Move to Normal mode */ + + mcp2515_readregs(priv, MCP2515_CANCTRL, ®val, 1); + regval = (regval & ~CANCTRL_REQOP_MASK) | (CANCTRL_REQOP_NORMAL); + mcp2515_writeregs(priv, MCP2515_CANCTRL, ®val, 1); + + mcp2515_dev_unlock(priv); + return OK; +} +#endif + +/**************************************************************************** + * Name: mcp2515_add_stdfilter + * + * Description: + * Add an address filter for a standard 11 bit address. + * + * Input Parameters: + * priv - An instance of the MCP2515 driver state structure. + * stdconfig - The configuration of the standard filter + * + * Returned Value: + * A non-negative filter ID is returned on success. Otherwise a negated + * errno value is returned to indicate the nature of the error. + * + ****************************************************************************/ + +static int mcp2515_add_stdfilter(FAR struct mcp2515_can_s *priv, + FAR struct canioc_stdfilter_s *stdconfig) +{ + FAR struct mcp2515_config_s *config; + uint8_t regval; + uint8_t offset; + uint8_t mode = CAN_FILTER_MASK; + int ndx; + + DEBUGASSERT(priv != NULL && priv->config != NULL); + config = priv->config; + + /* Get exclusive excess to the MCP2515 hardware */ + + mcp2515_dev_lock(priv); + + /* Find an unused standard filter */ + + for (ndx = 0; ndx < config->nfilters; ndx++) + { + /* Is this filter assigned? */ + + if ((priv->filters & (1 << ndx)) == 0) + { + /* No, assign the filter */ + + DEBUGASSERT(priv->nalloc < priv->config->nfilters); + priv->filters |= (1 << ndx); + priv->nalloc++; + + /* Format and write filter */ + + DEBUGASSERT(stdconfig->sf_id1 <= CAN_MAX_STDMSGID); + + DEBUGASSERT(stdconfig->sf_id2 <= CAN_MAX_STDMSGID); + + /* We can reach all RXFn registers (RXFnSIDH, RXFnSIDL, + * RXFnEID8 and RXFnEID0) using this formula: + * + * filterN = RXF0reg + offset + ((priv->nalloc - 1) * 4) ; + * maskN = RXM0reg + offset + */ + + if (priv->nalloc <= 3) + { + offset = 0; + } + else + { + offset = 4; + } + +#if 0 + /* N.B. Buffer 0 is higher priority than Buffer 1 + * but to separate these messages we will make this + * driver more complex. So let to consider that the + * first 2 IDs inserted in the filter will have more + * priority than the latest 4 IDs*/ + + if (stdconfig->sf_prio == CAN_MSGPRIO_LOW) + { + /* Use RXB1 filters */ + } + else + { + /* Use RXB0 filters */ + } +#endif + + switch (stdconfig->sf_type) + { + default: + case CAN_FILTER_DUAL: + mode = CAN_FILTER_DUAL; + break; + + case CAN_FILTER_MASK: + mode = CAN_FILTER_MASK; + break; + + case CAN_FILTER_RANGE: + /* not supported */ + break; + } + + /* Setup the CONFIG Mode */ + + mcp2515_readregs(priv, MCP2515_CANCTRL, ®val, 1); + regval = (regval & ~CANCTRL_REQOP_MASK) | (CANCTRL_REQOP_CONFIG); + mcp2515_writeregs(priv, MCP2515_CANCTRL, ®val, 1); + + if (mode == CAN_FILTER_DUAL) + { + /* The MSD IDs will be filtered by separated Mask and Filter */ + + /* Setup the Filter */ + + regval = (uint8_t) (((stdconfig->sf_id1) & 0x7f8) >> 3); + mcp2515_writeregs(priv, MCP2515_RXF0SIDH + offset + + ((priv->nalloc - 1) * 4), ®val, 1); + + regval = (uint8_t) ((stdconfig->sf_id1 & 0x07 ) << 5); + mcp2515_writeregs(priv, MCP2515_RXF0SIDL + offset + + ((priv->nalloc - 1) * 4), ®val, 1); + + /* Setup the Mask */ + + regval = (uint8_t) (((stdconfig->sf_id2) & 0x7f8) >> 3); + mcp2515_writeregs(priv, MCP2515_RXM0SIDH + offset, ®val, 1); + + regval = (uint8_t) ((stdconfig->sf_id2 & 0x07 ) << 5); + mcp2515_writeregs(priv, MCP2515_RXM0SIDL + offset, ®val, 1); + } + else + { + /* The IDs will be filtered only by the Filter register (Mask == Filter) */ + + /* Setup the Filter */ + + regval = (uint8_t) (((stdconfig->sf_id1) & 0x7f8) >> 3); + mcp2515_writeregs(priv, MCP2515_RXF0SIDH + offset + + ((priv->nalloc - 1) * 4), ®val, 1); + mcp2515_writeregs(priv, MCP2515_RXM0SIDH + offset, ®val, 1); + + regval = (uint8_t) ((stdconfig->sf_id1 & 0x07 ) << 5); + mcp2515_writeregs(priv, MCP2515_RXF0SIDL + offset + + ((priv->nalloc - 1) * 4), ®val, 1); + mcp2515_writeregs(priv, MCP2515_RXM0SIDL + offset, ®val, 1); + } + + /* We need to clear the extended ID bits */ + + regval = 0; + mcp2515_writeregs(priv, MCP2515_RXF0EID0 + offset + + ((priv->nalloc - 1) * 4), ®val, 1); + mcp2515_writeregs(priv, MCP2515_RXF0EID8 + offset + + ((priv->nalloc - 1) * 4), ®val, 1); + mcp2515_writeregs(priv, MCP2515_RXM0EID0 + offset, ®val, 1); + mcp2515_writeregs(priv, MCP2515_RXM0EID8 + offset, ®val, 1); + + /* Leave the Configuration mode, Move to Normal mode */ + + mcp2515_readregs(priv, MCP2515_CANCTRL, ®val, 1); + regval = (regval & ~CANCTRL_REQOP_MASK) | (CANCTRL_REQOP_NORMAL); + mcp2515_writeregs(priv, MCP2515_CANCTRL, ®val, 1); + + mcp2515_dev_unlock(priv); + return ndx; + } + } + + DEBUGASSERT(priv->nstdalloc == priv->config->nstdfilters); + mcp2515_dev_unlock(priv); + return -EAGAIN; +} + +/**************************************************************************** + * Name: mcp2515_del_stdfilter + * + * Description: + * Remove an address filter for a standard 29 bit address. + * + * Input Parameters: + * priv - An instance of the MCP2515 driver state structure. + * ndx - The filter index previously returned by the mcp2515_add_stdfilter(). + * + * Returned Value: + * Zero (OK) is returned on success. Otherwise a negated errno value is + * returned to indicate the nature of the error. + * + ****************************************************************************/ + +static int mcp2515_del_stdfilter(FAR struct mcp2515_can_s *priv, int ndx) +{ + FAR struct mcp2515_config_s *config; + uint8_t regval; + uint8_t offset; + + DEBUGASSERT(priv != NULL && priv->config != NULL); + config = priv->config; + + /* Check Userspace Parameters */ + + DEBUGASSERT(ndx >= 0 || ndx < config->nfilters); + + caninfo("ndx = %d\n", ndx); + + if (ndx < 0 || ndx >= config->nfilters) + { + return -EINVAL; + } + + /* Get exclusive excess to the MCP2515 hardware */ + + mcp2515_dev_lock(priv); + + /* Check if this filter is really assigned */ + + if ((priv->filters & (1 << ndx)) == 0) + { + /* No, error out */ + + mcp2515_dev_unlock(priv); + return -ENOENT; + } + + /* Release the filter */ + + priv->filters &= ~(1 << ndx); + + DEBUGASSERT(priv->nalloc > 0); + priv->nalloc--; + + /* We can reach all RXFn registers (RXFnSIDH, RXFnSIDL, + * RXFnEID8 and RXFnEID0) using this formula: + * + * filterN = RXF0reg + offset + ((priv->nalloc - 1) * 4) ; + * maskN = RXM0reg + offset + */ + + if (ndx < 3) + { + offset = 0; + } + else + { + offset = 4; + } + + /* Setup the CONFIG Mode */ + + mcp2515_readregs(priv, MCP2515_CANCTRL, ®val, 1); + regval = (regval & ~CANCTRL_REQOP_MASK) | (CANCTRL_REQOP_CONFIG); + mcp2515_writeregs(priv, MCP2515_CANCTRL, ®val, 1); + + /* Invalidade this filter, set its ID to 0 */ + + regval = 0; + mcp2515_writeregs(priv, MCP2515_RXF0SIDH + offset + (ndx * 4), ®val, 1); + mcp2515_writeregs(priv, MCP2515_RXF0SIDL + offset + (ndx * 4), ®val, 1); + + /* Leave the Configuration mode, Move to Normal mode */ + + mcp2515_readregs(priv, MCP2515_CANCTRL, ®val, 1); + regval = (regval & ~CANCTRL_REQOP_MASK) | (CANCTRL_REQOP_NORMAL); + mcp2515_writeregs(priv, MCP2515_CANCTRL, ®val, 1); + + mcp2515_dev_unlock(priv); + return OK; +} + +/**************************************************************************** + * Name: mcp2515_reset_lowlevel + * + * Description: + * Reset the MCP2515 device. Called early to initialize the hardware. This + * function is called, before mcp2515_setup() and on error conditions. + * + * Input Parameters: + * dev - An instance of the "upper half" can driver state structure. + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void mcp2515_reset_lowlevel(FAR struct mcp2515_can_s *priv) +{ + FAR struct mcp2515_config_s *config; + + DEBUGASSERT(priv); + config = priv->config; + DEBUGASSERT(config); + + UNUSED(config); + + /* Get exclusive access to the MCP2515 peripheral */ + + mcp2515_dev_lock(priv); + + /* Send SPI reset command to MCP2515 */ + + SPI_LOCK(config->spi, true); + SPI_SELECT(config->spi, SPIDEV_CANBUS(0), true); + SPI_SEND(config->spi, MCP2515_RESET); + SPI_LOCK(config->spi, false); + + /* Wait 1ms to let MCP2515 restart */ + + usleep(1000); + + /* Make sure that all buffers are released. + * + * REVISIT: What if a thread is waiting for a buffer? The following + * will not wake up any waiting threads. + */ + + sem_destroy(&priv->txfsem); + sem_init(&priv->txfsem, 0, config->ntxbuffers); + + /* Define the current state and unlock */ + + priv->state = MCP2515_STATE_RESET; + mcp2515_dev_unlock(priv); +} + +/**************************************************************************** + * Name: mcp2515_reset + * + * Description: + * Reset the MCP2515 device. Called early to initialize the hardware. This + * function is called, before mcp2515_setup() and on error conditions. + * + * Input Parameters: + * dev - An instance of the "upper half" can driver state structure. + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void mcp2515_reset(FAR struct can_dev_s *dev) +{ + FAR struct mcp2515_can_s *priv; + + DEBUGASSERT(dev); + priv = dev->cd_priv; + DEBUGASSERT(priv); + + /* Execute the reset */ + + mcp2515_reset_lowlevel(priv); + +} + +/**************************************************************************** + * Name: mcp2515_setup + * + * Description: + * Configure the MCP2515. This method is called the first time that the MCP2515 + * device is opened. This will occur when the device file is first opened. + * This setup includes configuring and attaching MCP2515 interrupts. + * All MCP2515 interrupts are disabled upon return. + * + * Input Parameters: + * dev - An instance of the "upper half" can driver state structure. + * + * Returned Value: + * Zero on success; a negated errno on failure + * + ****************************************************************************/ + +static int mcp2515_setup(FAR struct can_dev_s *dev) +{ + FAR struct mcp2515_can_s *priv; + FAR struct mcp2515_config_s *config; + int ret; + + DEBUGASSERT(dev); + priv = dev->cd_priv; + DEBUGASSERT(priv); + config = priv->config; + DEBUGASSERT(config); + + //caninfo("MCP2515%d pid: %d\n", config->port, config->pid); + + /* Get exclusive access to the MCP2515 peripheral */ + + mcp2515_dev_lock(priv); + + /* MCP2515 hardware initialization */ + + ret = mcp2515_hw_initialize(priv); + if (ret < 0) + { + canerr("ERROR: MCP2515%d H/W initialization failed: %d\n", config->devid, ret); + return ret; + } + + /* Attach the MCP2515 interrupt handler. */ + + ret = config->attach(config, (mcp2515_handler_t)mcp2515_interrupt, (FAR void *)dev); + if (ret < 0) + { + canerr("ERROR: Failed to attach to IRQ Handler!\n"); + return ret; + } + + /* Enable receive interrupts */ + + priv->state = MCP2515_STATE_SETUP; + mcp2515_rxint(dev, true); + + mcp2515_dev_unlock(priv); + return OK; +} + +/**************************************************************************** + * Name: mcp2515_shutdown + * + * Description: + * Disable the MCP2515. This method is called when the MCP2515 device is closed. + * This method reverses the operation the setup method. + * + * Input Parameters: + * dev - An instance of the "upper half" can driver state structure. + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void mcp2515_shutdown(FAR struct can_dev_s *dev) +{ + /* Nothing to do here! */ +} + +/**************************************************************************** + * Name: mcp2515_rxint + * + * Description: + * Call to enable or disable RX interrupts. + * + * Input Parameters: + * dev - An instance of the "upper half" can driver state structure. + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void mcp2515_rxint(FAR struct can_dev_s *dev, bool enable) +{ + FAR struct mcp2515_can_s *priv; + FAR struct mcp2515_config_s *config; + irqstate_t flags; + uint8_t regval; + + DEBUGASSERT(dev); + priv = dev->cd_priv; + DEBUGASSERT(priv); + config = priv->config; + DEBUGASSERT(config); + + caninfo("CAN%d enable: %d\n", config->devid, enable); + + /* Enable/disable the receive interrupts */ + + flags = enter_critical_section(); + + mcp2515_readregs(priv, MCP2515_CANINTE, ®val, 1); + + if (enable) + { + regval |= priv->rxints | MCP2515_ERROR_INTS; + } + else + { + regval &= ~priv->rxints; + } + + mcp2515_writeregs(priv, MCP2515_CANINTE, ®val, 1); + leave_critical_section(flags); +} + +/**************************************************************************** + * Name: mcp2515_txint + * + * Description: + * Call to enable or disable TX interrupts. + * + * Input Parameters: + * dev - An instance of the "upper half" can driver state structure. + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void mcp2515_txint(FAR struct can_dev_s *dev, bool enable) +{ + FAR struct mcp2515_can_s *priv = dev->cd_priv; + irqstate_t flags; + uint8_t regval; + + DEBUGASSERT(priv && priv->config); + + caninfo("CAN%d enable: %d\n", priv->config->devid, enable); + + /* Enable/disable the receive interrupts */ + + flags = enter_critical_section(); + mcp2515_readregs(priv, MCP2515_CANINTE, ®val, 1); + + if (enable) + { + regval |= priv->txints | MCP2515_ERROR_INTS; + } + else + { + regval &= ~priv->txints; + } + + mcp2515_writeregs(priv, MCP2515_CANINTE, ®val, 1); + leave_critical_section(flags); +} + +/**************************************************************************** + * Name: mcp2515_ioctl + * + * Description: + * All ioctl calls will be routed through this method + * + * Input Parameters: + * dev - An instance of the "upper half" can driver state structure. + * + * Returned Value: + * Zero on success; a negated errno on failure + * + ****************************************************************************/ + +static int mcp2515_ioctl(FAR struct can_dev_s *dev, int cmd, unsigned long arg) +{ + FAR struct mcp2515_can_s *priv; + int ret = -ENOTTY; + + caninfo("cmd=%04x arg=%lu\n", cmd, arg); + + DEBUGASSERT(dev && dev->cd_priv); + priv = dev->cd_priv; + + /* Handle the command */ + + switch (cmd) + { + /* CANIOC_GET_BITTIMING: + * Description: Return the current bit timing settings + * Argument: A pointer to a write-able instance of struct + * canioc_bittiming_s in which current bit timing values + * will be returned. + * Returned Value: Zero (OK) is returned on success. Otherwise -1 (ERROR) + * is returned with the errno variable set to indicate the + * nature of the error. + * Dependencies: None + */ + + case CANIOC_GET_BITTIMING: + { + FAR struct canioc_bittiming_s *bt = + (FAR struct canioc_bittiming_s *)arg; + uint8_t regval; + uint8_t brp; + + DEBUGASSERT(bt != NULL); + + mcp2515_readregs(priv, MCP2515_CNF1, ®val, 1); + bt->bt_sjw = ((regval & CNF1_SJW_MASK) >> CNF1_SJW_SHIFT) + 1; + brp = ((regval & CNF1_BRP_MASK) >> CNF1_BRP_SHIFT) + 1; + + mcp2515_readregs(priv, MCP2515_CNF2, ®val, 1); + bt->bt_tseg1 = ((regval & CNF2_PRSEG_MASK) >> CNF2_PRSEG_SHIFT) + 1; + bt->bt_tseg1 += ((regval & CNF2_PHSEG1_MASK) >> CNF2_PHSEG1_SHIFT) + 1; + + mcp2515_readregs(priv, MCP2515_CNF3, ®val, 1); + bt->bt_tseg2 = ((regval & CNF3_PHSEG2_MASK) >> CNF3_PHSEG2_SHIFT) + 1; + + bt->bt_baud = MCP2515_CANCLK_FREQUENCY / brp / + (bt->bt_tseg1 + bt->bt_tseg2 + 1); + ret = OK; + } + break; + + /* CANIOC_SET_BITTIMING: + * Description: Set new current bit timing values + * Argument: A pointer to a read-able instance of struct + * canioc_bittiming_s in which the new bit timing values + * are provided. + * Returned Value: Zero (OK) is returned on success. Otherwise -1 (ERROR) + * is returned with the errno variable set to indicate the + * nature of the error. + * Dependencies: None + * + * REVISIT: There is probably a limitation here: If there are multiple + * threads trying to send CAN packets, when one of these threads reconfigures + * the bitrate, the MCP2515 hardware will be reset and the context of operation + * will be lost. Hence, this IOCTL can only safely be executed in quiescent + * time periods. + */ + + case CANIOC_SET_BITTIMING: + { + FAR const struct canioc_bittiming_s *bt = + (FAR const struct canioc_bittiming_s *)arg; + irqstate_t flags; + uint8_t brp; + uint8_t sjw; + uint8_t tseg1; + uint8_t tseg2; + uint8_t prseg; + uint8_t phseg1; + uint8_t regval; + + DEBUGASSERT(bt != NULL); + DEBUGASSERT(bt->bt_baud < MCP2515_CANCLK_FREQUENCY); + DEBUGASSERT(bt->bt_sjw > 0 && bt->bt_sjw <= 4); + DEBUGASSERT(bt->bt_tseg1 > 1 && bt->bt_tseg1 <= 16); + DEBUGASSERT(bt->bt_tseg2 > 1 && bt->bt_tseg2 <= 8); + DEBUGASSERT(bt->bt_tseg1 > bt->bt_tseg2); + DEBUGASSERT(bt->bt_tseg2 > bt->bt_sjw); + + /* Extract bit timing data */ + + tseg1 = bt->bt_tseg1 - 1; + tseg2 = bt->bt_tseg2 - 1; + sjw = bt->bt_sjw - 1; + + /* PRSEG = TSEG1 - PHSEG1 + * Because we don't have PHSEG1 then let us to assume: + * PHSEG1 == PHSEG2 (PHSEG2 = TSEG2) + * + * See more at: + * + * http://www.analog.com/en/analog-dialogue/articles/configure-can-bit-timing.html + */ + + phseg1 = tseg2; + prseg = tseg1 - phseg1; + + brp = (uint32_t) + (((float) MCP2515_CANCLK_FREQUENCY / + ((float)(tseg1 + tseg2 + 1) * (float)bt->bt_baud)) - 1); + + /* Save the value of the new bit timing register */ + + flags = enter_critical_section(); + + /* Setup the CONFIG Mode */ + + mcp2515_readregs(priv, MCP2515_CANCTRL, ®val, 1); + regval = (regval & ~CANCTRL_REQOP_MASK) | (CANCTRL_REQOP_CONFIG); + mcp2515_writeregs(priv, MCP2515_CANCTRL, ®val, 1); + + /* Setup CNF1 register */ + + mcp2515_readregs(priv, MCP2515_CNF1, ®val, 1); + regval = (regval & ~CNF1_BRP_MASK) | (brp << CNF1_BRP_SHIFT); + regval = (regval & ~CNF1_SJW_MASK) | ((sjw) << CNF1_SJW_SHIFT); + mcp2515_writeregs(priv, MCP2515_CNF1, ®val, 1); + + /* Setup CNF2 register */ + + mcp2515_readregs(priv, MCP2515_CNF2, ®val, 1); + regval = (regval & ~CNF2_PRSEG_MASK) | ((prseg - 1) << CNF2_PRSEG_SHIFT); + regval = (regval & ~CNF2_PHSEG1_MASK) | (phseg1 << CNF2_PHSEG1_SHIFT); + regval = (regval | CNF2_SAM | CNF2_BTLMODE); + mcp2515_writeregs(priv, MCP2515_CNF2, ®val, 1); + + /* Setup CNF3 register */ + + mcp2515_readregs(priv, MCP2515_CNF3, ®val, 1); + regval = (regval & ~CNF3_PHSEG2_MASK) | (tseg2 << CNF3_PHSEG2_SHIFT); + regval = (regval | CNF3_SOF); + mcp2515_writeregs(priv, MCP2515_CNF3, ®val, 1); + + /* Leave the Configuration mode, Move to Normal mode */ + + mcp2515_readregs(priv, MCP2515_CANCTRL, ®val, 1); + regval = (regval & ~CANCTRL_REQOP_MASK) | (CANCTRL_REQOP_NORMAL); + mcp2515_writeregs(priv, MCP2515_CANCTRL, ®val, 1); + + leave_critical_section(flags); + + ret = OK; + } + break; + +#ifdef CONFIG_CAN_EXTID + /* CANIOC_ADD_EXTFILTER: + * Description: Add an address filter for a extended 29 bit + * address. + * Argument: A reference to struct canioc_extfilter_s + * Returned Value: A non-negative filter ID is returned on success. + * Otherwise -1 (ERROR) is returned with the errno + * variable set to indicate the nature of the error. + */ + + case CANIOC_ADD_EXTFILTER: + { + DEBUGASSERT(arg != 0); + ret = mcp2515_add_extfilter(priv, (FAR struct canioc_extfilter_s *)arg); + } + break; + + /* CANIOC_DEL_EXTFILTER: + * Description: Remove an address filter for a standard 29 bit address. + * Argument: The filter index previously returned by the + * CANIOC_ADD_EXTFILTER command + * Returned Value: Zero (OK) is returned on success. Otherwise -1 (ERROR) + * is returned with the errno variable set to indicate the + * nature of the error. + */ + + case CANIOC_DEL_EXTFILTER: + { + FAR int *ndx = (FAR int *)((uintptr_t)arg); + + DEBUGASSERT(*ndx <= priv->config->nfilters); + ret = mcp2515_del_extfilter(priv, (int)*ndx); + } + break; +#endif + + /* CANIOC_ADD_STDFILTER: + * Description: Add an address filter for a standard 11 bit + * address. + * Argument: A reference to struct canioc_stdfilter_s + * Returned Value: A non-negative filter ID is returned on success. + * Otherwise -1 (ERROR) is returned with the errno + * variable set to indicate the nature of the error. + */ + + case CANIOC_ADD_STDFILTER: + { + DEBUGASSERT(arg != 0); + ret = mcp2515_add_stdfilter(priv, (FAR struct canioc_stdfilter_s *)arg); + } + break; + + /* CANIOC_DEL_STDFILTER: + * Description: Remove an address filter for a standard 11 bit address. + * Argument: The filter index previously returned by the + * CANIOC_ADD_STDFILTER command + * Returned Value: Zero (OK) is returned on success. Otherwise -1 (ERROR) + * is returned with the errno variable set to indicate the + * nature of the error. + */ + + case CANIOC_DEL_STDFILTER: + { + FAR int *ndx = (FAR int *)((uintptr_t)arg); + + DEBUGASSERT(*ndx <= priv->config->nfilters); + ret = mcp2515_del_stdfilter(priv, (int)*ndx); + } + break; + + /* Unsupported/unrecognized command */ + + default: + canerr("ERROR: Unrecognized command: %04x\n", cmd); + break; + } + + return ret; +} + +/**************************************************************************** + * Name: mcp2515_remoterequest + * + * Description: + * Send a remote request + * + * Input Parameters: + * dev - An instance of the "upper half" can driver state structure. + * + * Returned Value: + * Zero on success; a negated errno on failure + * + ****************************************************************************/ + +static int mcp2515_remoterequest(FAR struct can_dev_s *dev, uint16_t id) +{ + /* REVISIT: Remote request not implemented */ + + return -ENOSYS; +} + +/**************************************************************************** + * Name: mcp2515_send + * + * Description: + * Send one can message. + * + * One CAN-message consists of a maximum of 10 bytes. A message is + * composed of at least the first 2 bytes (when there are no data bytes). + * + * Byte 0: Bits 0-7: Bits 3-10 of the 11-bit CAN identifier + * Byte 1: Bits 5-7: Bits 0-2 of the 11-bit CAN identifier + * Bit 4: Remote Transmission Request (RTR) + * Bits 0-3: Data Length Code (DLC) + * Bytes 2-10: CAN data + * + * Input Parameters: + * dev - An instance of the "upper half" can driver state structure. + * + * Returned Value: + * Zero on success; a negated errno on failure + * + ****************************************************************************/ + +static int mcp2515_send(FAR struct can_dev_s *dev, FAR struct can_msg_s *msg) +{ + FAR struct mcp2515_can_s *priv; + FAR struct mcp2515_config_s *config; + uint8_t regval; + uint8_t offset; + unsigned int nbytes; + unsigned int i; + + DEBUGASSERT(dev); + priv = dev->cd_priv; + DEBUGASSERT(priv && priv->config); + config = priv->config; + + caninfo("CAN%d\n", config->devid); + caninfo("CAN%d ID: %d DLC: %d\n", + config->devid, msg->cm_hdr.ch_id, msg->cm_hdr.ch_dlc); + + /* That that FIFO elements were configured. + * + * REVISIT: Dedicated TX buffers are not used by this driver. + */ + + DEBUGASSERT(config->ntxbuffers > 0); + + /* Select one empty transmit buffer */ + + mcp2515_readregs(priv, MCP2515_TXB0CTRL, ®val, 1); + if ((regval & TXBCTRL_TXREQ) == 0) + { + offset = MCP2515_TX0_OFFSET; + } + else + { + mcp2515_readregs(priv, MCP2515_TXB1CTRL, ®val, 1); + if ((regval & TXBCTRL_TXREQ) == 0) + { + offset = MCP2515_TX1_OFFSET; + } + else + { + mcp2515_readregs(priv, MCP2515_TXB2CTRL, ®val, 1); + if ((regval & TXBCTRL_TXREQ) == 0) + { + offset = MCP2515_TX2_OFFSET; + } + else + { + canerr("ERROR: No available transmit buffer!\n"); + return -EBUSY; + } + } + } + + /* Get exclusive access to the MCP2515 peripheral */ + + mcp2515_dev_lock(priv); + + /* Setup the MCP2515 TX Buffer with the message to send */ + +#ifdef CONFIG_CAN_EXTID + if (msg->cm_hdr.ch_extid) + { + DEBUGASSERT(msg->cm_hdr.ch_id <= CAN_MAX_EXTMSGID); + + /* EID7 - EID0 */ + + regval = (msg->cm_hdr.ch_id & 0xff); + mcp2515_writeregs(priv, MCP2515_TXB0EID0 + offset, ®val, 1); + + /* EID15 - EID8 */ + + regval = (msg->cm_hdr.ch_id & 0xff00) >> 8; + mcp2515_writeregs(priv, MCP2515_TXB0EID8 + offset, ®val, 1); + + /* EID17 and EID16 */ + + regval = (msg->cm_hdr.ch_id & 0x30000) >> 16; + regval |= TXBSIDL_EXIDE; + + /* STD2 - STD0 */ + + regval |= (msg->cm_hdr.ch_id & 0x1c0000) >> 18; + mcp2515_writeregs(priv, MCP2515_TXB0SIDL + offset, ®val, 1); + + /* STD10 - STD3 */ + + regval = (msg->cm_hdr.ch_id & 0x1fe00000) >> 21; + mcp2515_writeregs(priv, MCP2515_TXB0SIDH + offset, ®val, 1); + } + else +#endif + { + DEBUGASSERT(msg->cm_hdr.ch_id <= CAN_MAX_STDMSGID); + + /* Setup the Standard ID of the message to send */ + + /* STD10 - STD3 */ + + regval = (msg->cm_hdr.ch_id & 0x7f8) >> 3; + mcp2515_writeregs(priv, MCP2515_TXB0SIDH + offset, ®val, 1); + + /* STD2 - STD0 */ + + regval = (msg->cm_hdr.ch_id & 0x007) << 5; + mcp2515_writeregs(priv, MCP2515_TXB0SIDL + offset, ®val, 1); + } + + /* Setup the DLC */ + + regval = (msg->cm_hdr.ch_dlc & 0xf); + + if (msg->cm_hdr.ch_rtr) + { + regval |= TXBDLC_RTR; + } + + mcp2515_writeregs(priv, MCP2515_TXB0DLC + offset, ®val, 1); + + /* Fill the data buffer */ + + nbytes = msg->cm_hdr.ch_dlc; + + for (i = 0; i < nbytes; i++) + { + /* Little endian is assumed */ + + regval = msg->cm_data[i]; + mcp2515_writeregs(priv, MCP2515_TXB0D0 + offset + i, ®val, 1); + } + + /* And request to send the message */ + + mcp2515_readregs(priv, MCP2515_TXB0CTRL, ®val, 1); + regval |= TXBCTRL_TXREQ; + mcp2515_writeregs(priv, MCP2515_TXB0CTRL, ®val, 1); + + mcp2515_dev_unlock(priv); + + /* Report that the TX transfer is complete to the upper half logic. Of + * course, the transfer is not complete, but this early notification + * allows the upper half logic to free resources sooner. + * + * REVISIT: Should we disable interrupts? can_txdone() was designed to + * be called from an interrupt handler and, hence, may be unsafe when + * called from the tasking level. + */ + + (void)can_txdone(dev); + return OK; +} + +/**************************************************************************** + * Name: mcp2515_txready + * + * Description: + * Return true if the MCP2515 hardware can accept another TX message. + * + * Input Parameters: + * dev - An instance of the "upper half" can driver state structure. + * + * Returned Value: + * True if the MCP2515 hardware is ready to accept another TX message. + * + ****************************************************************************/ + +static bool mcp2515_txready(FAR struct can_dev_s *dev) +{ + FAR struct mcp2515_can_s *priv; + uint8_t regval; + bool empty; + + DEBUGASSERT(dev); + priv = dev->cd_priv; + DEBUGASSERT(priv); + + /* That that FIFO elements were configured. + * + * REVISIT: Dedicated TX buffers are not used by this driver. + */ + + DEBUGASSERT(config->ntxbuffers > 0); + + /* Get exclusive access to the MCP2515 peripheral */ + + mcp2515_dev_lock(priv); + + /* Select one empty transmit buffer */ + + mcp2515_readregs(priv, MCP2515_TXB0CTRL, ®val, 1); + if ((regval & TXBCTRL_TXREQ) == 0) + { + empty = true; + } + else + { + mcp2515_readregs(priv, MCP2515_TXB1CTRL, ®val, 1); + if ((regval & TXBCTRL_TXREQ) == 0) + { + empty = true; + } + else + { + mcp2515_readregs(priv, MCP2515_TXB2CTRL, ®val, 1); + if ((regval & TXBCTRL_TXREQ) == 0) + { + empty = true; + } + else + { + empty = false; + } + } + } + + mcp2515_dev_unlock(priv); + + return empty; +} + +/**************************************************************************** + * Name: mcp2515_txempty + * + * Description: + * Return true if all message have been sent. If for example, the MCP2515 + * hardware implements FIFOs, then this would mean the transmit FIFO is + * empty. This method is called when the driver needs to make sure that + * all characters are "drained" from the TX hardware before calling + * co_shutdown(). + * + * Input Parameters: + * dev - An instance of the "upper half" can driver state structure. + * + * Returned Value: + * True if there are no pending TX transfers in the MCP2515 hardware. + * + ****************************************************************************/ + +static bool mcp2515_txempty(FAR struct can_dev_s *dev) +{ + FAR struct mcp2515_can_s *priv; + uint8_t regval; + bool empty; + + DEBUGASSERT(dev); + priv = dev->cd_priv; + DEBUGASSERT(priv); + + /* That that FIFO elements were configured. + * + * REVISIT: Dedicated TX buffers are not used by this driver. + */ + + DEBUGASSERT(config->ntxbuffers > 0); + + /* Get exclusive access to the MCP2515 peripheral */ + + mcp2515_dev_lock(priv); + + /* Select one empty transmit buffer */ + + mcp2515_readregs(priv, MCP2515_TXB0CTRL, ®val, 1); + if ((regval & TXBCTRL_TXREQ) != 0) + { + empty = false; + } + else + { + mcp2515_readregs(priv, MCP2515_TXB1CTRL, ®val, 1); + if ((regval & TXBCTRL_TXREQ) != 0) + { + empty = false; + } + else + { + mcp2515_readregs(priv, MCP2515_TXB2CTRL, ®val, 1); + if ((regval & TXBCTRL_TXREQ) != 0) + { + empty = false; + } + else + { + empty = true; + } + } + } + + mcp2515_dev_unlock(priv); + + return empty; +} + +/**************************************************************************** + * Name: mcp2515_error + * + * Description: + * Report a CAN error + * + * Input Parameters: + * dev - CAN-common state data + * status - Interrupt status with error bits set + * oldstatus - Previous Interrupt status with error bits set + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_CAN_ERRORS +static void mcp2515_error(FAR struct can_dev_s *dev, uint8_t status, + uint8_t oldstatus) +{ + FAR struct mcp2515_can_s *priv = dev->cd_priv; + struct can_hdr_s hdr; + uint8_t eflg; + uint8_t txerr; + uint8_t txb0err; + uint8_t txb1err; + uint8_t txb2err; + uint16_t errbits; + uint8_t data[CAN_ERROR_DLC]; + int ret; + + /* Encode error bits */ + + errbits = 0; + memset(data, 0, sizeof(data)); + + /* Please note that MCP2515_CANINTF only reports if an error + * happened. It doesn't report what error it is. + * We need to check EFLG and TXBnCTRL to discover. + */ + + mcp2515_readregs(priv, MCP2515_EFLG, &eflg, 1); + if (eflg & EFLG_TXBO) + { + errbits |= CAN_ERROR_BUSOFF; + } + + if (eflg & EFLG_RXEP) + { + data[1] |= CAN_ERROR1_RXPASSIVE; + } + + if (eflg & EFLG_TXEP) + { + data[1] |= CAN_ERROR1_TXPASSIVE; + } + + if (eflg & EFLG_RXWAR) + { + data[1] |= CAN_ERROR1_RXWARNING; + } + + if (eflg & EFLG_TXWAR) + { + data[1] |= CAN_ERROR1_TXWARNING; + } + + if (eflg & (EFLG_RX0OVR | EFLG_RX1OVR)) + { + data[1] |= CAN_ERROR1_RXOVERFLOW; + } + + /* Verify Message Error */ + + mcp2515_readregs(priv, MCP2515_TXB0CTRL, &txb0err, 1); + mcp2515_readregs(priv, MCP2515_TXB1CTRL, &txb1err, 1); + mcp2515_readregs(priv, MCP2515_TXB2CTRL, &txb2err, 1); + + txerr = txb0err | txb1err | txb2err; + + if (txerr & (TXBCTRL_MLOA)) + { + errbits |= CAN_ERROR_LOSTARB; + } + + if (txerr & (TXBCTRL_ABTF)) + { + errbits |= CAN_ERROR_LOSTARB; + } + + if (txerr & (TXBCTRL_MLOA)) + { + data[0] |= CAN_ERROR0_UNSPEC; + } + + if ((status & (MCP2515_INT_ERR | MCP2515_INT_MERR)) != 0) + { + /* If Message Error or Other error */ + + errbits |= CAN_ERROR_CONTROLLER; + } + else if ((oldstatus & (MCP2515_INT_ERR | MCP2515_INT_MERR)) != 0) + { + errbits |= CAN_ERROR_CONTROLLER; + } + + if (errbits != 0) + { + /* Format the CAN header for the error report. */ + + hdr.ch_id = errbits; + hdr.ch_dlc = CAN_ERROR_DLC; + hdr.ch_rtr = 0; + hdr.ch_error = 1; +#ifdef CONFIG_CAN_EXTID + hdr.ch_extid = 0; +#endif + hdr.ch_unused = 0; + + /* And provide the error report to the upper half logic */ + + ret = can_receive(dev, &hdr, data); + if (ret < 0) + { + canerr("ERROR: can_receive failed: %d\n", ret); + } + } +} +#endif /* CONFIG_CAN_ERRORS */ + +/**************************************************************************** + * Name: mcp2515_receive + * + * Description: + * Receive an MCP2515 messages + * + * Input Parameters: + * dev - CAN-common state data + * rxbuffer - The RX buffer containing the received messages + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void mcp2515_receive(FAR struct can_dev_s *dev, uint8_t offset) +{ + FAR struct mcp2515_can_s *priv; + struct can_hdr_s hdr; + int ret; + uint8_t regval; + uint8_t data[CAN_MAXDATALEN]; + + DEBUGASSERT(dev); + priv = dev->cd_priv; + DEBUGASSERT(priv); + + /* Format the CAN header */ + + /* Get the CAN identifier. */ + + mcp2515_readregs(priv, MCP2515_RXB0SIDL + offset, ®val, 1); + +#ifdef CONFIG_CAN_EXTID + if ((regval & RXBSIDL_IDE) != 0) + { + + /* Save the extended ID of the newly received message */ + + /* EID7 - EID0 */ + + mcp2515_readregs(priv, MCP2515_RXB0EID0 + offset, ®val, 1); + hdr.ch_id = regval ; + + /* EID15 - EID8 */ + + mcp2515_readregs(priv, MCP2515_RXB0EID8 + offset, ®val, 1); + hdr.ch_id = hdr.ch_id | (regval << 8); + + /* EID17 and EID16 */ + + mcp2515_readregs(priv, MCP2515_RXB0SIDL + offset, ®val, 1); + hdr.ch_id = hdr.ch_id | ((regval & RXBSIDL_EID_MASK) << 16); + + /* STD2 - STD0 */ + + hdr.ch_id = hdr.ch_id | ((regval >> 5) << 18); + + /* STD10 - STD3 */ + + mcp2515_readregs(priv, MCP2515_RXB0SIDH + offset, ®val, 1); + hdr.ch_id = hdr.ch_id | (regval << 21); + hdr.ch_extid = true; + } + else + { + /* Save the standard ID of the newly received message */ + + mcp2515_readregs(priv, MCP2515_RXB0SIDH + offset, ®val, 1); + hdr.ch_id = regval; + mcp2515_readregs(priv, MCP2515_RXB0SIDL + offset, ®val, 1); + hdr.ch_id = (hdr.ch_id << 3) | (regval >> 5); + hdr.ch_extid = false; + } + +#else + if ((regval & RXBSIDL_IDE) != 0) + { + /* Drop any messages with extended IDs */ + + canerr("ERROR: Extended MSG in Standard Mode\n"); + + return; + } + + /* Save the standard ID of the newly received message */ + + mcp2515_readregs(priv, MCP2515_RXB0SIDH + offset, ®val, 1); + hdr.ch_id = regval; + mcp2515_readregs(priv, MCP2515_RXB0SIDL + offset, ®val, 1); + hdr.ch_id = (hdr.ch_id << 3) | (regval >> 5); +#endif + +#ifdef CONFIG_CAN_ERRORS + hdr.ch_error = 0; /* Error reporting not supported */ +#endif + hdr.ch_unused = 0; + + /* Extract the RTR bit */ + + mcp2515_readregs(priv, MCP2515_RXB0CTRL, ®val, 1); + hdr.ch_rtr = (regval & RXBCTRL_RXRTR) != 0; + + /* Get the DLC */ + + mcp2515_readregs(priv, MCP2515_RXB0DLC, ®val, 1); + hdr.ch_dlc = (regval & RXBDLC_DLC_MASK) >> RXBDLC_DLC_SHIFT; + + /* Save the message data */ + + mcp2515_readregs(priv, MCP2515_RXB0D0, data, (uint8_t) hdr.ch_dlc); + + ret = can_receive(dev, &hdr, (FAR uint8_t *) data); + + if (ret < 0) + { + canerr("ERROR: can_receive failed: %d\n", ret); + } +} + +/**************************************************************************** + * Name: mcp2515_interrupt + * + * Description: + * Common MCP2515 interrupt handler + * + * Input Parameters: + * dev - CAN-common state data + * + * Returned Value: + * None + * + ****************************************************************************/ + +static int mcp2515_interrupt(FAR struct mcp2515_config_s *config, FAR void *arg) +{ + FAR struct can_dev_s *dev = (FAR struct can_dev_s *)arg; + FAR struct mcp2515_can_s *priv; + uint8_t ir; + uint8_t ie; + uint8_t pending; + bool handled; + + DEBUGASSERT(dev); + priv = dev->cd_priv; + DEBUGASSERT(priv != NULL); + DEBUGASSERT(priv && priv->config); + + /* Loop while there are pending interrupt events */ + + do + { + /* Get the set of pending interrupts. */ + + mcp2515_readregs(priv, MCP2515_CANINTF, &ir, 1); + mcp2515_readregs(priv, MCP2515_CANINTE, &ie, 1); + + pending = (ir & ie); + handled = false; + + /* Check for any errors */ + + if ((pending & MCP2515_ERROR_INTS) != 0) + { + /* Clear interrupt errors */ + + mcp2515_modifyreg(priv, MCP2515_CANINTF, MCP2515_ERROR_INTS, ~MCP2515_ERROR_INTS); + +#ifdef CONFIG_CAN_ERRORS + /* Report errors */ + + mcp2515_error(dev, pending & MCP2515_ERROR_INTS, priv->olderrors); + + priv->olderrors = (pending & MCP2515_ERROR_INTS); +#endif + handled = true; + } +#ifdef CONFIG_CAN_ERRORS + else if (priv->olderrors != 0) + { + /* All (old) errors cleared */ + + canerr("ERROR: CLEARED\n"); + + mcp2515_error(dev, 0, priv->olderrors); + + priv->olderrors = 0; + handled = true; + } +#endif + + /* Check for successful completion of a transmission */ + + if ((pending & MCP2515_TXBUFFER_INTS) != 0) + { + /* Clear the pending TX completion interrupt (and all + * other TX-related interrupts) + */ + + if (pending & MCP2515_INT_TX0) + { + caninfo("TX0 is empty to transmit new message!\n"); + + /* Clear TX0 interrupt */ + + mcp2515_modifyreg(priv, MCP2515_CANINTF, MCP2515_INT_TX0, ~MCP2515_INT_TX0); + } + + if (pending & MCP2515_INT_TX1) + { + caninfo("TX1 is empty to transmit new message!\n"); + + /* Clear TX1 interrupt */ + + mcp2515_modifyreg(priv, MCP2515_CANINTF, MCP2515_INT_TX1, ~MCP2515_INT_TX1); + } + + if (pending & MCP2515_INT_TX2) + { + caninfo("TX2 is empty to transmit new message!\n"); + + /* Clear TX2 interrupt */ + + mcp2515_modifyreg(priv, MCP2515_CANINTF, MCP2515_INT_TX2, ~MCP2515_INT_TX2); + } + + handled = true; + +#ifdef CONFIG_CAN_TXREADY + /* Inform the upper half driver that we are again ready to accept + * data in mcp2515_send(). + */ + + (void)can_txready(dev); +#endif + } + else if ((pending & priv->txints) != 0) + { + /* Clear unhandled TX events */ + + //mcp2515_putreg(priv, MCP2515_IR_OFFSET, priv->txints); + handled = true; + } + + /* Check if there is a new message to read */ + + if ((pending & MCP2515_RXBUFFER_INTS) != 0) + { + /* RX Buffer 0 is the "high priority" buffer: We will process + * all messages in RXB0 before processing any message from RX + * RXB1. + */ + + if ((pending & MCP2515_INT_RX0) != 0) + { + mcp2515_receive(dev, MCP2515_RX0_OFFSET); + + /* Clear RX0 interrupt */ + + mcp2515_modifyreg(priv, MCP2515_CANINTF, MCP2515_INT_RX0, ~MCP2515_INT_RX0); + } + else + { + if ((pending & MCP2515_INT_RX1) != 0) + { + mcp2515_receive(dev, MCP2515_RX1_OFFSET); + + /* Clear RX1 interrupt */ + + mcp2515_modifyreg(priv, MCP2515_CANINTF, MCP2515_INT_RX1, ~MCP2515_INT_RX1); + } + } + + /* Acknowledge reading the FIFO entry */ + handled = true; + } + } + while (handled); + + return OK; +} + +/**************************************************************************** + * Name: mcp2515_hw_initialize + * + * Description: + * MCP2515 hardware initialization + * + * Input Parameter: + * priv - A pointer to the private data structure for this MCP2515 peripheral + * + * Returned Value: + * Zero on success; a negated errno value on failure. + * + ****************************************************************************/ + +static int mcp2515_hw_initialize(struct mcp2515_can_s *priv) +{ + FAR struct mcp2515_config_s *config = priv->config; + uint8_t regval; + + caninfo("CAN%d\n", config->devid); + + /* Setup CNF1 register */ + + mcp2515_readregs(priv, MCP2515_CNF1, ®val, 1); + regval = (regval & ~CNF1_BRP_MASK) | (MCP2515_BRP << CNF1_BRP_SHIFT); + regval = (regval & ~CNF1_SJW_MASK) | ((MCP2515_SJW - 1) << CNF1_SJW_SHIFT); + mcp2515_writeregs(priv, MCP2515_CNF1, ®val, 1); + + /* Setup CNF2 register */ + + mcp2515_readregs(priv, MCP2515_CNF2, ®val, 1); + regval = (regval & ~CNF2_PRSEG_MASK) | ((MCP2515_PROPSEG - 1) << CNF2_PRSEG_SHIFT); + regval = (regval & ~CNF2_PHSEG1_MASK) | ((MCP2515_PHSEG1 - 1) << CNF2_PHSEG1_SHIFT); + regval = (regval | CNF2_SAM | CNF2_BTLMODE); + mcp2515_writeregs(priv, MCP2515_CNF2, ®val, 1); + + /* Setup CNF3 register */ + + mcp2515_readregs(priv, MCP2515_CNF3, ®val, 1); + regval = (regval & ~CNF3_PHSEG2_MASK) | ((MCP2515_PHSEG2 - 1) << CNF3_PHSEG2_SHIFT); + regval = (regval | CNF3_SOF); + mcp2515_writeregs(priv, MCP2515_CNF3, ®val, 1); + + /* Mask all messages to be received */ + + mcp2515_readregs(priv, MCP2515_RXB0CTRL, ®val, 1); + regval = (regval & ~RXBCTRL_RXM_MASK) | (RXBCTRL_RXM_ALLVALID << RXBCTRL_RXM_SHIFT); + regval = (regval | RXB0CTRL_BUKT); /* Enable Rollover from RXB0 to RXB1 */ + mcp2515_writeregs(priv, MCP2515_RXB0CTRL, ®val, 1); + + mcp2515_readregs(priv, MCP2515_RXB1CTRL, ®val, 1); + regval = (regval & ~RXBCTRL_RXM_MASK) | (RXBCTRL_RXM_ALLVALID << RXBCTRL_RXM_SHIFT); + mcp2515_writeregs(priv, MCP2515_RXB1CTRL, ®val, 1); + + regval = 0x00; + mcp2515_writeregs(priv, MCP2515_RXM0SIDH, ®val, 1); + mcp2515_writeregs(priv, MCP2515_RXM0SIDL, ®val, 1); +#ifdef CONFIG_CAN_EXTID + mcp2515_writeregs(priv, MCP2515_RXM0EID8, ®val, 1); + mcp2515_writeregs(priv, MCP2515_RXM0EID0, ®val, 1); +#endif + + mcp2515_writeregs(priv, MCP2515_RXM1SIDH, ®val, 1); + mcp2515_writeregs(priv, MCP2515_RXM1SIDL, ®val, 1); +#ifdef CONFIG_CAN_EXTID + mcp2515_writeregs(priv, MCP2515_RXM1EID8, ®val, 1); + mcp2515_writeregs(priv, MCP2515_RXM1EID0, ®val, 1); +#endif + +#ifdef CONFIG_CAN_EXTID + mcp2515_modifyreg(priv, MCP2515_RXM0SIDL, RXFSIDL_EXIDE, RXFSIDL_EXIDE); + mcp2515_modifyreg(priv, MCP2515_RXM1SIDL, RXFSIDL_EXIDE, RXFSIDL_EXIDE); +#endif + + /* Leave the Configuration mode, Move to Normal mode */ + + mcp2515_readregs(priv, MCP2515_CANCTRL, ®val, 1); + regval = (regval & ~CANCTRL_REQOP_MASK) | (CANCTRL_REQOP_NORMAL); + mcp2515_writeregs(priv, MCP2515_CANCTRL, ®val, 1); + + usleep(100); + + /* Read the CANINTF */ + + mcp2515_readregs(priv, MCP2515_CANINTF, ®val, 1); + caninfo("CANINFT = 0x%02X\n", regval); + +#ifdef MCP2515_LOOPBACK + /* Is loopback mode selected for this peripheral? */ + + if (config->loopback) + { + /* To Be Implemented */ + } +#endif + + /* Configure interrupt lines */ + + /* Select RX-related interrupts */ + + priv->rxints = MCP2515_RXBUFFER_INTS; + + /* Select TX-related interrupts */ + + priv->txints = MCP2515_TXBUFFER_INTS; + + return OK; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: mcp2515_instantiate + * + * Description: + * Initialize the selected MCP2515 CAN Bus Controller over SPI + * + * Input Parameter: + * config - The configuration structure passed by the board. + * + * Returned Value: + * Valid CAN device structure reference on success; a NULL on failure + * + ****************************************************************************/ + +FAR struct mcp2515_can_s *mcp2515_instantiate(FAR struct mcp2515_config_s *config) +{ + FAR struct mcp2515_can_s *priv; + uint8_t canctrl; + + caninfo("Starting mcp2515_instantiate()!\n"); + + priv = (FAR struct mcp2515_can_s *)kmm_malloc(sizeof(struct mcp2515_can_s)); + if (priv == NULL) + { + canerr("ERROR: Failed to allocate instance of mcp2515_can_s!\n"); + return NULL; + } + + /* Setup SPI frequency and mode */ + + SPI_SETFREQUENCY(config->spi, MCP2515_SPI_FREQUENCY); + SPI_SETMODE(config->spi, MCP2515_SPI_MODE); + SPI_SETBITS(config->spi, 8); + (void)SPI_HWFEATURES(config->spi, 0); + + /* Perform one time data initialization */ + + memset(priv, 0, sizeof(struct mcp2515_can_s)); + priv->config = config; + + /* Set the initial bit timing. This might change subsequently + * due to IOCTL command processing. + */ + + //priv->btp = config->btp; + //priv->fbtp = config->fbtp; + + /* Initialize semaphores */ + + sem_init(&priv->locksem, 0, 1); + sem_init(&priv->txfsem, 0, config->ntxbuffers); + + /* And put the hardware in the initial state */ + + mcp2515_reset_lowlevel(priv); + + /* Probe the MCP2515 to confirm it was detected */ + + mcp2515_readregs(priv, MCP2515_CANCTRL, &canctrl, 1); + + if (canctrl != DEFAULT_CANCTRL_CONFMODE) + { + canerr("ERROR: CANCTRL = 0x%02X ! It should be 0x87\n", canctrl); + return NULL; + } + + /* Return our private data structure as an opaque handle */ + + return (MCP2515_HANDLE)priv; +} + +/**************************************************************************** + * Name: mcp2515_initialize + * + * Description: + * Initialize the selected MCP2515 CAN Bus Controller over SPI + * + * Input Parameter: + * config - The configuration structure passed by the board. + * + * Returned Value: + * Valid CAN device structure reference on success; a NULL on failure + * + ****************************************************************************/ + +FAR struct can_dev_s *mcp2515_initialize(FAR struct mcp2515_can_s *mcp2515can) +{ + FAR struct can_dev_s *dev; + + caninfo("Starting mcp2515_initialize()!\n"); + + /* Allocate a CAN Device structure */ + + dev = (FAR struct can_dev_s *)kmm_malloc(sizeof(struct can_dev_s)); + if (dev == NULL) + { + canerr("ERROR: Failed to allocate instance of can_dev_s!\n"); + return NULL; + } + + dev->cd_ops = &g_mcp2515ops; + dev->cd_priv = (FAR void *)mcp2515can; + + return dev; +} + +#endif /* CONFIG_CAN && CONFIG_MCP2515 */ diff --git a/drivers/can/mcp2515.h b/drivers/can/mcp2515.h new file mode 100644 index 0000000000..2b9c981572 --- /dev/null +++ b/drivers/can/mcp2515.h @@ -0,0 +1,397 @@ +/* Register Addresses */ + +#define MCP2515_RXF0SIDH 0x00 +#define MCP2515_RXF0SIDL 0x01 +#define MCP2515_RXF0EID8 0x02 +#define MCP2515_RXF0EID0 0x03 +#define MCP2515_RXF1SIDH 0x04 +#define MCP2515_RXF1SIDL 0x05 +#define MCP2515_RXF1EID8 0x06 +#define MCP2515_RXF1EID0 0x07 +#define MCP2515_RXF2SIDH 0x08 +#define MCP2515_RXF2SIDL 0x09 +#define MCP2515_RXF2EID8 0x0a +#define MCP2515_RXF2EID0 0x0b +#define MCP2515_BFPCTRL 0x0c +#define MCP2515_TXRTSCTRL 0x0d +#define MCP2515_CANSTAT 0x0e +#define MCP2515_CANCTRL 0x0f +#define MCP2515_RXF3SIDH 0x10 +#define MCP2515_RXF3SIDL 0x11 +#define MCP2515_RXF3EID8 0x12 +#define MCP2515_RXF3EID0 0x13 +#define MCP2515_RXF4SIDH 0x14 +#define MCP2515_RXF4SIDL 0x15 +#define MCP2515_RXF4EID8 0x16 +#define MCP2515_RXF4EID0 0x17 +#define MCP2515_RXF5SIDH 0x18 +#define MCP2515_RXF5SIDL 0x19 +#define MCP2515_RXF5EID8 0x1a +#define MCP2515_RXF5EID0 0x1b +#define MCP2515_TEC 0x1c +#define MCP2515_REC 0x1d +#define MCP2515_RXM0SIDH 0x20 +#define MCP2515_RXM0SIDL 0x21 +#define MCP2515_RXM0EID8 0x22 +#define MCP2515_RXM0EID0 0x23 +#define MCP2515_RXM1SIDH 0x24 +#define MCP2515_RXM1SIDL 0x25 +#define MCP2515_RXM1EID8 0x26 +#define MCP2515_RXM1EID0 0x27 +#define MCP2515_CNF3 0x28 +#define MCP2515_CNF2 0x29 +#define MCP2515_CNF1 0x2a +#define MCP2515_CANINTE 0x2b +#define MCP2515_CANINTF 0x2c +#define MCP2515_EFLG 0x2d +#define MCP2515_TXB0CTRL 0x30 +#define MCP2515_TXB0SIDH 0x31 +#define MCP2515_TXB0SIDL 0x32 +#define MCP2515_TXB0EID8 0x33 +#define MCP2515_TXB0EID0 0x34 +#define MCP2515_TXB0DLC 0x35 +#define MCP2515_TXB0D0 0x36 +#define MCP2515_TXB0D1 0x37 +#define MCP2515_TXB0D2 0x38 +#define MCP2515_TXB0D3 0x39 +#define MCP2515_TXB0D4 0x3a +#define MCP2515_TXB0D5 0x3b +#define MCP2515_TXB0D6 0x3c +#define MCP2515_TXB0D7 0x3d +#define MCP2515_TXB1CTRL 0x40 +#define MCP2515_TXB1SIDH 0x41 +#define MCP2515_TXB1SIDL 0x42 +#define MCP2515_TXB1EID8 0x43 +#define MCP2515_TXB1EID0 0x44 +#define MCP2515_TXB1DLC 0x45 +#define MCP2515_TXB1D0 0x46 +#define MCP2515_TXB1D1 0x47 +#define MCP2515_TXB1D2 0x48 +#define MCP2515_TXB1D3 0x49 +#define MCP2515_TXB1D4 0x4a +#define MCP2515_TXB1D5 0x4b +#define MCP2515_TXB1D6 0x4c +#define MCP2515_TXB1D7 0x4d +#define MCP2515_TXB2CTRL 0x50 +#define MCP2515_TXB2SIDH 0x51 +#define MCP2515_TXB2SIDL 0x52 +#define MCP2515_TXB2EID8 0x53 +#define MCP2515_TXB2EID0 0x54 +#define MCP2515_TXB2DLC 0x55 +#define MCP2515_TXB2D0 0x56 +#define MCP2515_TXB2D1 0x57 +#define MCP2515_TXB2D2 0x58 +#define MCP2515_TXB2D3 0x59 +#define MCP2515_TXB2D4 0x5a +#define MCP2515_TXB2D5 0x5b +#define MCP2515_TXB2D6 0x5c +#define MCP2515_TXB2D7 0x5d +#define MCP2515_RXB0CTRL 0x60 +#define MCP2515_RXB0SIDH 0x61 +#define MCP2515_RXB0SIDL 0x62 +#define MCP2515_RXB0EID8 0x63 +#define MCP2515_RXB0EID0 0x64 +#define MCP2515_RXB0DLC 0x65 +#define MCP2515_RXB0D0 0x66 +#define MCP2515_RXB0D1 0x67 +#define MCP2515_RXB0D2 0x68 +#define MCP2515_RXB0D3 0x69 +#define MCP2515_RXB0D4 0x6a +#define MCP2515_RXB0D5 0x6b +#define MCP2515_RXB0D6 0x6c +#define MCP2515_RXB0D7 0x6d +#define MCP2515_RXB1CTRL 0x70 +#define MCP2515_RXB1SIDH 0x71 +#define MCP2515_RXB1SIDL 0x72 +#define MCP2515_RXB1EID8 0x73 +#define MCP2515_RXB1EID0 0x74 +#define MCP2515_RXB1DLC 0x75 +#define MCP2515_RXB1D0 0x76 +#define MCP2515_RXB1D1 0x77 +#define MCP2515_RXB1D2 0x78 +#define MCP2515_RXB1D3 0x79 +#define MCP2515_RXB1D4 0x7a +#define MCP2515_RXB1D5 0x7b +#define MCP2515_RXB1D6 0x7c +#define MCP2515_RXB1D7 0x7d + +/* Offset to simplify mcp2515_receive() function */ + +#define MCP2515_RX0_OFFSET 0x00 +#define MCP2515_RX1_OFFSET 0x10 + +/* Offset to simplify mcp2515_send() function */ + +#define MCP2515_TX0_OFFSET 0x00 +#define MCP2515_TX1_OFFSET 0x10 +#define MCP2515_TX2_OFFSET 0x20 + +/* CANCTRL: CAN CONTROL REGISTER */ + +#define CANCTRL_CLKPRE_SHIFT (0) /* Bits 0-1: CLKOUT Pin Prescaler bits */ +#define CANCTRL_CLKPRE_MASK (3 << CANCTRL_CLKPRE_SHIFT) +#define CANCTRL_CLKEN (1 << 2) /* Bit 2: CLKOUT Pin Enable bit */ +#define CANCTRL_OSM (1 << 3) /* Bit 3: One-Shot Mode bit */ +#define CANCTRL_ABAT (1 << 4) /* Bit 4: Abort All Pending Transmissions bit */ +#define CANCTRL_REQOP_SHIFT (5) /* Bits 5-7: Request Operation Mode bits */ +#define CANCTRL_REQOP_MASK (7 << CANCTRL_REQOP_SHIFT) +#define CANCTRL_REQOP_NORMAL (0 << CANCTRL_REQOP_SHIFT) +#define CANCTRL_REQOP_SLEEP (1 << CANCTRL_REQOP_SHIFT) +#define CANCTRL_REQOP_LOOPBK (2 << CANCTRL_REQOP_SHIFT) +#define CANCTRL_REQOP_LISTEN (3 << CANCTRL_REQOP_SHIFT) +#define CANCTRL_REQOP_CONFIG (4 << CANCTRL_REQOP_SHIFT) + +/* TXBnCTRL – TRANSMIT BUFFER n CONTROL REGISTER */ + +#define TXBCTRL_TXP_SHIFT (0) /* Bits 0-1: Transmit Buffer Priority */ +#define TXBCTRL_TXP_MASK (3 << MCP2515_TXBCTRL_TXP_SHIFT) + /* Bit 2: Not used */ +#define TXBCTRL_TXREQ (1 << 3) /* Bit 3: Message Transmit Request bit */ +#define TXBCTRL_TXERR (1 << 4) /* Bit 4: Transmission Error Detected bit */ +#define TXBCTRL_MLOA (1 << 5) /* Bit 5: Message Lost Arbitration bit */ +#define TXBCTRL_ABTF (1 << 6) /* Bit 6: Message Aborted Flag bit */ + /* Bit 7: Not used */ + +/* TXRTSCTRL – TXnRTS PIN CONTROL AND STATUS REGISTER */ + +#define TXRTSCTRL_B0RTSM (1 << 0) /* Bit 0: TX0RTS Pin mode bit */ +#define TXRTSCTRL_B1RTSM (1 << 1) /* Bit 1: TX1RTS Pin mode bit */ +#define TXRTSCTRL_B2RTSM (1 << 2) /* Bit 2: TX2RTS Pin mode bit */ +#define TXRTSCTRL_B0RTS (1 << 3) /* Bit 3: TX0RTS Pin State bit */ +#define TXRTSCTRL_B1RTS (1 << 4) /* Bit 4: TX1RTS Pin State bit */ +#define TXRTSCTRL_B2RTS (1 << 5) /* Bit 5: TX2RTS Pin State bit */ + /* Bit 6-7: Not used */ + +/* TXBnSIDH – TRANSMIT BUFFER n STANDARD IDENTIFIER HIGH */ + +#define TXBSIDH_SID_MASK 0xff /* Standard Identifier bits <10:3> */ + + +/* TXBnSIDL – TRANSMIT BUFFER n STANDARD IDENTIFIER LOW */ + +#define TXBSIDL_SID_SHIFT (5) /* Bits 5-7: Standard Identifier bits <2:0> */ +#define TXBSIDL_SID_MASK (0x7 << TXBSIDL_SID_SHIFT) +#define TXBSIDL_EXIDE (1 << 3) /* Bit 3: Extended Identifier Enable bit */ +#define TXBSIDL_EID_SHIFT (0) /* Bits 0-1: Extended Identifier bits <17:16> */ +#define TXBSIDL_EID_MASK (0x03 << TXBSIDL_EID_MASK) + + +/* TXBnEID8 – TRANSMIT BUFFER n EXTENDED IDENTIFIER HIGH */ + +#define TXBEID8_EID_MASK 0xff /* Bits 0-7: Extended Identifier bits <15:8> */ + +/* TXBnEID0 – TRANSMIT BUFFER n EXTENDED IDENTIFIER LOW */ + +#define TXBEID0_EID_MASK 0xff /* Bits 0-7: Extended Identifier bits <7:0> */ + +/* TXBnDLC - TRANSMIT BUFFER n DATA LENGTH CODE */ + +#define TXBDLC_DLC_SHIFT (0) /* Bits 0-3: Data Length Code <3:0> bits */ +#define TXBDLC_DLC_MASK (0xf << TXBDLC_DLC_SHIFT) +#define TXBDLC_RTR (1 << 6) /* Bit 6: Remote Transmission Request bit */ + +/* TXBnDm – TRANSMIT BUFFER n DATA BYTE m */ + +#define TXBD_D0 (1 << 0) /* Bit 0: Transmit Buffer n Data Field Bytes 0 */ +#define TXBD_D1 (1 << 1) /* Bit 1: Transmit Buffer n Data Field Bytes 1 */ +#define TXBD_D2 (1 << 2) /* Bit 2: Transmit Buffer n Data Field Bytes 2 */ +#define TXBD_D3 (1 << 3) /* Bit 3: Transmit Buffer n Data Field Bytes 3 */ +#define TXBD_D4 (1 << 4) /* Bit 4: Transmit Buffer n Data Field Bytes 4 */ +#define TXBD_D5 (1 << 5) /* Bit 5: Transmit Buffer n Data Field Bytes 5 */ +#define TXBD_D6 (1 << 6) /* Bit 6: Transmit Buffer n Data Field Bytes 6 */ +#define TXBD_D7 (1 << 7) /* Bit 7: Transmit Buffer n Data Field Bytes 7 */ + +/* RXB0CTRL – RECEIVE BUFFER 0 CONTROL */ + +#define RXB0CTRL_FILHIT (1 << 0) /* Bit 0: Filter Hit bit - 1 = Msg was accepted by Filter 1; 0 = Filter 0 */ +#define RXB0CTRL_BUKT1 (1 << 1) /* Bit 1: Read-only Copy of BUKT bit (used internally by the MCP2515) */ +#define RXB0CTRL_BUKT (1 << 2) /* Bit 2: Rollover Enable bit */ + +/* These bits are common to RXB0 and RXB1: */ + +#define RXBCTRL_RXRTR (1 << 3) /* Bit 3: Received Remote Transfer Request bit */ + /* Bit 4: Not used */ +#define RXBCTRL_RXM_SHIFT (5) /* Bits 5-6: Receive Buffer Operating Mode bits */ +#define RXBCTRL_RXM_MASK (0x3 << RXBCTRL_RXM_SHIFT) +#define RXBCTRL_RXM_ALLMSG (3 << RXBCTRL_RXM_SHIFT) /* 11: Turn mask/filters off; receive any message */ +#define RXBCTRL_RXM_ALLVALID (0 << RXBCTRL_RXM_SHIFT) /* 00: Receive all valid msgs using (STD or EXT) that meet filter criteria */ + /* Bit 7: Not used */ + +/* N.B.: In the datasheet DS21801D the file RXM of RXBnCTRL could to assume + the value 01 and 10 to receive only STD or EXT msgs respectively. + But in a more recent datasheet DS20001801H it was removed. */ + +/* RXB1CTRL – RECEIVE BUFFER 1 CONTROL */ + +#define RXB1CTRL_FILHIT_SHIFT (0) /* Filter Hit bits - indicates which acceptance filter enabled reception of message */ +#define RXB1CTRL_FILHIT_MASK (0x7 << RXB0CTRL_FILHIT_SHIFT) +#define RXB1CTRL_FILHIT_F5 (5 << RXB1CTRL_FILHIT_SHIFT) /* Acceptance Filter 5 (RXF5) */ +#define RXB1CTRL_FILHIT_F4 (4 << RXB1CTRL_FILHIT_SHIFT) /* Acceptance Filter 4 (RXF4) */ +#define RXB1CTRL_FILHIT_F3 (3 << RXB1CTRL_FILHIT_SHIFT) /* Acceptance Filter 3 (RXF3) */ +#define RXB1CTRL_FILHIT_F2 (2 << RXB1CTRL_FILHIT_SHIFT) /* Acceptance Filter 2 (RXF2) */ +#define RXB1CTRL_FILHIT_F1 (1 << RXB1CTRL_FILHIT_SHIFT) /* Acceptance Filter 1 (RXF1) (Only if BUKT bit set in RXB0CTRL) */ +#define RXB1CTRL_FILHIT_F0 (0 << RXB1CTRL_FILHIT_SHIFT) /* Acceptance Filter 0 (RXF0) (Only if BUKT bit set in RXB0CTRL) */ + +/* BFPCTRL – RXnBF PIN CONTROL AND STATUS */ + +#define BFPCTRL_B0BFM (1 << 0) /* Bit 0: RX0BF Pin Operation Mode bit */ +#define BFPCTRL_B1BFM (1 << 1) /* Bit 1: RX1BF Pin Operation Mode bit */ +#define BFPCTRL_B0BFE (1 << 2) /* Bit 2: RX0BF Pin Function Enable bit */ +#define BFPCTRL_B1BFE (1 << 3) /* Bit 3: RX1BF Pin Function Enable bit */ +#define BFPCTRL_B0BFS (1 << 4) /* Bit 4: RX0BF Pin State bit (Digital Output mode only) */ +#define BFPCTRL_B1BFS (1 << 5) /* Bit 5: RX1BF Pin State bit (Digital Output mode only) */ + /* Bits 6-7: Not used */ + +/* RXBnSIDH – RECEIVE BUFFER n STANDARD IDENTIFIER HIGH */ + +#define RXBSIDH_SID_MASK 0xff /* Standard Identifier bits <10:3> */ + +/* RXBnSIDL – RECEIVE BUFFER n STANDARD IDENTIFIER LOW */ + +#define RXBSIDL_SID_SHIFT (5) /* Bits 5-7: Standard Identifier bits <2:0> */ +#define RXBSIDL_SID_MASK (0x7 << RXBSIDL_SID_SHIFT) +#define RXBSIDL_SRR (1 << 4) /* Bit 4: Standard Frame Remote Transmit Request bit (valid only if IDE bit = '0')*/ +#define RXBSIDL_IDE (1 << 3) /* Bit 3: Extended Identifier Message received */ + /* Bit 2: Not used */ +#define RXBSIDL_EID_SHIFT (0) /* Bits 0-1: Extended Identifier bits <17:16> */ +#define RXBSIDL_EID_MASK (0x03 << RXBSIDL_EID_SHIFT) + +/* RXBnEID8 – RECEIVE BUFFER n EXTENDED IDENTIFIER HIGH */ + +#define RXBEID8_EID_MASK 0xff /* Bits 0-7: Extended Identifier bits <15:8> */ + +/* RXBnEID0 – RECEIVE BUFFER n EXTENDED IDENTIFIER LOW */ + +#define RXBEID0_EID_MASK 0xff /* Bits 0-7: Extended Identifier bits <7:0> */ + +/* RXBnDLC – RECEIVE BUFFER n DATA LENGHT CODE */ + +#define RXBDLC_DLC_SHIFT (0) /* Bits 0-3: Data Length Code <3:0> bits */ +#define RXBDLC_DLC_MASK (0xf << RXBDLC_DLC_SHIFT) +#define RXBDLC_RB0 (1 << 4) /* Bit 4: Reserved bit 0 */ +#define RXBDLC_RB1 (1 << 5) /* Bit 5: Reserved bit 1 */ +#define RXBDLC_RTR (1 << 6) /* Bit 6: Remote Transmission Request bit */ + /* Bit 7: Not used */ + +/* RXFnSIDH – FILTER n STANDARD IDENTIFIER HIGH */ + +#define RXFSIDH_SID_MASK 0xff /* Standard Identifier Filter bits <10:3> */ + +/* RXFnSIDL – FILTER n STANDARD IDENTIFIER LOW */ + +#define RXFSIDL_EID_SHIFT (0) /* Bit 0-1: Extended Identifier Filter bits <17:16> */ +#define RXFSIDL_EID_MASK (3 << RXFSIDL_EID_SHIFT) +#define RXFSIDL_EXIDE (1 << 3) /* Bit 3: Extended Identifier Enable bit */ +#define RXFSIDL_SID_SHIFT (5) /* Bits 5-7: Standard Identifier Filter bits <2:0> */ +#define RXFSIDL_SID_MASK (0x7 << RXFSIDL_SID_SHIFT) + +/* RXFnEID8 – FILTER n EXTENDED IDENTIFIER HIGH */ + +#define RXFEID8_EID_MASK 0xff /* Extended Identifier bits <15:8> */ + +/* RXFnEID0 – FILTER n EXTENDED IDENTIFIER LOW */ + +#define RXFEID0_EID_MASK 0xff /* Extended Identifier bits <7:0> */ + +/* RXMnSIDH – MASK n STANDARD IDENTIFIER HIGH */ + +#define RXMSIDH_SID_MASK 0xff /* Standard Identifier Mask bits <10:3> */ + +/* RXMnSIDL – MASK n STANDARD IDENTIFIER LOW */ + +#define RXMSIDL_EID_SHIFT (0) /* Bits 0-1: Extended Identifier Mask bits <17:16> */ +#define RXMSIDL_EID_MASK (3 << RXMSIDH_EID_SHIFT) +#define RXMSIDL_SID_SHIFT (5) /* Bits 5-7: Standard Identifier Mask bits <2:0> */ +#define RXMSIDL_MASK (7 << RXMSIDH_SID_SHIFT) + +/* RXMnEID8 – MASK n EXTENDED IDENTIFIER HIGH */ + +#define RXMEID8_EID_MASK 0xff /* Extended Identifier bits <15:8> */ + +/* RXMnEID0 – MASK n EXTENDED IDENTIFIER LOW */ + +#define RXMEID0_EID_MASK 0xff /* Extended Identifier Mask bits <7:0> */ + +/* CNF1 – CONFIGURATION 1 */ + +#define CNF1_BRP_SHIFT (0) /* Bits 0-5: Baud Rate Prescaler bits <5:0>, TQ = 2 x (BRP + 1)/Fosc */ +#define CNF1_BRP_MASK (0x3f << CNF1_BRP_SHIFT) +#define CNF1_SJW_SHIFT (6) /* Bit 6-7: Synchronization Jump Width Length bits <1:0> */ +#define CNF1_SJW_MASK (3 << CNF1_SJW_SHIFT) +# define CNF1_SJW_4xTQ (3 << CNF1_SJW_SHIFT) /* Length = 4 x TQ */ +# define CNF1_SJW_3xTQ (2 << CNF1_SJW_SHIFT) /* Length = 3 x TQ */ +# define CNF1_SJW_2xTQ (1 << CNF1_SJW_SHIFT) /* Length = 2 x TQ */ +# define CNF1_SJW_1xTQ (0 << CNF1_SJW_SHIFT) /* Length = 1 x TQ */ + +/* CNF2 – CONFIGURATION 2 */ + +#define CNF2_PRSEG_SHIFT (0) /* Bits 0-2: Propagation Segment Length bits <2:0>, (PRSEG + 1) x TQ */ +#define CNF2_PRSEG_MASK (7 << CNF2_PRSEG_SHIFT) +#define CNF2_PHSEG1_SHIFT (3) /* Bits 3-5: PS1 Length bits <2:0>, (PHSEG1 + 1) x TQ */ +#define CNF2_PHSEG1_MASK (7 << CNF2_PHSEG1_SHIFT) +#define CNF2_SAM (1 << 6) /* Bit 6: Sample Point Configuration bit */ +#define CNF2_BTLMODE (1 << 7) /* Bit 7: PS2 Bit Time Length bit */ + +/* CNF3 - CONFIGURATION 3 */ + +#define CNF3_PHSEG2_SHIFT (0) /* Bits 0-2: PS2 Length bits<2:0>, (PHSEG2 + 1) x TQ */ +#define CNF3_PHSEG2_MASK (7 << CNF3_PHSEG2_SHIFT) +#define CNF3_WAKFIL (1 << 6) /* Bit 3: Wake-up Filter bit */ +#define CNF3_SOF (1 << 7) /* Bit 7: Start-of-Frame signal bit */ + +/* TEC – TRANSMIT ERROR COUNTER */ + +#define TEC_MASK 0xff /* Transmit Error Count bits <7:0> */ + +/* REC – RECEIVER ERROR COUNTER */ + +#define REC_MASK 0xff /* Receive Error Count bits <7:0> */ + +/* EFLG – ERROR FLAG */ + +#define EFLG_EWARN (1 << 0) /* Bit 0: Error Warning Flag bit */ +#define EFLG_RXWAR (1 << 1) /* Bit 1: Receive Error Warning Flag bit */ +#define EFLG_TXWAR (1 << 2) /* Bit 2: Transmit Error Warning Flag bit */ +#define EFLG_RXEP (1 << 3) /* Bit 3: Receive Error-Passive Flag bit */ +#define EFLG_TXEP (1 << 4) /* Bit 4: Transmit Error-Passive Flag bit */ +#define EFLG_TXBO (1 << 5) /* Bit 5: Bus-Off Error Flag bit */ +#define EFLG_RX0OVR (1 << 6) /* Bit 6: Receive Buffer 0 Overflow Flag bit */ +#define EFLG_RX1OVR (1 << 7) /* Bit 7: Receive Buffer 1 Overflow Flag bit */ + +/* CANINTE/CANINTF – INTERRUPT ENABLE/FLAG */ + +#define MCP2515_INT_RX0 (1 << 0) /* Bit 0: Receive Buffer 0 Full Interrupt Enable bit */ +#define MCP2515_INT_RX1 (1 << 1) /* Bit 1: Receive Buffer 1 Full Interrupt Enable bit */ +#define MCP2515_INT_TX0 (1 << 2) /* Bit 2: Transmit Buffer 0 Empty Interrupt Enable bit */ +#define MCP2515_INT_TX1 (1 << 3) /* Bit 3: Transmit Buffer 1 Empty Interrupt Enable bit */ +#define MCP2515_INT_TX2 (1 << 4) /* Bit 4: Transmit Buffer 2 Empty Interrupt Enable bit */ +#define MCP2515_INT_ERR (1 << 5) /* Bit 5: Error Interrupt Enable bit (multiple sources in EFLG register) */ +#define MCP2515_INT_WAK (1 << 6) /* Bit 6: Wakeup Interrupt Enable bit */ +#define MCP2515_INT_MERR (1 << 7) /* Bit 7: Message Error Interrupt Enable bit */ + +/* MCP2515 SPI Instruction/Command byte */ + +#define MCP2515_RESET 0xC0 +#define MCP2515_READ 0x03 +#define MCP2515_READ_RX0 0x90 +#define MCP2515_READ_RX1 0x94 +#define MCP2515_WRITE 0x02 +#define MCP2515_LOAD_TX0 0x40 +#define MCP2515_LOAD_TX1 0x42 +#define MCP2515_LOAD_TX2 0x44 +#define MCP2515_RTS_TX0 0x81 +#define MCP2515_RTS_TX1 0x82 +#define MCP2515_RTS_TX2 0x84 +#define MCP2515_RTS_ALL 0x87 +#define MCP2515_READ_STATUS 0xA0 +#define MCP2515_RX_STATUS 0xB0 +#define MCP2515_BITMOD 0x05 + +/* CANCTRL register will be 0x87 after reset and in Conf. Mode */ + +#define DEFAULT_CANCTRL_CONFMODE 0x87 + +/* Crystal Frequency used on MCP2515 board */ + +#define MCP2515_CANCLK_FREQUENCY 8000000 + diff --git a/include/nuttx/can/mcp2515.h b/include/nuttx/can/mcp2515.h new file mode 100644 index 0000000000..bca2d0db73 --- /dev/null +++ b/include/nuttx/can/mcp2515.h @@ -0,0 +1,164 @@ +/**************************************************************************** + * include/nuttx/can/mcp2515.h + * + * Copyright (C) 2017 Alan Carvalho de Assis. All rights reserved. + * Author: Alan Carvalho de Assis + * + * 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_CAN_MCP2515_H +#define __INCLUDE_NUTTX_CAN_MCP2515_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include +#include +#include + +#if defined(CONFIG_CAN) && defined(CONFIG_CAN_MCP2515) + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* SPI BUS PARAMETERS *******************************************************/ + +#define MCP2515_SPI_FREQUENCY (1000000) /* 1 MHz */ +#define MCP2515_SPI_MODE (SPIDEV_MODE0) /* Device uses SPI Mode 0: CPOL=0, CPHA=0 */ + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +typedef void (*mcp2515_handler_t)(FAR struct mcp2515_config_s *config, FAR void *arg); + +/* A reference to a structure of this type must be passed to the MCP2515 driver when the + * driver is instantiated. This structure provides information about the configuration of the + * MCP2515 and provides some board-specific hooks. + * + * Memory for this structure is provided by the caller. It is not copied by the driver + * and is presumed to persist while the driver is active. The memory must be writeable + * because, under certain circumstances, the driver may modify the frequency. + */ + +struct mcp2515_config_s +{ + struct spi_dev_s *spi; /* SPI used for MCP2515 communication */ + uint32_t baud; /* Configured baud */ + uint32_t btp; /* Bit timing/prescaler register setting */ + uint8_t devid; /* MCP2515 device ID */ + uint8_t mode; /* See enum mcp2515_canmod_e */ + uint8_t nfilters; /* Number of standard/extended filters */ + uint8_t ntxbuffers; /* Number of TX Buffer available */ + uint8_t txbuf0[10]; /* Transmit Buffer 0 */ + uint8_t txbuf1[10]; /* Transmit Buffer 1 */ + uint8_t txbuf2[10]; /* Transmit Buffer 2 */ +#ifdef MCP2515_LOOPBACK + bool loopback; /* True: Loopback mode */ +#endif + + /* Device characterization */ + + /* IRQ/GPIO access callbacks. These operations all hidden behind + * callbacks to isolate the ADXL345 driver from differences in GPIO + * interrupt handling by varying boards and MCUs. + * + * attach - Attach the ADXL345 interrupt handler to the GPIO interrupt + */ + + int (*attach)(FAR struct mcp2515_config_s *state, mcp2515_handler_t handler, + FAR void *arg); +}; + + +typedef FAR void *MCP2515_HANDLE; + +struct mcp2515_can_s; + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/**************************************************************************** + * Name: mcp2515_instantiate + * + * Description: + * Initialize a CAN Driver for MCP2515. + * + * Input Parameters: + * spi - An instance of the SPI interface to use to communicate with + * MCP2515 + * config - Describes the configuration of the MCP2515 part. + * + * Returned Value: + * Zero (OK) on success; a negated errno value on failure. + * + ****************************************************************************/ + +FAR struct mcp2515_can_s *mcp2515_instantiate(FAR struct mcp2515_config_s *config); + +/**************************************************************************** + * Name: mcp2515_initialize + * + * Description: + * Initialize a CAN Driver for MCP2515. + * + * Input Parameters: + * spi - An instance of the SPI interface to use to communicate with + * MCP2515 + * config - Describes the configuration of the MCP2515 part. + * + * Returned Value: + * Zero (OK) on success; a negated errno value on failure. + * + ****************************************************************************/ + +FAR struct can_dev_s *mcp2515_initialize(FAR struct mcp2515_can_s *mcp2515can); + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* CONFIG_CAN && CONFIG_CAN_MCP2515 */ + +#endif /* __INCLUDE_NUTTX_CAN_MCP2515_H */ -- GitLab From 607b9b5a8ce0b2da174afa8b5cca840ee7134e7c Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Tue, 23 May 2017 14:29:36 -0300 Subject: [PATCH 860/990] Add board support to test Microchip MCP2515 driver --- configs/stm32f103-minimum/mcp2515/Make.defs | 113 ++ configs/stm32f103-minimum/mcp2515/defconfig | 1345 +++++++++++++++++ configs/stm32f103-minimum/src/Makefile | 4 + configs/stm32f103-minimum/src/stm32_bringup.c | 7 + configs/stm32f103-minimum/src/stm32_mcp2515.c | 240 +++ configs/stm32f103-minimum/src/stm32_spi.c | 11 + .../stm32f103-minimum/src/stm32f103_minimum.h | 7 + 7 files changed, 1727 insertions(+) create mode 100644 configs/stm32f103-minimum/mcp2515/Make.defs create mode 100644 configs/stm32f103-minimum/mcp2515/defconfig create mode 100644 configs/stm32f103-minimum/src/stm32_mcp2515.c diff --git a/configs/stm32f103-minimum/mcp2515/Make.defs b/configs/stm32f103-minimum/mcp2515/Make.defs new file mode 100644 index 0000000000..8d3d478305 --- /dev/null +++ b/configs/stm32f103-minimum/mcp2515/Make.defs @@ -0,0 +1,113 @@ +############################################################################ +# configs/stm32f103-minimum/nsh/Make.defs +# +# Copyright (C) 2016 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. +# +############################################################################ + +include ${TOPDIR}/.config +include ${TOPDIR}/tools/Config.mk +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs + +LDSCRIPT = ld.script + +ifeq ($(WINTOOL),y) + # Windows-native toolchains + DIRLINK = $(TOPDIR)/tools/copydir.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mkwindeps.sh + ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" + ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" +else + # Linux/Cygwin-native toolchain + MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT) + ARCHINCLUDES = -I. -isystem $(TOPDIR)/include + ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) +endif + +CC = $(CROSSDEV)gcc +CXX = $(CROSSDEV)g++ +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(CROSSDEV)ar rcs +NM = $(CROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump + +ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} +ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} + +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + ARCHOPTIMIZATION = -g +endif + +ifneq ($(CONFIG_DEBUG_NOOPT),y) + ARCHOPTIMIZATION += $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer +endif + +ARCHCFLAGS = -fno-builtin +ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fcheck-new +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow -Wundef +ARCHWARNINGSXX = -Wall -Wshadow -Wundef +ARCHDEFINES = +ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 + +CFLAGS = $(ARCHCFLAGS) $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) +CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +NXFLATLDFLAGS1 = -r -d -warn-common +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections +LDNXFLATFLAGS = -e main -s 2048 + +ASMEXT = .S +OBJEXT = .o +LIBEXT = .a +EXEEXT = + +ifneq ($(CROSSDEV),arm-nuttx-elf-) + LDFLAGS += -nostartfiles -nodefaultlibs +endif +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + LDFLAGS += -g +endif + + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -Wundef -g -pipe +HOSTLDFLAGS = + diff --git a/configs/stm32f103-minimum/mcp2515/defconfig b/configs/stm32f103-minimum/mcp2515/defconfig new file mode 100644 index 0000000000..eaada4d3dc --- /dev/null +++ b/configs/stm32f103-minimum/mcp2515/defconfig @@ -0,0 +1,1345 @@ +# +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# + +# +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set +CONFIG_DEFAULT_SMALL=y +CONFIG_HOST_LINUX=y +# CONFIG_HOST_OSX is not set +# CONFIG_HOST_WINDOWS is not set +# CONFIG_HOST_OTHER is not set + +# +# Build Configuration +# +# CONFIG_APPS_DIR="../apps" +CONFIG_BUILD_FLAT=y +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +# CONFIG_INTELHEX_BINARY is not set +# CONFIG_MOTOROLA_SREC is not set +CONFIG_RAW_BINARY=y +# CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set + +# +# Customize Header Files +# +# CONFIG_ARCH_STDINT_H is not set +# CONFIG_ARCH_STDBOOL_H is not set +# CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_FLOAT_H is not set +# CONFIG_ARCH_STDARG_H is not set +# CONFIG_ARCH_DEBUG_H is not set + +# +# Debug Options +# +CONFIG_DEBUG_ALERT=y +CONFIG_DEBUG_FEATURES=y + +# +# Debug SYSLOG Output Controls +# +CONFIG_DEBUG_ERROR=y +CONFIG_DEBUG_WARN=y +CONFIG_DEBUG_INFO=y +# CONFIG_DEBUG_ASSERTIONS is not set + +# +# Subsystem Debug Options +# +# CONFIG_DEBUG_BINFMT is not set +# CONFIG_DEBUG_FS is not set +# CONFIG_DEBUG_GRAPHICS is not set +# CONFIG_DEBUG_LIB is not set +# CONFIG_DEBUG_MM is not set +# CONFIG_DEBUG_SCHED is not set + +# +# OS Function Debug Options +# +# CONFIG_DEBUG_IRQ is not set + +# +# Driver Debug Options +# +# CONFIG_DEBUG_LEDS is not set +CONFIG_DEBUG_CAN=y +CONFIG_DEBUG_CAN_ERROR=y +CONFIG_DEBUG_CAN_WARN=y +CONFIG_DEBUG_CAN_INFO=y +# CONFIG_DEBUG_GPIO is not set +# CONFIG_DEBUG_SPI is not set +# CONFIG_DEBUG_TIMER is not set +CONFIG_ARCH_HAVE_STACKCHECK=y +# CONFIG_STACK_COLORATION is not set +CONFIG_ARCH_HAVE_HEAPCHECK=y +# CONFIG_HEAP_COLORATION is not set +# CONFIG_DEBUG_SYMBOLS is not set +CONFIG_ARCH_HAVE_CUSTOMOPT=y +# CONFIG_DEBUG_NOOPT is not set +# CONFIG_DEBUG_CUSTOMOPT is not set +CONFIG_DEBUG_FULLOPT=y + +# +# System Type +# +CONFIG_ARCH_ARM=y +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_MISOC is not set +# CONFIG_ARCH_RENESAS is not set +# CONFIG_ARCH_RISCV is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_XTENSA is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="arm" + +# +# ARM Options +# +# CONFIG_ARCH_CHIP_A1X is not set +# CONFIG_ARCH_CHIP_C5471 is not set +# CONFIG_ARCH_CHIP_DM320 is not set +# CONFIG_ARCH_CHIP_EFM32 is not set +# CONFIG_ARCH_CHIP_IMX1 is not set +# CONFIG_ARCH_CHIP_IMX6 is not set +# CONFIG_ARCH_CHIP_KINETIS is not set +# CONFIG_ARCH_CHIP_KL is not set +# CONFIG_ARCH_CHIP_LM is not set +# CONFIG_ARCH_CHIP_TIVA is not set +# CONFIG_ARCH_CHIP_LPC11XX is not set +# CONFIG_ARCH_CHIP_LPC17XX is not set +# CONFIG_ARCH_CHIP_LPC214X is not set +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_NUC1XX is not set +# CONFIG_ARCH_CHIP_SAMA5 is not set +# CONFIG_ARCH_CHIP_SAMD is not set +# CONFIG_ARCH_CHIP_SAML is not set +# CONFIG_ARCH_CHIP_SAM34 is not set +# CONFIG_ARCH_CHIP_SAMV7 is not set +CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F0 is not set +# CONFIG_ARCH_CHIP_STM32F7 is not set +# CONFIG_ARCH_CHIP_STM32L4 is not set +# CONFIG_ARCH_CHIP_STR71X is not set +# CONFIG_ARCH_CHIP_TMS570 is not set +# CONFIG_ARCH_CHIP_XMC4 is not set +# CONFIG_ARCH_ARM7TDMI is not set +# CONFIG_ARCH_ARM926EJS is not set +# CONFIG_ARCH_ARM920T is not set +# CONFIG_ARCH_CORTEXM0 is not set +# CONFIG_ARCH_CORTEXM23 is not set +CONFIG_ARCH_CORTEXM3=y +# CONFIG_ARCH_CORTEXM33 is not set +# CONFIG_ARCH_CORTEXM4 is not set +# CONFIG_ARCH_CORTEXM7 is not set +# CONFIG_ARCH_CORTEXA5 is not set +# CONFIG_ARCH_CORTEXA8 is not set +# CONFIG_ARCH_CORTEXA9 is not set +# CONFIG_ARCH_CORTEXR4 is not set +# CONFIG_ARCH_CORTEXR4F is not set +# CONFIG_ARCH_CORTEXR5 is not set +# CONFIG_ARCH_CORTEX5F is not set +# CONFIG_ARCH_CORTEXR7 is not set +# CONFIG_ARCH_CORTEXR7F is not set +CONFIG_ARCH_FAMILY="armv7-m" +CONFIG_ARCH_CHIP="stm32" +# CONFIG_ARM_TOOLCHAIN_IAR is not set +CONFIG_ARM_TOOLCHAIN_GNU=y +# CONFIG_ARMV7M_USEBASEPRI is not set +CONFIG_ARCH_HAVE_CMNVECTOR=y +# CONFIG_ARMV7M_CMNVECTOR is not set +# CONFIG_ARMV7M_LAZYFPU is not set +# CONFIG_ARCH_HAVE_FPU is not set +# CONFIG_ARCH_HAVE_DPFPU is not set +# CONFIG_ARCH_HAVE_TRUSTZONE is not set +CONFIG_ARM_HAVE_MPU_UNIFIED=y +# CONFIG_ARM_MPU is not set +# CONFIG_DEBUG_HARDFAULT is not set + +# +# ARMV7M Configuration Options +# +# CONFIG_ARMV7M_HAVE_ICACHE is not set +# CONFIG_ARMV7M_HAVE_DCACHE is not set +# CONFIG_ARMV7M_HAVE_ITCM is not set +# CONFIG_ARMV7M_HAVE_DTCM is not set +# CONFIG_ARMV7M_TOOLCHAIN_IARL is not set +# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set +# CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set +# CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL is not set +CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL=y +CONFIG_ARMV7M_HAVE_STACKCHECK=y +# CONFIG_ARMV7M_STACKCHECK is not set +# CONFIG_ARMV7M_ITMSYSLOG is not set +CONFIG_SERIAL_TERMIOS=y +# CONFIG_CAN_EXTID is not set +# CONFIG_CAN_LOOPBACK is not set + +# +# STM32 Configuration Options +# +# CONFIG_ARCH_CHIP_STM32L151C6 is not set +# CONFIG_ARCH_CHIP_STM32L151C8 is not set +# CONFIG_ARCH_CHIP_STM32L151CB is not set +# CONFIG_ARCH_CHIP_STM32L151R6 is not set +# CONFIG_ARCH_CHIP_STM32L151R8 is not set +# CONFIG_ARCH_CHIP_STM32L151RB is not set +# CONFIG_ARCH_CHIP_STM32L151V6 is not set +# CONFIG_ARCH_CHIP_STM32L151V8 is not set +# CONFIG_ARCH_CHIP_STM32L151VB is not set +# CONFIG_ARCH_CHIP_STM32L152C6 is not set +# CONFIG_ARCH_CHIP_STM32L152C8 is not set +# CONFIG_ARCH_CHIP_STM32L152CB is not set +# CONFIG_ARCH_CHIP_STM32L152R6 is not set +# CONFIG_ARCH_CHIP_STM32L152R8 is not set +# CONFIG_ARCH_CHIP_STM32L152RB is not set +# CONFIG_ARCH_CHIP_STM32L152V6 is not set +# CONFIG_ARCH_CHIP_STM32L152V8 is not set +# CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC is not set +# CONFIG_ARCH_CHIP_STM32L162ZD is not set +# CONFIG_ARCH_CHIP_STM32L162VE is not set +# CONFIG_ARCH_CHIP_STM32F100C8 is not set +# CONFIG_ARCH_CHIP_STM32F100CB is not set +# CONFIG_ARCH_CHIP_STM32F100R8 is not set +# CONFIG_ARCH_CHIP_STM32F100RB is not set +# CONFIG_ARCH_CHIP_STM32F100RC is not set +# CONFIG_ARCH_CHIP_STM32F100RD is not set +# CONFIG_ARCH_CHIP_STM32F100RE is not set +# CONFIG_ARCH_CHIP_STM32F100V8 is not set +# CONFIG_ARCH_CHIP_STM32F100VB is not set +# CONFIG_ARCH_CHIP_STM32F100VC is not set +# CONFIG_ARCH_CHIP_STM32F100VD is not set +# CONFIG_ARCH_CHIP_STM32F100VE is not set +# CONFIG_ARCH_CHIP_STM32F102CB is not set +# CONFIG_ARCH_CHIP_STM32F103T8 is not set +# CONFIG_ARCH_CHIP_STM32F103TB is not set +# CONFIG_ARCH_CHIP_STM32F103C4 is not set +CONFIG_ARCH_CHIP_STM32F103C8=y +# CONFIG_ARCH_CHIP_STM32F103CB is not set +# CONFIG_ARCH_CHIP_STM32F103R8 is not set +# CONFIG_ARCH_CHIP_STM32F103RB is not set +# CONFIG_ARCH_CHIP_STM32F103RC is not set +# CONFIG_ARCH_CHIP_STM32F103RD is not set +# CONFIG_ARCH_CHIP_STM32F103RE is not set +# CONFIG_ARCH_CHIP_STM32F103RG is not set +# CONFIG_ARCH_CHIP_STM32F103V8 is not set +# CONFIG_ARCH_CHIP_STM32F103VB is not set +# CONFIG_ARCH_CHIP_STM32F103VC is not set +# CONFIG_ARCH_CHIP_STM32F103VE is not set +# CONFIG_ARCH_CHIP_STM32F103ZE is not set +# CONFIG_ARCH_CHIP_STM32F105VB is not set +# CONFIG_ARCH_CHIP_STM32F105RB is not set +# CONFIG_ARCH_CHIP_STM32F107VC is not set +# CONFIG_ARCH_CHIP_STM32F205RG is not set +# CONFIG_ARCH_CHIP_STM32F207IG is not set +# CONFIG_ARCH_CHIP_STM32F207ZE is not set +# CONFIG_ARCH_CHIP_STM32F302K6 is not set +# CONFIG_ARCH_CHIP_STM32F302K8 is not set +# CONFIG_ARCH_CHIP_STM32F302CB is not set +# CONFIG_ARCH_CHIP_STM32F302CC is not set +# CONFIG_ARCH_CHIP_STM32F302RB is not set +# CONFIG_ARCH_CHIP_STM32F302RC is not set +# CONFIG_ARCH_CHIP_STM32F302VB is not set +# CONFIG_ARCH_CHIP_STM32F302VC is not set +# CONFIG_ARCH_CHIP_STM32F303K6 is not set +# CONFIG_ARCH_CHIP_STM32F303K8 is not set +# CONFIG_ARCH_CHIP_STM32F303C6 is not set +# CONFIG_ARCH_CHIP_STM32F303C8 is not set +# CONFIG_ARCH_CHIP_STM32F303CB is not set +# CONFIG_ARCH_CHIP_STM32F303CC is not set +# CONFIG_ARCH_CHIP_STM32F303RB is not set +# CONFIG_ARCH_CHIP_STM32F303RC is not set +# CONFIG_ARCH_CHIP_STM32F303RD is not set +# CONFIG_ARCH_CHIP_STM32F303RE is not set +# CONFIG_ARCH_CHIP_STM32F303VB is not set +# CONFIG_ARCH_CHIP_STM32F303VC is not set +# CONFIG_ARCH_CHIP_STM32F334K4 is not set +# CONFIG_ARCH_CHIP_STM32F334K6 is not set +# CONFIG_ARCH_CHIP_STM32F334K8 is not set +# CONFIG_ARCH_CHIP_STM32F334C4 is not set +# CONFIG_ARCH_CHIP_STM32F334C6 is not set +# CONFIG_ARCH_CHIP_STM32F334C8 is not set +# CONFIG_ARCH_CHIP_STM32F334R4 is not set +# CONFIG_ARCH_CHIP_STM32F334R6 is not set +# CONFIG_ARCH_CHIP_STM32F334R8 is not set +# CONFIG_ARCH_CHIP_STM32F372C8 is not set +# CONFIG_ARCH_CHIP_STM32F372R8 is not set +# CONFIG_ARCH_CHIP_STM32F372V8 is not set +# CONFIG_ARCH_CHIP_STM32F372CB is not set +# CONFIG_ARCH_CHIP_STM32F372RB is not set +# CONFIG_ARCH_CHIP_STM32F372VB is not set +# CONFIG_ARCH_CHIP_STM32F372CC is not set +# CONFIG_ARCH_CHIP_STM32F372RC is not set +# CONFIG_ARCH_CHIP_STM32F372VC is not set +# CONFIG_ARCH_CHIP_STM32F373C8 is not set +# CONFIG_ARCH_CHIP_STM32F373R8 is not set +# CONFIG_ARCH_CHIP_STM32F373V8 is not set +# CONFIG_ARCH_CHIP_STM32F373CB is not set +# CONFIG_ARCH_CHIP_STM32F373RB is not set +# CONFIG_ARCH_CHIP_STM32F373VB is not set +# CONFIG_ARCH_CHIP_STM32F373CC is not set +# CONFIG_ARCH_CHIP_STM32F373RC is not set +# CONFIG_ARCH_CHIP_STM32F373VC is not set +# CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F411RE is not set +# CONFIG_ARCH_CHIP_STM32F411VE is not set +# CONFIG_ARCH_CHIP_STM32F405RG is not set +# CONFIG_ARCH_CHIP_STM32F405VG is not set +# CONFIG_ARCH_CHIP_STM32F405ZG is not set +# CONFIG_ARCH_CHIP_STM32F407VE is not set +# CONFIG_ARCH_CHIP_STM32F407VG is not set +# CONFIG_ARCH_CHIP_STM32F407ZE is not set +# CONFIG_ARCH_CHIP_STM32F407ZG is not set +# CONFIG_ARCH_CHIP_STM32F407IE is not set +# CONFIG_ARCH_CHIP_STM32F407IG is not set +# CONFIG_ARCH_CHIP_STM32F427V is not set +# CONFIG_ARCH_CHIP_STM32F427Z is not set +# CONFIG_ARCH_CHIP_STM32F427I is not set +# CONFIG_ARCH_CHIP_STM32F429V is not set +# CONFIG_ARCH_CHIP_STM32F429Z is not set +# CONFIG_ARCH_CHIP_STM32F429I is not set +# CONFIG_ARCH_CHIP_STM32F429B is not set +# CONFIG_ARCH_CHIP_STM32F429N is not set +# CONFIG_ARCH_CHIP_STM32F446M is not set +# CONFIG_ARCH_CHIP_STM32F446R is not set +# CONFIG_ARCH_CHIP_STM32F446V is not set +# CONFIG_ARCH_CHIP_STM32F446Z is not set +# CONFIG_ARCH_CHIP_STM32F469A is not set +# CONFIG_ARCH_CHIP_STM32F469I is not set +# CONFIG_ARCH_CHIP_STM32F469B is not set +# CONFIG_ARCH_CHIP_STM32F469N is not set +CONFIG_STM32_FLASH_CONFIG_DEFAULT=y +# CONFIG_STM32_FLASH_CONFIG_4 is not set +# CONFIG_STM32_FLASH_CONFIG_6 is not set +# CONFIG_STM32_FLASH_CONFIG_8 is not set +# CONFIG_STM32_FLASH_CONFIG_B is not set +# CONFIG_STM32_FLASH_CONFIG_C is not set +# CONFIG_STM32_FLASH_CONFIG_D is not set +# CONFIG_STM32_FLASH_CONFIG_E is not set +# CONFIG_STM32_FLASH_CONFIG_F is not set +# CONFIG_STM32_FLASH_CONFIG_G is not set +# CONFIG_STM32_FLASH_CONFIG_I is not set +# CONFIG_STM32_STM32L15XX is not set +# CONFIG_STM32_ENERGYLITE is not set +CONFIG_STM32_STM32F10XX=y +# CONFIG_STM32_VALUELINE is not set +# CONFIG_STM32_CONNECTIVITYLINE is not set +CONFIG_STM32_PERFORMANCELINE=y +# CONFIG_STM32_USBACCESSLINE is not set +# CONFIG_STM32_HIGHDENSITY is not set +CONFIG_STM32_MEDIUMDENSITY=y +# CONFIG_STM32_LOWDENSITY is not set +# CONFIG_STM32_STM32F20XX is not set +# CONFIG_STM32_STM32F205 is not set +# CONFIG_STM32_STM32F207 is not set +# CONFIG_STM32_STM32F30XX is not set +# CONFIG_STM32_STM32F302 is not set +# CONFIG_STM32_STM32F303 is not set +# CONFIG_STM32_STM32F33XX is not set +# CONFIG_STM32_STM32F37XX is not set +# CONFIG_STM32_STM32F40XX is not set +# CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F411 is not set +# CONFIG_STM32_STM32F405 is not set +# CONFIG_STM32_STM32F407 is not set +# CONFIG_STM32_STM32F427 is not set +# CONFIG_STM32_STM32F429 is not set +# CONFIG_STM32_STM32F446 is not set +# CONFIG_STM32_STM32F469 is not set +# CONFIG_STM32_DFU is not set + +# +# STM32 Peripheral Support +# +# CONFIG_STM32_HAVE_CCM is not set +CONFIG_STM32_HAVE_USBDEV=y +# CONFIG_STM32_HAVE_OTGFS is not set +# CONFIG_STM32_HAVE_FSMC is not set +# CONFIG_STM32_HAVE_HRTIM1 is not set +# CONFIG_STM32_HAVE_LTDC is not set +CONFIG_STM32_HAVE_USART3=y +CONFIG_STM32_HAVE_UART4=y +CONFIG_STM32_HAVE_UART5=y +# CONFIG_STM32_HAVE_USART6 is not set +# CONFIG_STM32_HAVE_UART7 is not set +# CONFIG_STM32_HAVE_UART8 is not set +CONFIG_STM32_HAVE_TIM1=y +# CONFIG_STM32_HAVE_TIM2 is not set +CONFIG_STM32_HAVE_TIM3=y +CONFIG_STM32_HAVE_TIM4=y +CONFIG_STM32_HAVE_TIM5=y +CONFIG_STM32_HAVE_TIM6=y +CONFIG_STM32_HAVE_TIM7=y +CONFIG_STM32_HAVE_TIM8=y +# CONFIG_STM32_HAVE_TIM9 is not set +# CONFIG_STM32_HAVE_TIM10 is not set +# CONFIG_STM32_HAVE_TIM11 is not set +# CONFIG_STM32_HAVE_TIM12 is not set +# CONFIG_STM32_HAVE_TIM13 is not set +# CONFIG_STM32_HAVE_TIM14 is not set +# CONFIG_STM32_HAVE_TIM15 is not set +# CONFIG_STM32_HAVE_TIM16 is not set +# CONFIG_STM32_HAVE_TIM17 is not set +CONFIG_STM32_HAVE_ADC2=y +CONFIG_STM32_HAVE_ADC3=y +# CONFIG_STM32_HAVE_ADC4 is not set +# CONFIG_STM32_HAVE_ADC1_DMA is not set +# CONFIG_STM32_HAVE_ADC2_DMA is not set +# CONFIG_STM32_HAVE_ADC3_DMA is not set +# CONFIG_STM32_HAVE_ADC4_DMA is not set +# CONFIG_STM32_HAVE_SDADC1 is not set +# CONFIG_STM32_HAVE_SDADC2 is not set +# CONFIG_STM32_HAVE_SDADC3 is not set +# CONFIG_STM32_HAVE_SDADC1_DMA is not set +# CONFIG_STM32_HAVE_SDADC2_DMA is not set +# CONFIG_STM32_HAVE_SDADC3_DMA is not set +CONFIG_STM32_HAVE_CAN1=y +# CONFIG_STM32_HAVE_CAN2 is not set +# CONFIG_STM32_HAVE_COMP1 is not set +# CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set +# CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set +# CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set +# CONFIG_STM32_HAVE_DAC1 is not set +# CONFIG_STM32_HAVE_DAC2 is not set +# CONFIG_STM32_HAVE_RNG is not set +# CONFIG_STM32_HAVE_ETHMAC is not set +CONFIG_STM32_HAVE_I2C2=y +# CONFIG_STM32_HAVE_I2C3 is not set +CONFIG_STM32_HAVE_SPI2=y +CONFIG_STM32_HAVE_SPI3=y +# CONFIG_STM32_HAVE_SPI4 is not set +# CONFIG_STM32_HAVE_SPI5 is not set +# CONFIG_STM32_HAVE_SPI6 is not set +# CONFIG_STM32_HAVE_SAIPLL is not set +# CONFIG_STM32_HAVE_I2SPLL is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set +# CONFIG_STM32_ADC1 is not set +# CONFIG_STM32_ADC2 is not set +# CONFIG_STM32_ADC3 is not set +# CONFIG_STM32_BKP is not set +# CONFIG_STM32_CAN1 is not set +# CONFIG_STM32_CRC is not set +# CONFIG_STM32_DMA1 is not set +# CONFIG_STM32_DMA2 is not set +# CONFIG_STM32_I2C1 is not set +# CONFIG_STM32_I2C2 is not set +# CONFIG_STM32_OPAMP is not set +# CONFIG_STM32_PWR is not set +# CONFIG_STM32_SDIO is not set +CONFIG_STM32_SPI1=y +# CONFIG_STM32_SPI2 is not set +# CONFIG_STM32_SPI3 is not set +# CONFIG_STM32_TIM1 is not set +# CONFIG_STM32_TIM2 is not set +# CONFIG_STM32_TIM3 is not set +# CONFIG_STM32_TIM4 is not set +# CONFIG_STM32_TIM5 is not set +# CONFIG_STM32_TIM6 is not set +# CONFIG_STM32_TIM7 is not set +# CONFIG_STM32_TIM8 is not set +CONFIG_STM32_USART1=y +# CONFIG_STM32_USART2 is not set +# CONFIG_STM32_USART3 is not set +# CONFIG_STM32_UART4 is not set +# CONFIG_STM32_UART5 is not set +# CONFIG_STM32_USB is not set +# CONFIG_STM32_IWDG is not set +# CONFIG_STM32_WWDG is not set +CONFIG_STM32_SPI=y +# CONFIG_STM32_NOEXT_VECTORS is not set + +# +# Alternate Pin Mapping +# +# CONFIG_STM32_SPI1_REMAP is not set +# CONFIG_STM32_USART1_REMAP is not set +# CONFIG_STM32_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set +# CONFIG_STM32_JTAG_DISABLE is not set +CONFIG_STM32_JTAG_FULL_ENABLE=y +# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set +# CONFIG_STM32_JTAG_SW_ENABLE is not set +CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y +# CONFIG_STM32_FORCEPOWER is not set +# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set + +# +# Timer Configuration +# +# CONFIG_STM32_ONESHOT is not set +# CONFIG_STM32_FREERUN is not set +# CONFIG_STM32_TIM1_CAP is not set +# CONFIG_STM32_TIM3_CAP is not set +# CONFIG_STM32_TIM4_CAP is not set +# CONFIG_STM32_TIM5_CAP is not set +# CONFIG_STM32_TIM8_CAP is not set +CONFIG_STM32_USART=y +CONFIG_STM32_SERIALDRIVER=y + +# +# U[S]ART Configuration +# + +# +# U[S]ART Device Configuration +# +CONFIG_STM32_USART1_SERIALDRIVER=y +# CONFIG_STM32_USART1_1WIREDRIVER is not set +# CONFIG_USART1_RS485 is not set + +# +# Serial Driver Configuration +# +# CONFIG_SERIAL_DISABLE_REORDERING is not set +# CONFIG_STM32_FLOWCONTROL_BROKEN is not set +# CONFIG_STM32_USART_BREAKS is not set +# CONFIG_STM32_USART_SINGLEWIRE is not set + +# +# SPI Configuration +# +# CONFIG_STM32_SPI_INTERRUPTS is not set +# CONFIG_STM32_SPI_DMA is not set +CONFIG_STM32_HAVE_RTC_COUNTER=y +# CONFIG_STM32_HAVE_RTC_SUBSECONDS is not set + +# +# USB FS Host Configuration +# + +# +# USB HS Host Configuration +# + +# +# USB Host Debug Configuration +# + +# +# USB Device Configuration +# + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_VECNOTIRQ is not set +# CONFIG_ARCH_DMA is not set +CONFIG_ARCH_HAVE_IRQPRIO=y +# CONFIG_ARCH_L2CACHE is not set +# CONFIG_ARCH_HAVE_COHERENT_DCACHE is not set +# CONFIG_ARCH_HAVE_ADDRENV is not set +# CONFIG_ARCH_NEED_ADDRENV_MAPPING is not set +# CONFIG_ARCH_HAVE_MULTICPU is not set +CONFIG_ARCH_HAVE_VFORK=y +# CONFIG_ARCH_HAVE_MMU is not set +CONFIG_ARCH_HAVE_MPU=y +# CONFIG_ARCH_NAND_HWECC is not set +# CONFIG_ARCH_HAVE_EXTCLK is not set +# CONFIG_ARCH_HAVE_POWEROFF is not set +CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set +# CONFIG_ARCH_USE_MPU is not set +# CONFIG_ARCH_IRQPRIO is not set +CONFIG_ARCH_STACKDUMP=y +# CONFIG_ENDIAN_BIG is not set +# CONFIG_ARCH_IDLE_CUSTOM is not set +# CONFIG_ARCH_HAVE_RAMFUNCS is not set +CONFIG_ARCH_HAVE_RAMVECTORS=y +# CONFIG_ARCH_RAMVECTORS is not set +# CONFIG_ARCH_MINIMAL_VECTORTABLE is not set + +# +# Board Settings +# +CONFIG_BOARD_LOOPSPERMSEC=5483 +# CONFIG_ARCH_CALIBRATION is not set + +# +# Interrupt options +# +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y +CONFIG_ARCH_INTERRUPTSTACK=0 +CONFIG_ARCH_HAVE_HIPRI_INTERRUPT=y +# CONFIG_ARCH_HIPRI_INTERRUPT is not set + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Boot Memory Configuration +# +CONFIG_RAM_START=0x20000000 +CONFIG_RAM_SIZE=20480 +# CONFIG_ARCH_HAVE_SDRAM is not set + +# +# Board Selection +# +# CONFIG_ARCH_BOARD_STM32_TINY is not set +CONFIG_ARCH_BOARD_STM32F103_MINIMUM=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="stm32f103-minimum" + +# +# Common Board Options +# +CONFIG_ARCH_HAVE_LEDS=y +CONFIG_ARCH_LEDS=y +CONFIG_ARCH_HAVE_BUTTONS=y +# CONFIG_ARCH_BUTTONS is not set +CONFIG_ARCH_HAVE_IRQBUTTONS=y + +# +# Board-Specific Options +# +# CONFIG_BOARD_CRASHDUMP is not set +CONFIG_LIB_BOARDCTL=y +# CONFIG_BOARDCTL_RESET is not set +# CONFIG_BOARDCTL_UNIQUEID is not set +# CONFIG_BOARDCTL_TSCTEST is not set +# CONFIG_BOARDCTL_GRAPHICS is not set +# CONFIG_BOARDCTL_IOCTL is not set + +# +# RTOS Features +# +# CONFIG_DISABLE_OS_API is not set + +# +# Clocks and Timers +# +CONFIG_ARCH_HAVE_TICKLESS=y +# CONFIG_SCHED_TICKLESS is not set +CONFIG_USEC_PER_TICK=10000 +# CONFIG_SYSTEM_TIME64 is not set +# CONFIG_CLOCK_MONOTONIC is not set +CONFIG_ARCH_HAVE_TIMEKEEPING=y +# CONFIG_JULIAN_TIME is not set +CONFIG_START_YEAR=2011 +CONFIG_START_MONTH=7 +CONFIG_START_DAY=5 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=4 +CONFIG_WDOG_INTRESERVE=0 +CONFIG_PREALLOC_TIMERS=4 + +# +# Tasks and Scheduling +# +# CONFIG_SPINLOCK is not set +# CONFIG_INIT_NONE is not set +CONFIG_INIT_ENTRYPOINT=y +# CONFIG_INIT_FILEPATH is not set +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_RR_INTERVAL=200 +# CONFIG_SCHED_SPORADIC is not set +CONFIG_TASK_NAME_SIZE=0 +CONFIG_MAX_TASKS=16 +# CONFIG_SCHED_HAVE_PARENT is not set +CONFIG_SCHED_WAITPID=y + +# +# Pthread Options +# +# CONFIG_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set +CONFIG_NPTHREAD_KEYS=4 +# CONFIG_PTHREAD_CLEANUP is not set +# CONFIG_CANCELLATION_POINTS is not set + +# +# Performance Monitoring +# +# CONFIG_SCHED_CPULOAD is not set +# CONFIG_SCHED_INSTRUMENTATION is not set + +# +# Files and I/O +# +CONFIG_DEV_CONSOLE=y +# CONFIG_FDCLONE_DISABLE is not set +# CONFIG_FDCLONE_STDIO is not set +CONFIG_SDCLONE_DISABLE=y +CONFIG_NFILE_DESCRIPTORS=8 +CONFIG_NFILE_STREAMS=8 +CONFIG_NAME_MAX=32 +# CONFIG_PRIORITY_INHERITANCE is not set + +# +# RTOS hooks +# +# CONFIG_BOARD_INITIALIZE is not set +# CONFIG_SCHED_STARTHOOK is not set +# CONFIG_SCHED_ATEXIT is not set +# CONFIG_SCHED_ONEXIT is not set +# CONFIG_SIG_EVTHREAD is not set + +# +# Signal Numbers +# +CONFIG_SIG_SIGUSR1=1 +CONFIG_SIG_SIGUSR2=2 +CONFIG_SIG_SIGALARM=3 +CONFIG_SIG_SIGCONDTIMEDOUT=16 +CONFIG_SIG_SIGWORK=17 + +# +# POSIX Message Queue Options +# +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_MQ_MAXMSGSIZE=32 +# CONFIG_MODULE is not set + +# +# Work queue support +# +CONFIG_SCHED_WORKQUEUE=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=192 +CONFIG_SCHED_HPWORKPERIOD=50000 +CONFIG_SCHED_HPWORKSTACKSIZE=2048 +# CONFIG_SCHED_LPWORK is not set + +# +# Stack and heap information +# +CONFIG_IDLETHREAD_STACKSIZE=1024 +CONFIG_USERMAIN_STACKSIZE=2048 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=2048 +# CONFIG_LIB_SYSCALL is not set + +# +# Device Drivers +# +CONFIG_DISABLE_POLL=y +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_DEV_URANDOM is not set +# CONFIG_DEV_LOOP is not set + +# +# Buffering +# +# CONFIG_DRVR_WRITEBUFFER is not set +# CONFIG_DRVR_READAHEAD is not set +# CONFIG_RAMDISK is not set +CONFIG_CAN=y +# CONFIG_ARCH_HAVE_CAN_ERRORS is not set +# CONFIG_CAN_FD is not set +CONFIG_CAN_FIFOSIZE=8 +CONFIG_CAN_NPENDINGRTR=4 +# CONFIG_CAN_TXREADY is not set + +# +# CAN Bus Controllers: +# +CONFIG_CAN_MCP2515=y +CONFIG_MCP2515_BITRATE=500000 +CONFIG_MCP2515_PROPSEG=1 +CONFIG_MCP2515_PHASESEG1=3 +CONFIG_MCP2515_PHASESEG2=3 +CONFIG_MCP2515_SJW=1 +# CONFIG_ARCH_HAVE_PWM_PULSECOUNT is not set +# CONFIG_ARCH_HAVE_PWM_MULTICHAN is not set +# CONFIG_PWM is not set +CONFIG_ARCH_HAVE_I2CRESET=y +# CONFIG_I2C is not set +# CONFIG_ARCH_HAVE_SPI_CRCGENERATION is not set +# CONFIG_ARCH_HAVE_SPI_CS_CONTROL is not set +CONFIG_ARCH_HAVE_SPI_BITORDER=y +CONFIG_SPI=y +# CONFIG_SPI_SLAVE is not set +CONFIG_SPI_EXCHANGE=y +# CONFIG_SPI_CMDDATA is not set +# CONFIG_SPI_CALLBACK is not set +# CONFIG_SPI_HWFEATURES is not set +# CONFIG_SPI_BITORDER is not set +# CONFIG_SPI_CS_DELAY_CONTROL is not set +# CONFIG_SPI_DRIVER is not set +# CONFIG_SPI_BITBANG is not set +# CONFIG_I2S is not set + +# +# Timer Driver Support +# +# CONFIG_TIMER is not set +# CONFIG_ONESHOT is not set +# CONFIG_RTC is not set +# CONFIG_WATCHDOG is not set +# CONFIG_ANALOG is not set +# CONFIG_AUDIO_DEVICES is not set +# CONFIG_VIDEO_DEVICES is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set + +# +# IO Expander/GPIO Support +# +# CONFIG_IOEXPANDER is not set +# CONFIG_DEV_GPIO is not set + +# +# LCD Driver Support +# +# CONFIG_LCD is not set +# CONFIG_SLCD is not set + +# +# LED Support +# +# CONFIG_USERLED is not set +# CONFIG_RGBLED is not set +# CONFIG_PCA9635PW is not set +# CONFIG_NCP5623C is not set +# CONFIG_MMCSD is not set +# CONFIG_MODEM is not set +# CONFIG_MTD is not set +# CONFIG_EEPROM is not set +# CONFIG_PIPES is not set +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +CONFIG_SERIAL=y +# CONFIG_DEV_LOWCONSOLE is not set +# CONFIG_SERIAL_REMOVABLE is not set +CONFIG_SERIAL_CONSOLE=y +# CONFIG_16550_UART is not set +# CONFIG_UART_SERIALDRIVER is not set +# CONFIG_UART0_SERIALDRIVER is not set +# CONFIG_UART1_SERIALDRIVER is not set +# CONFIG_UART2_SERIALDRIVER is not set +# CONFIG_UART3_SERIALDRIVER is not set +# CONFIG_UART4_SERIALDRIVER is not set +# CONFIG_UART5_SERIALDRIVER is not set +# CONFIG_UART6_SERIALDRIVER is not set +# CONFIG_UART7_SERIALDRIVER is not set +# CONFIG_UART8_SERIALDRIVER is not set +# CONFIG_SCI0_SERIALDRIVER is not set +# CONFIG_SCI1_SERIALDRIVER is not set +# CONFIG_USART0_SERIALDRIVER is not set +CONFIG_USART1_SERIALDRIVER=y +# CONFIG_USART2_SERIALDRIVER is not set +# CONFIG_USART3_SERIALDRIVER is not set +# CONFIG_USART4_SERIALDRIVER is not set +# CONFIG_USART5_SERIALDRIVER is not set +# CONFIG_USART6_SERIALDRIVER is not set +# CONFIG_USART7_SERIALDRIVER is not set +# CONFIG_USART8_SERIALDRIVER is not set +# CONFIG_OTHER_UART_SERIALDRIVER is not set +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +# CONFIG_SERIAL_IFLOWCONTROL is not set +# CONFIG_SERIAL_OFLOWCONTROL is not set +# CONFIG_SERIAL_DMA is not set +# CONFIG_SERIAL_TIOCSERGSTRUCT is not set +CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y +CONFIG_USART1_SERIAL_CONSOLE=y +# CONFIG_OTHER_SERIAL_CONSOLE is not set +# CONFIG_NO_SERIAL_CONSOLE is not set + +# +# USART1 Configuration +# +CONFIG_USART1_RXBUFSIZE=256 +CONFIG_USART1_TXBUFSIZE=256 +CONFIG_USART1_BAUD=115200 +CONFIG_USART1_BITS=8 +CONFIG_USART1_PARITY=0 +CONFIG_USART1_2STOP=0 +# CONFIG_USART1_IFLOWCONTROL is not set +# CONFIG_USART1_OFLOWCONTROL is not set +# CONFIG_USART1_DMA is not set +# CONFIG_PSEUDOTERM is not set +# CONFIG_USBDEV is not set +# CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set +# CONFIG_HAVE_USBTRACE is not set +# CONFIG_DRIVERS_WIRELESS is not set +# CONFIG_DRIVERS_CONTACTLESS is not set + +# +# System Logging +# +# CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y +# CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set +# CONFIG_SYSLOG_INTBUFFER is not set +# CONFIG_SYSLOG_TIMESTAMP is not set +CONFIG_SYSLOG_SERIAL_CONSOLE=y +# CONFIG_SYSLOG_CHAR is not set +CONFIG_SYSLOG_CONSOLE=y +# CONFIG_SYSLOG_NONE is not set +# CONFIG_SYSLOG_FILE is not set +# CONFIG_SYSLOG_CHARDEV is not set + +# +# Networking Support +# +# CONFIG_ARCH_HAVE_NET is not set +# CONFIG_ARCH_HAVE_PHY is not set +# CONFIG_NET is not set + +# +# Crypto API +# +# CONFIG_CRYPTO is not set + +# +# File Systems +# + +# +# File system configuration +# +# CONFIG_DISABLE_MOUNTPOINT is not set +# CONFIG_FS_AUTOMOUNTER is not set +CONFIG_DISABLE_PSEUDOFS_OPERATIONS=y +# CONFIG_FS_READABLE is not set +# CONFIG_FS_WRITABLE is not set +# CONFIG_FS_NAMED_SEMAPHORES is not set +CONFIG_FS_MQUEUE_MPATH="/var/mqueue" +# CONFIG_FS_RAMMAP is not set +# CONFIG_FS_FAT is not set +# CONFIG_FS_NXFFS is not set +# CONFIG_FS_ROMFS is not set +# CONFIG_FS_TMPFS is not set +# CONFIG_FS_SMARTFS is not set +# CONFIG_FS_BINFS is not set +# CONFIG_FS_PROCFS is not set +# CONFIG_FS_UNIONFS is not set + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=1 +# CONFIG_ARCH_HAVE_HEAP2 is not set +# CONFIG_GRAN is not set + +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + +# +# Audio Support +# +# CONFIG_AUDIO is not set + +# +# Wireless Support +# +# CONFIG_WIRELESS is not set + +# +# Binary Loader +# +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_BINFMT_EXEPATH is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +CONFIG_BUILTIN=y +# CONFIG_PIC is not set +CONFIG_SYMTAB_ORDEREDBYNAME=y + +# +# Library Routines +# + +# +# Standard C Library Options +# + +# +# Standard C I/O +# +# CONFIG_STDIO_DISABLE_BUFFERING is not set +CONFIG_STDIO_BUFFER_SIZE=64 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +# CONFIG_NOPRINTF_FIELDWIDTH is not set +# CONFIG_LIBC_FLOATINGPOINT is not set +# CONFIG_LIBC_LONG_LONG is not set +# CONFIG_LIBC_SCANSET is not set +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_MEMCPY_VIK is not set +# CONFIG_LIBM is not set + +# +# Architecture-Specific Support +# +CONFIG_ARCH_LOWPUTC=y +# CONFIG_ARCH_ROMGETC is not set +# CONFIG_LIBC_ARCH_MEMCPY is not set +# CONFIG_LIBC_ARCH_MEMCMP is not set +# CONFIG_LIBC_ARCH_MEMMOVE is not set +# CONFIG_LIBC_ARCH_MEMSET is not set +# CONFIG_LIBC_ARCH_STRCHR is not set +# CONFIG_LIBC_ARCH_STRCMP is not set +# CONFIG_LIBC_ARCH_STRCPY is not set +# CONFIG_LIBC_ARCH_STRNCPY is not set +# CONFIG_LIBC_ARCH_STRLEN is not set +# CONFIG_LIBC_ARCH_STRNLEN is not set +# CONFIG_LIBC_ARCH_ELF is not set +# CONFIG_ARMV7M_MEMCPY is not set + +# +# stdlib Options +# +CONFIG_LIB_RAND_ORDER=1 +CONFIG_LIB_HOMEDIR="/" + +# +# Program Execution Options +# +# CONFIG_LIBC_EXECFUNCS is not set +CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024 +CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=2048 + +# +# errno Decode Support +# +# CONFIG_LIBC_STRERROR is not set +# CONFIG_LIBC_PERROR_STDOUT is not set + +# +# memcpy/memset Options +# +# CONFIG_MEMSET_OPTSPEED is not set +# CONFIG_LIBC_DLLFCN is not set +# CONFIG_LIBC_MODLIB is not set +# CONFIG_LIBC_WCHAR is not set +# CONFIG_LIBC_LOCALE is not set + +# +# Time/Time Zone Support +# +# CONFIG_LIBC_LOCALTIME is not set +# CONFIG_TIME_EXTENDED is not set +CONFIG_ARCH_HAVE_TLS=y + +# +# Thread Local Storage (TLS) +# +# CONFIG_TLS is not set + +# +# Network-Related Options +# +# CONFIG_LIBC_IPv4_ADDRCONV is not set +# CONFIG_LIBC_IPv6_ADDRCONV is not set +# CONFIG_LIBC_NETDB is not set + +# +# NETDB Support +# +# CONFIG_LIBC_IOCTL_VARIADIC is not set +CONFIG_LIB_SENDFILE_BUFSIZE=512 + +# +# Non-standard Library Support +# +# CONFIG_LIB_CRC64_FAST is not set +# CONFIG_LIB_KBDCODEC is not set +# CONFIG_LIB_SLCDCODEC is not set +# CONFIG_LIB_HEX2BIN is not set + +# +# Basic CXX Support +# +# CONFIG_C99_BOOL8 is not set +# CONFIG_HAVE_CXX is not set + +# +# Application Configuration +# + +# +# Built-In Applications +# +CONFIG_BUILTIN_PROXY_STACKSIZE=1024 + +# +# CAN Utilities +# +CONFIG_CANUTILS_CANLIB=y + +# +# Examples +# +# CONFIG_EXAMPLES_BUTTONS is not set +CONFIG_EXAMPLES_CAN=y +CONFIG_EXAMPLES_CAN_DEVPATH="/dev/can0" +CONFIG_EXAMPLES_CAN_NMSGS=32 +CONFIG_EXAMPLES_CAN_READ=y +# CONFIG_EXAMPLES_CAN_WRITE is not set +# CONFIG_EXAMPLES_CAN_READWRITE is not set +# CONFIG_EXAMPLES_CCTYPE is not set +# CONFIG_EXAMPLES_CHAT is not set +# CONFIG_EXAMPLES_CONFIGDATA is not set +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HIDKBD is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_JSON is not set +# CONFIG_EXAMPLES_KEYPADTEST is not set +# CONFIG_EXAMPLES_MEDIA is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MODBUS is not set +# CONFIG_EXAMPLES_MOUNT is not set +CONFIG_EXAMPLES_NSH=y +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXLINES is not set +# CONFIG_EXAMPLES_NXTERM is not set +# CONFIG_EXAMPLES_NXTEXT is not set +# CONFIG_EXAMPLES_OSTEST is not set +# CONFIG_EXAMPLES_PCA9635 is not set +# CONFIG_EXAMPLES_POSIXSPAWN is not set +# CONFIG_EXAMPLES_PPPD is not set +# CONFIG_EXAMPLES_RFID_READUID is not set +# CONFIG_EXAMPLES_RGBLED is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERIALBLASTER is not set +# CONFIG_EXAMPLES_SERIALRX is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_SLCD is not set +# CONFIG_EXAMPLES_SMART is not set +# CONFIG_EXAMPLES_SMART_TEST is not set +# CONFIG_EXAMPLES_SMP is not set +# CONFIG_EXAMPLES_STAT is not set +# CONFIG_EXAMPLES_TCPECHO is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_USBSERIAL is not set +# CONFIG_EXAMPLES_WATCHDOG is not set +# CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set + +# +# File System Utilities +# +# CONFIG_FSUTILS_INIFILE is not set + +# +# GPS Utilities +# +# CONFIG_GPSUTILS_MINMEA_LIB is not set + +# +# Graphics Support +# +# CONFIG_TIFF is not set +# CONFIG_GRAPHICS_TRAVELER is not set + +# +# Interpreters +# +# CONFIG_INTERPRETERS_FICL is not set +# CONFIG_INTERPRETERS_MICROPYTHON is not set +# CONFIG_INTERPRETERS_MINIBASIC is not set +# CONFIG_INTERPRETERS_PCODE is not set + +# +# FreeModBus +# +# CONFIG_MODBUS is not set + +# +# Network Utilities +# +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_ESP8266 is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_JSON is not set +# CONFIG_NETUTILS_SMTP is not set + +# +# NSH Library +# +CONFIG_NSH_LIBRARY=y +# CONFIG_NSH_MOTD is not set + +# +# Command Line Configuration +# +CONFIG_NSH_READLINE=y +# CONFIG_NSH_CLE is not set +CONFIG_NSH_LINELEN=80 +CONFIG_NSH_DISABLE_SEMICOLON=y +# CONFIG_NSH_CMDPARMS is not set +CONFIG_NSH_MAXARGUMENTS=6 +# CONFIG_NSH_ARGCAT is not set +CONFIG_NSH_NESTDEPTH=3 +CONFIG_NSH_DISABLEBG=y +CONFIG_NSH_BUILTIN_APPS=y + +# +# Disable Individual commands +# +CONFIG_NSH_DISABLE_ADDROUTE=y +CONFIG_NSH_DISABLE_BASENAME=y +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +CONFIG_NSH_DISABLE_CMP=y +CONFIG_NSH_DISABLE_DATE=y +# CONFIG_NSH_DISABLE_DD is not set +CONFIG_NSH_DISABLE_DF=y +CONFIG_NSH_DISABLE_DELROUTE=y +CONFIG_NSH_DISABLE_DIRNAME=y +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_HEXDUMP is not set +CONFIG_NSH_DISABLE_IFCONFIG=y +CONFIG_NSH_DISABLE_IFUPDOWN=y +# CONFIG_NSH_DISABLE_KILL is not set +CONFIG_NSH_DISABLE_LOSETUP=y +CONFIG_NSH_DISABLE_LOSMART=y +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MB is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKRD is not set +# CONFIG_NSH_DISABLE_MH is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_MW is not set +CONFIG_NSH_DISABLE_PRINTF=y +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PUT is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SH is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +CONFIG_NSH_DISABLE_TIME=y +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +CONFIG_NSH_DISABLE_UNAME=y +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +# CONFIG_NSH_DISABLE_WGET is not set +# CONFIG_NSH_DISABLE_XD is not set +CONFIG_NSH_MMCSDMINOR=0 + +# +# Configure Command Options +# +# CONFIG_NSH_CMDOPT_DD_STATS is not set +CONFIG_NSH_CODECS_BUFSIZE=128 +# CONFIG_NSH_CMDOPT_HEXDUMP is not set +CONFIG_NSH_FILEIOSIZE=1024 + +# +# Scripting Support +# +# CONFIG_NSH_DISABLESCRIPT is not set +CONFIG_NSH_DISABLE_ITEF=y +CONFIG_NSH_DISABLE_LOOPS=y + +# +# Console Configuration +# +CONFIG_NSH_CONSOLE=y +# CONFIG_NSH_ALTCONDEV is not set +CONFIG_NSH_ARCHINIT=y +# CONFIG_NSH_LOGIN is not set +# CONFIG_NSH_CONSOLE_LOGIN is not set + +# +# NxWidgets/NxWM +# + +# +# Platform-specific Support +# +# CONFIG_PLATFORM_CONFIGDATA is not set + +# +# System Libraries and NSH Add-Ons +# +# CONFIG_SYSTEM_CLE is not set +# CONFIG_SYSTEM_CUTERM is not set +# CONFIG_SYSTEM_FREE is not set +# CONFIG_SYSTEM_HEX2BIN is not set +# CONFIG_SYSTEM_HEXED is not set +# CONFIG_SYSTEM_INSTALL is not set +# CONFIG_SYSTEM_RAMTEST is not set +CONFIG_READLINE_HAVE_EXTMATCH=y +CONFIG_SYSTEM_READLINE=y +CONFIG_READLINE_ECHO=y +# CONFIG_READLINE_TABCOMPLETION is not set +# CONFIG_READLINE_CMD_HISTORY is not set +# CONFIG_SYSTEM_SUDOKU is not set +# CONFIG_SYSTEM_SYSTEM is not set +# CONFIG_SYSTEM_TEE is not set +# CONFIG_SYSTEM_UBLOXMODEM is not set +# CONFIG_SYSTEM_VI is not set +# CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/stm32f103-minimum/src/Makefile b/configs/stm32f103-minimum/src/Makefile index 8402e553ea..760ac752c7 100644 --- a/configs/stm32f103-minimum/src/Makefile +++ b/configs/stm32f103-minimum/src/Makefile @@ -69,6 +69,10 @@ ifeq ($(CONFIG_AUDIO_TONE),y) CSRCS += stm32_tone.c endif +ifeq ($(CONFIG_CAN_MCP2515),y) +CSRCS += stm32_mcp2515.c +endif + ifeq ($(CONFIG_CL_MFRC522),y) CSRCS += stm32_mfrc522.c endif diff --git a/configs/stm32f103-minimum/src/stm32_bringup.c b/configs/stm32f103-minimum/src/stm32_bringup.c index 2e76db5b8c..14745c88d1 100644 --- a/configs/stm32f103-minimum/src/stm32_bringup.c +++ b/configs/stm32f103-minimum/src/stm32_bringup.c @@ -151,6 +151,13 @@ int stm32_bringup(void) } #endif +#ifdef CONFIG_CAN_MCP2515 + ret = stm32_mcp2515initialize("/dev/can0"); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: stm32_mcp2515initialize() failed: %d\n", ret); + } +#endif #ifdef CONFIG_CL_MFRC522 ret = stm32_mfrc522initialize("/dev/rfid0"); diff --git a/configs/stm32f103-minimum/src/stm32_mcp2515.c b/configs/stm32f103-minimum/src/stm32_mcp2515.c new file mode 100644 index 0000000000..00d73bd35e --- /dev/null +++ b/configs/stm32f103-minimum/src/stm32_mcp2515.c @@ -0,0 +1,240 @@ +/************************************************************************************ + * configs/stm32f4discovery/src/stm32_mcp2515.c + * + * Copyright (C) 2015 Alan Carvalho de Assis. All rights reserved. + * Author: Alan Carvalho de Assis + * + * 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 "stm32.h" +#include "stm32_spi.h" +#include "stm32f103_minimum.h" + +#if defined(CONFIG_SPI) && defined(CONFIG_STM32_SPI1) && defined(CONFIG_CAN_MCP2515) + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +#define MCP2515_SPI_PORTNO 1 /* On SPI1 */ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct stm32_mcp2515config_s +{ + /* Configuration structure as seen by the MCP2515 driver */ + + struct mcp2515_config_s config; + + /* Additional private definitions only known to this driver */ + + MCP2515_HANDLE handle; /* The MCP2515 driver handle */ + mcp2515_handler_t handler; /* The MCP2515 interrupt handler */ + FAR void *arg; /* Argument to pass to the interrupt handler */ +}; + +/**************************************************************************** + * Static Function Prototypes + ****************************************************************************/ + +/* IRQ/GPIO access callbacks. These operations all hidden behind callbacks + * to isolate the MCP2515 driver from differences in GPIO interrupt handling + * by varying boards and MCUs. + * + * attach - Attach the MCP2515 interrupt handler to the GPIO interrupt + */ + +static int mcp2515_attach(FAR struct mcp2515_config_s *state, + mcp2515_handler_t handler, FAR void *arg); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* A reference to a structure of this type must be passed to the MCP2515 + * driver. This structure provides information about the configuration + * of the MCP2515 and provides some board-specific hooks. + * + * Memory for this structure is provided by the caller. It is not copied + * by the driver and is presumed to persist while the driver is active. The + * memory must be writable because, under certain circumstances, the driver + * may modify frequency or X plate resistance values. + */ + +static struct stm32_mcp2515config_s g_mcp2515config = +{ + .config = + { + .devid = 0, + .nfilters = 6, + .ntxbuffers = 3, + .attach = mcp2515_attach, + }, +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/* This is the MCP2515 Interupt handler */ + +int mcp2515_interrupt(int irq, FAR void *context) +{ + /* Verify that we have a handler attached */ + + if (g_mcp2515config.handler) + { + /* Yes.. forward with interrupt along with its argument */ + + g_mcp2515config.handler(&g_mcp2515config.config, g_mcp2515config.arg); + } + + return OK; +} + +static int mcp2515_attach(FAR struct mcp2515_config_s *state, + mcp2515_handler_t handler, FAR void *arg) +{ + FAR struct stm32_mcp2515config_s *priv = + (FAR struct stm32_mcp2515config_s *) state; + irqstate_t flags; + + caninfo("Saving handle %p\n", handler); + + flags = enter_critical_section(); + + priv->handler = handler; + priv->arg = arg; + + /* Configure the interrupt for falling edge*/ + + (void)stm32_gpiosetevent(GPIO_MCP2515_IRQ, false, true, false, mcp2515_interrupt, NULL); + + leave_critical_section(flags); + + return OK; +} + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_mcp2515initialize + * + * Description: + * Initialize and register the MCP2515 RFID driver. + * + * Input parameters: + * devpath - The full path to the driver to register. E.g., "/dev/rfid0" + * + * Returned Value: + * Zero (OK) on success; a negated errno value on failure. + * + ************************************************************************************/ + +int stm32_mcp2515initialize(FAR const char *devpath) +{ + FAR struct spi_dev_s *spi; + FAR struct can_dev_s *can; + FAR struct mcp2515_can_s *mcp2515; + int ret; + + /* Check if we are already initialized */ + + if (!g_mcp2515config.handle) + { + sninfo("Initializing\n"); + + /* Configure the MCP2515 interrupt pin as an input */ + + (void)stm32_configgpio(GPIO_MCP2515_IRQ); + + spi = stm32_spibus_initialize(MCP2515_SPI_PORTNO); + + if (!spi) + { + return -ENODEV; + } + + /* Save the SPI instance in the mcp2515_config_s structure */ + + g_mcp2515config.config.spi = spi; + + /* Instantiate the MCP2515 CAN Driver */ + + mcp2515 = mcp2515_instantiate(&g_mcp2515config.config); + if (mcp2515 == NULL) + { + canerr("ERROR: Failed to get MCP2515 Driver Loaded\n"); + return -ENODEV; + } + + /* Save the opaque structure */ + + g_mcp2515config.handle = (MCP2515_HANDLE) mcp2515; + + /* Initialize the CAN Device with the MCP2515 operations */ + + can = mcp2515_initialize(mcp2515); + if (can == NULL) + { + canerr("ERROR: Failed to get CAN interface\n"); + return -ENODEV; + } + + /* Register the CAN driver at "/dev/can0" */ + + ret = can_register(devpath, can); + if (ret < 0) + { + canerr("ERROR: can_register failed: %d\n", ret); + return ret; + } + } + + return OK; +} + +#endif /* CONFIG_SPI && CONFIG_CAN_MCP2515 */ diff --git a/configs/stm32f103-minimum/src/stm32_spi.c b/configs/stm32f103-minimum/src/stm32_spi.c index 0ba7df49d3..ceab4e14d6 100644 --- a/configs/stm32f103-minimum/src/stm32_spi.c +++ b/configs/stm32f103-minimum/src/stm32_spi.c @@ -74,6 +74,10 @@ void stm32_spidev_initialize(void) * architecture. */ +#ifdef CONFIG_CAN_MCP2515 + (void)stm32_configgpio(GPIO_MCP2515_CS); /* MCP2515 chip select */ +#endif + #ifdef CONFIG_CL_MFRC522 (void)stm32_configgpio(GPIO_CS_MFRC522); /* MFRC522 chip select */ #endif @@ -120,6 +124,13 @@ void stm32_spidev_initialize(void) void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { +#if defined(CONFIG_CAN_MCP2515) + if (devid == SPIDEV_CANBUS(0)) + { + stm32_gpiowrite(GPIO_MCP2515_CS, !selected); + } +#endif + #if defined(CONFIG_CL_MFRC522) if (devid == SPIDEV_WIRELESS(0)) { diff --git a/configs/stm32f103-minimum/src/stm32f103_minimum.h b/configs/stm32f103-minimum/src/stm32f103_minimum.h index 5495596a0b..adabdbc3b0 100644 --- a/configs/stm32f103-minimum/src/stm32f103_minimum.h +++ b/configs/stm32f103-minimum/src/stm32f103_minimum.h @@ -86,6 +86,9 @@ #define STM32_LCD_CS (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\ GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4) +#define GPIO_MCP2515_CS (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4) + #define GPIO_NRF24L01_CS (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\ GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4) @@ -114,6 +117,10 @@ #define GPIO_NRF24L01_IRQ (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_PORTA|GPIO_PIN0) +/* MCP2515 IRQ line: PB.0 */ + +#define GPIO_MCP2515_IRQ (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_PORTB|GPIO_PIN0) + /* USB Soft Connect Pullup: PC.13 */ #define GPIO_USB_PULLUP (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\ -- GitLab From 001919ffe947ef39c3f28b725f2b4bd34351f0de Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Tue, 23 May 2017 14:33:52 -0300 Subject: [PATCH 861/990] Add CANBUS SPIDEV definition --- include/nuttx/spi/spi.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/include/nuttx/spi/spi.h b/include/nuttx/spi/spi.h index ddeb222635..6a03a2a9d8 100644 --- a/include/nuttx/spi/spi.h +++ b/include/nuttx/spi/spi.h @@ -457,6 +457,7 @@ #define SPIDEV_IEEE802154(n) SPIDEV_ID(SPIDEVTYPE_IEEE802154, (n)) #define SPIDEV_CONTACTLESS(n) SPIDEV_ID(SPIDEVTYPE_CONTACTLESS, (n)) #define SPIDEV_USER(n) SPIDEV_ID(SPIDEVTYPE_USER, (n)) +#define SPIDEV_CANBUS(n) SPIDEV_ID(SPIDEVTYPE_CANBUS, (n)) /**************************************************************************** * Public Types @@ -491,7 +492,8 @@ enum spi_devtype_e SPIDEVTYPE_TEMPERATURE, /* Select SPI Temperature sensor device */ SPIDEVTYPE_IEEE802154, /* Select SPI IEEE 802.15.4 wireless device */ SPIDEVTYPE_CONTACTLESS, /* Select SPI Contactless device */ - SPIDEVTYPE_USER /* Board-specific values start here */ + SPIDEVTYPE_USER, /* Board-specific values start here */ + SPIDEVTYPE_CANBUS /* Select SPI CAN Bus controller over SPI */ }; /* Certain SPI devices may required different clocking modes */ -- GitLab From 38ae28e97839a1369f9c8969fc414a2885356ebc Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 23 May 2017 12:22:49 -0600 Subject: [PATCH 862/990] MCP2515: Changes from review of last PR --- TODO | 3 + configs/stm32f103-minimum/mcp2515/Make.defs | 4 +- configs/stm32f103-minimum/mcp2515/defconfig | 51 +++------------- configs/stm32f103-minimum/src/stm32_bringup.c | 2 + configs/stm32f103-minimum/src/stm32_mcp2515.c | 33 ++++++---- drivers/can/Kconfig | 61 +++++++++---------- drivers/can/mcp2515.c | 37 ++++++----- drivers/can/mcp2515.h | 43 +++++++++++++ include/nuttx/can/mcp2515.h | 21 ++++--- include/nuttx/spi/spi.h | 7 ++- 10 files changed, 143 insertions(+), 119 deletions(-) diff --git a/TODO b/TODO index 503f2df46e..fe969060bf 100644 --- a/TODO +++ b/TODO @@ -1889,6 +1889,9 @@ o Build system the make during the archival, the timestamp on .archive is not updated. + The .archive file would have to be removed on 'make clean' and would + also need to appear in .gitignore files. + o Other drivers (drivers/) ^^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/configs/stm32f103-minimum/mcp2515/Make.defs b/configs/stm32f103-minimum/mcp2515/Make.defs index 8d3d478305..f47ecd8b08 100644 --- a/configs/stm32f103-minimum/mcp2515/Make.defs +++ b/configs/stm32f103-minimum/mcp2515/Make.defs @@ -1,7 +1,7 @@ ############################################################################ -# configs/stm32f103-minimum/nsh/Make.defs +# configs/stm32f103-minimum/mcp2515/Make.defs # -# Copyright (C) 2016 Gregory Nutt. All rights reserved. +# Copyright (C) 2017 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without diff --git a/configs/stm32f103-minimum/mcp2515/defconfig b/configs/stm32f103-minimum/mcp2515/defconfig index eaada4d3dc..982cc5767e 100644 --- a/configs/stm32f103-minimum/mcp2515/defconfig +++ b/configs/stm32f103-minimum/mcp2515/defconfig @@ -44,42 +44,7 @@ CONFIG_RAW_BINARY=y # Debug Options # CONFIG_DEBUG_ALERT=y -CONFIG_DEBUG_FEATURES=y - -# -# Debug SYSLOG Output Controls -# -CONFIG_DEBUG_ERROR=y -CONFIG_DEBUG_WARN=y -CONFIG_DEBUG_INFO=y -# CONFIG_DEBUG_ASSERTIONS is not set - -# -# Subsystem Debug Options -# -# CONFIG_DEBUG_BINFMT is not set -# CONFIG_DEBUG_FS is not set -# CONFIG_DEBUG_GRAPHICS is not set -# CONFIG_DEBUG_LIB is not set -# CONFIG_DEBUG_MM is not set -# CONFIG_DEBUG_SCHED is not set - -# -# OS Function Debug Options -# -# CONFIG_DEBUG_IRQ is not set - -# -# Driver Debug Options -# -# CONFIG_DEBUG_LEDS is not set -CONFIG_DEBUG_CAN=y -CONFIG_DEBUG_CAN_ERROR=y -CONFIG_DEBUG_CAN_WARN=y -CONFIG_DEBUG_CAN_INFO=y -# CONFIG_DEBUG_GPIO is not set -# CONFIG_DEBUG_SPI is not set -# CONFIG_DEBUG_TIMER is not set +# CONFIG_DEBUG_FEATURES is not set CONFIG_ARCH_HAVE_STACKCHECK=y # CONFIG_STACK_COLORATION is not set CONFIG_ARCH_HAVE_HEAPCHECK=y @@ -160,8 +125,6 @@ CONFIG_ARCH_CORTEXM3=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" -# CONFIG_ARM_TOOLCHAIN_IAR is not set -CONFIG_ARM_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set @@ -171,7 +134,6 @@ CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARCH_HAVE_TRUSTZONE is not set CONFIG_ARM_HAVE_MPU_UNIFIED=y # CONFIG_ARM_MPU is not set -# CONFIG_DEBUG_HARDFAULT is not set # # ARMV7M Configuration Options @@ -301,6 +263,7 @@ CONFIG_ARCH_CHIP_STM32F103C8=y # CONFIG_ARCH_CHIP_STM32F373RC is not set # CONFIG_ARCH_CHIP_STM32F373VC is not set # CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F410RB is not set # CONFIG_ARCH_CHIP_STM32F411RE is not set # CONFIG_ARCH_CHIP_STM32F411VE is not set # CONFIG_ARCH_CHIP_STM32F405RG is not set @@ -359,6 +322,7 @@ CONFIG_STM32_MEDIUMDENSITY=y # CONFIG_STM32_STM32F37XX is not set # CONFIG_STM32_STM32F40XX is not set # CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set # CONFIG_STM32_STM32F411 is not set # CONFIG_STM32_STM32F405 is not set # CONFIG_STM32_STM32F407 is not set @@ -430,6 +394,7 @@ CONFIG_STM32_HAVE_I2C2=y # CONFIG_STM32_HAVE_I2C3 is not set CONFIG_STM32_HAVE_SPI2=y CONFIG_STM32_HAVE_SPI3=y +# CONFIG_STM32_HAVE_I2S3 is not set # CONFIG_STM32_HAVE_SPI4 is not set # CONFIG_STM32_HAVE_SPI5 is not set # CONFIG_STM32_HAVE_SPI6 is not set @@ -543,6 +508,8 @@ CONFIG_STM32_HAVE_RTC_COUNTER=y # # USB Device Configuration # +# CONFIG_ARCH_TOOLCHAIN_IAR is not set +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -759,7 +726,8 @@ CONFIG_DEV_NULL=y # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set CONFIG_CAN=y -# CONFIG_ARCH_HAVE_CAN_ERRORS is not set +CONFIG_ARCH_HAVE_CAN_ERRORS=y +# CONFIG_CAN_ERRORS is not set # CONFIG_CAN_FD is not set CONFIG_CAN_FIFOSIZE=8 CONFIG_CAN_NPENDINGRTR=4 @@ -866,7 +834,6 @@ CONFIG_STANDARD_SERIAL=y # CONFIG_SERIAL_IFLOWCONTROL is not set # CONFIG_SERIAL_OFLOWCONTROL is not set # CONFIG_SERIAL_DMA is not set -# CONFIG_SERIAL_TIOCSERGSTRUCT is not set CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y CONFIG_USART1_SERIAL_CONSOLE=y # CONFIG_OTHER_SERIAL_CONSOLE is not set @@ -1136,10 +1103,10 @@ CONFIG_EXAMPLES_CAN_READ=y # CONFIG_EXAMPLES_MOUNT is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NX is not set # CONFIG_EXAMPLES_NXFFS is not set # CONFIG_EXAMPLES_NXHELLO is not set # CONFIG_EXAMPLES_NXIMAGE is not set -# CONFIG_EXAMPLES_NX is not set # CONFIG_EXAMPLES_NXLINES is not set # CONFIG_EXAMPLES_NXTERM is not set # CONFIG_EXAMPLES_NXTEXT is not set diff --git a/configs/stm32f103-minimum/src/stm32_bringup.c b/configs/stm32f103-minimum/src/stm32_bringup.c index 14745c88d1..00c9f89e0a 100644 --- a/configs/stm32f103-minimum/src/stm32_bringup.c +++ b/configs/stm32f103-minimum/src/stm32_bringup.c @@ -152,6 +152,8 @@ int stm32_bringup(void) #endif #ifdef CONFIG_CAN_MCP2515 + /* Configure and initialize the MCP2515 CAN device */ + ret = stm32_mcp2515initialize("/dev/can0"); if (ret < 0) { diff --git a/configs/stm32f103-minimum/src/stm32_mcp2515.c b/configs/stm32f103-minimum/src/stm32_mcp2515.c index 00d73bd35e..964af8ae8c 100644 --- a/configs/stm32f103-minimum/src/stm32_mcp2515.c +++ b/configs/stm32f103-minimum/src/stm32_mcp2515.c @@ -1,7 +1,7 @@ -/************************************************************************************ +/**************************************************************************** * configs/stm32f4discovery/src/stm32_mcp2515.c * - * Copyright (C) 2015 Alan Carvalho de Assis. All rights reserved. + * Copyright (C) 2017 Alan Carvalho de Assis. All rights reserved. * Author: Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without @@ -31,11 +31,11 @@ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * - ************************************************************************************/ + ****************************************************************************/ -/************************************************************************************ +/**************************************************************************** * Included Files - ************************************************************************************/ + ****************************************************************************/ #include @@ -49,11 +49,12 @@ #include "stm32_spi.h" #include "stm32f103_minimum.h" -#if defined(CONFIG_SPI) && defined(CONFIG_STM32_SPI1) && defined(CONFIG_CAN_MCP2515) +#if defined(CONFIG_SPI) && defined(CONFIG_STM32_SPI1) && \ + defined(CONFIG_CAN_MCP2515) -/************************************************************************************ +/**************************************************************************** * Pre-processor Definitions - ************************************************************************************/ + ****************************************************************************/ #define MCP2515_SPI_PORTNO 1 /* On SPI1 */ @@ -119,15 +120,20 @@ static struct stm32_mcp2515config_s g_mcp2515config = /* This is the MCP2515 Interupt handler */ -int mcp2515_interrupt(int irq, FAR void *context) +int mcp2515_interrupt(int irq, FAR void *context, FAR void *arg) { + FAR struct stm32_mcp2515config_s *priv = + (FAR struct stm32_mcp2515config_s *)arg; + + DEBUGASSERT(priv != NULL); + /* Verify that we have a handler attached */ - if (g_mcp2515config.handler) + if (priv->handler) { /* Yes.. forward with interrupt along with its argument */ - g_mcp2515config.handler(&g_mcp2515config.config, g_mcp2515config.arg); + priv->handler(&priv->config, priv->arg); } return OK; @@ -137,7 +143,7 @@ static int mcp2515_attach(FAR struct mcp2515_config_s *state, mcp2515_handler_t handler, FAR void *arg) { FAR struct stm32_mcp2515config_s *priv = - (FAR struct stm32_mcp2515config_s *) state; + (FAR struct stm32_mcp2515config_s *)state; irqstate_t flags; caninfo("Saving handle %p\n", handler); @@ -149,7 +155,8 @@ static int mcp2515_attach(FAR struct mcp2515_config_s *state, /* Configure the interrupt for falling edge*/ - (void)stm32_gpiosetevent(GPIO_MCP2515_IRQ, false, true, false, mcp2515_interrupt, NULL); + (void)stm32_gpiosetevent(GPIO_MCP2515_IRQ, false, true, false, + mcp2515_interrupt, priv); leave_critical_section(flags); diff --git a/drivers/can/Kconfig b/drivers/can/Kconfig index 69b044d274..62d69d1c09 100644 --- a/drivers/can/Kconfig +++ b/drivers/can/Kconfig @@ -127,49 +127,48 @@ config CAN_NPOLLWAITERS comment "CAN Bus Controllers:" config CAN_MCP2515 - bool "Microchip MCP2515 CAN Bus Controller over SPI" - default n - depends on SPI - select ARCH_HAVE_CAN_ERRORS - ---help--- - Enable driver support for Microchip MCP2515. + bool "Microchip MCP2515 CAN Bus Controller over SPI" + default n + depends on SPI + select ARCH_HAVE_CAN_ERRORS + ---help--- + Enable driver support for Microchip MCP2515. if CAN_MCP2515 config MCP2515_BITRATE - int "MCP2515 bitrate" - default 500000 - ---help--- - MCP2515 bitrate in bits per second. + int "MCP2515 bitrate" + default 500000 + ---help--- + MCP2515 bitrate in bits per second. config MCP2515_PROPSEG - int "MCP2515 Propagation Segment TQ" - default 2 - range 1 8 - ---help--- - The length of the bit time is Tquanta * (SyncSeg + PropSeg + PhaseSeg1 + PhaseSeg2). + int "MCP2515 Propagation Segment TQ" + default 2 + range 1 8 + ---help--- + The length of the bit time is Tquanta * (SyncSeg + PropSeg + PhaseSeg1 + PhaseSeg2). config MCP2515_PHASESEG1 - int "MCP2515 Phase Segment 1" - default 2 - range 1 8 - ---help--- - The length of the bit time is Tquanta * (SyncSeg + PropSeg + PhaseSeg1 + PhaseSeg2). + int "MCP2515 Phase Segment 1" + default 2 + range 1 8 + ---help--- + The length of the bit time is Tquanta * (SyncSeg + PropSeg + PhaseSeg1 + PhaseSeg2). config MCP2515_PHASESEG2 - int "MCP2515 Phase Segment 2" - default 3 - range 2 8 - ---help--- - The length of the bit time is Tquanta * (SyncSeg + PropSeg + PhaseSeg1 + PhaseSeg2). + int "MCP2515 Phase Segment 2" + default 3 + range 2 8 + ---help--- + The length of the bit time is Tquanta * (SyncSeg + PropSeg + PhaseSeg1 + PhaseSeg2). config MCP2515_SJW - int "MCP2515 Synchronization Jump Width" - default 1 - range 1 4 - ---help--- - The duration of a synchronization jump is SJW. + int "MCP2515 Synchronization Jump Width" + default 1 + range 1 4 + ---help--- + The duration of a synchronization jump is SJW. endif # CAN_MCP2515 - endif # CAN diff --git a/drivers/can/mcp2515.c b/drivers/can/mcp2515.c index 5a514e48e8..8fe6e35364 100644 --- a/drivers/can/mcp2515.c +++ b/drivers/can/mcp2515.c @@ -225,9 +225,9 @@ struct mcp2515_can_s /* MCP2515 Register access */ static void mcp2515_readregs(FAR struct mcp2515_can_s *priv, uint8_t regaddr, - uint8_t *buffer, uint8_t len); + FAR uint8_t *buffer, uint8_t len); static void mcp2515_writeregs(FAR struct mcp2515_can_s *priv, uint8_t regaddr, - uint8_t *buffer, uint8_t len); + FAR const uint8_t *buffer, uint8_t len); static void mcp2515_modifyreg(FAR struct mcp2515_can_s *priv, uint8_t regaddr, uint8_t mask, uint8_t value); #ifdef CONFIG_MCP2515_REGDEBUG @@ -273,7 +273,8 @@ static void mcp2515_error(FAR struct can_dev_s *dev, uint8_t status, uint8_t oldstatus); #endif static void mcp2515_receive(FAR struct can_dev_s *dev, uint8_t offset); -static int mcp2515_interrupt(FAR struct mcp2515_config_s *config, FAR void *arg); +static int mcp2515_interrupt(FAR struct mcp2515_config_s *config, + FAR void *arg); /* Hardware initialization */ @@ -285,16 +286,16 @@ static int mcp2515_hw_initialize(FAR struct mcp2515_can_s *priv); static const struct can_ops_s g_mcp2515ops = { - .co_reset = mcp2515_reset, - .co_setup = mcp2515_setup, - .co_shutdown = mcp2515_shutdown, - .co_rxint = mcp2515_rxint, - .co_txint = mcp2515_txint, - .co_ioctl = mcp2515_ioctl, - .co_remoterequest = mcp2515_remoterequest, - .co_send = mcp2515_send, - .co_txready = mcp2515_txready, - .co_txempty = mcp2515_txempty, + mcp2515_reset, /* co_reset */ + mcp2515_setup, /* co_setup */ + mcp2515_shutdown, /* co_shutdown */ + mcp2515_rxint, /* co_rxint */ + mcp2515_txint, /* co_txint */ + mcp2515_ioctl, /* co_ioctl */ + mcp2515_remoterequest, /* co_remoterequest */ + mcp2515_send, /* co_send */ + mcp2515_txready, /* co_txready */ + mcp2515_txempty, /* co_txempty */ }; /**************************************************************************** @@ -316,7 +317,7 @@ static const struct can_ops_s g_mcp2515ops = ****************************************************************************/ static void mcp2515_readregs(FAR struct mcp2515_can_s *priv, uint8_t regaddr, - uint8_t *buffer, uint8_t len) + FAR uint8_t *buffer, uint8_t len) { FAR struct mcp2515_config_s *config = priv->config; #ifdef CONFIG_CANBUS_REGDEBUG @@ -371,7 +372,7 @@ static void mcp2515_readregs(FAR struct mcp2515_can_s *priv, uint8_t regaddr, ****************************************************************************/ static void mcp2515_writeregs(FAR struct mcp2515_can_s *priv, uint8_t regaddr, - uint8_t *buffer, uint8_t len) + FAR const uint8_t *buffer, uint8_t len) { FAR struct mcp2515_config_s *config = priv->config; #ifdef CONFIG_CANBUS_REGDEBUG @@ -405,7 +406,6 @@ static void mcp2515_writeregs(FAR struct mcp2515_can_s *priv, uint8_t regaddr, /* Unlock bus */ (void)SPI_LOCK(config->spi, false); - } /**************************************************************************** @@ -425,7 +425,7 @@ static void mcp2515_writeregs(FAR struct mcp2515_can_s *priv, uint8_t regaddr, ****************************************************************************/ static void mcp2515_modifyreg(FAR struct mcp2515_can_s *priv, uint8_t regaddr, - uint8_t mask, uint8_t value) + uint8_t mask, uint8_t value) { FAR struct mcp2515_config_s *config = priv->config; @@ -458,7 +458,6 @@ static void mcp2515_modifyreg(FAR struct mcp2515_can_s *priv, uint8_t regaddr, /* Unlock bus */ (void)SPI_LOCK(config->spi, false); - } /**************************************************************************** @@ -1187,7 +1186,6 @@ static void mcp2515_reset(FAR struct can_dev_s *dev) /* Execute the reset */ mcp2515_reset_lowlevel(priv); - } /**************************************************************************** @@ -2351,6 +2349,7 @@ static int mcp2515_interrupt(FAR struct mcp2515_config_s *config, FAR void *arg) } /* Acknowledge reading the FIFO entry */ + handled = true; } } diff --git a/drivers/can/mcp2515.h b/drivers/can/mcp2515.h index 2b9c981572..b3e83f302b 100644 --- a/drivers/can/mcp2515.h +++ b/drivers/can/mcp2515.h @@ -1,3 +1,45 @@ +/**************************************************************************** + * drivers/can/mcp2515.c + * + * Copyright (C) 2017 Alan Carvalho de Assis. All rights reserved. + * Author: Alan Carvalho de Assis + * + * 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, Atmel, 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 __DRIVERS_CAN_MCP2514_H +#define __DRIVERS_CAN_MCP2514_H 1 + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + /* Register Addresses */ #define MCP2515_RXF0SIDH 0x00 @@ -395,3 +437,4 @@ #define MCP2515_CANCLK_FREQUENCY 8000000 +#endif /* __DRIVERS_CAN_MCP2514_H */ diff --git a/include/nuttx/can/mcp2515.h b/include/nuttx/can/mcp2515.h index bca2d0db73..f7618fd88e 100644 --- a/include/nuttx/can/mcp2515.h +++ b/include/nuttx/can/mcp2515.h @@ -61,15 +61,18 @@ * Public Types ****************************************************************************/ -typedef void (*mcp2515_handler_t)(FAR struct mcp2515_config_s *config, FAR void *arg); +typedef void (*mcp2515_handler_t)(FAR struct mcp2515_config_s *config, + FAR void *arg); -/* A reference to a structure of this type must be passed to the MCP2515 driver when the - * driver is instantiated. This structure provides information about the configuration of the - * MCP2515 and provides some board-specific hooks. +/* A reference to a structure of this type must be passed to the MCP2515 + * driver when the driver is instantiated. This structure provides + * information about the configuration of the MCP2515 and provides some + * board-specific hooks. * - * Memory for this structure is provided by the caller. It is not copied by the driver - * and is presumed to persist while the driver is active. The memory must be writeable - * because, under certain circumstances, the driver may modify the frequency. + * Memory for this structure is provided by the caller. It is not copied by + * the driver and is presumed to persist while the driver is active. The + * memory must be writeable because, under certain circumstances, the driver + * may modify the frequency. */ struct mcp2515_config_s @@ -97,8 +100,8 @@ struct mcp2515_config_s * attach - Attach the ADXL345 interrupt handler to the GPIO interrupt */ - int (*attach)(FAR struct mcp2515_config_s *state, mcp2515_handler_t handler, - FAR void *arg); + CODE int (*attach)(FAR struct mcp2515_config_s *state, + mcp2515_handler_t handler, FAR void *arg); }; diff --git a/include/nuttx/spi/spi.h b/include/nuttx/spi/spi.h index 6a03a2a9d8..c4757bb975 100644 --- a/include/nuttx/spi/spi.h +++ b/include/nuttx/spi/spi.h @@ -456,8 +456,8 @@ #define SPIDEV_TEMPERATURE(n) SPIDEV_ID(SPIDEVTYPE_TEMPERATURE, (n)) #define SPIDEV_IEEE802154(n) SPIDEV_ID(SPIDEVTYPE_IEEE802154, (n)) #define SPIDEV_CONTACTLESS(n) SPIDEV_ID(SPIDEVTYPE_CONTACTLESS, (n)) -#define SPIDEV_USER(n) SPIDEV_ID(SPIDEVTYPE_USER, (n)) #define SPIDEV_CANBUS(n) SPIDEV_ID(SPIDEVTYPE_CANBUS, (n)) +#define SPIDEV_USER(n) SPIDEV_ID(SPIDEVTYPE_USER, (n)) /**************************************************************************** * Public Types @@ -492,8 +492,9 @@ enum spi_devtype_e SPIDEVTYPE_TEMPERATURE, /* Select SPI Temperature sensor device */ SPIDEVTYPE_IEEE802154, /* Select SPI IEEE 802.15.4 wireless device */ SPIDEVTYPE_CONTACTLESS, /* Select SPI Contactless device */ - SPIDEVTYPE_USER, /* Board-specific values start here */ - SPIDEVTYPE_CANBUS /* Select SPI CAN Bus controller over SPI */ + SPIDEVTYPE_CANBUS, /* Select SPI CAN Bus controller over SPI */ + SPIDEVTYPE_USER /* Board-specific values start here + * This must always be the last definition. */ }; /* Certain SPI devices may required different clocking modes */ -- GitLab From fb7866bdc89a0b3705aff2c1f2d649b9cedbe82b Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Tue, 23 May 2017 19:30:12 -0300 Subject: [PATCH 863/990] Use the right variable name at mcp2515_txready() --- drivers/can/mcp2515.c | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/drivers/can/mcp2515.c b/drivers/can/mcp2515.c index 8fe6e35364..b1506bfa40 100644 --- a/drivers/can/mcp2515.c +++ b/drivers/can/mcp2515.c @@ -1823,7 +1823,7 @@ static bool mcp2515_txready(FAR struct can_dev_s *dev) { FAR struct mcp2515_can_s *priv; uint8_t regval; - bool empty; + bool ready; DEBUGASSERT(dev); priv = dev->cd_priv; @@ -1845,32 +1845,32 @@ static bool mcp2515_txready(FAR struct can_dev_s *dev) mcp2515_readregs(priv, MCP2515_TXB0CTRL, ®val, 1); if ((regval & TXBCTRL_TXREQ) == 0) { - empty = true; + ready = true; } else { mcp2515_readregs(priv, MCP2515_TXB1CTRL, ®val, 1); if ((regval & TXBCTRL_TXREQ) == 0) { - empty = true; + ready = true; } else { mcp2515_readregs(priv, MCP2515_TXB2CTRL, ®val, 1); if ((regval & TXBCTRL_TXREQ) == 0) { - empty = true; + ready = true; } else { - empty = false; + ready = false; } } } mcp2515_dev_unlock(priv); - return empty; + return ready; } /**************************************************************************** -- GitLab From bab5de15f6a2bc05d2a79237d37ed654b11c725e Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Tue, 23 May 2017 19:41:58 -0300 Subject: [PATCH 864/990] Remove warning from MCP2515 compilation --- configs/stm32f103-minimum/src/stm32f103_minimum.h | 12 ++++++++++++ drivers/can/mcp2515.c | 6 +++++- 2 files changed, 17 insertions(+), 1 deletion(-) diff --git a/configs/stm32f103-minimum/src/stm32f103_minimum.h b/configs/stm32f103-minimum/src/stm32f103_minimum.h index adabdbc3b0..9b2e62df14 100644 --- a/configs/stm32f103-minimum/src/stm32f103_minimum.h +++ b/configs/stm32f103-minimum/src/stm32f103_minimum.h @@ -194,6 +194,18 @@ int stm32_qencoder_initialize(FAR const char *devpath, int timer); int stm32_rgbled_setup(void); #endif +/************************************************************************************ + * Name: stm32_mcp2515initialize + * + * Description: + * Initialize and register the MCP2515 CAN driver. + * + ************************************************************************************/ + +#ifdef CONFIG_CAN_MCP2515 +int stm32_mcp2515initialize(FAR const char *devpath); +#endif + /************************************************************************************ * Name: stm32_usbinitialize * diff --git a/drivers/can/mcp2515.c b/drivers/can/mcp2515.c index b1506bfa40..50d4999e60 100644 --- a/drivers/can/mcp2515.c +++ b/drivers/can/mcp2515.c @@ -1298,6 +1298,7 @@ static void mcp2515_rxint(FAR struct can_dev_s *dev, bool enable) DEBUGASSERT(config); caninfo("CAN%d enable: %d\n", config->devid, enable); + UNUSED(config); /* Enable/disable the receive interrupts */ @@ -1670,6 +1671,7 @@ static int mcp2515_send(FAR struct can_dev_s *dev, FAR struct can_msg_s *msg) caninfo("CAN%d\n", config->devid); caninfo("CAN%d ID: %d DLC: %d\n", config->devid, msg->cm_hdr.ch_id, msg->cm_hdr.ch_dlc); + UNUSED(config); /* That that FIFO elements were configured. * @@ -2241,7 +2243,8 @@ static int mcp2515_interrupt(FAR struct mcp2515_config_s *config, FAR void *arg) { /* Clear interrupt errors */ - mcp2515_modifyreg(priv, MCP2515_CANINTF, MCP2515_ERROR_INTS, ~MCP2515_ERROR_INTS); + mcp2515_modifyreg(priv, MCP2515_CANINTF, MCP2515_ERROR_INTS, + (uint8_t)~MCP2515_ERROR_INTS); #ifdef CONFIG_CAN_ERRORS /* Report errors */ @@ -2378,6 +2381,7 @@ static int mcp2515_hw_initialize(struct mcp2515_can_s *priv) uint8_t regval; caninfo("CAN%d\n", config->devid); + UNUSED(config); /* Setup CNF1 register */ -- GitLab From 7ae81734495210c611c8d1f54b2d8b3d33357980 Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Wed, 24 May 2017 07:13:32 -0600 Subject: [PATCH 865/990] button_upper: fix interrupt enabling for poll-events --- drivers/input/button_upper.c | 22 +++++++--------------- 1 file changed, 7 insertions(+), 15 deletions(-) diff --git a/drivers/input/button_upper.c b/drivers/input/button_upper.c index 12f2896cf5..93b54454e0 100644 --- a/drivers/input/button_upper.c +++ b/drivers/input/button_upper.c @@ -202,9 +202,6 @@ static void btn_enable(FAR struct btn_upperhalf_s *priv) btn_buttonset_t press; btn_buttonset_t release; irqstate_t flags; -#ifndef CONFIG_DISABLE_POLL - int i; -#endif DEBUGASSERT(priv && priv->bu_lower); lower = priv->bu_lower; @@ -223,19 +220,10 @@ static void btn_enable(FAR struct btn_upperhalf_s *priv) for (opriv = priv->bu_open; opriv; opriv = opriv->bo_flink) { #ifndef CONFIG_DISABLE_POLL - /* Are there any poll waiters? */ - - for (i = 0; i < CONFIG_BUTTONS_NPOLLWAITERS; i++) - { - if (opriv->bo_fds[i]) - { - /* Yes.. OR in the poll event buttons */ + /* OR in the poll event buttons */ - press |= opriv->bo_pollevents.bp_press; - release |= opriv->bo_pollevents.bp_release; - break; - } - } + press |= opriv->bo_pollevents.bp_press; + release |= opriv->bo_pollevents.bp_release; #endif #ifndef CONFIG_DISABLE_SIGNALS @@ -448,6 +436,10 @@ static int btn_open(FAR struct file *filep) filep->f_priv = (FAR void *)opriv; ret = OK; + /* Enable/disable interrupt handling */ + + btn_enable(priv); + errout_with_sem: btn_givesem(&priv->bu_exclsem); return ret; -- GitLab From 6ccc01ad462964119d1a741cae80d9e439c63fcb Mon Sep 17 00:00:00 2001 From: Masayuki Ishikawa Date: Thu, 25 May 2017 09:22:34 +0900 Subject: [PATCH 866/990] netdb: Fix bugs in lib_gethostbynamer.c This fix sets h_name in struct hostent returned by gethostbyname() Signed-off-by: Masayuki Ishikawa --- libc/netdb/lib_gethostbynamer.c | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/libc/netdb/lib_gethostbynamer.c b/libc/netdb/lib_gethostbynamer.c index b655211651..e95d9a853a 100644 --- a/libc/netdb/lib_gethostbynamer.c +++ b/libc/netdb/lib_gethostbynamer.c @@ -205,6 +205,10 @@ static int lib_numeric_address(FAR const char *name, FAR struct hostent *host, } strncpy(ptr, name, buflen); + + /* Set the address to h_name */ + + host->h_name = ptr; return 0; } @@ -289,6 +293,10 @@ static int lib_localhost(FAR const char *name, FAR struct hostent *host, } strncpy(dest, name, buflen); + + /* Set the address to h_name */ + + host->h_name = dest; return 0; } @@ -401,6 +409,10 @@ static int lib_find_answer(FAR const char *name, FAR struct hostent *host, } strncpy(ptr, name, buflen); + + /* Set the address to h_name */ + + host->h_name = ptr; return OK; } #endif /* CONFIG_NETDB_DNSCLIENT */ @@ -543,6 +555,10 @@ static int lib_dns_lookup(FAR const char *name, FAR struct hostent *host, } strncpy(ptr, name, buflen); + + /* Set the address to h_name */ + + host->h_name = ptr; return OK; } -- GitLab From 32a638cdfeefddb2897fd4b9f422dabf0f9107a9 Mon Sep 17 00:00:00 2001 From: Masayuki Ishikawa Date: Thu, 25 May 2017 16:48:55 +0900 Subject: [PATCH 867/990] TCP: Fix tcp_findlistner() in dual stack mode Signed-off-by: Masayuki Ishikawa --- net/tcp/tcp.h | 8 ++++++++ net/tcp/tcp_input.c | 20 ++++++++++++++++++++ net/tcp/tcp_listen.c | 23 +++++++++++++++++++++++ net/tcp/tcp_timer.c | 4 ++++ 4 files changed, 55 insertions(+) diff --git a/net/tcp/tcp.h b/net/tcp/tcp.h index 2797f4f3bc..83891b1024 100644 --- a/net/tcp/tcp.h +++ b/net/tcp/tcp.h @@ -708,7 +708,11 @@ void tcp_listen_initialize(void); * ****************************************************************************/ +#if defined(CONFIG_NET_IPv4) && defined(CONFIG_NET_IPv6) +FAR struct tcp_conn_s *tcp_findlistener(uint16_t portno, uint8_t domain); +#else FAR struct tcp_conn_s *tcp_findlistener(uint16_t portno); +#endif /**************************************************************************** * Name: tcp_unlisten @@ -747,7 +751,11 @@ int tcp_listen(FAR struct tcp_conn_s *conn); * ****************************************************************************/ +#if defined(CONFIG_NET_IPv4) && defined(CONFIG_NET_IPv6) +bool tcp_islistener(uint16_t portno, uint8_t domain); +#else bool tcp_islistener(uint16_t portno); +#endif /**************************************************************************** * Name: tcp_accept_connection diff --git a/net/tcp/tcp_input.c b/net/tcp/tcp_input.c index a064fb0763..d299feeb0b 100644 --- a/net/tcp/tcp_input.c +++ b/net/tcp/tcp_input.c @@ -96,6 +96,18 @@ static void tcp_input(FAR struct net_driver_s *dev, unsigned int iplen) int len; int i; +#if defined(CONFIG_NET_IPv4) && defined(CONFIG_NET_IPv6) + uint8_t domain = PF_UNSPEC; + if (iplen == IPv4_HDRLEN) + { + domain = PF_INET; + } + else if (iplen == IPv6_HDRLEN) + { + domain = PF_INET6; + } +#endif + #ifdef CONFIG_NET_STATISTICS /* Bump up the count of TCP packets received */ @@ -165,7 +177,11 @@ static void tcp_input(FAR struct net_driver_s *dev, unsigned int iplen) */ tmp16 = tcp->destport; +#if defined(CONFIG_NET_IPv4) && defined(CONFIG_NET_IPv6) + if (tcp_islistener(tmp16, domain)) +#else if (tcp_islistener(tmp16)) +#endif { /* We matched the incoming packet with a connection in LISTEN. * We now need to create a new connection and send a SYNACK in @@ -327,7 +343,11 @@ found: /* Notify the listener for the connection of the reset event */ +#if defined(CONFIG_NET_IPv4) && defined(CONFIG_NET_IPv6) + listener = tcp_findlistener(conn->lport, domain); +#else listener = tcp_findlistener(conn->lport); +#endif /* We must free this TCP connection structure; this connection * will never be established. diff --git a/net/tcp/tcp_listen.c b/net/tcp/tcp_listen.c index b3d36a126d..8b3b686137 100644 --- a/net/tcp/tcp_listen.c +++ b/net/tcp/tcp_listen.c @@ -77,7 +77,11 @@ static FAR struct tcp_conn_s *tcp_listenports[CONFIG_NET_MAX_LISTENPORTS]; * ****************************************************************************/ +#if defined(CONFIG_NET_IPv4) && defined(CONFIG_NET_IPv6) +FAR struct tcp_conn_s *tcp_findlistener(uint16_t portno, uint8_t domain) +#else FAR struct tcp_conn_s *tcp_findlistener(uint16_t portno) +#endif { int ndx; @@ -90,7 +94,11 @@ FAR struct tcp_conn_s *tcp_findlistener(uint16_t portno) */ FAR struct tcp_conn_s *conn = tcp_listenports[ndx]; +#if defined(CONFIG_NET_IPv4) && defined(CONFIG_NET_IPv6) + if (conn && conn->lport == portno && conn->domain == domain) +#else if (conn && conn->lport == portno) +#endif { /* Yes.. we found a listener on this port */ @@ -183,7 +191,11 @@ int tcp_listen(FAR struct tcp_conn_s *conn) /* First, check if there is already a socket listening on this port */ +#if defined(CONFIG_NET_IPv4) && defined(CONFIG_NET_IPv6) + if (tcp_islistener(conn->lport, conn->domain)) +#else if (tcp_islistener(conn->lport)) +#endif { /* Yes, then we must refuse this request */ @@ -229,10 +241,17 @@ int tcp_listen(FAR struct tcp_conn_s *conn) * ****************************************************************************/ +#if defined(CONFIG_NET_IPv4) && defined(CONFIG_NET_IPv6) +bool tcp_islistener(uint16_t portno, uint8_t domain) +{ + return tcp_findlistener(portno, domain) != NULL; +} +#else bool tcp_islistener(uint16_t portno) { return tcp_findlistener(portno) != NULL; } +#endif /**************************************************************************** * Name: tcp_accept_connection @@ -256,7 +275,11 @@ int tcp_accept_connection(FAR struct net_driver_s *dev, * connection. */ +#if defined(CONFIG_NET_IPv4) && defined(CONFIG_NET_IPv6) + listener = tcp_findlistener(portno, conn->domain); +#else listener = tcp_findlistener(portno); +#endif if (listener != NULL) { /* Yes, there is a listener. Is it accepting connections now? */ diff --git a/net/tcp/tcp_timer.c b/net/tcp/tcp_timer.c index 03935c964b..3c760c1429 100644 --- a/net/tcp/tcp_timer.c +++ b/net/tcp/tcp_timer.c @@ -235,7 +235,11 @@ void tcp_timer(FAR struct net_driver_s *dev, FAR struct tcp_conn_s *conn, /* Find the listener for this connection. */ +#if defined(CONFIG_NET_IPv4) && defined(CONFIG_NET_IPv6) + listener = tcp_findlistener(conn->lport, conn->domain); +#else listener = tcp_findlistener(conn->lport); +#endif if (listener != NULL) { /* We call tcp_callback() for the connection with -- GitLab From 01b0a56371a8651fe799e13af9c05f10f5c9d53b Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 25 May 2017 08:02:08 -0600 Subject: [PATCH 868/990] TCP: tcp_input() now receives IP domain as an input parameter vs. deriving from the IP header length. --- net/icmpv6/icmpv6.h | 10 +++++----- net/tcp/tcp_input.c | 23 ++++++----------------- 2 files changed, 11 insertions(+), 22 deletions(-) diff --git a/net/icmpv6/icmpv6.h b/net/icmpv6/icmpv6.h index a45197d1c6..1f01202b8a 100644 --- a/net/icmpv6/icmpv6.h +++ b/net/icmpv6/icmpv6.h @@ -215,11 +215,6 @@ void icmpv6_poll(FAR struct net_driver_s *dev); void icmpv6_solicit(FAR struct net_driver_s *dev, FAR const net_ipv6addr_t ipaddr); -#undef EXTERN -#ifdef __cplusplus -} -#endif - /**************************************************************************** * Name: icmpv6_rsolicit * @@ -480,5 +475,10 @@ void icmpv6_rnotify(FAR struct net_driver_s *dev, const net_ipv6addr_t draddr, # define icmpv6_rnotify(d,p,l) #endif +#undef EXTERN +#ifdef __cplusplus +} +#endif + #endif /* CONFIG_NET_ICMPv6 */ #endif /* __NET_ICMPv6_ICMPv6_H */ diff --git a/net/tcp/tcp_input.c b/net/tcp/tcp_input.c index d299feeb0b..5200f1a601 100644 --- a/net/tcp/tcp_input.c +++ b/net/tcp/tcp_input.c @@ -72,8 +72,8 @@ * * Parameters: * dev - The device driver structure containing the received TCP packet. - * tcp - A pointer to the TCP header in the packet - * iplen - Combined length of the IP and TCP headers + * domain - IP domain (PF_INET or PF_INET6) + * iplen - Lngth of the IP header (IPv4_HDRLEN or IPv6_HDRLEN). * * Return: * None @@ -83,7 +83,8 @@ * ****************************************************************************/ -static void tcp_input(FAR struct net_driver_s *dev, unsigned int iplen) +static void tcp_input(FAR struct net_driver_s *dev, uint8_t domain, + unsigned int iplen) { FAR struct tcp_hdr_s *tcp; FAR struct tcp_conn_s *conn = NULL; @@ -96,18 +97,6 @@ static void tcp_input(FAR struct net_driver_s *dev, unsigned int iplen) int len; int i; -#if defined(CONFIG_NET_IPv4) && defined(CONFIG_NET_IPv6) - uint8_t domain = PF_UNSPEC; - if (iplen == IPv4_HDRLEN) - { - domain = PF_INET; - } - else if (iplen == IPv6_HDRLEN) - { - domain = PF_INET6; - } -#endif - #ifdef CONFIG_NET_STATISTICS /* Bump up the count of TCP packets received */ @@ -966,7 +955,7 @@ void tcp_ipv4_input(FAR struct net_driver_s *dev) /* Then process in the TCP IPv4 input */ - tcp_input(dev, IPv4_HDRLEN); + tcp_input(dev, PF_INET, IPv4_HDRLEN); } #endif @@ -996,7 +985,7 @@ void tcp_ipv6_input(FAR struct net_driver_s *dev) /* Then process in the TCP IPv6 input */ - tcp_input(dev, IPv6_HDRLEN); + tcp_input(dev, PF_INET6, IPv6_HDRLEN); } #endif -- GitLab From 488f42588b6bf7d5b91c3a0003e5a9e1ffb78018 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Thu, 25 May 2017 16:50:42 -1000 Subject: [PATCH 869/990] Kinetis:Removed base address from kinetis_adc.h --- arch/arm/src/kinetis/chip/kinetis_adc.h | 1 - 1 file changed, 1 deletion(-) diff --git a/arch/arm/src/kinetis/chip/kinetis_adc.h b/arch/arm/src/kinetis/chip/kinetis_adc.h index 6b3b74fa9c..536c254f5d 100644 --- a/arch/arm/src/kinetis/chip/kinetis_adc.h +++ b/arch/arm/src/kinetis/chip/kinetis_adc.h @@ -82,7 +82,6 @@ #define KINETIS_ADC_CLM0_OFFSET 0x006c /* ADC minus-side general calibration value register */ /* Register Addresses ***********************************************************************/ -# define KINETIS_ADC1_BASE 0x400bb000 /* Analog-to-digital converter (ADC) 1 */ #define KINETIS_ADC0_SC1A (KINETIS_ADC0_BASE+KINETIS_ADC_SC1A_OFFSET) #define KINETIS_ADC0_SC1B (KINETIS_ADC0_BASE+KINETIS_ADC_SC1B_OFFSET) -- GitLab From b4070209687ac10303c2f1b764e405d7c2535e61 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Thu, 25 May 2017 16:51:25 -1000 Subject: [PATCH 870/990] Kinetis:Fixed typo in kinetis_adc.h --- arch/arm/src/kinetis/chip/kinetis_adc.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/arch/arm/src/kinetis/chip/kinetis_adc.h b/arch/arm/src/kinetis/chip/kinetis_adc.h index 536c254f5d..db33a33207 100644 --- a/arch/arm/src/kinetis/chip/kinetis_adc.h +++ b/arch/arm/src/kinetis/chip/kinetis_adc.h @@ -204,7 +204,7 @@ # define ADC_CFG1_ADIV_DIV1 (0 << ADC_CFG1_ADIV_SHIFT) /* Divider=1 rate=input clock */ # define ADC_CFG1_ADIV_DIV2 (1 << ADC_CFG1_ADIV_SHIFT) /* Divider=2 rate=input clock/2 */ # define ADC_CFG1_ADIV_DIV4 (2 << ADC_CFG1_ADIV_SHIFT) /* Divider=4 rate=input clock/4 */ -# define ADC_CFG1_ADIV_DIV5 (3 << ADC_CFG1_ADIV_SHIFT) /* Divider=8 rate=input clock/8 */ +# define ADC_CFG1_ADIV_DIV8 (3 << ADC_CFG1_ADIV_SHIFT) /* Divider=8 rate=input clock/8 */ #define ADC_CFG1_ADLPC (1 << 7) /* Bit 7: Low-power configuration */ /* Bits 8-31: Reserved */ /* Configuration register 2 */ -- GitLab From a077d0285bf05b55380a59237ac13a9a071d7571 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Thu, 25 May 2017 16:52:08 -1000 Subject: [PATCH 871/990] Kinetis:Added ADC channel macro --- arch/arm/src/kinetis/chip/kinetis_adc.h | 1 + 1 file changed, 1 insertion(+) diff --git a/arch/arm/src/kinetis/chip/kinetis_adc.h b/arch/arm/src/kinetis/chip/kinetis_adc.h index db33a33207..847bd9b7b7 100644 --- a/arch/arm/src/kinetis/chip/kinetis_adc.h +++ b/arch/arm/src/kinetis/chip/kinetis_adc.h @@ -151,6 +151,7 @@ #define ADC_SC1_ADCH_SHIFT (0) /* Bits 0-4: Input channel select */ #define ADC_SC1_ADCH_MASK (31 << ADC_SC1_ADCH_SHIFT) +# define ADC_SC1_ADCH(c) (((c) & 0x1f) << ADC_SC1_ADCH_SHIFT) # define ADC_SC1_ADCH_DADP0 (0 << ADC_SC1_ADCH_SHIFT) /* DIFF=0 DADP0; DIFF=1, DAD0 */ # define ADC_SC1_ADCH_DADP1 (1 << ADC_SC1_ADCH_SHIFT) /* DIFF=0 DADP1; DIFF=1, DAD1 */ # define ADC_SC1_ADCH_DADP2 (2 << ADC_SC1_ADCH_SHIFT) /* DIFF=0 DADP2; DIFF=1, DAD2 */ -- GitLab From 8df5c29857e243b3cc0864e4c48ec0b231bb3e6f Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Fri, 26 May 2017 10:38:39 -0300 Subject: [PATCH 872/990] Add driver for Nokia 5110 (Philips PCD8544) --- drivers/lcd/Kconfig | 38 ++ drivers/lcd/Make.defs | 4 + drivers/lcd/pcd8544.c | 999 ++++++++++++++++++++++++++++++++++++ drivers/lcd/pcd8544.h | 87 ++++ include/nuttx/lcd/pcd8544.h | 148 ++++++ 5 files changed, 1276 insertions(+) create mode 100644 drivers/lcd/pcd8544.c create mode 100644 drivers/lcd/pcd8544.h create mode 100644 include/nuttx/lcd/pcd8544.h diff --git a/drivers/lcd/Kconfig b/drivers/lcd/Kconfig index 565ab07301..d432bab3be 100644 --- a/drivers/lcd/Kconfig +++ b/drivers/lcd/Kconfig @@ -576,6 +576,44 @@ config SSD1351_MSTRCONTRAST endif +config LCD_PCD8544 + bool "Nokia 5110 LCD Display (Philips PCD8544)" + default n + ---help--- + LCD Display Module, PCD8544, Philips + + Required LCD driver settings: + LCD_MAXCONTRAST should be 255, but any value >0 and <=255 will be accepted. + +if LCD_PCD8544 + +config PCD8544_NINTERFACES + int "Number of PCD8544 Devices" + default 1 + ---help--- + Specifies the number of physical PCD8544 devices that will be + supported. NOTE: At present, this must be undefined or defined to be 1. + +config PCD8544_XRES + int "PCD8544 X Resolution" + default 84 + ---help--- + Specifies the X resolution of the LCD. + +config PCD8544_YRES + int "PCD8544 Y Resolution" + default 48 + ---help--- + Specifies the Y resolution of the LCD. + +config PCD8544_INVERSE_VIDEO + bool "PCD8544 Inverse video" + default n + ---help--- + Inverse video on LCD. + +endif # LCD_PCD8544 + config LCD_ST7565 bool "ST7565 LCD Display Module" default n diff --git a/drivers/lcd/Make.defs b/drivers/lcd/Make.defs index 3eb60c791c..43d5ebd61d 100644 --- a/drivers/lcd/Make.defs +++ b/drivers/lcd/Make.defs @@ -81,6 +81,10 @@ ifeq ($(CONFIG_LCD_MIO283QT9A),y) CSRCS += mio283qt9a.c endif +ifeq ($(CONFIG_LCD_PCD8544),y) + CSRCS += pcd8544.c +endif + ifeq ($(CONFIG_LCD_ST7565),y) CSRCS += st7565.c endif diff --git a/drivers/lcd/pcd8544.c b/drivers/lcd/pcd8544.c new file mode 100644 index 0000000000..1e8f0e2f3b --- /dev/null +++ b/drivers/lcd/pcd8544.c @@ -0,0 +1,999 @@ +/************************************************************************************** + * drivers/lcd/pcd8544.c + * + * Driver for the Philips PCD8544 Display controller + * + * Copyright (C) 2017 Alan Carvalho de Assis. All rights reserved. + * Author: Alan Carvalho de Assis + * + * Based on drivers/lcd/pcd8544.c. + * + * Copyright (C) 2013 Zilogic Systems. All rights reserved. + * Author: Manikandan + * + * Copyright (C) 2011 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. + * + **************************************************************************************/ + +/************************************************************************************** + * Included Files + **************************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include "pcd8544.h" + +/************************************************************************************** + * Pre-processor Definitions + **************************************************************************************/ + +/* Configuration **********************************************************************/ +/* PCD8544 Configuration Settings: + * + * CONFIG_PCD8544_SPIMODE - Controls the SPI mode + * CONFIG_PCD8544_FREQUENCY - Define to use a different bus frequency + * CONFIG_PCD8544_NINTERFACES - Specifies the number of physical + * PCD8544 devices that will be supported. NOTE: At present, this + * must be undefined or defined to be 1. + * CONFIG_LCD_PCD8544DEBUG - Enable detailed PCD8544 debug pcd8544 output + * (CONFIG_DEBUG_FEATURES and CONFIG_VERBOSE must also be enabled). + * + * Required LCD driver settings: + * CONFIG_LCD_PCD8544 - Enable PCD8544 support + * CONFIG_LCD_MAXCONTRAST should be 255, but any value >0 and <=255 will be accepted. + * CONFIG_LCD_MAXPOWER should be 1: 0=off, 1=normal + * + * Required SPI driver settings: + * CONFIG_SPI_CMDDATA - Include support for cmd/data selection. + */ + +/* Verify that all configuration requirements have been met */ + +#ifndef CONFIG_PCD8544_SPIMODE +# define CONFIG_PCD8544_SPIMODE SPIDEV_MODE0 +#endif + +/* SPI frequency */ + +#ifndef CONFIG_PCD8544_FREQUENCY +# define CONFIG_PCD8544_FREQUENCY 3000000 +#endif + +/* CONFIG_PCD8544_NINTERFACES determines the number of physical interfaces + * that will be supported. + */ + +#ifndef CONFIG_PCD8544_NINTERFACES +# define CONFIG_PCD8544_NINTERFACES 1 +#endif + +#if CONFIG_PCD8544_NINTERFACES != 1 +# warning "Only a single PCD8544 interface is supported" +# undef CONFIG_PCD8544_NINTERFACES +# define CONFIG_PCD8544_NINTERFACES 1 +#endif + +/* Verbose debug pcd8544 must also be enabled to use the extra OLED debug pcd8544 */ + +#ifndef CONFIG_DEBUG_FEATURES +# undef CONFIG_DEBUG_INFO +# undef CONFIG_DEBUG_GRAPHICS +#endif + +#ifndef CONFIG_DEBUG_INFO +# undef CONFIG_LCD_PCD8544DEBUG +#endif + +/* Check contrast selection */ + +#ifndef CONFIG_LCD_MAXCONTRAST +# define CONFIG_LCD_MAXCONTRAST 127 +#endif + +#if CONFIG_LCD_MAXCONTRAST <= 0 || CONFIG_LCD_MAXCONTRAST > 127 +# error "CONFIG_LCD_MAXCONTRAST exceeds supported maximum" +#endif + +#if CONFIG_LCD_MAXCONTRAST < 60 +# warning "Optimal setting of CONFIG_LCD_MAXCONTRAST is 60" +#endif + +/* Check power setting */ + +#if !defined(CONFIG_LCD_MAXPOWER) +# define CONFIG_LCD_MAXPOWER 1 +#endif + +#if CONFIG_LCD_MAXPOWER != 1 +# warning "CONFIG_LCD_MAXPOWER should be 1" +# undef CONFIG_LCD_MAXPOWER +# define CONFIG_LCD_MAXPOWER 1 +#endif + +/* The Display requires CMD/DATA SPI support */ + +#ifndef CONFIG_SPI_CMDDATA +# error "CONFIG_SPI_CMDDATA must be defined in your NuttX configuration" +#endif + +/* Color is 1bpp monochrome with leftmost column contained in bits 0 */ + +#ifdef CONFIG_NX_DISABLE_1BPP +# warning "1 bit-per-pixel support needed" +#endif + +/* Color Properties *******************************************************************/ +/* The PCD8544 display controller can handle a resolution of 84x48. + */ +/* Display Resolution */ + +#ifdef CONFIG_PCD8544_XRES +#define PCD8544_XRES CONFIG_PCD8544_XRES +#else +#define PCD8544_XRES 84 +#endif + +#ifdef CONFIG_PCD8544_YRES +#define PCD8544_YRES CONFIG_PCD8544_YRES +#else +#define PCD8544_YRES 48 +#endif + +/* Color depth and format */ + +#define PCD8544_BPP 1 +#define PCD8544_COLORFMT FB_FMT_Y1 + +/* Bytes per logical row and actual device row */ + +#define PCD8544_XSTRIDE (PCD8544_XRES >> 3) /* Pixels arrange "horizontally for user" */ +#define PCD8544_YSTRIDE (PCD8544_YRES >> 3) /* But actual device arrangement is "vertical" */ + +/* The size of the shadow frame buffer */ + +#define PCD8544_FBSIZE (PCD8544_XRES * PCD8544_YSTRIDE) + +/* Bit helpers */ + +#define LS_BIT (1 << 0) +#define MS_BIT (1 << 7) + +/************************************************************************************** + * Private Type Definition + **************************************************************************************/ + +/* This structure describes the state of this driver */ + +struct pcd8544_dev_s +{ + /* Publically visible device structure */ + + struct lcd_dev_s dev; + + /* Private LCD-specific information follows */ + + FAR struct spi_dev_s *spi; + uint8_t contrast; + uint8_t powered; + + /* The PCD8544 does not support reading from the display memory in SPI mode. + * Since there is 1 BPP and access is byte-by-byte, it is necessary to keep + * a shadow copy of the framebuffer memory. + */ + + uint8_t fb[PCD8544_FBSIZE]; +}; + +/************************************************************************************** + * Private Function Protototypes + **************************************************************************************/ + +/* SPI helpers */ + +static void pcd8544_select(FAR struct spi_dev_s *spi); +static void pcd8544_deselect(FAR struct spi_dev_s *spi); + +/* LCD Data Transfer Methods */ + +static int pcd8544_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buffer, + size_t npixels); +static int pcd8544_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer, + size_t npixels); + +/* LCD Configuration */ + +static int pcd8544_getvideoinfo(FAR struct lcd_dev_s *dev, + FAR struct fb_videoinfo_s *vinfo); +static int pcd8544_getplaneinfo(FAR struct lcd_dev_s *dev, unsigned int planeno, + FAR struct lcd_planeinfo_s *pinfo); + +/* LCD RGB Mapping */ + +#ifdef CONFIG_FB_CMAP +# error "RGB color mapping not supported by this driver" +#endif + +/* Cursor Controls */ + +#ifdef CONFIG_FB_HWCURSOR +# error "Cursor control not supported by this driver" +#endif + +/* LCD Specific Controls */ + +static int pcd8544_getpower(struct lcd_dev_s *dev); +static int pcd8544_setpower(struct lcd_dev_s *dev, int power); +static int pcd8544_getcontrast(struct lcd_dev_s *dev); +static int pcd8544_setcontrast(struct lcd_dev_s *dev, unsigned int contrast); + +/* Initialization */ + +static inline void up_clear(FAR struct pcd8544_dev_s *priv); + +/************************************************************************************** + * Private Data + **************************************************************************************/ + +/* This is working memory allocated by the LCD driver for each LCD device + * and for each color plane. This memory will hold one raster line of data. + * The size of the allocated run buffer must therefore be at least + * (bpp * xres / 8). Actual alignment of the buffer must conform to the + * bitwidth of the underlying pixel type. + * + * If there are multiple planes, they may share the same working buffer + * because different planes will not be operate on concurrently. However, + * if there are multiple LCD devices, they must each have unique run buffers. + */ + +static uint8_t g_runbuffer[PCD8544_XSTRIDE+1]; + +/* This structure describes the overall LCD video controller */ + +static const struct fb_videoinfo_s g_videoinfo = +{ + .fmt = PCD8544_COLORFMT, /* Color format: RGB16-565: RRRR RGGG GGGB BBBB */ + .xres = PCD8544_XRES, /* Horizontal resolution in pixel columns */ + .yres = PCD8544_YRES, /* Vertical resolution in pixel rows */ + .nplanes = 1, /* Number of color planes supported */ +}; + +/* This is the standard, NuttX Plane information object */ + +static const struct lcd_planeinfo_s g_planeinfo = +{ + .putrun = pcd8544_putrun, /* Put a run into LCD memory */ + .getrun = pcd8544_getrun, /* Get a run from LCD memory */ + .buffer = (FAR uint8_t *)g_runbuffer, /* Run scratch buffer */ + .bpp = PCD8544_BPP, /* Bits-per-pixel */ +}; + +/* This is the standard, NuttX LCD driver object */ + +static struct pcd8544_dev_s g_pcd8544dev = +{ + .dev = + { + /* LCD Configuration */ + + .getvideoinfo = pcd8544_getvideoinfo, + .getplaneinfo = pcd8544_getplaneinfo, + + /* LCD RGB Mapping -- Not supported */ + /* Cursor Controls -- Not supported */ + + /* LCD Specific Controls */ + + .getpower = pcd8544_getpower, + .setpower = pcd8544_setpower, + .getcontrast = pcd8544_getcontrast, + .setcontrast = pcd8544_setcontrast, + }, +}; + +/************************************************************************************** + * Private Functions + **************************************************************************************/ + +/************************************************************************************** + * Name: pcd8544_powerstring + * + * Description: + * Convert the power setting to a string. + * + **************************************************************************************/ + +static inline FAR const char *pcd8544_powerstring(uint8_t power) +{ + if (power == PCD8544_POWER_OFF) + { + return "OFF"; + } + else if (power == PCD8544_POWER_ON) + { + return "ON"; + } + else + { + return "ERROR"; + } +} + +/************************************************************************************** + * Name: pcd8544_select + * + * Description: + * Select the SPI, locking and re-configuring if necessary + * + * Parameters: + * spi - Reference to the SPI driver structure + * + * Returned Value: + * None + * + * Assumptions: + * + **************************************************************************************/ + +static void pcd8544_select(FAR struct spi_dev_s *spi) +{ + /* Select PCD8544 chip (locking the SPI bus in case there are multiple + * devices competing for the SPI bus + */ + + SPI_LOCK(spi, true); + SPI_SELECT(spi, SPIDEV_DISPLAY(0), true); + + /* Now make sure that the SPI bus is configured for the PCD8544 (it + * might have gotten configured for a different device while unlocked) + */ + + SPI_SETMODE(spi, CONFIG_PCD8544_SPIMODE); + SPI_SETBITS(spi, 8); + (void)SPI_HWFEATURES(spi, 0); + (void)SPI_SETFREQUENCY(spi, CONFIG_PCD8544_FREQUENCY); +} + +/************************************************************************************** + * Name: pcd8544_deselect + * + * Description: + * De-select the SPI + * + * Parameters: + * spi - Reference to the SPI driver structure + * + * Returned Value: + * None + * + * Assumptions: + * + **************************************************************************************/ + +static void pcd8544_deselect(FAR struct spi_dev_s *spi) +{ + /* De-select PCD8544 chip and relinquish the SPI bus. */ + + SPI_SELECT(spi, SPIDEV_DISPLAY(0), false); + SPI_LOCK(spi, false); +} + +/************************************************************************************** + * Name: pcd8544_putrun + * + * Description: + * This method can be used to write a partial raster line to the LCD: + * + * row - Starting row to write to (range: 0 <= row < yres) + * col - Starting column to write to (range: 0 <= col <= xres-npixels) + * buffer - The buffer containing the run to be written to the LCD + * npixels - The number of pixels to write to the LCD + * (range: 0 < npixels <= xres-col) + * + **************************************************************************************/ + +static int pcd8544_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buffer, + size_t npixels) +{ + /* Because of this line of code, we will only be able to support a single PCD8544 device */ + + FAR struct pcd8544_dev_s *priv = &g_pcd8544dev; + FAR uint8_t *fbptr; + FAR uint8_t *ptr; + uint8_t fbmask; + uint8_t page; + uint8_t usrmask; + uint8_t i; + int pixlen; + + ginfo("row: %d col: %d npixels: %d\n", row, col, npixels); + DEBUGASSERT(buffer); + + /* Clip the run to the display */ + + pixlen = npixels; + if ((unsigned int)col + (unsigned int)pixlen > (unsigned int)PCD8544_XRES) + { + pixlen = (int)PCD8544_XRES - (int)col; + } + + /* Verify that some portion of the run remains on the display */ + + if (pixlen <= 0 || row > PCD8544_YRES) + { + return OK; + } + + /* Get the page number. The range of 48 lines is divided up into six + * pages of 8 lines each. + */ + + page = row >> 3; + + /* Update the shadow frame buffer memory. First determine the pixel + * position in the frame buffer memory. Pixels are organized like + * this: + * + * --------+---+---+---+---+-...-+----+ + * Segment | 0 | 1 | 2 | 3 | ... | 83 | + * --------+---+---+---+---+-...-+----+ + * Bit 0 | | X | | | | | + * Bit 1 | | X | | | | | + * Bit 2 | | X | | | | | + * Bit 3 | | X | | | | | + * Bit 4 | | X | | | | | + * Bit 5 | | X | | | | | + * Bit 6 | | X | | | | | + * Bit 7 | | X | | | | | + * --------+---+---+---+---+-...-+----+ + * + * So, in order to draw a white, horizontal line, at row 45. we + * would have to modify all of the bytes in page 45/8 = 5. We + * would have to set bit 45%8 = 5 in every byte in the page. + */ + + fbmask = 1 << (row & 7); + fbptr = &priv->fb[page * PCD8544_XRES + col]; + ptr = fbptr; +#ifdef CONFIG_NX_PACKEDMSFIRST + usrmask = MS_BIT; +#else + usrmask = LS_BIT; +#endif + + for (i = 0; i < pixlen; i++) + { + /* Set or clear the corresponding bit */ + + if ((*buffer & usrmask) != 0) + { + *ptr++ |= fbmask; + } + else + { + *ptr++ &= ~fbmask; + } + + /* Inc/Decrement to the next source pixel */ + +#ifdef CONFIG_NX_PACKEDMSFIRST + if (usrmask == LS_BIT) + { + buffer++; + usrmask = MS_BIT; + } + else + { + usrmask >>= 1; + } +#else + if (usrmask == MS_BIT) + { + buffer++; + usrmask = LS_BIT; + } + else + { + usrmask <<= 1; + } +#endif + } + + /* Select and lock the device */ + + pcd8544_select(priv->spi); + + /* Select command transfer */ + + SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY(0), true); + + /* Set the starting position for the run */ + + (void)SPI_SEND(priv->spi, PCD8544_SET_Y_ADDR+page); /* Set the page start */ + (void)SPI_SEND(priv->spi, PCD8544_SET_X_ADDR + (col & 0x7f)); /* Set the low column */ + + /* Select data transfer */ + + SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY(0), false); + + /* Then transfer all of the data */ + + (void)SPI_SNDBLOCK(priv->spi, fbptr, pixlen); + + /* Unlock and de-select the device */ + + pcd8544_deselect(priv->spi); + return OK; +} + +/************************************************************************************** + * Name: pcd8544_getrun + * + * Description: + * This method can be used to read a partial raster line from the LCD: + * + * row - Starting row to read from (range: 0 <= row < yres) + * col - Starting column to read read (range: 0 <= col <= xres-npixels) + * buffer - The buffer in which to return the run read from the LCD + * npixels - The number of pixels to read from the LCD + * (range: 0 < npixels <= xres-col) + * + **************************************************************************************/ + +static int pcd8544_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer, + size_t npixels) +{ + /* Because of this line of code, we will only be able to support a single PCD8544 device */ + + FAR struct pcd8544_dev_s *priv = &g_pcd8544dev; + FAR uint8_t *fbptr; + uint8_t page; + uint8_t fbmask; + uint8_t usrmask; + uint8_t i; + int pixlen; + + ginfo("row: %d col: %d npixels: %d\n", row, col, npixels); + DEBUGASSERT(buffer); + + /* Clip the run to the display */ + + pixlen = npixels; + if ((unsigned int)col + (unsigned int)pixlen > (unsigned int)PCD8544_XRES) + { + pixlen = (int)PCD8544_XRES - (int)col; + } + + /* Verify that some portion of the run is actually the display */ + + if (pixlen <= 0 || row > PCD8544_YRES) + { + return -EINVAL; + } + + /* Then transfer the display data from the shadow frame buffer memory */ + /* Get the page number. The range of 48 lines is divided up into six + * pages of 8 lines each. + */ + + page = row >> 3; + + /* Update the shadow frame buffer memory. First determine the pixel + * position in the frame buffer memory. Pixels are organized like + * this: + * + * --------+---+---+---+---+-...-+----+ + * Segment | 0 | 1 | 2 | 3 | ... | 83 | + * --------+---+---+---+---+-...-+----+ + * Bit 0 | | X | | | | | + * Bit 1 | | X | | | | | + * Bit 2 | | X | | | | | + * Bit 3 | | X | | | | | + * Bit 4 | | X | | | | | + * Bit 5 | | X | | | | | + * Bit 6 | | X | | | | | + * Bit 7 | | X | | | | | + * --------+---+---+---+---+-...-+----+ + * + * So, in order to draw a white, horizontal line, at row 45. we + * would have to modify all of the bytes in page 45/8 = 5. We + * would have to set bit 45%8 = 5 in every byte in the page. + */ + + fbmask = 1 << (row & 7); + fbptr = &priv->fb[page * PCD8544_XRES + col]; +#ifdef CONFIG_NX_PACKEDMSFIRST + usrmask = MS_BIT; +#else + usrmask = LS_BIT; +#endif + + *buffer = 0; + for (i = 0; i < pixlen; i++) + { + /* Set or clear the corresponding bit */ + + uint8_t byte = *fbptr++; + if ((byte & fbmask) != 0) + { + *buffer |= usrmask; + } + + /* Inc/Decrement to the next destination pixel. Hmmmm. It looks like + * this logic could write past the end of the user buffer. Revisit + * this! + */ + +#ifdef CONFIG_NX_PACKEDMSFIRST + if (usrmask == LS_BIT) + { + buffer++; + *buffer = 0; + usrmask = MS_BIT; + } + else + { + usrmask >>= 1; + } +#else + if (usrmask == MS_BIT) + { + buffer++; + *buffer = 0; + usrmask = LS_BIT; + } + else + { + usrmask <<= 1; + } +#endif + } + + return OK; +} + +/************************************************************************************** + * Name: pcd8544_getvideoinfo + * + * Description: + * Get information about the LCD video controller configuration. + * + **************************************************************************************/ + +static int pcd8544_getvideoinfo(FAR struct lcd_dev_s *dev, + FAR struct fb_videoinfo_s *vinfo) +{ + DEBUGASSERT(dev && vinfo); + ginfo("fmt: %d xres: %d yres: %d nplanes: %d\n", + g_videoinfo.fmt, g_videoinfo.xres, g_videoinfo.yres, g_videoinfo.nplanes); + memcpy(vinfo, &g_videoinfo, sizeof(struct fb_videoinfo_s)); + return OK; +} + +/************************************************************************************** + * Name: pcd8544_getplaneinfo + * + * Description: + * Get information about the configuration of each LCD color plane. + * + **************************************************************************************/ + +static int pcd8544_getplaneinfo(FAR struct lcd_dev_s *dev, unsigned int planeno, + FAR struct lcd_planeinfo_s *pinfo) +{ + DEBUGASSERT(dev && pinfo && planeno == 0); + ginfo("planeno: %d bpp: %d\n", planeno, g_planeinfo.bpp); + memcpy(pinfo, &g_planeinfo, sizeof(struct lcd_planeinfo_s)); + return OK; +} + +/************************************************************************************** + * Name: pcd8544_getpower + * + * Description: + * Get the LCD panel power status (0: full off - CONFIG_LCD_MAXPOWER: full on). On + * backlit LCDs, this setting may correspond to the backlight setting. + * + **************************************************************************************/ + +static int pcd8544_getpower(struct lcd_dev_s *dev) +{ + struct pcd8544_dev_s *priv = (struct pcd8544_dev_s *)dev; + DEBUGASSERT(priv); + ginfo("powered: %s\n", pcd8544_powerstring(priv->powered)); + return priv->powered; +} + +/************************************************************************************** + * Name: pcd8544_setpower + * + * Description: + * Enable/disable LCD panel power (0: full off - CONFIG_LCD_MAXPOWER: full on). On + * backlit LCDs, this setting may correspond to the backlight setting. + * + **************************************************************************************/ + +static int pcd8544_setpower(struct lcd_dev_s *dev, int power) +{ + struct pcd8544_dev_s *priv = (struct pcd8544_dev_s *)dev; + + DEBUGASSERT(priv && (unsigned)power <= CONFIG_LCD_MAXPOWER); + ginfo("power: %s powered: %s\n", + pcd8544_powerstring(power), pcd8544_powerstring(priv->powered)); + + /* Select and lock the device */ + + pcd8544_select(priv->spi); + + /* Select command transfer */ + + SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY(0), true); + + if (power <= PCD8544_POWER_OFF) + { + /* Turn the display off (power-down) */ + + (void)SPI_SEND(priv->spi, (PCD8544_FUNC_SET | PCD8544_POWER_DOWN)); + + priv->powered = PCD8544_POWER_OFF; + } + else + { + /* Leave the power-down */ + + (void)SPI_SEND(priv->spi, PCD8544_FUNC_SET); + + priv->powered = PCD8544_POWER_ON; + } + + /* Select data transfer */ + + SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY(0), false); + + /* Let go of the SPI lock and de-select the device */ + + pcd8544_deselect(priv->spi); + + return OK; +} + +/************************************************************************************** + * Name: pcd8544_getcontrast + * + * Description: + * Get the current contrast setting (0-CONFIG_LCD_MAXCONTRAST). + * + **************************************************************************************/ + +static int pcd8544_getcontrast(struct lcd_dev_s *dev) +{ + struct pcd8544_dev_s *priv = (struct pcd8544_dev_s *)dev; + DEBUGASSERT(priv); + return (int)priv->contrast; +} + +/************************************************************************************** + * Name: pcd8544_setcontrast + * + * Description: + * Set LCD panel contrast (0-CONFIG_LCD_MAXCONTRAST). + * + **************************************************************************************/ + +static int pcd8544_setcontrast(struct lcd_dev_s *dev, unsigned int contrast) +{ + struct pcd8544_dev_s *priv = (struct pcd8544_dev_s *)dev; + + ginfo("contrast: %d\n", contrast); + DEBUGASSERT(priv); + + if (contrast > 127) + { + return -EINVAL; + } + + /* Save the contrast */ + + priv->contrast = contrast; + + /* Select and lock the device */ + + pcd8544_select(priv->spi); + + /* Select command transfer */ + + SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY(0), true); + + /* Select the extended instruction set ( H = 1 ) */ + + (void)SPI_SEND(priv->spi, (PCD8544_FUNC_SET | PCD8544_MODEH)); + + /* Set the contrast */ + + (void)SPI_SEND(priv->spi, (PCD8544_WRITE_VOP | contrast) ); + + /* Return to normal mode */ + + (void)SPI_SEND(priv->spi, PCD8544_FUNC_SET); + + /* Select data transfer */ + + SPI_CMDDATA(priv->spi, SPIDEV_DISPLAY(0), false); + + /* Let go of the SPI lock and de-select the device */ + + pcd8544_deselect(priv->spi); + + return OK; +} + +/************************************************************************************** + * Name: up_clear + * + * Description: + * Clear the display. + * + **************************************************************************************/ + +static inline void up_clear(FAR struct pcd8544_dev_s *priv) +{ + FAR struct spi_dev_s *spi = priv->spi; + int page; + int i; + + /* Clear the framebuffer */ + + memset(priv->fb, PCD8544_Y1_BLACK, PCD8544_FBSIZE); + + /* Select and lock the device */ + + pcd8544_select(priv->spi); + + /* Go throw pcd8544 all 6 pages */ + + for (page = 0, i = 0; i < 6; i++) + { + /* Select command transfer */ + + SPI_CMDDATA(spi, SPIDEV_DISPLAY(0), true); + + /* Set the starting position for the run */ + + (void)SPI_SEND(priv->spi, PCD8544_SET_Y_ADDR+i); /* Set the page start */ + (void)SPI_SEND(priv->spi, PCD8544_SET_X_ADDR + page); /* Set the column */ + + + /* Select data transfer */ + + SPI_CMDDATA(spi, SPIDEV_DISPLAY(0), false); + + /* Then transfer all 84 columns of data */ + + (void)SPI_SNDBLOCK(priv->spi, &priv->fb[page * PCD8544_XRES], PCD8544_XRES); + } + + /* Unlock and de-select the device */ + + pcd8544_deselect(spi); +} + +/************************************************************************************** + * Public Functions + **************************************************************************************/ + +/************************************************************************************** + * Name: pcd8544_initialize + * + * Description: + * Initialize the PCD8544 video hardware. The initial state of the + * OLED is fully initialized, display memory cleared, and the OLED ready to + * use, but with the power setting at 0 (full off == sleep mode). + * + * Input Parameters: + * + * spi - A reference to the SPI driver instance. + * devno - A value in the range of 0 thropcd8544h CONFIG_PCD8544_NINTERFACES-1. + * This allows support for multiple OLED devices. + * + * Returned Value: + * + * On success, this function returns a reference to the LCD object for the specified + * OLED. NULL is returned on any failure. + * + **************************************************************************************/ + +FAR struct lcd_dev_s *pcd8544_initialize(FAR struct spi_dev_s *spi, unsigned int devno) +{ + /* Configure and enable LCD */ + + FAR struct pcd8544_dev_s *priv = &g_pcd8544dev; + + ginfo("Initializing\n"); + DEBUGASSERT(spi && devno == 0); + + /* Save the reference to the SPI device */ + + priv->spi = spi; + + /* Select and lock the device */ + + pcd8544_select(spi); + + /* Select command transfer */ + + SPI_CMDDATA(spi, SPIDEV_DISPLAY(0), true); + + /* Leave the power-down and select extended instruction set mode H = 1 */ + + (void)SPI_SEND(spi, (PCD8544_FUNC_SET | PCD8544_MODEH)); + + /* Set LCD Bias to n = 3 */ + + (void)SPI_SEND(spi, (PCD8544_BIAS_SYSTEM | PCD8544_BIAS_BS2)); + + /* Select the normal instruction set mode H = 0 */ + + (void)SPI_SEND(spi, PCD8544_FUNC_SET); + + /* Clear the screen */ + + (void)SPI_SEND(spi, (PCD8544_DISP_CTRL | PCD8544_DISP_BLANK)); + + /* Set the Display Control to Normal Mode D = 1 and E = 0 */ + + (void)SPI_SEND(spi, (PCD8544_DISP_CTRL | PCD8544_DISP_NORMAL)); + + /* Select data transfer */ + + SPI_CMDDATA(spi, SPIDEV_DISPLAY(0), false); + + /* Let go of the SPI lock and de-select the device */ + + pcd8544_deselect(spi); + + /* Clear the framebuffer */ + + up_mdelay(100); + up_clear(priv); + return &priv->dev; +} + diff --git a/drivers/lcd/pcd8544.h b/drivers/lcd/pcd8544.h new file mode 100644 index 0000000000..f5982b9fb7 --- /dev/null +++ b/drivers/lcd/pcd8544.h @@ -0,0 +1,87 @@ +/************************************************************************************** + * drivers/lcd/pcd8544.h + * + * Definitions for the PCD8544 LCD Display + * + * Copyright (C) 2017 Alan Carvalho de Assis. All rights reserved. + * Author: Alan Carvalho de Assis + * + * 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 __DRIVERS_LCD_PCD8544_H +#define __DRIVERS_LCD_PCD8544_H + +/************************************************************************************** + * Included Files + **************************************************************************************/ + +/************************************************************************************** + * Pre-processor Definitions + **************************************************************************************/ + +#define PCD8544_MAX_BANKS 6 +#define PCD8544_MAX_COLS 84 + +/* Fundamental Commands *****************************************************/ + +#define PCD8544_NOP 0x00 /* 0x00: No Operation */ +#define PCD8544_FUNC_SET (1 << 5) /* Used to select extend mode */ +#define PCD8544_POWER_DOWN (1 << 2) /* Enable power-down mode */ +#define PCD8544_MODEV (1 << 1) /* Enable Vertical Addressing */ +#define PCD8544_MODEH (1 << 0) /* Enable extended instruction set */ + +/* Command with Instructon Set H = 0 */ + +#define PCD8544_DISP_CTRL (1 << 3) /* sets display configuration */ +#define PCD8544_DISP_BLANK 0x00 /* display blank */ +#define PCD8544_DISP_ALLON 0x01 /* all display segments on */ +#define PCD8544_DISP_NORMAL 0x04 /* normal mode */ +#define PCD8544_DISP_INVERT 0x05 /* inverse video mode */ + +#define PCD8544_SET_Y_ADDR (1 << 6) /* Set the Y bank 0-5 */ +#define PCD8544_SET_X_ADDR (1 << 7) /* Set the X bank 0-83 */ + +/* Command with Instructon Set H = 1 */ + +#define PCD8544_TEMP_COEF (1 << 2) /* set Temperature Coefficient */ +#define PCD8544_BIAS_SYSTEM (1 << 4) /* set Bias System */ +#define PCD8544_BIAS_BS0 (1 << 0) /* set Bias System */ +#define PCD8544_BIAS_BS1 (1 << 1) /* set Bias System */ +#define PCD8544_BIAS_BS2 (1 << 2) /* set Bias System */ +#define PCD8544_WRITE_VOP (1 << 7) /* write Vop to register*/ +#define PCD8544_VOP0 (1 << 0) /* Vop0 */ +#define PCD8544_VOP1 (1 << 1) /* Vop1 */ +#define PCD8544_VOP2 (1 << 2) /* Vop2 */ +#define PCD8544_VOP3 (1 << 3) /* Vop3 */ +#define PCD8544_VOP4 (1 << 4) /* Vop4 */ +#define PCD8544_VOP5 (1 << 5) /* Vop5 */ +#define PCD8544_VOP6 (1 << 6) /* Vop6 */ + +#endif /* __DRIVERS_LCD_PCD8544_H */ diff --git a/include/nuttx/lcd/pcd8544.h b/include/nuttx/lcd/pcd8544.h new file mode 100644 index 0000000000..2437274b54 --- /dev/null +++ b/include/nuttx/lcd/pcd8544.h @@ -0,0 +1,148 @@ +/**************************************************************************** + * include/nuttx/lcd/pcd8544.h + * + * Driver for Displays with the PCD8544 LCD controller. + * + * Copyright (C) 2017 Alan Carvalho de Assis. All rights reserved. + * Author: Alan Carvalho de Assis + * + * Based on include/nuttx/lcd/ug-9664hswag01.h + * + * Copyright (C) 2011-2012 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. + * + ****************************************************************************/ + +#ifndef __INCLUDE_NUTTX_PCD8544_H +#define __INCLUDE_NUTTX_PCD8544_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* PCD8544 Configuration Settings: + * + * CONFIG_PCD8544_SPIMODE - Controls the SPI mode + * CONFIG_PCD8544_FREQUENCY - Define to use a different bus frequency + * CONFIG_PCD8544_NINTERFACES - Specifies the number of physical + * PCD8544 devices that will be supported. NOTE: At present, this + * must be undefined or defined to be 1. + * + * Required LCD driver settings: + * CONFIG_LCD_PCD8544 - Enable PCD8544 support + * CONFIG_LCD_MAXCONTRAST should be 255, but any value >0 and <=255 will be accepted. + * CONFIG_LCD_MAXPOWER should be 2: 0=off, 1=dim, 2=normal + * + * Required SPI driver settings: + * CONFIG_SPI_CMDDATA - Include support for cmd/data selection. + */ + +/* Some important "colors" */ + +#define PCD8544_Y1_BLACK 0 +#define PCD8544_Y1_WHITE 1 + +/* Only two power settings are supported: */ + +#define PCD8544_POWER_OFF 0 +#define PCD8544_POWER_ON 1 + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +#ifdef __cplusplus +extern "C" +{ +#endif + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Name: pcd8544_initialize + * + * Description: + * Initialize the PCD8544 video hardware. The initial state of the + * LCD is fully initialized, display memory cleared, and the LCD ready + * to use, but with the power setting at 0 (full off == sleep mode). + * + * Input Parameters: + * + * spi - A reference to the SPI driver instance. + * devno - A value in the range of 0 thropcd8544h CONFIG_PCD8544_NINTERFACES-1. + * This allows support for multiple LCD devices. + * + * Returned Value: + * + * On success, this function returns a reference to the LCD object for + * the specified LCD. NULL is returned on any failure. + * + ****************************************************************************/ + +struct lcd_dev_s; /* see nuttx/lcd.h */ +struct spi_dev_s; /* see nuttx/spi/spi.h */ +FAR struct lcd_dev_s *pcd8544_initialize(FAR struct spi_dev_s *spi, unsigned int devno); + +/**************************************************************************** + * Name: pcd8544_power + * + * Description: + * If the hardware supports a controllable LCD a power supply, this + * interface should be provided. It may be called by the driver to turn + * the LCD power on and off as needed. + * + * Input Parameters: + * + * devno - A value in the range of 0 throuh CONFIG_PCD8544_NINTERFACES-1. + * This allows support for multiple LCD devices. + * on - true:turn power on, false: turn power off. + * + * Returned Value: + * None + * + **************************************************************************************/ + +#ifdef __cplusplus +} +#endif + +#endif /* __INCLUDE_NUTTX_PCD8544_H */ -- GitLab From f5732f0d158eab3e8eafebc9ac1a434efc247151 Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Fri, 26 May 2017 10:48:11 -0300 Subject: [PATCH 873/990] Add board support to use the Nokia 5110 LCD display driver --- configs/stm32f103-minimum/README.txt | 66 ++++++++ configs/stm32f103-minimum/src/Makefile | 4 + configs/stm32f103-minimum/src/stm32_pcd8544.c | 145 ++++++++++++++++++ configs/stm32f103-minimum/src/stm32_spi.c | 27 +++- .../stm32f103-minimum/src/stm32f103_minimum.h | 3 + 5 files changed, 244 insertions(+), 1 deletion(-) create mode 100644 configs/stm32f103-minimum/src/stm32_pcd8544.c diff --git a/configs/stm32f103-minimum/README.txt b/configs/stm32f103-minimum/README.txt index 91e08731f2..dc227e443f 100644 --- a/configs/stm32f103-minimum/README.txt +++ b/configs/stm32f103-minimum/README.txt @@ -14,6 +14,7 @@ Contents - Using 128KiB of Flash instead of 64KiB - Quadrature Encoder - SDCard support + - Nokia 5110 LCD Display support - USB Console support - STM32F103 Minimum - specific Configuration Options - Configurations @@ -307,6 +308,71 @@ SDCard support: PA5, MOSI to PA7 and MISO to PA6. Note: some chinese boards use MOSO instead of MISO. +Nokia 5110 LCD Display support: +=============================== + + You can connect a low cost Nokia 5110 LCD display in the STM32F103 Minimum + board this way: connect PA5 (SPI1 CLK) to CLK; PA7 (SPI1 MOSI) to DIN; PA4 + to CE; PA3 to RST; PA2 to DC. Also connect 3.3V to VCC and GND to GND. + + You can start with default "stm32f103-minimum/nsh" configuration option and + enable these options using "make menuconfig" : + + System Type ---> + STM32 Peripheral Support ---> + [*] SPI1 + + Device Drivers ---> + -*- SPI Driver Support ---> + [*] SPI exchange + [*] SPI CMD/DATA + + Device Drivers ---> + LCD Driver Support ---> + [*] Graphic LCD Driver Support ---> + [*] Nokia 5110 LCD Display (Philips PCD8544) + (1) Number of PCD8544 Devices + (84) PCD8544 X Resolution + (48) PCD8544 Y Resolution + + Graphics Support ---> + [*] NX Graphics + (1) Number of Color Planes + + (0x0) Initial background color + Supported Pixel Depths ---> + [ ] Disable 1 BPP + [*] Packed MS First + + Font Selections ---> + (7) Bits in Character Set + [*] Mono 5x8 + + Application Configuration ---> + Examples ---> + [*] NX graphics "Hello, World!" example + (1) Bits-Per-Pixel + + After compiling and flashing the nuttx.bin inside the board, reset it. + You should see it: + + NuttShell (NSH) + nsh> ? + help usage: help [-v] [] + + [ dd free mb sh usleep + ? echo help mh sleep xd + cat exec hexdump mw test + cd exit kill pwd true + cp false ls set unset + + Builtin Apps: + nxhello + + Now just run nxhello and you should see "Hello World" in the display: + + nsh> nxhello + USB Console support: ==================== diff --git a/configs/stm32f103-minimum/src/Makefile b/configs/stm32f103-minimum/src/Makefile index 760ac752c7..ff51903c02 100644 --- a/configs/stm32f103-minimum/src/Makefile +++ b/configs/stm32f103-minimum/src/Makefile @@ -81,6 +81,10 @@ ifeq ($(CONFIG_LCD_ST7567),y) CSRCS += stm32_lcd.c endif +ifeq ($(CONFIG_LCD_PCD8544),y) +CSRCS += stm32_pcd8544.c +endif + ifeq ($(CONFIG_QENCODER),y) CSRCS += stm32_qencoder.c endif diff --git a/configs/stm32f103-minimum/src/stm32_pcd8544.c b/configs/stm32f103-minimum/src/stm32_pcd8544.c new file mode 100644 index 0000000000..3093a539b5 --- /dev/null +++ b/configs/stm32f103-minimum/src/stm32_pcd8544.c @@ -0,0 +1,145 @@ +/**************************************************************************** + * config/stm32f103-minimum/src/stm32_pcd8544.c + * + * Copyright (C) 2011, 2013, 2015 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include "stm32_gpio.h" +#include "stm32_spi.h" +#include "stm32f103_minimum.h" + +#ifdef CONFIG_NX_LCDDRIVER + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define LCD_SPI_PORTNO 1 /* On SPI1 */ + +#ifndef CONFIG_LCD_CONTRAST +# define CONFIG_LCD_CONTRAST 60 +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +FAR struct spi_dev_s *g_spidev; +FAR struct lcd_dev_s *g_lcddev; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_lcd_initialize + ****************************************************************************/ + +int board_lcd_initialize(void) +{ + /* Configure the GPIO pins */ + + stm32_configgpio(STM32_LCD_RST); + stm32_configgpio(STM32_LCD_CD); + stm32_gpiowrite(STM32_LCD_RST, 1); + stm32_gpiowrite(STM32_LCD_CD, 1); + + g_spidev = stm32_spibus_initialize(LCD_SPI_PORTNO); + + if (!g_spidev) + { + lcderr("ERROR: Failed to initialize SPI port %d\n", LCD_SPI_PORTNO); + return 0; + } + + stm32_gpiowrite(STM32_LCD_RST, 0); + up_mdelay(10); + stm32_gpiowrite(STM32_LCD_RST, 1); + return 1; +} + +/**************************************************************************** + * Name: board_lcd_getdev + ****************************************************************************/ + +FAR struct lcd_dev_s *board_lcd_getdev(int lcddev) +{ + g_lcddev = pcd8544_initialize(g_spidev, lcddev); + if (!g_lcddev) + { + lcderr("ERROR: Failed to bind SPI port 1 to LCD %d: %d\n", lcddev); + } + else + { + lcdinfo("SPI port 1 bound to LCD %d\n", lcddev); + + /* And turn the LCD on (CONFIG_LCD_MAXPOWER should be 1) */ + + (void)g_lcddev->setpower(g_lcddev, CONFIG_LCD_MAXPOWER); + + /* Set contrast to right value, otherwise background too dark */ + + (void)g_lcddev->setcontrast(g_lcddev, CONFIG_LCD_CONTRAST); + + return g_lcddev; + } + + return NULL; +} + +/**************************************************************************** + * Name: board_lcd_uninitialize + ****************************************************************************/ + +void board_lcd_uninitialize(void) +{ + /* TO-FIX */ +} + +#endif /* CONFIG_NX_LCDDRIVER */ diff --git a/configs/stm32f103-minimum/src/stm32_spi.c b/configs/stm32f103-minimum/src/stm32_spi.c index ceab4e14d6..c2476ebcf1 100644 --- a/configs/stm32f103-minimum/src/stm32_spi.c +++ b/configs/stm32f103-minimum/src/stm32_spi.c @@ -86,6 +86,10 @@ void stm32_spidev_initialize(void) (void)stm32_configgpio(STM32_LCD_CS); /* ST7567 chip select */ #endif +#ifdef CONFIG_LCD_PCD8544 + (void)stm32_configgpio(STM32_LCD_CS); /* ST7567 chip select */ +#endif + #ifdef CONFIG_WL_NRF24L01 stm32_configgpio(GPIO_NRF24L01_CS); /* nRF24L01 chip select */ #endif @@ -138,10 +142,17 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, } #endif +#ifdef CONFIG_LCD_PCD8544 + if (devid == SPIDEV_DISPLAY(0)) + { + stm32_gpiowrite(STM32_LCD_CS, !selected); + } +#endif + #ifdef CONFIG_LCD_ST7567 if (devid == SPIDEV_DISPLAY(0)) { - stm32_gpiowrite(GPIO_CS_MFRC522, !selected); + stm32_gpiowrite(STM32_LCD_CS, !selected); } #endif @@ -236,6 +247,20 @@ int stm32_spi1cmddata(FAR struct spi_dev_s *dev, uint32_t devid, } #endif +#ifdef CONFIG_LCD_PCD8544 + if (devid == SPIDEV_DISPLAY(0)) + { + /* This is the Data/Command control pad which determines whether the + * data bits are data or a command. + */ + + (void)stm32_gpiowrite(STM32_LCD_CD, !cmd); + + return OK; + } +#endif + + return -ENODEV; } #endif diff --git a/configs/stm32f103-minimum/src/stm32f103_minimum.h b/configs/stm32f103-minimum/src/stm32f103_minimum.h index adabdbc3b0..fd592c6507 100644 --- a/configs/stm32f103-minimum/src/stm32f103_minimum.h +++ b/configs/stm32f103-minimum/src/stm32f103_minimum.h @@ -101,6 +101,9 @@ #define STM32_LCD_RS (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\ GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN2) +#define STM32_LCD_CD (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN2) + /* PWN Configuration */ #define STM32F103MINIMUM_PWMTIMER 3 -- GitLab From 889d0151729fa63996a92498fe3479c18f519f7a Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 26 May 2017 08:19:49 -0600 Subject: [PATCH 874/990] Correct typos in a document. --- Documentation/NuttxPortingGuide.html | 78 ++++++++++++++-------------- 1 file changed, 39 insertions(+), 39 deletions(-) diff --git a/Documentation/NuttxPortingGuide.html b/Documentation/NuttxPortingGuide.html index ce18662b6d..01abeba222 100644 --- a/Documentation/NuttxPortingGuide.html +++ b/Documentation/NuttxPortingGuide.html @@ -149,7 +149,7 @@ 4.5.16 up_addrenv_kstackfree()
    4.6 boardctl() Application Interface
    - 4.7 Symmetric Multiprocssing (SMP) Application Interface + 4.7 Symmetric Multiprocessing (SMP) Application Interface
      4.7.1 up_testset()
      4.7.2 up_cpu_index()
      @@ -260,7 +260,7 @@

      Directory Structure. - The general directly layout for NuttX is very similar to the directory structure + The general directory layout for NuttX is very similar to the directory structure of the Linux kernel -- at least at the most superficial layers. At the top level is the main makefile and a series of sub-directories identified below and discussed in the following paragraphs: @@ -423,7 +423,7 @@ Chip/SoC specific files. Each processor processor architecture is embedded in chip or System-on-a-Chip (SoC) architecture. The full chip architecture includes the processor architecture plus chip-specific interrupt logic, - clocking logic, general purpose I/O (GIO) logic, and specialized, internal peripherals (such as UARTs, USB, etc.). + clocking logic, general purpose I/O (GPIO) logic, and specialized, internal peripherals (such as UARTs, USB, etc.).

      These chip-specific files are contained within chip-specific sub-directories in the arch/<arch-name>/ directory and are selected via @@ -908,7 +908,7 @@ config ARCH_BOARD In our case, these files reside in configs/myboard and we add the following to the long list of defaults (again in alphabetical order):

        -    default "myboar"              if ARCH_BOARD_MYBOARD
        +    default "myboard"             if ARCH_BOARD_MYBOARD
         

      Now the build system knows where to find your board configuration! @@ -1011,7 +1011,7 @@ drivers/ |-- spi/ | |-- Kconfig | |-- Make.defs -| `-- (Common SPI-related drivers and helper fuctions) +| `-- (Common SPI-related drivers and helper functions) |-- syslog/ | |-- Kconfig | |-- Make.defs @@ -1141,7 +1141,7 @@ include/ | |-input/ | | `-- (Input device driver header files) | |-ioexpander/ -| | `-- (I/O exander and GPIO drvier header files) +| | `-- (I/O expander and GPIO driver header files) | |-lcd/ | | `-- (LCD driver header files) | |-leds/ @@ -1184,7 +1184,7 @@ include/

      This is a (almost) empty directory that has a holding place for generated static libraries. - The NuttX build system generates a collection of such static libraries in this directory during the compile phaase. + The NuttX build system generates a collection of such static libraries in this directory during the compile phase. These libraries are then in a known place for the final link phase where they are accessed to generated the final binaries.

      @@ -1309,7 +1309,7 @@ tools/ |-- cnvwindeps.c |-- copydir.sh / copydir.bat |-- define.sh / define.bat -|-- incdir.sh / indir.bat +|-- incdir.sh / incdir.bat |-- indent.sh |-- link.sh / link.bat |-- mkconfig.c @@ -2137,7 +2137,7 @@ else
      Most MCUs include RTC hardware built into the chip. Other RTCs, external MCUs, may be provided as separate chips typically interfacing with the MCU via a serial interface such as SPI or I2C. - These external RTCs differ from the builtin RTCs in that they cannot be initialized + These external RTCs differ from the built-in RTCs in that they cannot be initialized until the operating system is fully booted and can support the required serial communications. CONFIG_RTC_EXTERNAL will configure the operating system so that it defers initialization of its time facilities. @@ -2165,7 +2165,7 @@ else

      • up_rtc_initialize(). - Initialize the builtin, MCU hardware RTC per the selected configuration. + Initialize the built-in, MCU hardware RTC per the selected configuration. This function is called once very early in the OS initialization sequence. NOTE that initialization of external RTC hardware that depends on the availability of OS resources (such as SPI or I2C) must be deferred @@ -2309,14 +2309,14 @@ config ARCH_SIM
      -

      4.3.4.4 Tickless Imported Intefaces

      +

      4.3.4.4 Tickless Imported Interfaces

      The interfaces that must be provided by the platform specified code are defined in include/nuttx/arch.h, listed below, and summarized in the following paragraphs:

      • <arch>_timer_initialize(): - Initializes the timer facilities. Called early in the intialization sequence (by up_intialize()). + Initializes the timer facilities. Called early in the initialization sequence (by up_initialize()).
      • up_timer_gettime(): @@ -2336,7 +2336,7 @@ config ARCH_SIM
      • up_alarm_start(): - Enables (or re-enables) the alaram. + Enables (or re-enables) the alarm.

      @@ -2379,7 +2379,7 @@ void <arch>_timer_initialize()(void);

    Description:

      - Initializes all platform-specific timer facilities. This function is called early in the initialization sequence by up_intialize(). On return, the current up-time should be available from up_timer_gettime() and the interval timer is ready for use (but not actively timing). + Initializes all platform-specific timer facilities. This function is called early in the initialization sequence by up_initialize(). On return, the current up-time should be available from up_timer_gettime() and the interval timer is ready for use (but not actively timing).

    Input Parameters:

      @@ -2438,7 +2438,7 @@ int up_alarm_cancel(FAR struct timespec *ts);

    Assumptions:

      - May be called from interrupt level handling or from the normal tasking level. iterrupts may need to be disabled internally to assure non-reentrancy. + May be called from interrupt level handling or from the normal tasking level. interrupts may need to be disabled internally to assure non-reentrancy.
    4.3.4.4.4 up_alarm_start()
    @@ -2448,7 +2448,7 @@ int up_alarm_cancel(FAR struct timespec *ts); int up_alarm_start(FAR const struct timespec *ts);

    Description:

    - Start the alarm. sched_timer_expiration() will be called when the alarm occurs (unless up_alaram_cancel is called to stop it). + Start the alarm. sched_timer_expiration() will be called when the alarm occurs (unless up_alarm_cancel is called to stop it).

    Input Parameters:

    @@ -2484,7 +2484,7 @@ int up_timer_cancel(FAR struct timespec *ts);

    Assumptions:

      - May be called from interrupt level handling or from the normal tasking level. iterrupts may need to be disabled internally to assure non-reentrancy. + May be called from interrupt level handling or from the normal tasking level. interrupts may need to be disabled internally to assure non-reentrancy.
    4.3.4.4.6 up_timer_start()
    @@ -2712,7 +2712,7 @@ VxWorks provides the following comparable interface:

         #include <nuttx/wdog.h>
    -    Sint wd_gettime(WDOG_ID wdog);
    +    int wd_gettime(WDOG_ID wdog);
     

    Description: @@ -2787,7 +2787,7 @@ typedef uint32_t wdparm_t;

    • CONFIG_SCHED_HPWORK. - Enables the hight prioirity work queue. + Enables the hight priority work queue.
    • CONFIG_SCHED_HPWORKPRIORITY. The execution priority of the high-priority worker thread. Default: 224 @@ -2815,7 +2815,7 @@ typedef uint32_t wdparm_t;

      Compared to the High Priority Work Queue. - The lower priority work queue runs at a lower priority than the high priority work queue, of course, and so is inapproperiate to serve as a driver bottom half. The lower priority work queue has the other advantages, however, that make it better suited for some tasks: + The lower priority work queue runs at a lower priority than the high priority work queue, of course, and so is inappropriate to serve as a driver bottom half. The lower priority work queue has the other advantages, however, that make it better suited for some tasks:

      • @@ -2925,7 +2925,7 @@ typedef uint32_t wdparm_t;
      • struct work_s. - Defines one entry in the work queue. This is a client-allocated structure. Work queue clients should not reference any field in this structure since they are subjec to change. The user only needs this structure in order to declare instances of the work structure. Handling of all fields is performed by the work queue interfaces described below. + Defines one entry in the work queue. This is a client-allocated structure. Work queue clients should not reference any field in this structure since they are subject to change. The user only needs this structure in order to declare instances of the work structure. Handling of all fields is performed by the work queue interfaces described below.
      @@ -3185,7 +3185,7 @@ void lpwork_restorepriority(uint8_t reqprio);

      CPUs that support memory management units (MMUs) may provide address environments within which tasks and their child threads execute. The configuration indicates the CPUs ability to support address environments by setting the configuration variable CONFIG_ARCH_HAVE_ADDRENV=y. - That will enable the selection of the actual address evironment support which is indicated by the selection of the configuration variable CONFIG_ARCH_ADDRENV=y. + That will enable the selection of the actual address environment support which is indicated by the selection of the configuration variable CONFIG_ARCH_ADDRENV=y. These address environments are created only when tasks are created via exec() or exec_module() (see include/nuttx/binfmt/binfmt.h).

      @@ -3697,7 +3697,7 @@ void lpwork_restorepriority(uint8_t reqprio); -1 (ERROR) is returned on failure with the errno variable to to indicate the nature of the failure.

    -

    4.7 Symmetric Multiprocssing (SMP) Application Interface

    +

    4.7 Symmetric Multiprocessing (SMP) Application Interface

    According to Wikipedia: "Symmetric multiprocessing (SMP) involves a symmetric multiprocessor system hardware and software architecture where two or more identical processors connect to a single, shared main memory, have full access to all I/O devices, and are controlled by a single operating system instance that treats all processors equally, reserving none for special purposes. Most multiprocessor systems today use an SMP architecture. In the case of multi-core processors, the SMP architecture applies to the cores, treating them as separate processors.

    @@ -3780,7 +3780,7 @@ int up_cpu_start(int cpu);

    Description:

      - In an SMP configution, only one CPU is initially active (CPU 0). + In an SMP configuration, only one CPU is initially active (CPU 0). System initialization occurs on that single thread. At the completion of the initialization of the OS, just before beginning normal multitasking, the additional CPUs would be started by calling this function.

      @@ -3926,7 +3926,7 @@ void sched_timer_expiration(void); Base code implementation assumes that this function is called from interrupt handling logic with interrupts disabled.
    -

    4.8.5 sched_alaram_expiration()

    +

    4.8.5 sched_alarm_expiration()

    Function Prototype:

       #include <nuttx/arch.h>
      @@ -4156,11 +4156,11 @@ void board_autoled_off(int led);
         
      NOTE: In most architectures, board_autoled_initialize() is called from board-specific initialization logic. But there are a few architectures where this initialization function is still called from common chip architecture logic. - This interface is nott, however, a common board interface in any event. + This interface is not, however, a common board interface in any event.
      WARNING: This interface name will eventually be removed; do not use it in new board ports. - New implementations should not use the naming convention for common board interfaces, but should instted use the naming conventions for microprocessor-specific interfaces or the board-specific interfaces (such as stm32_led_initialize()). + New implementations should not use the naming convention for common board interfaces, but should instead use the naming conventions for microprocessor-specific interfaces or the board-specific interfaces (such as stm32_led_initialize()).
    • @@ -4235,12 +4235,12 @@ This objectives of this feature are:
      CONFIG_IOB_THROTTLE
      I/O buffer throttle value. TCP write buffering and read-ahead buffer use the same pool of free I/O buffers. In order to prevent uncontrolled incoming TCP packets from hogging all of the available, pre-allocated I/O buffers, a throttling value is required. This throttle value assures that I/O buffers will be denied to the read-ahead logic before TCP writes are halted. - The default 0 if neither TCP write buffering nor TCP reada-ahead buffering is enabled. Otherwise, the default is 8. + The default 0 if neither TCP write buffering nor TCP read-ahead buffering is enabled. Otherwise, the default is 8.
      CONFIG_IOB_DEBUG
      Force I/O buffer debug. This option will force debug output from I/O buffer logic. This is not normally something that would want to do but is convenient if you are debugging the I/O buffer logic and do not want to get overloaded with other un-related debug output. - NOTE that this selection is not avaiable if DEBUG features are not enabled (CONFIG_DEBUG_FEATURES) with IOBs are being used to syslog buffering logic (CONFIG_SYSLOG_BUFFER). + NOTE that this selection is not available if DEBUG features are not enabled (CONFIG_DEBUG_FEATURES) with IOBs are being used to syslog buffering logic (CONFIG_SYSLOG_BUFFER).

      4.12.2 Throttling

      @@ -4251,7 +4251,7 @@ An allocation throttle was added. I/O buffer allocation logic supports a thrott

      4.12.3 Public Types

      - This structure epresents one I/O buffer. A packet is contained by one or more I/O buffers in a chain. The io_pktlen is only valid for the I/O buffer at the head of the chain. + This structure represents one I/O buffer. A packet is contained by one or more I/O buffers in a chain. The io_pktlen is only valid for the I/O buffer at the head of the chain.

      @@ -6116,7 +6116,7 @@ int setlogmask(int mask);
         
    • - Kernel Build: The kernel build is compliant with the POSIX requirement: There will be one mask for for each user process, controlling the SYSLOG output only form that process. There will be a separate mask accessable only in the kernel code to control kernel SYSLOG output. + Kernel Build: The kernel build is compliant with the POSIX requirement: There will be one mask for for each user process, controlling the SYSLOG output only form that process. There will be a separate mask accessible only in the kernel code to control kernel SYSLOG output.

    The above are all standard interfaces as defined at OpenGroup.org. Those interfaces are available for use by application software. The remaining interfaces discussed in this section are non-standard, OS-internal interfaces. @@ -6124,7 +6124,7 @@ int setlogmask(int mask);

    6.4.1.4 Debug Interfaces

    - In NuttX, syslog output is really synonymous to debug output and, herefore, the debugging interface macros defined in the header file + In NuttX, syslog output is really synonymous to debug output and, therefore, the debugging interface macros defined in the header file include/debug.h are also syslogging interfaces. Those macros are simply wrappers around syslog(). The debugging interfaces differ from the syslog interfaces in that:

      @@ -6158,7 +6158,7 @@ int setlogmask(int mask);
    • warn(). The warn() macro has medium priority (LOG_WARN) and is controlled by CONFIG_DEBUG_subsystem_WARN. The warn() is intended to - note exceptional or unexpected conditions that meigh be potential + note exceptional or unexpected conditions that might be potential errors or, perhaps, minor errors that easily recovered.

    • @@ -6210,7 +6210,7 @@ int syslog_channel(FAR const struct syslog_channel_s *channel); syslog_channel() is a non-standard, internal OS interface and is not available to applications. It may be called numerous times as necessary to change channel interfaces. By default, all system log output goes to console (/dev/console).

      -

      Input Parmeters: +

      Input Parameters:

      • @@ -6331,7 +6331,7 @@ int syslog_initialize(enum syslog_init_e phase);

      • - The output generated by up_putc() is immediate and in real-time. The normal SYSLOG output, on the other hand, is buffered in the serial driver and may be delayed with respect to the immediate output by many lines. Therefore, the interrupt level SYSLOG ouput provided throug up_putc() is grossly out of synchronization with other debug output + The output generated by up_putc() is immediate and in real-time. The normal SYSLOG output, on the other hand, is buffered in the serial driver and may be delayed with respect to the immediate output by many lines. Therefore, the interrupt level SYSLOG output provided through up_putc() is grossly out of synchronization with other debug output

      @@ -6383,7 +6383,7 @@ int syslog_initialize(enum syslog_init_e phase);
    • - CONFIG_SYSLOG_CONSOLE. This configuration option is manually selected from the SYSLOG menu. This is the option that acutally enables the SYSLOG console device. It depends on CONFIG_DEV_CONSOLE and it will automatically select CONFIG_SYSLOG_SERIAL_CONSOLE if CONFIG_SERIAL_CONSOLE is selected. + CONFIG_SYSLOG_CONSOLE. This configuration option is manually selected from the SYSLOG menu. This is the option that actually enables the SYSLOG console device. It depends on CONFIG_DEV_CONSOLE and it will automatically select CONFIG_SYSLOG_SERIAL_CONSOLE if CONFIG_SERIAL_CONSOLE is selected.

    • @@ -6412,7 +6412,7 @@ int syslog_initialize(enum syslog_init_e phase); The system console device, /dev/console, is a character driver with some special properties. However, any character driver may be used as the SYSLOG output channel. For example, suppose you have a serial console on /dev/ttyS0 and you want SYSLOG output on /dev/ttyS1. Or suppose you support only a Telnet console but want to capture debug output /dev/ttyS0.

      - This SYSLOG device channel is selected with CONFIG_SYSLOG_CHAR and has no other dependencies. Differences fromthe SYSLOG console channel include: + This SYSLOG device channel is selected with CONFIG_SYSLOG_CHAR and has no other dependencies. Differences from the SYSLOG console channel include:

      • @@ -6564,7 +6564,7 @@ int syslog_file_channel(FAR const char *devpath);
        • - Monitors activity from drivers (and from other parts of the syste), and + Monitors activity from drivers (and from other parts of the system), and

        • @@ -6615,7 +6615,7 @@ int syslog_file_channel(FAR const char *devpath); however, IDLE and some simple simple steps to reduce power consumption provided that they do not interfere with normal Operation. Simply dimming the a backlight might be an example - somethat that would be done when the system is idle. + some that that would be done when the system is idle.
          STANDBY
          Standby is a lower power consumption mode that may involve more extensive power management steps such has disabling clocking or -- GitLab From 96e1a80f99c42fb81731645b24bdfb0408f0cf00 Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Fri, 26 May 2017 11:36:36 -0300 Subject: [PATCH 875/990] Replace the structure initializer with C89 style --- drivers/lcd/pcd8544.c | 39 ++++++++++++++++++++++++--------------- 1 file changed, 24 insertions(+), 15 deletions(-) diff --git a/drivers/lcd/pcd8544.c b/drivers/lcd/pcd8544.c index 1e8f0e2f3b..c5d3c86fa1 100644 --- a/drivers/lcd/pcd8544.c +++ b/drivers/lcd/pcd8544.c @@ -291,42 +291,51 @@ static uint8_t g_runbuffer[PCD8544_XSTRIDE+1]; static const struct fb_videoinfo_s g_videoinfo = { - .fmt = PCD8544_COLORFMT, /* Color format: RGB16-565: RRRR RGGG GGGB BBBB */ - .xres = PCD8544_XRES, /* Horizontal resolution in pixel columns */ - .yres = PCD8544_YRES, /* Vertical resolution in pixel rows */ - .nplanes = 1, /* Number of color planes supported */ + PCD8544_COLORFMT, /* Color format: RGB16-565: RRRR RGGG GGGB BBBB */ + PCD8544_XRES, /* Horizontal resolution in pixel columns */ + PCD8544_YRES, /* Vertical resolution in pixel rows */ + 1, /* Number of color planes supported */ }; /* This is the standard, NuttX Plane information object */ static const struct lcd_planeinfo_s g_planeinfo = { - .putrun = pcd8544_putrun, /* Put a run into LCD memory */ - .getrun = pcd8544_getrun, /* Get a run from LCD memory */ - .buffer = (FAR uint8_t *)g_runbuffer, /* Run scratch buffer */ - .bpp = PCD8544_BPP, /* Bits-per-pixel */ + pcd8544_putrun, /* Put a run into LCD memory */ + pcd8544_getrun, /* Get a run from LCD memory */ + (FAR uint8_t *)g_runbuffer, /* Run scratch buffer */ + PCD8544_BPP, /* Bits-per-pixel */ }; /* This is the standard, NuttX LCD driver object */ static struct pcd8544_dev_s g_pcd8544dev = { - .dev = + /* struct lcd_dev_s */ { /* LCD Configuration */ - .getvideoinfo = pcd8544_getvideoinfo, - .getplaneinfo = pcd8544_getplaneinfo, + pcd8544_getvideoinfo, + pcd8544_getplaneinfo, /* LCD RGB Mapping -- Not supported */ +#ifdef CONFIG_FB_CMAP + NULL, + NULL, +#endif + /* Cursor Controls -- Not supported */ +#ifdef CONFIG_FB_HWCURSOR + NULL, + NULL, +#endif /* LCD Specific Controls */ - .getpower = pcd8544_getpower, - .setpower = pcd8544_setpower, - .getcontrast = pcd8544_getcontrast, - .setcontrast = pcd8544_setcontrast, + pcd8544_getpower, + pcd8544_setpower, + pcd8544_getcontrast, + pcd8544_setcontrast, }, }; -- GitLab From ef53800fa921a433a347718eeff6a768526c3e07 Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Fri, 26 May 2017 11:38:17 -0300 Subject: [PATCH 876/990] remove pcd8544_power() comment, this function doesn't exist for this driver --- include/nuttx/lcd/pcd8544.h | 19 ------------------- 1 file changed, 19 deletions(-) diff --git a/include/nuttx/lcd/pcd8544.h b/include/nuttx/lcd/pcd8544.h index 2437274b54..42458cfd93 100644 --- a/include/nuttx/lcd/pcd8544.h +++ b/include/nuttx/lcd/pcd8544.h @@ -122,25 +122,6 @@ struct lcd_dev_s; /* see nuttx/lcd.h */ struct spi_dev_s; /* see nuttx/spi/spi.h */ FAR struct lcd_dev_s *pcd8544_initialize(FAR struct spi_dev_s *spi, unsigned int devno); -/**************************************************************************** - * Name: pcd8544_power - * - * Description: - * If the hardware supports a controllable LCD a power supply, this - * interface should be provided. It may be called by the driver to turn - * the LCD power on and off as needed. - * - * Input Parameters: - * - * devno - A value in the range of 0 throuh CONFIG_PCD8544_NINTERFACES-1. - * This allows support for multiple LCD devices. - * on - true:turn power on, false: turn power off. - * - * Returned Value: - * None - * - **************************************************************************************/ - #ifdef __cplusplus } #endif -- GitLab From e9c55d8f7d4981043aaa3a21ac020da627d554f2 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 27 May 2017 08:03:00 -0600 Subject: [PATCH 877/990] IOBs: Fix a typing error mm/iob/iob.h mm/iob/iob_initialize.c --- mm/iob/iob.h | 2 +- mm/iob/iob_initialize.c | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/mm/iob/iob.h b/mm/iob/iob.h index 9f43612d71..855c5fd1ab 100644 --- a/mm/iob/iob.h +++ b/mm/iob/iob.h @@ -102,7 +102,7 @@ extern FAR struct iob_qentry_s *g_iob_freeqlist; /* A list of I/O buffer queue containers that are committed for allocation */ -extern FAR struct iob_s *g_iob_qcommitted; +extern FAR struct iob_qentry_s *g_iob_qcommitted; #endif /* Counting semaphores that tracks the number of free IOBs/qentries */ diff --git a/mm/iob/iob_initialize.c b/mm/iob/iob_initialize.c index adab03c228..b11d2f005c 100644 --- a/mm/iob/iob_initialize.c +++ b/mm/iob/iob_initialize.c @@ -84,7 +84,7 @@ FAR struct iob_qentry_s *g_iob_freeqlist; /* A list of I/O buffer queue containers that are committed for allocation */ -FAR struct iob_s *g_iob_qcommitted; +FAR struct iob_qentry_s *g_iob_qcommitted; #endif /* Counting semaphores that tracks the number of free IOBs/qentries */ -- GitLab From e71472b50868436170c09eb9fc6ac5a017c46b9f Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 27 May 2017 08:04:02 -0600 Subject: [PATCH 878/990] PIC32MX7MMB: add support for the Pinquino toolchain --- configs/mirtoo/README.txt | 4 +- configs/pic32mx7mmb/nsh/Make.defs | 20 +- .../{nsh/ld.script => scripts/c32-release.ld} | 2 +- configs/pic32mx7mmb/scripts/mips-release.ld | 317 ++++++++++++++++++ 4 files changed, 338 insertions(+), 5 deletions(-) rename configs/pic32mx7mmb/{nsh/ld.script => scripts/c32-release.ld} (99%) create mode 100644 configs/pic32mx7mmb/scripts/mips-release.ld diff --git a/configs/mirtoo/README.txt b/configs/mirtoo/README.txt index 29510b353a..aa38249e43 100644 --- a/configs/mirtoo/README.txt +++ b/configs/mirtoo/README.txt @@ -457,8 +457,8 @@ Toolchains Loading NuttX with ICD3 ======================== - Intel Hex Forma Files: - ---------------------- + Intel Hex Format Files: + ----------------------- When NuttX is built it will produce two files in the top-level NuttX directory: diff --git a/configs/pic32mx7mmb/nsh/Make.defs b/configs/pic32mx7mmb/nsh/Make.defs index 5c3e08f7ec..31afe6e928 100644 --- a/configs/pic32mx7mmb/nsh/Make.defs +++ b/configs/pic32mx7mmb/nsh/Make.defs @@ -37,6 +37,22 @@ include ${TOPDIR}/.config include ${TOPDIR}/tools/Config.mk include ${TOPDIR}/arch/mips/src/mips32/Toolchain.defs +ifeq ($(CONFIG_MIPS32_TOOLCHAIN_GNU_ELF),y) +LDSCRIPT = mips-release.ld +endif + +ifeq ($(CONFIG_MIPS32_TOOLCHAIN_PINGUINOW),y) +LDSCRIPT = mips-release.ld +endif + +ifeq ($(CONFIG_MIPS32_TOOLCHAIN_MICROCHIPW),y) +LDSCRIPT = c32-release.ld +endif + +ifeq ($(CONFIG_MIPS32_TOOLCHAIN_MICROCHIPW_LITE),y) +LDSCRIPT = c32-release.ld +endif + ifeq ($(WINTOOL),y) # Windows-native toolchains DIRLINK = $(TOPDIR)/tools/copydir.sh @@ -44,13 +60,13 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mkwindeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" - ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nsh/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" else # Linux/Cygwin-native toolchain MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT) ARCHINCLUDES = -I. -isystem $(TOPDIR)/include ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx - ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nsh/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) endif CC = $(CROSSDEV)gcc diff --git a/configs/pic32mx7mmb/nsh/ld.script b/configs/pic32mx7mmb/scripts/c32-release.ld similarity index 99% rename from configs/pic32mx7mmb/nsh/ld.script rename to configs/pic32mx7mmb/scripts/c32-release.ld index f6ec304c3e..2dc792d511 100644 --- a/configs/pic32mx7mmb/nsh/ld.script +++ b/configs/pic32mx7mmb/scripts/c32-release.ld @@ -1,5 +1,5 @@ /**************************************************************************** - * configs/pic32mx7mmb/nsh/ld.script + * configs/pic32mx7mmb/scripts/c32-release.ld * * Copyright (C) 2012 Gregory Nutt. All rights reserved. * Author: Gregory Nutt diff --git a/configs/pic32mx7mmb/scripts/mips-release.ld b/configs/pic32mx7mmb/scripts/mips-release.ld new file mode 100644 index 0000000000..3fcce7dec7 --- /dev/null +++ b/configs/pic32mx7mmb/scripts/mips-release.ld @@ -0,0 +1,317 @@ +/**************************************************************************** + * configs/pic32mx7mmb/scripts/mips-release.ld + * + * Copyright (C) 2012 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. + * + ****************************************************************************/ +/* Memory Regions ***********************************************************/ + +MEMORY +{ + /* The PIC32MX795F512L has 512Kb of program FLASH at physical address + * 0x1d000000 but is always accessed at KSEG0 address 0x9d00:0000 + */ + + kseg0_progmem (rx) : ORIGIN = 0x9d000000, LENGTH = 512K + + /* The PIC32MX795F512L has 12Kb of boot FLASH at physical address + * 0x1fc00000. The initial reset vector is in KSEG1, but all other + * accesses are in KSEG0. + * + * REGION PHYSICAL KSEG SIZE + * DESCRIPTION START ADDR (BYTES) + * ------------- ---------- ------ ---------------------- + * Exceptions:* + * Reset 0x1fc00000 KSEG1 512 512 + * TLB Refill 0x1fc00200 KSEG1 256 768 + * Cache Error 0x1fc00300 KSEG1 128 896 + * Others 0x1fc00380 KSEG1 128 1024 (1Kb) + * Interrupt 0x1fc00400 KSEG1 128 1152 + * JTAG 0x1fc00480 KSEG1 16 1168 + * Exceptions 0x1fc00490 KSEG0 8192-1168 8192 (4Kb) + * Debug code 0x1fc02000 KSEG1 4096-16 12272 + * DEVCFG3-0 0x1fc02ff0 KSEG1 16 12288 (12Kb) + * + * Exceptions assume: + * + * STATUS: BEV=0/1 and EXL=0 + * CAUSE: IV=1 + * JTAG: ProbEn=0 + * And multi-vector support disabled + */ + + kseg1_reset (rx) : ORIGIN = 0xbfc00000, LENGTH = 384 + kseg1_genexcpt (rx) : ORIGIN = 0xbfc00180, LENGTH = 128 + kseg1_ebexcpt (rx) : ORIGIN = 0xbfc00200, LENGTH = 128 + kseg1_bevexcpt (rx) : ORIGIN = 0xbfc00380, LENGTH = 128 + kseg1_intexcpt (rx) : ORIGIN = 0xbfc00400, LENGTH = 128 + kseg1_dbgexcpt (rx) : ORIGIN = 0xbfc00480, LENGTH = 16 + kseg0_bootmem (rx) : ORIGIN = 0x9fc00490, LENGTH = 8192-1168 + kseg1_dbgcode (rx) : ORIGIN = 0xbfc02000, LENGTH = 4096-16 + kseg1_devcfg (r) : ORIGIN = 0xbfc02ff0, LENGTH = 16 + + /* The PIC32MX795F512L has 128Kb of data memory at physical address + * 0x00000000. Since the PIC32MX has no data cache, this memory is + * always accessed through KSEG1. + * + * When used with MPLAB, we need to set aside 512 bytes of memory + * for use by MPLAB. + */ + + kseg1_datamem (w!x) : ORIGIN = 0xa0000200, LENGTH = 128K - 512 +} + +OUTPUT_FORMAT("elf32-littlemips") +OUTPUT_ARCH(mips) +ENTRY(__start) + +SECTIONS +{ + /* Boot FLASH sections */ + + .reset : + { + KEEP (*(.reset)) + } > kseg1_reset + + /* Exception handlers. The following is assumed: + * + * STATUS: BEV=1 and EXL=0 + * CAUSE: IV=1 + * JTAG: ProbEn=0 + * And multi-vector support disabled + * + * In that configuration, the vector locations become: + * + * Reset, Soft Reset bfc0:0000 + * TLB Refill bfc0:0200 + * Cache Error bfc0:0300 + * All others bfc0:0380 + * Interrupt bfc0:0400 + * EJTAG Debug bfc0:0480 + */ + + /* KSEG1 exception handler "trampolines" */ + + .gen_excpt : + { + KEEP (*(.gen_excpt)) + } > kseg1_genexcpt + + .ebase_excpt : + { + KEEP (*(.ebase_excpt)) + } > kseg1_ebexcpt + + .bev_excpt : + { + KEEP (*(.bev_excpt)) + } > kseg1_bevexcpt + + .int_excpt : + { + KEEP (*(.int_excpt)) + } > kseg1_intexcpt + + .dbg_excpt = ORIGIN(kseg1_dbgexcpt); + + .start : + { + /* KSEG0 Reset startup logic */ + + *(.start) + + /* KSEG0 exception handlers */ + + *(.nmi_handler) + *(.bev_handler) + *(.int_handler) + } > kseg0_bootmem + + .dbg_code = ORIGIN(kseg1_dbgcode); + + .devcfg : + { + KEEP (*(.devcfg)) + } > kseg1_devcfg + + /* Program FLASH sections */ + + .text : + { + _stext = ABSOLUTE(.); + *(.text .text.*) + *(.stub) + KEEP (*(.text.*personality*)) + *(.gnu.linkonce.t.*) + *(.gnu.warning) + *(.mips16.fn.*) + *(.mips16.call.*) + + /* Read-only data is included in the text section */ + + *(.rodata .rodata.*) + *(.rodata1) + *(.gnu.linkonce.r.*) + + /* Small initialized constant global and static data */ + + *(.sdata2 .sdata2.*) + *(.gnu.linkonce.s2.*) + + /* Uninitialized constant global and static data */ + + *(.sbss2 .sbss2.*) + *(.gnu.linkonce.sb2.*) + _etext = ABSOLUTE(.); + } > kseg0_progmem + + /* Initialization data begins here in progmem */ + + _data_loaddr = LOADADDR(.data); + + .eh_frame_hdr : { *(.eh_frame_hdr) } + .eh_frame : ONLY_IF_RO { KEEP (*(.eh_frame)) } + + /* RAM functions are positioned at the beginning of RAM so that + * they can be guaranteed to satisfy the 2Kb alignment requirement. + */ + +/* This causes failures if there are no RAM functions + .ramfunc ALIGN(2K) : + { + _sramfunc = ABSOLUTE(.); + *(.ramfunc .ramfunc.*) + _eramfunc = ABSOLUTE(.); + } > kseg1_datamem AT > kseg0_progmem + + _ramfunc_loadaddr = LOADADDR(.ramfunc); + _ramfunc_sizeof = SIZEOF(.ramfunc); + _bmxdkpba_address = _sramfunc - ORIGIN(kseg1_datamem) ; + _bmxdudba_address = LENGTH(kseg1_datamem) ; + _bmxdupba_address = LENGTH(kseg1_datamem) ; +*/ + + .data : + { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + KEEP (*(.gnu.linkonce.d.*personality*)) + *(.data1) + } > kseg1_datamem AT > kseg0_progmem + + .eh_frame : ONLY_IF_RW { KEEP (*(.eh_frame)) } + _gp = ALIGN(16) + 0x7FF0 ; + + .got : + { + *(.got.plt) *(.got) + } > kseg1_datamem AT > kseg0_progmem + + .sdata : + { + *(.sdata .sdata.* .gnu.linkonce.s.*) + } > kseg1_datamem AT > kseg0_progmem + + .lit8 : + { + *(.lit8) + } > kseg1_datamem AT > kseg0_progmem + + .lit4 : + { + *(.lit4) + _edata = ABSOLUTE(.); + } >kseg1_datamem AT>kseg0_progmem + + .sbss : + { + _sbss = ABSOLUTE(.); + *(.dynsbss) + *(.sbss .sbss.* .gnu.linkonce.sb.*) + *(.scommon) + } >kseg1_datamem + + .bss : + { + *(.dynbss) + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + _ebss = ABSOLUTE(.); + } > kseg1_datamem + + /* Stabs debugging sections */ + + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + + /* DWARF debug sections */ + /* DWARF 1 */ + + .debug 0 : { *(.debug) } + .line 0 : { *(.line) } + + /* GNU DWARF 1 extensions */ + + .debug_srcinfo 0 : { *(.debug_srcinfo) } + .debug_sfnames 0 : { *(.debug_sfnames) } + + /* DWARF 1.1 and DWARF 2 */ + + .debug_aranges 0 : { *(.debug_aranges) } + .debug_pubnames 0 : { *(.debug_pubnames) } + + /* DWARF 2 */ + + .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_line 0 : { *(.debug_line) } + .debug_frame 0 : { *(.debug_frame) } + .debug_str 0 : { *(.debug_str) } + .debug_loc 0 : { *(.debug_loc) } + .debug_macinfo 0 : { *(.debug_macinfo) } + + /* SGI/MIPS DWARF 2 extensions */ + + .debug_weaknames 0 : { *(.debug_weaknames) } + .debug_funcnames 0 : { *(.debug_funcnames) } + .debug_typenames 0 : { *(.debug_typenames) } + .debug_varnames 0 : { *(.debug_varnames) } + + /DISCARD/ : { *(.note.GNU-stack) } +} -- GitLab From 90680e28d40e4f5c86beab4fdde9763bab8ebf4f Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 27 May 2017 09:11:50 -0600 Subject: [PATCH 879/990] PIC32MX7MMB: Repartition files to match newer configurations. Add support for PROCFS file system. Default is now Pinguino toolchain. Verifty networking. --- configs/pic32mx7mmb/README.txt | 57 ++-- configs/pic32mx7mmb/nsh/defconfig | 51 +++- configs/pic32mx7mmb/src/Makefile | 2 +- configs/pic32mx7mmb/src/pic32_appinit.c | 345 ++---------------------- configs/pic32mx7mmb/src/pic32_boot.c | 25 +- configs/pic32mx7mmb/src/pic32mx7mmb.h | 18 +- 6 files changed, 131 insertions(+), 367 deletions(-) diff --git a/configs/pic32mx7mmb/README.txt b/configs/pic32mx7mmb/README.txt index b3b5d7400d..db8e5b4603 100644 --- a/configs/pic32mx7mmb/README.txt +++ b/configs/pic32mx7mmb/README.txt @@ -149,17 +149,19 @@ PIN CONFIGURATIONS SIGNAL NAME ON-BOARD CONNE Toolchains ========== - MPLAB/C32 - --------- + Pinguino mips-elf Toolchain + --------------------------- - I am using the free, "Lite" version of the PIC32MX toolchain available - for download from the microchip.com web site. I am using the Windows - version. The MicroChip toolchain is the only toolchain currently - supported in these configurations, but it should be a simple matter to - adapt to other toolchains by modifying the Make.defs file include in - each configuration. + These configurations currently assume the mips-elf toolchain used with the + Pinguino project. This is a relatively current mips-elf GCC and should + provide free C++ support as well. This toolchain can be downloded from the + Pinguino website: http://wiki.pinguino.cc/index.php/Main_Page#Download . + There is some general information about using the Pinguino mips-elf + toolchain in this thread: + https://groups.yahoo.com/neo/groups/nuttx/conversations/messages/1821 - C32 Toolchain Options: + It should be a simple matter to adapt to other toolchains by modifying the + Make.defs file include ineach configuration. CONFIG_MIPS32_TOOLCHAIN_MICROCHIPW - MicroChip full toolchain for Windows CONFIG_MIPS32_TOOLCHAIN_MICROCHIPL - MicroChip full toolchain for Linux @@ -170,6 +172,14 @@ Toolchains CONFIG_MIPS32_TOOLCHAIN_MICROCHIPOPENL - Microchip open toolchain for Linux CONFIG_MIPS32_TOOLCHAIN_GNU_ELF - General mips-elf toolchain for Linux + MPLAB/C32 + --------- + + Previously, I did use the old, obsoleted "Lite" version of the PIC32MX C32 + toolchain that was available for download from the microchip.com web site. + That MicroChip toolchain is the only Microchip toolchain currently supported + in these configurations. + NOTE: The "Lite" versions of the toolchain does not support C++. Also certain optimization levels are not supported by the "Lite" toolchain. @@ -200,26 +210,12 @@ Toolchains Note that the tools will have the prefix, mypic32- so, for example, the compiler will be called mypic32-gcc. - Pinguino mips-elf Toolchain - --------------------------- - - Another option is the mips-elf toolchain used with the Pinguino project. This - is a relatively current mips-elf GCC and should provide free C++ support as - well. This toolchain can be downloded from the Pinguino website: - http://wiki.pinguino.cc/index.php/Main_Page#Download . There is some general - information about using the Pinguino mips-elf toolchain in this thread: - https://groups.yahoo.com/neo/groups/nuttx/conversations/messages/1821 - - See also configs/mirtoo/README.txt. There is an experimental (untested) - configuration for the Mirtoo platform in that directory. - MPLAB/C32 vs MPLABX/X32 ----------------------- - It appears that Microchip is phasing out the MPLAB/C32 toolchain and replacing - it with MPLABX and XC32. At present, the XC32 toolchain is *not* compatible - with the NuttX build scripts. Here are some of the issues that I see when trying - to build with XC32: + Microchip has phased out the MPLAB/C32 toolchain and replacingit with MPLABX and + XC32. At present, the XC32 toolchain is *not* supported for this configuration. + Here are some of the issues that I see when trying to build with XC32: 1) Make.def changes: You have to change the tool prefix: @@ -238,6 +234,15 @@ Toolchains information. You will have to solve at least this undefined symbol problem if you want to used the XC32 toolchain. + Update: There have since been several successful uses of XC32 toolchains with + NuttX. XC32 is still not supported for this board, but you can see the README.txt + file and usage in other PIC32 configurations: + + $ find . -name xc32-* + ./mirtoo/scripts/xc32-debug.ld + ./mirtoo/scripts/xc32-release.ld + ./pic32mz-starterkit/scripts/xc32-debug.ld + Windows Native Toolchains ------------------------- diff --git a/configs/pic32mx7mmb/nsh/defconfig b/configs/pic32mx7mmb/nsh/defconfig index 4951d6041e..e2164c01ca 100644 --- a/configs/pic32mx7mmb/nsh/defconfig +++ b/configs/pic32mx7mmb/nsh/defconfig @@ -34,6 +34,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set # CONFIG_RAW_BINARY is not set # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -96,8 +97,8 @@ CONFIG_ARCH_MIPS_24KC=y # CONFIG_MIPS32_TOOLCHAIN_GNU_ELF is not set # CONFIG_MIPS32_TOOLCHAIN_MICROCHIPW_XC32 is not set # CONFIG_MIPS32_TOOLCHAIN_MICROCHIPW is not set -CONFIG_MIPS32_TOOLCHAIN_MICROCHIPW_LITE=y -# CONFIG_MIPS32_TOOLCHAIN_PINGUINOW is not set +# CONFIG_MIPS32_TOOLCHAIN_MICROCHIPW_LITE is not set +CONFIG_MIPS32_TOOLCHAIN_PINGUINOW=y # CONFIG_MIPS32_FRAMEPOINTER is not set # @@ -279,6 +280,8 @@ CONFIG_PIC32MX_VBUSIO=0 # CONFIG_PIC32MX_WDENABLE is not set CONFIG_PIC32MX_FETHIO=0 CONFIG_PIC32MX_FMIIEN=0 +# CONFIG_ARCH_TOOLCHAIN_IAR is not set +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -299,6 +302,7 @@ CONFIG_ARCH_HAVE_VFORK=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set # CONFIG_ARCH_HAVE_RESET is not set +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y # CONFIG_ENDIAN_BIG is not set @@ -488,14 +492,6 @@ CONFIG_DEV_NULL=y # # Buffering # - -# -# Common I/O Buffer Support -# -CONFIG_MM_IOB=y -CONFIG_IOB_NBUFFERS=24 -CONFIG_IOB_BUFSIZE=196 -CONFIG_IOB_NCHAINS=8 # CONFIG_DRVR_WRITEBUFFER is not set # CONFIG_DRVR_READAHEAD is not set # CONFIG_RAMDISK is not set @@ -736,7 +732,9 @@ CONFIG_USBMSC_SCSI_STACKSIZE=2048 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -894,7 +892,17 @@ CONFIG_FAT_MAXFNAME=32 # CONFIG_FS_TMPFS is not set # CONFIG_FS_SMARTFS is not set # CONFIG_FS_BINFS is not set -# CONFIG_FS_PROCFS is not set +CONFIG_FS_PROCFS=y +# CONFIG_FS_PROCFS_REGISTER is not set + +# +# Exclude individual procfs entries +# +# CONFIG_FS_PROCFS_EXCLUDE_PROCESS is not set +# CONFIG_FS_PROCFS_EXCLUDE_UPTIME is not set +# CONFIG_FS_PROCFS_EXCLUDE_MOUNTS is not set +# CONFIG_FS_PROCFS_EXCLUDE_NET is not set +# CONFIG_FS_PROCFS_EXCLUDE_MTD is not set # CONFIG_FS_UNIONFS is not set # @@ -910,6 +918,15 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +CONFIG_MM_IOB=y +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_BUFSIZE=196 +CONFIG_IOB_NCHAINS=8 +CONFIG_IOB_THROTTLE=0 + # # Audio Support # @@ -918,6 +935,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -1255,6 +1273,7 @@ CONFIG_NSH_CMDOPT_DF_H=y # CONFIG_NSH_CMDOPT_DD_STATS is not set CONFIG_NSH_CODECS_BUFSIZE=128 CONFIG_NSH_CMDOPT_HEXDUMP=y +CONFIG_NSH_PROC_MOUNTPOINT="/proc" CONFIG_NSH_FILEIOSIZE=512 # @@ -1274,6 +1293,7 @@ CONFIG_NSH_ARCHINIT=y # Networking Configuration # CONFIG_NSH_NETINIT=y +# CONFIG_NSH_NETLOCAL is not set # CONFIG_NSH_NETINIT_THREAD is not set # @@ -1318,12 +1338,14 @@ CONFIG_NSH_IOBUFFER_SIZE=512 # # CONFIG_SYSTEM_CLE is not set # CONFIG_SYSTEM_CUTERM is not set +# CONFIG_SYSTEM_DHCPC is not set # CONFIG_SYSTEM_FLASH_ERASEALL is not set # CONFIG_SYSTEM_FREE is not set # CONFIG_SYSTEM_HEX2BIN is not set # CONFIG_SYSTEM_HEXED is not set # CONFIG_SYSTEM_INSTALL is not set # CONFIG_SYSTEM_NETDB is not set +# CONFIG_SYSTEM_NTPC is not set # CONFIG_SYSTEM_RAMTEST is not set CONFIG_READLINE_HAVE_EXTMATCH=y CONFIG_SYSTEM_READLINE=y @@ -1351,3 +1373,10 @@ CONFIG_SYSTEM_USBMSC_CMD_PRIORITY=100 # # Wireless Libraries and NSH Add-Ons # + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/configs/pic32mx7mmb/src/Makefile b/configs/pic32mx7mmb/src/Makefile index df9909b162..67bebd502f 100644 --- a/configs/pic32mx7mmb/src/Makefile +++ b/configs/pic32mx7mmb/src/Makefile @@ -36,7 +36,7 @@ -include $(TOPDIR)/Make.defs ASRCS = -CSRCS = pic32_boot.c pic32_leds.c pic32_spi.c pic32_mio283qt2.c +CSRCS = pic32_boot.c pic32_bringup.c pic32_leds.c pic32_spi.c pic32_mio283qt2.c ifeq ($(CONFIG_PIC32MX_USBDEV),y) CSRCS += pic32_usbdev.c diff --git a/configs/pic32mx7mmb/src/pic32_appinit.c b/configs/pic32mx7mmb/src/pic32_appinit.c index 06f54e3b13..95e74d5763 100644 --- a/configs/pic32mx7mmb/src/pic32_appinit.c +++ b/configs/pic32mx7mmb/src/pic32_appinit.c @@ -39,319 +39,14 @@ #include -#include -#include -#include -#include -#include +#include +#include #include -#include -#include -#include -#include "pic32mx.h" #include "pic32mx7mmb.h" -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ -/* Configuration ************************************************************/ -/* Assume that we have MMC/SD, USB host (and USB device) */ - -#define NSH_HAVEMMCSD 1 -#define NSH_HAVEUSBHOST 1 - -/* The Mikroelektronika PIC32MX7 MMB has one SD slot on board, connected to SPI 1. */ - -#ifndef CONFIG_PIC32MX_MMCSDSPIPORTNO -# define CONFIG_PIC32MX_MMCSDSPIPORTNO 1 -#endif - -/* Make sure that the configuration will support the SD card */ - -#ifdef NSH_HAVEMMCSD - - /* Make sure that the NSH configuration uses the correct SPI */ - -# if !defined(CONFIG_NSH_MMCSDSPIPORTNO) -# define CONFIG_NSH_MMCSDSPIPORTNO CONFIG_PIC32MX_MMCSDSPIPORTNO -# elif CONFIG_NSH_MMCSDSPIPORTNO != CONFIG_PIC32MX_MMCSDSPIPORTNO -# warning "CONFIG_PIC32MX_MMCSDSPIPORTNO does not match CONFIG_NSH_MMCSDSPIPORTNO" -# undef CONFIG_NSH_MMCSDSPIPORTNO -# define CONFIG_NSH_MMCSDSPIPORTNO CONFIG_PIC32MX_MMCSDSPIPORTNO -# endif - - /* Make sure that the NSH configuration uses slot 0 (there is only one - * SD slot on the Mikroelektronica PIC32MX7 MMB). - */ - -# if !defined(CONFIG_NSH_MMCSDSLOTNO) -# define CONFIG_NSH_MMCSDSLOTNO 0 -# elif CONFIG_NSH_MMCSDSLOTNO != 0 -# warning "The Mikroelektronika PIC32MX7 MMB has only one slot (0)" -# undef CONFIG_NSH_MMCSDSLOTNO -# define CONFIG_NSH_MMCSDSLOTNO 0 -# endif - - /* Make sure that the correct SPI is enabled in the configuration */ - -# if CONFIG_PIC32MX_MMCSDSPIPORTNO == 1 && !defined(CONFIG_PIC32MX_SPI1) -# warning "CONFIG_PIC32MX_SPI1 is not enabled" -# undef NSH_HAVEMMCSD -# elif CONFIG_PIC32MX_MMCSDSPIPORTNO == 2 && !defined(CONFIG_PIC32MX_SPI2) -# warning "CONFIG_PIC32MX_SPI2 is not enabled" -# undef NSH_HAVEMMCSD -# elif CONFIG_PIC32MX_MMCSDSPIPORTNO == 3 && !defined(CONFIG_PIC32MX_SPI3) -# warning "CONFIG_PIC32MX_SPI3 is not enabled" -# undef NSH_HAVEMMCSD -# elif CONFIG_PIC32MX_MMCSDSPIPORTNO == 4 && !defined(CONFIG_PIC32MX_SPI4) -# warning "CONFIG_PIC32MX_SPI4 is not enabled" -# undef NSH_HAVEMMCSD -# endif -#endif - -/* Can't support MMC/SD features if mountpoints are disabled */ - -#if defined(CONFIG_DISABLE_MOUNTPOINT) -# undef NSH_HAVEMMCSD -#endif - -/* Select /dev/mmcsd0 if no other minor number is provided */ - -#ifndef CONFIG_NSH_MMCSDMINOR -# define CONFIG_NSH_MMCSDMINOR 0 -#endif - -/* USB Host */ - -#ifdef CONFIG_USBHOST -# ifndef CONFIG_PIC32MX_USBHOST -# error "CONFIG_PIC32MX_USBHOST is not selected" -# undef NSH_HAVEUSBHOST -# endif -#endif - -#ifdef CONFIG_PIC32MX_USBHOST -# ifndef CONFIG_USBHOST -# warning "CONFIG_USBHOST is not selected" -# undef NSH_HAVEUSBHOST -# endif -#endif - -#if !defined(CONFIG_USBHOST) || !defined(CONFIG_PIC32MX_USBHOST) -# undef NSH_HAVEUSBHOST -#endif - -#ifdef NSH_HAVEUSBHOST -# ifndef CONFIG_USBHOST_DEFPRIO -# define CONFIG_USBHOST_DEFPRIO 50 -# endif -# ifndef CONFIG_USBHOST_STACKSIZE -# ifdef CONFIG_USBHOST_HUB -# define CONFIG_USBHOST_STACKSIZE 1536 -# else -# define CONFIG_USBHOST_STACKSIZE 1024 -# endif -# endif -#endif - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -#ifdef NSH_HAVEUSBHOST -static struct usbhost_connection_s *g_usbconn; -#endif - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: nsh_waiter - * - * Description: - * Wait for USB devices to be connected. - * - ****************************************************************************/ - -#ifdef NSH_HAVEUSBHOST -static int nsh_waiter(int argc, char *argv[]) -{ - struct usbhost_hubport_s *hport; - - syslog(LOG_INFO, "nsh_waiter: Running\n"); - for (;;) - { - /* Wait for the device to change state */ - - DEBUGVERIFY(CONN_WAIT(g_usbconn, &hport)); - syslog(LOG_INFO, "nsh_waiter: %s\n", hport->connected ? "connected" : "disconnected"); - - /* Did we just become connected? */ - - if (hport->connected) - { - /* Yes.. enumerate the newly connected device */ - - (void)CONN_ENUMERATE(g_usbconn, hport); - } - } - - /* Keep the compiler from complaining */ - - return 0; -} -#endif - -/**************************************************************************** - * Name: nsh_sdinitialize - * - * Description: - * Initialize SPI-based microSD. - * - ****************************************************************************/ - -#ifdef NSH_HAVEMMCSD -static int nsh_sdinitialize(void) -{ - FAR struct spi_dev_s *spi; - int ret; - - /* Get the SPI port */ - - spi = pic32mx_spibus_initialize(CONFIG_NSH_MMCSDSPIPORTNO); - if (!spi) - { - syslog(LOG_ERR, "ERROR: Failed to initialize SPI port %d\n", - CONFIG_NSH_MMCSDSPIPORTNO); - ret = -ENODEV; - goto errout; - } - - syslog(LOG_INFO, "Successfully initialized SPI port %d\n", - CONFIG_NSH_MMCSDSPIPORTNO); - - /* The SPI should be in 8-bit (default) and mode2: CKP=1, CKE=0. - * The MMC/SD driver will control the SPI frequency. WARNING: - * this is not the right way to do this... this should be done - * the MMC/SD driver: Other device on SPI1 may need other mode - * settings. - */ - - SPI_SETMODE(spi, SPIDEV_MODE2); - - /* Bind the SPI port to the slot */ - - ret = mmcsd_spislotinitialize(CONFIG_NSH_MMCSDMINOR, - CONFIG_NSH_MMCSDSLOTNO, spi); - if (ret < 0) - { - syslog(LOG_ERR, - "ERROR: Failed to bind SPI port %d to MMC/SD slot %d: %d\n", - CONFIG_NSH_MMCSDSPIPORTNO, - CONFIG_NSH_MMCSDSLOTNO, ret); - goto errout; - } - - syslog(LOG_INFO, - "Successfully bound SPI port %d to MMC/SD slot %d\n", - CONFIG_NSH_MMCSDSPIPORTNO, - CONFIG_NSH_MMCSDSLOTNO); - - return OK; - -errout: - return ret; -} -#else -# define nsh_sdinitialize() (OK) -#endif - -/**************************************************************************** - * Name: nsh_usbhostinitialize - * - * Description: - * Initialize SPI-based microSD. - * - ****************************************************************************/ - -#ifdef NSH_HAVEUSBHOST -static int nsh_usbhostinitialize(void) -{ - int pid; - int ret; - - /* First, register all of the class drivers needed to support the drivers - * that we care about: - */ - - syslog(LOG_INFO, "Register class drivers\n"); - -#ifdef CONFIG_USBHOST_MSC - /* Register the USB host Mass Storage Class */ - - ret = usbhost_msc_initialize(); - if (ret != OK) - { - syslog(LOG_ERR, "ERROR: Failed to register the mass storage class: %d\n", ret); - } -#endif - -#ifdef CONFIG_USBHOST_CDCACM - /* Register the CDC/ACM serial class */ - - ret = usbhost_cdcacm_initialize(); - if (ret != OK) - { - syslog(LOG_ERR, "ERROR: Failed to register the CDC/ACM serial class: %d\n", ret); - } -#endif - - /* Then get an instance of the USB host interface */ - - syslog(LOG_INFO, "Initialize USB host\n"); - g_usbconn = pic32_usbhost_initialize(0); - if (g_usbconn) - { - /* Start a thread to handle device connection. */ - - syslog(LOG_INFO, "Start nsh_waiter\n"); - - pid = task_create("usbhost", CONFIG_USBHOST_DEFPRIO, - CONFIG_USBHOST_STACKSIZE, - (main_t)nsh_waiter, (FAR char * const *)NULL); - return pid < 0 ? -ENOEXEC : OK; - } - return -ENODEV; -} -#else -# define nsh_usbhostinitialize() (OK) -#endif - -/**************************************************************************** - * Name: nsh_usbdevinitialize - * - * Description: - * Initialize SPI-based microSD. - * - ****************************************************************************/ - -#ifdef CONFIG_USBDEV -static int nsh_usbdevinitialize(void) -{ - /* The Mikroelektronika PIC32MX7 MMB has no way to know when the USB is - * connected. So we will fake it and tell the USB driver that the USB is - * connected now. - */ - - pic32mx_usbattach(); - return OK; -} -#else -# define nsh_usbdevinitialize() (OK) -#endif +#ifdef CONFIG_LIB_BOARDCTL /**************************************************************************** * Public Functions @@ -365,6 +60,13 @@ static int nsh_usbdevinitialize(void) * called directly from application code, but only indirectly via the * (non-standard) boardctl() interface using the command BOARDIOC_INIT. * + * CONFIG_LIB_BOARDCTL=y : + * Called from the NSH library + * + * CONFIG_BOARD_INITIALIZE=y, CONFIG_NSH_LIBRARY=y, && + * CONFIG_LIB_BOARDCTL=n : + * Called from board_initialize(). + * * Input Parameters: * arg - The boardctl() argument is passed to the board_app_initialize() * implementation without modification. The argument has no @@ -384,24 +86,13 @@ static int nsh_usbdevinitialize(void) int board_app_initialize(uintptr_t arg) { - int ret; - - /* Initialize SPI-based microSD */ - - ret = nsh_sdinitialize(); - if (ret == OK) - { - /* Initialize USB host */ + /* Did we already initialize via board_initialize()? */ - ret = nsh_usbhostinitialize(); - } - - if (ret == OK) - { - /* Initialize USB device */ - - ret = nsh_usbdevinitialize(); - } - - return ret; +#ifndef CONFIG_BOARD_INITIALIZE + return pic32mx_bringup(); +#else + return OK; +#endif } + +#endif /* CONFIG_LIB_BOARDCTL */ diff --git a/configs/pic32mx7mmb/src/pic32_boot.c b/configs/pic32mx7mmb/src/pic32_boot.c index cda70ea95a..ec9d8b4a85 100644 --- a/configs/pic32mx7mmb/src/pic32_boot.c +++ b/configs/pic32mx7mmb/src/pic32_boot.c @@ -1,7 +1,7 @@ /************************************************************************************ * configs/pic32mx7mmb/src/pic32_boot.c * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2012, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -98,3 +98,26 @@ void pic32mx_boardinitialize(void) pic32mx_led_initialize(); #endif } + +/**************************************************************************** + * Name: board_initialize + * + * Description: + * If CONFIG_BOARD_INITIALIZE is selected, then an additional + * initialization call will be performed in the boot-up sequence to a + * function called board_initialize(). board_initialize() will be + * called immediately after up_initialize() is called and just before the + * initial application is started. This additional initialization phase + * may be used, for example, to initialize board-specific device drivers. + * + ****************************************************************************/ + +#ifdef CONFIG_BOARD_INITIALIZE +void board_initialize(void) +{ + /* Perform board-specific initialization here if so configured */ + + (void)pic32mx_bringup(); +} +#endif + diff --git a/configs/pic32mx7mmb/src/pic32mx7mmb.h b/configs/pic32mx7mmb/src/pic32mx7mmb.h index 4160779a7f..da60ef9b6f 100644 --- a/configs/pic32mx7mmb/src/pic32mx7mmb.h +++ b/configs/pic32mx7mmb/src/pic32mx7mmb.h @@ -1,7 +1,7 @@ /**************************************************************************** * configs/pic32mx7mmb/src/pic32mx7mmb.h * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2012, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -145,6 +145,22 @@ void weak_function pic32mx_spidev_initialize(void); void pic32mx_led_initialize(void); #endif +/************************************************************************************ + * Name: pic32mx_bringup + * + * Description: + * Perform architecture-specific initialization + * + * CONFIG_BOARD_INITIALIZE=y : + * Called from board_initialize(). + * + * CONFIG_BOARD_INITIALIZE=y && CONFIG_LIB_BOARDCTL=y : + * Called from the NSH library + * + ************************************************************************************/ + +int pic32mx_bringup(void); + /**************************************************************************** * Name: pic32mx_lcdinitialize * -- GitLab From 7f9700804fef3dca9edc72cbb86b4f2b1506c811 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 27 May 2017 09:17:46 -0600 Subject: [PATCH 880/990] Add file needed with previouis commit. --- configs/pic32mx7mmb/src/pic32_bringup.c | 411 ++++++++++++++++++++++++ 1 file changed, 411 insertions(+) create mode 100644 configs/pic32mx7mmb/src/pic32_bringup.c diff --git a/configs/pic32mx7mmb/src/pic32_bringup.c b/configs/pic32mx7mmb/src/pic32_bringup.c new file mode 100644 index 0000000000..c082621356 --- /dev/null +++ b/configs/pic32mx7mmb/src/pic32_bringup.c @@ -0,0 +1,411 @@ +/**************************************************************************** + * config/pic32mx7mmb/src/pic32_bringup.c + * + * Copyright (C) 2012, 2016-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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include "pic32mx.h" +#include "pic32mx7mmb.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ +/* Configuration ************************************************************/ +/* Assume that we have MMC/SD, USB host (and USB device) */ + +#define NSH_HAVEMMCSD 1 +#define NSH_HAVEUSBHOST 1 + +/* The Mikroelektronika PIC32MX7 MMB has one SD slot on board, connected to SPI 1. */ + +#ifndef CONFIG_PIC32MX_MMCSDSPIPORTNO +# define CONFIG_PIC32MX_MMCSDSPIPORTNO 1 +#endif + +/* Make sure that the configuration will support the SD card */ + +#ifdef NSH_HAVEMMCSD + + /* Make sure that the NSH configuration uses the correct SPI */ + +# if !defined(CONFIG_NSH_MMCSDSPIPORTNO) +# define CONFIG_NSH_MMCSDSPIPORTNO CONFIG_PIC32MX_MMCSDSPIPORTNO +# elif CONFIG_NSH_MMCSDSPIPORTNO != CONFIG_PIC32MX_MMCSDSPIPORTNO +# warning "CONFIG_PIC32MX_MMCSDSPIPORTNO does not match CONFIG_NSH_MMCSDSPIPORTNO" +# undef CONFIG_NSH_MMCSDSPIPORTNO +# define CONFIG_NSH_MMCSDSPIPORTNO CONFIG_PIC32MX_MMCSDSPIPORTNO +# endif + + /* Make sure that the NSH configuration uses slot 0 (there is only one + * SD slot on the Mikroelektronica PIC32MX7 MMB). + */ + +# if !defined(CONFIG_NSH_MMCSDSLOTNO) +# define CONFIG_NSH_MMCSDSLOTNO 0 +# elif CONFIG_NSH_MMCSDSLOTNO != 0 +# warning "The Mikroelektronika PIC32MX7 MMB has only one slot (0)" +# undef CONFIG_NSH_MMCSDSLOTNO +# define CONFIG_NSH_MMCSDSLOTNO 0 +# endif + + /* Make sure that the correct SPI is enabled in the configuration */ + +# if CONFIG_PIC32MX_MMCSDSPIPORTNO == 1 && !defined(CONFIG_PIC32MX_SPI1) +# warning "CONFIG_PIC32MX_SPI1 is not enabled" +# undef NSH_HAVEMMCSD +# elif CONFIG_PIC32MX_MMCSDSPIPORTNO == 2 && !defined(CONFIG_PIC32MX_SPI2) +# warning "CONFIG_PIC32MX_SPI2 is not enabled" +# undef NSH_HAVEMMCSD +# elif CONFIG_PIC32MX_MMCSDSPIPORTNO == 3 && !defined(CONFIG_PIC32MX_SPI3) +# warning "CONFIG_PIC32MX_SPI3 is not enabled" +# undef NSH_HAVEMMCSD +# elif CONFIG_PIC32MX_MMCSDSPIPORTNO == 4 && !defined(CONFIG_PIC32MX_SPI4) +# warning "CONFIG_PIC32MX_SPI4 is not enabled" +# undef NSH_HAVEMMCSD +# endif +#endif + +/* Can't support MMC/SD features if mountpoints are disabled */ + +#if defined(CONFIG_DISABLE_MOUNTPOINT) +# undef NSH_HAVEMMCSD +#endif + +/* Select /dev/mmcsd0 if no other minor number is provided */ + +#ifndef CONFIG_NSH_MMCSDMINOR +# define CONFIG_NSH_MMCSDMINOR 0 +#endif + +/* USB Host */ + +#ifdef CONFIG_USBHOST +# ifndef CONFIG_PIC32MX_USBHOST +# error "CONFIG_PIC32MX_USBHOST is not selected" +# undef NSH_HAVEUSBHOST +# endif +#endif + +#ifdef CONFIG_PIC32MX_USBHOST +# ifndef CONFIG_USBHOST +# warning "CONFIG_USBHOST is not selected" +# undef NSH_HAVEUSBHOST +# endif +#endif + +#if !defined(CONFIG_USBHOST) || !defined(CONFIG_PIC32MX_USBHOST) +# undef NSH_HAVEUSBHOST +#endif + +#ifdef NSH_HAVEUSBHOST +# ifndef CONFIG_USBHOST_DEFPRIO +# define CONFIG_USBHOST_DEFPRIO 50 +# endif +# ifndef CONFIG_USBHOST_STACKSIZE +# ifdef CONFIG_USBHOST_HUB +# define CONFIG_USBHOST_STACKSIZE 1536 +# else +# define CONFIG_USBHOST_STACKSIZE 1024 +# endif +# endif +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +#ifdef NSH_HAVEUSBHOST +static struct usbhost_connection_s *g_usbconn; +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nsh_waiter + * + * Description: + * Wait for USB devices to be connected. + * + ****************************************************************************/ + +#ifdef NSH_HAVEUSBHOST +static int nsh_waiter(int argc, char *argv[]) +{ + struct usbhost_hubport_s *hport; + + syslog(LOG_INFO, "nsh_waiter: Running\n"); + for (;;) + { + /* Wait for the device to change state */ + + DEBUGVERIFY(CONN_WAIT(g_usbconn, &hport)); + syslog(LOG_INFO, "nsh_waiter: %s\n", hport->connected ? "connected" : "disconnected"); + + /* Did we just become connected? */ + + if (hport->connected) + { + /* Yes.. enumerate the newly connected device */ + + (void)CONN_ENUMERATE(g_usbconn, hport); + } + } + + /* Keep the compiler from complaining */ + + return 0; +} +#endif + +/**************************************************************************** + * Name: nsh_sdinitialize + * + * Description: + * Initialize SPI-based microSD. + * + ****************************************************************************/ + +#ifdef NSH_HAVEMMCSD +static int nsh_sdinitialize(void) +{ + FAR struct spi_dev_s *spi; + int ret; + + /* Get the SPI port */ + + spi = pic32mx_spibus_initialize(CONFIG_NSH_MMCSDSPIPORTNO); + if (!spi) + { + syslog(LOG_ERR, "ERROR: Failed to initialize SPI port %d\n", + CONFIG_NSH_MMCSDSPIPORTNO); + ret = -ENODEV; + goto errout; + } + + syslog(LOG_INFO, "Successfully initialized SPI port %d\n", + CONFIG_NSH_MMCSDSPIPORTNO); + + /* The SPI should be in 8-bit (default) and mode2: CKP=1, CKE=0. + * The MMC/SD driver will control the SPI frequency. WARNING: + * this is not the right way to do this... this should be done + * the MMC/SD driver: Other device on SPI1 may need other mode + * settings. + */ + + SPI_SETMODE(spi, SPIDEV_MODE2); + + /* Bind the SPI port to the slot */ + + ret = mmcsd_spislotinitialize(CONFIG_NSH_MMCSDMINOR, + CONFIG_NSH_MMCSDSLOTNO, spi); + if (ret < 0) + { + syslog(LOG_ERR, + "ERROR: Failed to bind SPI port %d to MMC/SD slot %d: %d\n", + CONFIG_NSH_MMCSDSPIPORTNO, + CONFIG_NSH_MMCSDSLOTNO, ret); + goto errout; + } + + syslog(LOG_INFO, + "Successfully bound SPI port %d to MMC/SD slot %d\n", + CONFIG_NSH_MMCSDSPIPORTNO, + CONFIG_NSH_MMCSDSLOTNO); + + return OK; + +errout: + return ret; +} +#else +# define nsh_sdinitialize() (OK) +#endif + +/**************************************************************************** + * Name: nsh_usbhostinitialize + * + * Description: + * Initialize SPI-based microSD. + * + ****************************************************************************/ + +#ifdef NSH_HAVEUSBHOST +static int nsh_usbhostinitialize(void) +{ + int pid; + int ret; + + /* First, register all of the class drivers needed to support the drivers + * that we care about: + */ + + syslog(LOG_INFO, "Register class drivers\n"); + +#ifdef CONFIG_USBHOST_MSC + /* Register the USB host Mass Storage Class */ + + ret = usbhost_msc_initialize(); + if (ret != OK) + { + syslog(LOG_ERR, "ERROR: Failed to register the mass storage class: %d\n", ret); + } +#endif + +#ifdef CONFIG_USBHOST_CDCACM + /* Register the CDC/ACM serial class */ + + ret = usbhost_cdcacm_initialize(); + if (ret != OK) + { + syslog(LOG_ERR, "ERROR: Failed to register the CDC/ACM serial class: %d\n", ret); + } +#endif + + /* Then get an instance of the USB host interface */ + + syslog(LOG_INFO, "Initialize USB host\n"); + g_usbconn = pic32_usbhost_initialize(0); + if (g_usbconn) + { + /* Start a thread to handle device connection. */ + + syslog(LOG_INFO, "Start nsh_waiter\n"); + + pid = task_create("usbhost", CONFIG_USBHOST_DEFPRIO, + CONFIG_USBHOST_STACKSIZE, + (main_t)nsh_waiter, (FAR char * const *)NULL); + return pid < 0 ? -ENOEXEC : OK; + } + return -ENODEV; +} +#else +# define nsh_usbhostinitialize() (OK) +#endif + +/**************************************************************************** + * Name: nsh_usbdevinitialize + * + * Description: + * Initialize SPI-based microSD. + * + ****************************************************************************/ + +#ifdef CONFIG_USBDEV +static int nsh_usbdevinitialize(void) +{ + /* The Mikroelektronika PIC32MX7 MMB has no way to know when the USB is + * connected. So we will fake it and tell the USB driver that the USB is + * connected now. + */ + + pic32mx_usbattach(); + return OK; +} +#else +# define nsh_usbdevinitialize() (OK) +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: pic32mx_bringup + * + * Description: + * Perform architecture-specific initialization + * + * CONFIG_BOARD_INITIALIZE=y : + * Called from board_initialize(). + * + * CONFIG_BOARD_INITIALIZE=n && CONFIG_LIB_BOARDCTL=y : + * Called from the NSH library + * + ****************************************************************************/ + +int pic32mx_bringup(void) +{ + int ret; + +#ifdef CONFIG_FS_PROCFS + /* Mount the procfs file system */ + + ret = mount(NULL, "/proc", "procfs", 0, NULL); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: Failed to mount procfs at /proc: %d\n", ret); + } + + if (ret == OK) +#endif + { + /* Initialize SPI-based microSD */ + + ret = nsh_sdinitialize(); + } + + if (ret == OK) + { + /* Initialize USB host */ + + ret = nsh_usbhostinitialize(); + } + + if (ret == OK) + { + /* Initialize USB device */ + + ret = nsh_usbdevinitialize(); + } + + return ret; +} -- GitLab From f86287fd4316cc9d7b344a559b93b9898a92ae07 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 27 May 2017 09:23:23 -0600 Subject: [PATCH 881/990] PIC32MXMMB: Fix a few copy-paste errors. --- configs/pic32mx7mmb/src/pic32_mio283qt2.c | 2 +- configs/pic32mx7mmb/src/pic32_usbdev.c | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/configs/pic32mx7mmb/src/pic32_mio283qt2.c b/configs/pic32mx7mmb/src/pic32_mio283qt2.c index 16b1c7518a..d740edd700 100644 --- a/configs/pic32mx7mmb/src/pic32_mio283qt2.c +++ b/configs/pic32mx7mmb/src/pic32_mio283qt2.c @@ -1,5 +1,5 @@ /************************************************************************************** - * configs/stm32fdiscover/src/pic32_mio283qt2.c + * configs/pic32mx7mmb/src/pic32_mio283qt2.c * * Interface definition for the MI0283QT-2 LCD from Multi-Inno Technology Co., Ltd. * This LCD is based on the Himax HX8347-D LCD controller. diff --git a/configs/pic32mx7mmb/src/pic32_usbdev.c b/configs/pic32mx7mmb/src/pic32_usbdev.c index 75e4c4cff6..fe3481b5bc 100644 --- a/configs/pic32mx7mmb/src/pic32_usbdev.c +++ b/configs/pic32mx7mmb/src/pic32_usbdev.c @@ -130,7 +130,7 @@ void weak_function pic32mx_usbdevinitialize(void) * Description: * If USB is supported and the board supports a pullup via GPIO (for USB * software connect and disconnect), then the board software must provide - * stm32_pullup. See include/nuttx/usb/usbdev.h for additional description + * pic32mx_pullup. See include/nuttx/usb/usbdev.h for additional description * of this method. Alternatively, if no pull-up GPIO the following EXTERN * can be redefined to be NULL. * @@ -147,7 +147,7 @@ int pic32mx_usbpullup(FAR struct usbdev_s *dev, bool enable) * Name: pic32mx_usbsuspend * * Description: - * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver + * Board logic must provide the pic32mx_usbsuspend logic if the USBDEV driver * is used. This function is called whenever the USB enters or leaves * suspend mode. This is an opportunity for the board logic to shutdown * clocks, power, etc. while the USB is suspended. -- GitLab From a8708424c2ea40dcea2feb55a29c3ab176ac0625 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 29 May 2017 07:05:06 -0600 Subject: [PATCH 882/990] pthread_trylock: Fixes a problem in pthread_trylock() noted by initialkjc@yahoo.com. When CONFIG_PTHREAD_MUTEX_UNSAFE=y, the special return value EAGAIN was not being detected due to differences in reporting of returned values. --- sched/pthread/pthread.h | 14 ++++++---- sched/pthread/pthread_completejoin.c | 10 +++---- sched/pthread/pthread_condbroadcast.c | 2 +- sched/pthread/pthread_condsignal.c | 2 +- sched/pthread/pthread_condwait.c | 2 +- sched/pthread/pthread_create.c | 8 +++--- sched/pthread/pthread_detach.c | 4 +-- sched/pthread/pthread_initialize.c | 34 ++++++++++++++++++++--- sched/pthread/pthread_join.c | 14 +++++----- sched/pthread/pthread_mutex.c | 6 ++-- sched/pthread/pthread_mutexinconsistent.c | 2 +- 11 files changed, 64 insertions(+), 34 deletions(-) diff --git a/sched/pthread/pthread.h b/sched/pthread/pthread.h index 14a5797bb8..96fb66b8d9 100644 --- a/sched/pthread/pthread.h +++ b/sched/pthread/pthread.h @@ -107,8 +107,12 @@ void pthread_destroyjoin(FAR struct task_group_s *group, FAR struct join_s *pthread_findjoininfo(FAR struct task_group_s *group, pid_t pid); void pthread_release(FAR struct task_group_s *group); -int pthread_takesemaphore(sem_t *sem, bool intr); -int pthread_givesemaphore(sem_t *sem); + +int pthread_sem_take(sem_t *sem, bool intr); +#ifdef CONFIG_PTHREAD_MUTEX_UNSAFE +int pthread_sem_trytake(sem_t *sem); +#endif +int pthread_sem_give(sem_t *sem); #ifndef CONFIG_PTHREAD_MUTEX_UNSAFE int pthread_mutex_take(FAR struct pthread_mutex_s *mutex, bool intr); @@ -116,9 +120,9 @@ int pthread_mutex_trytake(FAR struct pthread_mutex_s *mutex); int pthread_mutex_give(FAR struct pthread_mutex_s *mutex); void pthread_mutex_inconsistent(FAR struct pthread_tcb_s *tcb); #else -# define pthread_mutex_take(m,i) pthread_takesemaphore(&(m)->sem,(i)) -# define pthread_mutex_trytake(m) sem_trywait(&(m)->sem) -# define pthread_mutex_give(m) pthread_givesemaphore(&(m)->sem) +# define pthread_mutex_take(m,i) pthread_sem_take(&(m)->sem,(i)) +# define pthread_mutex_trytake(m) pthread_sem_trytake(&(m)->sem) +# define pthread_mutex_give(m) pthread_sem_give(&(m)->sem) #endif #if defined(CONFIG_CANCELLATION_POINTS) && !defined(CONFIG_PTHREAD_MUTEX_UNSAFE) diff --git a/sched/pthread/pthread_completejoin.c b/sched/pthread/pthread_completejoin.c index 6053f6c1da..410b3b958c 100644 --- a/sched/pthread/pthread_completejoin.c +++ b/sched/pthread/pthread_completejoin.c @@ -87,7 +87,7 @@ static bool pthread_notifywaiters(FAR struct join_s *pjoin) do { - status = pthread_givesemaphore(&pjoin->exit_sem); + status = pthread_sem_give(&pjoin->exit_sem); if (status == OK) { status = sem_getvalue(&pjoin->exit_sem, &ntasks_waiting); @@ -99,7 +99,7 @@ static bool pthread_notifywaiters(FAR struct join_s *pjoin) * value. */ - (void)pthread_takesemaphore(&pjoin->data_sem, false); + (void)pthread_sem_take(&pjoin->data_sem, false); return true; } @@ -210,12 +210,12 @@ int pthread_completejoin(pid_t pid, FAR void *exit_value) /* First, find thread's structure in the private data set. */ - (void)pthread_takesemaphore(&group->tg_joinsem, false); + (void)pthread_sem_take(&group->tg_joinsem, false); pjoin = pthread_findjoininfo(group, pid); if (!pjoin) { serr("ERROR: Could not find join info, pid=%d\n", pid); - (void)pthread_givesemaphore(&group->tg_joinsem); + (void)pthread_sem_give(&group->tg_joinsem); return ERROR; } else @@ -246,7 +246,7 @@ int pthread_completejoin(pid_t pid, FAR void *exit_value) * to call pthread_destroyjoin. */ - (void)pthread_givesemaphore(&group->tg_joinsem); + (void)pthread_sem_give(&group->tg_joinsem); } return OK; diff --git a/sched/pthread/pthread_condbroadcast.c b/sched/pthread/pthread_condbroadcast.c index 35427ad48a..de637c9e1e 100644 --- a/sched/pthread/pthread_condbroadcast.c +++ b/sched/pthread/pthread_condbroadcast.c @@ -103,7 +103,7 @@ int pthread_cond_broadcast(FAR pthread_cond_t *cond) * Only the highest priority waiting thread will get to execute */ - ret = pthread_givesemaphore((FAR sem_t *)&cond->sem); + ret = pthread_sem_give((FAR sem_t *)&cond->sem); /* Increment the semaphore count (as was done by the * above post). diff --git a/sched/pthread/pthread_condsignal.c b/sched/pthread/pthread_condsignal.c index 8936572ac5..e5f9af31af 100644 --- a/sched/pthread/pthread_condsignal.c +++ b/sched/pthread/pthread_condsignal.c @@ -105,7 +105,7 @@ int pthread_cond_signal(FAR pthread_cond_t *cond) if (sval < 0) { sinfo("Signalling...\n"); - ret = pthread_givesemaphore((FAR sem_t *)&cond->sem); + ret = pthread_sem_give((FAR sem_t *)&cond->sem); } } } diff --git a/sched/pthread/pthread_condwait.c b/sched/pthread/pthread_condwait.c index 91138215fa..8d47d20673 100644 --- a/sched/pthread/pthread_condwait.c +++ b/sched/pthread/pthread_condwait.c @@ -107,7 +107,7 @@ int pthread_cond_wait(FAR pthread_cond_t *cond, FAR pthread_mutex_t *mutex) /* Take the semaphore */ - status = pthread_takesemaphore((FAR sem_t *)&cond->sem, false); + status = pthread_sem_take((FAR sem_t *)&cond->sem, false); if (ret == OK) { /* Report the first failure that occurs */ diff --git a/sched/pthread/pthread_create.c b/sched/pthread/pthread_create.c index 23ebd95489..0735e5d86a 100644 --- a/sched/pthread/pthread_create.c +++ b/sched/pthread/pthread_create.c @@ -177,14 +177,14 @@ static void pthread_start(void) /* Sucessfully spawned, add the pjoin to our data set. */ - (void)pthread_takesemaphore(&group->tg_joinsem, false); + (void)pthread_sem_take(&group->tg_joinsem, false); pthread_addjoininfo(group, pjoin); - (void)pthread_givesemaphore(&group->tg_joinsem); + (void)pthread_sem_give(&group->tg_joinsem); /* Report to the spawner that we successfully started. */ pjoin->started = true; - (void)pthread_givesemaphore(&pjoin->data_sem); + (void)pthread_sem_give(&pjoin->data_sem); /* The priority of this thread may have been boosted to avoid priority * inversion problems. If that is the case, then drop to the correct @@ -555,7 +555,7 @@ int pthread_create(FAR pthread_t *thread, FAR const pthread_attr_t *attr, * its join structure. */ - (void)pthread_takesemaphore(&pjoin->data_sem, false); + (void)pthread_sem_take(&pjoin->data_sem, false); /* Return the thread information to the caller */ diff --git a/sched/pthread/pthread_detach.c b/sched/pthread/pthread_detach.c index 9e3d900d7e..47e0a3b42d 100644 --- a/sched/pthread/pthread_detach.c +++ b/sched/pthread/pthread_detach.c @@ -87,7 +87,7 @@ int pthread_detach(pthread_t thread) /* Find the entry associated with this pthread. */ - (void)pthread_takesemaphore(&group->tg_joinsem, false); + (void)pthread_sem_take(&group->tg_joinsem, false); pjoin = pthread_findjoininfo(group, (pid_t)thread); if (!pjoin) { @@ -119,7 +119,7 @@ int pthread_detach(pthread_t thread) ret = OK; } - (void)pthread_givesemaphore(&group->tg_joinsem); + (void)pthread_sem_give(&group->tg_joinsem); sinfo("Returning %d\n", ret); return ret; diff --git a/sched/pthread/pthread_initialize.c b/sched/pthread/pthread_initialize.c index e5965d8b60..2054f109cb 100644 --- a/sched/pthread/pthread_initialize.c +++ b/sched/pthread/pthread_initialize.c @@ -72,11 +72,18 @@ void pthread_initialize(void) } /**************************************************************************** - * Name: pthread_takesemaphore and pthread_givesemaphore + * Name: pthread_sem_take, pthread_sem_trytake, and + * pthread_sem_give * * Description: * Support managed access to the private data sets. * + * REVISIT: These functions really do nothing more than match the return + * value of the semaphore functions (0 or -1 with errno set) to the + * return value of more pthread functions (0 or errno). A better solution + * would be to use an internal version of the semaphore functions that + * return the error value in the correct form. + * * Parameters: * sem - The semaphore to lock or unlock * intr - false: ignore EINTR errors when locking; true tread EINTR as @@ -87,7 +94,7 @@ void pthread_initialize(void) * ****************************************************************************/ -int pthread_takesemaphore(sem_t *sem, bool intr) +int pthread_sem_take(sem_t *sem, bool intr) { /* Verify input parameters */ @@ -120,7 +127,27 @@ int pthread_takesemaphore(sem_t *sem, bool intr) } } -int pthread_givesemaphore(sem_t *sem) +#ifdef CONFIG_PTHREAD_MUTEX_UNSAFE +int pthread_sem_trytake(sem_t *sem) +{ + int ret = EINVAL; + + /* Verify input parameters */ + + DEBUGASSERT(sem != NULL); + if (sem != NULL) + { + /* Try to take the semaphore */ + + int status = sem_trywait(sem); + ret = status < 0 ? get_errno() : OK; + } + + return ret; +} +#endif + +int pthread_sem_give(sem_t *sem) { /* Verify input parameters */ @@ -148,4 +175,3 @@ int pthread_givesemaphore(sem_t *sem) return EINVAL; } } - diff --git a/sched/pthread/pthread_join.c b/sched/pthread/pthread_join.c index 6d2b48c81a..8e14666fbb 100644 --- a/sched/pthread/pthread_join.c +++ b/sched/pthread/pthread_join.c @@ -114,7 +114,7 @@ int pthread_join(pthread_t thread, FAR pthread_addr_t *pexit_value) * because it will also attempt to get this semaphore. */ - (void)pthread_takesemaphore(&group->tg_joinsem, false); + (void)pthread_sem_take(&group->tg_joinsem, false); /* Find the join information associated with this thread. * This can fail for one of three reasons: (1) There is no @@ -148,7 +148,7 @@ int pthread_join(pthread_t thread, FAR pthread_addr_t *pexit_value) ret = EINVAL; } - (void)pthread_givesemaphore(&group->tg_joinsem); + (void)pthread_sem_give(&group->tg_joinsem); } else { @@ -189,7 +189,7 @@ int pthread_join(pthread_t thread, FAR pthread_addr_t *pexit_value) * semaphore. */ - (void)pthread_givesemaphore(&group->tg_joinsem); + (void)pthread_sem_give(&group->tg_joinsem); /* Take the thread's thread exit semaphore. We will sleep here * until the thread exits. We need to exercise caution because @@ -197,7 +197,7 @@ int pthread_join(pthread_t thread, FAR pthread_addr_t *pexit_value) * pthread to exit. */ - (void)pthread_takesemaphore(&pjoin->exit_sem, false); + (void)pthread_sem_take(&pjoin->exit_sem, false); /* The thread has exited! Get the thread exit value */ @@ -211,13 +211,13 @@ int pthread_join(pthread_t thread, FAR pthread_addr_t *pexit_value) * will know that we have received the data. */ - (void)pthread_givesemaphore(&pjoin->data_sem); + (void)pthread_sem_give(&pjoin->data_sem); /* Retake the join semaphore, we need to hold this when * pthread_destroyjoin is called. */ - (void)pthread_takesemaphore(&group->tg_joinsem, false); + (void)pthread_sem_take(&group->tg_joinsem, false); } /* Pre-emption is okay now. The logic still cannot be re-entered @@ -235,7 +235,7 @@ int pthread_join(pthread_t thread, FAR pthread_addr_t *pexit_value) (void)pthread_destroyjoin(group, pjoin); } - (void)pthread_givesemaphore(&group->tg_joinsem); + (void)pthread_sem_give(&group->tg_joinsem); ret = OK; } diff --git a/sched/pthread/pthread_mutex.c b/sched/pthread/pthread_mutex.c index 45c4ffd3fa..13dde1a53d 100644 --- a/sched/pthread/pthread_mutex.c +++ b/sched/pthread/pthread_mutex.c @@ -125,11 +125,11 @@ int pthread_mutex_take(FAR struct pthread_mutex_s *mutex, bool intr) } else { - /* Take semaphore underlying the mutex. pthread_takesemaphore + /* Take semaphore underlying the mutex. pthread_sem_take * returns zero on success and a positive errno value on failure. */ - ret = pthread_takesemaphore(&mutex->sem, intr); + ret = pthread_sem_take(&mutex->sem, intr); if (ret == OK) { /* Check if the holder of the mutex has terminated without @@ -273,7 +273,7 @@ int pthread_mutex_give(FAR struct pthread_mutex_s *mutex) /* Now release the underlying semaphore */ - ret = pthread_givesemaphore(&mutex->sem); + ret = pthread_sem_give(&mutex->sem); } return ret; diff --git a/sched/pthread/pthread_mutexinconsistent.c b/sched/pthread/pthread_mutexinconsistent.c index c9d2b20371..5f8d5f9cc8 100644 --- a/sched/pthread/pthread_mutexinconsistent.c +++ b/sched/pthread/pthread_mutexinconsistent.c @@ -95,7 +95,7 @@ void pthread_mutex_inconsistent(FAR struct pthread_tcb_s *tcb) /* Mark the mutex as INCONSISTENT and wake up any waiting thread */ mutex->flags |= _PTHREAD_MFLAGS_INCONSISTENT; - (void)pthread_givesemaphore(&mutex->sem); + (void)pthread_sem_give(&mutex->sem); } sched_unlock(); -- GitLab From d9bd5ca05fd71a419fb689ebd34f3a83ef7511d1 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 30 May 2017 09:19:04 -0600 Subject: [PATCH 883/990] Update README and some C comments --- README.txt | 21 +++++++++++++++++++-- TODO | 2 +- mm/shm/shmctl.c | 4 +++- 3 files changed, 23 insertions(+), 4 deletions(-) diff --git a/README.txt b/README.txt index b6144aca71..9a4775c77b 100644 --- a/README.txt +++ b/README.txt @@ -197,8 +197,25 @@ Ubuntu Bash under Windows 10 C:\Users\Username\AppData\Local\lxss\rootfs - However, I am unable to see my files under the rootfs/home directory - so this is not very useful. + However, I am unable to see my files under the rootfs\home directory. + After some looking around, I find the home directory + %localappdata%\lxss\home. + + With that trick access to the /home directory, you should actually be + able to use Windows tools outside of the Ubuntu sandbox with versions of + NuttX built within the sandbox using that path. + + You can also execute Windows tools from within the Ubuntu sandbox: + + $ /mnt/c/Program\ Files\ \(x86\)/Microchip/xc32/v1.43/bin/xc32-gcc.exe --version + Unable to translate current working directory. Using C:\WINDOWS\System32 + xc32-gcc.exe (Microchip Technology) 4.8.3 MPLAB XC32 Compiler v1.43 Build date: Mar 1 2017 + ... + + The error message indicates that there are more issues: You cannot mix + Windows tools that use Windows style paths in an environment that uses + POSIX paths. I think you would have to use Linux tools only from within + the Ubuntu sandbox. Install Linux Software. ----------------------- diff --git a/TODO b/TODO index fe969060bf..2cf4fdcaaa 100644 --- a/TODO +++ b/TODO @@ -196,7 +196,7 @@ o Task/Scheduler (sched/) OS can cause non-cancellation point interfaces to behave strangely. There was a change recently in pthread_cond_wait() and pthread_cond_timedwait() recently to effectively disable - the cancellation point behavior of sem_init(). This was + the cancellation point behavior of sem_wait(). This was accomplished with two functions: pthread_disable_cancel() and pthread_enable_cancel() diff --git a/mm/shm/shmctl.c b/mm/shm/shmctl.c index 0c468b36af..2421dea09e 100644 --- a/mm/shm/shmctl.c +++ b/mm/shm/shmctl.c @@ -171,7 +171,9 @@ int shmctl(int shmid, int cmd, struct shmid_ds *buf) if (region->sr_ds.shm_nattch > 0) { - /* Yes.. just set the UNLINKED flag. The region will be removed when there are no longer any processes attached to it. + /* Yes.. just set the UNLINKED flag. The region will be + * removed when there are no longer any processes attached to + * it. */ region->sr_flags |= SRFLAG_UNLINKED; -- GitLab From dc3a7e54a981e9fa400763e6824a022c3de851b4 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 30 May 2017 11:36:54 -0600 Subject: [PATCH 884/990] Cosmetic --- configs/boardctl.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/configs/boardctl.c b/configs/boardctl.c index 6c5185c572..208394e49f 100644 --- a/configs/boardctl.c +++ b/configs/boardctl.c @@ -438,7 +438,7 @@ int boardctl(unsigned int cmd, uintptr_t arg) case BOARDIOC_GRAPHICS_SETUP: { FAR struct boardioc_graphics_s *setup = - ( FAR struct boardioc_graphics_s *)arg; + (FAR struct boardioc_graphics_s *)arg; setup->dev = board_graphics_setup(setup->devno); ret = setup->dev ? OK : -ENODEV; -- GitLab From ae17e6bcf06ce8ff7af5885eac2bd091b53bd70a Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 30 May 2017 12:04:48 -0600 Subject: [PATCH 885/990] Cosmetic --- drivers/usbdev/usbmsc.h | 2 +- include/nuttx/usb/usbmsc.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/drivers/usbdev/usbmsc.h b/drivers/usbdev/usbmsc.h index 2da7b762f2..4fa8405248 100644 --- a/drivers/usbdev/usbmsc.h +++ b/drivers/usbdev/usbmsc.h @@ -592,7 +592,7 @@ struct usb_strdesc_s; int usbmsc_mkstrdesc(uint8_t id, struct usb_strdesc_s *strdesc); /************************************************************************************ - * Name: usbmsc_getepdesc + * Name: usbmsc_getdevdesc * * Description: * Return a pointer to the raw device descriptor diff --git a/include/nuttx/usb/usbmsc.h b/include/nuttx/usb/usbmsc.h index 270fac0da3..701fc95837 100644 --- a/include/nuttx/usb/usbmsc.h +++ b/include/nuttx/usb/usbmsc.h @@ -60,7 +60,7 @@ * Public Types ************************************************************************************/ - /************************************************************************************ +/************************************************************************************ * Public Data ************************************************************************************/ -- GitLab From 830ad9370a13e7aeec4c7017ff0a282b5413b994 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 31 May 2017 06:19:05 -0600 Subject: [PATCH 886/990] Update README file --- README.txt | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/README.txt b/README.txt index 9a4775c77b..c5e0b9c69e 100644 --- a/README.txt +++ b/README.txt @@ -186,6 +186,13 @@ Ubuntu Bash under Windows 10 With these differences (perhaps a few other Windows quirks) the Ubuntu install works just like Ubuntu running natively on your PC. + A good tip for file sharing is to use symbolic links within your Ubuntu + home directory. For example, suppose you have your "projects" directory + at C:\Documents\projects. Then you can set up a link to the projects/ + directory in your Ubuntu directory like: + + $ ln -s /mnt/c/Documents/projects projects + Accessing Ubuntu Files From Windows ----------------------------------- In Ubuntu Userspace for Windows, the Ubuntu file system root directory is @@ -205,6 +212,8 @@ Ubuntu Bash under Windows 10 able to use Windows tools outside of the Ubuntu sandbox with versions of NuttX built within the sandbox using that path. + Executing Windows Tools from Ubuntu + ----------------------------------- You can also execute Windows tools from within the Ubuntu sandbox: $ /mnt/c/Program\ Files\ \(x86\)/Microchip/xc32/v1.43/bin/xc32-gcc.exe --version @@ -217,7 +226,7 @@ Ubuntu Bash under Windows 10 POSIX paths. I think you would have to use Linux tools only from within the Ubuntu sandbox. - Install Linux Software. + Install Ubuntu Software ----------------------- Use "sudo apt-get install ". As examples, this is how you would get GIT: -- GitLab From b8b9309d2bd97ffeb13786e486edd884db3a96d1 Mon Sep 17 00:00:00 2001 From: Harri Luhtala Date: Wed, 31 May 2017 06:20:18 -0600 Subject: [PATCH 887/990] vfs: fdopen: add missing file stream flags clearing. Clear file stream structure regardless of config options. Structure clearing is needed as previous use of stream list entry might leave fs_flags set. --- fs/vfs/fs_fdopen.c | 4 ---- 1 file changed, 4 deletions(-) diff --git a/fs/vfs/fs_fdopen.c b/fs/vfs/fs_fdopen.c index 43e00f184a..ebacc4c5ff 100644 --- a/fs/vfs/fs_fdopen.c +++ b/fs/vfs/fs_fdopen.c @@ -221,11 +221,7 @@ FAR struct file_struct *fs_fdopen(int fd, int oflags, FAR struct tcb_s *tcb) { /* Zero the structure */ -#ifndef CONFIG_STDIO_DISABLE_BUFFERING memset(stream, 0, sizeof(FILE)); -#elif CONFIG_NUNGET_CHARS > 0 - stream->fs_nungotten = 0; -#endif #ifndef CONFIG_STDIO_DISABLE_BUFFERING /* Initialize the semaphore the manages access to the buffer */ -- GitLab From 80cc19d6b0ee6c4a70a367881dcdc45231ac41ce Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Wed, 31 May 2017 06:31:53 -0600 Subject: [PATCH 888/990] drivers/input: add Cypress MBR3108 CapSense touch button driver --- drivers/input/Kconfig | 24 + drivers/input/Make.defs | 4 + drivers/input/cypress_mbr3108.c | 1157 +++++++++++++++++++++++++ include/nuttx/input/cypress_mbr3108.h | 139 +++ 4 files changed, 1324 insertions(+) create mode 100644 drivers/input/cypress_mbr3108.c create mode 100644 include/nuttx/input/cypress_mbr3108.h diff --git a/drivers/input/Kconfig b/drivers/input/Kconfig index 0fc96d6c91..69d77e62d2 100644 --- a/drivers/input/Kconfig +++ b/drivers/input/Kconfig @@ -322,6 +322,30 @@ config STMPE811_REGDEBUG endif # INPUT_STMPE811 +config INPUT_CYPRESS_MBR3108 + bool "Enable Cypress MBR3108 CapSense driver" + default n + ---help--- + Enable support for Cypress MBR3108 CapSense touch button & proximity + input sensor. + +if INPUT_CYPRESS_MBR3108 + +config INPUT_CYPRESS_MBR3108_DEBUG + bool "Enable debug support for Cypress sensor" + default n + depends on DEBUG_FEATURES + ---help--- + Enable debugging traces for MBR3108 driver + +config INPUT_CYPRESS_MBR3108_NPOLLWAITERS + int "Number of waiters to poll" + default 1 + ---help--- + Maximum number of threads that can be waiting on poll() + +endif # INPUT_CYPRESS_MBR3108 + config BUTTONS bool "Button Inputs" default n diff --git a/drivers/input/Make.defs b/drivers/input/Make.defs index 8285bfda0f..af98782596 100644 --- a/drivers/input/Make.defs +++ b/drivers/input/Make.defs @@ -71,6 +71,10 @@ ifneq ($(CONFIG_INPUT_STMPE811_TEMP_DISABLE),y) endif endif +ifeq ($(CONFIG_INPUT_CYPRESS_MBR3108),y) + CSRCS += cypress_mbr3108.c +endif + ifeq ($(CONFIG_BUTTONS),y) CSRCS += button_upper.c ifeq ($(CONFIG_BUTTONS_LOWER),y) diff --git a/drivers/input/cypress_mbr3108.c b/drivers/input/cypress_mbr3108.c new file mode 100644 index 0000000000..d1b29f672c --- /dev/null +++ b/drivers/input/cypress_mbr3108.c @@ -0,0 +1,1157 @@ +/**************************************************************************** + * drivers/input/cypress_mbr3108.c + * + * Copyright (C) 2014 Haltian Ltd. All rights reserved. + * Author: Jussi Kivilinna + * + * 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 + +#include + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +#ifdef CONFIG_INPUT_CYPRESS_MBR3108_DEBUG +# define mbr3108_dbg(x, ...) _info(x, ##__VA_ARGS__) +#else +# define mbr3108_dbg(x, ...) iinfo(x, ##__VA_ARGS__) +#endif + +/* Register macros */ + +#define MBR3108_SENSOR_EN 0x0 +#define MBR3108_FSS_EN 0x02 +#define MBR3108_TOGGLE_EN 0x04 +#define MBR3108_LED_ON_EN 0x06 +#define MBR3108_SENSITIVITY0 0x08 +#define MBR3108_SENSITIVITY1 0x09 +#define MBR3108_BASE_THRESHOLD0 0x0c +#define MBR3108_BASE_THRESHOLD1 0x0d +#define MBR3108_FINGER_THRESHOLD2 0x0e +#define MBR3108_FINGER_THRESHOLD3 0x0f +#define MBR3108_FINGER_THRESHOLD4 0x10 +#define MBR3108_FINGER_THRESHOLD5 0x11 +#define MBR3108_FINGER_THRESHOLD6 0x12 +#define MBR3108_FINGER_THRESHOLD7 0x13 +#define MBR3108_SENSOR_DEBOUNCE 0x1c +#define MBR3108_BUTTON_HYS 0x1d +#define MBR3108_BUTTON_LBR 0x1f +#define MBR3108_BUTTON_NNT 0x20 +#define MBR3108_BUTTON_NT 0x21 +#define MBR3108_PROX_EN 0x26 +#define MBR3108_PROX_CFG 0x27 +#define MBR3108_PROX_CFG2 0x28 +#define MBR3108_PROX_TOUCH_TH0 0x2a +#define MBR3108_PROX_TOUCH_TH1 0x2c +#define MBR3108_PROX_RESOLUTION0 0x2e +#define MBR3108_PROX_RESOLUTION1 0x2f +#define MBR3108_PROX_HYS 0x30 +#define MBR3108_PROX_LBR 0x32 +#define MBR3108_PROX_NNT 0x33 +#define MBR3108_PROX_NT 0x34 +#define MBR3108_PROX_POSITIVE_TH0 0x35 +#define MBR3108_PROX_POSITIVE_TH1 0x36 +#define MBR3108_PROX_NEGATIVE_TH0 0x39 +#define MBR3108_PROX_NEGATIVE_TH1 0x3a +#define MBR3108_LED_ON_TIME 0x3d +#define MBR3108_BUZZER_CFG 0x3e +#define MBR3108_BUZZER_ON_TIME 0x3f +#define MBR3108_GPO_CFG 0x40 +#define MBR3108_PWM_DUTYCYCLE_CFG0 0x41 +#define MBR3108_PWM_DUTYCYCLE_CFG1 0x42 +#define MBR3108_PWM_DUTYCYCLE_CFG2 0x43 +#define MBR3108_PWM_DUTYCYCLE_CFG3 0x44 +#define MBR3108_SPO_CFG 0x4c +#define MBR3108_DEVICE_CFG0 0x4d +#define MBR3108_DEVICE_CFG1 0x4e +#define MBR3108_DEVICE_CFG2 0x4f +#define MBR3108_DEVICE_CFG3 0x50 +#define MBR3108_I2C_ADDR 0x51 +#define MBR3108_REFRESH_CTRL 0x52 +#define MBR3108_STATE_TIMEOUT 0x55 +#define MBR3108_CONFIG_CRC 0x7e +#define MBR3108_GPO_OUTPUT_STATE 0x80 +#define MBR3108_SENSOR_ID 0x82 +#define MBR3108_CTRL_CMD 0x86 +#define MBR3108_CTRL_CMD_STATUS 0x88 +#define MBR3108_CTRL_CMD_ERR 0x89 +#define MBR3108_SYSTEM_STATUS 0x8a +#define MBR3108_PREV_CTRL_CMD_CODE 0x8c +#define MBR3108_FAMILY_ID 0x8f +#define MBR3108_DEVICE_ID 0x90 +#define MBR3108_DEVICE_REV 0x92 +#define MBR3108_CALC_CRC 0x94 +#define MBR3108_TOTAL_WORKING_SNS 0x97 +#define MBR3108_SNS_CP_HIGH 0x98 +#define MBR3108_SNS_VDD_SHORT 0x9a +#define MBR3108_SNS_GND_SHORT 0x9c +#define MBR3108_SNS_SNS_SHORT 0x9e +#define MBR3108_CMOD_SHIELD_TEST 0xa0 +#define MBR3108_BUTTON_STAT 0xaa +#define MBR3108_LATCHED_BUTTON_STAT 0xac +#define MBR3108_PROX_STAT 0xae +#define MBR3108_LATCHED_PROX_STAT 0xaf +#define MBR3108_SYNC_COUNTER0 0xb9 +#define MBR3108_DIFFERENCE_COUNT_SENSOR0 0xba +#define MBR3108_DIFFERENCE_COUNT_SENSOR1 0xbc +#define MBR3108_DIFFERENCE_COUNT_SENSOR2 0xbe +#define MBR3108_DIFFERENCE_COUNT_SENSOR3 0xc0 +#define MBR3108_DIFFERENCE_COUNT_SENSOR4 0xc2 +#define MBR3108_DIFFERENCE_COUNT_SENSOR5 0xc4 +#define MBR3108_DIFFERENCE_COUNT_SENSOR6 0xc6 +#define MBR3108_DIFFERENCE_COUNT_SENSOR7 0xc8 +#define MBR3108_GPO_DATA 0xda +#define MBR3108_SYNC_COUNTER1 0xdb +#define MBR3108_DEBUG_SENSOR_ID 0xdc +#define MBR3108_DEBUG_CP 0xdd +#define MBR3108_DEBUG_DIFFERENCE_COUNT0 0xde +#define MBR3108_DEBUG_BASELINE0 0xe0 +#define MBR3108_DEBUG_RAW_COUNT0 0xe2 +#define MBR3108_DEBUG_AVG_RAW_COUNT0 0xe4 +#define MBR3108_SYNC_COUNTER2 0xe7 + +/* Device commands for MBR3108_CTRL_CMD */ + +#define MBR3108_CMD_COMPLETED 0 +#define MBR3108_CMD_CHECK_CONFIG_CRC 2 +#define MBR3108_CMD_SET_CONFIG_CRC 3 +#define MBR3108_CMD_ENTER_LOW_POWER_MODE 7 +#define MBR3108_CMD_CLEAR_LATCHED 8 +#define MBR3108_CMD_RESET_ADV_LOWPASS_FILTER_PROX_SENS_0 9 +#define MBR3108_CMD_RESET_ADV_LOWPASS_FILTER_PROX_SENS_1 10 +#define MBR3108_CMD_SOFTWARE_RESET 255 + +#define MBR3108_CMD_STATUS_SUCCESS 0 +#define MBR3108_CMD_STATUS_ERROR 1 +#define MBR3108_CMD_STATUS_MASK 1 + +/* Completion times for device commands */ + +#define MBR3108_CMD_MSECS_CHECK_CONFIG_CRC 280 /* >220 (typ.) */ +#define MBR3108_CMD_MSECS_SOFTWARE_RESET 50 +#define MBR3108_CMD_MSECS_CLEAR_LATCHED 50 + +/* Other macros */ + +#define MBR3108_I2C_RETRIES 10 +#define MBR3108_NUM_SENSORS 8 +#define MBR3108_EXPECTED_FAMILY_ID 0x9a +#define MBR3108_EXPECTED_DEVICE_ID 0x0a03 +#define MBR3108_EXPECTED_DEVICE_REV 1 +#define MBR3108_SYNC_RETRIES 10 + +#ifndef CONFIG_MBR3108_I2C_FREQUENCY +# define CONFIG_MBR3108_I2C_FREQUENCY 400000 +#endif + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct mbr3108_dev_s +{ + /* I2C bus and address for device. */ + + struct i2c_master_s *i2c; + uint8_t addr; + + /* Configuration for device. */ + + struct mbr3108_board_s *board; + const struct mbr3108_sensor_conf_s *sensor_conf; + sem_t devsem; + uint8_t cref; + struct mbr3108_debug_conf_s debug_conf; + bool int_pending; + +#ifndef CONFIG_DISABLE_POLL + struct pollfd *fds[CONFIG_INPUT_CYPRESS_MBR3108_NPOLLWAITERS]; +#endif +}; + +/**************************************************************************** +* Private Function Prototypes +*****************************************************************************/ + +static int mbr3108_open(FAR struct file *filep); +static int mbr3108_close(FAR struct file *filep); +static ssize_t mbr3108_read(FAR struct file *filep, FAR char *buffer, + size_t buflen); +static ssize_t mbr3108_write(FAR struct file *filep, FAR const char *buffer, + size_t buflen); +#ifndef CONFIG_DISABLE_POLL +static int mbr3108_poll(FAR struct file *filep, FAR struct pollfd *fds, + bool setup); +#endif + +/**************************************************************************** +* Private Data +****************************************************************************/ + +static const struct file_operations g_mbr3108_fileops = +{ + mbr3108_open, /* open */ + mbr3108_close, /* close */ + mbr3108_read, /* read */ + mbr3108_write, /* write */ + 0, /* seek */ + 0 /* ioctl */ +#ifndef CONFIG_DISABLE_POLL + , mbr3108_poll /* poll */ +#endif +}; + +/**************************************************************************** +* Private Functions +****************************************************************************/ + +static int mbr3108_i2c_write(FAR struct mbr3108_dev_s *dev, uint8_t reg, + const uint8_t *buf, size_t buflen) +{ + struct i2c_msg_s msgv[2] = + { + { + .frequency = CONFIG_MBR3108_I2C_FREQUENCY, + .addr = dev->addr, + .flags = 0, + .buffer = ®, + .length = 1 + }, + { + .frequency = CONFIG_MBR3108_I2C_FREQUENCY, + .addr = dev->addr, + .flags = I2C_M_NORESTART, + .buffer = (void *)buf, + .length = buflen + } + }; + int ret = -EIO; + int retries; + + /* MBR3108 will respond with NACK to address when in low-power mode. Host + * needs to retry address selection multiple times to get MBR3108 to wake-up. + */ + + for (retries = 0; retries < MBR3108_I2C_RETRIES; retries++) + { + ret = I2C_TRANSFER(dev->i2c, msgv, 2); + if (ret == -ENXIO) + { + /* -ENXIO is returned when getting NACK from response. + * Keep trying. + */ + + continue; + } + + if (ret >= 0) + { + /* Success! */ + + return 0; + } + } + + /* Failed to read sensor. */ + + return ret; +} + +static int mbr3108_i2c_read(FAR struct mbr3108_dev_s *dev, uint8_t reg, + uint8_t *buf, size_t buflen) +{ + struct i2c_msg_s msgv[2] = + { + { + .frequency = CONFIG_MBR3108_I2C_FREQUENCY, + .addr = dev->addr, + .flags = 0, + .buffer = ®, + .length = 1 + }, + { + .frequency = CONFIG_MBR3108_I2C_FREQUENCY, + .addr = dev->addr, + .flags = I2C_M_READ, + .buffer = buf, + .length = buflen + } + }; + int ret = -EIO; + int retries; + + /* MBR3108 will respond with NACK to address when in low-power mode. Host + * needs to retry address selection multiple times to get MBR3108 to wake-up. + */ + + for (retries = 0; retries < MBR3108_I2C_RETRIES; retries++) + { + ret = I2C_TRANSFER(dev->i2c, msgv, 2); + if (ret == -ENXIO) + { + /* -ENXIO is returned when getting NACK from response. + * Keep trying. + */ + + continue; + } + else if (ret >= 0) + { + /* Success! */ + + return 0; + } + else + { + /* Some other error. Try to reset I2C bus and keep trying. */ + +#ifdef CONFIG_I2C_RESET + if (retries == MBR3108_I2C_RETRIES - 1) + { + break; + } + + ret = I2C_RESET(dev->i2c); + if (ret < 0) + { + mbr3108_dbg("I2C_RESET failed: %d\n", ret); + return ret; + } +#endif + } + } + + /* Failed to read sensor. */ + + return ret; +} + +static int mbr3108_check_cmd_status(FAR struct mbr3108_dev_s *dev) +{ + const uint8_t start_reg = MBR3108_CTRL_CMD; + const uint8_t last_reg = MBR3108_CTRL_CMD_ERR; + uint8_t readbuf[MBR3108_CTRL_CMD_ERR - MBR3108_CTRL_CMD + 1]; + uint8_t cmd, cmd_status, cmd_err; + int ret; + + DEBUGASSERT(last_reg - start_reg + 1 == sizeof(readbuf)); + + /* Multi-byte read to get command status. */ + + ret = mbr3108_i2c_read(dev, start_reg, readbuf, sizeof(readbuf)); + if (ret < 0) + { + mbr3108_dbg("cmd status get failed. ret=%d\n", ret); + return ret; + } + + cmd = readbuf[MBR3108_CTRL_CMD - MBR3108_CTRL_CMD]; + cmd_status = readbuf[MBR3108_CTRL_CMD_STATUS - MBR3108_CTRL_CMD]; + cmd_err = readbuf[MBR3108_CTRL_CMD_ERR - MBR3108_CTRL_CMD]; + + mbr3108_dbg("cmd: %d, status: %d, err: %d\n", cmd, cmd_status, cmd_err); + + if (cmd != MBR3108_CMD_COMPLETED) + { + return -EBUSY; + } + + if ((cmd_status & MBR3108_CMD_STATUS_MASK) == MBR3108_CMD_STATUS_SUCCESS) + { + /* Success. */ + + return 0; + } + + return cmd_err; +} + +static int mbr3108_save_check_crc(FAR struct mbr3108_dev_s *dev) +{ + uint8_t reg = MBR3108_CTRL_CMD; + uint8_t cmd = MBR3108_CMD_CHECK_CONFIG_CRC; + int ret; + + ret = mbr3108_i2c_write(dev, reg, &cmd, 1); + if (ret < 0) + { + mbr3108_dbg("MBR3108_CTRL_CMD:CHECK_CONFIG_CRC write failed.\n"); + return ret; + } + + usleep(MBR3108_CMD_MSECS_CHECK_CONFIG_CRC * 1000); + + ret = mbr3108_check_cmd_status(dev); + if (ret != 0) + { + return ret < 0 ? ret : -EIO; + } + + return 0; +} + +static int mbr3108_software_reset(FAR struct mbr3108_dev_s *dev) +{ + uint8_t reg = MBR3108_CTRL_CMD; + uint8_t cmd = MBR3108_CMD_SOFTWARE_RESET; + int ret; + + ret = mbr3108_i2c_write(dev, reg, &cmd, 1); + if (ret < 0) + { + mbr3108_dbg("MBR3108_CTRL_CMD:SOFTWARE_RESET write failed.\n"); + return ret; + } + + usleep(MBR3108_CMD_MSECS_SOFTWARE_RESET * 1000); + + ret = mbr3108_check_cmd_status(dev); + if (ret != 0) + { + return ret < 0 ? ret : -EIO; + } + + return 0; +} + +static int mbr3108_enter_low_power_mode(FAR struct mbr3108_dev_s *dev) +{ + uint8_t reg = MBR3108_CTRL_CMD; + uint8_t cmd = MBR3108_CMD_ENTER_LOW_POWER_MODE; + int ret; + + ret = mbr3108_i2c_write(dev, reg, &cmd, 1); + if (ret < 0) + { + mbr3108_dbg("MBR3108_CTRL_CMD:SOFTWARE_RESET write failed.\n"); + return ret; + } + + /* Device is now in low-power mode and not scanning. Further communication + * will cause wake-up and make chip resume scanning operations. + */ + + return 0; +} + +static int mbr3108_clear_latched(FAR struct mbr3108_dev_s *dev) +{ + uint8_t reg = MBR3108_CTRL_CMD; + uint8_t cmd = MBR3108_CMD_CLEAR_LATCHED; + int ret; + + ret = mbr3108_i2c_write(dev, reg, &cmd, 1); + if (ret < 0) + { + mbr3108_dbg("MBR3108_CTRL_CMD:MBR3108_CMD_CLEAR_LATCHED write failed.\n"); + return ret; + } + + usleep(MBR3108_CMD_MSECS_CLEAR_LATCHED * 1000); + + ret = mbr3108_check_cmd_status(dev); + if (ret != 0) + { + return ret < 0 ? ret : -EIO; + } + + return 0; +} + +static int mbr3108_debug_setup(FAR struct mbr3108_dev_s *dev, + FAR const struct mbr3108_debug_conf_s *conf) +{ + uint8_t reg = MBR3108_SENSOR_ID; + int ret; + + /* Store new debug configuration. */ + + dev->debug_conf = *conf; + + if (!conf->debug_mode) + { + return 0; + } + + /* Setup debug sensor id. */ + + ret = mbr3108_i2c_write(dev, reg, &conf->debug_sensor_id, 1); + if (ret < 0) + { + mbr3108_dbg("MBR3108_SENSOR_ID write failed.\n"); + + dev->debug_conf.debug_mode = false; + } + + return ret; +} + +static int mbr3108_device_configuration(FAR struct mbr3108_dev_s *dev, + FAR const struct mbr3108_sensor_conf_s *conf) +{ + const uint8_t start_reg = MBR3108_SENSOR_EN; + const uint8_t last_reg = MBR3108_CONFIG_CRC + 1; + uint8_t value; + int ret = 0; + + DEBUGASSERT(sizeof(conf->conf_data) == last_reg - start_reg + 1); + + ret = mbr3108_i2c_read(dev, MBR3108_CTRL_CMD, &value, 1); + if (ret < 0) + { + mbr3108_dbg("MBR3108_CTRL_CMD read failed.\n"); + return ret; + } + + if (value != MBR3108_CMD_COMPLETED) + { + /* Device is busy processing previous command. */ + + return -EBUSY; + } + + ret = mbr3108_i2c_write(dev, start_reg, conf->conf_data, + last_reg - start_reg + 1); + if (ret < 0) + { + mbr3108_dbg("MBR3108 configuration write failed.\n"); + return ret; + } + + ret = mbr3108_save_check_crc(dev); + if (ret < 0) + { + mbr3108_dbg("MBR3108 save check CRC failed. ret=%d\n", ret); + return ret; + } + + ret = mbr3108_software_reset(dev); + if (ret < 0) + { + mbr3108_dbg("MBR3108 software reset failed.\n"); + return ret; + } + + dev->board->irq_enable(dev->board, true); + + return 0; +} + +static int mbr3108_get_sensor_status(FAR struct mbr3108_dev_s *dev, + FAR void *buf) +{ + struct mbr3108_sensor_status_s status = {}; + const uint8_t start_reg = MBR3108_BUTTON_STAT; + const uint8_t last_reg = MBR3108_LATCHED_PROX_STAT; + uint8_t readbuf[MBR3108_LATCHED_PROX_STAT - MBR3108_BUTTON_STAT + 1]; + int ret; + + DEBUGASSERT(last_reg - start_reg + 1 == sizeof(readbuf)); + + /* Attempt to sensor status registers.*/ + + ret = mbr3108_i2c_read(dev, start_reg, readbuf, sizeof(readbuf)); + if (ret < 0) + { + mbr3108_dbg("Sensor status read failed.\n"); + + return ret; + } + + status.button = (readbuf[MBR3108_BUTTON_STAT + 0 - start_reg]) | + (readbuf[MBR3108_BUTTON_STAT + 1 - start_reg] << 8); + status.proximity = readbuf[MBR3108_PROX_STAT - start_reg]; + + status.latched_button = + (readbuf[MBR3108_LATCHED_BUTTON_STAT + 0 - start_reg]) | + (readbuf[MBR3108_LATCHED_BUTTON_STAT + 1 - start_reg] << 8); + status.latched_proximity = readbuf[MBR3108_LATCHED_PROX_STAT - start_reg]; + + memcpy(buf, &status, sizeof(status)); + + mbr3108_dbg("but: %x, prox: %x; latched[btn: %x, prox: %x]\n", + status.button, status.proximity, status.latched_button, + status.latched_button); + + return 0; +} + +static int mbr3108_get_sensor_debug_data(FAR struct mbr3108_dev_s *dev, + FAR void *buf) +{ + struct mbr3108_sensor_debug_s data = {}; + const uint8_t start_reg = MBR3108_SYNC_COUNTER1; + const uint8_t last_reg = MBR3108_SYNC_COUNTER2; + uint8_t readbuf[MBR3108_SYNC_COUNTER2 - MBR3108_SYNC_COUNTER1 + 1]; + int ret; + int retries; + uint8_t sync1, sync2; + + DEBUGASSERT(last_reg - start_reg + 1 == sizeof(readbuf)); + + for (retries = MBR3108_SYNC_RETRIES; retries > 0; retries--) + { + ret = mbr3108_i2c_read(dev, start_reg, readbuf, sizeof(readbuf)); + if (ret < 0) + { + mbr3108_dbg("Sensor debug data read failed.\n"); + + return ret; + } + + /* Sync counters need to match. */ + + sync1 = readbuf[MBR3108_SYNC_COUNTER1 - start_reg]; + sync2 = readbuf[MBR3108_SYNC_COUNTER2 - start_reg]; + + if (sync1 == sync2) + { + break; + } + } + + if (retries == 0) + { + return -EIO; + } + + data.sensor_average_counts = + (readbuf[MBR3108_DEBUG_AVG_RAW_COUNT0 + 0 - start_reg]) | + (readbuf[MBR3108_DEBUG_AVG_RAW_COUNT0 + 1 - start_reg] << 8); + data.sensor_baseline = + (readbuf[MBR3108_DEBUG_BASELINE0 + 0 - start_reg]) | + (readbuf[MBR3108_DEBUG_BASELINE0 + 1 - start_reg] << 8); + data.sensor_diff_counts = + (readbuf[MBR3108_DEBUG_DIFFERENCE_COUNT0 + 0 - start_reg]) | + (readbuf[MBR3108_DEBUG_DIFFERENCE_COUNT0 + 1 - start_reg] << 8); + data.sensor_raw_counts = + (readbuf[MBR3108_DEBUG_RAW_COUNT0 + 0 - start_reg]) | + (readbuf[MBR3108_DEBUG_RAW_COUNT0 + 1 - start_reg] << 8); + data.sensor_total_capacitance = readbuf[MBR3108_DEBUG_CP - start_reg]; + + memcpy(buf, &data, sizeof(data)); + + mbr3108_dbg("avg_cnt: %d, baseline: %d, diff_cnt: %d, raw_cnt: %d, " + "total_cp: %d\n", + data.sensor_average_counts, data.sensor_baseline, + data.sensor_diff_counts, data.sensor_raw_counts, + data.sensor_total_capacitance); + + return 0; +} + +static int mbr3108_probe_device(FAR struct mbr3108_dev_s *dev) +{ + const uint8_t start_reg = MBR3108_FAMILY_ID; + const uint8_t last_reg = MBR3108_DEVICE_REV; + uint8_t readbuf[MBR3108_DEVICE_REV - MBR3108_FAMILY_ID + 1]; + uint8_t fam_id; + uint16_t dev_id; + uint8_t dev_rev; + int ret; + + DEBUGASSERT(last_reg - start_reg + 1 == sizeof(readbuf)); + + /* Attempt to read device identification registers with multi-byte read.*/ + + ret = mbr3108_i2c_read(dev, start_reg, readbuf, sizeof(readbuf)); + if (ret < 0) + { + /* Failed to read registers from device. */ + + mbr3108_dbg("Probe failed.\n"); + + return ret; + } + + /* Check result. */ + + fam_id = readbuf[MBR3108_FAMILY_ID - start_reg]; + dev_id = (readbuf[MBR3108_DEVICE_ID + 0 - start_reg]) | + (readbuf[MBR3108_DEVICE_ID + 1 - start_reg] << 8); + dev_rev = readbuf[MBR3108_DEVICE_REV - start_reg]; + + mbr3108_dbg("family_id: 0x%02x, device_id: 0x%04x, device_rev: %d\n", + fam_id, dev_id, dev_rev); + + if (fam_id != MBR3108_EXPECTED_FAMILY_ID || + dev_id != MBR3108_EXPECTED_DEVICE_ID || + dev_rev != MBR3108_EXPECTED_DEVICE_REV) + { + mbr3108_dbg("Probe failed, dev-id mismatch!\n"); + mbr3108_dbg( + " Expected: family_id: 0x%02x, device_id: 0x%04x, device_rev: %d\n", + MBR3108_EXPECTED_FAMILY_ID, + MBR3108_EXPECTED_DEVICE_ID, + MBR3108_EXPECTED_DEVICE_REV); + + return -ENXIO; + } + + return 0; +} + +static ssize_t mbr3108_read(FAR struct file *filep, FAR char *buffer, + size_t buflen) +{ + FAR struct inode *inode; + FAR struct mbr3108_dev_s *priv; + size_t outlen; + irqstate_t flags; + int ret; + + DEBUGASSERT(filep); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = inode->i_private; + + ret = sem_wait(&priv->devsem); + if (ret < 0) + { + return ret; + } + + ret = -EINVAL; + + if (priv->debug_conf.debug_mode) + { + outlen = sizeof(struct mbr3108_sensor_debug_s); + if (buflen >= outlen) + { + ret = mbr3108_get_sensor_debug_data(priv, buffer); + } + } + else + { + outlen = sizeof(struct mbr3108_sensor_status_s); + if (buflen >= outlen) + { + ret = mbr3108_get_sensor_status(priv, buffer); + } + } + + flags = enter_critical_section(); + priv->int_pending = false; + leave_critical_section(flags); + + sem_post(&priv->devsem); + return ret < 0 ? ret : outlen; +} + +static ssize_t mbr3108_write(FAR struct file *filep, FAR const char *buffer, + size_t buflen) +{ + FAR struct inode *inode; + FAR struct mbr3108_dev_s *priv; + enum mbr3108_cmd_e type; + int ret; + + DEBUGASSERT(filep); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = inode->i_private; + + if (buflen < sizeof(enum mbr3108_cmd_e)) + { + return -EINVAL; + } + + ret = sem_wait(&priv->devsem); + if (ret < 0) + { + return ret; + } + + type = *(FAR const enum mbr3108_cmd_e *)buffer; + + switch (type) + { + case CYPRESS_MBR3108_CMD_SENSOR_CONF: + { + FAR const struct mbr3108_cmd_sensor_conf_s *conf = + (FAR const struct mbr3108_cmd_sensor_conf_s *)buffer; + + if (buflen != sizeof(*conf)) + { + ret = -EINVAL; + goto out; + } + + ret = mbr3108_device_configuration(priv, &conf->conf); + break; + } + + case CYPRESS_MBR3108_CMD_DEBUG_CONF: + { + FAR const struct mbr3108_cmd_debug_conf_s *conf = + (FAR const struct mbr3108_cmd_debug_conf_s *)buffer; + + if (buflen != sizeof(*conf)) + { + ret = -EINVAL; + goto out; + } + + ret = mbr3108_debug_setup(priv, &conf->conf); + break; + } + + case CYPRESS_MBR3108_CMD_CLEAR_LATCHED: + { + if (buflen != sizeof(type)) + { + ret = -EINVAL; + goto out; + } + + ret = mbr3108_clear_latched(priv); + break; + } + + default: + ret = -EINVAL; + break; + } + +out: + sem_post(&priv->devsem); + + return ret < 0 ? ret : buflen; +} + +static int mbr3108_open(FAR struct file *filep) +{ + FAR struct inode *inode; + FAR struct mbr3108_dev_s *priv; + unsigned int use_count; + int ret; + + DEBUGASSERT(filep); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = inode->i_private; + + while (sem_wait(&priv->devsem) != 0) + { + assert(errno == EINTR); + } + + use_count = priv->cref + 1; + if (use_count == 1) + { + /* First user, do power on. */ + + ret = priv->board->set_power(priv->board, true); + if (ret < 0) + { + goto out_sem; + } + + /* Let chip to power up before probing */ + + usleep(100 * 1000); + + /* Check that device exists on I2C. */ + + ret = mbr3108_probe_device(priv); + if (ret < 0) + { + /* No such device. Power off the switch. */ + + (void)priv->board->set_power(priv->board, false); + goto out_sem; + } + + if (priv->sensor_conf) + { + /* Do configuration. */ + + ret = mbr3108_device_configuration(priv, priv->sensor_conf); + if (ret < 0) + { + /* Configuration failed. Power off the switch. */ + + (void)priv->board->set_power(priv->board, false); + goto out_sem; + } + } + + priv->cref = use_count; + } + else + { + DEBUGASSERT(use_count < UINT8_MAX && use_count > priv->cref); + + priv->cref = use_count; + ret = 0; + } + +out_sem: + sem_post(&priv->devsem); + return ret; +} + +static int mbr3108_close(FAR struct file *filep) +{ + FAR struct inode *inode; + FAR struct mbr3108_dev_s *priv; + int use_count; + + DEBUGASSERT(filep); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = inode->i_private; + + while (sem_wait(&priv->devsem) != 0) + { + assert(errno == EINTR); + } + + use_count = priv->cref - 1; + if (use_count == 0) + { + /* Disable interrupt */ + + priv->board->irq_enable(priv->board, false); + + /* Set chip in low-power mode. */ + + (void)mbr3108_enter_low_power_mode(priv); + + /* Last user, do power off. */ + + (void)priv->board->set_power(priv->board, false); + + priv->debug_conf.debug_mode = false; + priv->cref = use_count; + } + else + { + DEBUGASSERT(use_count > 0); + + priv->cref = use_count; + } + + sem_post(&priv->devsem); + + return 0; +} + +#ifndef CONFIG_DISABLE_POLL + +static void mbr3108_poll_notify(FAR struct mbr3108_dev_s *priv) +{ + int i; + + DEBUGASSERT(priv != NULL); + + for (i = 0; i < CONFIG_INPUT_CYPRESS_MBR3108_NPOLLWAITERS; i++) + { + struct pollfd *fds = priv->fds[i]; + if (fds) + { + mbr3108_dbg("Report events: %02x\n", fds->revents); + + fds->revents |= POLLIN; + sem_post(fds->sem); + } + } +} + +static int mbr3108_poll(FAR struct file *filep, FAR struct pollfd *fds, + bool setup) +{ + FAR struct mbr3108_dev_s *priv; + FAR struct inode *inode; + bool pending; + int ret = 0; + int i; + + DEBUGASSERT(filep && fds); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct mbr3108_dev_s *)inode->i_private; + + ret = sem_wait(&priv->devsem); + if (ret < 0) + { + return ret; + } + + 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_INPUT_CYPRESS_MBR3108_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_INPUT_CYPRESS_MBR3108_NPOLLWAITERS) + { + fds->priv = NULL; + ret = -EBUSY; + } + else + { + pending = priv->int_pending; + if (pending) + { + mbr3108_poll_notify(priv); + } + } + } + else if (fds->priv) + { + /* This is a request to tear down the poll. */ + + FAR struct pollfd **slot = (FAR 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; +} + +#endif /* !CONFIG_DISABLE_POLL */ + +static int mbr3108_isr_handler(int irq, FAR void *context, FAR void *arg) +{ + FAR struct mbr3108_dev_s *priv = (FAR struct mbr3108_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 + mbr3108_poll_notify(priv); +#endif + return 0; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +int cypress_mbr3108_register(FAR const char *devpath, + FAR struct i2c_master_s *i2c_dev, + uint8_t i2c_devaddr, + struct mbr3108_board_s *board_config, + const struct mbr3108_sensor_conf_s *sensor_conf) +{ + struct mbr3108_dev_s *priv; + int ret = 0; + + /* Allocate device private structure. */ + + priv = kmm_zalloc(sizeof(struct mbr3108_dev_s)); + if (!priv) + { + mbr3108_dbg("Memory cannot be allocated for mbr3108 sensor\n"); + return -ENOMEM; + } + + /* Setup device structure. */ + + priv->addr = i2c_devaddr; + priv->i2c = i2c_dev; + priv->board = board_config; + priv->sensor_conf = sensor_conf; + + sem_init(&priv->devsem, 0, 1); + + ret = register_driver(devpath, &g_mbr3108_fileops, 0666, priv); + if (ret < 0) + { + kmm_free(priv); + mbr3108_dbg("Error occurred during the driver registering\n"); + return ret; + } + + mbr3108_dbg("Registered with %d\n", ret); + + /* Prepare interrupt line and handler. */ + + priv->board->irq_attach(priv->board, mbr3108_isr_handler, priv); + priv->board->irq_enable(priv->board, false); + + return 0; +} diff --git a/include/nuttx/input/cypress_mbr3108.h b/include/nuttx/input/cypress_mbr3108.h new file mode 100644 index 0000000000..941de91cc0 --- /dev/null +++ b/include/nuttx/input/cypress_mbr3108.h @@ -0,0 +1,139 @@ +/**************************************************************************** + * include/nuttx/input/cypress_mbr3108.c + * + * Copyright (C) 2014 Haltian Ltd. All rights reserved. + * Author: Jussi Kivilinna + * + * 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_INPUT_CYPRESS_MBR3108_H_ +#define __INCLUDE_NUTTX_INPUT_CYPRESS_MBR3108_H_ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* Sensor configuration for Cypress MBR3108 device */ + +begin_packed_struct struct mbr3108_sensor_conf_s +{ + uint8_t conf_data[128]; /* Sensor configuration, generated with EZ-Click. */ +} end_packed_struct; + +/* Debug configuration */ + +begin_packed_struct struct mbr3108_debug_conf_s +{ + bool debug_mode; /* Configure to debug mode if 'true'. */ + uint8_t debug_sensor_id; /* Sensor to read in debug mode. */ +} end_packed_struct; + +/* Write commands to MBR3108 driver. */ + +begin_packed_struct enum mbr3108_cmd_e +{ + CYPRESS_MBR3108_CMD_SENSOR_CONF = -3, + CYPRESS_MBR3108_CMD_DEBUG_CONF, + CYPRESS_MBR3108_CMD_CLEAR_LATCHED, +} end_packed_struct; + +/* CYPRESS_MBR3108_CMD_SENSOR_CONF command structure. Used to reconfigure + * chip with new configuration generated using EZ-Click tool. */ + +begin_packed_struct struct mbr3108_cmd_sensor_conf_s +{ + enum mbr3108_cmd_e id; + struct mbr3108_sensor_conf_s conf; +} end_packed_struct; + +/* CYPRESS_MBR3108_CMD_DEBUG_CONF command structure. Use to enable debug + * output from chip/sensor, see 'struct mbr3108_sensor_data_s'. */ + +begin_packed_struct struct mbr3108_cmd_debug_conf_s +{ + enum mbr3108_cmd_e id; + struct mbr3108_debug_conf_s conf; +} end_packed_struct; + +/* Sensor status output */ + +begin_packed_struct struct mbr3108_sensor_status_s +{ + unsigned int button:8; /* MBR3108 has maximum of 8 button sensors + * configurable. + * Each bit in this field indicate if + * corresponding button is pressed. */ + unsigned int latched_button:8; + unsigned int proximity:2; /* MBR3108 has maximum of 2 proximity + * sensors configurable. */ + unsigned int latched_proximity:2; +} end_packed_struct; + +/* Sensor debug data output */ + +begin_packed_struct struct mbr3108_sensor_debug_s +{ + uint8_t sensor_total_capacitance; + uint16_t sensor_diff_counts; + uint16_t sensor_baseline; + uint16_t sensor_raw_counts; + uint16_t sensor_average_counts; +} end_packed_struct; + +/* Board configuration */ + +struct mbr3108_board_s +{ + int (*irq_attach) (FAR struct mbr3108_board_s *state, xcpt_t isr, FAR void *arg); + void (*irq_enable) (FAR struct mbr3108_board_s *state, bool enable); + int (*set_power) (FAR struct mbr3108_board_s *state, bool on); +}; + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/* Device registration */ + +int cypress_mbr3108_register(FAR const char *devpath, + FAR struct i2c_master_s *dev, + uint8_t i2c_devaddr, + struct mbr3108_board_s *board_config, + const struct mbr3108_sensor_conf_s *sensor_conf); + +#endif /* __INCLUDE_NUTTX_INPUT_CYPRESS_MBR3108_H_ */ -- GitLab From 14c233a2f5ee5ce4e8261f52311090d3e1a3417c Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Wed, 31 May 2017 06:34:14 -0600 Subject: [PATCH 889/990] STM32L4: gpio: put back EXTI line source selection --- arch/arm/src/stm32l4/stm32l4_gpio.c | 17 +++++++---------- 1 file changed, 7 insertions(+), 10 deletions(-) diff --git a/arch/arm/src/stm32l4/stm32l4_gpio.c b/arch/arm/src/stm32l4/stm32l4_gpio.c index 049c40fd2c..f46f341662 100644 --- a/arch/arm/src/stm32l4/stm32l4_gpio.c +++ b/arch/arm/src/stm32l4/stm32l4_gpio.c @@ -309,17 +309,15 @@ int stm32l4_configgpio(uint32_t cfgset) /* Otherwise, it is an input pin. Should it configured as an EXTI interrupt? */ - if ((cfgset & GPIO_EXTI) != 0) + if (pinmode != GPIO_MODER_OUTPUT && (cfgset & GPIO_EXTI) != 0) { -#if 0 - /* "In STM32 F1 the selection of the EXTI line source is performed through - * the EXTIx bits in the AFIO_EXTICRx registers, while in F2 series this - * selection is done through the EXTIx bits in the SYSCFG_EXTICRx registers. + /* The selection of the EXTI line source is performed through the EXTIx + * bits in the SYSCFG_EXTICRx registers. * - * "Only the mapping of the EXTICRx registers has been changed, without any - * changes to the meaning of the EXTIx bits. However, the range of EXTI - * bits values has been extended to 0b1000 to support the two ports added - * in F2, port H and I (in F1 series the maximum value is 0b0110)." + * The range of EXTI bit values in STM32L4x6 goes to 0b1000 to support the + * ports up to PI in STM32L496xx devices. For STM32L4x3 the EXTI bit values + * end at 0b111 (for PH0, PH1 and PH3 only) and values for non-existent + * ports F and G are reserved. */ uint32_t regaddr; @@ -334,7 +332,6 @@ int stm32l4_configgpio(uint32_t cfgset) regval |= (((uint32_t)port) << shift); putreg32(regval, regaddr); -#endif } leave_critical_section(flags); -- GitLab From c7fcdf968d797488f9aae8ed8255a66a1ec2b74d Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Wed, 31 May 2017 09:07:25 -0600 Subject: [PATCH 890/990] mtd/smart: Fix use of uninitialized variable --- drivers/mtd/smart.c | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/drivers/mtd/smart.c b/drivers/mtd/smart.c index c5c6e80a3e..e483bc99d3 100644 --- a/drivers/mtd/smart.c +++ b/drivers/mtd/smart.c @@ -1368,7 +1368,8 @@ static int smart_add_sector_to_cache(FAR struct smart_struct_s *dev, index = 1; if (dev->cache_entries < CONFIG_MTD_SMART_SECTOR_CACHE_SIZE) { - index = dev->cache_entries++; + oldest = 0; + index = dev->cache_entries++; } else { @@ -1387,7 +1388,7 @@ static int smart_add_sector_to_cache(FAR struct smart_struct_s *dev, if (dev->sCache[x].birth < oldest) { oldest = dev->sCache[x].birth; - index = x; + index = x; } } } -- GitLab From 8b006e705e9a81c94793aa3fb79c330d91382523 Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Wed, 31 May 2017 09:09:24 -0600 Subject: [PATCH 891/990] drivers/mtd/w25.c: erase sector only if it is not in erased state --- drivers/mtd/w25.c | 59 +++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 59 insertions(+) diff --git a/drivers/mtd/w25.c b/drivers/mtd/w25.c index 79ac0a5a66..fb292217a7 100644 --- a/drivers/mtd/w25.c +++ b/drivers/mtd/w25.c @@ -247,6 +247,7 @@ static void w25_unprotect(FAR struct w25_dev_s *priv); static uint8_t w25_waitwritecomplete(FAR struct w25_dev_s *priv); static inline void w25_wren(FAR struct w25_dev_s *priv); static inline void w25_wrdi(FAR struct w25_dev_s *priv); +static bool w25_is_erased(struct w25_dev_s *priv, off_t address, off_t size); static void w25_sectorerase(FAR struct w25_dev_s *priv, off_t offset); static inline int w25_chiperase(FAR struct w25_dev_s *priv); static void w25_byteread(FAR struct w25_dev_s *priv, FAR uint8_t *buffer, @@ -549,6 +550,55 @@ static inline void w25_wrdi(struct w25_dev_s *priv) SPI_SELECT(priv->spi, SPIDEV_FLASH(0), false); } +/************************************************************************************ + * Name: w25_is_erased + ************************************************************************************/ + +static bool w25_is_erased(struct w25_dev_s *priv, off_t address, off_t size) +{ + size_t npages = size >> W25_PAGE_SHIFT; + uint32_t erased_32; + unsigned int i; + uint32_t *buf; + + DEBUGASSERT((address % W25_PAGE_SIZE) == 0); + DEBUGASSERT((size % W25_PAGE_SIZE) == 0); + + buf = kmm_malloc(W25_PAGE_SIZE); + if (!buf) + { + return false; + } + + memset(&erased_32, W25_ERASED_STATE, sizeof(erased_32)); + + /* Walk all pages in given area. */ + + while (npages) + { + /* Check if all bytes of page is in erased state. */ + + w25_byteread(priv, (unsigned char *)buf, address, W25_PAGE_SIZE); + + for (i = 0; i < W25_PAGE_SIZE / sizeof(uint32_t); i++) + { + if (buf[i] != erased_32) + { + /* Page not in erased state! */ + + kmm_free(buf); + return false; + } + } + + address += W25_PAGE_SIZE; + npages--; + } + + kmm_free(buf); + return true; +} + /************************************************************************************ * Name: w25_sectorerase ************************************************************************************/ @@ -559,6 +609,15 @@ static void w25_sectorerase(struct w25_dev_s *priv, off_t sector) finfo("sector: %08lx\n", (long)sector); + /* Check if sector is already erased. */ + + if (w25_is_erased(priv, address, W25_SECTOR_SIZE)) + { + /* Sector already in erased state, so skip erase. */ + + return; + } + /* Wait for any preceding write or erase operation to complete. */ (void)w25_waitwritecomplete(priv); -- GitLab From 369b72f65a44dc067bab40a6d7c0482a0ef5f176 Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Wed, 31 May 2017 09:13:20 -0600 Subject: [PATCH 892/990] stm32f7: Add SPI DMA support --- arch/arm/src/stm32f7/stm32_spi.c | 70 ++++++++++++++++++++++---------- 1 file changed, 49 insertions(+), 21 deletions(-) diff --git a/arch/arm/src/stm32f7/stm32_spi.c b/arch/arm/src/stm32f7/stm32_spi.c index c00e717a09..d6b4cb9e9c 100644 --- a/arch/arm/src/stm32f7/stm32_spi.c +++ b/arch/arm/src/stm32f7/stm32_spi.c @@ -80,6 +80,7 @@ #include "up_internal.h" #include "up_arch.h" +#include "cache.h" #include "chip.h" #include "stm32_gpio.h" #include "stm32_dma.h" @@ -110,12 +111,10 @@ #ifdef CONFIG_STM32F7_SPI_DMA -# error "SPI DMA not yet supported" - # if defined(CONFIG_SPI_DMAPRIO) # define SPI_DMA_PRIO CONFIG_SPI_DMAPRIO # elif defined(DMA_SCR_PRIMED) -# define SPI_DMA_PRIO DMA_SCR_PRIMED +# define SPI_DMA_PRIO DMA_SCR_PRILO # else # error "Unknown STM32 DMA" # endif @@ -264,8 +263,8 @@ static struct stm32_spidev_s g_spi1dev = .spiirq = STM32_IRQ_SPI1, #endif #ifdef CONFIG_STM32F7_SPI_DMA - .rxch = DMACHAN_SPI1_RX, - .txch = DMACHAN_SPI1_TX, + .rxch = DMAMAP_SPI1_RX, + .txch = DMAMAP_SPI1_TX, #endif }; #endif @@ -308,8 +307,8 @@ static struct stm32_spidev_s g_spi2dev = .spiirq = STM32_IRQ_SPI2, #endif #ifdef CONFIG_STM32F7_SPI_DMA - .rxch = DMACHAN_SPI2_RX, - .txch = DMACHAN_SPI2_TX, + .rxch = DMAMAP_SPI2_RX, + .txch = DMAMAP_SPI2_TX, #endif }; #endif @@ -352,8 +351,8 @@ static struct stm32_spidev_s g_spi3dev = .spiirq = STM32_IRQ_SPI3, #endif #ifdef CONFIG_STM32F7_SPI_DMA - .rxch = DMACHAN_SPI3_RX, - .txch = DMACHAN_SPI3_TX, + .rxch = DMAMAP_SPI3_RX, + .txch = DMAMAP_SPI3_TX, #endif }; #endif @@ -396,8 +395,8 @@ static struct stm32_spidev_s g_spi4dev = .spiirq = STM32_IRQ_SPI4, #endif #ifdef CONFIG_STM32F7_SPI_DMA - .rxch = DMACHAN_SPI4_RX, - .txch = DMACHAN_SPI4_TX, + .rxch = DMAMAP_SPI4_RX, + .txch = DMAMAP_SPI4_TX, #endif }; #endif @@ -440,8 +439,8 @@ static struct stm32_spidev_s g_spi5dev = .spiirq = STM32_IRQ_SPI5, #endif #ifdef CONFIG_STM32F7_SPI_DMA - .rxch = DMACHAN_SPI5_RX, - .txch = DMACHAN_SPI5_TX, + .rxch = DMAMAP_SPI5_RX, + .txch = DMAMAP_SPI5_TX, #endif }; #endif @@ -484,8 +483,8 @@ static struct stm32_spidev_s g_spi6dev = .spiirq = STM32_IRQ_SPI6, #endif #ifdef CONFIG_STM32F7_SPI_DMA - .rxch = DMACHAN_SPI6_RX, - .txch = DMACHAN_SPI6_TX, + .rxch = DMAMAP_SPI6_RX, + .txch = DMAMAP_SPI6_TX, #endif }; #endif @@ -927,7 +926,7 @@ static void spi_dmatxsetup(FAR struct stm32_spidev_s *priv, FAR const void *txbu ************************************************************************************/ #ifdef CONFIG_STM32F7_SPI_DMA -static inline void spi_dmarxstart(FAR struct stm32_spidev_s *priv) +static void spi_dmarxstart(FAR struct stm32_spidev_s *priv) { priv->rxresult = 0; stm32_dmastart(priv->rxdma, spi_dmarxcallback, priv, false); @@ -943,7 +942,7 @@ static inline void spi_dmarxstart(FAR struct stm32_spidev_s *priv) ************************************************************************************/ #ifdef CONFIG_STM32F7_SPI_DMA -static inline void spi_dmatxstart(FAR struct stm32_spidev_s *priv) +static void spi_dmatxstart(FAR struct stm32_spidev_s *priv) { priv->txresult = 0; stm32_dmastart(priv->txdma, spi_dmatxcallback, priv, false); @@ -1528,6 +1527,8 @@ static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer, { FAR struct stm32_spidev_s *priv = (FAR struct stm32_spidev_s *)dev; + DEBUGASSERT(priv != NULL); + #ifdef CONFIG_STM32F7_DMACAPABLE if ((txbuffer && !stm32_dmacapable((uint32_t)txbuffer, nwords, priv->txccr)) || (rxbuffer && !stm32_dmacapable((uint32_t)rxbuffer, nwords, priv->rxccr))) @@ -1539,17 +1540,31 @@ static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer, else #endif { - static uint16_t rxdummy = 0xffff; + static uint8_t rxdummy[ARMV7M_DCACHE_LINESIZE] + __attribute__((aligned(ARMV7M_DCACHE_LINESIZE))); static const uint16_t txdummy = 0xffff; + size_t buflen = nwords; + + if (spi_9to16bitmode(priv)) + { + buflen = nwords * sizeof(uint16_t); + } spiinfo("txbuffer=%p rxbuffer=%p nwords=%d\n", txbuffer, rxbuffer, nwords); - DEBUGASSERT(priv && priv->spibase); + DEBUGASSERT(priv->spibase != 0); /* Setup DMAs */ - spi_dmarxsetup(priv, rxbuffer, &rxdummy, nwords); + spi_dmarxsetup(priv, rxbuffer, (uint16_t *)rxdummy, nwords); spi_dmatxsetup(priv, txbuffer, &txdummy, nwords); + /* Flush cache to physical memory */ + + if (txbuffer) + { + arch_flush_dcache((uintptr_t)txbuffer, (uintptr_t)txbuffer + buflen); + } + /* Start the DMAs */ spi_dmarxstart(priv); @@ -1559,6 +1574,19 @@ static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer, spi_dmarxwait(priv); spi_dmatxwait(priv); + + /* Force RAM re-read */ + + if (rxbuffer) + { + arch_invalidate_dcache((uintptr_t)rxbuffer, + (uintptr_t)rxbuffer + buflen); + } + else + { + arch_invalidate_dcache((uintptr_t)rxdummy, + (uintptr_t)rxdummy + sizeof(rxdummy)); + } } } #endif /* CONFIG_STM32F7_SPI_DMA */ @@ -1694,7 +1722,7 @@ static void spi_bus_initialize(FAR struct stm32_spidev_s *priv) priv->txdma = stm32_dmachannel(priv->txch); DEBUGASSERT(priv->rxdma && priv->txdma); - spi_putreg(priv, STM32_SPI_CR2_OFFSET, SPI_CR2_RXDMAEN | SPI_CR2_TXDMAEN); + spi_modifycr2(priv, SPI_CR2_RXDMAEN | SPI_CR2_TXDMAEN, 0); #endif /* Enable spi */ -- GitLab From 7af5cbb833146b9bd7fec18f54fa054dd59ab87f Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Wed, 31 May 2017 09:17:58 -0600 Subject: [PATCH 893/990] drivers/mtd/w25.c: Enable short delay after sector/chip erase --- drivers/mtd/w25.c | 15 +++++++++++---- 1 file changed, 11 insertions(+), 4 deletions(-) diff --git a/drivers/mtd/w25.c b/drivers/mtd/w25.c index fb292217a7..458c85e092 100644 --- a/drivers/mtd/w25.c +++ b/drivers/mtd/w25.c @@ -224,6 +224,7 @@ struct w25_dev_s struct mtd_dev_s mtd; /* MTD interface */ FAR struct spi_dev_s *spi; /* Saved SPI interface instance */ uint16_t nsectors; /* Number of erase sectors */ + uint8_t prev_instr; /* Previous instruction given to W25 device */ #if defined(CONFIG_W25_SECTOR512) && !defined(CONFIG_W25_READONLY) uint8_t flags; /* Buffered sector flags */ @@ -495,17 +496,17 @@ static uint8_t w25_waitwritecomplete(struct w25_dev_s *priv) /* Given that writing could take up to few tens of milliseconds, and erasing * could take more. The following short delay in the "busy" case will allow - * other peripherals to access the SPI bus. + * other peripherals to access the SPI bus. Delay would slow down writing + * too much, so go to sleep only if previous operation was not a page program + * operation. */ -#if 0 /* Makes writes too slow */ - if ((status & W25_SR_BUSY) != 0) + if (priv->prev_instr != W25_PP && (status & W25_SR_BUSY) != 0) { w25_unlock(priv->spi); usleep(1000); w25_lock(priv->spi); } -#endif } while ((status & W25_SR_BUSY) != 0); @@ -633,6 +634,7 @@ static void w25_sectorerase(struct w25_dev_s *priv, off_t sector) /* Send the "Sector Erase (SE)" instruction */ (void)SPI_SEND(priv->spi, W25_SE); + priv->prev_instr = W25_SE; /* Send the sector address high byte first. Only the most significant bits (those * corresponding to the sector) have any meaning. @@ -670,6 +672,7 @@ static inline int w25_chiperase(struct w25_dev_s *priv) /* Send the "Chip Erase (CE)" instruction */ (void)SPI_SEND(priv->spi, W25_CE); + priv->prev_instr = W25_CE; /* Deselect the FLASH */ @@ -706,8 +709,10 @@ static void w25_byteread(FAR struct w25_dev_s *priv, FAR uint8_t *buffer, #ifdef CONFIG_W25_SLOWREAD (void)SPI_SEND(priv->spi, W25_RDDATA); + priv->prev_instr = W25_RDDATA; #else (void)SPI_SEND(priv->spi, W25_FRD); + priv->prev_instr = W25_FRD; #endif /* Send the address high byte first. */ @@ -763,6 +768,7 @@ static void w25_pagewrite(struct w25_dev_s *priv, FAR const uint8_t *buffer, /* Send the "Page Program (W25_PP)" Command */ SPI_SEND(priv->spi, W25_PP); + priv->prev_instr = W25_PP; /* Send the address high byte first. */ @@ -819,6 +825,7 @@ static inline void w25_bytewrite(struct w25_dev_s *priv, FAR const uint8_t *buff /* Send "Page Program (PP)" command */ (void)SPI_SEND(priv->spi, W25_PP); + priv->prev_instr = W25_PP; /* Send the page offset high byte first. */ -- GitLab From 05e5841000e6df79349ee5cc7cdfa312b4daabed Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Wed, 31 May 2017 09:20:14 -0600 Subject: [PATCH 894/990] include/nuttx/spi/spi/h: Use of argument to SPI_SEND should be within parentheses. --- include/nuttx/spi/spi.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/nuttx/spi/spi.h b/include/nuttx/spi/spi.h index c4757bb975..08b28e2625 100644 --- a/include/nuttx/spi/spi.h +++ b/include/nuttx/spi/spi.h @@ -320,7 +320,7 @@ * ****************************************************************************/ -#define SPI_SEND(d,wd) ((d)->ops->send(d,(uint16_t)wd)) +#define SPI_SEND(d,wd) ((d)->ops->send(d,(uint16_t)(wd))) /**************************************************************************** * Name: SPI_SNDBLOCK -- GitLab From 1cc842794d45a4902e1cd670b08f3b9a747b72a4 Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Wed, 31 May 2017 09:28:20 -0600 Subject: [PATCH 895/990] drivers/rwbuffer.c: Fix compiler warnings --- drivers/rwbuffer.c | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/drivers/rwbuffer.c b/drivers/rwbuffer.c index a7db82e156..3871454e40 100644 --- a/drivers/rwbuffer.c +++ b/drivers/rwbuffer.c @@ -406,7 +406,9 @@ static int rwb_rhreload(struct rwbuffer_s *rwb, off_t startblock) int rwb_invalidate_writebuffer(FAR struct rwbuffer_s *rwb, off_t startblock, size_t blockcount) { - int ret; + int ret = OK; + + /* Is there a write buffer? Is data saved in the write buffer? */ if (rwb->wrmaxblocks > 0 && rwb->wrnblocks > 0) { @@ -909,7 +911,7 @@ ssize_t rwb_write(FAR struct rwbuffer_s *rwb, off_t startblock, */ } else -#else +#endif /* CONFIG_DRVR_WRITEBUFFER */ { /* No write buffer.. just pass the write operation through via the * flush callback. @@ -917,7 +919,6 @@ ssize_t rwb_write(FAR struct rwbuffer_s *rwb, off_t startblock, ret = rwb->wrflush(rwb->dev, wrbuffer, startblock, nblocks); } -#endif return (ssize_t)ret; } -- GitLab From 705185be1e32cda88cf6a5cf63bc997928a1df18 Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Wed, 31 May 2017 09:33:44 -0600 Subject: [PATCH 896/990] libc/string/lib_vikmemcpy.c: fix 'casting pointer to integer of different size' compiler warnings --- libc/string/lib_vikmemcpy.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libc/string/lib_vikmemcpy.c b/libc/string/lib_vikmemcpy.c index 41ab3ecf37..598672aac1 100644 --- a/libc/string/lib_vikmemcpy.c +++ b/libc/string/lib_vikmemcpy.c @@ -240,9 +240,9 @@ #define COPY_SHIFT(shift) \ { \ - UIntN* dstN = (UIntN*)((((UIntN)dst8) PRE_LOOP_ADJUST) & \ + UIntN* dstN = (UIntN*)((((uintptr_t)dst8) PRE_LOOP_ADJUST) & \ ~(TYPE_WIDTH - 1)); \ - UIntN* srcN = (UIntN*)((((UIntN)src8) PRE_LOOP_ADJUST) & \ + UIntN* srcN = (UIntN*)((((uintptr_t)src8) PRE_LOOP_ADJUST) & \ ~(TYPE_WIDTH - 1)); \ size_t length = count / TYPE_WIDTH; \ UIntN srcWord = INC_VAL(srcN); \ @@ -324,13 +324,13 @@ FAR void *memcpy(FAR void *dest, FAR const void *src, size_t count) START_VAL(dst8); START_VAL(src8); - while (((UIntN)dst8 & (TYPE_WIDTH - 1)) != WHILE_DEST_BREAK) + while (((uintptr_t)dst8 & (TYPE_WIDTH - 1)) != WHILE_DEST_BREAK) { INC_VAL(dst8) = INC_VAL(src8); count--; } - switch ((((UIntN)src8) PRE_SWITCH_ADJUST) & (TYPE_WIDTH - 1)) + switch ((((uintptr_t)src8) PRE_SWITCH_ADJUST) & (TYPE_WIDTH - 1)) { case 0: COPY_NO_SHIFT(); break; case 1: COPY_SHIFT(1); break; -- GitLab From 90dda9357ecbcc1aa53ee207a650d07a4192ac2f Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 31 May 2017 10:55:37 -0600 Subject: [PATCH 897/990] pthread robust mutexes: Fix memmory trashing problem: the main task may also use mutexes; need to check thread type before accessing pthread-specific mutex data structures. Problem noted by Jussi Kivilinna. --- configs/sim/ostest/defconfig | 30 +++++++- sched/pthread/pthread_mutex.c | 133 +++++++++++++++++++++++----------- 2 files changed, 117 insertions(+), 46 deletions(-) diff --git a/configs/sim/ostest/defconfig b/configs/sim/ostest/defconfig index d13dc5b991..374b538fc4 100644 --- a/configs/sim/ostest/defconfig +++ b/configs/sim/ostest/defconfig @@ -28,6 +28,7 @@ CONFIG_BUILD_FLAT=y # CONFIG_MOTOROLA_SREC is not set # CONFIG_RAW_BINARY is not set # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -77,11 +78,11 @@ CONFIG_HOST_X86_64=y CONFIG_SIM_X8664_SYSTEMV=y # CONFIG_SIM_X8664_MICROSOFT is not set # CONFIG_SIM_WALLTIME is not set -CONFIG_SIM_NET_HOST_ROUTE=y -# CONFIG_SIM_NET_BRIDGE is not set # CONFIG_SIM_FRAMEBUFFER is not set # CONFIG_SIM_SPIFLASH is not set # CONFIG_SIM_QSPIFLASH is not set +# CONFIG_ARCH_TOOLCHAIN_IAR is not set +# CONFIG_ARCH_TOOLCHAIN_GNU is not set # # Architecture Options @@ -102,6 +103,7 @@ CONFIG_ARCH_HAVE_MULTICPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set CONFIG_ARCH_HAVE_POWEROFF=y # CONFIG_ARCH_HAVE_RESET is not set +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_STACKDUMP is not set # CONFIG_ENDIAN_BIG is not set # CONFIG_ARCH_IDLE_CUSTOM is not set @@ -204,6 +206,8 @@ CONFIG_SCHED_WAITPID=y # CONFIG_PTHREAD_MUTEX_TYPES=y CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -368,6 +372,7 @@ CONFIG_SERIAL_CONSOLE=y # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -376,7 +381,9 @@ CONFIG_SERIAL_CONSOLE=y # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -437,6 +444,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -445,6 +457,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -594,7 +607,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set # CONFIG_EXAMPLES_NSH is not set # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -630,6 +642,7 @@ CONFIG_EXAMPLES_OSTEST_WAITRESULT=y # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -700,3 +713,14 @@ CONFIG_EXAMPLES_OSTEST_WAITRESULT=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/sched/pthread/pthread_mutex.c b/sched/pthread/pthread_mutex.c index 13dde1a53d..8b6566b8a2 100644 --- a/sched/pthread/pthread_mutex.c +++ b/sched/pthread/pthread_mutex.c @@ -58,7 +58,7 @@ * Name: pthread_mutex_add * * Description: - * Add the mutex to the list of mutexes held by this thread. + * Add the mutex to the list of mutexes held by this pthread. * * Parameters: * mutex - The mux to be locked @@ -70,17 +70,91 @@ static void pthread_mutex_add(FAR struct pthread_mutex_s *mutex) { - FAR struct pthread_tcb_s *rtcb = (FAR struct pthread_tcb_s *)this_task(); - irqstate_t flags; + FAR struct tcb_s *rtcb = this_task(); DEBUGASSERT(mutex->flink == NULL); - /* Add the mutex to the list of mutexes held by this task */ + /* Check if this is a pthread. The main thread may also lock and unlock + * mutexes. The main thread, however, does not participate in the mutex + * consistency logic. Presumably, when the main thread exits, all of the + * child pthreads will also terminate. + * + * REVISIT: NuttX does not support that behavior at present; child pthreads + * will persist after the main thread exits. + */ - flags = enter_critical_section(); - mutex->flink = rtcb->mhead; - rtcb->mhead = mutex; - leave_critical_section(flags); + if ((rtcb->flags & TCB_FLAG_TTYPE_MASK) == TCB_FLAG_TTYPE_PTHREAD) + { + FAR struct pthread_tcb_s *ptcb = (FAR struct pthread_tcb_s *)rtcb; + irqstate_t flags; + + /* Add the mutex to the list of mutexes held by this pthread */ + + flags = enter_critical_section(); + mutex->flink = ptcb->mhead; + ptcb->mhead = mutex; + leave_critical_section(flags); + } +} + +/**************************************************************************** + * Name: pthread_mutex_remove + * + * Description: + * Remove the mutex to the list of mutexes held by this pthread. + * + * Parameters: + * mutex - The mux to be locked + * + * Return Value: + * None + * + ****************************************************************************/ + +static void pthread_mutex_remove(FAR struct pthread_mutex_s *mutex) +{ + FAR struct tcb_s *rtcb = this_task(); + + DEBUGASSERT(mutex->flink == NULL); + + /* Check if this is a pthread. The main thread may also lock and unlock + * mutexes. The main thread, however, does not participate in the mutex + * consistency logic. + */ + + if ((rtcb->flags & TCB_FLAG_TTYPE_MASK) == TCB_FLAG_TTYPE_PTHREAD) + { + FAR struct pthread_tcb_s *ptcb = (FAR struct pthread_tcb_s *)rtcb; + FAR struct pthread_mutex_s *curr; + FAR struct pthread_mutex_s *prev; + irqstate_t flags; + + flags = enter_critical_section(); + + /* Remove the mutex from the list of mutexes held by this task */ + + for (prev = NULL, curr = ptcb->mhead; + curr != NULL && curr != mutex; + prev = curr, curr = curr->flink); + + DEBUGASSERT(curr == mutex); + + /* Remove the mutex from the list. prev == NULL means that the mutex + * to be removed is at the head of the list. + */ + + if (prev == NULL) + { + ptcb->mhead = mutex->flink; + } + else + { + prev->flink = mutex->flink; + } + + mutex->flink = NULL; + leave_critical_section(flags); + } } /**************************************************************************** @@ -233,8 +307,6 @@ int pthread_mutex_trytake(FAR struct pthread_mutex_s *mutex) int pthread_mutex_give(FAR struct pthread_mutex_s *mutex) { - FAR struct pthread_mutex_s *curr; - FAR struct pthread_mutex_s *prev; int ret = EINVAL; /* Verify input parameters */ @@ -242,34 +314,9 @@ int pthread_mutex_give(FAR struct pthread_mutex_s *mutex) DEBUGASSERT(mutex != NULL); if (mutex != NULL) { - FAR struct pthread_tcb_s *rtcb = (FAR struct pthread_tcb_s *)this_task(); - irqstate_t flags; - - flags = enter_critical_section(); - /* Remove the mutex from the list of mutexes held by this task */ - for (prev = NULL, curr = rtcb->mhead; - curr != NULL && curr != mutex; - prev = curr, curr = curr->flink); - - DEBUGASSERT(curr == mutex); - - /* Remove the mutex from the list. prev == NULL means that the mutex - * to be removed is at the head of the list. - */ - - if (prev == NULL) - { - rtcb->mhead = mutex->flink; - } - else - { - prev->flink = mutex->flink; - } - - mutex->flink = NULL; - leave_critical_section(flags); + pthread_mutex_remove(mutex); /* Now release the underlying semaphore */ @@ -300,7 +347,7 @@ int pthread_mutex_give(FAR struct pthread_mutex_s *mutex) #ifdef CONFIG_CANCELLATION_POINTS uint16_t pthread_disable_cancel(void) { - FAR struct pthread_tcb_s *tcb = (FAR struct pthread_tcb_s *)this_task(); + FAR struct tcb_s *tcb = this_task(); irqstate_t flags; uint16_t old; @@ -309,15 +356,15 @@ uint16_t pthread_disable_cancel(void) */ flags = enter_critical_section(); - old = tcb->cmn.flags & (TCB_FLAG_CANCEL_PENDING | TCB_FLAG_NONCANCELABLE); - tcb->cmn.flags &= ~(TCB_FLAG_CANCEL_PENDING | TCB_FLAG_NONCANCELABLE); + old = tcb->flags & (TCB_FLAG_CANCEL_PENDING | TCB_FLAG_NONCANCELABLE); + tcb->flags &= ~(TCB_FLAG_CANCEL_PENDING | TCB_FLAG_NONCANCELABLE); leave_critical_section(flags); return old; } void pthread_enable_cancel(uint16_t cancelflags) { - FAR struct pthread_tcb_s *tcb = (FAR struct pthread_tcb_s *)this_task(); + FAR struct tcb_s *tcb = this_task(); irqstate_t flags; /* We need perform the following operations from within a critical section @@ -325,7 +372,7 @@ void pthread_enable_cancel(uint16_t cancelflags) */ flags = enter_critical_section(); - tcb->cmn.flags |= cancelflags; + tcb->flags |= cancelflags; /* What should we do if there is a pending cancellation? * @@ -337,8 +384,8 @@ void pthread_enable_cancel(uint16_t cancelflags) * then we need to terminate now by simply calling pthread_exit(). */ - if ((tcb->cmn.flags & TCB_FLAG_CANCEL_DEFERRED) == 0 && - (tcb->cmn.flags & TCB_FLAG_CANCEL_PENDING) != 0) + if ((tcb->flags & TCB_FLAG_CANCEL_DEFERRED) == 0 && + (tcb->flags & TCB_FLAG_CANCEL_PENDING) != 0) { pthread_exit(NULL); } -- GitLab From e4b145b9a9b9c2803267f4af3102ed7c11081f37 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 31 May 2017 11:17:11 -0600 Subject: [PATCH 898/990] Upate TODO list --- TODO | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/TODO b/TODO index 2cf4fdcaaa..64c98a8c86 100644 --- a/TODO +++ b/TODO @@ -1,4 +1,4 @@ -NuttX TODO List (Last updated May 18, 2017) +NuttX TODO List (Last updated May 31, 2017) ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ This file summarizes known NuttX bugs, limitations, inconsistencies with @@ -45,6 +45,13 @@ o Task/Scheduler (sched/) terminated? Status: Closed. No, this behavior will not be implemented. Priority: Medium, required for good emulation of process/pthread model. + The current behavior allows for the main thread of a task to + exit() and any child pthreads will perist. That does raise + some issues: The main thread is treated much like just-another- + pthread but must follow the semantics of a task or a process. + That results in some inconsistencies (for example, with robust + mutexes, what should happen if the main thread exits while + holding a mutex?) Title: pause() NON-COMPLIANCE Description: In the POSIX description of this function the pause() function -- GitLab From bb02c0c92d08624e4b9660c3984199eed51ebf48 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 31 May 2017 15:17:28 -0600 Subject: [PATCH 899/990] Makefiles.*: It should be possible to run 'make menuconfig' with no .config and no Make.defs file. This change removes the dependency on Make.defs, but does not solve the problem of the missing .config file. Without a .config file, it is not currently possible for the Makefile.* to correctly setup up the symbolic links to directories. --- Makefile.unix | 4 +++- Makefile.win | 4 +++- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/Makefile.unix b/Makefile.unix index b7bf86b805..806b9af1fb 100644 --- a/Makefile.unix +++ b/Makefile.unix @@ -280,7 +280,9 @@ tools/cnvwindeps$(HOSTEXEEXT): # Directories links. Most of establishing the NuttX configuration involves # setting up symbolic links with 'generic' directory names to specific, # configured directories. -# + +Make.defs: + # Link the arch//include directory to include/arch include/arch: Make.defs diff --git a/Makefile.win b/Makefile.win index e1d9bc1278..9829c91341 100644 --- a/Makefile.win +++ b/Makefile.win @@ -275,7 +275,9 @@ tools\mkdeps$(HOSTEXEEXT): # Directories links. Most of establishing the NuttX configuration involves # setting up symbolic links with 'generic' directory names to specific, # configured directories. -# + +Make.defs: + # Link the arch\\include directory to include\arch include\arch: Make.defs -- GitLab From f5e6afe9cdab2feba74036be4896857e8f09239e Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 31 May 2017 15:39:18 -0600 Subject: [PATCH 900/990] Makefile.*: Create a Make.defs file if one does not exist --- Makefile.unix | 2 ++ Makefile.win | 2 ++ 2 files changed, 4 insertions(+) diff --git a/Makefile.unix b/Makefile.unix index 806b9af1fb..811b0551e3 100644 --- a/Makefile.unix +++ b/Makefile.unix @@ -282,6 +282,8 @@ tools/cnvwindeps$(HOSTEXEEXT): # configured directories. Make.defs: + echo "include $(TOPDIR)$(DELIM).config" > Make.defs + echo "include $(TOPDIR)$(DELIM)tools$(DELIM)Config.mk" >> Make.defs # Link the arch//include directory to include/arch diff --git a/Makefile.win b/Makefile.win index 9829c91341..32d42772c6 100644 --- a/Makefile.win +++ b/Makefile.win @@ -277,6 +277,8 @@ tools\mkdeps$(HOSTEXEEXT): # configured directories. Make.defs: + echo "include $(TOPDIR)$(DELIM).config" > Make.defs + echo "include $(TOPDIR)$(DELIM)tools$(DELIM)Config.mk" >> Make.defs # Link the arch\\include directory to include\arch -- GitLab From ad6515563b1da0b5103a1bd1487921045f37321f Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Thu, 1 Jun 2017 06:15:28 -0600 Subject: [PATCH 901/990] STM32L4 RTC: store RTC MAGIC to backup reg, not to address zero --- arch/arm/src/stm32l4/stm32l4_rcc.c | 2 +- arch/arm/src/stm32l4/stm32l4_rtc.h | 8 ++++---- arch/arm/src/stm32l4/stm32l4_rtc_lowerhalf.c | 2 +- arch/arm/src/stm32l4/stm32l4_rtcc.c | 19 +++++++++++-------- 4 files changed, 17 insertions(+), 14 deletions(-) diff --git a/arch/arm/src/stm32l4/stm32l4_rcc.c b/arch/arm/src/stm32l4/stm32l4_rcc.c index ffe1c4d2dc..c2f3cfa198 100644 --- a/arch/arm/src/stm32l4/stm32l4_rcc.c +++ b/arch/arm/src/stm32l4/stm32l4_rcc.c @@ -114,7 +114,7 @@ static inline void rcc_resetbkp(void) /* Check if the RTC is already configured */ - init_stat = rtc_is_inits(); + init_stat = stm32l4_rtc_is_initialized(); if(!init_stat) { /* Enable write access to the backup domain (RTC registers, RTC diff --git a/arch/arm/src/stm32l4/stm32l4_rtc.h b/arch/arm/src/stm32l4/stm32l4_rtc.h index 18e7f6031b..3e0a5a2130 100644 --- a/arch/arm/src/stm32l4/stm32l4_rtc.h +++ b/arch/arm/src/stm32l4/stm32l4_rtc.h @@ -76,7 +76,7 @@ enum alm_id_e RTC_ALARM_LAST }; -/* Structure used to pass parmaters to set an alarm */ +/* Structure used to pass parameters to set an alarm */ struct alm_setalarm_s { @@ -106,7 +106,7 @@ extern "C" ****************************************************************************/ /************************************************************************************ - * Name: rtc_is_inits + * Name: stm32l4_rtc_is_initialized * * Description: * Returns 'true' if the RTC has been initialized (according to the RTC itself). @@ -120,11 +120,11 @@ extern "C" * bool -- true if the INITS flag is set in the ISR. * ************************************************************************************/ + #ifdef CONFIG_RTC_DRIVER -bool rtc_is_inits(void); +bool stm32l4_rtc_is_initialized(void); #endif - /**************************************************************************** * Name: stm32l4_rtc_getdatetime_with_subseconds * diff --git a/arch/arm/src/stm32l4/stm32l4_rtc_lowerhalf.c b/arch/arm/src/stm32l4/stm32l4_rtc_lowerhalf.c index 5ab212dd86..f3415af305 100644 --- a/arch/arm/src/stm32l4/stm32l4_rtc_lowerhalf.c +++ b/arch/arm/src/stm32l4/stm32l4_rtc_lowerhalf.c @@ -176,7 +176,7 @@ static void stm32l4_alarm_callback(FAR void *arg, unsigned int alarmid) rtc_alarm_callback_t cb; FAR void *priv; - DEBUGASSERT(priv != NULL); + DEBUGASSERT(arg != NULL); DEBUGASSERT(alarmid == RTC_ALARMA || alarmid == RTC_ALARMB); lower = (struct stm32l4_lowerhalf_s *)arg; diff --git a/arch/arm/src/stm32l4/stm32l4_rtcc.c b/arch/arm/src/stm32l4/stm32l4_rtcc.c index f36d4d040c..d053ee9929 100644 --- a/arch/arm/src/stm32l4/stm32l4_rtcc.c +++ b/arch/arm/src/stm32l4/stm32l4_rtcc.c @@ -95,6 +95,10 @@ # define CONFIG_RTC_MAGIC_REG (0) #endif +#define RTC_MAGIC CONFIG_RTC_MAGIC +#define RTC_MAGIC_TIME_SET CONFIG_RTC_MAGIC_TIME_SET +#define RTC_MAGIC_REG STM32L4_RTC_BKR(CONFIG_RTC_MAGIC_REG) + /* Constants ************************************************************************/ #define SYNCHRO_TIMEOUT (0x00020000) @@ -816,7 +820,7 @@ static inline void rtc_enable_alarm(void) ************************************************************************************/ /************************************************************************************ - * Name: rtc_is_inits + * Name: stm32l4_rtc_is_initialized * * Description: * Returns 'true' if the RTC has been initialized (according to the RTC itself). @@ -831,7 +835,7 @@ static inline void rtc_enable_alarm(void) * ************************************************************************************/ -bool rtc_is_inits(void) +bool stm32l4_rtc_is_initialized(void) { uint32_t regval; @@ -867,8 +871,7 @@ int up_rtc_initialize(void) * backed, we don't need or want to re-initialize on each reset. */ - init_stat = rtc_is_inits(); - + init_stat = stm32l4_rtc_is_initialized(); if (!init_stat) { /* Enable write access to the backup domain (RTC registers, RTC @@ -1164,7 +1167,7 @@ int stm32l4_rtc_setdatetime(FAR const struct tm *tp) /* Then write the broken out values to the RTC */ - /* Convert the struct tm format to RTC time register fields. All of the STM32 + /* Convert the struct tm format to RTC time register fields. * All of the ranges of values correspond between struct tm and the time * register. */ @@ -1216,10 +1219,10 @@ int stm32l4_rtc_setdatetime(FAR const struct tm *tp) /* Remember that the RTC is initialized and had its time set. */ - if (getreg32(CONFIG_RTC_MAGIC_REG) != CONFIG_RTC_MAGIC_TIME_SET) + if (getreg32(RTC_MAGIC_REG) != RTC_MAGIC_TIME_SET) { stm32l4_pwr_enablebkp(true); - putreg32(CONFIG_RTC_MAGIC_TIME_SET, CONFIG_RTC_MAGIC_REG); + putreg32(RTC_MAGIC_TIME_SET, RTC_MAGIC_REG); stm32l4_pwr_enablebkp(false); } @@ -1243,7 +1246,7 @@ int stm32l4_rtc_setdatetime(FAR const struct tm *tp) bool stm32l4_rtc_havesettime(void) { - return getreg32(CONFIG_RTC_MAGIC_REG) == CONFIG_RTC_MAGIC_TIME_SET; + return getreg32(RTC_MAGIC_REG) == RTC_MAGIC_TIME_SET; } /************************************************************************************ -- GitLab From 32610b53f450aa2b426b0eaf4eccd97969463298 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Thu, 1 Jun 2017 06:19:54 -0600 Subject: [PATCH 902/990] drivers/{sensors,usbmisc}: Fix uninitialized I2C frequency --- drivers/sensors/Kconfig | 15 +++++++++++++++ drivers/sensors/hts221.c | 40 +++++++++++++++++++++++---------------- drivers/sensors/lis2dh.c | 22 +++++++++++++-------- drivers/sensors/lps25h.c | 40 +++++++++++++++++++++++---------------- drivers/usbmisc/Kconfig | 5 +++++ drivers/usbmisc/fusb301.c | 31 ++++++++++++++++++------------ 6 files changed, 101 insertions(+), 52 deletions(-) diff --git a/drivers/sensors/Kconfig b/drivers/sensors/Kconfig index 03911022b5..43c82293f1 100644 --- a/drivers/sensors/Kconfig +++ b/drivers/sensors/Kconfig @@ -41,6 +41,11 @@ config HTS221 if HTS221 +config HTS221_I2C_FREQUENCY + int "HTS221 I2C frequency" + default 400000 + range 1 400000 + config DEBUG_HTS221 bool "Debug support for the HTS221" default n @@ -84,6 +89,11 @@ config LIS2DH if LIS2DH +config LIS2DH_I2C_FREQUENCY + int "LIS2DH I2C frequency" + default 400000 + range 1 400000 + config DEBUG_LIS2DH bool "Debug support for the LIS2DH" default n @@ -144,6 +154,11 @@ config LPS25H if LPS25H +config LPS25H_I2C_FREQUENCY + int "LPS25H I2C frequency" + default 400000 + range 1 400000 + config DEBUG_LPS25H bool "Debug support for the LPS25H" default n diff --git a/drivers/sensors/hts221.c b/drivers/sensors/hts221.c index 9f3138bddf..9b85cf7e93 100644 --- a/drivers/sensors/hts221.c +++ b/drivers/sensors/hts221.c @@ -61,6 +61,10 @@ # define hts221_dbg(x, ...) sninfo(x, ##__VA_ARGS__) #endif +#ifndef CONFIG_HTS221_I2C_FREQUENCY +# define CONFIG_HTS221_I2C_FREQUENCY 400000 +#endif + #define HTS221_WHO_AM_I 0x0f #define HTS221_AV_CONF 0x10 #define HTS221_CTRL_REG1 0x20 @@ -221,16 +225,18 @@ static int32_t hts221_write_reg8(FAR struct hts221_dev_s *priv, struct i2c_msg_s msgv[2] = { { - .addr = priv->addr, - .flags = 0, - .buffer = (FAR void *)&command[0], - .length = 1 + .frequency = CONFIG_HTS221_I2C_FREQUENCY, + .addr = priv->addr, + .flags = 0, + .buffer = (FAR void *)&command[0], + .length = 1 }, { - .addr = priv->addr, - .flags = I2C_M_NORESTART, - .buffer = (FAR void *)&command[1], - .length = 1 + .frequency = CONFIG_HTS221_I2C_FREQUENCY, + .addr = priv->addr, + .flags = I2C_M_NORESTART, + .buffer = (FAR void *)&command[1], + .length = 1 } }; @@ -243,16 +249,18 @@ static int hts221_read_reg(FAR struct hts221_dev_s *priv, struct i2c_msg_s msgv[2] = { { - .addr = priv->addr, - .flags = 0, - .buffer = (FAR void *)command, - .length = 1 + .frequency = CONFIG_HTS221_I2C_FREQUENCY, + .addr = priv->addr, + .flags = 0, + .buffer = (FAR void *)command, + .length = 1 }, { - .addr = priv->addr, - .flags = I2C_M_READ, - .buffer = value, - .length = 1 + .frequency = CONFIG_HTS221_I2C_FREQUENCY, + .addr = priv->addr, + .flags = I2C_M_READ, + .buffer = value, + .length = 1 } }; diff --git a/drivers/sensors/lis2dh.c b/drivers/sensors/lis2dh.c index f7a982f151..67e0bf1185 100644 --- a/drivers/sensors/lis2dh.c +++ b/drivers/sensors/lis2dh.c @@ -65,6 +65,10 @@ # define lis2dh_dbg(x, ...) sninfo(x, ##__VA_ARGS__) #endif +#ifndef CONFIG_LIS2DH_I2C_FREQUENCY +# define CONFIG_LIS2DH_I2C_FREQUENCY 400000 +#endif + #ifdef CONFIG_LIS2DH_DRIVER_SELFTEST # define LSB_AT_10BIT_RESOLUTION 4 # define LSB_AT_12BIT_RESOLUTION 1 @@ -1594,16 +1598,18 @@ static int lis2dh_access(FAR struct lis2dh_dev_s *dev, uint8_t subaddr, struct i2c_msg_s msgv[2] = { { - .addr = dev->addr, - .flags = 0, - .buffer = &subaddr, - .length = 1 + .frequency = CONFIG_LIS2DH_I2C_FREQUENCY, + .addr = dev->addr, + .flags = 0, + .buffer = &subaddr, + .length = 1 }, { - .addr = dev->addr, - .flags = flags, - .buffer = buf, - .length = length + .frequency = CONFIG_LIS2DH_I2C_FREQUENCY, + .addr = dev->addr, + .flags = flags, + .buffer = buf, + .length = length } }; diff --git a/drivers/sensors/lps25h.c b/drivers/sensors/lps25h.c index bd35f38043..1eb762af0a 100644 --- a/drivers/sensors/lps25h.c +++ b/drivers/sensors/lps25h.c @@ -58,6 +58,10 @@ # define lps25h_dbg(x, ...) sninfo(x, ##__VA_ARGS__) #endif +#ifndef CONFIG_LPS25H_I2C_FREQUENCY +# define CONFIG_LPS25H_I2C_FREQUENCY 400000 +#endif + #define LPS25H_PRESSURE_INTERNAL_DIVIDER 4096 /* 'AN4450 - Hardware and software guidelines for use of LPS25H pressure @@ -277,16 +281,18 @@ static int lps25h_write_reg8(struct lps25h_dev_s *dev, uint8_t reg_addr, struct i2c_msg_s msgv[2] = { { - .addr = dev->addr, - .flags = 0, - .buffer = ®_addr, - .length = 1 + .frequency = CONFIG_LPS25H_I2C_FREQUENCY, + .addr = dev->addr, + .flags = 0, + .buffer = ®_addr, + .length = 1 }, { - .addr = dev->addr, - .flags = I2C_M_NORESTART, - .buffer = (void *)&value, - .length = 1 + .frequency = CONFIG_LPS25H_I2C_FREQUENCY, + .addr = dev->addr, + .flags = I2C_M_NORESTART, + .buffer = (void *)&value, + .length = 1 } }; @@ -300,16 +306,18 @@ static int lps25h_read_reg8(FAR struct lps25h_dev_s *dev, struct i2c_msg_s msgv[2] = { { - .addr = dev->addr, - .flags = 0, - .buffer = reg_addr, - .length = 1 + .frequency = CONFIG_LPS25H_I2C_FREQUENCY, + .addr = dev->addr, + .flags = 0, + .buffer = reg_addr, + .length = 1 }, { - .addr = dev->addr, - .flags = I2C_M_READ, - .buffer = value, - .length = 1 + .frequency = CONFIG_LPS25H_I2C_FREQUENCY, + .addr = dev->addr, + .flags = I2C_M_READ, + .buffer = value, + .length = 1 } }; diff --git a/drivers/usbmisc/Kconfig b/drivers/usbmisc/Kconfig index 68bd619ee3..6669061283 100644 --- a/drivers/usbmisc/Kconfig +++ b/drivers/usbmisc/Kconfig @@ -14,6 +14,11 @@ config FUSB301 if FUSB301 +config FUSB301_I2C_FREQUENCY + int "FUSB301 I2C frequency" + default 400000 + range 1 400000 + config DEBUG_FUSB301 bool "Enable debug support for the FUSB301" default n diff --git a/drivers/usbmisc/fusb301.c b/drivers/usbmisc/fusb301.c index f24ae78558..d57d8a95ec 100644 --- a/drivers/usbmisc/fusb301.c +++ b/drivers/usbmisc/fusb301.c @@ -63,6 +63,10 @@ # define fusb301_info(x, ...) uinfo(x, ##__VA_ARGS__) #endif +#ifndef CONFIG_FUSB301_I2C_FREQUENCY +# define CONFIG_FUSB301_I2C_FREQUENCY 400000 +#endif + /* Other macros */ #define FUSB301_I2C_RETRIES 10 @@ -146,15 +150,17 @@ static int fusb301_getreg(FAR struct fusb301_dev_s *priv, uint8_t reg) DEBUGASSERT(priv); - msg[0].addr = priv->addr; - msg[0].flags = 0; - msg[0].buffer = ® - msg[0].length = 1; + msg[0].frequency = CONFIG_FUSB301_I2C_FREQUENCY; + 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; + msg[1].frequency = CONFIG_FUSB301_I2C_FREQUENCY; + msg[1].addr = priv->addr; + msg[1].flags = I2C_M_READ; + msg[1].buffer = ®val; + msg[1].length = 1; /* Perform the transfer */ @@ -220,10 +226,11 @@ static int fusb301_putreg(FAR struct fusb301_dev_s *priv, uint8_t regaddr, /* Setup 8-bit FUSB301 address write message */ - msg.addr = priv->addr; - msg.flags = 0; - msg.buffer = txbuffer; - msg.length = 2; + msg.frequency = CONFIG_FUSB301_I2C_FREQUENCY; + msg.addr = priv->addr; + msg.flags = 0; + msg.buffer = txbuffer; + msg.length = 2; /* Perform the transfer */ -- GitLab From 06edfae1339272081c7c061f7d7df8c2add0b8d2 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Thu, 1 Jun 2017 06:22:27 -0600 Subject: [PATCH 903/990] mtd/config: Add some error checks for I/O errors --- drivers/mtd/mtd_config.c | 34 +++++++++++++++++++++++++++++++--- drivers/mtd/mtd_partition.c | 2 +- 2 files changed, 32 insertions(+), 4 deletions(-) diff --git a/drivers/mtd/mtd_config.c b/drivers/mtd/mtd_config.c index 69ac00237d..2566efedc8 100644 --- a/drivers/mtd/mtd_config.c +++ b/drivers/mtd/mtd_config.c @@ -352,7 +352,14 @@ static int mtdconfig_findfirstentry(FAR struct mtdconfig_struct_s *dev, off_t bytes_left_in_block; uint16_t endblock; - mtdconfig_readbytes(dev, 0, sig, sizeof(sig)); /* Read the signature bytes */ + /* Read the signature bytes */ + + ret = mtdconfig_readbytes(dev, 0, sig, sizeof(sig)); + if (ret != OK) + { + return 0; + } + if (sig[0] != 'C' || sig[1] != 'D' || sig[2] != CONFIGDATA_FORMAT_VERSION) { /* Config Data partition not formatted. */ @@ -788,7 +795,14 @@ static off_t mtdconfig_consolidate(FAR struct mtdconfig_struct_s *dev) /* Scan all headers and move them to the src_offset */ retry_relocate: - MTD_READ(dev->mtd, src_offset, sizeof(hdr), (uint8_t *) &hdr); + bytes = MTD_READ(dev->mtd, src_offset, sizeof(hdr), (uint8_t *) &hdr); + if (bytes != sizeof(hdr)) + { + /* I/O Error! */ + + goto errout; + } + if (hdr.flags == MTD_ERASED_FLAGS) { /* Test if the source entry is active or if we are at the end @@ -967,6 +981,11 @@ static ssize_t mtdconfig_read(FAR struct file *filep, FAR char *buffer, /* Read data from the file */ bytes = MTD_READ(dev->mtd, dev->readoff, len, (uint8_t *) buffer); + if (bytes != len) + { + return -EIO; + } + dev->readoff += bytes; return bytes; } @@ -981,6 +1000,7 @@ static int mtdconfig_findentry(FAR struct mtdconfig_struct_s *dev, FAR struct mtdconfig_header_s *phdr) { uint16_t endblock; + int ret; #ifdef CONFIG_MTD_CONFIG_RAM_CONSOLIDATE endblock = dev->neraseblocks; @@ -1013,7 +1033,15 @@ static int mtdconfig_findentry(FAR struct mtdconfig_struct_s *dev, /* Read the 1st header from the next block */ - mtdconfig_readbytes(dev, offset, (uint8_t *) phdr, sizeof(*phdr)); + ret = mtdconfig_readbytes(dev, offset, (uint8_t *) phdr, sizeof(*phdr)); + if (ret != OK) + { + /* Error reading the data */ + + offset = 0; + break; + } + if (phdr->flags == MTD_ERASED_FLAGS) { continue; diff --git a/drivers/mtd/mtd_partition.c b/drivers/mtd/mtd_partition.c index 655fe36826..f8438cdd97 100644 --- a/drivers/mtd/mtd_partition.c +++ b/drivers/mtd/mtd_partition.c @@ -157,7 +157,7 @@ static int part_procfs_stat(FAR const char *relpath, ****************************************************************************/ #if defined(CONFIG_FS_PROCFS) && !defined(CONFIG_PROCFS_EXCLUDE_PARTITIONS) -struct mtd_partition_s *g_pfirstpartition = NULL; +static struct mtd_partition_s *g_pfirstpartition = NULL; const struct procfs_operations part_procfsoperations = { -- GitLab From 0fe9c2f3f9b30ec967f27630b5aeaab327976318 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 1 Jun 2017 06:28:23 -0600 Subject: [PATCH 904/990] pthread mutex: Remove bogus DEBUGASSERT. Problem noted by Jussi Kivilinna --- sched/pthread/pthread_mutex.c | 2 -- 1 file changed, 2 deletions(-) diff --git a/sched/pthread/pthread_mutex.c b/sched/pthread/pthread_mutex.c index 8b6566b8a2..5a75481a51 100644 --- a/sched/pthread/pthread_mutex.c +++ b/sched/pthread/pthread_mutex.c @@ -115,8 +115,6 @@ static void pthread_mutex_remove(FAR struct pthread_mutex_s *mutex) { FAR struct tcb_s *rtcb = this_task(); - DEBUGASSERT(mutex->flink == NULL); - /* Check if this is a pthread. The main thread may also lock and unlock * mutexes. The main thread, however, does not participate in the mutex * consistency logic. -- GitLab From 4d46979a6fa86a595db2158737a797987839d356 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 1 Jun 2017 06:38:47 -0600 Subject: [PATCH 905/990] Tiva SSI: Resolves issue 52 'Copy-Paste error in tiva_ssibus_initialize()' submitted by Aleksandr Kazantsev. --- arch/arm/src/tiva/tiva_ssi.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/arch/arm/src/tiva/tiva_ssi.c b/arch/arm/src/tiva/tiva_ssi.c index 709850e01a..9930c6184f 100644 --- a/arch/arm/src/tiva/tiva_ssi.c +++ b/arch/arm/src/tiva/tiva_ssi.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/arm/src/tiva/tiva_ssi.c * - * Copyright (C) 2009-2010, 2014, 2016 Gregory Nutt. All rights reserved. + * Copyright (C) 2009-2010, 2014, 2016-2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -1616,8 +1616,8 @@ FAR struct spi_dev_s *tiva_ssibus_initialize(int port) * to the SSI3 peripheral, bringing it a fully functional state. */ - tiva_ssi1_enablepwr(); - tiva_ssi1_enableclk(); + tiva_ssi3_enablepwr(); + tiva_ssi3_enableclk(); /* Configure SSI3 GPIOs */ @@ -1626,7 +1626,7 @@ FAR struct spi_dev_s *tiva_ssibus_initialize(int port) tiva_configgpio(GPIO_SSI3_RX); /* PE2: SSI3 receive (SSI3Rx) */ tiva_configgpio(GPIO_SSI3_TX); /* PE3: SSI3 transmit (SSI3Tx) */ break; -#endif /* CONFIG_TIVA_SSI1 */ +#endif /* CONFIG_TIVA_SSI3 */ default: leave_critical_section(flags); -- GitLab From ff2b54a5e0b969748f132ef83bff710446e86ce9 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 1 Jun 2017 06:44:24 -0600 Subject: [PATCH 906/990] nucleo-f4x1re User LEDS: Issue #51 reports compilation problems with stm32_userled.c. Reported by Gappi92. --- configs/nucleo-f4x1re/src/stm32_userleds.c | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/configs/nucleo-f4x1re/src/stm32_userleds.c b/configs/nucleo-f4x1re/src/stm32_userleds.c index dd77500711..dcfaa89510 100644 --- a/configs/nucleo-f4x1re/src/stm32_userleds.c +++ b/configs/nucleo-f4x1re/src/stm32_userleds.c @@ -183,7 +183,7 @@ void board_userled(int led, bool ledon) { if (led == 1) { - stm32_gpiowrite(GPIO_LD2, ldeon); + stm32_gpiowrite(GPIO_LD2, ledon); } } @@ -193,10 +193,7 @@ void board_userled(int led, bool ledon) void board_userled_all(uint8_t ledset) { - if (led == 1) - { - stm32_gpiowrite(GPIO_LD2, (ledset & BOARD_LD2_BIT) != 0); - } + stm32_gpiowrite(GPIO_LD2, (ledset & BOARD_LD2_BIT) != 0); } /**************************************************************************** -- GitLab From 624bd0b9e983573d09659ae5fd42b87f47f548a5 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 2 Jun 2017 10:17:30 -0600 Subject: [PATCH 907/990] tools/: Add initialconfig.c so that perhaps in the future we will be able to use this to generate a new configuration from scratch (rather than having to derive new configurations from existing configurations) --- tools/Makefile.host | 15 +- tools/README.txt | 9 + tools/cfgparser.c | 2 +- tools/initialconfig.c | 845 ++++++++++++++++++++++++++++++++++++++++++ 4 files changed, 868 insertions(+), 3 deletions(-) create mode 100644 tools/initialconfig.c diff --git a/tools/Makefile.host b/tools/Makefile.host index 0ffc682b8b..297470dc6e 100644 --- a/tools/Makefile.host +++ b/tools/Makefile.host @@ -1,7 +1,7 @@ ############################################################################ # Makefile.host # -# Copyright (C) 2007, 2008, 2011-2012, 2015 Gregory Nutt. All rights reserved. +# Copyright (C) 2007, 2008, 2011-2012, 2015, 2017 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -70,7 +70,7 @@ endif all: b16$(HOSTEXEEXT) bdf-converter$(HOSTEXEEXT) cmpconfig$(HOSTEXEEXT) \ configure$(HOSTEXEEXT) mkconfig$(HOSTEXEEXT) mkdeps$(HOSTEXEEXT) \ mksymtab$(HOSTEXEEXT) mksyscall$(HOSTEXEEXT) mkversion$(HOSTEXEEXT) \ - cnvwindeps$(HOSTEXEEXT) nxstyle$(HOSTEXEEXT) + cnvwindeps$(HOSTEXEEXT) nxstyle$(HOSTEXEEXT) initialconfig$(HOSTEXEEXT) default: mkconfig$(HOSTEXEEXT) mksyscall$(HOSTEXEEXT) mkdeps$(HOSTEXEEXT) \ cnvwindeps$(HOSTEXEEXT) @@ -171,6 +171,17 @@ ifdef HOSTEXEEXT nxstyle: nxstyle$(HOSTEXEEXT) endif +# initialconfig - Create a barebones .config file sufficient only for +# instantiating the symbolic links necesary to do a real configuration +# from scratch. + +initialconfig$(HOSTEXEEXT): initialconfig.c + $(Q) $(HOSTCC) $(HOSTCFLAGS) -o initialconfig$(HOSTEXEEXT) initialconfig.c + +ifdef HOSTEXEEXT +initialconfig: initialconfig$(HOSTEXEEXT) +endif + # cnvwindeps - Convert dependences generated by a Windows native toolchain # for use in a Cygwin/POSIX build environment diff --git a/tools/README.txt b/tools/README.txt index e44f64a8d4..3d8443c295 100644 --- a/tools/README.txt +++ b/tools/README.txt @@ -82,6 +82,15 @@ cmdconfig.c This C file can be used to build a utility for comparing two NuttX configuration files. +initialconfig.c +--------------- + + This is a C file that can be used create an initial configuration. + This permits creating a new configuration from scratch, without + relying on any existing board configuration in place. This utility + will create a barebones .config file sufficient only for + instantiating the symbolic links necesary to do a real configuration. + kconfig2html.c -------------- diff --git a/tools/cfgparser.c b/tools/cfgparser.c index 959cf9e5eb..23e1d6a5e5 100644 --- a/tools/cfgparser.c +++ b/tools/cfgparser.c @@ -210,7 +210,7 @@ void parse_file(FILE *stream, struct variable_s **list) parse_line(ptr, &varname, &varval); - /* If the variable has not value (or the special value 'n'), then + /* If the variable has no value (or the special value 'n'), then * ignore it. */ diff --git a/tools/initialconfig.c b/tools/initialconfig.c new file mode 100644 index 0000000000..19a2bd420c --- /dev/null +++ b/tools/initialconfig.c @@ -0,0 +1,845 @@ +/**************************************************************************** + * tools/initialconfig.c + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include +#include +#include +#include +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define MAX_LINE 512 +#define MAX_ARCHITECTURES 32 +#define MAX_MCUS 64 +#define MAX_BOARDS 128 + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +typedef int (*direntcb_t)(const char *dirpath, struct dirent *entry, void *arg); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +#ifdef CONFIG_WINDOWS_NATIVE +static char g_delim = '\\'; /* Delimiter to use when forming paths */ +#else +static char g_delim = '/'; /* Delimiter to use when forming paths */ +#endif + +static const char g_archdir[] = "arch"; /* Architecture directory */ +static const char g_configdir[] = "configs"; /* Board configuration directory */ + +static char *g_arch[MAX_ARCHITECTURES]; /* List of architecture names */ +static int g_narch; /* Number of architecture names */ +static char *g_selected_arch; /* Selected architecture name */ +static char *g_selected_family; /* Selected architecture family name */ + +static char *g_mcu[MAX_MCUS]; /* List of MCU names */ +static int g_nmcu; /* Number of MCU names */ +static char *g_selected_mcu; /* Selected MCU name */ + +static char *g_board[MAX_BOARDS]; /* List of board names */ +static int g_nboard; /* Number of board names */ +static char *g_selected_board; /* Selected board name */ + +static char g_line[MAX_LINE + 1]; /* Line read from config file */ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: skip_space + * + * Description: + * Skip over any spaces + * + ****************************************************************************/ + +static char *skip_space(char *ptr) +{ + while (*ptr && isspace((int)*ptr)) ptr++; + return ptr; +} + +/**************************************************************************** + * Name: find_name_end + * + * Description: + * Find the end of a variable string + * + ****************************************************************************/ + +static char *find_name_end(char *ptr) +{ + while (*ptr && (isalnum((int)*ptr) || *ptr == '_')) ptr++; + return ptr; +} + +/**************************************************************************** + * Name: find_value_end + * + * Description: + * Find the end of a value string + * + ****************************************************************************/ + +static char *find_value_end(char *ptr) +{ + while (*ptr && !isspace((int)*ptr)) + { + if (*ptr == '"') + { + do ptr++; while (*ptr && *ptr != '"'); + if (*ptr) ptr++; + } + else + { + do ptr++; while (*ptr && !isspace((int)*ptr) && *ptr != '"'); + } + } + + return ptr; +} + +/**************************************************************************** + * Name: read_line + * + * Description: + * Read the next line from the configuration file + * + ****************************************************************************/ + +static char *read_line(FILE *stream) +{ + char *ptr; + + for (;;) + { + g_line[MAX_LINE] = '\0'; + if (!fgets(g_line, MAX_LINE, stream)) + { + return NULL; + } + else + { + ptr = skip_space(g_line); + if (*ptr && *ptr != '#' && *ptr != '\n') + { + return ptr; + } + } + } +} + +/**************************************************************************** + * Name: parse_line + * + * Description: + * Parse the line from the configuration file into a variable name + * string and a value string. + * + ****************************************************************************/ + +static void parse_line(char *ptr, char **varname, char **varval) +{ + /* Skip over any leading spaces */ + + ptr = skip_space(ptr); + + /* The first no-space is the beginning of the variable name */ + + *varname = skip_space(ptr); + *varval = NULL; + + /* Parse to the end of the variable name */ + + ptr = find_name_end(ptr); + + /* An equal sign is expected next, perhaps after some white space */ + + if (*ptr && *ptr != '=') + { + /* Some else follows the variable name. Terminate the variable + * name and skip over any spaces. + */ + + *ptr = '\0'; + ptr = skip_space(ptr + 1); + } + + /* Verify that the equal sign is present */ + + if (*ptr == '=') + { + /* Make sure that the variable name is terminated (this was already + * done if the name was followed by white space. + */ + + *ptr = '\0'; + + /* The variable value should follow =, perhaps separated by some + * white space. + */ + + ptr = skip_space(ptr + 1); + if (*ptr) + { + /* Yes.. a variable follows. Save the pointer to the start + * of the variable string. + */ + + *varval = ptr; + + /* Find the end of the variable string and make sure that it + * is terminated. + */ + + ptr = find_value_end(ptr); + *ptr = '\0'; + } + } +} + +/**************************************************************************** + * Name: find_variable + * + * Description: + * Return true if the selected variable exists. Also return the value of + * the variable. + * + ****************************************************************************/ + +static bool find_variable(const char *configpath, const char *varname, + char **varvalue) +{ + FILE *stream; + char *tmpname; + char *tmpvalue; + char *ptr; + + stream = fopen(configpath, "r"); + if (!stream) + { + fprintf(stderr, "ERROR: failed to open %s for reading: %s\n", + configpath, strerror(errno)); + exit(EXIT_FAILURE); + } + + /* Loop until the entire file has been parsed. */ + + do + { + /* Read the next line from the file */ + + ptr = read_line(stream); + if (ptr) + { + /* Parse the line into a variable and a value field */ + + tmpname = NULL; + tmpvalue = NULL; + parse_line(ptr, &tmpname, &tmpvalue); + + /* Make sure that both a variable name and value name were found. */ + + if (tmpname == NULL || tmpvalue == NULL) + { + continue; + } + + /* Check if this the variable name and value we are looking for */ + + if (strcmp(varname, tmpname) == 0) + { + /* Yes.. return the value of the variable */ + + *varvalue = tmpvalue; + fclose(stream); + return true; + } + } + } + while (ptr); + + /* Return failure */ + + fclose(stream); + return false; +} + +/**************************************************************************** + * Name: check_variable + * + * Description: + * Return true if the selected variable exists in the configuration file + * and has the specified value. + * + ****************************************************************************/ + +static bool check_variable(const char *configpath, const char *varname, + const char *varvalue) +{ + char *tmpvalue; + + if (find_variable(configpath, varname, &tmpvalue)) + { + /* The variable name exists. Does it have a value? Does the value + * match varvalue? + */ + + if (tmpvalue != NULL && strcmp(varvalue, tmpvalue) == 0) + { + /* Yes.. return success */ + + return true; + } + } + + /* Return failure */ + + return false; +} + +/**************************************************************************** + * Name: test_filepath + * + * Description: + * Test if a regular file exists at this path. + * + ****************************************************************************/ + +static bool test_filepath(const char *filepath) +{ + struct stat statbuf; + int ret; + + ret = stat(filepath, &statbuf); + if (ret < 0) + { + return false; + } + + return S_ISREG(statbuf.st_mode); +} + +/**************************************************************************** + * Name: test_dirpath + * + * Description: + * Test if a regular file exists at this path. + * + ****************************************************************************/ + +static bool test_dirpath(const char *filepath) +{ + struct stat statbuf; + int ret; + + ret = stat(filepath, &statbuf); + if (ret < 0) + { + return false; + } + + return S_ISDIR(statbuf.st_mode); +} + +/**************************************************************************** + * Name: foreach_dirent + * + * Description: + * Given a directory path, call the provided function for each entry in + * the directory. + * + ****************************************************************************/ + +static int foreach_dirent(const char *dirpath, direntcb_t cb, void *arg) +{ + DIR *dirp; + struct dirent *result; + struct dirent entry; + int ret; + + dirp = opendir(dirpath); + if (dirp == NULL) + { + fprintf(stderr, "ERROR: Failed to open directory '%s': %s\n", + dirpath, strerror(errno)); + exit(EXIT_FAILURE); + } + + for (;;) + { + ret = readdir_r(dirp, &entry, &result); + if (ret != 0) + { + fprintf(stderr, + "ERROR: Failed to reed directory '%s' entry: %s\n", + dirpath, strerror(ret)); + closedir(dirp); + exit(EXIT_FAILURE); + } + + if (result == NULL) + { + break; + } + + /* Skip over the . and .. hard links */ + + if (strcmp(entry.d_name, ".") == 0 || strcmp(entry.d_name, "..") == 0) + { + continue; + } + + ret = cb(dirpath, &entry, arg); + if (ret != 0) + { + break; + } + } + + closedir(dirp); + return ret; +} + +/**************************************************************************** + * Name: enum_architectures + * + * Description: + * Enumerate all architecture directory names. + * + ****************************************************************************/ + +static int enum_architectures(const char *dirpath, struct dirent *entry, void *arg) +{ + char *archpath; + char *testpath; + + /* All architecture directories should contain a Kconfig file, an include/ + * directory, and a src/ directory. + */ + + asprintf(&archpath, "%s%c%s", dirpath, g_delim, entry->d_name); + asprintf(&testpath, "%s%cKconfig", archpath, g_delim); + if (test_filepath(testpath)) + { + free(testpath); + asprintf(&testpath, "%s%cinclude", archpath, g_delim); + if (test_dirpath(testpath)) + { + free(testpath); + asprintf(&testpath, "%s%csrc", archpath, g_delim); + if (test_dirpath(testpath)) + { + if (g_narch >= MAX_ARCHITECTURES) + { + fprintf(stderr, + "ERROR: Too many architecture directories found\n"); + exit(EXIT_FAILURE); + } + + g_arch[g_narch] = strdup(entry->d_name); + g_narch++; + } + } + } + + free(testpath); + free(archpath); + return 0; +} + +/**************************************************************************** + * Name: enum_mcus + * + * Description: + * Enumerate all MCU directory names. + * + ****************************************************************************/ + +static int enum_mcus(const char *dirpath, struct dirent *entry, void *arg) +{ + char *mcupath; + char *testpath; + + /* All MCU directories should contain a Kconfig and a Make.defs file. */ + + asprintf(&mcupath, "%s%c%s", dirpath, g_delim, entry->d_name); + asprintf(&testpath, "%s%cKconfig", mcupath, g_delim); + if (test_filepath(testpath)) + { + free(testpath); + asprintf(&testpath, "%s%cMake.defs", mcupath, g_delim); + if (test_filepath(testpath)) + { + if (g_nmcu >= MAX_MCUS) + { + fprintf(stderr, + "ERROR: Too many MCU directories found\n"); + exit(EXIT_FAILURE); + } + + g_mcu[g_nmcu] = strdup(entry->d_name); + g_nmcu++; + } + } + + free(testpath); + free(mcupath); + return 0; +} + +/**************************************************************************** + * Name: enum_board_configurations + * + * Description: + * Enumerate all configurations for boards find the configuration + * directory for the selected MCU. + * + ****************************************************************************/ + +static int enum_board_configurations(const char *dirpath, + struct dirent *entry, void *arg) +{ + char *configpath; + char *varvalue; + int ret = 0; + + /* All board directories should contain a defconfig file. */ + + asprintf(&configpath, "%s%c%s%cdefconfig", + dirpath, g_delim, entry->d_name, g_delim); + if (test_filepath(configpath)) + { + /* We don't want all board configurations, we only want the name of + * the board that includes a configuration with: + * + * CONFIG_ARCH_CHIP="xxxx" + * + * Where xxxx is the selected MCU name. + */ + + asprintf(&varvalue, "\"%s\"", g_selected_mcu); + if (check_variable(configpath, "CONFIG_ARCH_CHIP", varvalue)) + { + /* Found it... add the board name to the list of boards for the + * selected MCU. + */ + + if (g_nboard >= MAX_BOARDS) + { + fprintf(stderr, + "ERROR: Too many board configurations found\n"); + exit(EXIT_FAILURE); + } + + g_board[g_nboard] = strdup(arg); + g_nboard++; + + /* If we have not yet extracted the architecture family, then do + * that here. + */ + + if (g_selected_family == NULL) + { + char *family; + + if (find_variable(configpath, "CONFIG_ARCH_FAMILY", &family)) + { + g_selected_family = strdup(family); + } + } + + /* Stop the enumeration if we find a match. Continue if not... + * that is because one board might possible support multiple + * architectures. + */ + + ret = 1; + } + + free(varvalue); + } + + free(configpath); + return ret; +} + +/**************************************************************************** + * Name: enum_boards + * + * Description: + * Enumerate all boards find the configuration directory for the selected + * MCU. + * + ****************************************************************************/ + +static int enum_boards(const char *dirpath, struct dirent *entry, void *arg) +{ + char *boardpath; + char *testpath; + + /* All board directories should contain a Kconfig file, an include/ + * directory, and a src/ directory. + */ + + asprintf(&boardpath, "%s%c%s", dirpath, g_delim, entry->d_name); + asprintf(&testpath, "%s%cKconfig", boardpath, g_delim); + if (test_filepath(testpath)) + { + free(testpath); + asprintf(&testpath, "%s%cinclude", boardpath, g_delim); + if (test_dirpath(testpath)) + { + free(testpath); + asprintf(&testpath, "%s%csrc", boardpath, g_delim); + if (test_dirpath(testpath)) + { + /* Enumerate the board configurations */ + + (void)foreach_dirent(boardpath, enum_board_configurations, + entry->d_name); + } + } + } + + free(testpath); + free(boardpath); + return 0; +} + +/**************************************************************************** + * Name: list_select + * + * Description: + * Select one value from a list. + * + ****************************************************************************/ + +char *list_select(char **list, unsigned nitems) +{ + char ch; + int ndx; + int i; + + /* Show the list */ + + for (i = 0, ch = '1'; i < nitems; i++) + { + printf(" %c. %s\n", ch, list[i]); + if (ch == '9') + { + ch = 'a'; + } + else if (ch == 'z') + { + ch = 'A'; + } + else + { + ch++; + } + } + + for(; ; ) + { + bool input = false; + + printf("Enter [1"); + if (nitems > 1) + { + printf("-%c", nitems >= 9 ? '9' : '0' + nitems); + if (nitems > 9) + { + printf(",a"); + if (nitems > 10) + { + printf("-%c", 'a' + nitems - 10); + if (nitems > 35) + { + printf(",A"); + if (nitems > 36) + { + printf("-%c", 'A' + nitems - 36); + } + } + } + } + } + + printf("]: "); + + do + { + ch = getchar(); + if (ch >= '1' && ch <= '9') + { + ndx = ch - '1'; + } + else if (ch >= 'a' && ch <= 'z') + { + ndx = ch - 'a' + 9; + } + else if (ch >= 'A' && ch <= 'Z') + { + ndx = ch - 'A' + 35; + } + else if (ch == '\n') + { + continue; + } + else + { + printf("Invalid selection: %c -- Try again\n", ch); + input = true; + continue; + } + + if (ndx < nitems) + { + return list[ndx]; + } + else + { + printf("Invalid selection: %c -- Try again\n", ch); + input = true; + } + } + while (!input); + } +} + +/**************************************************************************** + * Name: create_config + * + * Description: + * Generate a bogus .config file. There is only sufficient information + * in this bogus .config to estable the correct symbolic links. + * + ****************************************************************************/ + +static void create_config(void) +{ + FILE *stream; + + stream = fopen(".config", "w"); + if (!stream) + { + fprintf(stderr, "ERROR: failed to open .config for writing: %s\n", + strerror(errno)); + exit(EXIT_FAILURE); + } + + fprintf(stream, "CONFIG_ARCH=\"%s\"\n", g_selected_arch); + if (g_selected_family != NULL) + { + fprintf(stream, "CONFIG_ARCH_FAMILY=%s\n", g_selected_family); + } + + fprintf(stream, "CONFIG_ARCH_CHIP=\"%s\"\n", g_selected_mcu); + fprintf(stream, "CONFIG_ARCH_BOARD=\"%s\"\n", g_selected_board); + + fclose(stream); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: main + * + * Description: + * Program entry point. + * + ****************************************************************************/ + +int main(int argc, char **argv) +{ + char *archpath; + + /* Enumerate the architectures */ + + g_narch = 0; + foreach_dirent(g_archdir, enum_architectures, NULL); + + /* Select an architecture */ + + printf("Select an architecture:\n"); + g_selected_arch = list_select(g_arch, g_narch); + + /* Enumerate MCUs for the selected architecture */ + + g_nmcu = 0; + asprintf(&archpath, "%s%c%s%csrc", g_archdir, g_delim, g_selected_arch, g_delim); + foreach_dirent(archpath, enum_mcus, NULL); + + /* Select an MCU */ + + printf("Select an MCU for architecutre=%s:\n", g_selected_arch); + g_selected_mcu = list_select(g_mcu, g_nmcu); + + /* Enumerate the architectures */ + + g_nboard = 0; + foreach_dirent(g_configdir, enum_boards, NULL); + + /* Select an board */ + + printf("Select a board for MCU=%s:\n", g_selected_mcu); + g_selected_board = list_select(g_board, g_nboard); + + /* Then output a bogus .config file with enough information to establish + * the correct symbolic links + */ + + create_config(); + return 0; +} -- GitLab From efbd035b566245920dd58ec88eb3e753efcc133c Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 2 Jun 2017 11:24:19 -0600 Subject: [PATCH 908/990] Cosmetic changes to comments --- tools/initialconfig.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/tools/initialconfig.c b/tools/initialconfig.c index 19a2bd420c..bbfb194ef8 100644 --- a/tools/initialconfig.c +++ b/tools/initialconfig.c @@ -805,7 +805,7 @@ int main(int argc, char **argv) { char *archpath; - /* Enumerate the architectures */ + /* Enumerate all of the architectures */ g_narch = 0; foreach_dirent(g_archdir, enum_architectures, NULL); @@ -815,7 +815,7 @@ int main(int argc, char **argv) printf("Select an architecture:\n"); g_selected_arch = list_select(g_arch, g_narch); - /* Enumerate MCUs for the selected architecture */ + /* Enumerate the MCUs for the selected architecture */ g_nmcu = 0; asprintf(&archpath, "%s%c%s%csrc", g_archdir, g_delim, g_selected_arch, g_delim); @@ -826,7 +826,7 @@ int main(int argc, char **argv) printf("Select an MCU for architecutre=%s:\n", g_selected_arch); g_selected_mcu = list_select(g_mcu, g_nmcu); - /* Enumerate the architectures */ + /* Enumerate the boards for the selected MCU */ g_nboard = 0; foreach_dirent(g_configdir, enum_boards, NULL); -- GitLab From 430060e92e1fade7822f24135336dc26eb100b82 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 2 Jun 2017 13:06:09 -0600 Subject: [PATCH 909/990] Build system: Hook tools/initconfig into top-level Makefiles. --- Makefile.unix | 18 +++++++++++++----- Makefile.win | 18 +++++++++++++----- tools/initialconfig.c | 5 +++++ 3 files changed, 31 insertions(+), 10 deletions(-) diff --git a/Makefile.unix b/Makefile.unix index 811b0551e3..c33071a99d 100644 --- a/Makefile.unix +++ b/Makefile.unix @@ -282,30 +282,38 @@ tools/cnvwindeps$(HOSTEXEEXT): # configured directories. Make.defs: + $(Q) echo "No Make.defs file found, creating one" echo "include $(TOPDIR)$(DELIM).config" > Make.defs echo "include $(TOPDIR)$(DELIM)tools$(DELIM)Config.mk" >> Make.defs +tools/initialconfig$(HOSTEXEEXT): + $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" initialconfig$(HOSTEXEEXT) + +.config: tools/initialconfig$(HOSTEXEEXT) + $(Q) echo "No .config file found, creating one" + $(Q) tools/initialconfig$(HOSTEXEEXT) + # Link the arch//include directory to include/arch -include/arch: Make.defs +include/arch: .config Make.defs @echo "LN: include/arch to $(ARCH_DIR)/include" $(Q) $(DIRLINK) $(TOPDIR)/$(ARCH_DIR)/include include/arch # Link the configs//include directory to include/arch/board -include/arch/board: include/arch Make.defs include/arch +include/arch/board: include/arch @echo "LN: include/arch/board to $(BOARD_DIR)/include" $(Q) $(DIRLINK) $(BOARD_DIR)/include include/arch/board # Link the configs//src dir to arch//src/board -$(ARCH_SRC)/board: Make.defs +$(ARCH_SRC)/board: @echo "LN: $(ARCH_SRC)/board to $(BOARD_DIR)/src" $(Q) $(DIRLINK) $(BOARD_DIR)/src $(ARCH_SRC)/board # Link arch//include/ to arch//include/chip -$(ARCH_SRC)/chip: Make.defs +$(ARCH_SRC)/chip: ifneq ($(CONFIG_ARCH_CHIP),) @echo "LN: $(ARCH_SRC)/chip to $(ARCH_SRC)/$(CONFIG_ARCH_CHIP)" $(Q) $(DIRLINK) $(TOPDIR)/$(ARCH_SRC)/$(CONFIG_ARCH_CHIP) $(ARCH_SRC)/chip @@ -313,7 +321,7 @@ endif # Link arch//src/ to arch//src/chip -include/arch/chip: include/arch Make.defs +include/arch/chip: include/arch ifneq ($(CONFIG_ARCH_CHIP),) @echo "LN: include/arch/chip to $(ARCH_INC)/$(CONFIG_ARCH_CHIP)" $(Q) $(DIRLINK) $(TOPDIR)/$(ARCH_INC)/$(CONFIG_ARCH_CHIP) include/arch/chip diff --git a/Makefile.win b/Makefile.win index 32d42772c6..9827048271 100644 --- a/Makefile.win +++ b/Makefile.win @@ -277,12 +277,20 @@ tools\mkdeps$(HOSTEXEEXT): # configured directories. Make.defs: + $(Q) echo "No Make.defs file found, creating one" echo "include $(TOPDIR)$(DELIM).config" > Make.defs echo "include $(TOPDIR)$(DELIM)tools$(DELIM)Config.mk" >> Make.defs +tools\initialconfig$(HOSTEXEEXT): + $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" initialconfig$(HOSTEXEEXT) + +.config: tools\initialconfig$(HOSTEXEEXT) + $(Q) echo "No .config file found, creating one" + $(Q) tools\initialconfig$(HOSTEXEEXT) + # Link the arch\\include directory to include\arch -include\arch: Make.defs +include\arch: .config Make.defs @echo LN: include\arch to $(ARCH_DIR)\include ifeq ($(CONFIG_WINDOWS_MKLINK),y) $(Q) /user:administrator mklink /d include\arch $(TOPDIR)\$(ARCH_DIR)\include @@ -293,7 +301,7 @@ endif # Link the configs\\include directory to include\arch\board -include\arch\board: include\arch Make.defs include\arch +include\arch\board: include\arch @echo LN: include\arch\board to $(BOARD_DIR)\include ifeq ($(CONFIG_WINDOWS_MKLINK),y) $(Q) /user:administrator mklink /d include\arch\board $(BOARD_DIR)\include @@ -304,7 +312,7 @@ endif # Link the configs\\src dir to arch\\src\board -$(ARCH_SRC)\board: Make.defs +$(ARCH_SRC)\board: @echo LN: $(ARCH_SRC)\board to $(BOARD_DIR)\src ifeq ($(CONFIG_WINDOWS_MKLINK),y) $(Q) /user:administrator mklink /d $(ARCH_SRC)\board $(BOARD_DIR)\src @@ -315,7 +323,7 @@ endif # Link arch\\include\ to arch\\include\chip -$(ARCH_SRC)\chip: Make.defs +$(ARCH_SRC)\chip: ifneq ($(CONFIG_ARCH_CHIP),) @echo LN: $(ARCH_SRC)\chip to $(ARCH_SRC)\$(CONFIG_ARCH_CHIP) ifeq ($(CONFIG_WINDOWS_MKLINK),y) @@ -328,7 +336,7 @@ endif # Link arch\\src\ to arch\\src\chip -include\arch\chip: include\arch Make.defs +include\arch\chip: include\arch ifneq ($(CONFIG_ARCH_CHIP),) @echo LN: include\arch\chip to $(ARCH_INC)\$(CONFIG_ARCH_CHIP) ifeq ($(CONFIG_WINDOWS_MKLINK),y) diff --git a/tools/initialconfig.c b/tools/initialconfig.c index bbfb194ef8..7af4c5be21 100644 --- a/tools/initialconfig.c +++ b/tools/initialconfig.c @@ -841,5 +841,10 @@ int main(int argc, char **argv) */ create_config(); + + /* TODO: Copy a Make.defs file from a configuration for the selected + * board that supports the selected MCU. + */ + return 0; } -- GitLab From d1eaac7ed7133e69da095dde7c7bf4dd1b9299ba Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 2 Jun 2017 13:16:29 -0600 Subject: [PATCH 910/990] Build system: Suppress output of some command lines. --- Makefile.unix | 4 ++-- Makefile.win | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/Makefile.unix b/Makefile.unix index c33071a99d..8c36def651 100644 --- a/Makefile.unix +++ b/Makefile.unix @@ -283,8 +283,8 @@ tools/cnvwindeps$(HOSTEXEEXT): Make.defs: $(Q) echo "No Make.defs file found, creating one" - echo "include $(TOPDIR)$(DELIM).config" > Make.defs - echo "include $(TOPDIR)$(DELIM)tools$(DELIM)Config.mk" >> Make.defs + $(Q) echo "include $(TOPDIR)$(DELIM).config" > Make.defs + $(Q) echo "include $(TOPDIR)$(DELIM)tools$(DELIM)Config.mk" >> Make.defs tools/initialconfig$(HOSTEXEEXT): $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" initialconfig$(HOSTEXEEXT) diff --git a/Makefile.win b/Makefile.win index 9827048271..e904c26ae5 100644 --- a/Makefile.win +++ b/Makefile.win @@ -278,8 +278,8 @@ tools\mkdeps$(HOSTEXEEXT): Make.defs: $(Q) echo "No Make.defs file found, creating one" - echo "include $(TOPDIR)$(DELIM).config" > Make.defs - echo "include $(TOPDIR)$(DELIM)tools$(DELIM)Config.mk" >> Make.defs + $(Q) echo "include $(TOPDIR)$(DELIM).config" > Make.defs + $(Q) echo "include $(TOPDIR)$(DELIM)tools$(DELIM)Config.mk" >> Make.defs tools\initialconfig$(HOSTEXEEXT): $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" initialconfig$(HOSTEXEEXT) -- GitLab From 2c903d5c7a720371032e2516774a95be0be1812e Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 2 Jun 2017 16:12:21 -0600 Subject: [PATCH 911/990] Fix spelling in printf output --- tools/initialconfig.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tools/initialconfig.c b/tools/initialconfig.c index 7af4c5be21..40b98b460d 100644 --- a/tools/initialconfig.c +++ b/tools/initialconfig.c @@ -823,7 +823,7 @@ int main(int argc, char **argv) /* Select an MCU */ - printf("Select an MCU for architecutre=%s:\n", g_selected_arch); + printf("Select an MCU for architecture=%s:\n", g_selected_arch); g_selected_mcu = list_select(g_mcu, g_nmcu); /* Enumerate the boards for the selected MCU */ -- GitLab From c584d27c3c432a72b14e00cfb6b681c071791b32 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 2 Jun 2017 16:14:13 -0600 Subject: [PATCH 912/990] Revert "Build system: Hook tools/initconfig into top-level Makefiles." This reverts commit 430060e92e1fade7822f24135336dc26eb100b82. That commit has some unexpected side-effects --- Makefile.unix | 22 ++++++++++------------ Makefile.win | 17 +++++------------ tools/initialconfig.c | 5 ----- 3 files changed, 15 insertions(+), 29 deletions(-) diff --git a/Makefile.unix b/Makefile.unix index 8c36def651..8a88b5f9db 100644 --- a/Makefile.unix +++ b/Makefile.unix @@ -282,38 +282,36 @@ tools/cnvwindeps$(HOSTEXEEXT): # configured directories. Make.defs: +<<<<<<< HEAD $(Q) echo "No Make.defs file found, creating one" $(Q) echo "include $(TOPDIR)$(DELIM).config" > Make.defs $(Q) echo "include $(TOPDIR)$(DELIM)tools$(DELIM)Config.mk" >> Make.defs - -tools/initialconfig$(HOSTEXEEXT): - $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" initialconfig$(HOSTEXEEXT) - -.config: tools/initialconfig$(HOSTEXEEXT) - $(Q) echo "No .config file found, creating one" - $(Q) tools/initialconfig$(HOSTEXEEXT) +======= + echo "include $(TOPDIR)$(DELIM).config" > Make.defs + echo "include $(TOPDIR)$(DELIM)tools$(DELIM)Config.mk" >> Make.defs +>>>>>>> parent of 430060e92e... Build system: Hook tools/initconfig into top-level Makefiles. # Link the arch//include directory to include/arch -include/arch: .config Make.defs +include/arch: Make.defs @echo "LN: include/arch to $(ARCH_DIR)/include" $(Q) $(DIRLINK) $(TOPDIR)/$(ARCH_DIR)/include include/arch # Link the configs//include directory to include/arch/board -include/arch/board: include/arch +include/arch/board: include/arch Make.defs include/arch @echo "LN: include/arch/board to $(BOARD_DIR)/include" $(Q) $(DIRLINK) $(BOARD_DIR)/include include/arch/board # Link the configs//src dir to arch//src/board -$(ARCH_SRC)/board: +$(ARCH_SRC)/board: Make.defs @echo "LN: $(ARCH_SRC)/board to $(BOARD_DIR)/src" $(Q) $(DIRLINK) $(BOARD_DIR)/src $(ARCH_SRC)/board # Link arch//include/ to arch//include/chip -$(ARCH_SRC)/chip: +$(ARCH_SRC)/chip: Make.defs ifneq ($(CONFIG_ARCH_CHIP),) @echo "LN: $(ARCH_SRC)/chip to $(ARCH_SRC)/$(CONFIG_ARCH_CHIP)" $(Q) $(DIRLINK) $(TOPDIR)/$(ARCH_SRC)/$(CONFIG_ARCH_CHIP) $(ARCH_SRC)/chip @@ -321,7 +319,7 @@ endif # Link arch//src/ to arch//src/chip -include/arch/chip: include/arch +include/arch/chip: include/arch Make.defs ifneq ($(CONFIG_ARCH_CHIP),) @echo "LN: include/arch/chip to $(ARCH_INC)/$(CONFIG_ARCH_CHIP)" $(Q) $(DIRLINK) $(TOPDIR)/$(ARCH_INC)/$(CONFIG_ARCH_CHIP) include/arch/chip diff --git a/Makefile.win b/Makefile.win index e904c26ae5..a449cd346d 100644 --- a/Makefile.win +++ b/Makefile.win @@ -281,16 +281,9 @@ Make.defs: $(Q) echo "include $(TOPDIR)$(DELIM).config" > Make.defs $(Q) echo "include $(TOPDIR)$(DELIM)tools$(DELIM)Config.mk" >> Make.defs -tools\initialconfig$(HOSTEXEEXT): - $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" initialconfig$(HOSTEXEEXT) - -.config: tools\initialconfig$(HOSTEXEEXT) - $(Q) echo "No .config file found, creating one" - $(Q) tools\initialconfig$(HOSTEXEEXT) - # Link the arch\\include directory to include\arch -include\arch: .config Make.defs +include\arch: Make.defs @echo LN: include\arch to $(ARCH_DIR)\include ifeq ($(CONFIG_WINDOWS_MKLINK),y) $(Q) /user:administrator mklink /d include\arch $(TOPDIR)\$(ARCH_DIR)\include @@ -301,7 +294,7 @@ endif # Link the configs\\include directory to include\arch\board -include\arch\board: include\arch +include\arch\board: include\arch Make.defs include\arch @echo LN: include\arch\board to $(BOARD_DIR)\include ifeq ($(CONFIG_WINDOWS_MKLINK),y) $(Q) /user:administrator mklink /d include\arch\board $(BOARD_DIR)\include @@ -312,7 +305,7 @@ endif # Link the configs\\src dir to arch\\src\board -$(ARCH_SRC)\board: +$(ARCH_SRC)\board: Make.defs @echo LN: $(ARCH_SRC)\board to $(BOARD_DIR)\src ifeq ($(CONFIG_WINDOWS_MKLINK),y) $(Q) /user:administrator mklink /d $(ARCH_SRC)\board $(BOARD_DIR)\src @@ -323,7 +316,7 @@ endif # Link arch\\include\ to arch\\include\chip -$(ARCH_SRC)\chip: +$(ARCH_SRC)\chip: Make.defs ifneq ($(CONFIG_ARCH_CHIP),) @echo LN: $(ARCH_SRC)\chip to $(ARCH_SRC)\$(CONFIG_ARCH_CHIP) ifeq ($(CONFIG_WINDOWS_MKLINK),y) @@ -336,7 +329,7 @@ endif # Link arch\\src\ to arch\\src\chip -include\arch\chip: include\arch +include\arch\chip: include\arch Make.defs ifneq ($(CONFIG_ARCH_CHIP),) @echo LN: include\arch\chip to $(ARCH_INC)\$(CONFIG_ARCH_CHIP) ifeq ($(CONFIG_WINDOWS_MKLINK),y) diff --git a/tools/initialconfig.c b/tools/initialconfig.c index 40b98b460d..90246dbe63 100644 --- a/tools/initialconfig.c +++ b/tools/initialconfig.c @@ -841,10 +841,5 @@ int main(int argc, char **argv) */ create_config(); - - /* TODO: Copy a Make.defs file from a configuration for the selected - * board that supports the selected MCU. - */ - return 0; } -- GitLab From 6c3a3c305fb63675901f6cc710a3a92b287a1f4a Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 2 Jun 2017 16:42:44 -0600 Subject: [PATCH 913/990] Comment out most of 430060e92e1fade7822f24135336dc26eb100b82. Clean-up some dependencies in top-level Makefile --- Makefile.unix | 26 ++++++++++++++------------ Makefile.win | 21 ++++++++++++++------- 2 files changed, 28 insertions(+), 19 deletions(-) diff --git a/Makefile.unix b/Makefile.unix index 8a88b5f9db..1ccae8b123 100644 --- a/Makefile.unix +++ b/Makefile.unix @@ -281,19 +281,21 @@ tools/cnvwindeps$(HOSTEXEEXT): # setting up symbolic links with 'generic' directory names to specific, # configured directories. -Make.defs: -<<<<<<< HEAD - $(Q) echo "No Make.defs file found, creating one" - $(Q) echo "include $(TOPDIR)$(DELIM).config" > Make.defs - $(Q) echo "include $(TOPDIR)$(DELIM)tools$(DELIM)Config.mk" >> Make.defs -======= - echo "include $(TOPDIR)$(DELIM).config" > Make.defs - echo "include $(TOPDIR)$(DELIM)tools$(DELIM)Config.mk" >> Make.defs ->>>>>>> parent of 430060e92e... Build system: Hook tools/initconfig into top-level Makefiles. +# Make.defs: +# $(Q) echo "No Make.defs file found, creating one" +# $(Q) echo "include $(TOPDIR)$(DELIM).config" > Make.defs +# $(Q) echo "include $(TOPDIR)$(DELIM)tools$(DELIM)Config.mk" >> Make.defs + +# tools/initialconfig$(HOSTEXEEXT): +# $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" initialconfig$(HOSTEXEEXT) +# +# .config: tools/initialconfig$(HOSTEXEEXT) +# $(Q) echo "No .config file found, creating one" +# $(Q) tools/initialconfig$(HOSTEXEEXT) # Link the arch//include directory to include/arch -include/arch: Make.defs +include/arch: .config @echo "LN: include/arch to $(ARCH_DIR)/include" $(Q) $(DIRLINK) $(TOPDIR)/$(ARCH_DIR)/include include/arch @@ -305,13 +307,13 @@ include/arch/board: include/arch Make.defs include/arch # Link the configs//src dir to arch//src/board -$(ARCH_SRC)/board: Make.defs +$(ARCH_SRC)/board: .config @echo "LN: $(ARCH_SRC)/board to $(BOARD_DIR)/src" $(Q) $(DIRLINK) $(BOARD_DIR)/src $(ARCH_SRC)/board # Link arch//include/ to arch//include/chip -$(ARCH_SRC)/chip: Make.defs +$(ARCH_SRC)/chip: .config ifneq ($(CONFIG_ARCH_CHIP),) @echo "LN: $(ARCH_SRC)/chip to $(ARCH_SRC)/$(CONFIG_ARCH_CHIP)" $(Q) $(DIRLINK) $(TOPDIR)/$(ARCH_SRC)/$(CONFIG_ARCH_CHIP) $(ARCH_SRC)/chip diff --git a/Makefile.win b/Makefile.win index a449cd346d..e9eff22e90 100644 --- a/Makefile.win +++ b/Makefile.win @@ -276,14 +276,21 @@ tools\mkdeps$(HOSTEXEEXT): # setting up symbolic links with 'generic' directory names to specific, # configured directories. -Make.defs: - $(Q) echo "No Make.defs file found, creating one" - $(Q) echo "include $(TOPDIR)$(DELIM).config" > Make.defs - $(Q) echo "include $(TOPDIR)$(DELIM)tools$(DELIM)Config.mk" >> Make.defs +# Make.defs: +# $(Q) echo "No Make.defs file found, creating one" +# $(Q) echo "include $(TOPDIR)$(DELIM).config" > Make.defs +# $(Q) echo "include $(TOPDIR)$(DELIM)tools$(DELIM)Config.mk" >> Make.defs + +# tools\initialconfig$(HOSTEXEEXT): +# $(Q) $(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" initialconfig$(HOSTEXEEXT) +# +# .config: tools\initialconfig$(HOSTEXEEXT) +# $(Q) echo "No .config file found, creating one" +# $(Q) tools\initialconfig$(HOSTEXEEXT) # Link the arch\\include directory to include\arch -include\arch: Make.defs +include\arch: .config @echo LN: include\arch to $(ARCH_DIR)\include ifeq ($(CONFIG_WINDOWS_MKLINK),y) $(Q) /user:administrator mklink /d include\arch $(TOPDIR)\$(ARCH_DIR)\include @@ -305,7 +312,7 @@ endif # Link the configs\\src dir to arch\\src\board -$(ARCH_SRC)\board: Make.defs +$(ARCH_SRC)\board: .config @echo LN: $(ARCH_SRC)\board to $(BOARD_DIR)\src ifeq ($(CONFIG_WINDOWS_MKLINK),y) $(Q) /user:administrator mklink /d $(ARCH_SRC)\board $(BOARD_DIR)\src @@ -316,7 +323,7 @@ endif # Link arch\\include\ to arch\\include\chip -$(ARCH_SRC)\chip: Make.defs +$(ARCH_SRC)\chip: .config ifneq ($(CONFIG_ARCH_CHIP),) @echo LN: $(ARCH_SRC)\chip to $(ARCH_SRC)\$(CONFIG_ARCH_CHIP) ifeq ($(CONFIG_WINDOWS_MKLINK),y) -- GitLab From b27ccd1bc6321c598d161209b624f45d0d112899 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 2 Jun 2017 17:09:08 -0600 Subject: [PATCH 914/990] Makefiles: Remove some unnecessary dependencies --- Makefile.unix | 4 ++-- Makefile.win | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/Makefile.unix b/Makefile.unix index 1ccae8b123..bfdc3c5a8d 100644 --- a/Makefile.unix +++ b/Makefile.unix @@ -301,7 +301,7 @@ include/arch: .config # Link the configs//include directory to include/arch/board -include/arch/board: include/arch Make.defs include/arch +include/arch/board: include/arch @echo "LN: include/arch/board to $(BOARD_DIR)/include" $(Q) $(DIRLINK) $(BOARD_DIR)/include include/arch/board @@ -321,7 +321,7 @@ endif # Link arch//src/ to arch//src/chip -include/arch/chip: include/arch Make.defs +include/arch/chip: include/arch ifneq ($(CONFIG_ARCH_CHIP),) @echo "LN: include/arch/chip to $(ARCH_INC)/$(CONFIG_ARCH_CHIP)" $(Q) $(DIRLINK) $(TOPDIR)/$(ARCH_INC)/$(CONFIG_ARCH_CHIP) include/arch/chip diff --git a/Makefile.win b/Makefile.win index e9eff22e90..a023c6e013 100644 --- a/Makefile.win +++ b/Makefile.win @@ -301,7 +301,7 @@ endif # Link the configs\\include directory to include\arch\board -include\arch\board: include\arch Make.defs include\arch +include\arch\board: include\arch @echo LN: include\arch\board to $(BOARD_DIR)\include ifeq ($(CONFIG_WINDOWS_MKLINK),y) $(Q) /user:administrator mklink /d include\arch\board $(BOARD_DIR)\include @@ -336,7 +336,7 @@ endif # Link arch\\src\ to arch\\src\chip -include\arch\chip: include\arch Make.defs +include\arch\chip: include\arch ifneq ($(CONFIG_ARCH_CHIP),) @echo LN: include\arch\chip to $(ARCH_INC)\$(CONFIG_ARCH_CHIP) ifeq ($(CONFIG_WINDOWS_MKLINK),y) -- GitLab From 4526cd665ebcb210790b0afb6d3f134b8811382e Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 3 Jun 2017 06:43:14 -0600 Subject: [PATCH 915/990] =?UTF-8?q?Correct=20typo=20in=20header=20file=20i?= =?UTF-8?q?empotence.=20=20Noted=20as=20part=20of=20Issue=20#53=20by=20Gor?= =?UTF-8?q?an=20Meki=C4=87?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- libxx/libxx.hxx | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libxx/libxx.hxx b/libxx/libxx.hxx index be740aaf87..6abab2b365 100644 --- a/libxx/libxx.hxx +++ b/libxx/libxx.hxx @@ -34,7 +34,7 @@ //*************************************************************************** #ifndef __LIBXX_LIBXX_HXX -#define __LIBXX_LIBXX__HXX +#define __LIBXX_LIBXX_HXX 1 //*************************************************************************** // Included Files -- GitLab From 30ab574060b4bef692853c9bd8885bcb36fddf6d Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Sun, 4 Jun 2017 12:20:48 -0400 Subject: [PATCH 916/990] libfflush remove extra semicolon --- libc/stdio/lib_libfflush.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libc/stdio/lib_libfflush.c b/libc/stdio/lib_libfflush.c index 22172a66c7..3eef605340 100644 --- a/libc/stdio/lib_libfflush.c +++ b/libc/stdio/lib_libfflush.c @@ -137,7 +137,7 @@ ssize_t lib_fflush(FAR FILE *stream, bool bforce) */ stream->fs_flags |= __FS_FLAG_ERROR; - ret = -get_errno();; + ret = -get_errno(); goto errout_with_sem; } -- GitLab From 5aa23da717af5864ddcf9b9e5b04914c587337de Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 4 Jun 2017 14:23:11 -0600 Subject: [PATCH 917/990] Update ChangeLog in preparation for NuttX-7.21 release. --- ChangeLog | 1304 ++++++++++++++++++++++++++++++++++++++++++++++++++++- 1 file changed, 1303 insertions(+), 1 deletion(-) diff --git a/ChangeLog b/ChangeLog index 7466baf3d0..bc135b466c 100755 --- a/ChangeLog +++ b/ChangeLog @@ -14092,4 +14092,1306 @@ * usbhost_cdcacm: fix tx outbuffer overflow and remove now invalid assert. From Janne Rosberg (2017-03-07). -7.21 2017-xx-xx Gregory Nutt +7.21 2017-06-06 Gregory Nutt + + * tools/kconfig2html: Need to increase the maximum number of default + values (2017-03-08). + * C library: Add strerror_r() (2017-03-08). + * C Library: Add wcstoull(), swprintf(), wcstod(), wcstof(), wcstol(), + wcstold(), wcstoul(), wcstoll() functions. Add mbsnrtowcs() and + wcsnrtombs() (just returning success). Add mbtowc() and wctomb() to + C++ std namespace. From Alan Carvalho de Assis (2017-03-08). + * Kinetis: Fixed GPIO _PIN_OUTPUT_LOWDRIVE swapped with + _PIN_OUTPUT_OPENDRAIN. From David Sidrane (2017-03-08). + * Ensure interrupts are back on BEFORE running code dependant on + clock_systimer. From David Sidrane (2017-03-08). + * Enable compilation of libc++ same way as uClibc++. From Alan + Carvalho de Assis (2017-03-08). + * Add LPC4337FET256. From Andreas Bihlmaier (2017-03-09). + * Change Kconfig type of ADC0_MASK from hex to int; add ADC driver + options to lpc43xx. From Andreas Bihlmaier (2017-03-09). + * Add missing PINCONF_INBUFFER in several places of + lpc4310203050_pinconfig.h. From Andreas Bihlmaier (2017-03-09). + * Rename LPC43_GPDMA_GLOBAL_CONFIG (already slipped previous commit C + file); fix GPDMA_CONTROL_SBSIZE_*, improve usability of + GPDMA_CONTROL_{S,D} macros. From Andreas Bihlmaier (2017-03-09). + * Fix errors in LPC43 SCT and SGPIO headers. From Andreas Bihlmaier + (2017-03-09). + * Fix logic error in lpc43_adc. From Andreas Bihlmaier (2017-03-09). + * Fix logic in preprocessor checks and correct arguments to + lpc43_pin_config initialization. From Andreas Bihlmaier (2017-03-09). + * Use correct macro for irqid (fortunately both point to + LPC43_IRQ_EXTINT+18). From Andreas Bihlmaier (2017-03-09). + * Actually write modified value to register. From Andreas Bihlmaier + (2017-03-09). + * Increase number of supported PWM channels from 4 to 6. From Andreas + Bihlmaier (2017-03-09). + * Fix as5048b by adding missing frequency parameter. From Andreas + Bihlmaier (2017-03-09). + * Kinetis: Allow Board to add Pullups on SDHC lines. From David + Sidrane (2017-03-09). + * EZ80F910200KITG: Missing support logic in configs/Kconfig (2017-03-09). + * Olimex-STM32-P407: Update USB host support (2017-03-09). + * Olimex STM32 P407: USB host support for USB FLASH sticks is now + supported in the base nsh configuration (2017-03-09). + * STM32, STM32 F7, and STM32 L4: Back out part of + 3331e9c49aaaa6dcc3aefa6a9e2c80422ffedcd3. Returning immediately in + the case of a NAK makes the Mass Storage Class driver unreliable. + The retry/timeout logic is necessary. This implementation tries to + implement a compromise: If a NAK is received after some data is + received, then the partial data received is returned as with + 3331e9c49aaaa6dcc3aefa6a9e2c80422ffedcd3. If if a NAK is received + with no data, then no longer returns the NAK error immediately but + retries until data is received or a timeout occurs. Initial testing + indicates that this fixes the issues the MSC. However, I have + concerns that if multiple sectors are read in one transfer, there + could be NAKs between sectors as well and, in that case, then change + will still cause failures (2017-03-09). + * STM32F2: Add USB OTG HS support for stm32f20xxx cores. From Simon + Piriou (2017-03-09). + * Remove all references to arch_usbhost_initialize(). That was + incorrectly called from apps/examples/hidkbd. That is violation of + the OS interfacing rules and will no longer be supported. USB host + should be initialized as part of the board bring-up logic was with + any other devices and should not involve illegal calls from + applications into the OS (2017-03-09). + * STM32, STM32 F7, STM32 L4: OTG host drivers: Do not do data toggle + if interrupt transfer is NAKed. Sugested by webbbn@gmail.com + (2017-03-09). + * apps/examples/usbterm is gone because it can be configured to perform + an illegal call into the OS. Remove all traces of + CONFIG_EXAMPLES_USBTERM* and all of the illegal device support + (2017-03-09). + * Save elapsed time before handling I2C in stm32_i2c_sem_waitstop(). + This patch follows the same logic as in previous fix to + stm32_i2c_sem_waitdone(). It is possible that a context switch + occurs after I2C registers are read but before elapsed time is saved + in stm32_i2c_sem_waitstop(). It is then possible that the registers + were read only once with "elapsed time" equal 0. When scheduler + resumes this thread it is quite possible that now "elapsed time" will + be well above timeout threshold. In that case the function returns + and reports a timeout, even though the registers were not read + "recently". Fix this by inverting the order of operations in the loop + - save elapsed time before reading registers. This way a context + switch anywhere in the loop will not cause an erroneous "timeout" + error. From Freddie Chopin (2017-03-10). + * pthreads: Fix pthread_mutexattr_init(). It was not initializing the + protocol field when priority inheritance is enabled (2017-03-10). + * Priority inheritance: When CONFIG_SEM_PREALLOCHOLDERS==0, there is + only a single, hard-allocated holder structure. This is problem + because in sem_wait() the holder is released, but needs to remain in + the holder container until sem_restorebaseprio() is called. The call + to sem_restorebaseprio() must be one of the last things the + sem_wait() does because it can cause the task to be suspended. If in + sem_wait(), a new task gets the semaphore count then it will fail to + allocate the holder and will not participate in priority + inheritance. This fix is to add two hard-allocated holders in the + sem_t structure: One of the old holder and one for the new holder + (2017-03-10). + * STM32, STM32 F7, and STM32 L4: Clone Freddie Chopin's I2C change to + similar STM32 I2C drivers. From David Sidrane (2017-03-10). + * Priority Inversion fixes: Initalization. From David Sidrane + (2017-03-10). + * configs: Add Particle Photon board support. From Simon Piriou + (2017-03-10). + * tools/testbuild.sh: Add debug option (-d) (2017-03-10). + * multiple fixes in nrf24l01 driver: (1) signal POLLIN if there is + already data in the FIFO, (2) send ETIMEDOUT to userspace after 2 + seconds if TX IRQ was not received, (3) handle FIFO overflow, (4) + handle invalid pipes/empty FIFO, and (5) multiple cosmetics (missing + static, duplicate define, missing \n). From Leif Jakob (2017-03-10). + * STM32 F33 ADC: Correct bad definitions of base addresses; Fix + naming collision by changing colliding STM32_ADC12_BASE to + STM32_ADC12_CMN_BASE (2017-03-10). + * photon: Add iwdg timer support. From Simon Piriou (2017-03-11). + * photon: Add usb otg hs support and usbnsh app. From Simon Piriou + (2017-03-11). + * photon: Add LEDs and BUTTONS support. From Simon Piriou (2017-03-11). + * As discovered by dcabecinhas. This fix assume the 8 byte alignment + options for size stack size or this will overwrite the first word + after TOS. See + https://github.com/PX4/Firmware/issues/6613#issuecomment-285869778. + From David Sidrane (2017-03-11). + * STM32F20xxx: Add BOARD_DISABLE_USBOTG_HSULPI flag. From Simon + Piriou (2017-03-11). + * STM32: Propagate STM32 F2 changes of last PR to STM32 F4 and F7 + OTGHS (2017-03-11). + * STM32 OTG HS: A little research reveals that only the F2 RCC + initialization set the OTGHSULPIEN bit and Photon is the only F2 + board configuration that uses OTG. Therefore, we can simplify the + conditional logic of the last PR. Negative logic was used (#ifndef + BOARD_DISABLE_USBOTG_HSULPI) to prevent bad settings in other + configurations. But giveh these facts, the preferred positive logic + now makes more sense (#ifdef BOARD_ENABLE_USBOTG_HSULPI) (2017-03-11). + * STM32: OTG host implementations of stm32_in_transfer() must obey the + polling interval for the case of isochronous and interrupt endpoints + (2017-03-12). + * Photon: Add basic support for wlan chip. From Simon Piriou + (2017-03-12). + * Networking: Add registration support for integrated ieee80211 + wireless drivers. Rename CONFIG_IEEE802154 to + CONFIG_WIRELESS_IEEE8021514 following the convention of including the + location of the configuration variable as a part of its name + (2017-03-12). + * If whence is SEEK_END, the file offset shall be set to the size of + the file plus offset. Noted by eunb.song@samsung.com (2017-03-13). + * Move IEEE 802.11 wireless IOCTLs from include/nuttx/net/ioctl to + include/nuttx/wireless/wireless.h. Add some Linux compatible + structures to use with the IOCTL commands. (2017-03-13). + * semaphore: sem_holder sem_findholder missing inintalization of + pholder. sem_findholder would fail and code optimization covered + this up. From David Sidrane (2017-03-13). + * Partial Fix priority inheritance CONFIG_SEM_PREALLOCHOLDERS=0. From + David Sidrane (2017-03-13). + * semaphore: sem_boostholderprio prevent overrun of pend_reprios. The + second case rtcb->sched_priority <= htcb->sched_priority did not + check if there is sufficient space in the pend_reprios array. From + David Sidrane (2017-03-13). + * Include C++ library to 'make export'. From Alan Carvalho de Assis + (2017-03-13). + * arch/arm/src/xmc4: Initial, partial support for Infineon XMC4xxx + (2017-03-14). + * photon: Porting wlan device. From Simon Piriou (2017-03-14). + * lp_worker: Guard from pend_reprios overlow. From David Sidrane + (2017-03-15). + * wireless/ieee802154: Renamed file ieee802154_device to + radio802154_device. From Anthony Merlino (2017-03-15). + * Add option to enable wireless debug output (2017-03-15). + * wireless/ieee802.15.4: Refactors ieee802154_dev character driver to + be radio802154_device. From Anthony Merlino (2017-03-15). + * Integrate use of new wireless debug macros. Replace ad hoc debug + macros. Convert obsolete dbg() macros to current info(), warn(), + err() macros (2017-03-15). + * sem_holder: Fixes improper restoration of base_priority in the case + of CONFIG_SEM_PREALLOCHOLDERS=0. The call to + sem_restorebaseprio_task context switches in the + sem_foreachholder(sem, sem_restoreholderprioB, stcb); call prior to + releasing the holder. So the running task is left as a holder as is + the started task. Leaving both slots filled thus failing to perform + the boost/or restoration on the correct tcb. This PR fixes this by + releasing the running task slot prior to reprioritization that can + lead to the context switch. To faclitate this, the interface to + sem_restorebaseprio needed to take the tcb from the holder prior to + the holder being freed. In the failure case where sched_verifytcb + fails it added the overhead of looking up the holder. There is also + the additional thunking on the foreach to get from holer to + holder->tcb. An alternate approach could be to leve the interface + the same and allocate a holder on the stack of sem_restoreholderprioB + copy the sem's holder to it, free it as is done in this pr and and + then pass that address sem_restoreholderprio as the holder. It could + then get the holder's tcb but we would keep the same sem_findholder + in sched_verifytcb. From David Sidrane (2017-03-15). + * ARM: Remove redundant interrupt stack coloring. From David + Cabecinhas (2017-03-16). + * ARM: Set EABI stack alignment for all ARM architectures (remove OABI + code). From David Cabecinhas (2017-03-16). + * Remove redundant interrupt stack coloring and OABI code. From David + Cabecinhas (2017-03-16). + * Fixed descritpions of NUC100/120. From no1wudi (2017-03-16). + * XMC4500 Relax: Add basic board support infrastructure of Infineon + XMC4500 Relax Lite v1 (2017-03-16). + * Fix mksyscall host binary name. From Alan Carvalho de Assis + (2017-03-16). + * sem_holder: The logic for the list version is unchanged. From David + Sidrane (2017-03-16). + * sem_holder: Fixes improper restoration of base_priority. From David + Sidrane (2017-03-17). + * C Library: printf: Fix precision for string formatting. Fixes use + of format precision to truncate input string. From Jussi Kivilinna + (2017-03-17). + * vsnprintf(): If size is zero, then vsnprintf() should return the + size of the required buffer without writing anything. This is same + fix that was done for snprintf in 2014 by commit + 59846a8fe928abb389e3776ebdbb52022da45be3. From Jussi Kivilinna + (2017-03-17). + * Adds driver support for the XBox One controller. Currently only the + latest version (XBox One X) controller works. The older XBox One + controllers do not enumerate correctly. From Brian Webb (2017-03-17). + * USB Host driver for the XBox One game controller. From Brian Webb + (2017-03-18). + * ARM: Fix off-by-one interrupt stack allocation in 8-byte aligned + architectures. From David Cabecinhas (2017-03-18). + * configs/nucleo_f334r8: Add ADC example. From Mateusz Szafoni + (2017-03-18). + * mtd/progmem: fix incorrect target address calculation. + progmem_read/write() is incorrectly calculating the target address, + expecting the offset argument is given in a block number. This is + completely wrong and as a result invalid flash region is accessed. + Byte-oriented read/write interfaces of mtd device accept the target + address in a byte offset, not a block number. From Heesub Shin + (2017-03-18). + * STM32F33: Move DMA logic to a separate files + add ADC support. From + Mateusz Szafoni (2017-03-18). + * Nucleo-F334R8: Add COMP support. From Mateusz Szafoni (2017-03-19). + * STM32F3: Add COMP support. From Mateusz Szafoni (2017-03-19). + * XMC4xxx/XMC4500 Relax: First, clean build of basic NSH configurtion + (2017-03-20). + * XMC4500-Relax: Add LED support (2017-03-20). + * input/mxt: Prevent overriding i2c transfer return value. + put_reg/get_reg function was overriding i2c transfer error code with + i2creset return value, that lead to OK status although actual + transfer failed. From Juha Niskanen (2017-03-21). + * drivers/audio/wm8904: WM8904 has same problem as that fixed by Juha + Niskanen in the MaxTouch driver (2017-03-21). + * drivers/lcd/st7565.c: Extend to include support for the AQM_1248A. + From Masayuki Ishikawa (2017-03-21). + * Fixed wrong assert on udp dgram send. From Pascal Speck (2017-03-21). + * sem_holder: Indexing error. From David Sidrane (2017-03-21). + + if (sem->holder[0].htcb != NULL || sem->holder[**1**].htcb != NULL) + * sched/semaphore: Convert strange use of DEBUGASSERT to DEBUGPANIC + (2017-03-21). + * sched/semaphore: Fix a warning aout an unused variable when priority + inheritance is enabled (2017-03-21). + * Clicker2-STM32: Add support for Mikroelektronika Clicker 2 for + STM32. From Anthony Merlino (2017-03-21). + * Implement DMA support for the stm32f4 I2C. Max and I have verified + that it works on our systems. From rg (2017-03-21). + * drivers/lcd/st7565.c: Use ST7565_POWERCTRL_INT instead of + ST7565_POWERCTRL_BRF. From Masayuki Ishikawa (2017-03-21). + * SMP Kconfig: Change the minimum SMP_NCPUS to 1. From Masayuki + Ishikawa (2017-03-xx). + * SMP: Setting CONFIG_SMP_NCPUS=1 should only be permitted in a debug + configuration (2017-03-22). + * Clicker2-STM32: Create src/, kernel/, and scripts/ directories + (2017-03-22). + * Clicker2-STM32: Add an NSH configuration (2017-03-22). + * Clicker2 STM32: Add SPI support (2017-03-22). + * XMC4xxx: Add FPU support. From David S. Alessio (2017-03-22). + * Clicker2-STM32: Add definitions for remaining mikroBUS pins + (2017-03-22). + * STM32: Fix erase sector number for microcontrolers with more than 11 + sectors. Erase a sector from the second bank cause the bit 4 of SNB + being set but never unsed, so trying to erase a sector from the first + bank was acually eraseing a sector from the second bank. From José + Roberto de Souza (2017-03-22). + * STM32: Make up_progmem thread safe. Writing to a flash sector while + starting the erase of other sector have a undefined behavior so lets + add a semaphore and syncronize access to Flash registers. But for + the semaphore to work it needs to be initialized so each board needs + call stm32_flash_initialize() on initialization, so to avoid runtime + problems it is only using semaphore and making it thread safe if + initialized, after all boards starts to call stm32_flash_initialize() + we can remove the boolean and the check. From José Roberto de Souza + (2017-03-22). + * STM32: Add workaround for flash data cache corruption on + read-while-write. This is a known hardware issue on some STM32 see + the errata of your model and if you make use of both memory banks you + should enable it. From José Roberto de Souza (2017-03-22). + * Clicker2-STM32: Add framework for MRF24J40 support. Untested and + still some missing logic (2017-03-22). + * STM32 Flash fixes. From José Roberto de Souza (2017-03-22). + * STM32F7: In stm32_allocateheap.c There are 5 not 4 configurations. + From David Sidrane (2017-03-23). + * Clicker2-STM32: Add logic to register the MRF24J40 radio character + device (2017-03-23). + * Clicker2-STM32: Add some mostly bogus MAC initializatinon logic + (2017-03-23). + * STM32 I2C: Do not allow CONFIG_I2C_POLLED and CONFIG_I2C_DMA. From + rg (2017-03-23). + * stm32_flash: Need conditinal on non F4 targets. From David Sidrane + (2017-03-23). + * stm32_i2c_alt: Duplicate non CS dev of regval. From David Sidrane + (2017-03-23). + * stm32f40xxx_i2c: Duplicate non CS dev of regval. From David Sidrane + (2017-03-23). + * stm32_i2c_alt: Move def of regval to top func def per CS. From + David Sidrane (2017-03-31). + * stm322_flash: Missing unlock on F1 HSI off path. From David Sidrane + (2017-03-24). + * Fix compile error when disabled the flash data cache corruption for + stm32 f1xx. From no1wudi (2017-03-24). + * The interrupt occurs over the counter overflow. From Aleksandr + Vyhovanec (2017-03-24). + * I needed to use DS3231, I remember that in past it worked ok, but now + for stm32f4xx is used another driver (chip + specific, stm32f40xxx_i2c.c) and DS3231 driver doesn't work. After + investigating a problem I found that I2C driver (isr routine) has a + few places there it sends stop bit even if not all messages are + managed. So, e.g., removing stm32_i2c_sendstop (#1744) and adding + stm32_i2c_sendstart after data reading helps to make DS3231 working. + From Alexander Oryshchenko; verified by David Sidrane (2017-03-24). + * wireless/ieee802154: Adds IOCTL definitions for accessing PHY + layer. From Anthony Merlino (2017-03-24). + * Add ffsl(), ffsll(), fls(), flsl(), flsll() and use GCC's + __builtin_ctz/__builtin_clz for faster implementation of these. From + Jussi Kivilinna (2017-03-24). + * MRF24J40/Clicker2: Add an MRF24J40 radio configuration to the + Clicker2 STM32 board. Fix a few errors discovered during build + (2017-03-24). + * configs/: Rename all stm32_wireless.c files to stm32_cc3000.c + (2017-03-24). + * configs/: Rename all xyz_wifi.c files to stm32_cc3000.c (2017-03-24). + * Clicker2-STM32: Add usbnsh configuration (2017-03-25). + * drivers/analog: Add basic COMP driver. From Mateusz Szafoni + (2017-03-25). + * STM32F33: Support for COMP character driver. From Mateusz Szafoni + (2017-03-25). + * Nucleo-F334R8: Use new COMP driver. From Mateusz Szafoni + (2017-03-25). + * stm32/Kconfig: Update COMP and OPAMP definitions. From Mateusz + Szafoni (2017-03-26). + * pthreads: Add more robustness characteristics: pthread_mutex_lock() + and trylock() will now return EOWNERDEAD if the mutex is locked by a + thread that no longer exists. Add pthread_mutex_consistent() to + recover from this situation (2017-03-26). + * pthread: Fix return value of pthread_give/takesemaphore(). Add + option to pthread_takesemaphore to ignore EINTR or not (2017-03-26). + * pthreads: Partial implementation of final part of robust mutexes: + Keep list of all mutexes held by a thread in a list in the TCB + (2017-03-26). + * when pthread exits or is cancelled, mutexes held by thread are marked + inconsistent and the highest priority thread waiting for the mutex is + awakened (2017-03-26). + * pthreads: Add a configuration option to disable robust mutexes and + revert to the traditional unsafe mutexes (2017-03-26). + * pthread mutexes: Add option to support both unsafe and robust + mutexes via pthread_mutexattr_get/setrobust() (2017-03-26). + * pthread mutexes: Finish logic to support configuration mutex + robustness (2017-03-27). + * Rename CONFIG_MUTEX_TYPES to CONFIG_PTHREAD_MUTEX_TYPES (2017-03-27). + * Make sure that CONFIG_PTHREAD_MUTEX_ROBUST=y is selected every + configuration that enabled pthreads (2017-03-27). + * Add syscall support for pthread_mutex_consistent() (2017-03-27). + * Include wcstold in C++ cwchar header file. From Alan Carvalho de + Assis (2017-03-27). + * AT86RF23x: Clean-up, standardize lower half interface. Take + advantage of new OS features for interrupt parameter passing + (2017-03-xx). + * MRF24J40: Take advantage of new OS features for interrupt parameter + passing (2017-03-27). + * lcd/: PCF8574 backpack logic needs to include poll.h + CONFIG_DISABLE_POLL is not set (2017-03-27). + * drivers/analog: Add driver for the LTC1767L ADC. From Martin + Lederhilger (2017-03-28). + * realloc(): When realloc() has to fall back to calling malloc(), size + including overhead was being provided to malloc(), causing a slightly + larger allocation than needed. Noted by initialkjc@yahoo.com + (2017-03-28). + * Fix PTHREAD_MUTEX_INITIALIZER which was not updated with last mutex + changes. From Jussi Kivilinna (2017-03-28). + * STM32 F7: Add stm32 RNG support. This is copied from stm32l4. + Tested on STM32F746ZG board. From Juha Niskanen (2017-03-29). + * STM32 RNG: Fix semaphore initial value and disable priority + inheritance. From Juha Niskanen (2017-03-29). + * Fix an assertion noted by Jussi Kivilinna. This was a consequence of + the recent robust mutex changes. If robust mutexes are selected, + then each mutex that a thread takes is retained in a list in threads + TCB. If the thread exits and that list is not empty, then we know + that the thread exitted while holding mutexes. And, in that case, + each will be marked as inconsistent and the any waiter for the thread + is awakened. For the case of pthread_mutex_trywait(), the mutex was + not being added to the list! while not usually a fatal error, this + was caught by an assertion when pthread_mutex_unlock() was called: + It tried to remove the mutex from the TCB list and it was not there + when, of course, it shoule be. The fix was to add + pthread_mutex_trytake() which does sem_trywait() and if successful, + does correctly add the mutext to the TCB list. This should + eliminated the assertion (2017-03-29). + * 6loWPAN: IEEE802.15.4 MAC driver will need a special form of the + network device structure to manage fragmentation of the large packet + into frames (2017-03-29). + * wireless/ieee802154: Adds MAC character driver structure. + Nonfunctional. From Anthony Merlino (2017-03-29). + * configs/clicker2-STM32: Adds logic to create an 802.15.4 MAC and + register a character driver. From Anthony Merlino (2017-03-29). + * net/local: connect: Fix warning with gcc-arm-none-eabi-5-2016q1. + Using compiler from gcc-arm-none-eabi-5-2016q1 toolchain: + + gcc version 5.3.1 20160307 (release) [ARM/embedded-5-branch revision 234589] (GNU Tools for ARM Embedded Processors) + + gives error: + + local/local_connect.c:188:7: error: '_local_semtake' is static but used in inline function 'local_stream_connect' which is not static [-Werror] + + this is due to compiler enforcing ISO/IEC 9899:1999 6.7.4.3: "An + inline definition of a function with external linkage shall not + contain a definition of a modifiable object with static storage + duration, and shall not contain a reference to an identifier with + internal linkage." Fix by making inlined caller to have internal + linkage as well. From Juha Niskanen (2017-03-30). + * Add entropy pool and strong random number generator. Entropy pool + gathers environmental noise from device drivers, user-space, etc., + and returns good random numbers, suitable for cryptographic use. + Based on entropy pool design from *BSDs and uses BLAKE2Xs algorithm + for CSPRNG output. Patch also adds /dev/urandom support for using + entropy pool RNG and new 'getrandom' system call for getting + randomness without file-descriptor usage (thus avoiding + file-descriptor exhaustion attacks). The 'getrandom' interface is + similar as 'getentropy' and 'getrandom' available on OpenBSD and + Linux respectively. From Jussi Kivilinna (2017-03-30). + * Change STM32 tickless to use only one timer. From Konstantin + Berezenko (2017-03-30). + * drivers/sensors: Add driver for ST HTS221 humidity sensor. From Juha + Niskanen (2017-03-30). + * HTS221 driver: Modify to use new interrupt parameter passing hooks + (2017-03-31). + * drivers/sensors: Add driver for ST LPS25H pressure sensor. From + Juha Niskanen (2017-03-31). + * drivers/usbmisc: Add driver for Fairchild FUSB301 USB type-C + controller. From Harri Luhtala . Tested + with earlier version of NuttX; with current version checked that it + compiles. Via Juha Niskane (2017-03-31). + * Add user-space networking stack API (usrsock). User-space networking + stack API allows user-space daemon to provide TCP/IP stack + implementation for NuttX network. Main use for this is to allow use + and seamless integration of HW-provided TCP/IP stacks to NuttX. For + example, user-space daemon can translate /dev/usrsock API requests to + HW TCP/IP API requests while rest of the user-space can access + standard socket API, with socket descriptors that can be used with + NuttX system calls. From Jussi Kivilinna (2017-03-31). + * STM32F7: add support for LSE RTC and enable RTC subseconds. From + Jussi Kivilinna (2017-03-31). + * TCP/IPv6: Fix a compile issue when IPv6, but not IPv4 is enabled + (2017-03-31). + * net/: Fix MULTINIC/MULTILINK selection when 6loWPAN selected + (2017-03-31). + * net/: Permit net/neighbor to build when IPv6 is defined, but not + Ethernet. Needs more work to support 6loWPAN (2017-03-31). + * stm32f7: Serial fix for dropped data: (1) Revert the inherited dma + bug from the stm32. see + https://bitbucket.org/nuttx/nuttx/commits/df9ae3c13fc2fff2c21ebdb098c520b11f43280d + + for details. And (2) Most all CR1-CR3 settings can not be configured + while UE is true. Threfore we make all operation atomic and disable + UE and restore it's originalstate on exit. From David Sidrane + (2017-03-31). + * stm32f7: stm32_sdmmc removed stray semicolon. From David Sidrane + (2017-03-31). + * 6loWPAN: Contiki 6loWPAN port is now complete (but completely + untested) (2017-04-02). + * iee802154 loopback: Eliminate dependency on CONFIG_NET_LOOPBACK + (2017-04-02). + * drivers/sensors: Add driver for ST LIS2DH accelerometer. From Timo + Voutilainen et al. via Juha Niskanen + (2017-04-03). + * net/socket/accept: Fix building with CONFIG_NET_LOCAL_STREAM. From + Jussi Kivilinna (2017-04-03). + * STM32: Fix IWDG and WWDG debug mode stop for STM32L15XX. From Juha + Niskanen (2017-04-03). + * STM32: Add STM32L162VE to chip.h. From Juha Niskanen (2017-04-03). + * iee802154 loopback: Eliminate dependency on CONFIG_NET_LOOPBACK + (2017-04-02). + * sim: Add a configuration for testing 6loWPAN (2017-04-03). + * wireless/ieee802154: Add initialization logic for loopback driver; + configs/sim: Add configuration for testing 6loWPAN; net/sixlowpan: + Fix for compilation with debug output enabled (2017-04-03). + * 6loWPAN: Updates/fixes from initial testing with the IEEE802.15.4 + loopback driver (2017-04-03). + * STM32: Add I2C3 SDA pin mapping for STM32F411. From no1wudi + (2017-04-04). + * sensors: lis2dh: fix hardfault when reading from unconfigured + sensor. From Juha Niskanen (2017-04-04). + * STM32: stm32_flash: add EEPROM writing for STM32L15XX. From Juha + Niskanen (2017-04-04). + * 6loWPAN: Add option to dump buffers (2017-04-04). + * STM32: stm32l15xx_rcc: add support for using MSI as system clock. + From Juha Niskanen (2017-04-05). + * STM32: stm32l15xxx_rcc: configure medium performance voltage range + and zero wait-state when allowed by SYSCLK setting. Zero wait-state + for flash can be configured when: (1) Range 1 and SYSCLK <= 16 Mhz, + (2) Range 2 and SYSCLK <= 8 Mhz, or (3) Range 3 and SYSCLK <= 4.2 + Mhz. Medium performance voltage range (1.5V) can be configured when + SYSCLK is up to 16 Mhz and PLLVCO up to 48 Mhz. From Juha Niskanen + (2017-04-05). + * wireless/ieee802154: Initial MAC char driver write functionality. + From Anthony Merlino (2017-04-05). + * photon: wlan support. From Simon Piriou (2017-04-03). + * Document set [{+|-}{e|x|xe|ex}] [ ]. From David Sidrane + (2017-04-05). + * STM32: Fix SYSCFG_CFGR1_I2C_PBXFMP_SHIFT value. From Alan Carvalho + de Assis (2017-04-06). + * STM32F7: Serial: add interface to get uart_dev_t by USART number, + stm32_serial_get_uart. From Jussi Kivilinna (2017-04-06). + * STM32F7: Default CONFIG_STM32F7_DMACAPABLE to 'n'. STM32F7 does not + have CCM RAM but DTCM, so this option does not need to enabled. DTCM + RAM is DMA-able through CPU AHBS bus. From Jussi Kivilinna + (2017-04-06). + * STM32F7: Fix UART7 and UART8 IFLOWCONTROL options. From Jussi + Kivilinna (2017-04-06). + * STM32F7: add warning for RXDMA + IFLOWCONTROL combination. + Combination of RXDMA + IFLOWCONTROL does not work as one might + expect. Since RXDMA uses circular DMA-buffer, DMA will always keep + reading new data from USART peripheral even if DMA buffer underruns. + Thus this combination only does following: RTS is asserted on USART + setup and deasserted on shutdown and does not perform actual RTS + flow-control. Data loss can be demonstrated by doing long up_mdelay + inside irq critical section and feeding data to RXDMA+IFLOWCONTROL + UART. From Jussi Kivilinna (2017-04-06). + * sim/sixlowpan: Now supports apps/examples/udpblaster too (2017-04-06). + * SAMV7: Watchdog: fix Forbidden Window Value. According the Datasheet + the WDD Value is the lower bound of a so called Forbidden Window and + to disable this we have to set the WDD Value greater than or equal to + the WDV Value. This seems to be a bug in the datasheet. It looks + like we have to set it to a greater value than the WDV to really + disable this Thing. When triggering the Watchdog faster than the + (very slow) clock source of the Watchdog fires, this Forbidden Window + Feature resets the System if WDD equals to WDV. This Changeset + disables the Forbidden Window by setting the WDD Value to the Maximum + (0xfff) Value possible. From Frank Benkert (2017-04-06). + * RTC: add interface for check if RTC time has been set. New interface + allows checking if RTC time has been set. This allows to application + to detect if RTC has valid time (after reset) or should application + attempt to get real time by other means (for example, by launching + ntpclient or GPS). From Jussi Kivilinna (2017-04-06). + * 6loWPAN: Add network IOCTL support to set the node address + (2017-04-06). + * EFM32 I2C: Fix timeout calculation. From Masayuki Ishikawa + (2017-04-06). + * Disable serial console on stm32f103-minimum usbnsh example project + config. Devices enumerate after this change. From Bob Ryan + (2017-04-07). + * pthreads: Adding rwlock implementation. Adding an implementation for + read/write locks into the pthread library. These locks are writer + priority, such that if any writers come in they are given priority + for writing. From Mark Schulte (2017-04-07). + * pthread rwlock bugfixes. From Mark Schulte (2017-04-07). + * 6loWPAN: Add calculation of TCP header size. It is not a constant + (2017-04-07). + * Restore TCP_HDRLEN to MSS calculation. Also add to UDP MSS + calculation where it never appearred. Add some missing MSS and + RDVWNDO definitions for 6loWOPAN (2017-04-08). + * pthread.h: Remove duplicate, possible erroneous definition of + PTHREAD_MUTEX_INITIALIZER that crept in with some recent changes + (2017-04-08). + * pthread.h: Fix rwlock initializer. From Mark Schulte (2017-04-08). + * Add configuration/build support for an IEEE802.15.4 network device + (2017-04-08). + * Fix some old-style interrupt handling logic in drivers/net/skeleton.c + (2017-04-08). + * wireless/ieee802154: Add a implementation of the IEEE802.15.4 + network driver. This is very incomplete on the initial commit + (2017-04-08). + * Buttons: Change return value of board_buttons() and the type of + btn_buttonset_t to uint32_t so that more than 8 buttons can be + supported (2017-04-09). + * Add support for NuttX controlled LEDS and for board_initialize. + Separate initialization logic to stm32_bringup.c so that in + initialization can occur either through board_initialize() or through + board_app_initialize(). Same as with most other newer board + configurations (2017-04-09). + * net procfs: Some long lines were being generated that cause + buffer-related problems and corrupted output (2017-04-09). + * stm32 COMP: Logic in stm32_comp.h must be configured on + CONFIG_STM32_COMP or otherwise it causes an error via #error on every + platform without COMP support (2017-04-09). + * Photon: Add logic to automatically mount the procfs file system on + startup. Fix some LED-related configuration conflicts (2017-04-09). + * Buttons: Correct some comments left after last button-related + change: 32- vs 8-bit bit set (2017-04-09). + * pthread: Use cancel cleanup handlers in rwlock. From Juha Niskanen + (2017-04-10). + * STM32F7: serial: disallow broken configuration combination of + CONFIG_STM32F7_FLOWCONTROL_BROKEN=y and + CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS not set. From Jussi Kivilinna + (2017-04-11). + * STM32F7: serial: do not stop processing input in SW flow-control + mode. From Jussi Kivilinna (2017-04-11). + * STM32XX: Fix Pending Register definition. From Alan Carvalho de + Assis (2017-04-11). + * Add logic to disable cancellation points within the OS. This is + useful when an internal OS function that is NOT a cancellation point + calls an OS function which is a cancellation point. In that case, + irrecoverable states may occur if the cancellation is within the OS. + From Juha Niskanen (2017-04-11). + * Fix LLVM libc++ undefined reference to __cxa_guard_*. From Alan + Carvalho de Assis (2017-04-11). + * libc/netdb: in dns_query_callback, ret != -EADDRNOTAVAIL condition + consumes error returns including EAGAIN in this case, dns query + retransmission doesn't work. From Ritajina (2017-04-12). + * STM32L4 DMA: Correct bad channel definition. From Sebastien Lorquet + (2017-04-12). + * TUN driver: Implement TAP (OSI layer 2) mode. Enable by setting the + IFF_TAP flag instead of the IFF_TUN flag in ifr_flags. From Thomas + Keh (2017-04-13). + * Adds USB host support to stm32f411-disco board. From Brian Webb + (2017-04-13). + * ieee802.15.4 radio: Add data structure definitions for Radio IOCTLs + (2017-04-13). + * ieee802.15.4 MAC: Add data structure definitions for MAC IOCTLs + (2017-04-13). + * ieee802154 radio: Implement IOCTL decode and dispatch in all radio + drivers (2017-04-13). + * drivers/net/skeleton.c: Add support for IOCTL handling (2017-04-13). + * ieee802.15.4 netdev: Add IOCTL support (2017-04-13). + * ieee802.15.4 radio: Remove interface methods that duplicate IOCTL + commands (2017-04-13). + * ieee802.15.4: de-couple MAC driver interface. Now works more like + other drivers (2017-04-13). + * sched: Fix tg_flags check with GROUP_FLAG_NOCLDWAIT. From Masayuki + Ishikawa (2017-04-14). + * Add basic support for STM32F0. From Alan Carvalho de Assis + (2017-04-14). + * Add stm32f0discovery board support. From Alan Carvalho de Assis + (2017-04-14). + * arch/arm/Kconfig: Add option for STM32F0 (2017-04-14). + * IEEE802.15.4: There is only one instance of the IEEE802.15.4 MAC + lower level. There is no need for the interface to be indirect via a + vtable. In this case, standard global functions should be used + (2017-04-14). + * ieee802.15.4: New global functions exported by the lower MAC layer + should be private to the MAC module. Function prototypes moved from + include/nuttx/wireless/ieee802154/ieee802154_mac.h to + wireless/ieee802154/mac802154.h (2017-04-14). + * radio802154_device.c now accesses the PHY layer via the IOCTL helper + functions (2017-04-14). + * photon: add sdpcm + thread support for wlan. From Simon Piriou + (2017-04-13). + * Not a clean fix, but at least makes DHCP working with + CONFIG_NETDEV_MULTINIC. From Andreas Bihlmaier (2017-04-15). + * networking: IPv4 change of last PR should also be applied to + corresponding IPv6 logic (2017-04-15). + * 6loWPAN: Add some checks for the case where there are multiple + network devices and multiple link layer protocols (2017-04-15). + * net/: Add IOCTL support for forwarding IEEE802.15.4 MAC and PHY + IOCTLs (2017-04-15). + * Argument of network device IOCTL should be unsigned long, just as + will all other IOCTL methods (2017-04-15). + * wireless/ieee802154: Adds ability to receive notifications from MAC + char driver. From Anthony Merlino (2017-04-05). + * wireless/ieee802154/mrf24j40: Added bind method. From Anthony + Merlino (2017-04-15). + * wireless/ieee802154: Starts adding MAC request data functionality. + From Anthony Merlino (2017-04-15). + * wireless/ieee802154: Starts defining interface between PHY layer and + next highest layer. From Anthony Merlino (2017-04-15). + * wireless/ieee802154: Skeleton code for request associate. From + Anthony Merlino (2017-04-15). + * wireless/ieee802154: Bind MAC phyif to radio. From Anthony Merlino + (2017-04-15). + * STM32: Provide TIM5 definition for STM32F429. From Matias v01d + (2017-04-15). + * photon: Add sdpcm tx basic support. From Simon Piriou (2017-04-16). + * photon: Request firmware version and MAC address. From Simon Piriou + (2017-04-16). + * 6loWPAN network driver: Still only a skeleton but has some added + thought experimentation (2017-04-16). + * 6loWPAN: Correct ordering of headers. fragmentation header was + coming out before FCF (2017-04-16). + * wireless/ieee802154: Continues development on transmit structure. + From Anthony Merlino (2017-04-17). + * STM32F0: Enable the clock for all GPIO ports. From Alan Carvalho de + Assis (2017-04-17). + * STM32F0: Fix HSI clock definition. From Alan Carvalho de Assis + (2017-04-17). + * STM32F0: Fix System Clock value to 48MHz and remove MCLK + definition. From Alan Carvalho de Assis (2017-04-17). + * Update coding standard document to discuss un-named structure fields + (2017-04-17). + * STM32F0: Add basic support for STM32F07x family (2017-04-17). + * STM32F0: Move enabling of GPIO peripherals form UART setup to + clockconfig. This is not a UART function. It is needed by all + peripherals (2017-04-xx). + * STM32F0: Add logic to enable other USARTs. No UART4/5. Rather + USART4/5 (2017-04-17). + * STM32F7: Warn if no DMA2 configured when using ADC with DMA. Also + correct ADC channel numbers that DMA callback passes to upper half + driver. From Juha Niskanen (2017-04-18). + * STM32F7: stm32_adc: Do not override ADCPRE_DIV when measuring + internal voltage. From Juha Niskanen (2017-04-18). + * Move CONFIG_ADC_NO_START_CONV from drivers/adc/Kconfig to + arch/arm/src/stm32[f7]/Kconfig as STM32[F7]_ADC_NO_START_CONV. + Refresh all configurations with any reference to + CONFIG_ADC_NO_START_CONV (2017-04-18). + * STM32F0: The STM32F2 does not have use alternate function groupings + as does the F1. Rather, it is like other members of the STM32 family + with An alternate setting AF0-AF7 for each pin (2017-04-18). + * Nucleo-F072RB: Add board configuration (2017-04-18). + * wireless/ieee802154: Lots of small fixes to eliminate build issues. + Generally cleans things up and fixes lots of small issues preventing a + successful build. Does not completely build, but there are + significantly less errors. From Anthony Merlino (2017-04-18). + * Coding standard: Defining structures within the scope of another + structure is discouraged (2017-04-18). + * Nucleo-F072RB: Enable board_app_inititalize, procfs, and built-in + functions (2017-04-19). + * wireless/ieee802154: Simplifies MAC callback interface. Adds + missing data type definitions. From Anthony Merlino (2017-04-19). + * wireless/ieee802154: Renames mac802154_devwrapper_s to + mac802154_chardevice_s. From Anthony Merlino (2017-04-19). + * wireless/ieee802154: Changes radio interface to match MAC callback + design. From Anthony Merlino (2017-04-19). + * 6loWPAN: Fix a missing source address in header. Correct + calculation of payload size (2017-04-19). + * SAMV7 EMAC: Add conditional logic to account the fact that the + SAMV71 has 6 rather than 3 queues after version 1. From Ian McAfee + (2017-04-19). + * wireless/ieee802154: Starts structuring transmission completion + handling. From Anthony Merlino (2017-04-19). + * 6loWPAN: Add an IOCTL to set the IEEE802.15.4 PAN ID (2017-04-19). + * STM32 L1: stm32l15xx_rcc: Allow board to configure HSE clock in + bypass-mode. Allows using MCO output from ST-link chip (on Nucleo + and Discovery boards) as HSE input. From Juha Niskanen (2017-04-20). + * Add support for STM32L152CC, STM32L152RC and STM32L152VC. Update + some bits and comments for other STM32L1 parts in chip.h. From Juha + Niskanen (2017-04-20). + * UART 16550: Missing left parenthesis in function prototype. This is + Bitbucket Issue #41 (2017-04-20). + * procfs: Fix wrong member IDs are displayed when 'cat + /proc//group/status'. From Nobutaka Toyoshima (2017-04-28). + * STM32F0: Add support for HSI48 (2017-04-20). + * STM32F0: Add an untested port of the F1 USB device to the STM32F0 + (2017-04-20). + * Move include/nuttx/net/iob.h to include/drivers/iob.h; rename + CONFIG_NET_IOB to CONFIG_DRIVERS_IOB (2017-04-20). + * Move net/iob to drivers/iob so that the I/O buffering feature can be + available to other drivers when networking is disabled (2017-04-20). + * VFS poll(): Add some error handling logic (2017-04-20). + * Add support for the STM32F09X family. From Juha Niskanen (2017-04-21). + * clock: Add clock_resynchronize and use subseconds RTC. Add + clock_resynchronize for better synchronization of CLOCK_REALTIME and + CLOCK_MONOTONIC to match RTC after resume from low-power state. Add + up_rtc_getdatetime_with_subseconds under + CONFIG_ARCH_HAVE_RTC_SUBSECONDS to allow initializing (and + resynchronizing) system clock with subseconds accuracy RTC. From + Jussi Kivilinna (2017-04-21). + * clock: Add new type ssystime_t for relative 64-bit ticks, change + ticks<->time conversion functions to use ssystime_t. From Jussi + Kivilinna (2017-04-21). + * clock: add testing for 32-bit overflow of 64-bit system timer. From + Jussi Kivilinna (2017-04-21). + * wireless/ieee802154: Simplifies TX completion interface. Documents + and cleans up some functions. From Anthony Merlino (2017-04-21). + * Remove the 6loWPAN PANID IOCTLs they are redundant (2017-04-21). + * 6loWPAN: Remove the PAN ID from the 6loWPAN data structure. This is + owned by the radio driver. Rather, use an IOCTL to obtain the PAN ID + from the downstream radio driver (2017-04-21). + * photon: Add basic wlan scan function. From Simon Piriou (2017-04-22). + * 6loWPAN: Separate MAC-related definitions from sixlowpan.h. Put in + ieee802154.h (2017-04-22). + * net/: network drver now retains Ethernet MAC address in a union so + that other link layer addresses may be used in a MULTILINK + environment (2017-04-22). + * 6loWPAN: Add IEEE802.15.4 Rime address to union of link layer + addresses in the network driver (2017-04-22). + * SAM3/4: Fixed configurations for TWI master. Obviously an + incomplete port from SAMA5 (2017-04-23). + * SAM3/4: Remove inappropriate semicolon. From kc_dtm (2017-04-23). + * configs/photon: Add DOWNLOAD function to upload firmware through + DFU. From Simon Piriou (2017-04-23). + * drivers/ieee80211/: Change all occurrences of _info, _warn, and _err + to wlinfo, wlwarn, and wlerr (2017-04-23). + * USBMSC: Fix a wrong lun number issue. From Masayuki Ishikawa + (2017-04-24). + * sched: Fix CHILD_FLAG_EXITED in include/nuttx/sched.h. From + Masayuki Ishikawa (2017-04-24). + * wireless/ieee80211: Add skeleton for a broadcom network driver + (2017-04-24). + * wiress/ieee80211: Broadcom network driver needs to register as an + ieee802.11 driver, not an Ethernet driver (2017-04-24). + * wireless/ieee80211: Add broadcom network device registration logic + (2017-04-24). + * drivers/wireless/bcmf: Register network driver + update defconfig + file. From Simon Piriou (2017-04-24). + * procfs: Fix incorrect uptime with CONFIG_SYSTEM_TIME64. From + Masayuki Ishikawa (2017-04-25). + * configs/photon/wlan: Minor config changes to get a clean build + (2017-04-25). + * STM32L4: Add support for the STM32L496XX family. From Juha Niskanen + (2017-04-25). + * configs/photon: Rename ld.script to photon_jtag.ld for symmetry + (2017-04-25). + * configs/photon/src/stm32_wlan.c: Remove unused, inappropriate + network driver registration (2017-04-25). + * netdev_register: If there is only one ieee80211 and both + CONFIG_ETHERNET and CONFIG_DRIVERS_IEEE8011, then use the wlan0 + naming, not the eth0 naming (2017-04-25). + * configs/nucle-f072rb/nsh: Correct amount of available SRAM in + defconfig (2017-04-26). + * CONFIG_DEBUG_HARDFAULT should be available for Cortex-M0 too + (2017-04-26). + * drivers/wireless/bcmf: Enable DMA for SDIO transfers. From Simon + Piriou (2017-04-26). + * configs: Remove all setenv.bat files. Remove all references to + setenv.sh and setenv.bat from all config README files (2017-04-26). + * drivers/syslog: Use monotonic clock for timestamp when available. + From Jussi Kivilinna (2017-04-26). + * Enable wireless IOCTL commands in photon/wlan configuration + (2017-04-26). + * Network IOCTLs: Correct a compilation error when wireless IOCTLs are + enabled (2017-04-26). + * binfmt/elf: Fix offset value when calling elf_read() in + elf_symname(). From Masayuki Ishikawa (2017-04-26). + * STM32, STM32F7, STM32L4: Remove incorrect comment about STM32L1 + LSE/RTC/LCD. From Juha Niskanen (2017-04-27). + * STM32L4: Add some defines for the new peripherals in STM32L496 + parts. From Juha Niskanen (2017-04-27). + * STM32F0: Fix some missing settings in the clock configuration logic + (2017-04-27). + * IOCTLS. Separate wireless character driver IOCTL commands from + wireless network driver IOCTL commands. Move from wireless.h to + ioctl.h (2017-04-27). + * IEEE 802.15.4: Move MAC character driver IOCTL commands from + ieee802154_mac.h to ieee802154_ioctl.h (2017-04-27). + * Wireless IOCTLs: Correct use of _WLIOC where _WLCIOC is required + (2017-04-27). + * net/socket: Fix cloning of local and raw sockets. From Jussi + Kivilinna (2017-04-28). + * STM32L4: stm32l4_i2c: add I2C4 code. From Juha Niskanen (2017-04-28). + * STM32L4: I2C was not using current interrupt handling parameter + passing logic (2017-04-28). + * vfs/poll: round timeout up to next full tick. Calling poll() with + timeout less than half tick (thus MSEC2TICK(timeout) => 0) caused + returning error with EAGAIN. Instead of rounding timeout down, value + should be rounded up. Open Group spec for poll says: + "Implementations may place limitations on the granularity of timeout + intervals. If the requested timeout interval requires a finer + granularity than the implementation supports, the actual timeout + interval will be rounded up to the next supported value." From Jussi + Kivilinna (2017-04-28). + * In last change to poll(), converted timeout to unsigned to eliminate + the possibility of overflow of signed overflow (2017-04-28). + * drivers/wireless/bcmf: Add escan ioctls support + cleanup. From + Simon Piriou (2017-04-28). + * Add all network IOCTLs to include/sys/ioctl.h (2017-04-28). + * Add all ieee802.15.4 IOCTLs to include/sys/ioctl.h (2017-04-28). + * 6loWPAN: Can't reuse same header on each fragment. DSN needs to + increment (2017-04-29). + * SPI: Add an instance argument to the SPIDEV definitions (2017-04-29). + * STM32F0: Add some protection. There is only one interrupt for + USART3-8. Current interrupt handling logic will support only one + interrupt in that range (2017-04-29). + * STM32F0 I2C: Initial cut at driver. Still a work in progress. From + Alan Carvalho de Assis (2017-04-29). + * STM32F33: Add OPAMP support. From Mateusz Szafoni (2017-04-30). + * drivers/analog: Add basic OPAMP driver. From Mateusz Szafoni + (2017-04-30). + * Nucleo-F334R8: Add OPAMP support. From Mateusz Szafoni (2017-04-30). + * Nucleo-F072RB: Add support for the I2C driver used by I2C tools + (2017-04-20). + * drivers/i2c: Fix compile issus if CONFIG_DISABLE_PSEUDOFS_OPERATIONS + is enabled (2017-04-xx). + * STM32F0 I2C: Update driver to use the standard interrupt parameter + passing logic (2017-04-30). + * STM32F0 I2C: Pin definitions should specify open drain (and probably + 50Mhz) (2017-04-30). + * EFM32, STM32, and STM32 F7 I2C: Update to use the standard parameter + passing to interrupt handlers (2017-04-30). + * drivers/wireless/bcmf: Add netdev support for Broadcom FullMAC + driver. From Simon Piriou (2017-04-30). + * Tiva I2C: Update to use the standard parameter passing to interrupt + handlers (2017-04-30). + * ieee802.11: Bring some BSD licensed header files in from FreeBSD + (2017-04-30). + * Clicker2-STM32: Add protected build knsh configuration (2017-05-01). + * STM32F0: Fix I2C frequency table. From Alan Carvalho de Assis + (2017-05-01). + * STM32F0: I2C frequency quantization. Add logic to get closer if an + oddball frequency is used (2017-05-01). + * pthread: Fix compilation error on pthread_cond_wait when + CONFIG_CANCELLATION_POINTS and CONFIG_PTHREAD_MUTEX_UNSAFE are + enabled. From EunBong Song (2017-05-02). + * binfmt/elf: Fix offset value when calling elf_read() in + elf_sectname(). From Masayuki Ishikawa (2017-05-02). + * configs: Add nucleo-l496zg board files. From Juha Niskanen + (2017-05-02). + * configs: Add nucleo-f091rc board files. From Juha Niskanen + (2017-05-02). + * STM32L4: Don't think these chips have DPFPU, DTCM or ITCM. From + Juha Niskanen (2017-05-02). + * STM32L4: Add GPIO_PORTI definition. From Juha Niskanen (2017-05-02). + * STM32L4: Delete more references to DFPU, ITCM, and DTCM (2017-05-02). + * wireless/ieee802154: Changes transmit data path to use IOBs and + exposes function for getting size of MAC header. From Anthony + Merlino (2017-05-02). + * Extend wireless.h with definitions needed by wext. From Simon Piriou + (2017-05-02). + * drivers/wireless/bcmf: implement basic wext interface for + authentication. From Simon Piriou (2017-05-02). + * First attempt at a nucleo-l432kc board. From Sebastien Lorquet + (2017-05-02). + * STM32F7: Flash: macro naming errors, there is no FLASH_CONFIG_F for + F7. From Juha Niskanen (2017-05-02). + * STM32L4: stm32l4x6xx_pinmap: Update I2C4 and DCMI pins. From Juha + Niskanen (2017-05-02). + * 6loWPAN: Add basic call path to interface with the MAC layer through + the MAC network driver. Logic has not yet been implemented. This is + just a structural change in preparation for additional changes + (2017-05-02). + * wireless/ieee802154: Sets up default PIB attributes. From Anthony + Merlino (2017-05-02). + * wireless/ieee802154: Finishes some IOCTL logic for MAC layer. From + Anthony Merlino (2017-05-02). + * 6loWPAN: Changes to use new MAC interfaces. Incomplete and needs + some clean-up of dangling, unused definitions (2017-05-03). + * wireless/ieee802154: Starts work on setting PIB attributes. From + Anthony Merlino (2017-05-03). + * 6loWPAN: Fixes hang in loopback test (2017-05-03). + * drivers/wireless/bcmf: Fix frame not freed when dropped + cleanup. + From Simon Piriou (2017-05-03). + * STM32L4: stm32l4_i2c: change wrong macro to CONFIG_I2C_POLLED. From + Juha Niskanen (2017-05-04). + * STM32L4: modularize Kconfig to support different product + lines/families. This is modeled after STM32F7. Idea is to declare + each chip in Kconfig but allow for flash size override. Commit adds + many STM32L4_HAVE_XXX feature test macros. From Juha Niskanen + (2017-05-02). + * STM32L4: Changes needed for STM32L452 and Nucleo-L452RE board. GPIO + and UART seem similar across STMicro product matrix, so renamed files + accordingly. RCC is cloned just in case, while conflicting + differences there seem to be very minor. From Juha Niskanen + (2017-05-02). + * STM32L4: Flash: update override config macros and add + FLASH_CONFIG_B. From Juha Niskanen (2017-05-02). + * configs: Add nucleo-l452re board files. From Juha Niskanen + (2017-05-04). + * fixedmath: Add square root and b32_t conversion operators. From + Jussi Kivilinna (2017-05-04). + * Fix STM32F7 I2C interrupt handler. From Jussi Kivilinna (2017-05-04). + * STM32F7 serial: Allow configuring Rx DMA buffer size. From Jussi + Kivilinna (2017-05-04). + * 6loWPAN: Replace Rime address naming with more consistent + short/exended address terminology (2017-05-04). + * 6loWPAN: Remove all ieee802.15.4 MAC knowledge from 6loWPAN. Now + relies on wires/ieee802154 for all MAC-related operations (2017-05-04). + * STM32L4: stm32l4_i2c: change wrong macro to CONFIG_I2C_POLLED. From + Juha Niskanen (2017-05-04). + * 6loWPAN: Local address length is fixed by the configuration. The + remote address be with short or extended (2017-05-04). + * STM32L4: Separate SYSCFG into product line specific files for + clarity. From Juha Niskanen (2017-05-05). + * STM32L4: firewall for stm32l4x3xx. Not tested for any product + family, but now it at least compiles. L496 devices can have one bit + wider Volatile Data Segment. From Juha Niskanen (2017-05-05). + * STM32L4: Add more chips to Kconfig. This also removes + DPFPU/DTCM/ITCM features again, fixing a recent git history hickup. + From Juha Niskanen (2017-05-05). + * configs/nucleo-l496zg: Kconfig was copied from nucleo-144. Removed + as most options have not been tested. From Juha Niskanen (2017-05-05). + * nucleo-144: Default for choice in Kconfig was not one of the + possible choices (2017-05-05). + * Kinetis: Add TPM to K66 chip. From David Sidrane (2017-05-05). + * Kinetis: Fixed CLKSRC Bit Names. From David Sidrane (2017-05-05). + * Kinetis: Add OSC_DIV to the kinetis_osc header. From David Sidrane + (2017-05-05). + * Kinetis: Use optional BOARD_OSC_CR and BOARD_OSC_DIV in clock + configuration. From David Sidrane (2017-05-05). + * Kinetis: Added HW flow control and termios. From David Sidrane + (2017-05-05). + * wireless/ieee802154: Changes rxenable at radio layer. From Anthony + Merlino (2017-05-03). + * wireless/ieee802154: Finishes promiscuous mode IOCTL. From Anthony + Merlino (2017-05-03). + * wireless/ieee802154: Removes radio IOCTL. Starts bringing radio and + MAC closer with well-defined interface. From Anthony Merlino + (2017-05-05). + * STM32L4: add support for many new MCUs from STM32L4X3XX product line + and Nucleo-L452 board. From Juha Niskanen (2017-05-05). + * 6loWPAN: Use information in struct ieee802154_data_ind_s when + reassembling a packet (2017-05-05). + * ieee 802.15.4: Add a pool-based memory allocator for RX frame + meta-data (2017-05-05). + * kinetis k66, k64, k60, k40, k20: Pin mux configure all I2C signals as + Open Drain. The output structure of the GPIO for I2C needs to be + open drain. When left at the default, one can observe on a scope the + slave contending with the push-pull during the ACK. From David + Sidrane (2017-05-05). + * wireless/ieee802154: Removes msdu_length from meta-data since it is + intrinsically in the IOB. From Anthony Merlino (2017-05-06). + * wireless/ieee802154: Reworks data_ind allocation to include IOB + allocation/deallocation. Hides private data. From Anthony Merlino + (2017-05-05). + * wireless/ieee802154: Completes Rx data flow through MAC layer to + callback. From Anthony Merlino (2017-05-06). + * Kinetis: Add ARCH_HAVE_I2CRESET. From David Sidrane (2017-05-06). + * Reworks data_ind allocation to include IOB allocation/deallocation. + Hides private data. From Anthony Merlino (2017-05-06). + * STM32: Serial Allow configuring Rx DMA buffer size. From David + Sidrane (2017-05-06). + * 6loWPAN: Minor cleanup and re-verification of all compression modes + after so many recent changes (2017-05-06). + * Update the C coding standard document (2017-05-06). + * IEEE 802.15.4 network driver. Remove support for multicast address + filtering; doesn't work that way on an IEEE 802.15.4 network + (2017-05-08). + * STM32: Serial DMA buffer round off not up. From David Sidrane + (2017-05-08). + * STM32 TIM: Add method to get timer width. Freerun timer: Use timer + width to get the correct clock rollover point (2017-05-08). + * wireless/ieee802154: Finishes MAC processing of received data frame. + From Anthony Merlino (2017-05-08). + * wireless/ieee802154: Finishes MAC char driver read functionality. + From Anthony Merlino (2017-05-08). + * wireless/ieee802154: MRF24J40: Finishes receive functionality, + supports promicuous mode, and rxonidle attributes. From Anthony + Merlino (2017-05-08). + * wireless/ieee802154: Completes basic receive functionality. From + Anthony Merlino (2017-05-08). + * STM32: Serial DMA buffer round off not up. From David Sidrane + (2017-05-08). + * Final fixes to get the nucleo-l432kc config build. Execution not + tested yet. From Sebastien Lorquet (2017-05-09). + * Adapt stm32l43x pin definitions. From Sebastien Lorquet (2017-05-09). + * More unbuilt stm32 -> stm32l4 changes. From Sebastien Lorquet + (2017-05-09). + * Restore settings for UARTs 4 and 5. From Sebastien Lorquet + (2017-05-09). + * IOBs: Move from driver/iob to a better location in mm/iob + (2017-05-09). + * STM32L4: add dbgmcu header files. From Juha Niskanen (2017-05-09). + * wireless/ieee802154: Fixes missing handle of read/write being able to + be interrupted. From Anthony Merlino (2017-05-09). + * wireless/ieee802154: Starts implementing START.request primitive. + From Anthony Merlino (2017-05-09). + * drivers/serial: I discovered a problem in the file + drivers/serial/serial.c concerning the function uart_close(…). In the + case that a serial device is opened with the flag O_NONBLOCK the + function uart_close(…) blocks until all data in the buffer is + transmitted. The function close(…) called on an handle opened with + O_NONBLOCK should not block. The problem occurred with a CDC/ACM + device. From Stefan Kolb (2017-05-10). + * mtd/config: erase block between block read and write. From Juha + Niskanen (2017-05-10). + * Moved LIS3DSH from the I2C-dependent block to the SPI-block to make + Make.defs consistent with the driver (SPI only) and + drivers/sensors/Kconfig. From Floxx (2017-05-10). + * syslog: Add option to buffer SYSLOG output to avoid interleaving + (2017-05-10). + * syslog buffering: Use IOBs to buffer data, not an on-stack buffer + (2017-05-10). + * STM32L4: add internal flash write support. From Juha Niskanen + (2017-05-11). + * When syslog message has addition characters after last new-line. With + buffering those now get lost as vsyslog does not flush output after + lib_sprintf. Additional trailing characters could be ANSI escape + sequence to reset state that message setups. For example, macro here + uses colors and resets state after actual message (including '\n'): + With flushing added to vsyslog, then there is problem that next + syslog line might come from other task before reset sequence, causing + wrong line getting color. This could be avoided by not flushing on + '\n' but only if IOB is full and/or at end of vsyslog. Would this + make sense?. From Jussi Kivilinna (2017-05-11). + * Syslog: Need inclusion of errno.h for fix building with + CONFIG_SYSLOG_TIMESTMAP=y (2017-05-11). + * mtd: Build RAMTRON and AT45DB drivers only if selected. From Juha + Niskanen (2017-05-11). + * mtd/config: Fix byte read interface test. From Juha Niskanen + (2017-05-11). + * mtd: Fix some unallocated and NULL pointer issues. rwb->wrflush and + rwb->wrmaxblocks in rwbuffer could get unallocated values from + ftl_initialize() in some configurations. Also fixes related assert: + + up_assert: Assertion failed at file:rwbuffer.c line: 643 + + that can happen with the following configuration: + + CONFIG_FTL_WRITEBUFFER=y + CONFIG_DRVR_WRITEBUFFER=y + # CONFIG_FS_WRITABLE is not set + + These problems are caused by CONFIG variable differences between the + buffer layers. TODO: This is not a perfect solution. readahead + support has similar issues. From Juha Niskanen (2017-05-11). + * STM32L4: port stm32l4_serial_get_uart function from STM32F7. From + Juha Niskanen (2017-05-12). + * syslog: Avoid flushing syslog_stream buffer, if possible, until + lib_vsprintf() completely parses the format. This assures that the + flush will flush the entire output, even data that may potentially + follow the linefeed. And, in that case, it cannot be interleaved + with other devug output. Suggested by Jussi Kivilinna (2017-05-12). + * syslog: There is yet another place where the output can get split. + That is in syslog_dev_write(): It will break up the stream to insert + a CR before the LF. This can that can be avoid be generating the + CR-LF sequence in the buffer and then detecting and ignoring valid + CR-LF sequences, rather than expecting syslog_dev_write() to insert + the CR in this case. I don't like the idea that syslog_dev_write() + still scans the entire output buffer to expand CR-LF sequence. This + seems really wasteful, especially in this case where we can be sure + that the is no CR or LF without a matching LF or CR. Bu, I think, + the existing behavior in syslog_dev_write() must be retained because + it is needed in other contexts (2017-05-12). + * Bitbucket Issue 47: Some of last syslog changes needed to be + condition on #ifdef CONFIG_SYSLOG_BUFFER in order to be built without + syslog buffering enabled (2017-05-12). + * Move CAN subsystem to its own directory and put device drivers + there. From Alan Carvalho de Assis (2017-05-12). + * locale.h: Add a bogus definition of locale_t. From (2017-05-12). + * kinetis K66: Fixed TMP2_CH1 definition. From David Sidrane + (2017-05-12). + * kinetis K66: Fefine ALT1 to match ref manual. From David Sidrane + (2017-05-12). + * kinetis K66: GPIO and pin mux cleanup. From David Sidrane + (2017-05-13). + * STM32F410: Add support for STM32F410. STM32F410 is a version of + STM32F4 with 32 KB of RAM and 62 or 128 KB of flash. From Gwenhael + Goavec-Merou (2017-05-13). + * Kconfig/deconfigs: Add CONFIG_ARCH_TOOLCHAIN_GNU to indicate that + the toolchain is based on GNU gcc/as/ld. This is in addition to the + CPU-specific versions of the same definition (2017-05-13). + * Remove CONFIG_ARM_TOOLCHAIN_GNU; replace with + CONFIG_ARCH_TOOLCHAIN_GNU (2017-05-13). + * Tiva I2C: Correct an error in conditional compilation (2017-05-13). + * Kconfig: Rename CONFIG_ARM_TOOLCHAIN_IAR to + CONFIG_ARCH_TOOLCHAIN_IAR (2017-05-13). + * Move prototype for up_cxxinitialize() from nuttx/include/nuttx/arch.h + to apps/include/platform/cxxinitialize.h (2017-05-13). + * libc/wchar: Versions mbrlen and mbsrtowcs taken and adapted from + FreeBSD code (at https://github.com/freebsd/freebsd/). From Matias + v01d (2017-05-13). + * tcp: wait for 3-Way Handshare before accept() returns. From Simon + Piriou (2017-05-14). + * configs/photon/wlan: disable network logs and add nsh over telnet. + From Simon Piriou (2017-05-14). + * TCP: Send RST if applicaiton 'unlistens()' before we complete the + connection sequence (2017-05-14). + * drivers: fix some bad NULL checks. From Juha Niskanen (2017-05-15). + * drivers: rename newly introduced up_i2creset to I2C_RESET. From + Juha Niskanen (2017-05-15). + * TCP: An RST recevied suring the 3-way handshake requires a little + more clean-up (2017-05-15). + * STM32 CAN: I had the problem that the transmit FIFO size (= actual + elements in FIFO) was slowly increasing over time, and was full after + a few hours. The reason was that the code hit the line + "canerr("ERROR: No available mailbox\n");" in stm32_cansend, so + can_xmit thinks it has sent the packet to the hardware, but actually + has not. Therefore the transmit interrupt never happens which would + call can_txdone, and so the size of the FIFO size does not decrease. + The reason why the code actually hit the mentioned line above, is + because stm32can_txready uses a different (incomplete) condition than + stm32can_send to determine if the mailbox can be used for sending, + and thus can_xmit forwards the packet to stm32can_send. + stm32can_txready considered mailboxes OK for sending if the mailbox + was empty, but did not consider that mailboxes may not yet be used if + the request completed bit is set - stm32can_txinterrupt has to + process these mailboxes first. Note that I have also modified + stm32can_txinterrupt - I removed the if condition, because the CAN + controller retries to send the packet until it succeeds. Also if the + condition would not evaluate to true, can_txdone would not be called + and the FIFO size would not decrease also. From Lederhilger Martin + (2017-05-16). + * drivers/bch: BCH character driver bch_ioctl() always returns -ENOTTY + for DIOC_GETPRIV command. It should returns OK if DIOC_GETPRIV + command succeeds. From EunBong Song (2017-05-16). + * There can be a failure in IOB allocation to some asynchronous + behavior caused by the use of sem_post(). Consider this scenario: + (1) Task A holds an IOB.  There are no further IOBs.  The value of + semcount is zero. Task B calls iob_alloc().  Since there are not + IOBs, it calls sem_wait().  The value of semcount is now -1. (2) + Task A frees the IOB.  iob_free() adds the IOB to the free list and + calls sem_post() this makes Task B ready to run and sets semcount to + zero NOT 1.  There is one IOB in the free list and semcount is zero. + When Task B wakes up it would increment the sem_count back to the + correct value. (3) But an interrupt or another task runs occurs + before Task B executes.  The interrupt or other tak takes the IOB off + of the free list and decrements the semcount.  But since semcount is + then < 0, this causes the assertion because that is an invalid state + in the interrupt handler. So I think that the root cause is that + there the asynchrony between incrementing the semcount. This change + separates the list of IOBs: Currently there is only a free list of + IOBs. The problem, I believe, is because of asynchronies due + sem_post() post cause the semcount and the list content to become out + of sync. This change adds a new 'committed' list: When there is a + task waiting for an IOB, it will go into the committed list rather + than the free list before the semaphore is posted. On the waiting + side, when awakened from the semaphore wait, it will expect to find + its IOB in the committed list, rather than free list. In this way, + the content of the free list and the value of the semaphore count + always remain in sync (2017-05-16). + * stm32_serial: fix freezing serial port. Serial interrupt + enable/disable functions do not disable interrupts and can freeze + device when serial interrupt is received while execution is at those + functions. Trivially triggered with two or more threads write to + regular syslog stream and to emergency stream. In this case, freeze + happens because of mismatch of priv->ie (TXEIE == 0) and actually + enabled interrupts in USART registers (TXEIE == 1), which leads to + unhandled TXE interrupt and causes interrupt storm for USART. From + Jussi Kivilinna (2017-05-17). + * STM32 Ethernet: Add support for KSZ8081 PHY interrupts. From + Sebastien Lorquet (2017-05-17). + * IPv6: Fix net_ipv6_pref2mask(). From Masayuki Ishikawa (2017-05-18). + * net procfs: Fix buffer corruption and refactor netdev_statistics.c. + From Masayuki Ishikawa (2017-05-19). + * binfmt: Fix .dtor memory allocation. From Masayuki Ishikawa + (2017-05-19). + * stm32_i2c: make private symbols static. From Juha Niskanen + (2017-05-19). + * network IOCTL commands: The only place in net/netdev/netdev_ioctl.c + where the interface state should change is for SIOCSIFFLAGS. The + other ones .. SIOCSIFADDR, SIOSLIFADDR, SIODIFADDR .. should not + change the link state. From Sebastien Lorquet (2017-05-19). + * drivers/wireless/ieee80211: Add support for AP scanning. From Simon + Piriou (2017-05-21). + * drivers/audio: add cs43l22 audio driver STM32F4: Add i2s driver. + From Taras Drozdovsky (2017-05-21). + * This is based on a patch by Taras Drozdovsky. Basically, the delay + that was added during the integration of the CDC/ACM host driver was + interfering with streaming audio. That delay was put there to + prevent build endpoints from hogging the system bandwidth. So what + do we do? Do we hog the bandwidth or do we insert arbitrarity + delays. I think both ideas such (2017-05-21). + * Replace sprintf() with snprintf() in pipe.c. From Nobutaka Toyoshima + (2017-05-22). + * drivers/bch: Fix 'Missing Unlock' in bchdev_driver.c. From Masayuki + Ishikawa (2017-05-22). + * FAT: Fix 'Missing unlock' in fs_fat32.c. From Masayuki Ishikawa + (2017-05-22). + * netdb: Fix time info in lib_dnscache.c. From Masayuki Ishikawa + (2017-05-23). + * STM32L4: Add IWDG peripheral. This is the same as for STM32 except + that prescale and reload can be changed after watchdog has been + started, as this seems to work on L4. From Juha Niskanen (2017-05-23). + * drivers/can: Add Microchip MCP2515 CAN Bus controller driver. From + Alan Carvalho de Assis (2017-05-23). + * button_upper: fix interrupt enabling for poll-events. From Jussi + Kivilinna (2017-05-24). + * netdb: Fix bugs in lib_gethostbynamer.c. This fix sets h_name in + struct hostent returned by gethostbyname(). From Masayuki Ishikawa + (2017-05-25). + * TCP: Fix tcp_findlistner() in dual stack mode. From Masayuki + Ishikawa (2017-05-25). + * TCP: tcp_input() now receives IP domain as an input parameter vs. + deriving from the IP header length (2017-05-25). + * Kinetis ADC: Various corrections and updates. From David Sidrane + (2017-05-25). + * drivers/lcd: Add driver for Nokia 5110 (Philips PCD8544). From Alan + Carvalho de Assis (2017-05-26). + * configs/stm32f103-miniumum: Add board support to use the Nokia 5110 + LCD display driver. From Alan Carvalho de Assis (2017-05-26). + * configs/pic32mx7mmb: add support for the Pinquino toolchain + (2017-05-27). + * configs/pic32mx7mmb: Repartition files to match newer + configurations. Add support for PROCFS file system. Default is now + Pinguino toolchain. Verify networking (2017-05-27). + * pthread_trylock: Fixes a problem in pthread_trylock() noted by + initialkjc@yahoo.com. When CONFIG_PTHREAD_MUTEX_UNSAFE=y, the + special return value EAGAIN was not being detected due to differences + in reporting of returned values (2017-05-29). + * vfs: fdopen: add missing file stream flags clearing. Clear file + stream structure regardless of config options. Structure clearing is + needed as previous use of stream list entry might leave fs_flags + set. From Harri Luhtala (2017-05-31). + * drivers/input: add Cypress MBR3108 CapSense touch button driver. + From Juha Niskanen (2017-05-31). + * STM32L4: gpio: put back EXTI line source selection. From Juha + Niskanen (2017-05-31). + * mtd/smart: Fix use of uninitialized variable. From Jussi Kivilinna + (2017-05-31). + * drivers/mtd/w25.c: Erase sector only if it is not in erased state. + From Jussi Kivilinna (2017-05-31). + * stm32f7: Add SPI DMA support. From Jussi Kivilinna (2017-05-31). + * drivers/mtd/w25.c: Enable short delay after sector/chip erase. From + Jussi Kivilinna (2017-05-31). + * pthread robust mutexes: Fix memmory trashing problem: the main task + may also use mutexes; need to check thread type before accessing + pthread-specific mutex data structures. Problem noted by Jussi + Kivilinna (2017-05-31). + * STM32L4 RTC: store RTC MAGIC to backup reg, not to address zero. + From Juha Niskanen (2017-06-01). + * drivers/{sensors,usbmisc}: Fix uninitialized I2C frequency. From + Juha Niskanen (2017-06-01). + * mtd/config: Add some error checks for I/O errors. From Juha + Niskanen (2017-06-01). + * pthread mutex: Remove bogus DEBUGASSERT. Problem noted by Jussi + Kivilinna (2017-06-01). + * Tiva SSI: Resolves issue 52 'Copy-Paste error in + tiva_ssibus_initialize()' submitted by Aleksandr Kazantsev + (2017-06-01). + * nucleo-f4x1re User LEDS: Issue #51 reports compilation problems with + stm32_userled.c. Reported by Gappi92 (2017-06-01). + * tools/: Add initialconfig.c so that perhaps in the future we will be + able to use this to generate a new configuration from scratch (rather + than having to derive new configurations from existing + configurations). NOTE: Not yet intregated into the build system + (2017-06-02). + +7.22 2017-xx-xx Gregory Nutt -- GitLab From a46a748bfae757485dc9fd577764c020b4e8b58d Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 5 Jun 2017 13:22:11 -0600 Subject: [PATCH 918/990] Update ReleaseNotes in preparation for NuttX-7.21 release. --- ChangeLog | 104 +++--- ReleaseNotes | 988 +++++++++++++++++++++++++++++++++++++++++++++++++++ 2 files changed, 1038 insertions(+), 54 deletions(-) diff --git a/ChangeLog b/ChangeLog index bc135b466c..8d2f6deea9 100755 --- a/ChangeLog +++ b/ChangeLog @@ -584,7 +584,7 @@ * Added fixed precision math support * Added some color converson routines into what may become a real graphics library someday. * Added a framebuffer driver for the DM320 (untested on initial check-in) - * Network: add support for outgoing multicast addresses + * Network: Add support for outgoing multicast addresses * Added some rasterizers to the graphics library 0.4.0 2008-12-06 Gregory Nutt @@ -924,7 +924,7 @@ context switches and background/user context switches. This change should improve the performance of those background/user context switches by a factor of about two. - * arch/arm/src/stm32/: fix several typos in the serial logic. It turns out + * arch/arm/src/stm32/: Fix several typos in the serial logic. It turns out that these typose don't make any difference as long as you use only one serial port and all uarts are configured the same. But the typos are bugs waiting to happen in any other configuration. @@ -1591,7 +1591,7 @@ where the GPL driver(s) can be re-installed into the NuttX source tree. By re-installing the driver, you agree to the GPL licsensing and all of its implications. - * Makefile, apps/Makefile, tools/configure.sh: add logic to copy + * Makefile, apps/Makefile, tools/configure.sh: Add logic to copy configs///appdir to apps/.config and to simply the application configuration logic. * examples/nsh and apps/nshlib: Move the core NuttShell (NSH) logic @@ -1617,7 +1617,7 @@ without the SDcard (but one issue still exists in STM32) * arch/arm/src/stm32/stm32_tim.*: Added basic timer support TIM1..TIM8 with output PWMs and interrupt logic - * config/vsn/src: added basic support for Sensor Interface (GPIO and + * config/vsn/src: Added basic support for Sensor Interface (GPIO and PWM Power Output, and the sif utility program) * fs/: Reorgnize header so that file systems can be built outside of the nuttx source tree @@ -6362,7 +6362,7 @@ from Max Holtzberg (2014-1-4). * configs/olimex-stm32-p107/nsh/Make.defs: Add native Windows build support for the Olimex STM32 P107. From Max Holtzberg (2014-1-4). - * Makefile.win: Changes for native Windows build: fix creation of + * Makefile.win: Changes for native Windows build: Fix creation of a .version file if one does not exist. Make sure that the APPDIR environment variable is set before configuring. From Max Holtzberg (2014-1-4). @@ -9341,11 +9341,11 @@ That is because not handles not only the case of semaphore wait being awakened by a signal, but also the case with sem_timedwait.c when the semaphore wait is awakened by a timeout (2014-12-28). - * arch/arm/src/stm32/stm32_ltdc.c: stm32: fix faulty access to non- + * arch/arm/src/stm32/stm32_ltdc.c: stm32: Fix faulty access to non- existing layer. This disables operation that requires double layer support, when configured for single layer only. From Marco Krahl (2014-12-29). - * arch/arm/src/stm32/stm32_ltdc.c: stm32: fix wait upon vertical blank. + * arch/arm/src/stm32/stm32_ltdc.c: stm32: Fix wait upon vertical blank. This should never have occurred before. From Marco Krahl (2014-12-29). * configs/stm32f429i-disco/ltdc/defconfig and src/stm32_boot.c: stm32f429i-disco: change ltdc initializing during boot up. This moves @@ -9465,7 +9465,7 @@ * arch/arm/src/tiva/tm4c_ethernet.c: When calling into the stack from the worker thread, it is necessary to have the stack locked (2015-01-18). - * nuttx/arch/arm/src/stm32/stm32_serial.c: fix declaration and + * nuttx/arch/arm/src/stm32/stm32_serial.c: Fix declaration and definition of up_receive() and up_dma_receive() to match fields of uart_ops_s from nuttx/include/nuttx/serial/serial.h. From Freddie Chopin (2015-01-19). @@ -10323,7 +10323,7 @@ LED, PWM, and UART0 have been tested. The SPI pins are mapped correctly but have not yet been tested. From Michael Hope as SourceForge patch 51 (2015-05-07). - * arch/arm/src/kl/kl_pwm.c: fix PWM debugging. TPM1 and TPM2 have two + * arch/arm/src/kl/kl_pwm.c: Fix PWM debugging. TPM1 and TPM2 have two channels instead of six and will hard fault if you try to read the missing channels. From Michael Hope (2015-05-07). * arch/arm/src/kl/kl_lowputc.c: enable the clocks to UART1 and UART2. @@ -11954,7 +11954,7 @@ stm32_pwm.c. From Konstantin Berezenko (2016-06-09). * arch/arm/src/kinetis: Support up to 8 channels per timer. From kfazz (2016-06-09). - * lib/: crc16: fix error. From Paul Alexander Patience (2016-06-10). + * lib/: crc16: Fix error. From Paul Alexander Patience (2016-06-10). * lib/: Add crc64 support. From Paul Alexander Patience (2016-06-10). * arch/arm/src/kinetis: Added kl_dumpgpio functionality as kinetis_pindump. From kfazz (2016-06-10). @@ -12243,7 +12243,7 @@ * drivers/syslog: Add a SYSLOG character device that can be used to re- direct output to the SYSLOG (2016-07-05). * net/netdev: Break out internal interface psock_ioctl() (2016-07-06). - * configs/stm32f4disovery: add can driver for stm32f4discovery. From + * configs/stm32f4disovery: Add can driver for stm32f4discovery. From Matthias Renner (2016-07-06). * configs/freedom-k64f: Increase MCU clock to 120MHz (2016-07-06). * arch/arm/src/stm32: Add support for Tickless mode (two timer @@ -12598,7 +12598,7 @@ feature is EXPERIMENTAL because (1) it is untested and (2) has some know design issues that must be addressed before it can be of use (2016-08-28). - * CXXFLAGS: add -fcheck-new whenever -fno-exceptions is used. From Beat + * CXXFLAGS: Add -fcheck-new whenever -fno-exceptions is used. From Beat Küng (2016-08-23). * tools/mkfsdata.pl was still generating the old-style apps/include inclusion paths (2016-08-23). @@ -12769,7 +12769,7 @@ Mateusz Szafoni (2016-10-06). * STM32 SPI: stm32_modifycr2 should be available on all platforms if DMA is enabled. (2016-10-06). - * STM32 DMA2D: fix an error in up_dma2dcreatelayer where an invalid + * STM32 DMA2D: Fix an error in up_dma2dcreatelayer where an invalid pointer was returned when a certain underlying function failed. From Jens Gräf (2016-10-07). @@ -12808,10 +12808,10 @@ * libc/locale: Add clocale header file (2016-10-18). * libc/wchar: Add functions btowc, mbrtowc, mbtowc, wcscmp, wcscoll, wmemmove. From Alan Carvalho de Assis (2016-10-18). - * usbhost/enumerate: fix possible buffer overwrite. From Janne Rosberg + * usbhost/enumerate: Fix possible buffer overwrite. From Janne Rosberg (2016-10-18). * configs/Board.mk: Add extra clean operations (2016-10-18). - * usbhost/composite: fix compile; missing semicolons. From Jann + * usbhost/composite: Fix compile; missing semicolons. From Jann Rosberg (2016-10-18). * libc/stdio: Include wchar.h in lib_libvsprintf.c to fix compilation error. From Alan Carvalho de Assis (2016-10-18). @@ -12843,7 +12843,7 @@ From Alan Carvalho de Assis (2016-10-19). * syslog: Fixes required for file syslog output. From Max Kriegleder (2016-10-19). - * arch/arm/src/stm32: add TIM8 to STM32F103V pinmap. From Maciej Wójcik + * arch/arm/src/stm32: Add TIM8 to STM32F103V pinmap. From Maciej Wójcik (2016-10-19). * libc/locale: Allows c++ code to compile with or without CONFIG_LIBC_LOCALE and will generate a link error if CONFIG_LIBC_LOCALE @@ -12989,24 +12989,24 @@ * arch/arm/src/armv7-r: Fix compilation error. This commit fixes compilation errors on MPU support for ARMv7-R. From Heesub Shin (2016-11-06). - * arch/arm/src/armv7-r: fix invalid drbar handling. In ARMv7-R, + * arch/arm/src/armv7-r: Fix invalid drbar handling. In ARMv7-R, [31:5] bits of DRBAR is physical base address and other bits are reserved and SBZ. Thus, there is no point in passing other than the base address. From Heesub Shin (2016-11-06). * arch/arm/src/armv7-r: Remove the redundant update on SCTLR. mpu_control() is invoking cp15_wrsctlr() around SCTLR update redundantly. From Heesub Shin (2016-11-06). - * arch/arm/src/armv7-r: add new Kconfig entries for d/i-cache. + * arch/arm/src/armv7-r: Add new Kconfig entries for d/i-cache. Unlike in ARMv7-A/M, Kconfig entries for data and instruction caches are currently missing in ARMv7-R. This commit adds those missing Kconfig entries. Actual implmenetation for those functions will be added in the subsequent patches. From Heesub Shin (2016-11-06). - * arch/arm/src/armv7-r: add cache handling functions. This commit + * arch/arm/src/armv7-r: Add cache handling functions. This commit adds functions for enabling and disabling d/i-caches which were missing for ARMv7-R. From Heesub Shin (2016-11-06). - * arch/arm/src/armv7-r: fix typo in mpu support. s/ARMV7M/ARMV7R/g. + * arch/arm/src/armv7-r: Fix typo in mpu support. s/ARMV7M/ARMV7R/g. From Heesub Shin (2016-11-06). - * arch/arm/src/armv7-r: fix CPSR corruption after exception handling. + * arch/arm/src/armv7-r: Fix CPSR corruption after exception handling. A sporadic hang with consequent crash was observed when booting. It seemed to be caused by the corrupted or wrong CPSR restored on return from exception. NuttX restores the context using code like this: @@ -13027,7 +13027,7 @@ result in the corruption of cpsr and thus unexpected behavior. From Heesub Shin (2016-11-06). - * arch/arm/src/armv7-r: fix to restore the Thumb flag in CPSR. Thumb + * arch/arm/src/armv7-r: Fix to restore the Thumb flag in CPSR. Thumb flag in CPSR is not restored back when the context switch occurs while executing thumb instruction. From Heesub Shin (2016-11-06). * sched/wqueue: When queuing new LP work, don't signal any threads @@ -13271,9 +13271,9 @@ CONFIG_NET_MULTIBUFFER (2016-11-29). * stm32_otghshost: if STM32F446 increase number of channels to 16. From Janne Rosberg (2016-11-30). - * usbhost_composite: fix end offset in usbhost_copyinterface(). From + * usbhost_composite: Fix end offset in usbhost_copyinterface(). From Janne Rosberg (2016-11-30). - * usbhost_cdcacm: add CDC_SUBCLASS_ACM and CDC_PROTO_ATM to supported + * usbhost_cdcacm: Add CDC_SUBCLASS_ACM and CDC_PROTO_ATM to supported class and proto. From Janne Rosberg (2016-11-30). * LPC43 SD/MMC: Correct some git definitions on SMMC control register in lpc43_sdmmc.h. From Alan Carvalho de Assis (2016-11-30). @@ -13850,7 +13850,7 @@ * STM32L4: Bring LPTIM driver in from the Motorola MDK (2017-02-18). * drivers/sensors: Add driver for the ST L3GD20 3 axis gyro. From raiden00 (2017-02-19). - * config/stm32f429i-disco: add support for the L3GD20 driver. From + * config/stm32f429i-disco: Add support for the L3GD20 driver. From raiden00 (2017-02-19). * STM32L4 COMP: Port from Motorola MDK (2017-02-19). * Add twr-k64f120m config and fix some ENET related problems. From Marc @@ -14004,7 +14004,7 @@ standardized approach. From Mark Schulte (2017-03-01). * Fix open() a block device with CONFIG_DISABLE_PSEUDOFS_OPERATIONS=y. From Masayuki Ishikawa (2017-03-01). - * net/: fixed a nullptr-dereference on iob_clone. From Pascal Speck + * net/: Fixed a nullptr-dereference on iob_clone. From Pascal Speck (2017-03-01). * configs/: All functions that used to return an xcpt_t old handler value, not return NULL. The oldhandler value is no longer useful with the @@ -14089,7 +14089,7 @@ Janne Rosberg. Adapt Janne Rosberg's patch to STM32 OTGHS host to OTGFS host, and to similar USB host implementations for STM32 L4 and F7 (2017-03-07). - * usbhost_cdcacm: fix tx outbuffer overflow and remove now invalid + * usbhost_cdcacm: Fix tx outbuffer overflow and remove now invalid assert. From Janne Rosberg (2017-03-07). 7.21 2017-06-06 Gregory Nutt @@ -14313,7 +14313,7 @@ architectures. From David Cabecinhas (2017-03-18). * configs/nucleo_f334r8: Add ADC example. From Mateusz Szafoni (2017-03-18). - * mtd/progmem: fix incorrect target address calculation. + * mtd/progmem: Fix incorrect target address calculation. progmem_read/write() is incorrectly calculating the target address, expecting the offset argument is given in a block number. This is completely wrong and as a result invalid flash region is accessed. @@ -14540,7 +14540,7 @@ HW TCP/IP API requests while rest of the user-space can access standard socket API, with socket descriptors that can be used with NuttX system calls. From Jussi Kivilinna (2017-03-31). - * STM32F7: add support for LSE RTC and enable RTC subseconds. From + * STM32F7: Add support for LSE RTC and enable RTC subseconds. From Jussi Kivilinna (2017-03-31). * TCP/IPv6: Fix a compile issue when IPv6, but not IPv4 is enabled (2017-03-31). @@ -14580,12 +14580,12 @@ loopback driver (2017-04-03). * STM32: Add I2C3 SDA pin mapping for STM32F411. From no1wudi (2017-04-04). - * sensors: lis2dh: fix hardfault when reading from unconfigured + * sensors: lis2dh: Fix hardfault when reading from unconfigured sensor. From Juha Niskanen (2017-04-04). - * STM32: stm32_flash: add EEPROM writing for STM32L15XX. From Juha + * STM32: stm32_flash: Add EEPROM writing for STM32L15XX. From Juha Niskanen (2017-04-04). * 6loWPAN: Add option to dump buffers (2017-04-04). - * STM32: stm32l15xx_rcc: add support for using MSI as system clock. + * STM32: stm32l15xx_rcc: Add support for using MSI as system clock. From Juha Niskanen (2017-04-05). * STM32: stm32l15xxx_rcc: configure medium performance voltage range and zero wait-state when allowed by SYSCLK setting. Zero wait-state @@ -14601,7 +14601,7 @@ (2017-04-05). * STM32: Fix SYSCFG_CFGR1_I2C_PBXFMP_SHIFT value. From Alan Carvalho de Assis (2017-04-06). - * STM32F7: Serial: add interface to get uart_dev_t by USART number, + * STM32F7: Serial: Add interface to get uart_dev_t by USART number, stm32_serial_get_uart. From Jussi Kivilinna (2017-04-06). * STM32F7: Default CONFIG_STM32F7_DMACAPABLE to 'n'. STM32F7 does not have CCM RAM but DTCM, so this option does not need to enabled. DTCM @@ -14609,7 +14609,7 @@ (2017-04-06). * STM32F7: Fix UART7 and UART8 IFLOWCONTROL options. From Jussi Kivilinna (2017-04-06). - * STM32F7: add warning for RXDMA + IFLOWCONTROL combination. + * STM32F7: Add warning for RXDMA + IFLOWCONTROL combination. Combination of RXDMA + IFLOWCONTROL does not work as one might expect. Since RXDMA uses circular DMA-buffer, DMA will always keep reading new data from USART peripheral even if DMA buffer underruns. @@ -14619,7 +14619,7 @@ inside irq critical section and feeding data to RXDMA+IFLOWCONTROL UART. From Jussi Kivilinna (2017-04-06). * sim/sixlowpan: Now supports apps/examples/udpblaster too (2017-04-06). - * SAMV7: Watchdog: fix Forbidden Window Value. According the Datasheet + * SAMV7: Watchdog: Fix Forbidden Window Value. According the Datasheet the WDD Value is the lower bound of a so called Forbidden Window and to disable this we have to set the WDD Value greater than or equal to the WDV Value. This seems to be a bug in the datasheet. It looks @@ -14629,7 +14629,7 @@ Feature resets the System if WDD equals to WDV. This Changeset disables the Forbidden Window by setting the WDD Value to the Maximum (0xfff) Value possible. From Frank Benkert (2017-04-06). - * RTC: add interface for check if RTC time has been set. New interface + * RTC: Add interface for check if RTC time has been set. New interface allows checking if RTC time has been set. This allows to application to detect if RTC has valid time (after reset) or should application attempt to get real time by other means (for example, by launching @@ -14735,7 +14735,7 @@ wireless/ieee802154/mac802154.h (2017-04-14). * radio802154_device.c now accesses the PHY layer via the IOCTL helper functions (2017-04-14). - * photon: add sdpcm + thread support for wlan. From Simon Piriou + * photon: Add sdpcm + thread support for wlan. From Simon Piriou (2017-04-13). * Not a clean fix, but at least makes DHCP working with CONFIG_NETDEV_MULTINIC. From Andreas Bihlmaier (2017-04-15). @@ -14927,7 +14927,7 @@ (2017-04-27). * net/socket: Fix cloning of local and raw sockets. From Jussi Kivilinna (2017-04-28). - * STM32L4: stm32l4_i2c: add I2C4 code. From Juha Niskanen (2017-04-28). + * STM32L4: stm32l4_i2c: Add I2C4 code. From Juha Niskanen (2017-04-28). * STM32L4: I2C was not using current interrupt handling parameter passing logic (2017-04-28). * vfs/poll: round timeout up to next full tick. Calling poll() with @@ -15019,7 +15019,7 @@ * 6loWPAN: Fixes hang in loopback test (2017-05-03). * drivers/wireless/bcmf: Fix frame not freed when dropped + cleanup. From Simon Piriou (2017-05-03). - * STM32L4: stm32l4_i2c: change wrong macro to CONFIG_I2C_POLLED. From + * STM32L4: stm32l4_i2c: Change wrong macro to CONFIG_I2C_POLLED. From Juha Niskanen (2017-05-04). * STM32L4: modularize Kconfig to support different product lines/families. This is modeled after STM32F7. Idea is to declare @@ -15044,8 +15044,6 @@ short/exended address terminology (2017-05-04). * 6loWPAN: Remove all ieee802.15.4 MAC knowledge from 6loWPAN. Now relies on wires/ieee802154 for all MAC-related operations (2017-05-04). - * STM32L4: stm32l4_i2c: change wrong macro to CONFIG_I2C_POLLED. From - Juha Niskanen (2017-05-04). * 6loWPAN: Local address length is fixed by the configuration. The remote address be with short or extended (2017-05-04). * STM32L4: Separate SYSCFG into product line specific files for @@ -15075,7 +15073,7 @@ * wireless/ieee802154: Removes radio IOCTL. Starts bringing radio and MAC closer with well-defined interface. From Anthony Merlino (2017-05-05). - * STM32L4: add support for many new MCUs from STM32L4X3XX product line + * STM32L4: Add support for many new MCUs from STM32L4X3XX product line and Nucleo-L452 board. From Juha Niskanen (2017-05-05). * 6loWPAN: Use information in struct ieee802154_data_ind_s when reassembling a packet (2017-05-05). @@ -15117,8 +15115,6 @@ Merlino (2017-05-08). * wireless/ieee802154: Completes basic receive functionality. From Anthony Merlino (2017-05-08). - * STM32: Serial DMA buffer round off not up. From David Sidrane - (2017-05-08). * Final fixes to get the nucleo-l432kc config build. Execution not tested yet. From Sebastien Lorquet (2017-05-09). * Adapt stm32l43x pin definitions. From Sebastien Lorquet (2017-05-09). @@ -15128,7 +15124,7 @@ (2017-05-09). * IOBs: Move from driver/iob to a better location in mm/iob (2017-05-09). - * STM32L4: add dbgmcu header files. From Juha Niskanen (2017-05-09). + * STM32L4: Add dbgmcu header files. From Juha Niskanen (2017-05-09). * wireless/ieee802154: Fixes missing handle of read/write being able to be interrupted. From Anthony Merlino (2017-05-09). * wireless/ieee802154: Starts implementing START.request primitive. @@ -15149,7 +15145,7 @@ (2017-05-10). * syslog buffering: Use IOBs to buffer data, not an on-stack buffer (2017-05-10). - * STM32L4: add internal flash write support. From Juha Niskanen + * STM32L4: Add internal flash write support. From Juha Niskanen (2017-05-11). * When syslog message has addition characters after last new-line. With buffering those now get lost as vsyslog does not flush output after @@ -15208,7 +15204,7 @@ * locale.h: Add a bogus definition of locale_t. From (2017-05-12). * kinetis K66: Fixed TMP2_CH1 definition. From David Sidrane (2017-05-12). - * kinetis K66: Fefine ALT1 to match ref manual. From David Sidrane + * kinetis K66: Define ALT1 to match ref manual. From David Sidrane (2017-05-12). * kinetis K66: GPIO and pin mux cleanup. From David Sidrane (2017-05-13). @@ -15237,7 +15233,7 @@ * drivers: fix some bad NULL checks. From Juha Niskanen (2017-05-15). * drivers: rename newly introduced up_i2creset to I2C_RESET. From Juha Niskanen (2017-05-15). - * TCP: An RST recevied suring the 3-way handshake requires a little + * TCP: An RST received during the 3-way handshake requires a little more clean-up (2017-05-15). * STM32 CAN: I had the problem that the transmit FIFO size (= actual elements in FIFO) was slowly increasing over time, and was full after @@ -15287,7 +15283,7 @@ its IOB in the committed list, rather than free list. In this way, the content of the free list and the value of the semaphore count always remain in sync (2017-05-16). - * stm32_serial: fix freezing serial port. Serial interrupt + * stm32_serial: Fix freezing serial port. Serial interrupt enable/disable functions do not disable interrupts and can freeze device when serial interrupt is received while execution is at those functions. Trivially triggered with two or more threads write to @@ -15311,7 +15307,7 @@ change the link state. From Sebastien Lorquet (2017-05-19). * drivers/wireless/ieee80211: Add support for AP scanning. From Simon Piriou (2017-05-21). - * drivers/audio: add cs43l22 audio driver STM32F4: Add i2s driver. + * drivers/audio: Add cs43l22 audio driver STM32F4: Add i2s driver. From Taras Drozdovsky (2017-05-21). * This is based on a patch by Taras Drozdovsky. Basically, the delay that was added during the integration of the CDC/ACM host driver was @@ -15332,7 +15328,7 @@ started, as this seems to work on L4. From Juha Niskanen (2017-05-23). * drivers/can: Add Microchip MCP2515 CAN Bus controller driver. From Alan Carvalho de Assis (2017-05-23). - * button_upper: fix interrupt enabling for poll-events. From Jussi + * button_upper: Fix interrupt enabling for poll-events. From Jussi Kivilinna (2017-05-24). * netdb: Fix bugs in lib_gethostbynamer.c. This fix sets h_name in struct hostent returned by gethostbyname(). From Masayuki Ishikawa @@ -15347,7 +15343,7 @@ Carvalho de Assis (2017-05-26). * configs/stm32f103-miniumum: Add board support to use the Nokia 5110 LCD display driver. From Alan Carvalho de Assis (2017-05-26). - * configs/pic32mx7mmb: add support for the Pinquino toolchain + * configs/pic32mx7mmb: Add support for the Pinquino toolchain (2017-05-27). * configs/pic32mx7mmb: Repartition files to match newer configurations. Add support for PROCFS file system. Default is now @@ -15356,11 +15352,11 @@ initialkjc@yahoo.com. When CONFIG_PTHREAD_MUTEX_UNSAFE=y, the special return value EAGAIN was not being detected due to differences in reporting of returned values (2017-05-29). - * vfs: fdopen: add missing file stream flags clearing. Clear file + * vfs: fdopen: Add missing file stream flags clearing. Clear file stream structure regardless of config options. Structure clearing is needed as previous use of stream list entry might leave fs_flags set. From Harri Luhtala (2017-05-31). - * drivers/input: add Cypress MBR3108 CapSense touch button driver. + * drivers/input: Add Cypress MBR3108 CapSense touch button driver. From Juha Niskanen (2017-05-31). * STM32L4: gpio: put back EXTI line source selection. From Juha Niskanen (2017-05-31). diff --git a/ReleaseNotes b/ReleaseNotes index b15cf3cd68..2d338a9912 100644 --- a/ReleaseNotes +++ b/ReleaseNotes @@ -13546,3 +13546,991 @@ detailed bugfix information): - In apps/examples/mtdpart/mtdpart_main.c where CONFIG_EXAMPLES_MTDPART_NPARTITIONS defining is checked should be #ifndef instead of #ifdef. Noted by Oleg Evseev. + +NuttX-7.21 Release Notes +------------------------ + +The 121st release of NuttX, Version 7.21, was made on June 6, 2017, +and is available for download from the Bitbucket.org website. Note +that release consists of two tarballs: nuttx-7.21.tar.gz and +apps-7.21.tar.gz. These are available from: + + https://bitbucket.org/nuttx/nuttx/downloads + https://bitbucket.org/nuttx/apps/downloads + +Both may be needed (see the top-level nuttx/README.txt file for build +information). + +Additional new features and extended functionality: + + * Core OS: + + - pthread rwlocks: Add an implementation for read/write locks + (rwlocks) into the pthread library. These locks are writer + priority, such that if any writers come in they are given priority + for writing. From Mark Schulte. + - pthread robust mutexes: Implement robust mutex support: + pthread_mutex_lock() and trylock() will return EOWNERDEAD if the + mutex is locked by a thread that no longer exists. Add + pthread_mutex_consistent() to recover from this situation. Keep + list of all mutexes held by a thread in a list in the pthread's TCB. + When pthread exits or is cancelled, mutexes held by thread are + marked inconsistent and the highest priority thread waiting for the + mutex is awakened. There is a configuration option to (a) support + only robust mutexes, (b) support only traditional unsafe mutexes, + or (c) Support both unsafe and robust mutexes via + pthread_mutexattr_get/setrobust(). + - pthread cancellation points: Add logic to disable cancellation + points within the OS. This is useful when an internal OS function + that is NOT a cancellation point calls an OS function which is a + cancellation point. In that case, irrecoverable states may occur if + the cancellation is within the OS. From Juha Niskanen. + - clock: Add clock_resynchronize and use subseconds RTC. Add + clock_resynchronize for better synchronization of CLOCK_REALTIME and + CLOCK_MONOTONIC to match RTC after resume from low-power state. Add + up_rtc_getdatetime_with_subseconds under + CONFIG_ARCH_HAVE_RTC_SUBSECONDS to allow initializing (and + resynchronizing) system clock with subseconds accuracy RTC. From + Jussi Kivilinna. + - clock: Add new type ssystime_t for relative 64-bit ticks, change + ticks<->time conversion functions to use ssystime_t. From Jussi + Kivilinna. + - clock: Add testing for 32-bit overflow of 64-bit system timer. From + Jussi Kivilinna. + + * File Systems/Block and MTD Drivers + + - drivers/mtd/w25.c: Erase sector only if it is not in erased state. + From Jussi Kivilinna. + + * Graphics/Display Drivers: + + - drivers/lcd: Extend st7565 driver to include support for the + AQM_1248A. From Masayuki Ishikawa. + - drivers/lcd: Add driver for Nokia 5110 (Philips PCD8544). From Alan + Carvalho de Assis. + + * Networking/Network Drivers: + + - Extensive modifications to support wireless network (see below). + - TUN driver: Implement TAP (OSI layer 2) mode. Enable by setting the + IFF_TAP flag instead of the IFF_TUN flag in ifr_flags. From Thomas + Keh. + - Add user-space networking stack API (usrsock). User-space + networking stack API allows user-space daemon to provide TCP/IP + stack implementation for NuttX network. Main use for this is to + allow use and seamless integration of HW-provided TCP/IP stacks to + NuttX. For example, user-space daemon can translate /dev/usrsock + API requests to HW TCP/IP API requests while rest of the user-space + can access standard socket API, with socket descriptors that can be + used with NuttX system calls. From Jussi Kivilinna. + - net/: Network driver now retains Ethernet MAC address in a union so + that other link layer addresses may be used in a MULTILINK + environment. + + * Wireless Networking/Wireless Drivers: + + - BCM43362: Support for Broadcom's BCM43362 WiFi chip was contributed + by Simon Piriou as part of the port of the Particle Photon board. + Only station functionality is available at present. This work + includes not on the WiFi driver, but the support Particle Photon + board, the infrasture for IEEE 802.11 FullMAC networking including + the network device interface, WiFi configuration, AP scanning and + authentication and association with an AP. + - IEEE 802.11 networking tools and support. + - IEEE 802.15.4 MAC support. This is an effort that was started some + time back by Sebastien Lorquet (with some help from Matte Poppe). + Recently, Anthony Merlino has taken on this effort and has made + some significant progress. Using the Microchip MRF24J40 module with + the Mikroe Clicker2-STM32 board along with a PC-based IEEE 802.15.4 + sniffer, Anthonly has verified correct transmittion and receipt of + basic frames. + - Microchip MRF24J40: As mentioned above, this IEEE 802.15.4 radio + driver is now basically functional. + - IEEE 802.15.4 Network Driver: A driver that interfaces the NuttX + network with the IEEE 802.15.4 MAC has been developed but is still + incomplete and has not been verified. + - IEEE 802.15.4 Network Loopback Driver: A simple IEEE 802.15.4 MAC + loopback driver was developed. This driver allowed for parallel + development of the IEEE 802.15.4 MAC and 6loWPAN. + - 6loWPAN: The Contiki 6loWPAN stack has been ported so that works + within the NuttX networking framework and interfaces with the new + IEEE 802.15.4 MAC via the network driver. Live testing with + IEEE 802.15.4 radios has not yet been done; all testing has used + the loopback driver. There are no known problems and the stack + is ready for additional testing. + - Add option to enable wireless debug output. + + * Other Common Device Drivers: + + - Add entropy pool and strong random number generator. Entropy pool + gathers environmental noise from device drivers, user-space, etc., + and returns good random numbers, suitable for cryptographic use. + Based on entropy pool design from *BSDs and uses BLAKE2Xs algorithm + for CSPRNG output. Patch also adds /dev/urandom support for using + entropy pool RNG and new 'getrandom' system call for getting + randomness without file-descriptor usage (thus avoiding file- + descriptor exhaustion attacks). The 'getrandom' interface is similar + as 'getentropy' and 'getrandom' available on OpenBSD and Linux + respectively. From Jussi Kivilinna. + - XBox One controller: Adds USB host driver support for the XBox One + controller. Currently only the latest version (XBox One X) + controller works. The older XBox One controllers do not enumerate + correctly. From Brian Webb. + - drivers/analog: Add basic COMP driver. From Mateusz Szafoni. + - drivers/analog: Add driver for the LTC1767L ADC. From Martin + Lederhilger. + - drivers/analog: Add basic OPAMP driver. From Mateusz Szafoni. + - drivers/sensors: Add driver for ST HTS221 humidity sensor. From + Juha Niskanen. + - drivers/sensors: Add driver for ST LPS25H pressure sensor. From + Juha Niskanen. + - drivers/sensors: Add driver for ST LIS2DH accelerometer. From Timo + Voutilainen. + - drivers/usbmisc: Add driver for Fairchild FUSB301 USB type-C + controller. From Harri Luhtala. + - RTC: Add interface for check if RTC time has been set. New + interface allows checking if RTC time has been set. This allows to + application to detect if RTC has valid time (after reset) or should + application attempt to get real time by other means (for example, by + launching ntpclient or GPS). From Jussi Kivilinna. + - Buttons: Change return value of board_buttons() and the type of + btn_buttonset_t to uint32_t so that more than 8 buttons can be + supported. + - drivers/syslog: Use monotonic clock for timestamp when available. + From Jussi Kivilinna. + - SPI: Add an instance argument to the SPIDEV definitions. Thus, + instead of specifying a FLASH device, for example, as SPI_FLASH, you + would now use SPI_FLASH(0) where the "instance" argument now + distinguishes multiple FLASH devices on the same SPI bus. From + Sebastien Lorquet. + - IOBs: Move from net/iob to a better location in mm/iob where they + can be shared outside of the networking logic. Current also used + by IEEE 802.15.4 MAC and by syslog (when buffering enabled). + - syslog: Add option to buffer SYSLOG output to avoid interleaving. + Uses new shareable IOBs. Additional logic to assure that the the + write from the buffer is a single atomic write in normal debug + output. + - drivers/can: Move CAN subsystem to its own directory and put device + drivers there. From Alan Carvalho de Assis. + - drivers/can: Add Microchip MCP2515 CAN Bus controller driver. From + Alan Carvalho de Assis. + - drivers/audio: Add cs43l22 audio driver. From Taras Drozdovsky. + - drivers/input: Add Cypress MBR3108 CapSense touch button driver. + From Juha Niskanen. + + * Simulation + + - configs/sim/sixlowpan: Configuration for testing the 6loWPAN with + the IEEE 802.15.4 loopback network driver. + + * Infineon XMC4xxx: + + - arch/arm/src/xmc4: Initial, partial support for Infineon XMC4xxx. + + * Infineon XMC4xxx Boards: + + - XMC4500 Relax: Add basic board support infrastructure of Infineon + XMC4500 Relax Lite v1. Basic serial, LED, and button button support + for a simple NSH configuration. There are still stome remaining + issues with serial communications. + + * MicroChip PIC32MX Boards: + + - pic32mx7mmb: Add support for the Pinquino toolchain. + - pic32mx7mmb: Add support for PROCFS file system. + + * NXP Freescale Kinetis: + + - Kinetis: Allow board to add pullups on SDHC lines. From David + Sidrane. + - Kinetis: Use optional BOARD_OSC_CR and BOARD_OSC_DIV in clock + configuration. From David Sidrane. + + * NXP Freescale Kinetis Drivers: + + - Kinetis: Add Timer PWM Module (TPM) to K66 chip. From David + Sidrane. + - Kinetis: Added HW flow control and termios. From David Sidrane. + - Kinetis: Add ARCH_HAVE_I2CRESET. From David Sidrane. + + * NXP Freescale LPC43xx: + + - Add support for LPC4337FET256. From Andreas Bihlmaier. + + * STMicro STM32: + + - Change STM32 tickless to use only one timer. From Konstantin + Berezenko. + - STM3 2F7: Add support for LSE RTC and enable RTC subseconds. From + Jussi Kivilinna. + - STM32 L1: stm32l15xx_rcc: Add support for using MSI as system + clock. From Juha Niskanen. + - STM32 L1: stm32l15xxx_rcc: configure medium performance voltage + range and zero wait-state when allowed by SYSCLK setting. Zero + wait-state for flash can be configured when: (1) Range 1 and + SYSCLK <= 16 Mhz, (2) Range 2 and SYSCLK <= 8 Mhz, or (3) Range 3 + and SYSCLK <= 4.2 Mhz. Medium performance voltage range (1.5V) + can be configured when SYSCLK is up to 16 Mhz and PLLVCO up to + 48 Mhz. From Juha Niskanen. + - STM32 F0: Add basic support for STM32F0. From Alan Carvalho de + Assis. + - STM32 F0: Add basic support for STM32F07x family. + - STM32 L1: stm32l15xx_rcc: Allow board to configure HSE clock in + bypass-mode. Allows using MCO output from ST-link chip (on Nucleo + and Discovery boards) as HSE input. From Juha Niskanen. + - STM32 L1: Add support for STM32L152CC, STM32L152RC and STM32L152VC. + From Juha Niskanen. + - STM32 F0: Add support for HSI48. + - STM32 L4: Add support for the STM32L496XX family. From Juha + Niskanen. + - STM32 L4: modularize Kconfig to support different product + lines/families. This is modeled after STM32F7. Idea is to declare + each chip in Kconfig but allow for flash size override. Commit adds + many STM32L4_HAVE_XXX feature test macros. From Juha Niskanen. + - STM32 L4: Separate SYSCFG into product line specific files for + clarity. From Juha Niskanen. + - STM32 L4: Add support for many new MCUs from the STM32L4X3XX + product line. From Juha Niskanen. + - STM32 L4: Add dbgmcu header files. From Juha Niskanen. + - STM32 F410: Add support for STM32F410. STM32F410 is a version of + STM32F4 with 32 KB of RAM and 62 or 128 KB of flash. From Gwenhael + Goavec-Merou. + + * STMicro STM32 Drivers: + + - SDIO: Extensions to support the SDIO interface to the BCM43362 from + Simon Piriou. + - STM32 F2: Add USB OTG HS support for stm32f20xxx cores. From Simon + Piriou. + - STM32 F2, F4, and F7: Add BOARD_DISABLE_USBOTG_HSULPI flag. From + Simon Piriou. + - STM32 F33: Move DMA logic to a separate files + add ADC support. + From Mateusz Szafoni. + - STM32 F3: Add COMP support. From Mateusz Szafoni. + - STM32 F33: Support for COMP character driver. From Mateusz Szafoni. + - STM32 F4: Implement DMA support for the STM32F4 I2C. From rg. + - STM32 F7: Add stm32 RNG support. This is copied from stm32l4. + Tested on STM32F746ZG board. From Juha Niskanen. + - STM32 L1: Add STM32L162VE to chip.h. From Juha Niskanen. + - STM32 F4: Add I2C3 SDA pin mapping for STM32F411. From no1wudi. + - STM32 L1: stm32_flash: Add EEPROM writing for STM32L15XX. From + Juha Niskanen. + - STM32 F7: Serial: Add interface to get uart_dev_t by USART number, + stm32_serial_get_uart. From Jussi Kivilinna. + - STM32 F4: Provide TIM5 definition for STM32F429. From Matias v01d. + - STM32 F0: Add an untested port of the F1 USB device to the STM32F0. + - STM32 F0: Add support for the STM32F09X family. From Juha + Niskanen. + - STM32 F0: Initial cut at I2C driver. Still a work in progress. + From Alan Carvalho de Assis. + - STM32 F33: Add OPAMP support. From Mateusz Szafoni. + - STM32 L4: stm32l4_i2c: Add I2C4 code. From Juha Niskanen. + - STM32 L4: Add GPIO_PORTI definition. From Juha Niskanen. + - STM32 F7 Serial: Allow configuring Rx DMA buffer size. From Jussi + Kivilinna. + - STM32 L4: Firewall for stm32l4x3xx. Not tested for any product + family, but now it at least compiles. L496 devices can have one bit + wider Volatile Data Segment. From Juha Niskanen. + - STM32 TIM: Add method to get timer width. Freerun timer: Use timer + width to get the correct clock rollover point. + - STM32 L4: Add internal flash write support. From Juha Niskanen. + - STM32 L4: Port stm32l4_serial_get_uart function from STM32F7. From + Juha Niskanen. + - STM32 Ethernet: Add support for KSZ8081 PHY interrupts. From + Sebastien Lorquet. + - STM32 F4: Add i2s driver. From Taras Drozdovsky. + - STM32 L4: Add IWDG peripheral. This is the same as for STM32 + except that prescale and reload can be changed after watchdog has + been started, as this seems to work on L4. From Juha Niskanen. + - STM32 F7: Add SPI DMA support. From Jussi Kivilinna. + + * STMicro STM32 Boards: + + - Support for the Particle Photon board was contributed by Simon + Piriou. The Photon board is based on a STM32F205G MCU with and on- + board BCM43362 WiFi chip that interfaces via the STM32's SDIO + interface. Board configuration support includes, in addition, + buttons, LEDS, IWDG, USB OTG HS, and procfs support. Configurations + available for nsh, usbnsh, and wlan configurations. + - Clicker2-STM32: Support for the Mikroelektronika Clicker 2 for + STM32 was added by Anthony Merlino. This board, along with the + MRF24J40 Click board is the platform used to deveop the IEEE + 802.15.4 support. The boad configuration includes the MRF24J40 + intialization logic and SPI support. Configurations exist for nsh, + knsh, usbnsh, and mrf24j40-radio. + - Nucleo_F334R8: Add ADC example. From Mateusz Szafoni. + - Nucleo-F334R8: Add COMP support. From Mateusz Szafoni. + - Nucleo-F334R8: Use new COMP driver. From Mateusz Szafoni. + - Adds USB host support to stm32f411-disco board. From Brian Webb. + - Add stm32f0discovery board support. From Alan Carvalho de Assis. + - Nucleo-F072RB: Add board configuration. + - Nucleo-F334R8: Add OPAMP support. From Mateusz Szafoni. + - Nucleo-F072RB: Add support for the I2C driver used by I2C tools. + - Nucleo-L496ZG: Add nucleo-l496zg board files. From Juha Niskanen. + - Nucleo-F091RC: Add nucleo-f091rc board files. From Juha Niskanen. + - Nucleo-L432KC: Add nucleo-l432kc board files. From Sebastien + Lorquet. + - Nucleo-L452RE: Add nucleo-l452re board files. From Juha Niskanen. + - stm32f103-miniumum: Add board support to use the Nokia 5110 + LCD display driver. From Alan Carvalho de Assis. + + * C Library/Header Files: + + - C library: Add strerror_r(). + - C Library: Add wcstoull(), swprintf(), wcstod(), wcstof(), wcstol(), + wcstold(), wcstoul(), wcstoll() functions. Add mbsnrtowcs() and + wcsnrtombs() (just returning success). Add mbtowc() and wctomb() to + C++ std namespace. From Alan Carvalho de Assis. + - C Library: Add ffsl(), ffsll(), fls(), flsl(), flsll() and use + GCC's __builtin_ctz/__builtin_clz for faster implementation of these. + From Jussi Kivilinna. + - fixedmath: Add square root and b32_t conversion operators. From + Jussi Kivilinna. + - locale.h: Add a bogus definition of locale_t. + - C library: Versions mbrlen and mbsrtowcs taken and adapted from + FreeBSD code (at https://github.com/freebsd/freebsd/). From Matias + v01d. + + * Build/Configuration System: + + - Include C++ library in 'make export'. From Alan Carvalho de Assis. + - configs: Remove all setenv.sh and setenv.bat files. Remove all + references to setenv.sh and setenv.bat from all config README files. + - Kconfig/deconfigs: Add CONFIG_ARCH_TOOLCHAIN_GNU to indicate that + the toolchain is based on GNU gcc/as/ld. This is in addition to the + CPU-specific versions of the same definition. + - Move prototype for up_cxxinitialize() from nuttx/include/nuttx/arch.h + to apps/include/platform/cxxinitialize.h. + + * Tools: + + - Add initialconfig.c so that perhaps in the future we will be able to + use this to generate a new configuration from scratch (rather than + having to derive new configurations from existing configurations). + NOTE: Not yet intregated into the build system. + + * NSH: apps/nshlib: + + - Added support for set [{+|-}{e|x|xe|ex}] [ ]. Set the + 'exit on error control' and/or 'print a trace' of commands when + parsing scripts in NSH. The settinngs are in effect from the point + of exection, until they are changed again, or in the case of the init + script, the settings are returned to the default settings when it + exits. Included child scripts will run with the parents settings and + changes made in the child script will effect the parent on return. + Use 'set -e' to enable and 'set +e' to disable (ignore) the exit + condition on commands. The default is -e. Errors cause script to + exit. Use 'set -x' to enable and 'set +x' to disable (silence) + printing a trace of the script commands as they are ececuted. The + default is +x. No printing of a trace of script commands as they are + executed. From David Sidrane. + - Print expanded variables if -x. From David Sidrane. + - ifconfig command: Extend ifconfig to support 6loWPAN. Adapt to + some changes in configuration variable usage. + - Network initialization: If IEEE802.11 selected use wlan0 instead of + eth0 for network device name. + - Network initialization: NSH now has configuration options to select + the wireless properties. It builds the configuration structure and + passes this to wpa_driver_wext_associate() so that it will set the + network as configured. + - Network initialization: Add a new option CONFIG_NSH_NETLOCAL that + will suppress some built in operations and will support manual + configuration of a wireless network through command line tools. + + * Examples/Tests: apps/examples: + + - examples/xbc_text: Adds a test program for the XBox One controller + driver. From Brian Webb. + - examples/ostest: Add a test of robust mutexes. + - examples/ostest: Add tests for pthread_rwlock. Adding tests to be + used to verify the pthread_rwlock lock works. From Mark Schulte. + - examples/ostest: Additional test for rwlock and one for cancel + cleanup handlers. From Juha Niskanen. + - examples/usrsocktest: Add application for USRSOCK testing. From + Jussi Kivilinna. + - examples/nettest: Adapt for use in testing 6loWPAN. + - examples/nettest: If doing loopback, but not using the official + loopback device, then use the server should use the configured client + IP address. + - examples/udpblaster: Several fixes to work with 6loWPAN. + - examples/udpblaster: Add logic to bind the local UDP socket to a + well-known address. + - examples/configdata: Add stacksize and priority. From Juha Niskanen. + + * Network Utilies: apps/netuils: + + - netutils/netlib: Add IEEE 802.11 wireless IOCTL wrappers. + - netutils/netlib: Add a helper function to convert a string to a + 6loWPAN node address. + - netlib and NSH: Add logic to get/set the IEEE802.15.4 PAN ID. + - netutils/dhcpc: Make the network device name a configuration + option. Was hardcoded to eth0 but may, instead, need to be wlan0. + - netutils/dhcpc: Remove hard-coded interface device. Now passed as + a parameter to dhcpc_open(). From Sebastien Lorquet. + + * Wireless Utilies: apps/wireless: + + - wireless/wapi: Port of Wapi wireless services. The original + depended on features not supported by NuttX: Removed logic that + depends on Linux netlink. Removed functionality that depended on + the Linux procfs: This includes only 1) listing of available + interfaces and 2) listing of all routes. + - wireless/wapi: Create command line Wapi application based on + Wapi sample code. + - wireless/wapi: wpa_driver_wext_associate() now accepts a + configuration parameter that can be used to specify the wireless + properties. + - wireless/wapi: Add basic wapi_event_stream_extract implementation. + From Simon Piriou. + - wireless/ieee802154: Add iwpan and i8sak tools. iwpan is similar + in concept to wapi. From Anthony Merlino (i8sak was originally + by Sebastien Lorquet). + - wireless/ieee802154/libmac: IEEE 802.15.4 MAC library. + - wireless/wext: Add drivers_wext from the WPA supplicant; Integrate + into NSH. From Simon Piriou. + + * System Unitilities (apps/system) + + - apps/system/dhcpc: Add a command to renew or establish a lease on an + IPv4 address. + - apps/system/ntpc: Add a command to start or stop the NTPC daemon. + - apps/system/ramtest: Make stacksize and priority conigurable. + + * Platform-Specific Support (apps/platform) + + - apps/platform: Create gnu/ subdirectory that contains the one and + only GNU C++ initialization function. Remove all other C++ + initialization functions. + +Bugfixes. Only the most critical bugfixes are listed here (see the +ChangeLog for the complete list of bugfixes and for additional, more +detailed bugfix information): + + * Core OS: + + - Priority inheritance: When CONFIG_SEM_PREALLOCHOLDERS==0, there is + only a single, hard-allocated holder structure. This is problem + because in sem_wait() the holder is released, but needs to remain in + the holder container until sem_restorebaseprio() is called. The call + to sem_restorebaseprio() must be one of the last things the + sem_wait() does because it can cause the task to be suspended. If in + sem_wait(), a new task gets the semaphore count then it will fail to + allocate the holder and will not participate in priority + inheritance. This fix is to add two hard-allocated holders in the + sem_t structure: One of the old holder and one for the new holder. + - Priority inheritance: sem_holder sem_findholder missing + inintalization of pholder. sem_findholder would fail and code + optimization covered this up. From David Sidrane. + - Partial Fix priority inheritance CONFIG_SEM_PREALLOCHOLDERS=0. From + David Sidrane. + - Priority inheritance: sem_boostholderprio prevent overrun of + pend_reprios. The second case rtcb->sched_priority <= + htcb->sched_priority did not check if there is sufficient space in + the pend_reprios array. From David Sidrane. + - lp_worker: Guard from pend_reprios overlow. From David Sidrane. + - Priority inheritance: Fixes improper restoration of base_priority in + the case of CONFIG_SEM_PREALLOCHOLDERS=0. The call to + sem_restorebaseprio_task context switches in the + sem_foreachholder(sem, sem_restoreholderprioB, stcb); call prior to + releasing the holder. So the running task is left as a holder as is + the started task. Leaving both slots filled thus failing to perform + the boost/or restoration on the correct tcb. This PR fixes this by + releasing the running task slot prior to reprioritization that can + lead to the context switch. To faclitate this, the interface to + sem_restorebaseprio needed to take the tcb from the holder prior to + the holder being freed. In the failure case where sched_verifytcb + fails it added the overhead of looking up the holder. There is also + the additional thunking on the foreach to get from holer to + holder->tcb. An alternate approach could be to leve the interface + the same and allocate a holder on the stack of sem_restoreholderprioB + copy the sem's holder to it, free it as is done in this pr and and + then pass that address sem_restoreholderprio as the holder. It could + then get the holder's tcb but we would keep the same sem_findholder + in sched_verifytcb. From David Sidrane. + - Priority inheritance: Fixes improper restoration of base_priority. + From David Sidrane. + - sem_holder: Indexing error. From David Sidrane. + + if (sem->holder[0].htcb != NULL || sem->holder[**1**].htcb != NULL) + - realloc(): When realloc() has to fall back to calling malloc(), size + including overhead was being provided to malloc(), causing a slightly + larger allocation than needed. Noted by initialkjc@yahoo.com. + - scheduler: Fix tg_flags check with GROUP_FLAG_NOCLDWAIT. From Masayuki + Ishikawa. + - scheduler: Fix CHILD_FLAG_EXITED in include/nuttx/sched.h. From + Masayuki Ishikawa. + - binfmt/elf: Fix offset value when calling elf_read() in + elf_symname(). From Masayuki Ishikawa. + - binfmt/elf: Fix offset value when calling elf_read() in + elf_sectname(). From Masayuki Ishikawa. + - There can be a failure in IOB allocation to some asynchronous + behavior caused by the use of sem_post(). Consider this scenario: + (1) Task A holds an IOB.  There are no further IOBs.  The value of + semcount is zero. Task B calls iob_alloc().  Since there are not + IOBs, it calls sem_wait().  The value of semcount is now -1. (2) + Task A frees the IOB.  iob_free() adds the IOB to the free list and + calls sem_post() this makes Task B ready to run and sets semcount to + zero NOT 1.  There is one IOB in the free list and semcount is zero. + When Task B wakes up it would increment the sem_count back to the + correct value. (3) But an interrupt or another task runs occurs + before Task B executes.  The interrupt or other tak takes the IOB off + of the free list and decrements the semcount.  But since semcount is + then < 0, this causes the assertion because that is an invalid state + in the interrupt handler. So I think that the root cause is that + there the asynchrony between incrementing the semcount. This change + separates the list of IOBs: Currently there is only a free list of + IOBs. The problem, I believe, is because of asynchronies due + sem_post() post cause the semcount and the list content to become out + of sync. This change adds a new 'committed' list: When there is a + task waiting for an IOB, it will go into the committed list rather + than the free list before the semaphore is posted. On the waiting + side, when awakened from the semaphore wait, it will expect to find + its IOB in the committed list, rather than free list. In this way, + the content of the free list and the value of the semaphore count + always remain in sync. + - binfmt: Fix .dtor memory allocation. From Masayuki Ishikawa. + + * File System/Block and MTD Drivers: + + - SmartFS: If whence is SEEK_END, the file offset shall be set to the + size of the file plus offset. Noted by eunb.song@samsung.com. + - mtd/progmem: Fix incorrect target address calculation. + progmem_read/write() is incorrectly calculating the target address, + expecting the offset argument is given in a block number. This is + completely wrong and as a result invalid flash region is accessed. + Byte-oriented read/write interfaces of mtd device accept the target + address in a byte offset, not a block number. From Heesub Shin. + - procfs: Fix wrong member IDs are displayed when 'cat + /proc//group/status'. From Nobutaka Toyoshima. + - procfs: Fix incorrect uptime with CONFIG_SYSTEM_TIME64. From + Masayuki Ishikawa. + - vfs/poll: round timeout up to next full tick. Calling poll() with + timeout less than half tick (thus MSEC2TICK(timeout) => 0) caused + returning error with EAGAIN. Instead of rounding timeout down, value + should be rounded up. Open Group spec for poll says: + "Implementations may place limitations on the granularity of timeout + intervals. If the requested timeout interval requires a finer + granularity than the implementation supports, the actual timeout + interval will be rounded up to the next supported value." From Jussi + Kivilinna. + - mtd/config: erase block between block read and write. From Juha + Niskanen. + - mtd: Build RAMTRON and AT45DB drivers only if selected. From Juha + Niskanen. + - mtd/config: Fix byte read interface test. From Juha Niskanen. + - mtd: Fix some unallocated and NULL pointer issues. rwb->wrflush and + rwb->wrmaxblocks in rwbuffer could get unallocated values from + ftl_initialize() in some configurations. Also fixes related assert: + + up_assert: Assertion failed at file:rwbuffer.c line: 643 + + that can happen with the following configuration: + + CONFIG_FTL_WRITEBUFFER=y + CONFIG_DRVR_WRITEBUFFER=y + # CONFIG_FS_WRITABLE is not set + + These problems are caused by CONFIG variable differences between the + buffer layers. TODO: This is not a perfect solution. readahead + support has similar issues. From Juha Niskanen. + - net procfs: Fix buffer corruption and refactor netdev_statistics.c. + From Masayuki Ishikawa. + - FAT: Fix 'Missing unlock' in fs_fat32.c. From Masayuki Ishikawa. + - VFS fdopen: Add missing file stream flags clearing. Clear file + stream structure regardless of config options. Structure clearing is + needed as previous use of stream list entry might leave fs_flags + set. From Harri Luhtala. + - mtd/smart: Fix use of uninitialized variable. From Jussi Kivilinna. + - mtd/w25.c: Enable short delay after sector/chip erase. From Jussi + Kivilinna. + - mtd/config: Add some error checks for I/O errors. From Juha + Niskanen. + + * Graphics/Graphic Drivers: + + - net procfs: Some long lines were being generated that cause buffer- + related problems and corrupted output. + + * Networking/Network Drivers: + + - Fixed wrong assert on udp dgram send. From Pascal Speck. + - TCP/IPv6: Fix a compile issue when IPv6, but not IPv4 is enabled. + - net/socket/accept: Fix building with CONFIG_NET_LOCAL_STREAM. From + Jussi Kivilinna. + - Argument of network device IOCTL should be unsigned long, just as + will all other IOCTL methods. + - net/socket: Fix cloning of local and raw sockets. From Jussi + Kivilinna. + - TCP: Wait for 3-Way Handshare before accept() returns. From Simon + Piriou. + - TCP: Send RST if applicaiton 'unlistens()' before we complete the + connection sequence. + - TCP: An RST received during the 3-way handshake requires a little + more clean-up. + - IPv6: Fix net_ipv6_pref2mask(). From Masayuki Ishikawa. + - network IOCTL commands: The only place in net/netdev/netdev_ioctl.c + where the interface state should change is for SIOCSIFFLAGS. The + other ones .. SIOCSIFADDR, SIOSLIFADDR, SIODIFADDR .. should not + change the link state. From Sebastien Lorquet. + - TCP: Fix tcp_findlistner() in dual stack mode. From Masayuki + Ishikawa. + + * Common Drivers: + + - Fix as5048b by adding missing frequency parameter. From Andreas + Bihlmaier. + - multiple fixes in nrf24l01 driver: (1) signal POLLIN if there is + already data in the FIFO, (2) send ETIMEDOUT to userspace after 2 + seconds if TX IRQ was not received, (3) handle FIFO overflow, (4) + handle invalid pipes/empty FIFO, and (5) multiple cosmetics (missing + static, duplicate define, missing \n). From Leif Jakob. + - input/mxt: Prevent overriding i2c transfer return value. + put_reg/get_reg function was overriding i2c transfer error code with + i2creset return value, that lead to OK status although actual + transfer failed. From Juha Niskanen. + - drivers/audio/wm8904: WM8904 has same problem as that fixed by Juha + Niskanen in the MaxTouch driver. + - UART 16550: Missing left parenthesis in function prototype. This is + Bitbucket Issue #41. + - USBMSC: Fix a wrong lun number issue. From Masayuki Ishikawa. + - drivers/i2c: Fix compile issues if CONFIG_DISABLE_PSEUDOFS_OPERATIONS + is enabled. + - drivers/serial: I discovered a problem in the file + drivers/serial/serial.c concerning the function uart_close(…). In the + case that a serial device is opened with the flag O_NONBLOCK the + function uart_close(…) blocks until all data in the buffer is + transmitted. The function close(…) called on an handle opened with + O_NONBLOCK should not block. The problem occurred with a CDC/ACM + device. From Stefan Kolb. + - drivers: Fix some bad NULL checks. From Juha Niskanen. + - drivers: Rename newly introduced up_i2creset to I2C_RESET. From + Juha Niskanen. + - drivers/bch: BCH character driver bch_ioctl() always returns -ENOTTY + for DIOC_GETPRIV command. It should returns OK if DIOC_GETPRIV + command succeeds. From EunBong Song. + - Replace sprintf() with snprintf() in pipe.c. From Nobutaka Toyoshima. + - drivers/bch: Fix 'Missing Unlock' in bchdev_driver.c. From Masayuki + Ishikawa. + - button_upper: Fix interrupt enabling for poll-events. From Jussi + Kivilinna. + - drivers/{sensors,usbmisc}: Fix uninitialized I2C frequency. From + Juha Niskanen. + + * ARM: + + - Set EABI stack alignment for all ARM architectures (remove OABI + code). From David Cabecinhas. + - Remove redundant interrupt stack coloring and OABI code. From David + Cabecinhas. + - Fix off-by-one interrupt stack allocation in 8-byte aligned + architectures. From David Cabecinhas. + + * ARMv6-M: + + - CONFIG_DEBUG_HARDFAULT should be available for Cortex-M0 too. + + * Microchip/Atmel SAM3/4 Drivers: + + - SAM3/4: Fixed configurations for TWI master. Obviously an + incomplete port from SAMA5. + + * Microchip/Atmel SAMv7 Drivers: + + - SAMV7: Watchdog: Fix Forbidden Window Value. According the Datasheet + the WDD Value is the lower bound of a so called Forbidden Window and + to disable this we have to set the WDD Value greater than or equal to + the WDV Value. This seems to be a bug in the datasheet. It looks + like we have to set it to a greater value than the WDV to really + disable this Thing. When triggering the Watchdog faster than the + (very slow) clock source of the Watchdog fires, this Forbidden Window + Feature resets the System if WDD equals to WDV. This Changeset + disables the Forbidden Window by setting the WDD Value to the Maximum + (0xfff) Value possible. From Frank Benkert. + - SAMV7 EMAC: Add conditional logic to account the fact that the + SAMV71 has 6 rather than 3 queues after version 1. From Ian McAfee. + + * NXP/Freescale Kinetis Drivers: + + - Kinetis: Fixed GPIO _PIN_OUTPUT_LOWDRIVE swapped with + _PIN_OUTPUT_OPENDRAIN. From David Sidrane. + - Ensure interrupts are back on BEFORE running code dependant on + clock_systimer. From David Sidrane. + - Kinetis k66, k64, k60, k40, k20: Pin mux configure all I2C signals as + Open Drain. The output structure of the GPIO for I2C needs to be + open drain. When left at the default, one can observe on a scope the + slave contending with the push-pull during the ACK. From David + Sidrane. + - Kinetis K66: Fixed TMP2_CH1 definition. From David Sidrane. + - Kinetis K66: Define ALT1 to match ref manual. From David Sidrane. + - Kinetis K66: GPIO and pin mux cleanup. From David Sidrane. + - Kinetis ADC: Various corrections and updates. From David Sidrane. + + * NXP/Freescale LPC43xx: + + - Add missing PINCONF_INBUFFER in several places of + lpc4310203050_pinconfig.h. From Andreas Bihlmaier. + - Fix logic in preprocessor checks and correct arguments to + lpc43_pin_config initialization. From Andreas Bihlmaier. + + * NXP/Freescale LPC43xx Drivers: + + - Fix logic error in lpc43_adc. From Andreas Bihlmaier. + - Use correct macro for irqid (fortunately both point to + LPC43_IRQ_EXTINT+18). From Andreas Bihlmaier. + - Actually write modified value to register. From Andreas Bihlmaier. + - Increase number of supported PWM channels from 4 to 6. From Andreas + Bihlmaier. + + * Silicon Labs EFM32 Drivers: + + - EFM32 I2C: Fix timeout calculation. From Masayuki Ishikawa. + + * STMicro STM32: + + - As discovered by dcabecinhas. This fix assume the 8 byte alignment + options for size stack size or this will overwrite the first word + after TOS. See + https://github.com/PX4/Firmware/issues/6613#issuecomment-285869778. + From David Sidrane. + - STM32 F7: In stm32_allocateheap.c There are 5 not 4 configurations. + From David Sidrane. + + * STMicro STM32 Drivers: + + - STM32, STM32 F7, STM32 L4: OTG host drivers: Do not do data toggle + if interrupt transfer is NAKed. Sugested by webbbn@gmail.com. + - Save elapsed time before handling I2C in stm32_i2c_sem_waitstop(). + This change follows the same logic as in previous fix to + stm32_i2c_sem_waitdone(). It is possible that a context switch + occurs after I2C registers are read but before elapsed time is saved + in stm32_i2c_sem_waitstop(). It is then possible that the registers + were read only once with "elapsed time" equal 0. When scheduler + resumes this thread it is quite possible that now "elapsed time" will + be well above timeout threshold. In that case the function returns + and reports a timeout, even though the registers were not read + "recently". Fix this by inverting the order of operations in the loop + - save elapsed time before reading registers. This way a context + switch anywhere in the loop will not cause an erroneous "timeout" + error. From Freddie Chopin. + - STM32, STM32 F7, and STM32 L4: Clone Freddie Chopin's I2C change to + similar STM32 I2C drivers. From David Sidrane. + - STM32: OTG host implementations of stm32_in_transfer() must obey the + polling interval for the case of isochronous and interrupt endpoints. + - STM32: Fix erase sector number for microcontrolers with more than 11 + sectors. Erase a sector from the second bank cause the bit 4 of SNB + being set but never unsed, so trying to erase a sector from the first + bank was acually eraseing a sector from the second bank. From José + Roberto de Souza. + - STM32: Make up_progmem thread safe. Writing to a flash sector while + starting the erase of other sector have a undefined behavior so lets + add a semaphore and syncronize access to Flash registers. But for + the semaphore to work it needs to be initialized so each board needs + call stm32_flash_initialize() on initialization, so to avoid runtime + problems it is only using semaphore and making it thread safe if + initialized, after all boards starts to call stm32_flash_initialize() + we can remove the boolean and the check. From José Roberto de Souza. + - STM32: Add workaround for flash data cache corruption on + read-while-write. This is a known hardware issue on some STM32 see + the errata of your model and if you make use of both memory banks you + should enable it. From José Roberto de Souza. + - STM32 Flash fixes. From José Roberto de Souza. + - STM32 Flash: Missing unlock on F1 HSI off path. From David Sidrane. + - STM32 F4 I2C: I needed to use DS3231, I remember that in past it + worked ok, but now for stm32f4xx is used another driver (chip + specific, stm32f40xxx_i2c.c) and DS3231 driver doesn't work. After + investigating a problem I found that I2C driver (isr routine) has a + few places there it sends stop bit even if not all messages are + managed. So, e.g., removing stm32_i2c_sendstop (#1744) and adding + stm32_i2c_sendstart after data reading helps to make DS3231 working. + From Alexander Oryshchenko; verified by David Sidrane. + - STM32 F7 Serial: Serial fix for dropped data: (1) Revert the + inherited dma bug from the stm32. see + https://bitbucket.org/nuttx/nuttx/commits/df9ae3c13fc2fff2c21ebdb098c520b11f43280d + for details. And (2) Most all CR1-CR3 settings can not be configured + while UE is true. Threfore we make all operation atomic and disable + UE and restore it's originalstate on exit. From David Sidrane. + - STM32 L1: Fix IWDG and WWDG debug mode stop for STM32L15XX. From + Juha Niskanen. + - STM32 F7: Fix UART7 and UART8 IFLOWCONTROL options. From Jussi + Kivilinna. + - STM32 F7: Add warning for RXDMA + IFLOWCONTROL combination. + Combination of RXDMA + IFLOWCONTROL does not work as one might + expect. Since RXDMA uses circular DMA-buffer, DMA will always keep + reading new data from USART peripheral even if DMA buffer underruns. + Thus this combination only does following: RTS is asserted on USART + setup and deasserted on shutdown and does not perform actual RTS + flow-control. Data loss can be demonstrated by doing long up_mdelay + inside irq critical section and feeding data to RXDMA+IFLOWCONTROL + UART. From Jussi Kivilinna. + - STM32 F7 Serial: Do not stop processing input in SW flow-control + mode. From Jussi Kivilinna. + - STM32 L4 DMA: Correct bad channel definition. From Sebastien Lorquet. + - STM32 F7: Warn if no DMA2 configured when using ADC with DMA. Also + correct ADC channel numbers that DMA callback passes to upper half + driver. From Juha Niskanen. + - STM32 F7 ADC: Do not override ADCPRE_DIV when measuring + internal voltage. From Juha Niskanen. + - STM32 L4: Don't think these chips have DPFPU, DTCM or ITCM. From + Juha Niskanen. + - STM32 F7 Flash: macro naming errors, there is no FLASH_CONFIG_F for + F7. From Juha Niskanen. + - STM32 L4: stm32l4x6xx_pinmap: Update I2C4 and DCMI pins. From Juha + Niskanen. + - STM32 L4: stm32l4_i2c: change wrong macro to CONFIG_I2C_POLLED. From + Juha Niskanen. + - Fix STM32F7 I2C interrupt handler. From Jussi Kivilinna. + - STM32: Serial Allow configuring Rx DMA buffer size. From David + Sidrane. + - STM32 CAN: I had the problem that the transmit FIFO size (= actual + elements in FIFO) was slowly increasing over time, and was full after + a few hours. The reason was that the code hit the line + "canerr("ERROR: No available mailbox\n");" in stm32_cansend, so + can_xmit thinks it has sent the packet to the hardware, but actually + has not. Therefore the transmit interrupt never happens which would + call can_txdone, and so the size of the FIFO size does not decrease. + The reason why the code actually hit the mentioned line above, is + because stm32can_txready uses a different (incomplete) condition than + stm32can_send to determine if the mailbox can be used for sending, + and thus can_xmit forwards the packet to stm32can_send. + stm32can_txready considered mailboxes OK for sending if the mailbox + was empty, but did not consider that mailboxes may not yet be used if + the request completed bit is set - stm32can_txinterrupt has to + process these mailboxes first. Note that I have also modified + stm32can_txinterrupt - I removed the if condition, because the CAN + controller retries to send the packet until it succeeds. Also if the + condition would not evaluate to true, can_txdone would not be called + and the FIFO size would not decrease also. From Lederhilger Martin. + - STM32 Serial: Fix freezing serial port. Serial interrupt + enable/disable functions do not disable interrupts and can freeze + device when serial interrupt is received while execution is at those + functions. Trivially triggered with two or more threads write to + regular syslog stream and to emergency stream. In this case, freeze + happens because of mismatch of priv->ie (TXEIE == 0) and actually + enabled interrupts in USART registers (TXEIE == 1), which leads to + unhandled TXE interrupt and causes interrupt storm for USART. From + Jussi Kivilinna. + - STM32 I2C: Make private symbols static. From Juha Niskanen. + - STM32 L4 GPIO: Put back EXTI line source selection. From Juha + Niskanen. + - STM32 L4 RTC: Store RTC MAGIC to backup reg, not to address zero. + From Juha Niskanen. + + * STMicro STM32 Boards: + + - Disable serial console on stm32f103-minimum usbnsh example project + config. Devices enumerate after this change. From Bob Ryan. + - Nucleo-144: Default for choice in Kconfig was not one of the + possible choices. + - Nucleo-F4X1RE User LEDS: Issue #51 reports compilation problems with + stm32_userled.c. Reported by Gappi92. + + * TI Tiva Drivers: + + - Tiva I2C: Correct an error in conditional compilation. + - Tiva SSI: Resolves issue 52 'Copy-Paste error in + tiva_ssibus_initialize()' submitted by Aleksandr Kazantsev. + + * C Library/Header Files: + + - C Library vsnprintf(): Fix precision for string formatting. Fixes + use of format precision to truncate input string. From Jussi + Kivilinna. + - C Library vsnprintf(): If size is zero, then vsnprintf() should + return the size of the required buffer without writing anything. + From Jussi Kivilinna. + - C Library netdb: in dns_query_callback, ret != -EADDRNOTAVAIL + condition consumes error returns including EAGAIN in this case, + dns query retransmission doesn't work. From Ritajina. + - C Library netdb: Fix time info in lib_dnscache.c. From Masayuki + Ishikawa. + - C Library netdb: Fix bugs in lib_gethostbynamer.c. This fix sets + h_name in struct hostent returned by gethostbyname(). From Masayuki + Ishikawa. + - C Library Defect Workaround: replace '%6.6u' format with an + equivalent '%06u'. From Tomasz Wozniak. + + * Tools + + - Fix mksyscall host binary name. From Alan Carvalho de Assis. + + * Applications (apps/) + + - Fix some calls to task_create(): argv[0] is the first parameter, not + the name of the task. + - Bitbucket Issue 5: I found an unexpected behavior in apps/ + configuration generation. Adding external symbolic link in apps/ + directory and using Make.defs for Kconfig generation, Kconfig file + has a wrong path in the source argument. It contains original dir + path outside of the source tree instead path to sub-directory in + apps/. The problem is connected with make/system symbolic link path + resolution. Corrected by a patch submitted by Artur Madrzak with + Issue 5. + - apps/: Make more globals static to avoid name clashes. From Juha + Niskanen. + + * NSH: apps/nshlib: + + - NSH library: In nsh_argexand(), if CONFIG_NSH_ARGCAT is defined but + CONFIG_NSH_CMDPARMS defined and/or CONFIG_DISABLE_ENVIRON not + defined, then there is a situation that causes an infinite loop in + the parser. Noted by Freddie Chopin. + - NSH library: Fix building when CONFIG_NET_USRSOCK enabled with other + link-layers. From Jussi Kivilinna. + - NSH library: Fix some warnings about integer/pointer casts of + different sizes (probably only effects 64-bit simulation). + - NSH library: Fix open flags in nsh_codeccmd.c. From Masayuki + Ishikawa. + - I need to look at the registers that are at or around 0xe000ef90. + Using mw and xd, I see that nsh does not support pointers greater + than 0x7fffffff. A quick look at the source shows that the pointers + for those two commands are set with calls to strtol() rather than + strtoul(). Changing the two pointer-setting instances to strtoul() + fixes the problem, at least for my architecture/config. From Ian + McAfee. + - NSH library: Fix a resource leak in cmd_hexdump(). From Nobutaka + Toyoshima. + + * Examples/Tests: apps/examples: + + - apps/examples/hidkbd: Remove call to arch_usbhost_initialize(). + That is violation of the OS interfacing rules and will no longer be + supported. USB host should be initialized as part of the normal + board bring-up logic as with any other devices and should not involve + illegal calls from applications into the OS. + - apps/examples/usbterm: Removed because it is not very useful and + because it can be configured to use an illegal call into the OS. + - examples/mm: Fix Makefile. Built-in was not being registered. + - examples/hidkbd: Add some missing configuration settings. + - examples/random: Avoid stack overflows. From Juha Niskanen. + - examples/nettest: Fix an error in pre-processor expression. + - examples/mtdpart: Prevent part array overflow. mtdpart examples + create partions and allocate from 1 index not a 0 index to part[] + array. This cause buffer overflow for part array. This change fixes + this problem. From EunBong Song. + - examples/can: Fix can example app to print data when + CONFIG_EXAMPLE_CAN_READ is defined. From Alan Carvalho de Assis. + + * Network Utilies: apps/netuils: + + - Not a clean fix, but at least makes DHCP working with + CONFIG_NETDEV_MULTINIC. From Andreas Bihlmaier. + - Ensure netlib will not be broken when setip will not bring the + network up anymore. From Sebastien Lorquet. + + * CAN Utilies: apps/canutils: + + - Fix libcanard github download link to get it compiling correctly. + From Alan Carvalho de Assis. + - Fix to use the new canardInit() function. From Alan Carvalho de + Assis. + + * System Unitilities (apps/system) + + - system/dhcpc: Add missing argument of fprintf. + + * Tools (apps/tools): + + - The dedicated windows tool at tools/mkkconfig.bat uses $APPSDIR, + which is not a windows shell variable, and is left uninitialized, but + in fact should be the current directory. From Sebastien Lorquet. -- GitLab From ac93d4bda9c507affc6bb52b9ff60fcb2e31b711 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 5 Jun 2017 15:12:37 -0600 Subject: [PATCH 919/990] Update Documentation in preparation for 7.21 release. --- ChangeLog | 2 +- Documentation/NuttX.html | 237 +++++++++++++++++++++++++++++++++++---- ReleaseNotes | 4 +- 3 files changed, 220 insertions(+), 23 deletions(-) diff --git a/ChangeLog b/ChangeLog index 8d2f6deea9..991873f17b 100755 --- a/ChangeLog +++ b/ChangeLog @@ -14092,7 +14092,7 @@ * usbhost_cdcacm: Fix tx outbuffer overflow and remove now invalid assert. From Janne Rosberg (2017-03-07). -7.21 2017-06-06 Gregory Nutt +7.21 2017-06-05 Gregory Nutt * tools/kconfig2html: Need to increase the maximum number of default values (2017-03-08). diff --git a/Documentation/NuttX.html b/Documentation/NuttX.html index 1491d3b2fe..2fe4d5a538 100644 --- a/Documentation/NuttX.html +++ b/Documentation/NuttX.html @@ -8,7 +8,7 @@

    NuttX RTOS

    -

    Last Updated: March 8, 2017

    +

    Last Updated: June 5, 2017

    @@ -317,7 +317,7 @@

    -

  • POSIX/ANSI-like task controls, named message queues, counting semaphores, clocks/timers, signals, pthreads, cancellation points, environment variables, filesystem.
  • +
  • POSIX/ANSI-like task controls, named message queues, counting semaphores, clocks/timers, signals, pthreads, robust mutexes, cancellation points, environment variables, filesystem.
  • @@ -772,6 +772,14 @@

    + +
    + +

    +

  • User space stacks.
  • +

    + +
    @@ -792,7 +800,23 @@

    -

  • DNS name resolution.
  • +
  • DNS name resolution / NetDB
  • +

    + + + +
    + +

    +

  • IEEE 802.11 FullMac
  • +

    + + + +
    + +

    +

  • IEEE 802.15.4 MAC + 6loWPAN
  • @@ -1339,11 +1363,11 @@

    Released Versions

    In addition to the ever-changing GIT repository, there are frozen released versions of NuttX available. - The current release is NuttX 7.20. - NuttX 7.20 is the 120th release of NuttX. - It was released on March 8, 2016, and is available for download from the + The current release is NuttX 7.21. + NuttX 7.21 is the 121st release of NuttX. + It was released on June 5, 2016, and is available for download from the Bitbucket.org website. - Note that the release consists of two tarballs: nuttx-7.20.tar.gz and apps-7.20.tar.gz. + Note that the release consists of two tarballs: nuttx-7.21.tar.gz and apps-7.21.tar.gz. Both may be needed (see the top-level nuttx/README.txt file for build information).

    @@ -1352,7 +1376,7 @@ +
  • Infineon + +
  • Intel
  • STMicroelectronics (Continued)
      +
    • STMicro STM32F4x1 (STM32 F4 family, ARM Cortex-M4)
    • +
    • STMicro STM32F410 (STM32 F4 family, ARM Cortex-M4)
    • STMicro STM32F407x (STM32 F4 family, ARM Cortex-M4)
    • STMicro STM32 F427/F437 (STM32 F4 family, ARM Cortex-M4)
    • STMicro STM32 F429 (STM32 F4 family, ARM Cortex-M4)
    • STMicro STM32 F446 (STM32 F4 family, ARM Cortex-M4)
    • STMicro STM32 F46xx (STM32 F4 family, ARM Cortex-M4)
    • +
    • STMicro STM32 L4x2 (STM32 F4 family, ARM Cortex-M4)
    • STMicro STM32 L476 (STM32 F4 family, ARM Cortex-M4)
    • +
    • STMicro STM32 L496 (STM32 F4 family, ARM Cortex-M4)
    • STMicro STM32 F745/F746 (STM32 F7 family, ARM Cortex-M7)
    • STMicro STM32 F756 (STM32 F7 family, ARM Cortex-M7)
    • STMicro STM32 F76xx/F77xx (STM32 F7 family, ARM Cortex-M7)
    • @@ -2792,7 +2825,7 @@ nsh>

        - The STM32L-Discovery and 32L152CDISCOVERY kits are functionally equivalent. + The STM32L-Discovery and STM32L152C DISCOVERY kits are functionally equivalent. The difference is the internal Flash memory size (STM32L152RBT6 with 128 Kbytes or STM32L152RCT6 with 256 Kbytes). Both boards feature:

        @@ -2807,6 +2840,7 @@ nsh>

        STATUS. Initial support for the STM32L-Discovery was released in NuttX-6.28. + Addition (architecture-only) support for the STM32L152xC family was added in NuttX-7.21. This initial support includes a configuration using the NuttShell (NSH) that might be the basis for an application development. A driver for the on-board segment LCD is included as well as an option to drive the segment LCD from an NSH "built-in" command. As of this writing, a few more things are needed to make this a more complete port: 1) Verfication of more device drivers (timers, quadrature encoders, PWM, etc.), and 2) logic that actually uses the low-power consumption modes of the EnergyLite part. @@ -2855,6 +2889,44 @@ nsh>

        + + +
        +
        + + +
        + +

        + STMicro STM32F0xx (STM32 F0, ARM Cortex-M0). + Support for the STM32 F0 family was contributed by Alan Carvalho de Assis in NuttX-7.21. + There are ports to three different boards in this respository: +

        +
          +
        • + STM32F0-Discovery + This board features the STM32 2F051R8 and was used by Alan to produce the initial STM32 F0 port. + However, its very limited 8KB SRAM makes this port unsuitable for for usages. + Contributed by Alan Carvalho de Assis in NuttX-7.21. +
        • +
        • + Nucleo-F072RB + With 16KB of SRAM the STM32 F072RB makes a much more usable platform. +
        • +
        • + Nucleo-F091RC + With 32KB of SRAM the STM32 F091RC this board is a great match for NuttX. + Contributed by Juha Niskanen in NuttX-7.21. +
        • +
        +

        STATUS: + In this initial release, the level of support for the STM32 F0 family is minimal. + Certainly enough is in place to support a robust NSH configuration. + There are also unverified I2C and USB device drivers available in NuttX-7.21. +

        + + +

        @@ -3176,11 +3248,18 @@ nsh>

        STMicro STM32F205 (STM32 F2 family). - Architecture only support for the STM32F205RG was contributed as an anonymous contribution in NuttX-7.10 + Architecture only support for the STM32F205RG was contributed as an anonymous contribution in NuttX-7.10. +

        +

        + Particle.io Phone. + Support for the Particle.io Photon board was contributed by Simon Pirious in NuttX-7.21. + The Photon board features the STM32F205RG MCU. + The STM32F205RG is a 120 MHz Cortex-M3 operation with 1Mbit Flash memory and 128kbytes. + The board port includes support for the on-board Broadcom BCM43362 WiFi and fully usable FullMac network support.

          STATUS: - There are currently on board configurations for any board using the STM32F205. + In addition to the above-mention WiFI support, the Photon board support includes buttons, LEDS, IWDG, USB OTG HS, and procfs support. Configurations available for nsh, usbnsh, and wlan configurations. See the Photon https://bitbucket.org/nuttx/nuttx/src/master/configs/photon/README.txt" target="_blank">README file for additional information. @@ -3481,6 +3560,26 @@ nsh> ARM Cortex-M4. + + +
          + +

          + Infineon XMC45xx. + An initial but still incomplete port to the XMC4500 Relax board was released with NuttX-7.21 (although it is not really ready for prime time). + Much is functional but there are still some issues with the output to the NSH serial console. +

          +

          + This initial porting effort uses the Infineon XMC4500 Relax v1 board as described on the manufacturer's website. + The current status of the board is available in the board README file +

          + + + + +
          +
          +
          @@ -3499,6 +3598,7 @@ nsh>
        +

        @@ -3711,6 +3811,7 @@ nsh>

        +

        @@ -3719,26 +3820,53 @@ nsh>

        - STMicro STM32401x (STM32 F4 family). + STMicro STM324x1 (STM32 F4 family).

          Nucleo F401RE. - This port uses the STMicro Nucleo F401RE board featuring the STM32F104RE MCU. - Refer to the STMicro web site for further information about this board. + This port uses the STMicro Nucleo F401RE board featuring the STM32F401RE MCU. + Refer to the STMicro web site for further information about this board. +

          +

          + Nucleo F411RE. + This port uses the STMicro Nucleo F411RE board featuring the STM32F411RE MCU. + Refer to the STMicro web site for further information about this board.

          STATUS:

          • NuttX-7.2 The basic port for STMicro Nucleo F401RE board was contributed by Frank Bennett. +
          • +
          • NuttX-7.6 + The basic port for STMicro Nucleo F401RE board was added by Serg Podtynnyi. +
          • - Refer to the NuttX board README file for further information. + Refer to the NuttX board README file for further information.

          + + +
          +
          + + +
          + +

          + STMicro STM32410 (STM32 F4 family). +

          +

            +

            + Architecture-only support was contributed to NuttX-7.21 by Gwenhael Goavec-Merou. +

            + + +

            @@ -3867,6 +3995,20 @@ nsh> Support for the Olimex STM32 P407 development board appeared in NuttX-7.19. See the NuttX board README file for further information about the NuttX port.

            +

            + MikroElektronika Clicker2 for STM32. + This is yet another board supported by NuttX that uses the same STM32F407VGT6 MCU as does the STM32F4-Discovery board. + This board has been used primarily with the MRF24J40 Click board for the development of IEEE 802.15.4 MAC and 6loWPAN support. +

            + See the Mikroelektronika website for more information about this board and the NuttX board README file for further information about the NuttX port. +

            +
              +

              + STATUS: + The basic port for the Clicker2 STM32 was contributed by Anthony Merlino and was first released in NuttX-7.21. + All compatible drivers for the STM32 F4 family may be used with this board as well. +

              +
            @@ -4041,6 +4183,61 @@ nsh> + +
            +
            + + +
            + +

            + STMicro STM32 L4x2. + Architecture support for STM32 L4x2 family was contributed by Juha Niskanen in NuttX-7.21. + Two boards are currently supported. +

            +
              +
            • +

              + Nucleo-L432KC. + Board support for the STMicro Nucleo-L432KC board from ST Micro was contributed by JSebastien Lorquet in NuttX-7.21. See the STMicro website and the board README file for further information. +

              +
            • +
            • +

              + Nucleo-L452RE. + Board support for the STMicro Nucleo-L452RE board from ST Micro was contributed by Juha Niskanen in NuttX-7.21. See the STMicro website and the board README file for further information. +

              +
            • +
            +

            + See also the status above for the STM32 L476 most of which also applies to these parts. +

            + + + + +
            +
            + + +
            + +

            + STMicro STM32 L496. + Architecture support for STM32 L496 was contributed by Juha Niskanen along with board support for the Nucleo-L496ZG in NuttX-7.21: +

            +
              +
            • +

              + Nucleo-L496ZG. + Board support for the STMicro Nucleo-L496ZG board from ST Micro was contributed by Juha Niskanen in NuttX-7.21. See the STMicro website and the board README file for further information. + See also the status above for the STM32 L476 most of which also applies to this part. +

              +
            • +
            + + +

            diff --git a/ReleaseNotes b/ReleaseNotes index 2d338a9912..ee3b1e2418 100644 --- a/ReleaseNotes +++ b/ReleaseNotes @@ -2025,7 +2025,7 @@ standard I/O buffer flushing. See the ChangeLog for further details. NuttX-6.4 --------- -The 71st release of NuttX, Version 6.4, was made on June 6, 2011 +The 71st release of NuttX, Version 6.4, was made on June 5, 2011 and is available for download from the SourceForge website. The 6.4 release includes several new features: @@ -13762,7 +13762,7 @@ Additional new features and extended functionality: - Change STM32 tickless to use only one timer. From Konstantin Berezenko. - - STM3 2F7: Add support for LSE RTC and enable RTC subseconds. From + - STM32 F7: Add support for LSE RTC and enable RTC subseconds. From Jussi Kivilinna. - STM32 L1: stm32l15xx_rcc: Add support for using MSI as system clock. From Juha Niskanen. -- GitLab From 9120a78ee37ea3bd494c0f3238455875df455ebd Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Tue, 6 Jun 2017 06:41:17 -0600 Subject: [PATCH 920/990] Documentation: add hexdump args, fix ln cmd, STM32L status, typos --- Documentation/NuttShell.html | 124 ++++++++++++++++-------------- Documentation/NuttX.html | 39 ++++++---- Documentation/NuttxUserGuide.html | 9 --- 3 files changed, 91 insertions(+), 81 deletions(-) diff --git a/Documentation/NuttShell.html b/Documentation/NuttShell.html index af8eeba20b..5ee579995f 100644 --- a/Documentation/NuttShell.html +++ b/Documentation/NuttShell.html @@ -8,7 +8,7 @@

            NuttShell (NSH)

            -

            Last Updated: April 5, 2017

            +

            Last Updated: June 6, 2017

            @@ -779,7 +779,7 @@ nsh>

            Optional Syntax Extensions - Because these features commit significant resources, it is disabled by default. + Because these features commit significant resources, they are disabled by default.

            • @@ -804,7 +804,7 @@ set BAR 123 set FOOBAR ABC_${FOO}_${BAR}
            would set the environment variable FOO to XYZ, BAR to 123 and FOOBAR to ABC_XYZ_123. - If CONFIG_NSH_ARGCAT is not selected, then a slightly small FLASH footprint results but then also only simple environment variables like $FOO can be used on the command line. + If CONFIG_NSH_ARGCAT is not selected, then a slightly smaller FLASH footprint results but then also only simple environment variables like $FOO can be used on the command line.
          @@ -820,7 +820,7 @@ set FOOBAR ABC_${FOO}_${BAR} An if-then[-else]-fi construct is also supported in order to support conditional execution of commands. This works from the command line but is primarily intended for use within NSH scripts - (see the sh commnd). The syntax is as follows: + (see the sh command). The syntax is as follows:

             if <cmd>
            @@ -1058,7 +1058,7 @@ mount -t vfat /dev/ram1 /tmp
               All of the startup-behavior is contained in rcS.template.  The
               role of mkromfsimg.sh is to (1) apply the specific configuration
               settings to rcS.template to create the final rcS, and (2) to
            -  generate the header file nsh_romfsimg.h containg the ROMFS
            +  generate the header file nsh_romfsimg.h containing the ROMFS
               file system image.
             

            @@ -1139,7 +1139,7 @@ addroute <target> <netmask> <router>

            Synopsis. This command adds an entry in the routing table. - The new entry will map the IP address of a router on a local network(<router>) to an external network characterized by the <target> IP address and a network mask <netmask> + The new entry will map the IP address of a router on a local network (<router>) to an external network characterized by the <target> IP address and a network mask <netmask>

            Example: @@ -1274,7 +1274,7 @@ cat <path> [<path> [<path>

          Synopsis. - This command copies and concatentates all of the files at <path> + This command copies and concatenates all of the files at <path> to the console (or to another file if the output is redirected).

          @@ -1425,7 +1425,7 @@ nsh> dd if=/dev/zero of=/dev/ram0
      • - Read from a block devic, write to a character device. This + Read from a block device, write to a character device. This will read the entire block device and dump the contents in the bit bucket.
      • @@ -1564,7 +1564,7 @@ exit Synopsis. Exit NSH. Only useful for the serial front end if you have started some other tasks (perhaps using the exec command) and you would like to have NSH out of the - way. For the telnet front-end, exit terminates the telenet session. + way. For the telnet front-end, exit terminates the telnet session.

        @@ -1638,7 +1638,7 @@ get [-b|-n] [-f <local-path>] -h <ip-address> <remote-path> @@ -1686,12 +1686,25 @@ help [-v] [<cmd>]

        Command Syntax:

          -hexdump <file or device>
          +hexdump <file or device> [skip=<bytes>] [count=<bytes>]
           

        Synopsis. Dump data in hexadecimal format from a file or character device.

        +
          -b|-n - Selects either binary ("octet") or test ("netascii") transfer + Selects either binary ("octet") or text ("netascii") transfer mode. Default: text.
          + + + + + + +
          skip=<bytes>Will skip <bytes> number of bytes from the beginning. +
          count=<bytes>Will stop after dumping <bytes> number of bytes. +
        +

        +The skip and count options are only available if CONFIG_NSH_CMDOPT_HEXDUMP is defined in the NuttX configuration. +

        @@ -1707,7 +1720,7 @@ ifconfig [nic_name [<ip-address>|dhcp]] [dr|gw|gateway <dr-address>]

        Synopsis. - Multiple forms of the ifconfigcommand are supported: + Multiple forms of the ifconfig command are supported:

        1. @@ -1880,7 +1893,7 @@ nsh>

          NOTE: NuttX does not support a FULL POSIX signalling system. - Standard signals like SIGCHLD, SIGINTR, SIGKILL, etc. do not exist in NuttX and sending those signal may not have the result that you expect. + Standard signals like SIGCHLD, SIGINTR, SIGKILL, etc. do not exist in NuttX and sending those signals may not have the result that you expect. Rather, NuttX supports only what are referred to as POSIX real-time signals. These signals may be used to communicate with running tasks, may be use to waiting waiting tasks, etc. But, as an example, kill -9 (SIGKILL) will not terminate a task. @@ -1942,22 +1955,22 @@ losetup d <dev-path>

        -

        2.30 List to a File or Directory (ln)

        +

        2.30 Link to a File or Directory (ln)

        Command Syntax:

          -link [-s] <target> <link>
          +ln [-s] <target> <link>
           

        Synopsis. - The link command will create a new symbolic link at <link> for the existing file or directory, <target>. - This implementation is simplied for use with NuttX in these ways: + The ln command will create a new symbolic link at <link> for the existing file or directory, <target>. + This implementation is simplified for use with NuttX in these ways:

          -
        • Links may be created only within the NuttX top-level, pseudo file system. +
        • Links may be created only within the NuttX top-level, pseudo filesystem. No file system currently supported by NuttX provides symbolic links.
        • For the same reason, only soft links are implemented.
        • File privileges are ignored.
        • @@ -2073,20 +2086,19 @@ mw <hex-address>[=<hex-value>][ <hex-byte-count>]

            - + - + - +
            <hex-address>.<hex-address> Specifies the address to be accessed. The current value at that address will always be read and displayed.
            <hex-address>=<hex-value>.<hex-address>=<hex-value> Read the value, then write <hex-value> to the location.
            <hex-byte-count>.<hex-byte-count> Perform the mb, mh, or mw operation on a total - of <hex-byte-count> bytes, increment the <hex-address> appropriately - after each access + of <hex-byte-count> bytes, increment the <hex-address> appropriately after each access.

          Example:

          @@ -2307,8 +2319,8 @@ mount -t <fstype> [-o <options>] <block-device> <dir- If no parameters are provided on the command line after the mount command, then the mount command will enumerate all of the current mountpoints on the console.

          - If the mount parameters are provied on the command after the mount command, then the mount command will mount a file system in the NuttX pseudo-file system. - mount' performs a three way association, binding: + If the mount parameters are provided on the command after the mount command, then the mount command will mount a file system in the NuttX pseudo-file system. + mount performs a three way association, binding:

          1. File system. @@ -2335,7 +2347,7 @@ mount -t <fstype> [-o <options>] <block-device> <dir-

            After the volume has been mounted in the NuttX pseudo filesystem, - it may be access in the same way as other objects in thefile system. + it may be access in the same way as other objects in the file system.

            Examples:

            Using mount to mount a file system:

            @@ -2527,7 +2539,7 @@ put [-b|-n] [-f <remote-path>] -h <ip-address> <local-path> -b|-n - Selects either binary ("octet") or test ("netascii") transfer + Selects either binary ("octet") or text ("netascii") transfer mode. Default: text. @@ -2712,10 +2724,7 @@ set [{+|-}{e|x|xe|ex}] [<name> <value>]

        Synopsis. - Set the environment variable <name> to the string <value> and or set NSH - parser control options. For example, - - For example, + Set the environment variable <name> to the string <value> and or set NSH parser control options. For example,

           nsh> echo $foobar
          @@ -2728,7 +2737,7 @@ nsh>
           
           

          Set the 'exit on error control' and/or 'print a trace' of commands when parsing - scripts in NSH. The settinngs are in effect from the point of exection, until + scripts in NSH. The settings are in effect from the point of execution, until they are changed again, or in the case of the init script, the settings are returned to the default settings when it exits. Included child scripts will run with the parents settings and changes made in the child script will effect the @@ -2740,9 +2749,8 @@ nsh>

          Use 'set -x' to enable and 'set +x' to disable (silence) printing a trace of the script - commands as they are ececuted. - The default is +x. No printing of a trace of script commands as they are executed. - + commands as they are executed. + The default is +x: no printing of a trace of script commands as they are executed.

          Example 1 - no exit on command not found @@ -2757,16 +2765,16 @@ nsh> notacommand
        - Example 3 - will exit on command not found, and print a trace of the script commmands + Example 3 - will exit on command not found, and print a trace of the script commands
               set -ex
           
        - Example 4 - will exit on command not found, and print a trace of the script commmands + Example 4 - will exit on command not found, and print a trace of the script commands and set foobar to foovalue.
               set -ex foobar foovalue
          -    nsh> echo $foobar
          +    nsh> echo $foobar
               foovalue
           
        @@ -2855,8 +2863,7 @@ nsh> time "sleep 2" nsh>

      - The additional 10 millseconds in this example is due to the way that the sleep command works: It always waits one system clock tick longer than requested and this test setup used a 10 millisecond periodic system - timer. + The additional 10 milliseconds in this example is due to the way that the sleep command works: It always waits one system clock tick longer than requested and this test setup used a 10 millisecond periodic system timer. Sources of error could include various quantization errors, competing CPU usage, and the additional overhead of the time command execution itself which is included in the total.

      @@ -2949,7 +2956,7 @@ uname [-a | -imnoprsv] -n - Print the network node hostname (only availabel if CONFIG_NET=y) + Print the network node hostname (only available if CONFIG_NET=y) @@ -3167,7 +3174,7 @@ nsh>

      - Note that in addition to general NuttX configuation settings, each NSH command can be + Note that in addition to general NuttX configuration settings, each NSH command can be individually disabled via the settings in the rightmost column. All of these settings make the configuration of NSH potentially complex but also allow it to squeeze into very small memory footprints. @@ -3336,13 +3343,13 @@ nsh> ln - CONFIG_NFILE_DESCRIPTORS > 0 - CONFIG_NSH_DISABLE_LL + CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_PSEUDOFS_SOFTLINKS + CONFIG_NSH_DISABLE_LN ls CONFIG_NFILE_DESCRIPTORS > 0 - CONFIG_NSH_DISABLE_LS && CONFIG_PSEUDOFS_SOFTLINKS + CONFIG_NSH_DISABLE_LS lsmod @@ -3441,6 +3448,11 @@ nsh> !CONFIG_DISABLE_ENVIRON && CONFIG_NFILE_DESCRIPTORS > 0 CONFIG_NSH_DISABLE_PWD + + readlink + CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_PSEUDOFS_SOFTLINKS + CONFIG_NSH_DISABLE_READLINK + reboot CONFIG_BOARD_RESET @@ -3488,7 +3500,7 @@ nsh> time -   +   CONFIG_NSH_DISABLE_TIME @@ -3498,7 +3510,7 @@ nsh> uname - br +   CONFIG_NSH_DISABLE_UNAME @@ -3547,7 +3559,7 @@ nsh>

      1 Because of hardware padding, the actual required packet size may be larger
      2 - Special TFTP server start-up optionss will probably be required to permit + Special TFTP server start-up options will probably be required to permit creation of files for the correct operation of the put command.
      3 CONFIG_FS_READABLE is not a user configuration but is set automatically @@ -3837,7 +3849,7 @@ set FOOBAR ABC_${FOO}_${BAR} CONFIG_NSH_TELNET - If CONFIG_NSH_TELNET is set to y, then a TELENET + If CONFIG_NSH_TELNET is set to y, then a TELNET server front-end is selected. When this option is provided, you may log into NuttX remotely using telnet in order to access NSH. @@ -3932,7 +3944,7 @@ set FOOBAR ABC_${FOO}_${BAR} CONFIG_NSH_IOBUFFER_SIZE Determines the size of the I/O buffer to use for sending/ - receiving TELNET commands/reponses + receiving TELNET commands/responses @@ -4364,7 +4376,7 @@ struct cmdmap_s That last string is what is printed when enter "nsh> help".

      - So, for you sample commnd, you would add the following the to the g_cmdmap[] table: + So, for you sample command, you would add the following the to the g_cmdmap[] table:

         { "mycmd", cmd_mycmd, 1, 1, NULL },
        @@ -4525,7 +4537,7 @@ int hello_main(int argc, char *argv[])
             

      • - And finally, the apps/examples/Makefile will execute the context target in all configured examplesub-directores, getting us finally to apps/examples/Makefile which is covered below.

        + And finally, the apps/examples/Makefile will execute the context target in all configured examplesub-directories, getting us finally to apps/examples/Makefile which is covered below.

        @@ -4845,7 +4857,7 @@ mount -t vfat /dev/ram1 /tmp

        All of the startup-behavior is contained in rcS.template. - The role of mkromfsimg.sh script is to (1) apply the specific configuration settings to rcS.template to create the final rcS, and (2) to generate the header file nsh_romfsimg.h containg the ROMFS file system image. + The role of mkromfsimg.sh script is to (1) apply the specific configuration settings to rcS.template to create the final rcS, and (2) to generate the header file nsh_romfsimg.h containing the ROMFS file system image. To do this, mkromfsimg.sh uses two tools that must be installed in your system:

          @@ -5316,13 +5328,13 @@ xxd -i romfs_img >nsh_romfsimg.h
        1. insmod
        2. kill
        3. losetup
        4. -
        5. ln
        6. -
        7. ls
        8. +
        9. ln
        10. +
        11. ls
        12. mb
        13. Login
        14. Login, Credentials
        15. lsmod
        16. -
        17. md5
        18. +
        19. md5
        20. mh
        21. mw
        22. mkdir
        23. diff --git a/Documentation/NuttX.html b/Documentation/NuttX.html index 2fe4d5a538..494a08777c 100644 --- a/Documentation/NuttX.html +++ b/Documentation/NuttX.html @@ -1624,8 +1624,8 @@
        24. STMicroelectronics

      - You can see that 9.9KB (62%) of SRAM heap is staill available for further application development while NSH is running. + You can see that 9.9KB (62%) of SRAM heap is still available for further application development while NSH is running.

      @@ -2883,9 +2883,9 @@ nsh>

      - STMicro STM32F152x/162x(STM32 F1 "EnergyLite" Medium+ Density Family). - Support for the STM32152 and STM32162 Medium+ density parts from Jussi Kivilinna and Sami Pelkonen was included in NuttX-7.3, extending the basic STM32F152x support. - This is architecture-only support, meaning that support for the boards with these chips is available, but not support for any publicly available boards is included. + STMicro STM32L152x/162x (STM32 L1 "EnergyLite" Medium+ Density Family). + Support for the STM32L152 and STM32L162 Medium+ density parts from Jussi Kivilinna and Sami Pelkonen was included in NuttX-7.3, extending the basic STM32L152x support. + This is architecture-only support, meaning that support for the boards with these chips is available, but no support for any publicly available boards is included.

      @@ -2995,7 +2995,7 @@ nsh>
    • - The other port is for a generic minimual STM32F103CBT6 "blue" board contributed by Alan Carvalho de Assis. + The other port is for a generic minimal STM32F103CBT6 "blue" board contributed by Alan Carvalho de Assis. Alan added support for numerous sensors, tone generators, user LEDs, and LCD support in NuttX 7.18.

    • @@ -3170,7 +3170,7 @@ nsh>

      STMicro STM32F107x (STM32 F1 "Connectivity Line" family). - Chip support for the STM32 F1 "Connectivity Line" family has been present in NuttX for some time and users have reported that they have successful brought up NuttX on theor proprietary boards using this logic. + Chip support for the STM32 F1 "Connectivity Line" family has been present in NuttX for some time and users have reported that they have successful brought up NuttX on their proprietary boards using this logic.

      • @@ -3259,7 +3259,7 @@ nsh>

          STATUS: - In addition to the above-mention WiFI support, the Photon board support includes buttons, LEDS, IWDG, USB OTG HS, and procfs support. Configurations available for nsh, usbnsh, and wlan configurations. See the Photon https://bitbucket.org/nuttx/nuttx/src/master/configs/photon/README.txt" target="_blank">README file for additional information. + In addition to the above-mention WiFI support, the Photon board support includes buttons, LEDS, IWDG, USB OTG HS, and procfs support. Configurations available for nsh, usbnsh, and wlan configurations. See the Photon README file for additional information. @@ -3783,7 +3783,7 @@ nsh>

        - STMicro ST Nucleo F303RE board.. + STMicro ST Nucleo F303RE board. Contributed by Paul Alexander Patience.

          @@ -4047,7 +4047,7 @@ nsh>

          • - The intial release included support from either OTG FS or OTG HS in FS mode. + The initial release included support from either OTG FS or OTG HS in FS mode.
          • The F429 port adds support for the STM32F439 LCD and OTG HS (in FS mode). @@ -4176,10 +4176,17 @@ nsh>

            • Serial Audio Interface (SAI).
            • -
            • Power Managmement.
            • +
            • Power Management.
            • LPTIM.
            • Comparator (COMP).
            +

            + NuttX-7.21. + Additional drivers were added: +

            +
              +
            • Internal Watchdog (IWDG).
            • +
            @@ -4481,7 +4488,7 @@ nsh>
          • This board supports included two configurations for the NuttShell (NSH). Both are networked enabled: One configured to support IPv4 and one configured to supported IPv6. - Instructions are included in the board README file for configuring both IPv4 and IPv6 simultaneously.. + Instructions are included in the board README file for configuring both IPv4 and IPv6 simultaneously.
          • Tiva PWM and Quadrature Encoder drivers were contributed to NuttX in 7.18 by Young. diff --git a/Documentation/NuttxUserGuide.html b/Documentation/NuttxUserGuide.html index 4fd477401e..0a8233775c 100644 --- a/Documentation/NuttxUserGuide.html +++ b/Documentation/NuttxUserGuide.html @@ -5769,15 +5769,6 @@ be sent.
          • pthread_mutex_timedlock. lock a mutex.
          • pthread_mutexattr_getprioceiling. get and set the prioceiling attribute of the mutex attributes object.
          • pthread_mutexattr_setprioceiling. get and set the prioceiling attribute of the mutex attributes object.
          • -
          • pthread_rwlock_destroy. destroy and initialize a read-write lock object.
          • -
          • pthread_rwlock_init. destroy and initialize a read-write lock object.
          • -
          • pthread_rwlock_rdlock. lock a read-write lock object for reading.
          • -
          • pthread_rwlock_timedrdlock. lock a read-write lock for reading.
          • -
          • pthread_rwlock_timedwrlock. lock a read-write lock for writing.
          • -
          • pthread_rwlock_tryrdlock. lock a read-write lock object for reading.
          • -
          • pthread_rwlock_trywrlock. lock a read-write lock object for writing.
          • -
          • pthread_rwlock_unlock. unlock a read-write lock object.
          • -
          • pthread_rwlock_wrlock. lock a read-write lock object for writing.
          • pthread_rwlockattr_destroy. destroy and initialize the read-write lock attributes object.
          • pthread_rwlockattr_getpshared. get and set the process-shared attribute of the read-write lock attributes object.
          • pthread_rwlockattr_init. destroy and initialize the read-write lock attributes object.
          • -- GitLab From e577072790e7a952211fec2ff083bc95f4aaac28 Mon Sep 17 00:00:00 2001 From: Juha Niskanen Date: Tue, 6 Jun 2017 06:56:50 -0600 Subject: [PATCH 921/990] power: battery_charger: add ioctl for charging input current --- drivers/power/battery_charger.c | 12 +++++ drivers/power/bq2425x.c | 75 +++++++++++++++++++-------- include/nuttx/power/battery_charger.h | 27 +++++++--- include/nuttx/power/battery_ioctl.h | 13 ++--- 4 files changed, 92 insertions(+), 35 deletions(-) diff --git a/drivers/power/battery_charger.c b/drivers/power/battery_charger.c index 0a573375dc..4b489799f8 100644 --- a/drivers/power/battery_charger.c +++ b/drivers/power/battery_charger.c @@ -227,6 +227,18 @@ static int bat_charger_ioctl(FAR struct file *filep, int cmd, } break; + case BATIOC_INPUT_CURRENT: + { + int amps; + FAR int *ampsp = (FAR int *)((uintptr_t)arg); + if (ampsp) + { + amps = *ampsp; + ret = dev->ops->input_current(dev, amps); + } + } + break; + default: _err("ERROR: Unrecognized cmd: %d\n", cmd); ret = -ENOTTY; diff --git a/drivers/power/bq2425x.c b/drivers/power/bq2425x.c index 661187cdee..039baf01a3 100644 --- a/drivers/power/bq2425x.c +++ b/drivers/power/bq2425x.c @@ -122,6 +122,7 @@ static inline int bq2425x_getreport(FAR struct bq2425x_dev_s *priv, uint8_t *report); static inline int bq2425x_reset(FAR struct bq2425x_dev_s *priv); static inline int bq2425x_watchdog(FAR struct bq2425x_dev_s *priv, bool enable); +static inline int bq2425x_powersupply(FAR struct bq2425x_dev_s *priv, int current); static inline int bq2425x_setvolt(FAR struct bq2425x_dev_s *priv, int volts); static inline int bq2425x_setcurr(FAR struct bq2425x_dev_s *priv, int current); @@ -132,6 +133,7 @@ static int bq2425x_health(struct battery_charger_dev_s *dev, int *health); static int bq2425x_online(struct battery_charger_dev_s *dev, bool *status); static int bq2425x_voltage(struct battery_charger_dev_s *dev, int value); static int bq2425x_current(struct battery_charger_dev_s *dev, int value); +static int bq2425x_input_current(struct battery_charger_dev_s *dev, int value); /**************************************************************************** * Private Data @@ -143,7 +145,8 @@ static const struct battery_charger_operations_s g_bq2425xops = bq2425x_health, bq2425x_online, bq2425x_voltage, - bq2425x_current + bq2425x_current, + bq2425x_input_current }; /**************************************************************************** @@ -273,7 +276,7 @@ static inline int bq2425x_reset(FAR struct bq2425x_dev_s *priv) ret = bq2425x_getreg8(priv, BQ2425X_REG_2, ®val); if (ret < 0) { - baterr("ERROR: Error reading from BQ2425X! Error = %d\n", ret); + baterr("ERROR: Error reading from BQ2425X! Error = %d\n", ret); return ret; } @@ -283,7 +286,7 @@ static inline int bq2425x_reset(FAR struct bq2425x_dev_s *priv) ret = bq2425x_putreg8(priv, BQ2425X_REG_2, regval); if (ret < 0) { - baterr("ERROR: Error writing to BQ2425X! Error = %d\n", ret); + baterr("ERROR: Error writing to BQ2425X! Error = %d\n", ret); return ret; } @@ -297,7 +300,7 @@ static inline int bq2425x_reset(FAR struct bq2425x_dev_s *priv) ret = bq2425x_putreg8(priv, BQ2425X_REG_2, regval); if (ret < 0) { - baterr("ERROR: Error writing to BQ2425X! Error = %d\n", ret); + baterr("ERROR: Error writing to BQ2425X! Error = %d\n", ret); return ret; } @@ -320,7 +323,7 @@ static inline int bq2425x_watchdog(FAR struct bq2425x_dev_s *priv, bool enable) ret = bq2425x_getreg8(priv, BQ2425X_REG_1, ®val); if (ret < 0) { - baterr("ERROR: Error reading from BQ2425X! Error = %d\n", ret); + baterr("ERROR: Error reading from BQ2425X! Error = %d\n", ret); return ret; } @@ -336,7 +339,7 @@ static inline int bq2425x_watchdog(FAR struct bq2425x_dev_s *priv, bool enable) ret = bq2425x_putreg8(priv, BQ2425X_REG_1, regval); if (ret < 0) { - baterr("ERROR: Error writing to BQ2425X! Error = %d\n", ret); + baterr("ERROR: Error writing to BQ2425X! Error = %d\n", ret); return ret; } @@ -493,6 +496,10 @@ static inline int bq2425x_powersupply(FAR struct bq2425x_dev_s *priv, int curren switch (current) { + case BATTERY_INPUT_CURRENT_EXT_LIM: + idx = BQ2425X_INP_CURR_EXT_ILIM; + break; + case 100: idx = BQ2425X_INP_CURR_LIM_100MA; break; @@ -518,7 +525,7 @@ static inline int bq2425x_powersupply(FAR struct bq2425x_dev_s *priv, int curren break; default: - baterr("ERROR: Current not supported, setting default to 100mA.!\n"); + baterr("ERROR: Current not supported, setting default to 100mA!\n"); idx = BQ2425X_INP_CURR_LIM_100MA; break; } @@ -528,7 +535,7 @@ static inline int bq2425x_powersupply(FAR struct bq2425x_dev_s *priv, int curren ret = bq2425x_getreg8(priv, BQ2425X_REG_2, ®val); if (ret < 0) { - baterr("ERROR: Error reading from BQ2425X! Error = %d\n", ret); + baterr("ERROR: Error reading from BQ2425X! Error = %d\n", ret); return ret; } @@ -544,7 +551,7 @@ static inline int bq2425x_powersupply(FAR struct bq2425x_dev_s *priv, int curren ret = bq2425x_putreg8(priv, BQ2425X_REG_2, regval); if (ret < 0) { - baterr("ERROR: Error writing to BQ2425X! Error = %d\n", ret); + baterr("ERROR: Error writing to BQ2425X! Error = %d\n", ret); return ret; } @@ -575,7 +582,7 @@ static inline int bq2425x_setvolt(FAR struct bq2425x_dev_s *priv, int volts) ret = bq2425x_getreg8(priv, BQ2425X_REG_3, ®val); if (ret < 0) { - baterr("ERROR: Error reading from BQ2425X! Error = %d\n", ret); + baterr("ERROR: Error reading from BQ2425X! Error = %d\n", ret); return ret; } @@ -592,7 +599,7 @@ static inline int bq2425x_setvolt(FAR struct bq2425x_dev_s *priv, int volts) ret = bq2425x_putreg8(priv, BQ2425X_REG_3, regval); if (ret < 0) { - baterr("ERROR: Error writing to BQ2425X! Error = %d\n", ret); + baterr("ERROR: Error writing to BQ2425X! Error = %d\n", ret); return ret; } @@ -623,7 +630,7 @@ static inline int bq2425x_setcurr(FAR struct bq2425x_dev_s *priv, int current) ret = bq2425x_getreg8(priv, BQ2425X_REG_4, ®val); if (ret < 0) { - baterr("ERROR: Error reading from BQ2425X! Error = %d\n", ret); + baterr("ERROR: Error reading from BQ2425X! Error = %d\n", ret); return ret; } @@ -640,7 +647,7 @@ static inline int bq2425x_setcurr(FAR struct bq2425x_dev_s *priv, int current) ret = bq2425x_putreg8(priv, BQ2425X_REG_4, regval); if (ret < 0) { - baterr("ERROR: Error writing to BQ2425X! Error = %d\n", ret); + baterr("ERROR: Error writing to BQ2425X! Error = %d\n", ret); return ret; } @@ -666,7 +673,7 @@ static int bq2425x_voltage(struct battery_charger_dev_s *dev, int value) ret = bq2425x_setvolt(priv, value); if (ret < 0) { - baterr("ERROR: Error setting voltage to BQ2425X! Error = %d\n", ret); + baterr("ERROR: Error setting voltage to BQ2425X! Error = %d\n", ret); return ret; } @@ -691,7 +698,30 @@ static int bq2425x_current(struct battery_charger_dev_s *dev, int value) ret = bq2425x_setcurr(priv, value); if (ret < 0) { - baterr("ERROR: Error setting current to BQ2425X! Error = %d\n", ret); + baterr("ERROR: Error setting current to BQ2425X! Error = %d\n", ret); + return ret; + } + + return OK; +} + +/**************************************************************************** + * Name: bq2425x_input_current + * + * Description: + * Set the power-supply input current limit + * + ****************************************************************************/ + +static int bq2425x_input_current(struct battery_charger_dev_s *dev, int value) +{ + FAR struct bq2425x_dev_s *priv = (FAR struct bq2425x_dev_s *)dev; + int ret; + + ret = bq2425x_powersupply(priv, value); + if (ret < 0) + { + baterr("ERROR: Failed to set BQ2425x power supply input limit: %d\n", ret); return ret; } @@ -718,18 +748,19 @@ static int bq2425x_current(struct battery_charger_dev_s *dev, int value) * Input Parameters: * i2c - An instance of the I2C interface to use to communicate with * the BQ2425x - * addr - The I2C address of the BQ2425x (Better be 0x36). + * addr - The I2C address of the BQ2425x (Better be 0x6a) * frequency - The I2C frequency + * current - The input current our power-supply can offer to charger * * Returned Value: - * A pointer to the initializeed lower-half driver instance. A NULL pointer + * A pointer to the initialized lower-half driver instance. A NULL pointer * is returned on a failure to initialize the BQ2425x lower half. * ****************************************************************************/ FAR struct battery_charger_dev_s * bq2425x_initialize(FAR struct i2c_master_s *i2c, uint8_t addr, - uint32_t frequency) + uint32_t frequency, int current) { FAR struct bq2425x_dev_s *priv; int ret; @@ -767,12 +798,12 @@ FAR struct battery_charger_dev_s * return NULL; } - /* Define that our power supply can offer 2000mA to the charger */ + /* Define the current that our power supply can offer to the charger. */ - ret = bq2425x_powersupply(priv, 2000); + ret = bq2425x_powersupply(priv, current); if (ret < 0) { - baterr("ERROR: Failed to set BQ2425x power supply current: %d\n", ret); + baterr("ERROR: Failed to set BQ2425x power supply input limit: %d\n", ret); kmm_free(priv); return NULL; } @@ -781,4 +812,4 @@ FAR struct battery_charger_dev_s * return (FAR struct battery_charger_dev_s *)priv; } -#endif /* CONFIG_BATTERY && CONFIG_I2C && CONFIG_I2C_BQ2425X */ +#endif /* CONFIG_BATTERY_CHARGER && CONFIG_I2C && CONFIG_I2C_BQ2425X */ diff --git a/include/nuttx/power/battery_charger.h b/include/nuttx/power/battery_charger.h index 76cfa9e447..932e3ae37e 100644 --- a/include/nuttx/power/battery_charger.h +++ b/include/nuttx/power/battery_charger.h @@ -46,7 +46,6 @@ #include #include -#include #ifdef CONFIG_BATTERY_CHARGER @@ -81,8 +80,18 @@ * Input value: A pointer to type bool. * BATIOC_VOLTAGE - Define the wished charger voltage to charge the battery. * Input value: An int defining the voltage value. + * BATIOC_CURRENT - Define the wished charger current to charge the battery. + * Input value: An int defining the current value. + * BATIOC_INPUT_CURRENT - Define the input current limit of power supply. + * Input value: An int defining the input current limit value. */ +/* Special input values for BATIOC_INPUT_CURRENT that may optionally + * be supported by lower-half driver: + */ + +#define BATTERY_INPUT_CURRENT_EXT_LIM (-1) /* External input current limit */ + /**************************************************************************** * Public Types ****************************************************************************/ @@ -127,7 +136,7 @@ struct battery_charger_operations_s int (*health)(struct battery_charger_dev_s *dev, int *health); - /* Return true if the batter is online */ + /* Return true if the battery is online */ int (*online)(struct battery_charger_dev_s *dev, bool *status); @@ -138,6 +147,10 @@ struct battery_charger_operations_s /* Set the wished current rate used for charging */ int (*current)(struct battery_charger_dev_s *dev, int value); + + /* Set the input current limit of power supply */ + + int (*input_current)(struct battery_charger_dev_s *dev, int value); }; /* This structure defines the battery driver state structure */ @@ -201,27 +214,27 @@ int battery_charger_register(FAR const char *devpath, * CONFIG_BATTERY_CHARGER - Upper half battery fuel gauge driver support * CONFIG_I2C - I2C support * CONFIG_I2C_BQ2425X - And the driver must be explictly selected. - * CONFIG_I2C_BQ24250 or CONFIG_I2C_BQ24251 - The driver must know which - * chip is on the board in order to scale the voltage correctly. * * Input Parameters: * i2c - An instance of the I2C interface to use to communicate with * the BQ2425X * addr - The I2C address of the BQ2425X (Better be 0x6A). * frequency - The I2C frequency + * current - The input current our power-supply can offer to charger * * Returned Value: - * A pointer to the initializeed battery driver instance. A NULL pointer + * A pointer to the initialized battery driver instance. A NULL pointer * is returned on a failure to initialize the BQ2425X lower half. * ****************************************************************************/ #if defined(CONFIG_I2C) && defined(CONFIG_I2C_BQ2425X) -struct i2c_master_s; /* Forward reference */ +struct i2c_master_s; FAR struct battery_charger_dev_s *bq2425x_initialize(FAR struct i2c_master_s *i2c, uint8_t addr, - uint32_t frequency); + uint32_t frequency, + int current); #endif #undef EXTERN diff --git a/include/nuttx/power/battery_ioctl.h b/include/nuttx/power/battery_ioctl.h index 4bbd46e21b..a883bba3d6 100644 --- a/include/nuttx/power/battery_ioctl.h +++ b/include/nuttx/power/battery_ioctl.h @@ -48,11 +48,12 @@ * Pre-processor Definitions ****************************************************************************/ -#define BATIOC_STATE _BATIOC(0x0001) -#define BATIOC_HEALTH _BATIOC(0x0002) -#define BATIOC_ONLINE _BATIOC(0x0003) -#define BATIOC_VOLTAGE _BATIOC(0x0004) -#define BATIOC_CURRENT _BATIOC(0x0005) -#define BATIOC_CAPACITY _BATIOC(0x0006) +#define BATIOC_STATE _BATIOC(0x0001) +#define BATIOC_HEALTH _BATIOC(0x0002) +#define BATIOC_ONLINE _BATIOC(0x0003) +#define BATIOC_VOLTAGE _BATIOC(0x0004) +#define BATIOC_CURRENT _BATIOC(0x0005) +#define BATIOC_INPUT_CURRENT _BATIOC(0x0006) +#define BATIOC_CAPACITY _BATIOC(0x0007) #endif /* __INCLUDE_NUTTX_POWER_BATTERY_IOCTL_H */ -- GitLab From 942d6d1c144691cc5e2bb72749c159ed888b4155 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 6 Jun 2017 08:25:34 -0600 Subject: [PATCH 922/990] Add a few things to the acronym list. --- Documentation/acronyms.txt | 37 ++++++++++++++++++++++++++++++++++++- 1 file changed, 36 insertions(+), 1 deletion(-) diff --git a/Documentation/acronyms.txt b/Documentation/acronyms.txt index 00321607ba..bb6b153990 100644 --- a/Documentation/acronyms.txt +++ b/Documentation/acronyms.txt @@ -1,20 +1,36 @@ -AIC Advanced Interrupt Controller (Atmel SAM) +6loWPAN IPv6 over Low power Wireless Personal Area Networks +ACM Abstract Control Model (USB) ADC Analog to Digital Conversion +AIC Advanced Interrupt Controller (Atmel SAM) ARP Address Resolution Protocol (networking) BCH Block to Character BINFMT Binary Format (Dynamic Loader) CAN Controller Area Network +CDC Communication Device Class (USB) CP15 Coprocessor 15 (ARM) +CPU Central Processing Unit DEVIF Device Interface (networking) DAC Digital to Analog Conversion +DCD Device Controller Driver (USB) +DCMI Digital Camera Interface DEV Device +DHCP Dynamic Host Configuration Protocol +DHCPC DHCP Client +DHCPD DHCP Daemon (server) DMA Direct Memory Access (hardware) DMAC DMA Controller (hardware) DRAM Dynamic RAM +EABI Embedded-Application Binary Interface +EMAC Ethernet Media Access Controller (networking) FAT File Allocation Table (file systems) FTL FLASH Translation Layer (MTD) +GPIO General Purpose Input/Output +GMAC Gigabit Media Access Controller (networking) +HCD Host Controller Driver (USB) HSMCI High Speed Memory Card Interface (Atmel) I/O Input/Output +IOCTL Input/Output Control +IoT Internet of Things IP Internet Protocol (version 4?) (networking) IPv6 Internet Protocol Version 6 (networking) IRQ Interrupt Request @@ -22,36 +38,55 @@ I2C Inter-Integrated Circuit I2S Inter IC Sound ICMP Internet Control Message Protocol (networking) IOB I/O Buffer (networking) +LAN Local Area Network (networking) LIBC The "C" Library +MAC Media Access Control (networking, OSI model) MCI Memory Card Interface +MCU Microcontroller Unit MM Memory Management/Manager MMAP Memory Map MMC Multi-Media Card MMCSD See MMC and SD +MMU Memory Management Unit +MPU Memory Protection Unit MTD Memory Technology Device NFS Network File System +NETDB Network Data Base (networking) NETDEV Network Device (networking) NSH NuttShell NX NuttX, the NuttX Graphics server (graphics) NXFFS NuttX Flash File System NXWM The NuttX Window Manager (graphics) PID Peripheral ID (Atmel SAM) +OS Operating System +OTG On-The-Go (USB) PWM Pulse Width Modulation PKT "Raw" Packet socket (networking) +PRNG Pseudo-Random Number Generator RAM Random Access Memory +RNG Random Number Generator RTC Real Time Clock RTCC Real Time Clock/Calendar +RTOS Real Time Operating System SAIC Secure Advanced Interrupt Controller (Atmel SAM) SD Secure Digital +SDHC Secure Digital High Capacity (flash memory), + Secure Digital Host Controller SDIO Secure Digital I/O SMC Static Memory Controller (hardware) SPI Serial Periperhal Interface +SPRNG Scalable Parallel Random Number Generator +SYSLOG System Log TCP Transmission Control Protocol (networking) TSC Touchscreen Controller +TUN network TUNnel TWI Two-Wire Interface UDP User Datagram Protocol (networking) UART Universal Asynchronous Receiver/Transmitter USB Universal Serial Bus USART Universal Synchronous/Asynchronous Receiver/Transmitter +WAN Wide Area Network (networking) +WLAN Wireless Local Area Network (networking) +WPAN Wireless Personal Area Network (networking) WDT Watchdog Timer XDMAC Extended DMA Controller (Atmel) -- GitLab From 93625e80a7183204514f658c72501e673c783732 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 6 Jun 2017 15:04:55 -0600 Subject: [PATCH 923/990] Typos in documents + more acronyms. --- ChangeLog | 4 ++-- Documentation/acronyms.txt | 40 ++++++++++++++++++++++++++++---------- ReleaseNotes | 2 +- 3 files changed, 33 insertions(+), 13 deletions(-) diff --git a/ChangeLog b/ChangeLog index 991873f17b..bd1e20ba37 100755 --- a/ChangeLog +++ b/ChangeLog @@ -7917,7 +7917,7 @@ command line NxPlayer (2014-7-31). * audio/audio.c: More debug output (2014-7-31). * configs/sama5d3x-ek/README.txt: REAME update (2014-7-31). - * drivers/audio/wm8904.c: Was not saving i2s interface instance + * drivers/audio/wm8904.c: Was not saving I2S interface instance (2014-7-31). * sched/sem_wait.c: Use set_errno() and get_errno(). Direct access inside the OS may not be supported in the future (2014-7-31). @@ -15307,7 +15307,7 @@ change the link state. From Sebastien Lorquet (2017-05-19). * drivers/wireless/ieee80211: Add support for AP scanning. From Simon Piriou (2017-05-21). - * drivers/audio: Add cs43l22 audio driver STM32F4: Add i2s driver. + * drivers/audio: Add cs43l22 audio driver STM32F4: Add I2S driver. From Taras Drozdovsky (2017-05-21). * This is based on a patch by Taras Drozdovsky. Basically, the delay that was added during the integration of the CDC/ACM host driver was diff --git a/Documentation/acronyms.txt b/Documentation/acronyms.txt index bb6b153990..aab1760a2b 100644 --- a/Documentation/acronyms.txt +++ b/Documentation/acronyms.txt @@ -5,6 +5,7 @@ AIC Advanced Interrupt Controller (Atmel SAM) ARP Address Resolution Protocol (networking) BCH Block to Character BINFMT Binary Format (Dynamic Loader) +BPP Bits Per Pixel CAN Controller Area Network CDC Communication Device Class (USB) CP15 Coprocessor 15 (ARM) @@ -19,10 +20,15 @@ DHCPC DHCP Client DHCPD DHCP Daemon (server) DMA Direct Memory Access (hardware) DMAC DMA Controller (hardware) +DNS Domain Name Service (or System or Server) (networking) DRAM Dynamic RAM EABI Embedded-Application Binary Interface +EEPROM Electrically Erasable Programmable Read-Only Memory EMAC Ethernet Media Access Controller (networking) +EPROM Erasable Programmable Read-Only Memory FAT File Allocation Table (file systems) +FB Frame Buffer (video interface) +FSMC Flexible Static Memory Controller (STM32) FTL FLASH Translation Layer (MTD) GPIO General Purpose Input/Output GMAC Gigabit Media Access Controller (networking) @@ -30,16 +36,21 @@ HCD Host Controller Driver (USB) HSMCI High Speed Memory Card Interface (Atmel) I/O Input/Output IOCTL Input/Output Control -IoT Internet of Things +IoT Internet of Things (marketing BS) IP Internet Protocol (version 4?) (networking) +IPv4 Internet Protocol Version 4 (networking) IPv6 Internet Protocol Version 6 (networking) -IRQ Interrupt Request -I2C Inter-Integrated Circuit -I2S Inter IC Sound +IRQ Interrupt Request (hardware) +I2C Inter-Integrated Circuit (serial interface) +I2S Inter IC Sound (serial interface) ICMP Internet Control Message Protocol (networking) +ICMPv6 Internet Control Message Protocol for IPv6 (networking) +IGMP Internet Group Multicast Protocol (networking) IOB I/O Buffer (networking) LAN Local Area Network (networking) +LCD Liquid Crystal Display LIBC The "C" Library +LIBM The "C" Math Library MAC Media Access Control (networking, OSI model) MCI Memory Card Interface MCU Microcontroller Unit @@ -54,39 +65,48 @@ NFS Network File System NETDB Network Data Base (networking) NETDEV Network Device (networking) NSH NuttShell +NVM Non-Volatile Memory +NTP Network Time Protocol (networking) NX NuttX, the NuttX Graphics server (graphics) NXFFS NuttX Flash File System NXWM The NuttX Window Manager (graphics) -PID Peripheral ID (Atmel SAM) +PID Process ID (operating systems) + Peripheral ID (Atmel SAM) +PROM Programmable Read-Only Memory OS Operating System OTG On-The-Go (USB) +OTP One-Time Programmable PWM Pulse Width Modulation PKT "Raw" Packet socket (networking) PRNG Pseudo-Random Number Generator RAM Random Access Memory RNG Random Number Generator +ROM Read-Only Memory RTC Real Time Clock RTCC Real Time Clock/Calendar RTOS Real Time Operating System SAIC Secure Advanced Interrupt Controller (Atmel SAM) -SD Secure Digital +SD Secure Digital (flash memory) SDHC Secure Digital High Capacity (flash memory), - Secure Digital Host Controller + Secure Digital Host Controller (hardware) SDIO Secure Digital I/O +SDRAM Synchronous Dynamic Random Access Memory +SLCD Segment Liquid Crystal Display SMC Static Memory Controller (hardware) SPI Serial Periperhal Interface SPRNG Scalable Parallel Random Number Generator +SRAM Static RAM SYSLOG System Log TCP Transmission Control Protocol (networking) TSC Touchscreen Controller TUN network TUNnel -TWI Two-Wire Interface +TWI Two-Wire Interface (serial interface) UDP User Datagram Protocol (networking) UART Universal Asynchronous Receiver/Transmitter -USB Universal Serial Bus +USB Universal Serial Bus (serial interface) USART Universal Synchronous/Asynchronous Receiver/Transmitter WAN Wide Area Network (networking) WLAN Wireless Local Area Network (networking) WPAN Wireless Personal Area Network (networking) -WDT Watchdog Timer +WDT Watchdog Timer (hardware) XDMAC Extended DMA Controller (Atmel) diff --git a/ReleaseNotes b/ReleaseNotes index ee3b1e2418..92be9fef5f 100644 --- a/ReleaseNotes +++ b/ReleaseNotes @@ -13839,7 +13839,7 @@ Additional new features and extended functionality: Juha Niskanen. - STM32 Ethernet: Add support for KSZ8081 PHY interrupts. From Sebastien Lorquet. - - STM32 F4: Add i2s driver. From Taras Drozdovsky. + - STM32 F4: Add I2S driver. From Taras Drozdovsky. - STM32 L4: Add IWDG peripheral. This is the same as for STM32 except that prescale and reload can be changed after watchdog has been started, as this seems to work on L4. From Juha Niskanen. -- GitLab From 670d6a1e8d411206de7af12d9b340d97f9ff01c0 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 6 Jun 2017 16:10:41 -0600 Subject: [PATCH 924/990] MTD FLASH drivers: The byte write method of several drivers had a cloned error: It was not locking the bus while performing byte write operations. --- drivers/mtd/is25xp.c | 9 ++++++--- drivers/mtd/m25px.c | 4 +++- drivers/mtd/sst25xx.c | 7 +++++-- drivers/mtd/sst26.c | 4 +++- drivers/mtd/w25.c | 6 ++++-- 5 files changed, 21 insertions(+), 9 deletions(-) diff --git a/drivers/mtd/is25xp.c b/drivers/mtd/is25xp.c index 3ce5e3f0ce..1d663a42bd 100644 --- a/drivers/mtd/is25xp.c +++ b/drivers/mtd/is25xp.c @@ -4,7 +4,7 @@ * * Copyright (C) 2016 Marten Svanfeldt. All rights reserved. * - * Copyright (C) 2009-2011, 2013 Gregory Nutt. All rights reserved. + * Copyright (C) 2009-2011, 2013, 2017 Gregory Nutt. All rights reserved. * Author: Ken Pettit * * Copied from / based on m25px.c and sst25.c drivers written by @@ -568,8 +568,9 @@ static inline void is25xp_pagewrite(struct is25xp_dev_s *priv, FAR const uint8_t ************************************************************************************/ #ifdef CONFIG_MTD_BYTE_WRITE -static inline void is25xp_bytewrite(struct is25xp_dev_s *priv, FAR const uint8_t *buffer, - off_t offset, uint16_t count) +static inline void is25xp_bytewrite(struct is25xp_dev_s *priv, + FAR const uint8_t *buffer, off_t offset, + uint16_t count) { finfo("offset: %08lx count:%d\n", (long)offset, count); @@ -812,6 +813,7 @@ static ssize_t is25xp_write(FAR struct mtd_dev_s *dev, off_t offset, size_t nbyt startpage = offset / (1 << priv->pageshift); endpage = (offset + nbytes) / (1 << priv->pageshift); + is25xp_lock(priv->dev); if (startpage == endpage) { /* All bytes within one programmable page. Just do the write. */ @@ -856,6 +858,7 @@ static ssize_t is25xp_write(FAR struct mtd_dev_s *dev, off_t offset, size_t nbyt priv->lastwaswrite = true; } + is25xp_unlock(priv->dev); return nbytes; } #endif /* CONFIG_MTD_BYTE_WRITE */ diff --git a/drivers/mtd/m25px.c b/drivers/mtd/m25px.c index 2ce37d2e38..3b509eb6c5 100644 --- a/drivers/mtd/m25px.c +++ b/drivers/mtd/m25px.c @@ -3,7 +3,7 @@ * Driver for SPI-based M25P1 (128Kbit), M25P64 (32Mbit), M25P64 (64Mbit), and * M25P128 (128Mbit) FLASH (and compatible). * - * Copyright (C) 2009-2011, 2013 Gregory Nutt. All rights reserved. + * Copyright (C) 2009-2011, 2013, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -859,6 +859,7 @@ static ssize_t m25p_write(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes startpage = offset / (1 << priv->pageshift); endpage = (offset + nbytes) / (1 << priv->pageshift); + m25p_lock(priv->dev); if (startpage == endpage) { /* All bytes within one programmable page. Just do the write. */ @@ -901,6 +902,7 @@ static ssize_t m25p_write(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes } } + m25p_unlock(priv->dev); return nbytes; } #endif /* CONFIG_MTD_BYTE_WRITE */ diff --git a/drivers/mtd/sst25xx.c b/drivers/mtd/sst25xx.c index 93aca1a383..a6e71f12e1 100644 --- a/drivers/mtd/sst25xx.c +++ b/drivers/mtd/sst25xx.c @@ -546,8 +546,9 @@ static inline void sst25xx_pagewrite(struct sst25xx_dev_s *priv, FAR const uint8 ************************************************************************************/ #ifdef CONFIG_MTD_BYTE_WRITE -static inline void sst25xx_bytewrite(struct sst25xx_dev_s *priv, FAR const uint8_t *buffer, - off_t offset, uint16_t count) +static inline void sst25xx_bytewrite(struct sst25xx_dev_s *priv, + FAR const uint8_t *buffer, off_t offset, + uint16_t count) { finfo("offset: %08lx count:%d\n", (long)offset, count); @@ -790,6 +791,7 @@ static ssize_t sst25xx_write(FAR struct mtd_dev_s *dev, off_t offset, size_t nby startpage = offset / (1 << priv->pageshift); endpage = (offset + nbytes) / (1 << priv->pageshift); + sst25xx_lock(priv->dev); if (startpage == endpage) { /* All bytes within one programmable page. Just do the write. */ @@ -834,6 +836,7 @@ static ssize_t sst25xx_write(FAR struct mtd_dev_s *dev, off_t offset, size_t nby priv->lastwaswrite = true; } + sst25xx_unlock(priv->dev); return nbytes; } #endif /* CONFIG_MTD_BYTE_WRITE */ diff --git a/drivers/mtd/sst26.c b/drivers/mtd/sst26.c index d2702001c3..4a1260e9d3 100644 --- a/drivers/mtd/sst26.c +++ b/drivers/mtd/sst26.c @@ -8,7 +8,7 @@ * * For SST25VF064, see sst25cxx.c driver instead. * - * Copyright (C) 2009-2011, 2013, 2016 Gregory Nutt. All rights reserved. + * Copyright (C) 2009-2011, 2013, 2016-2017 Gregory Nutt. All rights reserved. * Author: Ken Pettit * Author: Sebastien Lorquet * @@ -791,6 +791,7 @@ static ssize_t sst26_write(FAR struct mtd_dev_s *dev, off_t offset, size_t nbyte startpage = offset / (1 << priv->pageshift); endpage = (offset + nbytes) / (1 << priv->pageshift); + sst26_lock(priv->dev); if (startpage == endpage) { /* All bytes within one programmable page. Just do the write. */ @@ -835,6 +836,7 @@ static ssize_t sst26_write(FAR struct mtd_dev_s *dev, off_t offset, size_t nbyte priv->lastwaswrite = true; } + sst26_unlock(priv->dev); return nbytes; } #endif /* CONFIG_MTD_BYTE_WRITE */ diff --git a/drivers/mtd/w25.c b/drivers/mtd/w25.c index 458c85e092..6bf757d3ef 100644 --- a/drivers/mtd/w25.c +++ b/drivers/mtd/w25.c @@ -2,7 +2,7 @@ * drivers/mtd/w25.c * Driver for SPI-based W25x16, x32, and x64 and W25q16, q32, q64, and q128 FLASH * - * Copyright (C) 2012-2013 Gregory Nutt. All rights reserved. + * Copyright (C) 2012-2013, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -802,7 +802,7 @@ static void w25_pagewrite(struct w25_dev_s *priv, FAR const uint8_t *buffer, #if defined(CONFIG_MTD_BYTE_WRITE) && !defined(CONFIG_W25_READONLY) static inline void w25_bytewrite(struct w25_dev_s *priv, FAR const uint8_t *buffer, - off_t offset, uint16_t count) + off_t offset, uint16_t count) { finfo("offset: %08lx count:%d\n", (long)offset, count); @@ -1157,6 +1157,7 @@ static ssize_t w25_write(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes, startpage = offset / W25_PAGE_SIZE; endpage = (offset + nbytes) / W25_PAGE_SIZE; + w25_lock(priv->spi); if (startpage == endpage) { /* All bytes within one programmable page. Just do the write. */ @@ -1198,6 +1199,7 @@ static ssize_t w25_write(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes, } } + w25_unlock(priv->spi); return nbytes; } #endif /* defined(CONFIG_MTD_BYTE_WRITE) && !defined(CONFIG_W25_READONLY) */ -- GitLab From c1a3208f8388f6c97a7fda4007e13f5eab0b5311 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Fri, 2 Jun 2017 11:30:34 -1000 Subject: [PATCH 925/990] Kinetis:Disable MPU when not in protected mode. The hardware reset state of the the MPU precludes any bus masters other then DMA access to memory. Unfortunately USB and SDHC have there own DMA and will not have access to memory in the default reset state. This change disabled the MPU if present on system startup. --- arch/arm/src/kinetis/Make.defs | 3 ++- arch/arm/src/kinetis/kinetis_mpuinit.c | 20 ++++++++++++++++++++ arch/arm/src/kinetis/kinetis_mpuinit.h | 12 ++++++++++++ arch/arm/src/kinetis/kinetis_start.c | 6 ++++++ 4 files changed, 40 insertions(+), 1 deletion(-) diff --git a/arch/arm/src/kinetis/Make.defs b/arch/arm/src/kinetis/Make.defs index 6ee494c652..8ec4063b6d 100644 --- a/arch/arm/src/kinetis/Make.defs +++ b/arch/arm/src/kinetis/Make.defs @@ -116,6 +116,7 @@ CHIP_CSRCS += kinetis_lowputc.c kinetis_pin.c kinetis_pingpio.c CHIP_CSRCS += kinetis_serialinit.c kinetis_serial.c CHIP_CSRCS += kinetis_start.c kinetis_uid.c kinetis_wdog.c CHIP_CSRCS += kinetis_cfmconfig.c +CHIP_CSRCS += kinetis_mpuinit.c # Configuration-dependent Kinetis files @@ -124,7 +125,7 @@ CHIP_CSRCS += kinetis_timerisr.c endif ifeq ($(CONFIG_BUILD_PROTECTED),y) -CHIP_CSRCS += kinetis_userspace.c kinetis_mpuinit.c +CHIP_CSRCS += kinetis_userspace.c endif ifeq ($(CONFIG_KINETIS_GPIOIRQ),y) diff --git a/arch/arm/src/kinetis/kinetis_mpuinit.c b/arch/arm/src/kinetis/kinetis_mpuinit.c index 6c41f85bf4..9618b5a071 100644 --- a/arch/arm/src/kinetis/kinetis_mpuinit.c +++ b/arch/arm/src/kinetis/kinetis_mpuinit.c @@ -45,6 +45,7 @@ #include "mpu.h" #include "kinetis_mpuinit.h" +#include "chip/kinetis_mpu.h" #if defined(CONFIG_BUILD_PROTECTED) && defined(CONFIG_ARM_MPU) @@ -120,5 +121,24 @@ void kinetis_mpu_uheap(uintptr_t start, size_t size) mpu_user_intsram(start, size); } +#elif defined(KINETIS_MPU) + +/**************************************************************************** + * Name: kinetis_mpudisable + * + * Description: + * Configure the MPU to permit All buss masters access to all resources. + * + ****************************************************************************/ + +void kinetis_mpudisable(void) +{ + uint32_t regval; + + regval = getreg32(KINETIS_MPU_CESR); + regval &= ~MPU_CESR_VLD; + putreg32(regval, KINETIS_MPU_CESR); +} + #endif /* CONFIG_BUILD_PROTECTED && CONFIG_ARM_MPU */ diff --git a/arch/arm/src/kinetis/kinetis_mpuinit.h b/arch/arm/src/kinetis/kinetis_mpuinit.h index 3327176841..91abf8e122 100644 --- a/arch/arm/src/kinetis/kinetis_mpuinit.h +++ b/arch/arm/src/kinetis/kinetis_mpuinit.h @@ -61,6 +61,18 @@ void kinetis_mpuinitialize(void); # define kinetis_mpuinitialize() #endif +/**************************************************************************** + * Name: kinetis_mpudisable + * + * Description: + * Configure the MPU to permit All buss masters access to all resources. + * + ****************************************************************************/ + +#if !defined(CONFIG_BUILD_PROTECTED) && defined(KINETIS_MPU) +void kinetis_mpudisable(void); +#endif + /**************************************************************************** * Name: kinetis_mpu_uheap * diff --git a/arch/arm/src/kinetis/kinetis_start.c b/arch/arm/src/kinetis/kinetis_start.c index f7445c5cde..d139d9533a 100644 --- a/arch/arm/src/kinetis/kinetis_start.c +++ b/arch/arm/src/kinetis/kinetis_start.c @@ -341,6 +341,12 @@ void __start(void) #ifdef CONFIG_BUILD_PROTECTED kinetis_userspace(); +#else +# ifdef KINETIS_MPU + /* Disable the MPU so that all master may access all buses */ + + kinetis_mpudisable(); +# endif #endif /* Initialize other on-board resources */ -- GitLab From 3f4d096707a9c7a3c93bdb2046a9bc7356e7ae81 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Fri, 2 Jun 2017 11:36:17 -1000 Subject: [PATCH 926/990] Kinetis:teensy-3.x Define USBOTG-FS Read from FLASH access in board config Allow the board config to define the USBOTG-FS to have Read access to FLASH. --- configs/teensy-3.x/include/board.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/configs/teensy-3.x/include/board.h b/configs/teensy-3.x/include/board.h index 508d5a811d..0a0eae9914 100644 --- a/configs/teensy-3.x/include/board.h +++ b/configs/teensy-3.x/include/board.h @@ -179,6 +179,9 @@ #define BOARD_USB_CLKSRC SIM_SOPT2_USBSRC #define BOARD_USB_FREQ BOARD_SIM_CLKDIV2_FREQ +/* Allow USBOTG-FS Controller to Read from FLASH */ + +#define BOARD_USB_FLASHACCESS /* PWM Configuration */ /* FTM0 Channels */ -- GitLab From 60c552ae0fc38bcf394cf7b2603eba49d7753f64 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Fri, 2 Jun 2017 16:25:27 -1000 Subject: [PATCH 927/990] Kinetis:usbdev clean up ensuring proper use of HW. Remove magic numbers from code, documented the use of undocumented bits. Remove comments and code that were not appropriate for this hardware. Removed ifdef that's that were always compiled and removed code blocks that were never compiled. Ensure proper access order to hardware. Per the reference manual: disable endpoints prior to configuring buffer descriptor, then enable endpoints Reorganize interrupt processing order to offload data after processing errors. Reorganize initialization so that there is a clear initialization phase, reset phase for both the hardware and software structures. By breaking the initialization into smaller pieces, the reset interrupt only resets the resources within the controller that should be reset. Rework suspend and resume logic so they perform properly Made attach and detach functions optional. As they do not make sense for a bus powered device. Ensured the calls to up_usbinitalize up_usbuninitalize do not violate the USB spec. --- arch/arm/src/kinetis/kinetis_usbdev.c | 631 ++++++++++++++------------ arch/arm/src/kinetis/kinetis_usbotg.h | 4 +- 2 files changed, 333 insertions(+), 302 deletions(-) diff --git a/arch/arm/src/kinetis/kinetis_usbdev.c b/arch/arm/src/kinetis/kinetis_usbdev.c index c550fbd325..20bfa9a92a 100644 --- a/arch/arm/src/kinetis/kinetis_usbdev.c +++ b/arch/arm/src/kinetis/kinetis_usbdev.c @@ -1,8 +1,9 @@ /**************************************************************************** * arch/arm/src/kinetis/kinetis_usbdev.c * - * Copyright (C) 2011-2014, 2016 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Copyright (C) 2011-2014, 2016-2017 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * David Sidrane * * References: * This file derives from the STM32 USB device driver with modifications @@ -12,6 +13,9 @@ * - Sample code provided with the Sure Electronics PIC32 board * (which seems to have derived from Microchip PICDEM PIC18 code). * + * K66 Sub-Family Reference Manual, Rev. 2, May 2015 + * How to Implement USB Suspend/Resume - Document Number: AN5385 + * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: @@ -169,6 +173,7 @@ /* Endpoint register initialization parameters */ +#define KHCI_EP_DISABLED (0) #define KHCI_EP_CONTROL (USB_ENDPT_EPHSHK | USB_ENDPT_EPTXEN | USB_ENDPT_EPRXEN) #define KHCI_EP_BULKIN (USB_ENDPT_EPTXEN | USB_ENDPT_EPCTLDIS | USB_ENDPT_EPHSHK) #define KHCI_EP_BULKOUT (USB_ENDPT_EPRXEN | USB_ENDPT_EPCTLDIS | USB_ENDPT_EPHSHK) @@ -189,6 +194,10 @@ #define RESTART_DELAY (150 * CLOCKS_PER_SEC / 1000) +#define USB0_USBTRC0_BIT6 0x40 /* Undocumented bit that is set in the + * Kinetis lib + */ + /* USB trace ****************************************************************/ /* Trace error codes */ @@ -256,7 +265,8 @@ #define KHCI_TRACEINTID_STALL 0x0021 #define KHCI_TRACEINTID_UERR 0x0022 #define KHCI_TRACEINTID_SUSPENDED 0x0023 -#define KHCI_TRACEINTID_WAITRESET 0x0024 +#define KHCI_TRACEINTID_RESUME 0x0024 +#define KHCI_TRACEINTID_WAITRESET 0x0025 #ifdef CONFIG_USBDEV_TRACE_STRINGS const struct trace_msg_t g_usb_trace_strings_intdecode[] = @@ -296,7 +306,8 @@ const struct trace_msg_t g_usb_trace_strings_intdecode[] = TRACE_STR(KHCI_TRACEINTID_STALL ), /* 0x0021 */ TRACE_STR(KHCI_TRACEINTID_UERR ), /* 0x0022 */ TRACE_STR(KHCI_TRACEINTID_SUSPENDED ), /* 0x0023 */ - TRACE_STR(KHCI_TRACEINTID_WAITRESET ), /* 0x0024 */ + TRACE_STR(KHCI_TRACEINTID_RESUME ), /* 0x0024 */ + TRACE_STR(KHCI_TRACEINTID_WAITRESET ), /* 0x0025 */ TRACE_STR_END }; #endif @@ -508,6 +519,7 @@ static void khci_putreg(uint32_t val, uint32_t addr); /* Suspend/Resume Helpers ***************************************************/ static void khci_suspend(struct khci_usbdev_s *priv); +static void khci_remote_resume(struct khci_usbdev_s *priv); static void khci_resume(struct khci_usbdev_s *priv); /* Request Queue Management *************************************************/ @@ -606,10 +618,13 @@ static int khci_selfpowered(struct usbdev_s *dev, bool selfpowered); static void khci_reset(struct khci_usbdev_s *priv); static void khci_attach(struct khci_usbdev_s *priv); +#if defined(CONFIG_USBDEV_SELFPOWERED) static void khci_detach(struct khci_usbdev_s *priv); +#endif static void khci_swreset(struct khci_usbdev_s *priv); static void khci_hwreset(struct khci_usbdev_s *priv); -static void khci_stateinit(struct khci_usbdev_s *priv); +static void khci_swinitalize(struct khci_usbdev_s *priv); +static void khci_hwinitalize(struct khci_usbdev_s *priv); static void khci_hwshutdown(struct khci_usbdev_s *priv); /**************************************************************************** @@ -767,7 +782,6 @@ static struct khci_req_s *khci_remfirst(struct khci_queue_s *queue) return ret; } - /**************************************************************************** * Name: khci_remlast ****************************************************************************/ @@ -2715,25 +2729,26 @@ static void khci_ep0transfer(struct khci_usbdev_s *priv, uint16_t ustat) static int khci_interrupt(int irq, void *context, FAR void *arg) { - /* For now there is only one USB controller, but we will always refer to - * it using a pointer to make any future ports to multiple USB controllers - * easier. - */ - - struct khci_usbdev_s *priv = &g_usbdev; uint16_t usbir; - uint16_t otgir; uint32_t regval; int i; +#ifdef CONFIG_USBOTG + uint16_t otgir; +#endif + + struct khci_usbdev_s *priv = (struct khci_usbdev_s *) arg; /* Get the set of pending USB and OTG interrupts interrupts */ usbir = khci_getreg(KINETIS_USB0_ISTAT) & khci_getreg(KINETIS_USB0_INTEN); + +#if !defined(CONFIG_USBOTG) + usbtrace(TRACE_INTENTRY(KHCI_TRACEINTID_INTERRUPT), usbir); +#else otgir = khci_getreg(KINETIS_USB0_OTGISTAT) & khci_getreg(KINETIS_USB0_OTGICR); usbtrace(TRACE_INTENTRY(KHCI_TRACEINTID_INTERRUPT), usbir | otgir); -#ifdef CONFIG_USBOTG /* Session Request Protocol (SRP) Time Out Check */ /* Check if USB OTG SRP is ready */ @@ -2759,69 +2774,36 @@ static int khci_interrupt(int irq, void *context, FAR void *arg) } #endif - /* Handle events while we are in the attached state */ + /* Handle events while we are in the attached state */ if (priv->devstate == DEVSTATE_ATTACHED) { - /* Clear all USB interrupts */ - - khci_putreg(USB_INT_ALL, KINETIS_USB0_ISTAT); - - /* Make sure that the USE reset and IDLE detect interrupts are enabled */ - - regval = khci_getreg(KINETIS_USB0_INTEN); - regval |= (USB_INT_USBRST | USB_INT_SLEEP); - khci_putreg(regval, KINETIS_USB0_INTEN); - /* Now were are in the powered state */ priv->devstate = DEVSTATE_POWERED; } -#ifdef CONFIG_USBOTG - /* Check if the ID Pin Changed State */ + /* Service error interrupts */ - if ((otgir & USBOTG_INT_ID) != 0) + if ((usbir & USB_INT_ERROR) != 0) { - usbtrace(TRACE_INTDECODE(KHCI_TRACEINTID_OTGID), otgir); + usbtrace(TRACE_INTDECODE(KHCI_TRACEINTID_UERR), usbir); + uerr("ERROR: EIR=%04x\n", khci_getreg(KINETIS_USB0_ERRSTAT)); - /* Re-detect and re-initialize */ -#warning "Missing logic" + /* Clear all pending USB error interrupts */ - khci_putreg(USBOTG_INT_ID, KINETIS_USB0_ISTAT); + khci_putreg(USB_EINT_ALL, KINETIS_USB0_ERRSTAT); } -#endif -#if 0 - /* Service the USB Activity Interrupt */ - - if ((otgir & USBOTG_INT_ACTV) != 0) - { - usbtrace(TRACE_INTDECODE(KHCI_TRACEINTID_WKUP), otgir); - /* Wake-up from susepnd mode */ + /* Service resume interrupts */ - khci_putreg(USBOTG_INT_ACTV, KINETIS_USB0_ISTAT); - khci_resume(priv); - } - - /* It is pointless to continue servicing if the device is in suspend mode. */ -x - if ((khci_getreg(KINETIS_USB0_CTL) & USB_USBCTRL_SUSP) != 0) + if ((usbir & USB_INT_RESUME) != 0) { - /* Just clear the interrupt and return */ - - usbtrace(TRACE_INTDECODE(KHCI_TRACEINTID_SUSPENDED), khci_getreg(KINETIS_USB0_CTL)); - goto interrupt_exit; + usbtrace(TRACE_INTDECODE(KHCI_TRACEINTID_RESUME), usbir); + khci_resume(priv); } -#endif - /* Service USB Bus Reset Interrupt. When bus reset is received during - * suspend, ACTVIF will be set first, once the UCONbits.SUSPND is clear, - * then the URSTIF bit will be asserted. This is why URSTIF is checked - * after ACTVIF. The USB reset flag is masked when the USB state is in - * DEVSTATE_DETACHED or DEVSTATE_ATTACHED, and therefore cannot cause a - * USB reset event during these two states. - */ + /* Service USB Bus Reset Interrupt. */ if ((usbir & USB_INT_USBRST) != 0) { @@ -2831,7 +2813,13 @@ x * hardware automatically resets the USB address, so we really just * need reset any existing configuration/transfer states. */ - khci_reset(priv); + + khci_swreset(priv); + khci_hwreset(priv); + + /* Configure EP0 */ + + khci_ep0configure(priv); priv->devstate = DEVSTATE_DEFAULT; #ifdef CONFIG_USBOTG @@ -2844,72 +2832,17 @@ x goto interrupt_exit; } - /* Service IDLE interrupts */ - - if ((usbir & USB_INT_SLEEP) != 0) - { - usbtrace(TRACE_INTDECODE(KHCI_TRACEINTID_IDLE), usbir); - #ifdef CONFIG_USBOTG - /* If Suspended, Try to switch to Host */ -#warning "Missing logic" -#else - khci_suspend(priv); - -#endif - khci_putreg(USB_INT_SLEEP, KINETIS_USB0_ISTAT); - } - - /* Service SOF interrupts */ - -#ifdef CONFIG_USB_SOFINTS - if ((usbir & USB_INT_SOFTOK) != 0) - { - usbtrace(TRACE_INTDECODE(KHCI_TRACEINTID_SOF), 0); - - /* I am not sure why you would ever enable SOF interrupts */ - - khci_putreg(USB_INT_SOFTOK, KINETIS_USB0_ISTAT); - } -#endif - - /* Service stall interrupts */ - - if ((usbir & USB_INT_STALL) != 0) - { - usbtrace(TRACE_INTDECODE(KHCI_TRACEINTID_STALL), usbir); - - khci_ep0stall(priv); - - /* Clear the pending STALL interrupt */ - - khci_putreg(USB_INT_STALL, KINETIS_USB0_ISTAT); - } - - /* Service error interrupts */ + /* Check if the ID Pin Changed State */ - if ((usbir & USB_INT_ERROR) != 0) + if ((otgir & USBOTG_INT_ID) != 0) { - usbtrace(TRACE_INTDECODE(KHCI_TRACEINTID_UERR), usbir); - uerr("ERROR: EIR=%04x\n", khci_getreg(KINETIS_USB0_ERRSTAT)); - - /* Clear all pending USB error interrupts */ - - khci_putreg(USB_EINT_ALL, KINETIS_USB0_ERRSTAT); - } - - /* There is no point in continuing if the host has not sent a bus reset. - * Once bus reset is received, the device transitions into the DEFAULT - * state and is ready for communication. - */ + usbtrace(TRACE_INTDECODE(KHCI_TRACEINTID_OTGID), otgir); -#if 0 - if (priv->devstate < DEVSTATE_DEFAULT) - { - /* Just clear the interrupt and return */ + /* Re-detect and re-initialize */ +#warning "Missing logic" - usbtrace(TRACE_INTDECODE(KHCI_TRACEINTID_WAITRESET), priv->devstate); - goto interrupt_exit; + khci_putreg(USBOTG_INT_ID, KINETIS_USB0_ISTAT); } #endif @@ -2958,7 +2891,57 @@ x } } - UNUSED(otgir); /* May not be used, depending on above conditional logic */ + /* Service IDLE interrupts */ + + if ((usbir & USB_INT_SLEEP) != 0) + { + usbtrace(TRACE_INTDECODE(KHCI_TRACEINTID_IDLE), usbir); + +#ifdef CONFIG_USBOTG + /* If Suspended, Try to switch to Host */ +#warning "Missing logic" +#else + khci_suspend(priv); + +#endif + khci_putreg(USB_INT_SLEEP, KINETIS_USB0_ISTAT); + } + + /* It is pointless to continue servicing if the device is in suspend mode. */ + + if ((khci_getreg(KINETIS_USB0_USBCTRL) & USB_USBCTRL_SUSP) != 0) + { + /* Just clear the interrupt and return */ + + usbtrace(TRACE_INTDECODE(KHCI_TRACEINTID_SUSPENDED), khci_getreg(KINETIS_USB0_CTL)); + goto interrupt_exit; + } + + /* Service SOF interrupts */ + +#ifdef CONFIG_USB_SOFINTS + if ((usbir & USB_INT_SOFTOK) != 0) + { + usbtrace(TRACE_INTDECODE(KHCI_TRACEINTID_SOF), 0); + + /* I am not sure why you would ever enable SOF interrupts */ + + khci_putreg(USB_INT_SOFTOK, KINETIS_USB0_ISTAT); + } +#endif + + /* Service stall interrupts */ + + if ((usbir & USB_INT_STALL) != 0) + { + usbtrace(TRACE_INTDECODE(KHCI_TRACEINTID_STALL), usbir); + + khci_ep0stall(priv); + + /* Clear the pending STALL interrupt */ + + khci_putreg(USB_INT_STALL, KINETIS_USB0_ISTAT); + } /* Clear the pending USB interrupt. Goto is used in the above to assure * that all interrupt exists pass through this logic. @@ -2966,7 +2949,11 @@ x interrupt_exit: kinetis_clrpend(KINETIS_IRQ_USBOTG); +#ifdef CONFIG_USBOTG usbtrace(TRACE_INTEXIT(KHCI_TRACEINTID_INTERRUPT), usbir | otgir); +#else + usbtrace(TRACE_INTEXIT(KHCI_TRACEINTID_INTERRUPT), usbir); +#endif return OK; } @@ -2979,9 +2966,7 @@ interrupt_exit: static void khci_suspend(struct khci_usbdev_s *priv) { -#if 0 uint32_t regval; -#endif /* Notify the class driver of the suspend event */ @@ -2990,47 +2975,41 @@ static void khci_suspend(struct khci_usbdev_s *priv) CLASS_SUSPEND(priv->driver, &priv->usbdev); } -#if 0 - /* Enable the ACTV interrupt. - * - * NOTE: Do not clear UIRbits.ACTVIF here! Reason: ACTVIF is only - * generated once an IDLEIF has been generated. This is a 1:1 ratio - * interrupt generation. For every IDLEIF, there will be only one ACTVIF - * regardless of the number of subsequent bus transitions. If the ACTIF - * is cleared here, a problem could occur. The driver services IDLEIF - * first because ACTIVIE=0. If this routine clears the only ACTIVIF, - * then it can never get out of the suspend mode. - */ - - regval = khci_getreg(KINETIS_USB0_OTGICR); - regval |= USBOTG_INT_ACTV; - khci_putreg(regval, KINETIS_USB0_OTGICR); - /* Disable further IDLE interrupts. Once is enough. */ regval = khci_getreg(KINETIS_USB0_INTEN); regval &= ~USB_INT_SLEEP; khci_putreg(regval, KINETIS_USB0_INTEN); -#endif + + /* Enable Resume */ + + regval |= USB_INT_RESUME; + khci_putreg(regval, KINETIS_USB0_INTEN); + + regval = khci_getreg(KINETIS_USB0_USBTRC0); + regval |= USB_USBTRC0_USBRESMEN; + khci_putreg(regval, KINETIS_USB0_USBTRC0); /* Invoke a callback into board-specific logic. The board-specific logic * may enter into sleep or idle modes or switch to a slower clock, etc. */ kinetis_usbsuspend((struct usbdev_s *)priv, false); + + regval = khci_getreg(KINETIS_USB0_USBCTRL); + regval |= USB_USBCTRL_SUSP; + khci_putreg(regval, KINETIS_USB0_USBCTRL); + } /**************************************************************************** - * Name: khci_resume + * Name: khci_remote_resume ****************************************************************************/ -static void khci_resume(struct khci_usbdev_s *priv) +static void khci_remote_resume(struct khci_usbdev_s *priv) { - irqstate_t flags; uint32_t regval; - flags = enter_critical_section(); - /* Start RESUME signaling */ regval = khci_getreg(KINETIS_USB0_CTL); @@ -3043,33 +3022,50 @@ static void khci_resume(struct khci_usbdev_s *priv) regval &= ~USB_CTL_RESUME; khci_putreg(regval, KINETIS_USB0_CTL); +} - /* This function is called when the USB activity interrupt occurs. +/**************************************************************************** + * Name: khci_resume + ****************************************************************************/ + +static void khci_resume(struct khci_usbdev_s *priv) +{ + irqstate_t flags; + uint32_t regval; + + flags = enter_critical_section(); + + /* This function is called when the USB resume interrupt occurs. * If using clock switching, this is the place to call out to * logic to restore the original MCU core clock frequency. */ kinetis_usbsuspend((struct usbdev_s *)priv, true); - /* Disable further activity interrupts */ -#if 0 - regval = khci_getreg(KINETIS_USB0_OTGICR); - regval &= ~USBOTG_INT_ACTV; - khci_putreg(regval, KINETIS_USB0_OTGICR); -#endif + /* Unsuspend */ - /* The ACTVIF bit cannot be cleared immediately after the USB module wakes - * up from Suspend or while the USB module is suspended. A few clock cycles - * are required to synchronize the internal hardware state machine before - * the ACTIVIF bit can be cleared by firmware. Clearing the ACTVIF bit - * before the internal hardware is synchronized may not have an effect on - * the value of ACTVIF. Additionally, if the USB module uses the clock from - * the 96 MHz PLL source, then after clearing the SUSPND bit, the USB - * module may not be immediately operational while waiting for the 96 MHz - * PLL to lock. - */ + regval = khci_getreg(KINETIS_USB0_USBCTRL); + regval &= ~USB_USBCTRL_SUSP; + khci_putreg(regval, KINETIS_USB0_USBCTRL); + + /* Enable the IDLE interrupt */ + + regval = khci_getreg(KINETIS_USB0_INTEN); + regval |= USB_INT_SLEEP; + khci_putreg(regval, KINETIS_USB0_INTEN); + + /* Disable the RESUME interrupt */ + + regval &= ~USB_INT_RESUME; + khci_putreg(regval, KINETIS_USB0_INTEN); + + /* Disable the the async resume interrupt */ + + regval = khci_getreg(KINETIS_USB0_USBTRC0); + regval &= ~USB_USBTRC0_USBRESMEN; + khci_putreg(regval, KINETIS_USB0_USBTRC0); - khci_putreg(USB_INT_SLEEP, KINETIS_USB0_ISTAT); + khci_putreg(USB_INT_RESUME, KINETIS_USB0_ISTAT); /* Notify the class driver of the resume event */ @@ -3149,22 +3145,21 @@ khci_epreserved(struct khci_usbdev_s *priv, int epno) /**************************************************************************** * Name: khci_ep0configure ****************************************************************************/ - static void khci_ep0configure(struct khci_usbdev_s *priv) { volatile struct usbotg_bdtentry_s *bdt; struct khci_ep_s *ep0; uint32_t bytecount; - /* Enable the EP0 endpoint */ - - khci_putreg(KHCI_EP_CONTROL, KINETIS_USB0_ENDPT0); - /* Configure the OUT BDTs. We assume that the ping-poing buffer index has * just been reset and we expect to receive on the EVEN BDT first. Data * toggle synchronization is not needed for SETUP packets. */ + /* Disabled the Endpoint first */ + + khci_putreg(KHCI_EP_DISABLED, KINETIS_USB0_ENDPT0); + ep0 = &priv->eplist[EP0]; bytecount = (USB_SIZEOF_CTRLREQ << USB_BDT_BYTECOUNT_SHIFT); @@ -3194,6 +3189,10 @@ static void khci_ep0configure(struct khci_usbdev_s *priv) ep0->rxdata1 = 0; ep0->txdata1 = 1; + + /* Enable the EP0 endpoint */ + + khci_putreg(KHCI_EP_CONTROL, KINETIS_USB0_ENDPT0); } /**************************************************************************** @@ -3260,9 +3259,9 @@ static int khci_epconfigure(struct usbdev_ep_s *ep, return -EINVAL; } - /* Enable the endpoint */ + /* First disable the endpoint */ - khci_putreg(regval, KINETIS_USB0_ENDPT(epno)); + khci_putreg(KHCI_EP_DISABLED, KINETIS_USB0_ENDPT(epno)); /* Setup up buffer descriptor table (BDT) entry/ies for this endpoint */ @@ -3333,6 +3332,8 @@ static int khci_epconfigure(struct usbdev_ep_s *ep, ep->eplog = USB_EPOUT(epno); } + khci_putreg(regval, KINETIS_USB0_ENDPT(epno)); + return OK; } @@ -3368,7 +3369,7 @@ static int khci_epdisable(struct usbdev_ep_s *ep) /* Disable the endpoint */ - khci_putreg(0, KINETIS_USB0_ENDPT(epno)); + khci_putreg(KHCI_EP_DISABLED, KINETIS_USB0_ENDPT(epno)); /* Reset the BDTs for the endpoint. Four BDT entries per endpoint; Two * 32-bit words per BDT. @@ -3924,7 +3925,7 @@ static int khci_wakeup(struct usbdev_s *dev) /* Resume normal operation. */ - khci_resume(priv); + khci_remote_resume(priv); return OK; } @@ -4003,25 +4004,24 @@ static void khci_attach(struct khci_usbdev_s *priv) /* Disable USB interrupts at the interrupt controller */ up_disable_irq(KINETIS_IRQ_USBOTG); + + /* Initialize the controller to known states. */ - /* Initialize registers to known states. */ + khci_putreg(USB_CTL_USBENSOFEN, KINETIS_USB0_CTL); -#if 1 - khci_putreg(0x1,KINETIS_USB0_CTL); - khci_putreg(0,KINETIS_USB0_USBCTRL); -#endif + /* Configure things like: pull ups, full/low-speed mode, + * set the ping pong mode, and set internal transceiver + */ + + khci_putreg(0, KINETIS_USB0_USBCTRL); /* Enable interrupts at the USB controller */ khci_putreg(ERROR_INTERRUPTS, KINETIS_USB0_ERREN); khci_putreg(NORMAL_INTERRUPTS, KINETIS_USB0_INTEN); - /* Configure EP0 */ - - khci_ep0configure(priv); - /* Flush any pending transactions */ -#if 1 + while ((khci_getreg(KINETIS_USB0_ISTAT) & USB_INT_TOKDNE) != 0) { khci_putreg(USB_INT_TOKDNE, KINETIS_USB0_ISTAT); @@ -4053,6 +4053,10 @@ static void khci_attach(struct khci_usbdev_s *priv) khci_putreg(regval, KINETIS_USB0_OTGCTL); #endif + /* Configure EP0 */ + + khci_ep0configure(priv); + /* Transition to the attached state */ priv->devstate = DEVSTATE_ATTACHED; @@ -4062,20 +4066,17 @@ static void khci_attach(struct khci_usbdev_s *priv) khci_putreg(USB_EINT_ALL, KINETIS_USB0_ERRSTAT); khci_putreg(USB_INT_ALL, KINETIS_USB0_ISTAT); -#endif + + kinetis_clrpend(KINETIS_IRQ_USBOTG); /* Enable USB interrupts at the interrupt controller */ up_enable_irq(KINETIS_IRQ_USBOTG); - /* Enable pull-up to connect the device. The host should enumerate us - * some time after this - */ - - kinetis_usbpullup(&priv->usbdev, true); } } +#if defined(CONFIG_USBDEV_SELFPOWERED) /**************************************************************************** * Name: khci_detach ****************************************************************************/ @@ -4126,7 +4127,7 @@ static void khci_detach(struct khci_usbdev_s *priv) } #endif } - +#endif /**************************************************************************** * Name: khci_swreset ****************************************************************************/ @@ -4144,9 +4145,9 @@ static void khci_swreset(struct khci_usbdev_s *priv) CLASS_DISCONNECT(priv->driver, &priv->usbdev); } - /* Flush and reset endpoint states (except EP0) */ + /* Flush and reset endpoint states */ - for (epno = 1; epno < KHCI_NENDPOINTS; epno++) + for (epno = 0; epno < KHCI_NENDPOINTS; epno++) { struct khci_ep_s *privep = &priv->eplist[epno]; @@ -4158,7 +4159,7 @@ static void khci_swreset(struct khci_usbdev_s *priv) * for each of its configured endpoints. */ - khci_cancelrequests(privep, -EAGAIN); + khci_cancelrequests(privep, -ESHUTDOWN); /* Reset endpoint status */ @@ -4167,18 +4168,7 @@ static void khci_swreset(struct khci_usbdev_s *priv) privep->txnullpkt = false; } - /* Reset to the default address */ - - khci_putreg(0, KINETIS_USB0_ADDR); - - /* Unconfigure each endpoint by clearing the endpoint control registers - * (except EP0) - */ - - for (epno = 1; epno < KHCI_NENDPOINTS; epno++) - { - khci_putreg(0, KINETIS_USB0_ENDPT(epno)); - } + priv->devstate = DEVSTATE_DETACHED; /* Reset the control state */ @@ -4196,31 +4186,79 @@ static void khci_swreset(struct khci_usbdev_s *priv) static void khci_hwreset(struct khci_usbdev_s *priv) { + int epno; uint32_t regval; -#define USB_FLASH_ACCESS -#ifdef USB_FLASH_ACCESS - /* Allow USBOTG-FS Controller to Read from FLASH */ + /* When bus reset is received during suspend, ensure we resume */ - regval = getreg32(KINETIS_FMC_PFAPR); - regval &= ~(FMC_PFAPR_M4AP_MASK); - regval |= (FMC_PFAPR_RDONLY << FMC_PFAPR_M4AP_SHIFT); - putreg32(regval, KINETIS_FMC_PFAPR); -#endif + if ((khci_getreg(KINETIS_USB0_USBCTRL) & USB_USBCTRL_SUSP) != 0) + { + khci_resume(priv); + } - /* Clear all of the buffer descriptor table (BDT) entries */ + /* Unconfigure each endpoint by clearing the endpoint control registers */ - memset((void *)g_bdt, 0, sizeof(g_bdt)); + for (epno = 0; epno < KHCI_NENDPOINTS; epno++) + { + khci_putreg(KHCI_EP_DISABLED, KINETIS_USB0_ENDPT(epno)); + } - /* Soft reset the USB Module */ + /* Reset the address */ + + khci_putreg(0, KINETIS_USB0_ADDR); + + /* Assert reset request to all of the Ping Pong buffer pointers. This + * will reset all Even/Odd buffer pointers to the EVEN BD banks. + */ + + regval = khci_getreg(KINETIS_USB0_CTL); + regval |= USB_CTL_ODDRST; + khci_putreg(regval, KINETIS_USB0_CTL); + + /* Bring the ping pong buffer pointers out of reset */ + + regval &= ~USB_CTL_ODDRST; + khci_putreg(regval, KINETIS_USB0_CTL); + + /* Enable interrupts at the USB controller */ + + khci_putreg(ERROR_INTERRUPTS, KINETIS_USB0_ERREN); + khci_putreg(NORMAL_INTERRUPTS, KINETIS_USB0_INTEN); +} + +/**************************************************************************** + * Name: khci_hwinitalize + * + * Description: + * Reset the hardware and leave it in a known, unready state. + * + ****************************************************************************/ + +static void khci_hwinitalize(struct khci_usbdev_s *priv) +{ + uint32_t regval; + + /* Initialize registers to known states. */ + + /* Reset USB Module */ regval = khci_getreg(KINETIS_USB0_USBTRC0); regval |= USB_USBTRC0_USBRESET; - khci_putreg(regval,KINETIS_USB0_USBTRC0); + khci_putreg(regval, KINETIS_USB0_USBTRC0); + + /* NOTE: This bit is always read as zero. Wait two + * USB clock cycles after setting this bit.That is ~42 Ns + */ + + /* Clear all of the buffer descriptor table (BDT) entries */ + + memset((void *)g_bdt, 0, sizeof(g_bdt)); - /* Is this really necessary? */ + /* Enable the USB-FS to operate */ - while (khci_getreg(KINETIS_USB0_USBTRC0) & USB_USBTRC0_USBRESET); + khci_putreg(0, KINETIS_USB0_CTL); + up_udelay(2); + khci_putreg(USB_CTL_USBENSOFEN, KINETIS_USB0_CTL); /* Set the address of the buffer descriptor table (BDT) * @@ -4231,59 +4269,31 @@ static void khci_hwreset(struct khci_usbdev_s *priv) khci_putreg((uint8_t)((uint32_t)g_bdt >> 24), KINETIS_USB0_BDTPAGE3); khci_putreg((uint8_t)((uint32_t)g_bdt >> 16), KINETIS_USB0_BDTPAGE2); - khci_putreg((uint8_t)(((uint32_t)g_bdt >> 8) & USB_BDTPAGE1_MASK), KINETIS_USB0_BDTPAGE1); + khci_putreg((uint8_t)(((uint32_t)g_bdt >> 8) & USB_BDTPAGE1_MASK), KINETIS_USB0_BDTPAGE1); uinfo("BDT Address %hhx \n" ,&g_bdt); uinfo("BDTPAGE3 %hhx\n",khci_getreg(KINETIS_USB0_BDTPAGE3)); uinfo("BDTPAGE2 %hhx\n",khci_getreg(KINETIS_USB0_BDTPAGE2)); uinfo("BDTPAGE1 %hhx\n",khci_getreg(KINETIS_USB0_BDTPAGE1)); - /* Clear any pending interrupts */ - - khci_putreg(0xFF, KINETIS_USB0_ERRSTAT); - khci_putreg(0xFF, KINETIS_USB0_ISTAT); - khci_putreg(0xFF,KINETIS_USB0_OTGISTAT); - -#if 1 - /* Assert reset request to all of the Ping Pong buffer pointers. This - * will reset all Even/Odd buffer pointers to the EVEN BD banks. - */ - - regval = khci_getreg(KINETIS_USB0_CTL); - regval |= USB_CTL_ODDRST; - khci_putreg(regval, KINETIS_USB0_CTL); - - /* Bring the ping pong buffer pointers out of reset */ - - regval &= ~USB_CTL_ODDRST; - khci_putreg(regval, KINETIS_USB0_CTL); -#endif - -#if 1 +#if defined(USB0_USBTRC0_BIT6) /* Undocumented bit */ regval = khci_getreg(KINETIS_USB0_USBTRC0); - regval |= 0x40; + regval |= USB0_USBTRC0_BIT6; khci_putreg(regval,KINETIS_USB0_USBTRC0); #endif - priv->devstate = DEVSTATE_DETACHED; } /**************************************************************************** - * Name: khci_stateinit + * Name: khci_swinitalize ****************************************************************************/ -static void khci_stateinit(struct khci_usbdev_s *priv) +static void khci_swinitalize(struct khci_usbdev_s *priv) { int epno; - /* Disconnect the device / disable the pull-up. We don't want the - * host to enumerate us until the class driver is registered. - */ - - kinetis_usbpullup(&priv->usbdev, false); - /* Initialize the device state structure. NOTE: many fields * have the initial value of zero and, hence, are not explicitly * initialized here. @@ -4292,9 +4302,22 @@ static void khci_stateinit(struct khci_usbdev_s *priv) memset(priv, 0, sizeof(struct khci_usbdev_s)); priv->usbdev.ops = &g_devops; priv->usbdev.ep0 = &priv->eplist[EP0].ep; + priv->usbdev.speed = USB_SPEED_UNKNOWN; priv->epavail = KHCI_ENDP_ALLSET & ~KHCI_ENDP_BIT(EP0); priv->rwakeup = 1; +#if defined(CONFIG_USBDEV_BUSPOWERED) + /* Since this code is running we are physically attached to power */ + + priv->attached = 1; +#endif + + /* Initialize the watchdog timer that is used to perform a delayed + * queue restart after recovering from a stall. + */ + + priv->wdog = wd_create(); + /* Initialize the endpoint list */ for (epno = 0; epno < KHCI_NENDPOINTS; epno++) @@ -4332,15 +4355,6 @@ static void khci_stateinit(struct khci_usbdev_s *priv) static void khci_hwshutdown(struct khci_usbdev_s *priv) { -#if 0 - uint32_t regval; -#endif - - /* Put the hardware and driver in its initial, unconnected state */ - - khci_swreset(priv); - khci_hwreset(priv); - priv->usbdev.speed = USB_SPEED_UNKNOWN; /* Disable all interrupts and force the USB controller into reset */ @@ -4352,18 +4366,7 @@ static void khci_hwshutdown(struct khci_usbdev_s *priv) khci_putreg(USB_EINT_ALL, KINETIS_USB0_ERRSTAT); khci_putreg(USB_INT_ALL, KINETIS_USB0_ISTAT); - /* Disconnect the device / disable the pull-up */ - - kinetis_usbpullup(&priv->usbdev, false); - - /* Power down the USB controller */ -#warning FIXME powerdown USB Controller - -#if 0 - regval = khci_getreg(KHCI_USB_PWRC); - regval &= ~USB_PWRC_USBPWR; - khci_putreg(regval, KHCI_USB_PWRC); -#endif + kinetis_clrpend(KINETIS_IRQ_USBOTG); } /**************************************************************************** @@ -4376,6 +4379,13 @@ static void khci_hwshutdown(struct khci_usbdev_s *priv) * Description: * Initialize the USB driver * + * Assumptions: + * - This function is called very early in the initialization sequence + * - PLL and GIO pin initialization is not performed here but should been in + * the low-level boot logic: SIM_SOPT2[PLLFLLSEL] and + * SIM_CLKDIV2[USBFRAC, USBDIV] will have been configured in + * kinetis_pllconfig. + * * Input Parameters: * None * @@ -4386,20 +4396,28 @@ static void khci_hwshutdown(struct khci_usbdev_s *priv) void up_usbinitialize(void) { - struct khci_usbdev_s *priv = &g_usbdev; - uint32_t regval; - /* For now there is only one USB controller, but we will always refer to * it using a pointer to make any future ports to multiple USB controllers * easier. */ + struct khci_usbdev_s *priv = &g_usbdev; + uint32_t regval; + + usbtrace(TRACE_DEVINIT, 0); + + /* Initialize the driver state structure */ + + khci_swinitalize(priv); + /* Select clock source: * SIM_SOPT2[PLLFLLSEL] and SIM_CLKDIV2[USBFRAC, USBDIV] will have been * configured in kinetis_pllconfig. So here we select between USB_CLKIN * or the output of SIM_CLKDIV2[USBFRAC, USBDIV] */ + /* 1: Select USB clock */ + regval = getreg32(KINETIS_SIM_SOPT2); regval &= ~(SIM_SOPT2_USBSRC); regval |= BOARD_USB_CLKSRC; @@ -4411,19 +4429,16 @@ void up_usbinitialize(void) regval |= SIM_SCGC4_USBOTG; putreg32(regval, KINETIS_SIM_SCGC4); - usbtrace(TRACE_DEVINIT, 0); - - /* Initialize the driver state structure */ - - khci_stateinit(priv); +#if defined(BOARD_USB_FLASHACCESS) + /* Allow USBOTG-FS Controller to Read from FLASH */ - /* Then perform a few one-time initialization operstions. First, initialize - * the watchdog timer that is used to perform a delayed queue restart - * after recovering from a stall. - */ + regval = getreg32(KINETIS_FMC_PFAPR); + regval &= ~(FMC_PFAPR_M4AP_MASK); + regval |= (FMC_PFAPR_RDONLY << FMC_PFAPR_M4AP_SHIFT); + putreg32(regval, KINETIS_FMC_PFAPR); +#endif - priv->epstalled = 0; - priv->wdog = wd_create(); + khci_swreset(priv); /* Attach USB controller interrupt handler. The hardware will not be * initialized and interrupts will not be enabled until the class device @@ -4431,11 +4446,12 @@ void up_usbinitialize(void) * them when we need them later. */ - if (irq_attach(KINETIS_IRQ_USBOTG, khci_interrupt, NULL) != 0) + if (irq_attach(KINETIS_IRQ_USBOTG, khci_interrupt, priv) != 0) { usbtrace(TRACE_DEVERROR(KHCI_TRACEERR_IRQREGISTRATION), (uint16_t)KINETIS_IRQ_USBOTG); up_usbuninitialize(); + return; } #ifdef CONFIG_ARCH_IRQPRIO @@ -4443,6 +4459,8 @@ void up_usbinitialize(void) up_prioritize_irq(KINETIS_IRQ_USBOTG, 112); #endif + + khci_hwinitalize(priv); } /**************************************************************************** @@ -4466,24 +4484,36 @@ void up_usbuninitialize(void) struct khci_usbdev_s *priv = &g_usbdev; irqstate_t flags; + uint32_t regval; - flags = enter_critical_section(); usbtrace(TRACE_DEVUNINIT, 0); + /* Disconnect the device */ + + flags = enter_critical_section(); + + khci_swreset(priv); + + kinetis_usbpullup(&priv->usbdev, false); + + wd_delete(priv->wdog); + + /* Put the hardware in an inactive state */ + + khci_hwreset(priv); + khci_hwshutdown(priv); + /* Disable and detach the USB IRQs */ up_disable_irq(KINETIS_IRQ_USBOTG); irq_detach(KINETIS_IRQ_USBOTG); - if (priv->driver) - { - usbtrace(TRACE_DEVERROR(KHCI_TRACEERR_DRIVERREGISTERED), 0); - usbdev_unregister(priv->driver); - } + /* Gate Off the USB controller */ - /* Put the hardware in an inactive state */ + regval = getreg32(KINETIS_SIM_SCGC4); + regval &= ~SIM_SCGC4_USBOTG; + putreg32(regval, KINETIS_SIM_SCGC4); - khci_hwshutdown(priv); leave_critical_section(flags); } @@ -4590,6 +4620,7 @@ int usbdev_unregister(struct usbdevclass_driver_s *driver) flags = enter_critical_section(); khci_swreset(priv); + kinetis_usbpullup(&priv->usbdev, false); khci_hwreset(priv); /* Unbind the class driver */ @@ -4606,15 +4637,13 @@ int usbdev_unregister(struct usbdevclass_driver_s *driver) */ khci_hwshutdown(priv); - khci_stateinit(priv); - - /* Unhook the driver */ + khci_swinitalize(priv); - priv->driver = NULL; leave_critical_section(flags); return OK; } +#if defined(CONFIG_USBDEV_SELFPOWERED) /**************************************************************************** * Name: khci_usbattach and khci_usbdetach * @@ -4664,5 +4693,5 @@ void khci_usbdetach(void) khci_detach(priv); } - +#endif /* CONFIG_USBDEV_SELFPOWERED */ #endif /* CONFIG_USBDEV && CONFIG_KHCI_USB */ diff --git a/arch/arm/src/kinetis/kinetis_usbotg.h b/arch/arm/src/kinetis/kinetis_usbotg.h index 655c7ccee9..fdd03567c4 100644 --- a/arch/arm/src/kinetis/kinetis_usbotg.h +++ b/arch/arm/src/kinetis/kinetis_usbotg.h @@ -66,6 +66,8 @@ struct usbotg_bdtentry_s struct usbdev_s; int kinetis_usbpullup(FAR struct usbdev_s *dev, bool enable); void kinetis_usbsuspend(FAR struct usbdev_s *dev, bool resume); +#if defined(CONFIG_USBDEV_SELFPOWERED) void khci_usbattach(void); - +void khci_usbdetach(void); +#endif #endif /* __ARCH_ARM_SRC_KINETIS_KINETIS_USBOTG_H */ -- GitLab From 5b07459af113f0403cb44a070c1145fd351dcd64 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Mon, 5 Jun 2017 11:50:04 -1000 Subject: [PATCH 928/990] Freedom-k66f:Refreshed config --- configs/freedom-k66f/nsh/defconfig | 56 ++++++++++++++++++++++++++---- 1 file changed, 49 insertions(+), 7 deletions(-) diff --git a/configs/freedom-k66f/nsh/defconfig b/configs/freedom-k66f/nsh/defconfig index 3ba8a3d279..91f33ffc14 100644 --- a/configs/freedom-k66f/nsh/defconfig +++ b/configs/freedom-k66f/nsh/defconfig @@ -28,6 +28,7 @@ CONFIG_BUILD_FLAT=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -89,6 +90,7 @@ CONFIG_ARCH_CHIP_KINETIS=y # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -96,11 +98,12 @@ CONFIG_ARCH_CHIP_KINETIS=y # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -121,8 +124,6 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="kinetis" -# CONFIG_ARCH_TOOLCHAIN_IAR is not set -CONFIG_ARCH_TOOLCHAIN_GNU=y CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y @@ -189,6 +190,7 @@ CONFIG_ARCH_CHIP_MK66FN2M0VMD18=y # CONFIG_KINETIS_HAVE_UART5 is not set CONFIG_KINETIS_HAVE_LPUART0=y # CONFIG_KINETIS_HAVE_LPUART1 is not set +CONFIG_KINETIS_SERIALDRIVER=y # CONFIG_KINETIS_LPUART is not set CONFIG_KINETIS_UART=y # CONFIG_ARCH_FAMILY_K20 is not set @@ -200,11 +202,14 @@ CONFIG_ARCH_FAMILY_K66=y # # Kinetis Peripheral Support # +CONFIG_KINETIS_HAVE_FTM3=y CONFIG_KINETIS_HAVE_I2C1=y CONFIG_KINETIS_HAVE_I2C2=y CONFIG_KINETIS_HAVE_I2C3=y CONFIG_KINETIS_HAVE_SPI1=y CONFIG_KINETIS_HAVE_SPI2=y +CONFIG_KINETIS_HAVE_TPM1=y +CONFIG_KINETIS_HAVE_TPM2=y # CONFIG_KINETIS_TRACE is not set # CONFIG_KINETIS_FLEXBUS is not set # CONFIG_KINETIS_UART0 is not set @@ -236,6 +241,8 @@ CONFIG_KINETIS_FTM0=y # CONFIG_KINETIS_FTM1 is not set # CONFIG_KINETIS_FTM2 is not set CONFIG_KINETIS_FTM3=y +# CONFIG_KINETIS_TPM1 is not set +# CONFIG_KINETIS_TPM2 is not set # CONFIG_KINETIS_LPTIMER is not set CONFIG_KINETIS_RTC=y # CONFIG_KINETIS_EWM is not set @@ -279,6 +286,17 @@ CONFIG_KINETIS_PORTDINTS=y # Kinetis UART Configuration # +# +# Serial Driver Configuration +# +CONFIG_KINETIS_UART_BREAKS=y +CONFIG_KINETIS_UART_EXTEDED_BREAK=y +CONFIG_KINETIS_SERIALBRK_BSDCOMPAT=y +# CONFIG_KINETIS_UART_SINGLEWIRE is not set +CONFIG_SERIAL_TERMIOS=y +# CONFIG_ARCH_TOOLCHAIN_IAR is not set +CONFIG_ARCH_TOOLCHAIN_GNU=y + # # Architecture Options # @@ -298,6 +316,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -422,6 +441,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -515,10 +536,11 @@ CONFIG_DEV_ZERO=y # CONFIG_ARCH_HAVE_PWM_PULSECOUNT is not set # CONFIG_ARCH_HAVE_PWM_MULTICHAN is not set CONFIG_PWM=y -# CONFIG_ARCH_HAVE_I2CRESET is not set +CONFIG_ARCH_HAVE_I2CRESET=y CONFIG_I2C=y # CONFIG_I2C_SLAVE is not set # CONFIG_I2C_POLLED is not set +CONFIG_I2C_RESET=y # CONFIG_I2C_TRACE is not set CONFIG_I2C_DRIVER=y # CONFIG_ARCH_HAVE_SPI_CRCGENERATION is not set @@ -633,7 +655,7 @@ CONFIG_SERIAL_NPOLLWAITERS=2 # CONFIG_SERIAL_IFLOWCONTROL is not set # CONFIG_SERIAL_OFLOWCONTROL is not set # CONFIG_SERIAL_DMA is not set -# CONFIG_ARCH_HAVE_SERIAL_TERMIOS is not set +CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y CONFIG_UART1_SERIAL_CONSOLE=y # CONFIG_UART4_SERIAL_CONSOLE is not set # CONFIG_OTHER_SERIAL_CONSOLE is not set @@ -667,6 +689,7 @@ CONFIG_UART4_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -675,7 +698,9 @@ CONFIG_UART4_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -751,6 +776,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -759,6 +789,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -934,13 +965,12 @@ CONFIG_EXAMPLES_BUTTONS_NAME7="BUTTON7" # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NULL is not set -# CONFIG_EXAMPLES_NX is not set # CONFIG_EXAMPLES_NXFFS is not set # CONFIG_EXAMPLES_NXHELLO is not set # CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NX is not set # CONFIG_EXAMPLES_NXLINES is not set # CONFIG_EXAMPLES_NXTERM is not set # CONFIG_EXAMPLES_NXTEXT is not set @@ -971,6 +1001,7 @@ CONFIG_EXAMPLES_PWM_DUTYPCT=50 # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1160,3 +1191,14 @@ CONFIG_READLINE_CMD_HISTORY_LEN=16 # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set -- GitLab From 7581cad592625466e813c45384b5f6e56ed180ae Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Tue, 6 Jun 2017 08:54:49 -1000 Subject: [PATCH 929/990] teensy-3.x:Refreshed config --- configs/teensy-3.x/usbnsh/defconfig | 54 +++++++++++++++++++++++++---- 1 file changed, 47 insertions(+), 7 deletions(-) diff --git a/configs/teensy-3.x/usbnsh/defconfig b/configs/teensy-3.x/usbnsh/defconfig index cf01c27675..ab846ebd2a 100644 --- a/configs/teensy-3.x/usbnsh/defconfig +++ b/configs/teensy-3.x/usbnsh/defconfig @@ -28,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -89,6 +90,7 @@ CONFIG_ARCH_CHIP_KINETIS=y # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -96,11 +98,12 @@ CONFIG_ARCH_CHIP_KINETIS=y # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -121,8 +124,6 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="kinetis" -# CONFIG_ARCH_TOOLCHAIN_IAR is not set -CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set @@ -189,6 +190,7 @@ CONFIG_ARCH_CHIP_MK20DX256VLH7=y CONFIG_KINETIS_HAVE_UART5=y # CONFIG_KINETIS_HAVE_LPUART0 is not set # CONFIG_KINETIS_HAVE_LPUART1 is not set +CONFIG_KINETIS_SERIALDRIVER=y # CONFIG_KINETIS_LPUART is not set CONFIG_KINETIS_UART=y CONFIG_ARCH_FAMILY_K20=y @@ -200,11 +202,14 @@ CONFIG_ARCH_FAMILY_K20=y # # Kinetis Peripheral Support # +# CONFIG_KINETIS_HAVE_FTM3 is not set CONFIG_KINETIS_HAVE_I2C1=y # CONFIG_KINETIS_HAVE_I2C2 is not set # CONFIG_KINETIS_HAVE_I2C3 is not set # CONFIG_KINETIS_HAVE_SPI1 is not set # CONFIG_KINETIS_HAVE_SPI2 is not set +# CONFIG_KINETIS_HAVE_TPM1 is not set +# CONFIG_KINETIS_HAVE_TPM2 is not set # CONFIG_KINETIS_TRACE is not set # CONFIG_KINETIS_FLEXBUS is not set CONFIG_KINETIS_UART0=y @@ -251,7 +256,18 @@ CONFIG_KINETIS_USBOTG=y # # Kinetis UART Configuration # + +# +# Serial Driver Configuration +# +CONFIG_KINETIS_UART_BREAKS=y +# CONFIG_KINETIS_UART_EXTEDED_BREAK is not set +CONFIG_KINETIS_SERIALBRK_BSDCOMPAT=y +# CONFIG_KINETIS_UART_SINGLEWIRE is not set CONFIG_KINETIS_UARTFIFOS=y +CONFIG_SERIAL_TERMIOS=y +# CONFIG_ARCH_TOOLCHAIN_IAR is not set +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -272,6 +288,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -386,6 +403,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -466,7 +485,7 @@ CONFIG_DEV_NULL=y # CONFIG_ARCH_HAVE_PWM_PULSECOUNT is not set # CONFIG_ARCH_HAVE_PWM_MULTICHAN is not set # CONFIG_PWM is not set -# CONFIG_ARCH_HAVE_I2CRESET is not set +CONFIG_ARCH_HAVE_I2CRESET=y # CONFIG_I2C is not set # CONFIG_ARCH_HAVE_SPI_CRCGENERATION is not set # CONFIG_ARCH_HAVE_SPI_CS_CONTROL is not set @@ -554,7 +573,7 @@ CONFIG_STANDARD_SERIAL=y # CONFIG_SERIAL_IFLOWCONTROL is not set # CONFIG_SERIAL_OFLOWCONTROL is not set # CONFIG_SERIAL_DMA is not set -# CONFIG_ARCH_HAVE_SERIAL_TERMIOS is not set +CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y CONFIG_UART0_SERIAL_CONSOLE=y # CONFIG_OTHER_SERIAL_CONSOLE is not set # CONFIG_NO_SERIAL_CONSOLE is not set @@ -617,6 +636,7 @@ CONFIG_CDCACM_VENDORSTR="NuttX" CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial" # CONFIG_USBMSC is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set CONFIG_HAVE_USBTRACE=y CONFIG_USBMONITOR=y CONFIG_USBMONITOR_STACKSIZE=2048 @@ -634,7 +654,9 @@ CONFIG_USBMONITOR_TRACEINTERRUPTS=y # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -694,6 +716,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -858,13 +885,12 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NULL is not set -# CONFIG_EXAMPLES_NX is not set # CONFIG_EXAMPLES_NXFFS is not set # CONFIG_EXAMPLES_NXHELLO is not set # CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NX is not set # CONFIG_EXAMPLES_NXLINES is not set # CONFIG_EXAMPLES_NXTERM is not set # CONFIG_EXAMPLES_NXTEXT is not set @@ -890,6 +916,7 @@ CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_USBSERIAL is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1062,6 +1089,8 @@ CONFIG_SYSTEM_HEXED_STACKSIZE=2048 CONFIG_SYSTEM_HEXED_PRIORITY=100 # CONFIG_SYSTEM_INSTALL is not set CONFIG_SYSTEM_RAMTEST=y +CONFIG_SYSTEM_RAMTEST_PRIORITY=100 +CONFIG_SYSTEM_RAMTEST_STACKSIZE=1024 CONFIG_READLINE_HAVE_EXTMATCH=y CONFIG_SYSTEM_READLINE=y CONFIG_READLINE_ECHO=y @@ -1077,3 +1106,14 @@ CONFIG_READLINE_CMD_HISTORY_LEN=16 # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set -- GitLab From cb62675b5e73bec04164496c9a873097a474ea7f Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Tue, 6 Jun 2017 12:35:32 -1000 Subject: [PATCH 930/990] Kinetis:sim ensure isolation of clock dividers for 0 value case This fixes a bug were a SoC does not have a clockdivN register and passes a 0 for the init value. This prevents overflow of the 0 decremented to -1 (0xffffffff) spilling over to other clockdivN feilds. --- arch/arm/src/kinetis/chip/kinetis_sim.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/arch/arm/src/kinetis/chip/kinetis_sim.h b/arch/arm/src/kinetis/chip/kinetis_sim.h index a1ffe6721e..fbeba3983d 100644 --- a/arch/arm/src/kinetis/chip/kinetis_sim.h +++ b/arch/arm/src/kinetis/chip/kinetis_sim.h @@ -1057,7 +1057,7 @@ #if defined(KINETIS_SIM_HAS_CLKDIV1_OUTDIV4) # define SIM_CLKDIV1_OUTDIV4_SHIFT (16) /* Bits 16-19: Clock 4 output divider value */ # define SIM_CLKDIV1_OUTDIV4_MASK (15 << SIM_CLKDIV1_OUTDIV4_SHIFT) -# define SIM_CLKDIV1_OUTDIV4(n) ((uint32_t)((n)-1) << SIM_CLKDIV1_OUTDIV4_SHIFT) /* n=1..16 */ +# define SIM_CLKDIV1_OUTDIV4(n) ((uint32_t)(((n)-1) & 0xf) << SIM_CLKDIV1_OUTDIV4_SHIFT) /* n=1..16 */ # define SIM_CLKDIV1_OUTDIV4_1 (0 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 1 */ # define SIM_CLKDIV1_OUTDIV4_2 (1 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 2 */ # define SIM_CLKDIV1_OUTDIV4_3 (2 << SIM_CLKDIV1_OUTDIV4_SHIFT) /* Divide by 3 */ @@ -1078,7 +1078,7 @@ #if defined(KINETIS_SIM_HAS_CLKDIV1_OUTDIV3) # define SIM_CLKDIV1_OUTDIV3_SHIFT (20) /* Bits 20-23: Clock 3 output divider value */ # define SIM_CLKDIV1_OUTDIV3_MASK (15 << SIM_CLKDIV1_OUTDIV3_SHIFT) -# define SIM_CLKDIV1_OUTDIV3(n) ((uint32_t)((n)-1) << SIM_CLKDIV1_OUTDIV3_SHIFT) /* n=1..16 */ +# define SIM_CLKDIV1_OUTDIV3(n) ((uint32_t)(((n)-1) & 0xf) << SIM_CLKDIV1_OUTDIV3_SHIFT) /* n=1..16 */ # define SIM_CLKDIV1_OUTDIV3_1 (0 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 1 */ # define SIM_CLKDIV1_OUTDIV3_2 (1 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 2 */ # define SIM_CLKDIV1_OUTDIV3_3 (2 << SIM_CLKDIV1_OUTDIV3_SHIFT) /* Divide by 3 */ @@ -1099,7 +1099,7 @@ #if defined(KINETIS_SIM_HAS_CLKDIV1_OUTDIV2) # define SIM_CLKDIV1_OUTDIV2_SHIFT (24) /* Bits 24-27: Clock 2 output divider value */ # define SIM_CLKDIV1_OUTDIV2_MASK (15 << SIM_CLKDIV1_OUTDIV2_SHIFT) -# define SIM_CLKDIV1_OUTDIV2(n) ((uint32_t)((n)-1) << SIM_CLKDIV1_OUTDIV2_SHIFT) /* n=1..16 */ +# define SIM_CLKDIV1_OUTDIV2(n) ((uint32_t)(((n)-1) & 0xf) << SIM_CLKDIV1_OUTDIV2_SHIFT) /* n=1..16 */ # define SIM_CLKDIV1_OUTDIV2_1 (0 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 1 */ # define SIM_CLKDIV1_OUTDIV2_2 (1 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 2 */ # define SIM_CLKDIV1_OUTDIV2_3 (2 << SIM_CLKDIV1_OUTDIV2_SHIFT) /* Divide by 3 */ @@ -1119,7 +1119,7 @@ #endif #define SIM_CLKDIV1_OUTDIV1_SHIFT (28) /* Bits 28-31: Clock 1 output divider value */ #define SIM_CLKDIV1_OUTDIV1_MASK (15 << SIM_CLKDIV1_OUTDIV1_SHIFT) -# define SIM_CLKDIV1_OUTDIV1(n) ((uint32_t)((n)-1) << SIM_CLKDIV1_OUTDIV1_SHIFT) /* n=1..16 */ +# define SIM_CLKDIV1_OUTDIV1(n) ((uint32_t)(((n)-1) & 0xf) << SIM_CLKDIV1_OUTDIV1_SHIFT) /* n=1..16 */ # define SIM_CLKDIV1_OUTDIV1_1 (0 << SIM_CLKDIV1_OUTDIV1_SHIFT) /* Divide by 1 */ # define SIM_CLKDIV1_OUTDIV1_2 (1 << SIM_CLKDIV1_OUTDIV1_SHIFT) /* Divide by 2 */ # define SIM_CLKDIV1_OUTDIV1_3 (2 << SIM_CLKDIV1_OUTDIV1_SHIFT) /* Divide by 3 */ -- GitLab From ad0cbd3f83b02a45e317b5b4f320713a54ca7f4a Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Tue, 6 Jun 2017 12:47:09 -1000 Subject: [PATCH 931/990] teensy-3.x:Removed call to khci_usbattach The call is not need by the driver if CONFIG_USBDEV_BUSPOWERED=y The class register will enable the soft connect pull up. The khci_usbattach call only set a flag, and that flag is only tested in the class register. On a USB powered device if we are running we are attached. --- configs/teensy-3.x/src/k20_appinit.c | 8 -------- 1 file changed, 8 deletions(-) diff --git a/configs/teensy-3.x/src/k20_appinit.c b/configs/teensy-3.x/src/k20_appinit.c index d59d4d9e21..9d89040fd8 100644 --- a/configs/teensy-3.x/src/k20_appinit.c +++ b/configs/teensy-3.x/src/k20_appinit.c @@ -80,14 +80,6 @@ int board_app_initialize(uintptr_t arg) { int ret; -#ifdef CONFIG_USBDEV - /* Teensy is powered from usb and (bug?) only boots from being programmed, - * so if usb is compiled in signal the controller driver that we're attached now. - */ - - khci_usbattach(); -#endif - #ifdef CONFIG_PWM /* Initialize PWM and register the PWM device. */ -- GitLab From 04a46d8d35bf454f0d7d63bbfbb4120df5ec0edf Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Tue, 6 Jun 2017 12:58:12 -1000 Subject: [PATCH 932/990] teensy-3.x:Refreshed config --- configs/teensy-3.x/nsh/defconfig | 73 ++++++++++++++++++++++---------- 1 file changed, 51 insertions(+), 22 deletions(-) diff --git a/configs/teensy-3.x/nsh/defconfig b/configs/teensy-3.x/nsh/defconfig index e4b50bd3c2..d2fcf166d5 100644 --- a/configs/teensy-3.x/nsh/defconfig +++ b/configs/teensy-3.x/nsh/defconfig @@ -12,12 +12,6 @@ # CONFIG_HOST_OSX is not set CONFIG_HOST_WINDOWS=y # CONFIG_HOST_OTHER is not set -CONFIG_TOOLCHAIN_WINDOWS=y -# CONFIG_WINDOWS_NATIVE is not set -CONFIG_WINDOWS_CYGWIN=y -# CONFIG_WINDOWS_UBUNTU is not set -# CONFIG_WINDOWS_MSYS is not set -# CONFIG_WINDOWS_OTHER is not set # # Build Configuration @@ -34,6 +28,7 @@ CONFIG_INTELHEX_BINARY=y # CONFIG_MOTOROLA_SREC is not set CONFIG_RAW_BINARY=y # CONFIG_UBOOT_UIMAGE is not set +# CONFIG_DFU_BINARY is not set # # Customize Header Files @@ -53,7 +48,7 @@ CONFIG_DEBUG_ALERT=y CONFIG_ARCH_HAVE_STACKCHECK=y # CONFIG_STACK_COLORATION is not set # CONFIG_ARCH_HAVE_HEAPCHECK is not set -# CONFIG_DEBUG_SYMBOLS is not set +CONFIG_DEBUG_SYMBOLS=y CONFIG_ARCH_HAVE_CUSTOMOPT=y # CONFIG_DEBUG_NOOPT is not set # CONFIG_DEBUG_CUSTOMOPT is not set @@ -95,6 +90,7 @@ CONFIG_ARCH_CHIP_KINETIS=y # CONFIG_ARCH_CHIP_LPC2378 is not set # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_MOXART is not set # CONFIG_ARCH_CHIP_NUC1XX is not set # CONFIG_ARCH_CHIP_SAMA5 is not set # CONFIG_ARCH_CHIP_SAMD is not set @@ -102,11 +98,12 @@ CONFIG_ARCH_CHIP_KINETIS=y # CONFIG_ARCH_CHIP_SAM34 is not set # CONFIG_ARCH_CHIP_SAMV7 is not set # CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STM32F0 is not set # CONFIG_ARCH_CHIP_STM32F7 is not set # CONFIG_ARCH_CHIP_STM32L4 is not set # CONFIG_ARCH_CHIP_STR71X is not set # CONFIG_ARCH_CHIP_TMS570 is not set -# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_CHIP_XMC4 is not set # CONFIG_ARCH_ARM7TDMI is not set # CONFIG_ARCH_ARM926EJS is not set # CONFIG_ARCH_ARM920T is not set @@ -127,8 +124,6 @@ CONFIG_ARCH_CORTEXM4=y # CONFIG_ARCH_CORTEXR7F is not set CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="kinetis" -# CONFIG_ARCH_TOOLCHAIN_IAR is not set -CONFIG_ARCH_TOOLCHAIN_GNU=y # CONFIG_ARMV7M_USEBASEPRI is not set CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set @@ -147,15 +142,11 @@ CONFIG_ARM_HAVE_MPU_UNIFIED=y # CONFIG_ARMV7M_HAVE_DCACHE is not set # CONFIG_ARMV7M_HAVE_ITCM is not set # CONFIG_ARMV7M_HAVE_DTCM is not set -# CONFIG_ARMV7M_TOOLCHAIN_IARW is not set -# CONFIG_ARMV7M_TOOLCHAIN_ATOLLIC is not set +# CONFIG_ARMV7M_TOOLCHAIN_IARL is not set # CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set -# CONFIG_ARMV7M_TOOLCHAIN_CODEREDW is not set -# CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYW is not set -# CONFIG_ARMV7M_TOOLCHAIN_DEVKITARM is not set -# CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL is not set -CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIW=y -# CONFIG_ARMV7M_TOOLCHAIN_RAISONANCE is not set +# CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set +# CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL is not set +CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL=y # CONFIG_ARMV7M_HAVE_STACKCHECK is not set # CONFIG_ARMV7M_ITMSYSLOG is not set @@ -199,6 +190,7 @@ CONFIG_ARCH_CHIP_MK20DX256VLH7=y CONFIG_KINETIS_HAVE_UART5=y # CONFIG_KINETIS_HAVE_LPUART0 is not set # CONFIG_KINETIS_HAVE_LPUART1 is not set +CONFIG_KINETIS_SERIALDRIVER=y # CONFIG_KINETIS_LPUART is not set CONFIG_KINETIS_UART=y CONFIG_ARCH_FAMILY_K20=y @@ -210,11 +202,14 @@ CONFIG_ARCH_FAMILY_K20=y # # Kinetis Peripheral Support # +# CONFIG_KINETIS_HAVE_FTM3 is not set CONFIG_KINETIS_HAVE_I2C1=y # CONFIG_KINETIS_HAVE_I2C2 is not set # CONFIG_KINETIS_HAVE_I2C3 is not set # CONFIG_KINETIS_HAVE_SPI1 is not set # CONFIG_KINETIS_HAVE_SPI2 is not set +# CONFIG_KINETIS_HAVE_TPM1 is not set +# CONFIG_KINETIS_HAVE_TPM2 is not set # CONFIG_KINETIS_TRACE is not set # CONFIG_KINETIS_FLEXBUS is not set CONFIG_KINETIS_UART0=y @@ -261,7 +256,18 @@ CONFIG_KINETIS_UART0=y # # Kinetis UART Configuration # + +# +# Serial Driver Configuration +# +CONFIG_KINETIS_UART_BREAKS=y +# CONFIG_KINETIS_UART_EXTEDED_BREAK is not set +CONFIG_KINETIS_SERIALBRK_BSDCOMPAT=y +# CONFIG_KINETIS_UART_SINGLEWIRE is not set CONFIG_KINETIS_UARTFIFOS=y +CONFIG_SERIAL_TERMIOS=y +# CONFIG_ARCH_TOOLCHAIN_IAR is not set +CONFIG_ARCH_TOOLCHAIN_GNU=y # # Architecture Options @@ -282,6 +288,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARCH_HAVE_EXTCLK is not set # CONFIG_ARCH_HAVE_POWEROFF is not set CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set # CONFIG_ARCH_USE_MPU is not set # CONFIG_ARCH_IRQPRIO is not set CONFIG_ARCH_STACKDUMP=y @@ -389,6 +396,8 @@ CONFIG_SCHED_WAITPID=y # # CONFIG_PTHREAD_MUTEX_TYPES is not set CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set CONFIG_NPTHREAD_KEYS=4 # CONFIG_PTHREAD_CLEANUP is not set # CONFIG_CANCELLATION_POINTS is not set @@ -469,7 +478,7 @@ CONFIG_DEV_NULL=y # CONFIG_ARCH_HAVE_PWM_PULSECOUNT is not set # CONFIG_ARCH_HAVE_PWM_MULTICHAN is not set # CONFIG_PWM is not set -# CONFIG_ARCH_HAVE_I2CRESET is not set +CONFIG_ARCH_HAVE_I2CRESET=y # CONFIG_I2C is not set # CONFIG_ARCH_HAVE_SPI_CRCGENERATION is not set # CONFIG_ARCH_HAVE_SPI_CS_CONTROL is not set @@ -557,7 +566,7 @@ CONFIG_STANDARD_SERIAL=y # CONFIG_SERIAL_IFLOWCONTROL is not set # CONFIG_SERIAL_OFLOWCONTROL is not set # CONFIG_SERIAL_DMA is not set -# CONFIG_ARCH_HAVE_SERIAL_TERMIOS is not set +CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y CONFIG_UART0_SERIAL_CONSOLE=y # CONFIG_OTHER_SERIAL_CONSOLE is not set # CONFIG_NO_SERIAL_CONSOLE is not set @@ -577,6 +586,7 @@ CONFIG_UART0_2STOP=0 # CONFIG_PSEUDOTERM is not set # CONFIG_USBDEV is not set # CONFIG_USBHOST is not set +# CONFIG_USBMISC is not set # CONFIG_HAVE_USBTRACE is not set # CONFIG_DRIVERS_WIRELESS is not set # CONFIG_DRIVERS_CONTACTLESS is not set @@ -585,7 +595,9 @@ CONFIG_UART0_2STOP=0 # System Logging # # CONFIG_ARCH_SYSLOG is not set +CONFIG_SYSLOG_WRITE=y # CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER is not set # CONFIG_SYSLOG_INTBUFFER is not set # CONFIG_SYSLOG_TIMESTAMP is not set CONFIG_SYSLOG_SERIAL_CONSOLE=y @@ -645,6 +657,11 @@ CONFIG_MM_REGIONS=1 # CONFIG_ARCH_HAVE_HEAP2 is not set # CONFIG_GRAN is not set +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + # # Audio Support # @@ -653,6 +670,7 @@ CONFIG_MM_REGIONS=1 # # Wireless Support # +# CONFIG_WIRELESS is not set # # Binary Loader @@ -808,13 +826,12 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024 # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set # CONFIG_EXAMPLES_MOUNT is not set -# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NULL is not set -# CONFIG_EXAMPLES_NX is not set # CONFIG_EXAMPLES_NXFFS is not set # CONFIG_EXAMPLES_NXHELLO is not set # CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NX is not set # CONFIG_EXAMPLES_NXLINES is not set # CONFIG_EXAMPLES_NXTERM is not set # CONFIG_EXAMPLES_NXTEXT is not set @@ -839,6 +856,7 @@ CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_TOUCHSCREEN is not set # CONFIG_EXAMPLES_WATCHDOG is not set # CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST is not set # # File System Utilities @@ -1006,3 +1024,14 @@ CONFIG_READLINE_ECHO=y # CONFIG_SYSTEM_UBLOXMODEM is not set # CONFIG_SYSTEM_VI is not set # CONFIG_SYSTEM_ZMODEM is not set + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set -- GitLab From 182259921f669aa1fbe1890b1a0e111c783bc94d Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Tue, 6 Jun 2017 12:58:40 -1000 Subject: [PATCH 933/990] teensy-3.x:Refreshed config and made board self powered --- configs/teensy-3.x/usbnsh/defconfig | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/configs/teensy-3.x/usbnsh/defconfig b/configs/teensy-3.x/usbnsh/defconfig index ab846ebd2a..649efb23af 100644 --- a/configs/teensy-3.x/usbnsh/defconfig +++ b/configs/teensy-3.x/usbnsh/defconfig @@ -598,8 +598,8 @@ CONFIG_USBDEV=y # # CONFIG_USBDEV_ISOCHRONOUS is not set CONFIG_USBDEV_DUALSPEED=y -CONFIG_USBDEV_SELFPOWERED=y -# CONFIG_USBDEV_BUSPOWERED is not set +# CONFIG_USBDEV_SELFPOWERED is not set +CONFIG_USBDEV_BUSPOWERED=y CONFIG_USBDEV_MAXPOWER=100 # CONFIG_USBDEV_DMA is not set # CONFIG_ARCH_USBDEV_STALLQUEUE is not set -- GitLab From 36da2b91c586b5785be4d9bc0c59be2cac0a12e0 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Tue, 6 Jun 2017 13:18:41 -1000 Subject: [PATCH 934/990] Kinetis:USB-FS driver Removed the notion of attached. The khci_usbattach is call early in the init either in board_initalize or in board_app_initalize. In either case it is always done prior to the the class register. Therefore the khci_usbattach call only set a flag, and that flag is only tested in the class register. The class register will enable the soft connect pull up. --- arch/arm/src/kinetis/kinetis_usbdev.c | 171 ++++---------------------- arch/arm/src/kinetis/kinetis_usbotg.h | 4 - 2 files changed, 22 insertions(+), 153 deletions(-) diff --git a/arch/arm/src/kinetis/kinetis_usbdev.c b/arch/arm/src/kinetis/kinetis_usbdev.c index 20bfa9a92a..ace2400ae1 100644 --- a/arch/arm/src/kinetis/kinetis_usbdev.c +++ b/arch/arm/src/kinetis/kinetis_usbdev.c @@ -493,7 +493,6 @@ struct khci_usbdev_s uint8_t ctrlstate; /* Control EP state (see enum khci_ctrlstate_e) */ uint8_t selfpowered:1; /* 1: Device is self powered */ uint8_t rwakeup:1; /* 1: Device supports remote wakeup */ - uint8_t attached:1; /* Device is attached to the host */ uint8_t ep0done:1; /* EP0 OUT already prepared */ uint8_t rxbusy:1; /* EP0 OUT data transfer in progress */ uint16_t epavail; /* Bitset of available endpoints */ @@ -618,9 +617,6 @@ static int khci_selfpowered(struct usbdev_s *dev, bool selfpowered); static void khci_reset(struct khci_usbdev_s *priv); static void khci_attach(struct khci_usbdev_s *priv); -#if defined(CONFIG_USBDEV_SELFPOWERED) -static void khci_detach(struct khci_usbdev_s *priv); -#endif static void khci_swreset(struct khci_usbdev_s *priv); static void khci_hwreset(struct khci_usbdev_s *priv); static void khci_swinitalize(struct khci_usbdev_s *priv); @@ -2753,31 +2749,32 @@ static int khci_interrupt(int irq, void *context, FAR void *arg) /* Check if USB OTG SRP is ready */ # warning "Missing logic" - { - /* Check if the 1 millisecond timer has expired */ + { + /* Check if the 1 millisecond timer has expired */ - if ((otgir & USBOTG_INT_T1MSEC) != 0) - { - usbtrace(TRACE_INTDECODE(KHCI_TRACEINTID_T1MSEC), otgir); + if ((otgir & USBOTG_INT_T1MSEC) != 0) + { + usbtrace(TRACE_INTDECODE(KHCI_TRACEINTID_T1MSEC), otgir); - /* Check for the USB OTG SRP timeout */ + /* Check for the USB OTG SRP timeout */ # warning "Missing logic" - { + { /* Handle OTG events of the SRP timeout has expired */ # warning "Missing logic" - } + } - /* Clear Interrupt 1 msec timer Flag */ + /* Clear Interrupt 1 msec timer Flag */ - khci_putreg(USBOTG_INT_T1MSEC, KINETIS_USB0_ISTAT); - } - } + khci_putreg(USBOTG_INT_T1MSEC, KINETIS_USB0_ISTAT); + } + } #endif - /* Handle events while we are in the attached state */ + /* Handle events while we are in the attached state */ if (priv->devstate == DEVSTATE_ATTACHED) { + /* Now were are in the powered state */ priv->devstate = DEVSTATE_POWERED; @@ -2999,7 +2996,6 @@ static void khci_suspend(struct khci_usbdev_s *priv) regval = khci_getreg(KINETIS_USB0_USBCTRL); regval |= USB_USBCTRL_SUSP; khci_putreg(regval, KINETIS_USB0_USBCTRL); - } /**************************************************************************** @@ -3145,6 +3141,7 @@ khci_epreserved(struct khci_usbdev_s *priv, int epno) /**************************************************************************** * Name: khci_ep0configure ****************************************************************************/ + static void khci_ep0configure(struct khci_usbdev_s *priv) { volatile struct usbotg_bdtentry_s *bdt; @@ -3959,9 +3956,8 @@ static int khci_selfpowered(struct usbdev_s *dev, bool selfpowered) * Name: khci_reset * * Description: - * Reset the software and hardware states. If the USB controller has been - * attached to a host, then connect to the bus as well. At the end of - * this reset, the hardware should be in the full up, ready-to-run state. + * Reset the software and hardware states. At the end of this reset, the + * hardware should be in the full up, ready-to-run state. * ****************************************************************************/ @@ -3975,18 +3971,9 @@ static void khci_reset(struct khci_usbdev_s *priv) khci_hwreset(priv); - /* khci_attach() was called, then the attach flag will be set and we - * should also attach to the USB bus. - */ - - if (priv->attached) - { - /* usbdev_attach() has already been called.. attach to the bus - * now - */ + /* Do the final hw attach */ - khci_attach(priv); - } + khci_attach(priv); } /**************************************************************************** @@ -4004,8 +3991,8 @@ static void khci_attach(struct khci_usbdev_s *priv) /* Disable USB interrupts at the interrupt controller */ up_disable_irq(KINETIS_IRQ_USBOTG); - - /* Initialize the controller to known states. */ + + /* Initialize the controller to known states. */ khci_putreg(USB_CTL_USBENSOFEN, KINETIS_USB0_CTL); @@ -4072,62 +4059,9 @@ static void khci_attach(struct khci_usbdev_s *priv) /* Enable USB interrupts at the interrupt controller */ up_enable_irq(KINETIS_IRQ_USBOTG); - } } -#if defined(CONFIG_USBDEV_SELFPOWERED) -/**************************************************************************** - * Name: khci_detach - ****************************************************************************/ - -static void khci_detach(struct khci_usbdev_s *priv) -{ -#ifdef CONFIG_USBOTG - uint32_t regval; -#endif - - /* Disable USB interrupts at the interrupt controller */ - - up_disable_irq(KINETIS_IRQ_USBOTG); - - /* Disable the USB controller and detach from the bus. */ - - khci_putreg(0, KINETIS_USB0_CTL); - - /* Mask all USB interrupts */ - - khci_putreg(0, KINETIS_USB0_INTEN); - - /* We are now in the detached state */ - - priv->attached = 0; - priv->devstate = DEVSTATE_DETACHED; - -#ifdef CONFIG_USBOTG - /* Disable the D+ Pullup */ - - regval = khci_getreg(KINETIS_USB0_OTGCTL); - regval &= ~USBOTG_CON_DPPULUP; - khci_putreg(regval, KINETIS_USB0_OTGCTL); - - /* Disable and deactivate HNP */ -#warning Missing Logic - - /* Check if the ID Pin Changed State */ - - if ((khci_getreg(KINETIS_USB0_ISTAT) & khci_getreg(KINETIS_USB0_OTGICR) & USBOTG_INT_ID) != 0) - { - /* Re-detect & Initialize */ -#warning "Missing logic" - - /* Clear ID Interrupt Flag */ - - khci_putreg(USBOTG_INT_ID, KINETIS_USB0_ISTAT); - } -#endif -} -#endif /**************************************************************************** * Name: khci_swreset ****************************************************************************/ @@ -4306,12 +4240,6 @@ static void khci_swinitalize(struct khci_usbdev_s *priv) priv->epavail = KHCI_ENDP_ALLSET & ~KHCI_ENDP_BIT(EP0); priv->rwakeup = 1; -#if defined(CONFIG_USBDEV_BUSPOWERED) - /* Since this code is running we are physically attached to power */ - - priv->attached = 1; -#endif - /* Initialize the watchdog timer that is used to perform a delayed * queue restart after recovering from a stall. */ @@ -4570,10 +4498,7 @@ int usbdev_register(struct usbdevclass_driver_s *driver) else { - /* Setup the USB controller in it initial ready-to-run state (might - * be connected or unconnected, depending on usbdev_attach() has - * been called). - */ + /* Setup the USB controller in it initial ready-to-run state */ DEBUGASSERT(priv->devstate == DEVSTATE_DETACHED); khci_reset(priv); @@ -4642,56 +4567,4 @@ int usbdev_unregister(struct usbdevclass_driver_s *driver) leave_critical_section(flags); return OK; } - -#if defined(CONFIG_USBDEV_SELFPOWERED) -/**************************************************************************** - * Name: khci_usbattach and khci_usbdetach - * - * Description: - * The USB stack must be notified when the device is attached or detached - * by calling one of these functions. - * - ****************************************************************************/ - -void khci_usbattach(void) -{ - /* For now there is only one USB controller, but we will always refer to - * it using a pointer to make any future ports to multiple USB controllers - * easier. - */ - - struct khci_usbdev_s *priv = &g_usbdev; - - /* Mark that we are attached */ - - priv->attached = 1; - - /* This API may be called asynchronously from other initialization - * interfaces. In particular, we may not want to attach the bus yet... - * that should only be done when the class driver is attached. Has - * the class driver been attached? - */ - - if (priv->driver) - { - /* Yes.. then attach to the bus */ - - khci_attach(priv); - } -} - -void khci_usbdetach(void) -{ - /* For now there is only one USB controller, but we will always refer to - * it using a pointer to make any future ports to multiple USB controllers - * easier. - */ - - struct khci_usbdev_s *priv = &g_usbdev; - - /* Detach from the bus */ - - khci_detach(priv); -} -#endif /* CONFIG_USBDEV_SELFPOWERED */ #endif /* CONFIG_USBDEV && CONFIG_KHCI_USB */ diff --git a/arch/arm/src/kinetis/kinetis_usbotg.h b/arch/arm/src/kinetis/kinetis_usbotg.h index fdd03567c4..6353cf7f46 100644 --- a/arch/arm/src/kinetis/kinetis_usbotg.h +++ b/arch/arm/src/kinetis/kinetis_usbotg.h @@ -66,8 +66,4 @@ struct usbotg_bdtentry_s struct usbdev_s; int kinetis_usbpullup(FAR struct usbdev_s *dev, bool enable); void kinetis_usbsuspend(FAR struct usbdev_s *dev, bool resume); -#if defined(CONFIG_USBDEV_SELFPOWERED) -void khci_usbattach(void); -void khci_usbdetach(void); -#endif #endif /* __ARCH_ARM_SRC_KINETIS_KINETIS_USBOTG_H */ -- GitLab From 4854eb1fd706de984380dac60f27be09de45718c Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Tue, 6 Jun 2017 15:18:01 -1000 Subject: [PATCH 935/990] Kinetis:Fixed waning for kinetis_mpudisable Missing header file added --- arch/arm/src/kinetis/kinetis_start.c | 1 + 1 file changed, 1 insertion(+) diff --git a/arch/arm/src/kinetis/kinetis_start.c b/arch/arm/src/kinetis/kinetis_start.c index d139d9533a..f70b9a7368 100644 --- a/arch/arm/src/kinetis/kinetis_start.c +++ b/arch/arm/src/kinetis/kinetis_start.c @@ -51,6 +51,7 @@ #include "kinetis.h" #include "chip/kinetis_smc.h" +#include "kinetis_mpuinit.h" #include "kinetis_userspace.h" #ifdef CONFIG_ARCH_FPU -- GitLab From 66e2247f30364f16f1736cd733d859fae26d168e Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 8 Jun 2017 08:52:09 -0600 Subject: [PATCH 936/990] STM32L4: Ad support for the STM32L475 family. Incomplete -- still needs pinmap, rcc, otgfs, syscfg --- arch/arm/include/stm32l4/chip.h | 47 +- arch/arm/include/stm32l4/irq.h | 8 +- arch/arm/include/stm32l4/stm32l4x6xx_irq.h | 12 +- arch/arm/src/stm32l4/Kconfig | 80 +++ .../arm/src/stm32l4/chip/stm32l4x5xx_dbgmcu.h | 113 ++++ arch/arm/src/stm32l4/chip/stm32l4x5xx_dma.h | 485 ++++++++++++++++++ .../src/stm32l4/chip/stm32l4x5xx_firewall.h | 112 ++++ .../src/stm32l4/chip/stm32l4x6xx_firewall.h | 7 + arch/arm/src/stm32l4/stm32l4_comp.c | 5 +- arch/arm/src/stm32l4/stm32l4_comp.h | 2 +- arch/arm/src/stm32l4/stm32l4_dbgmcu.h | 8 +- arch/arm/src/stm32l4/stm32l4_dma.c | 3 +- arch/arm/src/stm32l4/stm32l4_dma.h | 8 +- arch/arm/src/stm32l4/stm32l4_exti_comp.c | 3 +- arch/arm/src/stm32l4/stm32l4_firewall.h | 8 +- arch/arm/src/stm32l4/stm32l4_flash.c | 3 +- arch/arm/src/stm32l4/stm32l4_gpio.h | 3 +- arch/arm/src/stm32l4/stm32l4_pm.h | 6 +- arch/arm/src/stm32l4/stm32l4_pmlpr.c | 5 +- arch/arm/src/stm32l4/stm32l4_pmstandby.c | 3 +- arch/arm/src/stm32l4/stm32l4_pmstop.c | 6 +- arch/arm/src/stm32l4/stm32l4_uart.h | 3 +- 22 files changed, 895 insertions(+), 35 deletions(-) create mode 100644 arch/arm/src/stm32l4/chip/stm32l4x5xx_dbgmcu.h create mode 100644 arch/arm/src/stm32l4/chip/stm32l4x5xx_dma.h create mode 100644 arch/arm/src/stm32l4/chip/stm32l4x5xx_firewall.h diff --git a/arch/arm/include/stm32l4/chip.h b/arch/arm/include/stm32l4/chip.h index 589d88f675..1d278e6d71 100644 --- a/arch/arm/include/stm32l4/chip.h +++ b/arch/arm/include/stm32l4/chip.h @@ -1,8 +1,10 @@ /************************************************************************************ * arch/arm/include/stm32l4/chip.h * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Copyright (C) 2016 Sebastien Lorquet. All rights reserved. * Author: Sebastien Lorquet + * Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -45,9 +47,11 @@ /************************************************************************************ * Pre-processor Definitions ************************************************************************************/ -/* STM32L476, STM32L486, STM32L496, STM32L4A6 +/* STM32L475, STM32L476, STM32L486, STM32L496, STM32L4A6 * * Differences between family members: + * - L475 has no TSC, no LCD, no AES, no I2C4, no CAN2, No Hash/CRS, no DCMI, + * no DMA2D * - L486 has AES * - L496, L4A6 has 320 Kib SRAM, 2xCAN and CameraIF. Most (all?) of these have I2C4. * - L4A6 has AES and HASH @@ -55,6 +59,8 @@ * ----------- ---------------- ----- ------ ------ ---- ---- ----- * PART PACKAGE GPIOs LCD Tamper FSMC CapS AdcCh * ----------- ---------------- ----- ------ ------ ---- ---- ----- + * STM32L475Rx LQFP100 82 3 Yes 21 16 + * STM32L475Vx LQFP64 51 2 No 12 16 * STM32L4x6Jx WLCSP72L 57 8x28 2 No 12 16 * STM32L476Mx WLCSP81L 65 ? ? ? ? ? * STM32L4x6Qx UFBGA132L 109 8x40 3 Yes 24 16 @@ -75,7 +81,8 @@ #if defined(CONFIG_STM32L4_STM32L496XX) # define STM32L4_SRAM1_SIZE (256*1024) /* 256Kb SRAM1 on AHB bus Matrix */ # define STM32L4_SRAM2_SIZE (64*1024) /* 64Kb SRAM2 on AHB bus Matrix */ -#elif defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX) +#elif defined(CONFIG_STM32L4_STM32L475XX) || defined(CONFIG_STM32L4_STM32L476XX) || \ + defined(CONFIG_STM32L4_STM32L486XX) # define STM32L4_SRAM1_SIZE (96*1024) /* 96Kb SRAM1 on AHB bus Matrix */ # define STM32L4_SRAM2_SIZE (32*1024) /* 32Kb SRAM2 on AHB bus Matrix */ #elif defined(CONFIG_STM32L4_STM32L451XX) || defined(CONFIG_STM32L4_STM32L452XX) || \ @@ -89,6 +96,36 @@ # error "Unsupported STM32L4 chip" #endif +#if defined(CONFIG_STM32L4_STM32L4x5) +# define STM32L4_NFSMC 1 /* Have FSMC memory controller */ +# define STM32L4_NATIM 2 /* Two advanced timers TIM1 and 8 */ +# define STM32L4_NGTIM32 2 /* 32-bit general timers TIM2 and 5 with DMA */ +# define STM32L4_NGTIM16 2 /* 16-bit general timers TIM3 and 4 with DMA */ +# define STM32L4_NGTIMNDMA 3 /* 16-bit general timers TIM15-17 without DMA */ +# define STM32L4_NBTIM 2 /* Two basic timers, TIM6-7 */ +# define STM32L4_NLPTIM 2 /* Two low-power timers, LPTIM1-2 */ +# define STM32L4_NRNG 1 /* Random number generator (RNG) */ +# define STM32L4_NUART 2 /* UART 4-5 */ +# define STM32L4_NUSART 3 /* USART 1-3 */ +# define STM32L4_NLPUART 1 /* LPUART 1 */ +# define STM32L4_QSPI 1 /* QuadSPI1 */ +# define STM32L4_NSPI 3 /* SPI1-3 */ +# define STM32L4_NI2C 3 /* I2C1-3 */ +# define STM32L4_NSWPMI 1 /* SWPMI1 */ +# define STM32L4_NUSBOTGFS 1 /* USB OTG FS */ +# define STM32L4_NUSBFS 0 /* No USB FS */ +# define STM32L4_NCAN 1 /* CAN1 */ +# define STM32L4_NSAI 2 /* SAI1-2 */ +# define STM32L4_NSDMMC 1 /* SDMMC interface */ +# define STM32L4_NDMA 2 /* DMA1-2 */ +# define STM32L4_NPORTS 8 /* 8 GPIO ports, GPIOA-H */ +# define STM32L4_NADC 3 /* 12-bit ADC1-3, 16 channels */ +# define STM32L4_NDAC 2 /* 12-bit DAC1-2 */ +# define STM32L4_NCRC 1 /* CRC */ +# define STM32L4_NCOMP 2 /* Comparators */ +# define STM32L4_NOPAMP 2 /* Operational Amplifiers */ +#endif /* CONFIG_STM32L4_STM32L4x5 */ + #if defined(CONFIG_STM32L4_STM32L4X6) # define STM32L4_NFSMC 1 /* Have FSMC memory controller */ # define STM32L4_NATIM 2 /* Two advanced timers TIM1 and 8 */ @@ -101,12 +138,14 @@ # define STM32L4_NUART 2 /* UART 4-5 */ # define STM32L4_NUSART 3 /* USART 1-3 */ # define STM32L4_NLPUART 1 /* LPUART 1 */ +# define STM32L4_QSPI 1 /* QuadSPI1 */ # define STM32L4_NSPI 3 /* SPI1-3 */ #if defined(CONFIG_STM32L4_STM32L496XX) # define STM32L4_NI2C 4 /* I2C1-4 */ #else # define STM32L4_NI2C 3 /* I2C1-3 */ #endif +# define STM32L4_NSWPMI 1 /* SWPMI1 */ # define STM32L4_NUSBOTGFS 1 /* USB OTG FS */ # define STM32L4_NUSBFS 0 /* No USB FS */ #if defined(CONFIG_STM32L4_STM32L496XX) @@ -142,8 +181,10 @@ # define STM32L4_NUART 1 /* UART 4 */ # define STM32L4_NUSART 3 /* USART 1-3 */ # define STM32L4_NLPUART 1 /* LPUART 1 */ +# define STM32L4_QSPI 1 /* QuadSPI1 */ # define STM32L4_NSPI 3 /* SPI1-3 */ # define STM32L4_NI2C 4 /* I2C1-4 */ +# define STM32L4_NSWPMI 1 /* SWPMI1 */ # define STM32L4_NUSBOTGFS 0 /* No USB OTG FS */ #if defined(CONFIG_STM32L4_STM32L451XX) # define STM32L4_NUSBFS 0 /* No USB FS */ @@ -178,8 +219,10 @@ # define STM32L4_NUART 0 /* No UART */ # define STM32L4_NUSART 2 /* USART 1-2 */ # define STM32L4_NLPUART 1 /* LPUART 1 */ +# define STM32L4_QSPI 1 /* QuadSPI1 */ # define STM32L4_NSPI 2 /* SPI1, SPI3 */ # define STM32L4_NI2C 2 /* I2C1, I2C3 */ +# define STM32L4_NSWPMI 1 /* SWPMI1 */ # define STM32L4_NUSBOTGFS 0 /* No USB OTG FS */ # define STM32L4_NUSBFS 1 /* USB FS */ # define STM32L4_NCAN 1 /* CAN1 */ diff --git a/arch/arm/include/stm32l4/irq.h b/arch/arm/include/stm32l4/irq.h index 480b7d693a..a6419445ad 100644 --- a/arch/arm/include/stm32l4/irq.h +++ b/arch/arm/include/stm32l4/irq.h @@ -76,10 +76,12 @@ #define STM32L4_IRQ_FIRST (16) /* Vector number of the first external interrupt */ -#if defined(CONFIG_STM32L4_STM32L4X6) -# include -#elif defined(CONFIG_STM32L4_STM32L4X3) +#if defined(CONFIG_STM32L4_STM32L4X3) # include +#elif defined(CONFIG_STM32L4_STM32L4X5) +# include +#elif defined(CONFIG_STM32L4_STM32L4X6) +# include #else # error "Unsupported STM32 L4 chip" #endif diff --git a/arch/arm/include/stm32l4/stm32l4x6xx_irq.h b/arch/arm/include/stm32l4/stm32l4x6xx_irq.h index b675e786bb..3b0a8caa27 100644 --- a/arch/arm/include/stm32l4/stm32l4x6xx_irq.h +++ b/arch/arm/include/stm32l4/stm32l4x6xx_irq.h @@ -70,12 +70,12 @@ #define STM32L4_IRQ_EXTI2 (STM32L4_IRQ_FIRST+8) /* 8: EXTI Line 2 interrupt */ #define STM32L4_IRQ_EXTI3 (STM32L4_IRQ_FIRST+9) /* 9: EXTI Line 3 interrupt */ #define STM32L4_IRQ_EXTI4 (STM32L4_IRQ_FIRST+10) /* 10: EXTI Line 4 interrupt */ -#define STM32L4_IRQ_DMA1CH1 (STM32L4_IRQ_FIRST+11) /* 12: DMA1 Channel 1 global interrupt */ -#define STM32L4_IRQ_DMA1CH2 (STM32L4_IRQ_FIRST+12) /* 13: DMA1 Channel 2 global interrupt */ -#define STM32L4_IRQ_DMA1CH3 (STM32L4_IRQ_FIRST+13) /* 14: DMA1 Channel 3 global interrupt */ -#define STM32L4_IRQ_DMA1CH4 (STM32L4_IRQ_FIRST+14) /* 15: DMA1 Channel 4 global interrupt */ -#define STM32L4_IRQ_DMA1CH5 (STM32L4_IRQ_FIRST+15) /* 16: DMA1 Channel 5 global interrupt */ -#define STM32L4_IRQ_DMA1CH6 (STM32L4_IRQ_FIRST+16) /* 17: DMA1 Channel 6 global interrupt */ +#define STM32L4_IRQ_DMA1CH1 (STM32L4_IRQ_FIRST+11) /* 11: DMA1 Channel 1 global interrupt */ +#define STM32L4_IRQ_DMA1CH2 (STM32L4_IRQ_FIRST+12) /* 12: DMA1 Channel 2 global interrupt */ +#define STM32L4_IRQ_DMA1CH3 (STM32L4_IRQ_FIRST+13) /* 13: DMA1 Channel 3 global interrupt */ +#define STM32L4_IRQ_DMA1CH4 (STM32L4_IRQ_FIRST+14) /* 14: DMA1 Channel 4 global interrupt */ +#define STM32L4_IRQ_DMA1CH5 (STM32L4_IRQ_FIRST+15) /* 15: DMA1 Channel 5 global interrupt */ +#define STM32L4_IRQ_DMA1CH6 (STM32L4_IRQ_FIRST+16) /* 16: DMA1 Channel 6 global interrupt */ #define STM32L4_IRQ_DMA1CH7 (STM32L4_IRQ_FIRST+17) /* 17: DMA1 Channel 7 global interrupt */ #define STM32L4_IRQ_ADC12 (STM32L4_IRQ_FIRST+18) /* 18: ADC1 and ADC2 global interrupt */ #define STM32L4_IRQ_CAN1TX (STM32L4_IRQ_FIRST+19) /* 19: CAN1 TX interrupts */ diff --git a/arch/arm/src/stm32l4/Kconfig b/arch/arm/src/stm32l4/Kconfig index 2721ca3871..09f5d9860f 100644 --- a/arch/arm/src/stm32l4/Kconfig +++ b/arch/arm/src/stm32l4/Kconfig @@ -220,6 +220,54 @@ config ARCH_CHIP_STM32L462VE ---help--- STM32 L4 Cortex M4, USB FS, AES, 512 Kb FLASH, 128+32 Kb SRAM +config ARCH_CHIP_STM32L475RG + bool "STM32L475RG" + select STM32L4_STM32L475XX + select STM32L4_FLASH_CONFIG_G + select STM32L4_IO_CONFIG_R + ---help--- + STM32 L4 Cortex M4, 1024Kb FLASH, 96+32 Kb SRAM, LQFP100 + +config ARCH_CHIP_STM32L475RE + bool "STM32L475RE" + select STM32L4_STM32L475XX + select STM32L4_FLASH_CONFIG_E + select STM32L4_IO_CONFIG_R + ---help--- + STM32 L4 Cortex M4, 512Kb FLASH, 96+32 Kb SRAM, LQFP100 + +config ARCH_CHIP_STM32L475RC + bool "STM32L475RC" + select STM32L4_STM32L475XX + select STM32L4_FLASH_CONFIG_E + select STM32L4_IO_CONFIG_R + ---help--- + STM32 L4 Cortex M4, 256Kb FLASH, 96+32 Kb SRAM, LQFP100 + +config ARCH_CHIP_STM32L475VG + bool "STM32L475VG" + select STM32L4_STM32L475XX + select STM32L4_FLASH_CONFIG_G + select STM32L4_IO_CONFIG_R + ---help--- + STM32 L4 Cortex M4, 1024Kb FLASH, 96+32 Kb SRAM, LQFP64 + +config ARCH_CHIP_STM32L475VE + bool "STM32L475VE" + select STM32L4_STM32L475XX + select STM32L4_FLASH_CONFIG_E + select STM32L4_IO_CONFIG_R + ---help--- + STM32 L4 Cortex M4, 512Kb FLASH, 96+32 Kb SRAM, LQFP64 + +config ARCH_CHIP_STM32L475VC + bool "STM32L475VC" + select STM32L4_STM32L475XX + select STM32L4_FLASH_CONFIG_E + select STM32L4_IO_CONFIG_R + ---help--- + STM32 L4 Cortex M4, 256Kb FLASH, 96+32 Kb SRAM, LQFP64 + config ARCH_CHIP_STM32L476RG bool "STM32L476RG" select STM32L4_STM32L476XX @@ -322,6 +370,33 @@ config STM32L4_STM32L4X5 select STM32L4_HAVE_OTGFS select STM32L4_HAVE_DFSDM1 +config STM32L4_STM32L4X5 + bool + default n + select ARCH_HAVE_FPU + select STM32L4_HAVE_USART1 + select STM32L4_HAVE_USART2 + select STM32L4_HAVE_USART3 + select STM32L4_HAVE_UART4 + select STM32L4_HAVE_UART5 + select STM32L4_HAVE_ADC2 + select STM32L4_HAVE_ADC3 + select STM32L4_HAVE_DAC2 + select STM32L4_HAVE_FSMC + select STM32L4_HAVE_TIM3 + select STM32L4_HAVE_TIM4 + select STM32L4_HAVE_TIM5 + select STM32L4_HAVE_TIM7 + select STM32L4_HAVE_TIM8 + select STM32L4_HAVE_TIM17 + select STM32L4_HAVE_LPTIM1 + select STM32L4_HAVE_LPTIM2 + select STM32L4_HAVE_COMP + select STM32L4_HAVE_SAI1 + select STM32L4_HAVE_SAI2 + select STM32L4_HAVE_SDMMC1 + select STM32L4_HAVE_OTGFS + config STM32L4_STM32L4X6 bool default n @@ -422,6 +497,11 @@ config STM32L4_STM32L471XX default n # TODO +config STM32L4_STM32L475XX + bool + default n + select STM32L4_STM32L4X5 + config STM32L4_STM32L476XX bool default n diff --git a/arch/arm/src/stm32l4/chip/stm32l4x5xx_dbgmcu.h b/arch/arm/src/stm32l4/chip/stm32l4x5xx_dbgmcu.h new file mode 100644 index 0000000000..27afd39fe6 --- /dev/null +++ b/arch/arm/src/stm32l4/chip/stm32l4x5xx_dbgmcu.h @@ -0,0 +1,113 @@ +/**************************************************************************** + * arch/arm/src/stm32l4/chip/stm32l4x5xx_dbgmcu.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * David Sidrane + * 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 __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X5XX_DBGMCU_H +#define __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X5XX_DBGMCU_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include "chip.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Register Addresses *******************************************************/ + +#define STM32_DBGMCU_IDCODE 0xe0042000 /* MCU identifier */ +#define STM32_DBGMCU_CR 0xe0042004 /* MCU debug */ +#define STM32_DBGMCU_APB1_FZ 0xe0042008 /* Debug MCU APB1 freeze register */ +#define STM32_DBGMCU_APB1_FZ2 0xe004200c /* Debug MCU APB1 freeze register 2 */ +#define STM32_DBGMCU_APB2_FZ 0xe0042010 /* Debug MCU APB2 freeze register */ + +/* Register Bitfield Definitions ********************************************/ + +/* MCU identifier */ + +#define DBGMCU_IDCODE_DEVID_SHIFT (0) /* Bits 11-0: Device Identifier */ +#define DBGMCU_IDCODE_DEVID_MASK (0x0fff << DBGMCU_IDCODE_DEVID_SHIFT) +#define DBGMCU_IDCODE_REVID_SHIFT (16) /* Bits 31-16: Revision Identifier */ +#define DBGMCU_IDCODE_REVID_MASK (0xffff << DBGMCU_IDCODE_REVID_SHIFT) + +/* MCU debug */ + +#define DBGMCU_CR_SLEEP (1 << 0) /* Bit 0: Debug Sleep Mode */ +#define DBGMCU_CR_STOP (1 << 1) /* Bit 1: Debug Stop Mode */ +#define DBGMCU_CR_STANDBY (1 << 2) /* Bit 2: Debug Standby mode */ +#define DBGMCU_CR_TRACEIOEN (1 << 5) /* Bit 5: Trace enabled */ + +#define DBGMCU_CR_TRACEMODE_SHIFT (6) /* Bits 7-6: Trace mode pin assignment */ +#define DBGMCU_CR_TRACEMODE_MASK (3 << DBGMCU_CR_TRACEMODE_SHIFT) +# define DBGMCU_CR_ASYNCH (0 << DBGMCU_CR_TRACEMODE_SHIFT) /* Asynchronous Mode */ +# define DBGMCU_CR_SYNCH1 (1 << DBGMCU_CR_TRACEMODE_SHIFT) /* Synchronous Mode, TRACEDATA size=1 */ +# define DBGMCU_CR_SYNCH2 (2 << DBGMCU_CR_TRACEMODE_SHIFT) /* Synchronous Mode, TRACEDATA size=2 */ +# define DBGMCU_CR_SYNCH4 (3 << DBGMCU_CR_TRACEMODE_SHIFT) /* Synchronous Mode, TRACEDATA size=4 */ + +/* Debug MCU APB1 freeze register */ + +#define DBGMCU_APB1_TIM2STOP (1 << 0) /* Bit 0: TIM2 stopped when core is halted */ +#define DBGMCU_APB1_TIM3STOP (1 << 1) /* Bit 1: TIM3 stopped when core is halted */ +#define DBGMCU_APB1_TIM4STOP (1 << 2) /* Bit 2: TIM4 stopped when core is halted */ +#define DBGMCU_APB1_TIM5STOP (1 << 3) /* Bit 3: TIM5 stopped when core is halted */ +#define DBGMCU_APB1_TIM6STOP (1 << 4) /* Bit 4: TIM6 stopped when core is halted */ +#define DBGMCU_APB1_TIM7STOP (1 << 5) /* Bit 5: TIM7 stopped when core is halted */ +#define DBGMCU_APB1_RTCSTOP (1 << 10) /* Bit 10: RTC stopped when Core is halted */ +#define DBGMCU_APB1_WWDGSTOP (1 << 11) /* Bit 11: Window Watchdog stopped when core is halted */ +#define DBGMCU_APB1_IWDGSTOP (1 << 12) /* Bit 12: Independent Watchdog stopped when core is halted */ +#define DBGMCU_APB1_I2C1STOP (1 << 21) /* Bit 21: I2C1 SMBUS timeout mode stopped when Core is halted */ +#define DBGMCU_APB1_I2C2STOP (1 << 22) /* Bit 22: I2C2 SMBUS timeout mode stopped when Core is halted */ +#define DBGMCU_APB1_I2C3STOP (1 << 23) /* Bit 23: I2C3 SMBUS timeout mode stopped when Core is halted */ +#define DBGMCU_APB1_CAN1STOP (1 << 25) /* Bit 25: CAN1 stopped when core is halted */ +#define DBGMCU_APB1_LPTIM1STOP (1 << 31) /* Bit 31: LPTIM1 stopper when core is halted */ + +/* Debug MCU APB1 freeze register 2 */ + +#define DBGMCU_APB1_FZ2_LPTIM2STOP (1 << 5) /* Bit 5: LPTIM2 stopper when core is halted */ + +/* Debug MCU APB2 freeze register */ + +#define DBGMCU_APB2_TIM1STOP (1 << 11) /* Bit 11: TIM1 stopped when core is halted */ +#define DBGMCU_APB2_TIM8STOP (1 << 13) /* Bit 13: TIM8 stopped when core is halted */ +#define DBGMCU_APB2_TIM15STOP (1 << 16) /* Bit 16: TIM15 stopped when core is halted */ +#define DBGMCU_APB2_TIM16STOP (1 << 17) /* Bit 17: TIM16 stopped when core is halted */ +#define DBGMCU_APB2_TIM17STOP (1 << 18) /* Bit 18: TIM17 stopped when core is halted */ + +#endif /* __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X5XXDBGMCU_H */ diff --git a/arch/arm/src/stm32l4/chip/stm32l4x5xx_dma.h b/arch/arm/src/stm32l4/chip/stm32l4x5xx_dma.h new file mode 100644 index 0000000000..2b44d7f839 --- /dev/null +++ b/arch/arm/src/stm32l4/chip/stm32l4x5xx_dma.h @@ -0,0 +1,485 @@ +/************************************************************************************ + * arch/arm/src/stm32l4/chip/stm32l4x6xx_dma.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X5XX_DMA_H +#define __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X5XX_DMA_H + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* 14 Channels Total: 7 DMA1 Channels(1-7) and 7 DMA2 channels (1-7) */ + +#define DMA1 0 +#define DMA2 1 +#define DMA3 2 +#define DMA4 3 +#define DMA5 4 +#define DMA6 5 +#define DMA7 6 + +/* Register Offsets *****************************************************************/ + +#define STM32L4_DMA_ISR_OFFSET 0x0000 /* DMA interrupt status register */ +#define STM32L4_DMA_IFCR_OFFSET 0x0004 /* DMA interrupt flag clear register */ + +#define STM32L4_DMACHAN_OFFSET(n) (0x0014*(n)) +#define STM32L4_DMACHAN1_OFFSET 0x0000 +#define STM32L4_DMACHAN2_OFFSET 0x0014 +#define STM32L4_DMACHAN3_OFFSET 0x0028 +#define STM32L4_DMACHAN4_OFFSET 0x003c +#define STM32L4_DMACHAN5_OFFSET 0x0050 +#define STM32L4_DMACHAN6_OFFSET 0x0064 +#define STM32L4_DMACHAN7_OFFSET 0x0078 + +#define STM32L4_DMACHAN_CCR_OFFSET 0x0008 /* DMA channel configuration register */ +#define STM32L4_DMACHAN_CNDTR_OFFSET 0x000c /* DMA channel number of data register */ +#define STM32L4_DMACHAN_CPAR_OFFSET 0x0010 /* DMA channel peripheral address register */ +#define STM32L4_DMACHAN_CMAR_OFFSET 0x0014 /* DMA channel memory address register */ + +#define STM32L4_DMA_CCR_OFFSET(n) (STM32L4_DMACHAN_CCR_OFFSET+STM32L4_DMACHAN_OFFSET(n)) +#define STM32L4_DMA_CNDTR_OFFSET(n) (STM32L4_DMACHAN_CNDTR_OFFSET+STM32L4_DMACHAN_OFFSET(n)) +#define STM32L4_DMA_CPAR_OFFSET(n) (STM32L4_DMACHAN_CPAR_OFFSET+STM32L4_DMACHAN_OFFSET(n)) +#define STM32L4_DMA_CMAR_OFFSET(n) (STM32L4_DMACHAN_CMAR_OFFSET+STM32L4_DMACHAN_OFFSET(n)) + +#define STM32L4_DMA_CCR1_OFFSET 0x0008 /* DMA channel 1 configuration register */ +#define STM32L4_DMA_CCR2_OFFSET 0x001c /* DMA channel 2 configuration register */ +#define STM32L4_DMA_CCR3_OFFSET 0x0030 /* DMA channel 3 configuration register */ +#define STM32L4_DMA_CCR4_OFFSET 0x0044 /* DMA channel 4 configuration register */ +#define STM32L4_DMA_CCR5_OFFSET 0x0058 /* DMA channel 5 configuration register */ +#define STM32L4_DMA_CCR6_OFFSET 0x006c /* DMA channel 6 configuration register */ +#define STM32L4_DMA_CCR7_OFFSET 0x0080 /* DMA channel 7 configuration register */ + +#define STM32L4_DMA_CNDTR1_OFFSET 0x000c /* DMA channel 1 number of data register */ +#define STM32L4_DMA_CNDTR2_OFFSET 0x0020 /* DMA channel 2 number of data register */ +#define STM32L4_DMA_CNDTR3_OFFSET 0x0034 /* DMA channel 3 number of data register */ +#define STM32L4_DMA_CNDTR4_OFFSET 0x0048 /* DMA channel 4 number of data register */ +#define STM32L4_DMA_CNDTR5_OFFSET 0x005c /* DMA channel 5 number of data register */ +#define STM32L4_DMA_CNDTR6_OFFSET 0x0070 /* DMA channel 6 number of data register */ +#define STM32L4_DMA_CNDTR7_OFFSET 0x0084 /* DMA channel 7 number of data register */ + +#define STM32L4_DMA_CPAR1_OFFSET 0x0010 /* DMA channel 1 peripheral address register */ +#define STM32L4_DMA_CPAR2_OFFSET 0x0024 /* DMA channel 2 peripheral address register */ +#define STM32L4_DMA_CPAR3_OFFSET 0x0038 /* DMA channel 3 peripheral address register */ +#define STM32L4_DMA_CPAR4_OFFSET 0x004c /* DMA channel 4 peripheral address register */ +#define STM32L4_DMA_CPAR5_OFFSET 0x0060 /* DMA channel 5 peripheral address register */ +#define STM32L4_DMA_CPAR6_OFFSET 0x0074 /* DMA channel 6 peripheral address register */ +#define STM32L4_DMA_CPAR7_OFFSET 0x0088 /* DMA channel 7 peripheral address register */ + +#define STM32L4_DMA_CMAR1_OFFSET 0x0014 /* DMA channel 1 memory address register */ +#define STM32L4_DMA_CMAR2_OFFSET 0x0028 /* DMA channel 2 memory address register */ +#define STM32L4_DMA_CMAR3_OFFSET 0x003c /* DMA channel 3 memory address register */ +#define STM32L4_DMA_CMAR4_OFFSET 0x0050 /* DMA channel 4 memory address register */ +#define STM32L4_DMA_CMAR5_OFFSET 0x0064 /* DMA channel 5 memory address register */ +#define STM32L4_DMA_CMAR6_OFFSET 0x0078 /* DMA channel 6 memory address register */ +#define STM32L4_DMA_CMAR7_OFFSET 0x008c /* DMA channel 7 memory address register */ + +#define STM32L4_DMA_CSELR_OFFSET 0x00a8 /* DMA channel selection register */ + +/* Register Addresses ***************************************************************/ + +#define STM32L4_DMA1_ISRC (STM32L4_DMA1_BASE+STM32L4_DMA_ISR_OFFSET) +#define STM32L4_DMA1_IFCR (STM32L4_DMA1_BASE+STM32L4_DMA_IFCR_OFFSET) + +#define STM32L4_DMA1_CCR(n) (STM32L4_DMA1_BASE+STM32L4_DMA_CCR_OFFSET(n)) +#define STM32L4_DMA1_CCR1 (STM32L4_DMA1_BASE+STM32L4_DMA_CCR1_OFFSET) +#define STM32L4_DMA1_CCR2 (STM32L4_DMA1_BASE+STM32L4_DMA_CCR2_OFFSET) +#define STM32L4_DMA1_CCR3 (STM32L4_DMA1_BASE+STM32L4_DMA_CCR3_OFFSET) +#define STM32L4_DMA1_CCR4 (STM32L4_DMA1_BASE+STM32L4_DMA_CCR4_OFFSET) +#define STM32L4_DMA1_CCR5 (STM32L4_DMA1_BASE+STM32L4_DMA_CCR5_OFFSET) +#define STM32L4_DMA1_CCR6 (STM32L4_DMA1_BASE+STM32L4_DMA_CCR6_OFFSET) +#define STM32L4_DMA1_CCR7 (STM32L4_DMA1_BASE+STM32L4_DMA_CCR7_OFFSET) + +#define STM32L4_DMA1_CNDTR(n) (STM32L4_DMA1_BASE+STM32L4_DMA_CNDTR_OFFSET(n)) +#define STM32L4_DMA1_CNDTR1 (STM32L4_DMA1_BASE+STM32L4_DMA_CNDTR1_OFFSET) +#define STM32L4_DMA1_CNDTR2 (STM32L4_DMA1_BASE+STM32L4_DMA_CNDTR2_OFFSET) +#define STM32L4_DMA1_CNDTR3 (STM32L4_DMA1_BASE+STM32L4_DMA_CNDTR3_OFFSET) +#define STM32L4_DMA1_CNDTR4 (STM32L4_DMA1_BASE+STM32L4_DMA_CNDTR4_OFFSET) +#define STM32L4_DMA1_CNDTR5 (STM32L4_DMA1_BASE+STM32L4_DMA_CNDTR5_OFFSET) +#define STM32L4_DMA1_CNDTR6 (STM32L4_DMA1_BASE+STM32L4_DMA_CNDTR6_OFFSET) +#define STM32L4_DMA1_CNDTR7 (STM32L4_DMA1_BASE+STM32L4_DMA_CNDTR7_OFFSET) + +#define STM32L4_DMA1_CPAR(n) (STM32L4_DMA1_BASE+STM32L4_DMA_CPAR_OFFSET(n)) +#define STM32L4_DMA1_CPAR1 (STM32L4_DMA1_BASE+STM32L4_DMA_CPAR1_OFFSET) +#define STM32L4_DMA1_CPAR2 (STM32L4_DMA1_BASE+STM32L4_DMA_CPAR2_OFFSET) +#define STM32L4_DMA1_CPAR3 (STM32L4_DMA1_BASE+STM32L4_DMA_CPAR3_OFFSET) +#define STM32L4_DMA1_CPAR4 (STM32L4_DMA1_BASE+STM32L4_DMA_CPAR4_OFFSET) +#define STM32L4_DMA1_CPAR5 (STM32L4_DMA1_BASE+STM32L4_DMA_CPAR5_OFFSET) +#define STM32L4_DMA1_CPAR6 (STM32L4_DMA1_BASE+STM32L4_DMA_CPAR6_OFFSET) +#define STM32L4_DMA1_CPAR7 (STM32L4_DMA1_BASE+STM32L4_DMA_CPAR7_OFFSET) + +#define STM32L4_DMA1_CMAR(n) (STM32L4_DMA1_BASE+STM32L4_DMA_CMAR_OFFSET(n)) +#define STM32L4_DMA1_CMAR1 (STM32L4_DMA1_BASE+STM32L4_DMA_CMAR1_OFFSET) +#define STM32L4_DMA1_CMAR2 (STM32L4_DMA1_BASE+STM32L4_DMA_CMAR2_OFFSET) +#define STM32L4_DMA1_CMAR3 (STM32L4_DMA1_BASE+STM32L4_DMA_CMAR3_OFFSET) +#define STM32L4_DMA1_CMAR4 (STM32L4_DMA1_BASE+STM32L4_DMA_CMAR4_OFFSET) +#define STM32L4_DMA1_CMAR5 (STM32L4_DMA1_BASE+STM32L4_DMA_CMAR5_OFFSET) +#define STM32L4_DMA1_CMAR6 (STM32L4_DMA1_BASE+STM32L4_DMA_CMAR6_OFFSET) +#define STM32L4_DMA1_CMAR7 (STM32L4_DMA1_BASE+STM32L4_DMA_CMAR7_OFFSET) + +#define STM32L4_DMA2_ISRC (STM32L4_DMA2_BASE+STM32L4_DMA_ISR_OFFSET) +#define STM32L4_DMA2_IFCR (STM32L4_DMA2_BASE+STM32L4_DMA_IFCR_OFFSET) + +#define STM32L4_DMA2_CCR(n) (STM32L4_DMA2_BASE+STM32L4_DMA_CCR_OFFSET(n)) +#define STM32L4_DMA2_CCR1 (STM32L4_DMA2_BASE+STM32L4_DMA_CCR1_OFFSET) +#define STM32L4_DMA2_CCR2 (STM32L4_DMA2_BASE+STM32L4_DMA_CCR2_OFFSET) +#define STM32L4_DMA2_CCR3 (STM32L4_DMA2_BASE+STM32L4_DMA_CCR3_OFFSET) +#define STM32L4_DMA2_CCR4 (STM32L4_DMA2_BASE+STM32L4_DMA_CCR4_OFFSET) +#define STM32L4_DMA2_CCR5 (STM32L4_DMA2_BASE+STM32L4_DMA_CCR5_OFFSET) +#define STM32L4_DMA2_CCR6 (STM32L4_DMA2_BASE+STM32L4_DMA_CCR6_OFFSET) +#define STM32L4_DMA2_CCR7 (STM32L4_DMA2_BASE+STM32L4_DMA_CCR7_OFFSET) + +#define STM32L4_DMA2_CNDTR(n) (STM32L4_DMA2_BASE+STM32L4_DMA_CNDTR_OFFSET(n)) +#define STM32L4_DMA2_CNDTR1 (STM32L4_DMA2_BASE+STM32L4_DMA_CNDTR1_OFFSET) +#define STM32L4_DMA2_CNDTR2 (STM32L4_DMA2_BASE+STM32L4_DMA_CNDTR2_OFFSET) +#define STM32L4_DMA2_CNDTR3 (STM32L4_DMA2_BASE+STM32L4_DMA_CNDTR3_OFFSET) +#define STM32L4_DMA2_CNDTR4 (STM32L4_DMA2_BASE+STM32L4_DMA_CNDTR4_OFFSET) +#define STM32L4_DMA2_CNDTR5 (STM32L4_DMA2_BASE+STM32L4_DMA_CNDTR5_OFFSET) +#define STM32L4_DMA2_CNDTR6 (STM32L4_DMA2_BASE+STM32L4_DMA_CNDTR6_OFFSET) +#define STM32L4_DMA2_CNDTR7 (STM32L4_DMA2_BASE+STM32L4_DMA_CNDTR7_OFFSET) + +#define STM32L4_DMA2_CPAR(n) (STM32L4_DMA2_BASE+STM32L4_DMA_CPAR_OFFSET(n)) +#define STM32L4_DMA2_CPAR1 (STM32L4_DMA2_BASE+STM32L4_DMA_CPAR1_OFFSET) +#define STM32L4_DMA2_CPAR2 (STM32L4_DMA2_BASE+STM32L4_DMA_CPAR2_OFFSET) +#define STM32L4_DMA2_CPAR3 (STM32L4_DMA2_BASE+STM32L4_DMA_CPAR3_OFFSET) +#define STM32L4_DMA2_CPAR4 (STM32L4_DMA2_BASE+STM32L4_DMA_CPAR4_OFFSET) +#define STM32L4_DMA2_CPAR5 (STM32L4_DMA2_BASE+STM32L4_DMA_CPAR5_OFFSET) +#define STM32L4_DMA2_CPAR6 (STM32L4_DMA2_BASE+STM32L4_DMA_CPAR6_OFFSET) +#define STM32L4_DMA2_CPAR7 (STM32L4_DMA2_BASE+STM32L4_DMA_CPAR7_OFFSET) + +#define STM32L4_DMA2_CMAR(n) (STM32L4_DMA2_BASE+STM32L4_DMA_CMAR_OFFSET(n)) +#define STM32L4_DMA2_CMAR1 (STM32L4_DMA2_BASE+STM32L4_DMA_CMAR1_OFFSET) +#define STM32L4_DMA2_CMAR2 (STM32L4_DMA2_BASE+STM32L4_DMA_CMAR2_OFFSET) +#define STM32L4_DMA2_CMAR3 (STM32L4_DMA2_BASE+STM32L4_DMA_CMAR3_OFFSET) +#define STM32L4_DMA2_CMAR4 (STM32L4_DMA2_BASE+STM32L4_DMA_CMAR4_OFFSET) +#define STM32L4_DMA2_CMAR5 (STM32L4_DMA2_BASE+STM32L4_DMA_CMAR5_OFFSET) +#define STM32L4_DMA2_CMAR6 (STM32L4_DMA2_BASE+STM32L4_DMA_CMAR6_OFFSET) +#define STM32L4_DMA2_CMAR7 (STM32L4_DMA2_BASE+STM32L4_DMA_CMAR7_OFFSET) + +/* Register Bitfield Definitions ****************************************************/ + +#define DMA_CHAN_SHIFT(n) ((n) << 2) +#define DMA_CHAN_MASK 0x0f +#define DMA_CHAN_GIF_BIT (1 << 0) /* Bit 0: Channel Global interrupt flag */ +#define DMA_CHAN_TCIF_BIT (1 << 1) /* Bit 1: Channel Transfer Complete flag */ +#define DMA_CHAN_HTIF_BIT (1 << 2) /* Bit 2: Channel Half Transfer flag */ +#define DMA_CHAN_TEIF_BIT (1 << 3) /* Bit 3: Channel Transfer Error flag */ + +/* DMA interrupt status register */ + +#define DMA_ISR_CHAN_SHIFT(n) DMA_CHAN_SHIFT(n) +#define DMA_ISR_CHAN_MASK(n) (DMA_CHAN_MASK << DMA_ISR_CHAN_SHIFT(n)) +#define DMA_ISR_CHAN1_SHIFT (0) /* Bits 3-0: DMA Channel 1 interrupt status */ +#define DMA_ISR_CHAN1_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN1_SHIFT) +#define DMA_ISR_CHAN2_SHIFT (4) /* Bits 7-4: DMA Channel 2 interrupt status */ +#define DMA_ISR_CHAN2_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN2_SHIFT) +#define DMA_ISR_CHAN3_SHIFT (8) /* Bits 11-8: DMA Channel 3 interrupt status */ +#define DMA_ISR_CHAN3_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN3_SHIFT) +#define DMA_ISR_CHAN4_SHIFT (12) /* Bits 15-12: DMA Channel 4 interrupt status */ +#define DMA_ISR_CHAN4_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN4_SHIFT) +#define DMA_ISR_CHAN5_SHIFT (16) /* Bits 19-16: DMA Channel 5 interrupt status */ +#define DMA_ISR_CHAN5_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN5_SHIFT) +#define DMA_ISR_CHAN6_SHIFT (20) /* Bits 23-20: DMA Channel 6 interrupt status */ +#define DMA_ISR_CHAN6_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN6_SHIFT) +#define DMA_ISR_CHAN7_SHIFT (24) /* Bits 27-24: DMA Channel 7 interrupt status */ +#define DMA_ISR_CHAN7_MASK (DMA_CHAN_MASK << DMA_ISR_CHAN7_SHIFT) + +#define DMA_ISR_GIF(n) (DMA_CHAN_GIF_BIT << DMA_ISR_CHAN_SHIFT(n)) +#define DMA_ISR_TCIF(n) (DMA_CHAN_TCIF_BIT << DMA_ISR_CHAN_SHIFT(n)) +#define DMA_ISR_HTIF(n) (DMA_CHAN_HTIF_BIT << DMA_ISR_CHAN_SHIFT(n)) +#define DMA_ISR_TEIF(n) (DMA_CHAN_TEIF_BIT << DMA_ISR_CHAN_SHIFT(n)) + +/* DMA interrupt flag clear register */ + +#define DMA_IFCR_CHAN_SHIFT(n) DMA_CHAN_SHIFT(n) +#define DMA_IFCR_CHAN_MASK(n) (DMA_CHAN_MASK << DMA_IFCR_CHAN_SHIFT(n)) +#define DMA_IFCR_CHAN1_SHIFT (0) /* Bits 3-0: DMA Channel 1 interrupt flag clear */ +#define DMA_IFCR_CHAN1_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN1_SHIFT) +#define DMA_IFCR_CHAN2_SHIFT (4) /* Bits 7-4: DMA Channel 2 interrupt flag clear */ +#define DMA_IFCR_CHAN2_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN2_SHIFT) +#define DMA_IFCR_CHAN3_SHIFT (8) /* Bits 11-8: DMA Channel 3 interrupt flag clear */ +#define DMA_IFCR_CHAN3_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN3_SHIFT) +#define DMA_IFCR_CHAN4_SHIFT (12) /* Bits 15-12: DMA Channel 4 interrupt flag clear */ +#define DMA_IFCR_CHAN4_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN4_SHIFT) +#define DMA_IFCR_CHAN5_SHIFT (16) /* Bits 19-16: DMA Channel 5 interrupt flag clear */ +#define DMA_IFCR_CHAN5_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN5_SHIFT) +#define DMA_IFCR_CHAN6_SHIFT (20) /* Bits 23-20: DMA Channel 6 interrupt flag clear */ +#define DMA_IFCR_CHAN6_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN6_SHIFT) +#define DMA_IFCR_CHAN7_SHIFT (24) /* Bits 27-24: DMA Channel 7 interrupt flag clear */ +#define DMA_IFCR_CHAN7_MASK (DMA_CHAN_MASK << DMA_IFCR_CHAN7_SHIFT) +#define DMA_IFCR_ALLCHANNELS (0x0fffffff) + +#define DMA_IFCR_CGIF(n) (DMA_CHAN_GIF_BIT << DMA_IFCR_CHAN_SHIFT(n)) +#define DMA_IFCR_CTCIF(n) (DMA_CHAN_TCIF_BIT << DMA_IFCR_CHAN_SHIFT(n)) +#define DMA_IFCR_CHTIF(n) (DMA_CHAN_HTIF_BIT << DMA_IFCR_CHAN_SHIFT(n)) +#define DMA_IFCR_CTEIF(n) (DMA_CHAN_TEIF_BIT << DMA_IFCR_CHAN_SHIFT(n)) + +/* DMA channel configuration register */ + +#define DMA_CCR_EN (1 << 0) /* Bit 0: Channel enable */ +#define DMA_CCR_TCIE (1 << 1) /* Bit 1: Transfer complete interrupt enable */ +#define DMA_CCR_HTIE (1 << 2) /* Bit 2: Half Transfer interrupt enable */ +#define DMA_CCR_TEIE (1 << 3) /* Bit 3: Transfer error interrupt enable */ +#define DMA_CCR_DIR (1 << 4) /* Bit 4: Data transfer direction */ +#define DMA_CCR_CIRC (1 << 5) /* Bit 5: Circular mode */ +#define DMA_CCR_PINC (1 << 6) /* Bit 6: Peripheral increment mode */ +#define DMA_CCR_MINC (1 << 7) /* Bit 7: Memory increment mode */ +#define DMA_CCR_PSIZE_SHIFT (8) /* Bits 8-9: Peripheral size */ +#define DMA_CCR_PSIZE_MASK (3 << DMA_CCR_PSIZE_SHIFT) +# define DMA_CCR_PSIZE_8BITS (0 << DMA_CCR_PSIZE_SHIFT) /* 00: 8-bits */ +# define DMA_CCR_PSIZE_16BITS (1 << DMA_CCR_PSIZE_SHIFT) /* 01: 16-bits */ +# define DMA_CCR_PSIZE_32BITS (2 << DMA_CCR_PSIZE_SHIFT) /* 10: 32-bits */ +#define DMA_CCR_MSIZE_SHIFT (10) /* Bits 10-11: Memory size */ +#define DMA_CCR_MSIZE_MASK (3 << DMA_CCR_MSIZE_SHIFT) +# define DMA_CCR_MSIZE_8BITS (0 << DMA_CCR_MSIZE_SHIFT) /* 00: 8-bits */ +# define DMA_CCR_MSIZE_16BITS (1 << DMA_CCR_MSIZE_SHIFT) /* 01: 16-bits */ +# define DMA_CCR_MSIZE_32BITS (2 << DMA_CCR_MSIZE_SHIFT) /* 10: 32-bits */ +#define DMA_CCR_PL_SHIFT (12) /* Bits 12-13: Channel Priority level */ +#define DMA_CCR_PL_MASK (3 << DMA_CCR_PL_SHIFT) +# define DMA_CCR_PRILO (0 << DMA_CCR_PL_SHIFT) /* 00: Low */ +# define DMA_CCR_PRIMED (1 << DMA_CCR_PL_SHIFT) /* 01: Medium */ +# define DMA_CCR_PRIHI (2 << DMA_CCR_PL_SHIFT) /* 10: High */ +# define DMA_CCR_PRIVERYHI (3 << DMA_CCR_PL_SHIFT) /* 11: Very high */ +#define DMA_CCR_MEM2MEM (1 << 14) /* Bit 14: Memory to memory mode */ + +#define DMA_CCR_ALLINTS (DMA_CCR_TEIE|DMA_CCR_HTIE|DMA_CCR_TCIE) + +/* DMA channel number of data register */ + +#define DMA_CNDTR_NDT_SHIFT (0) /* Bits 15-0: Number of data to Transfer */ +#define DMA_CNDTR_NDT_MASK (0xffff << DMA_CNDTR_NDT_SHIFT) + +/* DMA Channel mapping. Each DMA channel has a mapping to one of several + * possible sources/sinks of data. The requests from peripherals assigned to a + * channel are multiplexed together before entering the DMA block. This means + * that only one request on a given channel can be enabled at once. + * + * Alternative DMA channel selections are provided with a numeric suffix like _1, + * _2, etc. Drivers, however, will use the pin selection without the numeric suffix. + * Additional definitions are required in the board.h file. + */ + +#define STM32L4_DMA1_CHAN1 (0) +#define STM32L4_DMA1_CHAN2 (1) +#define STM32L4_DMA1_CHAN3 (2) +#define STM32L4_DMA1_CHAN4 (3) +#define STM32L4_DMA1_CHAN5 (4) +#define STM32L4_DMA1_CHAN6 (5) +#define STM32L4_DMA1_CHAN7 (6) + +#define STM32L4_DMA2_CHAN1 (7) +#define STM32L4_DMA2_CHAN2 (8) +#define STM32L4_DMA2_CHAN3 (9) +#define STM32L4_DMA2_CHAN4 (10) +#define STM32L4_DMA2_CHAN5 (11) +#define STM32L4_DMA2_CHAN6 (12) +#define STM32L4_DMA2_CHAN7 (13) + +/* DMA Channel settings include a channel and an alternative function. + * Channel is in bits 0..7 + * Request number is in bits 8..15 + */ + +#define DMACHAN_SETTING(chan, req) ((((req) & 0xff) << 8) | ((chan) & 0xff)) +#define DMACHAN_SETTING_CHANNEL_MASK 0x00FF +#define DMACHAN_SETTING_CHANNEL_SHIFT (0) +#define DMACHAN_SETTING_FUNCTION_MASK 0xFF00 +#define DMACHAN_SETTING_FUNCTION_SHIFT (8) + +/* ADC */ + +#define DMACHAN_ADC1_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN1, 0) +#define DMACHAN_ADC1_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN3, 0) + +#define DMACHAN_ADC2_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN1, 0) +#define DMACHAN_ADC2_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN4, 0) + +#define DMACHAN_ADC3_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN1, 0) +#define DMACHAN_ADC3_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN5, 0) + +/* DAC */ + +#define DMACHAN_DAC1_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN3, 6) +#define DMACHAN_DAC1_3 DMACHAN_SETTING(STM32L4_DMA2_CHAN4, 3) + +#define DMACHAN_DAC2_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN4, 5) +#define DMACHAN_DAC2_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN5, 3) + +/* DFSDM */ + +#define DMACHAN_DFSDM0 DMACHAN_SETTING(STM32L4_DMA1_CHAN4, 0) +#define DMACHAN_DFSDM1 DMACHAN_SETTING(STM32L4_DMA1_CHAN5, 0) +#define DMACHAN_DFSDM2 DMACHAN_SETTING(STM32L4_DMA1_CHAN6, 0) +#define DMACHAN_DFSDM3 DMACHAN_SETTING(STM32L4_DMA1_CHAN7, 0) + +/* I2C */ + +#define DMACHAN_I2C1_RX_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN7, 3) +#define DMACHAN_I2C1_RX_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN6, 5) +#define DMACHAN_I2C1_TX_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN6, 3) +#define DMACHAN_I2C1_TX_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN7, 5) + +#define DMACHAN_I2C2_RX DMACHAN_SETTING(STM32L4_DMA1_CHAN5, 3) +#define DMACHAN_I2C2_TX DMACHAN_SETTING(STM32L4_DMA1_CHAN4, 3) + +#define DMACHAN_I2C3_RX DMACHAN_SETTING(STM32L4_DMA1_CHAN3, 3) +#define DMACHAN_I2C3_TX DMACHAN_SETTING(STM32L4_DMA1_CHAN2, 3) + +/* QUADSPI */ + +#define DMACHAN_QUADSPI_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN5, 5) +#define DMACHAN_QUADSPI_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN7, 3) + +/* SAI */ + +#define DMACHAN_SAI1_A_1 DMACHAN_SETTING(STM32L4_DMA2_CHAN1, 1) +#define DMACHAN_SAI1_A_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN6, 1) +#define DMACHAN_SAI1_B_1 DMACHAN_SETTING(STM32L4_DMA2_CHAN2, 1) +#define DMACHAN_SAI1_B_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN7, 1) + +#define DMACHAN_SAI2_A_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN6, 1) +#define DMACHAN_SAI2_A_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN3, 1) +#define DMACHAN_SAI2_B_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN7, 1) +#define DMACHAN_SAI2_B_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN4, 1) + +/* SDMMC */ + +#define DMACHAN_SDMMC_1 DMACHAN_SETTING(STM32L4_DMA2_CHAN4, 7) +#define DMACHAN_SDMMC_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN5, 7) + +/* SPI */ + +#define DMACHAN_SPI1_RX_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN2, 1) +#define DMACHAN_SPI1_RX_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN3, 4) +#define DMACHAN_SPI1_TX_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN3, 1) +#define DMACHAN_SPI1_TX_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN4, 4) + +#define DMACHAN_SPI2_RX DMACHAN_SETTING(STM32L4_DMA1_CHAN4, 1) +#define DMACHAN_SPI2_TX DMACHAN_SETTING(STM32L4_DMA1_CHAN5, 1) + +#define DMACHAN_SPI3_RX DMACHAN_SETTING(STM32L4_DMA2_CHAN1, 3) +#define DMACHAN_SPI3_TX DMACHAN_SETTING(STM32L4_DMA2_CHAN2, 3) + +/* SWPMI */ + +#define DMACHAN_SWPMI_RX DMACHAN_SETTING(STM32L4_DMA2_CHAN1, 4) +#define DMACHAN_SWPMI_TX DMACHAN_SETTING(STM32L4_DMA2_CHAN2, 4) + +/* TIM */ + +#define DMACHAN_TIM1_CH1 DMACHAN_SETTING(STM32L4_DMA1_CHAN2, 7) +#define DMACHAN_TIM1_CH2 DMACHAN_SETTING(STM32L4_DMA1_CHAN3, 7) +#define DMACHAN_TIM1_CH3 DMACHAN_SETTING(STM32L4_DMA1_CHAN7, 7) +#define DMACHAN_TIM1_CH4 DMACHAN_SETTING(STM32L4_DMA1_CHAN4, 7) +#define DMACHAN_TIM1_COM DMACHAN_SETTING(STM32L4_DMA1_CHAN4, 7) +#define DMACHAN_TIM1_TRIG DMACHAN_SETTING(STM32L4_DMA1_CHAN4, 7) +#define DMACHAN_TIM1_UP DMACHAN_SETTING(STM32L4_DMA1_CHAN6, 7) + +#define DMACHAN_TIM2_CH1 DMACHAN_SETTING(STM32L4_DMA1_CHAN5, 4) +#define DMACHAN_TIM2_CH2 DMACHAN_SETTING(STM32L4_DMA1_CHAN7, 4) +#define DMACHAN_TIM2_CH3 DMACHAN_SETTING(STM32L4_DMA1_CHAN1, 4) +#define DMACHAN_TIM2_CH4 DMACHAN_SETTING(STM32L4_DMA1_CHAN7, 4) +#define DMACHAN_TIM2_UP DMACHAN_SETTING(STM32L4_DMA1_CHAN2, 4) + +#define DMACHAN_TIM3_CH1 DMACHAN_SETTING(STM32L4_DMA1_CHAN6, 5) +#define DMACHAN_TIM3_CH3 DMACHAN_SETTING(STM32L4_DMA1_CHAN2, 5) +#define DMACHAN_TIM3_CH4 DMACHAN_SETTING(STM32L4_DMA1_CHAN3, 5) +#define DMACHAN_TIM3_TRIG DMACHAN_SETTING(STM32L4_DMA1_CHAN6, 5) +#define DMACHAN_TIM3_UP DMACHAN_SETTING(STM32L4_DMA1_CHAN3, 5) + +#define DMACHAN_TIM4_CH1 DMACHAN_SETTING(STM32L4_DMA1_CHAN1, 6) +#define DMACHAN_TIM4_CH2 DMACHAN_SETTING(STM32L4_DMA1_CHAN4, 6) +#define DMACHAN_TIM4_CH3 DMACHAN_SETTING(STM32L4_DMA1_CHAN5, 6) +#define DMACHAN_TIM4_UP DMACHAN_SETTING(STM32L4_DMA1_CHAN7, 6) + +#define DMACHAN_TIM5_CH1 DMACHAN_SETTING(STM32L4_DMA2_CHAN5, 5) +#define DMACHAN_TIM5_CH2 DMACHAN_SETTING(STM32L4_DMA2_CHAN4, 5) +#define DMACHAN_TIM5_CH3 DMACHAN_SETTING(STM32L4_DMA2_CHAN2, 5) +#define DMACHAN_TIM5_CH4 DMACHAN_SETTING(STM32L4_DMA2_CHAN1, 5) +#define DMACHAN_TIM5_COM DMACHAN_SETTING(STM32L4_DMA2_CHAN1, 5) +#define DMACHAN_TIM5_TRIG DMACHAN_SETTING(STM32L4_DMA2_CHAN1, 5) +#define DMACHAN_TIM5_UP DMACHAN_SETTING(STM32L4_DMA2_CHAN2, 5) + +#define DMACHAN_TIM6_UP_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN3, 6) +#define DMACHAN_TIM6_UP_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN4, 3) + +#define DMACHAN_TIM7_UP_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN4, 5) +#define DMACHAN_TIM7_UP_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN5, 3) + +#define DMACHAN_TIM8_CH1 DMACHAN_SETTING(STM32L4_DMA2_CHAN6, 7) +#define DMACHAN_TIM8_CH2 DMACHAN_SETTING(STM32L4_DMA2_CHAN7, 7) +#define DMACHAN_TIM8_CH3 DMACHAN_SETTING(STM32L4_DMA2_CHAN1, 7) +#define DMACHAN_TIM8_CH4 DMACHAN_SETTING(STM32L4_DMA2_CHAN2, 7) +#define DMACHAN_TIM8_COM DMACHAN_SETTING(STM32L4_DMA2_CHAN2, 7) +#define DMACHAN_TIM8_TRIG DMACHAN_SETTING(STM32L4_DMA2_CHAN2, 7) +#define DMACHAN_TIM8_UP DMACHAN_SETTING(STM32L4_DMA2_CHAN1, 7) + +#define DMACHAN_TIM15_CH1 DMACHAN_SETTING(STM32L4_DMA1_CHAN5, 7) +#define DMACHAN_TIM15_COM DMACHAN_SETTING(STM32L4_DMA1_CHAN5, 7) +#define DMACHAN_TIM15_TRIG DMACHAN_SETTING(STM32L4_DMA1_CHAN5, 7) +#define DMACHAN_TIM15_UP DMACHAN_SETTING(STM32L4_DMA1_CHAN5, 7) + +#define DMACHAN_TIM16_CH1_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN3, 4) +#define DMACHAN_TIM16_CH1_2 DMACHAN_SETTING(STM32L4_DMA1_CHAN6, 4) +#define DMACHAN_TIM16_UP_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN3, 4) +#define DMACHAN_TIM16_UP_2 DMACHAN_SETTING(STM32L4_DMA1_CHAN6, 4) + +#define DMACHAN_TIM17_CH1_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN1, 5) +#define DMACHAN_TIM17_CH1_2 DMACHAN_SETTING(STM32L4_DMA1_CHAN7, 5) +#define DMACHAN_TIM17_UP_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN1, 5) +#define DMACHAN_TIM17_UP_2 DMACHAN_SETTING(STM32L4_DMA1_CHAN7, 5) + +/* UART */ + +#define DMACHAN_USART1_RX_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN5, 2) +#define DMACHAN_USART1_RX_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN7, 2) +#define DMACHAN_USART1_TX_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN4, 2) +#define DMACHAN_USART1_TX_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN6, 2) + +#define DMACHAN_USART2_RX DMACHAN_SETTING(STM32L4_DMA1_CHAN6, 2) +#define DMACHAN_USART2_TX DMACHAN_SETTING(STM32L4_DMA1_CHAN7, 2) + +#define DMACHAN_USART3_RX DMACHAN_SETTING(STM32L4_DMA1_CHAN3, 2) +#define DMACHAN_USART3_TX DMACHAN_SETTING(STM32L4_DMA1_CHAN2, 2) + +#define DMACHAN_UART5_RX DMACHAN_SETTING(STM32L4_DMA2_CHAN2, 2) +#define DMACHAN_UART5_TX DMACHAN_SETTING(STM32L4_DMA2_CHAN1, 2) + +#define DMACHAN_UART4_RX DMACHAN_SETTING(STM32L4_DMA2_CHAN5, 2) +#define DMACHAN_UART4_TX DMACHAN_SETTING(STM32L4_DMA2_CHAN3, 2) + +#define DMACHAN_LPUART_RX DMACHAN_SETTING(STM32L4_DMA2_CHAN7, 4) +#define DMACHAN_LPUART_TX DMACHAN_SETTING(STM32L4_DMA2_CHAN6, 4) + +#endif /* __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X5XX_DMA_H */ diff --git a/arch/arm/src/stm32l4/chip/stm32l4x5xx_firewall.h b/arch/arm/src/stm32l4/chip/stm32l4x5xx_firewall.h new file mode 100644 index 0000000000..d2aeb9fd8f --- /dev/null +++ b/arch/arm/src/stm32l4/chip/stm32l4x5xx_firewall.h @@ -0,0 +1,112 @@ +/************************************************************************************ + * arch/arm/src/stm32l4/chip/stm32l4x5xx_firewall.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Copyright (C) 2016 Sebastien Lorquet. All rights reserved. + * Author: Sebastien Lorquet + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X5XX_FIREWALL_H +#define __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X5XX_FIREWALL_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include + +#include "chip.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Register Offsets *****************************************************************/ + +#define STM32L4_FIREWALL_CSSA_OFFSET 0x0000 +#define STM32L4_FIREWALL_CSL_OFFSET 0x0004 +#define STM32L4_FIREWALL_NVDSSA_OFFSET 0x0008 +#define STM32L4_FIREWALL_NVDSL_OFFSET 0x000C +#define STM32L4_FIREWALL_VDSSA_OFFSET 0x0010 +#define STM32L4_FIREWALL_VDSL_OFFSET 0x0014 +#define STM32L4_FIREWALL_CR_OFFSET 0x0020 + +/* Register Addresses ***************************************************************/ + +#define STM32L4_FIREWALL_CSSA (STM32L4_FIREWALL_BASE+STM32L4_FIREWALL_CSSA_OFFSET) +#define STM32L4_FIREWALL_CSL (STM32L4_FIREWALL_BASE+STM32L4_FIREWALL_CSL_OFFSET) +#define STM32L4_FIREWALL_NVDSSA (STM32L4_FIREWALL_BASE+STM32L4_FIREWALL_NVDSSA_OFFSET) +#define STM32L4_FIREWALL_NVDSL (STM32L4_FIREWALL_BASE+STM32L4_FIREWALL_NVDSL_OFFSET) +#define STM32L4_FIREWALL_VDSSA (STM32L4_FIREWALL_BASE+STM32L4_FIREWALL_VDSSA_OFFSET) +#define STM32L4_FIREWALL_VDSL (STM32L4_FIREWALL_BASE+STM32L4_FIREWALL_VDSL_OFFSET) +#define STM32L4_FIREWALL_CR (STM32L4_FIREWALL_BASE+STM32L4_FIREWALL_CR_OFFSET) + +/* Register Bitfield Definitions ****************************************************/ + +/* Code Segment Start Address */ + +#define FIREWALL_CSSADD_SHIFT 8 +#define FIREWALL_CSSADD_MASK (0xffff << FIREWALL_CSSADD_SHIFT) + +/* Code Segment Length */ + +#define FIREWALL_CSSLENG_SHIFT 8 +#define FIREWALL_CSSLENG_MASK (0x3fff << FIREWALL_CSSLENG_SHIFT) + +/* Non-volatile Data Segment Start Address */ + +#define FIREWALL_NVDSADD_SHIFT 8 +#define FIREWALL_NVDSADD_MASK (0xffff << FIREWALL_NVDSADD_SHIFT) + +/* Non-volatile Data Segment Length */ + +#define FIREWALL_NVDSLENG_SHIFT 8 +#define FIREWALL_NVDSLENG_MASK (0x3fff << FIREWALL_NVDSLENG_SHIFT) + +/* Volatile Data Segment Start Address */ + +#define FIREWALL_VDSADD_SHIFT 6 +#define FIREWALL_VDSADD_MASK (0x07ff << FIREWALL_VDSADD_SHIFT) + +/* Volatile Data Segment Length */ + +#define FIREWALL_VDSLENG_SHIFT 6 +#define FIREWALL_VDSLENG_MASK (0x07ff << FIREWALL_VDSLENG_SHIFT) + +/* Configuration Register */ + +#define FIREWALL_CR_FPA (1 << 0) /* Bit 0: Firewall prearm */ +#define FIREWALL_CR_VDS (1 << 1) /* Bit 1: Volatile data shared */ +#define FIREWALL_CR_VDE (1 << 2) /* Bit 2: Volatile data execution */ + +#endif /* __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X5XX_FIREWALL_H */ diff --git a/arch/arm/src/stm32l4/chip/stm32l4x6xx_firewall.h b/arch/arm/src/stm32l4/chip/stm32l4x6xx_firewall.h index 55826d73f7..8f1d837ceb 100644 --- a/arch/arm/src/stm32l4/chip/stm32l4x6xx_firewall.h +++ b/arch/arm/src/stm32l4/chip/stm32l4x6xx_firewall.h @@ -72,22 +72,27 @@ /* Register Bitfield Definitions ****************************************************/ /* Code Segment Start Address */ + #define FIREWALL_CSSADD_SHIFT 8 #define FIREWALL_CSSADD_MASK (0xFFFF << FIREWALL_CSSADD_SHIFT) /* Code Segment Length */ + #define FIREWALL_CSSLENG_SHIFT 8 #define FIREWALL_CSSLENG_MASK (0x3FFF << FIREWALL_CSSLENG_SHIFT) /* Non-volatile Data Segment Start Address */ + #define FIREWALL_NVDSADD_SHIFT 8 #define FIREWALL_NVDSADD_MASK (0xFFFF << FIREWALL_NVDSADD_SHIFT) /* Non-volatile Data Segment Length */ + #define FIREWALL_NVDSLENG_SHIFT 8 #define FIREWALL_NVDSLENG_MASK (0x3FFF << FIREWALL_NVDSLENG_SHIFT) /* Volatile Data Segment Start Address */ + #define FIREWALL_VDSADD_SHIFT 6 #if defined(CONFIG_STM32L4_STM32L496XX) #define FIREWALL_VDSADD_MASK (0x0FFF << FIREWALL_VDSADD_SHIFT) @@ -96,6 +101,7 @@ #endif /* Volatile Data Segment Length */ + #define FIREWALL_VDSLENG_SHIFT 6 #if defined(CONFIG_STM32L4_STM32L496XX) #define FIREWALL_VDSLENG_MASK (0x0FFF << FIREWALL_VDSLENG_SHIFT) @@ -104,6 +110,7 @@ #endif /* Configuration Register */ + #define FIREWALL_CR_FPA (1 << 0) /* Bit 0: Firewall prearm */ #define FIREWALL_CR_VDS (1 << 1) /* Bit 1: Volatile data shared */ #define FIREWALL_CR_VDE (1 << 2) /* Bit 2: Volatile data execution */ diff --git a/arch/arm/src/stm32l4/stm32l4_comp.c b/arch/arm/src/stm32l4/stm32l4_comp.c index 518e648639..f5f29fbd85 100644 --- a/arch/arm/src/stm32l4/stm32l4_comp.c +++ b/arch/arm/src/stm32l4/stm32l4_comp.c @@ -47,7 +47,8 @@ #include -#if !(defined(CONFIG_STM32L4_STM32L4X3) || defined(CONFIG_STM32L4_STM32L4X6)) +#if !(defined(CONFIG_STM32L4_STM32L4X3) || defined(CONFIG_STM32L4_STM32L4X5) || \ + defined(CONFIG_STM32L4_STM32L4X6)) # error "Unrecognized STM32 chip" #endif @@ -170,7 +171,7 @@ int stm32l4_compconfig(int cmp, const struct stm32l4_comp_config_s *cfg) case STM32L4_COMP_INM_PIN_2: stm32l4_configgpio(cmp == STM32L4_COMP1 ? GPIO_COMP1_INM_2 : GPIO_COMP2_INM_2); -#if defined(CONFIG_STM32L4_STM32L4X6) +#if defined(CONFIG_STM32L4_STM32L4X5) || defined(CONFIG_STM32L4_STM32L4X6) regval |= COMP_CSR_INMSEL_PIN2; #else regval |= COMP_CSR_INMSEL_INMESEL; diff --git a/arch/arm/src/stm32l4/stm32l4_comp.h b/arch/arm/src/stm32l4/stm32l4_comp.h index eecede715b..8262c6ef65 100644 --- a/arch/arm/src/stm32l4/stm32l4_comp.h +++ b/arch/arm/src/stm32l4/stm32l4_comp.h @@ -86,7 +86,7 @@ enum stm32l4_comp_inm_e STM32L4_COMP_INM_PIN_5 /* COMP1: PA5, COMP2: PA5 */ }; -#elif defined(CONFIG_STM32L4_STM32L4X6) +#elif defined(CONFIG_STM32L4_STM32L4X5) || defined(CONFIG_STM32L4_STM32L4X6) /* Comparators */ enum stm32l4_comp_e diff --git a/arch/arm/src/stm32l4/stm32l4_dbgmcu.h b/arch/arm/src/stm32l4/stm32l4_dbgmcu.h index ee753c0c0e..56ad7499a5 100644 --- a/arch/arm/src/stm32l4/stm32l4_dbgmcu.h +++ b/arch/arm/src/stm32l4/stm32l4_dbgmcu.h @@ -45,10 +45,12 @@ #include "chip.h" -#if defined(CONFIG_STM32L4_STM32L4X6) -# include "chip/stm32l4x6xx_dbgmcu.h" -#elif defined(CONFIG_STM32L4_STM32L4X3) +#if defined(CONFIG_STM32L4_STM32L4X3) # include "chip/stm32l4x3xx_dbgmcu.h" +#elif defined(CONFIG_STM32L4_STM32L4X5) +# include "chip/stm32l4x5xx_dbgmcu.h" +#elif defined(CONFIG_STM32L4_STM32L4X6) +# include "chip/stm32l4x6xx_dbgmcu.h" #else # error "Unsupported STM32L4 chip" #endif diff --git a/arch/arm/src/stm32l4/stm32l4_dma.c b/arch/arm/src/stm32l4/stm32l4_dma.c index fbde7e04e6..88c5637f41 100644 --- a/arch/arm/src/stm32l4/stm32l4_dma.c +++ b/arch/arm/src/stm32l4/stm32l4_dma.c @@ -49,7 +49,8 @@ * TODO: do we need separate implementation for STM32L4X3? */ -#if defined(CONFIG_STM32L4_STM32L4X6) || defined(CONFIG_STM32L4_STM32L4X3) +#if defined(CONFIG_STM32L4_STM32L4X3) || defined(CONFIG_STM32L4_STM32L4X5) || \ + defined(CONFIG_STM32L4_STM32L4X6) #include "stm32l4x6xx_dma.c" #else # error "Unsupported STM32L4 chip" diff --git a/arch/arm/src/stm32l4/stm32l4_dma.h b/arch/arm/src/stm32l4/stm32l4_dma.h index e21a6c1f66..5eb679be70 100644 --- a/arch/arm/src/stm32l4/stm32l4_dma.h +++ b/arch/arm/src/stm32l4/stm32l4_dma.h @@ -49,10 +49,12 @@ /* Include the correct DMA register definitions for this STM32 family */ -#if defined(CONFIG_STM32L4_STM32L4X6) -# include "chip/stm32l4x6xx_dma.h" -#elif defined(CONFIG_STM32L4_STM32L4X3) +#if defined(CONFIG_STM32L4_STM32L4X3) # include "chip/stm32l4x3xx_dma.h" +#elif defined(CONFIG_STM32L4_STM32L4X5) +# include "chip/stm32l4x5xx_dma.h" +#elif defined(CONFIG_STM32L4_STM32L4X6) +# include "chip/stm32l4x6xx_dma.h" #else # error "Unsupported STM32L4 chip" #endif diff --git a/arch/arm/src/stm32l4/stm32l4_exti_comp.c b/arch/arm/src/stm32l4/stm32l4_exti_comp.c index a1295b6970..aaab7ae0da 100644 --- a/arch/arm/src/stm32l4/stm32l4_exti_comp.c +++ b/arch/arm/src/stm32l4/stm32l4_exti_comp.c @@ -69,7 +69,8 @@ static struct comp_callback_s g_comp_handlers[STM32L4_COMP_NUM]; static const uint32_t g_comp_lines[STM32L4_COMP_NUM] = { -#if defined(CONFIG_STM32L4_STM32L4X3) || defined (CONFIG_STM32L4_STM32L4X6) +#if defined(CONFIG_STM32L4_STM32L4X3) || defined (CONFIG_STM32L4_STM32L4X5) || \ + defined(CONFIG_STM32L4_STM32L4X6) EXTI1_COMP1, EXTI1_COMP2 #else diff --git a/arch/arm/src/stm32l4/stm32l4_firewall.h b/arch/arm/src/stm32l4/stm32l4_firewall.h index 7b4a4dd0c4..6f201027e2 100644 --- a/arch/arm/src/stm32l4/stm32l4_firewall.h +++ b/arch/arm/src/stm32l4/stm32l4_firewall.h @@ -47,10 +47,12 @@ /* Include the correct firewall register definitions for this STM32L4 family */ -#if defined(CONFIG_STM32L4_STM32L4X6) -# include "chip/stm32l4x6xx_firewall.h" -#elif defined(CONFIG_STM32L4_STM32L4X3) +#if defined(CONFIG_STM32L4_STM32L4X3) # include "chip/stm32l4x3xx_firewall.h" +#elif defined(CONFIG_STM32L4_STM32L4X5) +# include "chip/stm32l4x5xx_firewall.h" +#elif defined(CONFIG_STM32L4_STM32L4X6) +# include "chip/stm32l4x6xx_firewall.h" #else # error "Unsupported STM32L4 chip" #endif diff --git a/arch/arm/src/stm32l4/stm32l4_flash.c b/arch/arm/src/stm32l4/stm32l4_flash.c index f81d48ffab..520f054c17 100644 --- a/arch/arm/src/stm32l4/stm32l4_flash.c +++ b/arch/arm/src/stm32l4/stm32l4_flash.c @@ -62,7 +62,8 @@ #include "up_arch.h" -#if !(defined(CONFIG_STM32L4_STM32L4X3) || defined(CONFIG_STM32L4_STM32L4X6)) +#if !(defined(CONFIG_STM32L4_STM32L4X3) || defined(CONFIG_STM32L4_STM32L4X5) || \ + defined(CONFIG_STM32L4_STM32L4X6)) # error "Unrecognized STM32 chip" #endif diff --git a/arch/arm/src/stm32l4/stm32l4_gpio.h b/arch/arm/src/stm32l4/stm32l4_gpio.h index e0fac1e273..3c7b615c4e 100644 --- a/arch/arm/src/stm32l4/stm32l4_gpio.h +++ b/arch/arm/src/stm32l4/stm32l4_gpio.h @@ -54,7 +54,8 @@ #include "chip.h" -#if defined(CONFIG_STM32L4_STM32L4X6) || defined(CONFIG_STM32L4_STM32L4X3) +#if defined(CONFIG_STM32L4_STM32L4X3) || defined(CONFIG_STM32L4_STM32L4X5) || \ + defined(CONFIG_STM32L4_STM32L4X6) # include "chip/stm32l4_gpio.h" #else # error "Unsupported STM32L4 chip" diff --git a/arch/arm/src/stm32l4/stm32l4_pm.h b/arch/arm/src/stm32l4/stm32l4_pm.h index 0bf7a827f3..40c06398c7 100644 --- a/arch/arm/src/stm32l4/stm32l4_pm.h +++ b/arch/arm/src/stm32l4/stm32l4_pm.h @@ -97,7 +97,8 @@ int stm32l4_pmstop(bool lpds); * ****************************************************************************/ -#if defined(CONFIG_STM32L4_STM32L4X6) || defined(CONFIG_STM32L4_STM32L4X3) +#if defined(CONFIG_STM32L4_STM32L4X3) || defined(CONFIG_STM32L4_STM32L4X5) || \ + defined(CONFIG_STM32L4_STM32L4X6) int stm32l4_pmstop2(void); #endif @@ -158,7 +159,8 @@ void stm32l4_pmsleep(bool sleeponexit); * ****************************************************************************/ -#if defined(CONFIG_STM32L4_STM32L4X6) || defined(CONFIG_STM32L4_STM32L4X3) +#if defined(CONFIG_STM32L4_STM32L4X3) || defined(CONFIG_STM32L4_STM32L4X5) || \ + defined(CONFIG_STM32L4_STM32L4X6) int stm32l4_pmlpr(void); #endif diff --git a/arch/arm/src/stm32l4/stm32l4_pmlpr.c b/arch/arm/src/stm32l4/stm32l4_pmlpr.c index 83a6782cf7..78237750be 100644 --- a/arch/arm/src/stm32l4/stm32l4_pmlpr.c +++ b/arch/arm/src/stm32l4/stm32l4_pmlpr.c @@ -48,7 +48,8 @@ #include "stm32l4_pm.h" #include "stm32l4_rcc.h" -#if defined(CONFIG_STM32L4_STM32L4X6) || defined(CONFIG_STM32L4_STM32L4X3) +#if defined(CONFIG_STM32L4_STM32L4X3) || defined(CONFIG_STM32L4_STM32L4X5) || \ + defined(CONFIG_STM32L4_STM32L4X6) /**************************************************************************** * Public Functions @@ -108,4 +109,4 @@ int stm32l4_pmlpr(void) return OK; } -#endif /* CONFIG_STM32L4_STM32L4X6 || CONFIG_STM32L4_STM32L4X3 */ +#endif /* CONFIG_STM32L4_STM32L4X3 || CONFIG_STM32L4_STM32L4X5 || CONFIG_STM32L4_STM32L4X6 */ diff --git a/arch/arm/src/stm32l4/stm32l4_pmstandby.c b/arch/arm/src/stm32l4/stm32l4_pmstandby.c index 99101ee528..bf068767a5 100644 --- a/arch/arm/src/stm32l4/stm32l4_pmstandby.c +++ b/arch/arm/src/stm32l4/stm32l4_pmstandby.c @@ -72,7 +72,8 @@ int stm32l4_pmstandby(void) { uint32_t regval; -#if defined(CONFIG_STM32L4_STM32L4X6) || defined(CONFIG_STM32L4_STM32L4X3) +#if defined(CONFIG_STM32L4_STM32L4X3) || defined(CONFIG_STM32L4_STM32L4X5) || \ + defined(CONFIG_STM32L4_STM32L4X6) /* Clear the Wake-Up Flags by setting the CWUFx bits in the power status * clear register */ diff --git a/arch/arm/src/stm32l4/stm32l4_pmstop.c b/arch/arm/src/stm32l4/stm32l4_pmstop.c index 9be563cf9e..df07a2b7f0 100644 --- a/arch/arm/src/stm32l4/stm32l4_pmstop.c +++ b/arch/arm/src/stm32l4/stm32l4_pmstop.c @@ -109,7 +109,8 @@ int stm32l4_pmstop(bool lpds) { uint32_t regval; -#if defined(CONFIG_STM32L4_STM32L4X6) || defined(CONFIG_STM32L4_STM32L4X3) +#if defined(CONFIG_STM32L4_STM32L4X3) || defined(CONFIG_STM32L4_STM32L4X5) || \ + defined(CONFIG_STM32L4_STM32L4X6) /* Clear Low-Power Mode Selection (LPMS) bits in power control register 1. */ regval = getreg32(STM32L4_PWR_CR1); regval &= ~PWR_CR1_LPMS_MASK; @@ -160,7 +161,8 @@ int stm32l4_pmstop(bool lpds) * ****************************************************************************/ -#if defined(CONFIG_STM32L4_STM32L4X6) || defined(CONFIG_STM32L4_STM32L4X3) +#if defined(CONFIG_STM32L4_STM32L4X3) || defined(CONFIG_STM32L4_STM32L4X5) || \ + defined(CONFIG_STM32L4_STM32L4X6) int stm32l4_pmstop2(void) { uint32_t regval; diff --git a/arch/arm/src/stm32l4/stm32l4_uart.h b/arch/arm/src/stm32l4/stm32l4_uart.h index 218e0c6b6f..c1f53957a5 100644 --- a/arch/arm/src/stm32l4/stm32l4_uart.h +++ b/arch/arm/src/stm32l4/stm32l4_uart.h @@ -45,7 +45,8 @@ #include "chip.h" -#if defined(CONFIG_STM32L4_STM32L4X6) || defined(CONFIG_STM32L4_STM32L4X3) +#if defined(CONFIG_STM32L4_STM32L4X3) || defined(CONFIG_STM32L4_STM32L4X5) || \ + defined(CONFIG_STM32L4_STM32L4X6) # include "chip/stm32l4_uart.h" #else # error "Unsupported STM32L4 chip" -- GitLab From 1a405d2881b28b42a8899d428341606ba5ab1998 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 8 Jun 2017 09:07:04 -0600 Subject: [PATCH 937/990] STM32L4: Add L475 syscfg register definitions. --- arch/arm/src/stm32l4/chip.h | 20 +- arch/arm/src/stm32l4/chip/stm32l4_syscfg.h | 8 +- .../arm/src/stm32l4/chip/stm32l4x5xx_syscfg.h | 177 ++++++++++++++++++ 3 files changed, 186 insertions(+), 19 deletions(-) create mode 100644 arch/arm/src/stm32l4/chip/stm32l4x5xx_syscfg.h diff --git a/arch/arm/src/stm32l4/chip.h b/arch/arm/src/stm32l4/chip.h index 99677fcfc7..861234894a 100644 --- a/arch/arm/src/stm32l4/chip.h +++ b/arch/arm/src/stm32l4/chip.h @@ -51,6 +51,10 @@ #include "chip/stm32l4_pinmap.h" #include "chip/stm32l4_memorymap.h" +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + /* If the common ARMv7-M vector handling logic is used, then it expects the * following definition in this file that provides the number of supported external * interrupts which, for this architecture, is provided in the arch/stm32l4/chip.h @@ -64,20 +68,4 @@ #define ARMV7M_DCACHE_LINESIZE 0 /* no cache */ #define ARMV7M_ICACHE_LINESIZE 0 /* no cache */ -/************************************************************************************ - * Pre-processor Definitions - ************************************************************************************/ - -/************************************************************************************ - * Public Types - ************************************************************************************/ - -/************************************************************************************ - * Public Data - ************************************************************************************/ - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - #endif /* __ARCH_ARM_SRC_STM32L4_CHIP_H */ diff --git a/arch/arm/src/stm32l4/chip/stm32l4_syscfg.h b/arch/arm/src/stm32l4/chip/stm32l4_syscfg.h index c68c992296..338d34bff1 100644 --- a/arch/arm/src/stm32l4/chip/stm32l4_syscfg.h +++ b/arch/arm/src/stm32l4/chip/stm32l4_syscfg.h @@ -43,10 +43,12 @@ #include #include "chip.h" -#if defined(CONFIG_STM32L4_STM32L4X6) -# include "chip/stm32l4x6xx_syscfg.h" -#elif defined(CONFIG_STM32L4_STM32L4X3) +#if defined(CONFIG_STM32L4_STM32L4X3) # include "chip/stm32l4x3xx_syscfg.h" +#elif defined(CONFIG_STM32L4_STM32L4X5) +# include "chip/stm32l4x5xx_syscfg.h" +#elif defined(CONFIG_STM32L4_STM32L4X6) +# include "chip/stm32l4x6xx_syscfg.h" #else # error "Unsupported STM32 L4 chip" #endif diff --git a/arch/arm/src/stm32l4/chip/stm32l4x5xx_syscfg.h b/arch/arm/src/stm32l4/chip/stm32l4x5xx_syscfg.h new file mode 100644 index 0000000000..2078261227 --- /dev/null +++ b/arch/arm/src/stm32l4/chip/stm32l4x5xx_syscfg.h @@ -0,0 +1,177 @@ +/**************************************************************************************************** + * arch/arm/src/stm32l4/chip/stm32l4x5xx_syscfg.h + * + * 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. + * + ****************************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X5XX_SYSCFG_H +#define __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X5XX_SYSCFG_H + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include "chip.h" + +#if defined(CONFIG_STM32L4_STM32L4X5) + +/**************************************************************************************************** + * Pre-processor Definitions + ****************************************************************************************************/ + +/* Register Offsets *********************************************************************************/ + +#define STM32L4_SYSCFG_MEMRMP_OFFSET 0x0000 /* SYSCFG memory remap register */ +#define STM32L4_SYSCFG_CFGR1_OFFSET 0x0004 /* SYSCFG configuration register 1 */ +#define STM32L4_SYSCFG_EXTICR_OFFSET(p) (0x0008 + ((p) & 0x000c)) /* Registers are displaced by 4! */ +#define STM32L4_SYSCFG_EXTICR1_OFFSET 0x0008 /* SYSCFG external interrupt configuration register 1 */ +#define STM32L4_SYSCFG_EXTICR2_OFFSET 0x000c /* SYSCFG external interrupt configuration register 2 */ +#define STM32L4_SYSCFG_EXTICR3_OFFSET 0x0010 /* SYSCFG external interrupt configuration register 3 */ +#define STM32L4_SYSCFG_EXTICR4_OFFSET 0x0014 /* SYSCFG external interrupt configuration register 4 */ +#define STM32L4_SYSCFG_SCSR_OFFSET 0x0018 /* SYSCFG SRAM2 control and status register */ +#define STM32L4_SYSCFG_CFGR2_OFFSET 0x001c /* SYSCFG configuration register 2 */ +#define STM32L4_SYSCFG_SWPR_OFFSET 0x0020 /* SYSCFG SRAM2 write protection register */ +#define STM32L4_SYSCFG_SKR_OFFSET 0x0024 /* SYSCFG SRAM2 key register */ + +/* Register Addresses *******************************************************************************/ + +#define STM32L4_SYSCFG_MEMRMP (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_MEMRMP_OFFSET) +#define STM32L4_SYSCFG_CFGR1 (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_CFGR1_OFFSET) +#define STM32L4_SYSCFG_EXTICR(p) (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_EXTICR_OFFSET(p)) +#define STM32L4_SYSCFG_EXTICR1 (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_EXTICR1_OFFSET) +#define STM32L4_SYSCFG_EXTICR2 (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_EXTICR2_OFFSET) +#define STM32L4_SYSCFG_EXTICR3 (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_EXTICR3_OFFSET) +#define STM32L4_SYSCFG_EXTICR4 (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_EXTICR4_OFFSET) +#define STM32L4_SYSCFG_SCSR (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_SCSR_OFFSET) +#define STM32L4_SYSCFG_CFGR2 (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_CFGR2_OFFSET) +#define STM32L4_SYSCFG_SWPR (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_SWPR_OFFSET) +#define STM32L4_SYSCFG_SKR (STM32L4_SYSCFG_BASE+STM32L4_SYSCFG_SKR_OFFSET) + +/* Register Bitfield Definitions ********************************************************************/ + +/* SYSCFG memory remap register */ + +#define SYSCFG_MEMRMP_SHIFT (0) /* Bits 2:0 MEM_MODE: Memory mapping selection */ +#define SYSCFG_MEMRMP_MASK (7 << SYSCFG_MEMRMP_SHIFT) +# define SYSCFG_MEMRMP_FLASH (0 << SYSCFG_MEMRMP_SHIFT) /* 000: Main Flash memory mapped at 0x0000 0000 */ +# define SYSCFG_MEMRMP_SYSTEM (1 << SYSCFG_MEMRMP_SHIFT) /* 001: System Flash memory mapped at 0x0000 0000 */ +# define SYSCFG_MEMRMP_FMC (2 << SYSCFG_MEMRMP_SHIFT) /* 010: FSMC Bank1 (NOR/PSRAM 1 and 2) mapped at 0x0000 0000 */ +# define SYSCFG_MEMRMP_SRAM (3 << SYSCFG_MEMRMP_SHIFT) /* 011: SRAM1 (112kB) mapped at 0x0000 0000 */ +# define SYSCFG_MEMRMP_QSPI (6 << SYSCFG_MEMRMP_SHIFT) /* 110: QUADSPI mapped at 0x0000 0000 */ +#define SYSCFG_FBMODE (1 << 8) /* Bit 8: Flash Bank mode selection */ + +/* SYSCFG configuration register 1 */ + +#define SYSCFG_CFGR1_FWDIS (1 << 0) /* Bit 0: Firewall disable */ +#define SYSCFG_CFGR1_BOOSTEN (1 << 8) /* Bit 8: I/O analog switch voltage booster enable (use when vdd is low) */ +#define SYSCFG_CFGR1_I2C_PB6_FMP (1 << 16) /* Bit 16: Fast-mode Plus (Fm+) driving capability activation on PB6 */ +#define SYSCFG_CFGR1_I2C_PB7_FMP (1 << 17) /* Bit 17: Fast-mode Plus (Fm+) driving capability activation on PB7 */ +#define SYSCFG_CFGR1_I2C_PB8_FMP (1 << 18) /* Bit 18: Fast-mode Plus (Fm+) driving capability activation on PB8 */ +#define SYSCFG_CFGR1_I2C_PB9_FMP (1 << 19) /* Bit 19: Fast-mode Plus (Fm+) driving capability activation on PB9 */ +#define SYSCFG_CFGR1_I2C1_FMP (1 << 20) /* Bit 20: I2C1 Fast-mode Plus (Fm+) driving capability activation */ +#define SYSCFG_CFGR1_I2C2_FMP (1 << 21) /* Bit 21: I2C2 Fast-mode Plus (Fm+) driving capability activation */ +#define SYSCFG_CFGR1_I2C3_FMP (1 << 22) /* Bit 22: I2C3 Fast-mode Plus (Fm+) driving capability activation */ +#define SYSCFG_CFGR1_FPU_IE0 (1 << 26) /* Bit 26: FPU Invalid operation interrupt enable */ +#define SYSCFG_CFGR1_FPU_IE1 (1 << 27) /* Bit 27: FPU Divide-by-zero interrupt enable */ +#define SYSCFG_CFGR1_FPU_IE2 (1 << 28) /* Bit 28: FPU Underflow interrupt enable */ +#define SYSCFG_CFGR1_FPU_IE3 (1 << 29) /* Bit 29: FPU Overflow interrupt enable */ +#define SYSCFG_CFGR1_FPU_IE4 (1 << 30) /* Bit 30: FPU Input denormal interrupt enable */ +#define SYSCFG_CFGR1_FPU_IE5 (1 << 31) /* Bit 31: FPU Inexact interrupt enable */ + +/* SYSCFG external interrupt configuration register 1-4 */ + +#define SYSCFG_EXTICR_PORTA (0) /* 0000: PA[x] pin */ +#define SYSCFG_EXTICR_PORTB (1) /* 0001: PB[x] pin */ +#define SYSCFG_EXTICR_PORTC (2) /* 0010: PC[x] pin */ +#define SYSCFG_EXTICR_PORTD (3) /* 0011: PD[x] pin */ +#define SYSCFG_EXTICR_PORTE (4) /* 0100: PE[x] pin */ +#define SYSCFG_EXTICR_PORTF (5) /* 0101: PF[C] pin */ +#define SYSCFG_EXTICR_PORTG (6) /* 0110: PG[x] pin */ +#define SYSCFG_EXTICR_PORTH (7) /* 0111: PH[x] pin (only on STM32L496xx/4A6xx) */ +#define SYSCFG_EXTICR_PORTI (8) /* 1000: PI[x] pin (only on STM32L496xx/4A6xx) */ + +#define SYSCFG_EXTICR_PORT_MASK (15) +#define SYSCFG_EXTICR_EXTI_SHIFT(g) (((g) & 3) << 2) +#define SYSCFG_EXTICR_EXTI_MASK(g) (SYSCFG_EXTICR_PORT_MASK << (SYSCFG_EXTICR_EXTI_SHIFT(g))) + +#define SYSCFG_EXTICR1_EXTI0_SHIFT (0) /* Bits 0-2: EXTI 0 configuration */ +#define SYSCFG_EXTICR1_EXTI0_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI0_SHIFT) +#define SYSCFG_EXTICR1_EXTI1_SHIFT (4) /* Bits 4-6: EXTI 1 configuration */ +#define SYSCFG_EXTICR1_EXTI1_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI1_SHIFT) +#define SYSCFG_EXTICR1_EXTI2_SHIFT (8) /* Bits 8-10: EXTI 2 configuration */ +#define SYSCFG_EXTICR1_EXTI2_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI2_SHIFT) +#define SYSCFG_EXTICR1_EXTI3_SHIFT (12) /* Bits 12-14: EXTI 3 configuration */ +#define SYSCFG_EXTICR1_EXTI3_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI3_SHIFT) + +#define SYSCFG_EXTICR2_EXTI4_SHIFT (0) /* Bits 0-2: EXTI 4 configuration */ +#define SYSCFG_EXTICR2_EXTI4_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI4_SHIFT) +#define SYSCFG_EXTICR2_EXTI5_SHIFT (4) /* Bits 4-6: EXTI 5 configuration */ +#define SYSCFG_EXTICR2_EXTI5_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI5_SHIFT) +#define SYSCFG_EXTICR2_EXTI6_SHIFT (8) /* Bits 8-10: EXTI 6 configuration */ +#define SYSCFG_EXTICR2_EXTI6_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI6_SHIFT) +#define SYSCFG_EXTICR2_EXTI7_SHIFT (12) /* Bits 12-14: EXTI 7 configuration */ +#define SYSCFG_EXTICR2_EXTI7_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI7_SHIFT) + +#define SYSCFG_EXTICR3_EXTI8_SHIFT (0) /* Bits 0-2: EXTI 8 configuration */ +#define SYSCFG_EXTICR3_EXTI8_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI8_SHIFT) +#define SYSCFG_EXTICR3_EXTI9_SHIFT (4) /* Bits 4-6: EXTI 9 configuration */ +#define SYSCFG_EXTICR3_EXTI9_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI9_SHIFT) +#define SYSCFG_EXTICR3_EXTI10_SHIFT (8) /* Bits 8-10: EXTI 10 configuration */ +#define SYSCFG_EXTICR3_EXTI10_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI10_SHIFT) +#define SYSCFG_EXTICR3_EXTI11_SHIFT (12) /* Bits 12-14: EXTI 11 configuration */ +#define SYSCFG_EXTICR3_EXTI11_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI11_SHIFT) + +#define SYSCFG_EXTICR4_EXTI12_SHIFT (0) /* Bits 0-2: EXTI 12 configuration */ +#define SYSCFG_EXTICR4_EXTI12_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI12_SHIFT) +#define SYSCFG_EXTICR4_EXTI13_SHIFT (4) /* Bits 4-6: EXTI 13 configuration */ +#define SYSCFG_EXTICR4_EXTI13_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI13_SHIFT) +#define SYSCFG_EXTICR4_EXTI14_SHIFT (8) /* Bits 8-10: EXTI 14 configuration */ +#define SYSCFG_EXTICR4_EXTI14_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI14_SHIFT) +#define SYSCFG_EXTICR4_EXTI15_SHIFT (12) /* Bits 12-14: EXTI 15 configuration */ +#define SYSCFG_EXTICR4_EXTI15_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI15_SHIFT) + +/* SYSCFG SRAM2 control and status register */ + +#define SYSCFG_SCSR_SRAM2ER (1 << 0) /* Bit 0: SRAM2 Erase */ +#define SYSCFG_SCSR_SRAM2BSY (1 << 1) /* Bit 1: SRAM2 busy in erase operation */ + +/* SYSCFG configuration register 2 */ + +#define SYSCFG_CFGR2_CLL (1 << 0) /* Bit 0: Cortex-M4 LOCKUP (Hardfault) output enable (TIMx break enable, see refman) */ +#define SYSCFG_CFGR2_SPL (1 << 1) /* Bit 1: SRAM2 parity lock enable (same) */ +#define SYSCFG_CFGR2_PVDL (1 << 2) /* Bit 2: PVD lock enable (same) */ +#define SYSCFG_CFGR2_ECCL (1 << 3) /* Bit 3: ECC lock enable (same) */ +#define SYSCFG_CFGR2_SPF (1 << 8) /* Bit 8: SRAM2 parity error flag */ + +#endif /* CONFIG_STM32L4_STM32L4X5 */ +#endif /* __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X5XX_SYSCFG_H */ -- GitLab From 95fcdff1fd92a129e3b00c42604df63132331eb4 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 8 Jun 2017 10:04:28 -0600 Subject: [PATCH 938/990] STM32L4: Add STM32L475 RCC definitions/logic. --- arch/arm/include/stm32l4/stm32l4x5xx_irq.h | 185 ++++ arch/arm/src/stm32l4/chip/stm32l4_syscfg.h | 1 - arch/arm/src/stm32l4/chip/stm32l4x3xx_rcc.h | 2 +- arch/arm/src/stm32l4/chip/stm32l4x5xx_rcc.h | 710 ++++++++++++++++ arch/arm/src/stm32l4/chip/stm32l4x6xx_rcc.h | 2 +- arch/arm/src/stm32l4/stm32l4_rcc.c | 8 +- arch/arm/src/stm32l4/stm32l4_rcc.h | 10 +- arch/arm/src/stm32l4/stm32l4x5xx_rcc.c | 893 ++++++++++++++++++++ arch/arm/src/stm32l4/stm32l4x6xx_rcc.c | 2 +- 9 files changed, 1802 insertions(+), 11 deletions(-) create mode 100644 arch/arm/include/stm32l4/stm32l4x5xx_irq.h create mode 100644 arch/arm/src/stm32l4/chip/stm32l4x5xx_rcc.h create mode 100644 arch/arm/src/stm32l4/stm32l4x5xx_rcc.c diff --git a/arch/arm/include/stm32l4/stm32l4x5xx_irq.h b/arch/arm/include/stm32l4/stm32l4x5xx_irq.h new file mode 100644 index 0000000000..62a135e140 --- /dev/null +++ b/arch/arm/include/stm32l4/stm32l4x5xx_irq.h @@ -0,0 +1,185 @@ +/**************************************************************************************************** + * arch/arm/include/stm32l4/stm32l4x5xx_irq.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Copyright (C) 2015 Sebastien Lorquet. All rights reserved. + * Author: Sebastien Lorquet + * 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. + * + ****************************************************************************************************/ + +/* This file should never be included directed but, rather, only indirectly through arch/irq.h */ + +#ifndef __ARCH_ARM_INCLUDE_STM32L4_STM32L4X5XX_IRQ_H +#define __ARCH_ARM_INCLUDE_STM32L4_STM32L4X5XX_IRQ_H + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include + +/**************************************************************************************************** + * Pre-processor Definitions + ****************************************************************************************************/ + +/* IRQ numbers. The IRQ number corresponds vector number and hence map directly to bits in the + * NVIC. This does, however, waste several words of memory in the IRQ to handle mapping tables. + * + * Processor Exceptions (vectors 0-15). These common definitions can be found in the file + * nuttx/arch/arm/include/stm32f7/irq.h which includes this file + * + * External interrupts (vectors >= 16) + */ + +#define STM32L4_IRQ_WWDG (STM32L4_IRQ_FIRST+0) /* 0: Window Watchdog interrupt */ +#define STM32L4_IRQ_PVD (STM32L4_IRQ_FIRST+1) /* 1: PVD through EXTI Line detection interrupt */ +#define STM32L4_IRQ_TAMPER (STM32L4_IRQ_FIRST+2) /* 2: Tamper and time stamp interrupts */ +#define STM32L4_IRQ_TIMESTAMP (STM32L4_IRQ_FIRST+2) /* 2: Tamper and time stamp interrupts */ +#define STM32L4_IRQ_RTC_WKUP (STM32L4_IRQ_FIRST+3) /* 3: RTC global interrupt */ +#define STM32L4_IRQ_FLASH (STM32L4_IRQ_FIRST+4) /* 4: Flash global interrupt */ +#define STM32L4_IRQ_RCC (STM32L4_IRQ_FIRST+5) /* 5: RCC global interrupt */ +#define STM32L4_IRQ_EXTI0 (STM32L4_IRQ_FIRST+6) /* 6: EXTI Line 0 interrupt */ +#define STM32L4_IRQ_EXTI1 (STM32L4_IRQ_FIRST+7) /* 7: EXTI Line 1 interrupt */ +#define STM32L4_IRQ_EXTI2 (STM32L4_IRQ_FIRST+8) /* 8: EXTI Line 2 interrupt */ +#define STM32L4_IRQ_EXTI3 (STM32L4_IRQ_FIRST+9) /* 9: EXTI Line 3 interrupt */ +#define STM32L4_IRQ_EXTI4 (STM32L4_IRQ_FIRST+10) /* 10: EXTI Line 4 interrupt */ +#define STM32L4_IRQ_DMA1CH1 (STM32L4_IRQ_FIRST+11) /* 11: DMA1 Channel 1 global interrupt */ +#define STM32L4_IRQ_DMA1CH2 (STM32L4_IRQ_FIRST+12) /* 12: DMA1 Channel 2 global interrupt */ +#define STM32L4_IRQ_DMA1CH3 (STM32L4_IRQ_FIRST+13) /* 13: DMA1 Channel 3 global interrupt */ +#define STM32L4_IRQ_DMA1CH4 (STM32L4_IRQ_FIRST+14) /* 14: DMA1 Channel 4 global interrupt */ +#define STM32L4_IRQ_DMA1CH5 (STM32L4_IRQ_FIRST+15) /* 15: DMA1 Channel 5 global interrupt */ +#define STM32L4_IRQ_DMA1CH6 (STM32L4_IRQ_FIRST+16) /* 16: DMA1 Channel 6 global interrupt */ +#define STM32L4_IRQ_DMA1CH7 (STM32L4_IRQ_FIRST+17) /* 17: DMA1 Channel 7 global interrupt */ +#define STM32L4_IRQ_ADC12 (STM32L4_IRQ_FIRST+18) /* 18: ADC1 and ADC2 global interrupt */ +#define STM32L4_IRQ_CAN1TX (STM32L4_IRQ_FIRST+19) /* 19: CAN1 TX interrupts */ +#define STM32L4_IRQ_CAN1RX0 (STM32L4_IRQ_FIRST+20) /* 20: CAN1 RX0 interrupts */ +#define STM32L4_IRQ_CAN1RX1 (STM32L4_IRQ_FIRST+21) /* 21: CAN1 RX1 interrupt */ +#define STM32L4_IRQ_CAN1SCE (STM32L4_IRQ_FIRST+22) /* 22: CAN1 SCE interrupt */ +#define STM32L4_IRQ_EXTI95 (STM32L4_IRQ_FIRST+23) /* 23: EXTI Line[9:5] interrupts */ +#define STM32L4_IRQ_TIM1BRK (STM32L4_IRQ_FIRST+24) /* 24: TIM1 Break interrupt */ +#define STM32L4_IRQ_TIM15 (STM32L4_IRQ_FIRST+24) /* 24: TIM15 global interrupt */ +#define STM32L4_IRQ_TIM1UP (STM32L4_IRQ_FIRST+25) /* 25: TIM1 Update interrupt */ +#define STM32L4_IRQ_TIM16 (STM32L4_IRQ_FIRST+25) /* 25: TIM16 global interrupt */ +#define STM32L4_IRQ_TIM1TRGCOM (STM32L4_IRQ_FIRST+26) /* 26: TIM1 Trigger and Commutation interrupts */ +#define STM32L4_IRQ_TIM17 (STM32L4_IRQ_FIRST+26) /* 26: TIM17 global interrupt */ +#define STM32L4_IRQ_TIM1CC (STM32L4_IRQ_FIRST+27) /* 27: TIM1 Capture Compare interrupt */ +#define STM32L4_IRQ_TIM2 (STM32L4_IRQ_FIRST+28) /* 28: TIM2 global interrupt */ +#define STM32L4_IRQ_TIM3 (STM32L4_IRQ_FIRST+29) /* 29: TIM3 global interrupt */ +#define STM32L4_IRQ_TIM4 (STM32L4_IRQ_FIRST+30) /* 30: TIM4 global interrupt */ +#define STM32L4_IRQ_I2C1EV (STM32L4_IRQ_FIRST+31) /* 31: I2C1 event interrupt */ +#define STM32L4_IRQ_I2C1ER (STM32L4_IRQ_FIRST+32) /* 32: I2C1 error interrupt */ +#define STM32L4_IRQ_I2C2EV (STM32L4_IRQ_FIRST+33) /* 33: I2C2 event interrupt */ +#define STM32L4_IRQ_I2C2ER (STM32L4_IRQ_FIRST+34) /* 34: I2C2 error interrupt */ +#define STM32L4_IRQ_SPI1 (STM32L4_IRQ_FIRST+35) /* 35: SPI1 global interrupt */ +#define STM32L4_IRQ_SPI2 (STM32L4_IRQ_FIRST+36) /* 36: SPI2 global interrupt */ +#define STM32L4_IRQ_USART1 (STM32L4_IRQ_FIRST+37) /* 37: USART1 global interrupt */ +#define STM32L4_IRQ_USART2 (STM32L4_IRQ_FIRST+38) /* 38: USART2 global interrupt */ +#define STM32L4_IRQ_USART3 (STM32L4_IRQ_FIRST+39) /* 39: USART3 global interrupt */ +#define STM32L4_IRQ_EXTI1510 (STM32L4_IRQ_FIRST+40) /* 40: EXTI Line[15:10] interrupts */ +#define STM32L4_IRQ_RTCALRM (STM32L4_IRQ_FIRST+41) /* 41: RTC alarm through EXTI line interrupt */ +#define STM32L4_IRQ_DFSDM3 (STM32L4_IRQ_FIRST+42) /* 42: Digital Filter / Sigma Delta Modulator interrupt */ +#define STM32L4_IRQ_TIM8BRK (STM32L4_IRQ_FIRST+43) /* 43: TIM8 Break interrupt */ +#define STM32L4_IRQ_TIM8UP (STM32L4_IRQ_FIRST+44) /* 44: TIM8 Update interrupt */ +#define STM32L4_IRQ_TIM8TRGCOM (STM32L4_IRQ_FIRST+45) /* 45: TIM8 Trigger and Commutation interrupts */ +#define STM32L4_IRQ_TIM8CC (STM32L4_IRQ_FIRST+46) /* 46: TIM8 Capture Compare interrupt */ +#define STM32L4_IRQ_ADC3 (STM32L4_IRQ_FIRST+47) /* 47: ADC3 global interrupt */ +#define STM32L4_IRQ_FSMC (STM32L4_IRQ_FIRST+48) /* 48: FSMC global interrupt */ +#define STM32L4_IRQ_SDMMC1 (STM32L4_IRQ_FIRST+49) /* 49: SDMMC1 global interrupt */ +#define STM32L4_IRQ_TIM5 (STM32L4_IRQ_FIRST+50) /* 50: TIM5 global interrupt */ +#define STM32L4_IRQ_SPI3 (STM32L4_IRQ_FIRST+51) /* 51: SPI3 global interrupt */ +#define STM32L4_IRQ_UART4 (STM32L4_IRQ_FIRST+52) /* 52: UART4 global interrupt */ +#define STM32L4_IRQ_UART5 (STM32L4_IRQ_FIRST+53) /* 53: UART5 global interrupt */ +#define STM32L4_IRQ_TIM6 (STM32L4_IRQ_FIRST+54) /* 54: TIM6 global interrupt */ +#define STM32L4_IRQ_DAC (STM32L4_IRQ_FIRST+54) /* 54: DAC1 and DAC2 underrun error interrupts */ +#define STM32L4_IRQ_TIM7 (STM32L4_IRQ_FIRST+55) /* 55: TIM7 global interrupt */ +#define STM32L4_IRQ_DMA2CH1 (STM32L4_IRQ_FIRST+56) /* 56: DMA2 Channel 1 global interrupt */ +#define STM32L4_IRQ_DMA2CH2 (STM32L4_IRQ_FIRST+57) /* 57: DMA2 Channel 2 global interrupt */ +#define STM32L4_IRQ_DMA2CH3 (STM32L4_IRQ_FIRST+58) /* 58: DMA2 Channel 3 global interrupt */ +#define STM32L4_IRQ_DMA2CH4 (STM32L4_IRQ_FIRST+59) /* 59: DMA2 Channel 4 global interrupt */ +#define STM32L4_IRQ_DMA2CH5 (STM32L4_IRQ_FIRST+60) /* 60: DMA2 Channel 5 global interrupt */ +#define STM32L4_IRQ_DFSDM0 (STM32L4_IRQ_FIRST+61) /* 61: DFSDM0 global interrupt */ +#define STM32L4_IRQ_DFSDM1 (STM32L4_IRQ_FIRST+62) /* 62: DFSDM1 global interrupt*/ +#define STM32L4_IRQ_DFSDM2 (STM32L4_IRQ_FIRST+63) /* 63: DFSDM2 global interrupt */ +#define STM32L4_IRQ_COMP (STM32L4_IRQ_FIRST+64) /* 64: COMP1/COMP2 interrupts */ +#define STM32L4_IRQ_LPTIM1 (STM32L4_IRQ_FIRST+65) /* 65: LPTIM1 global interrupt */ +#define STM32L4_IRQ_LPTIM2 (STM32L4_IRQ_FIRST+66) /* 66: LPTIM2 global interrupt */ +#define STM32L4_IRQ_OTGFS (STM32L4_IRQ_FIRST+67) /* 67: USB On The Go FS global interrupt */ +#define STM32L4_IRQ_DMA2CH6 (STM32L4_IRQ_FIRST+68) /* 68: DMA2 Channel 6 global interrupt */ +#define STM32L4_IRQ_DMA2CH7 (STM32L4_IRQ_FIRST+69) /* 69: DMA2 Channel 7 global interrupt */ +#define STM32L4_IRQ_LPUART1 (STM32L4_IRQ_FIRST+70) /* 70: Low power UART 1 global interrupt */ +#define STM32L4_IRQ_QUADSPI (STM32L4_IRQ_FIRST+71) /* 71: QUADSPI global interrupt */ +#define STM32L4_IRQ_I2C3EV (STM32L4_IRQ_FIRST+72) /* 72: I2C3 event interrupt */ +#define STM32L4_IRQ_I2C3ER (STM32L4_IRQ_FIRST+73) /* 73: I2C3 error interrupt */ +#define STM32L4_IRQ_SAI1 (STM32L4_IRQ_FIRST+74) /* 74: SAI1 global interrupt */ +#define STM32L4_IRQ_SAI2 (STM32L4_IRQ_FIRST+75) /* 75: SAI2 global interrupt */ +#define STM32L4_IRQ_SWPMI1 (STM32L4_IRQ_FIRST+76) /* 76: SWPMI1 global interrupt */ +#define STM32L4_IRQ_TSC (STM32L4_IRQ_FIRST+77) /* 77: TSC global interrupt */ +#define STM32_IRQ_RESERVED78 (STM32L4_IRQ_FIRST+78) /* 78: Reserved */ +#define STM32_IRQ_RESERVED79 (STM32L4_IRQ_FIRST+79) /* 79: Reserved */ +#define STM32L4_IRQ_RNG (STM32L4_IRQ_FIRST+80) /* 80: RNG global interrupt */ +#define STM32L4_IRQ_FPU (STM32L4_IRQ_FIRST+81) /* 81: FPU global interrupt */ + +#define NR_INTERRUPTS 82 +#define NR_VECTORS (STM32L4_IRQ_FIRST+NR_INTERRUPTS) + +/* EXTI interrupts (Do not use IRQ numbers) */ + +#define NR_IRQS NR_VECTORS + +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + +/**************************************************************************************************** + * Public Data + ****************************************************************************************************/ + +#ifndef __ASSEMBLY__ +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/**************************************************************************************************** + * Public Functions + ****************************************************************************************************/ + +#undef EXTERN +#ifdef __cplusplus +} +#endif +#endif + +#endif /* __ARCH_ARM_INCLUDE_STM32L4_STM32L4X5XX_IRQ_H */ diff --git a/arch/arm/src/stm32l4/chip/stm32l4_syscfg.h b/arch/arm/src/stm32l4/chip/stm32l4_syscfg.h index 338d34bff1..ba02c5c80f 100644 --- a/arch/arm/src/stm32l4/chip/stm32l4_syscfg.h +++ b/arch/arm/src/stm32l4/chip/stm32l4_syscfg.h @@ -54,4 +54,3 @@ #endif #endif /* __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4_SYSCFG_H */ - diff --git a/arch/arm/src/stm32l4/chip/stm32l4x3xx_rcc.h b/arch/arm/src/stm32l4/chip/stm32l4x3xx_rcc.h index 7aa7edfd6c..f05fec85cc 100644 --- a/arch/arm/src/stm32l4/chip/stm32l4x3xx_rcc.h +++ b/arch/arm/src/stm32l4/chip/stm32l4x3xx_rcc.h @@ -126,7 +126,7 @@ #define RCC_CR_MSION (1 << 0) /* Bit 0: Internal Multi Speed clock enable */ #define RCC_CR_MSIRDY (1 << 1) /* Bit 1: Internal Multi Speed clock ready flag */ #define RCC_CR_MSIPLLEN (1 << 2) /* Bit 2: MSI clock PLL enable */ -#define RCC_CR_MSIRGSEL (1 << 3) /* Bit 2: MSI clock range selection */ +#define RCC_CR_MSIRGSEL (1 << 3) /* Bit 3: MSI clock range selection */ #define RCC_CR_MSIRANGE_SHIFT (4) /* Bits 7-4: MSI clock range */ #define RCC_CR_MSIRANGE_MASK (0x0f << RCC_CR_MSIRANGE_SHIFT) # define RCC_CR_MSIRANGE_100K (0 << RCC_CR_MSIRANGE_SHIFT) /* 0000: around 100 kHz */ diff --git a/arch/arm/src/stm32l4/chip/stm32l4x5xx_rcc.h b/arch/arm/src/stm32l4/chip/stm32l4x5xx_rcc.h new file mode 100644 index 0000000000..8177609e26 --- /dev/null +++ b/arch/arm/src/stm32l4/chip/stm32l4x5xx_rcc.h @@ -0,0 +1,710 @@ +/**************************************************************************************************** + * arch/arm/src/stm32l4/chip/stm32l4x6xx_rcc.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Copyright (C) 2016 Sebastien Lorquet. All rights reserved. + * Author: Gregory Nutt + * Sebastien Lorquet + * + * 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 __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X5XX_RCC_H +#define __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X5XX_RCC_H + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include + +#if defined(CONFIG_STM32L4_STM32L4X5) + +/**************************************************************************************************** + * Pre-processor Definitions + ****************************************************************************************************/ + +/* Register Offsets *********************************************************************************/ + +#define STM32L4_RCC_CR_OFFSET 0x0000 /* Clock control register */ +#define STM32L4_RCC_ICSCR_OFFSET 0x0004 /* Internal clock sources calibration register */ +#define STM32L4_RCC_CFGR_OFFSET 0x0008 /* Clock configuration register */ +#define STM32L4_RCC_PLLCFG_OFFSET 0x000c /* PLL configuration register */ +#define STM32L4_RCC_PLLSAI1CFG_OFFSET 0x0010 /* PLLSAI1 configuration register */ +#define STM32L4_RCC_PLLSAI2CFG_OFFSET 0x0014 /* PLLSAI2 configuration register */ +#define STM32L4_RCC_CIER_OFFSET 0x0018 /* Clock interrupt enable register */ +#define STM32L4_RCC_CIFR_OFFSET 0x001c /* Clock interrupt flag register */ +#define STM32L4_RCC_CICR_OFFSET 0x0020 /* Clock interrupt clear register */ +#define STM32L4_RCC_AHB1RSTR_OFFSET 0x0028 /* AHB1 peripheral reset register */ +#define STM32L4_RCC_AHB2RSTR_OFFSET 0x002c /* AHB2 peripheral reset register */ +#define STM32L4_RCC_AHB3RSTR_OFFSET 0x0030 /* AHB3 peripheral reset register */ +#define STM32L4_RCC_APB1RSTR1_OFFSET 0x0038 /* APB1 Peripheral reset register 1 */ +#define STM32L4_RCC_APB1RSTR2_OFFSET 0x003c /* APB1 Peripheral reset register 2 */ +#define STM32L4_RCC_APB2RSTR_OFFSET 0x0040 /* APB2 Peripheral reset register */ +#define STM32L4_RCC_AHB1ENR_OFFSET 0x0048 /* AHB1 Peripheral Clock enable register */ +#define STM32L4_RCC_AHB2ENR_OFFSET 0x004c /* AHB2 Peripheral Clock enable register */ +#define STM32L4_RCC_AHB3ENR_OFFSET 0x0050 /* AHB3 Peripheral Clock enable register */ +#define STM32L4_RCC_APB1ENR1_OFFSET 0x0058 /* APB1 Peripheral Clock enable register 1 */ +#define STM32L4_RCC_APB1ENR2_OFFSET 0x005c /* APB1 Peripheral Clock enable register 2 */ +#define STM32L4_RCC_APB2ENR_OFFSET 0x0060 /* APB2 Peripheral Clock enable register */ +#define STM32L4_RCC_AHB1SMENR_OFFSET 0x0068 /* RCC AHB1 low power mode peripheral clock enable register */ +#define STM32L4_RCC_AHB2SMENR_OFFSET 0x006c /* RCC AHB2 low power mode peripheral clock enable register */ +#define STM32L4_RCC_AHB3SMENR_OFFSET 0x0070 /* RCC AHB3 low power mode peripheral clock enable register */ +#define STM32L4_RCC_APB1SMENR1_OFFSET 0x0078 /* RCC APB1 low power mode peripheral clock enable register 1 */ +#define STM32L4_RCC_APB1SMENR2_OFFSET 0x007c /* RCC APB1 low power mode peripheral clock enable register 2 */ +#define STM32L4_RCC_APB2SMENR_OFFSET 0x0080 /* RCC APB2 low power mode peripheral clock enable register */ +#define STM32L4_RCC_CCIPR_OFFSET 0x0088 /* Peripherals independent clock configuration register 1 */ +#define STM32L4_RCC_BDCR_OFFSET 0x0090 /* Backup domain control register */ +#define STM32L4_RCC_CSR_OFFSET 0x0094 /* Control/status register */ + +/* Register Addresses *******************************************************************************/ + +#define STM32L4_RCC_CR (STM32L4_RCC_BASE+STM32L4_RCC_CR_OFFSET) +#define STM32L4_RCC_ICSCR (STM32L4_RCC_BASE+STM32L4_RCC_ICSCR_OFFSET) +#define STM32L4_RCC_CFGR (STM32L4_RCC_BASE+STM32L4_RCC_CFGR_OFFSET) +#define STM32L4_RCC_PLLCFG (STM32L4_RCC_BASE+STM32L4_RCC_PLLCFG_OFFSET) +#define STM32L4_RCC_PLLSAI1CFG (STM32L4_RCC_BASE+STM32L4_RCC_PLLSAI1CFG_OFFSET) +#define STM32L4_RCC_PLLSAI2CFG (STM32L4_RCC_BASE+STM32L4_RCC_PLLSAI2CFG_OFFSET) +#define STM32L4_RCC_CIER (STM32L4_RCC_BASE+STM32L4_RCC_CIER_OFFSET) +#define STM32L4_RCC_CIFR (STM32L4_RCC_BASE+STM32L4_RCC_CIFR_OFFSET) +#define STM32L4_RCC_CICR (STM32L4_RCC_BASE+STM32L4_RCC_CICR_OFFSET) +#define STM32L4_RCC_AHB1RSTR (STM32L4_RCC_BASE+STM32L4_RCC_AHB1RSTR_OFFSET) +#define STM32L4_RCC_AHB2RSTR (STM32L4_RCC_BASE+STM32L4_RCC_AHB2RSTR_OFFSET) +#define STM32L4_RCC_AHB3RSTR (STM32L4_RCC_BASE+STM32L4_RCC_AHB3RSTR_OFFSET) +#define STM32L4_RCC_APB1RSTR1 (STM32L4_RCC_BASE+STM32L4_RCC_APB1RSTR1_OFFSET) +#define STM32L4_RCC_APB1RSTR2 (STM32L4_RCC_BASE+STM32L4_RCC_APB1RSTR2_OFFSET) +#define STM32L4_RCC_APB2RSTR (STM32L4_RCC_BASE+STM32L4_RCC_APB2RSTR_OFFSET) +#define STM32L4_RCC_AHB1ENR (STM32L4_RCC_BASE+STM32L4_RCC_AHB1ENR_OFFSET) +#define STM32L4_RCC_AHB2ENR (STM32L4_RCC_BASE+STM32L4_RCC_AHB2ENR_OFFSET) +#define STM32L4_RCC_AHB3ENR (STM32L4_RCC_BASE+STM32L4_RCC_AHB3ENR_OFFSET) +#define STM32L4_RCC_APB1ENR1 (STM32L4_RCC_BASE+STM32L4_RCC_APB1ENR1_OFFSET) +#define STM32L4_RCC_APB1ENR2 (STM32L4_RCC_BASE+STM32L4_RCC_APB1ENR2_OFFSET) +#define STM32L4_RCC_APB2ENR (STM32L4_RCC_BASE+STM32L4_RCC_APB2ENR_OFFSET) +#define STM32L4_RCC_AHB1SMENR (STM32L4_RCC_BASE+STM32L4_RCC_AHB1SMENR_OFFSET) +#define STM32L4_RCC_AHB2SMENR (STM32L4_RCC_BASE+STM32L4_RCC_AHB2SMENR) +#define STM32L4_RCC_AHB3SMENR (STM32L4_RCC_BASE+STM32L4_RCC_AHB3SMENR_OFFSET) +#define STM32L4_RCC_APB1SMENR1 (STM32L4_RCC_BASE+STM32L4_RCC_APB1SMENR1_OFFSET) +#define STM32L4_RCC_APB1SMENR2 (STM32L4_RCC_BASE+STM32L4_RCC_APB1SMENR2_OFFSET) +#define STM32L4_RCC_APB2SMENR (STM32L4_RCC_BASE+STM32L4_RCC_APB2SMENR_OFFSET) +#define STM32L4_RCC_CCIPR (STM32L4_RCC_BASE+STM32L4_RCC_CCIPR_OFFSET) +#define STM32L4_RCC_BDCR (STM32L4_RCC_BASE+STM32L4_RCC_BDCR_OFFSET) +#define STM32L4_RCC_CSR (STM32L4_RCC_BASE+STM32L4_RCC_CSR_OFFSET) + +/* Register Bitfield Definitions ********************************************************************/ + +/* Clock control register */ + +#define RCC_CR_MSION (1 << 0) /* Bit 0: Internal Multi Speed clock enable */ +#define RCC_CR_MSIRDY (1 << 1) /* Bit 1: Internal Multi Speed clock ready flag */ +#define RCC_CR_MSIPLLEN (1 << 2) /* Bit 2: MSI clock PLL enable */ +#define RCC_CR_MSIRGSEL (1 << 3) /* Bit 3: MSI clock range selection */ +#define RCC_CR_MSIRANGE_SHIFT (4) /* Bits 7-4: MSI clock range */ +#define RCC_CR_MSIRANGE_MASK (0x0f << RCC_CR_MSIRANGE_SHIFT) +# define RCC_CR_MSIRANGE_100K (0 << RCC_CR_MSIRANGE_SHIFT) /* 0000: around 100 kHz */ +# define RCC_CR_MSIRANGE_200K (1 << RCC_CR_MSIRANGE_SHIFT) /* 0001: around 200 kHz */ +# define RCC_CR_MSIRANGE_400K (2 << RCC_CR_MSIRANGE_SHIFT) /* 0010: around 400 kHz */ +# define RCC_CR_MSIRANGE_800K (3 << RCC_CR_MSIRANGE_SHIFT) /* 0011: around 800 kHz */ +# define RCC_CR_MSIRANGE_1M (4 << RCC_CR_MSIRANGE_SHIFT) /* 0100: around 1 MHz */ +# define RCC_CR_MSIRANGE_2M (5 << RCC_CR_MSIRANGE_SHIFT) /* 0101: around 2 MHz */ +# define RCC_CR_MSIRANGE_4M (6 << RCC_CR_MSIRANGE_SHIFT) /* 0110: around 4 MHz */ +# define RCC_CR_MSIRANGE_8M (7 << RCC_CR_MSIRANGE_SHIFT) /* 0111: around 8 MHz */ +# define RCC_CR_MSIRANGE_16M (8 << RCC_CR_MSIRANGE_SHIFT) /* 1000: around 16 MHz */ +# define RCC_CR_MSIRANGE_24M (9 << RCC_CR_MSIRANGE_SHIFT) /* 1001: around 24 MHz */ +# define RCC_CR_MSIRANGE_32M (10 << RCC_CR_MSIRANGE_SHIFT) /* 1010: around 32 MHz */ +# define RCC_CR_MSIRANGE_48M (11 << RCC_CR_MSIRANGE_SHIFT) /* 1011: around 48 MHz */ +#define RCC_CR_HSION (1 << 8) /* Bit 8: Internal High Speed clock enable */ +#define RCC_CR_HSIKERON (1 << 9) /* Bit 9: HSI16 always enable for peripheral kernels */ +#define RCC_CR_HSIRDY (1 << 10) /* Bit 10: Internal High Speed clock ready flag */ +#define RCC_CR_HSIASFS (1 << 11) /* Bit 11: HSI automatic start from stop */ +#define RCC_CR_HSEON (1 << 16) /* Bit 16: External High Speed clock enable */ +#define RCC_CR_HSERDY (1 << 17) /* Bit 17: External High Speed clock ready flag */ +#define RCC_CR_HSEBYP (1 << 18) /* Bit 18: External High Speed clock Bypass */ +#define RCC_CR_CSSON (1 << 19) /* Bit 19: Clock Security System enable */ +#define RCC_CR_PLLON (1 << 24) /* Bit 24: PLL enable */ +#define RCC_CR_PLLRDY (1 << 25) /* Bit 25: PLL clock ready flag */ +#define RCC_CR_PLLSAI1ON (1 << 26) /* Bit 26: PLLSAI1 enable */ +#define RCC_CR_PLLSAI1RDY (1 << 27) /* Bit 27: PLLSAI1 clock ready flag */ +#define RCC_CR_PLLSAI2ON (1 << 28) /* Bit 28: PLLSAI2 enable */ +#define RCC_CR_PLLSAI2RDY (1 << 29) /* Bit 29: PLLSAI2 clock ready flag */ + +/* Internal Clock Sources Calibration */ + +#define RCC_CR_MSICAL_SHIFT (0) /* Bits 7-0: Internal Multi Speed clock Calibration */ +#define RCC_CR_MSICAL_MASK (0xff << RCC_CR_MSICAL_SHIFT) +#define RCC_CR_MSITRIM_SHIFT (8) /* Bits 15-8: Internal Multi Speed clock trimming */ +#define RCC_CR_MSITRIM_MASK (0xff << RCC_CR_MSITRIM_SHIFT) +#define RCC_CR_HSICAL_SHIFT (16) /* Bits 23-16: Internal High Speed clock Calibration */ +#define RCC_CR_HSICAL_MASK (0xff << RCC_CR_HSICAL_SHIFT) +#define RCC_CR_HSITRIM_SHIFT (24) /* Bits 28-24: Internal High Speed clock trimming */ +#define RCC_CR_HSITRIM_MASK (0x1f << RCC_CR_HSITRIM_SHIFT) + +/* Clock configuration register */ + +#define RCC_CFGR_SW_SHIFT (0) /* Bits 0-1: System clock Switch */ +#define RCC_CFGR_SW_MASK (3 << RCC_CFGR_SW_SHIFT) +# define RCC_CFGR_SW_MSI (0 << RCC_CFGR_SW_SHIFT) /* 00: HSI selected as system clock */ +# define RCC_CFGR_SW_HSI (1 << RCC_CFGR_SW_SHIFT) /* 00: HSI selected as system clock */ +# define RCC_CFGR_SW_HSE (2 << RCC_CFGR_SW_SHIFT) /* 01: HSE selected as system clock */ +# define RCC_CFGR_SW_PLL (3 << RCC_CFGR_SW_SHIFT) /* 10: PLL selected as system clock */ +#define RCC_CFGR_SWS_SHIFT (2) /* Bits 2-3: System Clock Switch Status */ +#define RCC_CFGR_SWS_MASK (3 << RCC_CFGR_SWS_SHIFT) +# define RCC_CFGR_SWS_MSI (0 << RCC_CFGR_SWS_SHIFT) /* 00: HSI oscillator used as system clock */ +# define RCC_CFGR_SWS_HSI (1 << RCC_CFGR_SWS_SHIFT) /* 00: HSI oscillator used as system clock */ +# define RCC_CFGR_SWS_HSE (2 << RCC_CFGR_SWS_SHIFT) /* 01: HSE oscillator used as system clock */ +# define RCC_CFGR_SWS_PLL (3 << RCC_CFGR_SWS_SHIFT) /* 10: PLL used as system clock */ +#define RCC_CFGR_HPRE_SHIFT (4) /* Bits 4-7: AHB prescaler */ +#define RCC_CFGR_HPRE_MASK (0x0f << RCC_CFGR_HPRE_SHIFT) +# define RCC_CFGR_HPRE_SYSCLK (0 << RCC_CFGR_HPRE_SHIFT) /* 0xxx: SYSCLK not divided */ +# define RCC_CFGR_HPRE_SYSCLKd2 (8 << RCC_CFGR_HPRE_SHIFT) /* 1000: SYSCLK divided by 2 */ +# define RCC_CFGR_HPRE_SYSCLKd4 (9 << RCC_CFGR_HPRE_SHIFT) /* 1001: SYSCLK divided by 4 */ +# define RCC_CFGR_HPRE_SYSCLKd8 (10 << RCC_CFGR_HPRE_SHIFT) /* 1010: SYSCLK divided by 8 */ +# define RCC_CFGR_HPRE_SYSCLKd16 (11 << RCC_CFGR_HPRE_SHIFT) /* 1011: SYSCLK divided by 16 */ +# define RCC_CFGR_HPRE_SYSCLKd64 (12 << RCC_CFGR_HPRE_SHIFT) /* 1100: SYSCLK divided by 64 */ +# define RCC_CFGR_HPRE_SYSCLKd128 (13 << RCC_CFGR_HPRE_SHIFT) /* 1101: SYSCLK divided by 128 */ +# define RCC_CFGR_HPRE_SYSCLKd256 (14 << RCC_CFGR_HPRE_SHIFT) /* 1110: SYSCLK divided by 256 */ +# define RCC_CFGR_HPRE_SYSCLKd512 (15 << RCC_CFGR_HPRE_SHIFT) /* 1111: SYSCLK divided by 512 */ +#define RCC_CFGR_PPRE1_SHIFT (8) /* Bits 8-10: APB Low speed prescaler (APB1) */ +#define RCC_CFGR_PPRE1_MASK (7 << RCC_CFGR_PPRE1_SHIFT) +# define RCC_CFGR_PPRE1_HCLK (0 << RCC_CFGR_PPRE1_SHIFT) /* 0xx: HCLK not divided */ +# define RCC_CFGR_PPRE1_HCLKd2 (4 << RCC_CFGR_PPRE1_SHIFT) /* 100: HCLK divided by 2 */ +# define RCC_CFGR_PPRE1_HCLKd4 (5 << RCC_CFGR_PPRE1_SHIFT) /* 101: HCLK divided by 4 */ +# define RCC_CFGR_PPRE1_HCLKd8 (6 << RCC_CFGR_PPRE1_SHIFT) /* 110: HCLK divided by 8 */ +# define RCC_CFGR_PPRE1_HCLKd16 (7 << RCC_CFGR_PPRE1_SHIFT) /* 111: HCLK divided by 16 */ +#define RCC_CFGR_PPRE2_SHIFT (11) /* Bits 11-13: APB High speed prescaler (APB2) */ +#define RCC_CFGR_PPRE2_MASK (7 << RCC_CFGR_PPRE2_SHIFT) +# define RCC_CFGR_PPRE2_HCLK (0 << RCC_CFGR_PPRE2_SHIFT) /* 0xx: HCLK not divided */ +# define RCC_CFGR_PPRE2_HCLKd2 (4 << RCC_CFGR_PPRE2_SHIFT) /* 100: HCLK divided by 2 */ +# define RCC_CFGR_PPRE2_HCLKd4 (5 << RCC_CFGR_PPRE2_SHIFT) /* 101: HCLK divided by 4 */ +# define RCC_CFGR_PPRE2_HCLKd8 (6 << RCC_CFGR_PPRE2_SHIFT) /* 110: HCLK divided by 8 */ +# define RCC_CFGR_PPRE2_HCLKd16 (7 << RCC_CFGR_PPRE2_SHIFT) /* 111: HCLK divided by 16 */ +#define RCC_CFGR_STOPWUCK (1 << 15) /* Bit 15: Wakeup from Stop and CSS backup clock selection */ +# define RCC_CFGR_STOPWUCK_MSI (0 << 15) /* 0: MSI */ +# define RCC_CFGR_STOPWUCK_HSI (1 << 15) /* 0: HSI */ +#define RCC_CFGR_MCO_SHIFT (24) /* Bits 24-26: Microcontroller Clock Output */ +#define RCC_CFGR_MCO_MASK (7 << RCC_CFGR_MCO_SHIFT) +# define RCC_CFGR_MCO_NONE (0 << RCC_CFGR_MCO_SHIFT) /* 000: Disabled */ +# define RCC_CFGR_MCO_SYSCLK (1 << RCC_CFGR_MCO_SHIFT) /* 001: SYSCLK system clock selected */ +# define RCC_CFGR_MCO_MSI (2 << RCC_CFGR_MCO_SHIFT) /* 010: MSI clock selected */ +# define RCC_CFGR_MCO_HSI (3 << RCC_CFGR_MCO_SHIFT) /* 011: HSI clock selected */ +# define RCC_CFGR_MCO_HSE (4 << RCC_CFGR_MCO_SHIFT) /* 100: HSE clock selected */ +# define RCC_CFGR_MCO_PLL (5 << RCC_CFGR_MCO_SHIFT) /* 101: Main PLL selected */ +# define RCC_CFGR_MCO_LSI (6 << RCC_CFGR_MCO_SHIFT) /* 110: LSI clock selected */ +# define RCC_CFGR_MCO_LSE (7 << RCC_CFGR_MCO_SHIFT) /* 111: LSE clock selected */ +#define RCC_CFGR_MCOPRE_SHIFT (28) /* Bits 28-30: MCO prescaler */ +#define RCC_CFGR_MCOPRE_MASK (7 << RCC_CFGR_MCOPRE_SHIFT) +# define RCC_CFGR_MCOPRE_NONE (0 << RCC_CFGR_MCOPRE_SHIFT) /* 000: no division */ +# define RCC_CFGR_MCOPRE_DIV2 (1 << RCC_CFGR_MCOPRE_SHIFT) /* 001: division by 2 */ +# define RCC_CFGR_MCOPRE_DIV4 (2 << RCC_CFGR_MCOPRE_SHIFT) /* 010: division by 4 */ +# define RCC_CFGR_MCOPRE_DIV8 (3 << RCC_CFGR_MCOPRE_SHIFT) /* 011: division by 8 */ +# define RCC_CFGR_MCOPRE_DIV16 (4 << RCC_CFGR_MCOPRE_SHIFT) /* 100: division by 16 */ + +/* PLL configuration register */ + +#define RCC_PLLCFG_PLLSRC_SHIFT (0) /* Bit 0-1: Main PLL(PLL) and audio PLLs (PLLSAIx) + * entry clock source */ +#define RCC_PLLCFG_PLLSRC_MASK (3 << RCC_PLLCFG_PLLSRC_SHIFT) +# define RCC_PLLCFG_PLLSRC_NONE (0 << RCC_PLLCFG_PLLSRC_SHIFT) /* 000: No clock sent to PLLs */ +# define RCC_PLLCFG_PLLSRC_MSI (1 << RCC_PLLCFG_PLLSRC_SHIFT) /* 001: MSI selected as PLL source */ +# define RCC_PLLCFG_PLLSRC_HSI (2 << RCC_PLLCFG_PLLSRC_SHIFT) /* 001: HSI selected as PLL source */ +# define RCC_PLLCFG_PLLSRC_HSE (3 << RCC_PLLCFG_PLLSRC_SHIFT) /* 001: HSE selected as PLL source */ +#define RCC_PLLCFG_PLLM_SHIFT (4) /* Bits 4-6: Main PLL (PLL) input clock divider */ +#define RCC_PLLCFG_PLLM_MASK (0x07 << RCC_PLLCFG_PLLM_SHIFT) +# define RCC_PLLCFG_PLLM(n) ((n-1) << RCC_PLLCFG_PLLM_SHIFT) /* m = 1..8 */ +#define RCC_PLLCFG_PLLN_SHIFT (8) /* Bits 6-14: Main PLL (PLL) VCO multiplier */ +#define RCC_PLLCFG_PLLN_MASK (0x7f << RCC_PLLCFG_PLLN_SHIFT) +# define RCC_PLLCFG_PLLN(n) ((n) << RCC_PLLCFG_PLLN_SHIFT) /* n = 8..86 */ +#define RCC_PLLCFG_PLLPEN (1 << 16) /* Bit 16: Main PLL PLLSAI3CLK output enable */ +#define RCC_PLLCFG_PLLP (1 << 17) /* Bit 17: Main PLL div factor for PLLSAI3CLK */ +# define RCC_PLLCFG_PLLP_7 0 /* 0: PLLP = 7 */ +# define RCC_PLLCFG_PLLP_17 RCC_PLLCFG_PLLP /* 1: PLLP = 17 */ +#define RCC_PLLCFG_PLLQEN (1 << 20) /* Bit 20: Main PLL PLL48M1CLK output enable */ +#define RCC_PLLCFG_PLLQ_SHIFT (21) +#define RCC_PLLCFG_PLLQ_MASK (3 << RCC_PLLCFG_PLLQ_SHIFT) +# define RCC_PLLCFG_PLLQ(n) ((((n)>>1)-1)<< RCC_PLLCFG_PLLQ_SHIFT) /* n=2,4,6,8 */ +# define RCC_PLLCFG_PLLQ_2 (0 << RCC_PLLCFG_PLLQ_SHIFT) /* 00: PLLQ = 2 */ +# define RCC_PLLCFG_PLLQ_4 (1 << RCC_PLLCFG_PLLQ_SHIFT) /* 01: PLLQ = 4 */ +# define RCC_PLLCFG_PLLQ_6 (2 << RCC_PLLCFG_PLLQ_SHIFT) /* 10: PLLQ = 6 */ +# define RCC_PLLCFG_PLLQ_8 (3 << RCC_PLLCFG_PLLQ_SHIFT) /* 11: PLLQ = 8 */ +#define RCC_PLLCFG_PLLREN (1 << 24) /* Bit 24: Main PLL PLLCLK output enable */ +#define RCC_PLLCFG_PLLR_SHIFT (25) +#define RCC_PLLCFG_PLLR_MASK (3 << RCC_PLLCFG_PLLR_SHIFT) +# define RCC_PLLCFG_PLLR(n) ((((n)>>1)-1)<< RCC_PLLCFG_PLLR_SHIFT) /* n=2,4,6,8 */ +# define RCC_PLLCFG_PLLR_2 (0 << RCC_PLLCFG_PLLR_SHIFT) /* 00: PLLR = 2 */ +# define RCC_PLLCFG_PLLR_4 (1 << RCC_PLLCFG_PLLR_SHIFT) /* 01: PLLR = 4 */ +# define RCC_PLLCFG_PLLR_6 (2 << RCC_PLLCFG_PLLR_SHIFT) /* 10: PLLR = 6 */ +# define RCC_PLLCFG_PLLR_8 (3 << RCC_PLLCFG_PLLR_SHIFT) /* 11: PLLR = 8 */ + +#define RCC_PLLCFG_RESET (0x00001000) /* PLLCFG reset value */ + +/* PLLSAI1 Configuration register */ + +#define RCC_PLLSAI1CFG_PLLN_SHIFT (8) /* Bits 6-14: SAI1 PLL (PLLSAI1) VCO multiplier */ +#define RCC_PLLSAI1CFG_PLLN_MASK (0x7f << RCC_PLLSAI1CFG_PLLN_SHIFT) +# define RCC_PLLSAI1CFG_PLLN(n) ((n) << RCC_PLLSAI1CFG_PLLN_SHIFT) /* n = 8..86 */ +#define RCC_PLLSAI1CFG_PLLPEN (1 << 16) /* Bit 16: SAI1 PLL PLLSAI1CLK output enable */ +#define RCC_PLLSAI1CFG_PLLP (1 << 17) /* Bit 17: Main PLL div factor for PLLSAI1CLK */ +# define RCC_PLLSAI1CFG_PLLP_7 0 /* 0: PLLP = 7 */ +# define RCC_PLLSAI1CFG_PLLP_17 RCC_PLLSAI1CFG_PLLP /* 1: PLLP = 17 */ +#define RCC_PLLSAI1CFG_PLLQEN (1 << 20) /* Bit 20: Main PLL PLL48M2CLK output enable */ +#define RCC_PLLSAI1CFG_PLLQ_SHIFT (21) +#define RCC_PLLSAI1CFG_PLLQ_MASK (3 << RCC_PLLSAI1CFG_PLLQ_SHIFT) +# define RCC_PLLSAI1CFG_PLLQ(n) ((((n)>>1)-1)<< RCC_PLLSAI1CFG_PLLQ_SHIFT) /* n=2,4,6,8 */ +# define RCC_PLLSAI1CFG_PLLQ_2 (0 << RCC_PLLSAI1CFG_PLLQ_SHIFT) /* 00: PLLQ = 2 */ +# define RCC_PLLSAI1CFG_PLLQ_4 (1 << RCC_PLLSAI1CFG_PLLQ_SHIFT) /* 01: PLLQ = 4 */ +# define RCC_PLLSAI1CFG_PLLQ_6 (2 << RCC_PLLSAI1CFG_PLLQ_SHIFT) /* 10: PLLQ = 6 */ +# define RCC_PLLSAI1CFG_PLLQ_8 (3 << RCC_PLLSAI1CFG_PLLQ_SHIFT) /* 11: PLLQ = 8 */ +#define RCC_PLLSAI1CFG_PLLREN (1 << 24) /* Bit 24: SAI1 PLL PLLADC1CLK output enable */ +#define RCC_PLLSAI1CFG_PLLR_SHIFT (25) +#define RCC_PLLSAI1CFG_PLLR_MASK (3 << RCC_PLLSAI1CFG_PLLR_SHIFT) +# define RCC_PLLSAI1CFG_PLLR(n) ((((n)>>1)-1)<< RCC_PLLSAI1CFG_PLLR_SHIFT) /* n=2,4,6,8 */ +# define RCC_PLLSAI1CFG_PLLR_2 (0 << RCC_PLLSAI1CFG_PLLR_SHIFT) /* 00: PLLR = 2 */ +# define RCC_PLLSAI1CFG_PLLR_4 (1 << RCC_PLLSAI1CFG_PLLR_SHIFT) /* 01: PLLR = 4 */ +# define RCC_PLLSAI1CFG_PLLR_6 (2 << RCC_PLLSAI1CFG_PLLR_SHIFT) /* 10: PLLR = 6 */ +# define RCC_PLLSAI1CFG_PLLR_8 (3 << RCC_PLLSAI1CFG_PLLR_SHIFT) /* 11: PLLR = 8 */ + +/* PLLSAI2 Configuration register */ + +#define RCC_PLLSAI2CFG_PLLN_SHIFT (8) /* Bits 6-14: SAI2 PLL (PLLSAI2) VCO multiplier */ +#define RCC_PLLSAI2CFG_PLLN_MASK (0x7f << RCC_PLLSAI2CFG_PLLN_SHIFT) +# define RCC_PLLSAI2CFG_PLLN(n) ((n) << RCC_PLLSAI2CFG_PLLN_SHIFT) /* n = 8..86 */ +#define RCC_PLLSAI2CFG_PLLPEN (1 << 16) /* Bit 16: SAI1 PLL PLLSAI2CLK output enable */ +#define RCC_PLLSAI2CFG_PLLP (1 << 17) /* Bit 17: Main PLL div factor for PLLSAI2CLK */ +# define RCC_PLLSAI2CFG_PLLP_7 0 /* 0: PLLP = 7 */ +# define RCC_PLLSAI2CFG_PLLP_17 RCC_PLLSAI2CFG_PLLP /* 1: PLLP = 17 */ +#define RCC_PLLSAI2CFG_PLLREN (1 << 24) /* Bit 24: SAI2 PLL PLLADC2CLK output enable */ +#define RCC_PLLSAI2CFG_PLLR_SHIFT (25) +#define RCC_PLLSAI2CFG_PLLR_MASK (3 << RCC_PLLSAI2CFG_PLLR_SHIFT) +# define RCC_PLLSAI2CFG_PLLR(n) ((((n)>>1)-1)<< RCC_PLLSAI2CFG_PLLR_SHIFT) /* n=2,4,6,8 */ +# define RCC_PLLSAI2CFG_PLLR_2 (0 << RCC_PLLSAI2CFG_PLLR_SHIFT) /* 00: PLLR = 2 */ +# define RCC_PLLSAI2CFG_PLLR_4 (1 << RCC_PLLSAI2CFG_PLLR_SHIFT) /* 01: PLLR = 4 */ +# define RCC_PLLSAI2CFG_PLLR_6 (2 << RCC_PLLSAI2CFG_PLLR_SHIFT) /* 10: PLLR = 6 */ +# define RCC_PLLSAI2CFG_PLLR_8 (3 << RCC_PLLSAI2CFG_PLLR_SHIFT) /* 11: PLLR = 8 */ + +/* Clock interrupt enable register */ + +#define RCC_CIR_LSIRDYIE (1 << 0) /* Bit 0: LSI Ready Interrupt Enable */ +#define RCC_CIR_LSERDYIE (1 << 1) /* Bit 1: LSE Ready Interrupt Enable */ +#define RCC_CIR_MSIRDYIE (1 << 2) /* Bit 2: MSI Ready Interrupt Enable */ +#define RCC_CIR_HSIRDYIE (1 << 3) /* Bit 3: HSI Ready Interrupt Enable */ +#define RCC_CIR_HSERDYIE (1 << 4) /* Bit 4: HSE Ready Interrupt Enable */ +#define RCC_CIR_PLLRDYIE (1 << 5) /* Bit 5: PLL Ready Interrupt Enable */ +#define RCC_CIR_PLLSAI1RDYIE (1 << 6) /* Bit 6: PLLSAI1 Ready Interrupt enable */ +#define RCC_CIR_PLLSAI2RDYIE (1 << 7) /* Bit 7: PLLSAI2 Ready Interrupt enable */ +#define RCC_CIR_LSECSSIE (1 << 9) /* Bit 9: LSE Clock Security System Interrupt Enable */ + +/* Clock interrupt flag register */ + +#define RCC_CIR_LSIRDYIF (1 << 0) /* Bit 0: LSI Ready Interrupt Flag */ +#define RCC_CIR_LSERDYIF (1 << 1) /* Bit 1: LSE Ready Interrupt Flag */ +#define RCC_CIR_MSIRDYIF (1 << 2) /* Bit 2: MSI Ready Interrupt Flag */ +#define RCC_CIR_HSIRDYIF (1 << 3) /* Bit 3: HSI Ready Interrupt Flag */ +#define RCC_CIR_HSERDYIF (1 << 4) /* Bit 4: HSE Ready Interrupt Flag */ +#define RCC_CIR_PLLRDYIF (1 << 5) /* Bit 5: PLL Ready Interrupt Flag */ +#define RCC_CIR_PLLSAI1RDYIF (1 << 6) /* Bit 6: PLLSAI1 Ready Interrupt Flag */ +#define RCC_CIR_PLLSAI2RDYIF (1 << 7) /* Bit 7: PLLSAI2 Ready Interrupt Flag */ +#define RCC_CIR_CSSF (1 << 8) /* Bit 8: Clock Security System Interrupt Flag */ +#define RCC_CIR_LSECSSIF (1 << 9) /* Bit 9: LSE Clock Security System Interrupt Flag */ +#define RCC_CIR_HSI48RDYIF (1 << 10) /* Bit 10: HSI48 Ready Interrupt Flag */ + +/* Clock interrupt clear register */ + +#define RCC_CIR_LSIRDYIC (1 << 0) /* Bit 0: LSI Ready Interrupt Clear */ +#define RCC_CIR_LSERDYIC (1 << 1) /* Bit 1: LSE Ready Interrupt Clear */ +#define RCC_CIR_MSIRDYIC (1 << 2) /* Bit 2: MSI Ready Interrupt Clear */ +#define RCC_CIR_HSIRDYIC (1 << 3) /* Bit 3: HSI Ready Interrupt Clear */ +#define RCC_CIR_HSERDYIC (1 << 4) /* Bit 4: HSE Ready Interrupt Clear */ +#define RCC_CIR_PLLRDYIC (1 << 5) /* Bit 5: PLL Ready Interrupt Clear */ +#define RCC_CIR_PLLSAI1RDYIC (1 << 6) /* Bit 6: PLLSAI1 Ready Interrupt Clear */ +#define RCC_CIR_PLLSAI2RDYIC (1 << 7) /* Bit 7: PLLSAI2 Ready Interrupt Clear */ +#define RCC_CIR_CSSC (1 << 8) /* Bit 8: Clock Security System Interrupt Clear */ +#define RCC_CIR_LSECSSIC (1 << 9) /* Bit 9: LSE Clock Security System Interrupt Clear */ + +/* AHB1 peripheral reset register */ + +#define RCC_AHB1RSTR_DMA1RST (1 << 0) /* Bit 0: DMA1 reset */ +#define RCC_AHB1RSTR_DMA2RST (1 << 1) /* Bit 1: DMA2 reset */ +#define RCC_AHB1RSTR_FLASHRST (1 << 8) /* Bit 8: Flash memory interface reset */ +#define RCC_AHB1RSTR_CRCRST (1 << 12) /* Bit 12: CRC reset */ +#define RCC_AHB1RSTR_TSCRST (1 << 16) /* Bit 16: Touch Sensing Controller reset */ + +/* AHB2 peripheral reset register */ + +#define RCC_AHB1ENR_GPIOEN(port) (1 << (port)) +#define RCC_AHB2RSTR_GPIOARST (1 << 0) /* Bit 0: IO port A reset */ +#define RCC_AHB2RSTR_GPIOBRST (1 << 1) /* Bit 1: IO port B reset */ +#define RCC_AHB2RSTR_GPIOCRST (1 << 2) /* Bit 2: IO port C reset */ +#define RCC_AHB2RSTR_GPIODRST (1 << 3) /* Bit 3: IO port D reset */ +#define RCC_AHB2RSTR_GPIOERST (1 << 4) /* Bit 4: IO port E reset */ +#define RCC_AHB2RSTR_GPIOFRST (1 << 5) /* Bit 5: IO port F reset */ +#define RCC_AHB2RSTR_GPIOGRST (1 << 6) /* Bit 6: IO port G reset */ +#define RCC_AHB2RSTR_GPIOHRST (1 << 7) /* Bit 7: IO port H reset */ +#define RCC_AHB2RSTR_OTGFSRST (1 << 12) /* Bit 12: USB OTG FS module reset */ +#define RCC_AHB2RSTR_ADCRST (1 << 13) /* Bit 13: ADC interface reset (common to all ADCs) */ +#define RCC_AHB2RSTR_RNGRST (1 << 18) /* Bit 18: Random number generator module reset */ + +/* AHB3 peripheral reset register */ + +#define RCC_AHB3RSTR_FSMCRST (1 << 0) /* Bit 0: Flexible static memory controller module reset */ +#define RCC_AHB3RSTR_QSPIRST (1 << 8) /* Bit 8: Quad SPI module reset */ + +/* APB1 Peripheral reset register 1 */ + +#define RCC_APB1RSTR1_TIM2RST (1 << 0) /* Bit 0: TIM2 reset */ +#define RCC_APB1RSTR1_TIM3RST (1 << 1) /* Bit 1: TIM3 reset */ +#define RCC_APB1RSTR1_TIM4RST (1 << 2) /* Bit 2: TIM4 reset */ +#define RCC_APB1RSTR1_TIM5RST (1 << 3) /* Bit 3: TIM5 reset */ +#define RCC_APB1RSTR1_TIM6RST (1 << 4) /* Bit 4: TIM6 reset */ +#define RCC_APB1RSTR1_TIM7RST (1 << 5) /* Bit 5: TIM7 reset */ +#define RCC_APB1RSTR1_SPI2RST (1 << 14) /* Bit 14: SPI2 reset */ +#define RCC_APB1RSTR1_SPI3RST (1 << 15) /* Bit 15: SPI3 reset */ +#define RCC_APB1RSTR1_USART2RST (1 << 17) /* Bit 17: USART2 reset */ +#define RCC_APB1RSTR1_USART3RST (1 << 18) /* Bit 18: USART3 reset */ +#define RCC_APB1RSTR1_UART4RST (1 << 19) /* Bit 19: USART4 reset */ +#define RCC_APB1RSTR1_UART5RST (1 << 20) /* Bit 20: USART5 reset */ +#define RCC_APB1RSTR1_I2C1RST (1 << 21) /* Bit 21: I2C1 reset */ +#define RCC_APB1RSTR1_I2C2RST (1 << 22) /* Bit 22: I2C2 reset */ +#define RCC_APB1RSTR1_I2C3RST (1 << 23) /* Bit 23: I2C3 reset */ +#define RCC_APB1RSTR1_CAN1RST (1 << 25) /* Bit 25: CAN1 reset */ +#define RCC_APB1RSTR1_PWRRST (1 << 28) /* Bit 28: Power interface reset */ +#define RCC_APB1RSTR1_DAC1RST (1 << 29) /* Bit 29: DAC1 reset */ +#define RCC_APB1RSTR1_OPAMPRST (1 << 30) /* Bit 30: OPAMP reset */ +#define RCC_APB1RSTR1_LPTIM1RST (1 << 31) /* Bit 31: Low-power Timer 1 reset */ + +/* APB1 Peripheral reset register 2 */ + +#define RCC_APB1RSTR2_LPUART1RST (1 << 0) /* Bit 0: Low-power UART 1 reset */ +#define RCC_APB1RSTR2_SWPMI1RST (1 << 2) /* Bit 2: Single Wire Protocol reset */ +#define RCC_APB1RSTR2_LPTIM2RST (1 << 5) /* Bit 5: Low-power Timer 2 reset */ + +/* APB2 Peripheral reset register */ + +#define RCC_APB2RSTR_SYSCFGRST (1 << 0) /* Bit 0: System configuration controller reset */ +#define RCC_APB2RSTR_SDMMCRST (1 << 10) /* Bit 10: SDMMC reset */ +#define RCC_APB2RSTR_TIM1RST (1 << 11) /* Bit 11: TIM1 reset */ +#define RCC_APB2RSTR_SPI1RST (1 << 12) /* Bit 12: SPI1 reset */ +#define RCC_APB2RSTR_TIM8RST (1 << 13) /* Bit 13: TIM8 reset */ +#define RCC_APB2RSTR_USART1RST (1 << 14) /* Bit 14: USART1 reset */ +#define RCC_APB2RSTR_TIM15RST (1 << 16) /* Bit 16: TIM15 reset */ +#define RCC_APB2RSTR_TIM16RST (1 << 17) /* Bit 17: TIM16 reset */ +#define RCC_APB2RSTR_TIM17RST (1 << 18) /* Bit 18: TIM17 reset */ +#define RCC_APB2RSTR_SAI1RST (1 << 21) /* Bit 21: SAI1 reset */ +#define RCC_APB2RSTR_SAI2RST (1 << 22) /* Bit 22: SAI2 reset */ +#define RCC_APB2RSTR_DFSDMRST (1 << 24) /* Bit 24: DFSDM reset */ + +/* AHB1 Peripheral Clock enable register */ + +#define RCC_AHB1ENR_DMA1EN (1 << 0) /* Bit 0: DMA1 enable */ +#define RCC_AHB1ENR_DMA2EN (1 << 1) /* Bit 1: DMA2 enable */ +#define RCC_AHB1ENR_FLASHEN (1 << 8) /* Bit 8: Flash memory interface enable */ +#define RCC_AHB1ENR_CRCEN (1 << 12) /* Bit 12: CRC enable */ +#define RCC_AHB1ENR_TSCEN (1 << 16) /* Bit 16: Touch Sensing Controller enable */ + +/* AHB2 Peripheral Clock enable register */ + +#define RCC_AHB2ENR_GPIOAEN (1 << 0) /* Bit 0: IO port A enable */ +#define RCC_AHB2ENR_GPIOBEN (1 << 1) /* Bit 1: IO port B enable */ +#define RCC_AHB2ENR_GPIOCEN (1 << 2) /* Bit 2: IO port C enable */ +#define RCC_AHB2ENR_GPIODEN (1 << 3) /* Bit 3: IO port D enable */ +#define RCC_AHB2ENR_GPIOEEN (1 << 4) /* Bit 4: IO port E enable */ +#define RCC_AHB2ENR_GPIOFEN (1 << 5) /* Bit 5: IO port F enable */ +#define RCC_AHB2ENR_GPIOGEN (1 << 6) /* Bit 6: IO port G enable */ +#define RCC_AHB2ENR_GPIOHEN (1 << 7) /* Bit 7: IO port H enable */ +#define RCC_AHB2ENR_OTGFSEN (1 << 12) /* Bit 12: USB OTG FS module enable */ +#define RCC_AHB2ENR_ADCEN (1 << 13) /* Bit 13: ADC interface enable (common to all ADCs) */ +#define RCC_AHB2ENR_RNGEN (1 << 18) /* Bit 18: Random number generator module enable */ + +/* AHB3 Peripheral Clock enable register */ + +#define RCC_AHB3ENR_FSMCEN (1 << 0) /* Bit 0: Flexible static memory controller module enable */ +#define RCC_AHB3ENR_QSPIEN (1 << 8) /* Bit 8: Quad SPI module enable */ + +/* APB1 Peripheral Clock enable register 1 */ + +#define RCC_APB1ENR1_TIM2EN (1 << 0) /* Bit 0: TIM2 enable */ +#define RCC_APB1ENR1_TIM3EN (1 << 1) /* Bit 1: TIM3 enable */ +#define RCC_APB1ENR1_TIM4EN (1 << 2) /* Bit 2: TIM4 enable */ +#define RCC_APB1ENR1_TIM5EN (1 << 3) /* Bit 3: TIM5 enable */ +#define RCC_APB1ENR1_TIM6EN (1 << 4) /* Bit 4: TIM6 enable */ +#define RCC_APB1ENR1_TIM7EN (1 << 5) /* Bit 5: TIM7 enable */ +#define RCC_APB1ENR1_WWDGEN (1 << 11) /* Bit 11: Windowed Watchdog enable */ +#define RCC_APB1ENR1_SPI2EN (1 << 14) /* Bit 14: SPI2 enable */ +#define RCC_APB1ENR1_SPI3EN (1 << 15) /* Bit 15: SPI3 enable */ +#define RCC_APB1ENR1_USART2EN (1 << 17) /* Bit 17: USART2 enable */ +#define RCC_APB1ENR1_USART3EN (1 << 18) /* Bit 18: USART3 enable */ +#define RCC_APB1ENR1_UART4EN (1 << 19) /* Bit 19: USART4 enable */ +#define RCC_APB1ENR1_UART5EN (1 << 20) /* Bit 20: USART5 enable */ +#define RCC_APB1ENR1_I2C1EN (1 << 21) /* Bit 21: I2C1 enable */ +#define RCC_APB1ENR1_I2C2EN (1 << 22) /* Bit 22: I2C2 enable */ +#define RCC_APB1ENR1_I2C3EN (1 << 23) /* Bit 23: I2C3 enable */ +#define RCC_APB1ENR1_CAN1EN (1 << 25) /* Bit 25: CAN1 enable */ +#define RCC_APB1ENR1_PWREN (1 << 28) /* Bit 28: Power interface enable */ +#define RCC_APB1ENR1_DAC1EN (1 << 29) /* Bit 29: DAC1 enable */ +#define RCC_APB1ENR1_OPAMPEN (1 << 30) /* Bit 30: OPAMP enable */ +#define RCC_APB1ENR1_LPTIM1EN (1 << 31) /* Bit 31: Low-power Timer 1 enable */ + +/* APB1 Peripheral Clock enable register 2 */ + +#define RCC_APB1ENR2_LPUART1EN (1 << 0) /* Bit 0: Low-power UART 1 enable */ +#define RCC_APB1ENR2_SWPMI1EN (1 << 2) /* Bit 2: Single Wire Protocol enable */ +#define RCC_APB1ENR2_LPTIM2EN (1 << 5) /* Bit 5: Low-power Timer 2 enable */ + +/* APB2 Peripheral Clock enable register */ + +#define RCC_APB2ENR_SYSCFGEN (1 << 0) /* Bit 0: System configuration controller enable */ +#define RCC_APB2ENR_FWEN (1 << 7) /* Bit 7: Firewall enable */ +#define RCC_APB2ENR_SDMMCEN (1 << 10) /* Bit 10: SDMMC enable */ +#define RCC_APB2ENR_TIM1EN (1 << 11) /* Bit 11: TIM1 enable */ +#define RCC_APB2ENR_SPI1EN (1 << 12) /* Bit 12: SPI1 enable */ +#define RCC_APB2ENR_TIM8EN (1 << 13) /* Bit 13: TIM8 enable */ +#define RCC_APB2ENR_USART1EN (1 << 14) /* Bit 14: USART1 enable */ +#define RCC_APB2ENR_TIM15EN (1 << 16) /* Bit 16: TIM15 enable */ +#define RCC_APB2ENR_TIM16EN (1 << 17) /* Bit 17: TIM16 enable */ +#define RCC_APB2ENR_TIM17EN (1 << 18) /* Bit 18: TIM17 enable */ +#define RCC_APB2ENR_SAI1EN (1 << 21) /* Bit 21: SAI1 enable */ +#define RCC_APB2ENR_SAI2EN (1 << 22) /* Bit 22: SAI2 enable */ +#define RCC_APB2ENR_DFSDMEN (1 << 24) /* Bit 24: DFSDM enable */ + +/* RCC AHB1 low power mode peripheral clock enable register */ + +#define RCC_AHB1SMENR_DMA1LPSMEN (1 << 0) /* Bit 0: DMA1 enable during Sleep mode */ +#define RCC_AHB1SMENR_DMA2LPSMEN (1 << 1) /* Bit 1: DMA2 enable during Sleep mode */ +#define RCC_AHB1SMENR_FLASHLPSMEN (1 << 8) /* Bit 8: Flash memory interface enable during Sleep mode */ +#define RCC_AHB1SMENR_SRAM1SMEN (1 << 9) /* Bit 9: SRAM1 enable during Sleep mode */ +#define RCC_AHB1SMENR_CRCLPSMEN (1 << 12) /* Bit 12: CRC enable during Sleep mode */ +#define RCC_AHB1SMENR_TSCLPSMEN (1 << 16) /* Bit 16: Touch Sensing Controller enable during Sleep mode */ + +/* RCC AHB2 low power mode peripheral clock enable register */ + +#define RCC_AHB2SMENR_GPIOASMEN (1 << 0) /* Bit 0: IO port A enable during Sleep mode */ +#define RCC_AHB2SMENR_GPIOBSMEN (1 << 1) /* Bit 1: IO port B enable during Sleep mode */ +#define RCC_AHB2SMENR_GPIOCSMEN (1 << 2) /* Bit 2: IO port C enable during Sleep mode */ +#define RCC_AHB2SMENR_GPIODSMEN (1 << 3) /* Bit 3: IO port D enable during Sleep mode */ +#define RCC_AHB2SMENR_GPIOESMEN (1 << 4) /* Bit 4: IO port E enable during Sleep mode */ +#define RCC_AHB2SMENR_GPIOFSMEN (1 << 5) /* Bit 5: IO port F enable during Sleep mode */ +#define RCC_AHB2SMENR_GPIOGSMEN (1 << 6) /* Bit 6: IO port G enable during Sleep mode */ +#define RCC_AHB2SMENR_GPIOHSMEN (1 << 7) /* Bit 7: IO port H enable during Sleep mode */ +#define RCC_AHB2SMENR_SRAM2SMEN (1 << 9) /* Bit 9: SRAM2 enable during Sleep mode */ +#define RCC_AHB2SMENR_OTGFSSMEN (1 << 12) /* Bit 12: USB OTG FS module enable during Sleep mode */ +#define RCC_AHB2SMENR_ADCSMEN (1 << 13) /* Bit 13: ADC interface enable during Sleep mode (common to all ADCs) */ +#define RCC_AHB2SMENR_RNGSMEN (1 << 18) /* Bit 18: Random number generator module enable during Sleep mode */ + +/* RCC AHB3 low power mode peripheral clock enable register */ + +#define RCC_AHB3SMENR_FSMCSMEN (1 << 0) /* Bit 0: Flexible static memory controller module enable during Sleep mode */ +#define RCC_AHB3SMENR_QSPISMEN (1 << 8) /* Bit 8: Quad SPI module enable during Sleep mode */ + +/* RCC APB1 low power mode peripheral clock enable register 1 */ + +#define RCC_APB1SMENR1_TIM2SMEN (1 << 0) /* Bit 0: TIM2 enable during Sleep mode */ +#define RCC_APB1SMENR1_TIM3SMEN (1 << 1) /* Bit 1: TIM3 enable during Sleep mode */ +#define RCC_APB1SMENR1_TIM4SMEN (1 << 2) /* Bit 2: TIM4 enable during Sleep mode */ +#define RCC_APB1SMENR1_TIM5SMEN (1 << 3) /* Bit 3: TIM5 enable during Sleep mode */ +#define RCC_APB1SMENR1_TIM6SMEN (1 << 4) /* Bit 4: TIM6 enable during Sleep mode */ +#define RCC_APB1SMENR1_TIM7SMEN (1 << 5) /* Bit 5: TIM7 enable during Sleep mode */ +#define RCC_APB1SMENR1_WWDGSMEN (1 << 11) /* Bit 11: Windowed Watchdog enable during Sleep mode */ +#define RCC_APB1SMENR1_SPI2SMEN (1 << 14) /* Bit 14: SPI2 enable during Sleep mode */ +#define RCC_APB1SMENR1_SPI3SMEN (1 << 15) /* Bit 15: SPI3 enable during Sleep mode */ +#define RCC_APB1SMENR1_USART2SMEN (1 << 17) /* Bit 17: USART2 enable during Sleep mode */ +#define RCC_APB1SMENR1_USART3SMEN (1 << 18) /* Bit 18: USART3 enable during Sleep mode */ +#define RCC_APB1SMENR1_UART4SMEN (1 << 19) /* Bit 19: USART4 enable during Sleep mode */ +#define RCC_APB1SMENR1_UART5SMEN (1 << 20) /* Bit 20: USART5 enable during Sleep mode */ +#define RCC_APB1SMENR1_I2C1SMEN (1 << 21) /* Bit 21: I2C1 enable during Sleep mode */ +#define RCC_APB1SMENR1_I2C2SMEN (1 << 22) /* Bit 22: I2C2 enable during Sleep mode */ +#define RCC_APB1SMENR1_I2C3SMEN (1 << 23) /* Bit 23: I2C3 enable during Sleep mode */ +#define RCC_APB1SMENR1_CAN1SMEN (1 << 25) /* Bit 25: CAN1 enable during Sleep mode */ +#define RCC_APB1SMENR1_PWRSMEN (1 << 28) /* Bit 28: Power interface enable during Sleep mode */ +#define RCC_APB1SMENR1_DAC1SMEN (1 << 29) /* Bit 29: DAC1 enable during Sleep mode */ +#define RCC_APB1SMENR1_OPAMPSMEN (1 << 30) /* Bit 30: OPAMP enable during Sleep mode */ +#define RCC_APB1SMENR1_LPTIM1SMEN (1 << 31) /* Bit 31: Low-power Timer 1 enable during Sleep mode */ + +/* RCC APB1 low power modeperipheral clock enable register 2 */ + +#define RCC_APB1SMENR2_LPUART1SMEN (1 << 0) /* Bit 0: Low-power UART 1 enable during Sleep mode */ +#define RCC_APB1SMENR2_SWPMI1SMEN (1 << 2) /* Bit 2: Single Wire Protocol enable during Sleep mode */ +#define RCC_APB1SMENR2_LPTIM2SMEN (1 << 5) /* Bit 5: Low-power Timer 2 enable during Sleep mode */ + +/* RCC APB2 low power mode peripheral clock enable register */ + +#define RCC_APB2SMENR_SYSCFGSMEN (1 << 0) /* Bit 0: System configuration controller enable during Sleep mode */ +#define RCC_APB2SMENR_SDMMCSMEN (1 << 10) /* Bit 10: SDMMC enable during Sleep mode */ +#define RCC_APB2SMENR_TIM1SMEN (1 << 11) /* Bit 11: TIM1 enable during Sleep mode */ +#define RCC_APB2SMENR_SPI1SMEN (1 << 12) /* Bit 12: SPI1 enable during Sleep mode */ +#define RCC_APB2SMENR_TIM8SMEN (1 << 13) /* Bit 13: TIM8 enable during Sleep mode */ +#define RCC_APB2SMENR_USART1SMEN (1 << 14) /* Bit 14: USART1 enable during Sleep mode */ +#define RCC_APB2SMENR_TIM15SMEN (1 << 16) /* Bit 16: TIM15 enable during Sleep mode */ +#define RCC_APB2SMENR_TIM16SMEN (1 << 17) /* Bit 17: TIM16 enable during Sleep mode */ +#define RCC_APB2SMENR_TIM17SMEN (1 << 18) /* Bit 18: TIM17 enable during Sleep mode */ +#define RCC_APB2SMENR_SAI1SMEN (1 << 21) /* Bit 21: SAI1 enable during Sleep mode */ +#define RCC_APB2SMENR_SAI2SMEN (1 << 22) /* Bit 22: SAI2 enable during Sleep mode */ +#define RCC_APB2SMENR_DFSDMSMEN (1 << 24) /* Bit 24: DFSDM enable during Sleep mode */ + +/* Peripheral Independent Clock Configuration register */ + +#define RCC_CCIPR_USART1SEL_SHIFT (0) +#define RCC_CCIPR_USART1SEL_MASK (3 << RCC_CCIPR_USART1SEL_SHIFT) +# define RCC_CCIPR_USART1SEL_PCLK (0 << RCC_CCIPR_USART1SEL_SHIFT) +# define RCC_CCIPR_USART1SEL_SYSCLK (1 << RCC_CCIPR_USART1SEL_SHIFT) +# define RCC_CCIPR_USART1SEL_HSI (2 << RCC_CCIPR_USART1SEL_SHIFT) +# define RCC_CCIPR_USART1SEL_LSE (3 << RCC_CCIPR_USART1SEL_SHIFT) +#define RCC_CCIPR_USART2SEL_SHIFT (2) +#define RCC_CCIPR_USART2SEL_MASK (3 << RCC_CCIPR_USART2SEL_SHIFT) +# define RCC_CCIPR_USART2SEL_PCLK (0 << RCC_CCIPR_USART2SEL_SHIFT) +# define RCC_CCIPR_USART2SEL_SYSCLK (1 << RCC_CCIPR_USART2SEL_SHIFT) +# define RCC_CCIPR_USART2SEL_HSI (2 << RCC_CCIPR_USART2SEL_SHIFT) +# define RCC_CCIPR_USART2SEL_LSE (3 << RCC_CCIPR_USART2SEL_SHIFT) +#define RCC_CCIPR_USART3SEL_SHIFT (4) +#define RCC_CCIPR_USART3SEL_MASK (3 << RCC_CCIPR_USART3SEL_SHIFT) +# define RCC_CCIPR_USART3SEL_PCLK (0 << RCC_CCIPR_USART3SEL_SHIFT) +# define RCC_CCIPR_USART3SEL_SYSCLK (1 << RCC_CCIPR_USART3SEL_SHIFT) +# define RCC_CCIPR_USART3SEL_HSI (2 << RCC_CCIPR_USART3SEL_SHIFT) +# define RCC_CCIPR_USART3SEL_LSE (3 << RCC_CCIPR_USART3SEL_SHIFT) +#define RCC_CCIPR_UART4SEL_SHIFT (6) +#define RCC_CCIPR_UART4SEL_MASK (3 << RCC_CCIPR_UART4SEL_SHIFT) +# define RCC_CCIPR_UART4SEL_PCLK (0 << RCC_CCIPR_UART4SEL_SHIFT) +# define RCC_CCIPR_UART4SEL_SYSCLK (1 << RCC_CCIPR_UART4SEL_SHIFT) +# define RCC_CCIPR_UART4SEL_HSI (2 << RCC_CCIPR_UART4SEL_SHIFT) +# define RCC_CCIPR_UART4SEL_LSE (3 << RCC_CCIPR_UART4SEL_SHIFT) +#define RCC_CCIPR_UART5SEL_SHIFT (8) +#define RCC_CCIPR_UART5SEL_MASK (3 << RCC_CCIPR_UART5SEL_SHIFT) +# define RCC_CCIPR_UART5SEL_PCLK (0 << RCC_CCIPR_UART5SEL_SHIFT) +# define RCC_CCIPR_UART5SEL_SYSCLK (1 << RCC_CCIPR_UART5SEL_SHIFT) +# define RCC_CCIPR_UART5SEL_HSI (2 << RCC_CCIPR_UART5SEL_SHIFT) +# define RCC_CCIPR_UART5SEL_LSE (3 << RCC_CCIPR_UART5SEL_SHIFT) +#define RCC_CCIPR_LPUART1SEL_SHIFT (10) +#define RCC_CCIPR_LPUART1SEL_MASK (3 << RCC_CCIPR_LPUART1SEL_SHIFT) +# define RCC_CCIPR_LPUART1SEL_PCLK (0 << RCC_CCIPR_LPUART1SEL_SHIFT) +# define RCC_CCIPR_LPUART1SEL_SYSCLK (1 << RCC_CCIPR_LPUART1SEL_SHIFT) +# define RCC_CCIPR_LPUART1SEL_HSI (2 << RCC_CCIPR_LPUART1SEL_SHIFT) +# define RCC_CCIPR_LPUART1SEL_LSE (3 << RCC_CCIPR_LPUART1SEL_SHIFT) +#define RCC_CCIPR_I2C1SEL_SHIFT (12) +#define RCC_CCIPR_I2C1SEL_MASK (3 << RCC_CCIPR_I2C1SEL_SHIFT) +# define RCC_CCIPR_I2C1SEL_PCLK (0 << RCC_CCIPR_I2C1SEL_SHIFT) +# define RCC_CCIPR_I2C1SEL_SYSCLK (1 << RCC_CCIPR_I2C1SEL_SHIFT) +# define RCC_CCIPR_I2C1SEL_HSI (2 << RCC_CCIPR_I2C1SEL_SHIFT) +#define RCC_CCIPR_I2C2SEL_SHIFT (14) +#define RCC_CCIPR_I2C2SEL_MASK (3 << RCC_CCIPR_I2C2SEL_SHIFT) +# define RCC_CCIPR_I2C2SEL_PCLK (0 << RCC_CCIPR_I2C2SEL_SHIFT) +# define RCC_CCIPR_I2C2SEL_SYSCLK (1 << RCC_CCIPR_I2C2SEL_SHIFT) +# define RCC_CCIPR_I2C2SEL_HSI (2 << RCC_CCIPR_I2C2SEL_SHIFT) +#define RCC_CCIPR_I2C3SEL_SHIFT (16) +#define RCC_CCIPR_I2C3SEL_MASK (3 << RCC_CCIPR_I2C3SEL_SHIFT) +# define RCC_CCIPR_I2C3SEL_PCLK (0 << RCC_CCIPR_I2C3SEL_SHIFT) +# define RCC_CCIPR_I2C3SEL_SYSCLK (1 << RCC_CCIPR_I2C3SEL_SHIFT) +# define RCC_CCIPR_I2C3SEL_HSI (2 << RCC_CCIPR_I2C3SEL_SHIFT) +#define RCC_CCIPR_LPTIM1SEL_SHIFT (18) +#define RCC_CCIPR_LPTIM1SEL_MASK (3 << RCC_CCIPR_LPTIM1SEL_SHIFT) +# define RCC_CCIPR_LPTIM1SEL_PCLK (0 << RCC_CCIPR_LPTIM1SEL_SHIFT) +# define RCC_CCIPR_LPTIM1SEL_LSI (1 << RCC_CCIPR_LPTIM1SEL_SHIFT) +# define RCC_CCIPR_LPTIM1SEL_HSI (2 << RCC_CCIPR_LPTIM1SEL_SHIFT) +# define RCC_CCIPR_LPTIM1SEL_LSE (3 << RCC_CCIPR_LPTIM1SEL_SHIFT) +#define RCC_CCIPR_LPTIM2SEL_SHIFT (20) +#define RCC_CCIPR_LPTIM2SEL_MASK (3 << RCC_CCIPR_LPTIM2SEL_SHIFT) +# define RCC_CCIPR_LPTIM2SEL_PCLK (0 << RCC_CCIPR_LPTIM2SEL_SHIFT) +# define RCC_CCIPR_LPTIM2SEL_LSI (1 << RCC_CCIPR_LPTIM2SEL_SHIFT) +# define RCC_CCIPR_LPTIM2SEL_HSI (2 << RCC_CCIPR_LPTIM2SEL_SHIFT) +# define RCC_CCIPR_LPTIM2SEL_LSE (3 << RCC_CCIPR_LPTIM2SEL_SHIFT) +#define RCC_CCIPR_SAI1SEL_SHIFT (22) +#define RCC_CCIPR_SAI1SEL_MASK (3 << RCC_CCIPR_SAI1SEL_SHIFT) +# define RCC_CCIPR_SAI1SEL_PLLSAI1 (0 << RCC_CCIPR_SAI1SEL_SHIFT) +# define RCC_CCIPR_SAI1SEL_PLLSAI2 (1 << RCC_CCIPR_SAI1SEL_SHIFT) +# define RCC_CCIPR_SAI1SEL_PLLMAIN (2 << RCC_CCIPR_SAI1SEL_SHIFT) +# define RCC_CCIPR_SAI1SEL_EXTCLK (3 << RCC_CCIPR_SAI1SEL_SHIFT) +#define RCC_CCIPR_SAI2SEL_SHIFT (24) +#define RCC_CCIPR_SAI2SEL_MASK (3 << RCC_CCIPR_SAI2SEL_SHIFT) +# define RCC_CCIPR_SAI2SEL_PLLSAI1 (0 << RCC_CCIPR_SAI2SEL_SHIFT) +# define RCC_CCIPR_SAI2SEL_PLLSAI2 (1 << RCC_CCIPR_SAI2SEL_SHIFT) +# define RCC_CCIPR_SAI2SEL_PLLMAIN (2 << RCC_CCIPR_SAI2SEL_SHIFT) +# define RCC_CCIPR_SAI2SEL_EXTCLK (3 << RCC_CCIPR_SAI2SEL_SHIFT) +#define RCC_CCIPR_CLK48SEL_SHIFT (26) +#define RCC_CCIPR_CLK48SEL_MASK (3 << RCC_CCIPR_CLK48SEL_SHIFT) +# define RCC_CCIPR_CLK48SEL_NONE (0 << RCC_CCIPR_CLK48SEL_SHIFT) +# define RCC_CCIPR_CLK48SEL_PLLSAI1 (1 << RCC_CCIPR_CLK48SEL_SHIFT) +# define RCC_CCIPR_CLK48SEL_PLLMAIN (2 << RCC_CCIPR_CLK48SEL_SHIFT) +# define RCC_CCIPR_CLK48SEL_MSI (3 << RCC_CCIPR_CLK48SEL_SHIFT) +#define RCC_CCIPR_ADCSEL_SHIFT (28) +#define RCC_CCIPR_ADCSEL_MASK (3 << RCC_CCIPR_ADCSEL_SHIFT) +# define RCC_CCIPR_ADCSEL_NONE (0 << RCC_CCIPR_ADCSEL_SHIFT) +# define RCC_CCIPR_ADCSEL_PLLSAI1 (1 << RCC_CCIPR_ADCSEL_SHIFT) +# define RCC_CCIPR_ADCSEL_PLLSAI2 (2 << RCC_CCIPR_ADCSEL_SHIFT) +# define RCC_CCIPR_ADCSEL_SYSCLK (3 << RCC_CCIPR_ADCSEL_SHIFT) +#define RCC_CCIPR_SWPMI1SEL (1 << 30) +# define RCC_CCIPR_SWPMI1SEL_PCLK 0 +# define RCC_CCIPR_SWPMI1SEL_HSI RCC_CCIPR_SWPMI1SEL +#define RCC_CCIPR_DFSDMSEL (1 << 31) +# define RCC_CCIPR_DFSDMSEL_PCLK 0 +# define RCC_CCIPR_DFSDMSEL_SYSCLK RCC_CCIPR_DFSDMSEL + +/* Backup domain control register */ + +#define RCC_BDCR_LSEON (1 << 0) /* Bit 0: External Low Speed oscillator enable */ +#define RCC_BDCR_LSERDY (1 << 1) /* Bit 1: External Low Speed oscillator Ready */ +#define RCC_BDCR_LSEBYP (1 << 2) /* Bit 2: External Low Speed oscillator Bypass */ +#define RCC_BDCR_LSEDRV_SHIFT (3) /* Bits 3-4: LSE oscillator drive capability */ +#define RCC_BDCR_LSEDRV_MASK (3 << RCC_BDCR_LSEDRV_SHIFT) +# define RCC_BDCR_LSEDRV_LOWER (0 << RCC_BDCR_LSEDRV_SHIFT) /* 00: Lower driving capability */ +# define RCC_BDCR_LSEDRV_MIDLOW (1 << RCC_BDCR_LSEDRV_SHIFT) /* 01: Medium Low driving capability */ +# define RCC_BDCR_LSEDRV_MIDHI (2 << RCC_BDCR_LSEDRV_SHIFT) /* 10: Medium High driving capability*/ +# define RCC_BDCR_LSEDRV_HIGER (3 << RCC_BDCR_LSEDRV_SHIFT) /* 11: Higher driving capability */ +#define RCC_BDCR_LSECSSON (1 << 5) /* Bit 5: CSS on LSE enable */ +#define RCC_BDCR_LSECSSD (1 << 6) /* Bit 6: CSS on LSE failure Detection */ +#define RCC_BDCR_RTCSEL_SHIFT (8) /* Bits 9:8: RTC clock source selection */ +#define RCC_BDCR_RTCSEL_MASK (3 << RCC_BDCR_RTCSEL_SHIFT) +# define RCC_BDCR_RTCSEL_NOCLK (0 << RCC_BDCR_RTCSEL_SHIFT) /* 00: No clock */ +# define RCC_BDCR_RTCSEL_LSE (1 << RCC_BDCR_RTCSEL_SHIFT) /* 01: LSE oscillator clock used as RTC clock */ +# define RCC_BDCR_RTCSEL_LSI (2 << RCC_BDCR_RTCSEL_SHIFT) /* 10: LSI oscillator clock used as RTC clock */ +# define RCC_BDCR_RTCSEL_HSE (3 << RCC_BDCR_RTCSEL_SHIFT) /* 11: HSE oscillator clock divided by 32 used as RTC clock */ +#define RCC_BDCR_RTCEN (1 << 15) /* Bit 15: RTC clock enable */ +#define RCC_BDCR_BDRST (1 << 16) /* Bit 16: Backup domain software reset */ +#define RCC_BDCR_LSCOEN (1 << 24) /* Bit 24: Low speed clock output enable */ +#define RCC_BDCR_LSCOSEL (1 << 25) /* Bit 25: Low speed clock output selection */ +# define RCC_BCDR_LSCOSEL_LSI 0 /* LSI selected */ +# define RCC_BDCR_LSCOSEL_LSE RCC_BDCR_LSCOSEL /* LSE selected */ + +/* Control/status register */ + +#define RCC_CSR_LSION (1 << 0) /* Bit 0: Internal Low Speed oscillator enable */ +#define RCC_CSR_LSIRDY (1 << 1) /* Bit 1: Internal Low Speed oscillator Ready */ +#define RCC_CSR_MSISRANGE_SHIFT 8 +# define RCC_CSR_MSISRANGE_MASK (0x0F << RCC_CSR_MSISRANGE_SHIFT) /* MSI range after Standby mode */ +# define RCC_CSR_MSISRANGE_1M (4 << RCC_CSR_MSISRANGE_SHIFT) /* 0100: around 1 MHz */ +# define RCC_CSR_MSISRANGE_2M (5 << RCC_CSR_MSISRANGE_SHIFT) /* 0101: around 2 MHz */ +# define RCC_CSR_MSISRANGE_4M (6 << RCC_CSR_MSISRANGE_SHIFT) /* 0110: around 4 MHz */ +# define RCC_CSR_MSISRANGE_8M (7 << RCC_CSR_MSISRANGE_SHIFT) /* 0111: around 8 MHz */ +#define RCC_CSR_RMVF (1 << 23) /* Bit 23: Remove reset flag */ +#define RCC_CSR_FWRSTF (1 << 24) /* Bit 24: Firewall reset flag */ +#define RCC_CSR_OBLRSTF (1 << 25) /* Bit 25: Option byte loader reset flag */ +#define RCC_CSR_PINRSTF (1 << 26) /* Bit 26: PIN reset flag */ +#define RCC_CSR_BORRSTF (1 << 27) /* Bit 27: BOR reset flag */ +#define RCC_CSR_SFTRSTF (1 << 28) /* Bit 28: Software Reset flag */ +#define RCC_CSR_IWDGRSTF (1 << 29) /* Bit 29: Independent Watchdog reset flag */ +#define RCC_CSR_WWDGRSTF (1 << 30) /* Bit 30: Window watchdog reset flag */ +#define RCC_CSR_LPWRRSTF (1 << 31) /* Bit 31: Low-Power reset flag */ + +#endif /* CONFIG_STM32L4_STM32L4X5 */ +#endif /* __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X5XX_RCC_H */ diff --git a/arch/arm/src/stm32l4/chip/stm32l4x6xx_rcc.h b/arch/arm/src/stm32l4/chip/stm32l4x6xx_rcc.h index 6d55cfea9a..7a8f97a3b2 100644 --- a/arch/arm/src/stm32l4/chip/stm32l4x6xx_rcc.h +++ b/arch/arm/src/stm32l4/chip/stm32l4x6xx_rcc.h @@ -127,7 +127,7 @@ #define RCC_CR_MSION (1 << 0) /* Bit 0: Internal Multi Speed clock enable */ #define RCC_CR_MSIRDY (1 << 1) /* Bit 1: Internal Multi Speed clock ready flag */ #define RCC_CR_MSIPLLEN (1 << 2) /* Bit 2: MSI clock PLL enable */ -#define RCC_CR_MSIRGSEL (1 << 3) /* Bit 2: MSI clock range selection */ +#define RCC_CR_MSIRGSEL (1 << 3) /* Bit 3: MSI clock range selection */ #define RCC_CR_MSIRANGE_SHIFT (4) /* Bits 7-4: MSI clock range */ #define RCC_CR_MSIRANGE_MASK (0x0f << RCC_CR_MSIRANGE_SHIFT) # define RCC_CR_MSIRANGE_100K (0 << RCC_CR_MSIRANGE_SHIFT) /* 0000: around 100 kHz */ diff --git a/arch/arm/src/stm32l4/stm32l4_rcc.c b/arch/arm/src/stm32l4/stm32l4_rcc.c index c2f3cfa198..d18e0dbc88 100644 --- a/arch/arm/src/stm32l4/stm32l4_rcc.c +++ b/arch/arm/src/stm32l4/stm32l4_rcc.c @@ -78,10 +78,12 @@ /* Include chip-specific clocking initialization logic */ -#if defined(CONFIG_STM32L4_STM32L4X6) -# include "stm32l4x6xx_rcc.c" -#elif defined(CONFIG_STM32L4_STM32L4X3) +#if defined(CONFIG_STM32L4_STM32L4X3) # include "stm32l4x3xx_rcc.c" +#elif defined(CONFIG_STM32L4_STM32L4X5) +# include "stm32l4x5xx_rcc.c" +#elif defined(CONFIG_STM32L4_STM32L4X6) +# include "stm32l4x6xx_rcc.c" #else # error "Unsupported STM32L4 chip" #endif diff --git a/arch/arm/src/stm32l4/stm32l4_rcc.h b/arch/arm/src/stm32l4/stm32l4_rcc.h index 8e3f84adc8..8a8d2d7f2a 100644 --- a/arch/arm/src/stm32l4/stm32l4_rcc.h +++ b/arch/arm/src/stm32l4/stm32l4_rcc.h @@ -45,10 +45,12 @@ #include "up_arch.h" #include "chip.h" -#if defined(CONFIG_STM32L4_STM32L4X6) -# include "chip/stm32l4x6xx_rcc.h" -#elif defined(CONFIG_STM32L4_STM32L4X3) +#if defined(CONFIG_STM32L4_STM32L4X3) # include "chip/stm32l4x3xx_rcc.h" +#elif defined(CONFIG_STM32L4_STM32L4X5) +# include "chip/stm32l4x5xx_rcc.h" +#elif defined(CONFIG_STM32L4_STM32L4X6) +# include "chip/stm32l4x6xx_rcc.h" #else # error "Unsupported STM32L4 chip" #endif @@ -64,7 +66,7 @@ #define EXTERN extern "C" extern "C" { -#else +#elseO #define EXTERN extern #endif diff --git a/arch/arm/src/stm32l4/stm32l4x5xx_rcc.c b/arch/arm/src/stm32l4/stm32l4x5xx_rcc.c new file mode 100644 index 0000000000..4f104f391a --- /dev/null +++ b/arch/arm/src/stm32l4/stm32l4x5xx_rcc.c @@ -0,0 +1,893 @@ +/**************************************************************************** + * arch/arm/src/stm32l4/stm32l4x5xx_rcc.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Copyright (C) 2016 Sebastien Lorquet. All rights reserved. + * Author: Gregory Nutt + * Sebastien Lorquet + * + * 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 "stm32l4_pwr.h" +#include "stm32l4_flash.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Allow up to 100 milliseconds for the high speed clock to become ready. + * that is a very long delay, but if the clock does not become ready we are + * hosed anyway. Normally this is very fast, but I have seen at least one + * board that required this long, long timeout for the HSE to be ready. + */ + +#define HSERDY_TIMEOUT (100 * CONFIG_BOARD_LOOPSPERMSEC) + +/* Same for HSI and MSI */ + +#define HSIRDY_TIMEOUT HSERDY_TIMEOUT +#define MSIRDY_TIMEOUT HSERDY_TIMEOUT + +/* HSE divisor to yield ~1MHz RTC clock */ + +#define HSE_DIVISOR (STM32L4_HSE_FREQUENCY + 500000) / 1000000 + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: rcc_reset + * + * Description: + * Reset the RCC clock configuration to the default reset state + * + ****************************************************************************/ + +static inline void rcc_reset(void) +{ + uint32_t regval; + + /* Enable the Internal High Speed clock (HSI) */ + + regval = getreg32(STM32L4_RCC_CR); + regval |= RCC_CR_HSION; + putreg32(regval, STM32L4_RCC_CR); + + /* Reset CFGR register */ + + putreg32(0x00000000, STM32L4_RCC_CFGR); + + /* Reset HSION, HSEON, CSSON and PLLON bits */ + + regval = getreg32(STM32L4_RCC_CR); + regval &= ~(RCC_CR_HSION | RCC_CR_HSEON | RCC_CR_CSSON | RCC_CR_PLLON); + putreg32(regval, STM32L4_RCC_CR); + + /* Reset PLLCFGR register to reset default */ + + putreg32(RCC_PLLCFG_RESET, STM32L4_RCC_PLLCFG); + + /* Reset HSEBYP bit */ + + regval = getreg32(STM32L4_RCC_CR); + regval &= ~RCC_CR_HSEBYP; + putreg32(regval, STM32L4_RCC_CR); + + /* Disable all interrupts */ + + putreg32(0x00000000, STM32L4_RCC_CIER); +} + +/**************************************************************************** + * Name: rcc_enableahb1 + * + * Description: + * Enable selected AHB1 peripherals + * + ****************************************************************************/ + +static inline void rcc_enableahb1(void) +{ + uint32_t regval; + + /* Set the appropriate bits in the AHB1ENR register to enable the + * selected AHB1 peripherals. + */ + + regval = getreg32(STM32L4_RCC_AHB1ENR); + +#ifdef CONFIG_STM32L4_DMA1 + /* DMA 1 clock enable */ + + regval |= RCC_AHB1ENR_DMA1EN; +#endif + +#ifdef CONFIG_STM32L4_DMA2 + /* DMA 2 clock enable */ + + regval |= RCC_AHB1ENR_DMA2EN; +#endif + +#ifdef CONFIG_STM32L4_CRC + /* CRC clock enable */ + + regval |= RCC_AHB1ENR_CRCEN; +#endif + +#ifdef CONFIG_STM32L4_TSC + /* TSC clock enable */ + + regval |= RCC_AHB1ENR_TSCEN; +#endif + + putreg32(regval, STM32L4_RCC_AHB1ENR); /* Enable peripherals */ +} + +/**************************************************************************** + * Name: rcc_enableahb2 + * + * Description: + * Enable selected AHB2 peripherals + * + ****************************************************************************/ + +static inline void rcc_enableahb2(void) +{ + uint32_t regval; + + /* Set the appropriate bits in the AHB2ENR register to enabled the + * selected AHB2 peripherals. + */ + + regval = getreg32(STM32L4_RCC_AHB2ENR); + + /* Enable GPIOA, GPIOB, .... GPIOH */ + +#if STM32L4_NPORTS > 0 + regval |= (RCC_AHB2ENR_GPIOAEN +#if STM32L4_NPORTS > 1 + | RCC_AHB2ENR_GPIOBEN +#endif +#if STM32L4_NPORTS > 2 + | RCC_AHB2ENR_GPIOCEN +#endif +#if STM32L4_NPORTS > 3 + | RCC_AHB2ENR_GPIODEN +#endif +#if STM32L4_NPORTS > 4 + | RCC_AHB2ENR_GPIOEEN +#endif +#if STM32L4_NPORTS > 5 + | RCC_AHB2ENR_GPIOFEN +#endif +#if STM32L4_NPORTS > 6 + | RCC_AHB2ENR_GPIOGEN +#endif +#if STM32L4_NPORTS > 7 + | RCC_AHB2ENR_GPIOHEN +#endif + ); +#endif + +#ifdef CONFIG_STM32L4_OTGFS + /* USB OTG FS clock enable */ + + regval |= RCC_AHB2ENR_OTGFSEN; +#endif + +#if defined(CONFIG_STM32L4_ADC1) || defined(CONFIG_STM32L4_ADC2) || defined(CONFIG_STM32L4_ADC3) + /* ADC clock enable */ + + regval |= RCC_AHB2ENR_ADCEN; +#endif + +#ifdef CONFIG_STM32L4_RNG + /* Random number generator clock enable */ + + regval |= RCC_AHB2ENR_RNGEN; +#endif + + putreg32(regval, STM32L4_RCC_AHB2ENR); /* Enable peripherals */ +} + +/**************************************************************************** + * Name: rcc_enableahb3 + * + * Description: + * Enable selected AHB3 peripherals + * + ****************************************************************************/ + +static inline void rcc_enableahb3(void) +{ + uint32_t regval; + + /* Set the appropriate bits in the AHB3ENR register to enabled the + * selected AHB3 peripherals. + */ + + regval = getreg32(STM32L4_RCC_AHB3ENR); + +#ifdef CONFIG_STM32L4_FSMC + /* Flexible static memory controller module clock enable */ + + regval |= RCC_AHB3ENR_FSMCEN; +#endif + + +#ifdef CONFIG_STM32L4_QSPI + /* QuadSPI module clock enable */ + + regval |= RCC_AHB3ENR_QSPIEN; +#endif + + putreg32(regval, STM32L4_RCC_AHB3ENR); /* Enable peripherals */ +} + +/**************************************************************************** + * Name: rcc_enableapb1 + * + * Description: + * Enable selected APB1 peripherals + * + ****************************************************************************/ + +static inline void rcc_enableapb1(void) +{ + uint32_t regval; + + /* Set the appropriate bits in the APB1ENR register to enabled the + * selected APB1 peripherals. + */ + + regval = getreg32(STM32L4_RCC_APB1ENR1); + +#ifdef CONFIG_STM32L4_TIM2 + /* TIM2 clock enable */ + + regval |= RCC_APB1ENR1_TIM2EN; +#endif + +#ifdef CONFIG_STM32L4_TIM3 + /* TIM3 clock enable */ + + regval |= RCC_APB1ENR1_TIM3EN; +#endif + +#ifdef CONFIG_STM32L4_TIM4 + /* TIM4 clock enable */ + + regval |= RCC_APB1ENR1_TIM4EN; +#endif + +#ifdef CONFIG_STM32L4_TIM5 + /* TIM5 clock enable */ + + regval |= RCC_APB1ENR1_TIM5EN; +#endif + +#ifdef CONFIG_STM32L4_TIM6 + /* TIM6 clock enable */ + + regval |= RCC_APB1ENR1_TIM6EN; +#endif + +#ifdef CONFIG_STM32L4_TIM7 + /* TIM7 clock enable */ + + regval |= RCC_APB1ENR1_TIM7EN; +#endif + +#ifdef CONFIG_STM32L4_SPI2 + /* SPI2 clock enable */ + + regval |= RCC_APB1ENR1_SPI2EN; +#endif + +#ifdef CONFIG_STM32L4_SPI3 + /* SPI3 clock enable */ + + regval |= RCC_APB1ENR1_SPI3EN; +#endif + +#ifdef CONFIG_STM32L4_USART2 + /* USART 2 clock enable */ + + regval |= RCC_APB1ENR1_USART2EN; +#endif + +#ifdef CONFIG_STM32L4_USART3 + /* USART3 clock enable */ + + regval |= RCC_APB1ENR1_USART3EN; +#endif + +#ifdef CONFIG_STM32L4_UART4 + /* UART4 clock enable */ + + regval |= RCC_APB1ENR1_UART4EN; +#endif + +#ifdef CONFIG_STM32L4_UART5 + /* UART5 clock enable */ + + regval |= RCC_APB1ENR1_UART5EN; +#endif + +#ifdef CONFIG_STM32L4_I2C1 + /* I2C1 clock enable */ + + regval |= RCC_APB1ENR1_I2C1EN; +#endif + +#ifdef CONFIG_STM32L4_I2C2 + /* I2C2 clock enable */ + + regval |= RCC_APB1ENR1_I2C2EN; +#endif + +#ifdef CONFIG_STM32L4_I2C3 + /* I2C3 clock enable */ + + regval |= RCC_APB1ENR1_I2C3EN; +#endif + +#ifdef CONFIG_STM32L4_CAN1 + /* CAN 1 clock enable */ + + regval |= RCC_APB1ENR1_CAN1EN; +#endif + + /* Power interface clock enable. The PWR block is always enabled so that + * we can set the internal voltage regulator as required. + */ + + regval |= RCC_APB1ENR1_PWREN; + +#if defined (CONFIG_STM32L4_DAC1) || defined(CONFIG_STM32L4_DAC2) + /* DAC interface clock enable */ + + regval |= RCC_APB1ENR1_DACEN; +#endif + +#ifdef CONFIG_STM32L4_OPAMP + /* OPAMP clock enable */ + + regval |= RCC_APB1ENR1_OPAMPEN; +#endif + +#ifdef CONFIG_STM32L4_LPTIM1 + /* Low power timer 1 clock enable */ + + regval |= RCC_APB1ENR1_LPTIM1EN; +#endif + + putreg32(regval, STM32L4_RCC_APB1ENR1); /* Enable peripherals */ + + /* Second APB1 register */ + + regval = getreg32(STM32L4_RCC_APB1ENR2); + +#ifdef CONFIG_STM32L4_LPUART1 + /* Low power uart clock enable */ + + regval |= RCC_APB1ENR2_LPUART1EN; +#endif + +#ifdef CONFIG_STM32L4_SWPMI + /* Single-wire protocol master clock enable */ + + regval |= RCC_APB1ENR2_SWPMI1EN; +#endif + +#ifdef CONFIG_STM32L4_LPTIM2 + /* Low power timer 2 clock enable */ + + regval |= RCC_APB1ENR2_LPTIM2EN; +#endif + + putreg32(regval, STM32L4_RCC_APB1ENR2); /* Enable peripherals */ +} + +/**************************************************************************** + * Name: rcc_enableapb2 + * + * Description: + * Enable selected APB2 peripherals + * + ****************************************************************************/ + +static inline void rcc_enableapb2(void) +{ + uint32_t regval; + + /* Set the appropriate bits in the APB2ENR register to enabled the + * selected APB2 peripherals. + */ + + regval = getreg32(STM32L4_RCC_APB2ENR); + +#ifdef CONFIG_STM32L4_SYSCFG + /* System configuration controller clock enable */ + + regval |= RCC_APB2ENR_SYSCFGEN; +#endif + +#ifdef CONFIG_STM32L4_FIREWALL + /* Firewall clock enable */ + + regval |= RCC_APB2ENR_FWEN; +#endif + +#ifdef CONFIG_STM32L4_SDMMC + /* SDMMC clock enable */ + + regval |= RCC_APB2ENR_SDMMCEN; +#endif + +#ifdef CONFIG_STM32L4_TIM1 + /* TIM1 clock enable */ + + regval |= RCC_APB2ENR_TIM1EN; +#endif + +#ifdef CONFIG_STM32L4_SPI1 + /* SPI1 clock enable */ + + regval |= RCC_APB2ENR_SPI1EN; +#endif + +#ifdef CONFIG_STM32L4_TIM8 + /* TIM8 clock enable */ + + regval |= RCC_APB2ENR_TIM8EN; +#endif + +#ifdef CONFIG_STM32L4_USART1 + /* USART1 clock enable */ + + regval |= RCC_APB2ENR_USART1EN; +#endif + +#ifdef CONFIG_STM32L4_TIM15 + /* TIM15 clock enable */ + + regval |= RCC_APB2ENR_TIM15EN; +#endif + +#ifdef CONFIG_STM32L4_TIM16 + /* TIM16 clock enable */ + + regval |= RCC_APB2ENR_TIM16EN; +#endif + +#ifdef CONFIG_STM32L4_TIM17 + /* TIM17 clock enable */ + + regval |= RCC_APB2ENR_TIM17EN; +#endif + +#ifdef CONFIG_STM32L4_SAI1 + /* SAI1 clock enable */ + + regval |= RCC_APB2ENR_SAI1EN; +#endif + +#ifdef CONFIG_STM32L4_SAI2 + /* SAI2 clock enable */ + + regval |= RCC_APB2ENR_SAI2EN; +#endif + +#ifdef CONFIG_STM32L4_DFSDM1 + /* DFSDM clock enable */ + + regval |= RCC_APB2ENR_DFSDMEN; +#endif + + putreg32(regval, STM32L4_RCC_APB2ENR); /* Enable peripherals */ +} + +/**************************************************************************** + * Name: stm32l4_stdclockconfig + * + * Description: + * Called to change to new clock based on settings in board.h + * + * NOTE: This logic would need to be extended if you need to select low- + * power clocking modes! + ****************************************************************************/ + +#ifndef CONFIG_ARCH_BOARD_STM32L4_CUSTOM_CLOCKCONFIG +static void stm32l4_stdclockconfig(void) +{ + uint32_t regval; + volatile int32_t timeout; + +#ifdef STM32L4_BOARD_USEHSI + /* Enable Internal High-Speed Clock (HSI) */ + + regval = getreg32(STM32L4_RCC_CR); + regval |= RCC_CR_HSION; /* Enable HSI */ + putreg32(regval, STM32L4_RCC_CR); + + /* Wait until the HSI is ready (or until a timeout elapsed) */ + + for (timeout = HSIRDY_TIMEOUT; timeout > 0; timeout--) + { + /* Check if the HSIRDY flag is the set in the CR */ + + if ((getreg32(STM32L4_RCC_CR) & RCC_CR_HSIRDY) != 0) + { + /* If so, then break-out with timeout > 0 */ + + break; + } + } + +#elif defined(STM32L4_BOARD_USEMSI) + /* Enable Internal Multi-Speed Clock (MSI) */ + + /* Wait until the MSI is either off or ready (or until a timeout elapsed) */ + + for (timeout = MSIRDY_TIMEOUT; timeout > 0; timeout--) + { + if ((regval = getreg32(STM32L4_RCC_CR)), (regval & RCC_CR_MSIRDY) || ~(regval & RCC_CR_MSION)) + { + /* If so, then break-out with timeout > 0 */ + + break; + } + } + + /* setting MSIRANGE */ + + regval = getreg32(STM32L4_RCC_CR); + regval |= (STM32L4_BOARD_MSIRANGE | RCC_CR_MSION); /* Enable MSI and frequency */ + putreg32(regval, STM32L4_RCC_CR); + + /* Wait until the MSI is ready (or until a timeout elapsed) */ + + for (timeout = MSIRDY_TIMEOUT; timeout > 0; timeout--) + { + /* Check if the MSIRDY flag is the set in the CR */ + + if ((getreg32(STM32L4_RCC_CR) & RCC_CR_MSIRDY) != 0) + { + /* If so, then break-out with timeout > 0 */ + + break; + } + } + +#elif defined(STM32L4_BOARD_USEHSE) + /* Enable External High-Speed Clock (HSE) */ + + regval = getreg32(STM32L4_RCC_CR); + regval |= RCC_CR_HSEON; /* Enable HSE */ + putreg32(regval, STM32L4_RCC_CR); + + /* Wait until the HSE is ready (or until a timeout elapsed) */ + + for (timeout = HSERDY_TIMEOUT; timeout > 0; timeout--) + { + /* Check if the HSERDY flag is the set in the CR */ + + if ((getreg32(STM32L4_RCC_CR) & RCC_CR_HSERDY) != 0) + { + /* If so, then break-out with timeout > 0 */ + + break; + } + } +#else + +# error stm32l4_stdclockconfig(), must have one of STM32L4_BOARD_USEHSI, STM32L4_BOARD_USEMSI, STM32L4_BOARD_USEHSE defined + +#endif + + /* Check for a timeout. If this timeout occurs, then we are hosed. We + * have no real back-up plan, although the following logic makes it look + * as though we do. + */ + + if (timeout > 0) + { +#warning todo: regulator voltage according to clock freq +#if 0 + /* Ensure Power control is enabled before modifying it. */ + + regval = getreg32(STM32L4_RCC_APB1ENR); + regval |= RCC_APB1ENR_PWREN; + putreg32(regval, STM32L4_RCC_APB1ENR); + + /* Select regulator voltage output Scale 1 mode to support system + * frequencies up to 168 MHz. + */ + + regval = getreg32(STM32L4_PWR_CR); + regval &= ~PWR_CR_VOS_MASK; + regval |= PWR_CR_VOS_SCALE_1; + putreg32(regval, STM32L4_PWR_CR); +#endif + + /* Set the HCLK source/divider */ + + regval = getreg32(STM32L4_RCC_CFGR); + regval &= ~RCC_CFGR_HPRE_MASK; + regval |= STM32L4_RCC_CFGR_HPRE; + putreg32(regval, STM32L4_RCC_CFGR); + + /* Set the PCLK2 divider */ + + regval = getreg32(STM32L4_RCC_CFGR); + regval &= ~RCC_CFGR_PPRE2_MASK; + regval |= STM32L4_RCC_CFGR_PPRE2; + putreg32(regval, STM32L4_RCC_CFGR); + + /* Set the PCLK1 divider */ + + regval = getreg32(STM32L4_RCC_CFGR); + regval &= ~RCC_CFGR_PPRE1_MASK; + regval |= STM32L4_RCC_CFGR_PPRE1; + putreg32(regval, STM32L4_RCC_CFGR); + +#ifdef CONFIG_RTC_HSECLOCK + /* Set the RTC clock divisor */ + + regval = getreg32(STM32L4_RCC_CFGR); + regval &= ~RCC_CFGR_RTCPRE_MASK; + regval |= RCC_CFGR_RTCPRE(HSE_DIVISOR); + putreg32(regval, STM32L4_RCC_CFGR); +#endif + + /* Set the PLL source and main divider */ + + regval = getreg32(STM32L4_RCC_PLLCFG); + + /* Configure Main PLL */ + + /* Set the PLL dividers and multipliers to configure the main PLL */ + + regval = (STM32L4_PLLCFG_PLLM | STM32L4_PLLCFG_PLLN | STM32L4_PLLCFG_PLLP + | STM32L4_PLLCFG_PLLQ | STM32L4_PLLCFG_PLLR); + +#ifdef STM32L4_PLLCFG_PLLP_ENABLED + regval |= RCC_PLLCFG_PLLPEN; +#endif +#ifdef STM32L4_PLLCFG_PLLQ_ENABLED + regval |= RCC_PLLCFG_PLLQEN; +#endif +#ifdef STM32L4_PLLCFG_PLLR_ENABLED + regval |= RCC_PLLCFG_PLLREN; +#endif + + /* XXX The choice of clock source to PLL (all three) is independent + * of the sys clock source choice, review the STM32L4_BOARD_USEHSI + * name; probably split it into two, one for PLL source and one + * for sys clock source. + */ + +#ifdef STM32L4_BOARD_USEHSI + regval |= RCC_PLLCFG_PLLSRC_HSI; +#elif defined(STM32L4_BOARD_USEMSI) + regval |= RCC_PLLCFG_PLLSRC_MSI; +#else /* if STM32L4_BOARD_USEHSE */ + regval |= RCC_PLLCFG_PLLSRC_HSE; +#endif + + putreg32(regval, STM32L4_RCC_PLLCFG); + + /* Enable the main PLL */ + + regval = getreg32(STM32L4_RCC_CR); + regval |= RCC_CR_PLLON; + putreg32(regval, STM32L4_RCC_CR); + + /* Wait until the PLL is ready */ + + while ((getreg32(STM32L4_RCC_CR) & RCC_CR_PLLRDY) == 0) + { + } + +#ifdef CONFIG_STM32L4_SAI1PLL + /* Configure SAI1 PLL */ + + regval = getreg32(STM32L4_RCC_PLLSAI1CFG); + + /* Set the PLL dividers and multipliers to configure the SAI1 PLL */ + + regval = (STM32L4_PLLSAI1CFG_PLLN | STM32L4_PLLSAI1CFG_PLLP + | STM32L4_PLLSAI1CFG_PLLQ | STM32L4_PLLSAI1CFG_PLLR); + +#ifdef STM32L4_PLLSAI1CFG_PLLP_ENABLED + regval |= RCC_PLLSAI1CFG_PLLPEN; +#endif +#ifdef STM32L4_PLLSAI1CFG_PLLQ_ENABLED + regval |= RCC_PLLSAI1CFG_PLLQEN; +#endif +#ifdef STM32L4_PLLSAI1CFG_PLLR_ENABLED + regval |= RCC_PLLSAI1CFG_PLLREN; +#endif + + putreg32(regval, STM32L4_RCC_PLLSAI1CFG); + + /* Enable the SAI1 PLL */ + + regval = getreg32(STM32L4_RCC_CR); + regval |= RCC_CR_PLLSAI1ON; + putreg32(regval, STM32L4_RCC_CR); + + /* Wait until the PLL is ready */ + + while ((getreg32(STM32L4_RCC_CR) & RCC_CR_PLLSAI1RDY) == 0) + { + } +#endif + +#ifdef CONFIG_STM32L4_SAI2PLL + /* Configure SAI2 PLL */ + + regval = getreg32(STM32L4_RCC_PLLSAI2CFG); + + /* Set the PLL dividers and multipliers to configure the SAI2 PLL */ + + regval = (STM32L4_PLLSAI2CFG_PLLN | STM32L4_PLLSAI2CFG_PLLP | + STM32L4_PLLSAI2CFG_PLLR); + +#ifdef STM32L4_PLLSAI2CFG_PLLP_ENABLED + regval |= RCC_PLLSAI2CFG_PLLPEN; +#endif +#ifdef STM32L4_PLLSAI2CFG_PLLR_ENABLED + regval |= RCC_PLLSAI2CFG_PLLREN; +#endif + + putreg32(regval, STM32L4_RCC_PLLSAI2CFG); + + /* Enable the SAI2 PLL */ + + regval = getreg32(STM32L4_RCC_CR); + regval |= RCC_CR_PLLSAI2ON; + putreg32(regval, STM32L4_RCC_CR); + + /* Wait until the PLL is ready */ + + while ((getreg32(STM32L4_RCC_CR) & RCC_CR_PLLSAI2RDY) == 0) + { + } +#endif + + /* Enable FLASH prefetch, instruction cache, data cache, and 4 wait states */ + +#ifdef CONFIG_STM32L4_FLASH_PREFETCH + regval = (FLASH_ACR_LATENCY_4 | FLASH_ACR_ICEN | FLASH_ACR_DCEN | FLASH_ACR_PRFTEN); +#else + regval = (FLASH_ACR_LATENCY_4 | FLASH_ACR_ICEN | FLASH_ACR_DCEN); +#endif + putreg32(regval, STM32L4_FLASH_ACR); + + /* Select the main PLL as system clock source */ + + regval = getreg32(STM32L4_RCC_CFGR); + regval &= ~RCC_CFGR_SW_MASK; + regval |= RCC_CFGR_SW_PLL; + putreg32(regval, STM32L4_RCC_CFGR); + + /* Wait until the PLL source is used as the system clock source */ + + while ((getreg32(STM32L4_RCC_CFGR) & RCC_CFGR_SWS_MASK) != RCC_CFGR_SWS_PLL) + { + } + +#if defined(CONFIG_STM32L4_IWDG) || defined(CONFIG_RTC_LSICLOCK) + /* Low speed internal clock source LSI */ + + stm32l4_rcc_enablelsi(); +#endif + +#if defined(STM32L4_USE_LSE) + /* Low speed external clock source LSE + * + * TODO: There is another case where the LSE needs to + * be enabled: if the MCO1 pin selects LSE as source. + * XXX and other cases, like automatic trimming of MSI for USB use + */ + + /* ensure Power control is enabled since it is indirectly required + * to alter the LSE parameters. + */ + stm32l4_pwr_enableclk(true); + + /* XXX other LSE settings must be made before turning on the oscillator + * and we need to ensure it is first off before doing so. + */ + + /* Turn on the LSE oscillator + * XXX this will almost surely get moved since we also want to use + * this for automatically trimming MSI, etc. + */ + + stm32l4_rcc_enablelse(); + +# if defined(STM32L4_BOARD_USEMSI) + /* Now that LSE is up, auto trim the MSI */ + + regval = getreg32(STM32L4_RCC_CR); + regval |= RCC_CR_MSIPLLEN; + putreg32(regval, STM32L4_RCC_CR); +# endif +#endif + +#if defined(STM32L4_USE_CLK48) + /* XXX sanity if sdmmc1 or usb or rng, then we need to set the clk48 source + * and then we can also do away with STM32L4_USE_CLK48, and give better + * warning messages + * + * XXX sanity if our STM32L4_CLK48_SEL is YYY then we need to have already + * enabled ZZZ + */ + + regval = getreg32(STM32L4_RCC_CCIPR); + regval &= RCC_CCIPR_CLK48SEL_MASK; + regval |= STM32L4_CLK48_SEL; + putreg32(regval, STM32L4_RCC_CCIPR); +#endif + } +} +#endif + +/**************************************************************************** + * Name: rcc_enableperipherals + ****************************************************************************/ + +static inline void rcc_enableperipherals(void) +{ + rcc_enableahb1(); + rcc_enableahb2(); + rcc_enableahb3(); + rcc_enableapb1(); + rcc_enableapb2(); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ diff --git a/arch/arm/src/stm32l4/stm32l4x6xx_rcc.c b/arch/arm/src/stm32l4/stm32l4x6xx_rcc.c index 3b17417740..08dd4f4b30 100644 --- a/arch/arm/src/stm32l4/stm32l4x6xx_rcc.c +++ b/arch/arm/src/stm32l4/stm32l4x6xx_rcc.c @@ -129,7 +129,7 @@ static inline void rcc_enableahb1(void) { uint32_t regval; - /* Set the appropriate bits in the AHB1ENR register to enabled the + /* Set the appropriate bits in the AHB1ENR register to enable the * selected AHB1 peripherals. */ -- GitLab From 596fe6885412f85b901580d8fbd2def92c7098d6 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 8 Jun 2017 10:34:26 -0600 Subject: [PATCH 939/990] STM32L4: Add STM32L475 OTGFS header file. Not fully reviewed. --- arch/arm/src/stm32l4/chip/stm32l4x5xx_otgfs.h | 945 ++++++++++++++++++ arch/arm/src/stm32l4/stm32l4_otgfs.h | 10 +- arch/arm/src/stm32l4/stm32l4_usbhost.h | 9 +- 3 files changed, 961 insertions(+), 3 deletions(-) create mode 100644 arch/arm/src/stm32l4/chip/stm32l4x5xx_otgfs.h diff --git a/arch/arm/src/stm32l4/chip/stm32l4x5xx_otgfs.h b/arch/arm/src/stm32l4/chip/stm32l4x5xx_otgfs.h new file mode 100644 index 0000000000..ce7d8dd80d --- /dev/null +++ b/arch/arm/src/stm32l4/chip/stm32l4x5xx_otgfs.h @@ -0,0 +1,945 @@ +/**************************************************************************************************** + * arch/arm/src/stm32l4/chip/stm32l4x5xx_otgfs.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Copyright (C) 2016 Omni Hoverboards Inc. All rights reserved. + * Author: Gregory Nutt + * Paul Alexander Patience + * dev@ziggurat29.com + * + * 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 __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X5XX_OTGFS_H +#define __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X5XX_OTGFS_H + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ +/**************************************************************************************************** + * Pre-processor Definitions + ****************************************************************************************************/ +/* General definitions */ + +#define OTGFS_EPTYPE_CTRL (0) /* Control */ +#define OTGFS_EPTYPE_ISOC (1) /* Isochronous */ +#define OTGFS_EPTYPE_BULK (2) /* Bulk */ +#define OTGFS_EPTYPE_INTR (3) /* Interrupt */ + +#define OTGFS_PID_DATA0 (0) +#define OTGFS_PID_DATA2 (1) +#define OTGFS_PID_DATA1 (2) +#define OTGFS_PID_MDATA (3) /* Non-control */ +#define OTGFS_PID_SETUP (3) /* Control */ + +/* Register Offsets *********************************************************************************/ +/* Core global control and status registers */ + +#define STM32L4_OTGFS_GOTGCTL_OFFSET 0x0000 /* Control and status register */ +#define STM32L4_OTGFS_GOTGINT_OFFSET 0x0004 /* Interrupt register */ +#define STM32L4_OTGFS_GAHBCFG_OFFSET 0x0008 /* AHB configuration register */ +#define STM32L4_OTGFS_GUSBCFG_OFFSET 0x000c /* USB configuration register */ +#define STM32L4_OTGFS_GRSTCTL_OFFSET 0x0010 /* Reset register */ +#define STM32L4_OTGFS_GINTSTS_OFFSET 0x0014 /* Core interrupt register */ +#define STM32L4_OTGFS_GINTMSK_OFFSET 0x0018 /* Interrupt mask register */ +#define STM32L4_OTGFS_GRXSTSR_OFFSET 0x001c /* Receive status debug read/OTG status read register */ +#define STM32L4_OTGFS_GRXSTSP_OFFSET 0x0020 /* Receive status debug read/OTG status pop register */ +#define STM32L4_OTGFS_GRXFSIZ_OFFSET 0x0024 /* Receive FIFO size register */ +#define STM32L4_OTGFS_HNPTXFSIZ_OFFSET 0x0028 /* Host non-periodic transmit FIFO size register */ +#define STM32L4_OTGFS_DIEPTXF0_OFFSET 0x0028 /* Endpoint 0 Transmit FIFO size */ +#define STM32L4_OTGFS_HNPTXSTS_OFFSET 0x002c /* Non-periodic transmit FIFO/queue status register */ +#define STM32L4_OTGFS_GCCFG_OFFSET 0x0038 /* General core configuration register */ +#define STM32L4_OTGFS_CID_OFFSET 0x003c /* Core ID register */ +#define STM32L4_OTGFS_GLPMCFG_OFFSET 0x0054 /* LPM configuration register */ +#define STM32L4_OTGFS_GPWRDN_OFFSET 0x0058 /* Power down register */ +#define STM32L4_OTGFS_GADPCTL_OFSSET 0x005c /* ADP timer, control and status register */ +#define STM32L4_OTGFS_HPTXFSIZ_OFFSET 0x0100 /* Host periodic transmit FIFO size register */ + +#define STM32L4_OTGFS_DIEPTXF_OFFSET(n) (104+(((n)-1) << 2)) + +/* Host-mode control and status registers */ + +#define STM32L4_OTGFS_HCFG_OFFSET 0x0400 /* Host configuration register */ +#define STM32L4_OTGFS_HFIR_OFFSET 0x0404 /* Host frame interval register */ +#define STM32L4_OTGFS_HFNUM_OFFSET 0x0408 /* Host frame number/frame time remaining register */ +#define STM32L4_OTGFS_HPTXSTS_OFFSET 0x0410 /* Host periodic transmit FIFO/queue status register */ +#define STM32L4_OTGFS_HAINT_OFFSET 0x0414 /* Host all channels interrupt register */ +#define STM32L4_OTGFS_HAINTMSK_OFFSET 0x0418 /* Host all channels interrupt mask register */ +#define STM32L4_OTGFS_HPRT_OFFSET 0x0440 /* Host port control and status register */ + +#define STM32L4_OTGFS_CHAN_OFFSET(n) (0x500 + ((n) << 5) +#define STM32L4_OTGFS_HCCHAR_CHOFFSET 0x0000 /* Host channel characteristics register */ +#define STM32L4_OTGFS_HCINT_CHOFFSET 0x0008 /* Host channel interrupt register */ +#define STM32L4_OTGFS_HCINTMSK_CHOFFSET 0x000c /* Host channel interrupt mask register */ +#define STM32L4_OTGFS_HCTSIZ_CHOFFSET 0x0010 /* Host channel interrupt register */ + +#define STM32L4_OTGFS_HCCHAR_OFFSET(n) (0x500 + ((n) << 5)) + +#define STM32L4_OTGFS_HCINT_OFFSET(n) (0x508 + ((n) << 5)) + +#define STM32L4_OTGFS_HCINTMSK_OFFSET(n) (0x50c + ((n) << 5)) + +#define STM32L4_OTGFS_HCTSIZ_OFFSET(n) (0x510 + ((n) << 5)) + +/* Device-mode control and status registers */ + +#define STM32L4_OTGFS_DCFG_OFFSET 0x0800 /* Device configuration register */ +#define STM32L4_OTGFS_DCTL_OFFSET 0x0804 /* Device control register */ +#define STM32L4_OTGFS_DSTS_OFFSET 0x0808 /* Device status register */ +#define STM32L4_OTGFS_DIEPMSK_OFFSET 0x0810 /* Device IN endpoint common interrupt mask register */ +#define STM32L4_OTGFS_DOEPMSK_OFFSET 0x0814 /* Device OUT endpoint common interrupt mask register */ +#define STM32L4_OTGFS_DAINT_OFFSET 0x0818 /* Device all endpoints interrupt register */ +#define STM32L4_OTGFS_DAINTMSK_OFFSET 0x081c /* All endpoints interrupt mask register */ +#define STM32L4_OTGFS_DVBUSDIS_OFFSET 0x0828 /* Device VBUS discharge time register */ +#define STM32L4_OTGFS_DVBUSPULSE_OFFSET 0x082c /* Device VBUS pulsing time register */ +#define STM32L4_OTGFS_DIEPEMPMSK_OFFSET 0x0834 /* Device IN endpoint FIFO empty interrupt mask register */ + +#define STM32L4_OTGFS_DIEP_OFFSET(n) (0x0900 + ((n) << 5)) +#define STM32L4_OTGFS_DIEPCTL_EPOFFSET 0x0000 /* Device endpoint control register */ +#define STM32L4_OTGFS_DIEPINT_EPOFFSET 0x0008 /* Device endpoint interrupt register */ +#define STM32L4_OTGFS_DIEPTSIZ_EPOFFSET 0x0010 /* Device IN endpoint transfer size register */ +#define STM32L4_OTGFS_DTXFSTS_EPOFFSET 0x0018 /* Device IN endpoint transmit FIFO status register */ + +#define STM32L4_OTGFS_DIEPCTL_OFFSET(n) (0x0900 + ((n) << 5)) + +#define STM32L4_OTGFS_DIEPINT_OFFSET(n) (0x0908 + ((n) << 5)) + +#define STM32L4_OTGFS_DIEPTSIZ_OFFSET(n) (0x910 + ((n) << 5)) + +#define STM32L4_OTGFS_DTXFSTS_OFFSET(n) (0x0918 + ((n) << 5)) + +#define STM32L4_OTGFS_DOEP_OFFSET(n) (0x0b00 + ((n) << 5)) +#define STM32L4_OTGFS_DOEPCTL_EPOFFSET 0x0000 /* Device control OUT endpoint 0 control register */ +#define STM32L4_OTGFS_DOEPINT_EPOFFSET 0x0008 /* Device endpoint-x interrupt register */ +#define STM32L4_OTGFS_DOEPTSIZ_EPOFFSET 0x0010 /* Device endpoint OUT transfer size register */ + +#define STM32L4_OTGFS_DOEPCTL_OFFSET(n) (0x0b00 + ((n) << 5)) + +#define STM32L4_OTGFS_DOEPINT_OFFSET(n) (0x0b08 + ((n) << 5)) + +#define STM32L4_OTGFS_DOEPTSIZ_OFFSET(n) (0x0b10 + ((n) << 5)) + +/* Power and clock gating registers */ + +#define STM32L4_OTGFS_PCGCCTL_OFFSET 0x0e00 /* Power and clock gating control register */ + +/* Data FIFO (DFIFO) access registers */ + +#define STM32L4_OTGFS_DFIFO_DEP_OFFSET(n) (0x1000 + ((n) << 12)) +#define STM32L4_OTGFS_DFIFO_HCH_OFFSET(n) (0x1000 + ((n) << 12)) + +/* Register Addresses *******************************************************************************/ + +#define STM32L4_OTGFS_GOTGCTL (STM32L4_OTGFS_BASE+STM32L4_OTGFS_GOTGCTL_OFFSET) +#define STM32L4_OTGFS_GOTGINT (STM32L4_OTGFS_BASE+STM32L4_OTGFS_GOTGINT_OFFSET) +#define STM32L4_OTGFS_GAHBCFG (STM32L4_OTGFS_BASE+STM32L4_OTGFS_GAHBCFG_OFFSET) +#define STM32L4_OTGFS_GUSBCFG (STM32L4_OTGFS_BASE+STM32L4_OTGFS_GUSBCFG_OFFSET) +#define STM32L4_OTGFS_GRSTCTL (STM32L4_OTGFS_BASE+STM32L4_OTGFS_GRSTCTL_OFFSET) +#define STM32L4_OTGFS_GINTSTS (STM32L4_OTGFS_BASE+STM32L4_OTGFS_GINTSTS_OFFSET) +#define STM32L4_OTGFS_GINTMSK (STM32L4_OTGFS_BASE+STM32L4_OTGFS_GINTMSK_OFFSET) +#define STM32L4_OTGFS_GRXSTSR (STM32L4_OTGFS_BASE+STM32L4_OTGFS_GRXSTSR_OFFSET) +#define STM32L4_OTGFS_GRXSTSP (STM32L4_OTGFS_BASE+STM32L4_OTGFS_GRXSTSP_OFFSET) +#define STM32L4_OTGFS_GRXFSIZ (STM32L4_OTGFS_BASE+STM32L4_OTGFS_GRXFSIZ_OFFSET) +#define STM32L4_OTGFS_HNPTXFSIZ (STM32L4_OTGFS_BASE+STM32L4_OTGFS_HNPTXFSIZ_OFFSET) +#define STM32L4_OTGFS_DIEPTXF0 (STM32L4_OTGFS_BASE+STM32L4_OTGFS_DIEPTXF0_OFFSET) +#define STM32L4_OTGFS_HNPTXSTS (STM32L4_OTGFS_BASE+STM32L4_OTGFS_HNPTXSTS_OFFSET) +#define STM32L4_OTGFS_GCCFG (STM32L4_OTGFS_BASE+STM32L4_OTGFS_GCCFG_OFFSET) +#define STM32L4_OTGFS_CID (STM32L4_OTGFS_BASE+STM32L4_OTGFS_CID_OFFSET) +#define STM32L4_OTGFS_GLPMCFG (STM32L4_OTGFS_BASE+STM32L4_OTGFS_GLPMCFG_OFFSET) +#define STM32L4_OTGFS_GPWRDN (STM32L4_OTGFS_BASE+STM32L4_OTGFS_GPWRDN_OFFSET) +#define STM32L4_OTGFS_GADPCTL (STM32L4_OTGFS_BASE+STM32L4_OTGFS_GADPCTL_OFSSET) +#define STM32L4_OTGFS_HPTXFSIZ (STM32L4_OTGFS_BASE+STM32L4_OTGFS_HPTXFSIZ_OFFSET) + +#define STM32L4_OTGFS_DIEPTXF(n) (STM32L4_OTGFS_BASE+STM32L4_OTGFS_DIEPTXF_OFFSET(n)) + +/* Host-mode control and status registers */ + +#define STM32L4_OTGFS_HCFG (STM32L4_OTGFS_BASE+STM32L4_OTGFS_HCFG_OFFSET) +#define STM32L4_OTGFS_HFIR (STM32L4_OTGFS_BASE+STM32L4_OTGFS_HFIR_OFFSET) +#define STM32L4_OTGFS_HFNUM (STM32L4_OTGFS_BASE+STM32L4_OTGFS_HFNUM_OFFSET) +#define STM32L4_OTGFS_HPTXSTS (STM32L4_OTGFS_BASE+STM32L4_OTGFS_HPTXSTS_OFFSET) +#define STM32L4_OTGFS_HAINT (STM32L4_OTGFS_BASE+STM32L4_OTGFS_HAINT_OFFSET) +#define STM32L4_OTGFS_HAINTMSK (STM32L4_OTGFS_BASE+STM32L4_OTGFS_HAINTMSK_OFFSET) +#define STM32L4_OTGFS_HPRT (STM32L4_OTGFS_BASE+STM32L4_OTGFS_HPRT_OFFSET) + +#define STM32L4_OTGFS_CHAN(n) (STM32L4_OTGFS_BASE+STM32L4_OTGFS_CHAN_OFFSET(n)) + +#define STM32L4_OTGFS_HCCHAR(n) (STM32L4_OTGFS_BASE+STM32L4_OTGFS_HCCHAR_OFFSET(n)) + +#define STM32L4_OTGFS_HCINT(n) (STM32L4_OTGFS_BASE+STM32L4_OTGFS_HCINT_OFFSET(n)) + +#define STM32L4_OTGFS_HCINTMSK(n) (STM32L4_OTGFS_BASE+STM32L4_OTGFS_HCINTMSK_OFFSET(n)) + +#define STM32L4_OTGFS_HCTSIZ(n) (STM32L4_OTGFS_BASE+STM32L4_OTGFS_HCTSIZ_OFFSET(n)) + +/* Device-mode control and status registers */ + +#define STM32L4_OTGFS_DCFG (STM32L4_OTGFS_BASE+STM32L4_OTGFS_DCFG_OFFSET) +#define STM32L4_OTGFS_DCTL (STM32L4_OTGFS_BASE+STM32L4_OTGFS_DCTL_OFFSET) +#define STM32L4_OTGFS_DSTS (STM32L4_OTGFS_BASE+STM32L4_OTGFS_DSTS_OFFSET) +#define STM32L4_OTGFS_DIEPMSK (STM32L4_OTGFS_BASE+STM32L4_OTGFS_DIEPMSK_OFFSET) +#define STM32L4_OTGFS_DOEPMSK (STM32L4_OTGFS_BASE+STM32L4_OTGFS_DOEPMSK_OFFSET) +#define STM32L4_OTGFS_DAINT (STM32L4_OTGFS_BASE+STM32L4_OTGFS_DAINT_OFFSET) +#define STM32L4_OTGFS_DAINTMSK (STM32L4_OTGFS_BASE+STM32L4_OTGFS_DAINTMSK_OFFSET) +#define STM32L4_OTGFS_DVBUSDIS (STM32L4_OTGFS_BASE+STM32L4_OTGFS_DVBUSDIS_OFFSET) +#define STM32L4_OTGFS_DVBUSPULSE (STM32L4_OTGFS_BASE+STM32L4_OTGFS_DVBUSPULSE_OFFSET) +#define STM32L4_OTGFS_DIEPEMPMSK (STM32L4_OTGFS_BASE+STM32L4_OTGFS_DIEPEMPMSK_OFFSET) + +#define STM32L4_OTGFS_DIEP(n) (STM32L4_OTGFS_BASE+STM32L4_OTGFS_DIEP_OFFSET(n)) + +#define STM32L4_OTGFS_DIEPCTL(n) (STM32L4_OTGFS_BASE+STM32L4_OTGFS_DIEPCTL_OFFSET(n)) + +#define STM32L4_OTGFS_DIEPINT(n) (STM32L4_OTGFS_BASE+STM32L4_OTGFS_DIEPINT_OFFSET(n)) + +#define STM32L4_OTGFS_DIEPTSIZ(n) (STM32L4_OTGFS_BASE+STM32L4_OTGFS_DIEPTSIZ_OFFSET(n)) + +#define STM32L4_OTGFS_DTXFSTS(n) (STM32L4_OTGFS_BASE+STM32L4_OTGFS_DTXFSTS_OFFSET(n)) + +#define STM32L4_OTGFS_DOEP(n) (STM32L4_OTGFS_BASE+STM32L4_OTGFS_DOEP_OFFSET(n)) + +#define STM32L4_OTGFS_DOEPCTL(n) (STM32L4_OTGFS_BASE+STM32L4_OTGFS_DOEPCTL_OFFSET(n)) + +#define STM32L4_OTGFS_DOEPINT(n) (STM32L4_OTGFS_BASE+STM32L4_OTGFS_DOEPINT_OFFSET(n)) + +#define STM32L4_OTGFS_DOEPTSIZ(n) (STM32L4_OTGFS_BASE+STM32L4_OTGFS_DOEPTSIZ_OFFSET(n)) + +/* Power and clock gating registers */ + +#define STM32L4_OTGFS_PCGCCTL (STM32L4_OTGFS_BASE+STM32L4_OTGFS_PCGCCTL_OFFSET) + +/* Data FIFO (DFIFO) access registers */ + +#define STM32L4_OTGFS_DFIFO_DEP(n) (STM32L4_OTGFS_BASE+STM32L4_OTGFS_DFIFO_DEP_OFFSET(n)) +#define STM32L4_OTGFS_DFIFO_HCH(n) (STM32L4_OTGFS_BASE+STM32L4_OTGFS_DFIFO_HCH_OFFSET(n)) + + + +/* Register Bitfield Definitions ********************************************************************/ +/* Core global control and status registers */ + +/* Control and status register */ + +#define OTGFS_GOTGCTL_SRQSCS (1 << 0) /* Bit 0: Session request success */ +#define OTGFS_GOTGCTL_SRQ (1 << 1) /* Bit 1: Session request */ + /* Bits 2-7: Reserved */ +#define OTGFS_GOTGCTL_HNGSCS (1 << 8) /* Bit 8: Host negotiation success */ +#define OTGFS_GOTGCTL_HNPRQ (1 << 9) /* Bit 9: HNP request */ +#define OTGFS_GOTGCTL_HSHNPEN (1 << 10) /* Bit 10: host set HNP enable */ +#define OTGFS_GOTGCTL_DHNPEN (1 << 11) /* Bit 11: Device HNP enabled */ +#define OTGFS_GOTGCTL_EHEN (1 << 12) /* Bit 12: Embedded host enable */ + /* Bits 13-15: Reserved, must be kept at reset value */ +#define OTGFS_GOTGCTL_CIDSTS (1 << 16) /* Bit 16: Connector ID status */ +#define OTGFS_GOTGCTL_DBCT (1 << 17) /* Bit 17: Long/short debounce time */ +#define OTGFS_GOTGCTL_ASVLD (1 << 18) /* Bit 18: A-session valid */ +#define OTGFS_GOTGCTL_BSVLD (1 << 19) /* Bit 19: B-session valid */ +#define OTGFS_GOTGCTL_OTGVER (1 << 20) /* Bit 20: OTG version */ + /* Bits 21-31: Reserved, must be kept at reset value */ +/* Interrupt register */ + /* Bits 1:0 Reserved, must be kept at reset value */ +#define OTGFS_GOTGINT_SEDET (1 << 2) /* Bit 2: Session end detected */ + /* Bits 3-7: Reserved, must be kept at reset value */ +#define OTGFS_GOTGINT_SRSSCHG (1 << 8) /* Bit 8: Session request success status change */ +#define OTGFS_GOTGINT_HNSSCHG (1 << 9) /* Bit 9: Host negotiation success status change */ + /* Bits 16:10 Reserved, must be kept at reset value */ +#define OTGFS_GOTGINT_HNGDET (1 << 17) /* Bit 17: Host negotiation detected */ +#define OTGFS_GOTGINT_ADTOCHG (1 << 18) /* Bit 18: A-device timeout change */ +#define OTGFS_GOTGINT_DBCDNE (1 << 19) /* Bit 19: Debounce done */ +#define OTGFS_GOTGINT_IDCHNG (1 << 20) /* Bit 20: Change in ID pin input value */ + /* Bits 21-31: Reserved, must be kept at reset value */ + +/* AHB configuration register */ + +#define OTGFS_GAHBCFG_GINTMSK (1 << 0) /* Bit 0: Global interrupt mask */ + /* Bits 1-6: Reserved, must be kept at reset value */ +#define OTGFS_GAHBCFG_TXFELVL (1 << 7) /* Bit 7: TxFIFO empty level */ +#define OTGFS_GAHBCFG_PTXFELVL (1 << 8) /* Bit 8: Periodic TxFIFO empty level */ + /* Bits 20-31: Reserved, must be kept at reset value */ +/* USB configuration register */ + +#define OTGFS_GUSBCFG_TOCAL_SHIFT (0) /* Bits 0-2: FS timeout calibration */ +#define OTGFS_GUSBCFG_TOCAL_MASK (7 << OTGFS_GUSBCFG_TOCAL_SHIFT) + /* Bits 3-5: Reserved, must be kept at reset value */ +#define OTGFS_GUSBCFG_PHYSEL (1 << 6) /* Bit 6: Full Speed serial transceiver select */ + /* Bit 7: Reserved, must be kept at reset value */ +#define OTGFS_GUSBCFG_SRPCAP (1 << 8) /* Bit 8: SRP-capable */ +#define OTGFS_GUSBCFG_HNPCAP (1 << 9) /* Bit 9: HNP-capable */ +#define OTGFS_GUSBCFG_TRDT_SHIFT (10) /* Bits 10-13: USB turnaround time */ +#define OTGFS_GUSBCFG_TRDT_MASK (15 << OTGFS_GUSBCFG_TRDT_SHIFT) +# define OTGFS_GUSBCFG_TRDT(n) ((n) << OTGFS_GUSBCFG_TRDT_SHIFT) + /* Bits 14-28: Reserved, must be kept at reset value */ +#define OTGFS_GUSBCFG_FHMOD (1 << 29) /* Bit 29: Force host mode */ +#define OTGFS_GUSBCFG_FDMOD (1 << 30) /* Bit 30: Force device mode */ + /* Bit 31: Reserved, must be kept at reset value */ +/* Reset register */ + +#define OTGFS_GRSTCTL_CSRST (1 << 0) /* Bit 0: Core soft reset */ + /* Bit 1 Reserved, must be kept at reset value */ +#define OTGFS_GRSTCTL_FCRST (1 << 2) /* Bit 2: Host frame counter reset */ + /* Bit 3 Reserved, must be kept at reset value */ +#define OTGFS_GRSTCTL_RXFFLSH (1 << 4) /* Bit 4: RxFIFO flush */ +#define OTGFS_GRSTCTL_TXFFLSH (1 << 5) /* Bit 5: TxFIFO flush */ +#define OTGFS_GRSTCTL_TXFNUM_SHIFT (6) /* Bits 6-10: TxFIFO number */ +#define OTGFS_GRSTCTL_TXFNUM_MASK (31 << OTGFS_GRSTCTL_TXFNUM_SHIFT) +# define OTGFS_GRSTCTL_TXFNUM_HNONPER (0 << OTGFS_GRSTCTL_TXFNUM_SHIFT) /* Non-periodic TxFIFO flush in host mode */ +# define OTGFS_GRSTCTL_TXFNUM_HPER (1 << OTGFS_GRSTCTL_TXFNUM_SHIFT) /* Periodic TxFIFO flush in host mode */ +# define OTGFS_GRSTCTL_TXFNUM_HALL (16 << OTGFS_GRSTCTL_TXFNUM_SHIFT) /* Flush all the transmit FIFOs in host mode.*/ +# define OTGFS_GRSTCTL_TXFNUM_D(n) ((n) << OTGFS_GRSTCTL_TXFNUM_SHIFT) /* TXFIFO n flush in device mode, n=0-15 */ +# define OTGFS_GRSTCTL_TXFNUM_DALL (16 << OTGFS_GRSTCTL_TXFNUM_SHIFT) /* Flush all the transmit FIFOs in device mode.*/ + /* Bits 11-30: Reserved, must be kept at reset value */ +#define OTGFS_GRSTCTL_AHBIDL (1 << 31) /* Bit 31: AHB master idle */ + +/* Core interrupt and Interrupt mask registers */ + +#define OTGFS_GINTSTS_CMOD (1 << 0) /* Bit 0: Current mode of operation */ +# define OTGFS_GINTSTS_DEVMODE (0) +# define OTGFS_GINTSTS_HOSTMODE (OTGFS_GINTSTS_CMOD) +#define OTGFS_GINT_MMIS (1 << 1) /* Bit 1: Mode mismatch interrupt */ +#define OTGFS_GINT_OTG (1 << 2) /* Bit 2: OTG interrupt */ +#define OTGFS_GINT_SOF (1 << 3) /* Bit 3: Start of frame */ +#define OTGFS_GINT_RXFLVL (1 << 4) /* Bit 4: RxFIFO non-empty */ +#define OTGFS_GINT_NPTXFE (1 << 5) /* Bit 5: Non-periodic TxFIFO empty */ +#define OTGFS_GINT_GINAKEFF (1 << 6) /* Bit 6: Global IN non-periodic NAK effective */ +#define OTGFS_GINT_GONAKEFF (1 << 7) /* Bit 7: Global OUT NAK effective */ +#define OTGFS_GINT_RES89 (3 << 8) /* Bits 8-9: Reserved, must be kept at reset value */ +#define OTGFS_GINT_ESUSP (1 << 10) /* Bit 10: Early suspend */ +#define OTGFS_GINT_USBSUSP (1 << 11) /* Bit 11: USB suspend */ +#define OTGFS_GINT_USBRST (1 << 12) /* Bit 12: USB reset */ +#define OTGFS_GINT_ENUMDNE (1 << 13) /* Bit 13: Enumeration done */ +#define OTGFS_GINT_ISOODRP (1 << 14) /* Bit 14: Isochronous OUT packet dropped interrupt */ +#define OTGFS_GINT_EOPF (1 << 15) /* Bit 15: End of periodic frame interrupt */ +#define OTGFS_GINT_RES1617 (3 << 16) /* Bits 16-17: Reserved, must be kept at reset value */ +#define OTGFS_GINT_IEP (1 << 18) /* Bit 18: IN endpoint interrupt */ +#define OTGFS_GINT_OEP (1 << 19) /* Bit 19: OUT endpoint interrupt */ +#define OTGFS_GINT_IISOIXFR (1 << 20) /* Bit 20: Incomplete isochronous IN transfer */ +#define OTGFS_GINT_IISOOXFR (1 << 21) /* Bit 21: Incomplete isochronous OUT transfer (device) */ +#define OTGFS_GINT_IPXFR (1 << 21) /* Bit 21: Incomplete periodic transfer (host) */ +#define OTGFS_GINT_RES22 (1 << 22) /* Bit 22: Reserved, must be kept at reset value */ +#define OTGFS_GINT_RSTDET (1 << 23) /* Bit 23: Reset detected interrupt */ +#define OTGFS_GINT_HPRT (1 << 24) /* Bit 24: Host port interrupt */ +#define OTGFS_GINT_HC (1 << 25) /* Bit 25: Host channels interrupt */ +#define OTGFS_GINT_PTXFE (1 << 26) /* Bit 26: Periodic TxFIFO empty */ +#define OTGFS_GINT_LPMINT (1 << 27) /* Bit 27: LPM interrupt */ +#define OTGFS_GINT_CIDSCHG (1 << 28) /* Bit 28: Connector ID status change */ +#define OTGFS_GINT_DISC (1 << 29) /* Bit 29: Disconnect detected interrupt */ +#define OTGFS_GINT_SRQ (1 << 30) /* Bit 30: Session request/new session detected interrupt */ +#define OTGFS_GINT_WKUP (1 << 31) /* Bit 31: Resume/remote wakeup detected interrupt */ + +/* Receive status debug read/OTG status read and pop registers (host mode) */ + +#define OTGFS_GRXSTSH_CHNUM_SHIFT (0) /* Bits 0-3: Channel number */ +#define OTGFS_GRXSTSH_CHNUM_MASK (15 << OTGFS_GRXSTSH_CHNUM_SHIFT) +#define OTGFS_GRXSTSH_BCNT_SHIFT (4) /* Bits 4-14: Byte count */ +#define OTGFS_GRXSTSH_BCNT_MASK (0x7ff << OTGFS_GRXSTSH_BCNT_SHIFT) +#define OTGFS_GRXSTSH_DPID_SHIFT (15) /* Bits 15-16: Data PID */ +#define OTGFS_GRXSTSH_DPID_MASK (3 << OTGFS_GRXSTSH_DPID_SHIFT) +# define OTGFS_GRXSTSH_DPID_DATA0 (0 << OTGFS_GRXSTSH_DPID_SHIFT) +# define OTGFS_GRXSTSH_DPID_DATA2 (1 << OTGFS_GRXSTSH_DPID_SHIFT) +# define OTGFS_GRXSTSH_DPID_DATA1 (2 << OTGFS_GRXSTSH_DPID_SHIFT) +# define OTGFS_GRXSTSH_DPID_MDATA (3 << OTGFS_GRXSTSH_DPID_SHIFT) +#define OTGFS_GRXSTSH_PKTSTS_SHIFT (17) /* Bits 17-20: Packet status */ +#define OTGFS_GRXSTSH_PKTSTS_MASK (15 << OTGFS_GRXSTSH_PKTSTS_SHIFT) +# define OTGFS_GRXSTSH_PKTSTS_INRECVD (2 << OTGFS_GRXSTSH_PKTSTS_SHIFT) /* IN data packet received */ +# define OTGFS_GRXSTSH_PKTSTS_INDONE (3 << OTGFS_GRXSTSH_PKTSTS_SHIFT) /* IN transfer completed */ +# define OTGFS_GRXSTSH_PKTSTS_DTOGERR (5 << OTGFS_GRXSTSH_PKTSTS_SHIFT) /* Data toggle error */ +# define OTGFS_GRXSTSH_PKTSTS_HALTED (7 << OTGFS_GRXSTSH_PKTSTS_SHIFT) /* Channel halted */ + /* Bits 21-31: Reserved, must be kept at reset value */ +/* Receive status debug read/OTG status read and pop registers (device mode) */ + +#define OTGFS_GRXSTSD_EPNUM_SHIFT (0) /* Bits 0-3: Endpoint number */ +#define OTGFS_GRXSTSD_EPNUM_MASK (15 << OTGFS_GRXSTSD_EPNUM_SHIFT) +#define OTGFS_GRXSTSD_BCNT_SHIFT (4) /* Bits 4-14: Byte count */ +#define OTGFS_GRXSTSD_BCNT_MASK (0x7ff << OTGFS_GRXSTSD_BCNT_SHIFT) +#define OTGFS_GRXSTSD_DPID_SHIFT (15) /* Bits 15-16: Data PID */ +#define OTGFS_GRXSTSD_DPID_MASK (3 << OTGFS_GRXSTSD_DPID_SHIFT) +# define OTGFS_GRXSTSD_DPID_DATA0 (0 << OTGFS_GRXSTSD_DPID_SHIFT) +# define OTGFS_GRXSTSD_DPID_DATA2 (1 << OTGFS_GRXSTSD_DPID_SHIFT) +# define OTGFS_GRXSTSD_DPID_DATA1 (2 << OTGFS_GRXSTSD_DPID_SHIFT) +# define OTGFS_GRXSTSD_DPID_MDATA (3 << OTGFS_GRXSTSD_DPID_SHIFT) +#define OTGFS_GRXSTSD_PKTSTS_SHIFT (17) /* Bits 17-20: Packet status */ +#define OTGFS_GRXSTSD_PKTSTS_MASK (15 << OTGFS_GRXSTSD_PKTSTS_SHIFT) +# define OTGFS_GRXSTSD_PKTSTS_OUTNAK (1 << OTGFS_GRXSTSD_PKTSTS_SHIFT) /* Global OUT NAK */ +# define OTGFS_GRXSTSD_PKTSTS_OUTRECVD (2 << OTGFS_GRXSTSD_PKTSTS_SHIFT) /* OUT data packet received */ +# define OTGFS_GRXSTSD_PKTSTS_OUTDONE (3 << OTGFS_GRXSTSD_PKTSTS_SHIFT) /* OUT transfer completed */ +# define OTGFS_GRXSTSD_PKTSTS_SETUPDONE (4 << OTGFS_GRXSTSD_PKTSTS_SHIFT) /* SETUP transaction completed */ +# define OTGFS_GRXSTSD_PKTSTS_SETUPRECVD (6 << OTGFS_GRXSTSD_PKTSTS_SHIFT) /* SETUP data packet received */ +#define OTGFS_GRXSTSD_FRMNUM_SHIFT (21) /* Bits 21-24: Frame number */ +#define OTGFS_GRXSTSD_FRMNUM_MASK (15 << OTGFS_GRXSTSD_FRMNUM_SHIFT) + /* Bits 25-31: Reserved, must be kept at reset value */ +/* Receive FIFO size register */ + +#define OTGFS_GRXFSIZ_MASK (0xffff) + +/* Host non-periodic transmit FIFO size register */ + +#define OTGFS_HNPTXFSIZ_NPTXFSA_SHIFT (0) /* Bits 0-15: Non-periodic transmit RAM start address */ +#define OTGFS_HNPTXFSIZ_NPTXFSA_MASK (0xffff << OTGFS_HNPTXFSIZ_NPTXFSA_SHIFT) +#define OTGFS_HNPTXFSIZ_NPTXFD_SHIFT (16) /* Bits 16-31: Non-periodic TxFIFO depth */ +#define OTGFS_HNPTXFSIZ_NPTXFD_MASK (0xffff << OTGFS_HNPTXFSIZ_NPTXFD_SHIFT) +# define OTGFS_HNPTXFSIZ_NPTXFD_MIN (16 << OTGFS_HNPTXFSIZ_NPTXFD_SHIFT) +# define OTGFS_HNPTXFSIZ_NPTXFD_MAX (256 << OTGFS_HNPTXFSIZ_NPTXFD_SHIFT) + +/* Endpoint 0 Transmit FIFO size */ + +#define OTGFS_DIEPTXF0_TX0FD_SHIFT (0) /* Bits 0-15: Endpoint 0 transmit RAM start address */ +#define OTGFS_DIEPTXF0_TX0FD_MASK (0xffff << OTGFS_DIEPTXF0_TX0FD_SHIFT) +#define OTGFS_DIEPTXF0_TX0FSA_SHIFT (16) /* Bits 16-31: Endpoint 0 TxFIFO depth */ +#define OTGFS_DIEPTXF0_TX0FSA_MASK (0xffff << OTGFS_DIEPTXF0_TX0FSA_SHIFT) +# define OTGFS_DIEPTXF0_TX0FSA_MIN (16 << OTGFS_DIEPTXF0_TX0FSA_SHIFT) +# define OTGFS_DIEPTXF0_TX0FSA_MAX (256 << OTGFS_DIEPTXF0_TX0FSA_SHIFT) + +/* Non-periodic transmit FIFO/queue status register */ + +#define OTGFS_HNPTXSTS_NPTXFSAV_SHIFT (0) /* Bits 0-15: Non-periodic TxFIFO space available */ +#define OTGFS_HNPTXSTS_NPTXFSAV_MASK (0xffff << OTGFS_HNPTXSTS_NPTXFSAV_SHIFT) +# define OTGFS_HNPTXSTS_NPTXFSAV_FULL (0 << OTGFS_HNPTXSTS_NPTXFSAV_SHIFT) +#define OTGFS_HNPTXSTS_NPTQXSAV_SHIFT (16) /* Bits 16-23: Non-periodic transmit request queue space available */ +#define OTGFS_HNPTXSTS_NPTQXSAV_MASK (0xff << OTGFS_HNPTXSTS_NPTQXSAV_SHIFT) +# define OTGFS_HNPTXSTS_NPTQXSAV_FULL (0 << OTGFS_HNPTXSTS_NPTQXSAV_SHIFT) +#define OTGFS_HNPTXSTS_NPTXQTOP_SHIFT (24) /* Bits 24-30: Top of the non-periodic transmit request queue */ +#define OTGFS_HNPTXSTS_NPTXQTOP_MASK (0x7f << OTGFS_HNPTXSTS_NPTXQTOP_SHIFT) +# define OTGFS_HNPTXSTS_TERMINATE (1 << 24) /* Bit 24: Terminate (last entry for selected channel/endpoint) */ +# define OTGFS_HNPTXSTS_TYPE_SHIFT (25) /* Bits 25-26: Status */ +# define OTGFS_HNPTXSTS_TYPE_MASK (3 << OTGFS_HNPTXSTS_TYPE_SHIFT) +# define OTGFS_HNPTXSTS_TYPE_INOUT (0 << OTGFS_HNPTXSTS_TYPE_SHIFT) /* IN/OUT token */ +# define OTGFS_HNPTXSTS_TYPE_ZLP (1 << OTGFS_HNPTXSTS_TYPE_SHIFT) /* Zero-length transmit packet (device IN/host OUT) */ +# define OTGFS_HNPTXSTS_TYPE_HALT (3 << OTGFS_HNPTXSTS_TYPE_SHIFT) /* Channel halt command */ +# define OTGFS_HNPTXSTS_CHNUM_SHIFT (27) /* Bits 27-30: Channel number */ +# define OTGFS_HNPTXSTS_CHNUM_MASK (15 << OTGFS_HNPTXSTS_CHNUM_SHIFT) +# define OTGFS_HNPTXSTS_EPNUM_SHIFT (27) /* Bits 27-30: Endpoint number */ +# define OTGFS_HNPTXSTS_EPNUM_MASK (15 << OTGFS_HNPTXSTS_EPNUM_SHIFT) + /* Bit 31 Reserved, must be kept at reset value */ + +/* General core configuration register */ + +#define OTGFS_GCCFG_DCDET (1 << 0) /* Bit 0: Data contact detect */ +#define OTGFS_GCCFG_PDET (1 << 1) /* Bit 1: Primary detect */ +#define OTGFS_GCCFG_SDET (1 << 2) /* Bit 2: Secondary detect */ +#define OTGFS_GCCFG_PS2DET (1 << 3) /* Bit 3: DM pull-up detect */ + /* Bits 4-15: Reserved, must be kept at reset value */ +#define OTGFS_GCCFG_PWRDWN (1 << 16) /* Bit 16: Power down */ +#define OTGFS_GCCFG_BCDEN (1 << 18) /* Bit 17: Battery charging detector enable */ +#define OTGFS_GCCFG_DCDEN (1 << 18) /* Bit 18: Data contact detection mode enable */ +#define OTGFS_GCCFG_PDEN (1 << 19) /* Bit 19: Primary detection mode enable */ +#define OTGFS_GCCFG_SDEN (1 << 20) /* Bit 20: Secondary detection mode enable */ +#define OTGFS_GCCFG_VBDEN (1 << 21) /* Bit 21: USB VBUS detection enable */ + /* Bits 22-31: Reserved, must be kept at reset value */ + +/* Core ID register (32-bit product ID) */ + +#define OTGFS_GLPMCFG_LPMEN (1 << 0) /* Bit 0: XXX */ +#define OTGFS_GLPMCFG_LPMACK (1 << 1) /* Bit 1: XXX */ +#define OTGFS_GLPMCFG_BESL_SHIFT (2) /* Bits 2-5: XXX */ +#define OTGFS_GLPMCFG_BESL_MASK (15 << OTGFS_GLPMCFG_BESL_SHIFT) +#define OTGFS_GLPMCFG_REMWAKE (1 << 6) /* Bit 6: XXX */ +#define OTGFS_GLPMCFG_L1SSEN (1 << 7) /* Bit 7: XXX */ +#define OTGFS_GLPMCFG_BESLTHRS_SHIFT (8) /* Bits 8-11: XXX */ +#define OTGFS_GLPMCFG_BESLTHRS_MASK (15 << OTGFS_GLPMCFG_BESLTHRS_SHIFT) +#define OTGFS_GLPMCFG_L1DSEN (1 << 12) /* Bit 12: XXX */ +#define OTGFS_GLPMCFG_LPMRSP_SHIFT (13) /* Bits 13-14: XXXX */ +#define OTGFS_GLPMCFG_LPMRSP_MASK (3 << OTGFS_GLPMCFG_LPMRSP_SHIFT) +#define OTGFS_GLPMCFG_SLPSTS (1 << 15) /* Bit 15: XXX */ +#define OTGFS_GLPMCFG_L1RSMOK (1 << 16) /* Bit 16: XXX */ +#define OTGFS_GLPMCFG_LPMCHIDX_SHIFT (17) /* Bits 17-20: XXX */ +#define OTGFS_GLPMCFG_LPMCHIDX_MASK (15 << OTGFS_GLPMCFG_LPMCHIDX_SHIFT) +#define OTGFS_GLPMCFG_LPMRCNT_SHIFT (21) /* Bits 21-23: XXX */ +#define OTGFS_GLPMCFG_LPMRCNT_MASK (7 << OTGFS_GLPMCFG_LPMRCNT_SHIFT) +#define OTGFS_GLPMCFG_SNDLPM (1 << 24) /* Bit 24: XXX */ +#define OTGFS_GLPMCFG_LPMRCNTSTS_SHIFT (25) /* Bits 25-27: XXX */ +#define OTGFS_GLPMCFG_LPMRCNTSTS_MASK (7 << OTGFS_GLPMCFG_LPMRCNTSTS_SHIFT) +#define OTGFS_GLPMCFG_ENBESL (1 << 28) /* Bit 28: XXX */ + /* Bits 29-31: Reserved, must be kept at reset value */ + +/* GPWRDN */ + +#define OTGFS_GPWRDN_ADPMEN (1 << 0) /* Bit 0: XXX */ +#define OTGFS_GPWRDN_ADPIF (1 << 23) /* Bit 23: XXX */ + +/* GADPCTL */ + +#define OTGFS_GADPCTL_PRBDSCHG_SHIFT (0) /* Bits 0-1: XXX */ +#define OTGFS_GADPCTL_PRBDSCHG_MASK (3 << OTGFS_GADPCTL_PRBDSCHG_SHIFT) +#define OTGFS_GADPCTL_PRBDELTA_SHIFT (2) /* Bits 2-3: XXX */ +#define OTGFS_GADPCTL_PRBDELTA_MASK (3 << OTGFS_GADPCTL_PRBDELTA_SHIFT) +#define OTGFS_GADPCTL_PRBPER_SHIFT (4) /* Bits 4-5: XXX */ +#define OTGFS_GADPCTL_PRBPER_MASK (15 << OTGFS_GADPCTL_PRBPER_SHIFT) +#define OTGFS_GADPCTL_RTIM_SHIFT (6) /* Bits 6-9: XXX */ +#define OTGFS_GADPCTL_RTIM_SHIFT (6) /* Bits 6-9: XXX */ +#define OTGFS_GADPCTL_ENAPRB (1 << 17) /* Bit 17: XXX */ +#define OTGFS_GADPCTL_ENASNS (1 << 18) /* Bit 18: XXX */ +#define OTGFS_GADPCTL_ADPRST (1 << 19) /* Bit 19: XXX */ +#define OTGFS_GADPCTL_ADPEN (1 << 20) /* Bit 20: XXX */ +#define OTGFS_GADPCTL_ADPPRBIF (1 << 21) /* Bit 21: XXX */ +#define OTGFS_GADPCTL_ADPSNSIF (1 << 22) /* Bit 22: XXX */ +#define OTGFS_GADPCTL_ADPTOIF (1 << 23) /* Bit 23: XXX */ +#define OTGFS_GADPCTL_ADPPRBIM (1 << 24) /* Bit 24: XXX */ +#define OTGFS_GADPCTL_ADPSNSIM (1 << 25) /* Bit 25: XXX */ +#define OTGFS_GADPCTL_ADPTOIM (1 << 26) /* Bit 26: XXX */ +#define OTGFS_GADPCTL_AR_SHIFT (27) /* Bits 27-28: XXX */ +#define OTGFS_GADPCTL_AR_MASK (3 << OTGFS_GADPCTL_AR_SHIFT) + +/* Host periodic transmit FIFO size register */ + +#define OTGFS_HPTXFSIZ_PTXSA_SHIFT (0) /* Bits 0-15: Host periodic TxFIFO start address */ +#define OTGFS_HPTXFSIZ_PTXSA_MASK (0xffff << OTGFS_HPTXFSIZ_PTXSA_SHIFT) +#define OTGFS_HPTXFSIZ_PTXFD_SHIFT (16) /* Bits 16-31: Host periodic TxFIFO depth */ +#define OTGFS_HPTXFSIZ_PTXFD_MASK (0xffff << OTGFS_HPTXFSIZ_PTXFD_SHIFT) + +/* Device IN endpoint transmit FIFOn size register */ + +#define OTGFS_DIEPTXF_INEPTXSA_SHIFT (0) /* Bits 0-15: IN endpoint FIFOx transmit RAM start address */ +#define OTGFS_DIEPTXF_INEPTXSA_MASK (0xffff << OTGFS_DIEPTXF_INEPTXSA_SHIFT) +#define OTGFS_DIEPTXF_INEPTXFD_SHIFT (16) /* Bits 16-31: IN endpoint TxFIFO depth */ +#define OTGFS_DIEPTXF_INEPTXFD_MASK (0xffff << OTGFS_DIEPTXF_INEPTXFD_SHIFT) +# define OTGFS_DIEPTXF_INEPTXFD_MIN (16 << OTGFS_DIEPTXF_INEPTXFD_MASK) + +/* Host-mode control and status registers */ + +/* Host configuration register */ + +#define OTGFS_HCFG_FSLSPCS_SHIFT (0) /* Bits 0-1: FS/LS PHY clock select */ +#define OTGFS_HCFG_FSLSPCS_MASK (3 << OTGFS_HCFG_FSLSPCS_SHIFT) +# define OTGFS_HCFG_FSLSPCS_FS48MHz (1 << OTGFS_HCFG_FSLSPCS_SHIFT) /* FS host mode, PHY clock is running at 48 MHz */ +# define OTGFS_HCFG_FSLSPCS_LS48MHz (1 << OTGFS_HCFG_FSLSPCS_SHIFT) /* LS host mode, Select 48 MHz PHY clock frequency */ +# define OTGFS_HCFG_FSLSPCS_LS6MHz (2 << OTGFS_HCFG_FSLSPCS_SHIFT) /* LS host mode, Select 6 MHz PHY clock frequency */ +#define OTGFS_HCFG_FSLSS (1 << 2) /* Bit 2: FS- and LS-only support */ + /* Bits 31:3 Reserved, must be kept at reset value */ +/* Host frame interval register */ + +#define OTGFS_HFIR_MASK (0xffff) +#define OTGFS_HFIR_RLDCTRL (1 << 16) /* Bit 16: XXX */ + +/* Host frame number/frame time remaining register */ + +#define OTGFS_HFNUM_FRNUM_SHIFT (0) /* Bits 0-15: Frame number */ +#define OTGFS_HFNUM_FRNUM_MASK (0xffff << OTGFS_HFNUM_FRNUM_SHIFT) +#define OTGFS_HFNUM_FTREM_SHIFT (16) /* Bits 16-31: Frame time remaining */ +#define OTGFS_HFNUM_FTREM_MASK (0xffff << OTGFS_HFNUM_FTREM_SHIFT) + +/* Host periodic transmit FIFO/queue status register */ + +#define OTGFS_HPTXSTS_PTXFSAVL_SHIFT (0) /* Bits 0-15: Periodic transmit data FIFO space available */ +#define OTGFS_HPTXSTS_PTXFSAVL_MASK (0xffff << OTGFS_HPTXSTS_PTXFSAVL_SHIFT) +# define OTGFS_HPTXSTS_PTXFSAVL_FULL (0 << OTGFS_HPTXSTS_PTXFSAVL_SHIFT) +#define OTGFS_HPTXSTS_PTXQSAV_SHIFT (16) /* Bits 16-23: Periodic transmit request queue space available */ +#define OTGFS_HPTXSTS_PTXQSAV_MASK (0xff << OTGFS_HPTXSTS_PTXQSAV_SHIFT) +# define OTGFS_HPTXSTS_PTXQSAV_FULL (0 << OTGFS_HPTXSTS_PTXQSAV_SHIFT) +#define OTGFS_HPTXSTS_PTXQTOP_SHIFT (24) /* Bits 24-31: Top of the periodic transmit request queue */ +#define OTGFS_HPTXSTS_PTXQTOP_MASK (0x7f << OTGFS_HPTXSTS_PTXQTOP_SHIFT) +# define OTGFS_HPTXSTS_TERMINATE (1 << 24) /* Bit 24: Terminate (last entry for selected channel/endpoint) */ +# define OTGFS_HPTXSTS_TYPE_SHIFT (25) /* Bits 25-26: Type */ +# define OTGFS_HPTXSTS_TYPE_MASK (3 << OTGFS_HPTXSTS_TYPE_SHIFT) +# define OTGFS_HPTXSTS_TYPE_INOUT (0 << OTGFS_HPTXSTS_TYPE_SHIFT) /* IN/OUT token */ +# define OTGFS_HPTXSTS_TYPE_ZLP (1 << OTGFS_HPTXSTS_TYPE_SHIFT) /* Zero-length transmit packet */ +# define OTGFS_HPTXSTS_TYPE_HALT (3 << OTGFS_HPTXSTS_TYPE_SHIFT) /* Disable channel command */ +# define OTGFS_HPTXSTS_EPNUM_SHIFT (27) /* Bits 27-30: Endpoint number */ +# define OTGFS_HPTXSTS_EPNUM_MASK (15 << OTGFS_HPTXSTS_EPNUM_SHIFT) +# define OTGFS_HPTXSTS_CHNUM_SHIFT (27) /* Bits 27-30: Channel number */ +# define OTGFS_HPTXSTS_CHNUM_MASK (15 << OTGFS_HPTXSTS_CHNUM_SHIFT) +# define OTGFS_HPTXSTS_ODD (1 << 24) /* Bit 31: Send in odd (vs even) frame */ + +/* Host all channels interrupt and all channels interrupt mask registers */ + +#define OTGFS_HAINT(n) (1 << (n)) /* Bits 15:0 HAINTM: Channel interrupt */ + +/* Host port control and status register */ + +#define OTGFS_HPRT_PCSTS (1 << 0) /* Bit 0: Port connect status */ +#define OTGFS_HPRT_PCDET (1 << 1) /* Bit 1: Port connect detected */ +#define OTGFS_HPRT_PENA (1 << 2) /* Bit 2: Port enable */ +#define OTGFS_HPRT_PENCHNG (1 << 3) /* Bit 3: Port enable/disable change */ +#define OTGFS_HPRT_POCA (1 << 4) /* Bit 4: Port overcurrent active */ +#define OTGFS_HPRT_POCCHNG (1 << 5) /* Bit 5: Port overcurrent change */ +#define OTGFS_HPRT_PRES (1 << 6) /* Bit 6: Port resume */ +#define OTGFS_HPRT_PSUSP (1 << 7) /* Bit 7: Port suspend */ +#define OTGFS_HPRT_PRST (1 << 8) /* Bit 8: Port reset */ + /* Bit 9: Reserved, must be kept at reset value */ +#define OTGFS_HPRT_PLSTS_SHIFT (10) /* Bits 10-11: Port line status */ +#define OTGFS_HPRT_PLSTS_MASK (3 << OTGFS_HPRT_PLSTS_SHIFT) +# define OTGFS_HPRT_PLSTS_DP (1 << 10) /* Bit 10: Logic level of OTG_FS_FS_DP */ +# define OTGFS_HPRT_PLSTS_DM (1 << 11) /* Bit 11: Logic level of OTG_FS_FS_DM */ +#define OTGFS_HPRT_PPWR (1 << 12) /* Bit 12: Port power */ +#define OTGFS_HPRT_PTCTL_SHIFT (13) /* Bits 13-16: Port test control */ +#define OTGFS_HPRT_PTCTL_MASK (15 << OTGFS_HPRT_PTCTL_SHIFT) +# define OTGFS_HPRT_PTCTL_DISABLED (0 << OTGFS_HPRT_PTCTL_SHIFT) /* Test mode disabled */ +# define OTGFS_HPRT_PTCTL_J (1 << OTGFS_HPRT_PTCTL_SHIFT) /* Test_J mode */ +# define OTGFS_HPRT_PTCTL_L (2 << OTGFS_HPRT_PTCTL_SHIFT) /* Test_K mode */ +# define OTGFS_HPRT_PTCTL_SE0_NAK (3 << OTGFS_HPRT_PTCTL_SHIFT) /* Test_SE0_NAK mode */ +# define OTGFS_HPRT_PTCTL_PACKET (4 << OTGFS_HPRT_PTCTL_SHIFT) /* Test_Packet mode */ +# define OTGFS_HPRT_PTCTL_FORCE (5 << OTGFS_HPRT_PTCTL_SHIFT) /* Test_Force_Enable */ +#define OTGFS_HPRT_PSPD_SHIFT (17) /* Bits 17-18: Port speed */ +#define OTGFS_HPRT_PSPD_MASK (3 << OTGFS_HPRT_PSPD_SHIFT) +# define OTGFS_HPRT_PSPD_FS (1 << OTGFS_HPRT_PSPD_SHIFT) /* Full speed */ +# define OTGFS_HPRT_PSPD_LS (2 << OTGFS_HPRT_PSPD_SHIFT) /* Low speed */ + /* Bits 19-31: Reserved, must be kept at reset value */ + +/* Host channel-n characteristics register */ + +#define OTGFS_HCCHAR_MPSIZ_SHIFT (0) /* Bits 0-10: Maximum packet size */ +#define OTGFS_HCCHAR_MPSIZ_MASK (0x7ff << OTGFS_HCCHAR_MPSIZ_SHIFT) +#define OTGFS_HCCHAR_EPNUM_SHIFT (11) /* Bits 11-14: Endpoint number */ +#define OTGFS_HCCHAR_EPNUM_MASK (15 << OTGFS_HCCHAR_EPNUM_SHIFT) +#define OTGFS_HCCHAR_EPDIR (1 << 15) /* Bit 15: Endpoint direction */ +# define OTGFS_HCCHAR_EPDIR_OUT (0) +# define OTGFS_HCCHAR_EPDIR_IN OTGFS_HCCHAR_EPDIR + /* Bit 16 Reserved, must be kept at reset value */ +#define OTGFS_HCCHAR_LSDEV (1 << 17) /* Bit 17: Low-speed device */ +#define OTGFS_HCCHAR_EPTYP_SHIFT (18) /* Bits 18-19: Endpoint type */ +#define OTGFS_HCCHAR_EPTYP_MASK (3 << OTGFS_HCCHAR_EPTYP_SHIFT) +# define OTGFS_HCCHAR_EPTYP_CTRL (0 << OTGFS_HCCHAR_EPTYP_SHIFT) /* Control */ +# define OTGFS_HCCHAR_EPTYP_ISOC (1 << OTGFS_HCCHAR_EPTYP_SHIFT) /* Isochronous */ +# define OTGFS_HCCHAR_EPTYP_BULK (2 << OTGFS_HCCHAR_EPTYP_SHIFT) /* Bulk */ +# define OTGFS_HCCHAR_EPTYP_INTR (3 << OTGFS_HCCHAR_EPTYP_SHIFT) /* Interrupt */ +#define OTGFS_HCCHAR_MCNT_SHIFT (20) /* Bits 20-21: Multicount */ +#define OTGFS_HCCHAR_MCNT_MASK (3 << OTGFS_HCCHAR_MCNT_SHIFT) +#define OTGFS_HCCHAR_DAD_SHIFT (22) /* Bits 22-28: Device address */ +#define OTGFS_HCCHAR_DAD_MASK (0x7f << OTGFS_HCCHAR_DAD_SHIFT) +#define OTGFS_HCCHAR_ODDFRM (1 << 29) /* Bit 29: Odd frame */ +#define OTGFS_HCCHAR_CHDIS (1 << 30) /* Bit 30: Channel disable */ +#define OTGFS_HCCHAR_CHENA (1 << 31) /* Bit 31: Channel enable */ + +/* Host channel-n interrupt and Host channel-0 interrupt mask registers */ + +#define OTGFS_HCINT_XFRC (1 << 0) /* Bit 0: Transfer completed */ +#define OTGFS_HCINT_CHH (1 << 1) /* Bit 1: Channel halted */ + /* Bit 2: Reserved, must be kept at reset value */ +#define OTGFS_HCINT_STALL (1 << 3) /* Bit 3: STALL response received interrupt */ +#define OTGFS_HCINT_NAK (1 << 4) /* Bit 4: NAK response received interrupt */ +#define OTGFS_HCINT_ACK (1 << 5) /* Bit 5: ACK response received/transmitted interrupt */ +#define OTGFS_HCINT_TXERR (1 << 7) /* Bit 7: Transaction error */ +#define OTGFS_HCINT_BBERR (1 << 8) /* Bit 8: Babble error */ +#define OTGFS_HCINT_FRMOR (1 << 9) /* Bit 9: Frame overrun */ +#define OTGFS_HCINT_DTERR (1 << 10) /* Bit 10: Data toggle error */ + /* Bits 11-31 Reserved, must be kept at reset value */ +/* Host channel-n interrupt register */ + +#define OTGFS_HCTSIZ_XFRSIZ_SHIFT (0) /* Bits 0-18: Transfer size */ +#define OTGFS_HCTSIZ_XFRSIZ_MASK (0x7ffff << OTGFS_HCTSIZ_XFRSIZ_SHIFT) +#define OTGFS_HCTSIZ_PKTCNT_SHIFT (19) /* Bits 19-28: Packet count */ +#define OTGFS_HCTSIZ_PKTCNT_MASK (0x3ff << OTGFS_HCTSIZ_PKTCNT_SHIFT) +#define OTGFS_HCTSIZ_DPID_SHIFT (29) /* Bits 29-30: Data PID */ +#define OTGFS_HCTSIZ_DPID_MASK (3 << OTGFS_HCTSIZ_DPID_SHIFT) +# define OTGFS_HCTSIZ_DPID_DATA0 (0 << OTGFS_HCTSIZ_DPID_SHIFT) +# define OTGFS_HCTSIZ_DPID_DATA2 (1 << OTGFS_HCTSIZ_DPID_SHIFT) +# define OTGFS_HCTSIZ_DPID_DATA1 (2 << OTGFS_HCTSIZ_DPID_SHIFT) +# define OTGFS_HCTSIZ_DPID_MDATA (3 << OTGFS_HCTSIZ_DPID_SHIFT) /* Non-control */ +# define OTGFS_HCTSIZ_PID_SETUP (3 << OTGFS_HCTSIZ_DPID_SHIFT) /* Control */ + /* Bit 31 Reserved, must be kept at reset value */ +/* Device-mode control and status registers */ + +/* Device configuration register */ + +#define OTGFS_DCFG_DSPD_SHIFT (0) /* Bits 0-1: Device speed */ +#define OTGFS_DCFG_DSPD_MASK (3 << OTGFS_DCFG_DSPD_SHIFT) +# define OTGFS_DCFG_DSPD_FS (3 << OTGFS_DCFG_DSPD_SHIFT) /* Full speed */ +#define OTGFS_DCFG_NZLSOHSK (1 << 2) /* Bit 2: Non-zero-length status OUT handshake */ + /* Bit 3: Reserved, must be kept at reset value */ +#define OTGFS_DCFG_DAD_SHIFT (4) /* Bits 4-10: Device address */ +#define OTGFS_DCFG_DAD_MASK (0x7f << OTGFS_DCFG_DAD_SHIFT) +#define OTGFS_DCFG_PFIVL_SHIFT (11) /* Bits 11-12: Periodic frame interval */ +#define OTGFS_DCFG_PFIVL_MASK (3 << OTGFS_DCFG_PFIVL_SHIFT) +# define OTGFS_DCFG_PFIVL_80PCT (0 << OTGFS_DCFG_PFIVL_SHIFT) /* 80% of the frame interval */ +# define OTGFS_DCFG_PFIVL_85PCT (1 << OTGFS_DCFG_PFIVL_SHIFT) /* 85% of the frame interval */ +# define OTGFS_DCFG_PFIVL_90PCT (2 << OTGFS_DCFG_PFIVL_SHIFT) /* 90% of the frame interval */ +# define OTGFS_DCFG_PFIVL_95PCT (3 << OTGFS_DCFG_PFIVL_SHIFT) /* 95% of the frame interval */ + /* Bits 13-31 Reserved, must be kept at reset value */ +/* Device control register */ + +#define OTGFS_TESTMODE_DISABLED (0) /* Test mode disabled */ +#define OTGFS_TESTMODE_J (1) /* Test_J mode */ +#define OTGFS_TESTMODE_K (2) /* Test_K mode */ +#define OTGFS_TESTMODE_SE0_NAK (3) /* Test_SE0_NAK mode */ +#define OTGFS_TESTMODE_PACKET (4) /* Test_Packet mode */ +#define OTGFS_TESTMODE_FORCE (5) /* Test_Force_Enable */ + +#define OTGFS_DCTL_RWUSIG (1 << 0) /* Bit 0: Remote wakeup signaling */ +#define OTGFS_DCTL_SDIS (1 << 1) /* Bit 1: Soft disconnect */ +#define OTGFS_DCTL_GINSTS (1 << 2) /* Bit 2: Global IN NAK status */ +#define OTGFS_DCTL_GONSTS (1 << 3) /* Bit 3: Global OUT NAK status */ +#define OTGFS_DCTL_TCTL_SHIFT (4) /* Bits 4-6: Test control */ +#define OTGFS_DCTL_TCTL_MASK (7 << OTGFS_DCTL_TCTL_SHIFT) +# define OTGFS_DCTL_TCTL_DISABLED (0 << OTGFS_DCTL_TCTL_SHIFT) /* Test mode disabled */ +# define OTGFS_DCTL_TCTL_J (1 << OTGFS_DCTL_TCTL_SHIFT) /* Test_J mode */ +# define OTGFS_DCTL_TCTL_K (2 << OTGFS_DCTL_TCTL_SHIFT) /* Test_K mode */ +# define OTGFS_DCTL_TCTL_SE0_NAK (3 << OTGFS_DCTL_TCTL_SHIFT) /* Test_SE0_NAK mode */ +# define OTGFS_DCTL_TCTL_PACKET (4 << OTGFS_DCTL_TCTL_SHIFT) /* Test_Packet mode */ +# define OTGFS_DCTL_TCTL_FORCE (5 << OTGFS_DCTL_TCTL_SHIFT) /* Test_Force_Enable */ +#define OTGFS_DCTL_SGINAK (1 << 7) /* Bit 7: Set global IN NAK */ +#define OTGFS_DCTL_CGINAK (1 << 8) /* Bit 8: Clear global IN NAK */ +#define OTGFS_DCTL_SGONAK (1 << 9) /* Bit 9: Set global OUT NAK */ +#define OTGFS_DCTL_CGONAK (1 << 10) /* Bit 10: Clear global OUT NAK */ +#define OTGFS_DCTL_POPRGDNE (1 << 11) /* Bit 11: Power-on programming done */ + /* Bits 12-17: Reserved, must be kept at reset value */ +#define OTGFS_DCTL_DSBESLRJCT (1 << 18) /* Bit 18: Deep sleep BESL reject */ + /* Bits 19-31: Reserved, must be kept at reset value */ +/* Device status register */ + +#define OTGFS_DSTS_SUSPSTS (1 << 0) /* Bit 0: Suspend status */ +#define OTGFS_DSTS_ENUMSPD_SHIFT (1) /* Bits 1-2: Enumerated speed */ +#define OTGFS_DSTS_ENUMSPD_MASK (3 << OTGFS_DSTS_ENUMSPD_SHIFT) +# define OTGFS_DSTS_ENUMSPD_FS (3 << OTGFS_DSTS_ENUMSPD_MASK) /* Full speed */ + /* Bits 4-7: Reserved, must be kept at reset value */ +#define OTGFS_DSTS_EERR (1 << 3) /* Bit 3: Erratic error */ +#define OTGFS_DSTS_SOFFN_SHIFT (8) /* Bits 8-21: Frame number of the received SOF */ +#define OTGFS_DSTS_SOFFN_MASK (0x3fff << OTGFS_DSTS_SOFFN_SHIFT) +#define OTGFS_DSTS_SOFFN0 (1 << 8) /* Bits 8: Frame number even/odd bit */ +#define OTGFS_DSTS_SOFFN_EVEN 0 +#define OTGFS_DSTS_SOFFN_ODD OTGFS_DSTS_SOFFN0 +#define OTGFS_DSTS_DEVLNSTS_SHIFT (22) /* Bits 22-23: XXX */ +#define OTGFS_DSTS_DEVLNSTS_MASK (0x3 << OTGFS_DSTS_DEVLNSTS_SHIFT) + /* Bits 24-31: Reserved, must be kept at reset value */ +/* Device IN endpoint common interrupt mask register */ + +#define OTGFS_DIEPMSK_XFRCM (1 << 0) /* Bit 0: Transfer completed interrupt mask */ +#define OTGFS_DIEPMSK_EPDM (1 << 1) /* Bit 1: Endpoint disabled interrupt mask */ + /* Bit 2: Reserved, must be kept at reset value */ +#define OTGFS_DIEPMSK_TOM (1 << 3) /* Bit 3: Timeout condition mask (Non-isochronous endpoints) */ +#define OTGFS_DIEPMSK_ITTXFEMSK (1 << 4) /* Bit 4: IN token received when TxFIFO empty mask */ +#define OTGFS_DIEPMSK_INEPNMM (1 << 5) /* Bit 5: IN token received with EP mismatch mask */ +#define OTGFS_DIEPMSK_INEPNEM (1 << 6) /* Bit 6: IN endpoint NAK effective mask */ + /* Bits 7-12: Reserved, must be kept at reset value */ +#define OTGFS_DIEPMSK_NAKM (1 << 13) /* Bit 13: NAK interrupt mask */ + /* Bits 14-31: Reserved, must be kept at reset value */ +/* Device OUT endpoint common interrupt mask register */ + +#define OTGFS_DOEPMSK_XFRCM (1 << 0) /* Bit 0: Transfer completed interrupt mask */ +#define OTGFS_DOEPMSK_EPDM (1 << 1) /* Bit 1: Endpoint disabled interrupt mask */ + /* Bit 2: Reserved, must be kept at reset value */ +#define OTGFS_DOEPMSK_STUPM (1 << 3) /* Bit 3: SETUP phase done mask */ +#define OTGFS_DOEPMSK_OTEPDM (1 << 4) /* Bit 4: OUT token received when endpoint disabled mask */ + /* Bits 5-31: Reserved, must be kept at reset value */ +/* Device all endpoints interrupt and All endpoints interrupt mask registers */ + +#define OTGFS_DAINT_IEP_SHIFT (0) /* Bits 0-15: IN endpoint interrupt bits */ +#define OTGFS_DAINT_IEP_MASK (0xffff << OTGFS_DAINT_IEP_SHIFT) +# define OTGFS_DAINT_IEP(n) (1 << (n)) +#define OTGFS_DAINT_OEP_SHIFT (16) /* Bits 16-31: OUT endpoint interrupt bits */ +#define OTGFS_DAINT_OEP_MASK (0xffff << OTGFS_DAINT_OEP_SHIFT) +# define OTGFS_DAINT_OEP(n) (1 << ((n)+16)) + +/* Device VBUS discharge time register */ + +#define OTGFS_DVBUSDIS_MASK (0xffff) + +/* Device VBUS pulsing time register */ + +#define OTGFS_DVBUSPULSE_MASK (0xffff) + +/* Device IN endpoint FIFO empty interrupt mask register */ + +#define OTGFS_DIEPEMPMSK(n) (1 << (n)) + +/* Device control IN endpoint 0 control register */ + +#define OTGFS_DIEPCTL0_MPSIZ_SHIFT (0) /* Bits 0-1: Maximum packet size */ +#define OTGFS_DIEPCTL0_MPSIZ_MASK (3 << OTGFS_DIEPCTL0_MPSIZ_SHIFT) +# define OTGFS_DIEPCTL0_MPSIZ_64 (0 << OTGFS_DIEPCTL0_MPSIZ_SHIFT) /* 64 bytes */ +# define OTGFS_DIEPCTL0_MPSIZ_32 (1 << OTGFS_DIEPCTL0_MPSIZ_SHIFT) /* 32 bytes */ +# define OTGFS_DIEPCTL0_MPSIZ_16 (2 << OTGFS_DIEPCTL0_MPSIZ_SHIFT) /* 16 bytes */ +# define OTGFS_DIEPCTL0_MPSIZ_8 (3 << OTGFS_DIEPCTL0_MPSIZ_SHIFT) /* 8 bytes */ + /* Bits 2-14: Reserved, must be kept at reset value */ +#define OTGFS_DIEPCTL0_USBAEP (1 << 15) /* Bit 15: USB active endpoint */ + /* Bit 16: Reserved, must be kept at reset value */ +#define OTGFS_DIEPCTL0_NAKSTS (1 << 17) /* Bit 17: NAK status */ +#define OTGFS_DIEPCTL0_EPTYP_SHIFT (18) /* Bits 18-19: Endpoint type */ +#define OTGFS_DIEPCTL0_EPTYP_MASK (3 << OTGFS_DIEPCTL0_EPTYP_SHIFT) +# define OTGFS_DIEPCTL0_EPTYP_CTRL (0 << OTGFS_DIEPCTL0_EPTYP_SHIFT) /* Control (hard-coded) */ + /* Bit 20: Reserved, must be kept at reset value */ +#define OTGFS_DIEPCTL0_STALL (1 << 21) /* Bit 21: STALL handshake */ +#define OTGFS_DIEPCTL0_TXFNUM_SHIFT (22) /* Bits 22-25: TxFIFO number */ +#define OTGFS_DIEPCTL0_TXFNUM_MASK (15 << OTGFS_DIEPCTL0_TXFNUM_SHIFT) +#define OTGFS_DIEPCTL0_CNAK (1 << 26) /* Bit 26: Clear NAK */ +#define OTGFS_DIEPCTL0_SNAK (1 << 27) /* Bit 27: Set NAK */ + /* Bits 28-29: Reserved, must be kept at reset value */ +#define OTGFS_DIEPCTL0_EPDIS (1 << 30) /* Bit 30: Endpoint disable */ +#define OTGFS_DIEPCTL0_EPENA (1 << 31) /* Bit 31: Endpoint enable */ + +/* Device control IN endpoint n control register */ + +#define OTGFS_DIEPCTL_MPSIZ_SHIFT (0) /* Bits 0-10: Maximum packet size */ +#define OTGFS_DIEPCTL_MPSIZ_MASK (0x7ff << OTGFS_DIEPCTL_MPSIZ_SHIFT) + /* Bits 11-14: Reserved, must be kept at reset value */ +#define OTGFS_DIEPCTL_USBAEP (1 << 15) /* Bit 15: USB active endpoint */ +#define OTGFS_DIEPCTL_EONUM (1 << 16) /* Bit 16: Even/odd frame */ +# define OTGFS_DIEPCTL_EVEN (0) +# define OTGFS_DIEPCTL_ODD OTGFS_DIEPCTL_EONUM +# define OTGFS_DIEPCTL_DATA0 (0) +# define OTGFS_DIEPCTL_DATA1 OTGFS_DIEPCTL_EONUM +#define OTGFS_DIEPCTL_NAKSTS (1 << 17) /* Bit 17: NAK status */ +#define OTGFS_DIEPCTL_EPTYP_SHIFT (18) /* Bits 18-19: Endpoint type */ +#define OTGFS_DIEPCTL_EPTYP_MASK (3 << OTGFS_DIEPCTL_EPTYP_SHIFT) +# define OTGFS_DIEPCTL_EPTYP_CTRL (0 << OTGFS_DIEPCTL_EPTYP_SHIFT) /* Control */ +# define OTGFS_DIEPCTL_EPTYP_ISOC (1 << OTGFS_DIEPCTL_EPTYP_SHIFT) /* Isochronous */ +# define OTGFS_DIEPCTL_EPTYP_BULK (2 << OTGFS_DIEPCTL_EPTYP_SHIFT) /* Bulk */ +# define OTGFS_DIEPCTL_EPTYP_INTR (3 << OTGFS_DIEPCTL_EPTYP_SHIFT) /* Interrupt */ + /* Bit 20: Reserved, must be kept at reset value */ +#define OTGFS_DIEPCTL_STALL (1 << 21) /* Bit 21: STALL handshake */ +#define OTGFS_DIEPCTL_TXFNUM_SHIFT (22) /* Bits 22-25: TxFIFO number */ +#define OTGFS_DIEPCTL_TXFNUM_MASK (15 << OTGFS_DIEPCTL_TXFNUM_SHIFT) +#define OTGFS_DIEPCTL_CNAK (1 << 26) /* Bit 26: Clear NAK */ +#define OTGFS_DIEPCTL_SNAK (1 << 27) /* Bit 27: Set NAK */ +#define OTGFS_DIEPCTL_SD0PID (1 << 28) /* Bit 28: Set DATA0 PID (interrupt/bulk) */ +#define OTGFS_DIEPCTL_SEVNFRM (1 << 28) /* Bit 28: Set even frame (isochronous)) */ +#define OTGFS_DIEPCTL_SODDFRM (1 << 29) /* Bit 29: Set odd frame (isochronous) */ +#define OTGFS_DIEPCTL_EPDIS (1 << 30) /* Bit 30: Endpoint disable */ +#define OTGFS_DIEPCTL_EPENA (1 << 31) /* Bit 31: Endpoint enable */ + +/* Device endpoint-n interrupt register */ + +#define OTGFS_DIEPINT_XFRC (1 << 0) /* Bit 0: Transfer completed interrupt */ +#define OTGFS_DIEPINT_EPDISD (1 << 1) /* Bit 1: Endpoint disabled interrupt */ + /* Bit 2: Reserved, must be kept at reset value */ +#define OTGFS_DIEPINT_TOC (1 << 3) /* Bit 3: Timeout condition */ +#define OTGFS_DIEPINT_ITTXFE (1 << 4) /* Bit 4: IN token received when TxFIFO is empty */ + /* Bit 5: Reserved, must be kept at reset value */ +#define OTGFS_DIEPINT_INEPNE (1 << 6) /* Bit 6: IN endpoint NAK effective */ +#define OTGFS_DIEPINT_TXFE (1 << 7) /* Bit 7: Transmit FIFO empty */ + /* Bits 8-31: Reserved, must be kept at reset value */ +/* Device IN endpoint 0 transfer size register */ + +#define OTGFS_DIEPTSIZ0_XFRSIZ_SHIFT (0) /* Bits 0-6: Transfer size */ +#define OTGFS_DIEPTSIZ0_XFRSIZ_MASK (0x7f << OTGFS_DIEPTSIZ0_XFRSIZ_SHIFT) + /* Bits 7-18: Reserved, must be kept at reset value */ +#define OTGFS_DIEPTSIZ0_PKTCNT_SHIFT (19) /* Bits 19-20: Packet count */ +#define OTGFS_DIEPTSIZ0_PKTCNT_MASK (3 << OTGFS_DIEPTSIZ0_PKTCNT_SHIFT) + /* Bits 21-31: Reserved, must be kept at reset value */ +/* Device IN endpoint n transfer size register */ + +#define OTGFS_DIEPTSIZ_XFRSIZ_SHIFT (0) /* Bits 0-18: Transfer size */ +#define OTGFS_DIEPTSIZ_XFRSIZ_MASK (0x7ffff << OTGFS_DIEPTSIZ_XFRSIZ_SHIFT) +#define OTGFS_DIEPTSIZ_PKTCNT_SHIFT (19) /* Bit 19-28: Packet count */ +#define OTGFS_DIEPTSIZ_PKTCNT_MASK (0x3ff << OTGFS_DIEPTSIZ_PKTCNT_SHIFT) +#define OTGFS_DIEPTSIZ_MCNT_SHIFT (29) /* Bits 29-30: Multi count */ +#define OTGFS_DIEPTSIZ_MCNT_MASK (3 << OTGFS_DIEPTSIZ_MCNT_SHIFT) + /* Bit 31: Reserved, must be kept at reset value */ +/* Device OUT endpoint TxFIFO status register */ + +#define OTGFS_DTXFSTS_MASK (0xffff) + +/* Device OUT endpoint 0 control register */ + +#define OTGFS_DOEPCTL0_MPSIZ_SHIFT (0) /* Bits 0-1: Maximum packet size */ +#define OTGFS_DOEPCTL0_MPSIZ_MASK (3 << OTGFS_DOEPCTL0_MPSIZ_SHIFT) +# define OTGFS_DOEPCTL0_MPSIZ_64 (0 << OTGFS_DOEPCTL0_MPSIZ_SHIFT) /* 64 bytes */ +# define OTGFS_DOEPCTL0_MPSIZ_32 (1 << OTGFS_DOEPCTL0_MPSIZ_SHIFT) /* 32 bytes */ +# define OTGFS_DOEPCTL0_MPSIZ_16 (2 << OTGFS_DOEPCTL0_MPSIZ_SHIFT) /* 16 bytes */ +# define OTGFS_DOEPCTL0_MPSIZ_8 (3 << OTGFS_DOEPCTL0_MPSIZ_SHIFT) /* 8 bytes */ + /* Bits 2-14: Reserved, must be kept at reset value */ +#define OTGFS_DOEPCTL0_USBAEP (1 << 15) /* Bit 15: USB active endpoint */ + /* Bit 16: Reserved, must be kept at reset value */ +#define OTGFS_DOEPCTL0_NAKSTS (1 << 17) /* Bit 17: NAK status */ +#define OTGFS_DOEPCTL0_EPTYP_SHIFT (18) /* Bits 18-19: Endpoint type */ +#define OTGFS_DOEPCTL0_EPTYP_MASK (3 << OTGFS_DOEPCTL0_EPTYP_SHIFT) +# define OTGFS_DOEPCTL0_EPTYP_CTRL (0 << OTGFS_DOEPCTL0_EPTYP_SHIFT) /* Control (hard-coded) */ +#define OTGFS_DOEPCTL0_SNPM (1 << 20) /* Bit 20: Snoop mode */ +#define OTGFS_DOEPCTL0_STALL (1 << 21) /* Bit 21: STALL handshake */ + /* Bits 22-25: Reserved, must be kept at reset value */ +#define OTGFS_DOEPCTL0_CNAK (1 << 26) /* Bit 26: Clear NAK */ +#define OTGFS_DOEPCTL0_SNAK (1 << 27) /* Bit 27: Set NAK */ + /* Bits 28-29: Reserved, must be kept at reset value */ +#define OTGFS_DOEPCTL0_EPDIS (1 << 30) /* Bit 30: Endpoint disable */ +#define OTGFS_DOEPCTL0_EPENA (1 << 31) /* Bit 31: Endpoint enable */ + +/* Device OUT endpoint n control register */ + +#define OTGFS_DOEPCTL_MPSIZ_SHIFT (0) /* Bits 0-10: Maximum packet size */ +#define OTGFS_DOEPCTL_MPSIZ_MASK (0x7ff << OTGFS_DOEPCTL_MPSIZ_SHIFT) + /* Bits 11-14: Reserved, must be kept at reset value */ +#define OTGFS_DOEPCTL_USBAEP (1 << 15) /* Bit 15: USB active endpoint */ +#define OTGFS_DOEPCTL_DPID (1 << 16) /* Bit 16: Endpoint data PID (interrupt/buld) */ +# define OTGFS_DOEPCTL_DATA0 (0) +# define OTGFS_DOEPCTL_DATA1 OTGFS_DOEPCTL_DPID +#define OTGFS_DOEPCTL_EONUM (1 << 16) /* Bit 16: Even/odd frame (isochronous) */ +# define OTGFS_DOEPCTL_EVEN (0) +# define OTGFS_DOEPCTL_ODD OTGFS_DOEPCTL_EONUM +#define OTGFS_DOEPCTL_NAKSTS (1 << 17) /* Bit 17: NAK status */ +#define OTGFS_DOEPCTL_EPTYP_SHIFT (18) /* Bits 18-19: Endpoint type */ +#define OTGFS_DOEPCTL_EPTYP_MASK (3 << OTGFS_DOEPCTL_EPTYP_SHIFT) +# define OTGFS_DOEPCTL_EPTYP_CTRL (0 << OTGFS_DOEPCTL_EPTYP_SHIFT) /* Control */ +# define OTGFS_DOEPCTL_EPTYP_ISOC (1 << OTGFS_DOEPCTL_EPTYP_SHIFT) /* Isochronous */ +# define OTGFS_DOEPCTL_EPTYP_BULK (2 << OTGFS_DOEPCTL_EPTYP_SHIFT) /* Bulk */ +# define OTGFS_DOEPCTL_EPTYP_INTR (3 << OTGFS_DOEPCTL_EPTYP_SHIFT) /* Interrupt */ +#define OTGFS_DOEPCTL_SNPM (1 << 20) /* Bit 20: Snoop mode */ +#define OTGFS_DOEPCTL_STALL (1 << 21) /* Bit 21: STALL handshake */ + /* Bits 22-25: Reserved, must be kept at reset value */ +#define OTGFS_DOEPCTL_CNAK (1 << 26) /* Bit 26: Clear NAK */ +#define OTGFS_DOEPCTL_SNAK (1 << 27) /* Bit 27: Set NAK */ +#define OTGFS_DOEPCTL_SD0PID (1 << 28) /* Bit 28: Set DATA0 PID (interrupt/bulk) */ +#define OTGFS_DOEPCTL_SEVNFRM (1 << 28) /* Bit 28: Set even frame (isochronous) */ +#define OTGFS_DOEPCTL_SD1PID (1 << 29) /* Bit 29: Set DATA1 PID (interrupt/bulk) */ +#define OTGFS_DOEPCTL_SODDFRM (1 << 29) /* Bit 29: Set odd frame (isochronous */ +#define OTGFS_DOEPCTL_EPDIS (1 << 30) /* Bit 30: Endpoint disable */ +#define OTGFS_DOEPCTL_EPENA (1 << 31) /* Bit 31: Endpoint enable */ + +/* Device endpoint-n interrupt register */ + +#define OTGFS_DOEPINT_XFRC (1 << 0) /* Bit 0: Transfer completed interrupt */ +#define OTGFS_DOEPINT_EPDISD (1 << 1) /* Bit 1: Endpoint disabled interrupt */ + /* Bit 2: Reserved, must be kept at reset value */ +#define OTGFS_DOEPINT_SETUP (1 << 3) /* Bit 3: SETUP phase done */ +#define OTGFS_DOEPINT_OTEPDIS (1 << 4) /* Bit 4: OUT token received when endpoint disabled */ + /* Bit 5: Reserved, must be kept at reset value */ +#define OTGFS_DOEPINT_B2BSTUP (1 << 6) /* Bit 6: Back-to-back SETUP packets received */ + /* Bits 7-31: Reserved, must be kept at reset value */ +/* Device OUT endpoint-0 transfer size register */ + +#define OTGFS_DOEPTSIZ0_XFRSIZ_SHIFT (0) /* Bits 0-6: Transfer size */ +#define OTGFS_DOEPTSIZ0_XFRSIZ_MASK (0x7f << OTGFS_DOEPTSIZ0_XFRSIZ_SHIFT) + /* Bits 7-18: Reserved, must be kept at reset value */ +#define OTGFS_DOEPTSIZ0_PKTCNT (1 << 19) /* Bit 19 PKTCNT: Packet count */ + /* Bits 20-28: Reserved, must be kept at reset value */ +#define OTGFS_DOEPTSIZ0_STUPCNT_SHIFT (29) /* Bits 29-30: SETUP packet count */ +#define OTGFS_DOEPTSIZ0_STUPCNT_MASK (3 << OTGFS_DOEPTSIZ0_STUPCNT_SHIFT) + /* Bit 31: Reserved, must be kept at reset value */ +/* Device OUT endpoint-n transfer size register */ + +#define OTGFS_DOEPTSIZ_XFRSIZ_SHIFT (0) /* Bits 0-18: Transfer size */ +#define OTGFS_DOEPTSIZ_XFRSIZ_MASK (0x7ffff << OTGFS_DOEPTSIZ_XFRSIZ_SHIFT) +#define OTGFS_DOEPTSIZ_PKTCNT_SHIFT (19) /* Bit 19-28: Packet count */ +#define OTGFS_DOEPTSIZ_PKTCNT_MASK (0x3ff << OTGFS_DOEPTSIZ_PKTCNT_SHIFT) +#define OTGFS_DOEPTSIZ_STUPCNT_SHIFT (29) /* Bits 29-30: SETUP packet count */ +#define OTGFS_DOEPTSIZ_STUPCNT_MASK (3 << OTGFS_DOEPTSIZ_STUPCNT_SHIFT) +#define OTGFS_DOEPTSIZ_RXDPID_SHIFT (29) /* Bits 29-30: Received data PID */ +#define OTGFS_DOEPTSIZ_RXDPID_MASK (3 << OTGFS_DOEPTSIZ_RXDPID_SHIFT) +# define OTGFS_DOEPTSIZ_RXDPID_DATA0 (0 << OTGFS_DOEPTSIZ_RXDPID_SHIFT) +# define OTGFS_DOEPTSIZ_RXDPID_DATA2 (1 << OTGFS_DOEPTSIZ_RXDPID_SHIFT) +# define OTGFS_DOEPTSIZ_RXDPID_DATA1 (2 << OTGFS_DOEPTSIZ_RXDPID_SHIFT) +# define OTGFS_DOEPTSIZ_RXDPID_MDATA (3 << OTGFS_DOEPTSIZ_RXDPID_SHIFT) + /* Bit 31: Reserved, must be kept at reset value */ +/* Power and clock gating control register */ + +#define OTGFS_PCGCCTL_STPPCLK (1 << 0) /* Bit 0: Stop PHY clock */ +#define OTGFS_PCGCCTL_GATEHCLK (1 << 1) /* Bit 1: Gate HCLK */ + /* Bits 2-3: Reserved, must be kept at reset value */ +#define OTGFS_PCGCCTL_PHYSUSP (1 << 4) /* Bit 4: PHY Suspended */ +#define OTGFS_PCGCCTL_ENL1GTG (1 << 5) /* Bit 5: Enable Sleep clock gating */ +#define OTGFS_PCGCCTL_PHYSLEEP (1 << 6) /* Bit 6: PHY in Sleep */ +#define OTGFS_PCGCCTL_SUSP (1 << 7) /* Bit 7: Deep Sleep */ + /* Bits 8-31: Reserved, must be kept at reset value */ + +#endif /* __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X5XX_OTGFS_H */ diff --git a/arch/arm/src/stm32l4/stm32l4_otgfs.h b/arch/arm/src/stm32l4/stm32l4_otgfs.h index 0d64e0a72c..d9945bdbd5 100644 --- a/arch/arm/src/stm32l4/stm32l4_otgfs.h +++ b/arch/arm/src/stm32l4/stm32l4_otgfs.h @@ -47,10 +47,16 @@ #include "stm32l4.h" -#include "chip/stm32l4x6xx_otgfs.h" - #if defined(CONFIG_STM32L4_OTGFS) +#if defined(CONFIG_STM32L4_STM32L4X5) +# include "chip/stm32l4x5xx_otgfs.h" +#elif defined(CONFIG_STM32L4_STM32L4X6) +# include "chip/stm32l4x6xx_otgfs.h" +#else +# error "Unsupported STM32L4 chip" +#endif + /************************************************************************************ * Pre-processor Definitions ************************************************************************************/ diff --git a/arch/arm/src/stm32l4/stm32l4_usbhost.h b/arch/arm/src/stm32l4/stm32l4_usbhost.h index efa910414c..6c695ece1f 100644 --- a/arch/arm/src/stm32l4/stm32l4_usbhost.h +++ b/arch/arm/src/stm32l4/stm32l4_usbhost.h @@ -47,10 +47,17 @@ #include #include "chip.h" -#include "chip/stm32l4x6xx_otgfs.h" #if defined(CONFIG_STM32L4_OTGFS) && defined(CONFIG_USBHOST) +#if defined(CONFIG_STM32L4_STM32L4X5) +# include "chip/stm32l4x5xx_otgfs.h" +#elif defined(CONFIG_STM32L4_STM32L4X6) +# include "chip/stm32l4x6xx_otgfs.h" +#else +# error "Unsupported STM32L4 chip" +#endif + /************************************************************************************ * Public Types ************************************************************************************/ -- GitLab From d99ceec58cca1720519cddb81e0a8cb4daf4bc90 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 8 Jun 2017 10:55:27 -0600 Subject: [PATCH 940/990] STM32L4: Add STM32L475 pinmap. Initial cut is just the the L476 pinmap with unsupported devices removed. --- arch/arm/src/stm32l4/chip/stm32l4_pinmap.h | 9 +- .../arm/src/stm32l4/chip/stm32l4x5xx_pinmap.h | 789 ++++++++++++++++++ .../arm/src/stm32l4/chip/stm32l4x6xx_pinmap.h | 3 +- 3 files changed, 796 insertions(+), 5 deletions(-) create mode 100644 arch/arm/src/stm32l4/chip/stm32l4x5xx_pinmap.h diff --git a/arch/arm/src/stm32l4/chip/stm32l4_pinmap.h b/arch/arm/src/stm32l4/chip/stm32l4_pinmap.h index 85140db034..c29e059432 100644 --- a/arch/arm/src/stm32l4/chip/stm32l4_pinmap.h +++ b/arch/arm/src/stm32l4/chip/stm32l4_pinmap.h @@ -1,6 +1,7 @@ /************************************************************************************ * arch/arm/src/stm32l4/chip/stm32l4_pinmap.h * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. * Copyright (C) 2015 Sebastien Lorquet. All rights reserved. * Author: Sebastien Lorquet * @@ -43,10 +44,12 @@ #include #include "chip.h" -#if defined(CONFIG_STM32L4_STM32L4X6) -# include "chip/stm32l4x6xx_pinmap.h" -#elif defined(CONFIG_STM32L4_STM32L4X3) +#if defined(CONFIG_STM32L4_STM32L4X3) # include "chip/stm32l4x3xx_pinmap.h" +#elif defined(CONFIG_STM32L4_STM32L4X5) +# include "chip/stm32l4x5xx_pinmap.h" +#elif defined(CONFIG_STM32L4_STM32L4X6) +# include "chip/stm32l4x6xx_pinmap.h" #else # error "Unsupported STM32 L4 pin map" #endif diff --git a/arch/arm/src/stm32l4/chip/stm32l4x5xx_pinmap.h b/arch/arm/src/stm32l4/chip/stm32l4x5xx_pinmap.h new file mode 100644 index 0000000000..d6f6d1cf50 --- /dev/null +++ b/arch/arm/src/stm32l4/chip/stm32l4x5xx_pinmap.h @@ -0,0 +1,789 @@ +/************************************************************************************ + * arch/arm/src/stm32l4/chip/stm32l4x5xx_pinmap.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Copyright (C) 2015-2016 Sebastien Lorquet. All rights reserved. + * Author: Sebastien Lorquet + * + * 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 __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X5XX_PINMAP_H +#define __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X5XX_PINMAP_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include "stm32l4_gpio.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Alternate Pin Functions. All members of the STM32L4xxx family share the same + * pin multiplexing (although they may differ in the pins physically available). + * + * Alternative pin selections are provided with a numeric suffix like _1, _2, etc. + * Drivers, however, will use the pin selection without the numeric suffix. + * Additional definitions are required in the board.h file. For example, if + * CAN1_RX connects vis PA11 on some board, then the following definitions should + * appear inthe board.h header file for that board: + * + * #define GPIO_CAN1_RX GPIO_CAN1_RX_1 + * + * The driver will then automatically configre PA11 as the CAN1 RX pin. + */ + +/* WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!! + * Additional effort is required to select specific GPIO options such as frequency, + * open-drain/push-pull, and pull-up/down! Just the basics are defined for most + * pins in this file. + */ + +/* ADC */ + +#define GPIO_ADC1_IN1 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN0) +#define GPIO_ADC1_IN2 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN1) +#define GPIO_ADC1_IN3 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN2) +#define GPIO_ADC1_IN4 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN3) +#define GPIO_ADC1_IN5 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN0) +#define GPIO_ADC1_IN6 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN1) +#define GPIO_ADC1_IN7 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN2) +#define GPIO_ADC1_IN8 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN3) +#define GPIO_ADC1_IN9 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN4) +#define GPIO_ADC1_IN10 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN5) +#define GPIO_ADC1_IN11 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN6) +#define GPIO_ADC1_IN12 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN7) +#define GPIO_ADC1_IN13 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN4) +#define GPIO_ADC1_IN14 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN5) +#define GPIO_ADC1_IN15 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN0) +#define GPIO_ADC1_IN16 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN1) + +#define GPIO_ADC2_IN1 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN0) +#define GPIO_ADC2_IN2 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN1) +#define GPIO_ADC2_IN3 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN2) +#define GPIO_ADC2_IN4 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN3) +#define GPIO_ADC2_IN5 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN0) +#define GPIO_ADC2_IN6 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN1) +#define GPIO_ADC2_IN7 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN2) +#define GPIO_ADC2_IN8 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN3) +#define GPIO_ADC2_IN9 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN4) +#define GPIO_ADC2_IN10 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN5) +#define GPIO_ADC2_IN11 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN6) +#define GPIO_ADC2_IN12 (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN7) +#define GPIO_ADC2_IN13 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN4) +#define GPIO_ADC2_IN14 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN5) +#define GPIO_ADC2_IN15 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN0) +#define GPIO_ADC2_IN16 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN1) + +#define GPIO_ADC3_IN1 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN0) +#define GPIO_ADC3_IN2 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN1) +#define GPIO_ADC3_IN3 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN2) +#define GPIO_ADC3_IN4 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN3) +#define GPIO_ADC3_IN6 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN3) +#define GPIO_ADC3_IN7 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN4) +#define GPIO_ADC3_IN8 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN5) +#define GPIO_ADC3_IN9 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN6) +#define GPIO_ADC3_IN10 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN7) +#define GPIO_ADC3_IN11 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN8) +#define GPIO_ADC3_IN12 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN9) +#define GPIO_ADC3_IN13 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN10) + +/* CAN */ + +#define GPIO_CAN1_RX_1 (GPIO_ALT|GPIO_AF9 |GPIO_PORTA|GPIO_PIN11) +#define GPIO_CAN1_RX_2 (GPIO_ALT|GPIO_AF9 |GPIO_PORTB|GPIO_PIN8) +#define GPIO_CAN1_RX_3 (GPIO_ALT|GPIO_AF9 |GPIO_PORTD|GPIO_PIN0) +#define GPIO_CAN1_TX_1 (GPIO_ALT|GPIO_AF9 |GPIO_PORTA|GPIO_PIN12) +#define GPIO_CAN1_TX_2 (GPIO_ALT|GPIO_AF9 |GPIO_PORTB|GPIO_PIN9) +#define GPIO_CAN1_TX_3 (GPIO_ALT|GPIO_AF9 |GPIO_PORTD|GPIO_PIN1) + +/* Clocks outputs */ + +#define GPIO_MCO (GPIO_ALT|GPIO_AF0 |GPIO_PORTA|GPIO_PIN8) + +/* Comparators */ + +#define GPIO_COMP1_INM_1 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN1) +#define GPIO_COMP1_INM_2 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN4) +#define GPIO_COMP1_INP_1 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN2) +#define GPIO_COMP1_INP_2 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN5) +#define GPIO_COMP1_OUT_1 (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN0) +#define GPIO_COMP1_OUT_2 (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN10) + +#define GPIO_COMP2_INM_1 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN3) +#define GPIO_COMP2_INM_2 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN7) +#define GPIO_COMP2_INP_1 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN4) +#define GPIO_COMP2_INP_2 (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN6) +#define GPIO_COMP2_OUT_1 (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN5) +#define GPIO_COMP2_OUT_2 (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN11) + +/* DAC */ + +#define GPIO_DAC1_OUT (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN4) +#define GPIO_DAC2_OUT (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN5) + +/* Digital Filter for Sigma-Delta Modulators (DFSDM) */ + +#define GPIO_DFSDM_DATIN0_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTB|GPIO_PIN1) +#define GPIO_DFSDM_DATIN0_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTD|GPIO_PIN3) +#define GPIO_DFSDM_DATIN1_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTB|GPIO_PIN12) +#define GPIO_DFSDM_DATIN1_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTD|GPIO_PIN6) +#define GPIO_DFSDM_DATIN2_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTB|GPIO_PIN14) +#define GPIO_DFSDM_DATIN2_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTE|GPIO_PIN7) +#define GPIO_DFSDM_DATIN3_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTC|GPIO_PIN7) +#define GPIO_DFSDM_DATIN3_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTE|GPIO_PIN4) +#define GPIO_DFSDM_DATIN4_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTC|GPIO_PIN0) +#define GPIO_DFSDM_DATIN4_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTE|GPIO_PIN10) +#define GPIO_DFSDM_DATIN5_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTB|GPIO_PIN6) +#define GPIO_DFSDM_DATIN5_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTE|GPIO_PIN12) +#define GPIO_DFSDM_DATIN6_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTB|GPIO_PIN8) +#define GPIO_DFSDM_DATIN6_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTF|GPIO_PIN13) +#define GPIO_DFSDM_DATIN7_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTB|GPIO_PIN10) +#define GPIO_DFSDM_DATIN7_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTD|GPIO_PIN0) + +#define GPIO_DFSDM_CKIN0_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTB|GPIO_PIN2) +#define GPIO_DFSDM_CKIN0_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTD|GPIO_PIN4) +#define GPIO_DFSDM_CKIN1_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTB|GPIO_PIN13) +#define GPIO_DFSDM_CKIN1_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTD|GPIO_PIN7) +#define GPIO_DFSDM_CKIN2_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTB|GPIO_PIN15) +#define GPIO_DFSDM_CKIN2_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTE|GPIO_PIN8) +#define GPIO_DFSDM_CKIN3_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTC|GPIO_PIN6) +#define GPIO_DFSDM_CKIN3_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTE|GPIO_PIN5) +#define GPIO_DFSDM_CKIN4_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTC|GPIO_PIN1) +#define GPIO_DFSDM_CKIN4_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTE|GPIO_PIN11) +#define GPIO_DFSDM_CKIN5_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTB|GPIO_PIN7) +#define GPIO_DFSDM_CKIN5_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTE|GPIO_PIN13) +#define GPIO_DFSDM_CKIN6_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTB|GPIO_PIN9) +#define GPIO_DFSDM_CKIN6_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTF|GPIO_PIN14) +#define GPIO_DFSDM_CKIN7_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTB|GPIO_PIN11) +#define GPIO_DFSDM_CKIN7_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTD|GPIO_PIN1) + +#define GPIO_DFSDM_CKOUT_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTC|GPIO_PIN2) +#define GPIO_DFSDM_CKOUT_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTE|GPIO_PIN9) + +/* Flexible Static Memory Controller (FSMC) */ + +#define GPIO_FMC_NL (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN7) +#define GPIO_FMC_NBL0 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN0) +#define GPIO_FMC_NBL1 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN1) +#define GPIO_FMC_CLK (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN3) +#define GPIO_FMC_NOE (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN4) +#define GPIO_FMC_NWE (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN5) +#define GPIO_FMC_NWAIT (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN6) +#define GPIO_FMC_NE1 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN7) +#define GPIO_FMC_NE2 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN9) +#define GPIO_FMC_NE3 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN10) +#define GPIO_FMC_NE4 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN12) +#define GPIO_FMC_INT3 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN7) +#define GPIO_FMC_NCE3 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN9) + +#define GPIO_FMC_A0 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN0) +#define GPIO_FMC_A1 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN1) +#define GPIO_FMC_A2 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN2) +#define GPIO_FMC_A3 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN3) +#define GPIO_FMC_A4 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN4) +#define GPIO_FMC_A5 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN5) +#define GPIO_FMC_A6 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN12) +#define GPIO_FMC_A7 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN13) +#define GPIO_FMC_A8 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN14) +#define GPIO_FMC_A9 (GPIO_ALT|GPIO_AF12|GPIO_PORTF|GPIO_PIN15) +#define GPIO_FMC_A10 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN0) +#define GPIO_FMC_A11 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN1) +#define GPIO_FMC_A12 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN2) +#define GPIO_FMC_A13 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN3) +#define GPIO_FMC_A14 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN4) +#define GPIO_FMC_A15 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN5) +#define GPIO_FMC_A16 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN11) +#define GPIO_FMC_A17 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN12) +#define GPIO_FMC_A18 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN13) +#define GPIO_FMC_A19 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN3) +#define GPIO_FMC_A20 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN4) +#define GPIO_FMC_A21 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN5) +#define GPIO_FMC_A22 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN6) +#define GPIO_FMC_A23 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN2) +#define GPIO_FMC_A24 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN13) +#define GPIO_FMC_A25 (GPIO_ALT|GPIO_AF12|GPIO_PORTG|GPIO_PIN14) + +#define GPIO_FMC_D0 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN14) +#define GPIO_FMC_D1 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN15) +#define GPIO_FMC_D2 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN0) +#define GPIO_FMC_D3 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN1) +#define GPIO_FMC_D4 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN7) +#define GPIO_FMC_D5 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN8) +#define GPIO_FMC_D6 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN9) +#define GPIO_FMC_D7 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN10) +#define GPIO_FMC_D8 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN11) +#define GPIO_FMC_D9 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN12) +#define GPIO_FMC_D10 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN13) +#define GPIO_FMC_D11 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN14) +#define GPIO_FMC_D12 (GPIO_ALT|GPIO_AF12|GPIO_PORTE|GPIO_PIN15) +#define GPIO_FMC_D13 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN8) +#define GPIO_FMC_D14 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN9) +#define GPIO_FMC_D15 (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN10) + +/* I2C */ + +/* Note: STM32L496xx/4A6xx devices have few additional mappings for + * I2C1-3 that are not defined here. + */ + +#define GPIO_I2C1_SDA_1 (GPIO_ALT|GPIO_AF4 |GPIO_PORTB|GPIO_PIN7) +#define GPIO_I2C1_SDA_2 (GPIO_ALT|GPIO_AF4 |GPIO_PORTB|GPIO_PIN9) +#define GPIO_I2C1_SDA_3 (GPIO_ALT|GPIO_AF4 |GPIO_PORTG|GPIO_PIN13) +#define GPIO_I2C1_SCL_1 (GPIO_ALT|GPIO_AF4 |GPIO_PORTB|GPIO_PIN6) +#define GPIO_I2C1_SCL_2 (GPIO_ALT|GPIO_AF4 |GPIO_PORTB|GPIO_PIN8) +#define GPIO_I2C1_SCL_3 (GPIO_ALT|GPIO_AF4 |GPIO_PORTG|GPIO_PIN14) +#define GPIO_I2C1_SMBA_1 (GPIO_ALT|GPIO_AF4 |GPIO_PORTB|GPIO_PIN5) +#define GPIO_I2C1_SMBA_2 (GPIO_ALT|GPIO_AF4 |GPIO_PORTG|GPIO_PIN15) + +#define GPIO_I2C2_SDA_1 (GPIO_ALT|GPIO_AF4 |GPIO_PORTB|GPIO_PIN11) +#define GPIO_I2C2_SDA_2 (GPIO_ALT|GPIO_AF4 |GPIO_PORTB|GPIO_PIN14) +#define GPIO_I2C2_SDA_3 (GPIO_ALT|GPIO_AF4 |GPIO_PORTF|GPIO_PIN0) +#define GPIO_I2C2_SCL_1 (GPIO_ALT|GPIO_AF4 |GPIO_PORTB|GPIO_PIN10) +#define GPIO_I2C2_SCL_2 (GPIO_ALT|GPIO_AF4 |GPIO_PORTB|GPIO_PIN13) +#define GPIO_I2C2_SCL_3 (GPIO_ALT|GPIO_AF4 |GPIO_PORTF|GPIO_PIN1) +#define GPIO_I2C2_SMBA_1 (GPIO_ALT|GPIO_AF4 |GPIO_PORTB|GPIO_PIN12) +#define GPIO_I2C2_SMBA_2 (GPIO_ALT|GPIO_AF4 |GPIO_PORTF|GPIO_PIN2) + +#define GPIO_I2C3_SDA_1 (GPIO_ALT|GPIO_AF4 |GPIO_PORTC|GPIO_PIN1) +#define GPIO_I2C3_SDA_2 (GPIO_ALT|GPIO_AF4 |GPIO_PORTG|GPIO_PIN8) +#define GPIO_I2C3_SCL_1 (GPIO_ALT|GPIO_AF4 |GPIO_PORTC|GPIO_PIN0) +#define GPIO_I2C3_SCL_2 (GPIO_ALT|GPIO_AF4 |GPIO_PORTG|GPIO_PIN7) +#define GPIO_I2C3_SMBA_1 (GPIO_ALT|GPIO_AF4 |GPIO_PORTB|GPIO_PIN2) +#define GPIO_I2C3_SMBA_2 (GPIO_ALT|GPIO_AF4 |GPIO_PORTG|GPIO_PIN6) + +/* JTAG */ + +#define GPIO_JTCK_SWCLK (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN14) +#define GPIO_JTDI (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN15) +#define GPIO_JTDO (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN3) +#define GPIO_JTMS_SWDIO (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN13) +#define GPIO_JTRST (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN4) + +/* OTG FS */ + +#define GPIO_OTGFS_SOF (GPIO_ALT|GPIO_AF10|GPIO_PORTA|GPIO_PIN8) +#define GPIO_OTGFS_ID (GPIO_ALT|GPIO_AF10|GPIO_PORTA|GPIO_PIN10) +#define GPIO_OTGFS_DM (GPIO_ALT|GPIO_AF10|GPIO_PORTA|GPIO_PIN11) +#define GPIO_OTGFS_DP (GPIO_ALT|GPIO_AF10|GPIO_PORTA|GPIO_PIN12) +#define GPIO_OTGFS_NOE_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTA|GPIO_PIN13) +#define GPIO_OTGFS_NOE_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTC|GPIO_PIN9) + +/* QUADSPI */ + +#define GPIO_QSPI_NCS_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN11) +#define GPIO_QSPI_NCS_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTE|GPIO_PIN11) +#define GPIO_QSPI_CLK_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN10) +#define GPIO_QSPI_CLK_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTE|GPIO_PIN10) +#define GPIO_QSPI_BK1_IO0_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN1) +#define GPIO_QSPI_BK1_IO0_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTE|GPIO_PIN12) +#define GPIO_QSPI_BK1_IO1_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN0) +#define GPIO_QSPI_BK1_IO1_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTE|GPIO_PIN13) +#define GPIO_QSPI_BK1_IO2_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTA|GPIO_PIN7) +#define GPIO_QSPI_BK1_IO2_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTE|GPIO_PIN14) +#define GPIO_QSPI_BK1_IO3_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTA|GPIO_PIN6) +#define GPIO_QSPI_BK1_IO3_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTE|GPIO_PIN15) + +/* RTC */ + +#define GPIO_RTC_OUT (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN2) +#define GPIO_RTC_REFIN (GPIO_ALT|GPIO_AF0 |GPIO_PORTB|GPIO_PIN15) + +/* SAI */ + +#define GPIO_SAI1_EXTCLK (GPIO_ALT|GPIO_AF13|GPIO_PORTA|GPIO_PIN0) + +#define GPIO_SAI1_FS_A_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN9) +#define GPIO_SAI1_FS_A_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN4) +#define GPIO_SAI1_SCK_A_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN10) +#define GPIO_SAI1_SCK_A_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN5) +#define GPIO_SAI1_SD_A_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTC|GPIO_PIN3) +#define GPIO_SAI1_SD_A_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTD|GPIO_PIN6) +#define GPIO_SAI1_SD_A_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN6) +#define GPIO_SAI1_MCLK_A_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN8) +#define GPIO_SAI1_MCLK_A_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN2) + +#define GPIO_SAI1_FS_B_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTA|GPIO_PIN4) +#define GPIO_SAI1_FS_B_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN6) +#define GPIO_SAI1_FS_B_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTF|GPIO_PIN9) +#define GPIO_SAI1_FS_B_4 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN9) +#define GPIO_SAI1_SCK_B_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN3) +#define GPIO_SAI1_SCK_B_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN8) +#define GPIO_SAI1_SCK_B_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTF|GPIO_PIN8) +#define GPIO_SAI1_SD_B_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN5) +#define GPIO_SAI1_SD_B_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN3) +#define GPIO_SAI1_SD_B_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN7) +#define GPIO_SAI1_SD_B_4 (GPIO_ALT|GPIO_AF13|GPIO_PORTF|GPIO_PIN6) +#define GPIO_SAI1_MCLK_B_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN4) +#define GPIO_SAI1_MCLK_B_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTE|GPIO_PIN10) +#define GPIO_SAI1_MCLK_B_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTF|GPIO_PIN7) + +#define GPIO_SAI2_EXTCLK_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTA|GPIO_PIN2) +#define GPIO_SAI2_EXTCLK_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTC|GPIO_PIN9) + +#define GPIO_SAI2_FS_A_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN12) +#define GPIO_SAI2_FS_A_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTD|GPIO_PIN12) +#define GPIO_SAI2_FS_A_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTG|GPIO_PIN10) +#define GPIO_SAI2_SCK_A_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN13) +#define GPIO_SAI2_SCK_A_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTD|GPIO_PIN10) +#define GPIO_SAI2_SCK_A_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTG|GPIO_PIN9) +#define GPIO_SAI2_SD_A_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN15) +#define GPIO_SAI2_SD_A_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTD|GPIO_PIN11) +#define GPIO_SAI2_SD_A_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTG|GPIO_PIN12) +#define GPIO_SAI2_MCLK_A_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN14) +#define GPIO_SAI2_MCLK_A_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTC|GPIO_PIN6) +#define GPIO_SAI2_MCLK_A_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTD|GPIO_PIN9) +#define GPIO_SAI2_MCLK_A_4 (GPIO_ALT|GPIO_AF13|GPIO_PORTG|GPIO_PIN11) + +#define GPIO_SAI2_FS_B_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTA|GPIO_PIN15) +#define GPIO_SAI2_FS_B_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTG|GPIO_PIN3) +#define GPIO_SAI2_SCK_B_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTC|GPIO_PIN10) +#define GPIO_SAI2_SCK_B_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTG|GPIO_PIN2) +#define GPIO_SAI2_SD_B_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTC|GPIO_PIN12) +#define GPIO_SAI2_SD_B_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTG|GPIO_PIN5) +#define GPIO_SAI2_MCLK_B_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTC|GPIO_PIN7) +#define GPIO_SAI2_MCLK_B_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTC|GPIO_PIN11) +#define GPIO_SAI2_MCLK_B_3 (GPIO_ALT|GPIO_AF13|GPIO_PORTG|GPIO_PIN4) + +/* SDIO */ + +#define GPIO_SDMMC1_CK (GPIO_ALT|GPIO_AF12|GPIO_PORTC|GPIO_PIN12) +#define GPIO_SDMMC1_CMD (GPIO_ALT|GPIO_AF12|GPIO_PORTD|GPIO_PIN2) +#define GPIO_SDMMC1_D0 (GPIO_ALT|GPIO_AF12|GPIO_PORTC|GPIO_PIN8) +#define GPIO_SDMMC1_D1 (GPIO_ALT|GPIO_AF12|GPIO_PORTC|GPIO_PIN9) +#define GPIO_SDMMC1_D2 (GPIO_ALT|GPIO_AF12|GPIO_PORTC|GPIO_PIN10) +#define GPIO_SDMMC1_D3 (GPIO_ALT|GPIO_AF12|GPIO_PORTC|GPIO_PIN11) +#define GPIO_SDMMC1_D4 (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN8) +#define GPIO_SDMMC1_D5 (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN9) +#define GPIO_SDMMC1_D6 (GPIO_ALT|GPIO_AF12|GPIO_PORTC|GPIO_PIN6) +#define GPIO_SDMMC1_D7 (GPIO_ALT|GPIO_AF12|GPIO_PORTC|GPIO_PIN7) + +/* Single Wire Protocol Interface */ + +#define GPIO_SWPMI1_IO (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN12) +#define GPIO_SWPMI1_TX (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN13) +#define GPIO_SWPMI1_RX (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN14) +#define GPIO_SWPMI1_SUSPEND (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN15) + +/* SPI */ + +#define GPIO_SPI1_NSS_1 (GPIO_ALT|GPIO_AF5 |GPIO_PORTA|GPIO_PIN4) +#define GPIO_SPI1_NSS_2 (GPIO_ALT|GPIO_AF5 |GPIO_PORTA|GPIO_PIN15) +#define GPIO_SPI1_NSS_3 (GPIO_ALT|GPIO_AF5 |GPIO_PORTE|GPIO_PIN12) +#define GPIO_SPI1_NSS_4 (GPIO_ALT|GPIO_AF5 |GPIO_PORTG|GPIO_PIN5) +#define GPIO_SPI1_SCK_1 (GPIO_ALT|GPIO_AF5 |GPIO_PORTA|GPIO_PIN5) +#define GPIO_SPI1_SCK_2 (GPIO_ALT|GPIO_AF5 |GPIO_PORTB|GPIO_PIN3) +#define GPIO_SPI1_SCK_3 (GPIO_ALT|GPIO_AF5 |GPIO_PORTE|GPIO_PIN13) +#define GPIO_SPI1_SCK_4 (GPIO_ALT|GPIO_AF5 |GPIO_PORTG|GPIO_PIN2) +#define GPIO_SPI1_MOSI_1 (GPIO_ALT|GPIO_AF5 |GPIO_PORTA|GPIO_PIN7) +#define GPIO_SPI1_MOSI_2 (GPIO_ALT|GPIO_AF5 |GPIO_PORTB|GPIO_PIN5) +#define GPIO_SPI1_MOSI_3 (GPIO_ALT|GPIO_AF5 |GPIO_PORTE|GPIO_PIN15) +#define GPIO_SPI1_MOSI_4 (GPIO_ALT|GPIO_AF5 |GPIO_PORTG|GPIO_PIN4) +#define GPIO_SPI1_MISO_1 (GPIO_ALT|GPIO_AF5 |GPIO_PORTA|GPIO_PIN6) +#define GPIO_SPI1_MISO_2 (GPIO_ALT|GPIO_AF5 |GPIO_PORTB|GPIO_PIN4) +#define GPIO_SPI1_MISO_3 (GPIO_ALT|GPIO_AF5 |GPIO_PORTE|GPIO_PIN14) +#define GPIO_SPI1_MISO_4 (GPIO_ALT|GPIO_AF5 |GPIO_PORTG|GPIO_PIN3) + +#define GPIO_SPI2_NSS_1 (GPIO_ALT|GPIO_AF5 |GPIO_PORTB|GPIO_PIN9) +#define GPIO_SPI2_NSS_2 (GPIO_ALT|GPIO_AF5 |GPIO_PORTB|GPIO_PIN12) +#define GPIO_SPI2_NSS_3 (GPIO_ALT|GPIO_AF5 |GPIO_PORTD|GPIO_PIN0) +#define GPIO_SPI2_SCK_1 (GPIO_ALT|GPIO_AF5 |GPIO_PORTB|GPIO_PIN10) +#define GPIO_SPI2_SCK_2 (GPIO_ALT|GPIO_AF5 |GPIO_PORTB|GPIO_PIN13) +#define GPIO_SPI2_SCK_3 (GPIO_ALT|GPIO_AF5 |GPIO_PORTD|GPIO_PIN1) +#define GPIO_SPI2_MOSI_1 (GPIO_ALT|GPIO_AF5 |GPIO_PORTB|GPIO_PIN15) +#define GPIO_SPI2_MOSI_2 (GPIO_ALT|GPIO_AF5 |GPIO_PORTC|GPIO_PIN3) +#define GPIO_SPI2_MOSI_3 (GPIO_ALT|GPIO_AF5 |GPIO_PORTD|GPIO_PIN4) +#define GPIO_SPI2_MISO_1 (GPIO_ALT|GPIO_AF5 |GPIO_PORTB|GPIO_PIN14) +#define GPIO_SPI2_MISO_2 (GPIO_ALT|GPIO_AF5 |GPIO_PORTC|GPIO_PIN2) +#define GPIO_SPI2_MISO_3 (GPIO_ALT|GPIO_AF5 |GPIO_PORTD|GPIO_PIN3) + +#define GPIO_SPI3_NSS_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTA|GPIO_PIN4) +#define GPIO_SPI3_NSS_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTA|GPIO_PIN15) +#define GPIO_SPI3_NSS_3 (GPIO_ALT|GPIO_AF6 |GPIO_PORTG|GPIO_PIN12) +#define GPIO_SPI3_SCK_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTB|GPIO_PIN3) +#define GPIO_SPI3_SCK_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTC|GPIO_PIN10) +#define GPIO_SPI3_SCK_3 (GPIO_ALT|GPIO_AF6 |GPIO_PORTG|GPIO_PIN9) +#define GPIO_SPI3_MOSI_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTB|GPIO_PIN5) +#define GPIO_SPI3_MOSI_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTC|GPIO_PIN12) +#define GPIO_SPI3_MOSI_3 (GPIO_ALT|GPIO_AF6 |GPIO_PORTG|GPIO_PIN11) +#define GPIO_SPI3_MISO_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTB|GPIO_PIN4) +#define GPIO_SPI3_MISO_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTC|GPIO_PIN11) +#define GPIO_SPI3_MISO_3 (GPIO_ALT|GPIO_AF6 |GPIO_PORTG|GPIO_PIN10) + +/* Timers */ + +#define GPIO_TIM1_CH1IN_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN8) +#define GPIO_TIM1_CH1IN_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN9) +#define GPIO_TIM1_CH1OUT_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN8) +#define GPIO_TIM1_CH1OUT_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN9) +#define GPIO_TIM1_CH2IN_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN9) +#define GPIO_TIM1_CH2IN_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN11) +#define GPIO_TIM1_CH2OUT_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN9) +#define GPIO_TIM1_CH2OUT_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN11) +#define GPIO_TIM1_CH3IN_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN10) +#define GPIO_TIM1_CH3IN_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN13) +#define GPIO_TIM1_CH3OUT_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN10) +#define GPIO_TIM1_CH3OUT_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN13) +#define GPIO_TIM1_CH4IN_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN11) +#define GPIO_TIM1_CH4IN_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN14) +#define GPIO_TIM1_CH4OUT_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN11) +#define GPIO_TIM1_CH4OUT_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN14) +#define GPIO_TIM1_CH1N_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN7) +#define GPIO_TIM1_CH1N_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN13) +#define GPIO_TIM1_CH1N_3 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN8) +#define GPIO_TIM1_CH2N_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN0) +#define GPIO_TIM1_CH2N_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN14) +#define GPIO_TIM1_CH2N_3 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN10) +#define GPIO_TIM1_CH3N_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN1) +#define GPIO_TIM1_CH3N_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN15) +#define GPIO_TIM1_CH3N_3 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN12) +#define GPIO_TIM1_BKIN_1 (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN6) +#define GPIO_TIM1_BKIN_2 (GPIO_ALT|GPIO_AF1 |GPIO_PORTB|GPIO_PIN12) +#define GPIO_TIM1_BKIN_3 (GPIO_ALT|GPIO_AF1 |GPIO_PORTE|GPIO_PIN15) +#define GPIO_TIM1_BKIN_COMP1 (GPIO_ALT|GPIO_AF3 |GPIO_PORTE|GPIO_PIN15) +#define GPIO_TIM1_BKIN_COMP2_1 (GPIO_ALT|GPIO_AF12|GPIO_PORTA|GPIO_PIN6) +#define GPIO_TIM1_BKIN_COMP2_2 (GPIO_ALT|GPIO_AF3 |GPIO_PORTB|GPIO_PIN12) +#define GPIO_TIM1_BKIN2 (GPIO_ALT|GPIO_AF2 |GPIO_PORTA|GPIO_PIN11) +#define GPIO_TIM1_BKIN2_COMP1 (GPIO_ALT|GPIO_AF12|GPIO_PORTA|GPIO_PIN11) +#define GPIO_TIM1_BKIN2_COMP2 (GPIO_ALT|GPIO_AF3 |GPIO_PORTE|GPIO_PIN14) +#define GPIO_TIM1_ETR_1 (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN12) +#define GPIO_TIM1_ETR_2 (GPIO_ALT|GPIO_AF1 |GPIO_PORTE|GPIO_PIN7) + +#define GPIO_TIM2_CH1IN_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN0) +#define GPIO_TIM2_CH1IN_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN5) +#define GPIO_TIM2_CH1IN_3 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN15) +#define GPIO_TIM2_CH1OUT_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN0) +#define GPIO_TIM2_CH1OUT_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN5) +#define GPIO_TIM2_CH1OUT_3 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN15) +#define GPIO_TIM2_CH2IN_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN1) +#define GPIO_TIM2_CH2IN_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN3) +#define GPIO_TIM2_CH2OUT_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN1) +#define GPIO_TIM2_CH2OUT_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN3) +#define GPIO_TIM2_CH3IN_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN2) +#define GPIO_TIM2_CH3IN_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN10) +#define GPIO_TIM2_CH3OUT_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN2) +#define GPIO_TIM2_CH3OUT_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN10) +#define GPIO_TIM2_CH4IN_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN3) +#define GPIO_TIM2_CH4IN_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN11) +#define GPIO_TIM2_CH4OUT_1 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN3) +#define GPIO_TIM2_CH4OUT_2 (GPIO_ALT|GPIO_AF1 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN11) +#define GPIO_TIM2_BKIN (GPIO_ALT|GPIO_AF2 |GPIO_PORTE|GPIO_PIN14) +#define GPIO_TIM2_ETR_1 (GPIO_ALT|GPIO_AF14|GPIO_PORTA|GPIO_PIN0) +#define GPIO_TIM2_ETR_2 (GPIO_ALT|GPIO_AF2 |GPIO_PORTA|GPIO_PIN5) +#define GPIO_TIM2_ETR_3 (GPIO_ALT|GPIO_AF2 |GPIO_PORTA|GPIO_PIN15) + +#define GPIO_TIM3_CH1IN_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN6) +#define GPIO_TIM3_CH1IN_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN4) +#define GPIO_TIM3_CH1IN_3 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN6) +#define GPIO_TIM3_CH1IN_4 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN3) +#define GPIO_TIM3_CH1OUT_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN6) +#define GPIO_TIM3_CH1OUT_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN4) +#define GPIO_TIM3_CH1OUT_3 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN6) +#define GPIO_TIM3_CH1OUT_4 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN3) +#define GPIO_TIM3_CH2IN_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN7) +#define GPIO_TIM3_CH2IN_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN5) +#define GPIO_TIM3_CH2IN_3 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN7) +#define GPIO_TIM3_CH2IN_4 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN4) +#define GPIO_TIM3_CH2OUT_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN7) +#define GPIO_TIM3_CH2OUT_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN5) +#define GPIO_TIM3_CH2OUT_3 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN7) +#define GPIO_TIM3_CH2OUT_4 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN4) +#define GPIO_TIM3_CH3IN_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN0) +#define GPIO_TIM3_CH3IN_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN8) +#define GPIO_TIM3_CH3IN_3 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN5) +#define GPIO_TIM3_CH3OUT_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN0) +#define GPIO_TIM3_CH3OUT_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8) +#define GPIO_TIM3_CH3OUT_3 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN5) +#define GPIO_TIM3_CH4IN_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN1) +#define GPIO_TIM3_CH4IN_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN9) +#define GPIO_TIM3_CH4IN_3 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN6) +#define GPIO_TIM3_CH4OUT_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN1) +#define GPIO_TIM3_CH4OUT_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN9) +#define GPIO_TIM3_CH4OUT_3 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN6) +#define GPIO_TIM3_ETR_1 (GPIO_ALT|GPIO_AF2 |GPIO_PORTD|GPIO_PIN2) +#define GPIO_TIM3_ETR_2 (GPIO_ALT|GPIO_AF2 |GPIO_PORTE|GPIO_PIN2) + +#define GPIO_TIM4_CH1IN_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN6) +#define GPIO_TIM4_CH1IN_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN12) +#define GPIO_TIM4_CH1OUT_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN6) +#define GPIO_TIM4_CH1OUT_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN12) +#define GPIO_TIM4_CH2IN_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN7) +#define GPIO_TIM4_CH2IN_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN13) +#define GPIO_TIM4_CH2OUT_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN7) +#define GPIO_TIM4_CH2OUT_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN13) +#define GPIO_TIM4_CH3IN_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN8) +#define GPIO_TIM4_CH3IN_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN14) +#define GPIO_TIM4_CH3OUT_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN8) +#define GPIO_TIM4_CH3OUT_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN14) +#define GPIO_TIM4_CH4IN_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN9) +#define GPIO_TIM4_CH4IN_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN15) +#define GPIO_TIM4_CH4OUT_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN9) +#define GPIO_TIM4_CH4OUT_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN15) +#define GPIO_TIM4_ETR (GPIO_ALT|GPIO_AF2 |GPIO_PORTE|GPIO_PIN0) + +#define GPIO_TIM5_CH1IN_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN0) +#define GPIO_TIM5_CH1IN_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTF|GPIO_PIN6) +#define GPIO_TIM5_CH1OUT_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN0) +#define GPIO_TIM5_CH1OUT_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTF|GPIO_PIN6) +#define GPIO_TIM5_CH2IN_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN1) +#define GPIO_TIM5_CH2IN_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTF|GPIO_PIN7) +#define GPIO_TIM5_CH2OUT_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN1) +#define GPIO_TIM5_CH2OUT_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTF|GPIO_PIN7) +#define GPIO_TIM5_CH3IN_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN2) +#define GPIO_TIM5_CH3IN_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTF|GPIO_PIN8) +#define GPIO_TIM5_CH3OUT_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN2) +#define GPIO_TIM5_CH3OUT_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTF|GPIO_PIN8) +#define GPIO_TIM5_CH4IN_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN3) +#define GPIO_TIM5_CH4IN_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTF|GPIO_PIN9) +#define GPIO_TIM5_CH4OUT_1 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN3) +#define GPIO_TIM5_CH4OUT_2 (GPIO_ALT|GPIO_AF2 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTF|GPIO_PIN9) +#define GPIO_TIM5_ETR (GPIO_ALT|GPIO_AF1 |GPIO_PORTF|GPIO_PIN6) + +#define GPIO_TIM8_CH1IN (GPIO_ALT|GPIO_AF3 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN6) +#define GPIO_TIM8_CH1OUT (GPIO_ALT|GPIO_AF3 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN6) +#define GPIO_TIM8_CH2IN (GPIO_ALT|GPIO_AF3 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN7) +#define GPIO_TIM8_CH2OUT (GPIO_ALT|GPIO_AF3 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN7) +#define GPIO_TIM8_CH3IN (GPIO_ALT|GPIO_AF3 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN8) +#define GPIO_TIM8_CH3OUT (GPIO_ALT|GPIO_AF3 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8) +#define GPIO_TIM8_CH4IN (GPIO_ALT|GPIO_AF3 |GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN9) +#define GPIO_TIM8_CH4OUT (GPIO_ALT|GPIO_AF3 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN9) +#define GPIO_TIM8_CH1N_1 (GPIO_ALT|GPIO_AF3 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN5) +#define GPIO_TIM8_CH1N_2 (GPIO_ALT|GPIO_AF3 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN7) +#define GPIO_TIM8_CH2N_1 (GPIO_ALT|GPIO_AF3 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN0) +#define GPIO_TIM8_CH2N_2 (GPIO_ALT|GPIO_AF3 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN14) +#define GPIO_TIM8_CH3N_1 (GPIO_ALT|GPIO_AF3 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN1) +#define GPIO_TIM8_CH3N_2 (GPIO_ALT|GPIO_AF3 |GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN15) +#define GPIO_TIM8_BKIN_1 (GPIO_ALT|GPIO_AF3 |GPIO_PORTA|GPIO_PIN6) +#define GPIO_TIM8_BKIN_2 (GPIO_ALT|GPIO_AF3 |GPIO_PORTB|GPIO_PIN7) +#define GPIO_TIM8_BKIN_COMP1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN7) +#define GPIO_TIM8_BKIN_COMP2 (GPIO_ALT|GPIO_AF13|GPIO_PORTA|GPIO_PIN6) +#define GPIO_TIM8_BKIN2_1 (GPIO_ALT|GPIO_AF3 |GPIO_PORTB|GPIO_PIN6) +#define GPIO_TIM8_BKIN2_2 (GPIO_ALT|GPIO_AF1 |GPIO_PORTC|GPIO_PIN9) +#define GPIO_TIM8_BKIN2_COMP1 (GPIO_ALT|GPIO_AF14|GPIO_PORTC|GPIO_PIN9) +#define GPIO_TIM8_BKIN2_COMP2 (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN6) +#define GPIO_TIM8_ETR (GPIO_ALT|GPIO_AF3 |GPIO_PORTA|GPIO_PIN0) + +#define GPIO_TIM15_CH1IN_1 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN2) +#define GPIO_TIM15_CH1IN_2 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN14) +#define GPIO_TIM15_CH1IN_3 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTF|GPIO_PIN9) +#define GPIO_TIM15_CH1IN_4 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTG|GPIO_PIN10) +#define GPIO_TIM15_CH1OUT_1 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN2) +#define GPIO_TIM15_CH1OUT_2 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN14) +#define GPIO_TIM15_CH1OUT_3 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTF|GPIO_PIN9) +#define GPIO_TIM15_CH1OUT_4 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN10) +#define GPIO_TIM15_CH2IN_1 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN3) +#define GPIO_TIM15_CH2IN_2 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN15) +#define GPIO_TIM15_CH2IN_3 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTF|GPIO_PIN10) +#define GPIO_TIM15_CH2IN_4 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTG|GPIO_PIN11) +#define GPIO_TIM15_CH2OUT_1 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN3) +#define GPIO_TIM15_CH2OUT_2 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN15) +#define GPIO_TIM15_CH2OUT_3 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTF|GPIO_PIN10) +#define GPIO_TIM15_CH2OUT_4 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN11) +#define GPIO_TIM15_CH1N_1 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN1) +#define GPIO_TIM15_CH1N_2 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN13) +#define GPIO_TIM15_CH1N_3 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN9) +#define GPIO_TIM15_BKIN_1 (GPIO_ALT|GPIO_AF14|GPIO_PORTA|GPIO_PIN9) +#define GPIO_TIM15_BKIN_2 (GPIO_ALT|GPIO_AF14|GPIO_PORTB|GPIO_PIN12) + +#define GPIO_TIM16_CH1IN_1 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN6) +#define GPIO_TIM16_CH1IN_2 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN8) +#define GPIO_TIM16_CH1IN_3 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN0) +#define GPIO_TIM16_CH1OUT_1 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN6) +#define GPIO_TIM16_CH1OUT_2 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN8) +#define GPIO_TIM16_CH1OUT_3 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN0) +#define GPIO_TIM16_CH1N (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN6) +#define GPIO_TIM16_BKIN (GPIO_ALT|GPIO_AF14|GPIO_PORTB|GPIO_PIN5) + +#define GPIO_TIM17_CH1IN_1 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN7) +#define GPIO_TIM17_CH1IN_2 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN9) +#define GPIO_TIM17_CH1IN_3 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_FLOAT|GPIO_PORTE|GPIO_PIN1) +#define GPIO_TIM17_CH1OUT_1 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN7) +#define GPIO_TIM17_CH1OUT_2 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN9) +#define GPIO_TIM17_CH1OUT_3 (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN1) +#define GPIO_TIM17_CH1N (GPIO_ALT|GPIO_AF14|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN7) +#define GPIO_TIM17_BKIN_1 (GPIO_ALT|GPIO_AF14|GPIO_PORTA|GPIO_PIN10) +#define GPIO_TIM17_BKIN_2 (GPIO_ALT|GPIO_AF14|GPIO_PORTB|GPIO_PIN4) + +#define GPIO_LPTIM1_IN1_1 (GPIO_ALT|GPIO_AF1 |GPIO_PORTB|GPIO_PIN5) +#define GPIO_LPTIM1_IN1_2 (GPIO_ALT|GPIO_AF1 |GPIO_PORTC|GPIO_PIN0) +#define GPIO_LPTIM1_IN1_3 (GPIO_ALT|GPIO_AF1 |GPIO_PORTG|GPIO_PIN10) +#define GPIO_LPTIM1_IN2_1 (GPIO_ALT|GPIO_AF1 |GPIO_PORTB|GPIO_PIN7) +#define GPIO_LPTIM1_IN2_2 (GPIO_ALT|GPIO_AF1 |GPIO_PORTC|GPIO_PIN2) +#define GPIO_LPTIM1_IN2_3 (GPIO_ALT|GPIO_AF1 |GPIO_PORTG|GPIO_PIN11) +#define GPIO_LPTIM1_OUT_1 (GPIO_ALT|GPIO_AF1 |GPIO_PORTB|GPIO_PIN2) +#define GPIO_LPTIM1_OUT_2 (GPIO_ALT|GPIO_AF1 |GPIO_PORTC|GPIO_PIN1) +#define GPIO_LPTIM1_OUT_3 (GPIO_ALT|GPIO_AF1 |GPIO_PORTG|GPIO_PIN15) +#define GPIO_LPTIM1_ETR_1 (GPIO_ALT|GPIO_AF1 |GPIO_PORTB|GPIO_PIN6) +#define GPIO_LPTIM1_ETR_2 (GPIO_ALT|GPIO_AF1 |GPIO_PORTC|GPIO_PIN3) +#define GPIO_LPTIM1_ETR_3 (GPIO_ALT|GPIO_AF1 |GPIO_PORTG|GPIO_PIN12) + +#define GPIO_LPTIM2_IN1_1 (GPIO_ALT|GPIO_AF14|GPIO_PORTB|GPIO_PIN1) +#define GPIO_LPTIM2_IN1_2 (GPIO_ALT|GPIO_AF14|GPIO_PORTC|GPIO_PIN0) +#define GPIO_LPTIM2_IN1_3 (GPIO_ALT|GPIO_AF14|GPIO_PORTD|GPIO_PIN12) +#define GPIO_LPTIM2_OUT_1 (GPIO_ALT|GPIO_AF14|GPIO_PORTA|GPIO_PIN4) +#define GPIO_LPTIM2_OUT_2 (GPIO_ALT|GPIO_AF14|GPIO_PORTA|GPIO_PIN8) +#define GPIO_LPTIM2_OUT_3 (GPIO_ALT|GPIO_AF14|GPIO_PORTD|GPIO_PIN13) +#define GPIO_LPTIM2_ETR_1 (GPIO_ALT|GPIO_AF14|GPIO_PORTA|GPIO_PIN5) +#define GPIO_LPTIM2_ETR_2 (GPIO_ALT|GPIO_AF14|GPIO_PORTC|GPIO_PIN3) +#define GPIO_LPTIM2_ETR_3 (GPIO_ALT|GPIO_AF14|GPIO_PORTD|GPIO_PIN11) + +/* Touch Sensing Controller */ + +#define GPIO_TSC_SYNC (GPIO_ALT|GPIO_AF9 |GPIO_PORTD|GPIO_PIN2) + +#define GPIO_TSC_G1_IO1 (GPIO_ALT|GPIO_AF9 |GPIO_PORTB|GPIO_PIN12) +#define GPIO_TSC_G1_IO2 (GPIO_ALT|GPIO_AF9 |GPIO_PORTB|GPIO_PIN13) +#define GPIO_TSC_G1_IO3 (GPIO_ALT|GPIO_AF9 |GPIO_PORTB|GPIO_PIN14) +#define GPIO_TSC_G1_IO4 (GPIO_ALT|GPIO_AF9 |GPIO_PORTB|GPIO_PIN15) + +#define GPIO_TSC_G2_IO1 (GPIO_ALT|GPIO_AF9 |GPIO_PORTB|GPIO_PIN4) +#define GPIO_TSC_G2_IO2 (GPIO_ALT|GPIO_AF9 |GPIO_PORTB|GPIO_PIN5) +#define GPIO_TSC_G2_IO3 (GPIO_ALT|GPIO_AF9 |GPIO_PORTB|GPIO_PIN6) +#define GPIO_TSC_G2_IO4 (GPIO_ALT|GPIO_AF9 |GPIO_PORTB|GPIO_PIN7) + +#define GPIO_TSC_G3_IO1 (GPIO_ALT|GPIO_AF9 |GPIO_PORTA|GPIO_PIN15) +#define GPIO_TSC_G3_IO2 (GPIO_ALT|GPIO_AF9 |GPIO_PORTC|GPIO_PIN10) +#define GPIO_TSC_G3_IO3 (GPIO_ALT|GPIO_AF9 |GPIO_PORTC|GPIO_PIN11) +#define GPIO_TSC_G3_IO4 (GPIO_ALT|GPIO_AF9 |GPIO_PORTC|GPIO_PIN12) + +#define GPIO_TSC_G4_IO1 (GPIO_ALT|GPIO_AF9 |GPIO_PORTC|GPIO_PIN6) +#define GPIO_TSC_G4_IO2 (GPIO_ALT|GPIO_AF9 |GPIO_PORTC|GPIO_PIN7) +#define GPIO_TSC_G4_IO3 (GPIO_ALT|GPIO_AF9 |GPIO_PORTC|GPIO_PIN8) +#define GPIO_TSC_G4_IO4 (GPIO_ALT|GPIO_AF9 |GPIO_PORTC|GPIO_PIN9) + +#define GPIO_TSC_G5_IO1 (GPIO_ALT|GPIO_AF9 |GPIO_PORTE|GPIO_PIN10) +#define GPIO_TSC_G5_IO2 (GPIO_ALT|GPIO_AF9 |GPIO_PORTE|GPIO_PIN11) +#define GPIO_TSC_G5_IO3 (GPIO_ALT|GPIO_AF9 |GPIO_PORTE|GPIO_PIN12) +#define GPIO_TSC_G5_IO4 (GPIO_ALT|GPIO_AF9 |GPIO_PORTE|GPIO_PIN13) + +#define GPIO_TSC_G6_IO1 (GPIO_ALT|GPIO_AF9 |GPIO_PORTD|GPIO_PIN10) +#define GPIO_TSC_G6_IO2 (GPIO_ALT|GPIO_AF9 |GPIO_PORTD|GPIO_PIN11) +#define GPIO_TSC_G6_IO3 (GPIO_ALT|GPIO_AF9 |GPIO_PORTD|GPIO_PIN12) +#define GPIO_TSC_G6_IO4 (GPIO_ALT|GPIO_AF9 |GPIO_PORTD|GPIO_PIN13) + +#define GPIO_TSC_G7_IO1 (GPIO_ALT|GPIO_AF9 |GPIO_PORTE|GPIO_PIN2) +#define GPIO_TSC_G7_IO2 (GPIO_ALT|GPIO_AF9 |GPIO_PORTE|GPIO_PIN3) +#define GPIO_TSC_G7_IO3 (GPIO_ALT|GPIO_AF9 |GPIO_PORTE|GPIO_PIN4) +#define GPIO_TSC_G7_IO4 (GPIO_ALT|GPIO_AF9 |GPIO_PORTE|GPIO_PIN5) + +#define GPIO_TSC_G8_IO1 (GPIO_ALT|GPIO_AF9 |GPIO_PORTF|GPIO_PIN14) +#define GPIO_TSC_G8_IO2 (GPIO_ALT|GPIO_AF9 |GPIO_PORTF|GPIO_PIN15) +#define GPIO_TSC_G8_IO3 (GPIO_ALT|GPIO_AF9 |GPIO_PORTG|GPIO_PIN0) +#define GPIO_TSC_G8_IO4 (GPIO_ALT|GPIO_AF9 |GPIO_PORTG|GPIO_PIN1) + +/* IR interface (with timers 16 and 17) */ + +#define GPIO_IR_OUT_1 (GPIO_ALT|GPIO_AF1 |GPIO_PORTA|GPIO_PIN13) +#define GPIO_IR_OUT_2 (GPIO_ALT|GPIO_AF1 |GPIO_PORTB|GPIO_PIN9) + +/* Trace */ + +#define GPIO_TRACECK (GPIO_ALT|GPIO_AF0 |GPIO_PORTE|GPIO_PIN2) +#define GPIO_TRACED0 (GPIO_ALT|GPIO_AF0 |GPIO_PORTE|GPIO_PIN3) +#define GPIO_TRACED1 (GPIO_ALT|GPIO_AF0 |GPIO_PORTE|GPIO_PIN4) +#define GPIO_TRACED2 (GPIO_ALT|GPIO_AF0 |GPIO_PORTE|GPIO_PIN5) +#define GPIO_TRACED3 (GPIO_ALT|GPIO_AF0 |GPIO_PORTE|GPIO_PIN6) + +/* UARTs/USARTs */ + +#define GPIO_USART1_TX_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN9) +#define GPIO_USART1_TX_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTB|GPIO_PIN6) +#define GPIO_USART1_TX_3 (GPIO_ALT|GPIO_AF7 |GPIO_PORTG|GPIO_PIN9) +#define GPIO_USART1_RX_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN10) +#define GPIO_USART1_RX_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTB|GPIO_PIN7) +#define GPIO_USART1_RX_3 (GPIO_ALT|GPIO_AF7 |GPIO_PORTG|GPIO_PIN10) +#define GPIO_USART1_CK_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN8) +#define GPIO_USART1_CK_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTB|GPIO_PIN5) +#define GPIO_USART1_CK_3 (GPIO_ALT|GPIO_AF7 |GPIO_PORTG|GPIO_PIN13) +#define GPIO_USART1_CTS_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN11) +#define GPIO_USART1_CTS_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTB|GPIO_PIN4) +#define GPIO_USART1_CTS_3 (GPIO_ALT|GPIO_AF7 |GPIO_PORTG|GPIO_PIN11) +#define GPIO_USART1_RTS_DE_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN12) +#define GPIO_USART1_RTS_DE_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTB|GPIO_PIN3) +#define GPIO_USART1_RTS_DE_3 (GPIO_ALT|GPIO_AF7 |GPIO_PORTG|GPIO_PIN12) + +#define GPIO_USART2_TX_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN2) +#define GPIO_USART2_TX_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN5) +#define GPIO_USART2_RX_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN3) +#define GPIO_USART2_RX_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN6) +#define GPIO_USART2_CK_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN4) +#define GPIO_USART2_CK_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN7) +#define GPIO_USART2_CTS_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN0) +#define GPIO_USART2_CTS_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN3) +#define GPIO_USART2_RTS_DE_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN1) +#define GPIO_USART2_RTS_DE_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN4) + +#define GPIO_USART3_TX_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTB|GPIO_PIN10) +#define GPIO_USART3_TX_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTC|GPIO_PIN4) +#define GPIO_USART3_TX_3 (GPIO_ALT|GPIO_AF7 |GPIO_PORTC|GPIO_PIN10) +#define GPIO_USART3_TX_4 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN8) +#define GPIO_USART3_RX_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTB|GPIO_PIN11) +#define GPIO_USART3_RX_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTC|GPIO_PIN5) +#define GPIO_USART3_RX_3 (GPIO_ALT|GPIO_AF7 |GPIO_PORTC|GPIO_PIN11) +#define GPIO_USART3_RX_4 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN9) +#define GPIO_USART3_CK_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTB|GPIO_PIN0) +#define GPIO_USART3_CK_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTB|GPIO_PIN12) +#define GPIO_USART3_CK_3 (GPIO_ALT|GPIO_AF7 |GPIO_PORTC|GPIO_PIN12) +#define GPIO_USART3_CK_4 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN10) +#define GPIO_USART3_CTS_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTA|GPIO_PIN6) +#define GPIO_USART3_CTS_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTB|GPIO_PIN13) +#define GPIO_USART3_CTS_3 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN11) +#define GPIO_USART3_RTS_DE_1 (GPIO_ALT|GPIO_AF7 |GPIO_PORTB|GPIO_PIN1) +#define GPIO_USART3_RTS_DE_2 (GPIO_ALT|GPIO_AF7 |GPIO_PORTB|GPIO_PIN14) +#define GPIO_USART3_RTS_DE_3 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN2) +#define GPIO_USART3_RTS_DE_4 (GPIO_ALT|GPIO_AF7 |GPIO_PORTD|GPIO_PIN12) + +#define GPIO_UART4_TX_1 (GPIO_ALT|GPIO_AF8 |GPIO_PORTA|GPIO_PIN0) +#define GPIO_UART4_TX_2 (GPIO_ALT|GPIO_AF8 |GPIO_PORTC|GPIO_PIN10) +#define GPIO_UART4_RX_1 (GPIO_ALT|GPIO_AF8 |GPIO_PORTA|GPIO_PIN1) +#define GPIO_UART4_RX_2 (GPIO_ALT|GPIO_AF8 |GPIO_PORTC|GPIO_PIN11) +#define GPIO_UART4_CTS (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN7) +#define GPIO_UART4_RTS_DE (GPIO_ALT|GPIO_AF8 |GPIO_PORTA|GPIO_PIN15) + +#define GPIO_UART5_TX (GPIO_ALT|GPIO_AF8 |GPIO_PORTC|GPIO_PIN12) +#define GPIO_UART5_RX (GPIO_ALT|GPIO_AF8 |GPIO_PORTD|GPIO_PIN2) +#define GPIO_UART5_CTS (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN5) +#define GPIO_UART5_RTS_DE (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN4) + +#define GPIO_LPUART1_TX_1 (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN11) +#define GPIO_LPUART1_TX_2 (GPIO_ALT|GPIO_AF8 |GPIO_PORTC|GPIO_PIN1) +#define GPIO_LPUART1_TX_3 (GPIO_ALT|GPIO_AF8 |GPIO_PORTG|GPIO_PIN7) +#define GPIO_LPUART1_RX_1 (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN10) +#define GPIO_LPUART1_RX_2 (GPIO_ALT|GPIO_AF8 |GPIO_PORTC|GPIO_PIN0) +#define GPIO_LPUART1_RX_3 (GPIO_ALT|GPIO_AF8 |GPIO_PORTG|GPIO_PIN8) +#define GPIO_LPUART1_CTS_1 (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN13) +#define GPIO_LPUART1_CTS_2 (GPIO_ALT|GPIO_AF8 |GPIO_PORTG|GPIO_PIN5) +#define GPIO_LPUART1_RTS_DE_1 (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN12) +#define GPIO_LPUART1_RTS_DE_2 (GPIO_ALT|GPIO_AF8 |GPIO_PORTG|GPIO_PIN6) + +#endif /* __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X5XX_PINMAP_H */ diff --git a/arch/arm/src/stm32l4/chip/stm32l4x6xx_pinmap.h b/arch/arm/src/stm32l4/chip/stm32l4x6xx_pinmap.h index 4fd685b717..c149e1dd01 100644 --- a/arch/arm/src/stm32l4/chip/stm32l4x6xx_pinmap.h +++ b/arch/arm/src/stm32l4/chip/stm32l4x6xx_pinmap.h @@ -233,7 +233,6 @@ #define GPIO_DFSDM_CKOUT_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTC|GPIO_PIN2) #define GPIO_DFSDM_CKOUT_2 (GPIO_ALT|GPIO_AF6 |GPIO_PORTE|GPIO_PIN9) - /* Flexible Static Memory Controller (FSMC) */ #define GPIO_FMC_NL (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN7) @@ -776,7 +775,7 @@ #define GPIO_LPTIM2_ETR_2 (GPIO_ALT|GPIO_AF14|GPIO_PORTC|GPIO_PIN3) #define GPIO_LPTIM2_ETR_3 (GPIO_ALT|GPIO_AF14|GPIO_PORTD|GPIO_PIN11) -/* Touch Screen Controller */ +/* Touch Sensing Controller */ #define GPIO_TSC_SYNC (GPIO_ALT|GPIO_AF9 |GPIO_PORTD|GPIO_PIN2) -- GitLab From 8b907c4c1f6ac40a99024a3b3bc5fb307088f3d4 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 8 Jun 2017 11:07:20 -0600 Subject: [PATCH 941/990] STM32L4: Fix a typo --- arch/arm/include/stm32l4/chip.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/arch/arm/include/stm32l4/chip.h b/arch/arm/include/stm32l4/chip.h index 1d278e6d71..99f13d2baa 100644 --- a/arch/arm/include/stm32l4/chip.h +++ b/arch/arm/include/stm32l4/chip.h @@ -96,7 +96,7 @@ # error "Unsupported STM32L4 chip" #endif -#if defined(CONFIG_STM32L4_STM32L4x5) +#if defined(CONFIG_STM32L4_STM32L4X5) # define STM32L4_NFSMC 1 /* Have FSMC memory controller */ # define STM32L4_NATIM 2 /* Two advanced timers TIM1 and 8 */ # define STM32L4_NGTIM32 2 /* 32-bit general timers TIM2 and 5 with DMA */ @@ -124,7 +124,7 @@ # define STM32L4_NCRC 1 /* CRC */ # define STM32L4_NCOMP 2 /* Comparators */ # define STM32L4_NOPAMP 2 /* Operational Amplifiers */ -#endif /* CONFIG_STM32L4_STM32L4x5 */ +#endif /* CONFIG_STM32L4_STM32L4X5 */ #if defined(CONFIG_STM32L4_STM32L4X6) # define STM32L4_NFSMC 1 /* Have FSMC memory controller */ -- GitLab From fb8cfe857e6bad9a19e80838f8f2276bbee1564e Mon Sep 17 00:00:00 2001 From: Nicolas Estibals Date: Thu, 8 Jun 2017 11:15:08 -0600 Subject: [PATCH 942/990] configs/stm32f103-minumum SPI: SPIDEV_WIRELESS used when this has changed to SPIDEV_CONTACTLESS --- configs/stm32f103-minimum/src/stm32_spi.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/configs/stm32f103-minimum/src/stm32_spi.c b/configs/stm32f103-minimum/src/stm32_spi.c index c2476ebcf1..49b950f212 100644 --- a/configs/stm32f103-minimum/src/stm32_spi.c +++ b/configs/stm32f103-minimum/src/stm32_spi.c @@ -136,7 +136,7 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, #endif #if defined(CONFIG_CL_MFRC522) - if (devid == SPIDEV_WIRELESS(0)) + if (devid == SPIDEV_CONTACTLESS(0)) { stm32_gpiowrite(GPIO_CS_MFRC522, !selected); } @@ -157,7 +157,7 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, #endif #ifdef CONFIG_WL_NRF24L01 - if (devid == SPIDEV_WIRELESS(0)) + if (devid == SPIDEV_CONTACTLESS(0)) { stm32_gpiowrite(GPIO_NRF24L01_CS, !selected); } @@ -176,7 +176,7 @@ uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) uint8_t status = 0; #ifdef CONFIG_WL_NRF24L01 - if (devid == SPIDEV_WIRELESS(0)) + if (devid == SPIDEV_CONTACTLESS(0)) { status |= SPI_STATUS_PRESENT; } -- GitLab From 04eefd7c8b140be5b3b6be3571ad2f189c35fc0d Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Thu, 8 Jun 2017 11:23:46 -0600 Subject: [PATCH 943/990] stm32f103-minimum: dd GPIO device driver example for STM32F103-Minimum. This chang adds the initialization needed by stm32f103-minimum board to support the NuttX GPIO Subsystem. --- configs/stm32f103-minimum/src/Makefile | 4 + configs/stm32f103-minimum/src/stm32_bringup.c | 9 + configs/stm32f103-minimum/src/stm32_gpio.c | 305 ++++++++++++++++++ .../stm32f103-minimum/src/stm32f103_minimum.h | 24 ++ 4 files changed, 342 insertions(+) create mode 100644 configs/stm32f103-minimum/src/stm32_gpio.c diff --git a/configs/stm32f103-minimum/src/Makefile b/configs/stm32f103-minimum/src/Makefile index ff51903c02..b8f5c1f3d8 100644 --- a/configs/stm32f103-minimum/src/Makefile +++ b/configs/stm32f103-minimum/src/Makefile @@ -53,6 +53,10 @@ else CSRCS += stm32_userleds.c endif +ifeq ($(CONFIG_DEV_GPIO),y) +CSRCS += stm32_gpio.c +endif + ifeq ($(CONFIG_PWM),y) CSRCS += stm32_pwm.c endif diff --git a/configs/stm32f103-minimum/src/stm32_bringup.c b/configs/stm32f103-minimum/src/stm32_bringup.c index 00c9f89e0a..1d2542f0a4 100644 --- a/configs/stm32f103-minimum/src/stm32_bringup.c +++ b/configs/stm32f103-minimum/src/stm32_bringup.c @@ -112,6 +112,15 @@ int stm32_bringup(void) #endif int ret = OK; +#ifdef CONFIG_DEV_GPIO + ret = stm32_gpio_initialize(); + if (ret < 0) + { + syslog(LOG_ERR, "Failed to initialize GPIO Driver: %d\n", ret); + return ret; + } +#endif + #ifdef CONFIG_MMCSD ret = stm32_mmcsd_initialize(MMCSD_MINOR); if (ret < 0) diff --git a/configs/stm32f103-minimum/src/stm32_gpio.c b/configs/stm32f103-minimum/src/stm32_gpio.c new file mode 100644 index 0000000000..03c0e1da0b --- /dev/null +++ b/configs/stm32f103-minimum/src/stm32_gpio.c @@ -0,0 +1,305 @@ +/**************************************************************************** + * configs/stm32f103-minimum/src/stm32_gpio.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Copyright (C) 2017 Alan Carvalho de Assis. All rights reserved. + * Author: Alan Carvalho de Assis + * + * Based on: configs/sim/src/sim_gpio.c + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include +#include +#include + +#include + +#include "chip.h" +#include "stm32.h" +#include "stm32f103_minimum.h" + +#if defined(CONFIG_DEV_GPIO) && !defined(CONFIG_GPIO_LOWER_HALF) + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct stm32gpio_dev_s +{ + struct gpio_dev_s gpio; + uint8_t id; + bool value; +}; + +struct stm32gpint_dev_s +{ + struct stm32gpio_dev_s stm32gpio; + pin_interrupt_t callback; +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static int gpin_read(FAR struct gpio_dev_s *dev, FAR bool *value); +static int gpout_write(FAR struct gpio_dev_s *dev, bool value); +static int gpint_attach(FAR struct gpio_dev_s *dev, + pin_interrupt_t callback); +static int gpint_enable(FAR struct gpio_dev_s *dev, bool enable); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const struct gpio_operations_s gpin_ops = +{ + .go_read = gpin_read, + .go_write = NULL, + .go_attach = NULL, + .go_enable = NULL, +}; + +static const struct gpio_operations_s gpout_ops = +{ + .go_read = gpin_read, + .go_write = gpout_write, + .go_attach = NULL, + .go_enable = NULL, +}; + +static const struct gpio_operations_s gpint_ops = +{ + .go_read = gpin_read, + .go_write = NULL, + .go_attach = gpint_attach, + .go_enable = gpint_enable, +}; + +#if BOARD_NGPIOIN > 0 +/* This array maps the GPIO pins used as INPUT */ + +static const uint32_t g_gpioinputs[BOARD_NGPIOIN] = +{ + GPIO_IN1, +}; + +static struct stm32gpio_dev_s g_gpin[BOARD_NGPIOIN]; +#endif + +#if BOARD_NGPIOOUT +/* This array maps the GPIO pins used as OUTPUT */ + +static const uint32_t g_gpiooutputs[BOARD_NGPIOOUT] = +{ + GPIO_OUT1, +}; + +static struct stm32gpio_dev_s g_gpout[BOARD_NGPIOOUT]; +#endif + +#if BOARD_NGPIOINT > 0 +/* This array maps the GPIO pins used as INTERRUPT INPUTS */ + +static const uint32_t g_gpiointinputs[BOARD_NGPIOINT] = +{ + GPIO_INT1, +}; + +static struct stm32gpint_dev_s g_gpint[BOARD_NGPIOINT]; +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static int stm32gpio_interrupt(int irq, void *context, void *arg) +{ + FAR struct stm32gpint_dev_s *stm32gpint = (FAR struct stm32gpint_dev_s *)arg; + + DEBUGASSERT(stm32gpint != NULL && stm32gpint->callback != NULL); + gpioinfo("Interrupt! callback=%p\n", stm32gpint->callback); + + stm32gpint->callback(&stm32gpint->stm32gpio.gpio); + return OK; +} + +static int gpin_read(FAR struct gpio_dev_s *dev, FAR bool *value) +{ + FAR struct stm32gpio_dev_s *stm32gpio = (FAR struct stm32gpio_dev_s *)dev; + + DEBUGASSERT(stm32gpio != NULL && value != NULL); + gpioinfo("Reading...\n"); + + *value = stm32_gpioread(g_gpioinputs[stm32gpio->id]); + return OK; +} + +static int gpout_write(FAR struct gpio_dev_s *dev, bool value) +{ + FAR struct stm32gpio_dev_s *stm32gpio = (FAR struct stm32gpio_dev_s *)dev; + + DEBUGASSERT(stm32gpio != NULL); + gpioinfo("Writing %d\n", (int)value); + + stm32_gpiowrite(g_gpiooutputs[stm32gpio->id], value); + return OK; +} + +static int gpint_attach(FAR struct gpio_dev_s *dev, + pin_interrupt_t callback) +{ + FAR struct stm32gpint_dev_s *stm32gpint = (FAR struct stm32gpint_dev_s *)dev; + + gpioinfo("Attaching the callback\n"); + + /* Make sure the interrupt is disabled */ + + (void)stm32_gpiosetevent(g_gpiointinputs[stm32gpint->stm32gpio.id], false, + false, false, NULL, NULL); + + gpioinfo("Attach %p\n", callback); + stm32gpint->callback = callback; + return OK; +} + +static int gpint_enable(FAR struct gpio_dev_s *dev, bool enable) +{ + FAR struct stm32gpint_dev_s *stm32gpint = (FAR struct stm32gpint_dev_s *)dev; + + if (enable) + { + if (stm32gpint->callback != NULL) + { + gpioinfo("Enabling the interrupt\n"); + + /* Configure the interrupt for rising edge */ + + (void)stm32_gpiosetevent(g_gpiointinputs[stm32gpint->stm32gpio.id], + true, false, false, stm32gpio_interrupt, + &g_gpint[stm32gpint->stm32gpio.id]); + + } + } + else + { + gpioinfo("Disable the interrupt\n"); + (void)stm32_gpiosetevent(g_gpiointinputs[stm32gpint->stm32gpio.id], + false, false, false, NULL, NULL); + } + + return OK; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_gpio_initialize + * + * Description: + * Initialize GPIO drivers for use with /apps/examples/gpio + * + ****************************************************************************/ + +int stm32_gpio_initialize(void) +{ + int i; + int pincount = 0; + +#if BOARD_NGPIOIN > 0 + for (i = 0; i < BOARD_NGPIOIN; i++) + { + /* Setup and register the GPIO pin */ + + g_gpin[i].gpio.gp_pintype = GPIO_INPUT_PIN; + g_gpin[i].gpio.gp_ops = &gpin_ops; + g_gpin[i].id = i; + (void)gpio_pin_register(&g_gpin[i].gpio, pincount); + + /* Configure the pin that will be used as input */ + + stm32_configgpio(g_gpioinputs[i]); + + pincount++; + } +#endif + +#if BOARD_NGPIOOUT > 0 + for (i = 0; i < BOARD_NGPIOOUT; i++) + { + /* Setup and register the GPIO pin */ + + g_gpout[i].gpio.gp_pintype = GPIO_OUTPUT_PIN; + g_gpout[i].gpio.gp_ops = &gpout_ops; + g_gpout[i].id = i; + (void)gpio_pin_register(&g_gpout[i].gpio, pincount); + + /* Configure the pin that will be used as output */ + + stm32_configgpio(g_gpiooutputs[i]); + + pincount++; + } +#endif + +#if BOARD_NGPIOINT > 0 + for (i = 0; i < BOARD_NGPIOINT; i++) + { + /* Setup and register the GPIO pin */ + + g_gpint[i].stm32gpio.gpio.gp_pintype = GPIO_INTERRUPT_PIN; + g_gpint[i].stm32gpio.gpio.gp_ops = &gpint_ops; + g_gpint[i].stm32gpio.id = i; + (void)gpio_pin_register(&g_gpint[i].stm32gpio.gpio, pincount); + + /* Configure the pin that will be used as interrupt input */ + + stm32_configgpio(g_gpiointinputs[i]); + + pincount++; + } +#endif + + return 0; +} +#endif /* CONFIG_DEV_GPIO && !CONFIG_GPIO_LOWER_HALF */ diff --git a/configs/stm32f103-minimum/src/stm32f103_minimum.h b/configs/stm32f103-minimum/src/stm32f103_minimum.h index ada0a38f74..17c2e4c5e0 100644 --- a/configs/stm32f103-minimum/src/stm32f103_minimum.h +++ b/configs/stm32f103-minimum/src/stm32f103_minimum.h @@ -129,6 +129,18 @@ #define GPIO_USB_PULLUP (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\ GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN13) +/* GPIO pins used by the GPIO Subsystem */ + +#define BOARD_NGPIOIN 1 /* Amount of GPIO Input pins */ +#define BOARD_NGPIOOUT 1 /* Amount of GPIO Output pins */ +#define BOARD_NGPIOINT 1 /* Amount of GPIO Input w/ Interruption pins */ + +#define GPIO_IN1 (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_PORTA|GPIO_PIN0) +#define GPIO_OUT1 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\ + GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN1) + +#define GPIO_INT1 (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_PORTA|GPIO_PIN2) + /************************************************************************************ * Public Functions ************************************************************************************/ @@ -155,6 +167,18 @@ int stm32_bringup(void); +/**************************************************************************** + * Name: stm32_gpio_initialize + * + * Description: + * Initialize GPIO drivers for use with /apps/examples/gpio + * + ****************************************************************************/ + +#ifdef CONFIG_DEV_GPIO +int stm32_gpio_initialize(void); +#endif + /************************************************************************************ * Name: stm32_spidev_initialize * -- GitLab From 30cbb3059fa3329e388400c5c1945be60166b29b Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 8 Jun 2017 13:12:08 -0600 Subject: [PATCH 944/990] Cosmetic: Removing trailing whitespace at the end of lines. --- configs/stm32f103-minimum/src/stm32_gpio.c | 4 ++-- configs/stm32f103-minimum/src/stm32_mfrc522.c | 2 +- configs/stm32f103-minimum/src/stm32_tone.c | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/configs/stm32f103-minimum/src/stm32_gpio.c b/configs/stm32f103-minimum/src/stm32_gpio.c index 03c0e1da0b..6335acc4a3 100644 --- a/configs/stm32f103-minimum/src/stm32_gpio.c +++ b/configs/stm32f103-minimum/src/stm32_gpio.c @@ -181,14 +181,14 @@ static int gpout_write(FAR struct gpio_dev_s *dev, bool value) gpioinfo("Writing %d\n", (int)value); stm32_gpiowrite(g_gpiooutputs[stm32gpio->id], value); - return OK; + return OK; } static int gpint_attach(FAR struct gpio_dev_s *dev, pin_interrupt_t callback) { FAR struct stm32gpint_dev_s *stm32gpint = (FAR struct stm32gpint_dev_s *)dev; - + gpioinfo("Attaching the callback\n"); /* Make sure the interrupt is disabled */ diff --git a/configs/stm32f103-minimum/src/stm32_mfrc522.c b/configs/stm32f103-minimum/src/stm32_mfrc522.c index d55842eca7..441bc5a6fa 100644 --- a/configs/stm32f103-minimum/src/stm32_mfrc522.c +++ b/configs/stm32f103-minimum/src/stm32_mfrc522.c @@ -88,7 +88,7 @@ int stm32_mfrc522initialize(FAR const char *devpath) } /* Then register the MFRC522 */ - + ret = mfrc522_register(devpath, spi); if (ret < 0) { diff --git a/configs/stm32f103-minimum/src/stm32_tone.c b/configs/stm32f103-minimum/src/stm32_tone.c index 4afeb09f82..80449d56c6 100644 --- a/configs/stm32f103-minimum/src/stm32_tone.c +++ b/configs/stm32f103-minimum/src/stm32_tone.c @@ -2,7 +2,7 @@ * configs/stm32f103minimum/src/stm32_tone.c * * Copyright (C) 2016 Gregory Nutt. All rights reserved. - * Author: Alan Carvalho de Assis + * Author: Alan Carvalho de Assis * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions -- GitLab From 1e5125c5d5e69ea9894d9626ece57ae5be4585a1 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 8 Jun 2017 13:43:47 -0600 Subject: [PATCH 945/990] STM32L4: Remove some C++ style comments. --- arch/arm/src/stm32l4/chip/stm32l4x5xx_otgfs.h | 8 ++- arch/arm/src/stm32l4/chip/stm32l4x6xx_otgfs.h | 58 ++++++++++++------- 2 files changed, 41 insertions(+), 25 deletions(-) diff --git a/arch/arm/src/stm32l4/chip/stm32l4x5xx_otgfs.h b/arch/arm/src/stm32l4/chip/stm32l4x5xx_otgfs.h index ce7d8dd80d..ddbb5b0ce5 100644 --- a/arch/arm/src/stm32l4/chip/stm32l4x5xx_otgfs.h +++ b/arch/arm/src/stm32l4/chip/stm32l4x5xx_otgfs.h @@ -450,7 +450,9 @@ #define OTGFS_GCCFG_VBDEN (1 << 21) /* Bit 21: USB VBUS detection enable */ /* Bits 22-31: Reserved, must be kept at reset value */ -/* Core ID register (32-bit product ID) */ +/* Core ID register (32-bit product ID) */ + +/* LPM configuration register */ #define OTGFS_GLPMCFG_LPMEN (1 << 0) /* Bit 0: XXX */ #define OTGFS_GLPMCFG_LPMACK (1 << 1) /* Bit 1: XXX */ @@ -475,12 +477,12 @@ #define OTGFS_GLPMCFG_ENBESL (1 << 28) /* Bit 28: XXX */ /* Bits 29-31: Reserved, must be kept at reset value */ -/* GPWRDN */ +/* Power down register */ #define OTGFS_GPWRDN_ADPMEN (1 << 0) /* Bit 0: XXX */ #define OTGFS_GPWRDN_ADPIF (1 << 23) /* Bit 23: XXX */ -/* GADPCTL */ +/* ADP timer, control and status register */ #define OTGFS_GADPCTL_PRBDSCHG_SHIFT (0) /* Bits 0-1: XXX */ #define OTGFS_GADPCTL_PRBDSCHG_MASK (3 << OTGFS_GADPCTL_PRBDSCHG_SHIFT) diff --git a/arch/arm/src/stm32l4/chip/stm32l4x6xx_otgfs.h b/arch/arm/src/stm32l4/chip/stm32l4x6xx_otgfs.h index 49874d7233..a01427ea72 100644 --- a/arch/arm/src/stm32l4/chip/stm32l4x6xx_otgfs.h +++ b/arch/arm/src/stm32l4/chip/stm32l4x6xx_otgfs.h @@ -439,7 +439,9 @@ # define OTGFS_HNPTXSTS_EPNUM_SHIFT (27) /* Bits 27-30: Endpoint number */ # define OTGFS_HNPTXSTS_EPNUM_MASK (15 << OTGFS_HNPTXSTS_EPNUM_SHIFT) /* Bit 31 Reserved, must be kept at reset value */ + /* General core configuration register */ + #define OTGFS_GCCFG_DCDET (1 << 0) /* Bit 0: Data contact detect */ #define OTGFS_GCCFG_PDET (1 << 1) /* Bit 1: Primary detect */ #define OTGFS_GCCFG_SDET (1 << 2) /* Bit 2: Secondary detect */ @@ -453,35 +455,48 @@ #define OTGFS_GCCFG_VBDEN (1 << 21) /* Bit 21: USB VBUS detection enable */ /* Bits 22-31: Reserved, must be kept at reset value */ -/* Core ID register (32-bit product ID) */ +/* Core ID register (32-bit product ID) */ + +/* LPM configuration register */ -//XXX GLPMCFG -#define OTGFS_GLPMCFG_LPMEN (1 << 0) /* Bit 0: XXX */ -#define OTGFS_GLPMCFG_LPMACK (1 << 1) /* Bit 1: XXX */ -//#define OTGFS_GLPMCFG_BESL -#define OTGFS_GLPMCFG_REMWAKE (1 << 6) /* Bit 6: XXX */ -#define OTGFS_GLPMCFG_L1SSEN (1 << 7) /* Bit 7: XXX */ -//#define OTGFS_GLPMCFG_BESLTHRS +#define OTGFS_GLPMCFG_LPMEN (1 << 0) /* Bit 0: XXX */ +#define OTGFS_GLPMCFG_LPMACK (1 << 1) /* Bit 1: XXX */ +#define OTGFS_GLPMCFG_BESL_SHIFT (2) /* Bits 2-5: XXX */ +#define OTGFS_GLPMCFG_BESL_MASK (15 << OTGFS_GLPMCFG_BESL_SHIFT) +#define OTGFS_GLPMCFG_REMWAKE (1 << 6) /* Bit 6: XXX */ +#define OTGFS_GLPMCFG_L1SSEN (1 << 7) /* Bit 7: XXX */ +#define OTGFS_GLPMCFG_BESLTHRS_SHIFT (8) /* Bits 8-11: XXX */ +#define OTGFS_GLPMCFG_BESLTHRS_MASK (15 << OTGFS_GLPMCFG_BESLTHRS_SHIFT) #define OTGFS_GLPMCFG_L1DSEN (1 << 12) /* Bit 12: XXX */ -//#define OTGFS_GLPMCFG_LPMRSP +#define OTGFS_GLPMCFG_LPMRSP_SHIFT (13) /* Bits 13-14: XXXX */ +#define OTGFS_GLPMCFG_LPMRSP_MASK (3 << OTGFS_GLPMCFG_LPMRSP_SHIFT) #define OTGFS_GLPMCFG_SLPSTS (1 << 15) /* Bit 15: XXX */ #define OTGFS_GLPMCFG_L1RSMOK (1 << 16) /* Bit 16: XXX */ -//#define OTGFS_GLPMCFG_LPMCHIDX -//#define OTGFS_GLPMCFG_LPMRCNT +#define OTGFS_GLPMCFG_LPMCHIDX_SHIFT (17) /* Bits 17-20: XXX */ +#define OTGFS_GLPMCFG_LPMCHIDX_MASK (15 << OTGFS_GLPMCFG_LPMCHIDX_SHIFT) +#define OTGFS_GLPMCFG_LPMRCNT_SHIFT (21) /* Bits 21-23: XXX */ +#define OTGFS_GLPMCFG_LPMRCNT_MASK (7 << OTGFS_GLPMCFG_LPMRCNT_SHIFT) #define OTGFS_GLPMCFG_SNDLPM (1 << 24) /* Bit 24: XXX */ -//#define OTGFS_GLPMCFG_LPMRCNTSTS +#define OTGFS_GLPMCFG_LPMRCNTSTS_SHIFT (25) /* Bits 25-27: XXX */ +#define OTGFS_GLPMCFG_LPMRCNTSTS_MASK (7 << OTGFS_GLPMCFG_LPMRCNTSTS_SHIFT) #define OTGFS_GLPMCFG_ENBESL (1 << 28) /* Bit 28: XXX */ /* Bits 29-31: Reserved, must be kept at reset value */ -//XXX GPWRDN -#define OTGFS_GPWRDN_ADPMEN (1 << 0) /* Bit 0: XXX */ +/* Power down register */ + +#define OTGFS_GPWRDN_ADPMEN (1 << 0) /* Bit 0: XXX */ #define OTGFS_GPWRDN_ADPIF (1 << 23) /* Bit 23: XXX */ -//XXX GADPCTL -//#define OTGFS_GADPCTL_PRBDSCHG -//#define OTGFS_GADPCTL_PRBDELTA -//#define OTGFS_GADPCTL_PRBPER -//#define OTGFS_GADPCTL_RTIM +/* ADP timer, control and status register */ + +#define OTGFS_GADPCTL_PRBDSCHG_SHIFT (0) /* Bits 0-1: XXX */ +#define OTGFS_GADPCTL_PRBDSCHG_MASK (3 << OTGFS_GADPCTL_PRBDSCHG_SHIFT) +#define OTGFS_GADPCTL_PRBDELTA_SHIFT (2) /* Bits 2-3: XXX */ +#define OTGFS_GADPCTL_PRBDELTA_MASK (3 << OTGFS_GADPCTL_PRBDELTA_SHIFT) +#define OTGFS_GADPCTL_PRBPER_SHIFT (4) /* Bits 4-5: XXX */ +#define OTGFS_GADPCTL_PRBPER_MASK (15 << OTGFS_GADPCTL_PRBPER_SHIFT) +#define OTGFS_GADPCTL_RTIM_SHIFT (6) /* Bits 6-9: XXX */ +#define OTGFS_GADPCTL_RTIM_SHIFT (6) /* Bits 6-9: XXX */ #define OTGFS_GADPCTL_ENAPRB (1 << 17) /* Bit 17: XXX */ #define OTGFS_GADPCTL_ENASNS (1 << 18) /* Bit 18: XXX */ #define OTGFS_GADPCTL_ADPRST (1 << 19) /* Bit 19: XXX */ @@ -492,7 +507,8 @@ #define OTGFS_GADPCTL_ADPPRBIM (1 << 24) /* Bit 24: XXX */ #define OTGFS_GADPCTL_ADPSNSIM (1 << 25) /* Bit 25: XXX */ #define OTGFS_GADPCTL_ADPTOIM (1 << 26) /* Bit 26: XXX */ -//#define OTGFS_GADPCTL_AR +#define OTGFS_GADPCTL_AR_SHIFT (27) /* Bits 27-28: XXX */ +#define OTGFS_GADPCTL_AR_MASK (3 << OTGFS_GADPCTL_AR_SHIFT) /* Host periodic transmit FIFO size register */ @@ -622,7 +638,6 @@ #define OTGFS_HCINT_STALL (1 << 3) /* Bit 3: STALL response received interrupt */ #define OTGFS_HCINT_NAK (1 << 4) /* Bit 4: NAK response received interrupt */ #define OTGFS_HCINT_ACK (1 << 5) /* Bit 5: ACK response received/transmitted interrupt */ -//#define OTGFS_HCINT_NYET (1 << 6) /* Bit 6: Response received interrupt */ #define OTGFS_HCINT_TXERR (1 << 7) /* Bit 7: Transaction error */ #define OTGFS_HCINT_BBERR (1 << 8) /* Bit 8: Babble error */ #define OTGFS_HCINT_FRMOR (1 << 9) /* Bit 9: Frame overrun */ @@ -704,7 +719,6 @@ #define OTGFS_DSTS_SOFFN_ODD OTGFS_DSTS_SOFFN0 #define OTGFS_DSTS_DEVLNSTS_SHIFT (22) /* Bits 22-23: XXX */ #define OTGFS_DSTS_DEVLNSTS_MASK (0x3 << OTGFS_DSTS_DEVLNSTS_SHIFT) -//XXX /* Bits 24-31: Reserved, must be kept at reset value */ /* Device IN endpoint common interrupt mask register */ -- GitLab From 44b532e648fefdecfe0388ff981cba0c96a9b532 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 8 Jun 2017 14:42:31 -0600 Subject: [PATCH 946/990] configs/: a few more places where SPIDEV_WIRELELSS should be SPIDEV_CONTACTLESS. --- configs/shenzhou/src/stm32_spi.c | 2 +- configs/stm32_tiny/src/stm32_spi.c | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/configs/shenzhou/src/stm32_spi.c b/configs/shenzhou/src/stm32_spi.c index 6aeee5018b..277a5f27b4 100644 --- a/configs/shenzhou/src/stm32_spi.c +++ b/configs/shenzhou/src/stm32_spi.c @@ -179,7 +179,7 @@ void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) stm32_gpiowrite(GPIO_LCDSD_CS, !selected); } - else if (devid == SPIDEV_WIRELESS(0)) + else if (devid == SPIDEV_CONTACTLESS(0)) { /* Set the GPIO low to select and high to de-select */ diff --git a/configs/stm32_tiny/src/stm32_spi.c b/configs/stm32_tiny/src/stm32_spi.c index abaac37b9e..c1ed253abb 100644 --- a/configs/stm32_tiny/src/stm32_spi.c +++ b/configs/stm32_tiny/src/stm32_spi.c @@ -125,7 +125,7 @@ void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) switch(devid) { #ifdef CONFIG_WL_NRF24L01 - case SPIDEV_WIRELESS(0): + case SPIDEV_CONTACTLESS(0): spiinfo("nRF24L01 device %s\n", selected ? "asserted" : "de-asserted"); /* Set the GPIO low to select and high to de-select */ @@ -144,7 +144,7 @@ uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) switch(devid) { #ifdef CONFIG_WL_NRF24L01 - case SPIDEV_WIRELESS(0): + case SPIDEV_CONTACTLESS(0): status |= SPI_STATUS_PRESENT; break; #endif -- GitLab From bf6709b887bf16034eae089ee8ab6181887ff8fc Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 8 Jun 2017 15:34:13 -0600 Subject: [PATCH 947/990] configs/: Back out many of the changes in two recent commits: Too many changes from SPIDEV_WIRELESS to SPIDEV_CONTACTLESS. Specifically NRF24L01 should still be SPIDEV_WIRELESS. --- configs/shenzhou/src/stm32_spi.c | 2 +- configs/stm32_tiny/src/stm32_spi.c | 4 ++-- configs/stm32f103-minimum/src/stm32_spi.c | 4 ++-- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/configs/shenzhou/src/stm32_spi.c b/configs/shenzhou/src/stm32_spi.c index 277a5f27b4..6aeee5018b 100644 --- a/configs/shenzhou/src/stm32_spi.c +++ b/configs/shenzhou/src/stm32_spi.c @@ -179,7 +179,7 @@ void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) stm32_gpiowrite(GPIO_LCDSD_CS, !selected); } - else if (devid == SPIDEV_CONTACTLESS(0)) + else if (devid == SPIDEV_WIRELESS(0)) { /* Set the GPIO low to select and high to de-select */ diff --git a/configs/stm32_tiny/src/stm32_spi.c b/configs/stm32_tiny/src/stm32_spi.c index c1ed253abb..abaac37b9e 100644 --- a/configs/stm32_tiny/src/stm32_spi.c +++ b/configs/stm32_tiny/src/stm32_spi.c @@ -125,7 +125,7 @@ void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) switch(devid) { #ifdef CONFIG_WL_NRF24L01 - case SPIDEV_CONTACTLESS(0): + case SPIDEV_WIRELESS(0): spiinfo("nRF24L01 device %s\n", selected ? "asserted" : "de-asserted"); /* Set the GPIO low to select and high to de-select */ @@ -144,7 +144,7 @@ uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) switch(devid) { #ifdef CONFIG_WL_NRF24L01 - case SPIDEV_CONTACTLESS(0): + case SPIDEV_WIRELESS(0): status |= SPI_STATUS_PRESENT; break; #endif diff --git a/configs/stm32f103-minimum/src/stm32_spi.c b/configs/stm32f103-minimum/src/stm32_spi.c index 49b950f212..b638281f21 100644 --- a/configs/stm32f103-minimum/src/stm32_spi.c +++ b/configs/stm32f103-minimum/src/stm32_spi.c @@ -157,7 +157,7 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, #endif #ifdef CONFIG_WL_NRF24L01 - if (devid == SPIDEV_CONTACTLESS(0)) + if (devid == SPIDEV_WIRELESS(0)) { stm32_gpiowrite(GPIO_NRF24L01_CS, !selected); } @@ -176,7 +176,7 @@ uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) uint8_t status = 0; #ifdef CONFIG_WL_NRF24L01 - if (devid == SPIDEV_CONTACTLESS(0)) + if (devid == SPIDEV_WIRELESS(0)) { status |= SPI_STATUS_PRESENT; } -- GitLab From 18289e17ce26237f04daf28880fb4f28b6a289e6 Mon Sep 17 00:00:00 2001 From: Jim Paris Date: Fri, 9 Jun 2017 07:16:00 -0600 Subject: [PATCH 948/990] Fix C++ __guard implementation for ARM. The standard C++ ABI that most platforms follow defines __guard to be 64 bits. The existing implementation of libxx_cxa_guard.cxx follows this. However, the 32-bit ARM C++ ABI defines it as 32 bits instead, and changes the meaning slightly so only the lowest bit is used. This matters because GCC creates guard symbols without regards to what libxx_cxa_guard.cxx says. So on ARM, gcc allocates 4 bytes, but __cxa_guard_release writes 8 bytes, zeroing out another unlucky variable nearby. Fix it by special-casing 32-bit ARM in libxx_cxa_guard. --- libxx/libxx_cxa_guard.cxx | 24 +++++++++++++++++++++++- 1 file changed, 23 insertions(+), 1 deletion(-) diff --git a/libxx/libxx_cxa_guard.cxx b/libxx/libxx_cxa_guard.cxx index 47e9c4ea8d..8612400bcd 100644 --- a/libxx/libxx_cxa_guard.cxx +++ b/libxx/libxx_cxa_guard.cxx @@ -38,6 +38,7 @@ //*************************************************************************** #include +#include //*************************************************************************** // Pre-processor Definitions @@ -47,7 +48,20 @@ // Private Types //*************************************************************************** +#ifdef __ARM_EABI__ +// The 32-bit ARM C++ ABI specifies that the guard is a 32-bit +// variable and the least significant bit contains 0 prior to +// initialization, and 1 after. + +typedef int __guard; + +#else +// The "standard" C++ ABI specifies that the guard is a 64-bit +// variable and the first byte contains 0 prior to initialization, and +// 1 after. + __extension__ typedef int __guard __attribute__((mode(__DI__))); +#endif //*************************************************************************** // Private Data @@ -65,7 +79,11 @@ extern "C" int __cxa_guard_acquire(FAR __guard *g) { - return !*g; +#ifdef __ARM_EABI__ + return !(*g & 1); +#else + return !*(char *)g; +#endif } //************************************************************************* @@ -74,7 +92,11 @@ extern "C" void __cxa_guard_release(FAR __guard *g) { +#ifdef __ARM_EABI__ *g = 1; +#else + *(char *)g = 1; +#endif } //************************************************************************* -- GitLab From 4504ca7c82ef76e665128825fb4cf78feb65891d Mon Sep 17 00:00:00 2001 From: Jim Paris Date: Fri, 9 Jun 2017 07:40:31 -0600 Subject: [PATCH 949/990] Whoops -- that #include wasn't supposed to sneak in there. If present, it may already define a __cxxabiv1::__guard that we could use, but that file comes from libstdc++, and I don't think the NuttX buildroot-based toolchain would have that, which is why we need libxx in the first place. --- libc/netdb/lib_gethostbynamer.c | 2 +- libxx/libxx_cxa_guard.cxx | 1 - 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/libc/netdb/lib_gethostbynamer.c b/libc/netdb/lib_gethostbynamer.c index e95d9a853a..9e1a924bdf 100644 --- a/libc/netdb/lib_gethostbynamer.c +++ b/libc/netdb/lib_gethostbynamer.c @@ -546,7 +546,7 @@ static int lib_dns_lookup(FAR const char *name, FAR struct hostent *host, ptr += addrlen; buflen -= addrlen; - /* And copy name */ + /* And copy the name */ namelen = strlen(name); if (addrlen + namelen + 1 > buflen) diff --git a/libxx/libxx_cxa_guard.cxx b/libxx/libxx_cxa_guard.cxx index 8612400bcd..995ef7b7b1 100644 --- a/libxx/libxx_cxa_guard.cxx +++ b/libxx/libxx_cxa_guard.cxx @@ -38,7 +38,6 @@ //*************************************************************************** #include -#include //*************************************************************************** // Pre-processor Definitions -- GitLab From d1f69822d85d30862857b7891f5f0d33a1d939d2 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 9 Jun 2017 11:02:08 -0600 Subject: [PATCH 950/990] Update Coding Standard Document. --- Documentation/NuttXCCodingStandard.html | 67 ++++++++++++++++++++++--- 1 file changed, 61 insertions(+), 6 deletions(-) diff --git a/Documentation/NuttXCCodingStandard.html b/Documentation/NuttXCCodingStandard.html index 7d65a766a2..a116f981e7 100644 --- a/Documentation/NuttXCCodingStandard.html +++ b/Documentation/NuttXCCodingStandard.html @@ -12,7 +12,7 @@

            NuttX C Coding Standard

            -

            Last Updated: May 6, 2017

            +

            Last Updated: June 9, 2017

            @@ -736,12 +736,25 @@ void some_function(void)
            • Always on Separate Lines. - Braces always appear on a separate line containing nothing else other that white space. + Braces always appear on a separate line containing nothing else other than white space.
            • Never Comments on Braces. Do not put comments on the same line as braces.
            • +
            • + Compound Statements. + Within this document, an opening left brace followed by a sequence of statments, and ending with a closing right brace is refered to as a compound statement. +
            • +
            • + Nested Compound Statements. + In the case where there are nested compound statements that end with several consecutive right braces, each closing right brace must lie on a separate line and must be indented to match the corresponding opening brace. +
            • +
            • + Final brace followed by a single blank line. + The final right brace must be followed by a blank line as per standard rules. + In the case where there are nested several consecutive right braces, no blank lines should be inserted except for after the final right brace. +
            • Special Indentation Rules. Special indentation rules apply to braces. @@ -763,6 +776,19 @@ while (true) ... } /* not valid */ } /* end forever */ +if (a < b) { + if (a < 0) { + c = -a; + } else { + c = a; + } +} else { + if (b < 0) { + c = -b; + } else { + c = b; + } +}
            @@ -779,12 +805,36 @@ while (true) ... } } + +if (a < b) + { + if (a < 0) + { + c = -a; + } + else + { + c = a; + } + } +else + { + if (b < 0) + { + c = -b; + } + else + { + c = b; + } + } +

          - Exceptions. + Exception to Indentation Rule for Braces. The exception is braces that following structure, enumeration, union, and function declarations. There is no additional indentation for those braces; those braces align with the beginning of the definition @@ -854,6 +904,7 @@ int animals(int animal) { ... } +

        @@ -2123,11 +2174,15 @@ x++;
      • Braces and indentation. - The placement of braces and statements must follow the standard rules for braces and indentation. + The placement of braces and statements must follow the standard rules for braces and indentation.
      • - Followed by a single blank line. - The final right brace must be followed by a blank line. + Final brace followed by a single blank line. + The final right brace must be followed by a blank line. + This may be the final brace of the if compound statement. + Or it may be the the final brace of the else compound statement if present. + A blank line never follows the right brace closing the if compound statement if else is present. + Use of braces must follow all other standard rules for braces and spacing.

      -- GitLab From 39d222ebcb67eea2ab213da621646d7a3ae3fc71 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 9 Jun 2017 11:34:01 -0600 Subject: [PATCH 951/990] Update Coding Standard Document. --- Documentation/NuttXCCodingStandard.html | 14 +++++++++----- 1 file changed, 9 insertions(+), 5 deletions(-) diff --git a/Documentation/NuttXCCodingStandard.html b/Documentation/NuttXCCodingStandard.html index a116f981e7..87caa57034 100644 --- a/Documentation/NuttXCCodingStandard.html +++ b/Documentation/NuttXCCodingStandard.html @@ -2169,8 +2169,8 @@ x++;

    • Statement(s) always enclosed in braces. - Statement(s) following the if <condition> and else lines must always be enclosed in braces. - Braces must follow the if <condition> and else lines even in the case where these is no contained statement! + Statement(s) following the if <condition> and else keywords must always be enclosed in braces. + Braces must follow the if <condition> and else lines even in the cases where (a) there is no contained statement or (b) there is only a single statement!
    • Braces and indentation. @@ -2178,12 +2178,16 @@ x++;
    • Final brace followed by a single blank line. - The final right brace must be followed by a blank line. - This may be the final brace of the if compound statement. + The final right brace of the if-else must be followed by a blank line in most cases (the exception given below). + This may be the final brace of the if compound statement if the else keyword is not present. Or it may be the the final brace of the else compound statement if present. - A blank line never follows the right brace closing the if compound statement if else is present. + A blank line never follows the right brace closing the if compound statement if the else keyword is present. Use of braces must follow all other standard rules for braces and spacing.
    • +
    • + Exception where there is no blank line. + That blank line must also be omitted for certain cases where the if <condition>-else statement is nested within another compound statement; there should be no blank lines between consecutive right braces as discussed in the standard rules for use of braces. +
    • Other Applicable Coding Standards. -- GitLab From db80696d214a287498b8413a3b20b3108c9af305 Mon Sep 17 00:00:00 2001 From: Jim Paris Date: Fri, 9 Jun 2017 11:37:30 -0600 Subject: [PATCH 952/990] vfs/poll: fix timeout calculation --- fs/vfs/fs_poll.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/fs/vfs/fs_poll.c b/fs/vfs/fs_poll.c index 55160d7faa..b850ef217a 100644 --- a/fs/vfs/fs_poll.c +++ b/fs/vfs/fs_poll.c @@ -401,7 +401,7 @@ int poll(FAR struct pollfd *fds, nfds_t nfds, int timeout) #if (MSEC_PER_TICK * USEC_PER_MSEC) != USEC_PER_TICK && \ defined(CONFIG_HAVE_LONG_LONG) - ticks = ((unsigned long long)timeout * USEC_PER_MSEC) + (USEC_PER_TICK - 1) / + ticks = (((unsigned long long)timeout * USEC_PER_MSEC) + (USEC_PER_TICK - 1)) / USEC_PER_TICK; #else ticks = ((unsigned int)timeout + (MSEC_PER_TICK - 1)) / MSEC_PER_TICK; -- GitLab From fa2c7a694fbe76dfedf58935d9582afcfba2caa1 Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Fri, 9 Jun 2017 15:09:03 -0600 Subject: [PATCH 953/990] stm32f103-minimum: Fix a small BUG when reading from output pin. We need a different read_ops to read from output pin. This patch fixes the issue: nsh> gpio -o 0 /dev/gpout1 Driver: /dev/gpout1 Output pin: Value=1 Writing: Value=0 Verify: Value=1 Now: nsh> gpio -o 0 /dev/gpout1 Driver: /dev/gpout1 Output pin: Value=1 Writing: Value=0 Verify: Value=0 --- configs/stm32f103-minimum/src/stm32_gpio.c | 18 ++++++++++++++++-- 1 file changed, 16 insertions(+), 2 deletions(-) diff --git a/configs/stm32f103-minimum/src/stm32_gpio.c b/configs/stm32f103-minimum/src/stm32_gpio.c index 6335acc4a3..854b84a793 100644 --- a/configs/stm32f103-minimum/src/stm32_gpio.c +++ b/configs/stm32f103-minimum/src/stm32_gpio.c @@ -67,7 +67,6 @@ struct stm32gpio_dev_s { struct gpio_dev_s gpio; uint8_t id; - bool value; }; struct stm32gpint_dev_s @@ -81,6 +80,7 @@ struct stm32gpint_dev_s ****************************************************************************/ static int gpin_read(FAR struct gpio_dev_s *dev, FAR bool *value); +static int gpout_read(FAR struct gpio_dev_s *dev, FAR bool *value); static int gpout_write(FAR struct gpio_dev_s *dev, bool value); static int gpint_attach(FAR struct gpio_dev_s *dev, pin_interrupt_t callback); @@ -100,7 +100,7 @@ static const struct gpio_operations_s gpin_ops = static const struct gpio_operations_s gpout_ops = { - .go_read = gpin_read, + .go_read = gpout_read, .go_write = gpout_write, .go_attach = NULL, .go_enable = NULL, @@ -167,17 +167,31 @@ static int gpin_read(FAR struct gpio_dev_s *dev, FAR bool *value) FAR struct stm32gpio_dev_s *stm32gpio = (FAR struct stm32gpio_dev_s *)dev; DEBUGASSERT(stm32gpio != NULL && value != NULL); + DEBUGASSERT(stm32gpio->id < BOARD_NGPIOIN); gpioinfo("Reading...\n"); *value = stm32_gpioread(g_gpioinputs[stm32gpio->id]); return OK; } +static int gpout_read(FAR struct gpio_dev_s *dev, FAR bool *value) +{ + FAR struct stm32gpio_dev_s *stm32gpio = (FAR struct stm32gpio_dev_s *)dev; + + DEBUGASSERT(stm32gpio != NULL && value != NULL); + DEBUGASSERT(stm32gpio->id < BOARD_NGPIOOUT); + gpioinfo("Reading...\n"); + + *value = stm32_gpioread(g_gpiooutputs[stm32gpio->id]); + return OK; +} + static int gpout_write(FAR struct gpio_dev_s *dev, bool value) { FAR struct stm32gpio_dev_s *stm32gpio = (FAR struct stm32gpio_dev_s *)dev; DEBUGASSERT(stm32gpio != NULL); + DEBUGASSERT(stm32gpio->id < BOARD_NGPIOOUT); gpioinfo("Writing %d\n", (int)value); stm32_gpiowrite(g_gpiooutputs[stm32gpio->id], value); -- GitLab From 2b8abbb3c69e4144a8a675c5103c656d0a06f288 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 10 Jun 2017 08:58:47 -0600 Subject: [PATCH 954/990] configs: Add readme for B-L465E-IOT01A Development kit. This port is currently under consideration (but may not actually happen) --- Documentation/README.html | 4 +- README.txt | 2 + configs/b-l475e-iot01a/README.txt | 205 ++++++++++++++++++++++++++++++ 3 files changed, 210 insertions(+), 1 deletion(-) create mode 100644 configs/b-l475e-iot01a/README.txt diff --git a/Documentation/README.html b/Documentation/README.html index fe4dced9ad..7c44a55916 100644 --- a/Documentation/README.html +++ b/Documentation/README.html @@ -8,7 +8,7 @@

      NuttX README Files

      -

      Last Updated: May 9, 2017

      +

      Last Updated: June 10, 2017

      @@ -62,6 +62,8 @@ nuttx/ | | `- README.txt | |- avr32dev1/ | | `- README.txt + | |- b-l475e-iot01a/ + | | `- README.txt | |- bambino-200e/ | | `- README.txt | |- c5471evm/ diff --git a/README.txt b/README.txt index c5e0b9c69e..8e466a7dd4 100644 --- a/README.txt +++ b/README.txt @@ -1462,6 +1462,8 @@ nuttx/ | | `- README.txt | |- avr32dev1/ | | `- README.txt + | |- b-l475e-iot01a/ + | | `- README.txt | |- bambino-200e/ | | `- README.txt | |- c5471evm/ diff --git a/configs/b-l475e-iot01a/README.txt b/configs/b-l475e-iot01a/README.txt new file mode 100644 index 0000000000..5c299446f8 --- /dev/null +++ b/configs/b-l475e-iot01a/README.txt @@ -0,0 +1,205 @@ +README +====== + + This README discusses the port of NuttX to the STMicro B-L475E-IOT01A + Discovery kit powered by STM32L475VG Cortex-M4. This board targets IoT + nodes with a choice of connectivity options including WiFi, Bluetooth LE, + NFC, and sub-GHZ RF at 868 or 915 MHz, as well as a long list of various + environmental sensors. + +Contents +======== + + - Board Features + - LEDs and Buttons + - Serial Console + - Configurations + +Board Features +============== + + B-L475E-IOT01A Discovery kit key features and specifications: + + - MCU: STM32L475 Series MCU based on ARM Cortex-M4 core with 1 MB + Flash memory, 128 KB SRAM + - Storage: 64 Mbit (8MB)  Quad-SPI Flash memory (Macronix) + - Connectivity: + Bluetooth 4.1 LE module (SPBTLE-RF) + Sub-GHz (868 or 915 MHz) low-power-programmable RF module (SPSGRF-868 + or SPSGRF-915) + Wi-Fi module based on Inventek ISM43362-M3G-L44 (802.11 b/g/n + compliant) + Dynamic NFC tag based on M24SR with its printed NFC antenna + - Sensors: + 2x digital omni-directional microphones (MP34DT01) + Capacitive digital sensor for relative humidity and temperature + (HTS221) + 3-axis magnetometer (LIS3MDL) + 3D accelerometer and 3D gyroscope (LSM6DSL) + 260-1260 hPa absolute digital output barometer (LPS22HB) + Time-of-Flight and gesture-detection sensor (VL53L0X + - USB – 1x micro USB OTG port (Full speed) + - Expansion – Arduino UNO V3 headers, PMOD header + - Debugging – On-board ST-LINK/V2-1 debugger/programmer with USB + re-enumeration capability: mass storage, virtual COM port and debug + port + - Misc – 2 push-buttons (user and reset) + - Power Supply – 5V via ST LINK USB VBUS or external sources + + The board supports ARM mbed online compiler, but can also be programmed + using IDEs such as IAR, Keil, and GCC-based IDEs. STMicro also provides + HAL libraries and code samples as part of the STM32Cube Package, as well + as X-CUBE-AWS expansion software to connect to the Amazon Web Services + (AWS) IoT platform. + +LEDs and Buttons +================ + + The black button B1 located on top side is the reset of the STM32L475VGT6. + + The blue button B1 located top side is available to be used as a digital + input or as alternate function Wake-up. When the button is depressed the logic state is "0", otherwise the logic state is "1". + + Two green LEDs (LD1 and LD2), located on the top side are available for the user. To light a LED a high logic state "1" should be written in the corresponding GPIO. + + Reference Color Name Comment + B2 blue Wake-up Alternate function Wake-up + LD1 green LED1 PA5 (alternate with ARD.D13) + LD2 green LED2 PB14 + + These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is + defined. In that case, the usage by the board port is defined in + include/board.h and src/lpc31_leds.c. The LEDs are used to encode + OS-related events as follows: + + SYMBOL Meaning LED state + LED2 LED1 + ------------------- ----------------------- -------- -------- + LED_STARTED NuttX has been started OFF OFF + LED_HEAPALLOCATE Heap has been allocated OFF OFF + LED_IRQSENABLED Interrupts enabled OFF OFF + LED_STACKCREATED Idle stack created ON OFF + LED_INIRQ In an interrupt N/C N/C + LED_SIGNAL In a signal handler N/C N/C + LED_ASSERTION An assertion failed N/C N/C + LED_PANIC The system has crashed N/C Blinking + LED_IDLE MCU is is sleep mode Not used + + Thus if LED2 is statically on, NuttX has successfully booted and is, + apparently, running normmally. If LED1 is flashing at approximately + 2Hz, then a fatal error has been detected and the system has halted. + + NOTE: That LED2 is not used after completion of booting and may + be used by other board-specific logic. + +Serial Console +============== + + Arduino Serial Shield + --------------------- + An TLL-to-RS232 Converter shield may be used with UART4: + + UART4: + -------------- ---------------- ------------------ + STM32L475VGTx Board Signal Arduino Connector + -------------- ---------------- ------------------ + UART4_RX PA1 ARD.D0-UART4_RX CN3 pin1 RX/D0 + UART4_TX PA0 ARD.D1-UART4_TX CN3 pin2 TX/D1 + -------------- ---------------- ------------------ + + Virtual COM Port + ---------------- + The serial interface USART1 is directly available as a virtual COM port + of the PC connected to the ST-LINK/V2-1 USB connector CN7. + + USART1: + -------------- ---------------- -------------- + STM32L475VGTx Board Signal STM32F103CBT6 + -------------- ---------------- -------------- + USART1_TX PB6 ST-LINK-UART1_TX USART2_RX PA3 + UAART1_RX PB7 ST-LINK-UART1_RX USART2_TX PA2 + -------------- ---------------- -------------- + + The virtual COM port settings are configured as: 115200 b/s, 8 bits data, + no parity, 1 stop bit, no flow control. + + Other Options + ------------- + + USART2 - Available on CN10 if solder bridges closed. + -------------- ---------------- --------------------------- + STM32L475VGTx Board Signal PMOD / Solder Bridges + -------------- ---------------- --------------------------- + USART2_RX PD4 PMOD-UART2_RX CN10 pin1 or 2 (SB12, SB14) + USART2_TX PD5 PMOD-UART2_TX CN10 pin2 TX/D1 (SB20) + -------------- ---------------- --------------------------- + + USART3 - Dedicated to ISM43362-M3G-L44 Serial-to-Wifi Module. + -------------- ---------------- ------------------ + STM32L475VGTx Board Signal Arduino Connector + -------------- ---------------- ------------------ + USART3_RX PD9 INTERNAL-UART3_RX CN3 pin1 RX/D0 + USART3_TX PD8 INTERNAL-UART3_TX CN3 pin2 TX/D1 + -------------- ---------------- ------------------ + +Configurations +============== + + Information Common to All Configurations + ---------------------------------------- + Each B-L475E-IOT01A configuration is maintained in a sub-directory and + can be selected as follow: + + cd tools + ./configure.sh b-l475e-iot01a/ + cd - + + Before building, make sure that: + + 1. The PATH environment variable include the correct path to the + directory than holds your toolchain binaries. + 2. Make sure that the configuration is set for your build platform + and that the toolchain is set for the toolchain type you are using. + + And then build NuttX by simply typing the following. At the conclusion of + the make, the nuttx binary will reside in an ELF file called, simply, + nuttx. + + make oldconfig + make + + The that is provided above as an argument to the + tools/configure.sh must be is one of the following. + + NOTES: + + 1. These configurations use the mconf-based configuration tool. To + change any of these configurations using that tool, you should: + + a. Build and install the kconfig-mconf tool. See nuttx/README.txt + see additional README.txt files in the NuttX tools repository. + + b. Execute 'make menuconfig' in nuttx/ in order to start the + reconfiguration process. + + 2. Unless stated otherwise, all configurations generate console + output on USART1 (i.e., for ST-Link Virtual COM port). + + 3. All of these configurations are set up to build under Windows using the + "GNU Tools for ARM Embedded Processors" that is maintained by ARM + (unless stated otherwise in the description of the configuration). + + https://launchpad.net/gcc-arm-embedded + + That toolchain selection can easily be reconfigured using + 'make menuconfig'. Here are the relevant current settings: + + Build Setup: + CONFIG_HOST_WINDOWS=y : Window environment + CONFIG_WINDOWS_CYGWIN=y : Cywin under Windows + + System Type -> Toolchain: + CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIW=y : GNU ARM EABI toolchain + +Configuration sub-directories +----------------------------- -- GitLab From 6e0ec040842f9e5da696f349d9a36291dd49fa92 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 10 Jun 2017 17:54:16 -0600 Subject: [PATCH 955/990] Update README --- configs/b-l475e-iot01a/README.txt | 96 +++++++++++++++++++++---------- 1 file changed, 66 insertions(+), 30 deletions(-) diff --git a/configs/b-l475e-iot01a/README.txt b/configs/b-l475e-iot01a/README.txt index 5c299446f8..7fed5de236 100644 --- a/configs/b-l475e-iot01a/README.txt +++ b/configs/b-l475e-iot01a/README.txt @@ -10,41 +10,53 @@ README Contents ======== - - Board Features - - LEDs and Buttons - - Serial Console - - Configurations + o STATUS + o Board Features + o LEDs and Buttons + o Serial Console + o Configurations + +STATUS +====== + + o 2017-06-10: I have no hardware in hand and I am not sure that I will + even pursue this port. This README is really no more than a thought + experiment at the present time. + + A few days ago, I did add support for the STM32L4x5 MCU family to + NuttX. But no work has yet been done for this board port other + than writing this README file. Board Features ============== B-L475E-IOT01A Discovery kit key features and specifications: - - MCU: STM32L475 Series MCU based on ARM Cortex-M4 core with 1 MB - Flash memory, 128 KB SRAM - - Storage: 64 Mbit (8MB)  Quad-SPI Flash memory (Macronix) - - Connectivity: - Bluetooth 4.1 LE module (SPBTLE-RF) - Sub-GHz (868 or 915 MHz) low-power-programmable RF module (SPSGRF-868 - or SPSGRF-915) - Wi-Fi module based on Inventek ISM43362-M3G-L44 (802.11 b/g/n - compliant) - Dynamic NFC tag based on M24SR with its printed NFC antenna - - Sensors: - 2x digital omni-directional microphones (MP34DT01) - Capacitive digital sensor for relative humidity and temperature - (HTS221) - 3-axis magnetometer (LIS3MDL) - 3D accelerometer and 3D gyroscope (LSM6DSL) - 260-1260 hPa absolute digital output barometer (LPS22HB) - Time-of-Flight and gesture-detection sensor (VL53L0X - - USB – 1x micro USB OTG port (Full speed) - - Expansion – Arduino UNO V3 headers, PMOD header - - Debugging – On-board ST-LINK/V2-1 debugger/programmer with USB - re-enumeration capability: mass storage, virtual COM port and debug - port - - Misc – 2 push-buttons (user and reset) - - Power Supply – 5V via ST LINK USB VBUS or external sources + o MCU: STM32L475 Series MCU based on ARM Cortex-M4 core with 1 MB + Flash memory, 128 KB SRAM + o Storage: 64 Mbit (8MB)  Quad-SPI Flash memory (Macronix) + o Connectivity: + - Bluetooth 4.1 LE module (SPBTLE-RF) + - Sub-GHz (868 or 915 MHz) low-power-programmable RF module (SPSGRF-868 + or SPSGRF-915) + - Wi-Fi module based on Inventek ISM43362-M3G-L44 (802.11 b/g/n + compliant) + - Dynamic NFC tag based on M24SR with its printed NFC antenna + o Sensors: + - 2x digital omni-directional microphones (MP34DT01) + - Capacitive digital sensor for relative humidity and temperature + (HTS221) + - 3-axis magnetometer (LIS3MDL) + - 3D accelerometer and 3D gyroscope (LSM6DSL) + - 260-1260 hPa absolute digital output barometer (LPS22HB) + - Time-of-Flight and gesture-detection sensor (VL53L0X + o USB – 1x micro USB OTG port (Full speed) + o Expansion – Arduino UNO V3 headers, PMOD header + o Debugging – On-board ST-LINK/V2-1 debugger/programmer with USB + re-enumeration capability: mass storage, virtual COM port and debug + port + o Misc – 2 push-buttons (user and reset) + o Power Supply – 5V via ST LINK USB VBUS or external sources The board supports ARM mbed online compiler, but can also be programmed using IDEs such as IAR, Keil, and GCC-based IDEs. STMicro also provides @@ -52,6 +64,27 @@ Board Features as X-CUBE-AWS expansion software to connect to the Amazon Web Services (AWS) IoT platform. + NOTES: + 1. The board usese Wi-Fi® module Inventek ISM43362-M3G-L44 (802.11 b/g/n + compliant), which consists of BCM43362 and STM32F205 host processor + that has a standard SPI or UART interface capability. It means you + will only use AT command to talk with Wi-Fi® module by SPI. All the + tcp/ip stack is built-in STM32F205 in Wi-Fi® module. + + This cannot integrate cleanly with the NuttX network stack. A + USERSOCK option was recently added that would permit implementation + of the Inventek support in an applications. But that would then + preclude the 6loWPAN integration into IPv6. + + 2. The board uses Bluetooth® V4.1 module (SPBTLE-RF), which has built-in + BLE stack. Similar with wifi, you only use simple AT command to talk + with this BLE module. + + 3. STMicro provides contiki 6lowpan for mesh. + http://www.st.com/en/embedded-software/osxcontiki6lp.html but mesh + network is not popular in the market, star network is the mainstream + for its simplicity and robustness. + LEDs and Buttons ================ @@ -68,7 +101,7 @@ LEDs and Buttons LD2 green LED2 PB14 These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is - defined. In that case, the usage by the board port is defined in + selected. In that case, the usage by the board port is defined in include/board.h and src/lpc31_leds.c. The LEDs are used to encode OS-related events as follows: @@ -92,6 +125,9 @@ LEDs and Buttons NOTE: That LED2 is not used after completion of booting and may be used by other board-specific logic. + Of course, if CONFIG_ARCH_LEDS is not selected, then both LEDs are + available for use by other logic. + Serial Console ============== -- GitLab From b7ca90a721cfe686dbda2987540cb3e0ad939979 Mon Sep 17 00:00:00 2001 From: Alan Carvalho de Assis Date: Sun, 11 Jun 2017 07:20:18 -0600 Subject: [PATCH 956/990] stm32f103-minimum: Use separated read_ops for GPIO interrupt pins --- configs/b-l475e-iot01a/README.txt | 2 +- configs/stm32f103-minimum/src/stm32_gpio.c | 17 +++++++++++++++-- 2 files changed, 16 insertions(+), 3 deletions(-) diff --git a/configs/b-l475e-iot01a/README.txt b/configs/b-l475e-iot01a/README.txt index 7fed5de236..fe2cc91d97 100644 --- a/configs/b-l475e-iot01a/README.txt +++ b/configs/b-l475e-iot01a/README.txt @@ -78,7 +78,7 @@ Board Features 2. The board uses Bluetooth® V4.1 module (SPBTLE-RF), which has built-in BLE stack. Similar with wifi, you only use simple AT command to talk - with this BLE module. + with this BLE module. 3. STMicro provides contiki 6lowpan for mesh. http://www.st.com/en/embedded-software/osxcontiki6lp.html but mesh diff --git a/configs/stm32f103-minimum/src/stm32_gpio.c b/configs/stm32f103-minimum/src/stm32_gpio.c index 854b84a793..84f23dccd9 100644 --- a/configs/stm32f103-minimum/src/stm32_gpio.c +++ b/configs/stm32f103-minimum/src/stm32_gpio.c @@ -82,6 +82,7 @@ struct stm32gpint_dev_s static int gpin_read(FAR struct gpio_dev_s *dev, FAR bool *value); static int gpout_read(FAR struct gpio_dev_s *dev, FAR bool *value); static int gpout_write(FAR struct gpio_dev_s *dev, bool value); +static int gpint_read(FAR struct gpio_dev_s *dev, FAR bool *value); static int gpint_attach(FAR struct gpio_dev_s *dev, pin_interrupt_t callback); static int gpint_enable(FAR struct gpio_dev_s *dev, bool enable); @@ -108,7 +109,7 @@ static const struct gpio_operations_s gpout_ops = static const struct gpio_operations_s gpint_ops = { - .go_read = gpin_read, + .go_read = gpint_read, .go_write = NULL, .go_attach = gpint_attach, .go_enable = gpint_enable, @@ -198,6 +199,18 @@ static int gpout_write(FAR struct gpio_dev_s *dev, bool value) return OK; } +static int gpint_read(FAR struct gpio_dev_s *dev, FAR bool *value) +{ + FAR struct stm32gpint_dev_s *stm32gpint = (FAR struct stm32gpint_dev_s *)dev; + + DEBUGASSERT(stm32gpint != NULL && value != NULL); + DEBUGASSERT(stm32gpint->stm32gpio && stm32gpint->stm32gpio.id < BOARD_NGPIOINT); + gpioinfo("Reading int pin...\n"); + + *value = stm32_gpioread(g_gpiointinputs[stm32gpint->stm32gpio.id]); + return OK; +} + static int gpint_attach(FAR struct gpio_dev_s *dev, pin_interrupt_t callback) { @@ -289,7 +302,7 @@ int stm32_gpio_initialize(void) (void)gpio_pin_register(&g_gpout[i].gpio, pincount); /* Configure the pin that will be used as output */ - + stm32_gpiowrite(g_gpiooutputs[i], 0); stm32_configgpio(g_gpiooutputs[i]); pincount++; -- GitLab From 40f60d6da514e30a1c26591d5744bcf55fcff888 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 11 Jun 2017 10:01:14 -0600 Subject: [PATCH 957/990] Update to coding standard document and to a README file. --- Documentation/NuttXCCodingStandard.html | 50 ++++++++++++++++++++++--- configs/b-l475e-iot01a/README.txt | 13 +++++-- 2 files changed, 54 insertions(+), 9 deletions(-) diff --git a/Documentation/NuttXCCodingStandard.html b/Documentation/NuttXCCodingStandard.html index 87caa57034..a80b4d3960 100644 --- a/Documentation/NuttXCCodingStandard.html +++ b/Documentation/NuttXCCodingStandard.html @@ -12,7 +12,7 @@

      NuttX C Coding Standard

      -

      Last Updated: June 9, 2017

      +

      Last Updated: June 11, 2017

      @@ -2150,12 +2150,24 @@ x++; +

      + Forbidden Multicharacter Forms. + Many operators are expressed as a character in combination with = such as +=, >=, >>=, etc. + Some compilers will accept the = at the beginning or the end of the sequence. + This standard, however, requires that the = always appear last in order to avoid amiguities that may arise if the = were to appear first. For example, a =++ b; could also be interpreted as a =+ +b; or a = ++b all of which are very different. +

      +

      4.4 if then else Statement

      Coding Standard:

      • + if separated from <condition>. + The if keyword and the <condition> must appear on the same line. + The if keyword and the <condition> must be separated by a single space. +
      • + Keywords on separate lines. if <condition> and else must lie on separate lines with nothing else present on the line. @@ -2185,7 +2197,7 @@ x++; Use of braces must follow all other standard rules for braces and spacing.
      • - Exception where there is no blank line. + Exception. That blank line must also be omitted for certain cases where the if <condition>-else statement is nested within another compound statement; there should be no blank lines between consecutive right braces as discussed in the standard rules for use of braces.
      @@ -2280,6 +2292,11 @@ x++;

      Coding Standard:

        +
      • + switch separated from <value>. + The switch keyword and the switch <value> must appear on the same line. + The if keyword and the <value> must be separated by a single space. +
      • Falling through. Falling through a case statement into the next case statement is be permitted as long as a comment is included. @@ -2298,6 +2315,14 @@ x++; break statements are normally indented by two spaces. When used conditionally with case logic, the placement of the break statement follows normal indentation rules.
      • +
      • + Followed by a single blank line. + The final right brace that closes the switch <value> statement must be followed by a single blank line. +
      • +
      • + Exception. + That blank line must be omitted for certain cases where the switch <value> statement is nested within another compound statement; there should be no blank lines between consecutive right braces as discussed in the standard rules for use of braces. +

      Other Applicable Coding Standards. @@ -2333,6 +2358,11 @@ x++;

      4.6 while Statement

      Coding Standard:

        +
      • + while separated from <condition>. + The while keyword and the <condition> must appear on the same line. + The while keyword and the <condition> must be separated by a single space. +
      • Keywords on separate lines. while <condition> must lie on a separate line with nothing else present on the line. @@ -2356,7 +2386,11 @@ x++;
      • Followed by a single blank line. - The final right brace must be followed by a blank line. + The final right brace that closes the while <condition> statment must be followed by a single blank line. +
      • +
      • + Exception. + That blank line must be omitted for certain cases where the while <condition> statement is nested within another compound statement; there should be no blank lines between consecutive right braces as discussed in the standard rules for use of braces.

      @@ -2404,15 +2438,20 @@ x++;

    • Statements enclosed in braces - Statement(s) following the do must always be enclosed in braces, even if only a single statement follows. + Statement(s) following the do must always be enclosed in braces, even if only a single statement (or no statement) follows.
    • Braces and indentation. The placement of braces and statements must follow the standard rules for braces and indentation.
    • +
    • + while separated from <condition>. + The while keyword and the <condition> must appear on the same line. + The while keyword and the <condition> must be separated by a single space. +
    • Followed by a single blank line. - The final right brace must be followed by a blank line. + The concluding while <condition> must be followed by a single blank line.
    • @@ -2447,6 +2486,7 @@ x++; ptr++; } while (*ptr != '\0'); + diff --git a/configs/b-l475e-iot01a/README.txt b/configs/b-l475e-iot01a/README.txt index fe2cc91d97..e99c3a9503 100644 --- a/configs/b-l475e-iot01a/README.txt +++ b/configs/b-l475e-iot01a/README.txt @@ -65,6 +65,7 @@ Board Features (AWS) IoT platform. NOTES: + 1. The board usese Wi-Fi® module Inventek ISM43362-M3G-L44 (802.11 b/g/n compliant), which consists of BCM43362 and STM32F205 host processor that has a standard SPI or UART interface capability. It means you @@ -194,8 +195,12 @@ Configurations 1. The PATH environment variable include the correct path to the directory than holds your toolchain binaries. - 2. Make sure that the configuration is set for your build platform - and that the toolchain is set for the toolchain type you are using. + 2. Check the .config file. Make sure that the configuration is set for + your build platform (e.g., Linux vs. Windows) and that the toolchain + is set for the toolchain type you are using. + + The that is provided above as an argument to the + tools/configure.sh must be is one of those listed below. And then build NuttX by simply typing the following. At the conclusion of the make, the nuttx binary will reside in an ELF file called, simply, @@ -204,8 +209,8 @@ Configurations make oldconfig make - The that is provided above as an argument to the - tools/configure.sh must be is one of the following. + Where 'make oldconfig' brings the configuration up to data with the current configuration data and 'make' will compile all of the source + files and generate the final binary. NOTES: -- GitLab From 437ad3ccb22d1588061e76e05c1d2c09e5834859 Mon Sep 17 00:00:00 2001 From: Mateusz Szafoni Date: Sun, 11 Jun 2017 10:49:20 -0600 Subject: [PATCH 958/990] STM32F33: Fix hrtim definitions, Add beginning of HRTIM driver --- arch/arm/src/stm32/Make.defs | 4 + arch/arm/src/stm32/chip/stm32f33xxx_hrtim.h | 474 +++++++------------- arch/arm/src/stm32/stm32.h | 1 + arch/arm/src/stm32/stm32f33xxx_rcc.c | 2 - 4 files changed, 170 insertions(+), 311 deletions(-) diff --git a/arch/arm/src/stm32/Make.defs b/arch/arm/src/stm32/Make.defs index 07e31f7329..11f5c3dc1d 100644 --- a/arch/arm/src/stm32/Make.defs +++ b/arch/arm/src/stm32/Make.defs @@ -225,6 +225,10 @@ ifeq ($(CONFIG_OPAMP),y) CHIP_CSRCS += stm32_opamp.c endif +ifeq ($(CONFIG_HRTIM),y) +CHIP_CSRCS += stm32_hrtim.c +endif + ifeq ($(CONFIG_STM32_1WIREDRIVER),y) CHIP_CSRCS += stm32_1wire.c endif diff --git a/arch/arm/src/stm32/chip/stm32f33xxx_hrtim.h b/arch/arm/src/stm32/chip/stm32f33xxx_hrtim.h index fc22deeb25..31438fe30e 100644 --- a/arch/arm/src/stm32/chip/stm32f33xxx_hrtim.h +++ b/arch/arm/src/stm32/chip/stm32f33xxx_hrtim.h @@ -67,310 +67,190 @@ /* Register Offsets *********************************************************************************/ -/* Register Offsets for HRTIM Master Timer */ - -#define STM32_HRTIM_MASTER_MCR 0x0000 /* HRTIM Master Timer Control Register */ -#define STM32_HRTIM_MASTER_MISR 0x0004 /* HRTIM Master Timer Interrupt Status Register */ -#define STM32_HRTIM_MASTER_MICR 0x0008 /* HRTIM Master Timer Interrupt Clear Register */ -#define STM32_HRTIM_MASTER_MDIER 0x000C /* HRTIM Master Timer DMA/Interrupt Enable Register */ -#define STM32_HRTIM_MASTER_MCNTR 0x0010 /* HRTIM Master Timer Counter Register */ -#define STM32_HRTIM_MASTER_MPER 0x0014 /* HRTIM Master Timer Period Register */ -#define STM32_HRTIM_MASTER_MREP 0x0018 /* HRTIM Master Timer Repetition Register */ -#define STM32_HRTIM_MASTER_MCMP1R 0x001C /* HRTIM Master Timer Compare 1 Register */ -#define STM32_HRTIM_MASTER_MCMP2R 0x0024 /* HRTIM Master Timer Compare 2 Register */ -#define STM32_HRTIM_MASTER_MCMP3R 0x0028 /* HRTIM Master Timer Compare 3 Register */ -#define STM32_HRTIM_MASTER_MCMP4R 0x002C /* HRTIM Master Timer Compare 4 Register */ - -/* Register Offsets for HRTIM Timers A-E */ - -#define STM32_HRTIM_TIMX_CR 0x0000 /* HRTIM Timer X Control Register */ -#define STM32_HRTIM_TIMX_ISR 0x0004 /* HRTIM Timer X Interrupt Status Register */ -#define STM32_HRTIM_TIMX_ICR 0x0008 /* HRTIM Timer X Interrupt Clear Register */ -#define STM32_HRTIM_TIMX_DIER 0x000C /* HRTIM Timer X DMA/Interrupt Enable Register */ -#define STM32_HRTIM_TIMX_CNTR 0x0010 /* HRTIM Timer X Counter Register */ -#define STM32_HRTIM_TIMX_PER 0x0014 /* HRTIM Timer X Period Register */ -#define STM32_HRTIM_TIMX_REP 0x0018 /* HRTIM Timer X Repetition Register */ -#define STM32_HRTIM_TIMX_CMP1R 0x001C /* HRTIM Timer X Compare 1 Register */ -#define STM32_HRTIM_TIMX_CMP1CR 0x0020 /* HRTIM Timer X Compare 1 Compound Register */ -#define STM32_HRTIM_TIMX_CMP2R 0x0024 /* HRTIM Timer X Compare 2 Register */ -#define STM32_HRTIM_TIMX_CMP3R 0x0028 /* HRTIM Timer X Compare 3 Register */ -#define STM32_HRTIM_TIMX_CMP4R 0x002C /* HRTIM Timer X Compare 4 Register */ -#define STM32_HRTIM_TIMX_CPT1R 0x0030 /* HRTIM Timer X Capture 1 Register */ -#define STM32_HRTIM_TIMX_CPT2R 0x0034 /* HRTIM Timer X Capture 2 Register */ -#define STM32_HRTIM_TIMX_DTR 0x0038 /* HRTIM Timer X Deadtime Register */ -#define STM32_HRTIM_TIMX_SET1R 0x003C /* HRTIM Timer X Output1 Set Register */ -#define STM32_HRTIM_TIMX_RST1R 0x0040 /* HRTIM Timer X Output1 Reset Register */ -#define STM32_HRTIM_TIMX_SET2R 0x0044 /* HRTIM Timer X Output2 Set Register */ -#define STM32_HRTIM_TIMX_RST2R 0x0048 /* HRTIM Timer X Output2 Reset Register */ -#define STM32_HRTIM_TIMX_EEFR1 0x004C /* HRTIM Timer X External Event Filtering Register 1 */ -#define STM32_HRTIM_TIMX_EEFR2 0x0050 /* HRTIM Timer X External Event Filtering Register 2 */ -#define STM32_HRTIM_TIMX_RSTR 0x0054 /* HRTIM Timer X Reset Register */ -#define STM32_HRTIM_TIMX_CHPR 0x0058 /* HRTIM Timer X Chopper Register */ -#define STM32_HRTIM_TIMX_CPT1CR 0x005C /* HRTIM Timer X Capture 1 Control Register */ -#define STM32_HRTIM_TIMX_CPT2CR 0x0060 /* HRTIM Timer X Capture 2 Control Register */ -#define STM32_HRTIM_TIMX_OUTR 0x0064 /* HRTIM Timer X Output Register */ -#define STM32_HRTIM_TIMX_FLTR 0x0068 /* HRTIM Timer X Fault Register */ +/* Register Offsets Common for Master Timer and Timer X */ + +#define STM32_HRTIM_TIM_CR_OFFSET 0x0000 /* HRTIM Timer Control Register */ +#define STM32_HRTIM_TIM_ISR_OFFSET 0x0004 /* HRTIM Timer Interrupt Status Register */ +#define STM32_HRTIM_TIM_ICR_OFFSET 0x0008 /* HRTIM Timer Interrupt Clear Register */ +#define STM32_HRTIM_TIM_DIER_OFFSET 0x000C /* HRTIM Timer DMA/Interrupt Enable Register */ +#define STM32_HRTIM_TIM_CNTR_OFFSET 0x0010 /* HRTIM Timer Counter Register */ +#define STM32_HRTIM_TIM_PER_OFFSET 0x0014 /* HRTIM Timer Period Register */ +#define STM32_HRTIM_TIM_REPR_OFFSET 0x0018 /* HRTIM Timer Repetition Register */ +#define STM32_HRTIM_TIM_CMP1R_OFFSET 0x001C /* HRTIM Timer Compare 1 Register */ +#define STM32_HRTIM_TIM_CMP2R_OFFSET 0x0024 /* HRTIM Timer Compare 2 Register */ +#define STM32_HRTIM_TIM_CMP3R_OFFSET 0x0028 /* HRTIM Timer Compare 3 Register */ +#define STM32_HRTIM_TIM_CMP4R_OFFSET 0x002C /* HRTIM Timer Compare 4 Register */ + +/* Register offsets Specific for Timer A-E */ + +#define STM32_HRTIM_TIM_CMP1CR_OFFSET 0x0020 /* HRTIM Timer Compare 1 Compound Register */ +#define STM32_HRTIM_TIM_CPT1R_OFFSET 0x0030 /* HRTIM Timer Capture 1 Register */ +#define STM32_HRTIM_TIM_CPT2R_OFFSET 0x0034 /* HRTIM Timer Capture 2 Register */ +#define STM32_HRTIM_TIM_DTR_OFFSET 0x0038 /* HRTIM Timer Deadtime Register */ +#define STM32_HRTIM_TIM_SET1R_OFFSET 0x003C /* HRTIM Timer Output1 Set Register */ +#define STM32_HRTIM_TIM_RST1R_OFFSET 0x0040 /* HRTIM Timer Output1 Reset Register */ +#define STM32_HRTIM_TIM_SET2R_OFFSET 0x0044 /* HRTIM Timer Output2 Set Register */ +#define STM32_HRTIM_TIM_RST2R_OFFSET 0x0048 /* HRTIM Timer Output2 Reset Register */ +#define STM32_HRTIM_TIM_EEFR1_OFFSET 0x004C /* HRTIM Timer External Event Filtering Register 1 */ +#define STM32_HRTIM_TIM_EEFR2_OFFSET 0x0050 /* HRTIM Timer External Event Filtering Register 2 */ +#define STM32_HRTIM_TIM_RSTR_OFFSET 0x0054 /* HRTIM Timer Reset Register */ +#define STM32_HRTIM_TIM_CHPR_OFFSET 0x0058 /* HRTIM Timer Chopper Register */ +#define STM32_HRTIM_TIM_CPT1CR_OFFSET 0x005C /* HRTIM Timer Capture 1 Control Register */ +#define STM32_HRTIM_TIM_CPT2CR_OFFSET 0x0060 /* HRTIM Timer Capture 2 Control Register */ +#define STM32_HRTIM_TIM_OUTR_OFFSET 0x0064 /* HRTIM Timer Output Register */ +#define STM32_HRTIM_TIM_FLTR_OFFSET 0x0068 /* HRTIM Timer Fault Register */ /* Register Offset for HRTIM Common */ -#define STM32_HRTIM_CMN_CR1 0x0000 /* HRTIM Control Register 1 */ -#define STM32_HRTIM_CMN_CR2 0x0004 /* HRTIM Control Register 2 */ -#define STM32_HRTIM_CMN_ISR 0x0008 /* HRTIM Interrupt Status Register */ -#define STM32_HRTIM_CMN_ICR 0x000C /* HRTIM Interrupt Clear Register */ -#define STM32_HRTIM_CMN_IER 0x0010 /* HRTIM Interrupt Enable Register */ -#define STM32_HRTIM_CMN_OENR 0x0014 /* HRTIM Output Enable Register */ -#define STM32_HRTIM_CMN_DISR 0x0018 /* HRTIM Output Disable Register */ -#define STM32_HRTIM_CMN_ODSR 0x001C /* HRTIM Output Disable Status Register */ -#define STM32_HRTIM_CMN_BMCR 0x0020 /* HRTIM Burst Mode Control Register */ -#define STM32_HRTIM_CMN_BMTRGR 0x0024 /* HRTIM Burst Mode Trigger Register */ -#define STM32_HRTIM_CMN_BMCMPR 0x0028 /* HRTIM Burst Mode Compare Register */ -#define STM32_HRTIM_CMN_BMPER 0x002C /* HRTIM Burst Mode Period Register */ -#define STM32_HRTIM_CMN_EECR1 0x0030 /* HRTIM Timer External Event Control Register 1 */ -#define STM32_HRTIM_CMN_EECR2 0x0034 /* HRTIM Timer External Event Control Register 2 */ -#define STM32_HRTIM_CMN_EECR3 0x0038 /* HRTIM Timer External Event Control Register 3 */ -#define STM32_HRTIM_CMN_ADC1R 0x003C /* HRTIM ADC Trigger 1 Register */ -#define STM32_HRTIM_CMN_ADC2R 0x0040 /* HRTIM ADC Trigger 2 Register */ -#define STM32_HRTIM_CMN_ADC3R 0x0044 /* HRTIM ADC Trigger 3 Register */ -#define STM32_HRTIM_CMN_ADC4R 0x0048 /* HRTIM ADC Trigger 4 Register */ -#define STM32_HRTIM_CMN_DLLCR 0x004C /* HRTIM DLL Control Register */ -#define STM32_HRTIM_CMN_FLTINR1 0x0050 /* HRTIM Fault Input Register 1 */ -#define STM32_HRTIM_CMN_FLTINR2 0x0054 /* HRTIM Fault Input Register 2 */ -#define STM32_HRTIM_CMN_BDMUPDR 0x0058 /* HRTIM Master Timer Update Register */ -#define STM32_HRTIM_CMN_BDTAUPR 0x005C /* HRTIM Timer A Update Register */ -#define STM32_HRTIM_CMN_BDTBUPR 0x0060 /* HRTIM Timer B Update Register */ -#define STM32_HRTIM_CMN_BDTCUPR 0x0064 /* HRTIM Timer C Update Register */ -#define STM32_HRTIM_CMN_BDTDUPR 0x0068 /* HRTIM Timer D Update Register */ -#define STM32_HRTIM_CMN_BDTEUPR 0x006C /* HRTIM Timer E Update Register */ -#define STM32_HRTIM_CMN_BDMADR 0x0070 /* HRTIM DMA Data Register */ +#define STM32_HRTIM_CMN_CR1_OFFSET 0x0000 /* HRTIM Control Register 1 */ +#define STM32_HRTIM_CMN_CR2_OFFSET 0x0004 /* HRTIM Control Register 2 */ +#define STM32_HRTIM_CMN_ISR_OFFSET 0x0008 /* HRTIM Interrupt Status Register */ +#define STM32_HRTIM_CMN_ICR_OFFSET 0x000C /* HRTIM Interrupt Clear Register */ +#define STM32_HRTIM_CMN_IER_OFFSET 0x0010 /* HRTIM Interrupt Enable Register */ +#define STM32_HRTIM_CMN_OENR_OFFSET 0x0014 /* HRTIM Output Enable Register */ +#define STM32_HRTIM_CMN_DISR_OFFSET 0x0018 /* HRTIM Output Disable Register */ +#define STM32_HRTIM_CMN_ODSR_OFFSET 0x001C /* HRTIM Output Disable Status Register */ +#define STM32_HRTIM_CMN_BMCR_OFFSET 0x0020 /* HRTIM Burst Mode Control Register */ +#define STM32_HRTIM_CMN_BMTRGR_OFFSET 0x0024 /* HRTIM Burst Mode Trigger Register */ +#define STM32_HRTIM_CMN_BMCMPR_OFFSET 0x0028 /* HRTIM Burst Mode Compare Register */ +#define STM32_HRTIM_CMN_BMPER_OFFSET 0x002C /* HRTIM Burst Mode Period Register */ +#define STM32_HRTIM_CMN_EECR1_OFFSET 0x0030 /* HRTIM Timer External Event Control Register 1 */ +#define STM32_HRTIM_CMN_EECR2_OFFSET 0x0034 /* HRTIM Timer External Event Control Register 2 */ +#define STM32_HRTIM_CMN_EECR3_OFFSET 0x0038 /* HRTIM Timer External Event Control Register 3 */ +#define STM32_HRTIM_CMN_ADC1R_OFFSET 0x003C /* HRTIM ADC Trigger 1 Register */ +#define STM32_HRTIM_CMN_ADC2R_OFFSET 0x0040 /* HRTIM ADC Trigger 2 Register */ +#define STM32_HRTIM_CMN_ADC3R_OFFSET 0x0044 /* HRTIM ADC Trigger 3 Register */ +#define STM32_HRTIM_CMN_ADC4R_OFFSET 0x0048 /* HRTIM ADC Trigger 4 Register */ +#define STM32_HRTIM_CMN_DLLCR_OFFSET 0x004C /* HRTIM DLL Control Register */ +#define STM32_HRTIM_CMN_FLTINR1_OFFSET 0x0050 /* HRTIM Fault Input Register 1 */ +#define STM32_HRTIM_CMN_FLTINR2_OFFSET 0x0054 /* HRTIM Fault Input Register 2 */ +#define STM32_HRTIM_CMN_BDMUPDR_OFFSET 0x0058 /* HRTIM Master Timer Update Register */ +#define STM32_HRTIM_CMN_BDTAUPR_OFFSET 0x005C /* HRTIM Timer A Update Register */ +#define STM32_HRTIM_CMN_BDTBUPR_OFFSET 0x0060 /* HRTIM Timer B Update Register */ +#define STM32_HRTIM_CMN_BDTCUPR_OFFSET 0x0064 /* HRTIM Timer C Update Register */ +#define STM32_HRTIM_CMN_BDTDUPR_OFFSET 0x0068 /* HRTIM Timer D Update Register */ +#define STM32_HRTIM_CMN_BDTEUPR_OFFSET 0x006C /* HRTIM Timer E Update Register */ +#define STM32_HRTIM_CMN_BDMADR_OFFSET 0x0070 /* HRTIM DMA Data Register */ /* Register Addresses *******************************************************************************/ -/* HRTIM1 Master Timer */ - -#define STM32_HRTIM1_MASTER_MCR (STM32_HRTIM_MASTER_MCR+STM32_HRTIM1_MASTER_BASE) -#define STM32_HRTIM1_MASTER_MISR (STM32_HRTIM_MASTER_MISR+STM32_HRTIM1_MASTER_BASE) -#define STM32_HRTIM1_MASTER_MICR (STM32_HRTIM_MASTER_MICR+STM32_HRTIM1_MASTER_BASE) -#define STM32_HRTIM1_MASTER_MDIER (STM32_HRTIM_MASTER_MDIER+STM32_HRTIM1_MASTER_BASE) -#define STM32_HRTIM1_MASTER_MCNTR (STM32_HRTIM_MASTER_MCNTR+STM32_HRTIM1_MASTER_BASE) -#define STM32_HRTIM1_MASTER_MPER (STM32_HRTIM_MASTER_MPER+STM32_HRTIM1_MASTER_BASE) -#define STM32_HRTIM1_MASTER_MREP (STM32_HRTIM_MASTER_MREP+STM32_HRTIM1_MASTER_BASE) -#define STM32_HRTIM1_MASTER_MCMP1R (STM32_HRTIM_MASTER_MCMP1R+STM32_HRTIM1_MASTER_BASE) -#define STM32_HRTIM1_MASTER_MCMP2R (STM32_HRTIM_MASTER_MCMP2R+STM32_HRTIM1_MASTER_BASE) -#define STM32_HRTIM1_MASTER_MCMP3R (STM32_HRTIM_MASTER_MCMP3R+STM32_HRTIM1_MASTER_BASE) -#define STM32_HRTIM1_MASTER_MCMP4R (STM32_HRTIM_MASTER_MCMP4R+STM32_HRTIM1_MASTER_BASE) - /* HRTIM1 Timer A */ - -#define STM32_HRTIM1_TIMERA_CR (STM32_HRTIM_TIMERA_CR+STM32_HRTIM1_TIMERA_BASE) -#define STM32_HRTIM1_TIMERA_ISR (STM32_HRTIM_TIMERA_ISR+STM32_HRTIM1_TIMERA_BASE) -#define STM32_HRTIM1_TIMERA_ICR (STM32_HRTIM_TIMERA_ICR+STM32_HRTIM1_TIMERA_BASE) -#define STM32_HRTIM1_TIMERA_DIER (STM32_HRTIM_TIMERA_DIER+STM32_HRTIM1_TIMERA_BASE) -#define STM32_HRTIM1_TIMERA_CNTR (STM32_HRTIM_TIMERA_CNTR+STM32_HRTIM1_TIMERA_BASE) -#define STM32_HRTIM1_TIMERA_PER (STM32_HRTIM_TIMERA_PER+STM32_HRTIM1_TIMERA_BASE) -#define STM32_HRTIM1_TIMERA_REP (STM32_HRTIM_TIMERA_REP+STM32_HRTIM1_TIMERA_BASE) -#define STM32_HRTIM1_TIMERA_CMP1R (STM32_HRTIM_TIMERA_CMP1R+STM32_HRTIM1_TIMERA_BASE) -#define STM32_HRTIM1_TIMERA_CMP1CR (STM32_HRTIM_TIMERA_CMP1CR+STM32_HRTIM1_TIMERA_BASE) -#define STM32_HRTIM1_TIMERA_CMP2R (STM32_HRTIM_TIMERA_CMP2R+STM32_HRTIM1_TIMERA_BASE) -#define STM32_HRTIM1_TIMERA_CMP3R (STM32_HRTIM_TIMERA_CMP3R+STM32_HRTIM1_TIMERA_BASE) -#define STM32_HRTIM1_TIMERA_CMP4R (STM32_HRTIM_TIMERA_CMP4R+STM32_HRTIM1_TIMERA_BASE) -#define STM32_HRTIM1_TIMERA_CPT1R (STM32_HRTIM_TIMERA_CMPT1R+STM32_HRTIM1_TIMERA_BASE) -#define STM32_HRTIM1_TIMERA_CPT2R (STM32_HRTIM_TIMERA_CMPT2R+STM32_HRTIM1_TIMERA_BASE) -#define STM32_HRTIM1_TIMERA_DTR (STM32_HRTIM_TIMERA_DTR+STM32_HRTIM1_TIMERA_BASE) -#define STM32_HRTIM1_TIMERA_SET1R (STM32_HRTIM_TIMERA_SET1R+STM32_HRTIM1_TIMERA_BASE) -#define STM32_HRTIM1_TIMERA_RST1R (STM32_HRTIM_TIMERA_RST1R+STM32_HRTIM1_TIMERA_BASE) -#define STM32_HRTIM1_TIMERA_SET2R (STM32_HRTIM_TIMERA_SET2R+STM32_HRTIM1_TIMERA_BASE) -#define STM32_HRTIM1_TIMERA_RST2R (STM32_HRTIM_TIMERA_RST2R+STM32_HRTIM1_TIMERA_BASE) -#define STM32_HRTIM1_TIMERA_EEFR1 (STM32_HRTIM_TIMERA_EEFR1+STM32_HRTIM1_TIMERA_BASE) -#define STM32_HRTIM1_TIMERA_EEFR2 (STM32_HRTIM_TIMERA_EEFR2+STM32_HRTIM1_TIMERA_BASE) -#define STM32_HRTIM1_TIMERA_RSTR (STM32_HRTIM_TIMERA_RSTR+STM32_HRTIM1_TIMERA_BASE) -#define STM32_HRTIM1_TIMERA_CHPR (STM32_HRTIM_TIMERA_CHPR+STM32_HRTIM1_TIMERA_BASE) -#define STM32_HRTIM1_TIMERA_CPT1CR (STM32_HRTIM_TIMERA_CPT1CR+STM32_HRTIM1_TIMERA_BASE) -#define STM32_HRTIM1_TIMERA_CPT2CR (STM32_HRTIM_TIMERA_CPT2CR+STM32_HRTIM1_TIMERA_BASE) -#define STM32_HRTIM1_TIMERA_OUTR (STM32_HRTIM_TIMERA_OUTR+STM32_HRTIM1_TIMERA_BASE) -#define STM32_HRTIM1_TIMERA_FLTR (STM32_HRTIM_TIMERA_FLTR+STM32_HRTIM1_TIMERA_BASE) +/* remove ? */ + +#define STM32_HRTIM1_TIMERA_CR (STM32_HRTIM_TIM_CR_OFFSET+STM32_HRTIM1_TIMERA_BASE) +#define STM32_HRTIM1_TIMERA_ISR (STM32_HRTIM_TIM_ISR_OFFSET+STM32_HRTIM1_TIMERA_BASE) +#define STM32_HRTIM1_TIMERA_ICR (STM32_HRTIM_TIM_ICR_OFFSET+STM32_HRTIM1_TIMERA_BASE) +#define STM32_HRTIM1_TIMERA_DIER (STM32_HRTIM_TIM_DIER_OFFSET+STM32_HRTIM1_TIMERA_BASE) +#define STM32_HRTIM1_TIMERA_CNTR (STM32_HRTIM_TIM_CNTR_OFFSET+STM32_HRTIM1_TIMERA_BASE) +#define STM32_HRTIM1_TIMERA_PER (STM32_HRTIM_TIM_PER_OFFSET+STM32_HRTIM1_TIMERA_BASE) +#define STM32_HRTIM1_TIMERA_REP (STM32_HRTIM_TIM_REP_OFFSET+STM32_HRTIM1_TIMERA_BASE) +#define STM32_HRTIM1_TIMERA_CMP1R (STM32_HRTIM_TIM_CMP1R_OFFSET+STM32_HRTIM1_TIMERA_BASE) +#define STM32_HRTIM1_TIMERA_CMP1CR (STM32_HRTIM_TIM_CMP1CR_OFFSET+STM32_HRTIM1_TIMERA_BASE) +#define STM32_HRTIM1_TIMERA_CMP2R (STM32_HRTIM_TIM_CMP2R_OFFSET+STM32_HRTIM1_TIMERA_BASE) +#define STM32_HRTIM1_TIMERA_CMP3R (STM32_HRTIM_TIM_CMP3R_OFFSET+STM32_HRTIM1_TIMERA_BASE) +#define STM32_HRTIM1_TIMERA_CMP4R (STM32_HRTIM_TIM_CMP4R_OFFSET+STM32_HRTIM1_TIMERA_BASE) +#define STM32_HRTIM1_TIMERA_CPT1R (STM32_HRTIM_TIM_CMPT1R_OFFSET+STM32_HRTIM1_TIMERA_BASE) +#define STM32_HRTIM1_TIMERA_CPT2R (STM32_HRTIM_TIM_CMPT2R_OFFSET+STM32_HRTIM1_TIMERA_BASE) +#define STM32_HRTIM1_TIMERA_DTR (STM32_HRTIM_TIM_DTR_OFFSET+STM32_HRTIM1_TIMERA_BASE) +#define STM32_HRTIM1_TIMERA_SET1R (STM32_HRTIM_TIM_SET1R_OFFSET+STM32_HRTIM1_TIMERA_BASE) +#define STM32_HRTIM1_TIMERA_RST1R (STM32_HRTIM_TIM_RST1R_OFFSET+STM32_HRTIM1_TIMERA_BASE) +#define STM32_HRTIM1_TIMERA_SET2R (STM32_HRTIM_TIM_SET2R_OFFSET+STM32_HRTIM1_TIMERA_BASE) +#define STM32_HRTIM1_TIMERA_RST2R (STM32_HRTIM_TIM_RST2R_OFFSET+STM32_HRTIM1_TIMERA_BASE) +#define STM32_HRTIM1_TIMERA_EEFR1 (STM32_HRTIM_TIM_EEFR1_OFFSET+STM32_HRTIM1_TIMERA_BASE) +#define STM32_HRTIM1_TIMERA_EEFR2 (STM32_HRTIM_TIM_EEFR2_OFFSET+STM32_HRTIM1_TIMERA_BASE) +#define STM32_HRTIM1_TIMERA_RSTR (STM32_HRTIM_TIM_RSTR_OFFSET+STM32_HRTIM1_TIMERA_BASE) +#define STM32_HRTIM1_TIMERA_CHPR (STM32_HRTIM_TIM_CHPR_OFFSET+STM32_HRTIM1_TIMERA_BASE) +#define STM32_HRTIM1_TIMERA_CPT1CR (STM32_HRTIM_TIM_CPT1CR_OFFSET+STM32_HRTIM1_TIMERA_BASE) +#define STM32_HRTIM1_TIMERA_CPT2CR (STM32_HRTIM_TIM_CPT2CR_OFFSET+STM32_HRTIM1_TIMERA_BASE) +#define STM32_HRTIM1_TIMERA_OUTR (STM32_HRTIM_TIM_OUTR_OFFSET+STM32_HRTIM1_TIMERA_BASE) +#define STM32_HRTIM1_TIMERA_FLTR (STM32_HRTIM_TIM_FLTR_OFFSET+STM32_HRTIM1_TIMERA_BASE) /* HRTIM1 Timer B */ -#define STM32_HRTIM1_TIMERB_CR (STM32_HRTIM_TIMERB_CR+STM32_HRTIM1_TIMERB_BASE) -#define STM32_HRTIM1_TIMERB_ISR (STM32_HRTIM_TIMERB_ISR+STM32_HRTIM1_TIMERB_BASE) -#define STM32_HRTIM1_TIMERB_ICR (STM32_HRTIM_TIMERB_ICR+STM32_HRTIM1_TIMERB_BASE) -#define STM32_HRTIM1_TIMERB_DIER (STM32_HRTIM_TIMERB_DIER+STM32_HRTIM1_TIMERB_BASE) -#define STM32_HRTIM1_TIMERB_CNTR (STM32_HRTIM_TIMERB_CNTR+STM32_HRTIM1_TIMERB_BASE) -#define STM32_HRTIM1_TIMERB_PER (STM32_HRTIM_TIMERB_PER+STM32_HRTIM1_TIMERB_BASE) -#define STM32_HRTIM1_TIMERB_REP (STM32_HRTIM_TIMERB_REP+STM32_HRTIM1_TIMERB_BASE) -#define STM32_HRTIM1_TIMERB_CMP1R (STM32_HRTIM_TIMERB_CMP1R+STM32_HRTIM1_TIMERB_BASE) -#define STM32_HRTIM1_TIMERB_CMP1CR (STM32_HRTIM_TIMERB_CMP1CR+STM32_HRTIM1_TIMERB_BASE) -#define STM32_HRTIM1_TIMERB_CMP2R (STM32_HRTIM_TIMERB_CMP2R+STM32_HRTIM1_TIMERB_BASE) -#define STM32_HRTIM1_TIMERB_CMP3R (STM32_HRTIM_TIMERB_CMP3R+STM32_HRTIM1_TIMERB_BASE) -#define STM32_HRTIM1_TIMERB_CMP4R (STM32_HRTIM_TIMERB_CMP4R+STM32_HRTIM1_TIMERB_BASE) -#define STM32_HRTIM1_TIMERB_CPT1R (STM32_HRTIM_TIMERB_CMPT1R+STM32_HRTIM1_TIMERB_BASE) -#define STM32_HRTIM1_TIMERB_CPT2R (STM32_HRTIM_TIMERB_CMPT2R+STM32_HRTIM1_TIMERB_BASE) -#define STM32_HRTIM1_TIMERB_DTR (STM32_HRTIM_TIMERB_DTR+STM32_HRTIM1_TIMERB_BASE) -#define STM32_HRTIM1_TIMERB_SET1R (STM32_HRTIM_TIMERB_SET1R+STM32_HRTIM1_TIMERB_BASE) -#define STM32_HRTIM1_TIMERB_RST1R (STM32_HRTIM_TIMERB_RST1R+STM32_HRTIM1_TIMERB_BASE) -#define STM32_HRTIM1_TIMERB_SET2R (STM32_HRTIM_TIMERB_SET2R+STM32_HRTIM1_TIMERB_BASE) -#define STM32_HRTIM1_TIMERB_RST2R (STM32_HRTIM_TIMERB_RST2R+STM32_HRTIM1_TIMERB_BASE) -#define STM32_HRTIM1_TIMERB_EEFR1 (STM32_HRTIM_TIMERB_EEFR1+STM32_HRTIM1_TIMERB_BASE) -#define STM32_HRTIM1_TIMERB_EEFR2 (STM32_HRTIM_TIMERB_EEFR2+STM32_HRTIM1_TIMERB_BASE) -#define STM32_HRTIM1_TIMERB_RSTR (STM32_HRTIM_TIMERB_RSTR+STM32_HRTIM1_TIMERB_BASE) -#define STM32_HRTIM1_TIMERB_CHPR (STM32_HRTIM_TIMERB_CHPR+STM32_HRTIM1_TIMERB_BASE) -#define STM32_HRTIM1_TIMERB_CPT1CR (STM32_HRTIM_TIMERB_CPT1CR+STM32_HRTIM1_TIMERB_BASE) -#define STM32_HRTIM1_TIMERB_CPT2CR (STM32_HRTIM_TIMERB_CPT2CR+STM32_HRTIM1_TIMERB_BASE) -#define STM32_HRTIM1_TIMERB_OUTR (STM32_HRTIM_TIMERB_OUTR+STM32_HRTIM1_TIMERB_BASE) -#define STM32_HRTIM1_TIMERB_FLTR (STM32_HRTIM_TIMERB_FLTR+STM32_HRTIM1_TIMERB_BASE) - /* HRTIM1 Timer C */ -#define STM32_HRTIM1_TIMERC_CR (STM32_HRTIM_TIMERC_CR+STM32_HRTIM1_TIMERC_BASE) -#define STM32_HRTIM1_TIMERC_ISR (STM32_HRTIM_TIMERC_ISR+STM32_HRTIM1_TIMERC_BASE) -#define STM32_HRTIM1_TIMERC_ICR (STM32_HRTIM_TIMERC_ICR+STM32_HRTIM1_TIMERC_BASE) -#define STM32_HRTIM1_TIMERC_DIER (STM32_HRTIM_TIMERC_DIER+STM32_HRTIM1_TIMERC_BASE) -#define STM32_HRTIM1_TIMERC_CNTR (STM32_HRTIM_TIMERC_CNTR+STM32_HRTIM1_TIMERC_BASE) -#define STM32_HRTIM1_TIMERC_PER (STM32_HRTIM_TIMERC_PER+STM32_HRTIM1_TIMERC_BASE) -#define STM32_HRTIM1_TIMERC_REP (STM32_HRTIM_TIMERC_REP+STM32_HRTIM1_TIMERC_BASE) -#define STM32_HRTIM1_TIMERC_CMP1R (STM32_HRTIM_TIMERC_CMP1R+STM32_HRTIM1_TIMERC_BASE) -#define STM32_HRTIM1_TIMERC_CMP1CR (STM32_HRTIM_TIMERC_CMP1CR+STM32_HRTIM1_TIMERC_BASE) -#define STM32_HRTIM1_TIMERC_CMP2R (STM32_HRTIM_TIMERC_CMP2R+STM32_HRTIM1_TIMERC_BASE) -#define STM32_HRTIM1_TIMERC_CMP3R (STM32_HRTIM_TIMERC_CMP3R+STM32_HRTIM1_TIMERC_BASE) -#define STM32_HRTIM1_TIMERC_CMP4R (STM32_HRTIM_TIMERC_CMP4R+STM32_HRTIM1_TIMERC_BASE) -#define STM32_HRTIM1_TIMERC_CPT1R (STM32_HRTIM_TIMERC_CMPT1R+STM32_HRTIM1_TIMERC_BASE) -#define STM32_HRTIM1_TIMERC_CPT2R (STM32_HRTIM_TIMERC_CMPT2R+STM32_HRTIM1_TIMERC_BASE) -#define STM32_HRTIM1_TIMERC_DTR (STM32_HRTIM_TIMERC_DTR+STM32_HRTIM1_TIMERC_BASE) -#define STM32_HRTIM1_TIMERC_SET1R (STM32_HRTIM_TIMERC_SET1R+STM32_HRTIM1_TIMERC_BASE) -#define STM32_HRTIM1_TIMERC_RST1R (STM32_HRTIM_TIMERC_RST1R+STM32_HRTIM1_TIMERC_BASE) -#define STM32_HRTIM1_TIMERC_SET2R (STM32_HRTIM_TIMERC_SET2R+STM32_HRTIM1_TIMERC_BASE) -#define STM32_HRTIM1_TIMERC_RST2R (STM32_HRTIM_TIMERC_RST2R+STM32_HRTIM1_TIMERC_BASE) -#define STM32_HRTIM1_TIMERC_EEFR1 (STM32_HRTIM_TIMERC_EEFR1+STM32_HRTIM1_TIMERC_BASE) -#define STM32_HRTIM1_TIMERC_EEFR2 (STM32_HRTIM_TIMERC_EEFR2+STM32_HRTIM1_TIMERC_BASE) -#define STM32_HRTIM1_TIMERC_RSTR (STM32_HRTIM_TIMERC_RSTR+STM32_HRTIM1_TIMERC_BASE) -#define STM32_HRTIM1_TIMERC_CHPR (STM32_HRTIM_TIMERC_CHPR+STM32_HRTIM1_TIMERC_BASE) -#define STM32_HRTIM1_TIMERC_CPT1CR (STM32_HRTIM_TIMERC_CPT1CR+STM32_HRTIM1_TIMERC_BASE) -#define STM32_HRTIM1_TIMERC_CPT2CR (STM32_HRTIM_TIMERC_CPT2CR+STM32_HRTIM1_TIMERC_BASE) -#define STM32_HRTIM1_TIMERC_OUTR (STM32_HRTIM_TIMERC_OUTR+STM32_HRTIM1_TIMERC_BASE) -#define STM32_HRTIM1_TIMERC_FLTR (STM32_HRTIM_TIMERC_FLTR+STM32_HRTIM1_TIMERC_BASE) - /* HRTIM1 Timer D */ -#define STM32_HRTIM1_TIMERD_CR (STM32_HRTIM_TIMERD_CR+STM32_HRTIM1_TIMERD_BASE) -#define STM32_HRTIM1_TIMERD_ISR (STM32_HRTIM_TIMERD_ISR+STM32_HRTIM1_TIMERD_BASE) -#define STM32_HRTIM1_TIMERD_ICR (STM32_HRTIM_TIMERD_ICR+STM32_HRTIM1_TIMERD_BASE) -#define STM32_HRTIM1_TIMERD_DIER (STM32_HRTIM_TIMERD_DIER+STM32_HRTIM1_TIMERD_BASE) -#define STM32_HRTIM1_TIMERD_CNTR (STM32_HRTIM_TIMERD_CNTR+STM32_HRTIM1_TIMERD_BASE) -#define STM32_HRTIM1_TIMERD_PER (STM32_HRTIM_TIMERD_PER+STM32_HRTIM1_TIMERD_BASE) -#define STM32_HRTIM1_TIMERD_REP (STM32_HRTIM_TIMERD_REP+STM32_HRTIM1_TIMERD_BASE) -#define STM32_HRTIM1_TIMERD_CMP1R (STM32_HRTIM_TIMERD_CMP1R+STM32_HRTIM1_TIMERD_BASE) -#define STM32_HRTIM1_TIMERD_CMP1CR (STM32_HRTIM_TIMERD_CMP1CR+STM32_HRTIM1_TIMERD_BASE) -#define STM32_HRTIM1_TIMERD_CMP2R (STM32_HRTIM_TIMERD_CMP2R+STM32_HRTIM1_TIMERD_BASE) -#define STM32_HRTIM1_TIMERD_CMP3R (STM32_HRTIM_TIMERD_CMP3R+STM32_HRTIM1_TIMERD_BASE) -#define STM32_HRTIM1_TIMERD_CMP4R (STM32_HRTIM_TIMERD_CMP4R+STM32_HRTIM1_TIMERD_BASE) -#define STM32_HRTIM1_TIMERD_CPT1R (STM32_HRTIM_TIMERD_CMPT1R+STM32_HRTIM1_TIMERD_BASE) -#define STM32_HRTIM1_TIMERD_CPT2R (STM32_HRTIM_TIMERD_CMPT2R+STM32_HRTIM1_TIMERD_BASE) -#define STM32_HRTIM1_TIMERD_DTR (STM32_HRTIM_TIMERD_DTR+STM32_HRTIM1_TIMERD_BASE) -#define STM32_HRTIM1_TIMERD_SET1R (STM32_HRTIM_TIMERD_SET1R+STM32_HRTIM1_TIMERD_BASE) -#define STM32_HRTIM1_TIMERD_RST1R (STM32_HRTIM_TIMERD_RST1R+STM32_HRTIM1_TIMERD_BASE) -#define STM32_HRTIM1_TIMERD_SET2R (STM32_HRTIM_TIMERD_SET2R+STM32_HRTIM1_TIMERD_BASE) -#define STM32_HRTIM1_TIMERD_RST2R (STM32_HRTIM_TIMERD_RST2R+STM32_HRTIM1_TIMERD_BASE) -#define STM32_HRTIM1_TIMERD_EEFR1 (STM32_HRTIM_TIMERD_EEFR1+STM32_HRTIM1_TIMERD_BASE) -#define STM32_HRTIM1_TIMERD_EEFR2 (STM32_HRTIM_TIMERD_EEFR2+STM32_HRTIM1_TIMERD_BASE) -#define STM32_HRTIM1_TIMERD_RSTR (STM32_HRTIM_TIMERD_RSTR+STM32_HRTIM1_TIMERD_BASE) -#define STM32_HRTIM1_TIMERD_CHPR (STM32_HRTIM_TIMERD_CHPR+STM32_HRTIM1_TIMERD_BASE) -#define STM32_HRTIM1_TIMERD_CPT1CR (STM32_HRTIM_TIMERD_CPT1CR+STM32_HRTIM1_TIMERD_BASE) -#define STM32_HRTIM1_TIMERD_CPT2CR (STM32_HRTIM_TIMERD_CPT2CR+STM32_HRTIM1_TIMERD_BASE) -#define STM32_HRTIM1_TIMERD_OUTR (STM32_HRTIM_TIMERD_OUTR+STM32_HRTIM1_TIMERD_BASE) -#define STM32_HRTIM1_TIMERD_FLTR (STM32_HRTIM_TIMERD_FLTR+STM32_HRTIM1_TIMERD_BASE) - /* HRTIM1 Timer E */ -#define STM32_HRTIM1_TIMERE_CR (STM32_HRTIM_TIMERE_CR+STM32_HRTIM1_TIMERE_BASE) -#define STM32_HRTIM1_TIMERE_ISR (STM32_HRTIM_TIMERE_ISR+STM32_HRTIM1_TIMERE_BASE) -#define STM32_HRTIM1_TIMERE_ICR (STM32_HRTIM_TIMERE_ICR+STM32_HRTIM1_TIMERE_BASE) -#define STM32_HRTIM1_TIMERE_DIER (STM32_HRTIM_TIMERE_DIER+STM32_HRTIM1_TIMERE_BASE) -#define STM32_HRTIM1_TIMERE_CNTR (STM32_HRTIM_TIMERE_CNTR+STM32_HRTIM1_TIMERE_BASE) -#define STM32_HRTIM1_TIMERE_PER (STM32_HRTIM_TIMERE_PER+STM32_HRTIM1_TIMERE_BASE) -#define STM32_HRTIM1_TIMERE_REP (STM32_HRTIM_TIMERE_REP+STM32_HRTIM1_TIMERE_BASE) -#define STM32_HRTIM1_TIMERE_CMP1R (STM32_HRTIM_TIMERE_CMP1R+STM32_HRTIM1_TIMERE_BASE) -#define STM32_HRTIM1_TIMERE_CMP1CR (STM32_HRTIM_TIMERE_CMP1CR+STM32_HRTIM1_TIMERE_BASE) -#define STM32_HRTIM1_TIMERE_CMP2R (STM32_HRTIM_TIMERE_CMP2R+STM32_HRTIM1_TIMERE_BASE) -#define STM32_HRTIM1_TIMERE_CMP3R (STM32_HRTIM_TIMERE_CMP3R+STM32_HRTIM1_TIMERE_BASE) -#define STM32_HRTIM1_TIMERE_CMP4R (STM32_HRTIM_TIMERE_CMP4R+STM32_HRTIM1_TIMERE_BASE) -#define STM32_HRTIM1_TIMERE_CPT1R (STM32_HRTIM_TIMERE_CMPT1R+STM32_HRTIM1_TIMERE_BASE) -#define STM32_HRTIM1_TIMERE_CPT2R (STM32_HRTIM_TIMERE_CMPT2R+STM32_HRTIM1_TIMERE_BASE) -#define STM32_HRTIM1_TIMERE_DTR (STM32_HRTIM_TIMERE_DTR+STM32_HRTIM1_TIMERE_BASE) -#define STM32_HRTIM1_TIMERE_SET1R (STM32_HRTIM_TIMERE_SET1R+STM32_HRTIM1_TIMERE_BASE) -#define STM32_HRTIM1_TIMERE_RST1R (STM32_HRTIM_TIMERE_RST1R+STM32_HRTIM1_TIMERE_BASE) -#define STM32_HRTIM1_TIMERE_SET2R (STM32_HRTIM_TIMERE_SET2R+STM32_HRTIM1_TIMERE_BASE) -#define STM32_HRTIM1_TIMERE_RST2R (STM32_HRTIM_TIMERE_RST2R+STM32_HRTIM1_TIMERE_BASE) -#define STM32_HRTIM1_TIMERE_EEFR1 (STM32_HRTIM_TIMERE_EEFR1+STM32_HRTIM1_TIMERE_BASE) -#define STM32_HRTIM1_TIMERE_EEFR2 (STM32_HRTIM_TIMERE_EEFR2+STM32_HRTIM1_TIMERE_BASE) -#define STM32_HRTIM1_TIMERE_RSTR (STM32_HRTIM_TIMERE_RSTR+STM32_HRTIM1_TIMERE_BASE) -#define STM32_HRTIM1_TIMERE_CHPR (STM32_HRTIM_TIMERE_CHPR+STM32_HRTIM1_TIMERE_BASE) -#define STM32_HRTIM1_TIMERE_CPT1CR (STM32_HRTIM_TIMERE_CPT1CR+STM32_HRTIM1_TIMERE_BASE) -#define STM32_HRTIM1_TIMERE_CPT2CR (STM32_HRTIM_TIMERE_CPT2CR+STM32_HRTIM1_TIMERE_BASE) -#define STM32_HRTIM1_TIMERE_OUTR (STM32_HRTIM_TIMERE_OUTR+STM32_HRTIM1_TIMERE_BASE) -#define STM32_HRTIM1_TIMERE_FLTR (STM32_HRTIM_TIMERE_FLTR+STM32_HRTIM1_TIMERE_BASE) - /* HRTIM1 Common Registers */ -#define STM32_HRTIM_CMN_CR1 (STM32_HRTIM_CMN_CR1+STM32_HRTIM1_CMN_BASE) -#define STM32_HRTIM_CMN_CR2 (STM32_HRTIM_CMN_CR2+STM32_HRTIM1_CMN_BASE) -#define STM32_HRTIM_CMN_ISR (STM32_HRTIM_CMN_ISR+STM32_HRTIM1_CMN_BASE) -#define STM32_HRTIM_CMN_ICR (STM32_HRTIM_CMN_ICR+STM32_HRTIM1_CMN_BASE) -#define STM32_HRTIM_CMN_IER (STM32_HRTIM_CMN_IER+STM32_HRTIM1_CMN_BASE) -#define STM32_HRTIM_CMN_OENR (STM32_HRTIM_CMN_OENR+STM32_HRTIM1_CMN_BASE) -#define STM32_HRTIM_CMN_DISR (STM32_HRTIM_CMN_DISR+STM32_HRTIM1_CMN_BASE) -#define STM32_HRTIM_CMN_ODSR (STM32_HRTIM_CMN_ODSR+STM32_HRTIM1_CMN_BASE) -#define STM32_HRTIM_CMN_BMCR (STM32_HRTIM_CMN_BMCR+STM32_HRTIM1_CMN_BASE) -#define STM32_HRTIM_CMN_BMTGR (STM32_HRTIM_CMN_BMTGR+STM32_HRTIM1_CMN_BASE) -#define STM32_HRTIM_CMN_BMCMPR (STM32_HRTIM_CMN_MBCMPR+STM32_HRTIM1_CMN_BASE) -#define STM32_HRTIM_CMN_BMPER (STM32_HRTIM_CMN_BMPER+STM32_HRTIM1_CMN_BASE) -#define STM32_HRTIM_CMN_EECR1 (STM32_HRTIM_CMN_EECR1+STM32_HRTIM1_CMN_BASE) -#define STM32_HRTIM_CMN_EECR2 (STM32_HRTIM_CMN_EECR2+STM32_HRTIM1_CMN_BASE) -#define STM32_HRTIM_CMN_EECR3 (STM32_HRTIM_CMN_EECR3+STM32_HRTIM1_CMN_BASE) -#define STM32_HRTIM_CMN_ADC1R (STM32_HRTIM_CMN_ADC1R+STM32_HRTIM1_CMN_BASE) -#define STM32_HRTIM_CMN_ADC2R (STM32_HRTIM_CMN_ADC2R+STM32_HRTIM1_CMN_BASE) -#define STM32_HRTIM_CMN_ADC3R (STM32_HRTIM_CMN_ADC3R+STM32_HRTIM1_CMN_BASE) -#define STM32_HRTIM_CMN_ADC4R (STM32_HRTIM_CMN_ADC4R+STM32_HRTIM1_CMN_BASE) -#define STM32_HRTIM_CMN_DLLCR (STM32_HRTIM_CMN_DLLCR+STM32_HRTIM1_CMN_BASE) -#define STM32_HRTIM_CMN_FLTINR1 (STM32_HRTIM_CMN_FTLINR1+STM32_HRTIM1_CMN_BASE) -#define STM32_HRTIM_CMN_FLTINR2 (STM32_HRTIM_CMN_FLTINR2+STM32_HRTIM1_CMN_BASE) -#define STM32_HRTIM_CMN_BDMUPDR (STM32_HRTIM_CMN_BDMUPDR+STM32_HRTIM1_CMN_BASE) -#define STM32_HRTIM_CMN_BDTAUPR (STM32_HRTIM_CMN_BDTAUPR+STM32_HRTIM1_CMN_BASE) -#define STM32_HRTIM_CMN_BDTBUPR (STM32_HRTIM_CMN_BDTBUR+STM32_HRTIM1_CMN_BASE) -#define STM32_HRTIM_CMN_BDTCUPR (STM32_HRTIM_CMN_BDTCUPR+STM32_HRTIM1_CMN_BASE) -#define STM32_HRTIM_CMN_BDTDUPR (STM32_HRTIM_CMN_BDTDUPR+STM32_HRTIM1_CMN_BASE) -#define STM32_HRTIM_CMN_BDTEUPR (STM32_HRTIM_CMN_BDTEUPR+STM32_HRTIM1_CMN_BASE) -#define STM32_HRTIM_CMN_BDMADR (STM32_HRTIM_CMN_BDMADR+STM32_HRTIM1_CMN_BASE) +#define STM32_HRTIM_CMN_CR1 (STM32_HRTIM_CMN_CR1_OFFSET+STM32_HRTIM1_CMN_BASE) +#define STM32_HRTIM_CMN_CR2 (STM32_HRTIM_CMN_CR2_OFFSET+STM32_HRTIM1_CMN_BASE) +#define STM32_HRTIM_CMN_ISR (STM32_HRTIM_CMN_ISR_OFFSET+STM32_HRTIM1_CMN_BASE) +#define STM32_HRTIM_CMN_ICR (STM32_HRTIM_CMN_ICR_OFFSET+STM32_HRTIM1_CMN_BASE) +#define STM32_HRTIM_CMN_IER (STM32_HRTIM_CMN_IER_OFFSET+STM32_HRTIM1_CMN_BASE) +#define STM32_HRTIM_CMN_OENR (STM32_HRTIM_CMN_OENR_OFFSET+STM32_HRTIM1_CMN_BASE) +#define STM32_HRTIM_CMN_DISR (STM32_HRTIM_CMN_DISR_OFFSET+STM32_HRTIM1_CMN_BASE) +#define STM32_HRTIM_CMN_ODSR (STM32_HRTIM_CMN_ODSR_OFFSET+STM32_HRTIM1_CMN_BASE) +#define STM32_HRTIM_CMN_BMCR (STM32_HRTIM_CMN_BMCR_OFFSET+STM32_HRTIM1_CMN_BASE) +#define STM32_HRTIM_CMN_BMTGR (STM32_HRTIM_CMN_BMTGR_OFFSET+STM32_HRTIM1_CMN_BASE) +#define STM32_HRTIM_CMN_BMCMPR (STM32_HRTIM_CMN_MBCMPR_OFFSET+STM32_HRTIM1_CMN_BASE) +#define STM32_HRTIM_CMN_BMPER (STM32_HRTIM_CMN_BMPER_OFFSET+STM32_HRTIM1_CMN_BASE) +#define STM32_HRTIM_CMN_EECR1 (STM32_HRTIM_CMN_EECR1_OFFSET+STM32_HRTIM1_CMN_BASE) +#define STM32_HRTIM_CMN_EECR2 (STM32_HRTIM_CMN_EECR2_OFFSET+STM32_HRTIM1_CMN_BASE) +#define STM32_HRTIM_CMN_EECR3 (STM32_HRTIM_CMN_EECR3_OFFSET+STM32_HRTIM1_CMN_BASE) +#define STM32_HRTIM_CMN_ADC1R (STM32_HRTIM_CMN_ADC1R_OFFSET+STM32_HRTIM1_CMN_BASE) +#define STM32_HRTIM_CMN_ADC2R (STM32_HRTIM_CMN_ADC2R_OFFSET+STM32_HRTIM1_CMN_BASE) +#define STM32_HRTIM_CMN_ADC3R (STM32_HRTIM_CMN_ADC3R_OFFSET+STM32_HRTIM1_CMN_BASE) +#define STM32_HRTIM_CMN_ADC4R (STM32_HRTIM_CMN_ADC4R_OFFSET+STM32_HRTIM1_CMN_BASE) +#define STM32_HRTIM_CMN_DLLCR (STM32_HRTIM_CMN_DLLCR_OFFSET+STM32_HRTIM1_CMN_BASE) +#define STM32_HRTIM_CMN_FLTINR1 (STM32_HRTIM_CMN_FTLINR1_OFFSET+STM32_HRTIM1_CMN_BASE) +#define STM32_HRTIM_CMN_FLTINR2 (STM32_HRTIM_CMN_FLTINR2_OFFSET+STM32_HRTIM1_CMN_BASE) +#define STM32_HRTIM_CMN_BDMUPDR (STM32_HRTIM_CMN_BDMUPDR_OFFSET+STM32_HRTIM1_CMN_BASE) +#define STM32_HRTIM_CMN_BDTAUPR (STM32_HRTIM_CMN_BDTAUPR_OFFSET+STM32_HRTIM1_CMN_BASE) +#define STM32_HRTIM_CMN_BDTBUPR (STM32_HRTIM_CMN_BDTBUR_OFFSET+STM32_HRTIM1_CMN_BASE) +#define STM32_HRTIM_CMN_BDTCUPR (STM32_HRTIM_CMN_BDTCUPR_OFFSET+STM32_HRTIM1_CMN_BASE) +#define STM32_HRTIM_CMN_BDTDUPR (STM32_HRTIM_CMN_BDTDUPR_OFFSET+STM32_HRTIM1_CMN_BASE) +#define STM32_HRTIM_CMN_BDTEUPR (STM32_HRTIM_CMN_BDTEUPR_OFFSET+STM32_HRTIM1_CMN_BASE) +#define STM32_HRTIM_CMN_BDMADR (STM32_HRTIM_CMN_BDMADR_OFFSET+STM32_HRTIM1_CMN_BASE) /* Register Bitfield Definitions ****************************************************/ -/* Master Timer Control Register */ - -#define HRTIM_MCR_CKPSC_SHIFT 0 /* Bits 0-2: Clock prescaler */ -#define HRTIM_MCR_CKPSC_MASK (7 << HRTIM_MCR_CKPSC_SHIFT) -# define HRTIM_MCR_CKPSC_NODIV (0 << HRTIM_MCR_CKPSC_SHIFT) -# define HRTIM_MCR_CKPSC_d2 (1 << HRTIM_MCR_CKPSC_SHIFT) -# define HRTIM_MCR_CKPSC_d4 (2 << HRTIM_MCR_CKPSC_SHIFT) -# define HRTIM_MCR_CKPSC_d8 (3 << HRTIM_MCR_CKPSC_SHIFT) -# define HRTIM_MCR_CKPSC_d16 (4 << HRTIM_MCR_CKPSC_SHIFT) -# define HRTIM_MCR_CKPSC_d32 (5 << HRTIM_MCR_CKPSC_SHIFT) -# define HRTIM_MCR_CKPSC_d64 (6 << HRTIM_MCR_CKPSC_SHIFT) -# define HRTIM_MCR_CKPSC_d128 (7 << HRTIM_MCR_CKPSC_SHIFT) -#define HRTIM_MCR_CONT (1 << 3) /* Bit 3: Continuous mode */ -#define HRTIM_MCR_RETRIG (1 << 4) /* Bit 4: Re-triggerable mode */ -#define HRTIM_MCR_HALF (1 << 5) /* Bit 5: Half mode */ -#define HRTIM_MCR_SYNCIN_SHIFT 8 /* Bits 8-9: Synchronization input */ +/* Control Register Bits Common to Master Timer and Timer A-E */ + +#define HRTIM_CMNCR_CKPSC_SHIFT 0 /* Bits 0-2: Clock prescaler */ +#define HRTIM_CMNCR_CKPSC_MASK (7 << HRTIM_CMNCR_CKPSC_SHIFT) +# define HRTIM_CMNCR_CKPSC_NODIV (0 << HRTIM_CMNCR_CKPSC_SHIFT) +# define HRTIM_CMNCR_CKPSC_d2 (1 << HRTIM_CMNCR_CKPSC_SHIFT) +# define HRTIM_CMNCR_CKPSC_d4 (2 << HRTIM_CMNCR_CKPSC_SHIFT) +# define HRTIM_CMNCR_CKPSC_d8 (3 << HRTIM_CMNCR_CKPSC_SHIFT) +# define HRTIM_CMNCR_CKPSC_d16 (4 << HRTIM_CMNCR_CKPSC_SHIFT) +# define HRTIM_CMNCR_CKPSC_d32 (5 << HRTIM_CMNCR_CKPSC_SHIFT) +# define HRTIM_CMNCR_CKPSC_d64 (6 << HRTIM_CMNCR_CKPSC_SHIFT) +# define HRTIM_CMNCR_CKPSC_d128 (7 << HRTIM_CMNCR_CKPSC_SHIFT) +#define HRTIM_CMNCR_CONT (1 << 3) /* Bit 3: Continuous mode */ +#define HRTIM_CMNCR_RETRIG (1 << 4) /* Bit 4: Re-triggerable mode */ +#define HRTIM_CMNCR_HALF (1 << 5) /* Bit 5: Half mode */ + /* Bits 6-9 differs */ +#define HRTIM_CMNCR_SYNCRST (1 << 10) /* Bit 10: Synchronization Resets Master */ +#define HRTIM_CMNCR_SYNCSTRTM (1 << 11) /* Bit 11: Synchronization Starts Master */ + /* Bits 12-24 differs */ +#define HRTIM_CMNCR_DACSYNC_SHIFT 25 /* Bits 25-26: DAC Synchronization*/ +#define HRTIM_CMNCR_DACSYNC_MASK (3 << HRTIM_CMNCR_DACSYNC_SHIFT) +# define HRTIM_CMNCR_DACSYNC_00 (0 << HRTIM_CMNCR_DACSYNC_SHIFT) /* 00: */ +# define HRTIM_CMNCR_DACSYNC_01 (1 << HRTIM_CMNCR_DACSYNC_SHIFT) /* 01: */ +# define HRTIM_CMNCR_DACSYNC_10 (2 << HRTIM_CMNCR_DACSYNC_SHIFT) /* 10: */ +# define HRTIM_CMNCR_DACSYNC_11 (3 << HRTIM_CMNCR_DACSYNC_SHIFT) /* 11: */ +#define HRTIM_CMNCR_PREEN (1 << 27) /* Bit 27: Preload enable */ + /* Bits 29-31 differs */ + +/* Control Register Bits specific to Master Timer */ + + /* Bits 0-5 common */ + /* Bits 6-7 reserved */ + /* Bits 10-11 common */ +#define HRTIM_MCR_SYNCIN_SHIFT 8 /* Bits 8-9: Synchronization input */ #define HRTIM_MCR_SYNCIN_MASK (3 << HRTIM_MCR_SYNCIN_SHIFT) # define HRTIM_MCR_SYNCIN_DIS (0 << HRTIM_MCR_SYNCIN_SHIFT) /* 00 disabled */ # define HRTIM_MCR_SYNCIN_INTE (2 << HRTIM_MCR_SYNCIN_SHIFT) /* 10: Internal Event */ # define HRTIM_MCR_SYNCIN_EXTE (3 << HRTIM_MCR_SYNCIN_SHIFT) /* 11: External Event */ -#define HRTIM_MCR_SYNCRST (1 << 10) /* Bit 10: Synchronization Resets Master */ -#define HRTIM_MCR_SYNCSTRTM (1 << 11) /* Bit 11: Synchronization Starts Master */ -#define HRTIM_MCR_SYNCOUT_SHIFT 12 /* Bits 12-13: Synchronization output */ +#define HRTIM_MCR_SYNCOUT_SHIFT 12 /* Bits 12-13: Synchronization output */ #define HRTIM_MCR_SYNCOUT_MASK (3 << HRTIM_MCR_SYNCOUT_SHIFT) # define HRTIM_MCR_SYNCOUT_DIS (0 << HRTIM_MCR_SYNCOUT_SHIFT) /* 00: Disabled */ # define HRTIM_MCR_SYNCOUT_POS (2 << HRTIM_MCR_SYNCOUT_SHIFT) /* 10: Positive pulse on SCOUT */ # define HRTIM_MCR_SYNCOUT_NEG (3 << HRTIM_MCR_SYNCOUT_SHIFT) /* 11: Negative pulse on SCOUT */ -#define HRTIM_MCR_SYNCSRC_SHIFT 14 /* Bits 14-15: Synchronization source*/ +#define HRTIM_MCR_SYNCSRC_SHIFT 14 /* Bits 14-15: Synchronization source*/ #define HRTIM_MCR_SYNCSRC_MASK (3 << HRTIM_MCR_SYNCSRC_SHIFT) # define HRTIM_MCR_SYNCSRC_MSTRT (0 << HRTIM_MCR_SYNCSRC_SHIFT) /* 00: Master timer Start */ # define HRTIM_MCR_SYNCSRC_MCMP1 (1 << HRTIM_MCR_SYNCSRC_SHIFT) /* 01: Master timer Compare 1 Event */ @@ -382,15 +262,10 @@ #define HRTIM_MCR_TCCEN (1 << 19) /* Bit 19: Timer C counter enable */ #define HRTIM_MCR_TDCEN (1 << 20) /* Bit 20: Timer D counter enable */ #define HRTIM_MCR_TECEN (1 << 21) /* Bit 21: Timer E counter enable */ -#define HRTIM_MCR_DACSYNC_SHIFT 25 /* Bits 25-26: DAC Synchronization*/ -#define HRTIM_MCR_DACSYNC_MASK (3 << HRTIM_MCR_DACSYNC_SHIFT) -# define HRTIM_MCR_DACSYNC_00 (0 << HRTIM_MCR_DACSYNC_SHIFT) /* 00: */ -# define HRTIM_MCR_DACSYNC_01 (1 << HRTIM_MCR_DACSYNC_SHIFT) /* 01: */ -# define HRTIM_MCR_DACSYNC_10 (2 << HRTIM_MCR_DACSYNC_SHIFT) /* 10: */ -# define HRTIM_MCR_DACSYNC_11 (3 << HRTIM_MCR_DACSYNC_SHIFT) /* 11: */ -#define HRTIM_MCR_PREEN (1 << 27) /* Bit 27: Preload enable */ + /* Bits 22-24 reserved */ + /* Bits 25-27 common */ #define HRTIM_MCR_MREPU (1 << 29) /* Bit 29: Master Timer Repetition Update */ -#define HRTIM_MCR_BRSTDMA_SHIFT 30 /* Bits 30-31: Burs DMA Update*/ +#define HRTIM_MCR_BRSTDMA_SHIFT 30 /* Bits 30-31: Burs DMA Update*/ #define HRTIM_MCR_BRSTDMA_MASK (3 << HRTIM_MCR_BRSTDMA_SHIFT) # define HRTIM_MCR_BRSTDMA_00 (0 << HRTIM_MCR_BRSTDMA_SHIFT) /* 00 */ # define HRTIM_MCR_BRSTDMA_01 (1 << HRTIM_MCR_BRSTDMA_SHIFT) /* 01 */ @@ -468,24 +343,11 @@ #define HRTIM_MCMP4_SHIFT 0 /* Bits 0-15: Master Timer Compare 4 value */ #define HRTIM_MCMP4_MASK (0xffff << HRTIM_MCMP4_SHIFT) -/* Timer X Control Register */ - -#define HRTIM_TIMCR_CKPSC_SHIFT 0 /* Bits 0-2: HRTIM Timer X Clock Prescaler */ -#define HRTIM_TIMCR_CKPSC_MASK (7 << HRTIM_TIMCR_CKPSC_SHIFT) -# define HRTIM_TIMCR_CKPSC_000 (0 << HRTIM_TIMCR_CKPSC_SHIFT) /* 000: */ -# define HRTIM_TIMCR_CKPSC_001 (1 << HRTIM_TIMCR_CKPSC_SHIFT) /* 001: */ -# define HRTIM_TIMCR_CKPSC_010 (2 << HRTIM_TIMCR_CKPSC_SHIFT) /* 010: */ -# define HRTIM_TIMCR_CKPSC_011 (3 << HRTIM_TIMCR_CKPSC_SHIFT) /* 011: */ -# define HRTIM_TIMCR_CKPSC_100 (4 << HRTIM_TIMCR_CKPSC_SHIFT) /* 100: */ -# define HRTIM_TIMCR_CKPSC_101 (5 << HRTIM_TIMCR_CKPSC_SHIFT) /* 101: */ -# define HRTIM_TIMCR_CKPSC_110 (6 << HRTIM_TIMCR_CKPSC_SHIFT) /* 110: */ -# define HRTIM_TIMCR_CKPSC_111 (7 << HRTIM_TIMCR_CKPSC_SHIFT) /* 111: */ -#define HRTIM_TIMCR_CONT (1 << 3) /* Bit 3: Continuous mode */ -#define HRTIM_TIMCR_RETRIG (1 << 4) /* Bit 4: Re-triggerable mode */ -#define HRTIM_TIMCR_HALF (1 << 5) /* Bit 5: Half mode enable */ -#define HRTIM_TIMCR_PSHPLL (1 << 6) /* Bit 6:Push-Pull mode enable */ -#define HRTIM_TIMCR_SYNCRS (1 << 10) /* Bit 10: Synchronization Resets Timer X */ -#define HRTIM_TIMCR_SYNCSTR (1 << 11) /* Bit 11: Synchronization Starts Timer X */ +/* Timer A-E Control Register */ + + /* Bits 0-5 common */ +#define HRTIM_TIMCR_PSHPLL (1 << 6) /* Bit 6:Push-Pull mode enable */ + /* Bits 10-11 common */ #define HRTIM_TIMCR_DELCMP2_SHIFT 12 /* Bits 12-13: CMP2 auto-delayed mode */ #define HRTIM_TIMCR_DELCMP2_MASK (3 << HRTIM_TIMCR_DELCMP2_SHIFT) # define HRTIM_TIMCR_DELCMP2_00 (0 << HRTIM_TIMCR_DELCMP2_SHIFT) /* 00: */ @@ -506,13 +368,7 @@ #define HRTIM_TIMCR_TDU (1 << 22) /* Bit 22: Timer D Update */ #define HRTIM_TIMCR_TEU (1 << 23) /* Bit 23: Timer E Update */ #define HRTIM_TIMCR_MSTU (1 << 24) /* Bit 24: Master Timer Update */ -#define HRTIM_TIMCR_DACSYNC_SHIFT 25 /* Bits 25-26: DAC Synchronization */ -#define HRTIM_TIMCR_DACSYNC_MASK (3 << HRTIM_TIMCR_DACSYNC_SHIFT) -# define HRTIM_TIMCR_DACSYNC_00 (0 << HRTIM_TIMCR_DACSYNC_SHIFT) -# define HRTIM_TIMCR_DACSYNC_01 (1 << HRTIM_TIMCR_DACSYNC_SHIFT) -# define HRTIM_TIMCR_DACSYNC_10 (2 << HRTIM_TIMCR_DACSYNC_SHIFT) -# define HRTIM_TIMCR_DACSYNC_11 (3 << HRTIM_TIMCR_DACSYNC_SHIFT) -#define HRTIM_TIMCR_PREEN (1 << 27) /* Bit 27: Preload Enable */ + /* Bits 25-27 common */ #define HRTIM_TIMCR_UPDGAT_SHIFT 28 /* Bits 28-31: Update Gating */ #define HRTIM_TIMCR_UPDGAT_MASK (15 << HRTIM_TIMCR_UPDGAT_SHIFT) # define HRTIM_TIMCR_UPDGAT_0000 (0 << HRTIM_TIMCR_UPDGAT_SHIFT) /* 0000: */ @@ -838,7 +694,7 @@ # define HRTIM_TIMEEF1_EE2FLT_0 (0 << HRTIM_TIMEEF1_EE2FLT_SHIFT) /* 0000: No filtering */ # define HRTIM_TIMEEF1_EE2FLT_1 (1 << HRTIM_TIMEEF1_EE2FLT_SHIFT) /* 0001: Blanking from counter reset/roll-over to Compare 1 */ # define HRTIM_TIMEEF1_EE2FLT_2 (2 << HRTIM_TIMEEF1_EE2FLT_SHIFT) /* 0010: Blanking from counter reset/roll-over to Compare 2 */ -# define HRTIM_TIMEEF1_EE2FLT_2 (3 << HRTIM_TIMEEF1_EE2FLT_SHIFT) /* 0011: Blanking from counter reset/roll-over to Compare 3 */ +# define HRTIM_TIMEEF1_EE2FLT_3 (3 << HRTIM_TIMEEF1_EE2FLT_SHIFT) /* 0011: Blanking from counter reset/roll-over to Compare 3 */ # define HRTIM_TIMEEF1_EE2FLT_4 (4 << HRTIM_TIMEEF1_EE2FLT_SHIFT) /* 0100: Blanking from counter reset/roll-over to Compare 4 */ # define HRTIM_TIMEEF1_EE2FLT_5 (5 << HRTIM_TIMEEF1_EE2FLT_SHIFT) /* 0101: Blanking from TIMFLTR1 source */ # define HRTIM_TIMEEF1_EE2FLT_6 (6 << HRTIM_TIMEEF1_EE2FLT_SHIFT) /* 0110: Blanking from TIMFLTR2 source */ diff --git a/arch/arm/src/stm32/stm32.h b/arch/arm/src/stm32/stm32.h index 56225ee211..11c8f5b29e 100644 --- a/arch/arm/src/stm32/stm32.h +++ b/arch/arm/src/stm32/stm32.h @@ -67,6 +67,7 @@ #include "stm32_flash.h" #include "stm32_fsmc.h" #include "stm32_gpio.h" +#include "stm32_hrtim.h" #include "stm32_i2c.h" #include "stm32_ltdc.h" #include "stm32_opamp.h" diff --git a/arch/arm/src/stm32/stm32f33xxx_rcc.c b/arch/arm/src/stm32/stm32f33xxx_rcc.c index 82923a7ef8..6254294f5e 100644 --- a/arch/arm/src/stm32/stm32f33xxx_rcc.c +++ b/arch/arm/src/stm32/stm32f33xxx_rcc.c @@ -332,9 +332,7 @@ static inline void rcc_enableapb2(void) #ifdef CONFIG_STM32_HRTIM1 /* HRTIM1 Timer clock enable */ -#ifdef CONFIG_STM32_FORCEPOWER regval |= RCC_APB2ENR_HRTIM1EN; -#endif #endif putreg32(regval, STM32_RCC_APB2ENR); -- GitLab From fe813545e8bea6af2ccbde039747c407270eb9db Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 11 Jun 2017 11:00:29 -0600 Subject: [PATCH 959/990] STM32F33: Forgot to add new files that were a part of the last patch before committing. --- arch/arm/src/stm32/stm32_hrtim.c | 1519 ++++++++++++++++++++++++++++++ arch/arm/src/stm32/stm32_hrtim.h | 265 ++++++ 2 files changed, 1784 insertions(+) create mode 100644 arch/arm/src/stm32/stm32_hrtim.c create mode 100644 arch/arm/src/stm32/stm32_hrtim.h diff --git a/arch/arm/src/stm32/stm32_hrtim.c b/arch/arm/src/stm32/stm32_hrtim.c new file mode 100644 index 0000000000..c0cc3e48af --- /dev/null +++ b/arch/arm/src/stm32/stm32_hrtim.c @@ -0,0 +1,1519 @@ +/**************************************************************************** + * arch/arm/src/stm32/stm32_hrtim.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Mateusz Szafoni + * + * 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 "chip.h" +#include "stm32.h" +#include "stm32_gpio.h" +#include "stm32_hrtim.h" + +#if defined(CONFIG_STM32_HRTIM1) + +/* Only STM32F33XXX */ + +#if defined(CONFIG_STM32_STM32F33XX) + +#ifdef CONFIG_STM32_HRTIM_ADC +# error HRTIM ADC Triggering not supported yet +#endif + +#ifdef CONFIG_STM32_HRTIM_FAULT +# error HRTIM Faults not supported yet +#endif + +#ifdef CONFIG_STM32_HRTIM_EEV +# error HRTIM External Events not supported yet +#endif + +#ifdef CONFIG_STM32_HRTIM_BURST +# error HRTIM Burst mode not supported yet +#endif + +#ifdef CONFIG_STM32_HRTIM_IRQ +# error HRTIM Interrupts not supported yet +#endif + +#ifdef CONFIG_STM32_HRTIM_DMA +# error HRTIM DMA not supported yet +#endif + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* HRTIM default configuration **********************************************/ + +#ifndef HRTIM_TIMER_MASTER +# define HRTIM_MASTER_PRESCALER HRTIM_PRESCALER_2 +#endif + +/* HRTIM clock source configuration */ + +#ifdef CONFIG_STM32_HRTIM_CLK_FROM_PLL +# if STM32_SYSCLK_SW == RCC_CFGR_SW_PLL +# if (STM32_RCC_CFGR_PPRE2 != RCC_CFGR_PPRE2_HCLK) && \ + (STM32_RCC_CFGR_PPRE2 != RCC_CFGR_PPRE2_HCLKd2) +# error "APB2 prescaler factor can not be greater than 2" +# else +# define HRTIM_HAVE_CLK_FROM_PLL 1 +# define HRTIM_CLOCK 2*STM32_PLL_FREQUENCY +# endif +# else +# error "Clock system must be set to PLL" +# endif +#else +# define HRTIM_HAVE_CLK_FROM_APB2 1 +# if STM32_RCC_CFGR_PPRE2 == RCC_CFGR_PPRE2_HCLK +# define HRTIM_CLOCK STM32_PCLK2_FREQUENCY +# else +# define HRTIM_CLOCK 2*STM32_PCLK2_FREQUENCY +# endif +#endif + +#if defined(CONFIG_STM32_HRTIM_TIMA) || defined(CONFIG_STM32_HRTIM_TIMB) || \ + defined(CONFIG_STM32_HRTIM_TIMC) || defined(CONFIG_STM32_HRTIM_TIMD) || \ + defined(CONFIG_STM32_HRTIM_TIME) +# define HRTIM_HAVE_SLAVE 1 +#endif + +#if defined(CONFIG_STM32_HRTIM_TIMA_PWM) || defined(CONFIG_STM32_HRTIM_TIMB_PWM) || \ + defined(CONFIG_STM32_HRTIM_TIMC_PWM) || defined(CONFIG_STM32_HRTIM_TIMD_PWM) || \ + defined(CONFIG_STM32_HRTIM_TIME_PWM) +# define HRTIM_HAVE_PWM 1 +#endif + +#if defined(CONFIG_STM32_HRTIM_TIMA_CAP) || defined(CONFIG_STM32_HRTIM_TIMB_CAP) || \ + defined(CONFIG_STM32_HRTIM_TIMC_CAP) || defined(CONFIG_STM32_HRTIM_TIMD_CAP) || \ + defined(CONFIG_STM32_HRTIM_TIME_CAP) +# define HRTIM_HAVE_CAPTURE 1 +#endif + +#if defined(CONFIG_STM32_HRTIM_TIMA_DT) || defined(CONFIG_STM32_HRTIM_TIMB_DT) || \ + defined(CONFIG_STM32_HRTIM_TIMC_DT) || defined(CONFIG_STM32_HRTIM_TIMD_DT) || \ + defined(CONFIG_STM32_HRTIM_TIME_DT) +# define HRTIM_HAVE_DEADTIME 1 +#endif + +#if defined(CONFIG_STM32_HRTIM_TIMA_CHOP) || defined(CONFIG_STM32_HRTIM_TIMB_CHOP) || \ + defined(CONFIG_STM32_HRTIM_TIMC_CHOP) || defined(CONFIG_STM32_HRTIM_TIMD_CHOP) || \ + defined(CONFIG_STM32_HRTIM_TIME_CHOP) +# define HRTIM_HAVE_CHOPPER 1 +#endif + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +#ifdef HRTIM_HAVE_PWM + +/* HRTIM TimerX Single Output Set/Reset Configuration */ + +struct stm32_hrtim_timout_s +{ + uint32_t set; /* Set events*/ + uint32_t rst; /* Reset events*/ +}; + +/* HRTIM TimerX Output Chopper Configuration */ + +#ifdef HRTIM_HAVE_CHOPPER +struct stm32_hrtim_chopper_s +{ + uint32_t reserved; /* reserved for future use */ +}; +#endif + +/* HRTIM TimerX Output Deadtime Configuration*/ + +#ifdef HRTIM_HAVE_DEADTIME +struct stm32_hrtim_deadtime_s +{ + uint32_t reserved; /* reserved for future use */ +}; +#endif + +/* HRTIM Timer PWM structure */ + +struct stm32_hrtim_pwm_s +{ + struct stm32_hrtim_timout_s ch1; /* Channel 1 Set/Reset configuration*/ + struct stm32_hrtim_timout_s ch2; /* Channel 2 Set/Reset configuration */ + +#ifdef HRTIM_HAVE_CHOPPER + struct stm32_hrtim_chopper_s chp; +#endif +#ifdef HRTIM_HAVE_DEADTIME + struct stm32_hrtim_deadtime_s dt; +#endif +}; + +#endif + +#ifdef HRTIM_HAVE_CAPTURE +struct stm32_hrtim_capture_s +{ + uint32_t reserved; /* reserved for future use */ +} +#endif + +/* Common data structure for Master Timer and Slave Timers*/ + +struct stm32_hrtim_timcmn_s +{ + uint16_t cmp[4]; /* Compare registers */ + uint32_t base; /* The base adress of the timer */ + uint32_t frequency; /* Current frequency setting */ + uint32_t pclk; /* The frequency of the peripheral clock + * that drives the timer module */ +#ifdef CONFIG_STM32_HRTIM_DMA + uint32_t dmaburst; +#endif +}; + +/* Master Timer and Slave Timers structure */ + +struct stm32_hrtim_tim_s +{ + struct stm32_hrtim_timcmn_s tim; /* Common Timer data */ + FAR void *priv; /* Timer private data */ +}; + +/* Master Timer private data structure */ + +struct stm32_hrtim_master_priv_s +{ + uint32_t reserved; /* reserved for future use */ +}; + +/* Slave Timer (A-E) private data structure */ + +struct stm32_hrtim_slave_priv_s +{ + uint32_t reset; /* Timer reset events */ +#ifdef HRTIM_HAVE_PWM + struct stm32_hrtim_pwm_s pwm; /* PWM configuration */ +#endif +#ifdef HRTIM_HAVE_CAPTURE + struct stm32_hrtim_capture_s cap; /* Capture configuration */ +#endif +}; + +/* This structure describes the configuration of HRTIM device */ + +struct stm32_hrtim_s +{ + uint32_t base; /* Base adress of HRTIM block */ + FAR const struct hrtim_ops_s *ops; /* */ + struct stm32_hrtim_tim_s *master; /* Master Timer */ +#ifdef CONFIG_STM32_HRTIM_TIMA + struct stm32_hrtim_tim_s *tima; /* HRTIM Timer A */ +#endif +#ifdef CONFIG_STM32_HRTIM_TIMB + struct stm32_hrtim_tim_s *timb; /* HRTIM Timer B */ +#endif +#ifdef CONFIG_STM32_HRTIM_TIMC + struct stm32_hrtim_tim_s *timc; /* HRTIM Timer C */ +#endif +#ifdef CONFIG_STM32_HRTIM_TIMD + struct stm32_hrtim_tim_s *timd; /* HRTIM Timer D */ +#endif +#ifdef CONFIG_STM32_HRTIM_TIME + struct stm32_hrtim_tim_s *time; /* HRTIM Timer E */ +#endif +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* HRTIM Register access */ + +#ifdef HRTIM_HAVE_CLK_FROM_PLL +static void stm32_modifyreg32(unsigned int addr, uint32_t clrbits, + uint32_t setbits); +#endif +static uint32_t hrtim_getreg(FAR struct stm32_hrtim_s *priv, int offset); +static void hrtim_putreg(FAR struct stm32_hrtim_s *priv, int offset, + uint32_t value); +static void hrtim_modifyreg(FAR struct stm32_hrtim_s *priv, int offset, + uint32_t clrbits, uint32_t setbits); +static void hrtim_tim_putreg(FAR struct stm32_hrtim_s *priv, uint8_t index, + int offset, uint32_t value); +static void hrtim_tim_modifyreg(FAR struct stm32_hrtim_s *priv, uint8_t index, + int offset, uint32_t clrbits, uint32_t setbits); + +/* HRTIM helper */ + +static uint32_t hrtim_tim_getreg(FAR struct stm32_hrtim_s *priv, uint8_t index, + int offset); +static FAR struct stm32_hrtim_tim_s *hrtim_tim_get(FAR struct stm32_hrtim_s *priv, + uint8_t index); + +/* HRTIM Driver Methods */ + +static int hrtim_ioctl(FAR struct hrtim_dev_s *dev, int cmd, unsigned long arg); + +/* Configuration */ + +static int hrtim_dll_cal(FAR struct stm32_hrtim_s *priv); +static int hrtim_tim_clock_config(FAR struct stm32_hrtim_s *priv, uint8_t index, + uint8_t pre); +static int hrtim_tim_clocks_config(FAR struct stm32_hrtim_s *priv); +#if defined(HRTIM_HAVE_CAPTURE) || defined(HRTIM_HAVE_PWM) || defined(HRTIM_HAVE_SYNC) +static int hrtim_gpios_config(FAR struct stm32_hrtim_s *priv); +#endif +static void hrtim_preload_config(FAR struct stm32_hrtim_s *priv); +#if defined(HRTIM_HAVE_CAPTURE) +static int hrtim_inputs_config(FAR struct stm32_hrtim_s *priv); +#endif +#if defined(HRTIM_HAVE_SYNC) +static int hrtim_synch_config(FAR struct stm32_hrtim_s *priv); +#endif +#if defined(HRTIM_HAVE_PWM) +static int hrtim_outputs_config(FAR struct stm32_hrtim_s *priv); +#endif +#ifdef HRTIM_HAVE_ADC +static int hrtim_adc_config(FAR struct stm32_hrtim_s *priv); +#endif +#ifdef HRTIM_HAVE_FAULTS +static int hrtim_faults_config(FAR struct stm32_hrtim_s *priv); +#endif +#ifdef HRTIM_HAVE_EEV +static int hrtim_eev_config(FAR struct stm32_hrtim_s *priv); +#endif +#ifdef HRTIM_HAVE_INTERRUPTS +static int hrtim_irq_config(FAR struct stm32_hrtim_s *priv); +#endif + +/* Initialization */ + +static int stm32_hrtimconfig(FAR struct stm32_hrtim_s *priv); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* HRTIM interface operations */ + +static const struct hrtim_ops_s g_hrtimops = +{ + .ho_ioctl = hrtim_ioctl, +}; + +/* Master Timer data */ + +static struct stm32_hrtim_tim_s g_master = +{ + .tim = + { + .base = STM32_HRTIM1_MASTER_BASE, + .pclk = HRTIM_CLOCK/HRTIM_MASTER_PRESCALER + }, + .priv = NULL, +}; + +/* NOTE: only TIMER A data defined at this time */ + +#ifdef CONFIG_STM32_HRTIM_TIMA + +/* Timer A private data */ + +static struct stm32_hrtim_slave_priv_s g_tima_priv = +{ +#ifdef CONFIG_STM32_HRTIM_TIMA_PWM + .pwm = + { + .ch1 = + { + .set = HRTIM_TIMA_CH1_SET, + .rst = HRTIM_TIMA_CH1_RST + }, + .ch2 = + { + .set = HRTIM_TIMA_CH2_SET, + .rst = HRTIM_TIMA_CH2_RST + }, +#ifdef CONFIG_STM32_HRTIM_TIMA_CHOP + .chp = + { + .reserved = 0 + }, +#endif +#ifdef CONFIG_STM32_HRTIM_TIMA_DT + .dt = + { + .reserved = 0 + } +#endif + }, +#endif +#ifdef CONFIG_STM32_HRTIM_TIMA_CAP + .cap = + { + .reserved = 0 + } +#endif +}; + +/* Timer A data */ + +static struct stm32_hrtim_tim_s g_tima = +{ + .tim = + { + .base = STM32_HRTIM1_TIMERA_BASE, + .pclk = HRTIM_CLOCK/HRTIM_TIMA_PRESCALER + }, + .priv = &g_tima_priv +}; + +#endif + +/* HRTIM1 private data */ + +static struct stm32_hrtim_s g_hrtim1priv = +{ + .master = &g_master, + .base = STM32_HRTIM1_BASE, +#ifdef CONFIG_STM32_HRTIM_TIMA + .tima = &g_tima, +#endif +#ifdef CONFIG_STM32_HRTIM_TIMB + .timb = &g_timb, +#endif +#ifdef CONFIG_STM32_HRTIM_TIMC + .timc = &g_timc, +#endif +#ifdef CONFIG_STM32_HRTIM_TIMD + .timd = &g_timd, +#endif +#ifdef CONFIG_STM32_HRTIM_TIME + .time = &g_time, +#endif +}; + +struct hrtim_dev_s g_hrtim1dev = +{ + .hd_ops = &g_hrtimops, + .hd_priv = &g_hrtim1priv, +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_modifyreg32 + * + * Description: + * Modify the value of a 32-bit register (not atomic). + * + * Input Parameters: + * addr - The address of the register + * clrbits - The bits to clear + * setbits - The bits to set + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void stm32_modifyreg32(unsigned int addr, uint32_t clrbits, + uint32_t setbits) +{ + putreg32((getreg32(addr) & ~clrbits) | setbits, addr); +} + + +/**************************************************************************** + * Name: hrtim_getreg + * + * Description: + * Read the value of an HRTIM register. + * + * Input Parameters: + * priv - A reference to the HRTIM block + * offset - The offset to the register to read + * + * Returned Value: + * The current contents of the specified register + * + ****************************************************************************/ + +static uint32_t hrtim_getreg(FAR struct stm32_hrtim_s *priv, int offset) +{ + return getreg32(priv->base + offset); +} + +/**************************************************************************** + * Name: hrtim_putreg + * + * Description: + * Write a value to an HRTIM register. + * + * Input Parameters: + * priv - A reference to the HRTIM block + * offset - The offset to the register to write to + * value - The value to write to the register + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void hrtim_putreg(FAR struct stm32_hrtim_s *priv, int offset, + uint32_t value) +{ + putreg32(value, priv->base + offset); +} + +/**************************************************************************** + * Name: hrtim__modifyreg + * + * Description: + * Modify the value of an HRTIM register (not atomic). + * + * Input Parameters: + * priv - A reference to the HRTIM block + * offset - The offset to the register to modify + * clrbits - The bits to clear + * setbits - The bits to set + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void hrtim_modifyreg(FAR struct stm32_hrtim_s *priv, int offset, + uint32_t clrbits, uint32_t setbits) +{ + hrtim_putreg(priv, offset, (hrtim_getreg(priv, offset) & ~clrbits) | setbits); +} + + +/**************************************************************************** + * Name: hrtim_tim_get + * + * Description: + * Get Timer data structure for given HRTIM Timer index + * + * Input Parameters: + * priv - A reference to the HRTIM block + * index - An HRTIM Timer index to get + * + * Returned Value: + * Base adress offset for given timer index + * + ****************************************************************************/ + +static FAR struct stm32_hrtim_tim_s *hrtim_tim_get(FAR struct stm32_hrtim_s *priv, uint8_t index) +{ + FAR struct stm32_hrtim_tim_s *tim; + + switch (index) + { + case HRTIM_TIMER_MASTER: + { + tim = priv->master; + break; + } + +#ifdef CONFIG_STM32_HRTIM_TIMA + case HRTIM_TIMER_TIMA: + { + tim = priv->tima; + break; + } +#endif + +#ifdef CONFIG_STM32_HRTIM_TIMB + case HRTIM_TIMER_TIMB: + { + tim = &priv->timb; + break; + } +#endif + +#ifdef CONFIG_STM32_HRTIM_TIMC + case HRTIM_TIMER_TIMC: + { + tim = &priv->timc; + break; + } +#endif + +#ifdef CONFIG_STM32_HRTIM_TIMD + case HRTIM_TIMER_TIMD: + { + tim = &priv->timd; + break; + } +#endif + +#ifdef CONFIG_STM32_HRTIM_TIME + case HRTIM_TIMER_TIME: + { + tim = &priv->time; + break; + } +#endif + + default: + { + tmrerr("ERROR: No such timerx index: %d\n", index); + tim = NULL; + } + } + + return tim; +} + +/**************************************************************************** + * Name: hrtim_base_get + * + * Description: + * Get base adress offset for given HRTIM Timer index + * + * Input Parameters: + * priv - A reference to the HRTIM block + * index - An HRTIM Timer index to get + * + * Returned Value: + * Base adress offset for given timer index + * + ****************************************************************************/ + +static uint32_t hrtim_base_get(FAR struct stm32_hrtim_s* priv, uint8_t index) +{ + FAR struct stm32_hrtim_tim_s* tim; + uint32_t base; + + tim = hrtim_tim_get(priv,index); + if (tim == NULL) + { + base = 0; + goto errout; + } + + base = tim->tim.base; + +errout: + return base; +} + +/**************************************************************************** + * Name: hrtim_tim_getreg + * + * Description: + * Read the value of an HRTIM Timer register. + * + * Input Parameters: + * priv - A reference to the HRTIM block + * tim - An HRTIM timer index + * offset - The offset to the register to read + * + * Returned Value: + * The current contents of the specified register + * + ****************************************************************************/ + +static uint32_t hrtim_tim_getreg(FAR struct stm32_hrtim_s *priv, uint8_t index, + int offset) +{ + uint32_t base; + + base = hrtim_base_get(priv, index); + if (base < 0) + { + return 0; + } + + return getreg32(base + offset); +} + +/**************************************************************************** + * Name: hrtim_tim_putreg + * + * Description: + * Write a value to an HRTIM Timer register. + * + * Input Parameters: + * priv - A reference to the HRTIM block + * index - An HRTIM timer index + * offset - The offset to the register to write to + * value - The value to write to the register + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void hrtim_tim_putreg(FAR struct stm32_hrtim_s *priv, uint8_t index, + int offset, uint32_t value) +{ + uint32_t base; + + base = hrtim_base_get(priv, index); + if (base > 0) + { + putreg32(value, base + offset); + } +} + +/**************************************************************************** + * Name: hrtim_tim_modifyreg + * + * Description: + * Modify the value of an HRTIM Timer register (not atomic). + * + * Input Parameters: + * priv - A reference to the HRTIM block + * index - An HRTIM timer index + * offset - The offset to the register to modify + * clrbits - The bits to clear + * setbits - The bits to set + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void hrtim_tim_modifyreg(FAR struct stm32_hrtim_s *priv, uint8_t index, + int offset, uint32_t clrbits, uint32_t setbits) +{ + hrtim_tim_putreg(priv, index, offset, + (hrtim_tim_getreg(priv, index, offset) & ~clrbits) | setbits); +} + +/**************************************************************************** + * Name: hrtim_ioctl + * + * Description: + * All ioctl calls will be routed through this method. + * + * Input Parameters: + * dev - pointer to device structure used by the driver + * cmd - command + * arg - arguments passed with command + * + * Returned Value: + * Zero on success; a negated errno value on failure. + * + ****************************************************************************/ + +static int hrtim_ioctl(FAR struct hrtim_dev_s *dev, int cmd, unsigned long arg) +{ +#warning "hrtim_ioctl: missing logic" + return -ENOTTY; +} + +/**************************************************************************** + * Name: stm32_dll_cal + * + * Description: + * Calibrate HRTIM DLL + * + * Input Parameters: + * priv - A reference to the HRTIM structure + * + * Returned Value: + * 0 on success, a negated errno value on failure + * + ****************************************************************************/ + +static int hrtim_dll_cal(FAR struct stm32_hrtim_s *priv) +{ + uint32_t regval = 0; + +#ifdef CONFIG_STM32_HRTIM_PERIODIC_CAL + + /* Configure calibration rate */ + + regval |= HRTIM_DLLCR_CAL_RATE; + + /* Enable Periodic calibration */ + + regval |= HRTIM_DLLCR_CALEN; + +#endif + + /* DLL Calibration Start */ + + regval |= HRTIM_DLLCR_CAL; + + hrtim_putreg(priv, STM32_HRTIM_CMN_DLLCR, regval); + + /* Wait for HRTIM ready flag */ + + while(!(hrtim_getreg(priv, STM32_HRTIM_CMN_ISR) & HRTIM_ISR_DLLRDY)); + + return OK; +} + +/**************************************************************************** + * Name: stm32_tim_clock_config + * + * Description: + * Configure HRTIM Timer clock + * + * Input Parameters: + * priv - A reference to the HRTIM structure + * index - An HRTIM timer index + * + * Returned Value: + * 0 on success, a negated errno value on failure + * + ****************************************************************************/ + +static int hrtim_tim_clock_config(FAR struct stm32_hrtim_s *priv, uint8_t index, uint8_t pre) +{ + int ret = OK; + uint32_t regval = 0; + + regval = hrtim_tim_getreg(priv, index, STM32_HRTIM_TIM_CR_OFFSET); + + switch (pre) + { + case HRTIM_PRESCALER_1: + { + regval |= HRTIM_CMNCR_CKPSC_NODIV; + break; + } + case HRTIM_PRESCALER_2: + { + regval |= HRTIM_CMNCR_CKPSC_d2; + break; + } + case HRTIM_PRESCALER_4: + { + regval |= HRTIM_CMNCR_CKPSC_d4; + break; + } + case HRTIM_PRESCALER_8: + { + regval |= HRTIM_CMNCR_CKPSC_d8; + break; + } + case HRTIM_PRESCALER_16: + { + regval |= HRTIM_CMNCR_CKPSC_d16; + break; + } + case HRTIM_PRESCALER_32: + { + regval |= HRTIM_CMNCR_CKPSC_d32; + break; + } + case HRTIM_PRESCALER_64: + { + regval |= HRTIM_CMNCR_CKPSC_d64; + break; + } + case HRTIM_PRESCALER_128: + { + regval |= HRTIM_CMNCR_CKPSC_d128; + break; + } + default: + { + tmrerr("ERROR: invalid prescaler value %d for timer %d\n", index, + pre); + ret = -EINVAL; + goto errout; + } + } + +errout: + return ret; +} + + +/**************************************************************************** + * Name: stm32_tim_clocks_config + * + * Description: + * Configure HRTIM Timers Clocks + * + * Input Parameters: + * priv - A reference to the HRTIM structure + * + * Returned Value: + * 0 on success, a negated errno value on failure + * + ****************************************************************************/ + +static int hrtim_tim_clocks_config(FAR struct stm32_hrtim_s *priv) +{ + int ret = OK; + + /* Configure Master Timer clock */ + + ret = hrtim_tim_clock_config(priv, HRTIM_TIMER_MASTER, HRTIM_MASTER_PRESCALER); + if (ret < 0) + { + goto errout; + } + + /* Configure Timer A clock */ + +#ifdef CONFIG_STM32_HRTIM_TIMA + ret = hrtim_tim_clock_config(priv, HRTIM_TIMER_TIMA, HRTIM_TIMA_PRESCALER); + if (ret < 0) + { + goto errout; + } +#endif + + /* Configure Timer B clock */ + +#ifdef CONFIG_STM32_HRTIM_TIMB + ret = hrtim_tim_clock_config(priv, HRTIM_TIMER_TIMB, HRTIM_TIMB_PRESCALER); + if (ret < 0) + { + goto errout; + } +#endif + + /* Configure Timer C clock */ + +#ifdef CONFIG_STM32_HRTIM_TIMC + ret = hrtim_tim_clock_config(priv, HRTIM_TIMER_TIMC, HRTIM_TIMC_PRESCALER); + if (ret < 0) + { + goto errout; + } +#endif + + /* Configure Timer D clock */ + +#ifdef CONFIG_STM32_HRTIM_TIMD + ret = hrtim_tim_clock_config(priv, HRTIM_TIMER_TIMD, HRTIM_TIMD_PRESCALER); + if (ret < 0) + { + goto errout; + } +#endif + + /* Configure Timer E clock */ + +#ifdef CONFIG_STM32_HRTIM_TIME + ret = hrtim_tim_clock_config(priv, HRTIM_TIMER_TIME, HRTIM_TIME_PRESCALER); + if (ret < 0) + { + goto errout; + } +#endif + +errout: + return ret; +} + +/**************************************************************************** + * Name: stm32_gpios_config + * + * Description: + * Configure HRTIM GPIO + * + * Input Parameters: + * priv - A reference to the HRTIM structure + * + * Returned Value: + * 0 on success, a negated errno value on failure + * + ****************************************************************************/ + +#if defined(HRTIM_HAVE_CAPTURE) || defined(HRTIM_HAVE_PWM) || defined(HRTIM_HAVE_SYNC) +static int hrtim_gpios_config(FAR struct stm32_hrtim_s *priv) +{ +#warning "hrtim_gpios_config: missing logic" + return OK; +} +#endif + +/**************************************************************************** + * Name: stm32_inputs_config + * + * Description: + * Configure HRTIM Inputs + * + * Input Parameters: + * priv - A reference to the HRTIM structure + * + * Returned Value: + * 0 on success, a negated errno value on failure + * + ****************************************************************************/ + +#if defined(HRTIM_HAVE_CAPTURE) +static int hrtim_inputs_config(FAR struct stm32_hrtim_s *priv) +{ +#warning "hrtim_inputs_config: missing logic" + + /* source */ + + /* polarity */ + + /* edge-sensitivity */ + + return OK; +} +#endif + + +/**************************************************************************** + * Name: stm32_synch_config + * + * Description: + * Configure HRTIM Synchronization Input/Output + * + * Input Parameters: + * priv - A reference to the HRTIM structure + * + * Returned Value: + * 0 on success, a negated errno value on failure + * + ****************************************************************************/ + +#if defined(HRTIM_HAVE_SYNC) +static int hrtim_synch_config(FAR struct stm32_hrtim_s *priv) +{ +#warning "hrtim_synch_config: missing logic" + return OK; +} +#endif + +/**************************************************************************** + * Name: stm32_tim_outputs_config + * + * Description: + * Configure HRTIM Slave Timer Outputs (CH1 and CH2) + * + * Input Parameters: + * priv - A reference to the HRTIM structure + * + * Returned Value: + * 0 on success, a negated errno value on failure + * + ****************************************************************************/ + +#if defined(HRTIM_HAVE_PWM) +static int hrtim_tim_outputs_config(FAR struct stm32_hrtim_s *priv, uint8_t index) +{ + FAR struct stm32_hrtim_tim_s* tim; + FAR struct stm32_hrtim_slave_priv_s* slave; + + int ret = OK; + uint32_t regval = 0; + + /* Master Timer has no outputs */ + + if (index == HRTIM_TIMER_MASTER) + { + ret = -EINVAL; + goto errout; + } + + /* Get Timer data strucutre */ + + tim = hrtim_tim_get(priv, index); + if (tim == NULL) + { + ret = -EINVAL; + goto errout; + } + + slave = (struct stm32_hrtim_slave_priv_s*)tim->priv; + + /* Configure CH1 SET events */ + + regval = slave->pwm.ch1.set; + hrtim_tim_putreg(priv, index, STM32_HRTIM_TIM_SET1R_OFFSET, regval); + + /* Configure CH1 RESET events */ + + regval = slave->pwm.ch1.rst; + hrtim_tim_putreg(priv, index, STM32_HRTIM_TIM_RST1R_OFFSET, regval); + + /* Configure CH2 SET events */ + + regval = slave->pwm.ch2.set; + hrtim_tim_putreg(priv, index, STM32_HRTIM_TIM_SET2R_OFFSET, regval); + + /* Configure CH2 RESET events */ + + regval = slave->pwm.ch2.rst; + hrtim_tim_putreg(priv, index, STM32_HRTIM_TIM_RST2R_OFFSET, regval); + +errout: + return ret; +} +#endif + +/**************************************************************************** + * Name: stm32_outputs_config + * + * Description: + * Configure HRTIM Outputs + * + * Input Parameters: + * priv - A reference to the HRTIM structure + * + * Returned Value: + * 0 on success, a negated errno value on failure + * + ****************************************************************************/ + +#if defined(HRTIM_HAVE_PWM) +static int hrtim_outputs_config(FAR struct stm32_hrtim_s *priv) +{ + int ret = OK; + + /* Configure HRTIM TIMER A Outputs */ + +#ifdef CONFIG_STM32_HRTIM_TIMA_PWM + ret = hrtim_tim_outputs_config(priv, HRTIM_TIMER_TIMA); + if (ret < 0) + { + goto errout; + } +#endif + + /* Configure HRTIM TIMER B Outputs */ + +#ifdef CONFIG_STM32_HRTIM_TIMB_PWM + ret = hrtim_tim_outputs_config(priv, HRTIM_TIMER_TIMB); + if (ret < 0) + { + goto errout; + } +#endif + + /* Configure HRTIM TIMER C Outputs */ + +#ifdef CONFIG_STM32_HRTIM_TIMC_PWM + ret = hrtim_tim_outputs_config(priv, HRTIM_TIMER_TIMC); + if (ret < 0) + { + goto errout; + } +#endif + + /* Configure HRTIM TIMER D Outputs */ + +#ifdef CONFIG_STM32_HRTIM_TIMD_PWM + ret = hrtim_tim_outputs_config(priv, HRTIM_TIMER_TIMD); + if (ret < 0) + { + goto errout; + } +#endif + + /* Configure HRTIM TIMER E Outputs */ + +#ifdef CONFIG_STM32_HRTIM_TIME_PWM + ret = hrtim_tim_outputs_config(priv, HRTIM_TIMER_TIME); + if (ret < 0) + { + goto errout; + } +#endif + +errout: + return ret; +} +#endif + +/**************************************************************************** + * Name: stm32_adc_config + * + * Description: + * Configure HRTIM ADC triggers + * + * Input Parameters: + * priv - A reference to the HRTIM structure + * + * Returned Value: + * 0 on success, a negated errno value on failure + * + ****************************************************************************/ + +#ifdef HRTIM_HAVE_ADC +static int hrtim_adc_config(FAR struct stm32_hrtim_s *priv) +{ +#warning "hrtim_adc_config: missing logic" + return OK; +} +#endif + +/**************************************************************************** + * Name: stm32_faults_config + * + * Description: + * Configure HRTIM Faults + * + * Input Parameters: + * priv - A reference to the HRTIM structure + * + * Returned Value: + * 0 on success, a negated errno value on failure + * + ****************************************************************************/ + +#ifdef HRTIM_HAVE_FAULTS +static int hrtim_faults_config(FAR struct stm32_hrtim_s *priv) +{ +#warning "hrtim_faults_config: missing logic" + return OK; +} +#endif + +/**************************************************************************** + * Name: stm32_eev_config + * + * Description: + * Configure HRTIM External Events + * + * Input Parameters: + * priv - A reference to the HRTIM structure + * + * Returned Value: + * 0 on success, a negated errno value on failure + * + ****************************************************************************/ + +#ifdef HRTIM_HAVE_EEV +static int hrtim_eev_config(FAR struct stm32_hrtim_s *priv) +{ +#warning "hrtim_eev_confi: missing logic" + return OK; +} +#endif + +/**************************************************************************** + * Name: stm32_irq_config + * + * Description: + * Configure HRTIM interrupts + * + * Input Parameters: + * priv - A reference to the HRTIM structure + * + * Returned Value: + * 0 on success, a negated errno value on failure + * + ****************************************************************************/ + +#ifdef HRTIM_HAVE_INTERRUPTS +static int hrtim_irq_config(FAR struct stm32_hrtim_s *priv) +{ +#warning "hrtim_irq_config: missing logic" + return OK; +} +#endif + +/**************************************************************************** + * Name: stm32_preload_config + * + * Description: + * Configure HRTIM preload registers + * + * Input Parameters: + * priv - A reference to the HRTIM structure + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void hrtim_preload_config(FAR struct stm32_hrtim_s *priv) +{ + +#ifndef CONFIG_STM32_HRTIM_MASTER_PRELOAD_DIS + hrtim_tim_modifyreg(priv, HRTIM_TIMER_MASTER, STM32_HRTIM_TIM_CR_OFFSET, + 0, HRTIM_CMNCR_PREEN); +#endif + +#if defined(CONFIG_ST32_HRTIM_TIMA) && defined(CONFIG_STM32_HRTIM_TIMA_PRELOAD_DIS) + hrtim_tim_modifyreg(priv, HRTIM_TIMER_TIMA, STM32_HRTIM_TIM_CR_OFFSET, + 0, HRTIM_CMNCR_PREEN); +#endif + +#if defined(CONFIG_ST32_HRTIM_TIMB) && defined(CONFIG_STM32_HRTIM_TIMB_PRELOAD_DIS) + hrtim_tim_modifyreg(priv, HRTIM_TIMER_TIMB, STM32_HRTIM_TIM_CR_OFFSET, + 0, HRTIM_CMNCR_PREEN); +#endif + +#if defined(CONFIG_ST32_HRTIM_TIMC) && defined(CONFIG_STM32_HRTIM_TIMC_PRELOAD_DIS) + hrtim_tim_modifyreg(priv, HRTIM_TIMER_TIMC, STM32_HRTIM_TIM_CR_OFFSET, + 0, HRTIM_CMNCR_PREEN); +#endif + +#if defined(CONFIG_ST32_HRTIM_TIMD) && defined(CONFIG_STM32_HRTIM_TIMD_PRELOAD_DIS) + hrtim_tim_modifyreg(priv, HRTIM_TIMER_TIMD, STM32_HRTIM_TIM_CR_OFFSET, + 0, HRTIM_CMNCR_PREEN); +#endif + +#if defined(CONFIG_ST32_HRTIM_TIME) && defined(CONFIG_STM32_HRTIM_TIME_PRELOAD_DIS) + hrtim_tim_modifyreg(priv, HRTIM_TIMER_TIME, STM32_HRTIM_TIM_CR_OFFSET, + 0, HRTIM_CMNCR_PREEN); +#endif + +} + +/**************************************************************************** + * Name: stm32_hrtimconfig + * + * Description: + * Configure HRTIM + * + * Input Parameters: + * priv - A reference to the HRTIM structure + * + * Returned Value: + * 0 on success, a negated errno value on failure + * + ****************************************************************************/ + +static int stm32_hrtimconfig(FAR struct stm32_hrtim_s *priv) +{ + int ret; + uint32_t regval = 0; + + /* Configure PLL VCO output as HRTIM clock source */ + +#ifdef HRTIM_HAVE_CLK_FROM_PLL + stm32_modifyreg32(STM32_RCC_CFGR3, 0, RCC_CFGR3_HRTIM1SW); +#endif + + /* HRTIM DLL calibration */ + + ret = hrtim_dll_cal(priv); + if (ret != OK) + { + tmrerr("ERROR: HRTIM DLL calibration failed!\n"); + goto errout; + } + + /* Configure Timers Clocks */ + + ret = hrtim_tim_clocks_config(priv); + if (ret != OK) + { + tmrerr("ERROR: HRTIM timers clock configuration failed!\n"); + goto errout; + } + + /* Configure HRTIM GPIOs */ + +#if defined(HRTIM_HAVE_CAPTURE) || defined(HRTIM_HAVE_PWM) || defined(HRTIM_HAVE_SYNC) + ret = hrtim_gpios_config(priv); + if (ret != OK) + { + tmrerr("ERROR: HRTIM GPIOs configuration failed!\n"); + goto errout; + } +#endif + + /* Configure HRTIM inputs */ + +#if defined(HRTIM_HAVE_CAPTURE) + ret = hrtim_inputs_config(priv); + if (ret != OK) + { + tmrerr("ERROR: HRTIM inputs configuration failed!\n"); + goto errout; + } +#endif + + /* Configure Synchronisation IOs */ + +#if defined(HRTIM_HAVE_SYNC) + ret = hrtim_synch_config(priv); + if (ret != OK) + { + tmrerr("ERROR: HRTIM synchronisation configuration failed!\n"); + goto errout; + } +#endif + + /* Configure HRTIM outputs GPIOs */ + +#if defined(HRTIM_HAVE_PWM) + ret = hrtim_outputs_config(priv); + if (ret != OK) + { + tmrerr("ERROR: HRTIM outputs configuration failed!\n"); + goto errout; + } +#endif + + /* Configure ADC triggers */ + +#ifdef HRTIM_HAVE_ADC + ret = hrtim_adc_config(priv); + if (ret != OK) + { + tmrerr("ERROR: HRTIM ADC configuration failed!\n"); + goto errout; + } +#endif + + /* Configure Faults */ + +#ifdef HRTIM_HAVE_FAULTS + ret = hrtim_faults_config(priv); + if (ret != OK) + { + tmrerr("ERROR: HRTIM faults configuration failed!\n"); + goto errout; + } +#endif + + /* Configure Events */ + +#ifdef HRTIM_HAVE_EEV + ret = hrtim_eev_config(priv); + if (ret != OK) + { + tmrerr("ERROR: HRTIM EEV configuration failed!\n"); + goto errout; + } +#endif + + /* Configure interrupts */ + +#ifdef HRTIM_HAVE_INTERRUPTS + ret = hrtim_irq_config(priv); + if (ret != OK) + { + tmrerr("ERROR: HRTIM IRQ configuration failed!\n"); + goto errout; + } +#endif + + /* Enable registers preload */ + + hrtim_preload_config(priv); + + /* Enable Master Timer */ + + regval |= HRTIM_MCR_MCEN; + + /* Enable Slave Timers */ + +#ifdef CONFIG_STM32_HRTIM_TIMA + regval |= HRTIM_MCR_TACEN; +#endif + +#ifdef CONFIG_STM32_HRTIM_TIMB + regval |= HRTIM_MCR_TBCEN; +#endif + +#ifdef CONFIG_STM32_HRTIM_TIMC + regval |= HRTIM_MCR_TCCEN; +#endif + +#ifdef CONFIG_STM32_HRTIM_TIMD + regval |= HRTIM_MCR_TDCEN; +#endif + +#ifdef CONFIG_STM32_HRTIM_TIME + regval |= HRTIM_MCR_TECEN; +#endif + + /* Write enable bits at once */ + + hrtim_tim_modifyreg(priv, HRTIM_TIMER_MASTER, STM32_HRTIM_TIM_CR_OFFSET, 0, regval); + +errout: + return ret; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_hrtiminitialize + * + * Description: + * Initialize the HRTIM. + * + * Returned Value: + * Valid HRTIM device structure reference on succcess; a NULL on failure. + * + * Assumptions: + * 1. Clock to the HRTIM block has enabled, + * 2. Board-specific logic has already configured + * + ****************************************************************************/ + +FAR struct hrtim_dev_s* stm32_hrtiminitialize(void) +{ + FAR struct hrtim_dev_s *dev; + FAR struct stm32_hrtim_s *hrtim; + int ret; + + dev = &g_hrtim1dev; + + hrtim = dev->hd_priv; + + ret = stm32_hrtimconfig(hrtim); + if (ret < 0) + { + tmrerr("ERROR: Failed to initialize HRTIM1: %d\n", ret); + errno = -ret; + return NULL; + } + + return dev; +} + +#endif /* CONFIG_STM32_STM32F33XX */ + +#endif /* CONFIG_STM32_HRTIM1 */ diff --git a/arch/arm/src/stm32/stm32_hrtim.h b/arch/arm/src/stm32/stm32_hrtim.h new file mode 100644 index 0000000000..1fa9a4971a --- /dev/null +++ b/arch/arm/src/stm32/stm32_hrtim.h @@ -0,0 +1,265 @@ +/************************************************************************************ + * arch/arm/src/stm32/stm32_hrtim.h + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Mateusz Szafoni + * + * 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 __ARCH_ARM_SRC_STM32_STM32_HRTIM_H +#define __ARCH_ARM_SRC_STM32_STM32_HRTIM_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include "chip.h" + +#ifdef CONFIG_STM32_HRTIM1 + +#if defined(CONFIG_STM32_STM32F33XX) +# include "chip/stm32f33xxx_hrtim.h" +#else +# error +#endif + +/************************************************************************************ + * Pre-processor definitions + ************************************************************************************/ + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/* HRTIM Timer X index */ + +enum stm32_hrtim_tim_e +{ + HRTIM_TIMER_MASTER, +#ifdef CONFIG_STM32_HRTIM_TIMA + HRTIM_TIMER_TIMA, +#endif +#ifdef CONFIG_STM32_HRTIM_TIMB + HRTIM_TIMER_TIMB, +#endif +#ifdef CONFIG_STM32_HRTIM_TIMC + HRTIM_TIMER_TIMC, +#endif +#ifdef CONFIG_STM32_HRTIM_TIMD + HRTIM_TIMER_TIMD, +#endif +#ifdef CONFIG_STM32_HRTIM_TIME + HRTIM_TIMER_TIME, +#endif +}; + +/* Source which can force the Tx1/Tx2 output to its inactive state */ + +enum stm32_hrtim_out_rst_e +{ + HRTIM_OUT_RST_UPDATE = (1 << 0), + HRTIM_OUT_RST_EXTEVNT10 = (1 << 1), + HRTIM_OUT_RST_EXTEVNT9 = (1 << 2), + HRTIM_OUT_RST_EXTEVNT8 = (1 << 3), + HRTIM_OUT_RST_EXTEVNT7 = (1 << 4), + HRTIM_OUT_RST_EXTEVNT6 = (1 << 5), + HRTIM_OUT_RST_EXTEVNT5 = (1 << 6), + HRTIM_OUT_RST_EXTEVNT4 = (1 << 7), + HRTIM_OUT_RST_EXTEVNT3 = (1 << 8), + HRTIM_OUT_RST_EXTEVNT2 = (1 << 9), + HRTIM_OUT_RST_EXTEVNT1 = (1 << 10), + HRTIM_OUT_RST_TIMEVNT9 = (1 << 11), + HRTIM_OUT_RST_TIMEVNT8 = (1 << 12), + HRTIM_OUT_RST_TIMEVNT7 = (1 << 13), + HRTIM_OUT_RST_TIMEVNT6 = (1 << 14), + HRTIM_OUT_RST_TIMEVNT5 = (1 << 15), + HRTIM_OUT_RST_TIMEVNT4 = (1 << 16), + HRTIM_OUT_RST_TIMEVNT3 = (1 << 17), + HRTIM_OUT_RST_TIMEVNT2 = (1 << 18), + HRTIM_OUT_RST_TIMEVNT1 = (1 << 19), + HRTIM_OUT_RST_MSTCMP4 = (1 << 20), + HRTIM_OUT_RST_MSTCMP3 = (1 << 21), + HRTIM_OUT_RST_MSTCMP2 = (1 << 22), + HRTIM_OUT_RST_MSTCMP1 = (1 << 23), + HRTIM_OUT_RST_MSTPER = (1 << 24), + HRTIM_OUT_RST_CMP4 = (1 << 25), + HRTIM_OUT_RST_CMP3 = (1 << 26), + HRTIM_OUT_RST_CMP2 = (1 << 27), + HRTIM_OUT_RST_CMP1 = (1 << 28), + HRTIM_OUT_RST_PER = (1 << 29), + HRTIM_OUT_RST_RESYNC = (1 << 30), + HRTIM_OUT_RST_SOFT = (1 << 31), +}; + +/* Source which can force the Tx1/Tx2 output to its active state */ + +enum stm32_hrtim_out_set_e +{ + HRTIM_OUT_SET_UPDATE = (1 << 0), + HRTIM_OUT_SET_EXTEVNT10 = (1 << 1), + HRTIM_OUT_SET_EXTEVNT9 = (1 << 2), + HRTIM_OUT_SET_EXTEVNT8 = (1 << 3), + HRTIM_OUT_SET_EXTEVNT7 = (1 << 4), + HRTIM_OUT_SET_EXTEVNT6 = (1 << 5), + HRTIM_OUT_SET_EXTEVNT5 = (1 << 6), + HRTIM_OUT_SET_EXTEVNT4 = (1 << 7), + HRTIM_OUT_SET_EXTEVNT3 = (1 << 8), + HRTIM_OUT_SET_EXTEVNT2 = (1 << 9), + HRTIM_OUT_SET_EXTEVNT1 = (1 << 10), + HRTIM_OUT_SET_TIMEVNT9 = (1 << 11), + HRTIM_OUT_SET_TIMEVNT8 = (1 << 12), + HRTIM_OUT_SET_TIMEVNT7 = (1 << 13), + HRTIM_OUT_SET_TIMEVNT6 = (1 << 14), + HRTIM_OUT_SET_TIMEVNT5 = (1 << 15), + HRTIM_OUT_SET_TIMEVNT4 = (1 << 16), + HRTIM_OUT_SET_TIMEVNT3 = (1 << 17), + HRTIM_OUT_SET_TIMEVNT2 = (1 << 18), + HRTIM_OUT_SET_TIMEVNT1 = (1 << 19), + HRTIM_OUT_SET_MSTCMP4 = (1 << 20), + HRTIM_OUT_SET_MSTCMP3 = (1 << 21), + HRTIM_OUT_SET_MSTCMP2 = (1 << 22), + HRTIM_OUT_SET_MSTCMP1 = (1 << 23), + HRTIM_OUT_SET_MSTPER = (1 << 24), + HRTIM_OUT_SET_CMP4 = (1 << 25), + HRTIM_OUT_SET_CMP3 = (1 << 26), + HRTIM_OUT_SET_CMP2 = (1 << 27), + HRTIM_OUT_SET_CMP1 = (1 << 28), + HRTIM_OUT_SET_PER = (1 << 29), + HRTIM_OUT_SET_RESYNC = (1 << 30), + HRTIM_OUT_SET_SOFT = (1 << 31), +}; + +/* Events that can reset TimerX Counter */ + +enum stm32_hrtim_tim_rst_e +{ + /* Timer owns events */ + + HRTIM_RST_UPDT, + HRTIM_RST_CMP4, + HRTIM_RST_CMP2, + + /* Master Timer Events */ + + HRTIM_RST_MSTCMP4, + HRTIM_RST_MSTCMP3, + HRTIM_RST_MSTCMP2, + HRTIM_RST_MSTCMP1, + HRTIM_RST_MSTPER, + + /* TimerX events */ + + HRTIM_RST_TECMP4, + HRTIM_RST_TECMP2, + HRTIM_RST_TECMP1, + HRTIM_RST_TDCMP4, + HRTIM_RST_TDCMP2, + HRTIM_RST_TDCMP1, + HRTIM_RST_TCCMP4, + HRTIM_RST_TCCMP2, + HRTIM_RST_TCCMP1, + HRTIM_RST_TBCMP4, + HRTIM_RST_TBCMP2, + HRTIM_RST_TBCMP1, + HRTIM_RST_TACMP4, + HRTIM_RST_TACMP2, + HRTIM_RST_TACMP1, + + /* External Events */ + + HRTIM_RST_EXTEVNT10, + HRTIM_RST_EXTEVNT9, + HRTIM_RST_EXTEVNT8, + HRTIM_RST_EXTEVNT7, + HRTIM_RST_EXTEVNT6, + HRTIM_RST_EXTEVNT5, + HRTIM_RST_EXTEVNT4, + HRTIM_RST_EXTEVNT3, + HRTIM_RST_EXTEVNT2, + HRTIM_RST_EXTEVNT1, +}; + +/* HRTIM Timer X prescaler */ + +enum stm32_hrtim_tim_prescaler_e +{ + HRTIM_PRESCALER_1, + HRTIM_PRESCALER_2, + HRTIM_PRESCALER_4, + HRTIM_PRESCALER_8, + HRTIM_PRESCALER_16, + HRTIM_PRESCALER_32, + HRTIM_PRESCALER_64, + HRTIM_PRESCALER_128, +}; + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +#ifndef __ASSEMBLY__ +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/**************************************************************************** + * Name: stm32_hrtiminitialize + * + * Description: + * Initialize the HRTIM. + * + * Input Parameters: + * None + * + * Returned Value: + * Valid HRTIM device structure reference on succcess; a NULL on failure. + * + * Assumptions: + * 1. Clock to the HRTIM block has enabled, + * 2. Board-specific logic has already configured + * + ****************************************************************************/ + +FAR struct hrtim_dev_s* stm32_hrtiminitialize(void); + +#undef EXTERN +#ifdef __cplusplus +} +#endif +#endif /* __ASSEMBLY__ */ + +#endif /* CONFIG_STM32_HRTIM1 */ +#endif /* __ARCH_ARM_SRC_STM32_STM32_HRTIM_H */ -- GitLab From de8cd6c870db763c77a4d5cd0da3769b64a4ca1d Mon Sep 17 00:00:00 2001 From: raiden00pl Date: Sun, 11 Jun 2017 20:51:23 +0200 Subject: [PATCH 960/990] stm32_hrtim: add character driver --- arch/arm/src/stm32/stm32_hrtim.c | 149 ++++++++++++++++++++++++------- arch/arm/src/stm32/stm32_hrtim.h | 20 +++++ 2 files changed, 135 insertions(+), 34 deletions(-) diff --git a/arch/arm/src/stm32/stm32_hrtim.c b/arch/arm/src/stm32/stm32_hrtim.c index c0cc3e48af..aef00eaba6 100644 --- a/arch/arm/src/stm32/stm32_hrtim.c +++ b/arch/arm/src/stm32/stm32_hrtim.c @@ -45,7 +45,6 @@ #include #include -#include #include "chip.h" #include "stm32.h" @@ -248,7 +247,6 @@ struct stm32_hrtim_slave_priv_s struct stm32_hrtim_s { uint32_t base; /* Base adress of HRTIM block */ - FAR const struct hrtim_ops_s *ops; /* */ struct stm32_hrtim_tim_s *master; /* Master Timer */ #ifdef CONFIG_STM32_HRTIM_TIMA struct stm32_hrtim_tim_s *tima; /* HRTIM Timer A */ @@ -271,6 +269,12 @@ struct stm32_hrtim_s * Private Function Prototypes ****************************************************************************/ +/* HRTIM Driver Methods */ + +static int stm32_hrtim_open(FAR struct file *filep); +static int stm32_hrtim_close(FAR struct file *filep); +static int stm32_hrtim_ioctl(FAR struct file *filep, int cmd, unsigned long arg); + /* HRTIM Register access */ #ifdef HRTIM_HAVE_CLK_FROM_PLL @@ -294,10 +298,6 @@ static uint32_t hrtim_tim_getreg(FAR struct stm32_hrtim_s *priv, uint8_t index, static FAR struct stm32_hrtim_tim_s *hrtim_tim_get(FAR struct stm32_hrtim_s *priv, uint8_t index); -/* HRTIM Driver Methods */ - -static int hrtim_ioctl(FAR struct hrtim_dev_s *dev, int cmd, unsigned long arg); - /* Configuration */ static int hrtim_dll_cal(FAR struct stm32_hrtim_s *priv); @@ -338,11 +338,20 @@ static int stm32_hrtimconfig(FAR struct stm32_hrtim_s *priv); * Private Data ****************************************************************************/ -/* HRTIM interface operations */ - -static const struct hrtim_ops_s g_hrtimops = +static const struct file_operations hrtim_fops = { - .ho_ioctl = hrtim_ioctl, + stm32_hrtim_open, /* open */ + stm32_hrtim_close, /* close */ + NULL, /* read */ + NULL, /* write */ + NULL, /* seek */ + stm32_hrtim_ioctl /* ioctl */ +#ifndef CONFIG_DISABLE_POLL + , NULL /* poll */ +#endif +#ifndef CONFIG_DISABLE_PSEUDOFS_OPERATIONS + , NULL /* unlink */ +#endif }; /* Master Timer data */ @@ -439,7 +448,6 @@ static struct stm32_hrtim_s g_hrtim1priv = struct hrtim_dev_s g_hrtim1dev = { - .hd_ops = &g_hrtimops, .hd_priv = &g_hrtim1priv, }; @@ -447,6 +455,73 @@ struct hrtim_dev_s g_hrtim1dev = * Private Functions ****************************************************************************/ +/**************************************************************************** + * Name: stm32_hrtim_open + * + * Description: + * This function is called whenever the HRTIM device is opened. + * + ****************************************************************************/ + +static int stm32_hrtim_open(FAR struct file *filep) +{ +#warning "stm32_hrtim_open: missing logic" + return OK; +} + +/**************************************************************************** + * Name: stm32_hrtim_close + * + * Description: + * This function is called when the HRTIM device is closed. + * + ****************************************************************************/ + +static int stm32_hrtim_close(FAR struct file *filep) +{ +#warning "smt32_hrtim_close: missing logic" + return OK; +} + +/**************************************************************************** + * Name: stm32_hrtim_ioctl + * + * Description: + * The standard ioctl method. This is where ALL of the HRTIM work is done. + * + ****************************************************************************/ + +static int stm32_hrtim_ioctl(FAR struct file *filep, int cmd, unsigned long arg) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct hrtim_dev_s *dev; + FAR struct stm32_hrtim_s *hrtim; + int ret; + + tmrinfo("cmd: %d arg: %ld\n", cmd, arg); + dev = inode->i_private; + DEBUGASSERT(dev != NULL); + hrtim = dev->hd_priv; + + UNUSED(hrtim); + +#warning "smt32_hrtim_ioctl: missing logic" + + /* Handle HRTIM ioctl commands */ + + switch (cmd) + { + + default: + { + ret = -ENOSYS; + break; + } + } + + return ret; +} + /**************************************************************************** * Name: stm32_modifyreg32 * @@ -463,12 +538,13 @@ struct hrtim_dev_s g_hrtim1dev = * ****************************************************************************/ +#ifdef HRTIM_HAVE_CLK_FROM_PLL static void stm32_modifyreg32(unsigned int addr, uint32_t clrbits, uint32_t setbits) { putreg32((getreg32(addr) & ~clrbits) | setbits, addr); } - +#endif /**************************************************************************** * Name: hrtim_getreg @@ -730,28 +806,6 @@ static void hrtim_tim_modifyreg(FAR struct stm32_hrtim_s *priv, uint8_t index, (hrtim_tim_getreg(priv, index, offset) & ~clrbits) | setbits); } -/**************************************************************************** - * Name: hrtim_ioctl - * - * Description: - * All ioctl calls will be routed through this method. - * - * Input Parameters: - * dev - pointer to device structure used by the driver - * cmd - command - * arg - arguments passed with command - * - * Returned Value: - * Zero on success; a negated errno value on failure. - * - ****************************************************************************/ - -static int hrtim_ioctl(FAR struct hrtim_dev_s *dev, int cmd, unsigned long arg) -{ -#warning "hrtim_ioctl: missing logic" - return -ENOTTY; -} - /**************************************************************************** * Name: stm32_dll_cal * @@ -1514,6 +1568,33 @@ FAR struct hrtim_dev_s* stm32_hrtiminitialize(void) return dev; } +/**************************************************************************** + * Name: hrtim_register + ****************************************************************************/ + +int hrtim_register(FAR const char *path, FAR struct hrtim_dev_s *dev) +{ + int ret ; + + /* Initialize the HRTIM device structure */ + + dev->hd_ocount = 0; + + /* Initialize semaphores */ + + sem_init(&dev->hd_closesem, 0, 1); + + /* Register the HRTIM character driver */ + + ret = register_driver(path, &hrtim_fops, 0444, dev); + if (ret < 0) + { + sem_destroy(&dev->hd_closesem); + } + + return ret; +} + #endif /* CONFIG_STM32_STM32F33XX */ #endif /* CONFIG_STM32_HRTIM1 */ diff --git a/arch/arm/src/stm32/stm32_hrtim.h b/arch/arm/src/stm32/stm32_hrtim.h index 1fa9a4971a..e4fe9be912 100644 --- a/arch/arm/src/stm32/stm32_hrtim.h +++ b/arch/arm/src/stm32/stm32_hrtim.h @@ -222,6 +222,20 @@ enum stm32_hrtim_tim_prescaler_e HRTIM_PRESCALER_128, }; +struct hrtim_dev_s +{ +#ifdef CONFIG_HRTIM + /* Fields managed by common upper half HRTIM logic */ + + uint8_t hd_ocount; /* The number of times the device has been opened */ + sem_t hd_closesem; /* Locks out new opens while close is in progress */ +#endif + + /* Fields provided by lower half HRTIM logic */ + + FAR void *hd_priv; /* Used by the arch-specific logic */ +}; + /************************************************************************************ * Public Function Prototypes ************************************************************************************/ @@ -255,6 +269,12 @@ extern "C" FAR struct hrtim_dev_s* stm32_hrtiminitialize(void); +/**************************************************************************** + * Name: hrtim_register + ****************************************************************************/ + +int hrtim_register(FAR const char *path, FAR struct hrtim_dev_s *dev); + #undef EXTERN #ifdef __cplusplus } -- GitLab From 43e0c28acbeeed764f54fac07f4d69f9e123e911 Mon Sep 17 00:00:00 2001 From: raiden00pl Date: Sun, 11 Jun 2017 20:52:43 +0200 Subject: [PATCH 961/990] nucleo-f334r8: add HRTIM initialization --- configs/nucleo-f334r8/src/stm32_hrtim.c | 96 +++++++++++++++++++++++++ 1 file changed, 96 insertions(+) create mode 100644 configs/nucleo-f334r8/src/stm32_hrtim.c diff --git a/configs/nucleo-f334r8/src/stm32_hrtim.c b/configs/nucleo-f334r8/src/stm32_hrtim.c new file mode 100644 index 0000000000..d5af56f757 --- /dev/null +++ b/configs/nucleo-f334r8/src/stm32_hrtim.c @@ -0,0 +1,96 @@ +/**************************************************************************** + * configs/nucleo-f334r8/src/stm32_hrtim.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Author: Mateusz Szafoni + * + * 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 "stm32.h" + +#if defined(CONFIG_HRTIM) && defined(CONFIG_STM32_HRTIM1) + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_hrtim_setup + * + * Description: + * Initialize HRTIM + * + ****************************************************************************/ + +int stm32_hrtim_setup(void) +{ + static bool initialized = false; + struct hrtim_dev_s* hrtim = NULL; + int ret; + + if (!initialized) + { + /* Get the HRTIM interface */ + + hrtim = stm32_hrtiminitialize(); + if (hrtim == NULL) + { + aerr("ERROR: Failed to get HRTIM1interface\n"); + return -ENODEV; + } + + /* Register the HRTIM character driver at /dev/hrtim0 */ + + ret = hrtim_register("/dev/hrtim0", hrtim); + if (ret < 0) + { + aerr("ERROR: hrtim_register failed: %d\n", ret); + return ret; + } + + initialized = true; + } + + return OK; +} + +#endif /* CONFIG_HRTIM && CONFIG_STM32_HRTIM1 */ -- GitLab From fe7148dff0561f62f00d46b84e0395a8e5feb544 Mon Sep 17 00:00:00 2001 From: raiden00pl Date: Sun, 11 Jun 2017 21:14:48 +0200 Subject: [PATCH 962/990] nucleo-f334r8: cosmetics --- configs/nucleo-f334r8/src/stm32_hrtim.c | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/configs/nucleo-f334r8/src/stm32_hrtim.c b/configs/nucleo-f334r8/src/stm32_hrtim.c index d5af56f757..591e4c6fda 100644 --- a/configs/nucleo-f334r8/src/stm32_hrtim.c +++ b/configs/nucleo-f334r8/src/stm32_hrtim.c @@ -57,7 +57,10 @@ * Name: stm32_hrtim_setup * * Description: - * Initialize HRTIM + * Initialize HRTIM driver + * + * Returned Value: + * 0 on success, a negated errno value on failure * ****************************************************************************/ @@ -74,7 +77,7 @@ int stm32_hrtim_setup(void) hrtim = stm32_hrtiminitialize(); if (hrtim == NULL) { - aerr("ERROR: Failed to get HRTIM1interface\n"); + tmrerr("ERROR: Failed to get HRTIM1 interface\n"); return -ENODEV; } @@ -83,7 +86,7 @@ int stm32_hrtim_setup(void) ret = hrtim_register("/dev/hrtim0", hrtim); if (ret < 0) { - aerr("ERROR: hrtim_register failed: %d\n", ret); + tmrerr("ERROR: hrtim_register failed: %d\n", ret); return ret; } -- GitLab From e6a84763827109bb24a0499144c4be3bc7c75b36 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sun, 11 Jun 2017 18:48:35 -0600 Subject: [PATCH 963/990] Add some REVISIT comments. --- libc/netdb/lib_gethostbynamer.c | 16 ++++++++++++---- 1 file changed, 12 insertions(+), 4 deletions(-) diff --git a/libc/netdb/lib_gethostbynamer.c b/libc/netdb/lib_gethostbynamer.c index 9e1a924bdf..96fcf9312c 100644 --- a/libc/netdb/lib_gethostbynamer.c +++ b/libc/netdb/lib_gethostbynamer.c @@ -196,7 +196,9 @@ static int lib_numeric_address(FAR const char *name, FAR struct hostent *host, ptr += addrlen; buflen -= addrlen; - /* And copy name */ + /* And copy name + * REVISIT: Should the check not be (namelen + 1 > buflen)? + */ namelen = strlen(name); if (addrlen + namelen + 1 > buflen) @@ -284,7 +286,9 @@ static int lib_localhost(FAR const char *name, FAR struct hostent *host, dest += addrlen; buflen -= addrlen; - /* And copy name */ + /* And copy name + * REVISIT: Should the check not be (namelen + 1 > buflen)? + */ namelen = strlen(name); if (addrlen + namelen + 1 > buflen) @@ -400,7 +404,9 @@ static int lib_find_answer(FAR const char *name, FAR struct hostent *host, ptr += addrlen; buflen -= addrlen; - /* And copy the host name */ + /* And copy name + * REVISIT: Should the check not be (namelen + 1 > buflen)? + */ namelen = strlen(name); if (addrlen + namelen + 1 > buflen) @@ -546,7 +552,9 @@ static int lib_dns_lookup(FAR const char *name, FAR struct hostent *host, ptr += addrlen; buflen -= addrlen; - /* And copy the name */ + /* And copy name + * REVISIT: Should the check not be (namelen + 1 > buflen)? + */ namelen = strlen(name); if (addrlen + namelen + 1 > buflen) -- GitLab From 93a2d52b566a41ef0a08de25338d474b7500a3aa Mon Sep 17 00:00:00 2001 From: Masayuki Ishikawa Date: Mon, 12 Jun 2017 13:34:53 +0900 Subject: [PATCH 964/990] i.MX6: Fix a wrong parameter passed when calling irq_attach() in imx_serial.c --- arch/arm/src/imx6/imx_serial.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/arch/arm/src/imx6/imx_serial.c b/arch/arm/src/imx6/imx_serial.c index 8ae64136b5..6fdc021115 100644 --- a/arch/arm/src/imx6/imx_serial.c +++ b/arch/arm/src/imx6/imx_serial.c @@ -595,7 +595,7 @@ static int imx_attach(struct uart_dev_s *dev) /* Attach and enable the IRQ */ - ret = irq_attach(priv->irq, imx_interrupt, priv); + ret = irq_attach(priv->irq, imx_interrupt, dev); if (ret == OK) { /* Configure as a (high) level interrupt */ -- GitLab From f5f1c73b543fd6c49ef07e3e80570f605025a5dd Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 12 Jun 2017 06:22:35 -0600 Subject: [PATCH 965/990] Based on the last PR, review all serial driver vector attachment. Found one additional error and updated all relevant drivers to current interrupt parameter passing. --- arch/arm/src/a1x/a1x_serial.c | 6 +-- arch/arm/src/imx1/imx_serial.c | 72 ++++------------------------ arch/arm/src/lpc31xx/lpc31_serial.c | 11 +++-- arch/arm/src/sama5/sam_dbgu.c | 9 ++-- arch/misoc/src/common/misoc_serial.c | 6 +-- arch/renesas/src/sh1/sh1_serial.c | 30 +++--------- 6 files changed, 32 insertions(+), 102 deletions(-) diff --git a/arch/arm/src/a1x/a1x_serial.c b/arch/arm/src/a1x/a1x_serial.c index ec8de5e009..307dac2d5e 100644 --- a/arch/arm/src/a1x/a1x_serial.c +++ b/arch/arm/src/a1x/a1x_serial.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/arm/src/a1x/a1x_serial.c * - * Copyright (C) 2013-2014 Gregory Nutt. All rights reserved. + * Copyright (C) 2013-2014, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -1035,7 +1035,7 @@ static int up_attach(struct uart_dev_s *dev) /* Attach and enable the IRQ */ - ret = irq_attach(priv->irq, uart_interrupt, priv); + ret = irq_attach(priv->irq, uart_interrupt, dev); if (ret == OK) { /* Enable the interrupt (RX and TX interrupts are still disabled @@ -1080,7 +1080,7 @@ static void up_detach(struct uart_dev_s *dev) static int uart_interrupt(int irq, void *context, void *arg) { struct uart_dev_s *dev = (struct uart_dev_s *)arg; - struct up_dev_s *priv = (struct up_dev_s *)arg; + struct up_dev_s *priv; uint32_t status; int passes; diff --git a/arch/arm/src/imx1/imx_serial.c b/arch/arm/src/imx1/imx_serial.c index ebe996e81b..ef32ff5bf0 100644 --- a/arch/arm/src/imx1/imx_serial.c +++ b/arch/arm/src/imx1/imx_serial.c @@ -1,8 +1,7 @@ /**************************************************************************** * arch/arm/src/imx1/imx_serial.c - * arch/arm/src/chip/imx_serial.c * - * Copyright (C) 2009, 2012-2013 Gregory Nutt. All rights reserved. + * Copyright (C) 2009, 2012-2013, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -111,7 +110,6 @@ static int up_setup(struct uart_dev_s *dev); static void up_shutdown(struct uart_dev_s *dev); static int up_attach(struct uart_dev_s *dev); static void up_detach(struct uart_dev_s *dev); -static inline struct uart_dev_s *up_mapirq(int irq); static int up_interrupt(int irq, void *context, FAR void *arg); static int up_ioctl(struct file *filep, int cmd, unsigned long arg); static int up_receive(struct uart_dev_s *dev, uint32_t *status); @@ -753,13 +751,13 @@ static int up_attach(struct uart_dev_s *dev) /* Attach and enable the IRQ */ #if defined(CONFIG_ARCH_CHIP_IMX1) || defined(CONFIG_ARCH_CHIP_IMXL) - ret = irq_attach(priv->rxirq, up_interrupt, NULL); + ret = irq_attach(priv->rxirq, up_interrupt, dev); if (ret < 0) { return ret; } - ret = irq_attach(priv->txirq, up_interrupt, NULL); + ret = irq_attach(priv->txirq, up_interrupt, dev); if (ret < 0) { irq_detach(priv->rxirq); @@ -772,7 +770,7 @@ static int up_attach(struct uart_dev_s *dev) up_enable_irq(priv->txirq); #else - ret = irq_attach(priv->irq, up_interrupt, NULL); + ret = irq_attach(priv->irq, up_interrupt, dev); if (ret == OK) { /* Enable the interrupt (RX and TX interrupts are still disabled @@ -810,60 +808,6 @@ static void up_detach(struct uart_dev_s *dev) #endif } -/**************************************************************************** - * Name: up_mapirq - * - * Description: - * Map an IRQ number to internal UART state structure - * - ****************************************************************************/ - -static inline struct uart_dev_s *up_mapirq(int irq) -{ - struct uart_dev_s *dev; - - switch (irq) - { -#ifdef CONFIG_IMX1_UART1 -#if defined(CONFIG_ARCH_CHIP_IMX1) || defined(CONFIG_ARCH_CHIP_IMXL) - case IMX_IRQ_UART1RX: - case IMX_IRQ_UART1TX: -#else - case IMX_IRQ_UART1: -#endif - dev = &g_uart1port; - break; -#endif - -#ifdef CONFIG_IMX1_UART2 -#if defined(CONFIG_ARCH_CHIP_IMX1) || defined(CONFIG_ARCH_CHIP_IMXL) - case IMX_IRQ_UART2RX: - case IMX_IRQ_UART2TX: -#else - case IMX_IRQ_UART2: -#endif - dev = &g_uart2port; - break; -#endif - -#ifdef CONFIG_IMX1_UART3 -#if defined(CONFIG_ARCH_CHIP_IMX1) || defined(CONFIG_ARCH_CHIP_IMXL) - case IMX_IRQ_UART3RX: - case IMX_IRQ_UART3TX: -#else - case IMX_IRQ_UART3: -#endif - dev = &g_uart3port; - break; -#endif - - default: - PANIC(); - break; - } - return dev; -} - /**************************************************************************** * Name: up_interrupt (and front-ends) * @@ -879,12 +823,12 @@ static inline struct uart_dev_s *up_mapirq(int irq) static int up_interrupt(int irq, void *context, FAR void *arg) { - struct uart_dev_s *dev; - struct up_dev_s *priv; + struct uart_dev_s *dev = (struct uart_dev_s *)arg; + struct up_dev_s *priv; uint32_t usr1; - int passes = 0; + int passes = 0; - dev = up_mapirq(irq); + DEBUGASSERT(dev != NULL && dev->priv != NULL); priv = (struct up_dev_s *)dev->priv; /* Loop until there are no characters to be transferred or, diff --git a/arch/arm/src/lpc31xx/lpc31_serial.c b/arch/arm/src/lpc31xx/lpc31_serial.c index fa5f3b4563..7f79a0f41b 100644 --- a/arch/arm/src/lpc31xx/lpc31_serial.c +++ b/arch/arm/src/lpc31xx/lpc31_serial.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/arm/src/lpc31xx/lpc31_serial.c * - * Copyright (C) 2009, 2012-2013 Gregory Nutt. All rights reserved. + * Copyright (C) 2009, 2012-2013, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -444,7 +444,7 @@ static int up_attach(struct uart_dev_s *dev) /* Attach and enable the IRQ */ - ret = irq_attach(LPC31_IRQ_UART, up_interrupt, NULL); + ret = irq_attach(LPC31_IRQ_UART, up_interrupt, dev); if (ret == OK) { /* Enable the interrupt (RX and TX interrupts are still disabled @@ -453,6 +453,7 @@ static int up_attach(struct uart_dev_s *dev) up_enable_irq(LPC31_IRQ_UART); } + return ret; } @@ -484,9 +485,9 @@ static void up_detach(struct uart_dev_s *dev) static int up_interrupt(int irq, void *context, FAR void *arg) { - struct uart_dev_s *dev = &g_uartport; - uint8_t status; - int passes; + struct uart_dev_s *dev = (struct uart_dev_s *)arg; + uint8_t status; + int passes; /* Loop until there are no characters to be transferred or, * until we have been looping for a long time. diff --git a/arch/arm/src/sama5/sam_dbgu.c b/arch/arm/src/sama5/sam_dbgu.c index cc4f6bf7f4..f1237d9144 100644 --- a/arch/arm/src/sama5/sam_dbgu.c +++ b/arch/arm/src/sama5/sam_dbgu.c @@ -287,7 +287,7 @@ static int dbgu_attach(struct uart_dev_s *dev) /* Attach and enable the IRQ */ - ret = irq_attach(SAM_IRQ_DBGU, dbgu_interrupt, NULL); + ret = irq_attach(SAM_IRQ_DBGU, dbgu_interrupt, dev); if (ret == OK) { /* Enable the interrupt (RX and TX interrupts are still disabled @@ -330,13 +330,16 @@ static void dbgu_detach(struct uart_dev_s *dev) static int dbgu_interrupt(int irq, void *context, FAR void *arg) { - struct uart_dev_s *dev = &g_dbgu_port; - struct dbgu_dev_s *priv = (struct dbgu_dev_s *)dev->priv; + struct uart_dev_s *dev = (struct uart_dev_s *)arg; + struct dbgu_dev_s *priv; uint32_t pending; uint32_t imr; int passes; bool handled; + DEBUGASSERT(dev != NULL && dev->priv != NULL); + priv = (struct dbgu_dev_s *)dev->priv; + /* Loop until there are no characters to be transferred or, until we have * been looping for a long time. */ diff --git a/arch/misoc/src/common/misoc_serial.c b/arch/misoc/src/common/misoc_serial.c index b64b0ea737..8909d690eb 100644 --- a/arch/misoc/src/common/misoc_serial.c +++ b/arch/misoc/src/common/misoc_serial.c @@ -313,7 +313,7 @@ static int misoc_attach(struct uart_dev_s *dev) { struct misoc_dev_s *priv = (struct misoc_dev_s *)dev->priv; - (void)irq_attach(priv->irq, misoc_uart_interrupt, NULL); + (void)irq_attach(priv->irq, misoc_uart_interrupt, dev); up_enable_irq(priv->irq); return OK; @@ -351,10 +351,10 @@ static void misoc_detach(struct uart_dev_s *dev) static int misoc_uart_interrupt(int irq, void *context, FAR void *arg) { + struct uart_dev_s *dev = (struct uart_dev_s *)arg; uint32_t stat; - struct uart_dev_s *dev = NULL; - dev = &g_uart1port; + DEBUGASSERT(dev != NULL); /* Read as much as we can */ diff --git a/arch/renesas/src/sh1/sh1_serial.c b/arch/renesas/src/sh1/sh1_serial.c index 3dd5c1cff2..49ce5cda8a 100644 --- a/arch/renesas/src/sh1/sh1_serial.c +++ b/arch/renesas/src/sh1/sh1_serial.c @@ -485,17 +485,17 @@ static int up_attach(struct uart_dev_s *dev) /* Attach the RDR full IRQ (RXI) that is enabled by the RIE SCR bit */ - ret = irq_attach(priv->irq + SH1_RXI_IRQ_OFFSET, up_interrupt, NULL); + ret = irq_attach(priv->irq + SH1_RXI_IRQ_OFFSET, up_interrupt, dev); if (ret == OK) { /* The RIE interrupt enable also enables the receive error interrupt (ERI) */ - ret = irq_attach(priv->irq + SH1_ERI_IRQ_OFFSET, up_interrupt, NULL); + ret = irq_attach(priv->irq + SH1_ERI_IRQ_OFFSET, up_interrupt, dev); if (ret == OK) { /* Attach the TDR empty IRQ (TXI) enabled by the TIE SCR bit */ - ret = irq_attach(priv->irq + SH1_TXI_IRQ_OFFSET, up_interrupt, NULL); + ret = irq_attach(priv->irq + SH1_TXI_IRQ_OFFSET, up_interrupt, dev); if (ret == OK) { #ifdef CONFIG_ARCH_IRQPRIO @@ -569,28 +569,10 @@ static void up_detach(struct uart_dev_s *dev) static int up_interrupt(int irq, void *context, FAR void *arg) { - struct uart_dev_s *dev = NULL; - struct up_dev_s *priv; + struct uart_dev_s *dev = (struct uart_dev_s *)arg; + struct up_dev_s *priv; -#ifdef CONFIG_SH1_SCI0 - if ((irq >= g_sci0priv.irq) && - (irq <= g_sci0priv.irq + SH1_SCI_NIRQS)) - { - dev = &g_sci0port; - } - else -#endif -#ifdef CONFIG_SH1_SCI1 - if ((irq >= g_sci1priv.irq) && - (irq <= g_sci1priv.irq + SH1_SCI_NIRQS)) - { - dev = &g_sci1port; - } - else -#endif - { - PANIC(); - } + DEBUGASSERT(dev != NULL && dev->priv != NULL); priv = (struct up_dev_s*)dev->priv; /* Get the current SCI status */ -- GitLab From 85645284b37b0ada1ba8208cb228f419c1c52190 Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Mon, 12 Jun 2017 06:38:27 -0600 Subject: [PATCH 966/990] MTD: Fix problems in SPI locking in mp25x.c driver. Same problem probably in exists in several other drivers that derive from this this driver as well. --- drivers/mtd/m25px.c | 26 ++++++++++++++++++-------- 1 file changed, 18 insertions(+), 8 deletions(-) diff --git a/drivers/mtd/m25px.c b/drivers/mtd/m25px.c index 3b509eb6c5..c7b5c495ea 100644 --- a/drivers/mtd/m25px.c +++ b/drivers/mtd/m25px.c @@ -432,6 +432,7 @@ static void m25p_waitwritecomplete(struct m25p_dev_s *priv) { /* Select this FLASH part */ + m25p_lock(priv->dev); SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Read Status Register (RDSR)" command */ @@ -445,6 +446,7 @@ static void m25p_waitwritecomplete(struct m25p_dev_s *priv) /* Deselect the FLASH */ SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); + m25p_unlock(priv->dev); /* Given that writing could take up to few tens of milliseconds, and erasing * could take more. The following short delay in the "busy" case will allow @@ -453,9 +455,7 @@ static void m25p_waitwritecomplete(struct m25p_dev_s *priv) if ((status & M25P_SR_WIP) != 0) { - m25p_unlock(priv->dev); usleep(1000); - m25p_lock(priv->dev); } } while ((status & M25P_SR_WIP) != 0); @@ -471,6 +471,7 @@ static void m25p_writeenable(struct m25p_dev_s *priv) { /* Select this FLASH part */ + m25p_lock(priv->dev); SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Write Enable (WREN)" command */ @@ -480,6 +481,8 @@ static void m25p_writeenable(struct m25p_dev_s *priv) /* Deselect the FLASH */ SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); + m25p_unlock(priv->dev); + finfo("Enabled\n"); } @@ -518,6 +521,7 @@ static void m25p_sectorerase(struct m25p_dev_s *priv, off_t sector, uint8_t type /* Select this FLASH part */ + m25p_lock(priv->dev); SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send the "Sector Erase (SE)" or Sub-Sector Erase (SSE) instruction @@ -538,6 +542,8 @@ static void m25p_sectorerase(struct m25p_dev_s *priv, off_t sector, uint8_t type /* Deselect the FLASH */ SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); + m25p_unlock(priv->dev); + finfo("Erased\n"); } @@ -563,6 +569,7 @@ static inline int m25p_bulkerase(struct m25p_dev_s *priv) /* Select this FLASH part */ + m25p_lock(priv->dev); SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send the "Bulk Erase (BE)" instruction */ @@ -572,6 +579,8 @@ static inline int m25p_bulkerase(struct m25p_dev_s *priv) /* Deselect the FLASH */ SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); + m25p_unlock(priv->dev); + finfo("Return: OK\n"); return OK; } @@ -601,6 +610,7 @@ static inline void m25p_pagewrite(struct m25p_dev_s *priv, FAR const uint8_t *bu /* Select this FLASH part */ + m25p_lock(priv->dev); SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Page Program (PP)" command */ @@ -620,6 +630,8 @@ static inline void m25p_pagewrite(struct m25p_dev_s *priv, FAR const uint8_t *bu /* Deselect the FLASH: Chip Select high */ SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); + m25p_unlock(priv->dev); + finfo("Written\n"); } @@ -647,6 +659,7 @@ static inline void m25p_bytewrite(struct m25p_dev_s *priv, FAR const uint8_t *bu /* Select this FLASH part */ + m25p_lock(priv->dev); SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Page Program (PP)" command */ @@ -666,6 +679,8 @@ static inline void m25p_bytewrite(struct m25p_dev_s *priv, FAR const uint8_t *bu /* Deselect the FLASH: Chip Select high */ SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); + m25p_unlock(priv->dev); + finfo("Written\n"); } #endif @@ -683,7 +698,6 @@ static int m25p_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblock /* Lock access to the SPI bus until we complete the erase */ - m25p_lock(priv->dev); while (blocksleft > 0) { #ifdef CONFIG_M25P_SUBSECTOR_ERASE @@ -733,7 +747,6 @@ static int m25p_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblock blocksleft--; } - m25p_unlock(priv->dev); return (int)nblocks; } @@ -775,7 +788,6 @@ static ssize_t m25p_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t n /* Lock the SPI bus and write each page to FLASH */ - m25p_lock(priv->dev); while (blocksleft-- > 0) { m25p_pagewrite(priv, buffer, startblock); @@ -783,7 +795,6 @@ static ssize_t m25p_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t n startblock++; } - m25p_unlock(priv->dev); return nblocks; } @@ -829,6 +840,7 @@ static ssize_t m25p_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes, SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); m25p_unlock(priv->dev); + finfo("return nbytes: %d\n", (int)nbytes); return nbytes; } @@ -961,9 +973,7 @@ static int m25p_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg) { /* Erase the entire device */ - m25p_lock(priv->dev); ret = m25p_bulkerase(priv); - m25p_unlock(priv->dev); } break; -- GitLab From ee7217be63856fc6b5582ae93fe9768b49833642 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 12 Jun 2017 06:47:43 -0600 Subject: [PATCH 967/990] gethostbyname_r: Fix check for space in buffer. --- libc/netdb/lib_gethostbynamer.c | 24 ++++++++---------------- 1 file changed, 8 insertions(+), 16 deletions(-) diff --git a/libc/netdb/lib_gethostbynamer.c b/libc/netdb/lib_gethostbynamer.c index 96fcf9312c..8ad93ac6f3 100644 --- a/libc/netdb/lib_gethostbynamer.c +++ b/libc/netdb/lib_gethostbynamer.c @@ -196,12 +196,10 @@ static int lib_numeric_address(FAR const char *name, FAR struct hostent *host, ptr += addrlen; buflen -= addrlen; - /* And copy name - * REVISIT: Should the check not be (namelen + 1 > buflen)? - */ + /* And copy name */ namelen = strlen(name); - if (addrlen + namelen + 1 > buflen) + if ((namelen + 1) > buflen) { return -ERANGE; } @@ -286,12 +284,10 @@ static int lib_localhost(FAR const char *name, FAR struct hostent *host, dest += addrlen; buflen -= addrlen; - /* And copy name - * REVISIT: Should the check not be (namelen + 1 > buflen)? - */ + /* And copy name */ namelen = strlen(name); - if (addrlen + namelen + 1 > buflen) + if ((namelen + 1) > buflen) { return -ERANGE; } @@ -404,12 +400,10 @@ static int lib_find_answer(FAR const char *name, FAR struct hostent *host, ptr += addrlen; buflen -= addrlen; - /* And copy name - * REVISIT: Should the check not be (namelen + 1 > buflen)? - */ + /* And copy name */ namelen = strlen(name); - if (addrlen + namelen + 1 > buflen) + if ((namelen + 1) > buflen) { return -ERANGE; } @@ -552,12 +546,10 @@ static int lib_dns_lookup(FAR const char *name, FAR struct hostent *host, ptr += addrlen; buflen -= addrlen; - /* And copy name - * REVISIT: Should the check not be (namelen + 1 > buflen)? - */ + /* And copy name */ namelen = strlen(name); - if (addrlen + namelen + 1 > buflen) + if ((namelen + 1) > buflen) { return -ERANGE; } -- GitLab From d35a060a4100e02054634912a6752baeacf34b94 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 12 Jun 2017 07:23:06 -0600 Subject: [PATCH 968/990] Revert "MTD: Fix problems in SPI locking in mp25x.c driver. Same problem probably in exists in several other drivers that derive from this this driver as well." This reverts commit 85645284b37b0ada1ba8208cb228f419c1c52190. --- drivers/mtd/m25px.c | 26 ++++++++------------------ 1 file changed, 8 insertions(+), 18 deletions(-) diff --git a/drivers/mtd/m25px.c b/drivers/mtd/m25px.c index c7b5c495ea..3b509eb6c5 100644 --- a/drivers/mtd/m25px.c +++ b/drivers/mtd/m25px.c @@ -432,7 +432,6 @@ static void m25p_waitwritecomplete(struct m25p_dev_s *priv) { /* Select this FLASH part */ - m25p_lock(priv->dev); SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Read Status Register (RDSR)" command */ @@ -446,7 +445,6 @@ static void m25p_waitwritecomplete(struct m25p_dev_s *priv) /* Deselect the FLASH */ SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); - m25p_unlock(priv->dev); /* Given that writing could take up to few tens of milliseconds, and erasing * could take more. The following short delay in the "busy" case will allow @@ -455,7 +453,9 @@ static void m25p_waitwritecomplete(struct m25p_dev_s *priv) if ((status & M25P_SR_WIP) != 0) { + m25p_unlock(priv->dev); usleep(1000); + m25p_lock(priv->dev); } } while ((status & M25P_SR_WIP) != 0); @@ -471,7 +471,6 @@ static void m25p_writeenable(struct m25p_dev_s *priv) { /* Select this FLASH part */ - m25p_lock(priv->dev); SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Write Enable (WREN)" command */ @@ -481,8 +480,6 @@ static void m25p_writeenable(struct m25p_dev_s *priv) /* Deselect the FLASH */ SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); - m25p_unlock(priv->dev); - finfo("Enabled\n"); } @@ -521,7 +518,6 @@ static void m25p_sectorerase(struct m25p_dev_s *priv, off_t sector, uint8_t type /* Select this FLASH part */ - m25p_lock(priv->dev); SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send the "Sector Erase (SE)" or Sub-Sector Erase (SSE) instruction @@ -542,8 +538,6 @@ static void m25p_sectorerase(struct m25p_dev_s *priv, off_t sector, uint8_t type /* Deselect the FLASH */ SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); - m25p_unlock(priv->dev); - finfo("Erased\n"); } @@ -569,7 +563,6 @@ static inline int m25p_bulkerase(struct m25p_dev_s *priv) /* Select this FLASH part */ - m25p_lock(priv->dev); SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send the "Bulk Erase (BE)" instruction */ @@ -579,8 +572,6 @@ static inline int m25p_bulkerase(struct m25p_dev_s *priv) /* Deselect the FLASH */ SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); - m25p_unlock(priv->dev); - finfo("Return: OK\n"); return OK; } @@ -610,7 +601,6 @@ static inline void m25p_pagewrite(struct m25p_dev_s *priv, FAR const uint8_t *bu /* Select this FLASH part */ - m25p_lock(priv->dev); SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Page Program (PP)" command */ @@ -630,8 +620,6 @@ static inline void m25p_pagewrite(struct m25p_dev_s *priv, FAR const uint8_t *bu /* Deselect the FLASH: Chip Select high */ SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); - m25p_unlock(priv->dev); - finfo("Written\n"); } @@ -659,7 +647,6 @@ static inline void m25p_bytewrite(struct m25p_dev_s *priv, FAR const uint8_t *bu /* Select this FLASH part */ - m25p_lock(priv->dev); SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Page Program (PP)" command */ @@ -679,8 +666,6 @@ static inline void m25p_bytewrite(struct m25p_dev_s *priv, FAR const uint8_t *bu /* Deselect the FLASH: Chip Select high */ SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); - m25p_unlock(priv->dev); - finfo("Written\n"); } #endif @@ -698,6 +683,7 @@ static int m25p_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblock /* Lock access to the SPI bus until we complete the erase */ + m25p_lock(priv->dev); while (blocksleft > 0) { #ifdef CONFIG_M25P_SUBSECTOR_ERASE @@ -747,6 +733,7 @@ static int m25p_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblock blocksleft--; } + m25p_unlock(priv->dev); return (int)nblocks; } @@ -788,6 +775,7 @@ static ssize_t m25p_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t n /* Lock the SPI bus and write each page to FLASH */ + m25p_lock(priv->dev); while (blocksleft-- > 0) { m25p_pagewrite(priv, buffer, startblock); @@ -795,6 +783,7 @@ static ssize_t m25p_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t n startblock++; } + m25p_unlock(priv->dev); return nblocks; } @@ -840,7 +829,6 @@ static ssize_t m25p_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes, SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); m25p_unlock(priv->dev); - finfo("return nbytes: %d\n", (int)nbytes); return nbytes; } @@ -973,7 +961,9 @@ static int m25p_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg) { /* Erase the entire device */ + m25p_lock(priv->dev); ret = m25p_bulkerase(priv); + m25p_unlock(priv->dev); } break; -- GitLab From 2851959dee2c5fc3a92e3288b433759764a0d2b0 Mon Sep 17 00:00:00 2001 From: Sebastien Lorquet Date: Mon, 12 Jun 2017 09:34:09 -0600 Subject: [PATCH 969/990] MTD M2PX: If we READ while a write/erase is pending, the command is ignored and the write/erase continues. If we dont catch this situation we will return garbage to the user because the flash will not execute the command. So READ MUST wait for write completion, and before that, the bus must be locked since it's a precondition to calling waitwritecomplete(). --- drivers/mtd/m25px.c | 12 +++++++++--- 1 file changed, 9 insertions(+), 3 deletions(-) diff --git a/drivers/mtd/m25px.c b/drivers/mtd/m25px.c index 3b509eb6c5..bac7fdb7c9 100644 --- a/drivers/mtd/m25px.c +++ b/drivers/mtd/m25px.c @@ -798,6 +798,12 @@ static ssize_t m25p_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes, finfo("offset: %08lx nbytes: %d\n", (long)offset, (int)nbytes); + /* Lock the SPI bus NOW because the following call must be executed with + * the bus locked. + */ + + m25p_lock(priv->dev); + /* Wait for any preceding write to complete. We could simplify things by * perform this wait at the end of each write operation (rather than at * the beginning of ALL operations), but have the wait first will slightly @@ -806,12 +812,11 @@ static ssize_t m25p_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes, m25p_waitwritecomplete(priv); - /* Lock the SPI bus and select this FLASH part */ + /* Select this FLASH part */ - m25p_lock(priv->dev); SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); - /* Send "Read from Memory " instruction */ + /* Send "Read from Memory" instruction */ (void)SPI_SEND(priv->dev, M25P_READ); @@ -829,6 +834,7 @@ static ssize_t m25p_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes, SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); m25p_unlock(priv->dev); + finfo("return nbytes: %d\n", (int)nbytes); return nbytes; } -- GitLab From 0a85a41678b119dab362281ea96951c0b8c1936f Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 12 Jun 2017 09:51:42 -0600 Subject: [PATCH 970/990] MTD FLASH driver: Clone Sebastien Lorquet's m25px change to at25, is25xp, ramtron, and sst25xx. --- drivers/mtd/at25.c | 9 +++++++-- drivers/mtd/is25xp.c | 10 ++++++++-- drivers/mtd/ramtron.c | 13 +++++++++---- drivers/mtd/sst25xx.c | 12 +++++++++--- drivers/mtd/w25.c | 1 + 5 files changed, 34 insertions(+), 11 deletions(-) diff --git a/drivers/mtd/at25.c b/drivers/mtd/at25.c index c499ca2a55..042734593d 100644 --- a/drivers/mtd/at25.c +++ b/drivers/mtd/at25.c @@ -524,6 +524,12 @@ static ssize_t at25_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes, finfo("offset: %08lx nbytes: %d\n", (long)offset, (int)nbytes); + /* Lock the SPI bus NOW because the following call must be executed with + * the bus locked. + */ + + at25_lock(priv->dev); + /* Wait for any preceding write to complete. We could simplify things by * perform this wait at the end of each write operation (rather than at * the beginning of ALL operations), but have the wait first will slightly @@ -532,9 +538,8 @@ static ssize_t at25_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes, at25_waitwritecomplete(priv); - /* Lock the SPI bus and select this FLASH part */ + /* Select this FLASH part */ - at25_lock(priv->dev); SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Read from Memory " instruction */ diff --git a/drivers/mtd/is25xp.c b/drivers/mtd/is25xp.c index 1d663a42bd..5ea9e8ae1a 100644 --- a/drivers/mtd/is25xp.c +++ b/drivers/mtd/is25xp.c @@ -749,6 +749,12 @@ static ssize_t is25xp_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbyte finfo("offset: %08lx nbytes: %d\n", (long)offset, (int)nbytes); + /* Lock the SPI bus NOW because the following call must be executed with + * the bus locked. + */ + + is25xp_lock(priv->dev); + /* Wait for any preceding write to complete. We could simplify things by * perform this wait at the end of each write operation (rather than at * the beginning of ALL operations), but have the wait first will slightly @@ -760,9 +766,8 @@ static ssize_t is25xp_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbyte is25xp_waitwritecomplete(priv); } - /* Lock the SPI bus and select this FLASH part */ + /* Select this FLASH part */ - is25xp_lock(priv->dev); SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Read from Memory " instruction */ @@ -783,6 +788,7 @@ static ssize_t is25xp_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbyte SPI_SELECT(priv->dev, SPIDEV_FLASH(0), false); is25xp_unlock(priv->dev); + finfo("return nbytes: %d\n", (int)nbytes); return nbytes; } diff --git a/drivers/mtd/ramtron.c b/drivers/mtd/ramtron.c index ee07d18e07..2216a475e5 100644 --- a/drivers/mtd/ramtron.c +++ b/drivers/mtd/ramtron.c @@ -532,8 +532,8 @@ static inline void ramtron_sendaddr(const struct ramtron_dev_s *priv, uint32_t a * Name: ramtron_pagewrite ************************************************************************************/ -static inline int ramtron_pagewrite(struct ramtron_dev_s *priv, FAR const uint8_t *buffer, - off_t page) +static inline int ramtron_pagewrite(struct ramtron_dev_s *priv, + FAR const uint8_t *buffer, off_t page) { off_t offset = page << priv->pageshift; @@ -663,6 +663,12 @@ static ssize_t ramtron_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbyt finfo("offset: %08lx nbytes: %d\n", (long)offset, (int)nbytes); + /* Lock the SPI bus NOW because the ramtron_waitwritecomplete call must be + * executed with the bus locked. + */ + + ramtron_lock(priv); + #ifndef CONFIG_RAMTRON_WRITEWAIT /* Wait for any preceding write to complete. We could simplify things by * perform this wait at the end of each write operation (rather than at @@ -673,9 +679,8 @@ static ssize_t ramtron_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbyt (void)ramtron_waitwritecomplete(priv); #endif - /* Lock the SPI bus and select this FLASH part */ + /* Select this FLASH part */ - ramtron_lock(priv); SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Read from Memory " instruction */ diff --git a/drivers/mtd/sst25xx.c b/drivers/mtd/sst25xx.c index a6e71f12e1..efd5385916 100644 --- a/drivers/mtd/sst25xx.c +++ b/drivers/mtd/sst25xx.c @@ -680,7 +680,8 @@ static ssize_t sst25xx_bread(FAR struct mtd_dev_s *dev, off_t startblock, size_t /* On this device, we can handle the block read just like the byte-oriented read */ - nbytes = sst25xx_read(dev, startblock << priv->pageshift, nblocks << priv->pageshift, buffer); + nbytes = sst25xx_read(dev, startblock << priv->pageshift, + nblocks << priv->pageshift, buffer); if (nbytes > 0) { return nbytes >> priv->pageshift; @@ -727,6 +728,12 @@ static ssize_t sst25xx_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbyt finfo("offset: %08lx nbytes: %d\n", (long)offset, (int)nbytes); + /* Lock the SPI bus NOW because the following conditional call to + * sst25xx_waitwritecomplete must be executed with the bus locked. + */ + + sst25xx_lock(priv->dev); + /* Wait for any preceding write to complete. We could simplify things by * perform this wait at the end of each write operation (rather than at * the beginning of ALL operations), but have the wait first will slightly @@ -738,9 +745,8 @@ static ssize_t sst25xx_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbyt sst25xx_waitwritecomplete(priv); } - /* Lock the SPI bus and select this FLASH part */ + /* Select this FLASH part */ - sst25xx_lock(priv->dev); SPI_SELECT(priv->dev, SPIDEV_FLASH(0), true); /* Send "Read from Memory " instruction */ diff --git a/drivers/mtd/w25.c b/drivers/mtd/w25.c index 6bf757d3ef..9fc0d754a5 100644 --- a/drivers/mtd/w25.c +++ b/drivers/mtd/w25.c @@ -1070,6 +1070,7 @@ static ssize_t w25_bread(FAR struct mtd_dev_s *dev, off_t startblock, size_t nbl { nbytes >>= W25_SECTOR512_SHIFT; } + #else nbytes = w25_read(dev, startblock << W25_PAGE_SHIFT, nblocks << W25_PAGE_SHIFT, buffer); if (nbytes > 0) -- GitLab From f6ba4642a310f2b903ad77eb302cea5de0d7c8f2 Mon Sep 17 00:00:00 2001 From: raiden00pl Date: Mon, 12 Jun 2017 18:45:58 +0200 Subject: [PATCH 971/990] stm32_hrtim: GPIOs configuration + EEV and FAULT strucutres --- arch/arm/src/stm32/stm32_hrtim.c | 312 ++++++++++++++++++++++++++++++- arch/arm/src/stm32/stm32_hrtim.h | 20 ++ 2 files changed, 330 insertions(+), 2 deletions(-) diff --git a/arch/arm/src/stm32/stm32_hrtim.c b/arch/arm/src/stm32/stm32_hrtim.c index aef00eaba6..a99f37fc5f 100644 --- a/arch/arm/src/stm32/stm32_hrtim.c +++ b/arch/arm/src/stm32/stm32_hrtim.c @@ -144,6 +144,24 @@ # define HRTIM_HAVE_CHOPPER 1 #endif +#if defined(CONFIG_STM32_HRTIM_SCOUT) || defined(CONFIG_STM32_HRTIM_SCIN) +# define HRTIM_HAVE_SYNC 1 +#endif + +#if defined(CONFIG_STM32_HRTIM_FAULT1) || defined(CONFIG_STM32_HRTIM_FAULT2) || \ + defined(CONFIG_STM32_HRTIM_FAULT3) || defined(CONFIG_STM32_HRTIM_FAULT4) || \ + defined(CONFIG_STM32_HRTIM_FAULT5) +# define HRTIM_HAVE_FAULTS 1 +#endif + +#if defined(CONFIG_STM32_HRTIM_EEV1) || defined(CONFIG_STM32_HRTIM_EEV2) || \ + defined(CONFIG_STM32_HRTIM_EEV3) || defined(CONFIG_STM32_HRTIM_EEV4) || \ + defined(CONFIG_STM32_HRTIM_EEV5) || defined(CONFIG_STM32_HRTIM_EEV6) || \ + defined(CONFIG_STM32_HRTIM_EEV7) || defined(CONFIG_STM32_HRTIM_EEV8) || \ + defined(CONFIG_STM32_HRTIM_EEV9) || defined(CONFIG_STM32_HRTIM_EEV10) +# define HRTIM_HAVE_EEV 1 +#endif + /**************************************************************************** * Private Types ****************************************************************************/ @@ -242,6 +260,92 @@ struct stm32_hrtim_slave_priv_s #endif }; +#ifdef HRTIM_HAVE_FAULTS + +/* Structure describes single HRTIM Fault configuration */ + +struct stm32_hrtim_fault_cfg_s +{ + uint8_t pol:1; /* Fault poalrity */ + uint8_t src:1; /* Fault source */ + uint8_t filter:4; /* Fault filter */ + uint8_t flts:1; /* Fault Sampling clock division */ + uint8_t lock:1; /* Fault lock */ +}; + +/* Structure describes HRTIM Faults configuration */ + +struct stm32_hrtim_faults_s +{ +#ifdef CONFIG_STM32_HRTIM_FAULT1 + struct stm32_hrtim_fault_cfg_s flt1; +#endif +#ifdef CONFIG_STM32_HRTIM_FAULT2 + struct stm32_hrtim_fault_cfg_s flt2; +#endif +#ifdef CONFIG_STM32_HRTIM_FAULT3 + struct stm32_hrtim_fault_cfg_s flt3; +#endif +#ifdef CONFIG_STM32_HRTIM_FAULT4 + struct stm32_hrtim_fault_cfg_s flt4; +#endif +#ifdef CONFIG_STM32_HRTIM_FAULT5 + struct stm32_hrtim_fault_cfg_s flt5; +#endif +}; +#endif + +#ifdef HRTIM_HAVE_EEV + +/* Structure describes single HRTIM External Event configuration */ + +struct stm32_hrtim_eev_cfg_s +{ + uint8_t filter:4; /* External Event filter */ + uint8_t src:4; /* External Event source */ + uint8_t pol:1; /* External Event polarity */ + uint8_t sen:1; /* External Event sensivity */ + uint8_t mode:1; /* External Event mode */ + uint8_t _res:5; +}; + +/* Structure describes HRTIM External Events configuration */ + +struct stm32_hrtim_eev_s +{ +#ifdef CONFIG_STM32_HRTIM_EEV1 + struct stm32_hrtim_eev_cfg_s eev1; +#endif +#ifdef CONFIG_STM32_HRTIM_EEV2 + struct stm32_hrtim_eev_cfg_s eev2; +#endif +#ifdef CONFIG_STM32_HRTIM_EEV3 + struct stm32_hrtim_eev_cfg_s eev3; +#endif +#ifdef CONFIG_STM32_HRTIM_EEV4 + struct stm32_hrtim_eev_cfg_s eev4; +#endif +#ifdef CONFIG_STM32_HRTIM_EEV5 + struct stm32_hrtim_eev_cfg_s eev5; +#endif +#ifdef CONFIG_STM32_HRTIM_EEV6 + struct stm32_hrtim_eev_cfg_s eev6; +#endif +#ifdef CONFIG_STM32_HRTIM_EEV7 + struct stm32_hrtim_eev_cfg_s eev7; +#endif +#ifdef CONFIG_STM32_HRTIM_EEV8 + struct stm32_hrtim_eev_cfg_s eev8; +#endif +#ifdef CONFIG_STM32_HRTIM_EEV9 + struct stm32_hrtim_eev_cfg_s eev9; +#endif +#ifdef CONFIG_STM32_HRTIM_EEV10 + struct stm32_hrtim_eev_cfg_s eev10; +#endif +}; +#endif + /* This structure describes the configuration of HRTIM device */ struct stm32_hrtim_s @@ -263,6 +367,12 @@ struct stm32_hrtim_s #ifdef CONFIG_STM32_HRTIM_TIME struct stm32_hrtim_tim_s *time; /* HRTIM Timer E */ #endif +#ifdef HRTIM_HAVE_FAULTS + struct stm32_hrtim_faults_s *flt; +#endif +#ifdef HRTIM_HAVE_EEV + struct stm32_hrtim_eev_s *eev; +#endif }; /**************************************************************************** @@ -423,6 +533,23 @@ static struct stm32_hrtim_tim_s g_tima = #endif +/* Faults data */ +#ifdef HRTIM_HAVE_FAULTS +struct stm32_hrtim_faults_s g_flt = +{ +#warning "missing faults data" +}; +#endif + +/* External Events data */ + +#ifdef HRTIM_HAVE_EEV +struct stm32_hrtim_eev_s g_eev = +{ +#warning "missing eev data" +}; +#endif + /* HRTIM1 private data */ static struct stm32_hrtim_s g_hrtim1priv = @@ -444,6 +571,12 @@ static struct stm32_hrtim_s g_hrtim1priv = #ifdef CONFIG_STM32_HRTIM_TIME .time = &g_time, #endif +#ifdef HRTIM_HAVE_FAULTS + .flt = &g_flt; +#endif +#ifdef HRTIM_HAVE_EEV + .flt = &g_eev; +#endif }; struct hrtim_dev_s g_hrtim1dev = @@ -926,7 +1059,6 @@ errout: return ret; } - /**************************************************************************** * Name: stm32_tim_clocks_config * @@ -1024,7 +1156,183 @@ errout: #if defined(HRTIM_HAVE_CAPTURE) || defined(HRTIM_HAVE_PWM) || defined(HRTIM_HAVE_SYNC) static int hrtim_gpios_config(FAR struct stm32_hrtim_s *priv) { -#warning "hrtim_gpios_config: missing logic" +#ifdef HRTIM_HAVE_EEV + FAR struct stm32_hrtim_eev_s* eev = priv->eev; +#endif +#ifdef HRTIM_HAVE_FAULTS + FAR struct stm32_hrtim_faults_s* flt = priv->flt; +#endif + + /* Configure Timer A Outputs */ + +#ifdef CONFIG_STM32_HRTIM_TIMA_PWM_CH1 + stm32_configgpio(GPIO_HRTIM1_CHA1); +#endif + +#ifdef CONFIG_STM32_HRTIM_TIMA_PWM_CH2 + stm32_configgpio(GPIO_HRTIM1_CHA2); +#endif + + /* Configure Timer B Outputs */ + +#ifdef CONFIG_STM32_HRTIM_TIMB_PWM_CH1 + stm32_configgpio(GPIO_HRTIM1_CHB1); +#endif + +#ifdef CONFIG_STM32_HRTIM_TIMB_PWM_CH2 + stm32_configgpio(GPIO_HRTIM1_CHB2); +#endif + + /* Configure Timer C Outputs */ + +#ifdef CONFIG_STM32_HRTIM_TIMC_PWM_CH1 + stm32_configgpio(GPIO_HRTIM1_CHC1); +#endif + +#ifdef CONFIG_STM32_HRTIM_TIMC_PWM_CH2 + stm32_configgpio(GPIO_HRTIM1_CHC2); +#endif + + /* Configure Timer D Outputs */ + +#ifdef CONFIG_STM32_HRTIM_TIMD_PWM_CH1 + stm32_configgpio(GPIO_HRTIM1_CHD1); +#endif + +#ifdef CONFIG_STM32_HRTIM_TIMD_PWM_CH2 + stm32_configgpio(GPIO_HRTIM1_CHD2); +#endif + + /* Configure Timer E Outputs */ + +#ifdef CONFIG_STM32_HRTIM_TIME_PWM_CH1 + stm32_configgpio(GPIO_HRTIM1_CHE1); +#endif + +#ifdef CONFIG_STM32_HRTIM_TIME_PWM_CH2 + stm32_configgpio(GPIO_HRTIM1_CHE2); +#endif + /* Configure SCOUT */ + +#ifdef CONFIG_STM32_HRTIM_SCOUT + stm32_configgpio(GPIO_HRTIM1_SCOUT); +#endif + + /* Configure SCIN */ + +#ifdef CONFIG_STM32_HRTIM_SCIN + stm32_configgpio(GPIO_HRTIM1_SCIN); +#endif + + /* Configure Faults Inputs */ + +#ifdef CONFIG_STM32_HRTIM_FAULT1 + if (flt->flt1.src == HRTIM_FAULT_PIN) + { + stm32_configgpio(GPIO_HRTIM1_FLT1); + } +#endif + +#ifdef CONFIG_STM32_HRTIM_FAULT2 + if (flt->flt2.src == HRTIM_FAULT_PIN) + { + stm32_configgpio(GPIO_HRTIM1_FLT2); + } +#endif + +#ifdef CONFIG_STM32_HRTIM_FAULT3 + if (flt->flt3.src == HRTIM_FAULT_PIN) + { + stm32_configgpio(GPIO_HRTIM1_FLT3); + } +#endif + +#ifdef CONFIG_STM32_HRTIM_FAULT4 + if (flt->flt4.src == HRTIM_FAULT_PIN) + { + stm32_configgpio(GPIO_HRTIM1_FLT4); + } +#endif + +#ifdef CONFIG_STM32_HRTIM_FAULT5 + if (flt->flt5.src == HRTIM_FAULT_PIN) + { + stm32_configgpio(GPIO_HRTIM1_FLT5); + } +#endif + + /* Configure External Events Inputs */ + +#ifdef CONFIG_STM32_HRTIM_EEV1 + if (eev->eev1.src == HRTIM_EEV_SRC_PIN) + { + stm32_configgpio(GPIO_HRTIM1_EEV1); + } +#endif + +#ifdef CONFIG_STM32_HRTIM_EEV2 + if (eev->eev2.src == HRTIM_EEV_SRC_PIN) + { + stm32_configgpio(GPIO_HRTIM1_EEV2); + } +#endif + +#ifdef CONFIG_STM32_HRTIM_EEV3 + if (eev->eev3.src == HRTIM_EEV_SRC_PIN) + { + stm32_configgpio(GPIO_HRTIM1_EEV3); + } +#endif + +#ifdef CONFIG_STM32_HRTIM_EEV4 + if (eev->eev4.src == HRTIM_EEV_SRC_PIN) + { + stm32_configgpio(GPIO_HRTIM1_EEV4); + } +#endif + +#ifdef CONFIG_STM32_HRTIM_EEV5 + if (eev->eev5.src == HRTIM_EEV_SRC_PIN) + { + stm32_configgpio(GPIO_HRTIM1_EEV5); + } +#endif + +#ifdef CONFIG_STM32_HRTIM_EEV6 + if (eev->eev6.src == HRTIM_EEV_SRC_PIN) + { + stm32_configgpio(GPIO_HRTIM1_EEV6); + } +#endif + +#ifdef CONFIG_STM32_HRTIM_EEV7 + if (eev->eev7.src == HRTIM_EEV_SRC_PIN) + { + stm32_configgpio(GPIO_HRTIM1_EEV7); + } +#endif + +#ifdef CONFIG_STM32_HRTIM_EEV8 + if (eev->eev8.src == HRTIM_EEV_SRC_PIN) + { + stm32_configgpio(GPIO_HRTIM1_EEV8); + } +#endif + +#ifdef CONFIG_STM32_HRTIM_EEV9 + if (eev->eev9.src == HRTIM_EEV_SRC_PIN) + { + stm32_configgpio(GPIO_HRTIM1_EEV9); + } +#endif + +#ifdef CONFIG_STM32_HRTIM_EEV10 + if (eev->eev10.src == HRTIM_EEV_SRC_PIN) + { + stm32_configgpio(GPIO_HRTIM1_EEV10); + } +#endif + return OK; } #endif diff --git a/arch/arm/src/stm32/stm32_hrtim.h b/arch/arm/src/stm32/stm32_hrtim.h index e4fe9be912..e20d71e630 100644 --- a/arch/arm/src/stm32/stm32_hrtim.h +++ b/arch/arm/src/stm32/stm32_hrtim.h @@ -222,6 +222,26 @@ enum stm32_hrtim_tim_prescaler_e HRTIM_PRESCALER_128, }; +/* HRTIM Fault Source */ + +enum stm32_hrtim_fault_src_e +{ + HRTIM_FAULT_SRC_PIN, + HRTIM_FAULT_SRC_INTERNAL +}; + +/* HRTIM External Event Source + * NOTE: according to Table 82 from STM32F334XX Manual + */ + +enum stm32_hrtim_eev_src_e +{ + HRTIM_EEV_SRC_PIN, + HRTIM_EEV_SRC_ANALOG, + HRTIM_EEV_SRC_TRGO, + HRTIM_EEV_SRC_ADC +}; + struct hrtim_dev_s { #ifdef CONFIG_HRTIM -- GitLab From 7903a8a46ca0a9eab10eb0fef20427fe48d69043 Mon Sep 17 00:00:00 2001 From: JM Date: Tue, 13 Jun 2017 06:01:13 -0600 Subject: [PATCH 972/990] stm32/stm32l4 PWM: While attempting to output a 70 MHz square wave from the timer output of a STM32 clocked at 140 MHz (which works fine in baremetal C), I stumbled on what I believe to be an error in arch/arm/src/stm32/stm32_pwm.c. Line 1304 we are told that reload = timclk / info->frequency; which I belive to be incorrect, it should be reload = timclk / info->frequency - 1; since starting to count from 0, if I want to output half of the TIM clock, I must count to 1 and not to 2. Surely enough, the original code did output 140/3=47 MHz, while this correction does allow the output up to 70 MHz. I am not sure this affects most users generating slow PWM (e.g. PX4) but for frequencies close to the PCLK, indeed the difference becomes significant. --- arch/arm/src/stm32/stm32_pwm.c | 2 +- arch/arm/src/stm32l4/stm32l4_pwm.c | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/arch/arm/src/stm32/stm32_pwm.c b/arch/arm/src/stm32/stm32_pwm.c index 85ed3554fc..48640f9869 100644 --- a/arch/arm/src/stm32/stm32_pwm.c +++ b/arch/arm/src/stm32/stm32_pwm.c @@ -1300,7 +1300,7 @@ static int pwm_timer(FAR struct stm32_pwmtimer_s *priv, timclk = priv->pclk / prescaler; - reload = timclk / info->frequency; + reload = timclk / info->frequency - 1; if (reload < 1) { reload = 1; diff --git a/arch/arm/src/stm32l4/stm32l4_pwm.c b/arch/arm/src/stm32l4/stm32l4_pwm.c index fe46e8cc4e..3c0c8dab18 100644 --- a/arch/arm/src/stm32l4/stm32l4_pwm.c +++ b/arch/arm/src/stm32l4/stm32l4_pwm.c @@ -841,7 +841,7 @@ static int stm32l4pwm_timer(FAR struct stm32l4_pwmtimer_s *priv, timclk = priv->pclk / prescaler; - reload = timclk / info->frequency; + reload = timclk / info->frequency - 1; if (reload < 1) { reload = 1; -- GitLab From e379491d138b3da52970b2a81df13ab85ebbdbc5 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 13 Jun 2017 07:05:46 -0600 Subject: [PATCH 973/990] STM32/STM32L4: Review of last commit -- Eliminate possible underflow --- arch/arm/src/stm32/stm32_pwm.c | 8 ++++++-- arch/arm/src/stm32l4/stm32l4_pwm.c | 8 ++++++-- 2 files changed, 12 insertions(+), 4 deletions(-) diff --git a/arch/arm/src/stm32/stm32_pwm.c b/arch/arm/src/stm32/stm32_pwm.c index 48640f9869..8f66239a11 100644 --- a/arch/arm/src/stm32/stm32_pwm.c +++ b/arch/arm/src/stm32/stm32_pwm.c @@ -1300,8 +1300,8 @@ static int pwm_timer(FAR struct stm32_pwmtimer_s *priv, timclk = priv->pclk / prescaler; - reload = timclk / info->frequency - 1; - if (reload < 1) + reload = timclk / info->frequency; + if (reload < 2) { reload = 1; } @@ -1309,6 +1309,10 @@ static int pwm_timer(FAR struct stm32_pwmtimer_s *priv, { reload = 65535; } + else + { + reload--; + } pwminfo("TIM%u PCLK: %u frequency: %u TIMCLK: %u prescaler: %u reload: %u\n", priv->timid, priv->pclk, info->frequency, timclk, prescaler, reload); diff --git a/arch/arm/src/stm32l4/stm32l4_pwm.c b/arch/arm/src/stm32l4/stm32l4_pwm.c index 3c0c8dab18..71c4f1dad2 100644 --- a/arch/arm/src/stm32l4/stm32l4_pwm.c +++ b/arch/arm/src/stm32l4/stm32l4_pwm.c @@ -841,8 +841,8 @@ static int stm32l4pwm_timer(FAR struct stm32l4_pwmtimer_s *priv, timclk = priv->pclk / prescaler; - reload = timclk / info->frequency - 1; - if (reload < 1) + reload = timclk / info->frequency; + if (reload < 2) { reload = 1; } @@ -850,6 +850,10 @@ static int stm32l4pwm_timer(FAR struct stm32l4_pwmtimer_s *priv, { reload = 65535; } + else + { + reload--; + } pwminfo("TIM%u PCLK: %u frequency: %u TIMCLK: %u prescaler: %u reload: %u\n", priv->timid, priv->pclk, info->frequency, timclk, prescaler, reload); -- GitLab From 2596b14c90e168ce4c727e8642ae20bf5a88f2b4 Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Tue, 13 Jun 2017 07:33:34 -0600 Subject: [PATCH 974/990] mtd/w25: add missing locking and fix SPI_SELECT usage for w25_unprotect --- drivers/mtd/w25.c | 14 ++++++++------ 1 file changed, 8 insertions(+), 6 deletions(-) diff --git a/drivers/mtd/w25.c b/drivers/mtd/w25.c index 9fc0d754a5..0648306ec8 100644 --- a/drivers/mtd/w25.c +++ b/drivers/mtd/w25.c @@ -440,19 +440,16 @@ static inline int w25_readid(struct w25_dev_s *priv) #ifndef CONFIG_W25_READONLY static void w25_unprotect(FAR struct w25_dev_s *priv) { - /* Select this FLASH part */ + /* Lock and configure the SPI bus */ - SPI_SELECT(priv->spi, SPIDEV_FLASH(0), true); + w25_lock(priv->spi); /* Send "Write enable (WREN)" */ w25_wren(priv); - /* Re-select this FLASH part (This might not be necessary... but is it shown in - * the SST25 timing diagrams from which this code was leveraged.) - */ + /* Select this FLASH part */ - SPI_SELECT(priv->spi, SPIDEV_FLASH(0), false); SPI_SELECT(priv->spi, SPIDEV_FLASH(0), true); /* Send "Write enable status (EWSR)" */ @@ -463,6 +460,11 @@ static void w25_unprotect(FAR struct w25_dev_s *priv) SPI_SEND(priv->spi, 0); SPI_SEND(priv->spi, 0); + + /* Deselect the FLASH and unlock the bus */ + + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), false); + w25_unlock(priv->spi); } #endif -- GitLab From 7b8df1b930295094932a77657509022b0d980be1 Mon Sep 17 00:00:00 2001 From: Jussi Kivilinna Date: Tue, 13 Jun 2017 07:35:49 -0600 Subject: [PATCH 975/990] mtd/w25: wait for BUSY flag to clear in w25_readid and w25_unprotect. W25Q128 datasheet says that all instructions expect 'Read Status Register' and 'Erase/Program Suspend' are ignored when BUSY flag in status register is '1'. Therefore wait for busy flag to clear in w25_readid() and w25_unprotect(). --- drivers/mtd/w25.c | 19 +++++++++++++++++-- 1 file changed, 17 insertions(+), 2 deletions(-) diff --git a/drivers/mtd/w25.c b/drivers/mtd/w25.c index 0648306ec8..25f263f0ac 100644 --- a/drivers/mtd/w25.c +++ b/drivers/mtd/w25.c @@ -337,9 +337,16 @@ static inline int w25_readid(struct w25_dev_s *priv) finfo("priv: %p\n", priv); - /* Lock the SPI bus, configure the bus, and select this FLASH part. */ + /* Lock and configure the SPI bus */ w25_lock(priv->spi); + + /* Wait for any preceding write or erase operation to complete. */ + + (void)w25_waitwritecomplete(priv); + + /* Select this FLASH part. */ + SPI_SELECT(priv->spi, SPIDEV_FLASH(0), true); /* Send the "Read ID (RDID)" command and read the first three ID bytes */ @@ -444,6 +451,10 @@ static void w25_unprotect(FAR struct w25_dev_s *priv) w25_lock(priv->spi); + /* Wait for any preceding write or erase operation to complete. */ + + (void)w25_waitwritecomplete(priv); + /* Send "Write enable (WREN)" */ w25_wren(priv); @@ -476,7 +487,11 @@ static uint8_t w25_waitwritecomplete(struct w25_dev_s *priv) { uint8_t status; - /* Loop as long as the memory is busy with a write cycle */ + /* Loop as long as the memory is busy with a write cycle. Device sets BUSY + * flag to a 1 state whhen previous write or erase command is still executing + * and during this time, device will ignore further instructions except for + * "Read Status Register" and "Erase/Program Suspend" instructions. + */ do { -- GitLab From 48fb789cf340e0b0c99006c0024ed6e29b067615 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Sat, 10 Jun 2017 06:12:37 -1000 Subject: [PATCH 976/990] testbuild:Added -x to fail build on errors for CI On CI we want to know ASAP of a failure. This adds the -x (exit on build failures) option to faclitate that behavior. Use ${MAKE} ${MAKE_FLAGS} for make invocation. When -x is provided change MAKE_FLAGS to --silent --no-print-directory and set -e Ignore exit status when using grep for checking for CONFIG_NXWM=y --- tools/testbuild.sh | 27 +++++++++++++++++---------- 1 file changed, 17 insertions(+), 10 deletions(-) diff --git a/tools/testbuild.sh b/tools/testbuild.sh index 7e67b06137..a625f3d8a8 100755 --- a/tools/testbuild.sh +++ b/tools/testbuild.sh @@ -43,6 +43,8 @@ wenv=cygwin sizet=uint APPSDIR=../apps NXWDIR=../NxWidgets +MAKE_FLAGS=-i +MAKE=make unset testfile function showusage { @@ -58,6 +60,7 @@ function showusage { echo " -a provides the relative path to the apps/ directory. Default ../apps" echo " -n provides the relative path to the NxWidgets/ directory. Default ../NxWidgets" echo " -d enables script debug output" + echo " -x exit on build failures" echo " -h will show this help test and terminate" echo " selects the list of configurations to test. No default" echo "" @@ -96,6 +99,10 @@ while [ ! -z "$1" ]; do host=windows sizet=long ;; + -x ) + MAKE_FLAGS='--silent --no-print-directory' + set -e + ;; -a ) shift APPSDIR="$1" @@ -142,7 +149,7 @@ function distclean { cd $nuttx || { echo "ERROR: failed to CD to $nuttx"; exit 1; } if [ -f .config ]; then echo " Cleaning..." - make distclean 1>/dev/null + ${MAKE} ${MAKE_FLAGS} distclean 1>/dev/null fi } @@ -225,7 +232,7 @@ function configure { echo " Refreshing..." cd $nuttx || { echo "ERROR: failed to CD to $nuttx"; exit 1; } - make olddefconfig 1>/dev/null 2>&1 + ${MAKE} ${MAKE_FLAGS} olddefconfig 1>/dev/null 2>&1 } # Build the NxWidgets libraries @@ -237,7 +244,7 @@ function nxbuild { unset nxconfig if [ -d $NXWDIR ]; then - nxconfig=`grep CONFIG_NXWM=y $nuttx/.config` + nxconfig=`grep CONFIG_NXWM=y $nuttx/.config` || true fi if [ ! -z "$nxconfig" ]; then @@ -247,18 +254,18 @@ function nxbuild { cd $nuttx/$NXTOOLS || { echo "Failed to CD to $NXTOOLS"; exit 1; } ./install.sh $nuttx/$APPSDIR nxwm 1>/dev/null - make -C $nuttx/$APPSDIR/external TOPDIR=$nuttx APPDIR=$nuttx/$APPSDIR TOPDIR=$nuttx clean 1>/dev/null + ${MAKE} ${MAKE_FLAGS} -C $nuttx/$APPSDIR/external TOPDIR=$nuttx APPDIR=$nuttx/$APPSDIR TOPDIR=$nuttx clean 1>/dev/null cd $nuttx || { echo "Failed to CD to $nuttx"; exit 1; } - make -i context 1>/dev/null + ${MAKE} ${MAKE_FLAGS} context 1>/dev/null cd $nuttx/$NXWIDGETSDIR || { echo "Failed to CD to $NXWIDGETSDIR"; exit 1; } - make -i TOPDIR=$nuttx clean 1>/dev/null - make -i TOPDIR=$nuttx 1>/dev/null + ${MAKE} ${MAKE_FLAGS} TOPDIR=$nuttx clean 1>/dev/null + ${MAKE} ${MAKE_FLAGS} TOPDIR=$nuttx 1>/dev/null cd $nuttx/$NXWMDIR || { echo "Failed to CD to $NXWMDIR"; exit 1; } - make -i TOPDIR=$nuttx clean 1>/dev/null - make -i TOPDIR=$nuttx 1>/dev/null + ${MAKE} ${MAKE_FLAGS} TOPDIR=$nuttx clean 1>/dev/null + ${MAKE} ${MAKE_FLAGS} TOPDIR=$nuttx 1>/dev/null fi } @@ -268,7 +275,7 @@ function build { cd $nuttx || { echo "ERROR: failed to CD to $nuttx"; exit 1; } echo " Building NuttX..." echo "------------------------------------------------------------------------------------" - make -i 1>/dev/null + ${MAKE} ${MAKE_FLAGS} 1>/dev/null } # Coordinate the steps for the next build test -- GitLab From 466fccc494a9bd48111d549a1f4caf6ccb1d0a70 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 13 Jun 2017 17:39:38 -0600 Subject: [PATCH 977/990] NSH Documentation: A justification for 3 ENTERs when using USB serial console. --- Documentation/NuttShell.html | 103 ++++++++++++++++++++++------------- 1 file changed, 65 insertions(+), 38 deletions(-) diff --git a/Documentation/NuttShell.html b/Documentation/NuttShell.html index 5ee579995f..dae6f3019f 100644 --- a/Documentation/NuttShell.html +++ b/Documentation/NuttShell.html @@ -8,7 +8,7 @@

      NuttShell (NSH)

      -

      Last Updated: June 6, 2017

      +

      Last Updated: June 13, 2017

      @@ -305,7 +305,7 @@
      - 2.37 Create a FAT Filesystem (mkfatfs) + 2.37 Create a FAT File System (mkfatfs) @@ -335,7 +335,7 @@
      - 2.42 Mount an NFS file system (nfsmount) + 2.42 Mount an NFS File System (nfsmount) @@ -619,9 +619,35 @@ NuttShell (NSH) nsh> - The greating may also include NuttX versioning information if you are using a versioned copy of NuttX. + The greeting may also include NuttX versioning information if you are using a versioned copy of NuttX. nsh> is the NSH prompt and indicates that you may enter a command from the console.

      +

      + USB console startup. + When using a USB console, the start-up sequence differs a little: In this case, you are required to press ENTER three times. Then NSH prompt will appear as described above. + This is required for the following reasons: +

      +
        +
      1. + This assures that the USB connection is stable. + The USB connection may be made, broken, and re-established a few times if the USB cable is not yet fully seated. + Waiting for ENTER to be pressed three times assures that the connection is stable. +
      2. +
      3. + The establishment of the connection is two step process: First, the USB serial connection is made with the host PC. Then the application that uses the serial interface is started on the host. + When the serial connection is established on the host, the host operating system may send several AT modem commands to the host depending upon how the host serial port is configured. + By waiting for ENTER to be pressed three consecutive times, all of these modem commands will go to the bit-bucket and will not be interpreted as NSH command input. +
      4. +
      5. + Similarly, in the second step when the applications is started, there may be additional AT modem commands sent out the serial port. + Most serial terminal programs will do this unless they are specifically configured to suppress the modem command output. + Waiting for the ENTER input eliminates the invalid command errors from both (2) and (3). +
      6. +
      7. + Finally, if NSH did not wait for some positive indication that the serial terminal program is up and running, then the output of the NSH greeting and initial NSH prompt would be lost. +
      8. +
      +

      Extended Command Line Editing. By default, NuttX uses a simple command line editor that allows command entry after the nsh> and supports only the backspace key for editing. @@ -752,7 +778,7 @@ nsh> <file> is the full or relative path to any writable object - in the filesystem name space (file or character driver). + in the file system name space (file or character driver). Such objects will be referred to simply as files throughout this document. @@ -968,7 +994,7 @@ done

      • NSH will create a read-only RAM disk (a ROM disk), containing a tiny - ROMFS filesystem containing the following: + ROMFS file system containing the following:
           `--init.d/
                `-- rcS
          @@ -976,7 +1002,7 @@ done
                 Where rcS is the NSH start-up script.
               
               
        • - NSH will then mount the ROMFS filesystem at /etc, resulting in: + NSH will then mount the ROMFS file system at /etc, resulting in:
             |--dev/
             |   `-- ram0
            @@ -1352,7 +1378,7 @@ cp <source-path> <dest-path>
             

            Synopsis. Copy of the contents of the file at <source-path> to the location - in the filesystem indicated by <dest-path>. + in the file system indicated by <dest-path>.

            @@ -1726,7 +1752,7 @@ ifconfig [nic_name [<ip-address>|dhcp]] [dr|gw|gateway <dr-address>]
          • With one or no arguments, ifconfig will shows the - current configuration of the network and, perhaps, the status of ethernet + current configuration of the network and, perhaps, the status of Ethernet device:

              @@ -1749,7 +1775,7 @@ eth0    HWaddr 00:18:11:80:10:06
                 
            • If both the network interface name and an IP address are supplied as arguments, - then ifconfig will set the address of the ethernet device: + then ifconfig will set the address of the Ethernet device:

                 ifconfig nic_name ip_address
                @@ -1970,7 +1996,7 @@ ln [-s] <target> <link>
                   This implementation is simplified for use with NuttX in these ways:
                 

                  -
                • Links may be created only within the NuttX top-level, pseudo filesystem. +
                • Links may be created only within the NuttX top-level, pseudo file system. No file system currently supported by NuttX provides symbolic links.
                • For the same reason, only soft links are implemented.
                • File privileges are ignored.
                • @@ -1992,7 +2018,7 @@ ls [-lRs] <dir-path>

                  Synopsis. Show the contents of the directory at <dir-path>. NOTE: - <dir-path> must refer to a directory and no other filesystem + <dir-path> must refer to a directory and no other file system object.

                  Options:

                  @@ -2172,10 +2198,10 @@ mkdir <path>

                  Limited to Mounted File Systems. - Recall that NuttX uses a pseudo filesystem for its root file + Recall that NuttX uses a pseudo file system for its root file system. The mkdir command can only be used to create directories in volumes set up with the - mount command; it cannot be used to create directories in the pseudo filesystem. + mount command; it cannot be used to create directories in the pseudo file system.

                  Example:

                    @@ -2190,7 +2216,7 @@ nsh>
                     
          • -

            2.37 Create a FAT Filesystem (mkfatfs)

            +

            2.37 Create a FAT File System (mkfatfs)

            @@ -2208,7 +2234,7 @@ mkfatfs [-F <fatsize>] <block-driver>

            NSH provides this command to access the mkfatfs() NuttX API. - This block device must reside in the NuttX pseudo filesystem and + This block device must reside in the NuttX pseudo file system and must have been created by some call to register_blockdriver() (see include/nuttx/fs/fs.h).

            @@ -2323,22 +2349,22 @@ mount -t <fstype> [-o <options>] <block-device> <dir- mount performs a three way association, binding:

              -
            1. File system. +
            2. File System. The '-t <fstype>' option identifies the type of file system that has been formatted on the <block-device>. As of this writing, vfat is the only supported value for <fstype>
            3. Block Device. The <block-device> argument is the full or relative - path to a block driver inode in the pseudo filesystem. + path to a block driver inode in the pseudo file system. By convention, this is a name under the /dev sub-directory. This <block-device> must have been previously formatted with the same file system type as specified by <fstype>
            4. Mount Point. The mount point, <dir-path>, is the location in the - pseudo filesystem where the mounted volume will appear. - This mount point can only reside in the NuttX pseudo filesystem. + pseudo file system where the mounted volume will appear. + This mount point can only reside in the NuttX pseudo file system. By convention, this mount point is a subdirectory under /mnt. The mount command will create whatever pseudo directories that may be needed to complete the full path but the full path must not already exist. @@ -2346,7 +2372,7 @@ mount -t <fstype> [-o <options>] <block-device> <dir-

            After the volume has been mounted in the NuttX - pseudo filesystem, + pseudo file system, it may be access in the same way as other objects in the file system.

            Examples:

            @@ -2395,7 +2421,7 @@ mv <old-path> <new-path>

            Synopsis. Rename the file object at <old-path> to <new-path>. - Both paths must reside in the same mounted filesystem. + Both paths must reside in the same mounted file system.

            @@ -2628,11 +2654,11 @@ rm <file-path>

            Synopsis. Remove the specified <file-path> name from the mounted file system. - Recall that NuttX uses a pseudo filesystem for its root file + Recall that NuttX uses a pseudo file system for its root file system. The rm command can only be used to remove (unlink) files in volumes set up with the mount command; - it cannot be used to remove names in the pseudo filesystem. + it cannot be used to remove names in the pseudo file system.

            Example:

              @@ -2662,11 +2688,11 @@ rmdir <dir-path>
               

              Synopsis. Remove the specified <dir-path> directory from the mounted file system. - Recall that NuttX uses a pseudo filesystem for its root file + Recall that NuttX uses a pseudo file system for its root file system. The rmdir command can only be used to remove directories from volumes set up with the mount command; - it cannot be used to remove directories from the pseudo filesystem. + it cannot be used to remove directories from the pseudo file system.

              Example:

                @@ -3563,11 +3589,11 @@ nsh>
                   creation of files for the correct operation of the put command.
                3 CONFIG_FS_READABLE is not a user configuration but is set automatically - if any readable filesystem is selected. At present, this is either CONFIG_FS_FAT + if any readable file system is selected. At present, this is either CONFIG_FS_FAT or CONFIG_FS_ROMFS.
                4 CONFIG_FS_WRITABLE is not a user configuration but is set automatically - if any writable filesystem is selected. At present, this is only CONFIG_FS_FAT.
                + if any writable file system is selected. At present, this is only CONFIG_FS_FAT.
                5 Verbose help output can be suppressed by defining CONFIG_NSH_HELP_TERSE. In that case, the help command is still available but will be slightly smaller. @@ -3625,7 +3651,7 @@ nsh>
            @@ -3698,7 +3724,7 @@ set FOOBAR ABC_${FOO}_${BAR} @@ -3746,7 +3772,7 @@ set FOOBAR ABC_${FOO}_${BAR} @@ -4248,7 +4274,7 @@ mount -t vfat /dev/ram1 /tmp

          • - Mount the FAT filesystem at a configured mountpoint, /tmp. + Mount the FAT file system at a configured mountpoint, /tmp.

            @@ -4666,7 +4692,7 @@ CONFIG_SCHED_WAITPID=y

            You replace the sample code at apps/examples/nsh/nsh_main.c with whatever start-up logic that you want. NSH is a library at apps/nshlib. - apps.examplex/nsh is just a tiny, example start-up function (CONFIG_USER_ENTRYPOINT()) that that runs immediately and illustrates how to start NSH + apps.examples/nsh is just a tiny, example start-up function (CONFIG_USER_ENTRYPOINT()) that that runs immediately and illustrates how to start NSH If you want something else to run immediately then you can write your write your own custom CONFIG_USER_ENTRYPOINT() function and then start other tasks from your custom CONFIG_USER_ENTRYPOINT().

          • @@ -4723,7 +4749,7 @@ CONFIG_SCHED_WAITPID=y
            • - NSH will create a read-only RAM disk (a ROM disk), containing a tiny ROMFS filesystem containing the following: + NSH will create a read-only RAM disk (a ROM disk), containing a tiny ROMFS file system containing the following:

                 `--init.d/
                @@ -4734,7 +4760,7 @@ CONFIG_SCHED_WAITPID=y
                     

              • - NSH will then mount the ROMFS filesystem at /etc, resulting in: + NSH will then mount the ROMFS file system at /etc, resulting in:

                   |--dev/
                  @@ -4841,7 +4867,7 @@ mount -t vfat /dev/ram1 /tmp
                       

                  To generate a custom rcS file a copy of rcS.template needs to be placed at tools/ and changed according to the desired start-up behaviour. - Running tools/mkromfsimg.h creates nsh_romfsimg.h which needs to be copied to apps/nhslib OR if CONFIG_NSH_ARCHROMFS is defined to configs/<board>/include. + Running tools/mkromfsimg.h creates nsh_romfsimg.h which needs to be copied to apps/nshlib OR if CONFIG_NSH_ARCHROMFS is defined to configs/<board>/include.

                  @@ -5343,10 +5369,10 @@ xxd -i romfs_img >nsh_romfsimg.h
                • mkrd
                • mkromfsimg.sh
                • mount
                • +
                • mv
          • CONFIG_NSH_FILEIOSIZE Size of a static I/O buffer used for file access (ignored if - there is no filesystem). Default is 1024. + there is no file system). Default is 1024.
            CONFIG_NSH_NESTDEPTH The maximum number of nested if-then[-else]-fi sequences that - are permissable. Default: 3 + are permissible. Default: 3
            CONFIG_NSH_ROMFSETC - Mount a ROMFS filesystem at /etc and provide a startup script + Mount a ROMFS file system at /etc and provide a startup script at /etc/init.d/rcS. The default startup script will mount a FAT FS RAMDISK at /tmp but the logic is easily extensible. @@ -3975,7 +4001,7 @@ set FOOBAR ABC_${FOO}_${BAR}
            CONFIG_NSH_NOMAC - Set if your ethernet hardware has no built-in MAC address. + Set if your Ethernet hardware has no built-in MAC address. If set, a bogus MAC will be assigned.
              -
            • mv
            • nfsmount
            • nice
            • NSH library (nshlib)
            • @@ -5403,6 +5429,7 @@ xxd -i romfs_img >nsh_romfsimg.h
            • up_cxxinitialize()
            • urldecode
            • urlencode
            • +
            • USB console startup
            • useradd
            • userdel
            • usleep
            • -- GitLab From de3695d32ba6c6ae089e31d679b3d6d61135fad4 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Thu, 8 Jun 2017 12:14:51 -1000 Subject: [PATCH 978/990] kinetis:lpserial fixed header inclusion --- arch/arm/src/kinetis/kinetis_lpserial.c | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/arch/arm/src/kinetis/kinetis_lpserial.c b/arch/arm/src/kinetis/kinetis_lpserial.c index 5c0c336237..262bda4a8a 100644 --- a/arch/arm/src/kinetis/kinetis_lpserial.c +++ b/arch/arm/src/kinetis/kinetis_lpserial.c @@ -63,11 +63,9 @@ #include "up_arch.h" #include "up_internal.h" -#include "kinetis_config.h" -#include "chip.h" +#include "kinetis.h" #include "chip/kinetis_lpuart.h" #include "chip/kinetis_pinmux.h" -#include "kinetis.h" /**************************************************************************** * Pre-processor Definitions -- GitLab From b2d929e40a9163b2384d85084c5e2137831979b3 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Thu, 8 Jun 2017 16:30:48 -1000 Subject: [PATCH 979/990] Kinetis:SPI driver --- arch/arm/src/kinetis/Make.defs | 4 + arch/arm/src/kinetis/chip/kinetis_dspi.h | 6 +- arch/arm/src/kinetis/kinetis_spi.c | 1242 ++++++++++++++++++++++ 3 files changed, 1251 insertions(+), 1 deletion(-) create mode 100644 arch/arm/src/kinetis/kinetis_spi.c diff --git a/arch/arm/src/kinetis/Make.defs b/arch/arm/src/kinetis/Make.defs index 8ec4063b6d..4d9907907e 100644 --- a/arch/arm/src/kinetis/Make.defs +++ b/arch/arm/src/kinetis/Make.defs @@ -140,6 +140,10 @@ ifeq ($(CONFIG_KINETIS_SDHC),y) CHIP_CSRCS += kinetis_sdhc.c endif +ifeq ($(CONFIG_SPI),y) +CHIP_CSRCS += kinetis_spi.c +endif + ifeq ($(CONFIG_USBDEV),y) CHIP_CSRCS += kinetis_usbdev.c endif diff --git a/arch/arm/src/kinetis/chip/kinetis_dspi.h b/arch/arm/src/kinetis/chip/kinetis_dspi.h index e41674494f..897e766cfc 100644 --- a/arch/arm/src/kinetis/chip/kinetis_dspi.h +++ b/arch/arm/src/kinetis/chip/kinetis_dspi.h @@ -140,7 +140,7 @@ #define SPI_MCR_PCSIS_SHIFT (16) /* Bits 16-21: Peripheral Chip Select x Inactive State */ #define SPI_MCR_PCSIS_MASK (0x3f << SPI_MCR_PCSIS_SHIFT) # define SPI_MCR_PCSIS_CS(n) ((1 << (n)) << SPI_MCR_PCSIS_SHIFT) - /* Bits 22–23: Reserved */ + /* Bits 22-23: Reserved */ #define SPI_MCR_ROOE (1 << 24) /* Bit 24: Receive FIFO Overflow Overwrite Enable */ #define SPI_MCR_PCSSE (1 << 25) /* Bit 25: Peripheral Chip Select Strobe Enable */ #define SPI_MCR_MTFE (1 << 26) /* Bit 26: Modified Timing Format Enable */ @@ -165,6 +165,7 @@ #define SPI_CTARM_BR_SHIFT (0) /* Bits 0-3: Baud Rate Scaler */ #define SPI_CTARM_BR_MASK (15 << SPI_CTARM_BR_SHIFT) +# define SPI_CTARM_BR(n) ((((n) & 0xf)) << SPI_CTARM_BR_SHIFT) # define SPI_CTARM_BR_2 (0 << SPI_CTARM_BR_SHIFT) # define SPI_CTARM_BR_4 (1 << SPI_CTARM_BR_SHIFT) # define SPI_CTARM_BR_6 (2 << SPI_CTARM_BR_SHIFT) @@ -205,6 +206,7 @@ # define SPI_CTARM_CSSCK_65536 (15 << SPI_CTARM_CSSCK_SHIFT) #define SPI_CTARM_PBR_SHIFT (16) /* Bits 16-17: Baud Rate Prescaler */ #define SPI_CTARM_PBR_MASK (3 << SPI_CTARM_PBR_SHIFT) +# define SPI_CTARM_PBR(n) (((n) & 0x3) << SPI_CTARM_PBR_SHIFT) # define SPI_CTARM_PBR_2 (0 << SPI_CTARM_PBR_SHIFT) # define SPI_CTARM_PBR_3 (1 << SPI_CTARM_PBR_SHIFT) # define SPI_CTARM_PBR_5 (2 << SPI_CTARM_PBR_SHIFT) @@ -231,6 +233,7 @@ /* Bits 25-26: See common bits above */ #define SPI_CTARM_FMSZ_SHIFT (27) /* Bits 27-30: Frame Size */ #define SPI_CTARM_FMSZ_MASK (15 << SPI_CTARM_FMSZ_SHIFT) +#define SPI_CTARM_FMSZ(n) ((((n) & 0xf)) << SPI_CTARM_FMSZ_SHIFT) #define SPI_CTARM_DBR (1 << 31) /* Bit 31: Double Baud Rate */ /* DSPI Clock and Transfer Attributes Register (Slave Mode) */ @@ -281,6 +284,7 @@ #define SPI_PUSHR_TXDATA_SHIFT (0) /* Bits 0-15: Transmit Data */ #define SPI_PUSHR_TXDATA_MASK (0xffff << SPI_PUSHR_TXDATA_SHIFT) +# define SPI_PUSHR_TXDATA(d) (((d) & 0xffff) << SPI_PUSHR_TXDATA_SHIFT) #define SPI_PUSHR_PCS_SHIFT (16) /* Bits 16-21: Select PCS signals to assert */ #define SPI_PUSHR_PCS_MASK (0x3f << SPI_PUSHR_PCS_SHIFT) # define SPI_PUSHR_PCS(n) ((1 << (n)) << SPI_PUSHR_PCS_SHIFT) diff --git a/arch/arm/src/kinetis/kinetis_spi.c b/arch/arm/src/kinetis/kinetis_spi.c new file mode 100644 index 0000000000..1c25bc9754 --- /dev/null +++ b/arch/arm/src/kinetis/kinetis_spi.c @@ -0,0 +1,1242 @@ +/************************************************************************************ + * arch/arm/src/kinetis/kinetis_spi.c + * + * Copyright (C) 2017 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * David Sidrane + * + * 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. + * + ************************************************************************************/ + +/************************************************************************************ + * The external functions, kinetis_spi0/1/2select and kinetis_spi0/1/26status + * must be provided by board-specific logic. They are implementations of + * the select and status methods of the SPI interface defined by structure + * spi_ops_s (see include/nuttx/spi/spi.h). All other methods + * (including kinetis_spibus_initialize()) are provided by common Kinetis + * logic. + * To use this common SPI logic on your board: + * + * 1. Provide logic in kinetis_boardinitialize() to configure SPI chip + * select pins. + * 2. Provide kinetis_spi[n]select() and kinetis_spi[n]status() functions + * in your board-specific logic. These functions will perform chip + * selection and status operations using GPIOs in the way your board is + * configured. + * 3. Add a calls to kinetis_spibus_initialize() in your low level + * application initialization logic. + * 4. The handle returned by kinetis_spibus_initialize() may then be used to + * bind the SPI driver to higher level logic (e.g., calling + * mmcsd_spislotinitialize(), for example, will bind the SPI driver to + * the SPI MMC/SD driver). + * + ************************************************************************************/ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include + +#include "up_arch.h" + +#include "kinetis.h" +#include "kinetis_spi.h" +#include "chip/kinetis_memorymap.h" +#include "chip/kinetis_sim.h" +#include "chip/kinetis_dspi.h" +#include "chip/kinetis_pinmux.h" + +#if defined(CONFIG_KINETIS_SPI0) || defined(CONFIG_KINETIS_SPI1) || \ + defined(CONFIG_KINETIS_SPI2) + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +#define KINETIS_SPI_CLK_MAX (BOARD_BUS_FREQ / 2) +#define KINETIS_SPI_CLK_INIT 400000 + +/************************************************************************************ + * Private Types + ************************************************************************************/ + +struct kinetis_spidev_s +{ + struct spi_dev_s spidev; /* Externally visible part of the SPI interface */ + uint32_t spibase; /* Base address of SPI registers */ + sem_t exclsem; /* Held while chip is selected for mutual exclusion */ + uint32_t frequency; /* Requested clock frequency */ + uint32_t actual; /* Actual clock frequency */ + uint8_t nbits; /* Width of word in bits (8 to 16) */ + uint8_t mode; /* Mode 0,1,2,3 */ + uint8_t ctarsel; /* Which CTAR */ +}; + +/************************************************************************************ + * Private Function Prototypes + ************************************************************************************/ + +/* Helpers */ + +static inline uint32_t spi_getreg(FAR struct kinetis_spidev_s *priv, uint8_t offset); +static inline void spi_putreg(FAR struct kinetis_spidev_s *priv, uint8_t offset, + uint32_t value); +static inline uint16_t spi_getreg16(FAR struct kinetis_spidev_s *priv, uint8_t offset); +static inline void spi_putreg16(FAR struct kinetis_spidev_s *priv, uint8_t offset, + uint16_t value); +static inline uint8_t spi_getreg8(FAR struct kinetis_spidev_s *priv, uint8_t offset); +static inline void spi_putreg8(FAR struct kinetis_spidev_s *priv, uint8_t offset, + uint8_t value); +static inline uint16_t spi_readword(FAR struct kinetis_spidev_s *priv); +static inline void spi_writeword(FAR struct kinetis_spidev_s *priv, + uint16_t word); + +static inline void spi_run(FAR struct kinetis_spidev_s *priv, bool enable); +static inline void spi_write_control(FAR struct kinetis_spidev_s *priv, + uint32_t control); +static inline void spi_write_status(FAR struct kinetis_spidev_s *priv, + uint32_t status); +static inline void spi_wait_status(FAR struct kinetis_spidev_s *priv, + uint32_t status); +static uint16_t spi_send_data(FAR struct kinetis_spidev_s *priv, uint16_t wd, + bool last); + +/* SPI methods */ + +static int spi_lock(FAR struct spi_dev_s *dev, bool lock); +static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency); +static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode); +static void spi_setbits(FAR struct spi_dev_s *dev, int nbits); +#ifdef CONFIG_SPI_HWFEATURES +static int spi_hwfeatures(FAR struct spi_dev_s *dev, + spi_hwfeatures_t features); +#endif +static uint16_t spi_send(FAR struct spi_dev_s *dev, uint16_t wd); +static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer, + FAR void *rxbuffer, size_t nwords); +#ifndef CONFIG_SPI_EXCHANGE +static void spi_sndblock(FAR struct spi_dev_s *dev, FAR const void *txbuffer, + size_t nwords); +static void spi_recvblock(FAR struct spi_dev_s *dev, FAR void *rxbuffer, + size_t nwords); +#endif + +/************************************************************************************ + * Private Data + ************************************************************************************/ + +#ifdef CONFIG_KINETIS_SPI0 +static const struct spi_ops_s g_spi0ops = +{ + .lock = spi_lock, + .select = kinetis_spi0select, + .setfrequency = spi_setfrequency, + .setmode = spi_setmode, + .setbits = spi_setbits, +# ifdef CONFIG_SPI_HWFEATURES + .hwfeatures = spi_hwfeatures, +# endif + .status = kinetis_spi0status, +# ifdef CONFIG_SPI_CMDDATA + .cmddata = kinetis_spi0cmddata, +# endif + .send = spi_send, +# ifdef CONFIG_SPI_EXCHANGE + .exchange = spi_exchange, +# else + .sndblock = spi_sndblock, + .recvblock = spi_recvblock, +# endif +# ifdef CONFIG_SPI_CALLBACK + .registercallback = kinetis_spi0register, /* provided externally */ +# else + .registercallback = 0, /* not implemented */ +# endif +}; + +static struct kinetis_spidev_s g_spi0dev = +{ + .spidev = + { + &g_spi0ops + }, + .spibase = KINETIS_SPI0_BASE, + .ctarsel = KINETIS_SPI_CTAR0_OFFSET, +}; +#endif + +#ifdef CONFIG_KINETIS_SPI1 +static const struct spi_ops_s g_spi1ops = +{ + .lock = spi_lock, + .select = kinetis_spi1select, + .setfrequency = spi_setfrequency, + .setmode = spi_setmode, + .setbits = spi_setbits, +# ifdef CONFIG_SPI_HWFEATURES + .hwfeatures = spi_hwfeatures, +# endif + .status = kinetis_spi1status, +# ifdef CONFIG_SPI_CMDDATA + .cmddata = kinetis_spi1cmddata, +# endif + .send = spi_send, +# ifdef CONFIG_SPI_EXCHANGE + .exchange = spi_exchange, +# else + .sndblock = spi_sndblock, + .recvblock = spi_recvblock, +# endif +# ifdef CONFIG_SPI_CALLBACK + .registercallback = kinetis_spi1register, /* provided externally */ +# else + .registercallback = 0, /* not implemented */ +# endif +}; + +static struct kinetis_spidev_s g_spi1dev = +{ + .spidev = + { + &g_spi1ops + }, + .spibase = KINETIS_SPI1_BASE, + .ctarsel = KINETIS_SPI_CTAR0_OFFSET, +}; +#endif + +#ifdef CONFIG_KINETIS_SPI2 +static const struct spi_ops_s g_spi2ops = +{ + .lock = spi_lock, + .select = kinetis_spi2select, + .setfrequency = spi_setfrequency, + .setmode = spi_setmode, + .setbits = spi_setbits, +# ifdef CONFIG_SPI_HWFEATURES + .hwfeatures = spi_hwfeatures, +# endif + .status = kinetis_spi2status, +# ifdef CONFIG_SPI_CMDDATA + .cmddata = kinetis_spi2cmddata, +# endif + .send = spi_send, +# ifdef CONFIG_SPI_EXCHANGE + .exchange = spi_exchange, +# else + .sndblock = spi_sndblock, + .recvblock = spi_recvblock, +# endif +# ifdef CONFIG_SPI_CALLBACK + .registercallback = kinetis_spi2register, /* provided externally */ +# else + .registercallback = 0, /* not implemented */ +# endif +}; + +static struct kinetis_spidev_s g_spi2dev = +{ + .spidev = + { + &g_spi2ops + }, + .spibase = KINETIS_SPI2_BASE, + .ctarsel = KINETIS_SPI_CTAR0_OFFSET, +}; +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: spi_getreg + * + * Description: + * Get the 32-bit contents of the SPI register at offset + * + * Input Parameters: + * priv - private SPI device structure + * offset - offset to the register of interest + * + * Returned Value: + * The contents of the 32-bit register + * + ************************************************************************************/ + +static inline uint32_t spi_getreg(FAR struct kinetis_spidev_s *priv, uint8_t offset) +{ + return getreg32(priv->spibase + offset); +} + +/************************************************************************************ + * Name: spi_putreg + * + * Description: + * Write a 32-bit value to the SPI register at offset + * + * Input Parameters: + * priv - private SPI device structure + * offset - offset to the register of interest + * value - the 32-bit value to be written + * + * Returned Value: + * Nothing + * + ************************************************************************************/ + +static inline void spi_putreg(FAR struct kinetis_spidev_s *priv, uint8_t offset, + uint32_t value) +{ + putreg32(value, priv->spibase + offset); +} + +/************************************************************************************ + * Name: spi_getreg16 + * + * Description: + * Get the 16 bit contents of the SPI register at offset + * + * Input Parameters: + * priv - private SPI device structure + * offset - offset to the register of interest + * + * Returned Value: + * The contents of the 16-bit register + * + ************************************************************************************/ + +static inline uint16_t spi_getreg16(FAR struct kinetis_spidev_s *priv, uint8_t offset) +{ + return getreg16(priv->spibase + offset); +} + +/************************************************************************************ + * Name: spi_putreg16 + * + * Description: + * Write a 16-bit value to the SPI register at offset + * + * Input Parameters: + * priv - private SPI device structure + * offset - offset to the register of interest + * value - the 16-bit value to be written + * + * Returned Value: + * Nothing + * + ************************************************************************************/ + +static inline void spi_putreg16(FAR struct kinetis_spidev_s *priv, uint8_t offset, + uint16_t value) +{ + putreg16(value, priv->spibase + offset); +} + +/************************************************************************************ + * Name: spi_getreg8 + * + * Description: + * Get the 8 bit contents of the SPI register at offset + * + * Input Parameters: + * priv - private SPI device structure + * offset - offset to the register of interest + * + * Returned Value: + * The contents of the 8-bit register + * + ************************************************************************************/ + +static inline uint8_t spi_getreg8(FAR struct kinetis_spidev_s *priv, uint8_t offset) +{ + return getreg8(priv->spibase + offset); +} + +/************************************************************************************ + * Name: spi_putreg8 + * + * Description: + * Write a 8-bit value to the SPI register at offset + * + * Input Parameters: + * priv - private SPI device structure + * offset - offset to the register of interest + * value - the 8-bit value to be written + * + * Returned Value: + * Nothing + * + ************************************************************************************/ + +static inline void spi_putreg8(FAR struct kinetis_spidev_s *priv, uint8_t offset, + uint8_t value) +{ + putreg8(value, priv->spibase + offset); +} + +/************************************************************************************ + * Name: spi_write_status + * + * Description: + * Write the 32-bit status + * + * Input Parameters: + * priv - Device-specific state data + * status- any ones will clear flags. + * + * Returned Value: + * None + * + ************************************************************************************/ + +static inline void spi_write_status(FAR struct kinetis_spidev_s *priv, uint32_t status) +{ + + /* Write the SR Register */ + + spi_putreg(priv, KINETIS_SPI_SR_OFFSET, status); +} + +/************************************************************************************ + * Name: spi_wait_status + * + * Description: + * Wait for bit to be set in status + * + * Input Parameters: + * priv - Device-specific state data + * status- bit to wait on. + * + * Returned Value: + * None + * + ************************************************************************************/ + +static inline void spi_wait_status(FAR struct kinetis_spidev_s *priv, uint32_t status) +{ + + while (status != (spi_getreg(priv, KINETIS_SPI_SR_OFFSET) & status)); +} + +/************************************************************************************ + * Name: spi_write_control + * + * Description: + * Write the 16-bit control word to the TX FIFO + * + * Input Parameters: + * priv - Device-specific state data + * control- to write + * + * Returned Value: + * None + * + ************************************************************************************/ + +static inline void spi_write_control(FAR struct kinetis_spidev_s *priv, uint32_t control) +{ + + /* Write the control word to the SPI Data Register */ + + spi_putreg16(priv, KINETIS_SPI_PUSHR_OFFSET + 2, (uint16_t) (control >> 16)); +} + +/************************************************************************************ + * Name: spi_writeword + * + * Description: + * Write one 16 bit word to SPI TX FIFO + * + * Input Parameters: + * priv - Device-specific state data + * word - word to send + * + * Returned Value: + * None + * + ************************************************************************************/ + +static inline void spi_writeword(FAR struct kinetis_spidev_s *priv, uint16_t word) +{ + /* Wait until there is space in the fifo */ + + spi_wait_status(priv, SPI_SR_TFFF); + + /* Write the data to transmitted to the SPI Data Register */ + + spi_putreg16(priv, KINETIS_SPI_PUSHR_OFFSET, SPI_PUSHR_TXDATA(word)); +} + +/************************************************************************************ + * Name: spi_readword + * + * Description: + * Read one 16 bit word from SPI RX FIFO + * + * Input Parameters: + * priv - Device-specific state data + * + * Returned Value: + * The 8-bit value from the FIFO + * + ************************************************************************************/ + +static inline uint16_t spi_readword(FAR struct kinetis_spidev_s *priv) +{ + /* Wait until transfer completes and the data is in the RX FIFO */ + + spi_wait_status(priv, SPI_SR_RFDF | SPI_SR_TCF); + + /* Return the data */ + + return spi_getreg16(priv, KINETIS_SPI_POPR_OFFSET); +} + +/************************************************************************************ + * Name: spi_run + * + * Description: + * Sets or clears the HALT + * + * Input Parameters: + * priv - private SPI device structure + * enable - True clears HALT + * + * Returned Value: + * Last enable setting + * + ************************************************************************************/ + +void inline spi_run(FAR struct kinetis_spidev_s *priv, bool enable) +{ + uint32_t regval; + + regval = spi_getreg(priv, KINETIS_SPI_MCR_OFFSET); + regval &= ~SPI_MCR_HALT; + regval |= enable ? 0 : SPI_MCR_HALT; + spi_putreg(priv, KINETIS_SPI_MCR_OFFSET, regval); +} + +/************************************************************************************ + * Name: spi_lock + * + * Description: + * On SPI busses where there are multiple devices, it will be necessary to + * lock SPI to have exclusive access to the busses for a sequence of + * transfers. The bus should be locked before the chip is selected. After + * locking the SPI bus, the caller should then also call the setfrequency, + * setbits, and setmode methods to make sure that the SPI is properly + * configured for the device. If the SPI buss is being shared, then it + * may have been left in an incompatible state. + * + * Input Parameters: + * dev - Device-specific state data + * lock - true: Lock spi bus, false: unlock SPI bus + * + * Returned Value: + * None + * + ************************************************************************************/ + +static int spi_lock(FAR struct spi_dev_s *dev, bool lock) +{ + FAR struct kinetis_spidev_s *priv = (FAR struct kinetis_spidev_s *)dev; + + if (lock) + { + /* Take the semaphore (perhaps waiting) */ + + while (sem_wait(&priv->exclsem) != 0) + { + /* The only case that an error should occur here is if the wait was awakened + * by a signal. + */ + + ASSERT(errno == EINTR); + } + } + else + { + (void)sem_post(&priv->exclsem); + } + + return OK; +} + +/************************************************************************************ + * Name: spi_setfrequency + * + * Description: + * Set the SPI frequency. + * + * Input Parameters: + * dev - Device-specific state data + * frequency - The SPI frequency requested + * + * Returned Value: + * Returns the actual frequency selected + * + ************************************************************************************/ + +static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency) +{ + FAR struct kinetis_spidev_s *priv = (FAR struct kinetis_spidev_s *)dev; + + uint32_t prescale; + uint32_t prescalev; + uint32_t doublebr; + uint32_t scaler; + uint32_t scalerv; + uint32_t diff; + uint32_t actual; + uint32_t regval; + + uint32_t pbr = 0; + uint32_t dbr = 1; + uint32_t br = 0; + uint32_t min = UINT32_MAX; + + /* Check if requested frequency reasonable */ + + if (frequency > KINETIS_SPI_CLK_MAX) + { + frequency = KINETIS_SPI_CLK_MAX; + } + else if (frequency == 0) + { + frequency = KINETIS_SPI_CLK_INIT; + } + + /* Check if the requested frequency is the same as the frequency selection */ + + if (priv->frequency == frequency) + { + /* We are already at this frequency. Return the actual. */ + + return priv->actual; + } + + /* The clock source for the SPI baud rate generator is the bus clock. + * and the SCK is given by: + * + * SCK = (fP /PBR) x [(1+DBR)/BR] + * + * Where: + * fP - the Bus Clock + * PBR - Baud Rate Prescaler {2, 3, 5, 7} + * DBR - Double Baud Rate {0, 1} + * BR - Baud Rate Scaler {2, 4, 6, 8 ... 32,768} + * + * We need find a PBR and BR resulting in the in baudrate closest to the + * requested value. We give preference to DBR of 0 to maintina a 50/50 + * duty sysle + * + */ + + for (doublebr = 1; min && doublebr <= 2; doublebr++) + { + for (prescalev = 0, prescale = 2; + min && prescalev <= 3; + prescalev ++, prescale == 2 ? prescale++ : (prescale += 2)) + { + for (scalerv = 0, scaler = 2; + min && scalerv <= 15; + scalerv++, scaler < 8 ? (scaler += 2) : (scaler <<= 1)) + { + actual = ((BOARD_BUS_FREQ * doublebr) / (prescale * scaler)); + if (frequency >= actual) + { + diff = frequency - actual; + if (min > diff) + { + min = diff; + pbr = prescalev; + dbr = doublebr == 2 ? SPI_CTARM_DBR : 0; + br = scalerv; + priv->actual = actual; + } + } + } + } + } + + /* Write the new dividers to the CTAR register */ + + regval = spi_getreg(priv, priv->ctarsel); + regval &= ~(SPI_CTARM_BR_MASK | SPI_CTARM_PBR_MASK | SPI_CTARM_DBR); + regval |= (SPI_CTARM_BR(br) | SPI_CTARM_PBR(pbr) | dbr); + spi_putreg(priv, priv->ctarsel, regval); + + /* Save the frequency setting so that subsequent re-configurations will be + * faster. + */ + + priv->frequency = frequency; + + spiinfo("Frequency %d->%d\n", frequency, priv->actual); + return priv->actual; +} + +/************************************************************************************ + * Name: spi_setmode + * + * Description: + * Set the SPI mode. see enum spi_mode_e for mode definitions + * + * Input Parameters: + * dev - Device-specific state data + * mode - The SPI mode requested + * + * Returned Value: + * Returns the actual frequency selected + * + ************************************************************************************/ + +static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode) +{ + FAR struct kinetis_spidev_s *priv = (FAR struct kinetis_spidev_s *)dev; + uint32_t regval; + + spiinfo("mode=%d\n", mode); + + /* Has the mode changed? */ + + if (mode != priv->mode) + { + /* Yes... Set CTAR appropriately */ + + regval = spi_getreg(priv, priv->ctarsel); + regval &= ~(SPI_CTAR_CPOL | SPI_CTAR_CPHA); + + switch (mode) + { + case SPIDEV_MODE0: /* CPOL=0; CPHA=0 */ + break; + + case SPIDEV_MODE1: /* CPOL=0; CPHA=1 */ + regval |= SPI_CTAR_CPHA; + break; + + case SPIDEV_MODE2: /* CPOL=1; CPHA=0 */ + regval |= SPI_CTAR_CPOL; + break; + + case SPIDEV_MODE3: /* CPOL=1; CPHA=1 */ + regval |= (SPI_CTAR_CPOL | SPI_CTAR_CPHA); + break; + + default: + DEBUGASSERT(FALSE); + return; + } + + spi_putreg(priv, priv->ctarsel, regval); + + /* Save the mode so that subsequent re-configurations will be faster */ + + priv->mode = mode; + } +} + +/************************************************************************************ + * Name: spi_setbits + * + * Description: + * Set the number of bits per word. + * + * Input Parameters: + * dev - Device-specific state data + * nbits - The number of bits requested + * + * Returned Value: + * None + * + ************************************************************************************/ + +static void spi_setbits(FAR struct spi_dev_s *dev, int nbits) +{ + FAR struct kinetis_spidev_s *priv = (FAR struct kinetis_spidev_s *)dev; + uint32_t regval; + + if (nbits != priv->nbits) + { + /* Set the number of bits (valid range 4-16) */ + + if (nbits < 4 || nbits > 16) + { + return; + } + + regval = spi_getreg(priv, priv->ctarsel); + regval &= ~(SPI_CTARM_FMSZ_MASK); + regval |= SPI_CTARM_FMSZ(nbits-1); + spi_putreg(priv, priv->ctarsel, regval); + + /* Save the selection so the subsequence re-configurations will be faster */ + + priv->nbits = nbits; + } +} + +/************************************************************************************ + * Name: spi_hwfeatures + * + * Description: + * Set hardware-specific feature flags. + * + * Input Parameters: + * dev - Device-specific state data + * features - H/W feature flags + * + * Returned Value: + * Zero (OK) if the selected H/W features are enabled; A negated errno + * value if any H/W feature is not supportable. + * + ************************************************************************************/ + +#ifdef CONFIG_SPI_HWFEATURES +static int spi_hwfeatures(FAR struct spi_dev_s *dev, spi_hwfeatures_t features) +{ +#ifdef CONFIG_SPI_BITORDER + FAR struct kinetis_spidev_s *priv = (FAR struct spi_dev_s *)dev; + uint32_t setbits; + uint32_t clrbits; + + spiinfo("features=%08x\n", features); + + /* Transfer data LSB first? */ + + if ((features & HWFEAT_LSBFIRST) != 0) + { + setbits = SPI_CTARM_LSBFE; + clrbits = 0; + } + else + { + setbits = 0; + clrbits = SPI_CTARM_LSBFE; + } + + regval = spi_getreg(priv, priv->ctarsel); + regval &= ~clrbits; + regval |= setbits; + spi_putreg(priv, priv->ctarsel, regval); + + /* Other H/W features are not supported */ + + return ((features & ~HWFEAT_LSBFIRST) == 0) ? OK : -ENOSYS; +#else + return -ENOSYS; +#endif +} +#endif + +/************************************************************************************ + * Name: spi_send_data + * + * Description: + * Exchange one word on SPI + * + * Input Parameters: + * priv - Device-specific state data + * wd - The word to send. the size of the data is determined by the + * number of bits selected for the SPI interface. + * + * Returned Value: + * response + * + ************************************************************************************/ + +static uint16_t spi_send_data(FAR struct kinetis_spidev_s *priv, uint16_t wd, + bool last) +{ + uint16_t ret; + + /* On first write set control word and start transfer */ + + if (0 == (spi_getreg(priv, KINETIS_SPI_SR_OFFSET) & SPI_SR_TXRXS)) + { + spi_run(priv, true); + spi_write_control(priv, SPI_PUSHR_CTAS_CTAR0 | SPI_PUSHR_CTCNT); + } + + spi_writeword(priv, wd); + ret = spi_readword(priv); + + if (!last) + { + /* Clear the Transfer complete and the RX FIFO RDY */ + + spi_write_status(priv, SPI_SR_TCF | SPI_SR_RFDF); + } + else + { + /* Clear all status */ + + spi_write_status(priv, spi_getreg(priv, KINETIS_SPI_SR_OFFSET)); + spi_run(priv, false); + } + + return ret; +} + +/************************************************************************************ + * Name: spi_send + * + * Description: + * Exchange one word on SPI + * + * Input Parameters: + * dev - Device-specific state data + * wd - The word to send. the size of the data is determined by the + * number of bits selected for the SPI interface. + * + * Returned Value: + * response + * + ************************************************************************************/ + +static uint16_t spi_send(FAR struct spi_dev_s *dev, uint16_t wd) +{ + FAR struct kinetis_spidev_s *priv = (FAR struct kinetis_spidev_s *)dev; + + return spi_send_data(priv, wd, true); +} + +/************************************************************************************ + * Name: spi_exchange + * + * Description: + * Exchange a block of data on SPI without using DMA + * + * Input Parameters: + * dev - Device-specific state data + * txbuffer - A pointer to the buffer of data to be sent + * rxbuffer - A pointer to a buffer in which to receive data + * nwords - the length of data to be exchaned in units of words. + * The wordsize is determined by the number of bits-per-word + * selected for the SPI interface. If nbits <= 8, the data is + * packed into uint8_t's; if nbits >8, the data is packed into uint16_t's + * + * Returned Value: + * None + * + ************************************************************************************/ + +static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer, + FAR void *rxbuffer, size_t nwords) +{ + FAR struct kinetis_spidev_s *priv = (FAR struct kinetis_spidev_s *)dev; + uint8_t *brxptr = (uint8_t *)rxbuffer; + const uint8_t *btxptr = (uint8_t *)txbuffer; + uint16_t *wrxptr = (uint16_t *)rxbuffer; + const uint16_t *wtxptr = (const uint16_t *)txbuffer; + uint8_t byte; + uint16_t word; + + spiinfo("txbuffer=%p rxbuffer=%p nwords=%d\n", txbuffer, rxbuffer, nwords); + + if (priv->nbits > 8) + { + /* 16-bit mode */ + + while (nwords-- > 0) + { + /* Get the next word to write. Is there a source buffer? */ + + if (wtxptr) + { + word = *wtxptr++; + } + else + { + word = 0xffff; + } + + /* Exchange one word */ + + word = spi_send_data(priv, word, nwords ? false : true); + + /* Is there a buffer to receive the return value? */ + + if (wrxptr) + { + *wrxptr++ = word; + } + } + } + else + { + + /* 8-bit mode */ + + while (nwords-- > 0) + { + /* Get the next word to write. Is there a source buffer? */ + + if (btxptr) + { + byte = *btxptr++; + } + else + { + byte = 0xff; + } + + /* Exchange one word */ + + byte = (uint8_t) spi_send_data(priv, (uint16_t)byte, nwords ? false : true); + + /* Is there a buffer to receive the return value? */ + + if (brxptr) + { + *brxptr++ = byte; + } + } + } +} +/************************************************************************************ + * Name: spi_sndblock + * + * Description: + * Send a block of data on SPI + * + * Input Parameters: + * dev - Device-specific state data + * txbuffer - A pointer to the buffer of data to be sent + * nwords - the length of data to send from the buffer in number of words. + * The wordsize is determined by the number of bits-per-word + * selected for the SPI interface. If nbits <= 8, the data is + * packed into uint8_t's; if nbits >8, the data is packed into uint16_t's + * + * Returned Value: + * None + * + ************************************************************************************/ + +#ifndef CONFIG_SPI_EXCHANGE +static void spi_sndblock(FAR struct spi_dev_s *dev, FAR const void *txbuffer, + size_t nwords) +{ + spiinfo("txbuffer=%p nwords=%d\n", txbuffer, nwords); + return spi_exchange(dev, txbuffer, NULL, nwords); +} +#endif + +/************************************************************************************ + * Name: spi_recvblock + * + * Description: + * Receive a block of data from SPI + * + * Input Parameters: + * dev - Device-specific state data + * rxbuffer - A pointer to the buffer in which to recieve data + * nwords - the length of data that can be received in the buffer in number + * of words. The wordsize is determined by the number of bits-per-word + * selected for the SPI interface. If nbits <= 8, the data is + * packed into uint8_t's; if nbits >8, the data is packed into uint16_t's + * + * Returned Value: + * None + * + ************************************************************************************/ + +#ifndef CONFIG_SPI_EXCHANGE +static void spi_recvblock(FAR struct spi_dev_s *dev, FAR void *rxbuffer, size_t nwords) +{ + spiinfo("rxbuffer=%p nwords=%d\n", rxbuffer, nwords); + return spi_exchange(dev, NULL, rxbuffer, nwords); +} +#endif + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: kinetis_spibus_initialize + * + * Description: + * Initialize the selected SPI port. + * + * Input Parameter: + * Port number (for hardware that has mutiple SPI interfaces) + * + * Returned Value: + * Valid SPI device structure reference on succcess; a NULL on failure + * + ************************************************************************************/ + +FAR struct spi_dev_s *kinetis_spibus_initialize(int port) +{ + FAR struct kinetis_spidev_s *priv; + uint32_t regval; + + /* Configure multiplexed pins as connected on the board. Chip select pins + * must be configured by board-specific logic. Most SPI pins multiple, + * alternative pin selection. Definitions in the board.h file must be\ + * provided to resolve the board-specific pin configuration like: + * + * #define PIN_SPI0_SCK PIN_SPI0_SCK_1 + */ + +#ifdef CONFIG_KINETIS_SPI0 + if (port == 0) + { + priv = &g_spi0dev; + + /* Configure pins for SPI0 */ + + kinetis_pinconfig(PIN_SPI0_SCK); + kinetis_pinconfig(PIN_SPI0_SIN); + kinetis_pinconfig(PIN_SPI0_OUT); + + /* Enable clocking */ + + regval = getreg32(KINETIS_SIM_SCGC6); + regval |= SIM_SCGC6_SPI0; + putreg32(regval, KINETIS_SIM_SCGC6); + } + else +#endif +#ifdef CONFIG_KINETIS_SPI1 + if (port == 1) + { + priv = &g_spi1dev; + + /* Configure pins for SPI1 */ + + kinetis_pinconfig(PIN_SPI1_SCK); + kinetis_pinconfig(PIN_SPI1_SIN); + kinetis_pinconfig(PIN_SPI1_OUT); + + /* Enable clocking */ + + regval = getreg32(KINETIS_SIM_SCGC6); + regval |= SIM_SCGC6_SPI1; + putreg32(regval, KINETIS_SIM_SCGC6); + } + else +#endif +#ifdef CONFIG_KINETIS_SPI2 + if (port == 2) + { + priv = &g_spi2dev; + + /* Configure pins for SPI1 */ + + kinetis_pinconfig(PIN_SPI2_SCK); + kinetis_pinconfig(PIN_SPI2_SIN); + kinetis_pinconfig(PIN_SPI2_OUT); + + /* Enable clocking */ + + regval = getreg32(KINETIS_SIM_SCGC3); + regval |= SIM_SCGC3_SPI2; + putreg32(regval, KINETIS_SIM_SCGC3); + } + else +#endif + { + spierr("ERROR: Port %d not configured\n", port); + return NULL; + } + + /* Halt operations */ + + spi_run(priv, false); + + /* Configure master mode: + * Master Mode - Enabled + * Continuous SCK - Disabled + * SPI Configuration - SPI + * Freeze - Disabled + * Modified Transfer Format - Disabled + * Peripheral Chip Select Strobe - Peripheral Chip Select[5] signal + * Receive FIFO Overflow Overwrite - Ignore incoming + * Chip Select x Inactive State - High + * Doze - Disabled + * Module Disable - Enables the module clocks. + * Disable Transmit FIFO - yes + * Disable Receive FIFO - yes + * Clear TX FIFO - No + * Clear RX FIFO - No + * Sample Point - 0 clocks between edge and sample + * + */ + + spi_putreg(priv, KINETIS_SPI_MCR_OFFSET, SPI_MCR_MSTR | SPI_MCR_DCONF_SPI | + SPI_MCR_SMPL_PT_0CLKS | SPI_MCR_PCSIS_MASK | SPI_MCR_HALT| + SPI_MCR_DIS_RXF | SPI_MCR_DIS_TXF); + + /* Set the initial SPI configuration */ + + spi_putreg(priv, priv->ctarsel, 0); + + /* MSB first, 8 bit */ + + priv->nbits = 0; + spi_setbits(&priv->spidev, 8); + + /* select mode 0 */ + + priv->mode = SPIDEV_MODE3; + spi_setmode(&priv->spidev, SPIDEV_MODE0); + + /* Select a default frequency of approx. 400KHz */ + + priv->frequency = 0; + spi_setfrequency(&priv->spidev, KINETIS_SPI_CLK_INIT); + + /* Initialize the SPI semaphore that enforces mutually exclusive access */ + + sem_init(&priv->exclsem, 0, 1); + + return &priv->spidev; +} + +#endif /* CONFIG_KINETIS_SPI0 || CONFIG_KINETIS_SPI1 || CONFIG_KINETIS_SPI2 */ -- GitLab From fbea5abef0514dff55734b417dea6d38d6ec32bc Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Tue, 13 Jun 2017 11:10:09 -1000 Subject: [PATCH 980/990] freedom-k66f:Refreshed config --- configs/freedom-k66f/nsh/defconfig | 1 + 1 file changed, 1 insertion(+) diff --git a/configs/freedom-k66f/nsh/defconfig b/configs/freedom-k66f/nsh/defconfig index 91f33ffc14..aa55534ab8 100644 --- a/configs/freedom-k66f/nsh/defconfig +++ b/configs/freedom-k66f/nsh/defconfig @@ -576,6 +576,7 @@ CONFIG_INPUT=y # CONFIG_INPUT_ADS7843E is not set # CONFIG_INPUT_MXT is not set # CONFIG_INPUT_STMPE811 is not set +# CONFIG_INPUT_CYPRESS_MBR3108 is not set CONFIG_BUTTONS=y CONFIG_BUTTONS_LOWER=y CONFIG_BUTTONS_NPOLLWAITERS=2 -- GitLab From 611612c6f2365f35c87fa7c3666175ebc37777b0 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Tue, 13 Jun 2017 11:49:32 -1000 Subject: [PATCH 981/990] freedom-k66f:Use SPI driver. Initalize SPI1 on connector J6. No real use, as of yet. --- configs/freedom-k66f/include/board.h | 18 ++++++++++++++++++ configs/freedom-k66f/nsh/defconfig | 13 +++++++++++-- configs/freedom-k66f/src/freedom-k66f.h | 11 +++++++++++ configs/freedom-k66f/src/k66_bringup.c | 19 ++++++++++++++++++- configs/freedom-k66f/src/k66_spi.c | 9 ++++++--- 5 files changed, 64 insertions(+), 6 deletions(-) diff --git a/configs/freedom-k66f/include/board.h b/configs/freedom-k66f/include/board.h index 4a5673e936..d69bb153a1 100644 --- a/configs/freedom-k66f/include/board.h +++ b/configs/freedom-k66f/include/board.h @@ -348,6 +348,24 @@ #define PIN_I2C0_SCL PIN_I2C0_SCL_3 #define PIN_I2C0_SDA PIN_I2C0_SDA_3 +/* RF/WIFI + * + * J6 Pin Name K66 Name + * ------ ----- ------ --------- + * 1 GND + * 2 P3V3 + * 3 CE PTB20 PTB20 + * 4 CS PTD4 SPI1_PCS0 (use as GPIO) + * 5 SCK PTD5 SPI1_SCK + * 6 MOSI PTD6 SPI1_MOSI + * 7 MISO PTD7 SPI1_MISO + * 8 IRQ PTC18 PTC18 + */ + +#define PIN_SPI1_SCK PIN_SPI1_SCK_3 +#define PIN_SPI1_OUT PIN_SPI1_SOUT_3 +#define PIN_SPI1_SIN PIN_SPI1_SIN_3 + /* * Ethernet MAC/KSZ8081 PHY * ------------------------ diff --git a/configs/freedom-k66f/nsh/defconfig b/configs/freedom-k66f/nsh/defconfig index aa55534ab8..ca3eec729d 100644 --- a/configs/freedom-k66f/nsh/defconfig +++ b/configs/freedom-k66f/nsh/defconfig @@ -223,7 +223,7 @@ CONFIG_KINETIS_UART4=y # CONFIG_KINETIS_FLEXCAN0 is not set # CONFIG_KINETIS_FLEXCAN1 is not set # CONFIG_KINETIS_SPI0 is not set -# CONFIG_KINETIS_SPI1 is not set +CONFIG_KINETIS_SPI1=y # CONFIG_KINETIS_SPI2 is not set CONFIG_KINETIS_I2C0=y # CONFIG_KINETIS_I2C1 is not set @@ -546,7 +546,15 @@ CONFIG_I2C_DRIVER=y # CONFIG_ARCH_HAVE_SPI_CRCGENERATION is not set # CONFIG_ARCH_HAVE_SPI_CS_CONTROL is not set # CONFIG_ARCH_HAVE_SPI_BITORDER is not set -# CONFIG_SPI is not set +CONFIG_SPI=y +# CONFIG_SPI_SLAVE is not set +CONFIG_SPI_EXCHANGE=y +# CONFIG_SPI_CMDDATA is not set +# CONFIG_SPI_CALLBACK is not set +# CONFIG_SPI_HWFEATURES is not set +CONFIG_SPI_CS_DELAY_CONTROL=y +# CONFIG_SPI_DRIVER is not set +# CONFIG_SPI_BITBANG is not set # CONFIG_I2S is not set # @@ -608,6 +616,7 @@ CONFIG_MMCSD_NSLOTS=1 CONFIG_MMCSD_MULTIBLOCK_DISABLE=y CONFIG_MMCSD_MMCSUPPORT=y CONFIG_MMCSD_HAVECARDDETECT=y +# CONFIG_MMCSD_SPI is not set CONFIG_ARCH_HAVE_SDIO=y # CONFIG_SDIO_DMA is not set # CONFIG_ARCH_HAVE_SDIOWAIT_WRCOMPLETE is not set diff --git a/configs/freedom-k66f/src/freedom-k66f.h b/configs/freedom-k66f/src/freedom-k66f.h index 245c480493..da91d285e7 100644 --- a/configs/freedom-k66f/src/freedom-k66f.h +++ b/configs/freedom-k66f/src/freedom-k66f.h @@ -57,6 +57,7 @@ #define HAVE_PROC 1 #define HAVE_MMCSD 1 #define HAVE_AUTOMOUNTER 1 +#define HAVE_SPI 1 #define HAVE_USBDEV 1 #if defined(CONFIG_KINETIS_RTC) @@ -173,6 +174,11 @@ # undef CONFIG_KINETIS_SPI2 #endif +#if !defined(CONFIG_KINETIS_SPI0) && !defined(CONFIG_KINETIS_SPI1) && \ + !defined(CONFIG_KINETIS_SPI3) +# undef HAVE_SPI +#endif + /* FREEDOM-K66F GPIOs ****************************************************************/ /* A micro Secure Digital (SD) card slot is available on the FRDM-K66F connected to * the SD Host Controller (SDHC) signals of the MCU. This slot will accept micro @@ -223,6 +229,11 @@ #define GPIO_LED_G (GPIO_LOWDRIVE | GPIO_OUTPUT_ONE | PIN_PORTE | PIN6) #define GPIO_LED_B (GPIO_LOWDRIVE | GPIO_OUTPUT_ONE | PIN_PORTA | PIN11) +/* SPI1 on J6 */ + +#define PIN_CE (GPIO_LOWDRIVE | GPIO_OUTPUT_ONE | PIN_PORTB | PIN20) +#define PIN_SPI1_PCS0 (GPIO_LOWDRIVE | GPIO_OUTPUT_ONE | PIN_PORTD | PIN4) + /************************************************************************************ * Public data ************************************************************************************/ diff --git a/configs/freedom-k66f/src/k66_bringup.c b/configs/freedom-k66f/src/k66_bringup.c index 4ec736516a..8de8efb552 100644 --- a/configs/freedom-k66f/src/k66_bringup.c +++ b/configs/freedom-k66f/src/k66_bringup.c @@ -47,8 +47,10 @@ #include #include +#include #include +#include "kinetis_spi.h" #include "freedom-k66f.h" #if defined(CONFIG_LIB_BOARDCTL) || defined(CONFIG_BOARD_INITIALIZE) @@ -67,6 +69,9 @@ int k66_bringup(void) { +#ifdef HAVE_SPI + FAR struct spi_dev_s *spi1; +#endif int ret; #ifdef HAVE_PROC @@ -151,8 +156,20 @@ int k66_bringup(void) } #endif +#ifdef HAVE_SPI + + /* Verify we can initialize SPI bus 1 */ + + spi1 = kinetis_spibus_initialize(1); + + if (!spi1) + { + syslog(LOG_ERR, "ERROR:FAILED to initialize SPI port 1\n"); + return -ENODEV; + } +#endif + UNUSED(ret); return OK; } - #endif /* CONFIG_LIB_BOARDCTL CONFIG_BOARD_INITIALIZE */ diff --git a/configs/freedom-k66f/src/k66_spi.c b/configs/freedom-k66f/src/k66_spi.c index ce0c6eb78d..2f8e456785 100644 --- a/configs/freedom-k66f/src/k66_spi.c +++ b/configs/freedom-k66f/src/k66_spi.c @@ -53,7 +53,7 @@ #include "freedom-k66f.h" #if defined(CONFIG_KINETIS_SPI0) || defined(CONFIG_KINETIS_SPI1) || \ - defined(CONFIG_KINETIS_SPI2) + defined(CONFIG_KINETIS_SPI2) /************************************************************************************ * Public Functions @@ -69,7 +69,10 @@ void weak_function k66_spidev_initialize(void) { -# warning "Missing logic" + /* Initialize the CE CS pins on J6 RF/WIFI connector */ + + kinetis_pinconfig(PIN_CE); + kinetis_pinconfig(PIN_SPI1_PCS0); } /************************************************************************************ @@ -118,7 +121,7 @@ uint8_t kinetis_spi0status(FAR struct spi_dev_s *dev, uint32_t devid) void kinetis_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) { spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); -# warning "Missing logic" + kinetis_gpiowrite(PIN_SPI1_PCS0, !selected); } uint8_t kinetis_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) -- GitLab From 8ae5450268934014c8e630c7081c5ac92ee68392 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 14 Jun 2017 07:21:01 -0600 Subject: [PATCH 982/990] pthreads: Move pthread_yield from sched/pthreads to libc/pthreads. it is a simple wrapper for sched_yield and does not belong within the OS. --- configs/b-l475e-iot01a/README.txt | 3 +++ include/sys/syscall.h | 3 +-- libc/libc.csv | 1 + libc/pthread/Make.defs | 1 + {sched => libc}/pthread/pthread_yield.c | 4 ++-- sched/pthread/Make.defs | 2 +- syscall/syscall.csv | 1 - syscall/syscall_lookup.h | 1 - syscall/syscall_stublookup.c | 1 - 9 files changed, 9 insertions(+), 8 deletions(-) rename {sched => libc}/pthread/pthread_yield.c (96%) diff --git a/configs/b-l475e-iot01a/README.txt b/configs/b-l475e-iot01a/README.txt index e99c3a9503..013ac41fbf 100644 --- a/configs/b-l475e-iot01a/README.txt +++ b/configs/b-l475e-iot01a/README.txt @@ -27,6 +27,9 @@ STATUS NuttX. But no work has yet been done for this board port other than writing this README file. + o 2017-06-13: I just learned that development boards will not be + available for another month. + Board Features ============== diff --git a/include/sys/syscall.h b/include/sys/syscall.h index 6f1911c6c4..3f21f74d73 100644 --- a/include/sys/syscall.h +++ b/include/sys/syscall.h @@ -430,8 +430,7 @@ # define SYS_pthread_setschedparam (__SYS_pthread_once+1) # define SYS_pthread_setschedprio (__SYS_pthread_once+2) # define SYS_pthread_setspecific (__SYS_pthread_once+3) -# define SYS_pthread_yield (__SYS_pthread_once+4) -# define __SYS_pthread_smp (__SYS_pthread_once+5) +# define __SYS_pthread_smp (__SYS_pthread_once+4) # ifdef CONFIG_SMP # define SYS_pthread_setaffinity_np (__SYS_pthread_smp+0) diff --git a/libc/libc.csv b/libc/libc.csv index 02cf739bd3..89bc65c0b0 100644 --- a/libc/libc.csv +++ b/libc/libc.csv @@ -117,6 +117,7 @@ "pthread_mutexattr_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutexattr_t *" "pthread_mutexattr_setpshared","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutexattr_t *","int " "pthread_mutexattr_settype","pthread.h","!defined(CONFIG_DISABLE_PTHREAD) && defined(CONFIG_PTHREAD_MUTEX_TYPES)","int","pthread_mutexattr_t *","int" +"pthread_yield","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","void" "puts","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR const char *" "qsort","stdlib.h","","void","void *","size_t","size_t","int(*)(const void *","FAR const void *)" "rand","stdlib.h","","int" diff --git a/libc/pthread/Make.defs b/libc/pthread/Make.defs index 291dfdfd4e..5cd35f0255 100644 --- a/libc/pthread/Make.defs +++ b/libc/pthread/Make.defs @@ -53,6 +53,7 @@ CSRCS += pthread_mutexattr_setrobust.c pthread_mutexattr_getrobust.c CSRCS += pthread_setcancelstate.c pthread_setcanceltype.c CSRCS += pthread_testcancel.c CSRCS += pthread_rwlock.c pthread_rwlock_rdlock.c pthread_rwlock_wrlock.c +CSRCS += pthread_yield.c ifeq ($(CONFIG_SMP),y) CSRCS += pthread_attr_getaffinity.c pthread_attr_setaffinity.c diff --git a/sched/pthread/pthread_yield.c b/libc/pthread/pthread_yield.c similarity index 96% rename from sched/pthread/pthread_yield.c rename to libc/pthread/pthread_yield.c index 0577e21f83..2af7ea2b93 100644 --- a/sched/pthread/pthread_yield.c +++ b/libc/pthread/pthread_yield.c @@ -1,7 +1,7 @@ /**************************************************************************** - * sched/pthread/pthread_yield.c + * libc/pthread/pthread_yield.c * - * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2009, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without diff --git a/sched/pthread/Make.defs b/sched/pthread/Make.defs index 20bc7e8d6c..4d7b870957 100644 --- a/sched/pthread/Make.defs +++ b/sched/pthread/Make.defs @@ -36,7 +36,7 @@ ifneq ($(CONFIG_DISABLE_PTHREAD),y) CSRCS += pthread_create.c pthread_exit.c pthread_join.c pthread_detach.c -CSRCS += pthread_yield.c pthread_getschedparam.c pthread_setschedparam.c +CSRCS += pthread_getschedparam.c pthread_setschedparam.c CSRCS += pthread_mutexinit.c pthread_mutexdestroy.c CSRCS += pthread_mutexlock.c pthread_mutextrylock.c pthread_mutexunlock.c CSRCS += pthread_condinit.c pthread_conddestroy.c diff --git a/syscall/syscall.csv b/syscall/syscall.csv index 1ff6948d74..8afdd21caf 100644 --- a/syscall/syscall.csv +++ b/syscall/syscall.csv @@ -99,7 +99,6 @@ "pthread_setschedprio","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","pthread_t","int" "pthread_setspecific","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","pthread_key_t","FAR const void*" "pthread_sigmask","pthread.h","!defined(CONFIG_DISABLE_SIGNALS) && !defined(CONFIG_DISABLE_PTHREAD)","int","int","FAR const sigset_t*","FAR sigset_t*" -"pthread_yield","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","void" "putenv","stdlib.h","!defined(CONFIG_DISABLE_ENVIRON)","int","FAR const char*" "read","unistd.h","CONFIG_NSOCKET_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0","ssize_t","int","FAR void*","size_t" "readdir","dirent.h","CONFIG_NFILE_DESCRIPTORS > 0","FAR struct dirent*","FAR DIR*" diff --git a/syscall/syscall_lookup.h b/syscall/syscall_lookup.h index 0719358487..4096ebabb9 100644 --- a/syscall/syscall_lookup.h +++ b/syscall/syscall_lookup.h @@ -310,7 +310,6 @@ SYSCALL_LOOKUP(up_assert, 2, STUB_up_assert) SYSCALL_LOOKUP(pthread_setschedparam, 3, STUB_pthread_setschedparam) SYSCALL_LOOKUP(pthread_setschedprio, 2, STUB_pthread_setschedprio) SYSCALL_LOOKUP(pthread_setspecific, 2, STUB_pthread_setspecific) - SYSCALL_LOOKUP(pthread_yield, 0, STUB_pthread_yield) # ifdef CONFIG_SMP SYSCALL_LOOKUP(pthread_setaffinity, 3, STUB_pthread_setaffinity) SYSCALL_LOOKUP(pthread_getaffinity, 3, STUB_pthread_getaffinity) diff --git a/syscall/syscall_stublookup.c b/syscall/syscall_stublookup.c index 2cc52ad0a3..20119fbfbf 100644 --- a/syscall/syscall_stublookup.c +++ b/syscall/syscall_stublookup.c @@ -310,7 +310,6 @@ uintptr_t STUB_pthread_setschedprio(int nbr, uintptr_t parm1, uintptr_t parm2); uintptr_t STUB_pthread_setspecific(int nbr, uintptr_t parm1, uintptr_t parm2); -uintptr_t STUB_pthread_yield(int nbr); uintptr_t STUB_pthread_setaffinity(int nbr, uintptr_t parm1, uintptr_t parm2, uintptr_t parm3); -- GitLab From 557fd6504f714b9616e01731fc87eb0731b240d6 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 14 Jun 2017 07:30:49 -0600 Subject: [PATCH 983/990] pthreads: Move pthread_once from sched/pthreads to libc/pthreads. pthread_once just coordinates other OS interface calls but is not a fundamental OS interface and, hence, does not belong within the OS. --- include/sys/syscall.h | 13 ++++++------- libc/libc.csv | 1 + libc/pthread/Make.defs | 2 +- {sched => libc}/pthread/pthread_once.c | 4 ++-- sched/pthread/Make.defs | 2 +- syscall/syscall.csv | 1 - syscall/syscall_lookup.h | 1 - syscall/syscall_stublookup.c | 1 - 8 files changed, 11 insertions(+), 14 deletions(-) rename {sched => libc}/pthread/pthread_once.c (97%) diff --git a/include/sys/syscall.h b/include/sys/syscall.h index 3f21f74d73..84f2f9a7a6 100644 --- a/include/sys/syscall.h +++ b/include/sys/syscall.h @@ -421,16 +421,15 @@ #ifndef CONFIG_PTHREAD_MUTEX_UNSAFE # define SYS_pthread_mutex_consistent (__SYS_pthread+22) -# define __SYS_pthread_once (__SYS_pthread+23) +# define __SYS_pthread_setschedparam (__SYS_pthread+23) #else -# define __SYS_pthread_once (__SYS_pthread+22) +# define __SYS_pthread_setschedparam (__SYS_pthread+22) #endif -# define SYS_pthread_once (__SYS_pthread_once+0) -# define SYS_pthread_setschedparam (__SYS_pthread_once+1) -# define SYS_pthread_setschedprio (__SYS_pthread_once+2) -# define SYS_pthread_setspecific (__SYS_pthread_once+3) -# define __SYS_pthread_smp (__SYS_pthread_once+4) +# define SYS_pthread_setschedparam (__SYS_pthread_setschedparam+0) +# define SYS_pthread_setschedprio (__SYS_pthread_setschedparam+1) +# define SYS_pthread_setspecific (__SYS_pthread_setschedparam+2) +# define __SYS_pthread_smp (__SYS_pthread_setschedparam+3) # ifdef CONFIG_SMP # define SYS_pthread_setaffinity_np (__SYS_pthread_smp+0) diff --git a/libc/libc.csv b/libc/libc.csv index 89bc65c0b0..91d04270a5 100644 --- a/libc/libc.csv +++ b/libc/libc.csv @@ -117,6 +117,7 @@ "pthread_mutexattr_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutexattr_t *" "pthread_mutexattr_setpshared","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutexattr_t *","int " "pthread_mutexattr_settype","pthread.h","!defined(CONFIG_DISABLE_PTHREAD) && defined(CONFIG_PTHREAD_MUTEX_TYPES)","int","pthread_mutexattr_t *","int" +"pthread_once","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_once_t*","CODE void (*)(void)" "pthread_yield","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","void" "puts","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR const char *" "qsort","stdlib.h","","void","void *","size_t","size_t","int(*)(const void *","FAR const void *)" diff --git a/libc/pthread/Make.defs b/libc/pthread/Make.defs index 5cd35f0255..7f30abfd39 100644 --- a/libc/pthread/Make.defs +++ b/libc/pthread/Make.defs @@ -53,7 +53,7 @@ CSRCS += pthread_mutexattr_setrobust.c pthread_mutexattr_getrobust.c CSRCS += pthread_setcancelstate.c pthread_setcanceltype.c CSRCS += pthread_testcancel.c CSRCS += pthread_rwlock.c pthread_rwlock_rdlock.c pthread_rwlock_wrlock.c -CSRCS += pthread_yield.c +CSRCS += pthread_once.c pthread_yield.c ifeq ($(CONFIG_SMP),y) CSRCS += pthread_attr_getaffinity.c pthread_attr_setaffinity.c diff --git a/sched/pthread/pthread_once.c b/libc/pthread/pthread_once.c similarity index 97% rename from sched/pthread/pthread_once.c rename to libc/pthread/pthread_once.c index cd778a02d2..d73dde966f 100644 --- a/sched/pthread/pthread_once.c +++ b/libc/pthread/pthread_once.c @@ -1,7 +1,7 @@ /**************************************************************************** - * sched/pthread/pthread_once.c + * libc/pthread/pthread_once.c * - * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2009, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without diff --git a/sched/pthread/Make.defs b/sched/pthread/Make.defs index 4d7b870957..8cc744348a 100644 --- a/sched/pthread/Make.defs +++ b/sched/pthread/Make.defs @@ -46,7 +46,7 @@ CSRCS += pthread_cancel.c CSRCS += pthread_keycreate.c pthread_setspecific.c pthread_getspecific.c CSRCS += pthread_keydelete.c CSRCS += pthread_initialize.c pthread_completejoin.c pthread_findjoininfo.c -CSRCS += pthread_once.c pthread_release.c pthread_setschedprio.c +CSRCS += pthread_release.c pthread_setschedprio.c ifneq ($(CONFIG_PTHREAD_MUTEX_UNSAFE),y) CSRCS += pthread_mutex.c pthread_mutexconsistent.c pthread_mutexinconsistent.c diff --git a/syscall/syscall.csv b/syscall/syscall.csv index 8afdd21caf..ca512fbb24 100644 --- a/syscall/syscall.csv +++ b/syscall/syscall.csv @@ -93,7 +93,6 @@ "pthread_mutex_trylock","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutex_t*" "pthread_mutex_unlock","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutex_t*" "pthread_mutex_consistent","pthread.h","!defined(CONFIG_DISABLE_PTHREAD) && !defined(CONFIG_PTHREAD_MUTEX_UNSAFE)","int","FAR pthread_mutex_t*" -"pthread_once","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_once_t*","CODE void (*)(void)" "pthread_setaffinity_np","pthread.h","!defined(CONFIG_DISABLE_PTHREAD) && defined(CONFIG_SMP)","int","pthread_t","size_t","FAR const cpu_set_t*" "pthread_setschedparam","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","pthread_t","int","FAR const struct sched_param*" "pthread_setschedprio","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","pthread_t","int" diff --git a/syscall/syscall_lookup.h b/syscall/syscall_lookup.h index 4096ebabb9..ef38aa1d8c 100644 --- a/syscall/syscall_lookup.h +++ b/syscall/syscall_lookup.h @@ -306,7 +306,6 @@ SYSCALL_LOOKUP(up_assert, 2, STUB_up_assert) #ifndef CONFIG_PTHREAD_MUTEX_UNSAFE SYSCALL_LOOKUP(pthread_mutex_consistent, 1, STUB_pthread_mutex_consistent) #endif - SYSCALL_LOOKUP(pthread_once, 2, STUB_pthread_once) SYSCALL_LOOKUP(pthread_setschedparam, 3, STUB_pthread_setschedparam) SYSCALL_LOOKUP(pthread_setschedprio, 2, STUB_pthread_setschedprio) SYSCALL_LOOKUP(pthread_setspecific, 2, STUB_pthread_setspecific) diff --git a/syscall/syscall_stublookup.c b/syscall/syscall_stublookup.c index 20119fbfbf..ad891727bf 100644 --- a/syscall/syscall_stublookup.c +++ b/syscall/syscall_stublookup.c @@ -303,7 +303,6 @@ uintptr_t STUB_pthread_mutex_lock(int nbr, uintptr_t parm1); uintptr_t STUB_pthread_mutex_trylock(int nbr, uintptr_t parm1); uintptr_t STUB_pthread_mutex_unlock(int nbr, uintptr_t parm1); uintptr_t STUB_pthread_mutex_consistent(int nbr, uintptr_t parm1); -uintptr_t STUB_pthread_once(int nbr, uintptr_t parm1, uintptr_t parm2); uintptr_t STUB_pthread_setschedparam(int nbr, uintptr_t parm1, uintptr_t parm2, uintptr_t parm3); uintptr_t STUB_pthread_setschedprio(int nbr, uintptr_t parm1, -- GitLab From ae168bffa0125994fcf345f13c329a35e2b3a0ed Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 14 Jun 2017 07:48:45 -0600 Subject: [PATCH 984/990] pthreads: Move pthread_cond_init and pthread_cond_destory from sched/pthreads to libc/pthreads. This just coordinate other OS interface calls but are not a fundamental OS interfaces and, hence, do not belong within the OS. --- include/sys/syscall.h | 38 +++++++++---------- libc/libc.csv | 2 + libc/pthread/Make.defs | 1 + {sched => libc}/pthread/pthread_conddestroy.c | 5 +-- {sched => libc}/pthread/pthread_condinit.c | 6 +-- sched/pthread/Make.defs | 1 - syscall/syscall.csv | 2 - syscall/syscall_lookup.h | 2 - syscall/syscall_stublookup.c | 2 - 9 files changed, 25 insertions(+), 34 deletions(-) rename {sched => libc}/pthread/pthread_conddestroy.c (95%) rename {sched => libc}/pthread/pthread_condinit.c (95%) diff --git a/include/sys/syscall.h b/include/sys/syscall.h index 84f2f9a7a6..77d1c7c6d3 100644 --- a/include/sys/syscall.h +++ b/include/sys/syscall.h @@ -401,29 +401,27 @@ # define SYS_pthread_barrier_wait (__SYS_pthread+2) # define SYS_pthread_cancel (__SYS_pthread+3) # define SYS_pthread_cond_broadcast (__SYS_pthread+4) -# define SYS_pthread_cond_destroy (__SYS_pthread+5) -# define SYS_pthread_cond_init (__SYS_pthread+6) -# define SYS_pthread_cond_signal (__SYS_pthread+7) -# define SYS_pthread_cond_wait (__SYS_pthread+8) -# define SYS_pthread_create (__SYS_pthread+9) -# define SYS_pthread_detach (__SYS_pthread+10) -# define SYS_pthread_exit (__SYS_pthread+11) -# define SYS_pthread_getschedparam (__SYS_pthread+12) -# define SYS_pthread_getspecific (__SYS_pthread+13) -# define SYS_pthread_join (__SYS_pthread+14) -# define SYS_pthread_key_create (__SYS_pthread+15) -# define SYS_pthread_key_delete (__SYS_pthread+16) -# define SYS_pthread_mutex_destroy (__SYS_pthread+17) -# define SYS_pthread_mutex_init (__SYS_pthread+18) -# define SYS_pthread_mutex_lock (__SYS_pthread+19) -# define SYS_pthread_mutex_trylock (__SYS_pthread+20) -# define SYS_pthread_mutex_unlock (__SYS_pthread+21) +# define SYS_pthread_cond_signal (__SYS_pthread+5) +# define SYS_pthread_cond_wait (__SYS_pthread+6) +# define SYS_pthread_create (__SYS_pthread+7) +# define SYS_pthread_detach (__SYS_pthread+8) +# define SYS_pthread_exit (__SYS_pthread+9) +# define SYS_pthread_getschedparam (__SYS_pthread+10) +# define SYS_pthread_getspecific (__SYS_pthread+11) +# define SYS_pthread_join (__SYS_pthread+12) +# define SYS_pthread_key_create (__SYS_pthread+13) +# define SYS_pthread_key_delete (__SYS_pthread+14) +# define SYS_pthread_mutex_destroy (__SYS_pthread+15) +# define SYS_pthread_mutex_init (__SYS_pthread+16) +# define SYS_pthread_mutex_lock (__SYS_pthread+17) +# define SYS_pthread_mutex_trylock (__SYS_pthread+18) +# define SYS_pthread_mutex_unlock (__SYS_pthread+19) #ifndef CONFIG_PTHREAD_MUTEX_UNSAFE -# define SYS_pthread_mutex_consistent (__SYS_pthread+22) -# define __SYS_pthread_setschedparam (__SYS_pthread+23) +# define SYS_pthread_mutex_consistent (__SYS_pthread+20) +# define __SYS_pthread_setschedparam (__SYS_pthread+21) #else -# define __SYS_pthread_setschedparam (__SYS_pthread+22) +# define __SYS_pthread_setschedparam (__SYS_pthread+20) #endif # define SYS_pthread_setschedparam (__SYS_pthread_setschedparam+0) diff --git a/libc/libc.csv b/libc/libc.csv index 91d04270a5..a97d54b70f 100644 --- a/libc/libc.csv +++ b/libc/libc.csv @@ -111,6 +111,8 @@ "pthread_barrierattr_setpshared","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrierattr_t *","int" "pthread_condattr_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_condattr_t *" "pthread_condattr_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_condattr_t *" +"pthread_cond_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_cond_t*" +"pthread_cond_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_cond_t*","FAR const pthread_condattr_t*" "pthread_mutexattr_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutexattr_t *" "pthread_mutexattr_getpshared","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutexattr_t *","FAR int *" "pthread_mutexattr_gettype","pthread.h","!defined(CONFIG_DISABLE_PTHREAD) && defined(CONFIG_PTHREAD_MUTEX_TYPES)","int","FAR const pthread_mutexattr_t *","int *" diff --git a/libc/pthread/Make.defs b/libc/pthread/Make.defs index 7f30abfd39..5e08cbefa8 100644 --- a/libc/pthread/Make.defs +++ b/libc/pthread/Make.defs @@ -45,6 +45,7 @@ CSRCS += pthread_attr_setschedparam.c pthread_attr_getschedparam.c CSRCS += pthread_barrierattr_init.c pthread_barrierattr_destroy.c CSRCS += pthread_barrierattr_getpshared.c pthread_barrierattr_setpshared.c CSRCS += pthread_condattr_init.c pthread_condattr_destroy.c +CSRCS += pthread_condinit.c pthread_conddestroy.c CSRCS += pthread_mutexattr_init.c pthread_mutexattr_destroy.c CSRCS += pthread_mutexattr_getpshared.c pthread_mutexattr_setpshared.c CSRCS += pthread_mutexattr_setprotocol.c pthread_mutexattr_getprotocol.c diff --git a/sched/pthread/pthread_conddestroy.c b/libc/pthread/pthread_conddestroy.c similarity index 95% rename from sched/pthread/pthread_conddestroy.c rename to libc/pthread/pthread_conddestroy.c index bff0c3c28b..a691b60d7d 100644 --- a/sched/pthread/pthread_conddestroy.c +++ b/libc/pthread/pthread_conddestroy.c @@ -1,7 +1,7 @@ /**************************************************************************** - * sched/pthread/pthread_conddestroy.c + * libc/pthread/pthread_conddestroy.c * - * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -42,7 +42,6 @@ #include #include #include -#include "pthread/pthread.h" /**************************************************************************** * Public Functions diff --git a/sched/pthread/pthread_condinit.c b/libc/pthread/pthread_condinit.c similarity index 95% rename from sched/pthread/pthread_condinit.c rename to libc/pthread/pthread_condinit.c index 7368e0fb5a..81a31ea57f 100644 --- a/sched/pthread/pthread_condinit.c +++ b/libc/pthread/pthread_condinit.c @@ -1,7 +1,7 @@ /**************************************************************************** - * sched/pthread/pthread_condinit.c + * libc/pthread/pthread_condinit.c * - * Copyright (C) 2007-2009, 2016 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009, 2016-2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -46,8 +46,6 @@ #include -#include "pthread/pthread.h" - /**************************************************************************** * Public Functions ****************************************************************************/ diff --git a/sched/pthread/Make.defs b/sched/pthread/Make.defs index 8cc744348a..b450af2900 100644 --- a/sched/pthread/Make.defs +++ b/sched/pthread/Make.defs @@ -39,7 +39,6 @@ CSRCS += pthread_create.c pthread_exit.c pthread_join.c pthread_detach.c CSRCS += pthread_getschedparam.c pthread_setschedparam.c CSRCS += pthread_mutexinit.c pthread_mutexdestroy.c CSRCS += pthread_mutexlock.c pthread_mutextrylock.c pthread_mutexunlock.c -CSRCS += pthread_condinit.c pthread_conddestroy.c CSRCS += pthread_condwait.c pthread_condsignal.c pthread_condbroadcast.c CSRCS += pthread_barrierinit.c pthread_barrierdestroy.c pthread_barrierwait.c CSRCS += pthread_cancel.c diff --git a/syscall/syscall.csv b/syscall/syscall.csv index ca512fbb24..7624b5129f 100644 --- a/syscall/syscall.csv +++ b/syscall/syscall.csv @@ -72,8 +72,6 @@ "pthread_cleanup_pop","pthread.h","defined(CONFIG_PTHREAD_CLEANUP)","void","int" "pthread_cleanup_push","pthread.h","defined(CONFIG_PTHREAD_CLEANUP)","void","pthread_cleanup_t","FAR void*" "pthread_cond_broadcast","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_cond_t*" -"pthread_cond_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_cond_t*" -"pthread_cond_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_cond_t*","FAR const pthread_condattr_t*" "pthread_cond_signal","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_cond_t*" "pthread_cond_timedwait","pthread.h","!defined(CONFIG_DISABLE_SIGNALS) && !defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_cond_t*","FAR pthread_mutex_t*","FAR const struct timespec*" "pthread_cond_wait","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_cond_t*","FAR pthread_mutex_t*" diff --git a/syscall/syscall_lookup.h b/syscall/syscall_lookup.h index ef38aa1d8c..7c9b870981 100644 --- a/syscall/syscall_lookup.h +++ b/syscall/syscall_lookup.h @@ -286,8 +286,6 @@ SYSCALL_LOOKUP(up_assert, 2, STUB_up_assert) SYSCALL_LOOKUP(pthread_barrier_wait, 1, STUB_pthread_barrier_wait) SYSCALL_LOOKUP(pthread_cancel, 1, STUB_pthread_cancel) SYSCALL_LOOKUP(pthread_cond_broadcast, 1, STUB_pthread_cond_broadcast) - SYSCALL_LOOKUP(pthread_cond_destroy, 1, STUB_pthread_cond_destroy) - SYSCALL_LOOKUP(pthread_cond_init, 2, STUB_pthread_cond_init) SYSCALL_LOOKUP(pthread_cond_signal, 1, STUB_pthread_cond_signal) SYSCALL_LOOKUP(pthread_cond_wait, 2, STUB_pthread_cond_wait) SYSCALL_LOOKUP(pthread_create, 4, STUB_pthread_create) diff --git a/syscall/syscall_stublookup.c b/syscall/syscall_stublookup.c index ad891727bf..cdc2ef7c36 100644 --- a/syscall/syscall_stublookup.c +++ b/syscall/syscall_stublookup.c @@ -281,8 +281,6 @@ uintptr_t STUB_pthread_barrier_init(int nbr, uintptr_t parm1, uintptr_t STUB_pthread_barrier_wait(int nbr, uintptr_t parm1); uintptr_t STUB_pthread_cancel(int nbr, uintptr_t parm1); uintptr_t STUB_pthread_cond_broadcast(int nbr, uintptr_t parm1); -uintptr_t STUB_pthread_cond_destroy(int nbr, uintptr_t parm1); -uintptr_t STUB_pthread_cond_init(int nbr, uintptr_t parm1, uintptr_t parm2); uintptr_t STUB_pthread_cond_signal(int nbr, uintptr_t parm1); uintptr_t STUB_pthread_cond_wait(int nbr, uintptr_t parm1, uintptr_t parm2); uintptr_t STUB_pthread_create(int nbr, uintptr_t parm1, uintptr_t parm2, -- GitLab From 23a6ff5846cdc62cf9ae8962c5388de7c729d1a7 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 14 Jun 2017 07:59:54 -0600 Subject: [PATCH 985/990] pthreads: Move pthread_barrier_init, pthread_barrier_destroy, and pthread_barrier_wait from sched/pthreads to libc/pthreads. This just coordinate other OS interface calls but are not a fundamental OS interfaces and, hence, do not belong within the OS. --- include/sys/syscall.h | 43 +++++++++---------- libc/libc.csv | 3 ++ libc/pthread/Make.defs | 1 + .../pthread/pthread_barrierdestroy.c | 5 ++- {sched => libc}/pthread/pthread_barrierinit.c | 4 +- {sched => libc}/pthread/pthread_barrierwait.c | 4 +- sched/pthread/Make.defs | 1 - syscall/syscall.csv | 3 -- syscall/syscall_lookup.h | 3 -- syscall/syscall_stublookup.c | 4 -- 10 files changed, 31 insertions(+), 40 deletions(-) rename {sched => libc}/pthread/pthread_barrierdestroy.c (96%) rename {sched => libc}/pthread/pthread_barrierinit.c (97%) rename {sched => libc}/pthread/pthread_barrierwait.c (98%) diff --git a/include/sys/syscall.h b/include/sys/syscall.h index 77d1c7c6d3..81d17e027c 100644 --- a/include/sys/syscall.h +++ b/include/sys/syscall.h @@ -396,32 +396,29 @@ /* The following are defined if pthreads are enabled */ #ifndef CONFIG_DISABLE_PTHREAD -# define SYS_pthread_barrier_destroy (__SYS_pthread+0) -# define SYS_pthread_barrier_init (__SYS_pthread+1) -# define SYS_pthread_barrier_wait (__SYS_pthread+2) -# define SYS_pthread_cancel (__SYS_pthread+3) -# define SYS_pthread_cond_broadcast (__SYS_pthread+4) -# define SYS_pthread_cond_signal (__SYS_pthread+5) -# define SYS_pthread_cond_wait (__SYS_pthread+6) -# define SYS_pthread_create (__SYS_pthread+7) -# define SYS_pthread_detach (__SYS_pthread+8) -# define SYS_pthread_exit (__SYS_pthread+9) -# define SYS_pthread_getschedparam (__SYS_pthread+10) -# define SYS_pthread_getspecific (__SYS_pthread+11) -# define SYS_pthread_join (__SYS_pthread+12) -# define SYS_pthread_key_create (__SYS_pthread+13) -# define SYS_pthread_key_delete (__SYS_pthread+14) -# define SYS_pthread_mutex_destroy (__SYS_pthread+15) -# define SYS_pthread_mutex_init (__SYS_pthread+16) -# define SYS_pthread_mutex_lock (__SYS_pthread+17) -# define SYS_pthread_mutex_trylock (__SYS_pthread+18) -# define SYS_pthread_mutex_unlock (__SYS_pthread+19) +# define SYS_pthread_cancel (__SYS_pthread+0) +# define SYS_pthread_cond_broadcast (__SYS_pthread+1) +# define SYS_pthread_cond_signal (__SYS_pthread+2) +# define SYS_pthread_cond_wait (__SYS_pthread+3) +# define SYS_pthread_create (__SYS_pthread+4) +# define SYS_pthread_detach (__SYS_pthread+5) +# define SYS_pthread_exit (__SYS_pthread+6) +# define SYS_pthread_getschedparam (__SYS_pthread+7) +# define SYS_pthread_getspecific (__SYS_pthread+8) +# define SYS_pthread_join (__SYS_pthread+9) +# define SYS_pthread_key_create (__SYS_pthread+10) +# define SYS_pthread_key_delete (__SYS_pthread+11) +# define SYS_pthread_mutex_destroy (__SYS_pthread+12) +# define SYS_pthread_mutex_init (__SYS_pthread+13) +# define SYS_pthread_mutex_lock (__SYS_pthread+14) +# define SYS_pthread_mutex_trylock (__SYS_pthread+15) +# define SYS_pthread_mutex_unlock (__SYS_pthread+16) #ifndef CONFIG_PTHREAD_MUTEX_UNSAFE -# define SYS_pthread_mutex_consistent (__SYS_pthread+20) -# define __SYS_pthread_setschedparam (__SYS_pthread+21) +# define SYS_pthread_mutex_consistent (__SYS_pthread+17) +# define __SYS_pthread_setschedparam (__SYS_pthread+18) #else -# define __SYS_pthread_setschedparam (__SYS_pthread+20) +# define __SYS_pthread_setschedparam (__SYS_pthread+17) #endif # define SYS_pthread_setschedparam (__SYS_pthread_setschedparam+0) diff --git a/libc/libc.csv b/libc/libc.csv index a97d54b70f..d4a86fe5bf 100644 --- a/libc/libc.csv +++ b/libc/libc.csv @@ -109,6 +109,9 @@ "pthread_barrierattr_getpshared","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR const pthread_barrierattr_t *","FAR int *" "pthread_barrierattr_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrierattr_t *" "pthread_barrierattr_setpshared","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrierattr_t *","int" +"pthread_barrier_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrier_t*" +"pthread_barrier_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrier_t*","FAR const pthread_barrierattr_t*","unsigned int" +"pthread_barrier_wait","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrier_t*" "pthread_condattr_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_condattr_t *" "pthread_condattr_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_condattr_t *" "pthread_cond_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_cond_t*" diff --git a/libc/pthread/Make.defs b/libc/pthread/Make.defs index 5e08cbefa8..04ca83dc6a 100644 --- a/libc/pthread/Make.defs +++ b/libc/pthread/Make.defs @@ -44,6 +44,7 @@ CSRCS += pthread_attr_setstacksize.c pthread_attr_getstacksize.c CSRCS += pthread_attr_setschedparam.c pthread_attr_getschedparam.c CSRCS += pthread_barrierattr_init.c pthread_barrierattr_destroy.c CSRCS += pthread_barrierattr_getpshared.c pthread_barrierattr_setpshared.c +CSRCS += pthread_barrierinit.c pthread_barrierdestroy.c pthread_barrierwait.c CSRCS += pthread_condattr_init.c pthread_condattr_destroy.c CSRCS += pthread_condinit.c pthread_conddestroy.c CSRCS += pthread_mutexattr_init.c pthread_mutexattr_destroy.c diff --git a/sched/pthread/pthread_barrierdestroy.c b/libc/pthread/pthread_barrierdestroy.c similarity index 96% rename from sched/pthread/pthread_barrierdestroy.c rename to libc/pthread/pthread_barrierdestroy.c index 6bf0270b13..3f74e06c49 100644 --- a/sched/pthread/pthread_barrierdestroy.c +++ b/libc/pthread/pthread_barrierdestroy.c @@ -1,7 +1,7 @@ /**************************************************************************** - * sched/pthread/pthread_barriedestroy.c + * libc/pthread/pthread_barriedestroy.c * - * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2009, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -87,5 +87,6 @@ int pthread_barrier_destroy(FAR pthread_barrier_t *barrier) sem_destroy(&barrier->sem); barrier->count = 0; } + return ret; } diff --git a/sched/pthread/pthread_barrierinit.c b/libc/pthread/pthread_barrierinit.c similarity index 97% rename from sched/pthread/pthread_barrierinit.c rename to libc/pthread/pthread_barrierinit.c index 5051601417..6f8d427dfe 100644 --- a/sched/pthread/pthread_barrierinit.c +++ b/libc/pthread/pthread_barrierinit.c @@ -1,7 +1,7 @@ /**************************************************************************** - * sched/pthread/pthread_barrieinit.c + * libc/pthread/pthread_barrieinit.c * - * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2009, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without diff --git a/sched/pthread/pthread_barrierwait.c b/libc/pthread/pthread_barrierwait.c similarity index 98% rename from sched/pthread/pthread_barrierwait.c rename to libc/pthread/pthread_barrierwait.c index cf2f959c4e..8ba29d1d94 100644 --- a/sched/pthread/pthread_barrierwait.c +++ b/libc/pthread/pthread_barrierwait.c @@ -1,7 +1,7 @@ /**************************************************************************** - * sched/pthread/pthread_barrierwait.c + * libc/pthread/pthread_barrierwait.c * - * Copyright (C) 2007, 2009, 2014 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2009, 2014, 2017 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without diff --git a/sched/pthread/Make.defs b/sched/pthread/Make.defs index b450af2900..ebb512963d 100644 --- a/sched/pthread/Make.defs +++ b/sched/pthread/Make.defs @@ -40,7 +40,6 @@ CSRCS += pthread_getschedparam.c pthread_setschedparam.c CSRCS += pthread_mutexinit.c pthread_mutexdestroy.c CSRCS += pthread_mutexlock.c pthread_mutextrylock.c pthread_mutexunlock.c CSRCS += pthread_condwait.c pthread_condsignal.c pthread_condbroadcast.c -CSRCS += pthread_barrierinit.c pthread_barrierdestroy.c pthread_barrierwait.c CSRCS += pthread_cancel.c CSRCS += pthread_keycreate.c pthread_setspecific.c pthread_getspecific.c CSRCS += pthread_keydelete.c diff --git a/syscall/syscall.csv b/syscall/syscall.csv index 7624b5129f..bfb950a8eb 100644 --- a/syscall/syscall.csv +++ b/syscall/syscall.csv @@ -65,9 +65,6 @@ "pwrite","unistd.h","CONFIG_NSOCKET_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0","ssize_t","int","FAR const void*","size_t","off_t" "posix_spawnp","spawn.h","!defined(CONFIG_BINFMT_DISABLE) && defined(CONFIG_LIBC_EXECFUNCS) && defined(CONFIG_BINFMT_EXEPATH)","int","FAR pid_t *","FAR const char *","FAR const posix_spawn_file_actions_t *","FAR const posix_spawnattr_t *","FAR char *const []|FAR char *const *","FAR char *const []" "posix_spawn","spawn.h","!defined(CONFIG_BINFMT_DISABLE) && defined(CONFIG_LIBC_EXECFUNCS) && !defined(CONFIG_BINFMT_EXEPATH)","int","FAR pid_t *","FAR const char *","FAR const posix_spawn_file_actions_t *","FAR const posix_spawnattr_t *","FAR char *const []|FAR char *const *","FAR char *const []|FAR char *const *" -"pthread_barrier_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrier_t*" -"pthread_barrier_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrier_t*","FAR const pthread_barrierattr_t*","unsigned int" -"pthread_barrier_wait","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrier_t*" "pthread_cancel","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","pthread_t" "pthread_cleanup_pop","pthread.h","defined(CONFIG_PTHREAD_CLEANUP)","void","int" "pthread_cleanup_push","pthread.h","defined(CONFIG_PTHREAD_CLEANUP)","void","pthread_cleanup_t","FAR void*" diff --git a/syscall/syscall_lookup.h b/syscall/syscall_lookup.h index 7c9b870981..66a3153aa8 100644 --- a/syscall/syscall_lookup.h +++ b/syscall/syscall_lookup.h @@ -281,9 +281,6 @@ SYSCALL_LOOKUP(up_assert, 2, STUB_up_assert) /* The following are defined if pthreads are enabled */ #ifndef CONFIG_DISABLE_PTHREAD - SYSCALL_LOOKUP(pthread_barrier_destroy, 1, STUB_pthread_barrier_destroy) - SYSCALL_LOOKUP(pthread_barrier_init, 3, STUB_pthread_barrier_init) - SYSCALL_LOOKUP(pthread_barrier_wait, 1, STUB_pthread_barrier_wait) SYSCALL_LOOKUP(pthread_cancel, 1, STUB_pthread_cancel) SYSCALL_LOOKUP(pthread_cond_broadcast, 1, STUB_pthread_cond_broadcast) SYSCALL_LOOKUP(pthread_cond_signal, 1, STUB_pthread_cond_signal) diff --git a/syscall/syscall_stublookup.c b/syscall/syscall_stublookup.c index cdc2ef7c36..289244e7a8 100644 --- a/syscall/syscall_stublookup.c +++ b/syscall/syscall_stublookup.c @@ -275,10 +275,6 @@ uintptr_t STUB_shmdt(int nbr, uintptr_t parm1); /* The following are defined if pthreads are enabled */ -uintptr_t STUB_pthread_barrier_destroy(int nbr, uintptr_t parm1); -uintptr_t STUB_pthread_barrier_init(int nbr, uintptr_t parm1, - uintptr_t parm2, uintptr_t parm3); -uintptr_t STUB_pthread_barrier_wait(int nbr, uintptr_t parm1); uintptr_t STUB_pthread_cancel(int nbr, uintptr_t parm1); uintptr_t STUB_pthread_cond_broadcast(int nbr, uintptr_t parm1); uintptr_t STUB_pthread_cond_signal(int nbr, uintptr_t parm1); -- GitLab From 46f86982eeaa91b3b8f8d1b9f26f7541071454f3 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 14 Jun 2017 08:39:26 -0600 Subject: [PATCH 986/990] Update TODO list --- TODO | 29 ++++++++++++++++++++++++++++- 1 file changed, 28 insertions(+), 1 deletion(-) diff --git a/TODO b/TODO index 64c98a8c86..46f6c597e4 100644 --- a/TODO +++ b/TODO @@ -1,4 +1,4 @@ -NuttX TODO List (Last updated May 31, 2017) +NuttX TODO List (Last updated June 14, 2017) ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ This file summarizes known NuttX bugs, limitations, inconsistencies with @@ -234,6 +234,33 @@ o Task/Scheduler (sched/) could be improved and made a little more efficient with this change. + Title: INAPPROPRIATE USE OF sched_lock() BY pthreads + Description: In implementation of standard pthread functions, the non- + standard, NuttX function sched_lock() is used. This is very + strong sense it disables pre-emption for all threads in all + task groups. I believe it is only really necessary in most + cases to lock threads in the task group with a new non- + standard interface, say pthread_lock(). + + This is because the OS resources used by a thread such as + mutexes, condition variable, barriers, etc. are only + meaningful from within the task group. So, in order to + performance exclusive operations on these resources, it is + only necessary to block other threads executing within the + task group. + + This is an easy change: pthread_lock() and pthread_unlock() + would simply operate on a semaphore retained in the task + group structure. I am, however, hesitant to make this change: + I the flat build model, there is nothing that prevents people + from accessing the inter-thread controls from threads in + differnt task groups. Making this change, while correct, + might introduce subtle bugs in code by people who are not + using NuttX correctly. + Status: Open + Priority: Low. This change would improve real-time performance of the + OS but is not otherwise required. + o SMP ^^^ -- GitLab From a86f46bc54fe38781e35c1edad85b2f2f9ae6ac8 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 14 Jun 2017 09:38:58 -0600 Subject: [PATCH 987/990] MCP1515: Eliminate some warnings --- drivers/can/mcp2515.c | 2 +- include/nuttx/can/mcp2515.h | 6 ++++-- 2 files changed, 5 insertions(+), 3 deletions(-) diff --git a/drivers/can/mcp2515.c b/drivers/can/mcp2515.c index 50d4999e60..4a325a0426 100644 --- a/drivers/can/mcp2515.c +++ b/drivers/can/mcp2515.c @@ -2543,7 +2543,7 @@ FAR struct mcp2515_can_s *mcp2515_instantiate(FAR struct mcp2515_config_s *confi /* Return our private data structure as an opaque handle */ - return (MCP2515_HANDLE)priv; + return priv; } /**************************************************************************** diff --git a/include/nuttx/can/mcp2515.h b/include/nuttx/can/mcp2515.h index f7618fd88e..5689f76f1f 100644 --- a/include/nuttx/can/mcp2515.h +++ b/include/nuttx/can/mcp2515.h @@ -61,6 +61,9 @@ * Public Types ****************************************************************************/ +/* Type of the MCP2515 interrupt handling callback */ + +struct mcp2515_config_s; /* Forward reference */ typedef void (*mcp2515_handler_t)(FAR struct mcp2515_config_s *config, FAR void *arg); @@ -104,8 +107,7 @@ struct mcp2515_config_s mcp2515_handler_t handler, FAR void *arg); }; - -typedef FAR void *MCP2515_HANDLE; +/* Internal representation of the MCP2515 state data */ struct mcp2515_can_s; -- GitLab From 78281ef8e0125433a976acbd176e7136fb1c2581 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 14 Jun 2017 10:10:57 -0600 Subject: [PATCH 988/990] configs/stm32f103-minimum/mcp2515/defconfig: Enable CONFIG_CAN_TXREADY=y to eliminate a warning. --- configs/stm32f103-minimum/mcp2515/defconfig | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/configs/stm32f103-minimum/mcp2515/defconfig b/configs/stm32f103-minimum/mcp2515/defconfig index 982cc5767e..56727ae711 100644 --- a/configs/stm32f103-minimum/mcp2515/defconfig +++ b/configs/stm32f103-minimum/mcp2515/defconfig @@ -731,7 +731,9 @@ CONFIG_ARCH_HAVE_CAN_ERRORS=y # CONFIG_CAN_FD is not set CONFIG_CAN_FIFOSIZE=8 CONFIG_CAN_NPENDINGRTR=4 -# CONFIG_CAN_TXREADY is not set +CONFIG_CAN_TXREADY=y +# CONFIG_CAN_TXREADY_LOPRI is not set +CONFIG_CAN_TXREADY_HIPRI=y # # CAN Bus Controllers: -- GitLab From 04ae3d51c23215f9d59622abfd34ccebc6c163a9 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 14 Jun 2017 10:13:38 -0600 Subject: [PATCH 989/990] drivers/mp2515.c: Remove an incorrect warning. --- drivers/can/mcp2515.c | 8 -------- 1 file changed, 8 deletions(-) diff --git a/drivers/can/mcp2515.c b/drivers/can/mcp2515.c index 4a325a0426..10ab6e2508 100644 --- a/drivers/can/mcp2515.c +++ b/drivers/can/mcp2515.c @@ -64,14 +64,6 @@ /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ -/* Common definitions *******************************************************/ - -/* General Configuration ****************************************************/ - -#ifndef CONFIG_CAN_TXREADY -# warning WARNING!!! CONFIG_CAN_TXREADY is required by this driver -#endif - /* MCP2515 Configuration ****************************************************/ /* Bit timing */ -- GitLab From 2245dddaf9bdb37c51e49d4c53c2faab6bb69b43 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 14 Jun 2017 13:42:56 -0600 Subject: [PATCH 990/990] Break up some long lines --- sched/init/os_smpstart.c | 3 ++- sched/init/os_start.c | 3 ++- sched/sched/sched_note.c | 18 ++++++++++++------ sched/sched/sched_resumescheduler.c | 3 ++- sched/semaphore/sem_holder.c | 3 ++- sched/signal/sig_deliver.c | 5 +++-- sched/signal/sig_dispatch.c | 6 +++--- sched/task/task_prctl.c | 8 ++++++-- sched/wqueue/kwork_inherit.c | 3 ++- 9 files changed, 34 insertions(+), 18 deletions(-) diff --git a/sched/init/os_smpstart.c b/sched/init/os_smpstart.c index 17316e5b61..f5c1213a04 100644 --- a/sched/init/os_smpstart.c +++ b/sched/init/os_smpstart.c @@ -223,7 +223,8 @@ int os_smp_start(void) * this task is locked to this CPU. */ - tcb->flags = (TCB_FLAG_TTYPE_KERNEL | TCB_FLAG_NONCANCELABLE | TCB_FLAG_CPU_LOCKED); + tcb->flags = (TCB_FLAG_TTYPE_KERNEL | TCB_FLAG_NONCANCELABLE | + TCB_FLAG_CPU_LOCKED); tcb->cpu = cpu; } diff --git a/sched/init/os_start.c b/sched/init/os_start.c index 00f932fd13..961152ec4b 100644 --- a/sched/init/os_start.c +++ b/sched/init/os_start.c @@ -543,7 +543,8 @@ void os_start(void) sem_initialize(); -#if defined(MM_KERNEL_USRHEAP_INIT) || defined(CONFIG_MM_KERNEL_HEAP) || defined(CONFIG_MM_PGALLOC) +#if defined(MM_KERNEL_USRHEAP_INIT) || defined(CONFIG_MM_KERNEL_HEAP) || \ + defined(CONFIG_MM_PGALLOC) /* Initialize the memory manager */ { diff --git a/sched/sched/sched_note.c b/sched/sched/sched_note.c index bdc308fa91..6dc17b9936 100644 --- a/sched/sched/sched_note.c +++ b/sched/sched/sched_note.c @@ -447,7 +447,8 @@ void sched_note_cpu_start(FAR struct tcb_s *tcb, int cpu) /* Format the note */ - note_common(tcb, ¬e.ncs_cmn, sizeof(struct note_cpu_start_s), NOTE_CPU_START); + note_common(tcb, ¬e.ncs_cmn, sizeof(struct note_cpu_start_s), + NOTE_CPU_START); note.ncs_target = (uint8_t)cpu; /* Add the note to circular buffer */ @@ -461,7 +462,8 @@ void sched_note_cpu_started(FAR struct tcb_s *tcb) /* Format the note */ - note_common(tcb, ¬e.ncs_cmn, sizeof(struct note_cpu_started_s), NOTE_CPU_STARTED); + note_common(tcb, ¬e.ncs_cmn, sizeof(struct note_cpu_started_s), + NOTE_CPU_STARTED); /* Add the note to circular buffer */ @@ -474,7 +476,8 @@ void sched_note_cpu_pause(FAR struct tcb_s *tcb, int cpu) /* Format the note */ - note_common(tcb, ¬e.ncp_cmn, sizeof(struct note_cpu_pause_s), NOTE_CPU_PAUSE); + note_common(tcb, ¬e.ncp_cmn, sizeof(struct note_cpu_pause_s), + NOTE_CPU_PAUSE); note.ncp_target = (uint8_t)cpu; /* Add the note to circular buffer */ @@ -488,7 +491,8 @@ void sched_note_cpu_paused(FAR struct tcb_s *tcb) /* Format the note */ - note_common(tcb, ¬e.ncp_cmn, sizeof(struct note_cpu_paused_s), NOTE_CPU_PAUSED); + note_common(tcb, ¬e.ncp_cmn, sizeof(struct note_cpu_paused_s), + NOTE_CPU_PAUSED); /* Add the note to circular buffer */ @@ -501,7 +505,8 @@ void sched_note_cpu_resume(FAR struct tcb_s *tcb, int cpu) /* Format the note */ - note_common(tcb, ¬e.ncr_cmn, sizeof(struct note_cpu_resume_s), NOTE_CPU_RESUME); + note_common(tcb, ¬e.ncr_cmn, sizeof(struct note_cpu_resume_s), + NOTE_CPU_RESUME); note.ncr_target = (uint8_t)cpu; /* Add the note to circular buffer */ @@ -515,7 +520,8 @@ void sched_note_cpu_resumed(FAR struct tcb_s *tcb) /* Format the note */ - note_common(tcb, ¬e.ncr_cmn, sizeof(struct note_cpu_resumed_s), NOTE_CPU_RESUMED); + note_common(tcb, ¬e.ncr_cmn, sizeof(struct note_cpu_resumed_s), + NOTE_CPU_RESUMED); /* Add the note to circular buffer */ diff --git a/sched/sched/sched_resumescheduler.c b/sched/sched/sched_resumescheduler.c index 52eaef8374..96097d4fcd 100644 --- a/sched/sched/sched_resumescheduler.c +++ b/sched/sched/sched_resumescheduler.c @@ -103,4 +103,5 @@ void sched_resume_scheduler(FAR struct tcb_s *tcb) } -#endif /* CONFIG_RR_INTERVAL > 0 || CONFIG_SCHED_SPORADIC || CONFIG_SCHED_INSTRUMENTATION */ +#endif /* CONFIG_RR_INTERVAL > 0 || CONFIG_SCHED_SPORADIC || \ + * CONFIG_SCHED_INSTRUMENTATION */ diff --git a/sched/semaphore/sem_holder.c b/sched/semaphore/sem_holder.c index a46cf3a8be..bb11dbdeaf 100644 --- a/sched/semaphore/sem_holder.c +++ b/sched/semaphore/sem_holder.c @@ -439,7 +439,8 @@ static int sem_boostholderprio(FAR struct semholder_s *pholder, static int sem_verifyholder(FAR struct semholder_s *pholder, FAR sem_t *sem, FAR void *arg) { -#if 0 // Need to revisit this, but these assumptions seem to be untrue -- OR there is a bug??? +#if 0 /* Need to revisit this, but these assumptions seem to be untrue -- \ + * OR there is a bug??? */ FAR struct tcb_s *htcb = (FAR struct tcb_s *)pholder->htcb; /* Called after a semaphore has been released (incremented), the semaphore diff --git a/sched/signal/sig_deliver.c b/sched/signal/sig_deliver.c index 7f676a14a1..728e3a10d0 100644 --- a/sched/signal/sig_deliver.c +++ b/sched/signal/sig_deliver.c @@ -106,8 +106,9 @@ void sig_deliver(FAR struct tcb_s *stcb) * delivered plus the signal being delivered. */ - savesigprocmask = stcb->sigprocmask; - stcb->sigprocmask = savesigprocmask | sigq->mask | SIGNO2SET(sigq->info.si_signo); + savesigprocmask = stcb->sigprocmask; + stcb->sigprocmask = savesigprocmask | sigq->mask | + SIGNO2SET(sigq->info.si_signo); /* Deliver the signal. In the kernel build this has to be handled * differently if we are dispatching to a signal handler in a user- diff --git a/sched/signal/sig_dispatch.c b/sched/signal/sig_dispatch.c index 4399dc01f5..c69c6388f6 100644 --- a/sched/signal/sig_dispatch.c +++ b/sched/signal/sig_dispatch.c @@ -315,9 +315,9 @@ int sig_tcbdispatch(FAR struct tcb_s *stcb, siginfo_t *info) if (sigismember(&stcb->sigprocmask, info->si_signo)) { - /* Check if the task is waiting for this pending signal. If so, then unblock it. - * This must be performed in a critical section because signals can be queued - * from the interrupt level. + /* Check if the task is waiting for this pending signal. If so, then + * unblock it. This must be performed in a critical section because + * signals can be queued * from the interrupt level. */ flags = enter_critical_section(); diff --git a/sched/task/task_prctl.c b/sched/task/task_prctl.c index 5c74ea09f0..f28e76d6fe 100644 --- a/sched/task/task_prctl.c +++ b/sched/task/task_prctl.c @@ -129,14 +129,18 @@ int prctl(int option, ...) if (option == PR_SET_NAME) { - /* Ensure that tcb->name will be null-terminated, truncating if necessary */ + /* Ensure that tcb->name will be null-terminated, truncating if + * necessary. + */ strncpy(tcb->name, name, CONFIG_TASK_NAME_SIZE); tcb->name[CONFIG_TASK_NAME_SIZE] = '\0'; } else { - /* The returned value will be null-terminated, truncating if necessary */ + /* The returned value will be null-terminated, truncating if + * necessary. + */ strncpy(name, tcb->name, CONFIG_TASK_NAME_SIZE-1); name[CONFIG_TASK_NAME_SIZE-1] = '\0'; diff --git a/sched/wqueue/kwork_inherit.c b/sched/wqueue/kwork_inherit.c index a960480bd0..ae4c0e6187 100644 --- a/sched/wqueue/kwork_inherit.c +++ b/sched/wqueue/kwork_inherit.c @@ -403,4 +403,5 @@ void lpwork_restorepriority(uint8_t reqprio) leave_critical_section(flags); } -#endif /* CONFIG_SCHED_WORKQUEUE && CONFIG_SCHED_LPWORK && CONFIG_PRIORITY_INHERITANCE */ +#endif /* CONFIG_SCHED_WORKQUEUE && CONFIG_SCHED_LPWORK && \ + * CONFIG_PRIORITY_INHERITANCE */ -- GitLab